Update WPILib, roborio compilers, and CTRE Phoenix libraries

This borrows heavily from work that Ravago did to initially get this
stuff working.

Tested rudimentary functionality on a test bench, ensured that we could:
* Enable the robot.
* Read joystick and button values.
* Switch between auto and teleop modes.
* Read sensor values (encoder, absolute encoder, potentiometer).
* Read PDP values.
* Drive PWM motors.
* Drive CANivore motors.

Non-WPILib changes are made to accommodate the upgrade roborio
compiler's improved pickiness.

Merge commit '125aac16d9bf03c833ffa18de2f113a33758a4b8' into HEAD

Change-Id: I8648956fb7517b2d784bf58e0a236742af7a306a
Signed-off-by: James Kuszmaul <jabukuszmaul+collab@gmail.com>
diff --git a/WORKSPACE b/WORKSPACE
index e7baa81..c926b0e 100644
--- a/WORKSPACE
+++ b/WORKSPACE
@@ -45,9 +45,15 @@
     register_toolchains = False,
 )
 
-load("@python3_9//:defs.bzl", python_interpreter = "interpreter")
+load(
+    "@python3_9//:defs.bzl",
+    python_interpreter = "interpreter",
+)
 load("@rules_python//python:pip.bzl", "pip_parse")
-load("//tools/python:package_annotations.bzl", PYTHON_ANNOTATIONS = "ANNOTATIONS")
+load(
+    "//tools/python:package_annotations.bzl",
+    PYTHON_ANNOTATIONS = "ANNOTATIONS",
+)
 
 pip_parse(
     name = "pip_deps",
@@ -61,7 +67,10 @@
 )
 
 # Load the starlark macro which will define your dependencies.
-load("@pip_deps//:requirements.bzl", install_pip_deps = "install_deps")
+load(
+    "@pip_deps//:requirements.bzl",
+    install_pip_deps = "install_deps",
+)
 
 install_pip_deps()
 
@@ -463,14 +472,14 @@
     remote = "https://github.com/avventi/Slycot.git",
 )
 
-# TODO(austin): https://github.com/wpilibsuite/roborio-toolchain/releases/tag/v2022-1
+# TODO(Ravago, Max, Alex): https://github.com/wpilibsuite/opensdk
 http_archive(
     name = "arm_frc_linux_gnueabi_repo",
     build_file = "@//tools/cpp/arm-frc-linux-gnueabi:arm-frc-linux-gnueabi.BUILD",
     patches = ["//debian:fts.patch"],
-    sha256 = "043a5b047c2af9cf80d146d8327b588264c98a01e0f3f41e3564dd2bbbc95c0e",
-    strip_prefix = "frc2020/roborio/",
-    url = "https://www.frc971.org/Build-Dependencies/FRC-2020-Linux-Toolchain-7.3.0.tar.gz",
+    sha256 = "f53c6b86c25b4827d50365efe760a08edfea39c027dd08674ae696c9093d6a37",
+    strip_prefix = "roborio-academic",
+    url = "https://www.frc971.org/Build-Dependencies/cortexa9_vfpv3-roborio-academic-2023-x86_64-linux-gnu-Toolchain-12.1.0.tgz",
 )
 
 # The main partition from https://downloads.raspberrypi.org/raspios_lite_armhf/images/raspios_lite_armhf-2021-11-08/2021-10-30-raspios-bullseye-armhf-lite.zip.sig
@@ -519,8 +528,9 @@
 http_archive(
     name = "allwpilib_ni_libraries",
     build_file = "@//debian:ni-libraries.BUILD",
-    sha256 = "525b9d777cd00091b9095893c2e4fd0a70c7609c76db161161d407769ad4ba74",
-    url = "https://www.frc971.org/Build-Dependencies/allwpilib_ni-libraries_776db4e8aed31a651fa2f590e7468c69b384b42a.tar.gz",
+    sha256 = "c5d03ce5ed3807d9c4a5d415d8123d9ab3479498428eb0f1d77e74891f107aa0",
+    strip_prefix = "ni-libraries-2023.3.0",
+    url = "https://github.com/wpilibsuite/ni-libraries/archive/refs/tags/v2023.3.0.zip",
 )
 
 # For protobuf. Don't use these.
@@ -718,6 +728,86 @@
 )
 
 http_archive(
+    name = "ctre_phoenixpro_api_cpp_headers",
+    build_file_content = """
+cc_library(
+    name = 'api-cpp',
+    visibility = ['//visibility:public'],
+    hdrs = glob(['ctre/phoenixpro/**/*.hpp', 'units/*.h']),
+    includes = ["."],
+    deps = ["@//third_party/allwpilib/wpimath"],
+)
+""",
+    sha256 = "d9d6c48df9318cf106237a44bf7ad95e4092618bc3ab731092e9b733cacb1ffc",
+    urls = [
+        "https://maven.ctr-electronics.com/release/com/ctre/phoenixpro/api-cpp/23.0.1/api-cpp-23.0.1-headers.zip",
+    ],
+)
+
+http_archive(
+    name = "ctre_phoenixpro_api_cpp_athena",
+    build_file_content = """
+filegroup(
+    name = 'shared_libraries',
+    srcs = [
+        'linux/athena/shared/libCTRE_PhoenixPro.so',
+    ],
+    visibility = ['//visibility:public'],
+)
+
+cc_library(
+    name = 'api-cpp',
+    visibility = ['//visibility:public'],
+    srcs = ['linux/athena/shared/libCTRE_PhoenixPro.so'],
+    target_compatible_with = ['@//tools/platforms/hardware:roborio'],
+)
+""",
+    sha256 = "3d228fdf8565de5411a739fa2670d4ef5390acb15ceb4d3cbef8c76b5adc7682",
+    urls = [
+        "https://maven.ctr-electronics.com/release/com/ctre/phoenixpro/api-cpp/23.0.1/api-cpp-23.0.1-linuxathena.zip",
+    ],
+)
+
+http_archive(
+    name = "ctre_phoenixpro_tools_headers",
+    build_file_content = """
+cc_library(
+    name = 'tools',
+    visibility = ['//visibility:public'],
+    hdrs = glob(['ctre/**/*.h', 'ctre/**/*.hpp']),
+)
+""",
+    sha256 = "74d79bb3e739d9d6b87311656b0530aaefc211952cc647a3d57776a0cee9efce",
+    urls = [
+        "https://maven.ctr-electronics.com/release/com/ctre/phoenixpro/tools/23.0.1/tools-23.0.1-headers.zip",
+    ],
+)
+
+http_archive(
+    name = "ctre_phoenixpro_tools_athena",
+    build_file_content = """
+filegroup(
+    name = 'shared_libraries',
+    srcs = [
+        'linux/athena/shared/libCTRE_PhoenixTools.so',
+    ],
+    visibility = ['//visibility:public'],
+)
+
+cc_library(
+    name = 'tools',
+    visibility = ['//visibility:public'],
+    srcs = ['linux/athena/shared/libCTRE_PhoenixTools.so'],
+    target_compatible_with = ['@//tools/platforms/hardware:roborio'],
+)
+""",
+    sha256 = "1791b35fdf76aa08ad120e4d689d9440bd386542f63f5c44e4047a06e2e05b9a",
+    urls = [
+        "https://maven.ctr-electronics.com/release/com/ctre/phoenixpro/tools/23.0.1/tools-23.0.1-linuxathena.zip",
+    ],
+)
+
+http_archive(
     name = "ctre_phoenix_api_cpp_headers",
     build_file_content = """
 cc_library(
@@ -726,9 +816,9 @@
     hdrs = glob(['ctre/phoenix/**/*.h']),
 )
 """,
-    sha256 = "ea4131d1809bc8ccbd72b15cc7a65bd6ebb89a65019afc6a336e2c92d91ec824",
+    sha256 = "93cc41c53e98bbcd5db7b0631ab95a7de7744527d5847d2e795e6c8acec46bf8",
     urls = [
-        "http://devsite.ctr-electronics.com/maven/release/com/ctre/phoenix/api-cpp/5.21.1/api-cpp-5.21.1-headers.zip",
+        "https://maven.ctr-electronics.com/release/com/ctre/phoenix/api-cpp/5.30.2/api-cpp-5.30.2-headers.zip",
     ],
 )
 
@@ -750,9 +840,9 @@
     target_compatible_with = ['@//tools/platforms/hardware:roborio'],
 )
 """,
-    sha256 = "328130012a0fc1050c3ff09f30a2adf5106d15accc3d850b744fa60ec635a462",
+    sha256 = "63889beeeaac8bbef2573d23f1a9500b6382d28ab91c78f3605b6b624c27d68e",
     urls = [
-        "http://devsite.ctr-electronics.com/maven/release/com/ctre/phoenix/api-cpp/5.21.1/api-cpp-5.21.1-linuxathena.zip",
+        "https://maven.ctr-electronics.com/release/com/ctre/phoenix/api-cpp/5.30.2/api-cpp-5.30.2-linuxathena.zip",
     ],
 )
 
@@ -765,9 +855,9 @@
     hdrs = glob(['ctre/phoenix/**/*.h']),
 )
 """,
-    sha256 = "b3332885c6afe082f9f67c2335086e89f705b6ac6c5101188616f81c58d3e49a",
+    sha256 = "d41dd70aa4397cba934292e636c90511e571a56971f696348851fcd3bb88894d",
     urls = [
-        "http://devsite.ctr-electronics.com/maven/release/com/ctre/phoenix/cci/5.21.1/cci-5.21.1-headers.zip",
+        "https://maven.ctr-electronics.com/release/com/ctre/phoenix/cci/5.30.2/cci-5.30.2-headers.zip",
     ],
 )
 
@@ -789,9 +879,9 @@
     target_compatible_with = ['@//tools/platforms/hardware:roborio'],
 )
 """,
-    sha256 = "94812541734d7905774d97e10a97e9c79b5c37cba60d9b6b2d6e4bf3bbabc2fb",
+    sha256 = "b01f78b74ffcf01f48636dca894942e801ec6eac3daadcea7d65c4b74a80a056",
     urls = [
-        "http://devsite.ctr-electronics.com/maven/release/com/ctre/phoenix/cci/5.21.1/cci-5.21.1-linuxathena.zip",
+        "https://maven.ctr-electronics.com/release/com/ctre/phoenix/cci/5.30.2/cci-5.30.2-linuxathena.zip",
     ],
 )
 
diff --git a/aos/actions/actions.h b/aos/actions/actions.h
index 9a62483..bda29cc 100644
--- a/aos/actions/actions.h
+++ b/aos/actions/actions.h
@@ -106,8 +106,8 @@
  public:
   // A convenient way to refer to the type of our goals.
   typedef T GoalType;
-  typedef typename std::remove_reference<decltype(
-      *static_cast<GoalType *>(nullptr)->params())>::type ParamType;
+  typedef typename std::remove_pointer<typename std::invoke_result<
+      decltype(&GoalType::params), const GoalType *>::type>::type ParamType;
 
   TypedAction(typename ::aos::Fetcher<Status> *status_fetcher,
               typename ::aos::Sender<GoalType> *goal_sender,
@@ -194,8 +194,8 @@
 class TypedActionFactory {
  public:
   typedef T GoalType;
-  typedef typename std::remove_reference<decltype(
-      *static_cast<GoalType *>(nullptr)->params())>::type ParamType;
+  typedef typename std::remove_pointer<typename std::invoke_result<
+      decltype(&GoalType::params), const GoalType *>::type>::type ParamType;
 
   explicit TypedActionFactory(::aos::EventLoop *event_loop,
                               const ::std::string &name)
diff --git a/aos/actions/actor.h b/aos/actions/actor.h
index b906059..c27f7dd 100644
--- a/aos/actions/actor.h
+++ b/aos/actions/actor.h
@@ -20,8 +20,8 @@
 class ActorBase {
  public:
   typedef T GoalType;
-  typedef typename std::remove_reference<decltype(
-      *static_cast<GoalType *>(nullptr)->params())>::type ParamType;
+  typedef typename std::remove_pointer<typename std::invoke_result<
+      decltype(&GoalType::params), const GoalType *>::type>::type ParamType;
 
   // Commonly used offset for autonomous phased loops
   static constexpr monotonic_clock::duration kLoopOffset =
diff --git a/aos/events/logging/BUILD b/aos/events/logging/BUILD
index 7201e70..7e8daf9 100644
--- a/aos/events/logging/BUILD
+++ b/aos/events/logging/BUILD
@@ -215,7 +215,10 @@
     hdrs = [
         "s3_fetcher.h",
     ],
-    target_compatible_with = ["@platforms//os:linux"],
+    target_compatible_with = [
+        "@platforms//os:linux",
+        "@platforms//cpu:x86_64",
+    ],
     visibility = ["//visibility:public"],
     deps = [
         ":buffer_encoder",
diff --git a/aos/events/logging/log_cat.cc b/aos/events/logging/log_cat.cc
index a2441c8..b9e940c 100644
--- a/aos/events/logging/log_cat.cc
+++ b/aos/events/logging/log_cat.cc
@@ -83,7 +83,7 @@
   aos::logger::SpanReader reader(argv[1]);
   absl::Span<const uint8_t> raw_log_file_header_span = reader.ReadMessage();
 
-  if (raw_log_file_header_span == absl::Span<const uint8_t>()) {
+  if (raw_log_file_header_span.empty()) {
     LOG(WARNING) << "Empty log file on " << reader.filename();
     return 0;
   }
@@ -98,7 +98,7 @@
   }
   while (true) {
     absl::Span<const uint8_t> maybe_header_data = reader.PeekMessage();
-    if (maybe_header_data == absl::Span<const uint8_t>()) {
+    if (maybe_header_data.empty()) {
       break;
     }
 
@@ -153,7 +153,7 @@
   while (true) {
     const aos::SizePrefixedFlatbufferSpan<aos::logger::MessageHeader> message(
         reader.ReadMessage());
-    if (message.span() == absl::Span<const uint8_t>()) {
+    if (message.span().empty()) {
       break;
     }
     CHECK(message.Verify());
diff --git a/aos/events/logging/log_edit.cc b/aos/events/logging/log_edit.cc
index 969d59c..e3cfc3a 100644
--- a/aos/events/logging/log_edit.cc
+++ b/aos/events/logging/log_edit.cc
@@ -55,7 +55,7 @@
 
     while (true) {
       absl::Span<const uint8_t> msg_data = span_reader.ReadMessage();
-      if (msg_data == absl::Span<const uint8_t>()) {
+      if (msg_data.empty()) {
         break;
       }
 
diff --git a/aos/events/logging/logfile_utils.cc b/aos/events/logging/logfile_utils.cc
index 342cf8b..94337d3 100644
--- a/aos/events/logging/logfile_utils.cc
+++ b/aos/events/logging/logfile_utils.cc
@@ -85,8 +85,7 @@
   if (!util::MkdirPIfSpace(filename, 0777)) {
     ran_out_of_space_ = true;
   } else {
-    fd_ = open(filename_.c_str(),
-               O_RDWR | O_CLOEXEC | O_CREAT | O_EXCL, 0774);
+    fd_ = open(filename_.c_str(), O_RDWR | O_CLOEXEC | O_CREAT | O_EXCL, 0774);
     if (fd_ == -1 && errno == ENOSPC) {
       ran_out_of_space_ = true;
     } else {
@@ -441,7 +440,8 @@
   // want to control and understand it here.  Changing the order can increase
   // the amount of padding bytes in the middle.
   //
-  // It is also easier to follow...  And doesn't actually make things much bigger.
+  // It is also easier to follow...  And doesn't actually make things much
+  // bigger.
   switch (log_type) {
     case LogType::kLogRemoteMessage:
       message_header_builder.add_queue_index(context.remote_queue_index);
@@ -575,8 +575,7 @@
   LOG(FATAL);
 }
 
-flatbuffers::uoffset_t PackMessageSize(LogType log_type,
-                                       size_t data_size) {
+flatbuffers::uoffset_t PackMessageSize(LogType log_type, size_t data_size) {
   static_assert(sizeof(flatbuffers::uoffset_t) == 4u,
                 "Update size logic please.");
   const flatbuffers::uoffset_t aligned_data_length =
@@ -934,7 +933,7 @@
 
 absl::Span<const uint8_t> SpanReader::ReadMessage() {
   absl::Span<const uint8_t> result = PeekMessage();
-  if (result != absl::Span<const uint8_t>()) {
+  if (!result.empty()) {
     ConsumeMessage();
   } else {
     is_finished_ = true;
@@ -977,7 +976,7 @@
   absl::Span<const uint8_t> config_data = span_reader->ReadMessage();
 
   // Make sure something was read.
-  if (config_data == absl::Span<const uint8_t>()) {
+  if (config_data.empty()) {
     return std::nullopt;
   }
 
@@ -996,7 +995,7 @@
   if (FLAGS_workaround_double_headers && !result.message().has_logger_sha1()) {
     while (true) {
       absl::Span<const uint8_t> maybe_header_data = span_reader->PeekMessage();
-      if (maybe_header_data == absl::Span<const uint8_t>()) {
+      if (maybe_header_data.empty()) {
         break;
       }
 
@@ -1035,7 +1034,7 @@
     data_span = span_reader.ReadMessage();
 
     // Make sure something was read.
-    if (data_span == absl::Span<const uint8_t>()) {
+    if (data_span.empty()) {
       return std::nullopt;
     }
   }
@@ -1079,7 +1078,7 @@
 
 std::shared_ptr<UnpackedMessageHeader> MessageReader::ReadMessage() {
   absl::Span<const uint8_t> msg_data = span_reader_.ReadMessage();
-  if (msg_data == absl::Span<const uint8_t>()) {
+  if (msg_data.empty()) {
     if (is_corrupted()) {
       LOG(ERROR) << "Total corrupted volumes: before = "
                  << total_verified_before_
@@ -1116,7 +1115,7 @@
     while (true) {
       absl::Span<const uint8_t> msg_data = span_reader_.ReadMessage();
 
-      if (msg_data == absl::Span<const uint8_t>()) {
+      if (msg_data.empty()) {
         if (!ignore_corrupt_messages_flag_) {
           LOG(ERROR) << "Total corrupted volumes: before = "
                      << total_verified_before_
@@ -1212,20 +1211,17 @@
     remote_queue_index = message.remote_queue_index();
   }
 
-  new (unpacked_message) UnpackedMessageHeader{
-      .channel_index = message.channel_index(),
-      .monotonic_sent_time = monotonic_clock::time_point(
+  new (unpacked_message) UnpackedMessageHeader(
+      message.channel_index(),
+      monotonic_clock::time_point(
           chrono::nanoseconds(message.monotonic_sent_time())),
-      .realtime_sent_time = realtime_clock::time_point(
+      realtime_clock::time_point(
           chrono::nanoseconds(message.realtime_sent_time())),
-      .queue_index = message.queue_index(),
-      .monotonic_remote_time = monotonic_remote_time,
-      .realtime_remote_time = realtime_remote_time,
-      .remote_queue_index = remote_queue_index,
-      .monotonic_timestamp_time = monotonic_clock::time_point(
+      message.queue_index(), monotonic_remote_time, realtime_remote_time,
+      remote_queue_index,
+      monotonic_clock::time_point(
           std::chrono::nanoseconds(message.monotonic_timestamp_time())),
-      .has_monotonic_timestamp_time = message.has_monotonic_timestamp_time(),
-      .span = span};
+      message.has_monotonic_timestamp_time(), span);
 
   if (data_size > 0) {
     memcpy(span.data(), message.data()->data(), data_size);
diff --git a/aos/events/logging/logfile_utils.h b/aos/events/logging/logfile_utils.h
index e034bfe..7105b0c 100644
--- a/aos/events/logging/logfile_utils.h
+++ b/aos/events/logging/logfile_utils.h
@@ -438,6 +438,24 @@
 // Stores MessageHeader as a flat header and inline, aligned block of data.
 class UnpackedMessageHeader {
  public:
+  UnpackedMessageHeader(
+      uint32_t channel_index, monotonic_clock::time_point monotonic_sent_time,
+      realtime_clock::time_point realtime_sent_time, uint32_t queue_index,
+      std::optional<monotonic_clock::time_point> monotonic_remote_time,
+      std::optional<realtime_clock::time_point> realtime_remote_time,
+      std::optional<uint32_t> remote_queue_index,
+      monotonic_clock::time_point monotonic_timestamp_time,
+      bool has_monotonic_timestamp_time, absl::Span<const uint8_t> span)
+      : channel_index(channel_index),
+        monotonic_sent_time(monotonic_sent_time),
+        realtime_sent_time(realtime_sent_time),
+        queue_index(queue_index),
+        monotonic_remote_time(monotonic_remote_time),
+        realtime_remote_time(realtime_remote_time),
+        remote_queue_index(remote_queue_index),
+        monotonic_timestamp_time(monotonic_timestamp_time),
+        has_monotonic_timestamp_time(has_monotonic_timestamp_time),
+        span(span) {}
   UnpackedMessageHeader(const UnpackedMessageHeader &) = delete;
   UnpackedMessageHeader &operator=(const UnpackedMessageHeader &) = delete;
 
diff --git a/aos/events/shm_event_loop_test.cc b/aos/events/shm_event_loop_test.cc
index 90a6d1c..132ef20 100644
--- a/aos/events/shm_event_loop_test.cc
+++ b/aos/events/shm_event_loop_test.cc
@@ -42,7 +42,7 @@
     }
     ::std::unique_ptr<ShmEventLoop> loop(new ShmEventLoop(configuration()));
     loop->set_name(name);
-    return std::move(loop);
+    return loop;
   }
 
   ::std::unique_ptr<EventLoop> MakePrimary(std::string_view name) override {
@@ -54,7 +54,7 @@
         ::std::unique_ptr<ShmEventLoop>(new ShmEventLoop(configuration()));
     primary_event_loop_ = loop.get();
     loop->set_name(name);
-    return std::move(loop);
+    return loop;
   }
 
   void Run() override { CHECK_NOTNULL(primary_event_loop_)->Run(); }
diff --git a/aos/events/simulated_event_loop.cc b/aos/events/simulated_event_loop.cc
index d2328fb..944a22b 100644
--- a/aos/events/simulated_event_loop.cc
+++ b/aos/events/simulated_event_loop.cc
@@ -67,10 +67,11 @@
   AlignedOwningSpan *const span = reinterpret_cast<AlignedOwningSpan *>(
       malloc(sizeof(AlignedOwningSpan) + size + kChannelDataAlignment - 1));
 
-  absl::Span mutable_span(
+  absl::Span<uint8_t> mutable_span(
       reinterpret_cast<uint8_t *>(RoundChannelData(&span->data[0], size)),
       size);
-  new (span) AlignedOwningSpan{.span = mutable_span};
+  // Use the placement new operator to construct an actual absl::Span in place.
+  new (&span->span) absl::Span(mutable_span);
 
   return std::make_pair(
       RawSender::SharedSpan(
@@ -1009,7 +1010,7 @@
   ::std::unique_ptr<SimulatedFetcher> fetcher(
       new SimulatedFetcher(event_loop, this));
   fetchers_.push_back(fetcher.get());
-  return ::std::move(fetcher);
+  return fetcher;
 }
 
 std::optional<uint32_t> SimulatedChannel::Send(
@@ -1584,7 +1585,7 @@
 
   VLOG(1) << scheduler_.distributed_now() << " " << NodeName(node())
           << monotonic_now() << " MakeEventLoop(\"" << result->name() << "\")";
-  return std::move(result);
+  return result;
 }
 
 void SimulatedEventLoopFactory::AllowApplicationCreationDuring(
diff --git a/aos/ipc_lib/lockless_queue.cc b/aos/ipc_lib/lockless_queue.cc
index 5f12423..f380848 100644
--- a/aos/ipc_lib/lockless_queue.cc
+++ b/aos/ipc_lib/lockless_queue.cc
@@ -692,7 +692,7 @@
   queue.Initialize();
   LocklessQueueWatcher result(queue.memory(), priority);
   if (result.watcher_index_ != -1) {
-    return std::move(result);
+    return result;
   } else {
     return std::nullopt;
   }
@@ -891,7 +891,7 @@
   queue.Initialize();
   LocklessQueueSender result(queue.memory(), channel_storage_duration);
   if (result.sender_index_ != -1) {
-    return std::move(result);
+    return result;
   } else {
     return std::nullopt;
   }
@@ -1199,7 +1199,7 @@
   queue.Initialize();
   LocklessQueuePinner result(queue.memory(), queue.const_memory());
   if (result.pinner_index_ != -1) {
-    return std::move(result);
+    return result;
   } else {
     return std::nullopt;
   }
diff --git a/aos/network/web_proxy.h b/aos/network/web_proxy.h
index 2b57c05..e38dcea 100644
--- a/aos/network/web_proxy.h
+++ b/aos/network/web_proxy.h
@@ -229,7 +229,7 @@
     bool requested = true;
   };
 
-  std::map<int, ChannelState> channels_;
+  std::map<size_t, ChannelState> channels_;
   const std::vector<std::unique_ptr<Subscriber>> &subscribers_;
 
   const std::vector<FlatbufferDetachedBuffer<MessageHeader>> config_headers_;
diff --git a/debian/boringssl.patch b/debian/boringssl.patch
index ceae8bc..d12a7db 100644
--- a/debian/boringssl.patch
+++ b/debian/boringssl.patch
@@ -1,8 +1,16 @@
 diff --git a/BUILD b/BUILD
-index cba9ccb1d..7890c88e6 100644
+index cba9ccb1d..37fab16a7 100644
 --- a/BUILD
 +++ b/BUILD
-@@ -25,6 +25,8 @@ load(
+@@ -16,6 +16,7 @@ licenses(["notice"])
+ 
+ exports_files(["LICENSE"])
+ 
++load("@//tools/build_rules:select.bzl", "compiler_select")
+ load("@rules_cc//cc:defs.bzl", "cc_binary", "cc_library")
+ 
+ load(
+@@ -25,6 +26,8 @@ load(
      "crypto_sources",
      "crypto_sources_linux_x86_64",
      "crypto_sources_linux_ppc64le",
@@ -11,7 +19,7 @@
      "crypto_sources_mac_x86_64",
      "fips_fragments",
      "ssl_headers",
-@@ -36,7 +38,17 @@ load(
+@@ -36,7 +39,17 @@ load(
  
  config_setting(
      name = "linux_x86_64",
@@ -30,17 +38,18 @@
  )
  
  config_setting(
-@@ -76,6 +88,9 @@ posix_copts = [
+@@ -76,6 +89,10 @@ posix_copts = [
      "-Wwrite-strings",
      "-Wshadow",
      "-fno-common",
 +    "-Wno-cast-qual",
 +    "-Wno-cast-align",
 +    "-Wno-unused-parameter",
++    "-Wno-cast-function-type",
  
      # Modern build environments should be able to set this to use atomic
      # operations for reference counting rather than locks. However, it's
-@@ -86,6 +101,8 @@ posix_copts = [
+@@ -86,17 +103,26 @@ posix_copts = [
  boringssl_copts = select({
      ":linux_x86_64": posix_copts,
      ":linux_ppc64le": posix_copts,
@@ -49,7 +58,16 @@
      ":mac_x86_64": posix_copts,
      ":windows_x86_64": [
          "-DWIN32_LEAN_AND_MEAN",
-@@ -97,6 +114,8 @@ boringssl_copts = select({
+         "-DOPENSSL_NO_ASM",
+     ],
+     "//conditions:default": ["-DOPENSSL_NO_ASM"],
++}) + compiler_select({
++    "clang": [],
++    "gcc": [
++      "-Wno-array-parameter",
++    ],
+ })
+ 
  crypto_sources_asm = select({
      ":linux_x86_64": crypto_sources_linux_x86_64,
      ":linux_ppc64le": crypto_sources_linux_ppc64le,
@@ -58,7 +76,7 @@
      ":mac_x86_64": crypto_sources_mac_x86_64,
      "//conditions:default": [],
  })
-@@ -112,6 +131,8 @@ posix_copts_c11 = [
+@@ -112,6 +138,8 @@ posix_copts_c11 = [
  boringssl_copts_c11 = boringssl_copts + select({
      ":linux_x86_64": posix_copts_c11,
      ":linux_ppc64le": posix_copts_c11,
@@ -67,7 +85,7 @@
      ":mac_x86_64": posix_copts_c11,
      "//conditions:default": [],
  })
-@@ -125,6 +146,8 @@ posix_copts_cxx = [
+@@ -125,6 +153,8 @@ posix_copts_cxx = [
  boringssl_copts_cxx = boringssl_copts + select({
      ":linux_x86_64": posix_copts_cxx,
      ":linux_ppc64le": posix_copts_cxx,
diff --git a/debian/fts.patch b/debian/fts.patch
index 7357940..ff0c8d6 100644
--- a/debian/fts.patch
+++ b/debian/fts.patch
@@ -1,5 +1,5 @@
---- arm-frc2020-linux-gnueabi/usr/include/fts.h
-+++ arm-frc2020-linux-gnueabi/usr/include/fts.h
+--- arm-nilrt-linux-gnueabi/usr/include/fts.h
++++ arm-nilrt-linux-gnueabi/sysroot/usr/include/fts.h
 @@ -193,7 +193,7 @@ FTS *__REDIRECT (fts_open, (char * const *, int,
  				int (*)(const FTSENT **, const FTSENT **)),
  		     fts64_open);
diff --git a/debian/ni-libraries.BUILD b/debian/ni-libraries.BUILD
index 571f80f..e93895c 100644
--- a/debian/ni-libraries.BUILD
+++ b/debian/ni-libraries.BUILD
@@ -21,9 +21,9 @@
     srcs = [
         "libNiFpgaLv.so.13",
         "libnirio_emb_can.so.21",
-        "src/lib/chipobject/libRoboRIO_FRC_ChipObject.so.22.0.0",
-        "src/lib/netcomm/libFRC_NetworkCommunication.so.22.0.0",
-        "src/lib/visa/libvisa.so.21.0.0",
+        "src/lib/chipobject/libRoboRIO_FRC_ChipObject.so.23.0.0",
+        "src/lib/netcomm/libFRC_NetworkCommunication.so.23.0.0",
+        "src/lib/visa/libvisa.so.22.5.0",
     ],
     hdrs = glob(["src/include/**"]),
     includes = [
diff --git a/frc971/constants/constants_sender_lib.h b/frc971/constants/constants_sender_lib.h
index 6c849c3..92c14fa 100644
--- a/frc971/constants/constants_sender_lib.h
+++ b/frc971/constants/constants_sender_lib.h
@@ -14,17 +14,14 @@
 template <typename ConstantsData, typename ConstantsList>
 class ConstantSender {
  public:
-  ConstantSender<ConstantsData, ConstantsList>(
-      aos::EventLoop *event_loop, std::string constants_path,
-      std::string_view channel_name = "/constants")
+  ConstantSender(aos::EventLoop *event_loop, std::string constants_path,
+                 std::string_view channel_name = "/constants")
       : ConstantSender<ConstantsData, ConstantsList>(
             event_loop, constants_path, aos::network::GetTeamNumber(),
             channel_name) {}
 
-  ConstantSender<ConstantsData, ConstantsList>(aos::EventLoop *event_loop,
-                                               std::string constants_path,
-                                               const uint16_t team_number,
-                                               std::string_view channel_name)
+  ConstantSender(aos::EventLoop *event_loop, std::string constants_path,
+                 const uint16_t team_number, std::string_view channel_name)
       : team_number_(team_number),
         channel_name_(channel_name),
         constants_path_(constants_path),
diff --git a/frc971/control_loops/dlqr.h b/frc971/control_loops/dlqr.h
index ec70593..d7af426 100644
--- a/frc971/control_loops/dlqr.h
+++ b/frc971/control_loops/dlqr.h
@@ -38,9 +38,9 @@
 // Computes the optimal LQR controller K for the provided system and costs.
 template <int kN, int kM>
 int dlqr(::Eigen::Matrix<double, kN, kN> A, ::Eigen::Matrix<double, kN, kM> B,
-          ::Eigen::Matrix<double, kN, kN> Q, ::Eigen::Matrix<double, kM, kM> R,
-          ::Eigen::Matrix<double, kM, kN> *K,
-          ::Eigen::Matrix<double, kN, kN> *S) {
+         ::Eigen::Matrix<double, kN, kN> Q, ::Eigen::Matrix<double, kM, kM> R,
+         ::Eigen::Matrix<double, kM, kN> *K,
+         ::Eigen::Matrix<double, kN, kN> *S) {
   *K = ::Eigen::Matrix<double, kM, kN>::Zero();
   *S = ::Eigen::Matrix<double, kN, kN>::Zero();
   // Discrete (not continuous)
@@ -69,9 +69,9 @@
   double ALFAR[kN * 2];
   double ALFAI[kN * 2];
   double BETA[kN * 2];
-  memset(ALFAR, 0, kN * 2);
-  memset(ALFAI, 0, kN * 2);
-  memset(BETA, 0, kN * 2);
+  memset(ALFAR, 0, sizeof(ALFAR));
+  memset(ALFAI, 0, sizeof(ALFAI));
+  memset(BETA, 0, sizeof(BETA));
 
   long LDS = 2 * kN + kM;
   ::Eigen::Matrix<double, 2 * kN + kM, 2 *kN + kM> S_schur =
@@ -88,17 +88,17 @@
   double TOL = 0.0;
 
   long IWORK[2 * kN > kM ? 2 * kN : kM];
-  memset(IWORK, 0, 2 * kN > kM ? 2 * kN : kM);
+  memset(IWORK, 0, sizeof(IWORK));
 
   long LDWORK = 16 * kN + 3 * kM + 16;
 
   double DWORK[LDWORK];
-  memset(DWORK, 0, LDWORK);
+  memset(DWORK, 0, sizeof(DWORK));
 
   long INFO = 0;
 
-  long BWORK[2 * kN];
-  memset(BWORK, 0, 2 * kN);
+  long BWORK[kN * 2];
+  memset(BWORK, 0, sizeof(BWORK));
 
   // TODO(austin): I can't tell if anything here is transposed...
   sb02od_(&DICO, &JOBB, &FACT, &UPLO, &JOBL, &SORT, &N, &M, &P, A.data(), &N,
diff --git a/frc971/control_loops/drivetrain/hybrid_ekf_test.cc b/frc971/control_loops/drivetrain/hybrid_ekf_test.cc
index b491719..4bdf4de 100644
--- a/frc971/control_loops/drivetrain/hybrid_ekf_test.cc
+++ b/frc971/control_loops/drivetrain/hybrid_ekf_test.cc
@@ -338,8 +338,8 @@
 
 // Ensure that we check kSaveSamples - 1, for potential corner cases.
 INSTANTIATE_TEST_SUITE_P(OldCorrectionTest, HybridEkfOldCorrectionsTest,
-                        ::testing::Values(0, 1, 10,
-                                          HybridEkf<>::kSaveSamples - 1));
+                         ::testing::Values(0, 1, 10,
+                                           HybridEkf<>::kSaveSamples - 1));
 
 // Tests that creating a correction that is too old results in the correction
 // being dropped and ignored.
@@ -492,9 +492,10 @@
 TEST_F(HybridEkfDeathTest, DieOnNoU) {
   // Expect death if the user does not provide U when creating a fresh
   // measurement.
-  EXPECT_DEATH(ekf_.Correct({1, 2, 3}, nullptr, {}, {}, {}, {},
-                            t0_ + std::chrono::seconds(1)),
-               "U != nullptr");
+  EXPECT_DEATH(
+      ekf_.Correct({1, 2, 3}, nullptr, {}, {}, {}, Eigen::Matrix3d::Zero(),
+                   t0_ + std::chrono::seconds(1)),
+      "U != nullptr");
 }
 
 // Because the user can choose to provide only one of make_h or (h, dhdx), check
@@ -503,21 +504,22 @@
   // Check that we die when no h-related functions are provided:
   Input U;
   U << 1.0, 2.0, 0.0, 0.0;
-  EXPECT_DEATH(ekf_.Correct({1, 2, 3}, &U, {}, {}, {}, {},
+  EXPECT_DEATH(ekf_.Correct({1, 2, 3}, &U, {}, {}, {}, Eigen::Matrix3d::Zero(),
                             t0_ + std::chrono::seconds(1)),
                "make_h");
   // Check that we die when only one of h and dhdx are provided:
-  EXPECT_DEATH(ekf_.Correct({1, 2, 3}, &U, {}, {},
-                            [](const State &) {
-                              return Eigen::Matrix<double, 3, 12>::Zero();
-                            },
-                            {}, t0_ + std::chrono::seconds(1)),
-               "make_h");
-  EXPECT_DEATH(ekf_.Correct({1, 2, 3}, &U, {},
-                            [](const State &, const Input &) {
-                              return Eigen::Matrix<double, 3, 1>::Zero();
-                            },
-                            {}, {}, t0_ + std::chrono::seconds(1)),
+  EXPECT_DEATH(
+      ekf_.Correct(
+          {1, 2, 3}, &U, {}, {},
+          [](const State &) { return Eigen::Matrix<double, 3, 12>::Zero(); },
+          Eigen::Matrix3d::Zero(), t0_ + std::chrono::seconds(1)),
+      "make_h");
+  EXPECT_DEATH(ekf_.Correct(
+                   {1, 2, 3}, &U, {},
+                   [](const State &, const Input &) {
+                     return Eigen::Matrix<double, 3, 1>::Zero();
+                   },
+                   {}, Eigen::Matrix3d::Zero(), t0_ + std::chrono::seconds(1)),
                "make_h");
 }
 
diff --git a/frc971/wpilib/ADIS16448.cc b/frc971/wpilib/ADIS16448.cc
index 4be346c..597c5e8 100644
--- a/frc971/wpilib/ADIS16448.cc
+++ b/frc971/wpilib/ADIS16448.cc
@@ -128,9 +128,7 @@
   // 0.781MHz, so that's what this actually does.
   spi_->SetClockRate(1e5);
   spi_->SetChipSelectActiveLow();
-  spi_->SetClockActiveLow();
-  spi_->SetSampleDataOnFalling();
-  spi_->SetMSBFirst();
+  spi_->SetMode(frc::SPI::Mode::kMode3);
 
   dio1_->RequestInterrupts();
   dio1_->SetUpSourceEdge(true, false);
@@ -154,9 +152,7 @@
   if (dummy_spi_) {
     dummy_spi_->SetClockRate(1e5);
     dummy_spi_->SetChipSelectActiveLow();
-    dummy_spi_->SetClockActiveLow();
-    dummy_spi_->SetSampleDataOnFalling();
-    dummy_spi_->SetMSBFirst();
+    dummy_spi_->SetMode(frc::SPI::Mode::kMode3);
   }
 }
 
diff --git a/frc971/wpilib/ADIS16470.cc b/frc971/wpilib/ADIS16470.cc
index b7b315b..d43d2fb 100644
--- a/frc971/wpilib/ADIS16470.cc
+++ b/frc971/wpilib/ADIS16470.cc
@@ -204,9 +204,7 @@
   // We're not doing burst mode, so this is the IMU's rated speed.
   spi_->SetClockRate(2'000'000);
   spi_->SetChipSelectActiveLow();
-  spi_->SetClockActiveLow();
-  spi_->SetSampleDataOnTrailingEdge();
-  spi_->SetMSBFirst();
+  spi_->SetMode(frc::SPI::Mode::kMode3);
 
   // NI's SPI driver defaults to SCHED_OTHER.  Find it's PID with ps, and change
   // it to a RT priority of 33.
diff --git a/frc971/wpilib/ahal/DriverStation.cc b/frc971/wpilib/ahal/DriverStation.cc
index 8b31af7..8762203 100644
--- a/frc971/wpilib/ahal/DriverStation.cc
+++ b/frc971/wpilib/ahal/DriverStation.cc
@@ -8,9 +8,9 @@
 #include "frc971/wpilib/ahal/DriverStation.h"
 
 #include <chrono>
+#include <functional>
 #include <memory>
 #include <string_view>
-#include <functional>
 
 #include "FRC_NetworkCommunication/FRCComm.h"
 #include "frc971/wpilib/ahal/AnalogInput.h"
@@ -272,10 +272,10 @@
 }
 
 /**
-  * Returns the game specific message provided by the FMS.
-  *
-  * @return A string containing the game specific message.
-  */
+ * Returns the game specific message provided by the FMS.
+ *
+ * @return A string containing the game specific message.
+ */
 std::string_view DriverStation::GetGameSpecificMessage() const {
   return std::string_view(
       reinterpret_cast<const char *>(info_.gameSpecificMessage),
@@ -283,41 +283,35 @@
 }
 
 /**
-  * Returns the name of the competition event provided by the FMS.
-  *
-  * @return A string containing the event name
-  */
-std::string_view DriverStation::GetEventName() const {
-  return info_.eventName;
-}
+ * Returns the name of the competition event provided by the FMS.
+ *
+ * @return A string containing the event name
+ */
+std::string_view DriverStation::GetEventName() const { return info_.eventName; }
 
 /**
-  * Returns the match number provided by the FMS.
-  *
-  * @return The number of the match
-  */
+ * Returns the match number provided by the FMS.
+ *
+ * @return The number of the match
+ */
 DriverStation::MatchType DriverStation::GetMatchType() const {
   return static_cast<DriverStation::MatchType>(info_.matchType);
 }
 
 /**
-  * Returns the match number provided by the FMS.
-  *
-  * @return The number of the match
-  */
-int DriverStation::GetMatchNumber() const {
-  return info_.matchNumber;
-}
+ * Returns the match number provided by the FMS.
+ *
+ * @return The number of the match
+ */
+int DriverStation::GetMatchNumber() const { return info_.matchNumber; }
 
 /**
-  * Returns the number of times the current match has been replayed from the
-  * FMS.
-  *
-  * @return The number of replays
-  */
-int DriverStation::GetReplayNumber() const {
-  return info_.replayNumber;
-}
+ * Returns the number of times the current match has been replayed from the
+ * FMS.
+ *
+ * @return The number of replays
+ */
+int DriverStation::GetReplayNumber() const { return info_.replayNumber; }
 
 /**
  * Return the alliance that the driver station says it is on.
@@ -408,6 +402,8 @@
  * the data will be copied from the DS polling loop.
  */
 void DriverStation::GetData() {
+  HAL_RefreshDSData();
+
   // Get the status of all of the joysticks, and save to the cache
   for (uint8_t stick = 0; stick < kJoystickPorts; stick++) {
     HAL_GetJoystickAxes(stick, &m_joystickAxesCache[stick]);
@@ -475,7 +471,6 @@
 }
 
 void DriverStation::RunIteration(std::function<void()> on_data) {
-  HAL_WaitForDSData();
   GetData();
 
   // We have to feed some sort of watchdog so that the driver's station knows
diff --git a/frc971/wpilib/ahal/DutyCycle.cc b/frc971/wpilib/ahal/DutyCycle.cc
index 13ccaa0..b400cf3 100644
--- a/frc971/wpilib/ahal/DutyCycle.cc
+++ b/frc971/wpilib/ahal/DutyCycle.cc
@@ -75,13 +75,6 @@
   return retVal;
 }
 
-unsigned int DutyCycle::GetOutputRaw() const {
-  int32_t status = 0;
-  auto retVal = HAL_GetDutyCycleOutputRaw(m_handle, &status);
-  wpi_setHALError(status);
-  return retVal;
-}
-
 unsigned int DutyCycle::GetOutputScaleFactor() const {
   int32_t status = 0;
   auto retVal = HAL_GetDutyCycleOutputScaleFactor(m_handle, &status);
diff --git a/frc971/wpilib/ahal/DutyCycle.h b/frc971/wpilib/ahal/DutyCycle.h
index cfc9256..88d6a54 100644
--- a/frc971/wpilib/ahal/DutyCycle.h
+++ b/frc971/wpilib/ahal/DutyCycle.h
@@ -84,16 +84,6 @@
   double GetOutput() const;
 
   /**
-   * Get the raw output ratio of the duty cycle signal.
-   *
-   * <p> 0 means always low, an output equal to
-   * GetOutputScaleFactor() means always high.
-   *
-   * @return output ratio in raw units
-   */
-  unsigned int GetOutputRaw() const;
-
-  /**
    * Get the scale factor of the output.
    *
    * <p> An output equal to this value is always high, and then linearly scales
diff --git a/frc971/wpilib/ahal/SPI.cc b/frc971/wpilib/ahal/SPI.cc
index d51b20f..8568210 100644
--- a/frc971/wpilib/ahal/SPI.cc
+++ b/frc971/wpilib/ahal/SPI.cc
@@ -7,13 +7,13 @@
 
 #include "frc971/wpilib/ahal/SPI.h"
 
-#include <cstring>
-#include <utility>
-
 #include <hal/SPI.h>
 #include <wpi/SmallVector.h>
 #include <wpi/mutex.h>
 
+#include <cstring>
+#include <utility>
+
 #include "absl/types/span.h"
 #include "frc971/wpilib/ahal/DigitalSource.h"
 #include "frc971/wpilib/ahal/WPIErrors.h"
@@ -30,44 +30,37 @@
 
 void SPI::SetClockRate(int hz) { HAL_SetSPISpeed(m_port, hz); }
 
-void SPI::SetMSBFirst() {
-  m_msbFirst = true;
-  HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
-}
-
-void SPI::SetLSBFirst() {
-  m_msbFirst = false;
-  HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+void SPI::SetMode(Mode mode) {
+  m_mode = static_cast<HAL_SPIMode>(mode & 0x3);
+  HAL_SetSPIMode(m_port, m_mode);
 }
 
 void SPI::SetSampleDataOnLeadingEdge() {
-  m_sampleOnTrailing = false;
-  HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+  int mode = m_mode;
+  mode &= 2;
+  m_mode = static_cast<HAL_SPIMode>(mode);
+  HAL_SetSPIMode(m_port, m_mode);
 }
 
 void SPI::SetSampleDataOnTrailingEdge() {
-  m_sampleOnTrailing = true;
-  HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
-}
-
-void SPI::SetSampleDataOnFalling() {
-  m_sampleOnTrailing = true;
-  HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
-}
-
-void SPI::SetSampleDataOnRising() {
-  m_sampleOnTrailing = false;
-  HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+  int mode = m_mode;
+  mode |= 2;
+  m_mode = static_cast<HAL_SPIMode>(mode);
+  HAL_SetSPIMode(m_port, m_mode);
 }
 
 void SPI::SetClockActiveLow() {
-  m_clockIdleHigh = true;
-  HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+  int mode = m_mode;
+  mode |= 1;
+  m_mode = static_cast<HAL_SPIMode>(mode);
+  HAL_SetSPIMode(m_port, m_mode);
 }
 
 void SPI::SetClockActiveHigh() {
-  m_clockIdleHigh = false;
-  HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+  int mode = m_mode;
+  mode &= 1;
+  m_mode = static_cast<HAL_SPIMode>(mode);
+  HAL_SetSPIMode(m_port, m_mode);
 }
 
 void SPI::SetChipSelectActiveHigh() {
@@ -82,13 +75,13 @@
   wpi_setHALError(status);
 }
 
-int SPI::Write(uint8_t* data, int size) {
+int SPI::Write(uint8_t *data, int size) {
   int retVal = 0;
   retVal = HAL_WriteSPI(m_port, data, size);
   return retVal;
 }
 
-int SPI::Read(bool initiate, uint8_t* dataReceived, int size) {
+int SPI::Read(bool initiate, uint8_t *dataReceived, int size) {
   int retVal = 0;
   if (initiate) {
     wpi::SmallVector<uint8_t, 32> dataToSend;
@@ -100,7 +93,7 @@
   return retVal;
 }
 
-int SPI::Transaction(uint8_t* dataToSend, uint8_t* dataReceived, int size) {
+int SPI::Transaction(uint8_t *dataToSend, uint8_t *dataReceived, int size) {
   int retVal = 0;
   retVal = HAL_TransactionSPI(m_port, dataToSend, dataReceived, size);
   return retVal;
@@ -132,7 +125,7 @@
   wpi_setHALError(status);
 }
 
-void SPI::StartAutoTrigger(DigitalSource& source, bool rising, bool falling) {
+void SPI::StartAutoTrigger(DigitalSource &source, bool rising, bool falling) {
   int32_t status = 0;
   HAL_StartSPIAutoTrigger(
       m_port, source.GetPortHandleForRouting(),
@@ -155,8 +148,8 @@
 
 int SPI::ReadAutoReceivedData(uint32_t *buffer, int numToRead, double timeout) {
   int32_t status = 0;
-  int32_t val = HAL_ReadSPIAutoReceivedData(m_port, buffer, numToRead,
-                                            timeout, &status);
+  int32_t val =
+      HAL_ReadSPIAutoReceivedData(m_port, buffer, numToRead, timeout, &status);
   wpi_setHALError(status);
   return val;
 }
diff --git a/frc971/wpilib/ahal/SPI.h b/frc971/wpilib/ahal/SPI.h
index 6421535..542db80 100644
--- a/frc971/wpilib/ahal/SPI.h
+++ b/frc971/wpilib/ahal/SPI.h
@@ -9,11 +9,12 @@
 
 #include <hal/SPITypes.h>
 #include <wpi/deprecated.h>
-#include <wpi/span.h>
-#include "absl/types/span.h"
 
 #include <cstdint>
 #include <memory>
+#include <span>
+
+#include "absl/types/span.h"
 
 namespace frc {
 
@@ -29,6 +30,12 @@
 class SPI final {
  public:
   enum Port { kOnboardCS0 = 0, kOnboardCS1, kOnboardCS2, kOnboardCS3, kMXP };
+  enum Mode {
+    kMode0 = HAL_SPI_kMode0,
+    kMode1 = HAL_SPI_kMode1,
+    kMode2 = HAL_SPI_kMode2,
+    kMode3 = HAL_SPI_kMode3
+  };
 
   /**
    * Constructor
@@ -55,54 +62,73 @@
   /**
    * Configure the order that bits are sent and received on the wire
    * to be most significant bit first.
+   *
+   * @deprecated Does not work, will be removed.
    */
+  WPI_DEPRECATED("Not supported by roboRIO.")
   void SetMSBFirst();
 
   /**
    * Configure the order that bits are sent and received on the wire
    * to be least significant bit first.
+   *
+   * @deprecated Does not work, will be removed.
    */
+  WPI_DEPRECATED("Not supported by roboRIO.")
   void SetLSBFirst();
 
   /**
    * Configure that the data is stable on the leading edge and the data
    * changes on the trailing edge.
+   *
+   * @deprecated Use SetMode() instead.
    */
+  WPI_DEPRECATED("Use SetMode() instead")
   void SetSampleDataOnLeadingEdge();
 
   /**
    * Configure that the data is stable on the trailing edge and the data
    * changes on the leading edge.
+   *
+   * @deprecated Use SetMode() instead.
    */
+  WPI_DEPRECATED("Use SetMode() instead")
   void SetSampleDataOnTrailingEdge();
 
   /**
-   * Configure that the data is stable on the falling edge and the data
-   * changes on the rising edge.
-   */
-  WPI_DEPRECATED("Use SetSampleDataOnTrailingEdge in most cases.")
-  void SetSampleDataOnFalling();
-
-  /**
-   * Configure that the data is stable on the rising edge and the data
-   * changes on the falling edge.
-   */
-  WPI_DEPRECATED("Use SetSampleDataOnLeadingEdge in most cases")
-  void SetSampleDataOnRising();
-
-  /**
    * Configure the clock output line to be active low.
    * This is sometimes called clock polarity high or clock idle high.
+   *
+   * @deprecated Use SetMode() instead.
    */
+  WPI_DEPRECATED("Use SetMode() instead")
   void SetClockActiveLow();
 
   /**
    * Configure the clock output line to be active high.
    * This is sometimes called clock polarity low or clock idle low.
+   *
+   * @deprecated Use SetMode() instead.
    */
+  WPI_DEPRECATED("Use SetMode() instead")
   void SetClockActiveHigh();
 
   /**
+   * Sets the mode for the SPI device.
+   *
+   * <p>Mode 0 is Clock idle low, data sampled on rising edge
+   *
+   * <p>Mode 1 is Clock idle low, data sampled on falling edge
+   *
+   * <p>Mode 2 is Clock idle high, data sampled on falling edge
+   *
+   * <p>Mode 3 is Clock idle high, data sampled on rising edge
+   *
+   * @param mode The mode to set.
+   */
+  void SetMode(Mode mode);
+
+  /**
    * Configure the chip select line to be active high.
    */
   void SetChipSelectActiveHigh();
@@ -247,9 +273,7 @@
 
  protected:
   hal::SPIPort m_port;
-  bool m_msbFirst = false;          // Default little-endian
-  bool m_sampleOnTrailing = false;  // Default data updated on falling edge
-  bool m_clockIdleHigh = false;     // Default clock active high
+  HAL_SPIMode m_mode = HAL_SPIMode::HAL_SPI_kMode0;
 
  private:
   void Init();
diff --git a/frc971/wpilib/dma.cc b/frc971/wpilib/dma.cc
index 6cc8bf0..a2b2d20 100644
--- a/frc971/wpilib/dma.cc
+++ b/frc971/wpilib/dma.cc
@@ -317,7 +317,9 @@
   }
 }
 
-static_assert(::std::is_pod<DMASample>::value, "DMASample needs to be POD");
+static_assert(::std::is_trivial<DMASample>::value &&
+                  ::std::is_standard_layout<DMASample>::value,
+              "DMASample needs to be POD");
 
 ssize_t DMASample::offset(int index) const {
   return dma_->channel_offsets_[index];
diff --git a/frc971/wpilib/gyro_interface.cc b/frc971/wpilib/gyro_interface.cc
index 7ed24b7..a90e95a 100644
--- a/frc971/wpilib/gyro_interface.cc
+++ b/frc971/wpilib/gyro_interface.cc
@@ -18,9 +18,7 @@
   // The myRIO goes up to 4MHz, so the roboRIO probably does too.
   gyro_->SetClockRate(4e6);
   gyro_->SetChipSelectActiveLow();
-  gyro_->SetClockActiveHigh();
-  gyro_->SetSampleDataOnRising();
-  gyro_->SetMSBFirst();
+  gyro_->SetMode(frc::SPI::Mode::kMode3);
 }
 
 bool GyroInterface::InitializeGyro() {
diff --git a/frc971/wpilib/joystick_sender.cc b/frc971/wpilib/joystick_sender.cc
index 9137a99..26f7545 100644
--- a/frc971/wpilib/joystick_sender.cc
+++ b/frc971/wpilib/joystick_sender.cc
@@ -24,9 +24,13 @@
   event_loop_->OnRun([this]() {
     frc::DriverStation *const ds = &frc::DriverStation::GetInstance();
 
+    wpi::Event event{false, false};
+    HAL_ProvideNewDataEventHandle(event.GetHandle());
+
     // TODO(Brian): Fix the potential deadlock when stopping here (condition
     // variable / mutex needs to get exposed all the way out or something).
     while (event_loop_->is_running()) {
+      wpi::WaitForObject(event.GetHandle());
       ds->RunIteration([&]() {
         auto builder = joystick_state_sender_.MakeBuilder();
 
@@ -129,6 +133,8 @@
         }
       });
     }
+
+    HAL_RemoveNewDataEventHandle(event.GetHandle());
   });
 }
 
diff --git a/third_party/BUILD b/third_party/BUILD
index a550a24..145a7b3 100644
--- a/third_party/BUILD
+++ b/third_party/BUILD
@@ -35,6 +35,24 @@
         "@ctre_phoenix_api_cpp_headers//:api-cpp",
         "@ctre_phoenix_cci_athena//:cci",
         "@ctre_phoenix_cci_headers//:cci",
+        "@ctre_phoenixpro_tools_athena//:tools",
+        "@ctre_phoenixpro_tools_headers//:tools",
+    ],
+)
+
+cc_library(
+    name = "phoenixpro",
+    linkopts = [
+        "-Wl,-rpath",
+        "-Wl,.",
+    ],
+    target_compatible_with = ["//tools/platforms/hardware:roborio"],
+    visibility = ["//visibility:public"],
+    deps = [
+        "@ctre_phoenixpro_api_cpp_athena//:api-cpp",
+        "@ctre_phoenixpro_api_cpp_headers//:api-cpp",
+        "@ctre_phoenixpro_tools_athena//:tools",
+        "@ctre_phoenixpro_tools_headers//:tools",
     ],
 )
 
diff --git a/third_party/abseil/abseil.patch b/third_party/abseil/abseil.patch
index 748791b..981a7bc 100644
--- a/third_party/abseil/abseil.patch
+++ b/third_party/abseil/abseil.patch
@@ -1,8 +1,8 @@
 diff --git a/absl/copts/GENERATED_AbseilCopts.cmake b/absl/copts/GENERATED_AbseilCopts.cmake
-index 04e7b444..5d164438 100644
+index 04e7b444..81884a6d 100644
 --- a/absl/copts/GENERATED_AbseilCopts.cmake
 +++ b/absl/copts/GENERATED_AbseilCopts.cmake
-@@ -49,6 +49,12 @@ list(APPEND ABSL_GCC_FLAGS
+@@ -49,6 +49,13 @@ list(APPEND ABSL_GCC_FLAGS
      "-Wundef"
      "-Wunused-local-typedefs"
      "-Wunused-result"
@@ -12,10 +12,11 @@
 +    "-Wno-sign-conversion"
 +    "-Wno-shorten-64-to-32"
 +    "-Wno-shadow"
++    "-Wno-stringop-overflow"
      "-Wvarargs"
      "-Wvla"
      "-Wwrite-strings"
-@@ -66,6 +72,12 @@ list(APPEND ABSL_GCC_TEST_FLAGS
+@@ -66,6 +73,13 @@ list(APPEND ABSL_GCC_TEST_FLAGS
      "-Wundef"
      "-Wunused-local-typedefs"
      "-Wunused-result"
@@ -25,10 +26,11 @@
 +    "-Wno-sign-conversion"
 +    "-Wno-shorten-64-to-32"
 +    "-Wno-shadow"
++    "-Wno-stringop-overflow"
      "-Wvarargs"
      "-Wvla"
      "-Wwrite-strings"
-@@ -95,8 +107,8 @@ list(APPEND ABSL_LLVM_FLAGS
+@@ -95,8 +109,8 @@ list(APPEND ABSL_LLVM_FLAGS
      "-Woverlength-strings"
      "-Wpointer-arith"
      "-Wself-assign"
@@ -38,7 +40,7 @@
      "-Wsign-conversion"
      "-Wstring-conversion"
      "-Wtautological-overlap-compare"
-@@ -114,6 +126,11 @@ list(APPEND ABSL_LLVM_FLAGS
+@@ -114,6 +128,12 @@ list(APPEND ABSL_LLVM_FLAGS
      "-Wno-implicit-int-float-conversion"
      "-Wno-unknown-warning-option"
      "-DNOMINMAX"
@@ -47,10 +49,11 @@
 +    "-Wno-tautological-type-limit-compare"
 +    "-Wno-sign-conversion"
 +    "-Wno-shorten-64-to-32"
++    "-Wno-stringop-overflow"
  )
  
  list(APPEND ABSL_LLVM_TEST_FLAGS
-@@ -133,7 +150,7 @@ list(APPEND ABSL_LLVM_TEST_FLAGS
+@@ -133,7 +153,7 @@ list(APPEND ABSL_LLVM_TEST_FLAGS
      "-Woverlength-strings"
      "-Wpointer-arith"
      "-Wself-assign"
@@ -59,7 +62,7 @@
      "-Wstring-conversion"
      "-Wtautological-overlap-compare"
      "-Wtautological-unsigned-zero-compare"
-@@ -150,6 +167,11 @@ list(APPEND ABSL_LLVM_TEST_FLAGS
+@@ -150,6 +170,12 @@ list(APPEND ABSL_LLVM_TEST_FLAGS
      "-Wno-implicit-int-float-conversion"
      "-Wno-unknown-warning-option"
      "-DNOMINMAX"
@@ -68,14 +71,15 @@
 +    "-Wno-tautological-type-limit-compare"
 +    "-Wno-sign-conversion"
 +    "-Wno-shorten-64-to-32"
++    "-Wno-stringop-overflow"
      "-Wno-deprecated-declarations"
      "-Wno-implicit-int-conversion"
      "-Wno-missing-prototypes"
 diff --git a/absl/copts/GENERATED_copts.bzl b/absl/copts/GENERATED_copts.bzl
-index 84f4bffc..f15266dd 100644
+index 84f4bffc..21f487a1 100644
 --- a/absl/copts/GENERATED_copts.bzl
 +++ b/absl/copts/GENERATED_copts.bzl
-@@ -50,6 +50,12 @@ ABSL_GCC_FLAGS = [
+@@ -50,6 +50,13 @@ ABSL_GCC_FLAGS = [
      "-Wundef",
      "-Wunused-local-typedefs",
      "-Wunused-result",
@@ -85,10 +89,11 @@
 +    "-Wno-sign-conversion",
 +    "-Wno-shorten-64-to-32",
 +    "-Wno-shadow",
++    "-Wno-stringop-overflow",
      "-Wvarargs",
      "-Wvla",
      "-Wwrite-strings",
-@@ -67,6 +73,12 @@ ABSL_GCC_TEST_FLAGS = [
+@@ -67,6 +74,13 @@ ABSL_GCC_TEST_FLAGS = [
      "-Wundef",
      "-Wunused-local-typedefs",
      "-Wunused-result",
@@ -98,10 +103,11 @@
 +    "-Wno-sign-conversion",
 +    "-Wno-shorten-64-to-32",
 +    "-Wno-shadow",
++    "-Wno-stringop-overflow",
      "-Wvarargs",
      "-Wvla",
      "-Wwrite-strings",
-@@ -96,8 +108,8 @@ ABSL_LLVM_FLAGS = [
+@@ -96,8 +110,8 @@ ABSL_LLVM_FLAGS = [
      "-Woverlength-strings",
      "-Wpointer-arith",
      "-Wself-assign",
@@ -111,7 +117,7 @@
      "-Wsign-conversion",
      "-Wstring-conversion",
      "-Wtautological-overlap-compare",
-@@ -115,6 +127,11 @@ ABSL_LLVM_FLAGS = [
+@@ -115,6 +129,12 @@ ABSL_LLVM_FLAGS = [
      "-Wno-implicit-int-float-conversion",
      "-Wno-unknown-warning-option",
      "-DNOMINMAX",
@@ -120,10 +126,11 @@
 +    "-Wno-tautological-type-limit-compare",
 +    "-Wno-sign-conversion",
 +    "-Wno-shorten-64-to-32",
++    "-Wno-stringop-overflow",
  ]
  
  ABSL_LLVM_TEST_FLAGS = [
-@@ -134,7 +151,7 @@ ABSL_LLVM_TEST_FLAGS = [
+@@ -134,7 +154,7 @@ ABSL_LLVM_TEST_FLAGS = [
      "-Woverlength-strings",
      "-Wpointer-arith",
      "-Wself-assign",
@@ -132,7 +139,7 @@
      "-Wstring-conversion",
      "-Wtautological-overlap-compare",
      "-Wtautological-unsigned-zero-compare",
-@@ -151,6 +168,11 @@ ABSL_LLVM_TEST_FLAGS = [
+@@ -151,6 +171,12 @@ ABSL_LLVM_TEST_FLAGS = [
      "-Wno-implicit-int-float-conversion",
      "-Wno-unknown-warning-option",
      "-DNOMINMAX",
@@ -141,14 +148,15 @@
 +    "-Wno-tautological-type-limit-compare",
 +    "-Wno-sign-conversion",
 +    "-Wno-shorten-64-to-32",
++    "-Wno-stringop-overflow",
      "-Wno-deprecated-declarations",
      "-Wno-implicit-int-conversion",
      "-Wno-missing-prototypes",
 diff --git a/absl/copts/copts.py b/absl/copts/copts.py
-index 06eeb67b..bfd49c1d 100644
+index 06eeb67b..d2a3e74f 100644
 --- a/absl/copts/copts.py
 +++ b/absl/copts/copts.py
-@@ -23,6 +23,12 @@ ABSL_GCC_FLAGS = [
+@@ -23,6 +23,13 @@ ABSL_GCC_FLAGS = [
      "-Wundef",
      "-Wunused-local-typedefs",
      "-Wunused-result",
@@ -158,10 +166,11 @@
 +    "-Wno-sign-conversion",
 +    "-Wno-shorten-64-to-32",
 +    "-Wno-shadow",
++    "-Wno-stringop-overflow",
      "-Wvarargs",
      "-Wvla",  # variable-length array
      "-Wwrite-strings",
-@@ -56,8 +62,8 @@ ABSL_LLVM_FLAGS = [
+@@ -56,8 +63,8 @@ ABSL_LLVM_FLAGS = [
      "-Woverlength-strings",
      "-Wpointer-arith",
      "-Wself-assign",
@@ -171,7 +180,7 @@
      "-Wsign-conversion",
      "-Wstring-conversion",
      "-Wtautological-overlap-compare",
-@@ -80,6 +86,11 @@ ABSL_LLVM_FLAGS = [
+@@ -80,6 +87,12 @@ ABSL_LLVM_FLAGS = [
      "-Wno-unknown-warning-option",
      # Don't define min and max macros (Build on Windows using clang)
      "-DNOMINMAX",
@@ -180,6 +189,7 @@
 +    "-Wno-tautological-type-limit-compare",
 +    "-Wno-sign-conversion",
 +    "-Wno-shorten-64-to-32",
++    "-Wno-stringop-overflow",
  ]
  
  ABSL_LLVM_TEST_ADDITIONAL_FLAGS = [
diff --git a/third_party/allwpilib/.clang-format b/third_party/allwpilib/.clang-format
index 2643c1b..fef62d1 100644
--- a/third_party/allwpilib/.clang-format
+++ b/third_party/allwpilib/.clang-format
@@ -1,5 +1,4 @@
 ---
-Language:        Cpp
 BasedOnStyle:  Google
 AccessModifierOffset: -1
 AlignAfterOpenBracket: Align
diff --git a/third_party/allwpilib/.clang-tidy b/third_party/allwpilib/.clang-tidy
index b68e2ed..62783c0 100644
--- a/third_party/allwpilib/.clang-tidy
+++ b/third_party/allwpilib/.clang-tidy
@@ -53,7 +53,6 @@
   google-readability-avoid-underscore-in-googletest-name,
   google-readability-casting,
   google-runtime-operator,
-  llvm-twine-local,
   misc-definitions-in-headers,
   misc-misplaced-const,
   misc-new-delete-overloads,
@@ -70,6 +69,3 @@
   modernize-use-using,
   readability-braces-around-statements'
 FormatStyle: file
-CheckOptions:
-  - key: bugprone-dangling-handle
-    value: 'wpi::StringRef;wpi::Twine'
diff --git a/third_party/allwpilib/.github/workflows/cmake.yml b/third_party/allwpilib/.github/workflows/cmake.yml
index c0c0be7..f465a16 100644
--- a/third_party/allwpilib/.github/workflows/cmake.yml
+++ b/third_party/allwpilib/.github/workflows/cmake.yml
@@ -2,64 +2,55 @@
 
 on: [pull_request, push]
 
+concurrency:
+  group: ${{ github.workflow }}-${{ github.head_ref || github.ref }}
+  cancel-in-progress: true
+
 jobs:
   build:
     strategy:
       fail-fast: false
       matrix:
         include:
-          - os: ubuntu-latest
+          - os: ubuntu-22.04
             name: Linux
-            container: wpilib/roborio-cross-ubuntu:2022-20.04
+            container: wpilib/roborio-cross-ubuntu:2023-22.04
             flags: ""
           - os: macOS-11
             name: macOS
             container: ""
             flags: "-DWITH_JAVA=OFF"
+
     name: "Build - ${{ matrix.name }}"
     runs-on: ${{ matrix.os }}
     container: ${{ matrix.container }}
     steps:
-      - uses: actions/checkout@v2
-      - name: Install Dependencies
-        run: |
-          if [ "$RUNNER_OS" == "macOS" ]; then
-            brew install opencv
-          fi
-      - name: Set up Python 3.8
-        uses: actions/setup-python@v2
+      - uses: actions/checkout@v3
+
+      - name: Install dependencies (Linux)
+        if: runner.os == 'Linux'
+        run: sudo apt-get update && sudo apt-get install -y libopencv-dev libopencv4.5-java python-is-python3
+
+      - name: Install opencv (macOS)
+        run: brew install opencv
+        if: runner.os == 'macOS'
+
+      - name: Set up Python 3.8 (macOS)
+        if: runner.os == 'macOS'
+        uses: actions/setup-python@v4
         with:
           python-version: 3.8
+
       - name: Install jinja
         run: python -m pip install jinja2
+
       - name: configure
         run: mkdir build && cd build && cmake ${{ matrix.flags }} ..
+
       - name: build
         working-directory: build
-        run: cmake --build . -j$(nproc)
+        run: cmake --build . --parallel $(nproc)
+
       - name: test
         working-directory: build
         run: ctest --output-on-failure
-
-  build-vcpkg:
-    name: "Build - Windows"
-    runs-on: windows-2019
-    steps:
-      - uses: actions/checkout@v2
-      - name: Prepare vcpkg
-        uses: lukka/run-vcpkg@v7
-        with:
-          vcpkgArguments: opencv
-          vcpkgDirectory: ${{ runner.workspace }}/vcpkg
-          vcpkgTriplet: x64-windows
-          vcpkgGitCommitId: d781bd9ca77ac3dc2f13d88169021d48459c665f # HEAD on 2021-07-25
-      - name: Configure & Build
-        uses: lukka/run-cmake@v3
-        with:
-          buildDirectory: ${{ runner.workspace }}/build
-          cmakeAppendedArgs: -DWITH_JAVA=OFF
-          cmakeListsOrSettingsJson: CMakeListsTxtAdvanced
-          useVcpkgToolchainFile: true
-      - name: Run Tests
-        run: ctest -C "Debug" --output-on-failure
-        working-directory: ${{ runner.workspace }}/build
diff --git a/third_party/allwpilib/.github/workflows/comment-command.yml b/third_party/allwpilib/.github/workflows/comment-command.yml
new file mode 100644
index 0000000..f58ed18
--- /dev/null
+++ b/third_party/allwpilib/.github/workflows/comment-command.yml
@@ -0,0 +1,64 @@
+name: Comment Commands
+on:
+  issue_comment:
+    types: [ created ]
+
+jobs:
+  format:
+    if: github.event.issue.pull_request && startsWith(github.event.comment.body, '/format')
+    runs-on: ubuntu-22.04
+    steps:
+      - name: React Rocket
+        uses: actions/github-script@v4
+        with:
+          script: |
+            const {owner, repo} = context.issue
+            github.reactions.createForIssueComment({
+              owner,
+              repo,
+              comment_id: context.payload.comment.id,
+              content: "rocket",
+            });
+      - uses: actions/checkout@v3
+        with:
+          token: ${{ secrets.COMMENT_COMMAND_PAT_TOKEN }}
+      - name: Fetch all history and metadata
+        run: |
+          git fetch --prune --unshallow
+          git checkout -b pr
+          git branch -f main origin/main
+      - name: Checkout PR
+        run: |
+          gh pr checkout $NUMBER
+        env:
+          GITHUB_TOKEN: "${{ secrets.COMMENT_COMMAND_PAT_TOKEN }}"
+          NUMBER: ${{ github.event.issue.number }}
+      - name: Set up Python 3.8
+        uses: actions/setup-python@v2
+        with:
+          python-version: 3.8
+      - name: Setup Java
+        uses: actions/setup-java@v3
+        with:
+          distribution: 'zulu'
+          java-version: 11
+      - name: Install clang-format
+        run: |
+          wget -O - https://apt.llvm.org/llvm-snapshot.gpg.key | sudo apt-key add -
+          sudo sh -c "echo 'deb http://apt.llvm.org/jammy/ llvm-toolchain-jammy-14 main' >> /etc/apt/sources.list.d/proposed-repositories.list"
+          sudo apt-get update -q
+          sudo apt-get install -y clang-format-14
+      - name: Install wpiformat
+        run: pip3 install wpiformat
+      - name: Run wpiformat
+        run: wpiformat -clang 14
+      - name: Run spotlessApply
+        run: ./gradlew spotlessApply
+      - name: Commit
+        run: |
+          # Set credentials
+          git config user.name "github-actions[bot]"
+          git config user.email "41898282+github-actions[bot]@users.noreply.github.com"
+          # Commit
+          git commit -am "Formatting fixes"
+          git push
diff --git a/third_party/allwpilib/.github/workflows/documentation.yml b/third_party/allwpilib/.github/workflows/documentation.yml
index ab59b0f..c963383 100644
--- a/third_party/allwpilib/.github/workflows/documentation.yml
+++ b/third_party/allwpilib/.github/workflows/documentation.yml
@@ -2,24 +2,28 @@
 
 on: [push, workflow_dispatch]
 
+concurrency:
+  group: ${{ github.workflow }}-${{ github.ref }}
+  cancel-in-progress: true
+
 env:
   BASE_PATH: allwpilib/docs
 
 jobs:
   publish:
     name: "Documentation - Publish"
-    runs-on: ubuntu-latest
+    runs-on: ubuntu-22.04
     if: github.repository_owner == 'wpilibsuite' && (github.ref == 'refs/heads/main' || startsWith(github.ref, 'refs/tags/v'))
+    concurrency: ci-docs-publish
     steps:
-      - uses: actions/checkout@v2
+      - uses: actions/checkout@v3
         with:
           fetch-depth: 0
           persist-credentials: false
-      - uses: actions/setup-java@v1
+      - uses: actions/setup-java@v3
         with:
+          distribution: 'zulu'
           java-version: 13
-      - name: Install libclang-9
-        run: sudo apt update && sudo apt install -y libclang-cpp9 libclang1-9
       - name: Set environment variables (Development)
         run: |
           echo "TARGET_FOLDER=$BASE_PATH/development" >> $GITHUB_ENV
@@ -37,7 +41,7 @@
       - name: Build with Gradle
         run: ./gradlew docs:generateJavaDocs docs:doxygen -PbuildServer ${{ env.EXTRA_GRADLE_ARGS }}
       - name: Install SSH Client 🔑
-        uses: webfactory/ssh-agent@v0.4.1
+        uses: webfactory/ssh-agent@v0.7.0
         with:
           ssh-private-key: ${{ secrets.GH_DEPLOY_KEY }}
       - name: Deploy Java 🚀
diff --git a/third_party/allwpilib/.github/workflows/gazebo.yml b/third_party/allwpilib/.github/workflows/gazebo.yml
deleted file mode 100644
index 53948fb..0000000
--- a/third_party/allwpilib/.github/workflows/gazebo.yml
+++ /dev/null
@@ -1,15 +0,0 @@
-name: Gazebo
-
-on: [pull_request, push]
-
-jobs:
-  build:
-    name: "Build"
-    runs-on: ubuntu-latest
-    container: wpilib/gazebo-ubuntu:18.04
-    steps:
-      - uses: actions/checkout@v2
-        with:
-          fetch-depth: 0
-      - name: Build with Gradle
-        run: ./gradlew simulation:frc_gazebo_plugins:build simulation:halsim_gazebo:build -PbuildServer -PforceGazebo
diff --git a/third_party/allwpilib/.github/workflows/gradle-wrapper-validation.yml b/third_party/allwpilib/.github/workflows/gradle-wrapper-validation.yml
index c16f58f..d678bc4 100644
--- a/third_party/allwpilib/.github/workflows/gradle-wrapper-validation.yml
+++ b/third_party/allwpilib/.github/workflows/gradle-wrapper-validation.yml
@@ -1,10 +1,14 @@
 name: "Validate Gradle Wrapper"
 on: [pull_request, push]
 
+concurrency:
+  group: ${{ github.workflow }}-${{ github.head_ref || github.ref }}
+  cancel-in-progress: true
+
 jobs:
   validation:
     name: "Validation"
     runs-on: ubuntu-latest
     steps:
-      - uses: actions/checkout@v2
+      - uses: actions/checkout@v3
       - uses: gradle/wrapper-validation-action@v1
diff --git a/third_party/allwpilib/.github/workflows/gradle.yml b/third_party/allwpilib/.github/workflows/gradle.yml
index e05b3e6..f603a50 100644
--- a/third_party/allwpilib/.github/workflows/gradle.yml
+++ b/third_party/allwpilib/.github/workflows/gradle.yml
@@ -2,66 +2,87 @@
 
 on: [pull_request, push]
 
+concurrency:
+  group: ${{ github.workflow }}-${{ github.head_ref || github.ref }}
+  cancel-in-progress: true
+
 jobs:
   build-docker:
     strategy:
       fail-fast: false
       matrix:
         include:
-          - container: wpilib/roborio-cross-ubuntu:2022-18.04
+          - container: wpilib/roborio-cross-ubuntu:2023-22.04
             artifact-name: Athena
             build-options: "-Ponlylinuxathena"
-          - container: wpilib/raspbian-cross-ubuntu:10-18.04
-            artifact-name: Raspbian
-            build-options: "-Ponlylinuxraspbian"
-          - container: wpilib/aarch64-cross-ubuntu:bionic-18.04
-            artifact-name: Aarch64
-            build-options: "-Ponlylinuxaarch64bionic"
-          - container: wpilib/ubuntu-base:18.04
+          - container: wpilib/raspbian-cross-ubuntu:bullseye-22.04
+            artifact-name: Arm32
+            build-options: "-Ponlylinuxarm32"
+          - container: wpilib/aarch64-cross-ubuntu:bullseye-22.04
+            artifact-name: Arm64
+            build-options: "-Ponlylinuxarm64"
+          - container: wpilib/ubuntu-base:22.04
             artifact-name: Linux
-            build-options: "-Dorg.gradle.jvmargs=-Xmx2g"
+            build-options: "-Ponlylinuxx86-64"
     name: "Build - ${{ matrix.artifact-name }}"
-    runs-on: ubuntu-latest
+    runs-on: ubuntu-22.04
     container: ${{ matrix.container }}
     steps:
-      - uses: actions/checkout@v2
+      - uses: actions/checkout@v3
         with:
           fetch-depth: 0
       - name: Set release environment variable
         run: echo "EXTRA_GRADLE_ARGS=-PreleaseMode" >> $GITHUB_ENV
         if: startsWith(github.ref, 'refs/tags/v')
       - name: Build with Gradle
-        run: ./gradlew build -PbuildServer -PskipJavaFormat ${{ matrix.build-options }} ${{ env.EXTRA_GRADLE_ARGS }}
-      - uses: actions/upload-artifact@v2
+        run: ./gradlew build --build-cache -PbuildServer -PskipJavaFormat ${{ matrix.build-options }} ${{ env.EXTRA_GRADLE_ARGS }}
+        env:
+          ARTIFACTORY_PUBLISH_USERNAME: ${{ secrets.ARTIFACTORY_USERNAME }}
+          ARTIFACTORY_PUBLISH_PASSWORD: ${{ secrets.ARTIFACTORY_PASSWORD }}
+      - uses: actions/upload-artifact@v3
         with:
           name: ${{ matrix.artifact-name }}
           path: build/allOutputs
 
   build-host:
     env:
-      MACOSX_DEPLOYMENT_TARGET: 10.14
+      MACOSX_DEPLOYMENT_TARGET: 10.15
     strategy:
       fail-fast: false
       matrix:
         include:
-          - os: windows-2019
-            artifact-name: Win64
+          - os: windows-2022
+            artifact-name: Win64Debug
             architecture: x64
-          - os: windows-2019
-            artifact-name: Win32
-            architecture: x86
+            task: "build"
+            build-options: "-PciDebugOnly --max-workers 1"
+            outputs: "build/allOutputs"
+          - os: windows-2022
+            artifact-name: Win64Release
+            architecture: x64
+            build-options: "-PciReleaseOnly --max-workers 1"
+            task: "copyAllOutputs"
+            outputs: "build/allOutputs"
           - os: macOS-11
             artifact-name: macOS
             architecture: x64
+            task: "build"
+            outputs: "build/allOutputs"
+          - os: windows-2022
+            artifact-name: Win32
+            architecture: x86
+            task: ":ntcoreffi:build"
+            outputs: "ntcoreffi/build/outputs"
     name: "Build - ${{ matrix.artifact-name }}"
     runs-on: ${{ matrix.os }}
     steps:
-      - uses: actions/checkout@v2
+      - uses: actions/checkout@v3
         with:
           fetch-depth: 0
-      - uses: actions/setup-java@v1
+      - uses: actions/setup-java@v3
         with:
-          java-version: 11
+          distribution: 'zulu'
+          java-version: 17
           architecture: ${{ matrix.architecture }}
       - name: Import Developer ID Certificate
         uses: wpilibsuite/import-signing-certificate@v1
@@ -81,36 +102,44 @@
         run: echo "EXTRA_GRADLE_ARGS=-PreleaseMode" >> $GITHUB_ENV
         shell: bash
         if: startsWith(github.ref, 'refs/tags/v')
+      - name: Set Java Heap Size
+        run: sed -i 's/-Xmx2g/-Xmx1g/g' gradle.properties
+        if: matrix.artifact-name == 'Win32'
       - name: Build with Gradle
-        run: ./gradlew build -PbuildServer -PskipJavaFormat ${{ env.EXTRA_GRADLE_ARGS }}
+        run: ./gradlew ${{ matrix.task }} --build-cache -PbuildServer -PskipJavaFormat ${{ matrix.build-options }} ${{ env.EXTRA_GRADLE_ARGS }}
+        env:
+          ARTIFACTORY_PUBLISH_USERNAME: ${{ secrets.ARTIFACTORY_USERNAME }}
+          ARTIFACTORY_PUBLISH_PASSWORD: ${{ secrets.ARTIFACTORY_PASSWORD }}
       - name: Sign Libraries with Developer ID
-        run: ./gradlew build -PbuildServer -PskipJavaFormat -PdeveloperID=${{ secrets.APPLE_DEVELOPER_ID }} ${{ env.EXTRA_GRADLE_ARGS }}
+        run: ./gradlew copyAllOutputs --build-cache -PbuildServer -PskipJavaFormat -PdeveloperID=${{ secrets.APPLE_DEVELOPER_ID }} ${{ matrix.build-options }} ${{ env.EXTRA_GRADLE_ARGS }}
         if: |
           matrix.artifact-name == 'macOS' && (github.repository_owner == 'wpilibsuite' &&
           (github.ref == 'refs/heads/main' || startsWith(github.ref, 'refs/tags/v')))
-      - uses: actions/upload-artifact@v2
+      - uses: actions/upload-artifact@v3
         with:
           name: ${{ matrix.artifact-name }}
-          path: build/allOutputs
+          path: ${{ matrix.outputs }}
 
   build-documentation:
     name: "Build - Documentation"
-    runs-on: ubuntu-latest
+    runs-on: ubuntu-22.04
     steps:
-      - uses: actions/checkout@v2
+      - uses: actions/checkout@v3
         with:
           fetch-depth: 0
-      - uses: actions/setup-java@v1
+      - uses: actions/setup-java@v3
         with:
+          distribution: 'zulu'
           java-version: 13
-      - name: Install libclang-9
-        run: sudo apt update && sudo apt install -y libclang-cpp9 libclang1-9
       - name: Set release environment variable
         run: echo "EXTRA_GRADLE_ARGS=-PreleaseMode" >> $GITHUB_ENV
         if: startsWith(github.ref, 'refs/tags/v')
       - name: Build with Gradle
-        run: ./gradlew docs:zipDocs -PbuildServer ${{ env.EXTRA_GRADLE_ARGS }}
-      - uses: actions/upload-artifact@v2
+        run: ./gradlew docs:zipDocs --build-cache -PbuildServer ${{ env.EXTRA_GRADLE_ARGS }}
+        env:
+          ARTIFACTORY_PUBLISH_USERNAME: ${{ secrets.ARTIFACTORY_USERNAME }}
+          ARTIFACTORY_PUBLISH_PASSWORD: ${{ secrets.ARTIFACTORY_PASSWORD }}
+      - uses: actions/upload-artifact@v3
         with:
           name: Documentation
           path: docs/build/outputs
@@ -118,12 +147,12 @@
   combine:
     name: Combine
     needs: [build-docker, build-host, build-documentation]
-    runs-on: ubuntu-latest
+    runs-on: ubuntu-22.04
     steps:
-      - uses: actions/checkout@v2
+      - uses: actions/checkout@v3
         with:
           repository: wpilibsuite/build-tools
-      - uses: actions/download-artifact@v2
+      - uses: actions/download-artifact@v3
         with:
           path: combiner/products/build/allOutputs
       - name: Flatten Artifacts
@@ -132,8 +161,9 @@
         run: |
           cat combiner/products/build/allOutputs/version.txt
           test -s combiner/products/build/allOutputs/version.txt
-      - uses: actions/setup-java@v1
+      - uses: actions/setup-java@v3
         with:
+          distribution: 'zulu'
           java-version: 11
       - name: Combine
         if: |
@@ -158,7 +188,7 @@
           RUN_AZURE_ARTIFACTORY_RELEASE: "TRUE"
           ARTIFACTORY_PUBLISH_USERNAME: ${{ secrets.ARTIFACTORY_USERNAME }}
           ARTIFACTORY_PUBLISH_PASSWORD: ${{ secrets.ARTIFACTORY_PASSWORD }}
-      - uses: actions/upload-artifact@v2
+      - uses: actions/upload-artifact@v3
         with:
           name: Maven
           path: ~/releases
diff --git a/third_party/allwpilib/.github/workflows/lint-format.yml b/third_party/allwpilib/.github/workflows/lint-format.yml
index 6d806f7..ba25a05 100644
--- a/third_party/allwpilib/.github/workflows/lint-format.yml
+++ b/third_party/allwpilib/.github/workflows/lint-format.yml
@@ -6,61 +6,76 @@
     branches-ignore:
       - main
 
+concurrency:
+  group: ${{ github.workflow }}-${{ github.head_ref || github.ref }}
+  cancel-in-progress: true
+
 jobs:
   wpiformat:
     name: "wpiformat"
-    runs-on: ubuntu-latest
-    container: wpilib/roborio-cross-ubuntu:2022-20.04
+    runs-on: ubuntu-22.04
     steps:
-      - uses: actions/checkout@v2
+      - uses: actions/checkout@v3
       - name: Fetch all history and metadata
         run: |
+          git config --global --add safe.directory /__w/allwpilib/allwpilib
           git fetch --prune --unshallow
           git checkout -b pr
           git branch -f main origin/main
       - name: Set up Python 3.8
-        uses: actions/setup-python@v2
+        uses: actions/setup-python@v4
         with:
           python-version: 3.8
       - name: Install clang-format
         run: |
-          sudo sh -c "echo 'deb http://archive.ubuntu.com/ubuntu/ $(lsb_release -cs)-proposed restricted main multiverse universe' >> /etc/apt/sources.list.d/proposed-repositories.list"
+          wget -O - https://apt.llvm.org/llvm-snapshot.gpg.key | sudo apt-key add -
+          sudo sh -c "echo 'deb http://apt.llvm.org/jammy/ llvm-toolchain-jammy-14 main' >> /etc/apt/sources.list.d/proposed-repositories.list"
           sudo apt-get update -q
-          sudo apt-get install -y clang-format-12
+          sudo apt-get install -y clang-format-14
       - name: Install wpiformat
         run: pip3 install wpiformat
       - name: Run
-        run: wpiformat -clang 12
+        run: wpiformat -clang 14
       - name: Check output
         run: git --no-pager diff --exit-code HEAD
       - name: Generate diff
         run: git diff HEAD > wpiformat-fixes.patch
         if: ${{ failure() }}
-      - uses: actions/upload-artifact@v2
+      - uses: actions/upload-artifact@v3
         with:
           name: wpiformat fixes
           path: wpiformat-fixes.patch
         if: ${{ failure() }}
+      - name: Write to job summary
+        run: |
+          echo '```diff' >> $GITHUB_STEP_SUMMARY
+          cat wpiformat-fixes.patch >> $GITHUB_STEP_SUMMARY
+          echo '' >> $GITHUB_STEP_SUMMARY
+          echo '```' >> $GITHUB_STEP_SUMMARY
+        if: ${{ failure() }}
+
   tidy:
     name: "clang-tidy"
-    runs-on: ubuntu-latest
-    container: wpilib/roborio-cross-ubuntu:2022-20.04
+    runs-on: ubuntu-22.04
+    container: wpilib/roborio-cross-ubuntu:2023-22.04
     steps:
-      - uses: actions/checkout@v2
+      - uses: actions/checkout@v3
       - name: Fetch all history and metadata
         run: |
+          git config --global --add safe.directory /__w/allwpilib/allwpilib
           git fetch --prune --unshallow
           git checkout -b pr
           git branch -f main origin/main
       - name: Set up Python 3.8
-        uses: actions/setup-python@v2
+        uses: actions/setup-python@v4
         with:
           python-version: 3.8
       - name: Install clang-tidy
         run: |
-          sudo sh -c "echo 'deb http://archive.ubuntu.com/ubuntu/ $(lsb_release -cs)-proposed restricted main multiverse universe' >> /etc/apt/sources.list.d/proposed-repositories.list"
+          wget -O - https://apt.llvm.org/llvm-snapshot.gpg.key | sudo apt-key add -
+          sudo sh -c "echo 'deb http://apt.llvm.org/jammy/ llvm-toolchain-jammy-14 main' >> /etc/apt/sources.list.d/proposed-repositories.list"
           sudo apt-get update -q
-          sudo apt-get install -y clang-tidy-12 clang-format-12
+          sudo apt-get install -y clang-tidy-14 clang-format-14
       - name: Install wpiformat
         run: pip3 install wpiformat
       - name: Create compile_commands.json
@@ -68,15 +83,19 @@
       - name: List changed files
         run: wpiformat -list-changed-files
       - name: Run clang-tidy
-        run: wpiformat -clang 12 -no-format -tidy-changed -compile-commands=build/compile_commands/linuxx86-64 -vv
+        run: wpiformat -clang 14 -no-format -tidy-changed -compile-commands=build/compile_commands/linuxx86-64 -vv
   javaformat:
     name: "Java format"
-    runs-on: ubuntu-latest
-    container: wpilib/ubuntu-base:18.04
+    runs-on: ubuntu-22.04
+    container: wpilib/ubuntu-base:22.04
     steps:
-      - uses: actions/checkout@v2
-        with:
-          fetch-depth: 0
+      - uses: actions/checkout@v3
+      - name: Fetch all history and metadata
+        run: |
+          git config --global --add safe.directory /__w/allwpilib/allwpilib
+          git fetch --prune --unshallow
+          git checkout -b pr
+          git branch -f main origin/main
       - name: Run Java format
         run: ./gradlew javaFormat spotbugsMain spotbugsTest spotbugsDev
       - name: Check output
@@ -86,15 +105,14 @@
         if: ${{ failure() }}
   documentation:
     name: "Documentation"
-    runs-on: ubuntu-latest
+    runs-on: ubuntu-22.04
     steps:
-      - uses: actions/checkout@v2
+      - uses: actions/checkout@v3
         with:
           fetch-depth: 0
-      - uses: actions/setup-java@v1
+      - uses: actions/setup-java@v3
         with:
+          distribution: 'zulu'
           java-version: 13
-      - name: Install libclang-9
-        run: sudo apt update && sudo apt install -y libclang-cpp9 libclang1-9
       - name: Build with Gradle
         run: ./gradlew docs:zipDocs -PbuildServer -PdocWarningsAsErrors ${{ env.EXTRA_GRADLE_ARGS }}
diff --git a/third_party/allwpilib/.github/workflows/sanitizers.yml b/third_party/allwpilib/.github/workflows/sanitizers.yml
index 8c0e516..3f68a61 100644
--- a/third_party/allwpilib/.github/workflows/sanitizers.yml
+++ b/third_party/allwpilib/.github/workflows/sanitizers.yml
@@ -2,6 +2,10 @@
 
 on: [pull_request, push]
 
+concurrency:
+  group: ${{ github.workflow }}-${{ github.head_ref || github.ref }}
+  cancel-in-progress: true
+
 jobs:
   build:
     strategy:
@@ -11,39 +15,34 @@
           - name: asan
             cmake-flags: "-DCMAKE_BUILD_TYPE=Asan"
             ctest-env: ""
-            ctest-flags: "-E 'wpiutil|ntcore|wpilibc'"
+            ctest-flags: "-E 'wpilibc'"
           - name: tsan
             cmake-flags: "-DCMAKE_BUILD_TYPE=Tsan"
             ctest-env: "TSAN_OPTIONS=second_deadlock_stack=1"
-            ctest-flags: "-E 'ntcore|cscore|cameraserver|wpilibc|wpilibNewCommands'"
+            ctest-flags: "-E 'cscore|cameraserver|wpilibc|wpilibNewCommands'"
           - name: ubsan
             cmake-flags: "-DCMAKE_BUILD_TYPE=Ubsan"
             ctest-env: ""
             ctest-flags: ""
     name: "${{ matrix.name }}"
-    runs-on: ubuntu-latest
-    container: wpilib/roborio-cross-ubuntu:2022-20.04
+    runs-on: ubuntu-22.04
+    container: wpilib/roborio-cross-ubuntu:2023-22.04
     steps:
-      - uses: actions/checkout@v2
+      - uses: actions/checkout@v3
+
       - name: Install Dependencies
-        run: |
-          sudo add-apt-repository ppa:ubuntu-toolchain-r/test
-          sudo apt install -y gcc-11 g++-11
-          sudo update-alternatives \
-            --install /usr/bin/gcc gcc /usr/bin/gcc-11 11 \
-            --slave /usr/bin/g++ g++ /usr/bin/g++-11
-          sudo update-alternatives --set gcc /usr/bin/gcc-11
-      - name: Set up Python 3.8
-        uses: actions/setup-python@v2
-        with:
-          python-version: 3.8
+        run: sudo apt-get update && sudo apt-get install -y libopencv-dev libopencv4.5-java python-is-python3 clang-14
+
       - name: Install jinja
         run: python -m pip install jinja2
+
       - name: configure
-        run: mkdir build && cd build && cmake ${{ matrix.cmake-flags }} ..
+        run: mkdir build && cd build && cmake -DCMAKE_C_COMPILER:FILEPATH=/usr/bin/clang-14 -DCMAKE_CXX_COMPILER:FILEPATH=/usr/bin/clang++-14 ${{ matrix.cmake-flags }} ..
+
       - name: build
         working-directory: build
-        run: cmake --build . -j$(nproc)
+        run: cmake --build . --parallel $(nproc)
+
       - name: test
         working-directory: build
         run: ${{ matrix.ctest-env }} ctest --output-on-failure ${{ matrix.ctest-flags }}
diff --git a/third_party/allwpilib/.github/workflows/upstream-utils.yml b/third_party/allwpilib/.github/workflows/upstream-utils.yml
new file mode 100644
index 0000000..ea6e9aa
--- /dev/null
+++ b/third_party/allwpilib/.github/workflows/upstream-utils.yml
@@ -0,0 +1,67 @@
+name: Upstream utils
+
+on:
+  pull_request:
+  push:
+    branches-ignore:
+      - main
+
+concurrency:
+  group: ${{ github.workflow }}-${{ github.head_ref || github.ref }}
+  cancel-in-progress: true
+
+jobs:
+  update:
+    name: "Update"
+    runs-on: ubuntu-22.04
+    steps:
+      - uses: actions/checkout@v3
+      - name: Fetch all history and metadata
+        run: |
+          git fetch --prune --unshallow
+          git checkout -b pr
+          git branch -f main origin/main
+      - name: Set up Python 3.9
+        uses: actions/setup-python@v4
+        with:
+          python-version: 3.9
+      - name: Configure committer identity
+        run: |
+          git config --global user.email "you@example.com"
+          git config --global user.name "Your Name"
+      - name: Run update_drake.py
+        run: |
+          cd upstream_utils
+          ./update_drake.py
+      - name: Run update_eigen.py
+        run: |
+          cd upstream_utils
+          ./update_eigen.py
+      - name: Run update_fmt.py
+        run: |
+          cd upstream_utils
+          ./update_fmt.py
+      - name: Run update_libuv.py
+        run: |
+          cd upstream_utils
+          ./update_libuv.py
+      - name: Run update_llvm.py
+        run: |
+          cd upstream_utils
+          ./update_llvm.py
+      - name: Run update_mpack.py
+        run: |
+          cd upstream_utils
+          ./update_mpack.py
+      - name: Run update_stack_walker.py
+        run: |
+          cd upstream_utils
+          ./update_stack_walker.py
+      - name: Run update_memory.py
+        run: |
+          cd upstream_utils
+          ./update_memory.py
+      - name: Add untracked files to index so they count as changes
+        run: git add -A
+      - name: Check output
+        run: git --no-pager diff --exit-code HEAD
diff --git a/third_party/allwpilib/.gitignore b/third_party/allwpilib/.gitignore
index 6a6dde7..8db5645 100644
--- a/third_party/allwpilib/.gitignore
+++ b/third_party/allwpilib/.gitignore
@@ -5,6 +5,10 @@
 build*/
 !buildSrc/
 
+simgui-ds.json
+simgui-window.json
+simgui.json
+
 # Created by the jenkins test script
 test-reports
 
@@ -15,6 +19,9 @@
 .idea/
 out/
 
+# Fleet
+.fleet
+
 # Created by http://www.gitignore.io
 
 ### Linux ###
diff --git a/third_party/allwpilib/.styleguide b/third_party/allwpilib/.styleguide
index b17762e..9df73f7 100644
--- a/third_party/allwpilib/.styleguide
+++ b/third_party/allwpilib/.styleguide
@@ -18,6 +18,7 @@
   FRCNetComm\.java$
   simulation/gz_msgs/src/include/simulation/gz_msgs/msgs\.h$
   fieldImages/src/main/native/resources/
+  apriltag/src/test/resources/
 }
 
 repoRootNameOverride {
@@ -44,4 +45,5 @@
   ^wpi/
   ^wpigui
   ^wpimath/
+  ^wpinet/
 }
diff --git a/third_party/allwpilib/CMakeLists.txt b/third_party/allwpilib/CMakeLists.txt
index 5296f02..076eca2 100644
--- a/third_party/allwpilib/CMakeLists.txt
+++ b/third_party/allwpilib/CMakeLists.txt
@@ -36,25 +36,25 @@
 # (but later on when installing)
 SET(CMAKE_BUILD_WITH_INSTALL_RPATH FALSE)
 
-SET(CMAKE_INSTALL_RPATH "${CMAKE_INSTALL_PREFIX}/wpilib/lib")
+SET(CMAKE_INSTALL_RPATH "${CMAKE_INSTALL_PREFIX}/lib")
 
 # add the automatically determined parts of the RPATH
 # which point to directories outside the build tree to the install RPATH
 SET(CMAKE_INSTALL_RPATH_USE_LINK_PATH TRUE)
 
 # the RPATH to be used when installing, but only if it's not a system directory
-LIST(FIND CMAKE_PLATFORM_IMPLICIT_LINK_DIRECTORIES "${CMAKE_INSTALL_PREFIX}/wpilib/lib" isSystemDir)
+LIST(FIND CMAKE_PLATFORM_IMPLICIT_LINK_DIRECTORIES "${CMAKE_INSTALL_PREFIX}/lib" isSystemDir)
 IF("${isSystemDir}" STREQUAL "-1")
-   SET(CMAKE_INSTALL_RPATH "${CMAKE_INSTALL_PREFIX}/wpilib/lib")
+   SET(CMAKE_INSTALL_RPATH "${CMAKE_INSTALL_PREFIX}/lib")
 ENDIF("${isSystemDir}" STREQUAL "-1")
 
 # Options for building certain parts of the repo. Everything is built by default.
 option(BUILD_SHARED_LIBS "Build with shared libs (needed for JNI)" ON)
 option(WITH_JAVA "Include java and JNI in the build" ON)
 option(WITH_CSCORE "Build cscore (needs OpenCV)" ON)
+option(WITH_NTCORE "Build ntcore" ON)
 option(WITH_WPIMATH "Build wpimath" ON)
 option(WITH_WPILIB "Build hal, wpilibc/j, and myRobot (needs OpenCV)" ON)
-option(WITH_OLD_COMMANDS "Build old commands" OFF)
 option(WITH_EXAMPLES "Build examples" OFF)
 option(WITH_TESTS "Build unit tests (requires internet connection)" ON)
 option(WITH_GUI "Build GUI items" ON)
@@ -64,10 +64,10 @@
 option(WITH_EXTERNAL_HAL "Use a separately built HAL" OFF)
 set(EXTERNAL_HAL_FILE "" CACHE FILEPATH "Location to look for an external HAL CMake File")
 
-# Options for using a package manager (vcpkg) for certain dependencies.
-option(USE_VCPKG_FMTLIB "Use vcpkg fmtlib" OFF)
-option(USE_VCPKG_LIBUV "Use vcpkg libuv" OFF)
-option(USE_VCPKG_EIGEN "Use vcpkg eigen" OFF)
+# Options for using a package manager (e.g., vcpkg) for certain dependencies.
+option(USE_SYSTEM_FMTLIB "Use system fmtlib" OFF)
+option(USE_SYSTEM_LIBUV "Use system libuv" OFF)
+option(USE_SYSTEM_EIGEN "Use system eigen" OFF)
 
 # Options for installation.
 option(WITH_FLAT_INSTALL "Use a flat install directory" OFF)
@@ -118,6 +118,34 @@
 ")
 endif()
 
+if (NOT WITH_NTCORE AND WITH_CSCORE)
+    message(FATAL_ERROR "
+FATAL: Cannot build cameraserver without ntcore.
+       Enable ntcore by setting WITH_NTCORE=ON
+")
+endif()
+
+if (NOT WITH_NTCORE AND WITH_GUI)
+    message(FATAL_ERROR "
+FATAL: Cannot build GUI modules without ntcore.
+       Enable ntcore by setting WITH_NTCORE=ON
+")
+endif()
+
+if (NOT WITH_NTCORE AND WITH_SIMULATION_MODULES)
+    message(FATAL_ERROR "
+FATAL: Cannot build simulation modules without ntcore.
+       Enable ntcore by setting WITH_NTCORE=ON
+")
+endif()
+
+if (NOT WITH_NTCORE AND WITH_WPILIB)
+    message(FATAL_ERROR "
+FATAL: Cannot build wpilib without ntcore.
+       Enable ntcore by setting WITH_NTCORE=ON
+")
+endif()
+
 if (NOT WITH_WPIMATH AND WITH_WPILIB)
     message(FATAL_ERROR "
 FATAL: Cannot build wpilib without wpimath.
@@ -125,11 +153,11 @@
 ")
 endif()
 
-set( wpilib_dest wpilib)
-set( include_dest wpilib/include )
-set( main_lib_dest wpilib/lib )
-set( java_lib_dest wpilib/java )
-set( jni_lib_dest wpilib/jni )
+set( wpilib_dest "")
+set( include_dest include )
+set( main_lib_dest lib )
+set( java_lib_dest java )
+set( jni_lib_dest jni )
 
 if (WITH_FLAT_INSTALL)
     set (wpilib_config_dir ${wpilib_dest})
@@ -137,18 +165,22 @@
     set (wpilib_config_dir share/wpilib)
 endif()
 
-if (USE_VCPKG_LIBUV)
-set (LIBUV_VCPKG_REPLACE "find_package(unofficial-libuv CONFIG)")
+if (USE_SYSTEM_LIBUV)
+set (LIBUV_SYSTEM_REPLACE "
+find_package(PkgConfig REQUIRED)
+pkg_check_modules(libuv REQUIRED IMPORTED_TARGET libuv)
+")
 endif()
 
-if (USE_VCPKG_EIGEN)
-set (EIGEN_VCPKG_REPLACE "find_package(Eigen3 CONFIG)")
+if (USE_SYSTEM_EIGEN)
+set (EIGEN_SYSTEM_REPLACE "find_package(Eigen3 CONFIG)")
 endif()
 
 find_package(LIBSSH 0.7.1)
 
 if (WITH_FLAT_INSTALL)
 set(WPIUTIL_DEP_REPLACE "include($\{SELF_DIR\}/wpiutil-config.cmake)")
+set(WPINET_DEP_REPLACE "include($\{SELF_DIR\}/wpinet-config.cmake)")
 set(NTCORE_DEP_REPLACE "include($\{SELF_DIR\}/ntcore-config.cmake)")
 set(CSCORE_DEP_REPLACE_IMPL "include(\${SELF_DIR}/cscore-config.cmake)")
 set(CAMERASERVER_DEP_REPLACE_IMPL "include(\${SELF_DIR}/cameraserver-config.cmake)")
@@ -156,9 +188,9 @@
 set(WPIMATH_DEP_REPLACE "include($\{SELF_DIR\}/wpimath-config.cmake)")
 set(WPILIBC_DEP_REPLACE_IMPL "include(\${SELF_DIR}/wpilibc-config.cmake)")
 set(WPILIBNEWCOMMANDS_DEP_REPLACE "include(\${SELF_DIR}/wpilibNewcommands-config.cmake)")
-set(WPILIBOLDCOMMANDS_DEP_REPLACE "include(\${SELF_DIR}/wpilibOldcommands-config.cmake)")
 else()
 set(WPIUTIL_DEP_REPLACE "find_dependency(wpiutil)")
+set(WPINET_DEP_REPLACE "find_dependency(wpinet)")
 set(NTCORE_DEP_REPLACE "find_dependency(ntcore)")
 set(CSCORE_DEP_REPLACE_IMPL "find_dependency(cscore)")
 set(CAMERASERVER_DEP_REPLACE_IMPL "find_dependency(cameraserver)")
@@ -166,7 +198,6 @@
 set(WPIMATH_DEP_REPLACE "find_dependency(wpimath)")
 set(WPILIBC_DEP_REPLACE_IMPL "find_dependency(wpilibc)")
 set(WPILIBNEWCOMMANDS_DEP_REPLACE "find_dependency(wpilibNewCommands)")
-set(WPILIBOLDCOMMANDS_DEP_REPLACE "find_dependency(wpilibOldCommands)")
 endif()
 
 set(FILENAME_DEP_REPLACE "get_filename_component(SELF_DIR \"$\{CMAKE_CURRENT_LIST_FILE\}\" PATH)")
@@ -248,7 +279,11 @@
 endif()
 
 add_subdirectory(wpiutil)
-add_subdirectory(ntcore)
+
+if (WITH_NTCORE)
+    add_subdirectory(wpinet)
+    add_subdirectory(ntcore)
+endif()
 
 if (WITH_WPIMATH)
     add_subdirectory(wpimath)
@@ -262,6 +297,7 @@
     add_subdirectory(outlineviewer)
     if (LIBSSH_FOUND)
         add_subdirectory(roborioteamnumbersetter)
+        add_subdirectory(datalogtool)
     endif()
 endif()
 
@@ -279,12 +315,10 @@
 
 if (WITH_WPILIB)
     set(WPILIBC_DEP_REPLACE ${WPILIBC_DEP_REPLACE_IMPL})
+    add_subdirectory(apriltag)
     add_subdirectory(wpilibj)
     add_subdirectory(wpilibc)
     add_subdirectory(wpilibNewCommands)
-    if (WITH_OLD_COMMANDS)
-        add_subdirectory(wpilibOldCommands)
-    endif()
     if (WITH_EXAMPLES)
         add_subdirectory(wpilibcExamples)
     endif()
diff --git a/third_party/allwpilib/CONTRIBUTING.md b/third_party/allwpilib/CONTRIBUTING.md
index 61f121d..d4ab59c 100644
--- a/third_party/allwpilib/CONTRIBUTING.md
+++ b/third_party/allwpilib/CONTRIBUTING.md
@@ -37,8 +37,7 @@
 
 ## Coding Guidelines
 
-WPILib uses modified Google style guides for both C++ and Java, which can be found in the [styleguide repository](https://github.com/wpilibsuite/styleguide). Autoformatters are available for many popular editors at https://github.com/google/styleguide. Running wpiformat is required for all contributions and is enforced by our continuous integration system. We currently use clang-format 10.0 with wpiformat.
-
+WPILib uses modified Google style guides for both C++ and Java, which can be found in the [styleguide repository](https://github.com/wpilibsuite/styleguide). Autoformatters are available for many popular editors at https://github.com/google/styleguide. Running wpiformat is required for all contributions and is enforced by our continuous integration system.
 While the library should be fully formatted according to the styles, additional elements of the style guide were not followed when the library was initially created. All new code should follow the guidelines. If you are looking for some easy ramp-up tasks, finding areas that don't follow the style guide and fixing them is very welcome.
 
 When writing math expressions in documentation, use https://www.unicodeit.net/ to convert LaTeX to a Unicode equivalent that's easier to read. Not all expressions will translate (e.g., superscripts of superscripts) so focus on making it readable by someone who isn't familiar with LaTeX. If content on multiple lines needs to be aligned in Doxygen/Javadoc comments (e.g., integration/summation limits, matrices packed with square brackets and superscripts for them), put them in @verbatim/@endverbatim blocks in Doxygen or `<pre>` tags in Javadoc so they render with monospace font.
diff --git a/third_party/allwpilib/DevelopmentBuilds.md b/third_party/allwpilib/DevelopmentBuilds.md
new file mode 100644
index 0000000..e452f3a
--- /dev/null
+++ b/third_party/allwpilib/DevelopmentBuilds.md
@@ -0,0 +1,98 @@
+# Installing Development Builds
+
+This article contains instructions on building projects using a development build and a local WPILib build.
+
+**Note:** This only applies to Java/C++ teams.
+
+## Development Build
+
+Development builds are the per-commit build hosted every time a commit is pushed to the [allwpilib](https://github.com/wpilibsuite/allwpilib/) repository. These builds are then hosted on [artifactory](https://frcmaven.wpi.edu/artifactory/webapp/#/home).
+
+To build a project using a development build, find the build.gradle file and open it. Then, add the following code below the plugin section and replace YEAR with the year of the development version. It is also necessary to use a 2023 GradleRIO version, ie `2023.0.0-alpha-1`
+
+```groovy
+wpi.maven.useLocal = false
+wpi.maven.useDevelopment = true
+wpi.versions.wpilibVersion = 'YEAR.+'
+wpi.versions.wpimathVersion = 'YEAR.+
+```
+
+The top of your ``build.gradle`` file should now look similar to the code below. Ignore any differences in versions.
+
+Java
+```groovy
+plugins {
+  id "java"
+  id "edu.wpi.first.GradleRIO" version "2023.0.0-alpha-1"
+}
+
+wpi.maven.useLocal = false
+wpi.maven.useDevelopment = true
+wpi.versions.wpilibVersion = '2023.+'
+wpi.versions.wpimathVersion = '2023.+'
+```
+
+C++
+```groovy
+plugins {
+  id "cpp"
+  id "google-test-test-suite"
+  id "edu.wpi.first.GradleRIO" version "2023.0.0-alpha-1"
+}
+
+wpi.maven.useLocal = false
+wpi.maven.useDevelopment = true
+wpi.versions.wpilibVersion = '2023.+'
+wpi.versions.wpimathVersion = '2023.+'
+```
+
+### Development Build Documentation
+
+* C++: https://github.wpilib.org/allwpilib/docs/development/cpp/
+* Java: https://github.wpilib.org/allwpilib/docs/development/java/
+
+## Local Build
+
+Building with a local build is very similar to building with a development build. Ensure you have built and published WPILib by following the instructions attached [here](https://github.com/wpilibsuite/allwpilib#building-wpilib). Next, find the ``build.gradle`` file in your robot project and open it. Then, add the following code below the plugin section and replace ``YEAR`` with the year of the local version.
+
+Java
+```groovy
+plugins {
+  id "java"
+  id "edu.wpi.first.GradleRIO" version "2023.0.0-alpha-1"
+}
+
+wpi.maven.useLocal = false
+wpi.maven.useFrcMavenLocalDevelopment = true
+wpi.versions.wpilibVersion = 'YEAR.424242.+'
+wpi.versions.wpimathVersion = 'YEAR.424242.+'
+```
+
+C++
+```groovy
+plugins {
+  id "cpp"
+  id "google-test-test-suite"
+  id "edu.wpi.first.GradleRIO" version "2023.0.0-alpha-1"
+}
+
+wpi.maven.useLocal = false
+wpi.maven.useFrcMavenLocalDevelopment = true
+wpi.versions.wpilibVersion = 'YEAR.424242.+'
+wpi.versions.wpimathVersion = 'YEAR.424242.+'
+```
+
+# roboRIO Development
+
+This repo contains a myRobot project built in way to do full project development without needing to do a full publish into GradleRIO. These also only require building the minimum amount of binaries for the roboRIO, so the builds are much faster as well.
+
+The setup only works if the roboRIO is USB connected. If an alternate IP address is preferred, the `address` block in myRobot\build.gradle can be changed to point to another address.
+
+The following 3 tasks can be used for deployment:
+* `:myRobot:deployShared` deploys the C++ project using shared dependencies. Prefer this one for most C++ development.
+* `:myRobot:deployStatic` deploys the C++ project with all dependencies statically linked.
+* `:myRobot:deployJava` deploys the Java project and all required dependencies. Also installs the JRE if not currently installed.
+
+Deploying any of these to the roboRIO will disable the current startup project until it is redeployed.
+
+From here, ssh into the roboRIO using the `lvuser` account and run `frcRunRobot.sh` (It's in path).
diff --git a/third_party/allwpilib/MavenArtifacts.md b/third_party/allwpilib/MavenArtifacts.md
index 2b93b26..8ea5a49 100644
--- a/third_party/allwpilib/MavenArtifacts.md
+++ b/third_party/allwpilib/MavenArtifacts.md
@@ -72,12 +72,16 @@
 * wpigui
   * imgui
 
-* ntcore
-  * wpiutil
-
 * wpimath
   * wpiutil
 
+* wpinet
+  * wpiutil
+
+* ntcore
+  * wpiutil
+  * wpinet
+
 * glass/libglass
   * wpiutil
   * wpimath
@@ -85,6 +89,7 @@
 
 * glass/libglassnt
   * wpiutil
+  * wpinet
   * ntcore
   * wpimath
   * wpigui
@@ -94,6 +99,7 @@
 
 * halsim
   * wpiutil
+  * wpinet
   * ntcore
   * wpimath
   * wpigui
@@ -102,12 +108,14 @@
 
 * cscore
   * opencv
+  * wpinet
   * wpiutil
 
 * cameraserver
   * ntcore
   * cscore
   * opencv
+  * wpinet
   * wpiutil
 
 * wpilibj
@@ -115,6 +123,7 @@
   * cameraserver
   * ntcore
   * cscore
+  * wpinet
   * wpiutil
 
 * wpilibc
@@ -123,6 +132,7 @@
   * ntcore
   * cscore
   * wpimath
+  * wpinet
   * wpiutil
 
 * wpilibNewCommands
@@ -132,14 +142,7 @@
   * ntcore
   * cscore
   * wpimath
-  * wpiutil
-
-* wpilibOldCommands
-  * wpilibc
-  * hal
-  * cameraserver
-  * ntcore
-  * cscore
+  * wpinet
   * wpiutil
 
 
diff --git a/third_party/allwpilib/OtherVersions.md b/third_party/allwpilib/OtherVersions.md
deleted file mode 100644
index a58b9fb..0000000
--- a/third_party/allwpilib/OtherVersions.md
+++ /dev/null
@@ -1,93 +0,0 @@
-# Installing Development Builds
-
-This article contains instructions on building projects using a development build and a local WPILib build.
-
-**Note:** This only applies to Java/C++ teams.
-
-## Development Build
-
-Development builds are the per-commit build hosted everytime a commit is pushed to the [allwpilib](https://github.com/wpilibsuite/allwpilib/) repository. These builds are then hosted on [artifactory](https://frcmaven.wpi.edu/artifactory/webapp/#/home).
-
-In order to build a project using a development build, find the build.gradle file and open it. Then, add the following code below the plugin section and replace YEAR with the year of the development version.
-
-```groovy
-wpi.maven.useLocal = false
-wpi.maven.useDevelopment = true
-wpi.versions.wpilibVersion = 'YEAR.+'
-wpi.versions.wpimathVersion = 'YEAR.+
-```
-
-The top of your ``build.gradle`` file should now look similar to the code below. Ignore any differences in versions.
-
-Java
-```groovy
-plugins {
-  id "java"
-  id "edu.wpi.first.GradleRIO" version "2022.1.1"
-}
-
-wpi.maven.useLocal = false
-wpi.maven.useDevelopment = true
-wpi.versions.wpilibVersion = '2022.+'
-wpi.versions.wpimathVersion = '2022.+'
-```
-
-C++
-```groovy
-plugins {
-  id "cpp"
-  id "google-test-test-suite"
-  id "edu.wpi.first.GradleRIO" version "2022.1.1"
-}
-
-wpi.maven.useLocal = false
-wpi.maven.useDevelopment = true
-wpi.versions.wpilibVersion = '2022.+'
-wpi.versions.wpimathVersion = '2022.+'
-```
-
-## Local Build
-
-Building with a local build is very similar to building with a development build. Ensure you have built and published WPILib by following the instructions attached [here](https://github.com/wpilibsuite/allwpilib#building-wpilib). Next, find the ``build.gradle`` file in your robot project and open it. Then, add the following code below the plugin section and replace ``YEAR`` with the year of the local version.
-
-Java
-```groovy
-plugins {
-  id "java"
-  id "edu.wpi.first.GradleRIO" version "2022.1.1"
-}
-
-wpi.maven.useLocal = false
-wpi.maven.useFrcMavenLocalDevelopment = true
-wpi.versions.wpilibVersion = 'YEAR.424242.+'
-wpi.versions.wpimathVersion = 'YEAR.424242.+'
-```
-
-C++
-```groovy
-plugins {
-  id "cpp"
-  id "google-test-test-suite"
-  id "edu.wpi.first.GradleRIO" version "2022.1.1"
-}
-
-wpi.maven.useLocal = false
-wpi.maven.useFrcMavenLocalDevelopment = true
-wpi.versions.wpilibVersion = 'YEAR.424242.+'
-wpi.versions.wpimathVersion = 'YEAR.424242.+'
-```
-
-# roboRIO Development
-
-This repo contains a myRobot project built in way to do full project development without needing to do a full publish into GradleRIO. These also only require building the minimum amount of binaries for the roboRIO, so the builds are much faster as well.
-
-The setup only works if the roboRIO is USB connected. If an alternate IP address is preferred, the `address` block in myRobot\build.gradle can be changed to point to another address.
-
-The following 3 tasks can be used for deployment:
-* `:myRobot:deployShared` deploys the C++ project using shared dependencies. Prefer this one for most C++ development.
-* `:myRobot:deployStatic` deploys the C++ project with all dependencies statically linked.
-* `:myRobot:deployJava` deploys the Java project and all required dependencies. Also installs the JRE if not currently installed.
-
-Deploying any of these to the roboRIO will disable the current startup project until it is redeployed.
-
-From here, ssh into the roboRIO using the `admin` account (`lvuser` will fail to run in many cases). In the admin home directory, a file for each deploy type will exist (`myRobotCpp`, `myRobotCppStatic` and `myRobotJavaRun`). These can be run to start up the corresponding project.
diff --git a/third_party/allwpilib/README-CMAKE.md b/third_party/allwpilib/README-CMAKE.md
index 361a5b9..6a10d5b 100644
--- a/third_party/allwpilib/README-CMAKE.md
+++ b/third_party/allwpilib/README-CMAKE.md
@@ -31,14 +31,20 @@
   * This option will enable Java and JNI builds. If this is on, `WITH_SHARED_LIBS` must be on. Otherwise CMake will error.
 * `WITH_SHARED_LIBS` (ON Default)
   * This option will cause cmake to build static libraries instead of shared libraries. If this is off, `WITH_JAVA` must be off. Otherwise CMake will error.
-* `WITH_TESTS` (ON Default)
-  * This option will build C++ unit tests. These can be run via `make test`.
 * `WITH_CSCORE` (ON Default)
   * This option will cause cscore to be built. Turning this off will implicitly disable cameraserver, the hal and wpilib as well, irrespective of their specific options. If this is off, the OpenCV build requirement is removed.
+* `WITH_NTCORE` (ON Default)
+  * This option will cause ntcore to be built. Turning this off will implicitly disable wpinet and wpilib as well, irrespective of their specific options.
 * `WITH_WPIMATH` (ON Default)
   * This option will build the wpimath library. This option must be on to build wpilib.
 * `WITH_WPILIB` (ON Default)
   * This option will build the hal and wpilibc/j during the build. The HAL is the simulator hal, unless the external hal options are used. The cmake build has no capability to build for the RoboRIO.
+* `WITH_EXAMPLES` (ON Default)
+  * This option will build C++ examples.
+* `WITH_TESTS` (ON Default)
+  * This option will build C++ unit tests. These can be run via `make test`.
+* `WITH_GUI` (ON Default)
+  * This option will build GUI items.
 * `WITH_SIMULATION_MODULES` (ON Default)
   * This option will build simulation modules, including wpigui and the HALSim plugins.
 * `WITH_EXTERNAL_HAL` (OFF Default)
diff --git a/third_party/allwpilib/README.md b/third_party/allwpilib/README.md
index 62dccc1..998d91f 100644
--- a/third_party/allwpilib/README.md
+++ b/third_party/allwpilib/README.md
@@ -1,8 +1,8 @@
 # WPILib Project
 
-![CI](https://github.com/wpilibsuite/allwpilib/workflows/CI/badge.svg)
-[![C++ Documentation](https://img.shields.io/badge/documentation-c%2B%2B-blue)](https://first.wpi.edu/wpilib/allwpilib/docs/development/cpp/)
-[![Java Documentation](https://img.shields.io/badge/documentation-java-orange)](https://first.wpi.edu/wpilib/allwpilib/docs/development/java/)
+[![Gradle](https://github.com/wpilibsuite/allwpilib/actions/workflows/gradle.yml/badge.svg?branch=main)](https://github.com/wpilibsuite/allwpilib/actions/workflows/gradle.yml)
+[![C++ Documentation](https://img.shields.io/badge/documentation-c%2B%2B-blue)](https://github.wpilib.org/allwpilib/docs/development/cpp/)
+[![Java Documentation](https://img.shields.io/badge/documentation-java-orange)](https://github.wpilib.org/allwpilib/docs/development/java/)
 
 Welcome to the WPILib project. This repository contains the HAL, WPILibJ, and WPILibC projects. These are the core libraries for creating robot programs for the roboRIO.
 
@@ -15,8 +15,7 @@
     - [Faster builds](#faster-builds)
     - [Using Development Builds](#using-development-builds)
     - [Custom toolchain location](#custom-toolchain-location)
-    - [Gazebo simulation](#gazebo-simulation)
-    - [Formatting/linting with wpiformat](#formattinglinting-with-wpiformat)
+    - [Formatting/Linting](#formattinglinting)
     - [CMake](#cmake)
   - [Publishing](#publishing)
   - [Structure and Organization](#structure-and-organization)
@@ -26,6 +25,15 @@
 
 The WPILib Mission is to enable FIRST Robotics teams to focus on writing game-specific software rather than focusing on hardware details - "raise the floor, don't lower the ceiling". We work to enable teams with limited programming knowledge and/or mentor experience to be as successful as possible, while not hampering the abilities of teams with more advanced programming capabilities. We support Kit of Parts control system components directly in the library. We also strive to keep parity between major features of each language (Java, C++, and NI's LabVIEW), so that teams aren't at a disadvantage for choosing a specific programming language. WPILib is an open source project, licensed under the BSD 3-clause license. You can find a copy of the license [here](LICENSE.md).
 
+# Quick Start
+
+Below is a list of instructions that guide you through cloning, building, publishing and using local allwpilib binaries in a robot project. This quick start is not intended as a replacement for the information further listed in this document.
+
+1. Clone the repository with `git clone https://github.com/wpilibsuite/allwpilib.git`
+2. Build the repository with `./gradlew build` or `./gradlew build --build-cache` if you have an internet connection
+3. Publish the artifacts locally by running `./gradlew publish`
+4. [Update your](DevelopmentBuilds.md) `build.gradle` [to use the artifacts](DevelopmentBuilds.md)
+
 # Building WPILib
 
 Using Gradle makes building WPILib very straightforward. It only has a few dependencies on outside tools, such as the ARM cross compiler for creating roboRIO binaries.
@@ -38,20 +46,22 @@
     - On Windows, install the JDK 11 .msi from the link above
     - On macOS, install the JDK 11 .pkg from the link above
 - C++ compiler
-    - On Linux, install GCC 8 or greater
-    - On Windows, install [Visual Studio Community 2022 or 2019](https://visualstudio.microsoft.com/vs/community/) and select the C++ programming language during installation (Gradle can't use the build tools for Visual Studio)
+    - On Linux, install GCC 11 or greater
+    - On Windows, install [Visual Studio Community 2022](https://visualstudio.microsoft.com/vs/community/) and select the C++ programming language during installation (Gradle can't use the build tools for Visual Studio)
     - On macOS, install the Xcode command-line build tools via `xcode-select --install`
 - ARM compiler toolchain
     - Run `./gradlew installRoboRioToolchain` after cloning this repository
     - If the WPILib installer was used, this toolchain is already installed
 - Raspberry Pi toolchain (optional)
-    - Run `./gradlew installRaspbianToolchain` after cloning this repository
+    - Run `./gradlew installArm32Toolchain` after cloning this repository
+
+On macOS ARM, run `softwareupdate --install-rosetta`. This is necessary to be able to use the macOS x86 roboRIO toolchain on ARM.
 
 ## Setup
 
 Clone the WPILib repository and follow the instructions above for installing any required tooling.
 
-See the [styleguide README](https://github.com/wpilibsuite/styleguide/blob/main/README.md) for wpiformat setup instructions.
+See the [styleguide README](https://github.com/wpilibsuite/styleguide/blob/main/README.md) for wpiformat setup instructions. We use clang-format 14.
 
 ## Building
 
@@ -79,13 +89,21 @@
 
 `./gradlew testDesktopCpp` and `./gradlew testDesktopJava` will build and run the tests for `wpilibc` and `wpilibj` respectively. They will only build the minimum components required to run the tests.
 
-`testDesktopCpp` and `testDesktopJava` tasks also exist for the projects `wpiutil`, `ntcore`, `cscore`, `hal` `wpilibOldCommands`, `wpilibNewCommands` and `cameraserver`. These can be ran with `./gradlew :projectName:task`.
+`testDesktopCpp` and `testDesktopJava` tasks also exist for the projects `wpiutil`, `ntcore`, `cscore`, `hal` `wpilibNewCommands` and `cameraserver`. These can be ran with `./gradlew :projectName:task`.
 
 `./gradlew buildDesktopCpp` and `./gradlew buildDesktopJava` will compile `wpilibcExamples` and `wpilibjExamples` respectively. The results can't be ran, but they can compile.
 
+### Build Cache
+
+Run with `--build-cache` on the command-line to use the shared [build cache](https://docs.gradle.org/current/userguide/build_cache.html) artifacts generated by the continuous integration server. Example:
+
+```bash
+./gradlew build --build-cache
+```
+
 ### Using Development Builds
 
-Please read the documentation available [here](OtherVersions.md)
+Please read the documentation available [here](DevelopmentBuilds.md)
 
 ### Custom toolchain location
 
@@ -95,30 +113,13 @@
 ./gradlew build -PtoolChainPath=some/path/to/frc/toolchain/bin
 ```
 
-### Gazebo simulation
-
-If you also want to force building Gazebo simulation support, add -PforceGazebo. This requires gazebo_transport. We have tested on 14.04 and 15.05, but any correct install of Gazebo should work, even on Windows if you build Gazebo from source. Correct means CMake needs to be able to find gazebo-config.cmake. See [The Gazebo website](https://gazebosim.org/) for installation instructions.
-
-```bash
-./gradlew build -PforceGazebo
-```
-
-If you prefer to use CMake directly, the you can still do so.
-The common CMake tasks are wpilibcSim, frc_gazebo_plugins, and gz_msgs
-
-```bash
-mkdir build #run this in the root of allwpilib
-cd build
-cmake ..
-make
-```
-
-
 ### Formatting/linting
 
+Once a PR has been submitted, formatting can be run in CI by commenting `/format` on the PR. A new commit will be pushed with the formatting changes.
+
 #### wpiformat
 
-wpiformat can be executed anywhere in the repository via `py -3 -m wpiformat` on Windows or `python3 -m wpiformat` on other platforms.
+wpiformat can be executed anywhere in the repository via `py -3 -m wpiformat -clang 14` on Windows or `python3 -m wpiformat -clang 14` on other platforms.
 
 #### Java Code Quality Tools
 
@@ -143,13 +144,11 @@
 
 ## Structure and Organization
 
-The main WPILib code you're probably looking for is in WPILibJ and WPILibC. Those directories are split into shared, sim, and athena. Athena contains the WPILib code meant to run on your roboRIO. Sim is WPILib code meant to run on your computer with Gazebo, and shared is code shared between the two. Shared code must be platform-independent, since it will be compiled with both the ARM cross-compiler and whatever desktop compiler you are using (g++, msvc, etc...).
-
-The Simulation directory contains extra simulation tools and libraries, such as gz_msgs and JavaGazebo. See sub-directories for more information.
+The main WPILib code you're probably looking for is in WPILibJ and WPILibC. Those directories are split into shared, sim, and athena. Athena contains the WPILib code meant to run on your roboRIO. Sim is WPILib code meant to run on your computer, and shared is code shared between the two. Shared code must be platform-independent, since it will be compiled with both the ARM cross-compiler and whatever desktop compiler you are using (g++, msvc, etc...).
 
 The integration test directories for C++ and Java contain test code that runs on our test-system. When you submit code for review, it is tested by those programs. If you add new functionality you should make sure to write tests for it so we don't break it in the future.
 
-The hal directory contains more C++ code meant to run on the roboRIO. HAL is an acronym for "Hardware Abstraction Layer", and it interfaces with the NI Libraries. The NI Libraries contain the low-level code for controlling devices on your robot. The NI Libraries are found in the ni-libraries folder.
+The hal directory contains more C++ code meant to run on the roboRIO. HAL is an acronym for "Hardware Abstraction Layer", and it interfaces with the NI Libraries. The NI Libraries contain the low-level code for controlling devices on your robot. The NI Libraries are found in the [ni-libraries](https://github.com/wpilibsuite/ni-libraries) project.
 
 The upstream_utils directory contains scripts for updating copies of thirdparty code in the repository.
 
diff --git a/third_party/allwpilib/ThirdPartyNotices.txt b/third_party/allwpilib/ThirdPartyNotices.txt
index 69cbd4a..18163b2 100644
--- a/third_party/allwpilib/ThirdPartyNotices.txt
+++ b/third_party/allwpilib/ThirdPartyNotices.txt
@@ -17,44 +17,35 @@
 -------               ---------
 RoboRIO Libraries     ni-libraries
 Google Test           gtest
-LLVM                  wpiutil/src/main/native/include/wpi/{various files}
-                      wpiutil/src/main/native/cpp/llvm/
-                      wpiutil/src/main/native/cpp/leb128.cpp
-                      wpiutil/src/test/native/cpp/leb128Test.cpp
-JSON for Modern C++   wpiutil/src/main/native/include/wpi/json.h
-                      wpiutil/src/main/native/cpp/json_*.cpp
+LLVM                  wpiutil/src/main/native/thirdparty/llvm
+                      wpiutil/src/test/native/cpp/llvm/
+JSON for Modern C++   wpiutil/src/main/native/thirdparty/json
                       wpiutil/src/test/native/cpp/json/
-libuv                 wpiutil/src/main/native/include/uv.h
-                      wpiutil/src/main/native/include/uv/
-                      wpiutil/src/main/native/libuv/
-fmtlib                wpiutil/src/main/native/fmtlib/
-sigslot               wpiutil/src/main/native/include/wpi/Signal.h
-                      wpiutil/src/test/native/cpp/sigslot/
-tcpsockets            wpiutil/src/main/native/cpp/TCP{Stream,Connector,Acceptor}.cpp
-                      wpiutil/src/main/native/include/wpi/TCP*.h
-MPack                 wpiutil/src/main/native/include/mpack.h
-                      wpiutil/src/main/native/cpp/mpack.cpp
-Bootstrap             wpiutil/src/main/native/resources/bootstrap-*
-CoreUI                wpiutil/src/main/native/resources/coreui-*
-Feather Icons         wpiutil/src/main/native/resources/feather-*
-jQuery                wpiutil/src/main/native/resources/jquery-*
-popper.js             wpiutil/src/main/native/resources/popper-*
+libuv                 wpinet/src/main/native/thirdparty/libuv/
+fmtlib                wpiutil/src/main/native/thirdparty/fmtlib/
+sigslot               wpiutil/src/main/native/thirdparty/sigslot
+tcpsockets            wpinet/src/main/native/thirdparty/tcpsockets
+MPack                 wpiutil/src/main/native/thirdparty/mpack
+Bootstrap             wpinet/src/main/native/resources/bootstrap-*
+CoreUI                wpinet/src/main/native/resources/coreui-*
+Feather Icons         wpinet/src/main/native/resources/feather-*
+jQuery                wpinet/src/main/native/resources/jquery-*
+popper.js             wpinet/src/main/native/resources/popper-*
 units                 wpimath/src/main/native/include/units/
-Eigen                 wpimath/src/main/native/eigeninclude/
-                      wpimath/src/main/native/include/unsupported/
+Eigen                 wpimath/src/main/native/thirdparty/eigen/include/
 StackWalker           wpiutil/src/main/native/windows/StackWalker.*
-TCB span              wpiutil/src/main/native/include/wpi/span.h
-                      wpiutil/src/test/native/cpp/span/
-GHC filesystem        wpiutil/src/main/native/include/wpi/ghc/
+GHC filesystem        wpiutil/src/main/native/thirdparty/include/wpi/ghc/
 Team 254 Library      wpilibj/src/main/java/edu/wpi/first/wpilibj/spline/SplineParameterizer.java
                       wpilibj/src/main/java/edu/wpi/first/wpilibj/trajectory/TrajectoryParameterizer.java
                       wpilibc/src/main/native/include/spline/SplineParameterizer.h
                       wpilibc/src/main/native/include/trajectory/TrajectoryParameterizer.h
                       wpilibc/src/main/native/cpp/trajectory/TrajectoryParameterizer.cpp
 Portable File Dialogs wpigui/src/main/native/include/portable-file-dialogs.h
-Drake                 wpimath/src/main/native/cpp/drake/common/drake_assert_and_throw.cpp
-                      wpimath/src/main/native/cpp/drake/math/discrete_algebraic_riccati_equation.cpp
-
+Drake                 wpimath/src/main/native/thirdparty/drake/
+                      wpimath/src/test/native/cpp/drake/
+                      wpimath/src/test/native/include/drake/
+V8 export-template    wpiutil/src/main/native/include/wpi/SymbolExports.h
+GCEM                  wpimath/src/main/native/thirdparty/gcem/include/
 
 ==============================================================================
 Google Test License
@@ -90,12 +81,247 @@
 
 
 ==============================================================================
-LLVM Release License
+The LLVM Project is under the Apache License v2.0 with LLVM Exceptions:
+==============================================================================
+
+                                 Apache License
+                           Version 2.0, January 2004
+                        http://www.apache.org/licenses/
+
+    TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION
+
+    1. Definitions.
+
+      "License" shall mean the terms and conditions for use, reproduction,
+      and distribution as defined by Sections 1 through 9 of this document.
+
+      "Licensor" shall mean the copyright owner or entity authorized by
+      the copyright owner that is granting the License.
+
+      "Legal Entity" shall mean the union of the acting entity and all
+      other entities that control, are controlled by, or are under common
+      control with that entity. For the purposes of this definition,
+      "control" means (i) the power, direct or indirect, to cause the
+      direction or management of such entity, whether by contract or
+      otherwise, or (ii) ownership of fifty percent (50%) or more of the
+      outstanding shares, or (iii) beneficial ownership of such entity.
+
+      "You" (or "Your") shall mean an individual or Legal Entity
+      exercising permissions granted by this License.
+
+      "Source" form shall mean the preferred form for making modifications,
+      including but not limited to software source code, documentation
+      source, and configuration files.
+
+      "Object" form shall mean any form resulting from mechanical
+      transformation or translation of a Source form, including but
+      not limited to compiled object code, generated documentation,
+      and conversions to other media types.
+
+      "Work" shall mean the work of authorship, whether in Source or
+      Object form, made available under the License, as indicated by a
+      copyright notice that is included in or attached to the work
+      (an example is provided in the Appendix below).
+
+      "Derivative Works" shall mean any work, whether in Source or Object
+      form, that is based on (or derived from) the Work and for which the
+      editorial revisions, annotations, elaborations, or other modifications
+      represent, as a whole, an original work of authorship. For the purposes
+      of this License, Derivative Works shall not include works that remain
+      separable from, or merely link (or bind by name) to the interfaces of,
+      the Work and Derivative Works thereof.
+
+      "Contribution" shall mean any work of authorship, including
+      the original version of the Work and any modifications or additions
+      to that Work or Derivative Works thereof, that is intentionally
+      submitted to Licensor for inclusion in the Work by the copyright owner
+      or by an individual or Legal Entity authorized to submit on behalf of
+      the copyright owner. For the purposes of this definition, "submitted"
+      means any form of electronic, verbal, or written communication sent
+      to the Licensor or its representatives, including but not limited to
+      communication on electronic mailing lists, source code control systems,
+      and issue tracking systems that are managed by, or on behalf of, the
+      Licensor for the purpose of discussing and improving the Work, but
+      excluding communication that is conspicuously marked or otherwise
+      designated in writing by the copyright owner as "Not a Contribution."
+
+      "Contributor" shall mean Licensor and any individual or Legal Entity
+      on behalf of whom a Contribution has been received by Licensor and
+      subsequently incorporated within the Work.
+
+    2. Grant of Copyright License. Subject to the terms and conditions of
+      this License, each Contributor hereby grants to You a perpetual,
+      worldwide, non-exclusive, no-charge, royalty-free, irrevocable
+      copyright license to reproduce, prepare Derivative Works of,
+      publicly display, publicly perform, sublicense, and distribute the
+      Work and such Derivative Works in Source or Object form.
+
+    3. Grant of Patent License. Subject to the terms and conditions of
+      this License, each Contributor hereby grants to You a perpetual,
+      worldwide, non-exclusive, no-charge, royalty-free, irrevocable
+      (except as stated in this section) patent license to make, have made,
+      use, offer to sell, sell, import, and otherwise transfer the Work,
+      where such license applies only to those patent claims licensable
+      by such Contributor that are necessarily infringed by their
+      Contribution(s) alone or by combination of their Contribution(s)
+      with the Work to which such Contribution(s) was submitted. If You
+      institute patent litigation against any entity (including a
+      cross-claim or counterclaim in a lawsuit) alleging that the Work
+      or a Contribution incorporated within the Work constitutes direct
+      or contributory patent infringement, then any patent licenses
+      granted to You under this License for that Work shall terminate
+      as of the date such litigation is filed.
+
+    4. Redistribution. You may reproduce and distribute copies of the
+      Work or Derivative Works thereof in any medium, with or without
+      modifications, and in Source or Object form, provided that You
+      meet the following conditions:
+
+      (a) You must give any other recipients of the Work or
+          Derivative Works a copy of this License; and
+
+      (b) You must cause any modified files to carry prominent notices
+          stating that You changed the files; and
+
+      (c) You must retain, in the Source form of any Derivative Works
+          that You distribute, all copyright, patent, trademark, and
+          attribution notices from the Source form of the Work,
+          excluding those notices that do not pertain to any part of
+          the Derivative Works; and
+
+      (d) If the Work includes a "NOTICE" text file as part of its
+          distribution, then any Derivative Works that You distribute must
+          include a readable copy of the attribution notices contained
+          within such NOTICE file, excluding those notices that do not
+          pertain to any part of the Derivative Works, in at least one
+          of the following places: within a NOTICE text file distributed
+          as part of the Derivative Works; within the Source form or
+          documentation, if provided along with the Derivative Works; or,
+          within a display generated by the Derivative Works, if and
+          wherever such third-party notices normally appear. The contents
+          of the NOTICE file are for informational purposes only and
+          do not modify the License. You may add Your own attribution
+          notices within Derivative Works that You distribute, alongside
+          or as an addendum to the NOTICE text from the Work, provided
+          that such additional attribution notices cannot be construed
+          as modifying the License.
+
+      You may add Your own copyright statement to Your modifications and
+      may provide additional or different license terms and conditions
+      for use, reproduction, or distribution of Your modifications, or
+      for any such Derivative Works as a whole, provided Your use,
+      reproduction, and distribution of the Work otherwise complies with
+      the conditions stated in this License.
+
+    5. Submission of Contributions. Unless You explicitly state otherwise,
+      any Contribution intentionally submitted for inclusion in the Work
+      by You to the Licensor shall be under the terms and conditions of
+      this License, without any additional terms or conditions.
+      Notwithstanding the above, nothing herein shall supersede or modify
+      the terms of any separate license agreement you may have executed
+      with Licensor regarding such Contributions.
+
+    6. Trademarks. This License does not grant permission to use the trade
+      names, trademarks, service marks, or product names of the Licensor,
+      except as required for reasonable and customary use in describing the
+      origin of the Work and reproducing the content of the NOTICE file.
+
+    7. Disclaimer of Warranty. Unless required by applicable law or
+      agreed to in writing, Licensor provides the Work (and each
+      Contributor provides its Contributions) on an "AS IS" BASIS,
+      WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or
+      implied, including, without limitation, any warranties or conditions
+      of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A
+      PARTICULAR PURPOSE. You are solely responsible for determining the
+      appropriateness of using or redistributing the Work and assume any
+      risks associated with Your exercise of permissions under this License.
+
+    8. Limitation of Liability. In no event and under no legal theory,
+      whether in tort (including negligence), contract, or otherwise,
+      unless required by applicable law (such as deliberate and grossly
+      negligent acts) or agreed to in writing, shall any Contributor be
+      liable to You for damages, including any direct, indirect, special,
+      incidental, or consequential damages of any character arising as a
+      result of this License or out of the use or inability to use the
+      Work (including but not limited to damages for loss of goodwill,
+      work stoppage, computer failure or malfunction, or any and all
+      other commercial damages or losses), even if such Contributor
+      has been advised of the possibility of such damages.
+
+    9. Accepting Warranty or Additional Liability. While redistributing
+      the Work or Derivative Works thereof, You may choose to offer,
+      and charge a fee for, acceptance of support, warranty, indemnity,
+      or other liability obligations and/or rights consistent with this
+      License. However, in accepting such obligations, You may act only
+      on Your own behalf and on Your sole responsibility, not on behalf
+      of any other Contributor, and only if You agree to indemnify,
+      defend, and hold each Contributor harmless for any liability
+      incurred by, or claims asserted against, such Contributor by reason
+      of your accepting any such warranty or additional liability.
+
+    END OF TERMS AND CONDITIONS
+
+    APPENDIX: How to apply the Apache License to your work.
+
+      To apply the Apache License to your work, attach the following
+      boilerplate notice, with the fields enclosed by brackets "[]"
+      replaced with your own identifying information. (Don't include
+      the brackets!)  The text should be enclosed in the appropriate
+      comment syntax for the file format. We also recommend that a
+      file or class name and description of purpose be included on the
+      same "printed page" as the copyright notice for easier
+      identification within third-party archives.
+
+    Copyright [yyyy] [name of copyright owner]
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+       http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing, software
+    distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+    See the License for the specific language governing permissions and
+    limitations under the License.
+
+
+---- LLVM Exceptions to the Apache 2.0 License ----
+
+As an exception, if, as a result of your compiling your source code, portions
+of this Software are embedded into an Object form of such source code, you
+may redistribute such embedded portions in such Object form without complying
+with the conditions of Sections 4(a), 4(b) and 4(d) of the License.
+
+In addition, if you combine or link compiled forms of this Software with
+software that is licensed under the GPLv2 ("Combined Software") and if a
+court of competent jurisdiction determines that the patent provision (Section
+3), the indemnity provision (Section 9) or other Section of the License
+conflicts with the conditions of the GPLv2, you may retroactively and
+prospectively choose to deem waived or otherwise exclude such Section(s) of
+the License, but only in their entirety and only with respect to the Combined
+Software.
+
+==============================================================================
+Software from third parties included in the LLVM Project:
+==============================================================================
+The LLVM Project contains third party software which is under different license
+terms. All such code will be identified clearly using at least one of two
+mechanisms:
+1) It will be in a separate directory tree with its own `LICENSE.txt` or
+   `LICENSE` file at the top containing the specific license and restrictions
+   which apply to that software, or
+2) It will contain specific license and restriction terms at the top of every
+   file.
+
+==============================================================================
+Legacy LLVM License (https://llvm.org/docs/DeveloperPolicy.html#legacy):
 ==============================================================================
 University of Illinois/NCSA
 Open Source License
 
-Copyright (c) 2003-2017 University of Illinois at Urbana-Champaign.
+Copyright (c) 2003-2019 University of Illinois at Urbana-Champaign.
 All rights reserved.
 
 Developed by:
@@ -969,3 +1195,50 @@
 LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
 OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
 SOFTWARE.
+
+==================
+V8 export-template
+==================
+Copyright 2014, the V8 project authors. All rights reserved.
+Redistribution and use in source and binary forms, with or without
+modification, are permitted provided that the following conditions are
+met:
+
+    * Redistributions of source code must retain the above copyright
+      notice, this list of conditions and the following disclaimer.
+    * Redistributions in binary form must reproduce the above
+      copyright notice, this list of conditions and the following
+      disclaimer in the documentation and/or other materials provided
+      with the distribution.
+    * Neither the name of Google Inc. nor the names of its
+      contributors may be used to endorse or promote products derived
+      from this software without specific prior written permission.
+
+THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+"AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
+LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+
+============
+GCEM License
+============
+Copyright 2022 - ktholer (https://github.com/kthohr/gcem)
+
+Licensed under the Apache License, Version 2.0 (the "License");
+you may not use this file except in compliance with the License.
+You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+Unless required by applicable law or agreed to in writing, software
+distributed under the License is distributed on an "AS IS" BASIS,
+WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+See the License for the specific language governing permissions and
+limitations under the License.
diff --git a/third_party/allwpilib/apriltag/CMakeLists.txt b/third_party/allwpilib/apriltag/CMakeLists.txt
new file mode 100644
index 0000000..29dcd2b
--- /dev/null
+++ b/third_party/allwpilib/apriltag/CMakeLists.txt
@@ -0,0 +1,118 @@
+project(apriltag)
+
+include(CompileWarnings)
+include(GenResources)
+include(FetchContent)
+
+FetchContent_Declare(
+    apriltaglib
+    GIT_REPOSITORY  https://github.com/wpilibsuite/apriltag.git
+    GIT_TAG         ad31e33d20f9782b7239cb15cde57c56c91383ad
+)
+
+# Don't use apriltag's CMakeLists.txt due to conflicting naming and JNI
+FetchContent_GetProperties(apriltaglib)
+if(NOT apriltaglib_POPULATED)
+    FetchContent_Populate(apriltaglib)
+endif()
+
+aux_source_directory(${apriltaglib_SOURCE_DIR}/common APRILTAGLIB_COMMON_SRC)
+file(GLOB TAG_FILES ${apriltaglib_SOURCE_DIR}/tag*.c)
+set(APRILTAGLIB_SRCS ${apriltaglib_SOURCE_DIR}/apriltag.c ${apriltaglib_SOURCE_DIR}/apriltag_pose.c ${apriltaglib_SOURCE_DIR}/apriltag_quad_thresh.c)
+
+file(GLOB apriltag_jni_src src/main/native/cpp/jni/AprilTagJNI.cpp)
+
+if (WITH_JAVA)
+  find_package(Java REQUIRED)
+  find_package(JNI REQUIRED)
+  include(UseJava)
+  set(CMAKE_JAVA_COMPILE_FLAGS "-encoding" "UTF8" "-Xlint:unchecked")
+
+  set(CMAKE_JNI_TARGET true)
+
+  file(GLOB EJML_JARS "${WPILIB_BINARY_DIR}/wpimath/thirdparty/ejml/*.jar")
+  file(GLOB JACKSON_JARS "${WPILIB_BINARY_DIR}/wpiutil/thirdparty/jackson/*.jar")
+  find_file(OPENCV_JAR_FILE
+    NAMES opencv-${OpenCV_VERSION_MAJOR}${OpenCV_VERSION_MINOR}${OpenCV_VERSION_PATCH}.jar
+    PATHS ${OPENCV_JAVA_INSTALL_DIR} ${OpenCV_INSTALL_PATH}/bin ${OpenCV_INSTALL_PATH}/share/java
+    NO_DEFAULT_PATH)
+
+  set(CMAKE_JAVA_INCLUDE_PATH apriltag.jar ${EJML_JARS} ${JACKSON_JARS})
+
+  file(GLOB_RECURSE JAVA_SOURCES src/main/java/*.java)
+  file(GLOB_RECURSE JAVA_RESOURCES src/main/native/resources/*.json)
+  add_jar(apriltag_jar
+    SOURCES ${JAVA_SOURCES}
+    RESOURCES NAMESPACE "edu/wpi/first/apriltag" ${JAVA_RESOURCES}
+    INCLUDE_JARS wpimath_jar ${EJML_JARS} wpiutil_jar ${OPENCV_JAR_FILE}
+    OUTPUT_NAME apriltag
+    GENERATE_NATIVE_HEADERS apriltag_jni_headers)
+
+  get_property(APRILTAG_JAR_FILE TARGET apriltag_jar PROPERTY JAR_FILE)
+  install(FILES ${APRILTAG_JAR_FILE} DESTINATION "${java_lib_dest}")
+
+  set_property(TARGET apriltag_jar PROPERTY FOLDER "java")
+
+  add_library(apriltagjni ${apriltag_jni_src})
+  wpilib_target_warnings(apriltagjni)
+  target_link_libraries(apriltagjni PUBLIC apriltag)
+
+  set_property(TARGET apriltagjni PROPERTY FOLDER "libraries")
+
+  target_link_libraries(apriltagjni PRIVATE apriltag_jni_headers)
+  add_dependencies(apriltagjni apriltag_jar)
+
+  if (MSVC)
+    install(TARGETS apriltagjni RUNTIME DESTINATION "${jni_lib_dest}" COMPONENT Runtime)
+  endif()
+
+  install(TARGETS apriltagjni EXPORT apriltagjni DESTINATION "${main_lib_dest}")
+
+endif()
+
+GENERATE_RESOURCES(src/main/native/resources/edu/wpi/first/apriltag generated/main/cpp APRILTAG frc apriltag_resources_src)
+
+file(GLOB apriltag_native_src src/main/native/cpp/*.cpp)
+
+add_library(apriltag ${apriltag_native_src} ${apriltag_resources_src} ${APRILTAGLIB_SRCS} ${APRILTAGLIB_COMMON_SRC} ${TAG_FILES})
+set_target_properties(apriltag PROPERTIES DEBUG_POSTFIX "d")
+
+set_property(TARGET apriltag PROPERTY FOLDER "libraries")
+target_compile_features(apriltag PUBLIC cxx_std_20)
+wpilib_target_warnings(apriltag)
+# disable warnings that apriltaglib can't handle
+if (MSVC)
+  target_compile_options(apriltag PRIVATE /wd4018)
+else()
+  target_compile_options(apriltag PRIVATE -Wno-sign-compare -Wno-gnu-zero-variadic-macro-arguments)
+endif()
+
+target_link_libraries(apriltag wpimath)
+
+target_include_directories(apriltag PUBLIC
+  $<BUILD_INTERFACE:${apriltaglib_SOURCE_DIR}>
+  $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/src/main/native/include>
+  $<INSTALL_INTERFACE:${include_dest}/apriltag>)
+
+install(TARGETS apriltag EXPORT apriltag DESTINATION "${main_lib_dest}")
+install(DIRECTORY src/main/native/include/ DESTINATION "${include_dest}/apriltag")
+
+if (WITH_JAVA AND MSVC)
+    install(TARGETS apriltag RUNTIME DESTINATION "${jni_lib_dest}" COMPONENT Runtime)
+endif()
+
+if (WITH_FLAT_INSTALL)
+    set (apriltag_config_dir ${wpilib_dest})
+else()
+    set (apriltag_config_dir share/apriltag)
+endif()
+
+configure_file(apriltag-config.cmake.in ${WPILIB_BINARY_DIR}/apriltag-config.cmake )
+install(FILES ${WPILIB_BINARY_DIR}/apriltag-config.cmake DESTINATION ${apriltag_config_dir})
+install(EXPORT apriltag DESTINATION ${apriltag_config_dir})
+
+if (WITH_TESTS)
+    wpilib_add_test(apriltag src/test/native/cpp)
+    target_include_directories(apriltag_test PRIVATE src/test/native/include)
+    target_link_libraries(apriltag_test apriltag gmock_main)
+endif()
diff --git a/third_party/allwpilib/apriltag/apriltag-config.cmake.in b/third_party/allwpilib/apriltag/apriltag-config.cmake.in
new file mode 100644
index 0000000..7477a0e
--- /dev/null
+++ b/third_party/allwpilib/apriltag/apriltag-config.cmake.in
@@ -0,0 +1,7 @@
+include(CMakeFindDependencyMacro)
+@FILENAME_DEP_REPLACE@
+@WPIMATH_DEP_REPLACE@
+@WPIUTIL_DEP_REPLACE@
+
+@FILENAME_DEP_REPLACE@
+include(${SELF_DIR}/apriltag.cmake)
diff --git a/third_party/allwpilib/apriltag/build.gradle b/third_party/allwpilib/apriltag/build.gradle
new file mode 100644
index 0000000..960af58
--- /dev/null
+++ b/third_party/allwpilib/apriltag/build.gradle
@@ -0,0 +1,88 @@
+apply from: "${rootDir}/shared/resources.gradle"
+
+ext {
+    nativeName = 'apriltag'
+    devMain = 'edu.wpi.first.apriltag.DevMain'
+    useJava = true
+    useCpp = true
+    sharedCvConfigs = [
+        apriltagDev : [],
+        apriltagTest: []]
+    staticCvConfigs = []
+
+    def generateTask = createGenerateResourcesTask('main', 'APRILTAG', 'frc', project)
+
+    tasks.withType(CppCompile) {
+        dependsOn generateTask
+    }
+    splitSetup = {
+        it.sources {
+            resourcesCpp(CppSourceSet) {
+                source {
+                    srcDirs "$buildDir/generated/main/cpp", "$rootDir/shared/singlelib"
+                    include '*.cpp'
+                }
+            }
+        }
+    }
+}
+
+evaluationDependsOn(':wpimath')
+
+apply from: "${rootDir}/shared/jni/setupBuild.gradle"
+apply from: "${rootDir}/shared/apriltaglib.gradle"
+apply from: "${rootDir}/shared/opencv.gradle"
+
+dependencies {
+    implementation project(':wpimath')
+    devImplementation project(':wpimath')
+}
+
+sourceSets {
+    main {
+        resources {
+            srcDirs 'src/main/native/resources'
+        }
+    }
+}
+
+model {
+    components {}
+    binaries {
+        all {
+            if (!it.buildable || !(it instanceof NativeBinarySpec)) {
+                return
+            }
+            it.cppCompiler.define 'WPILIB_EXPORTS'
+
+            if (it.component.name == "${nativeName}JNI") {
+                lib project: ':wpimath', library: 'wpimath', linkage: 'static'
+                lib project: ':wpiutil', library: 'wpiutil', linkage: 'static'
+            } else {
+                lib project: ':wpimath', library: 'wpimath', linkage: 'shared'
+                lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+            }
+
+            nativeUtils.useRequiredLibrary(it, 'apriltaglib')
+        }
+    }
+    tasks {
+        def c = $.components
+        def found = false
+        def systemArch = getCurrentArch()
+        c.each {
+            if (it in NativeExecutableSpec && it.name == "${nativeName}Dev") {
+                it.binaries.each {
+                    if (!found) {
+                        def arch = it.targetPlatform.name
+                        if (arch == systemArch) {
+                            def filePath = it.tasks.install.installDirectory.get().toString() + File.separatorChar + 'lib'
+
+                            found = true
+                        }
+                    }
+                }
+            }
+        }
+    }
+}
diff --git a/third_party/allwpilib/apriltag/src/dev/java/edu/wpi/first/apriltag/DevMain.java b/third_party/allwpilib/apriltag/src/dev/java/edu/wpi/first/apriltag/DevMain.java
new file mode 100644
index 0000000..1047088
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/dev/java/edu/wpi/first/apriltag/DevMain.java
@@ -0,0 +1,20 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.apriltag;
+
+public final class DevMain {
+  /** Main entry point. */
+  public static void main(String[] args) {
+    System.out.println("Hello World!");
+    AprilTagDetector detector = new AprilTagDetector();
+    detector.addFamily("tag16h5");
+    AprilTagDetector.Config config = new AprilTagDetector.Config();
+    config.refineEdges = false;
+    detector.setConfig(config);
+    detector.close();
+  }
+
+  private DevMain() {}
+}
diff --git a/third_party/allwpilib/apriltag/src/dev/native/cpp/main.cpp b/third_party/allwpilib/apriltag/src/dev/native/cpp/main.cpp
new file mode 100644
index 0000000..515202e
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/dev/native/cpp/main.cpp
@@ -0,0 +1,11 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/apriltag/AprilTagDetector.h"
+
+int main() {
+  frc::AprilTagDetector detector;
+  detector.AddFamily("tag16h5");
+  detector.SetConfig({.refineEdges = false});
+}
diff --git a/third_party/allwpilib/apriltag/src/main/java/edu/wpi/first/apriltag/AprilTag.java b/third_party/allwpilib/apriltag/src/main/java/edu/wpi/first/apriltag/AprilTag.java
new file mode 100644
index 0000000..8e455f6
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/main/java/edu/wpi/first/apriltag/AprilTag.java
@@ -0,0 +1,47 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.apriltag;
+
+import com.fasterxml.jackson.annotation.JsonCreator;
+import com.fasterxml.jackson.annotation.JsonProperty;
+import edu.wpi.first.math.geometry.Pose3d;
+import java.util.Objects;
+
+@SuppressWarnings("MemberName")
+public class AprilTag {
+  @JsonProperty(value = "ID")
+  public int ID;
+
+  @JsonProperty(value = "pose")
+  public Pose3d pose;
+
+  @SuppressWarnings("ParameterName")
+  @JsonCreator
+  public AprilTag(
+      @JsonProperty(required = true, value = "ID") int ID,
+      @JsonProperty(required = true, value = "pose") Pose3d pose) {
+    this.ID = ID;
+    this.pose = pose;
+  }
+
+  @Override
+  public boolean equals(Object obj) {
+    if (obj instanceof AprilTag) {
+      var other = (AprilTag) obj;
+      return ID == other.ID && pose.equals(other.pose);
+    }
+    return false;
+  }
+
+  @Override
+  public int hashCode() {
+    return Objects.hash(ID, pose);
+  }
+
+  @Override
+  public String toString() {
+    return "AprilTag(ID: " + ID + ", pose: " + pose + ")";
+  }
+}
diff --git a/third_party/allwpilib/apriltag/src/main/java/edu/wpi/first/apriltag/AprilTagDetection.java b/third_party/allwpilib/apriltag/src/main/java/edu/wpi/first/apriltag/AprilTagDetection.java
new file mode 100644
index 0000000..9270cc9
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/main/java/edu/wpi/first/apriltag/AprilTagDetection.java
@@ -0,0 +1,190 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.apriltag;
+
+import edu.wpi.first.math.MatBuilder;
+import edu.wpi.first.math.Matrix;
+import edu.wpi.first.math.Nat;
+import edu.wpi.first.math.numbers.N3;
+import java.util.Arrays;
+
+/** A detection of an AprilTag tag. */
+public class AprilTagDetection {
+  /**
+   * Gets the decoded tag's family name.
+   *
+   * @return Decoded family name
+   */
+  public String getFamily() {
+    return m_family;
+  }
+
+  /**
+   * Gets the decoded ID of the tag.
+   *
+   * @return Decoded ID
+   */
+  public int getId() {
+    return m_id;
+  }
+
+  /**
+   * Gets how many error bits were corrected. Note: accepting large numbers of corrected errors
+   * leads to greatly increased false positive rates. NOTE: As of this implementation, the detector
+   * cannot detect tags with a hamming distance greater than 2.
+   *
+   * @return Hamming distance (number of corrected error bits)
+   */
+  public int getHamming() {
+    return m_hamming;
+  }
+
+  /**
+   * Gets a measure of the quality of the binary decoding process: the average difference between
+   * the intensity of a data bit versus the decision threshold. Higher numbers roughly indicate
+   * better decodes. This is a reasonable measure of detection accuracy only for very small tags--
+   * not effective for larger tags (where we could have sampled anywhere within a bit cell and still
+   * gotten a good detection.)
+   *
+   * @return Decision margin
+   */
+  public float getDecisionMargin() {
+    return m_decisionMargin;
+  }
+
+  /**
+   * Gets the 3x3 homography matrix describing the projection from an "ideal" tag (with corners at
+   * (-1,1), (1,1), (1,-1), and (-1, -1)) to pixels in the image.
+   *
+   * @return Homography matrix data
+   */
+  @SuppressWarnings("PMD.MethodReturnsInternalArray")
+  public double[] getHomography() {
+    return m_homography;
+  }
+
+  /**
+   * Gets the 3x3 homography matrix describing the projection from an "ideal" tag (with corners at
+   * (-1,1), (1,1), (1,-1), and (-1, -1)) to pixels in the image.
+   *
+   * @return Homography matrix
+   */
+  public Matrix<N3, N3> getHomographyMatrix() {
+    return new MatBuilder<>(Nat.N3(), Nat.N3()).fill(m_homography);
+  }
+
+  /**
+   * Gets the center of the detection in image pixel coordinates.
+   *
+   * @return Center point X coordinate
+   */
+  public double getCenterX() {
+    return m_centerX;
+  }
+
+  /**
+   * Gets the center of the detection in image pixel coordinates.
+   *
+   * @return Center point Y coordinate
+   */
+  public double getCenterY() {
+    return m_centerY;
+  }
+
+  /**
+   * Gets a corner of the tag in image pixel coordinates. These always wrap counter-clock wise
+   * around the tag.
+   *
+   * @param ndx Corner index (range is 0-3, inclusive)
+   * @return Corner point X coordinate
+   */
+  public double getCornerX(int ndx) {
+    return m_corners[ndx * 2];
+  }
+
+  /**
+   * Gets a corner of the tag in image pixel coordinates. These always wrap counter-clock wise
+   * around the tag.
+   *
+   * @param ndx Corner index (range is 0-3, inclusive)
+   * @return Corner point Y coordinate
+   */
+  public double getCornerY(int ndx) {
+    return m_corners[ndx * 2 + 1];
+  }
+
+  /**
+   * Gets the corners of the tag in image pixel coordinates. These always wrap counter-clock wise
+   * around the tag.
+   *
+   * @return Corner point array (X and Y for each corner in order)
+   */
+  @SuppressWarnings("PMD.MethodReturnsInternalArray")
+  public double[] getCorners() {
+    return m_corners;
+  }
+
+  private final String m_family;
+  private final int m_id;
+  private final int m_hamming;
+  private final float m_decisionMargin;
+  private final double[] m_homography;
+  private final double m_centerX;
+  private final double m_centerY;
+  private final double[] m_corners;
+
+  /**
+   * Constructs a new detection result. Used from JNI.
+   *
+   * @param family family
+   * @param id id
+   * @param hamming hamming
+   * @param decisionMargin dm
+   * @param homography homography
+   * @param centerX centerX
+   * @param centerY centerY
+   * @param corners corners
+   */
+  @SuppressWarnings("PMD.ArrayIsStoredDirectly")
+  public AprilTagDetection(
+      String family,
+      int id,
+      int hamming,
+      float decisionMargin,
+      double[] homography,
+      double centerX,
+      double centerY,
+      double[] corners) {
+    m_family = family;
+    m_id = id;
+    m_hamming = hamming;
+    m_decisionMargin = decisionMargin;
+    m_homography = homography;
+    m_centerX = centerX;
+    m_centerY = centerY;
+    m_corners = corners;
+  }
+
+  @Override
+  public String toString() {
+    return "DetectionResult [centerX="
+        + m_centerX
+        + ", centerY="
+        + m_centerY
+        + ", corners="
+        + Arrays.toString(m_corners)
+        + ", decisionMargin="
+        + m_decisionMargin
+        + ", hamming="
+        + m_hamming
+        + ", homography="
+        + Arrays.toString(m_homography)
+        + ", family="
+        + m_family
+        + ", id="
+        + m_id
+        + "]";
+  }
+}
diff --git a/third_party/allwpilib/apriltag/src/main/java/edu/wpi/first/apriltag/AprilTagDetector.java b/third_party/allwpilib/apriltag/src/main/java/edu/wpi/first/apriltag/AprilTagDetector.java
new file mode 100644
index 0000000..b8e9cb0
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/main/java/edu/wpi/first/apriltag/AprilTagDetector.java
@@ -0,0 +1,281 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.apriltag;
+
+import edu.wpi.first.apriltag.jni.AprilTagJNI;
+import org.opencv.core.Mat;
+
+/**
+ * An AprilTag detector engine. This is expensive to set up and tear down, so most use cases should
+ * only create one of these, add a family to it, set up any other configuration, and repeatedly call
+ * Detect().
+ */
+public class AprilTagDetector implements AutoCloseable {
+  /** Detector configuration. */
+  @SuppressWarnings("MemberName")
+  public static class Config {
+    /**
+     * How many threads should be used for computation. Default is single-threaded operation (1
+     * thread).
+     */
+    public int numThreads = 1;
+
+    /**
+     * Quad decimation. Detection of quads can be done on a lower-resolution image, improving speed
+     * at a cost of pose accuracy and a slight decrease in detection rate. Decoding the binary
+     * payload is still done at full resolution. Default is 2.0.
+     */
+    public float quadDecimate = 2.0f;
+
+    /**
+     * What Gaussian blur should be applied to the segmented image (used for quad detection). Very
+     * noisy images benefit from non-zero values (e.g. 0.8). Default is 0.0.
+     */
+    public float quadSigma;
+
+    /**
+     * When true, the edges of the each quad are adjusted to "snap to" strong gradients nearby. This
+     * is useful when decimation is employed, as it can increase the quality of the initial quad
+     * estimate substantially. Generally recommended to be on (true). Default is true.
+     *
+     * <p>Very computationally inexpensive. Option is ignored if quad_decimate = 1.
+     */
+    public boolean refineEdges = true;
+
+    /**
+     * How much sharpening should be done to decoded images. This can help decode small tags but may
+     * or may not help in odd lighting conditions or low light conditions. Default is 0.25.
+     */
+    public double decodeSharpening = 0.25;
+
+    /**
+     * Debug mode. When true, the decoder writes a variety of debugging images to the current
+     * working directory at various stages through the detection process. This is slow and should
+     * *not* be used on space-limited systems such as the RoboRIO. Default is disabled (false).
+     */
+    public boolean debug;
+
+    public Config() {}
+
+    Config(
+        int numThreads,
+        float quadDecimate,
+        float quadSigma,
+        boolean refineEdges,
+        double decodeSharpening,
+        boolean debug) {
+      this.numThreads = numThreads;
+      this.quadDecimate = quadDecimate;
+      this.quadSigma = quadSigma;
+      this.refineEdges = refineEdges;
+      this.decodeSharpening = decodeSharpening;
+      this.debug = debug;
+    }
+
+    @Override
+    public int hashCode() {
+      return numThreads
+          + Float.hashCode(quadDecimate)
+          + Float.hashCode(quadSigma)
+          + Boolean.hashCode(refineEdges)
+          + Double.hashCode(decodeSharpening)
+          + Boolean.hashCode(debug);
+    }
+
+    @Override
+    public boolean equals(Object obj) {
+      if (!(obj instanceof Config)) {
+        return false;
+      }
+
+      Config other = (Config) obj;
+      return numThreads == other.numThreads
+          && quadDecimate == other.quadDecimate
+          && quadSigma == other.quadSigma
+          && refineEdges == other.refineEdges
+          && decodeSharpening == other.decodeSharpening
+          && debug == other.debug;
+    }
+  }
+
+  /** Quad threshold parameters. */
+  @SuppressWarnings("MemberName")
+  public static class QuadThresholdParameters {
+    /** Threshold used to reject quads containing too few pixels. Default is 5 pixels. */
+    public int minClusterPixels = 5;
+
+    /**
+     * How many corner candidates to consider when segmenting a group of pixels into a quad. Default
+     * is 10.
+     */
+    public int maxNumMaxima = 10;
+
+    /**
+     * Critical angle, in radians. The detector will reject quads where pairs of edges have angles
+     * that are close to straight or close to 180 degrees. Zero means that no quads are rejected.
+     * Default is 10 degrees.
+     */
+    public double criticalAngle = 10 * Math.PI / 180.0;
+
+    /**
+     * When fitting lines to the contours, the maximum mean squared error allowed. This is useful in
+     * rejecting contours that are far from being quad shaped; rejecting these quads "early" saves
+     * expensive decoding processing. Default is 10.0.
+     */
+    public float maxLineFitMSE = 10.0f;
+
+    /**
+     * Minimum brightness offset. When we build our model of black &amp; white pixels, we add an
+     * extra check that the white model must be (overall) brighter than the black model. How much
+     * brighter? (in pixel values, [0,255]). Default is 5.
+     */
+    public int minWhiteBlackDiff = 5;
+
+    /**
+     * Whether the thresholded image be should be deglitched. Only useful for very noisy images.
+     * Default is disabled (false).
+     */
+    public boolean deglitch;
+
+    public QuadThresholdParameters() {}
+
+    QuadThresholdParameters(
+        int minClusterPixels,
+        int maxNumMaxima,
+        double criticalAngle,
+        float maxLineFitMSE,
+        int minWhiteBlackDiff,
+        boolean deglitch) {
+      this.minClusterPixels = minClusterPixels;
+      this.maxNumMaxima = maxNumMaxima;
+      this.criticalAngle = criticalAngle;
+      this.maxLineFitMSE = maxLineFitMSE;
+      this.minWhiteBlackDiff = minWhiteBlackDiff;
+      this.deglitch = deglitch;
+    }
+
+    @Override
+    public int hashCode() {
+      return minClusterPixels
+          + maxNumMaxima
+          + Double.hashCode(criticalAngle)
+          + Float.hashCode(maxLineFitMSE)
+          + minWhiteBlackDiff
+          + Boolean.hashCode(deglitch);
+    }
+
+    @Override
+    public boolean equals(Object obj) {
+      if (!(obj instanceof QuadThresholdParameters)) {
+        return false;
+      }
+
+      QuadThresholdParameters other = (QuadThresholdParameters) obj;
+      return minClusterPixels == other.minClusterPixels
+          && maxNumMaxima == other.maxNumMaxima
+          && criticalAngle == other.criticalAngle
+          && maxLineFitMSE == other.maxLineFitMSE
+          && minWhiteBlackDiff == other.minWhiteBlackDiff
+          && deglitch == other.deglitch;
+    }
+  }
+
+  public AprilTagDetector() {
+    m_native = AprilTagJNI.createDetector();
+  }
+
+  @Override
+  public void close() {
+    if (m_native != 0) {
+      AprilTagJNI.destroyDetector(m_native);
+    }
+    m_native = 0;
+  }
+
+  /**
+   * Sets detector configuration.
+   *
+   * @param config Configuration
+   */
+  public void setConfig(Config config) {
+    AprilTagJNI.setDetectorConfig(m_native, config);
+  }
+
+  /**
+   * Gets detector configuration.
+   *
+   * @return Configuration
+   */
+  public Config getConfig() {
+    return AprilTagJNI.getDetectorConfig(m_native);
+  }
+
+  /**
+   * Sets quad threshold parameters.
+   *
+   * @param params Parameters
+   */
+  public void setQuadThresholdParameters(QuadThresholdParameters params) {
+    AprilTagJNI.setDetectorQTP(m_native, params);
+  }
+
+  /**
+   * Gets quad threshold parameters.
+   *
+   * @return Parameters
+   */
+  public QuadThresholdParameters getQuadThresholdParameters() {
+    return AprilTagJNI.getDetectorQTP(m_native);
+  }
+
+  /**
+   * Adds a family of tags to be detected.
+   *
+   * @param fam Family name, e.g. "tag16h5"
+   * @throws IllegalArgumentException if family name not recognized
+   */
+  public void addFamily(String fam) {
+    addFamily(fam, 2);
+  }
+
+  /**
+   * Adds a family of tags to be detected.
+   *
+   * @param fam Family name, e.g. "tag16h5"
+   * @param bitsCorrected maximum number of bits to correct
+   * @throws IllegalArgumentException if family name not recognized
+   */
+  public void addFamily(String fam, int bitsCorrected) {
+    if (!AprilTagJNI.addFamily(m_native, fam, bitsCorrected)) {
+      throw new IllegalArgumentException("unknown family name '" + fam + "'");
+    }
+  }
+
+  /**
+   * Removes a family of tags from the detector.
+   *
+   * @param fam Family name, e.g. "tag16h5"
+   */
+  public void removeFamily(String fam) {
+    AprilTagJNI.removeFamily(m_native, fam);
+  }
+
+  /** Unregister all families. */
+  public void clearFamilies() {
+    AprilTagJNI.clearFamilies(m_native);
+  }
+
+  /**
+   * Detect tags from an 8-bit image.
+   *
+   * @param img 8-bit OpenCV Mat image
+   * @return Results (array of AprilTagDetection)
+   */
+  public AprilTagDetection[] detect(Mat img) {
+    return AprilTagJNI.detect(m_native, img.cols(), img.rows(), img.cols(), img.dataAddr());
+  }
+
+  private long m_native;
+}
diff --git a/third_party/allwpilib/apriltag/src/main/java/edu/wpi/first/apriltag/AprilTagFieldLayout.java b/third_party/allwpilib/apriltag/src/main/java/edu/wpi/first/apriltag/AprilTagFieldLayout.java
new file mode 100644
index 0000000..605c97c
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/main/java/edu/wpi/first/apriltag/AprilTagFieldLayout.java
@@ -0,0 +1,235 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.apriltag;
+
+import com.fasterxml.jackson.annotation.JsonAutoDetect;
+import com.fasterxml.jackson.annotation.JsonCreator;
+import com.fasterxml.jackson.annotation.JsonIgnore;
+import com.fasterxml.jackson.annotation.JsonIgnoreProperties;
+import com.fasterxml.jackson.annotation.JsonProperty;
+import com.fasterxml.jackson.databind.ObjectMapper;
+import edu.wpi.first.math.geometry.Pose3d;
+import edu.wpi.first.math.geometry.Rotation3d;
+import edu.wpi.first.math.geometry.Translation3d;
+import java.io.IOException;
+import java.io.InputStream;
+import java.io.InputStreamReader;
+import java.nio.file.Path;
+import java.util.ArrayList;
+import java.util.HashMap;
+import java.util.List;
+import java.util.Map;
+import java.util.Objects;
+import java.util.Optional;
+
+/**
+ * Class for representing a layout of AprilTags on a field and reading them from a JSON format.
+ *
+ * <p>The JSON format contains two top-level objects, "tags" and "field". The "tags" object is a
+ * list of all AprilTags contained within a layout. Each AprilTag serializes to a JSON object
+ * containing an ID and a Pose3d. The "field" object is a descriptor of the size of the field in
+ * meters with "width" and "length" values. This is to account for arbitrary field sizes when
+ * transforming the poses.
+ *
+ * <p>Pose3ds in the JSON are measured using the normal FRC coordinate system, NWU with the origin
+ * at the bottom-right corner of the blue alliance wall. {@link #setOrigin(OriginPosition)} can be
+ * used to change the poses returned from {@link AprilTagFieldLayout#getTagPose(int)} to be from the
+ * perspective of a specific alliance.
+ */
+@JsonIgnoreProperties(ignoreUnknown = true)
+@JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE)
+public class AprilTagFieldLayout {
+  public enum OriginPosition {
+    kBlueAllianceWallRightSide,
+    kRedAllianceWallRightSide,
+  }
+
+  private final Map<Integer, AprilTag> m_apriltags = new HashMap<>();
+
+  @JsonProperty(value = "field")
+  private FieldDimensions m_fieldDimensions;
+
+  private Pose3d m_origin;
+
+  /**
+   * Construct a new AprilTagFieldLayout with values imported from a JSON file.
+   *
+   * @param path Path of the JSON file to import from.
+   * @throws IOException If reading from the file fails.
+   */
+  public AprilTagFieldLayout(String path) throws IOException {
+    this(Path.of(path));
+  }
+
+  /**
+   * Construct a new AprilTagFieldLayout with values imported from a JSON file.
+   *
+   * @param path Path of the JSON file to import from.
+   * @throws IOException If reading from the file fails.
+   */
+  public AprilTagFieldLayout(Path path) throws IOException {
+    AprilTagFieldLayout layout =
+        new ObjectMapper().readValue(path.toFile(), AprilTagFieldLayout.class);
+    m_apriltags.putAll(layout.m_apriltags);
+    m_fieldDimensions = layout.m_fieldDimensions;
+    setOrigin(OriginPosition.kBlueAllianceWallRightSide);
+  }
+
+  /**
+   * Construct a new AprilTagFieldLayout from a list of {@link AprilTag} objects.
+   *
+   * @param apriltags List of {@link AprilTag}.
+   * @param fieldLength Length of the field the layout is representing in meters.
+   * @param fieldWidth Width of the field the layout is representing in meters.
+   */
+  public AprilTagFieldLayout(List<AprilTag> apriltags, double fieldLength, double fieldWidth) {
+    this(apriltags, new FieldDimensions(fieldLength, fieldWidth));
+  }
+
+  @JsonCreator
+  private AprilTagFieldLayout(
+      @JsonProperty(required = true, value = "tags") List<AprilTag> apriltags,
+      @JsonProperty(required = true, value = "field") FieldDimensions fieldDimensions) {
+    // To ensure the underlying semantics don't change with what kind of list is passed in
+    for (AprilTag tag : apriltags) {
+      m_apriltags.put(tag.ID, tag);
+    }
+    m_fieldDimensions = fieldDimensions;
+    setOrigin(OriginPosition.kBlueAllianceWallRightSide);
+  }
+
+  /**
+   * Returns a List of the {@link AprilTag AprilTags} used in this layout.
+   *
+   * @return The {@link AprilTag AprilTags} used in this layout.
+   */
+  @JsonProperty("tags")
+  public List<AprilTag> getTags() {
+    return new ArrayList<>(m_apriltags.values());
+  }
+
+  /**
+   * Sets the origin based on a predefined enumeration of coordinate frame origins. The origins are
+   * calculated from the field dimensions.
+   *
+   * <p>This transforms the Pose3d objects returned by {@link #getTagPose(int)} to return the
+   * correct pose relative to a predefined coordinate frame.
+   *
+   * @param origin The predefined origin
+   */
+  @JsonIgnore
+  public void setOrigin(OriginPosition origin) {
+    switch (origin) {
+      case kBlueAllianceWallRightSide:
+        setOrigin(new Pose3d());
+        break;
+      case kRedAllianceWallRightSide:
+        setOrigin(
+            new Pose3d(
+                new Translation3d(m_fieldDimensions.fieldLength, m_fieldDimensions.fieldWidth, 0),
+                new Rotation3d(0, 0, Math.PI)));
+        break;
+      default:
+        throw new IllegalArgumentException("Unsupported enum value");
+    }
+  }
+
+  /**
+   * Sets the origin for tag pose transformation.
+   *
+   * <p>This transforms the Pose3d objects returned by {@link #getTagPose(int)} to return the
+   * correct pose relative to the provided origin.
+   *
+   * @param origin The new origin for tag transformations
+   */
+  @JsonIgnore
+  public void setOrigin(Pose3d origin) {
+    m_origin = origin;
+  }
+
+  /**
+   * Gets an AprilTag pose by its ID.
+   *
+   * @param ID The ID of the tag.
+   * @return The pose corresponding to the ID passed in or an empty optional if a tag with that ID
+   *     was not found.
+   */
+  @SuppressWarnings("ParameterName")
+  public Optional<Pose3d> getTagPose(int ID) {
+    AprilTag tag = m_apriltags.get(ID);
+    if (tag == null) {
+      return Optional.empty();
+    }
+    return Optional.of(tag.pose.relativeTo(m_origin));
+  }
+
+  /**
+   * Serializes a AprilTagFieldLayout to a JSON file.
+   *
+   * @param path The path to write to.
+   * @throws IOException If writing to the file fails.
+   */
+  public void serialize(String path) throws IOException {
+    serialize(Path.of(path));
+  }
+
+  /**
+   * Serializes a AprilTagFieldLayout to a JSON file.
+   *
+   * @param path The path to write to.
+   * @throws IOException If writing to the file fails.
+   */
+  public void serialize(Path path) throws IOException {
+    new ObjectMapper().writeValue(path.toFile(), this);
+  }
+
+  /**
+   * Deserializes a field layout from a resource within a jar file.
+   *
+   * @param resourcePath The absolute path of the resource
+   * @return The deserialized layout
+   * @throws IOException If the resource could not be loaded
+   */
+  public static AprilTagFieldLayout loadFromResource(String resourcePath) throws IOException {
+    try (InputStream stream = AprilTagFieldLayout.class.getResourceAsStream(resourcePath);
+        InputStreamReader reader = new InputStreamReader(stream)) {
+      return new ObjectMapper().readerFor(AprilTagFieldLayout.class).readValue(reader);
+    }
+  }
+
+  @Override
+  public boolean equals(Object obj) {
+    if (obj instanceof AprilTagFieldLayout) {
+      var other = (AprilTagFieldLayout) obj;
+      return m_apriltags.equals(other.m_apriltags) && m_origin.equals(other.m_origin);
+    }
+    return false;
+  }
+
+  @Override
+  public int hashCode() {
+    return Objects.hash(m_apriltags, m_origin);
+  }
+
+  @JsonIgnoreProperties(ignoreUnknown = true)
+  @JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE)
+  private static class FieldDimensions {
+    @SuppressWarnings("MemberName")
+    @JsonProperty(value = "length")
+    public double fieldLength;
+
+    @SuppressWarnings("MemberName")
+    @JsonProperty(value = "width")
+    public double fieldWidth;
+
+    @JsonCreator()
+    FieldDimensions(
+        @JsonProperty(required = true, value = "length") double fieldLength,
+        @JsonProperty(required = true, value = "width") double fieldWidth) {
+      this.fieldLength = fieldLength;
+      this.fieldWidth = fieldWidth;
+    }
+  }
+}
diff --git a/third_party/allwpilib/apriltag/src/main/java/edu/wpi/first/apriltag/AprilTagFields.java b/third_party/allwpilib/apriltag/src/main/java/edu/wpi/first/apriltag/AprilTagFields.java
new file mode 100644
index 0000000..28eeb58
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/main/java/edu/wpi/first/apriltag/AprilTagFields.java
@@ -0,0 +1,20 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.apriltag;
+
+public enum AprilTagFields {
+  k2022RapidReact("2022-rapidreact.json");
+
+  public static final String kBaseResourceDir = "/edu/wpi/first/apriltag/";
+
+  /** Alias to the current game. */
+  public static final AprilTagFields kDefaultField = k2022RapidReact;
+
+  public final String m_resourceFile;
+
+  AprilTagFields(String resourceFile) {
+    m_resourceFile = kBaseResourceDir + resourceFile;
+  }
+}
diff --git a/third_party/allwpilib/apriltag/src/main/java/edu/wpi/first/apriltag/AprilTagPoseEstimate.java b/third_party/allwpilib/apriltag/src/main/java/edu/wpi/first/apriltag/AprilTagPoseEstimate.java
new file mode 100644
index 0000000..7bf079a
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/main/java/edu/wpi/first/apriltag/AprilTagPoseEstimate.java
@@ -0,0 +1,55 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.apriltag;
+
+import edu.wpi.first.math.geometry.Transform3d;
+
+/** A pair of AprilTag pose estimates. */
+@SuppressWarnings("MemberName")
+public class AprilTagPoseEstimate {
+  /**
+   * Constructs a pose estimate.
+   *
+   * @param pose1 first pose
+   * @param pose2 second pose
+   * @param error1 error of first pose
+   * @param error2 error of second pose
+   */
+  public AprilTagPoseEstimate(Transform3d pose1, Transform3d pose2, double error1, double error2) {
+    this.pose1 = pose1;
+    this.pose2 = pose2;
+    this.error1 = error1;
+    this.error2 = error2;
+  }
+
+  /**
+   * Get the ratio of pose reprojection errors, called ambiguity. Numbers above 0.2 are likely to be
+   * ambiguous.
+   *
+   * @return The ratio of pose reprojection errors.
+   */
+  public double getAmbiguity() {
+    double min = Math.min(error1, error2);
+    double max = Math.max(error1, error2);
+
+    if (max > 0) {
+      return min / max;
+    } else {
+      return -1;
+    }
+  }
+
+  /** Pose 1. */
+  public final Transform3d pose1;
+
+  /** Pose 2. */
+  public final Transform3d pose2;
+
+  /** Object-space error of pose 1. */
+  public final double error1;
+
+  /** Object-space error of pose 2. */
+  public final double error2;
+}
diff --git a/third_party/allwpilib/apriltag/src/main/java/edu/wpi/first/apriltag/AprilTagPoseEstimator.java b/third_party/allwpilib/apriltag/src/main/java/edu/wpi/first/apriltag/AprilTagPoseEstimator.java
new file mode 100644
index 0000000..2b7f68a
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/main/java/edu/wpi/first/apriltag/AprilTagPoseEstimator.java
@@ -0,0 +1,190 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.apriltag;
+
+import edu.wpi.first.apriltag.jni.AprilTagJNI;
+import edu.wpi.first.math.geometry.Transform3d;
+
+/** Pose estimators for AprilTag tags. */
+public class AprilTagPoseEstimator {
+  /** Configuration for the pose estimator. */
+  @SuppressWarnings("MemberName")
+  public static class Config {
+    /**
+     * Creates a pose estimator configuration.
+     *
+     * @param tagSize tag size, in meters
+     * @param fx camera horizontal focal length, in pixels
+     * @param fy camera vertical focal length, in pixels
+     * @param cx camera horizontal focal center, in pixels
+     * @param cy camera vertical focal center, in pixels
+     */
+    public Config(double tagSize, double fx, double fy, double cx, double cy) {
+      this.tagSize = tagSize;
+      this.fx = fx;
+      this.fy = fy;
+      this.cx = cx;
+      this.cy = cy;
+    }
+
+    public double tagSize;
+    public double fx;
+    public double fy;
+    public double cx;
+    public double cy;
+
+    @Override
+    public int hashCode() {
+      return Double.hashCode(tagSize)
+          + Double.hashCode(fx)
+          + Double.hashCode(fy)
+          + Double.hashCode(cx)
+          + Double.hashCode(cy);
+    }
+
+    @Override
+    public boolean equals(Object obj) {
+      if (!(obj instanceof Config)) {
+        return false;
+      }
+
+      Config other = (Config) obj;
+      return tagSize == other.tagSize
+          && fx == other.fx
+          && fy == other.fy
+          && cx == other.cx
+          && cy == other.cy;
+    }
+  }
+
+  /**
+   * Creates estimator.
+   *
+   * @param config Configuration
+   */
+  public AprilTagPoseEstimator(Config config) {
+    m_config = new Config(config.tagSize, config.fx, config.fy, config.cx, config.cy);
+  }
+
+  /**
+   * Sets estimator configuration.
+   *
+   * @param config Configuration
+   */
+  public void setConfig(Config config) {
+    m_config.tagSize = config.tagSize;
+    m_config.fx = config.fx;
+    m_config.fy = config.fy;
+    m_config.cx = config.cx;
+    m_config.cy = config.cy;
+  }
+
+  /**
+   * Gets estimator configuration.
+   *
+   * @return Configuration
+   */
+  public Config getConfig() {
+    return new Config(m_config.tagSize, m_config.fx, m_config.fy, m_config.cx, m_config.cy);
+  }
+
+  /**
+   * Estimates the pose of the tag using the homography method described in [1].
+   *
+   * @param detection Tag detection
+   * @return Pose estimate
+   */
+  public Transform3d estimateHomography(AprilTagDetection detection) {
+    return estimateHomography(detection.getHomography());
+  }
+
+  /**
+   * Estimates the pose of the tag using the homography method described in [1].
+   *
+   * @param homography Homography 3x3 matrix data
+   * @return Pose estimate
+   */
+  public Transform3d estimateHomography(double[] homography) {
+    return AprilTagJNI.estimatePoseHomography(
+        homography, m_config.tagSize, m_config.fx, m_config.fy, m_config.cx, m_config.cy);
+  }
+
+  /**
+   * Estimates the pose of the tag. This returns one or two possible poses for the tag, along with
+   * the object-space error of each.
+   *
+   * <p>This uses the homography method described in [1] for the initial estimate. Then Orthogonal
+   * Iteration [2] is used to refine this estimate. Then [3] is used to find a potential second
+   * local minima and Orthogonal Iteration is used to refine this second estimate.
+   *
+   * <p>[1]: E. Olson, “Apriltag: A robust and flexible visual fiducial system,” in 2011 IEEE
+   * International Conference on Robotics and Automation, May 2011, pp. 3400–3407.
+   *
+   * <p>[2]: Lu, G. D. Hager and E. Mjolsness, "Fast and globally convergent pose estimation from
+   * video images," in IEEE Transactions on Pattern Analysis and Machine Intelligence, vol. 22, no.
+   * 6, pp. 610-622, June 2000. doi: 10.1109/34.862199
+   *
+   * <p>[3]: Schweighofer and A. Pinz, "Robust Pose Estimation from a Planar Target," in IEEE
+   * Transactions on Pattern Analysis and Machine Intelligence, vol. 28, no. 12, pp. 2024-2030, Dec.
+   * 2006. doi: 10.1109/TPAMI.2006.252
+   *
+   * @param detection Tag detection
+   * @param nIters Number of iterations
+   * @return Initial and (possibly) second pose estimates
+   */
+  public AprilTagPoseEstimate estimateOrthogonalIteration(AprilTagDetection detection, int nIters) {
+    return estimateOrthogonalIteration(detection.getHomography(), detection.getCorners(), nIters);
+  }
+
+  /**
+   * Estimates the pose of the tag. This returns one or two possible poses for the tag, along with
+   * the object-space error of each.
+   *
+   * @param homography Homography 3x3 matrix data
+   * @param corners Corner point array (X and Y for each corner in order)
+   * @param nIters Number of iterations
+   * @return Initial and (possibly) second pose estimates
+   */
+  public AprilTagPoseEstimate estimateOrthogonalIteration(
+      double[] homography, double[] corners, int nIters) {
+    return AprilTagJNI.estimatePoseOrthogonalIteration(
+        homography,
+        corners,
+        m_config.tagSize,
+        m_config.fx,
+        m_config.fy,
+        m_config.cx,
+        m_config.cy,
+        nIters);
+  }
+
+  /**
+   * Estimates tag pose. This method is an easier to use interface to
+   * EstimatePoseOrthogonalIteration(), running 50 iterations and returning the pose with the lower
+   * object-space error.
+   *
+   * @param detection Tag detection
+   * @return Pose estimate
+   */
+  public Transform3d estimate(AprilTagDetection detection) {
+    return estimate(detection.getHomography(), detection.getCorners());
+  }
+
+  /**
+   * Estimates tag pose. This method is an easier to use interface to
+   * EstimatePoseOrthogonalIteration(), running 50 iterations and returning the pose with the lower
+   * object-space error.
+   *
+   * @param homography Homography 3x3 matrix data
+   * @param corners Corner point array (X and Y for each corner in order)
+   * @return Pose estimate
+   */
+  public Transform3d estimate(double[] homography, double[] corners) {
+    return AprilTagJNI.estimatePose(
+        homography, corners, m_config.tagSize, m_config.fx, m_config.fy, m_config.cx, m_config.cy);
+  }
+
+  private final Config m_config;
+}
diff --git a/third_party/allwpilib/apriltag/src/main/java/edu/wpi/first/apriltag/jni/AprilTagJNI.java b/third_party/allwpilib/apriltag/src/main/java/edu/wpi/first/apriltag/jni/AprilTagJNI.java
new file mode 100644
index 0000000..1a7c692
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/main/java/edu/wpi/first/apriltag/jni/AprilTagJNI.java
@@ -0,0 +1,90 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.apriltag.jni;
+
+import edu.wpi.first.apriltag.AprilTagDetection;
+import edu.wpi.first.apriltag.AprilTagDetector;
+import edu.wpi.first.apriltag.AprilTagPoseEstimate;
+import edu.wpi.first.math.geometry.Transform3d;
+import edu.wpi.first.util.RuntimeLoader;
+import java.io.IOException;
+import java.util.concurrent.atomic.AtomicBoolean;
+
+public class AprilTagJNI {
+  static boolean libraryLoaded = false;
+
+  static RuntimeLoader<AprilTagJNI> loader = null;
+
+  public static class Helper {
+    private static AtomicBoolean extractOnStaticLoad = new AtomicBoolean(true);
+
+    public static boolean getExtractOnStaticLoad() {
+      return extractOnStaticLoad.get();
+    }
+
+    public static void setExtractOnStaticLoad(boolean load) {
+      extractOnStaticLoad.set(load);
+    }
+  }
+
+  static {
+    if (Helper.getExtractOnStaticLoad()) {
+      try {
+        loader =
+            new RuntimeLoader<>(
+                "apriltagjni", RuntimeLoader.getDefaultExtractionRoot(), AprilTagJNI.class);
+        loader.loadLibrary();
+      } catch (IOException ex) {
+        ex.printStackTrace();
+        System.exit(1);
+      }
+      libraryLoaded = true;
+    }
+  }
+
+  public static native long createDetector();
+
+  public static native void destroyDetector(long det);
+
+  public static native void setDetectorConfig(long det, AprilTagDetector.Config config);
+
+  public static native AprilTagDetector.Config getDetectorConfig(long det);
+
+  public static native void setDetectorQTP(
+      long det, AprilTagDetector.QuadThresholdParameters params);
+
+  public static native AprilTagDetector.QuadThresholdParameters getDetectorQTP(long det);
+
+  public static native boolean addFamily(long det, String fam, int bitsCorrected);
+
+  public static native void removeFamily(long det, String fam);
+
+  public static native void clearFamilies(long det);
+
+  public static native AprilTagDetection[] detect(
+      long det, int width, int height, int stride, long bufAddr);
+
+  public static native Transform3d estimatePoseHomography(
+      double[] homography, double tagSize, double fx, double fy, double cx, double cy);
+
+  public static native AprilTagPoseEstimate estimatePoseOrthogonalIteration(
+      double[] homography,
+      double[] corners,
+      double tagSize,
+      double fx,
+      double fy,
+      double cx,
+      double cy,
+      int nIters);
+
+  public static native Transform3d estimatePose(
+      double[] homography,
+      double[] corners,
+      double tagSize,
+      double fx,
+      double fy,
+      double cx,
+      double cy);
+}
diff --git a/third_party/allwpilib/apriltag/src/main/native/cpp/AprilTag.cpp b/third_party/allwpilib/apriltag/src/main/native/cpp/AprilTag.cpp
new file mode 100644
index 0000000..3805573
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/main/native/cpp/AprilTag.cpp
@@ -0,0 +1,18 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/apriltag/AprilTag.h"
+
+#include <wpi/json.h>
+
+using namespace frc;
+
+void frc::to_json(wpi::json& json, const AprilTag& apriltag) {
+  json = wpi::json{{"ID", apriltag.ID}, {"pose", apriltag.pose}};
+}
+
+void frc::from_json(const wpi::json& json, AprilTag& apriltag) {
+  apriltag.ID = json.at("ID").get<int>();
+  apriltag.pose = json.at("pose").get<Pose3d>();
+}
diff --git a/third_party/allwpilib/apriltag/src/main/native/cpp/AprilTagDetection.cpp b/third_party/allwpilib/apriltag/src/main/native/cpp/AprilTagDetection.cpp
new file mode 100644
index 0000000..aaa80be
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/main/native/cpp/AprilTagDetection.cpp
@@ -0,0 +1,37 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/apriltag/AprilTagDetection.h"
+
+#include <type_traits>
+
+#ifdef _WIN32
+#pragma warning(disable : 4200)
+#elif defined(__clang__)
+#pragma clang diagnostic ignored "-Wc99-extensions"
+#elif defined(__GNUC__)
+#pragma GCC diagnostic ignored "-Wpedantic"
+#endif
+
+#include "apriltag.h"
+
+using namespace frc;
+
+static_assert(sizeof(AprilTagDetection) == sizeof(apriltag_detection_t),
+              "structure sizes don't match");
+static_assert(std::is_standard_layout_v<AprilTagDetection>,
+              "AprilTagDetection is not standard layout?");
+
+std::string_view AprilTagDetection::GetFamily() const {
+  return static_cast<const apriltag_family_t*>(family)->name;
+}
+
+std::span<const double, 9> AprilTagDetection::GetHomography() const {
+  return std::span<const double, 9>{static_cast<matd_t*>(H)->data, 9};
+}
+
+Eigen::Matrix3d AprilTagDetection::GetHomographyMatrix() const {
+  return Eigen::Map<Eigen::Matrix<double, 3, 3, Eigen::RowMajor>>{
+      static_cast<matd_t*>(H)->data};
+}
diff --git a/third_party/allwpilib/apriltag/src/main/native/cpp/AprilTagDetector.cpp b/third_party/allwpilib/apriltag/src/main/native/cpp/AprilTagDetector.cpp
new file mode 100644
index 0000000..cae9c0a
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/main/native/cpp/AprilTagDetector.cpp
@@ -0,0 +1,200 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/apriltag/AprilTagDetector.h"
+
+#include <cmath>
+#include <numbers>
+
+#ifdef _WIN32
+#pragma warning(disable : 4200)
+#elif defined(__clang__)
+#pragma clang diagnostic ignored "-Wc99-extensions"
+#elif defined(__GNUC__)
+#pragma GCC diagnostic ignored "-Wpedantic"
+#endif
+
+#include "apriltag.h"
+#include "tag16h5.h"
+#include "tag25h9.h"
+#include "tag36h11.h"
+#include "tagCircle21h7.h"
+#include "tagCircle49h12.h"
+#include "tagCustom48h12.h"
+#include "tagStandard41h12.h"
+#include "tagStandard52h13.h"
+
+using namespace frc;
+
+AprilTagDetector::Results::Results(void* impl, const private_init&)
+    : span{reinterpret_cast<AprilTagDetection**>(
+               static_cast<zarray_t*>(impl)->data),
+           static_cast<size_t>(static_cast<zarray_t*>(impl)->size)},
+      m_impl{impl} {}
+
+AprilTagDetector::Results& AprilTagDetector::Results::operator=(Results&& rhs) {
+  Destroy();
+  m_impl = rhs.m_impl;
+  rhs.m_impl = nullptr;
+  return *this;
+}
+
+void AprilTagDetector::Results::Destroy() {
+  if (m_impl) {
+    apriltag_detections_destroy(static_cast<zarray_t*>(m_impl));
+  }
+}
+
+AprilTagDetector::AprilTagDetector() : m_impl{apriltag_detector_create()} {}
+
+AprilTagDetector& AprilTagDetector::operator=(AprilTagDetector&& rhs) {
+  Destroy();
+  m_impl = rhs.m_impl;
+  rhs.m_impl = nullptr;
+  m_families = std::move(rhs.m_families);
+  rhs.m_families.clear();
+  m_qtpCriticalAngle = rhs.m_qtpCriticalAngle;
+  return *this;
+}
+
+void AprilTagDetector::SetConfig(const Config& config) {
+  auto& impl = *static_cast<apriltag_detector_t*>(m_impl);
+  impl.nthreads = config.numThreads;
+  impl.quad_decimate = config.quadDecimate;
+  impl.quad_sigma = config.quadSigma;
+  impl.refine_edges = config.refineEdges;
+  impl.decode_sharpening = config.decodeSharpening;
+  impl.debug = config.debug;
+}
+
+AprilTagDetector::Config AprilTagDetector::GetConfig() const {
+  auto& impl = *static_cast<apriltag_detector_t*>(m_impl);
+  return {
+      .numThreads = impl.nthreads,
+      .quadDecimate = impl.quad_decimate,
+      .quadSigma = impl.quad_sigma,
+      .refineEdges = impl.refine_edges,
+      .decodeSharpening = impl.decode_sharpening,
+      .debug = impl.debug,
+  };
+}
+
+void AprilTagDetector::SetQuadThresholdParameters(
+    const QuadThresholdParameters& params) {
+  auto& qtp = static_cast<apriltag_detector_t*>(m_impl)->qtp;
+  qtp.min_cluster_pixels = params.minClusterPixels;
+  qtp.max_nmaxima = params.maxNumMaxima;
+  qtp.critical_rad = params.criticalAngle.value();
+  qtp.cos_critical_rad = std::cos(params.criticalAngle.value());
+  qtp.max_line_fit_mse = params.maxLineFitMSE;
+  qtp.min_white_black_diff = params.minWhiteBlackDiff;
+  qtp.deglitch = params.deglitch;
+
+  m_qtpCriticalAngle = params.criticalAngle;
+}
+
+AprilTagDetector::QuadThresholdParameters
+AprilTagDetector::GetQuadThresholdParameters() const {
+  auto& qtp = static_cast<apriltag_detector_t*>(m_impl)->qtp;
+  return {
+      .minClusterPixels = qtp.min_cluster_pixels,
+      .maxNumMaxima = qtp.max_nmaxima,
+      .criticalAngle = m_qtpCriticalAngle,
+      .maxLineFitMSE = qtp.max_line_fit_mse,
+      .minWhiteBlackDiff = qtp.min_white_black_diff,
+      .deglitch = qtp.deglitch != 0,
+  };
+}
+
+bool AprilTagDetector::AddFamily(std::string_view fam, int bitsCorrected) {
+  auto& data = m_families[fam];
+  if (data) {
+    return true;  // already detecting
+  }
+  // create the family
+  if (fam == "tag16h5") {
+    data = tag16h5_create();
+  } else if (fam == "tag25h9") {
+    data = tag25h9_create();
+  } else if (fam == "tag36h11") {
+    data = tag36h11_create();
+  } else if (fam == "tagCircle21h7") {
+    data = tagCircle21h7_create();
+  } else if (fam == "tagCircle49h12") {
+    data = tagCircle49h12_create();
+  } else if (fam == "tagStandard41h12") {
+    data = tagStandard41h12_create();
+  } else if (fam == "tagStandard52h13") {
+    data = tagStandard52h13_create();
+  } else if (fam == "tagCustom48h12") {
+    data = tagCustom48h12_create();
+  }
+  if (!data) {
+    m_families.erase(fam);  // don't keep null value
+    return false;           // can't add
+  }
+  apriltag_detector_add_family_bits(static_cast<apriltag_detector_t*>(m_impl),
+                                    static_cast<apriltag_family_t*>(data),
+                                    bitsCorrected);
+  return true;
+}
+
+void AprilTagDetector::RemoveFamily(std::string_view fam) {
+  auto it = m_families.find(fam);
+  if (it != m_families.end()) {
+    apriltag_detector_remove_family(
+        static_cast<apriltag_detector_t*>(m_impl),
+        static_cast<apriltag_family_t*>(it->second));
+    DestroyFamily(it->getKey(), it->second);
+    m_families.erase(it);
+  }
+}
+
+void AprilTagDetector::ClearFamilies() {
+  apriltag_detector_clear_families(static_cast<apriltag_detector_t*>(m_impl));
+  DestroyFamilies();
+  m_families.clear();
+}
+
+AprilTagDetector::Results AprilTagDetector::Detect(int width, int height,
+                                                   int stride, uint8_t* buf) {
+  image_u8_t img{width, height, stride, buf};
+  return {
+      apriltag_detector_detect(static_cast<apriltag_detector_t*>(m_impl), &img),
+      Results::private_init{}};
+}
+
+void AprilTagDetector::Destroy() {
+  if (m_impl) {
+    apriltag_detector_destroy(static_cast<apriltag_detector_t*>(m_impl));
+  }
+  DestroyFamilies();
+}
+
+void AprilTagDetector::DestroyFamilies() {
+  for (auto&& entry : m_families) {
+    DestroyFamily(entry.getKey(), entry.second);
+  }
+}
+
+void AprilTagDetector::DestroyFamily(std::string_view name, void* data) {
+  auto fam = static_cast<apriltag_family_t*>(data);
+  if (name == "tag16h5") {
+    tag16h5_destroy(fam);
+  } else if (name == "tag25h9") {
+    tag25h9_destroy(fam);
+  } else if (name == "tag36h11") {
+    tag36h11_destroy(fam);
+  } else if (name == "tagCircle21h7") {
+    tagCircle21h7_destroy(fam);
+  } else if (name == "tagCircle49h12") {
+    tagCircle49h12_destroy(fam);
+  } else if (name == "tagStandard41h12") {
+    tagStandard41h12_destroy(fam);
+  } else if (name == "tagStandard52h13") {
+    tagStandard52h13_destroy(fam);
+  } else if (name == "tagCustom48h12") {
+    tagCustom48h12_destroy(fam);
+  }
+}
diff --git a/third_party/allwpilib/apriltag/src/main/native/cpp/AprilTagFieldLayout.cpp b/third_party/allwpilib/apriltag/src/main/native/cpp/AprilTagFieldLayout.cpp
new file mode 100644
index 0000000..31e4cac
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/main/native/cpp/AprilTagFieldLayout.cpp
@@ -0,0 +1,107 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/apriltag/AprilTagFieldLayout.h"
+
+#include <system_error>
+
+#include <units/angle.h>
+#include <units/length.h>
+#include <wpi/json.h>
+#include <wpi/raw_istream.h>
+#include <wpi/raw_ostream.h>
+
+using namespace frc;
+
+AprilTagFieldLayout::AprilTagFieldLayout(std::string_view path) {
+  std::error_code error_code;
+
+  wpi::raw_fd_istream input{path, error_code};
+  if (error_code) {
+    throw std::runtime_error(fmt::format("Cannot open file: {}", path));
+  }
+
+  wpi::json json;
+  input >> json;
+
+  for (const auto& tag : json.at("tags").get<std::vector<AprilTag>>()) {
+    m_apriltags[tag.ID] = tag;
+  }
+  m_fieldWidth = units::meter_t{json.at("field").at("width").get<double>()};
+  m_fieldLength = units::meter_t{json.at("field").at("length").get<double>()};
+}
+
+AprilTagFieldLayout::AprilTagFieldLayout(std::vector<AprilTag> apriltags,
+                                         units::meter_t fieldLength,
+                                         units::meter_t fieldWidth)
+    : m_fieldLength(std::move(fieldLength)),
+      m_fieldWidth(std::move(fieldWidth)) {
+  for (const auto& tag : apriltags) {
+    m_apriltags[tag.ID] = tag;
+  }
+}
+
+void AprilTagFieldLayout::SetOrigin(OriginPosition origin) {
+  switch (origin) {
+    case OriginPosition::kBlueAllianceWallRightSide:
+      SetOrigin(Pose3d{});
+      break;
+    case OriginPosition::kRedAllianceWallRightSide:
+      SetOrigin(Pose3d{Translation3d{m_fieldLength, m_fieldWidth, 0_m},
+                       Rotation3d{0_deg, 0_deg, 180_deg}});
+      break;
+    default:
+      throw std::invalid_argument("Invalid origin");
+  }
+}
+
+void AprilTagFieldLayout::SetOrigin(const Pose3d& origin) {
+  m_origin = origin;
+}
+
+std::optional<frc::Pose3d> AprilTagFieldLayout::GetTagPose(int ID) const {
+  const auto& it = m_apriltags.find(ID);
+  if (it == m_apriltags.end()) {
+    return std::nullopt;
+  }
+  return it->second.pose.RelativeTo(m_origin);
+}
+
+void AprilTagFieldLayout::Serialize(std::string_view path) {
+  std::error_code error_code;
+
+  wpi::raw_fd_ostream output{path, error_code};
+  if (error_code) {
+    throw std::runtime_error(fmt::format("Cannot open file: {}", path));
+  }
+
+  wpi::json json = *this;
+  output << json;
+  output.flush();
+}
+
+void frc::to_json(wpi::json& json, const AprilTagFieldLayout& layout) {
+  std::vector<AprilTag> tagVector;
+  tagVector.reserve(layout.m_apriltags.size());
+  for (const auto& pair : layout.m_apriltags) {
+    tagVector.push_back(pair.second);
+  }
+
+  json = wpi::json{{"field",
+                    {{"length", layout.m_fieldLength.value()},
+                     {"width", layout.m_fieldWidth.value()}}},
+                   {"tags", tagVector}};
+}
+
+void frc::from_json(const wpi::json& json, AprilTagFieldLayout& layout) {
+  layout.m_apriltags.clear();
+  for (const auto& tag : json.at("tags").get<std::vector<AprilTag>>()) {
+    layout.m_apriltags[tag.ID] = tag;
+  }
+
+  layout.m_fieldLength =
+      units::meter_t{json.at("field").at("length").get<double>()};
+  layout.m_fieldWidth =
+      units::meter_t{json.at("field").at("width").get<double>()};
+}
diff --git a/third_party/allwpilib/apriltag/src/main/native/cpp/AprilTagFields.cpp b/third_party/allwpilib/apriltag/src/main/native/cpp/AprilTagFields.cpp
new file mode 100644
index 0000000..3d7b1ed
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/main/native/cpp/AprilTagFields.cpp
@@ -0,0 +1,28 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/apriltag/AprilTagFields.h"
+
+#include <wpi/json.h>
+
+namespace frc {
+
+// C++ generated from resource files
+std::string_view GetResource_2022_rapidreact_json();
+
+AprilTagFieldLayout LoadAprilTagLayoutField(AprilTagField field) {
+  std::string_view fieldString;
+  switch (field) {
+    case AprilTagField::k2022RapidReact:
+      fieldString = GetResource_2022_rapidreact_json();
+      break;
+    case AprilTagField::kNumFields:
+      throw std::invalid_argument("Invalid Field");
+  }
+
+  wpi::json json = wpi::json::parse(fieldString);
+  return json.get<AprilTagFieldLayout>();
+}
+
+}  // namespace frc
diff --git a/third_party/allwpilib/apriltag/src/main/native/cpp/AprilTagPoseEstimate.cpp b/third_party/allwpilib/apriltag/src/main/native/cpp/AprilTagPoseEstimate.cpp
new file mode 100644
index 0000000..f755fd5
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/main/native/cpp/AprilTagPoseEstimate.cpp
@@ -0,0 +1,20 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/apriltag/AprilTagPoseEstimate.h"
+
+#include <algorithm>
+
+using namespace frc;
+
+double AprilTagPoseEstimate::GetAmbiguity() const {
+  auto min = (std::min)(error1, error2);
+  auto max = (std::max)(error1, error2);
+
+  if (max > 0) {
+    return min / max;
+  } else {
+    return -1;
+  }
+}
diff --git a/third_party/allwpilib/apriltag/src/main/native/cpp/AprilTagPoseEstimator.cpp b/third_party/allwpilib/apriltag/src/main/native/cpp/AprilTagPoseEstimator.cpp
new file mode 100644
index 0000000..dc4acde
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/main/native/cpp/AprilTagPoseEstimator.cpp
@@ -0,0 +1,154 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/apriltag/AprilTagPoseEstimator.h"
+
+#include <Eigen/QR>
+
+#include "frc/apriltag/AprilTagDetection.h"
+
+#ifdef _WIN32
+#pragma warning(disable : 4200)
+#elif defined(__clang__)
+#pragma clang diagnostic ignored "-Wc99-extensions"
+#elif defined(__GNUC__)
+#pragma GCC diagnostic ignored "-Wpedantic"
+#endif
+
+#include "apriltag.h"
+#include "apriltag_pose.h"
+
+using namespace frc;
+
+static Eigen::Matrix3d OrthogonalizeRotationMatrix(
+    const Eigen::Matrix3d& input) {
+  Eigen::HouseholderQR<Eigen::Matrix3d> qr{input};
+
+  Eigen::Matrix3d Q = qr.householderQ();
+  Eigen::Matrix3d R = qr.matrixQR().triangularView<Eigen::Upper>();
+
+  // Fix signs in R if they're < 0 so it's close to an identity matrix
+  // (our QR decomposition implementation sometimes flips the signs of
+  // columns)
+  for (int colR = 0; colR < 3; ++colR) {
+    if (R(colR, colR) < 0) {
+      for (int rowQ = 0; rowQ < 3; ++rowQ) {
+        Q(rowQ, colR) = -Q(rowQ, colR);
+      }
+    }
+  }
+
+  return Q;
+}
+
+static Transform3d MakePose(const apriltag_pose_t& pose) {
+  if (!pose.R || !pose.t) {
+    return {};
+  }
+  return {Translation3d{units::meter_t{pose.t->data[0]},
+                        units::meter_t{pose.t->data[1]},
+                        units::meter_t{pose.t->data[2]}},
+          Rotation3d{OrthogonalizeRotationMatrix(
+              Eigen::Map<Eigen::Matrix<double, 3, 3, Eigen::RowMajor>>{
+                  pose.R->data})}};
+}
+
+static apriltag_detection_info_t MakeDetectionInfo(
+    const apriltag_detection_t* det,
+    const AprilTagPoseEstimator::Config& config) {
+  return {const_cast<apriltag_detection_t*>(det),
+          config.tagSize.value(),
+          config.fx,
+          config.fy,
+          config.cx,
+          config.cy};
+}
+
+static apriltag_detection_t MakeBasicDet(
+    std::span<const double, 9> homography,
+    const std::span<const double, 8>* corners) {
+  apriltag_detection_t detection;
+  detection.H = matd_create(3, 3);
+  std::memcpy(detection.H->data, homography.data(), 9 * sizeof(double));
+  if (corners) {
+    for (int i = 0; i < 4; i++) {
+      detection.p[i][0] = (*corners)[i * 2];
+      detection.p[i][1] = (*corners)[i * 2 + 1];
+    }
+  }
+  return detection;
+}
+
+static Transform3d DoEstimateHomography(
+    const apriltag_detection_t* detection,
+    const AprilTagPoseEstimator::Config& config) {
+  auto info = MakeDetectionInfo(detection, config);
+  apriltag_pose_t pose;
+  estimate_pose_for_tag_homography(&info, &pose);
+  return MakePose(pose);
+}
+
+Transform3d AprilTagPoseEstimator::EstimateHomography(
+    const AprilTagDetection& detection) const {
+  return DoEstimateHomography(
+      reinterpret_cast<const apriltag_detection_t*>(&detection), m_config);
+}
+
+Transform3d AprilTagPoseEstimator::EstimateHomography(
+    std::span<const double, 9> homography) const {
+  auto detection = MakeBasicDet(homography, nullptr);
+  auto rv = DoEstimateHomography(&detection, m_config);
+  matd_destroy(detection.H);
+  return rv;
+}
+
+static AprilTagPoseEstimate DoEstimateOrthogonalIteration(
+    const apriltag_detection_t* detection,
+    const AprilTagPoseEstimator::Config& config, int nIters) {
+  auto info = MakeDetectionInfo(detection, config);
+  apriltag_pose_t pose1, pose2;
+  double err1, err2;
+  estimate_tag_pose_orthogonal_iteration(&info, &err1, &pose1, &err2, &pose2,
+                                         nIters);
+  return {MakePose(pose1), MakePose(pose2), err1, err2};
+}
+
+AprilTagPoseEstimate AprilTagPoseEstimator::EstimateOrthogonalIteration(
+    const AprilTagDetection& detection, int nIters) const {
+  return DoEstimateOrthogonalIteration(
+      reinterpret_cast<const apriltag_detection_t*>(&detection), m_config,
+      nIters);
+}
+
+AprilTagPoseEstimate AprilTagPoseEstimator::EstimateOrthogonalIteration(
+    std::span<const double, 9> homography, std::span<const double, 8> corners,
+    int nIters) const {
+  auto detection = MakeBasicDet(homography, &corners);
+  auto rv = DoEstimateOrthogonalIteration(&detection, m_config, nIters);
+  matd_destroy(detection.H);
+  return rv;
+}
+
+static Transform3d DoEstimate(const apriltag_detection_t* detection,
+                              const AprilTagPoseEstimator::Config& config) {
+  auto info = MakeDetectionInfo(detection, config);
+  apriltag_pose_t pose;
+  estimate_tag_pose(&info, &pose);
+  return MakePose(pose);
+}
+
+Transform3d AprilTagPoseEstimator::Estimate(
+    const AprilTagDetection& detection) const {
+  return DoEstimate(reinterpret_cast<const apriltag_detection_t*>(&detection),
+                    m_config);
+}
+
+Transform3d AprilTagPoseEstimator::Estimate(
+    std::span<const double, 9> homography,
+    std::span<const double, 8> corners) const {
+  auto detection = MakeBasicDet(homography, &corners);
+  auto rv = DoEstimate(&detection, m_config);
+  matd_destroy(detection.H);
+  return rv;
+}
diff --git a/third_party/allwpilib/apriltag/src/main/native/cpp/jni/AprilTagJNI.cpp b/third_party/allwpilib/apriltag/src/main/native/cpp/jni/AprilTagJNI.cpp
new file mode 100644
index 0000000..31fd4f9
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/main/native/cpp/jni/AprilTagJNI.cpp
@@ -0,0 +1,595 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <cstdio>
+#include <cstring>
+
+#include <wpi/jni_util.h>
+
+#include "edu_wpi_first_apriltag_jni_AprilTagJNI.h"
+#include "frc/apriltag/AprilTagDetector.h"
+#include "frc/apriltag/AprilTagPoseEstimator.h"
+
+using namespace frc;
+using namespace wpi::java;
+
+static JavaVM* jvm = nullptr;
+
+static JClass detectionCls;
+static JClass detectorConfigCls;
+static JClass detectorQTPCls;
+static JClass poseEstimateCls;
+static JClass quaternionCls;
+static JClass rotation3dCls;
+static JClass transform3dCls;
+static JClass translation3dCls;
+static JException illegalArgEx;
+static JException nullPointerEx;
+
+static const JClassInit classes[] = {
+    {"edu/wpi/first/apriltag/AprilTagDetection", &detectionCls},
+    {"edu/wpi/first/apriltag/AprilTagDetector$Config", &detectorConfigCls},
+    {"edu/wpi/first/apriltag/AprilTagDetector$QuadThresholdParameters",
+     &detectorQTPCls},
+    {"edu/wpi/first/apriltag/AprilTagPoseEstimate", &poseEstimateCls},
+    {"edu/wpi/first/math/geometry/Quaternion", &quaternionCls},
+    {"edu/wpi/first/math/geometry/Rotation3d", &rotation3dCls},
+    {"edu/wpi/first/math/geometry/Transform3d", &transform3dCls},
+    {"edu/wpi/first/math/geometry/Translation3d", &translation3dCls}};
+
+static const JExceptionInit exceptions[] = {
+    {"java/lang/IllegalArgumentException", &illegalArgEx},
+    {"java/lang/NullPointerException", &nullPointerEx}};
+
+extern "C" {
+
+JNIEXPORT jint JNICALL JNI_OnLoad(JavaVM* vm, void* reserved) {
+  jvm = vm;
+
+  JNIEnv* env;
+  if (vm->GetEnv(reinterpret_cast<void**>(&env), JNI_VERSION_1_6) != JNI_OK) {
+    return JNI_ERR;
+  }
+
+  // Cache references to classes
+  for (auto& c : classes) {
+    *c.cls = JClass(env, c.name);
+    if (!*c.cls) {
+      std::fprintf(stderr, "could not load class %s\n", c.name);
+      return JNI_ERR;
+    }
+  }
+
+  for (auto& c : exceptions) {
+    *c.cls = JException(env, c.name);
+    if (!*c.cls) {
+      std::fprintf(stderr, "could not load exception %s\n", c.name);
+      return JNI_ERR;
+    }
+  }
+
+  return JNI_VERSION_1_6;
+}
+
+JNIEXPORT void JNICALL JNI_OnUnload(JavaVM* vm, void* reserved) {
+  JNIEnv* env;
+  if (vm->GetEnv(reinterpret_cast<void**>(&env), JNI_VERSION_1_6) != JNI_OK) {
+    return;
+  }
+  // Delete global references
+  for (auto& c : classes) {
+    c.cls->free(env);
+  }
+  for (auto& c : exceptions) {
+    c.cls->free(env);
+  }
+  jvm = nullptr;
+}
+
+}  // extern "C"
+
+//
+// Conversions from Java to C++ objects
+//
+
+static AprilTagDetector::Config FromJavaDetectorConfig(JNIEnv* env,
+                                                       jobject jconfig) {
+  if (!jconfig) {
+    return {};
+  }
+#define FIELD(name, sig)                                          \
+  static jfieldID name##Field = nullptr;                          \
+  if (!name##Field) {                                             \
+    name##Field = env->GetFieldID(detectorConfigCls, #name, sig); \
+  }
+
+  FIELD(numThreads, "I");
+  FIELD(quadDecimate, "F");
+  FIELD(quadSigma, "F");
+  FIELD(refineEdges, "Z");
+  FIELD(decodeSharpening, "D");
+  FIELD(debug, "Z");
+
+#undef FIELD
+
+#define FIELD(ctype, jtype, name) \
+  .name = static_cast<ctype>(env->Get##jtype##Field(jconfig, name##Field))
+
+  return {
+      FIELD(int, Int, numThreads),
+      FIELD(float, Float, quadDecimate),
+      FIELD(float, Float, quadSigma),
+      FIELD(bool, Boolean, refineEdges),
+      FIELD(double, Double, decodeSharpening),
+      FIELD(bool, Boolean, debug),
+  };
+
+#undef GET
+#undef FIELD
+}
+
+static AprilTagDetector::QuadThresholdParameters FromJavaDetectorQTP(
+    JNIEnv* env, jobject jparams) {
+  if (!jparams) {
+    return {};
+  }
+#define FIELD(name, sig)                                       \
+  static jfieldID name##Field = nullptr;                       \
+  if (!name##Field) {                                          \
+    name##Field = env->GetFieldID(detectorQTPCls, #name, sig); \
+  }
+
+  FIELD(minClusterPixels, "I");
+  FIELD(maxNumMaxima, "I");
+  FIELD(criticalAngle, "D");
+  FIELD(maxLineFitMSE, "F");
+  FIELD(minWhiteBlackDiff, "I");
+  FIELD(deglitch, "Z");
+
+#undef FIELD
+
+#define FIELD(ctype, jtype, name) \
+  .name = static_cast<ctype>(env->Get##jtype##Field(jparams, name##Field))
+
+  return {
+      FIELD(int, Int, minClusterPixels),
+      FIELD(int, Int, maxNumMaxima),
+      .criticalAngle = units::radian_t{static_cast<double>(
+          env->GetDoubleField(jparams, criticalAngleField))},
+      FIELD(float, Float, maxLineFitMSE),
+      FIELD(int, Int, minWhiteBlackDiff),
+      FIELD(bool, Boolean, deglitch),
+  };
+
+#undef GET
+#undef FIELD
+}
+
+//
+// Conversions from C++ to Java objects
+//
+
+static jobject MakeJObject(JNIEnv* env, const AprilTagDetection& detect) {
+  static jmethodID constructor = env->GetMethodID(
+      detectionCls, "<init>", "(Ljava/lang/String;IIF[DDD[D)V");
+  if (!constructor) {
+    return nullptr;
+  }
+
+  JLocal<jstring> fam{env, MakeJString(env, detect.GetFamily())};
+
+  auto homography = detect.GetHomography();
+  JLocal<jdoubleArray> harr{
+      env, MakeJDoubleArray(
+               env, {reinterpret_cast<const jdouble*>(homography.data()),
+                     homography.size()})};
+
+  double cornersBuf[8];
+  auto corners = detect.GetCorners(cornersBuf);
+  JLocal<jdoubleArray> carr{
+      env,
+      MakeJDoubleArray(env, {reinterpret_cast<const jdouble*>(corners.data()),
+                             corners.size()})};
+
+  auto center = detect.GetCenter();
+
+  return env->NewObject(detectionCls, constructor, fam.obj(),
+                        static_cast<jint>(detect.GetId()),
+                        static_cast<jint>(detect.GetHamming()),
+                        static_cast<jfloat>(detect.GetDecisionMargin()),
+                        harr.obj(), static_cast<jdouble>(center.x),
+                        static_cast<jdouble>(center.y), carr.obj());
+}
+
+static jobjectArray MakeJObject(JNIEnv* env,
+                                std::span<const AprilTagDetection* const> arr) {
+  jobjectArray jarr = env->NewObjectArray(arr.size(), detectionCls, nullptr);
+  if (!jarr) {
+    return nullptr;
+  }
+  for (size_t i = 0; i < arr.size(); ++i) {
+    JLocal<jobject> elem{env, MakeJObject(env, *arr[i])};
+    env->SetObjectArrayElement(jarr, i, elem.obj());
+  }
+  return jarr;
+}
+
+static jobject MakeJObject(JNIEnv* env,
+                           const AprilTagDetector::Config& config) {
+  static jmethodID constructor =
+      env->GetMethodID(detectorConfigCls, "<init>", "(IFFZDZ)V");
+  if (!constructor) {
+    return nullptr;
+  }
+
+  return env->NewObject(detectorConfigCls, constructor,
+                        static_cast<jint>(config.numThreads),
+                        static_cast<jfloat>(config.quadDecimate),
+                        static_cast<jfloat>(config.quadSigma),
+                        static_cast<jboolean>(config.refineEdges),
+                        static_cast<jdouble>(config.decodeSharpening),
+                        static_cast<jboolean>(config.debug));
+}
+
+static jobject MakeJObject(
+    JNIEnv* env, const AprilTagDetector::QuadThresholdParameters& params) {
+  static jmethodID constructor =
+      env->GetMethodID(detectorQTPCls, "<init>", "(IIDFIZ)V");
+  if (!constructor) {
+    return nullptr;
+  }
+
+  return env->NewObject(detectorQTPCls, constructor,
+                        static_cast<jint>(params.minClusterPixels),
+                        static_cast<jint>(params.maxNumMaxima),
+                        static_cast<jdouble>(params.criticalAngle),
+                        static_cast<jfloat>(params.maxLineFitMSE),
+                        static_cast<jint>(params.minWhiteBlackDiff),
+                        static_cast<jboolean>(params.deglitch));
+}
+
+static jobject MakeJObject(JNIEnv* env, const Translation3d& xlate) {
+  static jmethodID constructor =
+      env->GetMethodID(translation3dCls, "<init>", "(DDD)V");
+  if (!constructor) {
+    return nullptr;
+  }
+
+  return env->NewObject(
+      translation3dCls, constructor, static_cast<jdouble>(xlate.X()),
+      static_cast<jdouble>(xlate.Y()), static_cast<jdouble>(xlate.Z()));
+}
+
+static jobject MakeJObject(JNIEnv* env, const Quaternion& q) {
+  static jmethodID constructor =
+      env->GetMethodID(quaternionCls, "<init>", "(DDDD)V");
+  if (!constructor) {
+    return nullptr;
+  }
+
+  return env->NewObject(quaternionCls, constructor, static_cast<jdouble>(q.W()),
+                        static_cast<jdouble>(q.X()),
+                        static_cast<jdouble>(q.Y()),
+                        static_cast<jdouble>(q.Z()));
+}
+
+static jobject MakeJObject(JNIEnv* env, const Rotation3d& rot) {
+  static jmethodID constructor = env->GetMethodID(
+      rotation3dCls, "<init>", "(Ledu/wpi/first/math/geometry/Quaternion;)V");
+  if (!constructor) {
+    return nullptr;
+  }
+
+  JLocal<jobject> q{env, MakeJObject(env, rot.GetQuaternion())};
+  return env->NewObject(rotation3dCls, constructor, q.obj());
+}
+
+static jobject MakeJObject(JNIEnv* env, const Transform3d& xform) {
+  static jmethodID constructor =
+      env->GetMethodID(transform3dCls, "<init>",
+                       "(Ledu/wpi/first/math/geometry/Translation3d;"
+                       "Ledu/wpi/first/math/geometry/Rotation3d;)V");
+  if (!constructor) {
+    return nullptr;
+  }
+
+  JLocal<jobject> xlate{env, MakeJObject(env, xform.Translation())};
+  JLocal<jobject> rot{env, MakeJObject(env, xform.Rotation())};
+  return env->NewObject(transform3dCls, constructor, xlate.obj(), rot.obj());
+}
+
+static jobject MakeJObject(JNIEnv* env, const AprilTagPoseEstimate& est) {
+  static jmethodID constructor =
+      env->GetMethodID(poseEstimateCls, "<init>",
+                       "(Ledu/wpi/first/math/geometry/Transform3d;"
+                       "Ledu/wpi/first/math/geometry/Transform3d;DD)V");
+  if (!constructor) {
+    return nullptr;
+  }
+
+  JLocal<jobject> pose1{env, MakeJObject(env, est.pose1)};
+  JLocal<jobject> pose2{env, MakeJObject(env, est.pose2)};
+  return env->NewObject(poseEstimateCls, constructor, pose1.obj(), pose2.obj(),
+                        static_cast<jdouble>(est.error1),
+                        static_cast<jdouble>(est.error2));
+}
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_apriltag_jni_AprilTagJNI
+ * Method:    createDetector
+ * Signature: ()J
+ */
+JNIEXPORT jlong JNICALL
+Java_edu_wpi_first_apriltag_jni_AprilTagJNI_createDetector
+  (JNIEnv* env, jclass)
+{
+  return reinterpret_cast<jlong>(new AprilTagDetector);
+}
+
+/*
+ * Class:     edu_wpi_first_apriltag_jni_AprilTagJNI
+ * Method:    destroyDetector
+ * Signature: (J)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_apriltag_jni_AprilTagJNI_destroyDetector
+  (JNIEnv* env, jclass, jlong det)
+{
+  delete reinterpret_cast<AprilTagDetector*>(det);
+}
+
+/*
+ * Class:     edu_wpi_first_apriltag_jni_AprilTagJNI
+ * Method:    setDetectorConfig
+ * Signature: (JLjava/lang/Object;)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_apriltag_jni_AprilTagJNI_setDetectorConfig
+  (JNIEnv* env, jclass, jlong det, jobject config)
+{
+  if (det == 0) {
+    nullPointerEx.Throw(env, "det cannot be null");
+    return;
+  }
+  reinterpret_cast<AprilTagDetector*>(det)->SetConfig(
+      FromJavaDetectorConfig(env, config));
+}
+
+/*
+ * Class:     edu_wpi_first_apriltag_jni_AprilTagJNI
+ * Method:    getDetectorConfig
+ * Signature: (J)Ljava/lang/Object;
+ */
+JNIEXPORT jobject JNICALL
+Java_edu_wpi_first_apriltag_jni_AprilTagJNI_getDetectorConfig
+  (JNIEnv* env, jclass, jlong det)
+{
+  if (det == 0) {
+    nullPointerEx.Throw(env, "det cannot be null");
+    return nullptr;
+  }
+  return MakeJObject(env,
+                     reinterpret_cast<AprilTagDetector*>(det)->GetConfig());
+}
+
+/*
+ * Class:     edu_wpi_first_apriltag_jni_AprilTagJNI
+ * Method:    setDetectorQTP
+ * Signature: (JLjava/lang/Object;)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_apriltag_jni_AprilTagJNI_setDetectorQTP
+  (JNIEnv* env, jclass, jlong det, jobject params)
+{
+  if (det == 0) {
+    nullPointerEx.Throw(env, "det cannot be null");
+    return;
+  }
+  reinterpret_cast<AprilTagDetector*>(det)->SetQuadThresholdParameters(
+      FromJavaDetectorQTP(env, params));
+}
+
+/*
+ * Class:     edu_wpi_first_apriltag_jni_AprilTagJNI
+ * Method:    getDetectorQTP
+ * Signature: (J)Ljava/lang/Object;
+ */
+JNIEXPORT jobject JNICALL
+Java_edu_wpi_first_apriltag_jni_AprilTagJNI_getDetectorQTP
+  (JNIEnv* env, jclass, jlong det)
+{
+  if (det == 0) {
+    nullPointerEx.Throw(env, "det cannot be null");
+    return nullptr;
+  }
+  return MakeJObject(
+      env,
+      reinterpret_cast<AprilTagDetector*>(det)->GetQuadThresholdParameters());
+}
+
+/*
+ * Class:     edu_wpi_first_apriltag_jni_AprilTagJNI
+ * Method:    addFamily
+ * Signature: (JLjava/lang/String;I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_apriltag_jni_AprilTagJNI_addFamily
+  (JNIEnv* env, jclass, jlong det, jstring fam, jint bitsCorrected)
+{
+  if (det == 0) {
+    nullPointerEx.Throw(env, "det cannot be null");
+    return false;
+  }
+  if (!fam) {
+    nullPointerEx.Throw(env, "fam cannot be null");
+    return false;
+  }
+  return reinterpret_cast<AprilTagDetector*>(det)->AddFamily(
+      JStringRef{env, fam}, bitsCorrected);
+}
+
+/*
+ * Class:     edu_wpi_first_apriltag_jni_AprilTagJNI
+ * Method:    removeFamily
+ * Signature: (JLjava/lang/String;)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_apriltag_jni_AprilTagJNI_removeFamily
+  (JNIEnv* env, jclass, jlong det, jstring fam)
+{
+  if (det == 0) {
+    nullPointerEx.Throw(env, "det cannot be null");
+    return;
+  }
+  if (!fam) {
+    nullPointerEx.Throw(env, "fam cannot be null");
+    return;
+  }
+  reinterpret_cast<AprilTagDetector*>(det)->RemoveFamily(JStringRef{env, fam});
+}
+
+/*
+ * Class:     edu_wpi_first_apriltag_jni_AprilTagJNI
+ * Method:    clearFamilies
+ * Signature: (J)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_apriltag_jni_AprilTagJNI_clearFamilies
+  (JNIEnv* env, jclass, jlong det)
+{
+  if (det == 0) {
+    nullPointerEx.Throw(env, "det cannot be null");
+    return;
+  }
+  reinterpret_cast<AprilTagDetector*>(det)->ClearFamilies();
+}
+
+/*
+ * Class:     edu_wpi_first_apriltag_jni_AprilTagJNI
+ * Method:    detect
+ * Signature: (JIIIJ)[Ljava/lang/Object;
+ */
+JNIEXPORT jobjectArray JNICALL
+Java_edu_wpi_first_apriltag_jni_AprilTagJNI_detect
+  (JNIEnv* env, jclass, jlong det, jint width, jint height, jint stride,
+   jlong bufAddr)
+{
+  if (det == 0) {
+    nullPointerEx.Throw(env, "det cannot be null");
+    return nullptr;
+  }
+  if (bufAddr == 0) {
+    nullPointerEx.Throw(env, "bufAddr cannot be null");
+    return nullptr;
+  }
+  return MakeJObject(
+      env, reinterpret_cast<AprilTagDetector*>(det)->Detect(
+               width, height, stride, reinterpret_cast<uint8_t*>(bufAddr)));
+}
+
+/*
+ * Class:     edu_wpi_first_apriltag_jni_AprilTagJNI
+ * Method:    estimatePoseHomography
+ * Signature: ([DDDDDD)Ljava/lang/Object;
+ */
+JNIEXPORT jobject JNICALL
+Java_edu_wpi_first_apriltag_jni_AprilTagJNI_estimatePoseHomography
+  (JNIEnv* env, jclass, jdoubleArray homography, jdouble tagSize, jdouble fx,
+   jdouble fy, jdouble cx, jdouble cy)
+{
+  if (!homography) {
+    nullPointerEx.Throw(env, "homography cannot be null");
+    return nullptr;
+  }
+  JDoubleArrayRef harr{env, homography};
+  if (harr.size() != 9) {
+    illegalArgEx.Throw(env, "homography array must be size 9");
+    return nullptr;
+  }
+
+  AprilTagPoseEstimator estimator({units::meter_t{tagSize}, fx, fy, cx, cy});
+  return MakeJObject(env, estimator.EstimateHomography(
+                              std::span<const double, 9>{harr.array()}));
+}
+
+/*
+ * Class:     edu_wpi_first_apriltag_jni_AprilTagJNI
+ * Method:    estimatePoseOrthogonalIteration
+ * Signature: ([D[DDDDDDI)Ljava/lang/Object;
+ */
+JNIEXPORT jobject JNICALL
+Java_edu_wpi_first_apriltag_jni_AprilTagJNI_estimatePoseOrthogonalIteration
+  (JNIEnv* env, jclass, jdoubleArray homography, jdoubleArray corners,
+   jdouble tagSize, jdouble fx, jdouble fy, jdouble cx, jdouble cy, jint nIters)
+{
+  // homography
+  if (!homography) {
+    nullPointerEx.Throw(env, "homography cannot be null");
+    return nullptr;
+  }
+  JDoubleArrayRef harr{env, homography};
+  if (harr.size() != 9) {
+    illegalArgEx.Throw(env, "homography array must be size 9");
+    return nullptr;
+  }
+
+  // corners
+  if (!corners) {
+    nullPointerEx.Throw(env, "corners cannot be null");
+    return nullptr;
+  }
+  JDoubleArrayRef carr{env, corners};
+  if (carr.size() != 8) {
+    illegalArgEx.Throw(env, "corners array must be size 8");
+    return nullptr;
+  }
+
+  AprilTagPoseEstimator estimator({units::meter_t{tagSize}, fx, fy, cx, cy});
+  return MakeJObject(env,
+                     estimator.EstimateOrthogonalIteration(
+                         std::span<const double, 9>{harr.array()},
+                         std::span<const double, 8>{carr.array()}, nIters));
+}
+
+/*
+ * Class:     edu_wpi_first_apriltag_jni_AprilTagJNI
+ * Method:    estimatePose
+ * Signature: ([D[DDDDDD)Ljava/lang/Object;
+ */
+JNIEXPORT jobject JNICALL
+Java_edu_wpi_first_apriltag_jni_AprilTagJNI_estimatePose
+  (JNIEnv* env, jclass, jdoubleArray homography, jdoubleArray corners,
+   jdouble tagSize, jdouble fx, jdouble fy, jdouble cx, jdouble cy)
+{
+  // homography
+  if (!homography) {
+    nullPointerEx.Throw(env, "homography cannot be null");
+    return nullptr;
+  }
+  JDoubleArrayRef harr{env, homography};
+  if (harr.size() != 9) {
+    illegalArgEx.Throw(env, "homography array must be size 9");
+    return nullptr;
+  }
+
+  // corners
+  if (!corners) {
+    nullPointerEx.Throw(env, "corners cannot be null");
+    return nullptr;
+  }
+  JDoubleArrayRef carr{env, corners};
+  if (carr.size() != 8) {
+    illegalArgEx.Throw(env, "corners array must be size 8");
+    return nullptr;
+  }
+
+  AprilTagPoseEstimator estimator({units::meter_t{tagSize}, fx, fy, cx, cy});
+  return MakeJObject(
+      env, estimator.Estimate(std::span<const double, 9>{harr.array()},
+                              std::span<const double, 8>{carr.array()}));
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib/apriltag/src/main/native/include/frc/apriltag/AprilTag.h b/third_party/allwpilib/apriltag/src/main/native/include/frc/apriltag/AprilTag.h
new file mode 100644
index 0000000..fc57231
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/main/native/include/frc/apriltag/AprilTag.h
@@ -0,0 +1,34 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <wpi/SymbolExports.h>
+
+#include "frc/geometry/Pose3d.h"
+
+namespace wpi {
+class json;
+}  // namespace wpi
+
+namespace frc {
+
+struct WPILIB_DLLEXPORT AprilTag {
+  int ID;
+
+  Pose3d pose;
+
+  /**
+   * Checks equality between this AprilTag and another object.
+   */
+  bool operator==(const AprilTag&) const = default;
+};
+
+WPILIB_DLLEXPORT
+void to_json(wpi::json& json, const AprilTag& apriltag);
+
+WPILIB_DLLEXPORT
+void from_json(const wpi::json& json, AprilTag& apriltag);
+
+}  // namespace frc
diff --git a/third_party/allwpilib/apriltag/src/main/native/include/frc/apriltag/AprilTagDetection.h b/third_party/allwpilib/apriltag/src/main/native/include/frc/apriltag/AprilTagDetection.h
new file mode 100644
index 0000000..5225f21
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/main/native/include/frc/apriltag/AprilTagDetection.h
@@ -0,0 +1,160 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <stdint.h>
+
+#include <span>
+#include <string_view>
+
+#include <wpi/SymbolExports.h>
+
+#include "frc/EigenCore.h"
+
+namespace frc {
+
+/**
+ * A detection of an AprilTag tag.
+ */
+class WPILIB_DLLEXPORT AprilTagDetection final {
+ public:
+  AprilTagDetection() = delete;
+  AprilTagDetection(const AprilTagDetection&) = delete;
+  AprilTagDetection& operator=(const AprilTagDetection&) = delete;
+
+  /** A point. Used for center and corner points. */
+  struct Point {
+    double x;
+    double y;
+  };
+
+  /**
+   * Gets the decoded tag's family name.
+   *
+   * @return Decoded family name
+   */
+  std::string_view GetFamily() const;
+
+  /**
+   * Gets the decoded ID of the tag.
+   *
+   * @return Decoded ID
+   */
+  int GetId() const { return id; }
+
+  /**
+   * Gets how many error bits were corrected. Note: accepting large numbers of
+   * corrected errors leads to greatly increased false positive rates.
+   * NOTE: As of this implementation, the detector cannot detect tags with
+   * a hamming distance greater than 2.
+   *
+   * @return Hamming distance (number of corrected error bits)
+   */
+  int GetHamming() const { return hamming; }
+
+  /**
+   * Gets a measure of the quality of the binary decoding process: the
+   * average difference between the intensity of a data bit versus
+   * the decision threshold. Higher numbers roughly indicate better
+   * decodes. This is a reasonable measure of detection accuracy
+   * only for very small tags-- not effective for larger tags (where
+   * we could have sampled anywhere within a bit cell and still
+   * gotten a good detection.)
+   *
+   * @return Decision margin
+   */
+  float GetDecisionMargin() const { return decision_margin; }
+
+  /**
+   * Gets the 3x3 homography matrix describing the projection from an
+   * "ideal" tag (with corners at (-1,1), (1,1), (1,-1), and (-1,
+   * -1)) to pixels in the image.
+   *
+   * @return Homography matrix data
+   */
+  std::span<const double, 9> GetHomography() const;
+
+  /**
+   * Gets the 3x3 homography matrix describing the projection from an
+   * "ideal" tag (with corners at (-1,1), (1,1), (1,-1), and (-1,
+   * -1)) to pixels in the image.
+   *
+   * @return Homography matrix
+   */
+  Eigen::Matrix3d GetHomographyMatrix() const;
+
+  /**
+   * Gets the center of the detection in image pixel coordinates.
+   *
+   * @return Center point
+   */
+  const Point& GetCenter() const { return *reinterpret_cast<const Point*>(c); }
+
+  /**
+   * Gets a corner of the tag in image pixel coordinates. These always
+   * wrap counter-clock wise around the tag.
+   *
+   * @param ndx Corner index (range is 0-3, inclusive)
+   * @return Corner point
+   */
+  const Point& GetCorner(int ndx) const {
+    return *reinterpret_cast<const Point*>(p[ndx]);
+  }
+
+  /**
+   * Gets the corners of the tag in image pixel coordinates. These always
+   * wrap counter-clock wise around the tag.
+   *
+   * @param cornersBuf Corner point array (X and Y for each corner in order)
+   * @return Corner point array (copy of cornersBuf span)
+   */
+  std::span<double, 8> GetCorners(std::span<double, 8> cornersBuf) const {
+    for (int i = 0; i < 4; i++) {
+      cornersBuf[i * 2] = p[i][0];
+      cornersBuf[i * 2 + 1] = p[i][1];
+    }
+    return cornersBuf;
+  }
+
+ private:
+  // This class *must* be standard-layout-compatible with apriltag_detection
+  // as we use reinterpret_cast from that structure. This means the below
+  // members must exactly match the contents of the apriltag_detection struct.
+
+  // The tag family.
+  void* family;
+
+  // The decoded ID of the tag.
+  int id;
+
+  // How many error bits were corrected? Note: accepting large numbers of
+  // corrected errors leads to greatly increased false positive rates.
+  // NOTE: As of this implementation, the detector cannot detect tags with
+  // a hamming distance greater than 2.
+  int hamming;
+
+  // A measure of the quality of the binary decoding process: the
+  // average difference between the intensity of a data bit versus
+  // the decision threshold. Higher numbers roughly indicate better
+  // decodes. This is a reasonable measure of detection accuracy
+  // only for very small tags-- not effective for larger tags (where
+  // we could have sampled anywhere within a bit cell and still
+  // gotten a good detection.)
+  float decision_margin;
+
+  // The 3x3 homography matrix describing the projection from an
+  // "ideal" tag (with corners at (-1,1), (1,1), (1,-1), and (-1,
+  // -1)) to pixels in the image.
+  void* H;
+
+  // The center of the detection in image pixel coordinates.
+  double c[2];
+
+  // The corners of the tag in image pixel coordinates. These always
+  // wrap counter-clock wise around the tag.
+  double p[4][2];
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib/apriltag/src/main/native/include/frc/apriltag/AprilTagDetector.h b/third_party/allwpilib/apriltag/src/main/native/include/frc/apriltag/AprilTagDetector.h
new file mode 100644
index 0000000..8a78d1b
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/main/native/include/frc/apriltag/AprilTagDetector.h
@@ -0,0 +1,260 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <stdint.h>
+
+#include <memory>
+#include <span>
+#include <string_view>
+#include <utility>
+
+#include <units/angle.h>
+#include <wpi/StringMap.h>
+#include <wpi/SymbolExports.h>
+
+#include "frc/apriltag/AprilTagDetection.h"
+
+namespace frc {
+
+/**
+ * An AprilTag detector engine. This is expensive to set up and tear down, so
+ * most use cases should only create one of these, add a family to it, set up
+ * any other configuration, and repeatedly call Detect().
+ */
+class WPILIB_DLLEXPORT AprilTagDetector {
+ public:
+  /** Detector configuration. */
+  struct Config {
+    bool operator==(const Config&) const = default;
+
+    /**
+     * How many threads should be used for computation. Default is
+     * single-threaded operation (1 thread).
+     */
+    int numThreads = 1;
+
+    /**
+     * Quad decimation. Detection of quads can be done on a lower-resolution
+     * image, improving speed at a cost of pose accuracy and a slight decrease
+     * in detection rate. Decoding the binary payload is still done at full
+     * resolution. Default is 2.0.
+     */
+    float quadDecimate = 2.0f;
+
+    /**
+     * What Gaussian blur should be applied to the segmented image (used for
+     * quad detection). Very noisy images benefit from non-zero values (e.g.
+     * 0.8). Default is 0.0.
+     */
+    float quadSigma = 0.0f;
+
+    /**
+     * When true, the edges of the each quad are adjusted to "snap to" strong
+     * gradients nearby. This is useful when decimation is employed, as it can
+     * increase the quality of the initial quad estimate substantially.
+     * Generally recommended to be on (true). Default is true.
+     *
+     * Very computationally inexpensive. Option is ignored if
+     * quad_decimate = 1.
+     */
+    bool refineEdges = true;
+
+    /**
+     * How much sharpening should be done to decoded images. This can help
+     * decode small tags but may or may not help in odd lighting conditions or
+     * low light conditions. Default is 0.25.
+     */
+    double decodeSharpening = 0.25;
+
+    /**
+     * Debug mode. When true, the decoder writes a variety of debugging images
+     * to the current working directory at various stages through the detection
+     * process. This is slow and should *not* be used on space-limited systems
+     * such as the RoboRIO. Default is disabled (false).
+     */
+    bool debug = false;
+  };
+
+  /** Quad threshold parameters. */
+  struct QuadThresholdParameters {
+    bool operator==(const QuadThresholdParameters&) const = default;
+
+    /**
+     * Threshold used to reject quads containing too few pixels. Default is 5
+     * pixels.
+     */
+    int minClusterPixels = 5;
+
+    /**
+     * How many corner candidates to consider when segmenting a group of pixels
+     * into a quad. Default is 10.
+     */
+    int maxNumMaxima = 10;
+
+    /**
+     * Critical angle. The detector will reject quads where pairs of edges have
+     * angles that are close to straight or close to 180 degrees. Zero means
+     * that no quads are rejected. Default is 10 degrees.
+     */
+    units::radian_t criticalAngle = 10_deg;
+
+    /**
+     * When fitting lines to the contours, the maximum mean squared error
+     * allowed. This is useful in rejecting contours that are far from being
+     * quad shaped; rejecting these quads "early" saves expensive decoding
+     * processing. Default is 10.0.
+     */
+    float maxLineFitMSE = 10.0f;
+
+    /**
+     * Minimum brightness offset. When we build our model of black & white
+     * pixels, we add an extra check that the white model must be (overall)
+     * brighter than the black model. How much brighter? (in pixel values,
+     * [0,255]). Default is 5.
+     */
+    int minWhiteBlackDiff = 5;
+
+    /**
+     * Whether the thresholded image be should be deglitched. Only useful for
+     * very noisy images. Default is disabled (false).
+     */
+    bool deglitch = false;
+  };
+
+  /**
+   * Array of detection results. Each array element is a pointer to an
+   * AprilTagDetection.
+   */
+  class WPILIB_DLLEXPORT Results
+      : public std::span<AprilTagDetection const* const> {
+    struct private_init {};
+    friend class AprilTagDetector;
+
+   public:
+    Results() = default;
+    Results(void* impl, const private_init&);
+    ~Results() { Destroy(); }
+    Results(const Results&) = delete;
+    Results& operator=(const Results&) = delete;
+    Results(Results&& rhs) : span{std::move(rhs)}, m_impl{rhs.m_impl} {
+      rhs.m_impl = nullptr;
+    }
+    Results& operator=(Results&& rhs);
+
+   private:
+    void Destroy();
+    void* m_impl = nullptr;
+  };
+
+  AprilTagDetector();
+  ~AprilTagDetector() { Destroy(); }
+  AprilTagDetector(const AprilTagDetector&) = delete;
+  AprilTagDetector& operator=(const AprilTagDetector&) = delete;
+  AprilTagDetector(AprilTagDetector&& rhs)
+      : m_impl{rhs.m_impl},
+        m_families{std::move(rhs.m_families)},
+        m_qtpCriticalAngle{rhs.m_qtpCriticalAngle} {
+    rhs.m_impl = nullptr;
+  }
+  AprilTagDetector& operator=(AprilTagDetector&& rhs);
+
+  /**
+   * @{
+   * @name Configuration functions
+   */
+
+  /**
+   * Sets detector configuration.
+   *
+   * @param config Configuration
+   */
+  void SetConfig(const Config& config);
+
+  /**
+   * Gets detector configuration.
+   *
+   * @return Configuration
+   */
+  Config GetConfig() const;
+
+  /**
+   * Sets quad threshold parameters.
+   *
+   * @param params Parameters
+   */
+  void SetQuadThresholdParameters(const QuadThresholdParameters& params);
+
+  /**
+   * Gets quad threshold parameters.
+   *
+   * @return Parameters
+   */
+  QuadThresholdParameters GetQuadThresholdParameters() const;
+
+  /** @} */
+
+  /**
+   * @{
+   * @name Tag family functions
+   */
+
+  /**
+   * Adds a family of tags to be detected.
+   *
+   * @param fam Family name, e.g. "tag16h5"
+   * @param bitsCorrected
+   * @return False if family can't be found
+   */
+  bool AddFamily(std::string_view fam, int bitsCorrected = 2);
+
+  /**
+   * Removes a family of tags from the detector.
+   *
+   * @param fam Family name, e.g. "tag16h5"
+   */
+  void RemoveFamily(std::string_view fam);
+
+  /**
+   * Unregister all families.
+   */
+  void ClearFamilies();
+
+  /** @} */
+
+  /**
+   * Detect tags from an 8-bit image.
+   *
+   * @param width width of the image
+   * @param height height of the image
+   * @param stride number of bytes between image rows (often the same as width)
+   * @param buf image buffer
+   * @return Results (array of AprilTagDetection pointers)
+   */
+  Results Detect(int width, int height, int stride, uint8_t* buf);
+
+  /**
+   * Detect tags from an 8-bit image.
+   *
+   * @param width width of the image
+   * @param height height of the image
+   * @param buf image buffer
+   * @return Results (array of AprilTagDetection pointers)
+   */
+  Results Detect(int width, int height, uint8_t* buf) {
+    return Detect(width, height, width, buf);
+  }
+
+ private:
+  void Destroy();
+  void DestroyFamilies();
+  void DestroyFamily(std::string_view name, void* data);
+
+  void* m_impl;
+  wpi::StringMap<void*> m_families;
+  units::radian_t m_qtpCriticalAngle = 10_deg;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib/apriltag/src/main/native/include/frc/apriltag/AprilTagDetector_cv.h b/third_party/allwpilib/apriltag/src/main/native/include/frc/apriltag/AprilTagDetector_cv.h
new file mode 100644
index 0000000..7231430
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/main/native/include/frc/apriltag/AprilTagDetector_cv.h
@@ -0,0 +1,18 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <opencv2/core/mat.hpp>
+
+#include "frc/apriltag/AprilTagDetector.h"
+
+namespace frc {
+
+inline AprilTagDetector::Results AprilTagDetect(AprilTagDetector& detector,
+                                                cv::Mat& image) {
+  return detector.Detect(image.cols, image.rows, image.data);
+}
+
+}  // namespace frc
diff --git a/third_party/allwpilib/apriltag/src/main/native/include/frc/apriltag/AprilTagFieldLayout.h b/third_party/allwpilib/apriltag/src/main/native/include/frc/apriltag/AprilTagFieldLayout.h
new file mode 100644
index 0000000..c69e429
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/main/native/include/frc/apriltag/AprilTagFieldLayout.h
@@ -0,0 +1,125 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <optional>
+#include <string_view>
+#include <unordered_map>
+#include <vector>
+
+#include <units/length.h>
+#include <wpi/SymbolExports.h>
+
+#include "frc/apriltag/AprilTag.h"
+#include "frc/geometry/Pose3d.h"
+
+namespace wpi {
+class json;
+}  // namespace wpi
+
+namespace frc {
+/**
+ * Class for representing a layout of AprilTags on a field and reading them from
+ * a JSON format.
+ *
+ * The JSON format contains two top-level objects, "tags" and "field".
+ * The "tags" object is a list of all AprilTags contained within a layout. Each
+ * AprilTag serializes to a JSON object containing an ID and a Pose3d. The
+ * "field" object is a descriptor of the size of the field in meters with
+ * "width" and "length" values.  This is to account for arbitrary field sizes
+ * when transforming the poses.
+ *
+ * Pose3ds in the JSON are measured using the normal FRC coordinate system, NWU
+ * with the origin at the bottom-right corner of the blue alliance wall.
+ * SetOrigin(OriginPosition) can be used to change the poses returned from
+ * GetTagPose(int) to be from the perspective of a specific alliance. */
+class WPILIB_DLLEXPORT AprilTagFieldLayout {
+ public:
+  enum class OriginPosition {
+    kBlueAllianceWallRightSide,
+    kRedAllianceWallRightSide,
+  };
+
+  AprilTagFieldLayout() = default;
+
+  /**
+   * Construct a new AprilTagFieldLayout with values imported from a JSON file.
+   *
+   * @param path Path of the JSON file to import from.
+   */
+  explicit AprilTagFieldLayout(std::string_view path);
+
+  /**
+   * Construct a new AprilTagFieldLayout from a vector of AprilTag objects.
+   *
+   * @param apriltags Vector of AprilTags.
+   * @param fieldLength Length of field the layout is representing.
+   * @param fieldWidth Width of field the layout is representing.
+   */
+  AprilTagFieldLayout(std::vector<AprilTag> apriltags,
+                      units::meter_t fieldLength, units::meter_t fieldWidth);
+
+  /**
+   * Sets the origin based on a predefined enumeration of coordinate frame
+   * origins. The origins are calculated from the field dimensions.
+   *
+   * This transforms the Pose3ds returned by GetTagPose(int) to return the
+   * correct pose relative to a predefined coordinate frame.
+   *
+   * @param origin The predefined origin
+   */
+  void SetOrigin(OriginPosition origin);
+
+  /**
+   * Sets the origin for tag pose transformation.
+   *
+   * This tranforms the Pose3ds returned by GetTagPose(int) to return the
+   * correct pose relative to the provided origin.
+   *
+   * @param origin The new origin for tag transformations
+   */
+  void SetOrigin(const Pose3d& origin);
+
+  /**
+   * Gets an AprilTag pose by its ID.
+   *
+   * @param ID The ID of the tag.
+   * @return The pose corresponding to the ID that was passed in or an empty
+   * optional if a tag with that ID is not found.
+   */
+  std::optional<Pose3d> GetTagPose(int ID) const;
+
+  /**
+   * Serializes an AprilTagFieldLayout to a JSON file.
+   *
+   * @param path The path to write the JSON file to.
+   */
+  void Serialize(std::string_view path);
+
+  /*
+   * Checks equality between this AprilTagFieldLayout and another object.
+   */
+  bool operator==(const AprilTagFieldLayout&) const = default;
+
+ private:
+  std::unordered_map<int, AprilTag> m_apriltags;
+  units::meter_t m_fieldLength;
+  units::meter_t m_fieldWidth;
+  Pose3d m_origin;
+
+  friend WPILIB_DLLEXPORT void to_json(wpi::json& json,
+                                       const AprilTagFieldLayout& layout);
+
+  friend WPILIB_DLLEXPORT void from_json(const wpi::json& json,
+                                         AprilTagFieldLayout& layout);
+};
+
+WPILIB_DLLEXPORT
+void to_json(wpi::json& json, const AprilTagFieldLayout& layout);
+
+WPILIB_DLLEXPORT
+void from_json(const wpi::json& json, AprilTagFieldLayout& layout);
+
+}  // namespace frc
diff --git a/third_party/allwpilib/apriltag/src/main/native/include/frc/apriltag/AprilTagFields.h b/third_party/allwpilib/apriltag/src/main/native/include/frc/apriltag/AprilTagFields.h
new file mode 100644
index 0000000..2810a1a
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/main/native/include/frc/apriltag/AprilTagFields.h
@@ -0,0 +1,31 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <string_view>
+
+#include <wpi/SymbolExports.h>
+
+#include "frc/apriltag/AprilTagFieldLayout.h"
+
+namespace frc {
+
+enum class AprilTagField {
+  k2022RapidReact,
+
+  // This is a placeholder for denoting the last supported field. This should
+  // always be the last entry in the enum and should not be used by users
+  kNumFields,
+};
+
+/**
+ * Loads an AprilTagFieldLayout from a predefined field
+ *
+ * @param field The predefined field
+ */
+WPILIB_DLLEXPORT AprilTagFieldLayout
+LoadAprilTagLayoutField(AprilTagField field);
+
+}  // namespace frc
diff --git a/third_party/allwpilib/apriltag/src/main/native/include/frc/apriltag/AprilTagPoseEstimate.h b/third_party/allwpilib/apriltag/src/main/native/include/frc/apriltag/AprilTagPoseEstimate.h
new file mode 100644
index 0000000..28c7d51
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/main/native/include/frc/apriltag/AprilTagPoseEstimate.h
@@ -0,0 +1,36 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <wpi/SymbolExports.h>
+
+#include "frc/geometry/Transform3d.h"
+
+namespace frc {
+
+/** A pair of AprilTag pose estimates. */
+struct WPILIB_DLLEXPORT AprilTagPoseEstimate {
+  /** Pose 1. */
+  Transform3d pose1;
+
+  /** Pose 2. */
+  Transform3d pose2;
+
+  /** Object-space error of pose 1. */
+  double error1;
+
+  /** Object-space error of pose 2. */
+  double error2;
+
+  /**
+   * Gets the ratio of pose reprojection errors, called ambiguity. Numbers
+   * above 0.2 are likely to be ambiguous.
+   *
+   * @return The ratio of pose reprojection errors.
+   */
+  double GetAmbiguity() const;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib/apriltag/src/main/native/include/frc/apriltag/AprilTagPoseEstimator.h b/third_party/allwpilib/apriltag/src/main/native/include/frc/apriltag/AprilTagPoseEstimator.h
new file mode 100644
index 0000000..1e1e852
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/main/native/include/frc/apriltag/AprilTagPoseEstimator.h
@@ -0,0 +1,145 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <span>
+
+#include <units/length.h>
+#include <wpi/SymbolExports.h>
+
+#include "frc/apriltag/AprilTagPoseEstimate.h"
+#include "frc/geometry/Transform3d.h"
+
+namespace frc {
+
+class AprilTagDetection;
+
+/** Pose estimators for AprilTag tags. */
+class WPILIB_DLLEXPORT AprilTagPoseEstimator {
+ public:
+  /** Configuration for the pose estimator. */
+  struct Config {
+    bool operator==(const Config&) const = default;
+
+    /** The tag size. */
+    units::meter_t tagSize;
+
+    /** Camera horizontal focal length, in pixels. */
+    double fx;
+
+    /** Camera vertical focal length, in pixels. */
+    double fy;
+
+    /** Camera horizontal focal center, in pixels. */
+    double cx;
+
+    /** Camera vertical focal center, in pixels. */
+    double cy;
+  };
+
+  /**
+   * Creates estimator.
+   *
+   * @param config Configuration
+   */
+  explicit AprilTagPoseEstimator(const Config& config) : m_config{config} {}
+
+  /**
+   * Sets estimator configuration.
+   *
+   * @param config Configuration
+   */
+  void SetConfig(const Config& config) { m_config = config; }
+
+  /**
+   * Gets estimator configuration.
+   *
+   * @return Configuration
+   */
+  const Config& GetConfig() const { return m_config; }
+
+  /**
+   * Estimates the pose of the tag using the homography method described in [1].
+   *
+   * @param detection Tag detection
+   * @return Pose estimate
+   */
+  Transform3d EstimateHomography(const AprilTagDetection& detection) const;
+
+  /**
+   * Estimates the pose of the tag using the homography method described in [1].
+   *
+   * @param homography Homography 3x3 matrix data
+   * @return Pose estimate
+   */
+  Transform3d EstimateHomography(std::span<const double, 9> homography) const;
+
+  /**
+   * Estimates the pose of the tag. This returns one or two possible poses for
+   * the tag, along with the object-space error of each.
+   *
+   * This uses the homography method described in [1] for the initial estimate.
+   * Then Orthogonal Iteration [2] is used to refine this estimate. Then [3] is
+   * used to find a potential second local minima and Orthogonal Iteration is
+   * used to refine this second estimate.
+   *
+   * [1]: E. Olson, “Apriltag: A robust and flexible visual fiducial system,” in
+   *      2011 IEEE International Conference on Robotics and Automation,
+   *      May 2011, pp. 3400–3407.
+   * [2]: Lu, G. D. Hager and E. Mjolsness, "Fast and globally convergent pose
+   *      estimation from video images," in IEEE Transactions on Pattern
+   * Analysis and Machine Intelligence, vol. 22, no. 6, pp. 610-622, June 2000.
+   *      doi: 10.1109/34.862199
+   * [3]: Schweighofer and A. Pinz, "Robust Pose Estimation from a Planar
+   * Target," in IEEE Transactions on Pattern Analysis and Machine Intelligence,
+   *      vol. 28, no. 12, pp. 2024-2030, Dec. 2006. doi: 10.1109/TPAMI.2006.252
+   *
+   * @param detection Tag detection
+   * @param nIters Number of iterations
+   * @return Initial and (possibly) second pose estimates
+   */
+  AprilTagPoseEstimate EstimateOrthogonalIteration(
+      const AprilTagDetection& detection, int nIters) const;
+
+  /**
+   * Estimates the pose of the tag. This returns one or two possible poses for
+   * the tag, along with the object-space error of each.
+   *
+   * @param homography Homography 3x3 matrix data
+   * @param corners Corner point array (X and Y for each corner in order)
+   * @param nIters Number of iterations
+   * @return Initial and (possibly) second pose estimates
+   */
+  AprilTagPoseEstimate EstimateOrthogonalIteration(
+      std::span<const double, 9> homography, std::span<const double, 8> corners,
+      int nIters) const;
+
+  /**
+   * Estimates tag pose. This method is an easier to use interface to
+   * EstimatePoseOrthogonalIteration(), running 50 iterations and returning the
+   * pose with the lower object-space error.
+   *
+   * @param detection Tag detection
+   * @return Pose estimate
+   */
+  Transform3d Estimate(const AprilTagDetection& detection) const;
+
+  /**
+   * Estimates tag pose. This method is an easier to use interface to
+   * EstimatePoseOrthogonalIteration(), running 50 iterations and returning the
+   * pose with the lower object-space error.
+   *
+   * @param homography Homography 3x3 matrix data
+   * @param corners Corner point array (X and Y for each corner in order)
+   * @return Pose estimate
+   */
+  Transform3d Estimate(std::span<const double, 9> homography,
+                       std::span<const double, 8> corners) const;
+
+ private:
+  Config m_config;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib/apriltag/src/main/native/resources/edu/wpi/first/apriltag/2022-rapidreact.json b/third_party/allwpilib/apriltag/src/main/native/resources/edu/wpi/first/apriltag/2022-rapidreact.json
new file mode 100644
index 0000000..78cb523
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/main/native/resources/edu/wpi/first/apriltag/2022-rapidreact.json
@@ -0,0 +1,415 @@
+{
+  "tags" : [ {
+    "ID" : 0,
+    "pose" : {
+      "translation" : {
+        "x" : -0.0035306,
+        "y" : 7.578928199999999,
+        "z" : 0.8858503999999999
+      },
+      "rotation" : {
+        "quaternion" : {
+          "W" : 1.0,
+          "X" : 0.0,
+          "Y" : 0.0,
+          "Z" : 0.0
+        }
+      }
+    }
+  }, {
+    "ID" : 1,
+    "pose" : {
+      "translation" : {
+        "x" : 3.2327088,
+        "y" : 5.486654,
+        "z" : 1.7254728
+      },
+      "rotation" : {
+        "quaternion" : {
+          "W" : 1.0,
+          "X" : 0.0,
+          "Y" : 0.0,
+          "Z" : 0.0
+        }
+      }
+    }
+  }, {
+    "ID" : 2,
+    "pose" : {
+      "translation" : {
+        "x" : 3.067812,
+        "y" : 5.3305202,
+        "z" : 1.3762228
+      },
+      "rotation" : {
+        "quaternion" : {
+          "W" : 0.7071067811865476,
+          "X" : 0.0,
+          "Y" : 0.0,
+          "Z" : -0.7071067811865475
+        }
+      }
+    }
+  }, {
+    "ID" : 3,
+    "pose" : {
+      "translation" : {
+        "x" : 0.0039878,
+        "y" : 5.058536999999999,
+        "z" : 0.80645
+      },
+      "rotation" : {
+        "quaternion" : {
+          "W" : 1.0,
+          "X" : 0.0,
+          "Y" : 0.0,
+          "Z" : 0.0
+        }
+      }
+    }
+  }, {
+    "ID" : 4,
+    "pose" : {
+      "translation" : {
+        "x" : 0.0039878,
+        "y" : 3.5124898,
+        "z" : 0.80645
+      },
+      "rotation" : {
+        "quaternion" : {
+          "W" : 1.0,
+          "X" : 0.0,
+          "Y" : 0.0,
+          "Z" : 0.0
+        }
+      }
+    }
+  }, {
+    "ID" : 5,
+    "pose" : {
+      "translation" : {
+        "x" : 0.12110719999999998,
+        "y" : 1.7178274,
+        "z" : 0.8906002000000001
+      },
+      "rotation" : {
+        "quaternion" : {
+          "W" : 0.9196502204050923,
+          "X" : 0.0,
+          "Y" : 0.0,
+          "Z" : 0.39273842708457407
+        }
+      }
+    }
+  }, {
+    "ID" : 6,
+    "pose" : {
+      "translation" : {
+        "x" : 0.8733027999999999,
+        "y" : 0.9412985999999999,
+        "z" : 0.8906002000000001
+      },
+      "rotation" : {
+        "quaternion" : {
+          "W" : 0.9196502204050923,
+          "X" : 0.0,
+          "Y" : 0.0,
+          "Z" : 0.39273842708457407
+        }
+      }
+    }
+  }, {
+    "ID" : 7,
+    "pose" : {
+      "translation" : {
+        "x" : 1.6150844,
+        "y" : 0.15725139999999999,
+        "z" : 0.8906002000000001
+      },
+      "rotation" : {
+        "quaternion" : {
+          "W" : 0.9196502204050923,
+          "X" : 0.0,
+          "Y" : 0.0,
+          "Z" : 0.39273842708457407
+        }
+      }
+    }
+  }, {
+    "ID" : 10,
+    "pose" : {
+      "translation" : {
+        "x" : 16.4627306,
+        "y" : 0.6506718,
+        "z" : 0.8858503999999999
+      },
+      "rotation" : {
+        "quaternion" : {
+          "W" : 6.123233995736766E-17,
+          "X" : 0.0,
+          "Y" : 0.0,
+          "Z" : 1.0
+        }
+      }
+    }
+  }, {
+    "ID" : 11,
+    "pose" : {
+      "translation" : {
+        "x" : 13.2350002,
+        "y" : 2.743454,
+        "z" : 1.7254728
+      },
+      "rotation" : {
+        "quaternion" : {
+          "W" : 6.123233995736766E-17,
+          "X" : 0.0,
+          "Y" : 0.0,
+          "Z" : 1.0
+        }
+      }
+    }
+  }, {
+    "ID" : 12,
+    "pose" : {
+      "translation" : {
+        "x" : 13.391388000000001,
+        "y" : 2.8998418,
+        "z" : 1.3762228
+      },
+      "rotation" : {
+        "quaternion" : {
+          "W" : 0.7071067811865476,
+          "X" : 0.0,
+          "Y" : 0.0,
+          "Z" : 0.7071067811865475
+        }
+      }
+    }
+  }, {
+    "ID" : 13,
+    "pose" : {
+      "translation" : {
+        "x" : 16.4552122,
+        "y" : 3.1755079999999998,
+        "z" : 0.80645
+      },
+      "rotation" : {
+        "quaternion" : {
+          "W" : 6.123233995736766E-17,
+          "X" : 0.0,
+          "Y" : 0.0,
+          "Z" : 1.0
+        }
+      }
+    }
+  }, {
+    "ID" : 14,
+    "pose" : {
+      "translation" : {
+        "x" : 16.4552122,
+        "y" : 4.7171356,
+        "z" : 0.80645
+      },
+      "rotation" : {
+        "quaternion" : {
+          "W" : 6.123233995736766E-17,
+          "X" : 0.0,
+          "Y" : 0.0,
+          "Z" : 1.0
+        }
+      }
+    }
+  }, {
+    "ID" : 15,
+    "pose" : {
+      "translation" : {
+        "x" : 16.3350194,
+        "y" : 6.5149729999999995,
+        "z" : 0.8937752
+      },
+      "rotation" : {
+        "quaternion" : {
+          "W" : -0.37298778257580906,
+          "X" : -0.0,
+          "Y" : 0.0,
+          "Z" : 0.9278362538989199
+        }
+      }
+    }
+  }, {
+    "ID" : 16,
+    "pose" : {
+      "translation" : {
+        "x" : 15.5904946,
+        "y" : 7.292695599999999,
+        "z" : 0.8906002000000001
+      },
+      "rotation" : {
+        "quaternion" : {
+          "W" : -0.37298778257580906,
+          "X" : -0.0,
+          "Y" : 0.0,
+          "Z" : 0.9278362538989199
+        }
+      }
+    }
+  }, {
+    "ID" : 17,
+    "pose" : {
+      "translation" : {
+        "x" : 14.847188999999998,
+        "y" : 8.0691228,
+        "z" : 0.8906002000000001
+      },
+      "rotation" : {
+        "quaternion" : {
+          "W" : -0.37298778257580906,
+          "X" : -0.0,
+          "Y" : 0.0,
+          "Z" : 0.9278362538989199
+        }
+      }
+    }
+  }, {
+    "ID" : 40,
+    "pose" : {
+      "translation" : {
+        "x" : 7.874127,
+        "y" : 4.9131728,
+        "z" : 0.7032752
+      },
+      "rotation" : {
+        "quaternion" : {
+          "W" : 0.5446390350150271,
+          "X" : 0.0,
+          "Y" : 0.0,
+          "Z" : 0.838670567945424
+        }
+      }
+    }
+  }, {
+    "ID" : 41,
+    "pose" : {
+      "translation" : {
+        "x" : 7.4312271999999995,
+        "y" : 3.759327,
+        "z" : 0.7032752
+      },
+      "rotation" : {
+        "quaternion" : {
+          "W" : -0.20791169081775934,
+          "X" : -0.0,
+          "Y" : 0.0,
+          "Z" : 0.9781476007338057
+        }
+      }
+    }
+  }, {
+    "ID" : 42,
+    "pose" : {
+      "translation" : {
+        "x" : 8.585073,
+        "y" : 3.3164272,
+        "z" : 0.7032752
+      },
+      "rotation" : {
+        "quaternion" : {
+          "W" : 0.838670567945424,
+          "X" : 0.0,
+          "Y" : 0.0,
+          "Z" : -0.5446390350150271
+        }
+      }
+    }
+  }, {
+    "ID" : 43,
+    "pose" : {
+      "translation" : {
+        "x" : 9.0279728,
+        "y" : 4.470273,
+        "z" : 0.7032752
+      },
+      "rotation" : {
+        "quaternion" : {
+          "W" : 0.9781476007338057,
+          "X" : 0.0,
+          "Y" : 0.0,
+          "Z" : 0.20791169081775934
+        }
+      }
+    }
+  }, {
+    "ID" : 50,
+    "pose" : {
+      "translation" : {
+        "x" : 7.6790296,
+        "y" : 4.3261534,
+        "z" : 2.4177244
+      },
+      "rotation" : {
+        "quaternion" : {
+          "W" : 0.17729273396782605,
+          "X" : -0.22744989571511945,
+          "Y" : 0.04215534644161733,
+          "Z" : 0.9565859910053995
+        }
+      }
+    }
+  }, {
+    "ID" : 51,
+    "pose" : {
+      "translation" : {
+        "x" : 8.0182466,
+        "y" : 3.5642296,
+        "z" : 2.4177244
+      },
+      "rotation" : {
+        "quaternion" : {
+          "W" : -0.5510435465842192,
+          "X" : -0.19063969497246985,
+          "Y" : -0.13102303230819815,
+          "Z" : 0.8017733354717242
+        }
+      }
+    }
+  }, {
+    "ID" : 52,
+    "pose" : {
+      "translation" : {
+        "x" : 8.7801704,
+        "y" : 3.9034466,
+        "z" : 2.4177244
+      },
+      "rotation" : {
+        "quaternion" : {
+          "W" : -0.9565859910053994,
+          "X" : -0.04215534644161739,
+          "Y" : -0.22744989571511942,
+          "Z" : 0.17729273396782633
+        }
+      }
+    }
+  }, {
+    "ID" : 53,
+    "pose" : {
+      "translation" : {
+        "x" : 8.4409534,
+        "y" : 4.6653704,
+        "z" : 2.4177244
+      },
+      "rotation" : {
+        "quaternion" : {
+          "W" : 0.8017733354717241,
+          "X" : -0.1310230323081982,
+          "Y" : 0.19063969497246983,
+          "Z" : 0.5510435465842194
+        }
+      }
+    }
+  } ],
+  "field" : {
+    "length" : 16.4592,
+    "width" : 8.2296
+  }
+}
diff --git a/third_party/allwpilib/apriltag/src/test/java/edu/wpi/first/apriltag/AprilTagDetectorTest.java b/third_party/allwpilib/apriltag/src/test/java/edu/wpi/first/apriltag/AprilTagDetectorTest.java
new file mode 100644
index 0000000..e91e0b4
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/test/java/edu/wpi/first/apriltag/AprilTagDetectorTest.java
@@ -0,0 +1,264 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.apriltag;
+
+import static org.junit.jupiter.api.Assertions.assertDoesNotThrow;
+import static org.junit.jupiter.api.Assertions.assertEquals;
+import static org.junit.jupiter.api.Assertions.fail;
+
+import edu.wpi.first.math.geometry.Transform3d;
+import edu.wpi.first.math.util.Units;
+import edu.wpi.first.util.RuntimeLoader;
+import java.io.ByteArrayOutputStream;
+import java.io.IOException;
+import java.io.InputStream;
+import org.junit.jupiter.api.AfterEach;
+import org.junit.jupiter.api.BeforeAll;
+import org.junit.jupiter.api.BeforeEach;
+import org.junit.jupiter.api.Test;
+import org.opencv.core.Core;
+import org.opencv.core.CvType;
+import org.opencv.core.Mat;
+import org.opencv.imgcodecs.Imgcodecs;
+import org.opencv.imgproc.Imgproc;
+
+@SuppressWarnings("PMD.MutableStaticState")
+class AprilTagDetectorTest {
+  @SuppressWarnings("MemberName")
+  AprilTagDetector detector;
+
+  static RuntimeLoader<Core> loader;
+
+  @BeforeAll
+  static void beforeAll() {
+    try {
+      loader =
+          new RuntimeLoader<>(
+              Core.NATIVE_LIBRARY_NAME, RuntimeLoader.getDefaultExtractionRoot(), Core.class);
+      loader.loadLibrary();
+    } catch (IOException ex) {
+      fail(ex);
+    }
+  }
+
+  @BeforeEach
+  void beforeEach() {
+    detector = new AprilTagDetector();
+  }
+
+  @AfterEach
+  void afterEach() {
+    detector.close();
+  }
+
+  @Test
+  void testConfigDefaults() {
+    var config = detector.getConfig();
+    assertEquals(new AprilTagDetector.Config(), config);
+  }
+
+  @Test
+  void testQtpDefaults() {
+    var params = detector.getQuadThresholdParameters();
+    assertEquals(new AprilTagDetector.QuadThresholdParameters(), params);
+  }
+
+  @Test
+  void testSetConfigNumThreads() {
+    var newConfig = new AprilTagDetector.Config();
+    newConfig.numThreads = 2;
+    detector.setConfig(newConfig);
+    var config = detector.getConfig();
+    assertEquals(2, config.numThreads);
+  }
+
+  @Test
+  void testQtpMinClusterPixels() {
+    var newParams = new AprilTagDetector.QuadThresholdParameters();
+    newParams.minClusterPixels = 8;
+    detector.setQuadThresholdParameters(newParams);
+    var params = detector.getQuadThresholdParameters();
+    assertEquals(8, params.minClusterPixels);
+  }
+
+  @Test
+  void testAdd16h5() {
+    assertDoesNotThrow(() -> detector.addFamily("tag16h5"));
+    // duplicate addition is also okay
+    assertDoesNotThrow(() -> detector.addFamily("tag16h5"));
+  }
+
+  @Test
+  void testAdd25h9() {
+    assertDoesNotThrow(() -> detector.addFamily("tag25h9"));
+  }
+
+  @Test
+  void testAdd36h11() {
+    assertDoesNotThrow(() -> detector.addFamily("tag36h11"));
+  }
+
+  @Test
+  void testAddMultiple() {
+    assertDoesNotThrow(() -> detector.addFamily("tag16h5"));
+    assertDoesNotThrow(() -> detector.addFamily("tag36h11"));
+  }
+
+  @Test
+  void testRemoveFamily() {
+    // okay to remove non-existent family
+    detector.removeFamily("tag16h5");
+
+    // add and remove
+    detector.addFamily("tag16h5");
+    detector.removeFamily("tag16h5");
+  }
+
+  @SuppressWarnings("PMD.AssignmentInOperand")
+  public Mat loadImage(String resource) throws IOException {
+    Mat encoded;
+    try (InputStream is = getClass().getResource(resource).openStream()) {
+      try (ByteArrayOutputStream os = new ByteArrayOutputStream(is.available())) {
+        byte[] buffer = new byte[4096];
+        int bytesRead;
+        while ((bytesRead = is.read(buffer)) != -1) {
+          os.write(buffer, 0, bytesRead);
+        }
+        encoded = new Mat(1, os.size(), CvType.CV_8U);
+        encoded.put(0, 0, os.toByteArray());
+      }
+    }
+    Mat image = Imgcodecs.imdecode(encoded, Imgcodecs.IMREAD_COLOR);
+    encoded.release();
+    Imgproc.cvtColor(image, image, Imgproc.COLOR_BGR2GRAY);
+    return image;
+  }
+
+  @Test
+  void testDecodeAndPose() {
+    detector.addFamily("tag16h5");
+    detector.addFamily("tag36h11");
+
+    Mat image;
+    try {
+      image = loadImage("tag1_640_480.jpg");
+    } catch (IOException ex) {
+      fail(ex);
+      return;
+    }
+    try {
+      AprilTagDetection[] results = detector.detect(image);
+      assertEquals(1, results.length);
+      assertEquals("tag36h11", results[0].getFamily());
+      assertEquals(1, results[0].getId());
+      assertEquals(0, results[0].getHamming());
+
+      var estimator =
+          new AprilTagPoseEstimator(new AprilTagPoseEstimator.Config(0.2, 500, 500, 320, 240));
+      AprilTagPoseEstimate est = estimator.estimateOrthogonalIteration(results[0], 50);
+      assertEquals(new Transform3d(), est.pose2);
+      Transform3d pose = estimator.estimate(results[0]);
+      assertEquals(est.pose1, pose);
+    } finally {
+      image.release();
+    }
+  }
+
+  /**
+   * This tag is rotated such that the top is closer to the camera than the bottom. In the camera
+   * frame, with +x to the right, this is a rotation about +X by 45 degrees.
+   */
+  @Test
+  void testPoseRotatedX() {
+    detector.addFamily("tag16h5");
+
+    Mat image;
+    try {
+      image = loadImage("tag2_45deg_X.png");
+    } catch (IOException ex) {
+      fail(ex);
+      return;
+    }
+    try {
+      AprilTagDetection[] results = detector.detect(image);
+      assertEquals(1, results.length);
+
+      var estimator =
+          new AprilTagPoseEstimator(
+              new AprilTagPoseEstimator.Config(
+                  0.2, 500, 500, image.cols() / 2.0, image.rows() / 2.0));
+      AprilTagPoseEstimate est = estimator.estimateOrthogonalIteration(results[0], 50);
+
+      assertEquals(Units.degreesToRadians(45), est.pose1.getRotation().getX(), 0.1);
+      assertEquals(Units.degreesToRadians(0), est.pose1.getRotation().getY(), 0.1);
+      assertEquals(Units.degreesToRadians(0), est.pose1.getRotation().getZ(), 0.1);
+    } finally {
+      image.release();
+    }
+  }
+
+  /**
+   * This tag is rotated such that the right is closer to the camera than the left. In the camera
+   * frame, with +y down, this is a rotation of 45 degrees about +y.
+   */
+  @Test
+  void testPoseRotatedY() {
+    detector.addFamily("tag16h5");
+
+    Mat image;
+    try {
+      image = loadImage("tag2_45deg_y.png");
+    } catch (IOException ex) {
+      fail(ex);
+      return;
+    }
+    try {
+      AprilTagDetection[] results = detector.detect(image);
+      assertEquals(1, results.length);
+
+      var estimator =
+          new AprilTagPoseEstimator(
+              new AprilTagPoseEstimator.Config(
+                  0.2, 500, 500, image.cols() / 2.0, image.rows() / 2.0));
+      AprilTagPoseEstimate est = estimator.estimateOrthogonalIteration(results[0], 50);
+
+      assertEquals(Units.degreesToRadians(0), est.pose1.getRotation().getX(), 0.1);
+      assertEquals(Units.degreesToRadians(45), est.pose1.getRotation().getY(), 0.1);
+      assertEquals(Units.degreesToRadians(0), est.pose1.getRotation().getZ(), 0.1);
+    } finally {
+      image.release();
+    }
+  }
+
+  /** This tag is facing right at the camera -- no rotation should be observed. */
+  @Test
+  void testPoseStraightOn() {
+    detector.addFamily("tag16h5");
+
+    Mat image;
+    try {
+      image = loadImage("tag2_16h5_straight.png");
+    } catch (IOException ex) {
+      fail(ex);
+      return;
+    }
+    try {
+      AprilTagDetection[] results = detector.detect(image);
+      assertEquals(1, results.length);
+
+      var estimator =
+          new AprilTagPoseEstimator(
+              new AprilTagPoseEstimator.Config(
+                  0.2, 500, 500, image.cols() / 2.0, image.rows() / 2.0));
+      AprilTagPoseEstimate est = estimator.estimateOrthogonalIteration(results[0], 50);
+
+      assertEquals(Units.degreesToRadians(0), est.pose1.getRotation().getX(), 0.1);
+      assertEquals(Units.degreesToRadians(0), est.pose1.getRotation().getY(), 0.1);
+      assertEquals(Units.degreesToRadians(0), est.pose1.getRotation().getZ(), 0.1);
+    } finally {
+      image.release();
+    }
+  }
+}
diff --git a/third_party/allwpilib/apriltag/src/test/java/edu/wpi/first/apriltag/AprilTagPoseSetOriginTest.java b/third_party/allwpilib/apriltag/src/test/java/edu/wpi/first/apriltag/AprilTagPoseSetOriginTest.java
new file mode 100644
index 0000000..999fe87
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/test/java/edu/wpi/first/apriltag/AprilTagPoseSetOriginTest.java
@@ -0,0 +1,46 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.apriltag;
+
+import static org.junit.jupiter.api.Assertions.assertEquals;
+
+import edu.wpi.first.math.geometry.Pose3d;
+import edu.wpi.first.math.geometry.Rotation3d;
+import edu.wpi.first.math.geometry.Translation3d;
+import edu.wpi.first.math.util.Units;
+import java.util.List;
+import org.junit.jupiter.api.Test;
+
+class AprilTagPoseSetOriginTest {
+  @Test
+  void transformationMatches() {
+    var layout =
+        new AprilTagFieldLayout(
+            List.of(
+                new AprilTag(1, new Pose3d(new Translation3d(0, 0, 0), new Rotation3d(0, 0, 0))),
+                new AprilTag(
+                    2,
+                    new Pose3d(
+                        new Translation3d(
+                            Units.feetToMeters(4.0), Units.feetToMeters(4), Units.feetToMeters(4)),
+                        new Rotation3d(0, 0, Units.degreesToRadians(180))))),
+            Units.feetToMeters(54.0),
+            Units.feetToMeters(27.0));
+    layout.setOrigin(AprilTagFieldLayout.OriginPosition.kRedAllianceWallRightSide);
+
+    assertEquals(
+        new Pose3d(
+            new Translation3d(Units.feetToMeters(54.0), Units.feetToMeters(27.0), 0.0),
+            new Rotation3d(0.0, 0.0, Units.degreesToRadians(180.0))),
+        layout.getTagPose(1).orElse(null));
+
+    assertEquals(
+        new Pose3d(
+            new Translation3d(
+                Units.feetToMeters(50.0), Units.feetToMeters(23.0), Units.feetToMeters(4)),
+            new Rotation3d(0.0, 0.0, 0)),
+        layout.getTagPose(2).orElse(null));
+  }
+}
diff --git a/third_party/allwpilib/apriltag/src/test/java/edu/wpi/first/apriltag/AprilTagSerializationTest.java b/third_party/allwpilib/apriltag/src/test/java/edu/wpi/first/apriltag/AprilTagSerializationTest.java
new file mode 100644
index 0000000..5f5d1fd
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/test/java/edu/wpi/first/apriltag/AprilTagSerializationTest.java
@@ -0,0 +1,38 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.apriltag;
+
+import static org.junit.jupiter.api.Assertions.assertDoesNotThrow;
+import static org.junit.jupiter.api.Assertions.assertEquals;
+
+import com.fasterxml.jackson.databind.ObjectMapper;
+import edu.wpi.first.math.geometry.Pose3d;
+import edu.wpi.first.math.geometry.Rotation3d;
+import edu.wpi.first.math.util.Units;
+import java.util.List;
+import org.junit.jupiter.api.Test;
+
+class AprilTagSerializationTest {
+  @Test
+  void deserializeMatches() {
+    var layout =
+        new AprilTagFieldLayout(
+            List.of(
+                new AprilTag(1, new Pose3d(0, 0, 0, new Rotation3d(0, 0, 0))),
+                new AprilTag(3, new Pose3d(0, 1, 0, new Rotation3d(0, 0, 0)))),
+            Units.feetToMeters(54.0),
+            Units.feetToMeters(27.0));
+
+    var objectMapper = new ObjectMapper();
+
+    var deserialized =
+        assertDoesNotThrow(
+            () ->
+                objectMapper.readValue(
+                    objectMapper.writeValueAsString(layout), AprilTagFieldLayout.class));
+
+    assertEquals(layout, deserialized);
+  }
+}
diff --git a/third_party/allwpilib/apriltag/src/test/java/edu/wpi/first/apriltag/LoadConfigTest.java b/third_party/allwpilib/apriltag/src/test/java/edu/wpi/first/apriltag/LoadConfigTest.java
new file mode 100644
index 0000000..ab15994
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/test/java/edu/wpi/first/apriltag/LoadConfigTest.java
@@ -0,0 +1,74 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.apriltag;
+
+import static org.junit.jupiter.api.Assertions.assertEquals;
+import static org.junit.jupiter.api.Assertions.assertFalse;
+import static org.junit.jupiter.api.Assertions.assertNotNull;
+import static org.junit.jupiter.api.Assertions.assertTrue;
+
+import edu.wpi.first.math.geometry.Pose3d;
+import edu.wpi.first.math.geometry.Rotation3d;
+import edu.wpi.first.math.util.Units;
+import java.io.IOException;
+import java.util.Optional;
+import org.junit.jupiter.api.Assertions;
+import org.junit.jupiter.api.Test;
+import org.junit.jupiter.params.ParameterizedTest;
+import org.junit.jupiter.params.provider.EnumSource;
+
+class LoadConfigTest {
+  @ParameterizedTest
+  @EnumSource(AprilTagFields.class)
+  void testLoad(AprilTagFields field) {
+    AprilTagFieldLayout layout =
+        Assertions.assertDoesNotThrow(
+            () -> AprilTagFieldLayout.loadFromResource(field.m_resourceFile));
+    assertNotNull(layout);
+  }
+
+  @Test
+  void test2022RapidReact() throws IOException {
+    AprilTagFieldLayout layout =
+        AprilTagFieldLayout.loadFromResource(AprilTagFields.k2022RapidReact.m_resourceFile);
+
+    // Blue Hangar Truss - Hub
+    Pose3d expectedPose =
+        new Pose3d(
+            Units.inchesToMeters(127.272),
+            Units.inchesToMeters(216.01),
+            Units.inchesToMeters(67.932),
+            new Rotation3d(0, 0, 0));
+    Optional<Pose3d> maybePose = layout.getTagPose(1);
+    assertTrue(maybePose.isPresent());
+    assertEquals(expectedPose, maybePose.get());
+
+    // Blue Terminal Near Station
+    expectedPose =
+        new Pose3d(
+            Units.inchesToMeters(4.768),
+            Units.inchesToMeters(67.631),
+            Units.inchesToMeters(35.063),
+            new Rotation3d(0, 0, Math.toRadians(46.25)));
+    maybePose = layout.getTagPose(5);
+    assertTrue(maybePose.isPresent());
+    assertEquals(expectedPose, maybePose.get());
+
+    // Upper Hub Blue-Near
+    expectedPose =
+        new Pose3d(
+            Units.inchesToMeters(332.321),
+            Units.inchesToMeters(183.676),
+            Units.inchesToMeters(95.186),
+            new Rotation3d(0, Math.toRadians(26.75), Math.toRadians(69)));
+    maybePose = layout.getTagPose(53);
+    assertTrue(maybePose.isPresent());
+    assertEquals(expectedPose, maybePose.get());
+
+    // Doesn't exist
+    maybePose = layout.getTagPose(54);
+    assertFalse(maybePose.isPresent());
+  }
+}
diff --git a/third_party/allwpilib/apriltag/src/test/native/cpp/AprilTagDetectorTest.cpp b/third_party/allwpilib/apriltag/src/test/native/cpp/AprilTagDetectorTest.cpp
new file mode 100644
index 0000000..8f93bb3
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/test/native/cpp/AprilTagDetectorTest.cpp
@@ -0,0 +1,67 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/apriltag/AprilTagDetector.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+TEST(AprilTagDetectorTest, ConfigDefaults) {
+  AprilTagDetector detector;
+  auto config = detector.GetConfig();
+  ASSERT_EQ(config, AprilTagDetector::Config{});
+}
+
+TEST(AprilTagDetectorTest, QtpDefaults) {
+  AprilTagDetector detector;
+  auto params = detector.GetQuadThresholdParameters();
+  ASSERT_EQ(params, AprilTagDetector::QuadThresholdParameters{});
+}
+
+TEST(AprilTagDetectorTest, SetConfigNumThreads) {
+  AprilTagDetector detector;
+  detector.SetConfig({.numThreads = 2});
+  auto config = detector.GetConfig();
+  ASSERT_EQ(config.numThreads, 2);
+}
+
+TEST(AprilTagDetectorTest, QtpMinClusterPixels) {
+  AprilTagDetector detector;
+  detector.SetQuadThresholdParameters({.minClusterPixels = 8});
+  auto params = detector.GetQuadThresholdParameters();
+  ASSERT_EQ(params.minClusterPixels, 8);
+}
+
+TEST(AprilTagDetectorTest, Add16h5) {
+  AprilTagDetector detector;
+  ASSERT_TRUE(detector.AddFamily("tag16h5"));
+  // duplicate addition is also okay
+  ASSERT_TRUE(detector.AddFamily("tag16h5"));
+}
+
+TEST(AprilTagDetectorTest, Add25h9) {
+  AprilTagDetector detector;
+  ASSERT_TRUE(detector.AddFamily("tag25h9"));
+}
+
+TEST(AprilTagDetectorTest, Add36h11) {
+  AprilTagDetector detector;
+  ASSERT_TRUE(detector.AddFamily("tag36h11"));
+}
+
+TEST(AprilTagDetectorTest, AddMultiple) {
+  AprilTagDetector detector;
+  ASSERT_TRUE(detector.AddFamily("tag16h5"));
+  ASSERT_TRUE(detector.AddFamily("tag36h11"));
+}
+
+TEST(AprilTagDetectorTest, RemoveFamily) {
+  AprilTagDetector detector;
+  // okay to remove non-existent family
+  detector.RemoveFamily("tag16h5");
+
+  // add and remove
+  detector.AddFamily("tag16h5");
+  detector.RemoveFamily("tag16h5");
+}
diff --git a/third_party/allwpilib/apriltag/src/test/native/cpp/AprilTagJsonTest.cpp b/third_party/allwpilib/apriltag/src/test/native/cpp/AprilTagJsonTest.cpp
new file mode 100644
index 0000000..157c40f
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/test/native/cpp/AprilTagJsonTest.cpp
@@ -0,0 +1,27 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <vector>
+
+#include <wpi/json.h>
+
+#include "frc/apriltag/AprilTag.h"
+#include "frc/apriltag/AprilTagFieldLayout.h"
+#include "frc/geometry/Pose3d.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+TEST(AprilTagJsonTest, DeserializeMatches) {
+  auto layout = AprilTagFieldLayout{
+      std::vector{
+          AprilTag{1, Pose3d{}},
+          AprilTag{3, Pose3d{0_m, 1_m, 0_m, Rotation3d{0_deg, 0_deg, 0_deg}}}},
+      54_ft, 27_ft};
+
+  AprilTagFieldLayout deserialized;
+  wpi::json json = layout;
+  EXPECT_NO_THROW(deserialized = json.get<AprilTagFieldLayout>());
+  EXPECT_EQ(layout, deserialized);
+}
diff --git a/third_party/allwpilib/apriltag/src/test/native/cpp/AprilTagPoseSetOriginTest.cpp b/third_party/allwpilib/apriltag/src/test/native/cpp/AprilTagPoseSetOriginTest.cpp
new file mode 100644
index 0000000..3849649
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/test/native/cpp/AprilTagPoseSetOriginTest.cpp
@@ -0,0 +1,33 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <vector>
+
+#include <wpi/json.h>
+
+#include "frc/apriltag/AprilTag.h"
+#include "frc/apriltag/AprilTagFieldLayout.h"
+#include "frc/geometry/Pose3d.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+TEST(AprilTagPoseSetOriginTest, TransformationMatches) {
+  auto layout = AprilTagFieldLayout{
+      std::vector<AprilTag>{
+          AprilTag{1,
+                   Pose3d{0_ft, 0_ft, 0_ft, Rotation3d{0_deg, 0_deg, 0_deg}}},
+          AprilTag{
+              2, Pose3d{4_ft, 4_ft, 4_ft, Rotation3d{0_deg, 0_deg, 180_deg}}}},
+      54_ft, 27_ft};
+
+  layout.SetOrigin(
+      AprilTagFieldLayout::OriginPosition::kRedAllianceWallRightSide);
+
+  auto mirrorPose =
+      Pose3d{54_ft, 27_ft, 0_ft, Rotation3d{0_deg, 0_deg, 180_deg}};
+  EXPECT_EQ(mirrorPose, *layout.GetTagPose(1));
+  mirrorPose = Pose3d{50_ft, 23_ft, 4_ft, Rotation3d{0_deg, 0_deg, 0_deg}};
+  EXPECT_EQ(mirrorPose, *layout.GetTagPose(2));
+}
diff --git a/third_party/allwpilib/apriltag/src/test/native/cpp/LoadConfigTest.cpp b/third_party/allwpilib/apriltag/src/test/native/cpp/LoadConfigTest.cpp
new file mode 100644
index 0000000..9db61e9
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/test/native/cpp/LoadConfigTest.cpp
@@ -0,0 +1,61 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/apriltag/AprilTagFields.h"
+#include "gtest/gtest.h"
+
+namespace frc {
+
+std::vector<AprilTagField> GetAllFields() {
+  std::vector<AprilTagField> output;
+
+  for (int i = 0; i < static_cast<int>(AprilTagField::kNumFields); ++i) {
+    output.push_back(static_cast<AprilTagField>(i));
+  }
+
+  return output;
+}
+
+TEST(AprilTagFieldsTest, TestLoad2022RapidReact) {
+  AprilTagFieldLayout layout =
+      LoadAprilTagLayoutField(AprilTagField::k2022RapidReact);
+
+  // Blue Hangar Truss - Hub
+  auto expectedPose =
+      Pose3d{127.272_in, 216.01_in, 67.932_in, Rotation3d{0_deg, 0_deg, 0_deg}};
+  auto maybePose = layout.GetTagPose(1);
+  EXPECT_TRUE(maybePose);
+  EXPECT_EQ(expectedPose, *maybePose);
+
+  // Blue Terminal Near Station
+  expectedPose = Pose3d{4.768_in, 67.631_in, 35.063_in,
+                        Rotation3d{0_deg, 0_deg, 46.25_deg}};
+  maybePose = layout.GetTagPose(5);
+  EXPECT_TRUE(maybePose);
+  EXPECT_EQ(expectedPose, *maybePose);
+
+  // Upper Hub Blue-Near
+  expectedPose = Pose3d{332.321_in, 183.676_in, 95.186_in,
+                        Rotation3d{0_deg, 26.75_deg, 69_deg}};
+  maybePose = layout.GetTagPose(53);
+  EXPECT_TRUE(maybePose);
+  EXPECT_EQ(expectedPose, *maybePose);
+
+  // Doesn't exist
+  maybePose = layout.GetTagPose(54);
+  EXPECT_FALSE(maybePose);
+}
+
+// Test all of the fields in the enum
+class AllFieldsFixtureTest : public ::testing::TestWithParam<AprilTagField> {};
+
+TEST_P(AllFieldsFixtureTest, CheckEntireEnum) {
+  AprilTagField field = GetParam();
+  EXPECT_NO_THROW(LoadAprilTagLayoutField(field));
+}
+
+INSTANTIATE_TEST_SUITE_P(ValuesEnumTestInstTests, AllFieldsFixtureTest,
+                         ::testing::ValuesIn(GetAllFields()));
+
+}  // namespace frc
diff --git a/third_party/allwpilib/apriltag/src/test/native/cpp/main.cpp b/third_party/allwpilib/apriltag/src/test/native/cpp/main.cpp
new file mode 100644
index 0000000..09072ee
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/test/native/cpp/main.cpp
@@ -0,0 +1,11 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "gtest/gtest.h"
+
+int main(int argc, char** argv) {
+  ::testing::InitGoogleTest(&argc, argv);
+  int ret = RUN_ALL_TESTS();
+  return ret;
+}
diff --git a/third_party/allwpilib/apriltag/src/test/resources/edu/wpi/first/apriltag/tag1_640_480.jpg b/third_party/allwpilib/apriltag/src/test/resources/edu/wpi/first/apriltag/tag1_640_480.jpg
new file mode 100644
index 0000000..a18957d
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/test/resources/edu/wpi/first/apriltag/tag1_640_480.jpg
Binary files differ
diff --git a/third_party/allwpilib/apriltag/src/test/resources/edu/wpi/first/apriltag/tag2_16h5_straight.png b/third_party/allwpilib/apriltag/src/test/resources/edu/wpi/first/apriltag/tag2_16h5_straight.png
new file mode 100644
index 0000000..39f6595
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/test/resources/edu/wpi/first/apriltag/tag2_16h5_straight.png
Binary files differ
diff --git a/third_party/allwpilib/apriltag/src/test/resources/edu/wpi/first/apriltag/tag2_45deg_X.png b/third_party/allwpilib/apriltag/src/test/resources/edu/wpi/first/apriltag/tag2_45deg_X.png
new file mode 100644
index 0000000..8d3521d
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/test/resources/edu/wpi/first/apriltag/tag2_45deg_X.png
Binary files differ
diff --git a/third_party/allwpilib/apriltag/src/test/resources/edu/wpi/first/apriltag/tag2_45deg_y.png b/third_party/allwpilib/apriltag/src/test/resources/edu/wpi/first/apriltag/tag2_45deg_y.png
new file mode 100644
index 0000000..f024f5c
--- /dev/null
+++ b/third_party/allwpilib/apriltag/src/test/resources/edu/wpi/first/apriltag/tag2_45deg_y.png
Binary files differ
diff --git a/third_party/allwpilib/azure-pipelines-testbench.yaml b/third_party/allwpilib/azure-pipelines-testbench.yaml
index 2fc5252..7815268 100644
--- a/third_party/allwpilib/azure-pipelines-testbench.yaml
+++ b/third_party/allwpilib/azure-pipelines-testbench.yaml
@@ -15,7 +15,7 @@
           vmImage: 'ubuntu-latest'
 
         container:
-          image: wpilib/roborio-cross-ubuntu:2022-18.04
+          image: wpilib/roborio-cross-ubuntu:2023-22.04
 
         timeoutInMinutes: 0
 
@@ -38,6 +38,7 @@
 
   - stage: TestBench
     displayName: Test Bench
+    condition: false
     jobs:
       - job: Cpp
         displayName: C++
diff --git a/third_party/allwpilib/build.gradle b/third_party/allwpilib/build.gradle
index c2d5f98..ed2c520 100644
--- a/third_party/allwpilib/build.gradle
+++ b/third_party/allwpilib/build.gradle
@@ -2,7 +2,9 @@
 
 buildscript {
     repositories {
-        mavenCentral()
+        maven {
+            url = 'https://frcmaven.wpi.edu/artifactory/ex-mvn'
+        }
     }
     dependencies {
         classpath 'com.hubspot.jinjava:jinjava:2.6.0'
@@ -11,17 +13,17 @@
 
 plugins {
     id 'base'
-    id 'edu.wpi.first.wpilib.versioning.WPILibVersioningPlugin' version '4.1.0'
+    id 'edu.wpi.first.wpilib.versioning.WPILibVersioningPlugin' version '2023.0.1'
     id 'edu.wpi.first.wpilib.repositories.WPILibRepositoriesPlugin' version '2020.2'
     id 'edu.wpi.first.NativeUtils' apply false
-    id 'edu.wpi.first.GradleJni' version '1.0.0'
+    id 'edu.wpi.first.GradleJni' version '1.1.0'
     id 'edu.wpi.first.GradleVsCode'
     id 'idea'
     id 'visual-studio'
     id 'net.ltgt.errorprone' version '2.0.2' apply false
     id 'com.github.johnrengelman.shadow' version '7.1.2' apply false
-    id 'com.diffplug.spotless' version '6.1.2' apply false
-    id 'com.github.spotbugs' version '5.0.4' apply false
+    id 'com.diffplug.spotless' version '6.12.0' apply false
+    id 'com.github.spotbugs' version '5.0.8' apply false
 }
 
 wpilibVersioning.buildServerMode = project.hasProperty('buildServer')
@@ -29,7 +31,9 @@
 
 allprojects {
     repositories {
-        mavenCentral()
+        maven {
+        url = 'https://frcmaven.wpi.edu/artifactory/ex-mvn'
+    }
     }
     if (project.hasProperty('releaseMode')) {
         wpilibRepositories.addAllReleaseRepositories(it)
@@ -83,7 +87,12 @@
 build.dependsOn copyAllOutputs
 copyAllOutputs.dependsOn outputVersions
 
+def copyReleaseOnly = project.hasProperty('ciReleaseOnly')
+
 ext.addTaskToCopyAllOutputs = { task ->
+    if (copyReleaseOnly && task.name.contains('debug')) {
+        return
+    }
     copyAllOutputs.dependsOn task
     copyAllOutputs.inputs.file task.archivePath
     copyAllOutputs.from task.archivePath
@@ -99,6 +108,11 @@
         subproj.apply plugin: MultiBuilds
     }
 
+    plugins.withType(JavaPlugin) {
+        sourceCompatibility = 11
+        targetCompatibility = 11
+    }
+
     apply from: "${rootDir}/shared/java/javastyle.gradle"
 
     // Disables doclint in java 8.
@@ -110,6 +124,10 @@
         }
     }
 
+    tasks.withType(JavaCompile) {
+        options.compilerArgs.add '-XDstringConcat=inline'
+    }
+
     // Enables UTF-8 support in Javadoc
     tasks.withType(Javadoc) {
         options.addStringOption("charset", "utf-8")
@@ -118,8 +136,10 @@
     }
 
     // Sign outputs with Developer ID
-    if (project.hasProperty("developerID")) {
-        tasks.withType(AbstractLinkTask) { task ->
+    tasks.withType(AbstractLinkTask) { task ->
+        task.inputs.property "HasDeveloperId", project.hasProperty("developerID")
+
+        if (project.hasProperty("developerID")) {
             // Don't sign any executables because codesign complains
             // about relative rpath.
             if (!(task instanceof LinkExecutable)) {
@@ -147,5 +167,5 @@
 }
 
 wrapper {
-    gradleVersion = '7.3.3'
+    gradleVersion = '7.5.1'
 }
diff --git a/third_party/allwpilib/buildSrc/build.gradle b/third_party/allwpilib/buildSrc/build.gradle
index a784c0f..5886aec 100644
--- a/third_party/allwpilib/buildSrc/build.gradle
+++ b/third_party/allwpilib/buildSrc/build.gradle
@@ -1,9 +1,13 @@
 repositories {
     maven {
-        url "https://plugins.gradle.org/m2/"
         mavenLocal()
+        maven {
+            url = 'https://frcmaven.wpi.edu/artifactory/ex-gradle'
+        }
+        mavenCentral()
+        url "https://plugins.gradle.org/m2/"
     }
 }
 dependencies {
-    implementation "edu.wpi.first:native-utils:2022.7.1"
+    implementation "edu.wpi.first:native-utils:2023.11.1"
 }
diff --git a/third_party/allwpilib/buildSrc/src/main/groovy/WPIJREArtifact.groovy b/third_party/allwpilib/buildSrc/src/main/groovy/WPIJREArtifact.groovy
index abe4851..1a0139b 100644
--- a/third_party/allwpilib/buildSrc/src/main/groovy/WPIJREArtifact.groovy
+++ b/third_party/allwpilib/buildSrc/src/main/groovy/WPIJREArtifact.groovy
@@ -1,13 +1,14 @@
-import groovy.transform.CompileStatic

-import javax.inject.Inject

-import edu.wpi.first.deployutils.deploy.artifact.MavenArtifact

-import edu.wpi.first.deployutils.deploy.context.DeployContext

-import org.gradle.api.Project

-import edu.wpi.first.deployutils.ActionWrapper

-import edu.wpi.first.deployutils.deploy.target.RemoteTarget

-import edu.wpi.first.deployutils.PredicateWrapper

+import groovy.transform.CompileStatic;

+import javax.inject.Inject;

 

-import java.util.function.Function

+import org.gradle.api.Project;

+

+import edu.wpi.first.deployutils.deploy.CommandDeployResult;

+import edu.wpi.first.deployutils.deploy.artifact.MavenArtifact;

+import edu.wpi.first.deployutils.deploy.context.DeployContext;

+import edu.wpi.first.deployutils.deploy.target.RemoteTarget;

+import edu.wpi.first.deployutils.PredicateWrapper;

+import edu.wpi.first.deployutils.ActionWrapper;

 

 @CompileStatic

 public class WPIJREArtifact extends MavenArtifact {

@@ -17,6 +18,18 @@
         return configName;

     }

 

+    public boolean isCheckJreVersion() {

+        return checkJreVersion;

+    }

+

+    public void setCheckJreVersion(boolean checkJreVersion) {

+        this.checkJreVersion = checkJreVersion;

+    }

+

+    private boolean checkJreVersion = true;

+

+    private final String artifactLocation = "edu.wpi.first.jdk:roborio-2023:17.0.5u7-1"

+

     @Inject

     public WPIJREArtifact(String name, RemoteTarget target) {

         super(name, target);

@@ -24,10 +37,10 @@
         this.configName = configName;

         Project project = target.getProject();

         getConfiguration().set(project.getConfigurations().create(configName));

-        getDependency().set(project.getDependencies().add(configName, "edu.wpi.first.jdk:roborio-2022:11.0.12u5-1"));

+        getDependency().set(project.getDependencies().add(configName, artifactLocation));

 

         setOnlyIf(new PredicateWrapper({ DeployContext ctx ->

-            return jreMissing(ctx) || project.hasProperty("force-redeploy-jre");

+            return jreMissing(ctx) || jreOutOfDate(ctx) || project.hasProperty("force-redeploy-jre");

         }));

 

         getDirectory().set("/tmp");

@@ -35,7 +48,7 @@
 

         getPostdeploy().add(new ActionWrapper({ DeployContext ctx ->

             ctx.getLogger().log("Installing JRE...");

-            ctx.execute("opkg remove frc2022-openjdk*; opkg install /tmp/frcjre.ipk; rm /tmp/frcjre.ipk");

+            ctx.execute("opkg remove frc*-openjdk*; opkg install /tmp/frcjre.ipk; rm /tmp/frcjre.ipk");

             ctx.getLogger().log("JRE Deployed!");

         }));

     }

@@ -44,5 +57,21 @@
         return ctx.execute("if [[ -f \"/usr/local/frc/JRE/bin/java\" ]]; then echo OK; else echo MISSING; fi").getResult().contains("MISSING");

     }

 

-

+    private boolean jreOutOfDate(DeployContext ctx) {

+        if (!checkJreVersion) {

+            return false;

+        }

+        String version = getDependency().get().getVersion();

+        CommandDeployResult cmdResult = ctx.execute("opkg list-installed | grep openjdk");

+        if (cmdResult.getExitCode() != 0) {

+            ctx.getLogger().log("JRE not found");

+            return false;

+        }

+        String result = cmdResult.getResult().trim();

+        ctx.getLogger().log("Searching for JRE " + version);

+        ctx.getLogger().log("Found JRE " + result);

+        boolean matches = result.contains(version);

+        ctx.getLogger().log(matches ? "JRE Is Correct Version" : "JRE is mismatched. Reinstalling");

+        return !matches;

+    }

 }

diff --git a/third_party/allwpilib/cameraserver/build.gradle b/third_party/allwpilib/cameraserver/build.gradle
index 7a611e6..3f4b208 100644
--- a/third_party/allwpilib/cameraserver/build.gradle
+++ b/third_party/allwpilib/cameraserver/build.gradle
@@ -11,9 +11,11 @@
 
 dependencies {
     implementation project(':wpiutil')
+    implementation project(':wpinet')
     implementation project(':ntcore')
     implementation project(':cscore')
     devImplementation project(':wpiutil')
+    devImplementation project(':wpinet')
     devImplementation project(':ntcore')
     devImplementation project(':cscore')
 }
@@ -32,19 +34,6 @@
 
 nativeUtils.exportsConfigs {
     cameraserver {
-        x86ExcludeSymbols = [
-            '_CT??_R0?AV_System_error',
-            '_CT??_R0?AVexception',
-            '_CT??_R0?AVfailure',
-            '_CT??_R0?AVruntime_error',
-            '_CT??_R0?AVsystem_error',
-            '_CTA5?AVfailure',
-            '_TI5?AVfailure',
-            '_CT??_R0?AVout_of_range',
-            '_CTA3?AVout_of_range',
-            '_TI3?AVout_of_range',
-            '_CT??_R0?AVbad_cast'
-        ]
         x64ExcludeSymbols = [
             '_CT??_R0?AV_System_error',
             '_CT??_R0?AVexception',
@@ -68,8 +57,9 @@
             if (!it.buildable || !(it instanceof NativeBinarySpec)) {
                 return
             }
-            lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
+            project(':ntcore').addNtcoreDependency(it, 'shared')
             lib project: ':cscore', library: 'cscore', linkage: 'shared'
+            lib project: ':wpinet', library: 'wpinet', linkage: 'shared'
             lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
         }
     }
diff --git a/third_party/allwpilib/cameraserver/multiCameraServer/build.gradle b/third_party/allwpilib/cameraserver/multiCameraServer/build.gradle
index f7a78c1..4aafd26 100644
--- a/third_party/allwpilib/cameraserver/multiCameraServer/build.gradle
+++ b/third_party/allwpilib/cameraserver/multiCameraServer/build.gradle
@@ -23,13 +23,16 @@
 apply plugin: 'com.github.johnrengelman.shadow'
 
 repositories {
-    mavenCentral()
+    maven {
+        url = 'https://frcmaven.wpi.edu/artifactory/ex-mvn'
+    }
 }
 
 dependencies {
     implementation 'com.google.code.gson:gson:2.8.9'
 
     implementation project(':wpiutil')
+    implementation project(':wpinet')
     implementation project(':ntcore')
     implementation project(':cscore')
     implementation project(':cameraserver')
@@ -38,7 +41,6 @@
 model {
     components {
         multiCameraServerCpp(NativeExecutableSpec) {
-            targetBuildTypes 'release'
             sources {
                 cpp {
                     source {
@@ -53,8 +55,9 @@
             }
             binaries.all { binary ->
                 lib project: ':cameraserver', library: 'cameraserver', linkage: 'static'
-                lib project: ':ntcore', library: 'ntcore', linkage: 'static'
+                project(':ntcore').addNtcoreDependency(binary, 'static')
                 lib project: ':cscore', library: 'cscore', linkage: 'static'
+                lib project: ':wpinet', library: 'wpinet', linkage: 'static'
                 lib project: ':wpiutil', library: 'wpiutil', linkage: 'static'
             }
         }
diff --git a/third_party/allwpilib/cameraserver/multiCameraServer/src/main/java/edu/wpi/Main.java b/third_party/allwpilib/cameraserver/multiCameraServer/src/main/java/edu/wpi/Main.java
index 622b939..1f79182 100644
--- a/third_party/allwpilib/cameraserver/multiCameraServer/src/main/java/edu/wpi/Main.java
+++ b/third_party/allwpilib/cameraserver/multiCameraServer/src/main/java/edu/wpi/Main.java
@@ -175,7 +175,8 @@
       ntinst.startServer();
     } else {
       System.out.println("Setting up NetworkTables client for team " + team);
-      ntinst.startClientTeam(team);
+      ntinst.setServerTeam(team);
+      ntinst.startClient4("multicameraserver");
     }
 
     // start cameras
diff --git a/third_party/allwpilib/cameraserver/multiCameraServer/src/main/native/cpp/main.cpp b/third_party/allwpilib/cameraserver/multiCameraServer/src/main/native/cpp/main.cpp
index 45b56d4..2cb1c89 100644
--- a/third_party/allwpilib/cameraserver/multiCameraServer/src/main/native/cpp/main.cpp
+++ b/third_party/allwpilib/cameraserver/multiCameraServer/src/main/native/cpp/main.cpp
@@ -5,6 +5,7 @@
 #include <cstdio>
 #include <string>
 #include <string_view>
+#include <thread>
 #include <vector>
 
 #include <networktables/NetworkTableInstance.h>
@@ -182,7 +183,8 @@
     ntinst.StartServer();
   } else {
     fmt::print("Setting up NetworkTables client for team {}\n", team);
-    ntinst.StartClientTeam(team);
+    ntinst.StartClient4("multicameraserver");
+    ntinst.SetServerTeam(team);
   }
 
   // start cameras
diff --git a/third_party/allwpilib/cameraserver/src/main/java/edu/wpi/first/cameraserver/CameraServer.java b/third_party/allwpilib/cameraserver/src/main/java/edu/wpi/first/cameraserver/CameraServer.java
index 11de969..d4a1dd6 100644
--- a/third_party/allwpilib/cameraserver/src/main/java/edu/wpi/first/cameraserver/CameraServer.java
+++ b/third_party/allwpilib/cameraserver/src/main/java/edu/wpi/first/cameraserver/CameraServer.java
@@ -15,13 +15,18 @@
 import edu.wpi.first.cscore.VideoListener;
 import edu.wpi.first.cscore.VideoMode;
 import edu.wpi.first.cscore.VideoMode.PixelFormat;
-import edu.wpi.first.cscore.VideoProperty;
 import edu.wpi.first.cscore.VideoSink;
 import edu.wpi.first.cscore.VideoSource;
-import edu.wpi.first.networktables.EntryListenerFlags;
+import edu.wpi.first.networktables.BooleanEntry;
+import edu.wpi.first.networktables.BooleanPublisher;
+import edu.wpi.first.networktables.IntegerEntry;
+import edu.wpi.first.networktables.IntegerPublisher;
 import edu.wpi.first.networktables.NetworkTable;
-import edu.wpi.first.networktables.NetworkTableEntry;
 import edu.wpi.first.networktables.NetworkTableInstance;
+import edu.wpi.first.networktables.StringArrayPublisher;
+import edu.wpi.first.networktables.StringArrayTopic;
+import edu.wpi.first.networktables.StringEntry;
+import edu.wpi.first.networktables.StringPublisher;
 import java.util.ArrayList;
 import java.util.Arrays;
 import java.util.HashMap;
@@ -33,36 +38,172 @@
  * Singleton class for creating and keeping camera servers. Also publishes camera information to
  * NetworkTables.
  */
-@SuppressWarnings("PMD.UnusedPrivateField")
 public final class CameraServer {
   public static final int kBasePort = 1181;
 
-  @Deprecated public static final int kSize640x480 = 0;
-  @Deprecated public static final int kSize320x240 = 1;
-  @Deprecated public static final int kSize160x120 = 2;
-
   private static final String kPublishName = "/CameraPublisher";
-  private static CameraServer server;
 
-  /**
-   * Get the CameraServer instance.
-   *
-   * @return The CameraServer instance.
-   * @deprecated Use the static methods
-   */
-  @Deprecated
-  public static synchronized CameraServer getInstance() {
-    if (server == null) {
-      server = new CameraServer();
+  private static final class PropertyPublisher implements AutoCloseable {
+    @SuppressWarnings({"PMD.MissingBreakInSwitch", "PMD.ImplicitSwitchFallThrough", "fallthrough"})
+    PropertyPublisher(NetworkTable table, VideoEvent event) {
+      String name;
+      String infoName;
+      if (event.name.startsWith("raw_")) {
+        name = "RawProperty/" + event.name;
+        infoName = "RawPropertyInfo/" + event.name;
+      } else {
+        name = "Property/" + event.name;
+        infoName = "PropertyInfo/" + event.name;
+      }
+
+      try {
+        switch (event.propertyKind) {
+          case kBoolean:
+            m_booleanValueEntry = table.getBooleanTopic(name).getEntry(false);
+            m_booleanValueEntry.setDefault(event.value != 0);
+            break;
+          case kEnum:
+            m_choicesTopic = table.getStringArrayTopic(infoName + "/choices");
+            // fall through
+          case kInteger:
+            m_integerValueEntry = table.getIntegerTopic(name).getEntry(0);
+            m_minPublisher = table.getIntegerTopic(infoName + "/min").publish();
+            m_maxPublisher = table.getIntegerTopic(infoName + "/max").publish();
+            m_stepPublisher = table.getIntegerTopic(infoName + "/step").publish();
+            m_defaultPublisher = table.getIntegerTopic(infoName + "/default").publish();
+
+            m_integerValueEntry.setDefault(event.value);
+            m_minPublisher.set(CameraServerJNI.getPropertyMin(event.propertyHandle));
+            m_maxPublisher.set(CameraServerJNI.getPropertyMax(event.propertyHandle));
+            m_stepPublisher.set(CameraServerJNI.getPropertyStep(event.propertyHandle));
+            m_defaultPublisher.set(CameraServerJNI.getPropertyDefault(event.propertyHandle));
+            break;
+          case kString:
+            m_stringValueEntry = table.getStringTopic(name).getEntry("");
+            m_stringValueEntry.setDefault(event.valueStr);
+            break;
+          default:
+            break;
+        }
+      } catch (VideoException ignored) {
+        // ignore
+      }
     }
-    return server;
+
+    void update(VideoEvent event) {
+      switch (event.propertyKind) {
+        case kBoolean:
+          if (m_booleanValueEntry != null) {
+            m_booleanValueEntry.set(event.value != 0);
+          }
+          break;
+        case kInteger:
+        case kEnum:
+          if (m_integerValueEntry != null) {
+            m_integerValueEntry.set(event.value);
+          }
+          break;
+        case kString:
+          if (m_stringValueEntry != null) {
+            m_stringValueEntry.set(event.valueStr);
+          }
+          break;
+        default:
+          break;
+      }
+    }
+
+    @Override
+    public void close() throws Exception {
+      if (m_booleanValueEntry != null) {
+        m_booleanValueEntry.close();
+      }
+      if (m_integerValueEntry != null) {
+        m_integerValueEntry.close();
+      }
+      if (m_stringValueEntry != null) {
+        m_stringValueEntry.close();
+      }
+      if (m_minPublisher != null) {
+        m_minPublisher.close();
+      }
+      if (m_maxPublisher != null) {
+        m_maxPublisher.close();
+      }
+      if (m_stepPublisher != null) {
+        m_stepPublisher.close();
+      }
+      if (m_defaultPublisher != null) {
+        m_defaultPublisher.close();
+      }
+      if (m_choicesPublisher != null) {
+        m_choicesPublisher.close();
+      }
+    }
+
+    BooleanEntry m_booleanValueEntry;
+    IntegerEntry m_integerValueEntry;
+    StringEntry m_stringValueEntry;
+    IntegerPublisher m_minPublisher;
+    IntegerPublisher m_maxPublisher;
+    IntegerPublisher m_stepPublisher;
+    IntegerPublisher m_defaultPublisher;
+    StringArrayTopic m_choicesTopic;
+    StringArrayPublisher m_choicesPublisher;
+  }
+
+  private static final class SourcePublisher implements AutoCloseable {
+    SourcePublisher(NetworkTable table, int sourceHandle) {
+      this.m_table = table;
+      m_sourcePublisher = table.getStringTopic("source").publish();
+      m_descriptionPublisher = table.getStringTopic("description").publish();
+      m_connectedPublisher = table.getBooleanTopic("connected").publish();
+      m_streamsPublisher = table.getStringArrayTopic("streams").publish();
+      m_modeEntry = table.getStringTopic("mode").getEntry("");
+      m_modesPublisher = table.getStringArrayTopic("modes").publish();
+
+      m_sourcePublisher.set(makeSourceValue(sourceHandle));
+      m_descriptionPublisher.set(CameraServerJNI.getSourceDescription(sourceHandle));
+      m_connectedPublisher.set(CameraServerJNI.isSourceConnected(sourceHandle));
+      m_streamsPublisher.set(getSourceStreamValues(sourceHandle));
+
+      try {
+        VideoMode mode = CameraServerJNI.getSourceVideoMode(sourceHandle);
+        m_modeEntry.setDefault(videoModeToString(mode));
+        m_modesPublisher.set(getSourceModeValues(sourceHandle));
+      } catch (VideoException ignored) {
+        // Do nothing. Let the other event handlers update this if there is an error.
+      }
+    }
+
+    @Override
+    public void close() throws Exception {
+      m_sourcePublisher.close();
+      m_descriptionPublisher.close();
+      m_connectedPublisher.close();
+      m_streamsPublisher.close();
+      m_modeEntry.close();
+      m_modesPublisher.close();
+      for (PropertyPublisher pp : m_properties.values()) {
+        pp.close();
+      }
+    }
+
+    final NetworkTable m_table;
+    final StringPublisher m_sourcePublisher;
+    final StringPublisher m_descriptionPublisher;
+    final BooleanPublisher m_connectedPublisher;
+    final StringArrayPublisher m_streamsPublisher;
+    final StringEntry m_modeEntry;
+    final StringArrayPublisher m_modesPublisher;
+    final Map<Integer, PropertyPublisher> m_properties = new HashMap<>();
   }
 
   private static final AtomicInteger m_defaultUsbDevice = new AtomicInteger();
   private static String m_primarySourceName;
   private static final Map<String, VideoSource> m_sources = new HashMap<>();
   private static final Map<String, VideoSink> m_sinks = new HashMap<>();
-  private static final Map<Integer, NetworkTable> m_tables =
+  private static final Map<Integer, SourcePublisher> m_publishers =
       new HashMap<>(); // indexed by source handle
   // source handle indexed by sink handle
   private static final Map<Integer, Integer> m_fixedSources = new HashMap<>();
@@ -81,190 +222,132 @@
   // - "PropertyInfo/{Property}" - Property supporting information
 
   // Listener for video events
+  @SuppressWarnings({"PMD.UnusedPrivateField", "PMD.AvoidCatchingGenericException"})
   private static final VideoListener m_videoListener =
       new VideoListener(
           event -> {
-            switch (event.kind) {
-              case kSourceCreated:
-                {
-                  // Create subtable for the camera
-                  NetworkTable table = m_publishTable.getSubTable(event.name);
-                  m_tables.put(event.sourceHandle, table);
-                  table.getEntry("source").setString(makeSourceValue(event.sourceHandle));
-                  table
-                      .getEntry("description")
-                      .setString(CameraServerJNI.getSourceDescription(event.sourceHandle));
-                  table
-                      .getEntry("connected")
-                      .setBoolean(CameraServerJNI.isSourceConnected(event.sourceHandle));
-                  table
-                      .getEntry("streams")
-                      .setStringArray(getSourceStreamValues(event.sourceHandle));
-                  try {
-                    VideoMode mode = CameraServerJNI.getSourceVideoMode(event.sourceHandle);
-                    table.getEntry("mode").setDefaultString(videoModeToString(mode));
-                    table.getEntry("modes").setStringArray(getSourceModeValues(event.sourceHandle));
-                  } catch (VideoException ignored) {
-                    // Do nothing. Let the other event handlers update this if there is an error.
+            synchronized (CameraServer.class) {
+              switch (event.kind) {
+                case kSourceCreated:
+                  {
+                    // Create subtable for the camera
+                    NetworkTable table = m_publishTable.getSubTable(event.name);
+                    m_publishers.put(
+                        event.sourceHandle, new SourcePublisher(table, event.sourceHandle));
+                    break;
                   }
-                  break;
-                }
-              case kSourceDestroyed:
-                {
-                  NetworkTable table = m_tables.get(event.sourceHandle);
-                  if (table != null) {
-                    table.getEntry("source").setString("");
-                    table.getEntry("streams").setStringArray(new String[0]);
-                    table.getEntry("modes").setStringArray(new String[0]);
-                  }
-                  break;
-                }
-              case kSourceConnected:
-                {
-                  NetworkTable table = m_tables.get(event.sourceHandle);
-                  if (table != null) {
-                    // update the description too (as it may have changed)
-                    table
-                        .getEntry("description")
-                        .setString(CameraServerJNI.getSourceDescription(event.sourceHandle));
-                    table.getEntry("connected").setBoolean(true);
-                  }
-                  break;
-                }
-              case kSourceDisconnected:
-                {
-                  NetworkTable table = m_tables.get(event.sourceHandle);
-                  if (table != null) {
-                    table.getEntry("connected").setBoolean(false);
-                  }
-                  break;
-                }
-              case kSourceVideoModesUpdated:
-                {
-                  NetworkTable table = m_tables.get(event.sourceHandle);
-                  if (table != null) {
-                    table.getEntry("modes").setStringArray(getSourceModeValues(event.sourceHandle));
-                  }
-                  break;
-                }
-              case kSourceVideoModeChanged:
-                {
-                  NetworkTable table = m_tables.get(event.sourceHandle);
-                  if (table != null) {
-                    table.getEntry("mode").setString(videoModeToString(event.mode));
-                  }
-                  break;
-                }
-              case kSourcePropertyCreated:
-                {
-                  NetworkTable table = m_tables.get(event.sourceHandle);
-                  if (table != null) {
-                    putSourcePropertyValue(table, event, true);
-                  }
-                  break;
-                }
-              case kSourcePropertyValueUpdated:
-                {
-                  NetworkTable table = m_tables.get(event.sourceHandle);
-                  if (table != null) {
-                    putSourcePropertyValue(table, event, false);
-                  }
-                  break;
-                }
-              case kSourcePropertyChoicesUpdated:
-                {
-                  NetworkTable table = m_tables.get(event.sourceHandle);
-                  if (table != null) {
-                    try {
-                      String[] choices =
-                          CameraServerJNI.getEnumPropertyChoices(event.propertyHandle);
-                      table
-                          .getEntry("PropertyInfo/" + event.name + "/choices")
-                          .setStringArray(choices);
-                    } catch (VideoException ignored) {
-                      // ignore
+                case kSourceDestroyed:
+                  {
+                    SourcePublisher publisher = m_publishers.remove(event.sourceHandle);
+                    if (publisher != null) {
+                      try {
+                        publisher.close();
+                      } catch (Exception e) {
+                        // ignore (nothing we can do about it)
+                      }
                     }
+                    break;
                   }
+                case kSourceConnected:
+                  {
+                    SourcePublisher publisher = m_publishers.get(event.sourceHandle);
+                    if (publisher != null) {
+                      // update the description too (as it may have changed)
+                      publisher.m_descriptionPublisher.set(
+                          CameraServerJNI.getSourceDescription(event.sourceHandle));
+                      publisher.m_connectedPublisher.set(true);
+                    }
+                    break;
+                  }
+                case kSourceDisconnected:
+                  {
+                    SourcePublisher publisher = m_publishers.get(event.sourceHandle);
+                    if (publisher != null) {
+                      publisher.m_connectedPublisher.set(false);
+                    }
+                    break;
+                  }
+                case kSourceVideoModesUpdated:
+                  {
+                    SourcePublisher publisher = m_publishers.get(event.sourceHandle);
+                    if (publisher != null) {
+                      publisher.m_modesPublisher.set(getSourceModeValues(event.sourceHandle));
+                    }
+                    break;
+                  }
+                case kSourceVideoModeChanged:
+                  {
+                    SourcePublisher publisher = m_publishers.get(event.sourceHandle);
+                    if (publisher != null) {
+                      publisher.m_modeEntry.set(videoModeToString(event.mode));
+                    }
+                    break;
+                  }
+                case kSourcePropertyCreated:
+                  {
+                    SourcePublisher publisher = m_publishers.get(event.sourceHandle);
+                    if (publisher != null) {
+                      publisher.m_properties.put(
+                          event.propertyHandle, new PropertyPublisher(publisher.m_table, event));
+                    }
+                    break;
+                  }
+                case kSourcePropertyValueUpdated:
+                  {
+                    SourcePublisher publisher = m_publishers.get(event.sourceHandle);
+                    if (publisher != null) {
+                      PropertyPublisher pp = publisher.m_properties.get(event.propertyHandle);
+                      if (pp != null) {
+                        pp.update(event);
+                      }
+                    }
+                    break;
+                  }
+                case kSourcePropertyChoicesUpdated:
+                  {
+                    SourcePublisher publisher = m_publishers.get(event.sourceHandle);
+                    if (publisher != null) {
+                      PropertyPublisher pp = publisher.m_properties.get(event.propertyHandle);
+                      if (pp != null && pp.m_choicesTopic != null) {
+                        try {
+                          String[] choices =
+                              CameraServerJNI.getEnumPropertyChoices(event.propertyHandle);
+                          if (pp.m_choicesPublisher == null) {
+                            pp.m_choicesPublisher = pp.m_choicesTopic.publish();
+                          }
+                          pp.m_choicesPublisher.set(choices);
+                        } catch (VideoException ignored) {
+                          // ignore (just don't publish choices if we can't get them)
+                        }
+                      }
+                    }
+                    break;
+                  }
+                case kSinkSourceChanged:
+                case kSinkCreated:
+                case kSinkDestroyed:
+                case kNetworkInterfacesChanged:
+                  {
+                    m_addresses = CameraServerJNI.getNetworkInterfaces();
+                    updateStreamValues();
+                    break;
+                  }
+                default:
                   break;
-                }
-              case kSinkSourceChanged:
-              case kSinkCreated:
-              case kSinkDestroyed:
-              case kNetworkInterfacesChanged:
-                {
-                  m_addresses = CameraServerJNI.getNetworkInterfaces();
-                  updateStreamValues();
-                  break;
-                }
-              default:
-                break;
+              }
             }
           },
           0x4fff,
           true);
 
-  private static final int m_tableListener =
-      NetworkTableInstance.getDefault()
-          .addEntryListener(
-              kPublishName + "/",
-              event -> {
-                String relativeKey = event.name.substring(kPublishName.length() + 1);
-
-                // get source (sourceName/...)
-                int subKeyIndex = relativeKey.indexOf('/');
-                if (subKeyIndex == -1) {
-                  return;
-                }
-                String sourceName = relativeKey.substring(0, subKeyIndex);
-                VideoSource source = m_sources.get(sourceName);
-                if (source == null) {
-                  return;
-                }
-
-                // get subkey
-                relativeKey = relativeKey.substring(subKeyIndex + 1);
-
-                // handle standard names
-                String propName;
-                if ("mode".equals(relativeKey)) {
-                  // reset to current mode
-                  event.getEntry().setString(videoModeToString(source.getVideoMode()));
-                  return;
-                } else if (relativeKey.startsWith("Property/")) {
-                  propName = relativeKey.substring(9);
-                } else if (relativeKey.startsWith("RawProperty/")) {
-                  propName = relativeKey.substring(12);
-                } else {
-                  return; // ignore
-                }
-
-                // everything else is a property
-                VideoProperty property = source.getProperty(propName);
-                switch (property.getKind()) {
-                  case kNone:
-                    return;
-                  case kBoolean:
-                    // reset to current setting
-                    event.getEntry().setBoolean(property.get() != 0);
-                    return;
-                  case kInteger:
-                  case kEnum:
-                    // reset to current setting
-                    event.getEntry().setDouble(property.get());
-                    return;
-                  case kString:
-                    // reset to current setting
-                    event.getEntry().setString(property.getString());
-                    return;
-                  default:
-                    return;
-                }
-              },
-              EntryListenerFlags.kImmediate | EntryListenerFlags.kUpdate);
   private static int m_nextPort = kBasePort;
   private static String[] m_addresses = new String[0];
 
-  @SuppressWarnings("MissingJavadocMethod")
+  /**
+   * Return URI of source with the given index.
+   *
+   * @param source Source index.
+   */
   private static String makeSourceValue(int source) {
     switch (VideoSource.getKindFromInt(CameraServerJNI.getSourceKind(source))) {
       case kUsb:
@@ -285,12 +368,21 @@
     }
   }
 
-  @SuppressWarnings("MissingJavadocMethod")
+  /**
+   * Return URI of stream with the given address and port.
+   *
+   * @param address Stream IP address.
+   * @param port Stream remote port.
+   */
   private static String makeStreamValue(String address, int port) {
     return "mjpg:http://" + address + ":" + port + "/?action=stream";
   }
 
-  @SuppressWarnings("MissingJavadocMethod")
+  /**
+   * Return URI of sink stream with the given index.
+   *
+   * @param sink Sink index.
+   */
   private static synchronized String[] getSinkStreamValues(int sink) {
     // Ignore all but MjpegServer
     if (VideoSink.getKindFromInt(CameraServerJNI.getSinkKind(sink)) != VideoSink.Kind.kMjpeg) {
@@ -320,7 +412,11 @@
     return values.toArray(new String[0]);
   }
 
-  @SuppressWarnings("MissingJavadocMethod")
+  /**
+   * Return list of stream source URIs for the given source index.
+   *
+   * @param source Source index.
+   */
   private static synchronized String[] getSourceStreamValues(int source) {
     // Ignore all but HttpCamera
     if (VideoSource.getKindFromInt(CameraServerJNI.getSourceKind(source))
@@ -355,7 +451,7 @@
     return values;
   }
 
-  @SuppressWarnings("MissingJavadocMethod")
+  /** Update list of stream URIs. */
   private static synchronized void updateStreamValues() {
     // Over all the sinks...
     for (VideoSink i : m_sinks.values()) {
@@ -369,8 +465,8 @@
       if (source == 0) {
         continue;
       }
-      NetworkTable table = m_tables.get(source);
-      if (table != null) {
+      SourcePublisher publisher = m_publishers.get(source);
+      if (publisher != null) {
         // Don't set stream values if this is a HttpCamera passthrough
         if (VideoSource.getKindFromInt(CameraServerJNI.getSourceKind(source))
             == VideoSource.Kind.kHttp) {
@@ -380,7 +476,7 @@
         // Set table value
         String[] values = getSinkStreamValues(sink);
         if (values.length > 0) {
-          table.getEntry("streams").setStringArray(values);
+          publisher.m_streamsPublisher.set(values);
         }
       }
     }
@@ -390,18 +486,18 @@
       int source = i.getHandle();
 
       // Get the source's subtable (if none exists, we're done)
-      NetworkTable table = m_tables.get(source);
-      if (table != null) {
+      SourcePublisher publisher = m_publishers.get(source);
+      if (publisher != null) {
         // Set table value
         String[] values = getSourceStreamValues(source);
         if (values.length > 0) {
-          table.getEntry("streams").setStringArray(values);
+          publisher.m_streamsPublisher.set(values);
         }
       }
     }
   }
 
-  @SuppressWarnings("MissingJavadocMethod")
+  /** Provide string description of pixel format. */
   private static String pixelFormatToString(PixelFormat pixelFormat) {
     switch (pixelFormat) {
       case kMJPEG:
@@ -419,9 +515,11 @@
     }
   }
 
-  /// Provide string description of video mode.
-  /// The returned string is "{width}x{height} {format} {fps} fps".
-  @SuppressWarnings("MissingJavadocMethod")
+  /**
+   * Provide string description of video mode.
+   *
+   * <p>The returned string is "{width}x{height} {format} {fps} fps".
+   */
   private static String videoModeToString(VideoMode mode) {
     return mode.width
         + "x"
@@ -433,7 +531,11 @@
         + " fps";
   }
 
-  @SuppressWarnings("MissingJavadocMethod")
+  /**
+   * Get list of video modes for the given source handle.
+   *
+   * @param sourceHandle Source handle.
+   */
   private static String[] getSourceModeValues(int sourceHandle) {
     VideoMode[] modes = CameraServerJNI.enumerateSourceVideoModes(sourceHandle);
     String[] modeStrings = new String[modes.length];
@@ -443,63 +545,6 @@
     return modeStrings;
   }
 
-  @SuppressWarnings("MissingJavadocMethod")
-  private static void putSourcePropertyValue(NetworkTable table, VideoEvent event, boolean isNew) {
-    String name;
-    String infoName;
-    if (event.name.startsWith("raw_")) {
-      name = "RawProperty/" + event.name;
-      infoName = "RawPropertyInfo/" + event.name;
-    } else {
-      name = "Property/" + event.name;
-      infoName = "PropertyInfo/" + event.name;
-    }
-
-    NetworkTableEntry entry = table.getEntry(name);
-    try {
-      switch (event.propertyKind) {
-        case kBoolean:
-          if (isNew) {
-            entry.setDefaultBoolean(event.value != 0);
-          } else {
-            entry.setBoolean(event.value != 0);
-          }
-          break;
-        case kInteger:
-        case kEnum:
-          if (isNew) {
-            entry.setDefaultDouble(event.value);
-            table
-                .getEntry(infoName + "/min")
-                .setDouble(CameraServerJNI.getPropertyMin(event.propertyHandle));
-            table
-                .getEntry(infoName + "/max")
-                .setDouble(CameraServerJNI.getPropertyMax(event.propertyHandle));
-            table
-                .getEntry(infoName + "/step")
-                .setDouble(CameraServerJNI.getPropertyStep(event.propertyHandle));
-            table
-                .getEntry(infoName + "/default")
-                .setDouble(CameraServerJNI.getPropertyDefault(event.propertyHandle));
-          } else {
-            entry.setDouble(event.value);
-          }
-          break;
-        case kString:
-          if (isNew) {
-            entry.setDefaultString(event.valueStr);
-          } else {
-            entry.setString(event.valueStr);
-          }
-          break;
-        default:
-          break;
-      }
-    } catch (VideoException ignored) {
-      // ignore
-    }
-  }
-
   private CameraServer() {}
 
   /**
diff --git a/third_party/allwpilib/cameraserver/src/main/java/edu/wpi/first/vision/package-info.java b/third_party/allwpilib/cameraserver/src/main/java/edu/wpi/first/vision/package-info.java
index 3715570..e4515cb 100644
--- a/third_party/allwpilib/cameraserver/src/main/java/edu/wpi/first/vision/package-info.java
+++ b/third_party/allwpilib/cameraserver/src/main/java/edu/wpi/first/vision/package-info.java
@@ -9,7 +9,7 @@
  * <p>An example use case for grabbing a yellow tote from 2015 in autonomous: <br>
  *
  * <pre><code>
- * public class Robot extends IterativeRobot
+ * public class Robot extends TimedRobot
  *     implements VisionRunner.Listener&lt;MyFindTotePipeline&gt; {
  *
  *      // A USB camera connected to the roboRIO.
diff --git a/third_party/allwpilib/cameraserver/src/main/native/cpp/cameraserver/CameraServer.cpp b/third_party/allwpilib/cameraserver/src/main/native/cpp/cameraserver/CameraServer.cpp
index afeff62..c6ecc3c 100644
--- a/third_party/allwpilib/cameraserver/src/main/native/cpp/cameraserver/CameraServer.cpp
+++ b/third_party/allwpilib/cameraserver/src/main/native/cpp/cameraserver/CameraServer.cpp
@@ -8,8 +8,12 @@
 #include <vector>
 
 #include <fmt/format.h>
+#include <networktables/BooleanTopic.h>
+#include <networktables/IntegerTopic.h>
 #include <networktables/NetworkTable.h>
 #include <networktables/NetworkTableInstance.h>
+#include <networktables/StringArrayTopic.h>
+#include <networktables/StringTopic.h>
 #include <wpi/DenseMap.h>
 #include <wpi/SmallString.h>
 #include <wpi/StringExtras.h>
@@ -24,9 +28,42 @@
 static constexpr char const* kPublishName = "/CameraPublisher";
 
 namespace {
+
+struct Instance;
+
+struct PropertyPublisher {
+  PropertyPublisher(nt::NetworkTable& table, const cs::VideoEvent& event);
+
+  void Update(const cs::VideoEvent& event);
+
+  nt::BooleanEntry booleanValueEntry;
+  nt::IntegerEntry integerValueEntry;
+  nt::StringEntry stringValueEntry;
+  nt::IntegerPublisher minPublisher;
+  nt::IntegerPublisher maxPublisher;
+  nt::IntegerPublisher stepPublisher;
+  nt::IntegerPublisher defaultPublisher;
+  nt::StringArrayTopic choicesTopic;
+  nt::StringArrayPublisher choicesPublisher;
+};
+
+struct SourcePublisher {
+  SourcePublisher(Instance& inst, std::shared_ptr<nt::NetworkTable> table,
+                  CS_Source source);
+
+  std::shared_ptr<nt::NetworkTable> table;
+  nt::StringPublisher sourcePublisher;
+  nt::StringPublisher descriptionPublisher;
+  nt::BooleanPublisher connectedPublisher;
+  nt::StringArrayPublisher streamsPublisher;
+  nt::StringEntry modeEntry;
+  nt::StringArrayPublisher modesPublisher;
+  wpi::DenseMap<CS_Property, PropertyPublisher> properties;
+};
+
 struct Instance {
   Instance();
-  std::shared_ptr<nt::NetworkTable> GetSourceTable(CS_Source source);
+  SourcePublisher* GetPublisher(CS_Source source);
   std::vector<std::string> GetSinkStreamValues(CS_Sink sink);
   std::vector<std::string> GetSourceStreamValues(CS_Source source);
   void UpdateStreamValues();
@@ -37,7 +74,7 @@
   wpi::StringMap<cs::VideoSource> m_sources;
   wpi::StringMap<cs::VideoSink> m_sinks;
   wpi::DenseMap<CS_Sink, CS_Source> m_fixedSources;
-  wpi::DenseMap<CS_Source, std::shared_ptr<nt::NetworkTable>> m_tables;
+  wpi::DenseMap<CS_Source, SourcePublisher> m_publishers;
   std::shared_ptr<nt::NetworkTable> m_publishTable{
       nt::NetworkTableInstance::GetDefault().GetTable(kPublishName)};
   cs::VideoListener m_videoListener;
@@ -45,6 +82,7 @@
   int m_nextPort{CameraServer::kBasePort};
   std::vector<std::string> m_addresses;
 };
+
 }  // namespace
 
 static Instance& GetInstance() {
@@ -52,12 +90,6 @@
   return instance;
 }
 
-CameraServer* CameraServer::GetInstance() {
-  ::GetInstance();
-  static CameraServer instance;
-  return &instance;
-}
-
 static std::string_view MakeSourceValue(CS_Source source,
                                         wpi::SmallVectorImpl<char>& buf) {
   CS_Status status = 0;
@@ -92,9 +124,13 @@
   return fmt::format("mjpg:http://{}:{}/?action=stream", address, port);
 }
 
-std::shared_ptr<nt::NetworkTable> Instance::GetSourceTable(CS_Source source) {
-  std::scoped_lock lock(m_mutex);
-  return m_tables.lookup(source);
+SourcePublisher* Instance::GetPublisher(CS_Source source) {
+  auto it = m_publishers.find(source);
+  if (it != m_publishers.end()) {
+    return &it->second;
+  } else {
+    return nullptr;
+  }
 }
 
 std::vector<std::string> Instance::GetSinkStreamValues(CS_Sink sink) {
@@ -164,7 +200,6 @@
 }
 
 void Instance::UpdateStreamValues() {
-  std::scoped_lock lock(m_mutex);
   // Over all the sinks...
   for (const auto& i : m_sinks) {
     CS_Status status = 0;
@@ -178,8 +213,7 @@
     if (source == 0) {
       continue;
     }
-    auto table = m_tables.lookup(source);
-    if (table) {
+    if (auto publisher = GetPublisher(source)) {
       // Don't set stream values if this is a HttpCamera passthrough
       if (cs::GetSourceKind(source, &status) == CS_SOURCE_HTTP) {
         continue;
@@ -188,7 +222,7 @@
       // Set table value
       auto values = GetSinkStreamValues(sink);
       if (!values.empty()) {
-        table->GetEntry("streams").SetStringArray(values);
+        publisher->streamsPublisher.Set(values);
       }
     }
   }
@@ -198,12 +232,11 @@
     CS_Source source = i.second.GetHandle();
 
     // Get the source's subtable (if none exists, we're done)
-    auto table = m_tables.lookup(source);
-    if (table) {
+    if (auto publisher = GetPublisher(source)) {
       // Set table value
       auto values = GetSourceStreamValues(source);
       if (!values.empty()) {
-        table->GetEntry("streams").SetStringArray(values);
+        publisher->streamsPublisher.Set(values);
       }
     }
   }
@@ -240,51 +273,71 @@
   return rv;
 }
 
-static void PutSourcePropertyValue(nt::NetworkTable* table,
-                                   const cs::VideoEvent& event, bool isNew) {
-  std::string_view namePrefix;
-  std::string_view infoPrefix;
+PropertyPublisher::PropertyPublisher(nt::NetworkTable& table,
+                                     const cs::VideoEvent& event) {
+  std::string name;
+  std::string infoName;
   if (wpi::starts_with(event.name, "raw_")) {
-    namePrefix = "RawProperty";
-    infoPrefix = "RawPropertyInfo";
+    name = fmt::format("RawProperty/{}", event.name);
+    infoName = fmt::format("RawPropertyInfo/{}", event.name);
   } else {
-    namePrefix = "Property";
-    infoPrefix = "PropertyInfo";
+    name = fmt::format("Property/{}", event.name);
+    infoName = fmt::format("PropertyInfo/{}", event.name);
   }
 
-  wpi::SmallString<64> buf;
   CS_Status status = 0;
-  nt::NetworkTableEntry entry =
-      table->GetEntry(fmt::format("{}/{}", namePrefix, event.name));
   switch (event.propertyKind) {
     case CS_PROP_BOOLEAN:
-      if (isNew) {
-        entry.SetDefaultBoolean(event.value != 0);
-      } else {
-        entry.SetBoolean(event.value != 0);
+      booleanValueEntry = table.GetBooleanTopic(name).GetEntry(false);
+      booleanValueEntry.SetDefault(event.value != 0);
+      break;
+    case CS_PROP_ENUM:
+      choicesTopic =
+          table.GetStringArrayTopic(fmt::format("{}/choices", infoName));
+      [[fallthrough]];
+    case CS_PROP_INTEGER:
+      integerValueEntry = table.GetIntegerTopic(name).GetEntry(0);
+      minPublisher =
+          table.GetIntegerTopic(fmt::format("{}/min", infoName)).Publish();
+      maxPublisher =
+          table.GetIntegerTopic(fmt::format("{}/max", infoName)).Publish();
+      stepPublisher =
+          table.GetIntegerTopic(fmt::format("{}/step", infoName)).Publish();
+      defaultPublisher =
+          table.GetIntegerTopic(fmt::format("{}/default", infoName)).Publish();
+
+      integerValueEntry.SetDefault(event.value);
+      minPublisher.Set(cs::GetPropertyMin(event.propertyHandle, &status));
+      maxPublisher.Set(cs::GetPropertyMax(event.propertyHandle, &status));
+      stepPublisher.Set(cs::GetPropertyStep(event.propertyHandle, &status));
+      defaultPublisher.Set(
+          cs::GetPropertyDefault(event.propertyHandle, &status));
+      break;
+    case CS_PROP_STRING:
+      stringValueEntry = table.GetStringTopic(name).GetEntry("");
+      stringValueEntry.SetDefault(event.valueStr);
+      break;
+    default:
+      break;
+  }
+}
+
+void PropertyPublisher::Update(const cs::VideoEvent& event) {
+  switch (event.propertyKind) {
+    case CS_PROP_BOOLEAN:
+      if (booleanValueEntry) {
+        booleanValueEntry.Set(event.value != 0);
       }
       break;
     case CS_PROP_INTEGER:
     case CS_PROP_ENUM:
-      if (isNew) {
-        entry.SetDefaultDouble(event.value);
-        table->GetEntry(fmt::format("{}/{}/min", infoPrefix, event.name))
-            .SetDouble(cs::GetPropertyMin(event.propertyHandle, &status));
-        table->GetEntry(fmt::format("{}/{}/max", infoPrefix, event.name))
-            .SetDouble(cs::GetPropertyMax(event.propertyHandle, &status));
-        table->GetEntry(fmt::format("{}/{}/step", infoPrefix, event.name))
-            .SetDouble(cs::GetPropertyStep(event.propertyHandle, &status));
-        table->GetEntry(fmt::format("{}/{}/default", infoPrefix, event.name))
-            .SetDouble(cs::GetPropertyDefault(event.propertyHandle, &status));
-      } else {
-        entry.SetDouble(event.value);
+      if (integerValueEntry) {
+        integerValueEntry.Set(event.value);
       }
       break;
     case CS_PROP_STRING:
-      if (isNew) {
-        entry.SetDefaultString(event.valueStr);
-      } else {
-        entry.SetString(event.valueStr);
+      if (stringValueEntry) {
+        stringValueEntry.Set(event.valueStr);
       }
       break;
     default:
@@ -292,6 +345,28 @@
   }
 }
 
+SourcePublisher::SourcePublisher(Instance& inst,
+                                 std::shared_ptr<nt::NetworkTable> table,
+                                 CS_Source source)
+    : table{table},
+      sourcePublisher{table->GetStringTopic("source").Publish()},
+      descriptionPublisher{table->GetStringTopic("description").Publish()},
+      connectedPublisher{table->GetBooleanTopic("connected").Publish()},
+      streamsPublisher{table->GetStringArrayTopic("streams").Publish()},
+      modeEntry{table->GetStringTopic("mode").GetEntry("")},
+      modesPublisher{table->GetStringArrayTopic("modes").Publish()} {
+  CS_Status status = 0;
+  wpi::SmallString<64> buf;
+  sourcePublisher.Set(MakeSourceValue(source, buf));
+  wpi::SmallString<64> descBuf;
+  descriptionPublisher.Set(cs::GetSourceDescription(source, descBuf, &status));
+  connectedPublisher.Set(cs::IsSourceConnected(source, &status));
+  streamsPublisher.Set(inst.GetSourceStreamValues(source));
+  auto mode = cs::GetSourceVideoMode(source, &status);
+  modeEntry.SetDefault(VideoModeToString(mode));
+  modesPublisher.Set(GetSourceModeValues(source));
+}
+
 Instance::Instance() {
   // We publish sources to NetworkTables using the following structure:
   // "/CameraPublisher/{Source.Name}/" - root
@@ -306,177 +381,88 @@
 
   // Listener for video events
   m_videoListener = cs::VideoListener{
-      [=](const cs::VideoEvent& event) {
+      [=, this](const cs::VideoEvent& event) {
+        std::scoped_lock lock(m_mutex);
         CS_Status status = 0;
         switch (event.kind) {
           case cs::VideoEvent::kSourceCreated: {
             // Create subtable for the camera
             auto table = m_publishTable->GetSubTable(event.name);
-            {
-              std::scoped_lock lock(m_mutex);
-              m_tables.insert(std::make_pair(event.sourceHandle, table));
-            }
-            wpi::SmallString<64> buf;
-            table->GetEntry("source").SetString(
-                MakeSourceValue(event.sourceHandle, buf));
-            wpi::SmallString<64> descBuf;
-            table->GetEntry("description")
-                .SetString(cs::GetSourceDescription(event.sourceHandle, descBuf,
-                                                    &status));
-            table->GetEntry("connected")
-                .SetBoolean(cs::IsSourceConnected(event.sourceHandle, &status));
-            table->GetEntry("streams").SetStringArray(
-                GetSourceStreamValues(event.sourceHandle));
-            auto mode = cs::GetSourceVideoMode(event.sourceHandle, &status);
-            table->GetEntry("mode").SetDefaultString(VideoModeToString(mode));
-            table->GetEntry("modes").SetStringArray(
-                GetSourceModeValues(event.sourceHandle));
+            m_publishers.insert(
+                {event.sourceHandle,
+                 SourcePublisher{*this, table, event.sourceHandle}});
             break;
           }
-          case cs::VideoEvent::kSourceDestroyed: {
-            auto table = GetSourceTable(event.sourceHandle);
-            if (table) {
-              table->GetEntry("source").SetString("");
-              table->GetEntry("streams").SetStringArray(
-                  std::vector<std::string>{});
-              table->GetEntry("modes").SetStringArray(
-                  std::vector<std::string>{});
-            }
+          case cs::VideoEvent::kSourceDestroyed:
+            m_publishers.erase(event.sourceHandle);
             break;
-          }
-          case cs::VideoEvent::kSourceConnected: {
-            auto table = GetSourceTable(event.sourceHandle);
-            if (table) {
+          case cs::VideoEvent::kSourceConnected:
+            if (auto publisher = GetPublisher(event.sourceHandle)) {
               // update the description too (as it may have changed)
               wpi::SmallString<64> descBuf;
-              table->GetEntry("description")
-                  .SetString(cs::GetSourceDescription(event.sourceHandle,
-                                                      descBuf, &status));
-              table->GetEntry("connected").SetBoolean(true);
+              publisher->descriptionPublisher.Set(cs::GetSourceDescription(
+                  event.sourceHandle, descBuf, &status));
+              publisher->connectedPublisher.Set(true);
             }
             break;
-          }
-          case cs::VideoEvent::kSourceDisconnected: {
-            auto table = GetSourceTable(event.sourceHandle);
-            if (table) {
-              table->GetEntry("connected").SetBoolean(false);
+          case cs::VideoEvent::kSourceDisconnected:
+            if (auto publisher = GetPublisher(event.sourceHandle)) {
+              publisher->connectedPublisher.Set(false);
             }
             break;
-          }
-          case cs::VideoEvent::kSourceVideoModesUpdated: {
-            auto table = GetSourceTable(event.sourceHandle);
-            if (table) {
-              table->GetEntry("modes").SetStringArray(
+          case cs::VideoEvent::kSourceVideoModesUpdated:
+            if (auto publisher = GetPublisher(event.sourceHandle)) {
+              publisher->modesPublisher.Set(
                   GetSourceModeValues(event.sourceHandle));
             }
             break;
-          }
-          case cs::VideoEvent::kSourceVideoModeChanged: {
-            auto table = GetSourceTable(event.sourceHandle);
-            if (table) {
-              table->GetEntry("mode").SetString(VideoModeToString(event.mode));
+          case cs::VideoEvent::kSourceVideoModeChanged:
+            if (auto publisher = GetPublisher(event.sourceHandle)) {
+              publisher->modeEntry.Set(VideoModeToString(event.mode));
             }
             break;
-          }
-          case cs::VideoEvent::kSourcePropertyCreated: {
-            auto table = GetSourceTable(event.sourceHandle);
-            if (table) {
-              PutSourcePropertyValue(table.get(), event, true);
+          case cs::VideoEvent::kSourcePropertyCreated:
+            if (auto publisher = GetPublisher(event.sourceHandle)) {
+              publisher->properties.insert(
+                  {event.propertyHandle,
+                   PropertyPublisher{*publisher->table, event}});
             }
             break;
-          }
-          case cs::VideoEvent::kSourcePropertyValueUpdated: {
-            auto table = GetSourceTable(event.sourceHandle);
-            if (table) {
-              PutSourcePropertyValue(table.get(), event, false);
+          case cs::VideoEvent::kSourcePropertyValueUpdated:
+            if (auto publisher = GetPublisher(event.sourceHandle)) {
+              auto ppIt = publisher->properties.find(event.propertyHandle);
+              if (ppIt != publisher->properties.end()) {
+                ppIt->second.Update(event);
+              }
             }
             break;
-          }
-          case cs::VideoEvent::kSourcePropertyChoicesUpdated: {
-            auto table = GetSourceTable(event.sourceHandle);
-            if (table) {
-              auto choices =
-                  cs::GetEnumPropertyChoices(event.propertyHandle, &status);
-              table
-                  ->GetEntry(fmt::format("PropertyInfo/{}/choices", event.name))
-                  .SetStringArray(choices);
+          case cs::VideoEvent::kSourcePropertyChoicesUpdated:
+            if (auto publisher = GetPublisher(event.sourceHandle)) {
+              auto ppIt = publisher->properties.find(event.propertyHandle);
+              if (ppIt != publisher->properties.end() &&
+                  ppIt->second.choicesTopic) {
+                auto choices =
+                    cs::GetEnumPropertyChoices(event.propertyHandle, &status);
+                if (!ppIt->second.choicesPublisher) {
+                  ppIt->second.choicesPublisher =
+                      ppIt->second.choicesTopic.Publish();
+                }
+                ppIt->second.choicesPublisher.Set(choices);
+              }
             }
             break;
-          }
           case cs::VideoEvent::kSinkSourceChanged:
           case cs::VideoEvent::kSinkCreated:
           case cs::VideoEvent::kSinkDestroyed:
-          case cs::VideoEvent::kNetworkInterfacesChanged: {
+          case cs::VideoEvent::kNetworkInterfacesChanged:
             m_addresses = cs::GetNetworkInterfaces();
             UpdateStreamValues();
             break;
-          }
           default:
             break;
         }
       },
       0x4fff, true};
-
-  // Listener for NetworkTable events
-  // We don't currently support changing settings via NT due to
-  // synchronization issues, so just update to current setting if someone
-  // else tries to change it.
-  wpi::SmallString<64> buf;
-  m_tableListener = nt::NetworkTableInstance::GetDefault().AddEntryListener(
-      fmt::format("{}/", kPublishName),
-      [=](const nt::EntryNotification& event) {
-        auto relativeKey = wpi::drop_front(
-            event.name, std::string_view{kPublishName}.size() + 1);
-
-        // get source (sourceName/...)
-        auto subKeyIndex = relativeKey.find('/');
-        if (subKeyIndex == std::string_view::npos) {
-          return;
-        }
-        auto sourceName = wpi::slice(relativeKey, 0, subKeyIndex);
-        auto sourceIt = m_sources.find(sourceName);
-        if (sourceIt == m_sources.end()) {
-          return;
-        }
-
-        // get subkey
-        relativeKey.remove_prefix(subKeyIndex + 1);
-
-        // handle standard names
-        std::string_view propName;
-        nt::NetworkTableEntry entry{event.entry};
-        if (relativeKey == "mode") {
-          // reset to current mode
-          entry.SetString(VideoModeToString(sourceIt->second.GetVideoMode()));
-          return;
-        } else if (wpi::starts_with(relativeKey, "Property/")) {
-          propName = wpi::substr(relativeKey, 9);
-        } else if (wpi::starts_with(relativeKey, "RawProperty/")) {
-          propName = wpi::substr(relativeKey, 12);
-        } else {
-          return;  // ignore
-        }
-
-        // everything else is a property
-        auto property = sourceIt->second.GetProperty(propName);
-        switch (property.GetKind()) {
-          case cs::VideoProperty::kNone:
-            return;
-          case cs::VideoProperty::kBoolean:
-            entry.SetBoolean(property.Get() != 0);
-            return;
-          case cs::VideoProperty::kInteger:
-          case cs::VideoProperty::kEnum:
-            entry.SetDouble(property.Get());
-            return;
-          case cs::VideoProperty::kString:
-            entry.SetString(property.GetString());
-            return;
-          default:
-            return;
-        }
-      },
-      NT_NOTIFY_IMMEDIATE | NT_NOTIFY_UPDATE);
 }
 
 cs::UsbCamera CameraServer::StartAutomaticCapture() {
@@ -525,7 +511,7 @@
   return AddAxisCamera("Axis Camera", host);
 }
 
-cs::AxisCamera CameraServer::AddAxisCamera(wpi::span<const std::string> hosts) {
+cs::AxisCamera CameraServer::AddAxisCamera(std::span<const std::string> hosts) {
   return AddAxisCamera("Axis Camera", hosts);
 }
 
@@ -557,7 +543,7 @@
 }
 
 cs::AxisCamera CameraServer::AddAxisCamera(std::string_view name,
-                                           wpi::span<const std::string> hosts) {
+                                           std::span<const std::string> hosts) {
   cs::AxisCamera camera{name, hosts};
   StartAutomaticCapture(camera);
   auto csShared = GetCameraServerShared();
@@ -615,7 +601,7 @@
       if (kind != cs::VideoSink::kCv) {
         auto csShared = GetCameraServerShared();
         csShared->SetCameraServerError("expected OpenCV sink, but got {}",
-                                       kind);
+                                       static_cast<int>(kind));
         return cs::CvSink{};
       }
       return *static_cast<cs::CvSink*>(&it->second);
diff --git a/third_party/allwpilib/cameraserver/src/main/native/include/cameraserver/CameraServer.h b/third_party/allwpilib/cameraserver/src/main/native/include/cameraserver/CameraServer.h
index 6d087e9..f47d8aa 100644
--- a/third_party/allwpilib/cameraserver/src/main/native/include/cameraserver/CameraServer.h
+++ b/third_party/allwpilib/cameraserver/src/main/native/include/cameraserver/CameraServer.h
@@ -6,12 +6,10 @@
 
 #include <stdint.h>
 
+#include <span>
 #include <string>
 #include <string_view>
 
-#include <wpi/deprecated.h>
-#include <wpi/span.h>
-
 #include "cscore.h"
 #include "cscore_cv.h"
 
@@ -30,13 +28,6 @@
   static constexpr int kSize160x120 = 2;
 
   /**
-   * Get the CameraServer instance.
-   * @deprecated Use the static methods
-   */
-  WPI_DEPRECATED("Use static methods")
-  static CameraServer* GetInstance();
-
-  /**
    * Start automatically capturing images to send to the dashboard.
    *
    * You should call this method to see a camera feed on the dashboard. If you
@@ -118,7 +109,7 @@
    *
    * @param hosts Array of Camera host IPs/DNS names
    */
-  static cs::AxisCamera AddAxisCamera(wpi::span<const std::string> hosts);
+  static cs::AxisCamera AddAxisCamera(std::span<const std::string> hosts);
 
   /**
    * Adds an Axis IP camera.
@@ -163,7 +154,7 @@
    * @param hosts Array of Camera host IPs/DNS names
    */
   static cs::AxisCamera AddAxisCamera(std::string_view name,
-                                      wpi::span<const std::string> hosts);
+                                      std::span<const std::string> hosts);
 
   /**
    * Adds an Axis IP camera.
diff --git a/third_party/allwpilib/cameraserver/src/main/native/include/cameraserver/CameraServerShared.h b/third_party/allwpilib/cameraserver/src/main/native/include/cameraserver/CameraServerShared.h
index f6c6ae7..a95d322 100644
--- a/third_party/allwpilib/cameraserver/src/main/native/include/cameraserver/CameraServerShared.h
+++ b/third_party/allwpilib/cameraserver/src/main/native/include/cameraserver/CameraServerShared.h
@@ -27,20 +27,17 @@
 
   template <typename S, typename... Args>
   inline void SetCameraServerError(const S& format, Args&&... args) {
-    SetCameraServerErrorV(format,
-                          fmt::make_args_checked<Args...>(format, args...));
+    SetCameraServerErrorV(format, fmt::make_format_args(args...));
   }
 
   template <typename S, typename... Args>
   inline void SetVisionRunnerError(const S& format, Args&&... args) {
-    SetVisionRunnerErrorV(format,
-                          fmt::make_args_checked<Args...>(format, args...));
+    SetVisionRunnerErrorV(format, fmt::make_format_args(args...));
   }
 
   template <typename S, typename... Args>
   inline void ReportDriverStationError(const S& format, Args&&... args) {
-    ReportDriverStationErrorV(format,
-                              fmt::make_args_checked<Args...>(format, args...));
+    ReportDriverStationErrorV(format, fmt::make_format_args(args...));
   }
 };
 
diff --git a/third_party/allwpilib/cmake/modules/CompileWarnings.cmake b/third_party/allwpilib/cmake/modules/CompileWarnings.cmake
index b9d1ab8..93b35b8 100644
--- a/third_party/allwpilib/cmake/modules/CompileWarnings.cmake
+++ b/third_party/allwpilib/cmake/modules/CompileWarnings.cmake
@@ -1,7 +1,15 @@
 macro(wpilib_target_warnings target)
     if(NOT MSVC)
-        target_compile_options(${target} PRIVATE -Wall -pedantic -Wextra -Werror -Wno-unused-parameter -Wno-error=deprecated-declarations ${WPILIB_TARGET_WARNINGS})
+        target_compile_options(${target} PRIVATE -Wall -pedantic -Wextra -Werror -Wno-unused-parameter ${WPILIB_TARGET_WARNINGS})
     else()
-        target_compile_options(${target} PRIVATE /wd4146 /wd4244 /wd4251 /wd4267 /wd4996 /WX ${WPILIB_TARGET_WARNINGS})
+        target_compile_options(${target} PRIVATE /wd4146 /wd4244 /wd4251 /wd4267 /WX /D_CRT_SECURE_NO_WARNINGS ${WPILIB_TARGET_WARNINGS})
+    endif()
+
+    # Suppress C++-specific OpenCV warning; C compiler rejects it with an error
+    # https://github.com/opencv/opencv/issues/20269
+    if(UNIX AND NOT APPLE)
+        target_compile_options(${target} PRIVATE $<$<COMPILE_LANGUAGE:CXX>:-Wno-deprecated-enum-enum-conversion>)
+    elseif(UNIX AND APPLE)
+        target_compile_options(${target} PRIVATE $<$<COMPILE_LANGUAGE:CXX>:-Wno-deprecated-anon-enum-enum-conversion>)
     endif()
 endmacro()
diff --git a/third_party/allwpilib/cmake/modules/FindLIBSSH.cmake b/third_party/allwpilib/cmake/modules/FindLIBSSH.cmake
index 1c09818..ba2d778 100644
--- a/third_party/allwpilib/cmake/modules/FindLIBSSH.cmake
+++ b/third_party/allwpilib/cmake/modules/FindLIBSSH.cmake
@@ -110,7 +110,7 @@
     set(LIBSSH_LIBRARIES ${LIBSSH_LIBRARY} ${LIBSSH_THREADS_LIBRARY})
     mark_as_advanced(LIBSSH_INCLUDE_DIRS LIBSSH_LIBRARIES)
 
-    find_package_handle_standard_args(LibSSH FOUND_VAR LIBSSH_FOUND
+    find_package_handle_standard_args(LIBSSH FOUND_VAR LIBSSH_FOUND
         REQUIRED_VARS LIBSSH_INCLUDE_DIRS LIBSSH_LIBRARIES
         VERSION_VAR LIBSSH_VERSION)
 endif()
diff --git a/third_party/allwpilib/cmake/toolchains/gnu.toolchain.cmake b/third_party/allwpilib/cmake/toolchains/gnu.toolchain.cmake
index 95156a5..b21dad2 100644
--- a/third_party/allwpilib/cmake/toolchains/gnu.toolchain.cmake
+++ b/third_party/allwpilib/cmake/toolchains/gnu.toolchain.cmake
@@ -1,4 +1,4 @@
-cmake_minimum_required(VERSION 2.8)
+cmake_minimum_required(VERSION 3.3.0)
 
 # load settings in case of "try compile"
 set(TOOLCHAIN_CONFIG_FILE "${WPILIB_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/toolchain.config.cmake")
diff --git a/third_party/allwpilib/crossConnIntegrationTests/build.gradle b/third_party/allwpilib/crossConnIntegrationTests/build.gradle
index 8775359..1c55e1b 100644
--- a/third_party/allwpilib/crossConnIntegrationTests/build.gradle
+++ b/third_party/allwpilib/crossConnIntegrationTests/build.gradle
@@ -84,13 +84,9 @@
                             }
                         }
                     }
-                    binary.tasks.withType(CppCompile) {
-                        cppCompiler.args "-Wno-missing-field-initializers"
-                        cppCompiler.args "-Wno-unused-variable"
-                        cppCompiler.args "-Wno-error=deprecated-declarations"
-                    }
                     project(':hal').addHalDependency(binary, 'shared')
                     project(':hal').addHalJniDependency(binary)
+                    lib project: ':wpinet', library: 'wpinet', linkage: 'shared'
                     lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
                     if (binary.targetPlatform.name == nativeUtils.wpi.platforms.roborio) {
                         nativeUtils.useRequiredLibrary(binary, 'ni_link_libraries', 'ni_runtime_libraries')
diff --git a/third_party/allwpilib/crossConnIntegrationTests/src/main/native/cpp/PWMTest.cpp b/third_party/allwpilib/crossConnIntegrationTests/src/main/native/cpp/PWMTest.cpp
index 27fcce7..316234a 100644
--- a/third_party/allwpilib/crossConnIntegrationTests/src/main/native/cpp/PWMTest.cpp
+++ b/third_party/allwpilib/crossConnIntegrationTests/src/main/native/cpp/PWMTest.cpp
@@ -100,8 +100,9 @@
       auto value = HAL_GetDMASampleDigitalSource(&dmaSamples[startIndex],
                                                  dioHandle, &status);
       ASSERT_EQ(0, status);
-      if (value)
+      if (value) {
         break;
+      }
       startIndex++;
     }
     ASSERT_LT(startIndex, 6);
diff --git a/third_party/allwpilib/crossConnIntegrationTests/src/main/native/cpp/TestEnvironment.cpp b/third_party/allwpilib/crossConnIntegrationTests/src/main/native/cpp/TestEnvironment.cpp
index ee8c2b1..458046c 100644
--- a/third_party/allwpilib/crossConnIntegrationTests/src/main/native/cpp/TestEnvironment.cpp
+++ b/third_party/allwpilib/crossConnIntegrationTests/src/main/native/cpp/TestEnvironment.cpp
@@ -49,6 +49,7 @@
       HAL_GetControlWord(&controlWord);
       return controlWord.enabled && controlWord.dsAttached;
     };
+    HAL_RefreshDSData();
     while (!checkEnabled()) {
       if (enableCounter > 50) {
         // Robot did not enable properly after 5 seconds.
@@ -60,6 +61,7 @@
       std::this_thread::sleep_for(100ms);
 
       fmt::print("Waiting for enable: {}\n", enableCounter++);
+      HAL_RefreshDSData();
     }
     std::this_thread::sleep_for(500ms);
   }
diff --git a/third_party/allwpilib/crossConnIntegrationTests/src/main/native/cpp/mockds/MockDS.cpp b/third_party/allwpilib/crossConnIntegrationTests/src/main/native/cpp/mockds/MockDS.cpp
index b2e5c2d..2e53a9a 100644
--- a/third_party/allwpilib/crossConnIntegrationTests/src/main/native/cpp/mockds/MockDS.cpp
+++ b/third_party/allwpilib/crossConnIntegrationTests/src/main/native/cpp/mockds/MockDS.cpp
@@ -12,7 +12,7 @@
 #include <hal/cpp/fpga_clock.h>
 #include <wpi/Logger.h>
 #include <wpi/SmallVector.h>
-#include <wpi/UDPClient.h>
+#include <wpinet/UDPClient.h>
 
 static void LoggerFunc(unsigned int level, const char* file, unsigned int line,
                        const char* msg) {
diff --git a/third_party/allwpilib/crossConnIntegrationTests/src/main/native/include/LifetimeWrappers.h b/third_party/allwpilib/crossConnIntegrationTests/src/main/native/include/LifetimeWrappers.h
index 9f0eb15..5731200 100644
--- a/third_party/allwpilib/crossConnIntegrationTests/src/main/native/include/LifetimeWrappers.h
+++ b/third_party/allwpilib/crossConnIntegrationTests/src/main/native/include/LifetimeWrappers.h
@@ -194,6 +194,7 @@
   do {                                                               \
     ASSERT_EQ(status, HAL_USE_LAST_ERROR);                           \
     const char* lastErrorMessageInMacro = HAL_GetLastError(&status); \
+    static_cast<void>(lastErrorMessageInMacro);                      \
     ASSERT_EQ(status, x);                                            \
   } while (0)
 
diff --git a/third_party/allwpilib/cscore/.styleguide b/third_party/allwpilib/cscore/.styleguide
index f0732e1..dadecd2 100644
--- a/third_party/allwpilib/cscore/.styleguide
+++ b/third_party/allwpilib/cscore/.styleguide
@@ -13,6 +13,10 @@
   \.cpp$
 }
 
+modifiableFileExclude {
+  objcpp
+}
+
 licenseUpdateExclude {
   src/main/native/cpp/default_init_allocator\.h$
 }
@@ -36,4 +40,5 @@
   ^support/
   ^tcpsockets/
   ^wpi/
+  ^wpinet/
 }
diff --git a/third_party/allwpilib/cscore/CMakeLists.txt b/third_party/allwpilib/cscore/CMakeLists.txt
index 9ab9ca7..af0d803 100644
--- a/third_party/allwpilib/cscore/CMakeLists.txt
+++ b/third_party/allwpilib/cscore/CMakeLists.txt
@@ -11,6 +11,7 @@
     cscore_native_src src/main/native/cpp/*.cpp)
 file(GLOB cscore_linux_src src/main/native/linux/*.cpp)
 file(GLOB cscore_osx_src src/main/native/osx/*.cpp)
+file(GLOB cscore_osx_objc_src src/main/native/objcpp/*.mm)
 file(GLOB cscore_windows_src src/main/native/windows/*.cpp)
 
 add_library(cscore ${cscore_native_src})
@@ -18,7 +19,9 @@
 
 if(NOT MSVC)
     if (APPLE)
-        target_sources(cscore PRIVATE ${cscore_osx_src})
+        target_sources(cscore PRIVATE ${cscore_osx_src} ${cscore_osx_objc_src})
+        target_compile_options(cscore PRIVATE "-fobjc-arc")
+        set_target_properties(cscore PROPERTIES LINK_FLAGS "-framework CoreFoundation -framework AVFoundation -framework Foundation -framework CoreMedia -framework CoreVideo")
     else()
         target_sources(cscore PRIVATE ${cscore_linux_src})
     endif()
@@ -33,7 +36,7 @@
                             $<INSTALL_INTERFACE:${include_dest}/cscore>)
 target_include_directories(cscore PRIVATE src/main/native/cpp)
 wpilib_target_warnings(cscore)
-target_link_libraries(cscore PUBLIC wpiutil ${OpenCV_LIBS})
+target_link_libraries(cscore PUBLIC wpinet wpiutil ${OpenCV_LIBS})
 
 set_property(TARGET cscore PROPERTY FOLDER "libraries")
 
diff --git a/third_party/allwpilib/cscore/build.gradle b/third_party/allwpilib/cscore/build.gradle
index cd03465..a656731 100644
--- a/third_party/allwpilib/cscore/build.gradle
+++ b/third_party/allwpilib/cscore/build.gradle
@@ -2,16 +2,16 @@
 
 ext {
     nativeName = 'cscore'
-    devMain = 'edu.wpi.cscore.DevMain'
+    devMain = 'edu.wpi.first.cscore.DevMain'
 }
 
 // Removed because having the objective-cpp plugin added breaks
 // embedded tools and its toolchain check. It causes an obj-cpp
 // source set to be added to all binaries, even cross binaries
 // with no support.
-// if (OperatingSystem.current().isMacOsX()) {
-//     apply plugin: 'objective-cpp'
-// }
+if (OperatingSystem.current().isMacOsX()) {
+    apply plugin: 'objective-cpp'
+}
 
 apply from: "${rootDir}/shared/jni/setupBuild.gradle"
 
@@ -23,8 +23,8 @@
             enableCheckTask true
             javaCompileTasks << compileJava
             jniCrossCompileOptions << JniCrossCompileOptions(nativeUtils.wpi.platforms.roborio)
-            jniCrossCompileOptions << JniCrossCompileOptions(nativeUtils.wpi.platforms.raspbian)
-            jniCrossCompileOptions << JniCrossCompileOptions(nativeUtils.wpi.platforms.aarch64bionic)
+            jniCrossCompileOptions << JniCrossCompileOptions(nativeUtils.wpi.platforms.linuxarm32)
+            jniCrossCompileOptions << JniCrossCompileOptions(nativeUtils.wpi.platforms.linuxarm64)
 
             sources {
                 cpp {
@@ -45,6 +45,7 @@
                     return
                 }
                 lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+                lib project: ':wpinet', library: 'wpinet', linkage: 'shared'
 
                 if (it.targetPlatform.operatingSystem.linux) {
                     it.linker.args '-Wl,--version-script=' + file('src/main/native/LinuxSymbolScript.txt')
@@ -55,6 +56,20 @@
             }
         }
     }
+    binaries {
+        all {
+            if (!it.buildable || !(it instanceof NativeBinarySpec)) {
+                return
+            }
+            if (it.component.name == "${nativeName}JNI") {
+                lib project: ':wpinet', library: 'wpinet', linkage: 'static'
+                lib project: ':wpiutil', library: 'wpiutil', linkage: 'static'
+            } else {
+                lib project: ':wpinet', library: 'wpinet', linkage: 'shared'
+                lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+            }
+        }
+    }
 }
 
 
@@ -72,16 +87,16 @@
     splitSetup = {
         if (it.targetPlatform.operatingSystem.isMacOsX()) {
             it.sources {
-                // macObjCpp(ObjectiveCppSourceSet) {
-                //     source {
-                //         srcDirs = ['src/main/native/objcpp']
-                //         include '**/*.mm'
-                //     }
-                //     exportedHeaders {
-                //         srcDirs 'src/main/native/include'
-                //         include '**/*.h'
-                //     }
-                // }
+                macObjCpp(ObjectiveCppSourceSet) {
+                    source {
+                        srcDirs = ['src/main/native/objcpp']
+                        include '**/*.mm'
+                    }
+                    exportedHeaders {
+                        srcDirs 'src/main/native/include', 'src/main/native/cpp'
+                        include '**/*.h'
+                    }
+                }
                 cscoreMacCpp(CppSourceSet) {
                     source {
                         srcDirs 'src/main/native/osx'
@@ -142,21 +157,14 @@
     symbols.removeIf({ !it.startsWith('CS_') })
 } as Action<List<String>>;
 
+run {
+    if (OperatingSystem.current().isMacOsX()) {
+        jvmArgs("-XstartOnFirstThread");
+    }
+}
+
 nativeUtils.exportsConfigs {
     cscore {
-        x86ExcludeSymbols = [
-            '_CT??_R0?AV_System_error',
-            '_CT??_R0?AVexception',
-            '_CT??_R0?AVfailure',
-            '_CT??_R0?AVruntime_error',
-            '_CT??_R0?AVsystem_error',
-            '_CTA5?AVfailure',
-            '_TI5?AVfailure',
-            '_CT??_R0?AVout_of_range',
-            '_CTA3?AVout_of_range',
-            '_TI3?AVout_of_range',
-            '_CT??_R0?AVbad_cast'
-        ]
         x64ExcludeSymbols = [
             '_CT??_R0?AV_System_error',
             '_CT??_R0?AVexception',
@@ -172,28 +180,29 @@
         ]
     }
     cscoreJNI {
-        x86SymbolFilter = symbolFilter
         x64SymbolFilter = symbolFilter
     }
     cscoreJNICvStatic {
-        x86SymbolFilter = symbolFilter
         x64SymbolFilter = symbolFilter
     }
 }
 
+apply from: "${rootDir}/shared/imgui.gradle"
+
 model {
     components {
         examplesMap.each { key, value ->
             if (key == "usbviewer") {
-                if (!project.hasProperty('onlylinuxathena') && !project.hasProperty('onlylinuxraspbian') && !project.hasProperty('onlylinuxaarch64bionic')) {
+                if (!project.hasProperty('onlylinuxathena')) {
                     "${key}"(NativeExecutableSpec) {
                         targetBuildTypes 'debug'
                         binaries.all {
                             lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+                            lib project: ':wpinet', library: 'wpinet', linkage: 'shared'
                             lib project: ':wpigui', library: 'wpigui', linkage: 'static'
                             lib library: 'cscore', linkage: 'shared'
-                            nativeUtils.useRequiredLibrary(it, 'imgui_static')
-                            if (it.targetPlatform.name == nativeUtils.wpi.platforms.roborio || it.targetPlatform.name == nativeUtils.wpi.platforms.raspbian || it.targetPlatform.name == nativeUtils.wpi.platforms.aarch64bionic) {
+                            nativeUtils.useRequiredLibrary(it, 'imgui')
+                            if (it.targetPlatform.name == nativeUtils.wpi.platforms.roborio) {
                                 it.buildable = false
                                 return
                             }
@@ -203,6 +212,9 @@
                                 it.linker.args << '-framework' << 'Metal' << '-framework' << 'MetalKit' << '-framework' << 'Cocoa' << '-framework' << 'IOKit' << '-framework' << 'CoreFoundation' << '-framework' << 'CoreVideo' << '-framework' << 'QuartzCore'
                             } else {
                                 it.linker.args << '-lX11'
+                                if (it.targetPlatform.name.startsWith('linuxarm')) {
+                                    it.linker.args << '-lGL'
+                                }
                             }
                         }
                         sources {
@@ -220,6 +232,7 @@
                     targetBuildTypes 'debug'
                     binaries.all {
                         lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+                        lib project: ':wpinet', library: 'wpinet', linkage: 'shared'
                         lib library: 'cscore', linkage: 'shared'
                     }
                     sources {
diff --git a/third_party/allwpilib/cscore/src/main/java/edu/wpi/first/cscore/CameraServerJNI.java b/third_party/allwpilib/cscore/src/main/java/edu/wpi/first/cscore/CameraServerJNI.java
index fe46baf..37f35b0 100644
--- a/third_party/allwpilib/cscore/src/main/java/edu/wpi/first/cscore/CameraServerJNI.java
+++ b/third_party/allwpilib/cscore/src/main/java/edu/wpi/first/cscore/CameraServerJNI.java
@@ -390,4 +390,10 @@
   public static native long allocateRawFrame();
 
   public static native void freeRawFrame(long frame);
+
+  public static native void runMainRunLoop();
+
+  public static native int runMainRunLoopTimeout(double timeoutSeconds);
+
+  public static native void stopMainRunLoop();
 }
diff --git a/third_party/allwpilib/cscore/src/main/java/edu/wpi/first/cscore/UsbCameraInfo.java b/third_party/allwpilib/cscore/src/main/java/edu/wpi/first/cscore/UsbCameraInfo.java
index df856e8..04b1229 100644
--- a/third_party/allwpilib/cscore/src/main/java/edu/wpi/first/cscore/UsbCameraInfo.java
+++ b/third_party/allwpilib/cscore/src/main/java/edu/wpi/first/cscore/UsbCameraInfo.java
@@ -5,6 +5,7 @@
 package edu.wpi.first.cscore;
 
 /** USB camera information. */
+@SuppressWarnings("MemberName")
 public class UsbCameraInfo {
   /**
    * Create a new set of UsbCameraInfo.
@@ -28,26 +29,20 @@
   }
 
   /** Device number (e.g. N in '/dev/videoN' on Linux). */
-  @SuppressWarnings("MemberName")
   public int dev;
 
   /** Path to device if available (e.g. '/dev/video0' on Linux). */
-  @SuppressWarnings("MemberName")
   public String path;
 
   /** Vendor/model name of the camera as provided by the USB driver. */
-  @SuppressWarnings("MemberName")
   public String name;
 
   /** Other path aliases to device (e.g. '/dev/v4l/by-id/...' etc on Linux). */
-  @SuppressWarnings("MemberName")
   public String[] otherPaths;
 
   /** USB vendor id. */
-  @SuppressWarnings("MemberName")
   public int vendorId;
 
   /** USB product id. */
-  @SuppressWarnings("MemberName")
   public int productId;
 }
diff --git a/third_party/allwpilib/cscore/src/main/java/edu/wpi/first/cscore/VideoEvent.java b/third_party/allwpilib/cscore/src/main/java/edu/wpi/first/cscore/VideoEvent.java
index 50f041c..0c60d6d 100644
--- a/third_party/allwpilib/cscore/src/main/java/edu/wpi/first/cscore/VideoEvent.java
+++ b/third_party/allwpilib/cscore/src/main/java/edu/wpi/first/cscore/VideoEvent.java
@@ -5,6 +5,7 @@
 package edu.wpi.first.cscore;
 
 /** Video event. */
+@SuppressWarnings("MemberName")
 public class VideoEvent {
   public enum Kind {
     kUnknown(0x0000),
@@ -117,39 +118,29 @@
     this.listener = listener;
   }
 
-  @SuppressWarnings("MemberName")
   public Kind kind;
 
   // Valid for kSource* and kSink* respectively
-  @SuppressWarnings("MemberName")
   public int sourceHandle;
 
-  @SuppressWarnings("MemberName")
   public int sinkHandle;
 
   // Source/sink/property name
-  @SuppressWarnings("MemberName")
   public String name;
 
   // Fields for kSourceVideoModeChanged event
-  @SuppressWarnings("MemberName")
   public VideoMode mode;
 
   // Fields for kSourceProperty* events
-  @SuppressWarnings("MemberName")
   public int propertyHandle;
 
-  @SuppressWarnings("MemberName")
   public VideoProperty.Kind propertyKind;
 
-  @SuppressWarnings("MemberName")
   public int value;
 
-  @SuppressWarnings("MemberName")
   public String valueStr;
 
   // Listener that was triggered
-  @SuppressWarnings("MemberName")
   public int listener;
 
   public VideoSource getSource() {
diff --git a/third_party/allwpilib/cscore/src/main/java/edu/wpi/first/cscore/VideoListener.java b/third_party/allwpilib/cscore/src/main/java/edu/wpi/first/cscore/VideoListener.java
index 0d77461..652d12d 100644
--- a/third_party/allwpilib/cscore/src/main/java/edu/wpi/first/cscore/VideoListener.java
+++ b/third_party/allwpilib/cscore/src/main/java/edu/wpi/first/cscore/VideoListener.java
@@ -64,7 +64,6 @@
   private static boolean s_waitQueue;
   private static final Condition s_waitQueueCond = s_lock.newCondition();
 
-  @SuppressWarnings("PMD.AvoidCatchingThrowable")
   private static void startThread() {
     s_thread =
         new Thread(
diff --git a/third_party/allwpilib/cscore/src/main/java/edu/wpi/first/cscore/VideoMode.java b/third_party/allwpilib/cscore/src/main/java/edu/wpi/first/cscore/VideoMode.java
index 726b210..012874d 100644
--- a/third_party/allwpilib/cscore/src/main/java/edu/wpi/first/cscore/VideoMode.java
+++ b/third_party/allwpilib/cscore/src/main/java/edu/wpi/first/cscore/VideoMode.java
@@ -5,6 +5,7 @@
 package edu.wpi.first.cscore;
 
 /** Video mode. */
+@SuppressWarnings("MemberName")
 public class VideoMode {
   public enum PixelFormat {
     kUnknown(0),
@@ -12,7 +13,9 @@
     kYUYV(2),
     kRGB565(3),
     kBGR(4),
-    kGray(5);
+    kGray(5),
+    kY16(6),
+    kUYVY(7);
 
     private final int value;
 
@@ -62,18 +65,14 @@
   }
 
   /** Pixel format. */
-  @SuppressWarnings("MemberName")
   public PixelFormat pixelFormat;
 
   /** Width in pixels. */
-  @SuppressWarnings("MemberName")
   public int width;
 
   /** Height in pixels. */
-  @SuppressWarnings("MemberName")
   public int height;
 
   /** Frames per second. */
-  @SuppressWarnings("MemberName")
   public int fps;
 }
diff --git a/third_party/allwpilib/cscore/src/main/native/cpp/ConfigurableSourceImpl.cpp b/third_party/allwpilib/cscore/src/main/native/cpp/ConfigurableSourceImpl.cpp
index 16452f1..48677a6 100644
--- a/third_party/allwpilib/cscore/src/main/native/cpp/ConfigurableSourceImpl.cpp
+++ b/third_party/allwpilib/cscore/src/main/native/cpp/ConfigurableSourceImpl.cpp
@@ -88,7 +88,7 @@
 }
 
 void ConfigurableSourceImpl::SetEnumPropertyChoices(
-    int property, wpi::span<const std::string> choices, CS_Status* status) {
+    int property, std::span<const std::string> choices, CS_Status* status) {
   std::scoped_lock lock(m_mutex);
   auto prop = GetProperty(property);
   if (!prop) {
diff --git a/third_party/allwpilib/cscore/src/main/native/cpp/ConfigurableSourceImpl.h b/third_party/allwpilib/cscore/src/main/native/cpp/ConfigurableSourceImpl.h
index bb9f3ed..31236f5 100644
--- a/third_party/allwpilib/cscore/src/main/native/cpp/ConfigurableSourceImpl.h
+++ b/third_party/allwpilib/cscore/src/main/native/cpp/ConfigurableSourceImpl.h
@@ -8,12 +8,11 @@
 #include <atomic>
 #include <functional>
 #include <memory>
+#include <span>
 #include <string>
 #include <string_view>
 #include <vector>
 
-#include <wpi/span.h>
-
 #include "SourceImpl.h"
 
 namespace cs {
@@ -42,7 +41,7 @@
                      int maximum, int step, int defaultValue, int value,
                      std::function<void(CS_Property property)> onChange);
   void SetEnumPropertyChoices(int property,
-                              wpi::span<const std::string> choices,
+                              std::span<const std::string> choices,
                               CS_Status* status);
 
  private:
diff --git a/third_party/allwpilib/cscore/src/main/native/cpp/CvSinkImpl.cpp b/third_party/allwpilib/cscore/src/main/native/cpp/CvSinkImpl.cpp
index dbda6c6..942fdaf 100644
--- a/third_party/allwpilib/cscore/src/main/native/cpp/CvSinkImpl.cpp
+++ b/third_party/allwpilib/cscore/src/main/native/cpp/CvSinkImpl.cpp
@@ -110,7 +110,7 @@
       std::this_thread::sleep_for(std::chrono::seconds(1));
       continue;
     }
-    SDEBUG4("{}", "waiting for frame");
+    SDEBUG4("waiting for frame");
     Frame frame = source->GetNextFrame();  // blocks
     if (!m_active) {
       break;
diff --git a/third_party/allwpilib/cscore/src/main/native/cpp/CvSourceImpl.cpp b/third_party/allwpilib/cscore/src/main/native/cpp/CvSourceImpl.cpp
index 7cd4fe0..511cf6c 100644
--- a/third_party/allwpilib/cscore/src/main/native/cpp/CvSourceImpl.cpp
+++ b/third_party/allwpilib/cscore/src/main/native/cpp/CvSourceImpl.cpp
@@ -139,7 +139,7 @@
 }
 
 void SetSourceEnumPropertyChoices(CS_Source source, CS_Property property,
-                                  wpi::span<const std::string> choices,
+                                  std::span<const std::string> choices,
                                   CS_Status* status) {
   auto data = Instance::GetInstance().GetSource(source);
   if (!data || (data->kind & SourceMask) == 0) {
diff --git a/third_party/allwpilib/cscore/src/main/native/cpp/Frame.cpp b/third_party/allwpilib/cscore/src/main/native/cpp/Frame.cpp
index 0aa1947..e6f8e7c 100644
--- a/third_party/allwpilib/cscore/src/main/native/cpp/Frame.cpp
+++ b/third_party/allwpilib/cscore/src/main/native/cpp/Frame.cpp
@@ -217,7 +217,7 @@
   // Color convert
   switch (pixelFormat) {
     case VideoMode::kRGB565:
-      // If source is YUYV or Gray, need to convert to BGR first
+      // If source is YUYV, UYVY, Gray, or Y16, need to convert to BGR first
       if (cur->pixelFormat == VideoMode::kYUYV) {
         // Check to see if BGR version already exists...
         if (Image* newImage =
@@ -226,6 +226,14 @@
         } else {
           cur = ConvertYUYVToBGR(cur);
         }
+      } else if (cur->pixelFormat == VideoMode::kUYVY) {
+        // Check to see if BGR version already exists...
+        if (Image* newImage =
+                GetExistingImage(cur->width, cur->height, VideoMode::kBGR)) {
+          cur = newImage;
+        } else {
+          cur = ConvertUYVYToBGR(cur);
+        }
       } else if (cur->pixelFormat == VideoMode::kGray) {
         // Check to see if BGR version already exists...
         if (Image* newImage =
@@ -234,18 +242,35 @@
         } else {
           cur = ConvertGrayToBGR(cur);
         }
-      }
-      return ConvertBGRToRGB565(cur);
-    case VideoMode::kGray:
-      // If source is YUYV or RGB565, need to convert to BGR first
-      if (cur->pixelFormat == VideoMode::kYUYV) {
+      } else if (cur->pixelFormat == VideoMode::kY16) {
         // Check to see if BGR version already exists...
         if (Image* newImage =
                 GetExistingImage(cur->width, cur->height, VideoMode::kBGR)) {
           cur = newImage;
+        } else if (Image* newImage = GetExistingImage(cur->width, cur->height,
+                                                      VideoMode::kGray)) {
+          cur = ConvertGrayToBGR(newImage);
         } else {
-          cur = ConvertYUYVToBGR(cur);
+          cur = ConvertGrayToBGR(ConvertY16ToGray(cur));
         }
+      }
+      return ConvertBGRToRGB565(cur);
+    case VideoMode::kGray:
+    case VideoMode::kY16:
+      // If source is also grayscale, convert directly
+      if (pixelFormat == VideoMode::kGray &&
+          cur->pixelFormat == VideoMode::kY16) {
+        return ConvertY16ToGray(cur);
+      } else if (pixelFormat == VideoMode::kY16 &&
+                 cur->pixelFormat == VideoMode::kGray) {
+        return ConvertGrayToY16(cur);
+      }
+      // If source is YUYV, UYVY, convert directly to Gray
+      // If RGB565, need to convert to BGR first
+      if (cur->pixelFormat == VideoMode::kYUYV) {
+        cur = ConvertYUYVToGray(cur);
+      } else if (cur->pixelFormat == VideoMode::kUYVY) {
+        cur = ConvertUYVYToGray(cur);
       } else if (cur->pixelFormat == VideoMode::kRGB565) {
         // Check to see if BGR version already exists...
         if (Image* newImage =
@@ -254,12 +279,18 @@
         } else {
           cur = ConvertRGB565ToBGR(cur);
         }
+        cur = ConvertBGRToGray(cur);
       }
-      return ConvertBGRToGray(cur);
+      if (pixelFormat == VideoMode::kY16) {
+        cur = ConvertGrayToY16(cur);
+      }
+      return cur;
     case VideoMode::kBGR:
     case VideoMode::kMJPEG:
       if (cur->pixelFormat == VideoMode::kYUYV) {
         cur = ConvertYUYVToBGR(cur);
+      } else if (cur->pixelFormat == VideoMode::kUYVY) {
+        cur = ConvertUYVYToBGR(cur);
       } else if (cur->pixelFormat == VideoMode::kRGB565) {
         cur = ConvertRGB565ToBGR(cur);
       } else if (cur->pixelFormat == VideoMode::kGray) {
@@ -268,9 +299,23 @@
         } else {
           return ConvertGrayToMJPEG(cur, defaultJpegQuality);
         }
+      } else if (cur->pixelFormat == VideoMode::kY16) {
+        // Check to see if Gray version already exists...
+        if (Image* newImage =
+                GetExistingImage(cur->width, cur->height, VideoMode::kGray)) {
+          cur = newImage;
+        } else {
+          cur = ConvertY16ToGray(cur);
+        }
+        if (pixelFormat == VideoMode::kBGR) {
+          return ConvertGrayToBGR(cur);
+        } else {
+          return ConvertGrayToMJPEG(cur, defaultJpegQuality);
+        }
       }
       break;
     case VideoMode::kYUYV:
+    case VideoMode::kUYVY:
     default:
       return nullptr;  // Unsupported
   }
@@ -351,6 +396,72 @@
   return rv;
 }
 
+Image* Frame::ConvertYUYVToGray(Image* image) {
+  if (!image || image->pixelFormat != VideoMode::kYUYV) {
+    return nullptr;
+  }
+
+  // Allocate a grayscale image
+  auto newImage =
+      m_impl->source.AllocImage(VideoMode::kGray, image->width, image->height,
+                                image->width * image->height);
+
+  // Convert
+  cv::cvtColor(image->AsMat(), newImage->AsMat(), cv::COLOR_YUV2GRAY_YUYV);
+
+  // Save the result
+  Image* rv = newImage.release();
+  if (m_impl) {
+    std::scoped_lock lock(m_impl->mutex);
+    m_impl->images.push_back(rv);
+  }
+  return rv;
+}
+
+Image* Frame::ConvertUYVYToBGR(Image* image) {
+  if (!image || image->pixelFormat != VideoMode::kUYVY) {
+    return nullptr;
+  }
+
+  // Allocate a BGR image
+  auto newImage =
+      m_impl->source.AllocImage(VideoMode::kBGR, image->width, image->height,
+                                image->width * image->height * 3);
+
+  // Convert
+  cv::cvtColor(image->AsMat(), newImage->AsMat(), cv::COLOR_YUV2BGR_UYVY);
+
+  // Save the result
+  Image* rv = newImage.release();
+  if (m_impl) {
+    std::scoped_lock lock(m_impl->mutex);
+    m_impl->images.push_back(rv);
+  }
+  return rv;
+}
+
+Image* Frame::ConvertUYVYToGray(Image* image) {
+  if (!image || image->pixelFormat != VideoMode::kUYVY) {
+    return nullptr;
+  }
+
+  // Allocate a grayscale image
+  auto newImage =
+      m_impl->source.AllocImage(VideoMode::kGray, image->width, image->height,
+                                image->width * image->height);
+
+  // Convert
+  cv::cvtColor(image->AsMat(), newImage->AsMat(), cv::COLOR_YUV2GRAY_UYVY);
+
+  // Save the result
+  Image* rv = newImage.release();
+  if (m_impl) {
+    std::scoped_lock lock(m_impl->mutex);
+    m_impl->images.push_back(rv);
+  }
+  return rv;
+}
+
 Image* Frame::ConvertBGRToRGB565(Image* image) {
   if (!image || image->pixelFormat != VideoMode::kBGR) {
     return nullptr;
@@ -509,6 +620,50 @@
   return rv;
 }
 
+Image* Frame::ConvertGrayToY16(Image* image) {
+  if (!image || image->pixelFormat != VideoMode::kGray) {
+    return nullptr;
+  }
+
+  // Allocate a Y16 image
+  auto newImage =
+      m_impl->source.AllocImage(VideoMode::kY16, image->width, image->height,
+                                image->width * image->height * 2);
+
+  // Convert with linear scaling
+  image->AsMat().convertTo(newImage->AsMat(), CV_16U, 256);
+
+  // Save the result
+  Image* rv = newImage.release();
+  if (m_impl) {
+    std::scoped_lock lock(m_impl->mutex);
+    m_impl->images.push_back(rv);
+  }
+  return rv;
+}
+
+Image* Frame::ConvertY16ToGray(Image* image) {
+  if (!image || image->pixelFormat != VideoMode::kY16) {
+    return nullptr;
+  }
+
+  // Allocate a Grayscale image
+  auto newImage =
+      m_impl->source.AllocImage(VideoMode::kGray, image->width, image->height,
+                                image->width * image->height);
+
+  // Scale min to 0 and max to 255
+  cv::normalize(image->AsMat(), newImage->AsMat(), 255, 0, cv::NORM_MINMAX);
+
+  // Save the result
+  Image* rv = newImage.release();
+  if (m_impl) {
+    std::scoped_lock lock(m_impl->mutex);
+    m_impl->images.push_back(rv);
+  }
+  return rv;
+}
+
 Image* Frame::GetImageImpl(int width, int height,
                            VideoMode::PixelFormat pixelFormat,
                            int requiredJpegQuality, int defaultJpegQuality) {
@@ -523,7 +678,8 @@
 
   WPI_DEBUG4(Instance::GetInstance().logger,
              "converting image from {}x{} type {} to {}x{} type {}", cur->width,
-             cur->height, cur->pixelFormat, width, height, pixelFormat);
+             cur->height, static_cast<int>(cur->pixelFormat), width, height,
+             static_cast<int>(pixelFormat));
 
   // If the source image is a JPEG, we need to decode it before we can do
   // anything else with it.  Note that if the destination format is JPEG, we
diff --git a/third_party/allwpilib/cscore/src/main/native/cpp/Frame.h b/third_party/allwpilib/cscore/src/main/native/cpp/Frame.h
index 9a16824..d5f5373 100644
--- a/third_party/allwpilib/cscore/src/main/native/cpp/Frame.h
+++ b/third_party/allwpilib/cscore/src/main/native/cpp/Frame.h
@@ -195,12 +195,17 @@
   Image* ConvertMJPEGToBGR(Image* image);
   Image* ConvertMJPEGToGray(Image* image);
   Image* ConvertYUYVToBGR(Image* image);
+  Image* ConvertYUYVToGray(Image* image);
+  Image* ConvertUYVYToBGR(Image* image);
+  Image* ConvertUYVYToGray(Image* image);
   Image* ConvertBGRToRGB565(Image* image);
   Image* ConvertRGB565ToBGR(Image* image);
   Image* ConvertBGRToGray(Image* image);
   Image* ConvertGrayToBGR(Image* image);
   Image* ConvertBGRToMJPEG(Image* image, int quality);
   Image* ConvertGrayToMJPEG(Image* image, int quality);
+  Image* ConvertGrayToY16(Image* image);
+  Image* ConvertY16ToGray(Image* image);
 
   Image* GetImage(int width, int height, VideoMode::PixelFormat pixelFormat) {
     if (pixelFormat == VideoMode::kMJPEG) {
diff --git a/third_party/allwpilib/cscore/src/main/native/cpp/HttpCameraImpl.cpp b/third_party/allwpilib/cscore/src/main/native/cpp/HttpCameraImpl.cpp
index 9756a5d..7875060 100644
--- a/third_party/allwpilib/cscore/src/main/native/cpp/HttpCameraImpl.cpp
+++ b/third_party/allwpilib/cscore/src/main/native/cpp/HttpCameraImpl.cpp
@@ -6,8 +6,8 @@
 
 #include <wpi/MemAlloc.h>
 #include <wpi/StringExtras.h>
-#include <wpi/TCPConnector.h>
 #include <wpi/timestamp.h>
+#include <wpinet/TCPConnector.h>
 
 #include "Handle.h"
 #include "Instance.h"
@@ -75,7 +75,7 @@
     std::unique_lock lock(m_mutex);
     // sleep for 1 second between checks
     m_monitorCond.wait_for(lock, std::chrono::seconds(1),
-                           [=] { return !m_active; });
+                           [=, this] { return !m_active; });
 
     if (!m_active) {
       break;
@@ -85,7 +85,7 @@
     // (this will result in an error at the read point, and ultimately
     // a reconnect attempt)
     if (m_streamConn && m_frameCount == 0) {
-      SWARNING("{}", "Monitor detected stream hung, disconnecting");
+      SWARNING("Monitor detected stream hung, disconnecting");
       m_streamConn->stream->close();
     }
 
@@ -93,7 +93,7 @@
     m_frameCount = 0;
   }
 
-  SDEBUG("{}", "Monitor Thread exiting");
+  SDEBUG("Monitor Thread exiting");
 }
 
 void HttpCameraImpl::StreamThreadMain() {
@@ -110,7 +110,8 @@
         m_streamConn->stream->close();
       }
       // Wait for enable
-      m_sinkEnabledCond.wait(lock, [=] { return !m_active || IsEnabled(); });
+      m_sinkEnabledCond.wait(lock,
+                             [=, this] { return !m_active || IsEnabled(); });
       if (!m_active) {
         return;
       }
@@ -140,7 +141,7 @@
     }
   }
 
-  SDEBUG("{}", "Camera Thread exiting");
+  SDEBUG("Camera Thread exiting");
   SetConnected(false);
 }
 
@@ -151,7 +152,7 @@
   {
     std::scoped_lock lock(m_mutex);
     if (m_locations.empty()) {
-      SERROR("{}", "locations array is empty!?");
+      SERROR("locations array is empty!?");
       std::this_thread::sleep_for(std::chrono::seconds(1));
       return nullptr;
     }
@@ -272,7 +273,7 @@
   wpi::SmallString<64> contentTypeBuf;
   wpi::SmallString<64> contentLengthBuf;
   if (!ParseHttpHeaders(is, &contentTypeBuf, &contentLengthBuf)) {
-    SWARNING("{}", "disconnected during headers");
+    SWARNING("disconnected during headers");
     PutError("disconnected during headers", wpi::Now());
     return false;
   }
@@ -294,7 +295,7 @@
     // Ugh, no Content-Length?  Read the blocks of the JPEG file.
     int width, height;
     if (!ReadJpeg(is, imageBuf, &width, &height)) {
-      SWARNING("{}", "did not receive a JPEG image");
+      SWARNING("did not receive a JPEG image");
       PutError("did not receive a JPEG image", wpi::Now());
       return false;
     }
@@ -313,7 +314,7 @@
   }
   int width, height;
   if (!GetJpegSize(image->str(), &width, &height)) {
-    SWARNING("{}", "did not receive a JPEG image");
+    SWARNING("did not receive a JPEG image");
     PutError("did not receive a JPEG image", wpi::Now());
     return false;
   }
@@ -329,7 +330,7 @@
     wpi::HttpRequest req;
     {
       std::unique_lock lock(m_mutex);
-      m_settingsCond.wait(lock, [=] {
+      m_settingsCond.wait(lock, [=, this] {
         return !m_active || (m_prefLocation != -1 && !m_settings.empty());
       });
       if (!m_active) {
@@ -343,7 +344,7 @@
     DeviceSendSettings(req);
   }
 
-  SDEBUG("{}", "Settings Thread exiting");
+  SDEBUG("Settings Thread exiting");
 }
 
 void HttpCameraImpl::DeviceSendSettings(wpi::HttpRequest& req) {
@@ -378,7 +379,7 @@
   return m_kind;
 }
 
-bool HttpCameraImpl::SetUrls(wpi::span<const std::string> urls,
+bool HttpCameraImpl::SetUrls(std::span<const std::string> urls,
                              CS_Status* status) {
   std::vector<wpi::HttpLocation> locations;
   for (const auto& url : urls) {
@@ -572,14 +573,14 @@
       break;
   }
   std::string urlStr{url};
-  if (!source->SetUrls(wpi::span{&urlStr, 1}, status)) {
+  if (!source->SetUrls(std::span{&urlStr, 1}, status)) {
     return 0;
   }
   return inst.CreateSource(CS_SOURCE_HTTP, source);
 }
 
 CS_Source CreateHttpCamera(std::string_view name,
-                           wpi::span<const std::string> urls,
+                           std::span<const std::string> urls,
                            CS_HttpCameraKind kind, CS_Status* status) {
   auto& inst = Instance::GetInstance();
   if (urls.empty()) {
@@ -603,7 +604,7 @@
   return static_cast<HttpCameraImpl&>(*data->source).GetKind();
 }
 
-void SetHttpCameraUrls(CS_Source source, wpi::span<const std::string> urls,
+void SetHttpCameraUrls(CS_Source source, std::span<const std::string> urls,
                        CS_Status* status) {
   if (urls.empty()) {
     *status = CS_EMPTY_VALUE;
diff --git a/third_party/allwpilib/cscore/src/main/native/cpp/HttpCameraImpl.h b/third_party/allwpilib/cscore/src/main/native/cpp/HttpCameraImpl.h
index 2c58936..f224ad4 100644
--- a/third_party/allwpilib/cscore/src/main/native/cpp/HttpCameraImpl.h
+++ b/third_party/allwpilib/cscore/src/main/native/cpp/HttpCameraImpl.h
@@ -9,17 +9,17 @@
 #include <functional>
 #include <initializer_list>
 #include <memory>
+#include <span>
 #include <string>
 #include <string_view>
 #include <thread>
 #include <vector>
 
-#include <wpi/HttpUtil.h>
 #include <wpi/SmallString.h>
 #include <wpi/StringMap.h>
 #include <wpi/condition_variable.h>
 #include <wpi/raw_istream.h>
-#include <wpi/span.h>
+#include <wpinet/HttpUtil.h>
 
 #include "SourceImpl.h"
 #include "cscore_cpp.h"
@@ -55,7 +55,7 @@
   void NumSinksEnabledChanged() override;
 
   CS_HttpCameraKind GetKind() const;
-  bool SetUrls(wpi::span<const std::string> urls, CS_Status* status);
+  bool SetUrls(std::span<const std::string> urls, CS_Status* status);
   std::vector<std::string> GetUrls() const;
 
   // Property data
diff --git a/third_party/allwpilib/cscore/src/main/native/cpp/Image.h b/third_party/allwpilib/cscore/src/main/native/cpp/Image.h
index 9a1579f..cb8df91 100644
--- a/third_party/allwpilib/cscore/src/main/native/cpp/Image.h
+++ b/third_party/allwpilib/cscore/src/main/native/cpp/Image.h
@@ -22,7 +22,9 @@
 
  public:
 #ifndef __linux__
-  explicit Image(size_t capacity) { m_data.reserve(capacity); }
+  explicit Image(size_t capacity) {
+    m_data.reserve(capacity);
+  }
 #else
   explicit Image(size_t capacity)
       : m_data{capacity, default_init_allocator<uchar>{}} {
@@ -34,26 +36,46 @@
   Image& operator=(const Image&) = delete;
 
   // Getters
-  operator std::string_view() const { return str(); }  // NOLINT
-  std::string_view str() const { return {data(), size()}; }
-  size_t capacity() const { return m_data.capacity(); }
+  operator std::string_view() const {  // NOLINT
+    return str();
+  }
+  std::string_view str() const {
+    return {data(), size()};
+  }
+  size_t capacity() const {
+    return m_data.capacity();
+  }
   const char* data() const {
     return reinterpret_cast<const char*>(m_data.data());
   }
-  char* data() { return reinterpret_cast<char*>(m_data.data()); }
-  size_t size() const { return m_data.size(); }
+  char* data() {
+    return reinterpret_cast<char*>(m_data.data());
+  }
+  size_t size() const {
+    return m_data.size();
+  }
 
-  const std::vector<uchar>& vec() const { return m_data; }
-  std::vector<uchar>& vec() { return m_data; }
+  const std::vector<uchar>& vec() const {
+    return m_data;
+  }
+  std::vector<uchar>& vec() {
+    return m_data;
+  }
 
-  void resize(size_t size) { m_data.resize(size); }
-  void SetSize(size_t size) { m_data.resize(size); }
+  void resize(size_t size) {
+    m_data.resize(size);
+  }
+  void SetSize(size_t size) {
+    m_data.resize(size);
+  }
 
   cv::Mat AsMat() {
     int type;
     switch (pixelFormat) {
       case VideoMode::kYUYV:
       case VideoMode::kRGB565:
+      case VideoMode::kY16:
+      case VideoMode::kUYVY:
         type = CV_8UC2;
         break;
       case VideoMode::kBGR:
@@ -68,7 +90,9 @@
     return cv::Mat{height, width, type, m_data.data()};
   }
 
-  cv::_InputArray AsInputArray() { return cv::_InputArray{m_data}; }
+  cv::_InputArray AsInputArray() {
+    return cv::_InputArray{m_data};
+  }
 
   bool Is(int width_, int height_) {
     return width == width_ && height == height_;
@@ -90,8 +114,12 @@
   bool IsLarger(const Image& oth) {
     return width >= oth.width && height >= oth.height;
   }
-  bool IsSmaller(int width_, int height_) { return !IsLarger(width_, height_); }
-  bool IsSmaller(const Image& oth) { return !IsLarger(oth); }
+  bool IsSmaller(int width_, int height_) {
+    return !IsLarger(width_, height_);
+  }
+  bool IsSmaller(const Image& oth) {
+    return !IsLarger(oth);
+  }
 
  private:
   std::vector<uchar> m_data;
diff --git a/third_party/allwpilib/cscore/src/main/native/cpp/Instance.h b/third_party/allwpilib/cscore/src/main/native/cpp/Instance.h
index f84eacf..c8ba81d 100644
--- a/third_party/allwpilib/cscore/src/main/native/cpp/Instance.h
+++ b/third_party/allwpilib/cscore/src/main/native/cpp/Instance.h
@@ -8,8 +8,8 @@
 #include <memory>
 #include <utility>
 
-#include <wpi/EventLoopRunner.h>
 #include <wpi/Logger.h>
+#include <wpinet/EventLoopRunner.h>
 
 #include "Log.h"
 #include "NetworkListener.h"
@@ -86,16 +86,16 @@
   void DestroySource(CS_Source handle);
   void DestroySink(CS_Sink handle);
 
-  wpi::span<CS_Source> EnumerateSourceHandles(
+  std::span<CS_Source> EnumerateSourceHandles(
       wpi::SmallVectorImpl<CS_Source>& vec) {
     return m_sources.GetAll(vec);
   }
 
-  wpi::span<CS_Sink> EnumerateSinkHandles(wpi::SmallVectorImpl<CS_Sink>& vec) {
+  std::span<CS_Sink> EnumerateSinkHandles(wpi::SmallVectorImpl<CS_Sink>& vec) {
     return m_sinks.GetAll(vec);
   }
 
-  wpi::span<CS_Sink> EnumerateSourceSinks(CS_Source source,
+  std::span<CS_Sink> EnumerateSourceSinks(CS_Source source,
                                           wpi::SmallVectorImpl<CS_Sink>& vec) {
     vec.clear();
     m_sinks.ForEach([&](CS_Sink sinkHandle, const SinkData& data) {
diff --git a/third_party/allwpilib/cscore/src/main/native/cpp/Log.h b/third_party/allwpilib/cscore/src/main/native/cpp/Log.h
index 21becdf..66fa08f 100644
--- a/third_party/allwpilib/cscore/src/main/native/cpp/Log.h
+++ b/third_party/allwpilib/cscore/src/main/native/cpp/Log.h
@@ -21,32 +21,43 @@
                      Args&&... args) {
   if (logger.HasLogger() && level >= logger.min_level()) {
     NamedLogV(logger, level, file, line, name, format,
-              fmt::make_args_checked<Args...>(format, args...));
+              fmt::make_format_args(args...));
   }
 }
 
 }  // namespace cs
 
-#define LOG(level, format, ...) WPI_LOG(m_logger, level, format, __VA_ARGS__)
+#define LOG(level, format, ...) \
+  WPI_LOG(m_logger, level, format __VA_OPT__(, ) __VA_ARGS__)
 
 #undef ERROR
-#define ERROR(format, ...) WPI_ERROR(m_logger, format, __VA_ARGS__)
-#define WARNING(format, ...) WPI_WARNING(m_logger, format, __VA_ARGS__)
-#define INFO(format, ...) WPI_INFO(m_logger, format, __VA_ARGS__)
+#define ERROR(format, ...) \
+  WPI_ERROR(m_logger, format __VA_OPT__(, ) __VA_ARGS__)
+#define WARNING(format, ...) \
+  WPI_WARNING(m_logger, format __VA_OPT__(, ) __VA_ARGS__)
+#define INFO(format, ...) WPI_INFO(m_logger, format __VA_OPT__(, ) __VA_ARGS__)
 
-#define DEBUG0(format, ...) WPI_DEBUG(m_logger, format, __VA_ARGS__)
-#define DEBUG1(format, ...) WPI_DEBUG1(m_logger, format, __VA_ARGS__)
-#define DEBUG2(format, ...) WPI_DEBUG2(m_logger, format, __VA_ARGS__)
-#define DEBUG3(format, ...) WPI_DEBUG3(m_logger, format, __VA_ARGS__)
-#define DEBUG4(format, ...) WPI_DEBUG4(m_logger, format, __VA_ARGS__)
+#define DEBUG0(format, ...) \
+  WPI_DEBUG(m_logger, format __VA_OPT__(, ) __VA_ARGS__)
+#define DEBUG1(format, ...) \
+  WPI_DEBUG1(m_logger, format __VA_OPT__(, ) __VA_ARGS__)
+#define DEBUG2(format, ...) \
+  WPI_DEBUG2(m_logger, format __VA_OPT__(, ) __VA_ARGS__)
+#define DEBUG3(format, ...) \
+  WPI_DEBUG3(m_logger, format __VA_OPT__(, ) __VA_ARGS__)
+#define DEBUG4(format, ...) \
+  WPI_DEBUG4(m_logger, format __VA_OPT__(, ) __VA_ARGS__)
 
-#define SLOG(level, format, ...)                                               \
-  NamedLog(m_logger, level, __FILE__, __LINE__, GetName(), FMT_STRING(format), \
-           __VA_ARGS__)
+#define SLOG(level, format, ...)                           \
+  NamedLog(m_logger, level, __FILE__, __LINE__, GetName(), \
+           FMT_STRING(format) __VA_OPT__(, ) __VA_ARGS__)
 
-#define SERROR(format, ...) SLOG(::wpi::WPI_LOG_ERROR, format, __VA_ARGS__)
-#define SWARNING(format, ...) SLOG(::wpi::WPI_LOG_WARNING, format, __VA_ARGS__)
-#define SINFO(format, ...) SLOG(::wpi::WPI_LOG_INFO, format, __VA_ARGS__)
+#define SERROR(format, ...) \
+  SLOG(::wpi::WPI_LOG_ERROR, format __VA_OPT__(, ) __VA_ARGS__)
+#define SWARNING(format, ...) \
+  SLOG(::wpi::WPI_LOG_WARNING, format __VA_OPT__(, ) __VA_ARGS__)
+#define SINFO(format, ...) \
+  SLOG(::wpi::WPI_LOG_INFO, format __VA_OPT__(, ) __VA_ARGS__)
 
 #ifdef NDEBUG
 #define SDEBUG(format, ...) \
@@ -65,11 +76,16 @@
   do {                       \
   } while (0)
 #else
-#define SDEBUG(format, ...) SLOG(::wpi::WPI_LOG_DEBUG, format, __VA_ARGS__)
-#define SDEBUG1(format, ...) SLOG(::wpi::WPI_LOG_DEBUG1, format, __VA_ARGS__)
-#define SDEBUG2(format, ...) SLOG(::wpi::WPI_LOG_DEBUG2, format, __VA_ARGS__)
-#define SDEBUG3(format, ...) SLOG(::wpi::WPI_LOG_DEBUG3, format, __VA_ARGS__)
-#define SDEBUG4(format, ...) SLOG(::wpi::WPI_LOG_DEBUG4, format, __VA_ARGS__)
+#define SDEBUG(format, ...) \
+  SLOG(::wpi::WPI_LOG_DEBUG, format __VA_OPT__(, ) __VA_ARGS__)
+#define SDEBUG1(format, ...) \
+  SLOG(::wpi::WPI_LOG_DEBUG1, format __VA_OPT__(, ) __VA_ARGS__)
+#define SDEBUG2(format, ...) \
+  SLOG(::wpi::WPI_LOG_DEBUG2, format __VA_OPT__(, ) __VA_ARGS__)
+#define SDEBUG3(format, ...) \
+  SLOG(::wpi::WPI_LOG_DEBUG3, format __VA_OPT__(, ) __VA_ARGS__)
+#define SDEBUG4(format, ...) \
+  SLOG(::wpi::WPI_LOG_DEBUG4, format __VA_OPT__(, ) __VA_ARGS__)
 #endif
 
 #endif  // CSCORE_LOG_H_
diff --git a/third_party/allwpilib/cscore/src/main/native/cpp/MjpegServerImpl.cpp b/third_party/allwpilib/cscore/src/main/native/cpp/MjpegServerImpl.cpp
index 6a8cd2b..ea9ebe1 100644
--- a/third_party/allwpilib/cscore/src/main/native/cpp/MjpegServerImpl.cpp
+++ b/third_party/allwpilib/cscore/src/main/native/cpp/MjpegServerImpl.cpp
@@ -7,13 +7,13 @@
 #include <chrono>
 
 #include <fmt/format.h>
-#include <wpi/HttpUtil.h>
 #include <wpi/SmallString.h>
 #include <wpi/StringExtras.h>
-#include <wpi/TCPAcceptor.h>
 #include <wpi/fmt/raw_ostream.h>
-#include <wpi/raw_socket_istream.h>
-#include <wpi/raw_socket_ostream.h>
+#include <wpinet/HttpUtil.h>
+#include <wpinet/TCPAcceptor.h>
+#include <wpinet/raw_socket_istream.h>
+#include <wpinet/raw_socket_ostream.h>
 
 #include "Handle.h"
 #include "Instance.h"
@@ -460,6 +460,12 @@
       case VideoMode::kGray:
         os << "gray";
         break;
+      case VideoMode::kY16:
+        os << "Y16";
+        break;
+      case VideoMode::kUYVY:
+        os << "UYVY";
+        break;
       default:
         os << "unknown";
         break;
@@ -495,7 +501,7 @@
     auto kind = source.GetPropertyKind(prop);
     fmt::print(os, "\n\"name\": \"{}\"", name);
     fmt::print(os, ",\n\"id\": \"{}\"", prop);
-    fmt::print(os, ",\n\"type\": \"{}\"", kind);
+    fmt::print(os, ",\n\"type\": \"{}\"", static_cast<int>(kind));
     fmt::print(os, ",\n\"min\": \"{}\"", source.GetPropertyMin(prop, &status));
     fmt::print(os, ",\n\"max\": \"{}\"", source.GetPropertyMax(prop, &status));
     fmt::print(os, ",\n\"step\": \"{}\"",
@@ -569,6 +575,12 @@
       case VideoMode::kGray:
         os << "gray";
         break;
+      case VideoMode::kY16:
+        os << "Y16";
+        break;
+      case VideoMode::kUYVY:
+        os << "UYVY";
+        break;
       default:
         os << "unknown";
         break;
@@ -650,7 +662,7 @@
 // Send HTTP response and a stream of JPG-frames
 void MjpegServerImpl::ConnThread::SendStream(wpi::raw_socket_ostream& os) {
   if (m_noStreaming) {
-    SERROR("{}", "Too many simultaneous client streams");
+    SERROR("Too many simultaneous client streams");
     SendError(os, 503, "Too many simultaneous streams");
     return;
   }
@@ -663,7 +675,7 @@
   SendHeader(oss, 200, "OK", "multipart/x-mixed-replace;boundary=" BOUNDARY);
   os << oss.str();
 
-  SDEBUG("{}", "Headers send, sending stream now");
+  SDEBUG("Headers send, sending stream now");
 
   Frame::Time lastFrameTime = 0;
   Frame::Time timePerFrame = 0;
@@ -685,7 +697,7 @@
       std::this_thread::sleep_for(std::chrono::milliseconds(200));
       continue;
     }
-    SDEBUG4("{}", "waiting for frame");
+    SDEBUG4("waiting for frame");
     Frame frame = source->GetNextFrame(0.225);  // blocks
     if (!m_active) {
       break;
@@ -740,8 +752,10 @@
         // for adding it if required.
         addDHT = JpegNeedsDHT(data, &size, &locSOF);
         break;
-      case VideoMode::kYUYV:
+      case VideoMode::kUYVY:
       case VideoMode::kRGB565:
+      case VideoMode::kYUYV:
+      case VideoMode::kY16:
       default:
         // Bad frame; sleep for 10 ms so we don't consume all processor time.
         std::this_thread::sleep_for(std::chrono::milliseconds(10));
@@ -783,7 +797,7 @@
   wpi::SmallString<128> reqBuf;
   std::string_view req = is.getline(reqBuf, 4096);
   if (is.has_error()) {
-    SDEBUG("{}", "error getting request string");
+    SDEBUG("error getting request string");
     return;
   }
 
@@ -824,7 +838,7 @@
   } else if (req.find("GET / ") != std::string_view::npos || req == "GET /\n") {
     kind = kRootPage;
   } else {
-    SDEBUG("{}", "HTTP request resource not found");
+    SDEBUG("HTTP request resource not found");
     SendError(os, 404, "Resource not found");
     return;
   }
@@ -866,11 +880,11 @@
         SendHeader(os, 200, "OK", "text/plain");
         os << "Ignored due to no connected source."
            << "\r\n";
-        SDEBUG("{}", "Ignored due to no connected source.");
+        SDEBUG("Ignored due to no connected source.");
       }
       break;
     case kGetSettings:
-      SDEBUG("{}", "request for JSON file");
+      SDEBUG("request for JSON file");
       if (auto source = GetSource()) {
         SendJSON(os, *source, true);
       } else {
@@ -878,7 +892,7 @@
       }
       break;
     case kGetSourceConfig:
-      SDEBUG("{}", "request for JSON file");
+      SDEBUG("request for JSON file");
       if (auto source = GetSource()) {
         SendHeader(os, 200, "OK", "application/json");
         CS_Status status = CS_OK;
@@ -889,7 +903,7 @@
       }
       break;
     case kRootPage:
-      SDEBUG("{}", "request for root page");
+      SDEBUG("request for root page");
       SendHeader(os, 200, "OK", "text/html");
       if (auto source = GetSource()) {
         SendHTML(os, *source, false);
@@ -900,7 +914,7 @@
       break;
   }
 
-  SDEBUG("{}", "leaving HTTP client thread");
+  SDEBUG("leaving HTTP client thread");
 }
 
 // worker thread for clients that connected to this server
@@ -927,7 +941,7 @@
     return;
   }
 
-  SDEBUG("{}", "waiting for clients to connect");
+  SDEBUG("waiting for clients to connect");
   while (m_active) {
     auto stream = m_acceptor->accept();
     if (!stream) {
@@ -977,7 +991,7 @@
     thr->m_cond.notify_one();
   }
 
-  SDEBUG("{}", "leaving server thread");
+  SDEBUG("leaving server thread");
 }
 
 void MjpegServerImpl::SetSourceImpl(std::shared_ptr<SourceImpl> source) {
diff --git a/third_party/allwpilib/cscore/src/main/native/cpp/MjpegServerImpl.h b/third_party/allwpilib/cscore/src/main/native/cpp/MjpegServerImpl.h
index e323e69..01f41da 100644
--- a/third_party/allwpilib/cscore/src/main/native/cpp/MjpegServerImpl.h
+++ b/third_party/allwpilib/cscore/src/main/native/cpp/MjpegServerImpl.h
@@ -12,13 +12,13 @@
 #include <thread>
 #include <vector>
 
-#include <wpi/NetworkAcceptor.h>
-#include <wpi/NetworkStream.h>
 #include <wpi/SafeThread.h>
 #include <wpi/SmallVector.h>
 #include <wpi/raw_istream.h>
 #include <wpi/raw_ostream.h>
-#include <wpi/raw_socket_ostream.h>
+#include <wpinet/NetworkAcceptor.h>
+#include <wpinet/NetworkStream.h>
+#include <wpinet/raw_socket_ostream.h>
 
 #include "SinkImpl.h"
 
diff --git a/third_party/allwpilib/cscore/src/main/native/cpp/PropertyContainer.cpp b/third_party/allwpilib/cscore/src/main/native/cpp/PropertyContainer.cpp
index b1d3a6f..0b8474f 100644
--- a/third_party/allwpilib/cscore/src/main/native/cpp/PropertyContainer.cpp
+++ b/third_party/allwpilib/cscore/src/main/native/cpp/PropertyContainer.cpp
@@ -27,7 +27,7 @@
   return ndx;
 }
 
-wpi::span<int> PropertyContainer::EnumerateProperties(
+std::span<int> PropertyContainer::EnumerateProperties(
     wpi::SmallVectorImpl<int>& vec, CS_Status* status) const {
   if (!m_properties_cached && !CacheProperties(status)) {
     return {};
diff --git a/third_party/allwpilib/cscore/src/main/native/cpp/PropertyContainer.h b/third_party/allwpilib/cscore/src/main/native/cpp/PropertyContainer.h
index a00c675..1f4ffc3 100644
--- a/third_party/allwpilib/cscore/src/main/native/cpp/PropertyContainer.h
+++ b/third_party/allwpilib/cscore/src/main/native/cpp/PropertyContainer.h
@@ -8,13 +8,13 @@
 #include <atomic>
 #include <cstddef>
 #include <memory>
+#include <span>
 #include <string>
 #include <string_view>
 #include <vector>
 
 #include <wpi/StringMap.h>
 #include <wpi/mutex.h>
-#include <wpi/span.h>
 
 #include "PropertyImpl.h"
 #include "cscore_cpp.h"
@@ -33,7 +33,7 @@
   virtual ~PropertyContainer() = default;
 
   int GetPropertyIndex(std::string_view name) const;
-  wpi::span<int> EnumerateProperties(wpi::SmallVectorImpl<int>& vec,
+  std::span<int> EnumerateProperties(wpi::SmallVectorImpl<int>& vec,
                                      CS_Status* status) const;
   CS_PropertyKind GetPropertyKind(int property) const;
   std::string_view GetPropertyName(int property,
diff --git a/third_party/allwpilib/cscore/src/main/native/cpp/RawSinkImpl.cpp b/third_party/allwpilib/cscore/src/main/native/cpp/RawSinkImpl.cpp
index fbc1028..31c57d2 100644
--- a/third_party/allwpilib/cscore/src/main/native/cpp/RawSinkImpl.cpp
+++ b/third_party/allwpilib/cscore/src/main/native/cpp/RawSinkImpl.cpp
@@ -127,7 +127,7 @@
       std::this_thread::sleep_for(std::chrono::seconds(1));
       continue;
     }
-    SDEBUG4("{}", "waiting for frame");
+    SDEBUG4("waiting for frame");
     Frame frame = source->GetNextFrame();  // blocks
     if (!m_active) {
       break;
diff --git a/third_party/allwpilib/cscore/src/main/native/cpp/RawSourceImpl.cpp b/third_party/allwpilib/cscore/src/main/native/cpp/RawSourceImpl.cpp
index 9ce0628..bad26a0 100644
--- a/third_party/allwpilib/cscore/src/main/native/cpp/RawSourceImpl.cpp
+++ b/third_party/allwpilib/cscore/src/main/native/cpp/RawSourceImpl.cpp
@@ -26,6 +26,8 @@
   switch (image.pixelFormat) {
     case VideoMode::kYUYV:
     case VideoMode::kRGB565:
+    case VideoMode::kY16:
+    case VideoMode::kUYVY:
       type = CV_8UC2;
       break;
     case VideoMode::kBGR:
diff --git a/third_party/allwpilib/cscore/src/main/native/cpp/SourceImpl.cpp b/third_party/allwpilib/cscore/src/main/native/cpp/SourceImpl.cpp
index da5aa1d..045bdd4 100644
--- a/third_party/allwpilib/cscore/src/main/native/cpp/SourceImpl.cpp
+++ b/third_party/allwpilib/cscore/src/main/native/cpp/SourceImpl.cpp
@@ -76,7 +76,7 @@
 Frame SourceImpl::GetNextFrame() {
   std::unique_lock lock{m_frameMutex};
   auto oldTime = m_frame.GetTime();
-  m_frameCv.wait(lock, [=] { return m_frame.GetTime() != oldTime; });
+  m_frameCv.wait(lock, [=, this] { return m_frame.GetTime() != oldTime; });
   return m_frame;
 }
 
@@ -85,7 +85,7 @@
   auto oldTime = m_frame.GetTime();
   if (!m_frameCv.wait_for(
           lock, std::chrono::milliseconds(static_cast<int>(timeout * 1000)),
-          [=] { return m_frame.GetTime() != oldTime; })) {
+          [=, this] { return m_frame.GetTime() != oldTime; })) {
     m_frame = Frame{*this, "timed out getting frame", wpi::Now()};
   }
   return m_frame;
@@ -198,6 +198,10 @@
         mode.pixelFormat = cs::VideoMode::kBGR;
       } else if (wpi::equals_lower(str, "gray")) {
         mode.pixelFormat = cs::VideoMode::kGray;
+      } else if (wpi::equals_lower(str, "y16")) {
+        mode.pixelFormat = cs::VideoMode::kY16;
+      } else if (wpi::equals_lower(str, "uyvy")) {
+        mode.pixelFormat = cs::VideoMode::kUYVY;
       } else {
         SWARNING("SetConfigJson: could not understand pixel format value '{}'",
                  str);
@@ -360,6 +364,12 @@
     case VideoMode::kGray:
       pixelFormat = "gray";
       break;
+    case VideoMode::kY16:
+      pixelFormat = "y16";
+      break;
+    case VideoMode::kUYVY:
+      pixelFormat = "uyvy";
+      break;
     default:
       break;
   }
diff --git a/third_party/allwpilib/cscore/src/main/native/cpp/SourceImpl.h b/third_party/allwpilib/cscore/src/main/native/cpp/SourceImpl.h
index dd2e574..5df9ad0 100644
--- a/third_party/allwpilib/cscore/src/main/native/cpp/SourceImpl.h
+++ b/third_party/allwpilib/cscore/src/main/native/cpp/SourceImpl.h
@@ -50,6 +50,7 @@
 
   void SetConnectionStrategy(CS_ConnectionStrategy strategy) {
     m_strategy = static_cast<int>(strategy);
+    NumSinksChanged();
   }
   bool IsEnabled() const {
     return m_strategy == CS_CONNECTION_KEEP_OPEN ||
diff --git a/third_party/allwpilib/cscore/src/main/native/cpp/UnlimitedHandleResource.h b/third_party/allwpilib/cscore/src/main/native/cpp/UnlimitedHandleResource.h
index f7671ae..28ad301 100644
--- a/third_party/allwpilib/cscore/src/main/native/cpp/UnlimitedHandleResource.h
+++ b/third_party/allwpilib/cscore/src/main/native/cpp/UnlimitedHandleResource.h
@@ -6,12 +6,12 @@
 #define CSCORE_UNLIMITEDHANDLERESOURCE_H_
 
 #include <memory>
+#include <span>
 #include <utility>
 #include <vector>
 
 #include <wpi/SmallVector.h>
 #include <wpi/mutex.h>
-#include <wpi/span.h>
 
 namespace cs {
 
@@ -50,7 +50,7 @@
   std::shared_ptr<TStruct> Free(THandle handle);
 
   template <typename T>
-  wpi::span<T> GetAll(wpi::SmallVectorImpl<T>& vec);
+  std::span<T> GetAll(wpi::SmallVectorImpl<T>& vec);
 
   std::vector<std::shared_ptr<TStruct>> FreeAll();
 
@@ -151,10 +151,10 @@
 
 template <typename THandle, typename TStruct, int typeValue, typename TMutex>
 template <typename T>
-inline wpi::span<T>
+inline std::span<T>
 UnlimitedHandleResource<THandle, TStruct, typeValue, TMutex>::GetAll(
     wpi::SmallVectorImpl<T>& vec) {
-  ForEach([&](THandle handle, const TStruct& data) { vec.push_back(handle); });
+  ForEach([&](THandle handle, const TStruct&) { vec.push_back(handle); });
   return vec;
 }
 
diff --git a/third_party/allwpilib/cscore/src/main/native/cpp/cscore_cpp.cpp b/third_party/allwpilib/cscore/src/main/native/cpp/cscore_cpp.cpp
index 3b4e570..f81405b 100644
--- a/third_party/allwpilib/cscore/src/main/native/cpp/cscore_cpp.cpp
+++ b/third_party/allwpilib/cscore/src/main/native/cpp/cscore_cpp.cpp
@@ -5,8 +5,8 @@
 #include "cscore_cpp.h"
 
 #include <wpi/SmallString.h>
-#include <wpi/hostname.h>
 #include <wpi/json.h>
+#include <wpinet/hostname.h>
 
 #include "Handle.h"
 #include "Instance.h"
@@ -286,7 +286,7 @@
   return Handle{source, property, Handle::kProperty};
 }
 
-wpi::span<CS_Property> EnumerateSourceProperties(
+std::span<CS_Property> EnumerateSourceProperties(
     CS_Source source, wpi::SmallVectorImpl<CS_Property>& vec,
     CS_Status* status) {
   auto data = Instance::GetInstance().GetSource(source);
@@ -398,7 +398,7 @@
   return data->source->EnumerateVideoModes(status);
 }
 
-wpi::span<CS_Sink> EnumerateSourceSinks(CS_Source source,
+std::span<CS_Sink> EnumerateSourceSinks(CS_Source source,
                                         wpi::SmallVectorImpl<CS_Sink>& vec,
                                         CS_Status* status) {
   auto& inst = Instance::GetInstance();
@@ -583,7 +583,7 @@
   return Handle{sink, property, Handle::kSinkProperty};
 }
 
-wpi::span<CS_Property> EnumerateSinkProperties(
+std::span<CS_Property> EnumerateSinkProperties(
     CS_Sink sink, wpi::SmallVectorImpl<CS_Property>& vec, CS_Status* status) {
   auto data = Instance::GetInstance().GetSink(sink);
   if (!data) {
@@ -865,12 +865,12 @@
 // Utility Functions
 //
 
-wpi::span<CS_Source> EnumerateSourceHandles(
+std::span<CS_Source> EnumerateSourceHandles(
     wpi::SmallVectorImpl<CS_Source>& vec, CS_Status* status) {
   return Instance::GetInstance().EnumerateSourceHandles(vec);
 }
 
-wpi::span<CS_Sink> EnumerateSinkHandles(wpi::SmallVectorImpl<CS_Sink>& vec,
+std::span<CS_Sink> EnumerateSinkHandles(wpi::SmallVectorImpl<CS_Sink>& vec,
                                         CS_Status* status) {
   return Instance::GetInstance().EnumerateSinkHandles(vec);
 }
diff --git a/third_party/allwpilib/cscore/src/main/native/cpp/jni/CameraServerJNI.cpp b/third_party/allwpilib/cscore/src/main/native/cpp/jni/CameraServerJNI.cpp
index b99d322..ddd0ff5 100644
--- a/third_party/allwpilib/cscore/src/main/native/cpp/jni/CameraServerJNI.cpp
+++ b/third_party/allwpilib/cscore/src/main/native/cpp/jni/CameraServerJNI.cpp
@@ -3,16 +3,17 @@
 // the WPILib BSD license file in the root directory of this project.
 
 #include <exception>
+#include <span>
 
 #include <fmt/format.h>
 #include <opencv2/core/core.hpp>
 #include <wpi/SmallString.h>
 #include <wpi/jni_util.h>
-#include <wpi/span.h>
 
 #include "cscore_cpp.h"
 #include "cscore_cv.h"
 #include "cscore_raw.h"
+#include "cscore_runloop.h"
 #include "edu_wpi_first_cscore_CameraServerJNI.h"
 
 namespace cv {
@@ -296,7 +297,7 @@
 }
 
 static jobjectArray MakeJObject(JNIEnv* env,
-                                wpi::span<const cs::RawEvent> arr) {
+                                std::span<const cs::RawEvent> arr) {
   jobjectArray jarr = env->NewObjectArray(arr.size(), videoEventCls, nullptr);
   if (!jarr) {
     return nullptr;
@@ -2226,4 +2227,40 @@
   delete ptr;
 }
 
+/*
+ * Class:     edu_wpi_first_cscore_CameraServerJNI
+ * Method:    runMainRunLoop
+ * Signature: ()V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_cscore_CameraServerJNI_runMainRunLoop
+  (JNIEnv*, jclass)
+{
+  cs::RunMainRunLoop();
+}
+
+/*
+ * Class:     edu_wpi_first_cscore_CameraServerJNI
+ * Method:    runMainRunLoopTimeout
+ * Signature: (D)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_cscore_CameraServerJNI_runMainRunLoopTimeout
+  (JNIEnv*, jclass, jdouble timeoutSeconds)
+{
+  return cs::RunMainRunLoopTimeout(timeoutSeconds);
+}
+
+/*
+ * Class:     edu_wpi_first_cscore_CameraServerJNI
+ * Method:    stopMainRunLoop
+ * Signature: ()V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_cscore_CameraServerJNI_stopMainRunLoop
+  (JNIEnv*, jclass)
+{
+  return cs::StopMainRunLoop();
+}
+
 }  // extern "C"
diff --git a/third_party/allwpilib/cscore/src/main/native/include/cscore_c.h b/third_party/allwpilib/cscore/src/main/native/include/cscore_c.h
index 76bd836..ba8c811 100644
--- a/third_party/allwpilib/cscore/src/main/native/include/cscore_c.h
+++ b/third_party/allwpilib/cscore/src/main/native/include/cscore_c.h
@@ -93,7 +93,9 @@
   CS_PIXFMT_YUYV,
   CS_PIXFMT_RGB565,
   CS_PIXFMT_BGR,
-  CS_PIXFMT_GRAY
+  CS_PIXFMT_GRAY,
+  CS_PIXFMT_Y16,
+  CS_PIXFMT_UYVY
 };
 
 /**
diff --git a/third_party/allwpilib/cscore/src/main/native/include/cscore_cpp.h b/third_party/allwpilib/cscore/src/main/native/include/cscore_cpp.h
index 8b1eab1..0031e5e 100644
--- a/third_party/allwpilib/cscore/src/main/native/include/cscore_cpp.h
+++ b/third_party/allwpilib/cscore/src/main/native/include/cscore_cpp.h
@@ -8,12 +8,12 @@
 #include <stdint.h>
 
 #include <functional>
+#include <span>
 #include <string>
 #include <string_view>
 #include <vector>
 
 #include <wpi/SmallVector.h>
-#include <wpi/span.h>
 
 #include "cscore_c.h"
 
@@ -68,7 +68,9 @@
     kYUYV = CS_PIXFMT_YUYV,
     kRGB565 = CS_PIXFMT_RGB565,
     kBGR = CS_PIXFMT_BGR,
-    kGray = CS_PIXFMT_GRAY
+    kGray = CS_PIXFMT_GRAY,
+    kY16 = CS_PIXFMT_Y16,
+    kUYVY = CS_PIXFMT_UYVY
   };
   VideoMode() {
     pixelFormat = 0;
@@ -89,7 +91,10 @@
            height == other.height && fps == other.fps;
   }
 
-  bool operator!=(const VideoMode& other) const { return !(*this == other); }
+  bool CompareWithoutFps(const VideoMode& other) const {
+    return pixelFormat == other.pixelFormat && width == other.width &&
+           height == other.height;
+  }
 };
 
 /**
@@ -203,7 +208,7 @@
 CS_Source CreateHttpCamera(std::string_view name, std::string_view url,
                            CS_HttpCameraKind kind, CS_Status* status);
 CS_Source CreateHttpCamera(std::string_view name,
-                           wpi::span<const std::string> urls,
+                           std::span<const std::string> urls,
                            CS_HttpCameraKind kind, CS_Status* status);
 CS_Source CreateCvSource(std::string_view name, const VideoMode& mode,
                          CS_Status* status);
@@ -230,7 +235,7 @@
 bool IsSourceEnabled(CS_Source source, CS_Status* status);
 CS_Property GetSourceProperty(CS_Source source, std::string_view name,
                               CS_Status* status);
-wpi::span<CS_Property> EnumerateSourceProperties(
+std::span<CS_Property> EnumerateSourceProperties(
     CS_Source source, wpi::SmallVectorImpl<CS_Property>& vec,
     CS_Status* status);
 VideoMode GetSourceVideoMode(CS_Source source, CS_Status* status);
@@ -249,7 +254,7 @@
 wpi::json GetSourceConfigJsonObject(CS_Source source, CS_Status* status);
 std::vector<VideoMode> EnumerateSourceVideoModes(CS_Source source,
                                                  CS_Status* status);
-wpi::span<CS_Sink> EnumerateSourceSinks(CS_Source source,
+std::span<CS_Sink> EnumerateSourceSinks(CS_Source source,
                                         wpi::SmallVectorImpl<CS_Sink>& vec,
                                         CS_Status* status);
 CS_Source CopySource(CS_Source source, CS_Status* status);
@@ -285,7 +290,7 @@
  * @{
  */
 CS_HttpCameraKind GetHttpCameraKind(CS_Source source, CS_Status* status);
-void SetHttpCameraUrls(CS_Source source, wpi::span<const std::string> urls,
+void SetHttpCameraUrls(CS_Source source, std::span<const std::string> urls,
                        CS_Status* status);
 std::vector<std::string> GetHttpCameraUrls(CS_Source source, CS_Status* status);
 /** @} */
@@ -304,7 +309,7 @@
                                  int step, int defaultValue, int value,
                                  CS_Status* status);
 void SetSourceEnumPropertyChoices(CS_Source source, CS_Property property,
-                                  wpi::span<const std::string> choices,
+                                  std::span<const std::string> choices,
                                   CS_Status* status);
 /** @} */
 
@@ -335,7 +340,7 @@
                                     CS_Status* status);
 CS_Property GetSinkProperty(CS_Sink sink, std::string_view name,
                             CS_Status* status);
-wpi::span<CS_Property> EnumerateSinkProperties(
+std::span<CS_Property> EnumerateSinkProperties(
     CS_Sink sink, wpi::SmallVectorImpl<CS_Property>& vec, CS_Status* status);
 void SetSinkSource(CS_Sink sink, CS_Source source, CS_Status* status);
 CS_Property GetSinkSourceProperty(CS_Sink sink, std::string_view name,
@@ -430,9 +435,9 @@
  */
 std::vector<UsbCameraInfo> EnumerateUsbCameras(CS_Status* status);
 
-wpi::span<CS_Source> EnumerateSourceHandles(
+std::span<CS_Source> EnumerateSourceHandles(
     wpi::SmallVectorImpl<CS_Source>& vec, CS_Status* status);
-wpi::span<CS_Sink> EnumerateSinkHandles(wpi::SmallVectorImpl<CS_Sink>& vec,
+std::span<CS_Sink> EnumerateSinkHandles(wpi::SmallVectorImpl<CS_Sink>& vec,
                                         CS_Status* status);
 
 std::string GetHostname();
diff --git a/third_party/allwpilib/cscore/src/main/native/include/cscore_oo.h b/third_party/allwpilib/cscore/src/main/native/include/cscore_oo.h
index 4fd1bff..ab09fe7 100644
--- a/third_party/allwpilib/cscore/src/main/native/include/cscore_oo.h
+++ b/third_party/allwpilib/cscore/src/main/native/include/cscore_oo.h
@@ -6,13 +6,12 @@
 #define CSCORE_CSCORE_OO_H_
 
 #include <initializer_list>
+#include <span>
 #include <string>
 #include <string_view>
 #include <utility>
 #include <vector>
 
-#include <wpi/span.h>
-
 #include "cscore_cpp.h"
 
 namespace cs {
@@ -141,8 +140,6 @@
     return m_handle == other.m_handle;
   }
 
-  bool operator!=(const VideoSource& other) const { return !(*this == other); }
-
   /**
    * Get the kind of the source.
    */
@@ -516,7 +513,7 @@
    * @param urls Array of Camera URLs
    * @param kind Camera kind (e.g. kAxis)
    */
-  HttpCamera(std::string_view name, wpi::span<const std::string> urls,
+  HttpCamera(std::string_view name, std::span<const std::string> urls,
              HttpCameraKind kind = kUnknown);
 
   /**
@@ -541,7 +538,7 @@
   /**
    * Change the URLs used to connect to the camera.
    */
-  void SetUrls(wpi::span<const std::string> urls);
+  void SetUrls(std::span<const std::string> urls);
 
   /**
    * Change the URLs used to connect to the camera.
@@ -560,7 +557,7 @@
  */
 class AxisCamera : public HttpCamera {
   static std::string HostToUrl(std::string_view host);
-  static std::vector<std::string> HostToUrl(wpi::span<const std::string> hosts);
+  static std::vector<std::string> HostToUrl(std::span<const std::string> hosts);
   template <typename T>
   static std::vector<std::string> HostToUrl(std::initializer_list<T> hosts);
 
@@ -595,7 +592,7 @@
    * @param name Source name (arbitrary unique identifier)
    * @param hosts Array of Camera host IPs/DNS names
    */
-  AxisCamera(std::string_view name, wpi::span<const std::string> hosts);
+  AxisCamera(std::string_view name, std::span<const std::string> hosts);
 
   /**
    * Create a source for an Axis IP camera.
@@ -696,7 +693,7 @@
    * @param choices Choices
    */
   void SetEnumPropertyChoices(const VideoProperty& property,
-                              wpi::span<const std::string> choices);
+                              std::span<const std::string> choices);
 
   /**
    * Configure enum property choices.
@@ -737,8 +734,6 @@
     return m_handle == other.m_handle;
   }
 
-  bool operator!=(const VideoSink& other) const { return !(*this == other); }
-
   /**
    * Get the kind of the sink.
    */
diff --git a/third_party/allwpilib/cscore/src/main/native/include/cscore_oo.inc b/third_party/allwpilib/cscore/src/main/native/include/cscore_oo.inc
index 5037d97..ff3540d 100644
--- a/third_party/allwpilib/cscore/src/main/native/include/cscore_oo.inc
+++ b/third_party/allwpilib/cscore/src/main/native/include/cscore_oo.inc
@@ -302,7 +302,7 @@
     : HttpCamera(name, std::string_view{url}, kind) {}
 
 inline HttpCamera::HttpCamera(std::string_view name,
-                              wpi::span<const std::string> urls,
+                              std::span<const std::string> urls,
                               HttpCameraKind kind) {
   m_handle = CreateHttpCamera(
       name, urls, static_cast<CS_HttpCameraKind>(static_cast<int>(kind)),
@@ -329,7 +329,7 @@
       static_cast<int>(::cs::GetHttpCameraKind(m_handle, &m_status)));
 }
 
-inline void HttpCamera::SetUrls(wpi::span<const std::string> urls) {
+inline void HttpCamera::SetUrls(std::span<const std::string> urls) {
   m_status = 0;
   ::cs::SetHttpCameraUrls(m_handle, urls, &m_status);
 }
@@ -351,7 +351,7 @@
 }
 
 inline std::vector<std::string> AxisCamera::HostToUrl(
-    wpi::span<const std::string> hosts) {
+    std::span<const std::string> hosts) {
   std::vector<std::string> rv;
   rv.reserve(hosts.size());
   for (const auto& host : hosts) {
@@ -381,7 +381,7 @@
     : HttpCamera(name, HostToUrl(std::string_view{host}), kAxis) {}
 
 inline AxisCamera::AxisCamera(std::string_view name,
-                              wpi::span<const std::string> hosts)
+                              std::span<const std::string> hosts)
     : HttpCamera(name, HostToUrl(hosts), kAxis) {}
 
 template <typename T>
@@ -452,7 +452,7 @@
 }
 
 inline void ImageSource::SetEnumPropertyChoices(
-    const VideoProperty& property, wpi::span<const std::string> choices) {
+    const VideoProperty& property, std::span<const std::string> choices) {
   m_status = 0;
   SetSourceEnumPropertyChoices(m_handle, property.m_handle, choices, &m_status);
 }
diff --git a/third_party/allwpilib/cscore/src/main/native/include/cscore_runloop.h b/third_party/allwpilib/cscore/src/main/native/include/cscore_runloop.h
new file mode 100644
index 0000000..149e39d
--- /dev/null
+++ b/third_party/allwpilib/cscore/src/main/native/include/cscore_runloop.h
@@ -0,0 +1,11 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+namespace cs {
+void RunMainRunLoop();
+int RunMainRunLoopTimeout(double timeoutSeconds);
+void StopMainRunLoop();
+}  // namespace cs
diff --git a/third_party/allwpilib/cscore/src/main/native/linux/RunLoopHelpers.cpp b/third_party/allwpilib/cscore/src/main/native/linux/RunLoopHelpers.cpp
new file mode 100644
index 0000000..cfed76e
--- /dev/null
+++ b/third_party/allwpilib/cscore/src/main/native/linux/RunLoopHelpers.cpp
@@ -0,0 +1,38 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <wpi/Synchronization.h>
+
+#include "cscore_runloop.h"
+
+static wpi::Event& GetInstance() {
+  static wpi::Event event;
+  return event;
+}
+
+namespace cs {
+void RunMainRunLoop() {
+  wpi::Event& event = GetInstance();
+  wpi::WaitForObject(event.GetHandle());
+}
+
+int RunMainRunLoopTimeout(double timeoutSeconds) {
+  wpi::Event& event = GetInstance();
+  bool timedOut = false;
+  bool signaled =
+      wpi::WaitForObject(event.GetHandle(), timeoutSeconds, &timedOut);
+  if (timedOut) {
+    return 3;
+  }
+  if (signaled) {
+    return 2;
+  }
+  return 1;
+}
+
+void StopMainRunLoop() {
+  wpi::Event& event = GetInstance();
+  event.Set();
+}
+}  // namespace cs
diff --git a/third_party/allwpilib/cscore/src/main/native/linux/UsbCameraImpl.cpp b/third_party/allwpilib/cscore/src/main/native/linux/UsbCameraImpl.cpp
index b49a93d..270905b 100644
--- a/third_party/allwpilib/cscore/src/main/native/linux/UsbCameraImpl.cpp
+++ b/third_party/allwpilib/cscore/src/main/native/linux/UsbCameraImpl.cpp
@@ -82,6 +82,10 @@
       return VideoMode::kBGR;
     case V4L2_PIX_FMT_GREY:
       return VideoMode::kGray;
+    case V4L2_PIX_FMT_Y16:
+      return VideoMode::kY16;
+    case V4L2_PIX_FMT_UYVY:
+      return VideoMode::kUYVY;
     default:
       return VideoMode::kUnknown;
   }
@@ -100,6 +104,10 @@
       return V4L2_PIX_FMT_BGR24;
     case VideoMode::kGray:
       return V4L2_PIX_FMT_GREY;
+    case VideoMode::kY16:
+      return V4L2_PIX_FMT_Y16;
+    case VideoMode::kUYVY:
+      return V4L2_PIX_FMT_UYVY;
     default:
       return 0;
   }
@@ -140,6 +148,12 @@
     }
     return 100;
   }
+  // Arducam OV9281 exposure setting quirk
+  if (m_ov9281_exposure && rawProp.name == "raw_exposure_absolute" &&
+      rawProp.minimum == 1 && rawProp.maximum == 5000) {
+    // real range is 1-75
+    return 100.0 * (rawValue - 1) / (75 - 1);
+  }
   return 100.0 * (rawValue - rawProp.minimum) /
          (rawProp.maximum - rawProp.minimum);
 }
@@ -159,6 +173,12 @@
     }
     return quirkLifeCamHd3000[ndx];
   }
+  // Arducam OV9281 exposure setting quirk
+  if (m_ov9281_exposure && rawProp.name == "raw_exposure_absolute" &&
+      rawProp.minimum == 1 && rawProp.maximum == 5000) {
+    // real range is 1-75
+    return 1 + (75 - 1) * (percentValue / 100.0);
+  }
   return rawProp.minimum +
          (rawProp.maximum - rawProp.minimum) * (percentValue / 100.0);
 }
@@ -454,7 +474,7 @@
 
     // Handle notify events
     if (notify_fd >= 0 && FD_ISSET(notify_fd, &readfds)) {
-      SDEBUG4("{}", "notify event");
+      SDEBUG4("notify event");
       struct inotify_event event;
       do {
         // Read the event structure
@@ -483,7 +503,7 @@
 
     // Handle commands
     if (command_fd >= 0 && FD_ISSET(command_fd, &readfds)) {
-      SDEBUG4("{}", "got command");
+      SDEBUG4("got command");
       // Read it to clear
       eventfd_t val;
       eventfd_read(command_fd, &val);
@@ -493,7 +513,7 @@
 
     // Handle frames
     if (m_streaming && fd >= 0 && FD_ISSET(fd, &readfds)) {
-      SDEBUG4("{}", "grabbing image");
+      SDEBUG4("grabbing image");
 
       // Dequeue buffer
       struct v4l2_buffer buf;
@@ -501,7 +521,7 @@
       buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
       buf.memory = V4L2_MEMORY_MMAP;
       if (DoIoctl(fd, VIDIOC_DQBUF, &buf) != 0) {
-        SWARNING("{}", "could not dequeue buffer");
+        SWARNING("could not dequeue buffer");
         wasStreaming = m_streaming;
         DeviceStreamOff();
         DeviceDisconnect();
@@ -525,7 +545,7 @@
         bool good = true;
         if (m_mode.pixelFormat == VideoMode::kMJPEG &&
             !GetJpegSize(image, &width, &height)) {
-          SWARNING("{}", "invalid JPEG image received from camera");
+          SWARNING("invalid JPEG image received from camera");
           good = false;
         }
         if (good) {
@@ -536,7 +556,7 @@
 
       // Requeue buffer
       if (DoIoctl(fd, VIDIOC_QBUF, &buf) != 0) {
-        SWARNING("{}", "could not requeue buffer");
+        SWARNING("could not requeue buffer");
         wasStreaming = m_streaming;
         DeviceStreamOff();
         DeviceDisconnect();
@@ -579,7 +599,7 @@
   }
 
   // Try to open the device
-  SDEBUG3("{}", "opening device");
+  SDEBUG3("opening device");
   int fd = open(m_path.c_str(), O_RDWR);
   if (fd < 0) {
     return;
@@ -587,7 +607,7 @@
   m_fd = fd;
 
   // Get capabilities
-  SDEBUG3("{}", "getting capabilities");
+  SDEBUG3("getting capabilities");
   struct v4l2_capability vcap;
   std::memset(&vcap, 0, sizeof(vcap));
   if (DoIoctl(fd, VIDIOC_QUERYCAP, &vcap) >= 0) {
@@ -599,18 +619,18 @@
 
   // Get or restore video mode
   if (!m_properties_cached) {
-    SDEBUG3("{}", "caching properties");
+    SDEBUG3("caching properties");
     DeviceCacheProperties();
     DeviceCacheVideoModes();
     DeviceCacheMode();
     m_properties_cached = true;
   } else {
-    SDEBUG3("{}", "restoring video mode");
+    SDEBUG3("restoring video mode");
     DeviceSetMode();
     DeviceSetFPS();
 
     // Restore settings
-    SDEBUG3("{}", "restoring settings");
+    SDEBUG3("restoring settings");
     std::unique_lock lock2(m_mutex);
     for (size_t i = 0; i < m_propertyData.size(); ++i) {
       const auto prop =
@@ -625,21 +645,21 @@
   }
 
   // Request buffers
-  SDEBUG3("{}", "allocating buffers");
+  SDEBUG3("allocating buffers");
   struct v4l2_requestbuffers rb;
   std::memset(&rb, 0, sizeof(rb));
   rb.count = kNumBuffers;
   rb.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
   rb.memory = V4L2_MEMORY_MMAP;
   if (DoIoctl(fd, VIDIOC_REQBUFS, &rb) != 0) {
-    SWARNING("{}", "could not allocate buffers");
+    SWARNING("could not allocate buffers");
     close(fd);
     m_fd = -1;
     return;
   }
 
   // Map buffers
-  SDEBUG3("{}", "mapping buffers");
+  SDEBUG3("mapping buffers");
   for (int i = 0; i < kNumBuffers; ++i) {
     struct v4l2_buffer buf;
     std::memset(&buf, 0, sizeof(buf));
@@ -689,7 +709,7 @@
   }
 
   // Queue buffers
-  SDEBUG3("{}", "queuing buffers");
+  SDEBUG3("queuing buffers");
   for (int i = 0; i < kNumBuffers; ++i) {
     struct v4l2_buffer buf;
     std::memset(&buf, 0, sizeof(buf));
@@ -708,7 +728,6 @@
     if (errno == ENOSPC) {
       // indicates too much USB bandwidth requested
       SERROR(
-          "{}",
           "could not start streaming due to USB bandwidth limitations; try a "
           "lower resolution or a different pixel format (VIDIOC_STREAMON: "
           "No space left on device)");
@@ -718,7 +737,7 @@
     }
     return false;
   }
-  SDEBUG4("{}", "enabled streaming");
+  SDEBUG4("enabled streaming");
   m_streaming = true;
   return true;
 }
@@ -735,7 +754,7 @@
   if (DoIoctl(fd, VIDIOC_STREAMOFF, &type) != 0) {
     return false;
   }
-  SDEBUG4("{}", "disabled streaming");
+  SDEBUG4("disabled streaming");
   m_streaming = false;
   return true;
 }
@@ -1000,7 +1019,7 @@
 #endif
   vfmt.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
   if (DoIoctl(fd, VIDIOC_G_FMT, &vfmt) != 0) {
-    SERROR("{}", "could not read current video mode");
+    SERROR("could not read current video mode");
     std::scoped_lock lock(m_mutex);
     m_mode = VideoMode{VideoMode::kMJPEG, 320, 240, 30};
     return;
@@ -1385,6 +1404,7 @@
   std::string_view desc = GetDescription(descbuf);
   m_lifecam_exposure = wpi::ends_with(desc, "LifeCam HD-3000") ||
                        wpi::ends_with(desc, "LifeCam Cinema (TM)");
+  m_ov9281_exposure = wpi::contains(desc, "OV9281");
   m_picamera = wpi::ends_with(desc, "mmal service");
 
   int deviceNum = GetDeviceNum(m_path.c_str());
@@ -1668,7 +1688,7 @@
     ::closedir(dp);
   } else {
     // *status = ;
-    WPI_ERROR(Instance::GetInstance().logger, "{}", "Could not open /dev");
+    WPI_ERROR(Instance::GetInstance().logger, "Could not open /dev");
     return retval;
   }
 
diff --git a/third_party/allwpilib/cscore/src/main/native/linux/UsbCameraImpl.h b/third_party/allwpilib/cscore/src/main/native/linux/UsbCameraImpl.h
index a032466..acf1bfc 100644
--- a/third_party/allwpilib/cscore/src/main/native/linux/UsbCameraImpl.h
+++ b/third_party/allwpilib/cscore/src/main/native/linux/UsbCameraImpl.h
@@ -161,6 +161,7 @@
   // Quirks
   bool m_lifecam_exposure{false};    // Microsoft LifeCam exposure
   bool m_ps3eyecam_exposure{false};  // PS3 Eyecam exposure
+  bool m_ov9281_exposure{false};     // Arducam OV9281 exposure
   bool m_picamera{false};            // Raspberry Pi camera
 
   //
diff --git a/third_party/allwpilib/cscore/src/main/native/linux/UsbCameraListener.cpp b/third_party/allwpilib/cscore/src/main/native/linux/UsbCameraListener.cpp
index 40e84c5..c5a9934 100644
--- a/third_party/allwpilib/cscore/src/main/native/linux/UsbCameraListener.cpp
+++ b/third_party/allwpilib/cscore/src/main/native/linux/UsbCameraListener.cpp
@@ -4,10 +4,10 @@
 
 #include "UsbCameraListener.h"
 
-#include <wpi/EventLoopRunner.h>
 #include <wpi/StringExtras.h>
-#include <wpi/uv/FsEvent.h>
-#include <wpi/uv/Timer.h>
+#include <wpinet/EventLoopRunner.h>
+#include <wpinet/uv/FsEvent.h>
+#include <wpinet/uv/Timer.h>
 
 #include "Notifier.h"
 
diff --git a/third_party/allwpilib/cscore/src/main/native/linux/UsbUtil.cpp b/third_party/allwpilib/cscore/src/main/native/linux/UsbUtil.cpp
index 7d22054..fc6cbd2 100644
--- a/third_party/allwpilib/cscore/src/main/native/linux/UsbUtil.cpp
+++ b/third_party/allwpilib/cscore/src/main/native/linux/UsbUtil.cpp
@@ -58,13 +58,13 @@
       // next vendor, but didn't match product?
       if (line[0] != '\t') {
         buf += "Unknown";
-        return buf;
+        return std::string{buf};
       }
 
       // look for product
       if (wpi::starts_with(wpi::substr(line, 1), productStr)) {
         buf += wpi::trim(wpi::substr(line, 6));
-        return buf;
+        return std::string{buf};
       }
     }
   }
diff --git a/third_party/allwpilib/cscore/src/main/native/objcpp/RunLoopHelpers.mm b/third_party/allwpilib/cscore/src/main/native/objcpp/RunLoopHelpers.mm
new file mode 100644
index 0000000..10acef8
--- /dev/null
+++ b/third_party/allwpilib/cscore/src/main/native/objcpp/RunLoopHelpers.mm
@@ -0,0 +1,30 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "cscore_runloop.h"
+
+#include <CoreFoundation/CFRunLoop.h>
+#import <Foundation/Foundation.h>
+
+namespace cs {
+void RunMainRunLoop() {
+  if (CFRunLoopGetMain() != CFRunLoopGetCurrent()) {
+    NSLog(@"This method can only be called from the main thread");
+    return;
+  }
+  CFRunLoopRun();
+}
+
+int RunMainRunLoopTimeout(double timeoutSeconds) {
+  if (CFRunLoopGetMain() != CFRunLoopGetCurrent()) {
+    NSLog(@"This method can only be called from the main thread");
+    return -1;
+  }
+  return CFRunLoopRunInMode(kCFRunLoopDefaultMode, timeoutSeconds, false);
+}
+
+void StopMainRunLoop() {
+  CFRunLoopStop(CFRunLoopGetMain());
+}
+}
diff --git a/third_party/allwpilib/cscore/src/main/native/objcpp/UsbCameraDelegate.h b/third_party/allwpilib/cscore/src/main/native/objcpp/UsbCameraDelegate.h
new file mode 100644
index 0000000..61a0473
--- /dev/null
+++ b/third_party/allwpilib/cscore/src/main/native/objcpp/UsbCameraDelegate.h
@@ -0,0 +1,22 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#import <AVFoundation/AVFoundation.h>
+#include <memory>
+
+namespace cs {
+class UsbCameraImpl;
+}
+
+@interface UsbCameraDelegate
+    : NSObject <AVCaptureVideoDataOutputSampleBufferDelegate>
+
+@property(nonatomic) std::weak_ptr<cs::UsbCameraImpl> cppImpl;
+
+- (void)captureOutput:(AVCaptureOutput*)captureOutput
+    didOutputSampleBuffer:(CMSampleBufferRef)sampleBuffer
+           fromConnection:(AVCaptureConnection*)connection;
+@end
diff --git a/third_party/allwpilib/cscore/src/main/native/objcpp/UsbCameraDelegate.mm b/third_party/allwpilib/cscore/src/main/native/objcpp/UsbCameraDelegate.mm
new file mode 100644
index 0000000..efa0fbf
--- /dev/null
+++ b/third_party/allwpilib/cscore/src/main/native/objcpp/UsbCameraDelegate.mm
@@ -0,0 +1,67 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#import "UsbCameraDelegate.h"
+#include "UsbCameraImpl.h"
+
+#include <wpi/timestamp.h>
+
+#include <opencv2/core/core.hpp>
+#include <opencv2/imgproc/imgproc.hpp>
+
+@implementation UsbCameraDelegate
+
+- (id)init {
+  self = [super init];
+  return self;
+}
+
+- (void)captureOutput:(AVCaptureOutput*)captureOutput
+    didOutputSampleBuffer:(CMSampleBufferRef)sampleBuffer
+           fromConnection:(AVCaptureConnection*)connection {
+  (void)captureOutput;
+  (void)sampleBuffer;
+  (void)connection;
+
+  auto sharedThis = self.cppImpl.lock();
+  if (!sharedThis) {
+    return;
+  }
+
+  // Buffer always comes in a 32BGRA
+  auto imageBuffer = CMSampleBufferGetImageBuffer(sampleBuffer);
+
+  CVPixelBufferLockBaseAddress(imageBuffer, 0);
+
+  void* baseaddress = CVPixelBufferGetBaseAddress(imageBuffer);
+
+  size_t width = CVPixelBufferGetWidth(imageBuffer);
+  size_t height = CVPixelBufferGetHeight(imageBuffer);
+  size_t rowBytes = CVPixelBufferGetBytesPerRow(imageBuffer);
+  OSType pixelFormat = CVPixelBufferGetPixelFormatType(imageBuffer);
+
+  if (rowBytes == 0) {
+    CVPixelBufferUnlockBaseAddress(imageBuffer, 0);
+    return;
+  }
+
+  if (pixelFormat != kCVPixelFormatType_32BGRA) {
+    NSLog(@"Unknown Pixel Format %u", pixelFormat);
+    CVPixelBufferUnlockBaseAddress(imageBuffer, 0);
+    return;
+  }
+
+  size_t currSize = width * 3 * height;
+
+  auto tmpMat = cv::Mat(height, width, CV_8UC4, baseaddress, rowBytes);
+  auto image = sharedThis->AllocImage(cs::VideoMode::PixelFormat::kBGR, width,
+                                      height, currSize);
+  cv::cvtColor(tmpMat, image->AsMat(), cv::COLOR_BGRA2BGR);
+
+  CVPixelBufferUnlockBaseAddress(imageBuffer, 0);
+
+  sharedThis->objcPutFrame(std::move(image), wpi::Now());
+}
+
+@end
diff --git a/third_party/allwpilib/cscore/src/main/native/objcpp/UsbCameraImpl.h b/third_party/allwpilib/cscore/src/main/native/objcpp/UsbCameraImpl.h
new file mode 100644
index 0000000..0fd09fb
--- /dev/null
+++ b/third_party/allwpilib/cscore/src/main/native/objcpp/UsbCameraImpl.h
@@ -0,0 +1,96 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#import <AVFoundation/AVFoundation.h>
+#import "UsbCameraDelegate.h"
+#import "UsbCameraImplObjc.h"
+
+#include <memory>
+#include <string>
+#include <optional>
+
+#include "SourceImpl.h"
+
+namespace cs {
+struct CameraFPSRange {
+  int min;
+  int max;
+
+  bool IsWithinRange(int fps) { return fps >= min && fps <= max; }
+};
+
+struct CameraModeStore {
+  VideoMode mode;
+  AVCaptureDeviceFormat* format;
+  std::vector<CameraFPSRange> fpsRanges;
+};
+
+class UsbCameraImpl : public SourceImpl {
+ public:
+  UsbCameraImpl(std::string_view name, wpi::Logger& logger, Notifier& notifier,
+                Telemetry& telemetry, std::string_view path);
+  UsbCameraImpl(std::string_view name, wpi::Logger& logger, Notifier& notifier,
+                Telemetry& telemetry, int deviceId);
+  ~UsbCameraImpl() override;
+
+  void Start() override;
+
+  // Property functions
+  void SetProperty(int property, int value, CS_Status* status) override;
+  void SetStringProperty(int property, std::string_view value,
+                         CS_Status* status) override;
+
+  // Standard common camera properties
+  void SetBrightness(int brightness, CS_Status* status) override;
+  int GetBrightness(CS_Status* status) const override;
+  void SetWhiteBalanceAuto(CS_Status* status) override;
+  void SetWhiteBalanceHoldCurrent(CS_Status* status) override;
+  void SetWhiteBalanceManual(int value, CS_Status* status) override;
+  void SetExposureAuto(CS_Status* status) override;
+  void SetExposureHoldCurrent(CS_Status* status) override;
+  void SetExposureManual(int value, CS_Status* status) override;
+
+  bool SetVideoMode(const VideoMode& mode, CS_Status* status) override;
+  bool SetPixelFormat(VideoMode::PixelFormat pixelFormat,
+                      CS_Status* status) override;
+  bool SetResolution(int width, int height, CS_Status* status) override;
+  bool SetFPS(int fps, CS_Status* status) override;
+
+  void NumSinksChanged() override;
+  void NumSinksEnabledChanged() override;
+
+  cs::Notifier& objcGetNotifier() { return m_notifier; }
+
+  void objcSwapVideoModes(std::vector<VideoMode>& modes) {
+    std::scoped_lock lock(m_mutex);
+    m_videoModes.swap(modes);
+  }
+
+  void objcSetVideoMode(const VideoMode& mode) {
+    std::scoped_lock lock(m_mutex);
+    m_mode = mode;
+  }
+
+  void objcPutFrame(std::unique_ptr<Image> image, Frame::Time time) {
+    PutFrame(std::move(image), time);
+  }
+
+  const VideoMode& objcGetVideoMode() const { return m_mode; }
+
+  std::vector<CameraModeStore>& objcGetPlatformVideoModes() {
+    return m_platformModes;
+  }
+
+  wpi::Logger& objcGetLogger() { return m_logger; }
+
+  UsbCameraImplObjc* cppGetObjc() { return m_objc; }
+
+ private:
+  UsbCameraImplObjc* m_objc;
+  std::vector<CameraModeStore> m_platformModes;
+  VideoMode m_mode;
+};
+}  // namespace cs
diff --git a/third_party/allwpilib/cscore/src/main/native/objcpp/UsbCameraImpl.mm b/third_party/allwpilib/cscore/src/main/native/objcpp/UsbCameraImpl.mm
new file mode 100644
index 0000000..5607fbf
--- /dev/null
+++ b/third_party/allwpilib/cscore/src/main/native/objcpp/UsbCameraImpl.mm
@@ -0,0 +1,203 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#import <Foundation/Foundation.h>
+#import <AVFoundation/AVFoundation.h>
+
+#include <iostream>
+
+#include <vector>
+#include <string>
+#include <wpi/timestamp.h>
+
+#pragma GCC diagnostic ignored "-Wunused-parameter"
+#include "Handle.h"
+#include "Log.h"
+#include "Notifier.h"
+#include "Instance.h"
+#include "c_util.h"
+#include "cscore_cpp.h"
+#include "opencv2/imgproc.hpp"
+#include "UsbCameraImpl.h"
+
+namespace cs {
+
+UsbCameraImpl::UsbCameraImpl(std::string_view name, wpi::Logger& logger,
+                             Notifier& notifier, Telemetry& telemetry,
+                             std::string_view path)
+    : SourceImpl{name, logger, notifier, telemetry} {
+  UsbCameraImplObjc* objc = [[UsbCameraImplObjc alloc] init];
+  objc.path = [[NSString alloc] initWithBytes:path.data()
+                                       length:path.size()
+                                     encoding:NSUTF8StringEncoding];
+  m_objc = objc;
+}
+UsbCameraImpl::UsbCameraImpl(std::string_view name, wpi::Logger& logger,
+                             Notifier& notifier, Telemetry& telemetry,
+                             int deviceId)
+    : SourceImpl{name, logger, notifier, telemetry} {
+  UsbCameraImplObjc* objc = [[UsbCameraImplObjc alloc] init];
+  objc.path = nil;
+  objc.deviceId = deviceId;
+  m_objc = objc;
+}
+
+UsbCameraImpl::~UsbCameraImpl() {
+  m_objc = nil;
+}
+
+void UsbCameraImpl::Start() {
+  [m_objc start];
+}
+
+// Property functions
+void UsbCameraImpl::SetProperty(int property, int value, CS_Status* status) {
+  [m_objc setProperty:property withValue:value status:status];
+}
+void UsbCameraImpl::SetStringProperty(int property, std::string_view value,
+                                      CS_Status* status) {
+  [m_objc setStringProperty:property withValue:&value status:status];
+}
+
+// Standard common camera properties
+void UsbCameraImpl::SetBrightness(int brightness, CS_Status* status) {
+  [m_objc setBrightness:brightness status:status];
+}
+int UsbCameraImpl::GetBrightness(CS_Status* status) const {
+  return [m_objc getBrightness:status];
+}
+void UsbCameraImpl::SetWhiteBalanceAuto(CS_Status* status) {
+  [m_objc setWhiteBalanceAuto:status];
+}
+void UsbCameraImpl::SetWhiteBalanceHoldCurrent(CS_Status* status) {
+  [m_objc setWhiteBalanceHoldCurrent:status];
+}
+void UsbCameraImpl::SetWhiteBalanceManual(int value, CS_Status* status) {
+  [m_objc setWhiteBalanceManual:value status:status];
+}
+void UsbCameraImpl::SetExposureAuto(CS_Status* status) {
+  [m_objc setExposureAuto:status];
+}
+void UsbCameraImpl::SetExposureHoldCurrent(CS_Status* status) {
+  [m_objc setExposureHoldCurrent:status];
+}
+void UsbCameraImpl::SetExposureManual(int value, CS_Status* status) {
+  [m_objc setExposureManual:value status:status];
+}
+
+bool UsbCameraImpl::SetVideoMode(const VideoMode& mode, CS_Status* status) {
+  return [m_objc setVideoMode:mode status:status];
+}
+bool UsbCameraImpl::SetPixelFormat(VideoMode::PixelFormat pixelFormat,
+                                   CS_Status* status) {
+  return [m_objc setPixelFormat:pixelFormat status:status];
+}
+bool UsbCameraImpl::SetResolution(int width, int height, CS_Status* status) {
+  return [m_objc setResolutionWidth:width withHeight:height status:status];
+}
+bool UsbCameraImpl::SetFPS(int fps, CS_Status* status) {
+  return [m_objc setFPS:fps status:status];
+}
+
+void UsbCameraImpl::NumSinksChanged() {
+  [m_objc numSinksChanged];
+}
+void UsbCameraImpl::NumSinksEnabledChanged() {
+  [m_objc numSinksEnabledChanged];
+}
+
+CS_Source CreateUsbCameraDev(std::string_view name, int dev,
+                             CS_Status* status) {
+  std::vector<UsbCameraInfo> devices = cs::EnumerateUsbCameras(status);
+  if (static_cast<int>(devices.size()) > dev) {
+    return CreateUsbCameraPath(name, devices[dev].path, status);
+  }
+  auto& inst = Instance::GetInstance();
+  return inst.CreateSource(CS_SOURCE_USB, std::make_shared<UsbCameraImpl>(
+                                              name, inst.logger, inst.notifier,
+                                              inst.telemetry, dev));
+}
+
+CS_Source CreateUsbCameraPath(std::string_view name, std::string_view path,
+                              CS_Status* status) {
+  (void)status;
+  auto& inst = Instance::GetInstance();
+  auto val = std::make_shared<UsbCameraImpl>(name, inst.logger, inst.notifier,
+                                             inst.telemetry, path);
+  val->cppGetObjc().cppImpl = val;
+  return inst.CreateSource(CS_SOURCE_USB, val);
+}
+
+std::vector<UsbCameraInfo> EnumerateUsbCameras(CS_Status* status) {
+  @autoreleasepool {
+    (void)status;
+    std::vector<UsbCameraInfo> retval;
+    NSArray<AVCaptureDeviceType>* deviceTypes = @[
+      AVCaptureDeviceTypeBuiltInWideAngleCamera,
+      AVCaptureDeviceTypeExternalUnknown
+    ];
+    AVCaptureDeviceDiscoverySession* session = [AVCaptureDeviceDiscoverySession
+        discoverySessionWithDeviceTypes:deviceTypes
+                              mediaType:AVMediaTypeVideo
+                               position:AVCaptureDevicePositionUnspecified];
+
+    NSArray* captureDevices = [session devices];
+
+    int count = 0;
+    for (id device in captureDevices) {
+      NSString* name = [device localizedName];
+      NSString* uniqueIdentifier = [(AVCaptureDevice*)device uniqueID];
+      retval.push_back(
+          {count, [uniqueIdentifier UTF8String], [name UTF8String], {}});
+
+      count++;
+    }
+
+    return retval;
+  }
+}
+
+void SetUsbCameraPath(CS_Source source, std::string_view path,
+                      CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data || data->kind != CS_SOURCE_USB) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  [static_cast<UsbCameraImpl&>(*data->source).cppGetObjc()
+      setNewCameraPath:&path];
+}
+
+std::string GetUsbCameraPath(CS_Source source, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data || data->kind != CS_SOURCE_USB) {
+    *status = CS_INVALID_HANDLE;
+    return std::string{};
+  }
+  std::string ret;
+  [static_cast<UsbCameraImpl&>(*data->source).cppGetObjc()
+      getCurrentCameraPath:&ret];
+  return ret;
+}
+
+UsbCameraInfo GetUsbCameraInfo(CS_Source source, CS_Status* status) {
+  UsbCameraInfo info;
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data || data->kind != CS_SOURCE_USB) {
+    *status = CS_INVALID_HANDLE;
+    return info;
+  }
+
+  [static_cast<UsbCameraImpl&>(*data->source).cppGetObjc()
+      getCurrentCameraPath:&info.path];
+  [static_cast<UsbCameraImpl&>(*data->source).cppGetObjc()
+      getCameraName:&info.name];
+  info.productId = 0;
+  info.vendorId = 0;
+  // ParseVidAndPid(info.path, &info.productId, &info.vendorId);
+  info.dev = -1;  // We have lost dev information by this point in time.
+  return info;
+}
+
+}  // namespace cs
diff --git a/third_party/allwpilib/cscore/src/main/native/objcpp/UsbCameraImplObjc.h b/third_party/allwpilib/cscore/src/main/native/objcpp/UsbCameraImplObjc.h
new file mode 100644
index 0000000..c173e80
--- /dev/null
+++ b/third_party/allwpilib/cscore/src/main/native/objcpp/UsbCameraImplObjc.h
@@ -0,0 +1,71 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#import <AVFoundation/AVFoundation.h>
+#import "UsbCameraDelegate.h"
+#include <memory>
+#include <string_view>
+#include "cscore_cpp.h"
+
+namespace cs {
+class UsbCameraImpl;
+}
+
+@interface UsbCameraImplObjc : NSObject
+
+@property(nonatomic) AVCaptureDeviceFormat* currentFormat;
+@property(nonatomic) int currentFPS;
+@property(nonatomic) std::weak_ptr<cs::UsbCameraImpl> cppImpl;
+@property(nonatomic) dispatch_queue_t sessionQueue;
+@property(nonatomic) NSString* path;
+@property(nonatomic) int deviceId;
+@property(nonatomic) bool propertiesCached;
+@property(nonatomic) bool streaming;
+@property(nonatomic) bool deviceValid;
+@property(nonatomic) bool isAuthorized;
+
+@property(nonatomic) AVCaptureDevice* videoDevice;
+@property(nonatomic) AVCaptureDeviceInput* videoInput;
+@property(nonatomic) UsbCameraDelegate* callback;
+@property(nonatomic) AVCaptureVideoDataOutput* videoOutput;
+@property(nonatomic) AVCaptureSession* session;
+
+- (void)start;
+
+// Property functions
+- (void)setProperty:(int)property
+          withValue:(int)value
+             status:(CS_Status*)status;
+- (void)setStringProperty:(int)property
+                withValue:(std::string_view*)value
+                   status:(CS_Status*)status;
+
+// Standard common camera properties
+- (void)setBrightness:(int)brightness status:(CS_Status*)status;
+- (int)getBrightness:(CS_Status*)status;
+- (void)setWhiteBalanceAuto:(CS_Status*)status;
+- (void)setWhiteBalanceHoldCurrent:(CS_Status*)status;
+- (void)setWhiteBalanceManual:(int)value status:(CS_Status*)status;
+- (void)setExposureAuto:(CS_Status*)status;
+- (void)setExposureHoldCurrent:(CS_Status*)status;
+- (void)setExposureManual:(int)value status:(CS_Status*)status;
+
+- (bool)setVideoMode:(const cs::VideoMode&)mode status:(CS_Status*)status;
+- (bool)setPixelFormat:(cs::VideoMode::PixelFormat)pixelFormat
+                status:(CS_Status*)status;
+- (bool)setResolutionWidth:(int)width
+                withHeight:(int)height
+                    status:(CS_Status*)status;
+- (bool)setFPS:(int)fps status:(CS_Status*)status;
+
+- (void)numSinksChanged;
+- (void)numSinksEnabledChanged;
+
+- (void)getCurrentCameraPath:(std::string*)path;
+- (void)getCameraName:(std::string*)name;
+- (void)setNewCameraPath:(std::string_view*)path;
+
+@end
diff --git a/third_party/allwpilib/cscore/src/main/native/objcpp/UsbCameraImplObjc.mm b/third_party/allwpilib/cscore/src/main/native/objcpp/UsbCameraImplObjc.mm
new file mode 100644
index 0000000..febe6a5
--- /dev/null
+++ b/third_party/allwpilib/cscore/src/main/native/objcpp/UsbCameraImplObjc.mm
@@ -0,0 +1,669 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#import "UsbCameraImplObjc.h"
+#include "UsbCameraImpl.h"
+
+#pragma GCC diagnostic ignored "-Wunused-parameter"
+#include "Notifier.h"
+#include "Log.h"
+
+template <typename S, typename... Args>
+inline void NamedLog(UsbCameraImplObjc* objc, unsigned int level,
+                     const char* file, unsigned int line, const S& format,
+                     Args&&... args) {
+  auto sharedThis = objc.cppImpl.lock();
+  if (!sharedThis) {
+    return;
+  }
+
+  wpi::Logger& logger = sharedThis->objcGetLogger();
+  std::string_view name = sharedThis->GetName();
+
+  if (logger.HasLogger() && level >= logger.min_level()) {
+    cs::NamedLogV(logger, level, file, line, name, format,
+                  fmt::make_format_args(args...));
+  }
+}
+
+#define OBJCLOG(level, format, ...)         \
+  NamedLog(self, level, __FILE__, __LINE__, \
+           FMT_STRING(format) __VA_OPT__(, ) __VA_ARGS__)
+
+#define OBJCERROR(format, ...) \
+  OBJCLOG(::wpi::WPI_LOG_ERROR, format __VA_OPT__(, ) __VA_ARGS__)
+#define OBJCWARNING(format, ...) \
+  OBJCLOG(::wpi::WPI_LOG_WARNING, format __VA_OPT__(, ) __VA_ARGS__)
+#define OBJCINFO(format, ...) \
+  OBJCLOG(::wpi::WPI_LOG_INFO, format __VA_OPT__(, ) __VA_ARGS__)
+
+#ifdef NDEBUG
+#define OBJCDEBUG(format, ...) \
+  do {                         \
+  } while (0)
+#define OBJCDEBUG1(format, ...) \
+  do {                          \
+  } while (0)
+#define OBJCDEBUG2(format, ...) \
+  do {                          \
+  } while (0)
+#define OBJCDEBUG3(format, ...) \
+  do {                          \
+  } while (0)
+#define OBJCDEBUG4(format, ...) \
+  do {                          \
+  } while (0)
+#else
+#define OBJCDEBUG(format, ...) \
+  OBJCLOG(::wpi::WPI_LOG_DEBUG, format __VA_OPT__(, ) __VA_ARGS__)
+#define OBJCDEBUG1(format, ...) \
+  OBJCLOG(::wpi::WPI_LOG_DEBUG1, format __VA_OPT__(, ) __VA_ARGS__)
+#define OBJCDEBUG2(format, ...) \
+  OBJCLOG(::wpi::WPI_LOG_DEBUG2, format __VA_OPT__(, ) __VA_ARGS__)
+#define OBJCDEBUG3(format, ...) \
+  OBJCLOG(::wpi::WPI_LOG_DEBUG3, format __VA_OPT__(, ) __VA_ARGS__)
+#define OBJCDEBUG4(format, ...) \
+  OBJCLOG(::wpi::WPI_LOG_DEBUG4, format __VA_OPT__(, ) __VA_ARGS__)
+#endif
+
+using namespace cs;
+
+@implementation UsbCameraImplObjc
+
+- (void)start {
+  switch ([AVCaptureDevice authorizationStatusForMediaType:AVMediaTypeVideo]) {
+    case AVAuthorizationStatusAuthorized:
+      self.isAuthorized = true;
+      break;
+    default:
+      OBJCERROR(
+          "Camera access explicitly blocked for application. No cameras are "
+          "accessable");
+      self.isAuthorized = false;
+      // TODO log
+      break;
+    case AVAuthorizationStatusNotDetermined:
+      dispatch_suspend(self.sessionQueue);
+      [AVCaptureDevice requestAccessForMediaType:AVMediaTypeVideo
+                               completionHandler:^(BOOL granted) {
+                                 self.isAuthorized = granted;
+                                 dispatch_resume(self.sessionQueue);
+                               }];
+      break;
+  }
+  dispatch_async(self.sessionQueue, ^{
+    [[NSNotificationCenter defaultCenter]
+        addObserver:self
+           selector:@selector(cameraConnected:)
+               name:AVCaptureDeviceWasConnectedNotification
+             object:nil];
+    [[NSNotificationCenter defaultCenter]
+        addObserver:self
+           selector:@selector(cameraDisconnected:)
+               name:AVCaptureDeviceWasDisconnectedNotification
+             object:nil];
+    [self deviceConnect];
+  });
+}
+
+// Property functions
+- (void)setProperty:(int)property
+          withValue:(int)value
+             status:(CS_Status*)status {
+}
+- (void)setStringProperty:(int)property
+                withValue:(std::string_view*)value
+                   status:(CS_Status*)status {
+}
+
+// Standard common camera properties
+- (void)setBrightness:(int)brightness status:(CS_Status*)status {
+  *status = CS_INVALID_PROPERTY;
+}
+- (int)getBrightness:(CS_Status*)status {
+  *status = CS_INVALID_PROPERTY;
+  return 0;
+}
+- (void)setWhiteBalanceAuto:(CS_Status*)status {
+  *status = CS_INVALID_PROPERTY;
+}
+- (void)setWhiteBalanceHoldCurrent:(CS_Status*)status {
+  *status = CS_INVALID_PROPERTY;
+}
+- (void)setWhiteBalanceManual:(int)value status:(CS_Status*)status {
+  *status = CS_INVALID_PROPERTY;
+}
+- (void)setExposureAuto:(CS_Status*)status {
+  *status = CS_INVALID_PROPERTY;
+}
+- (void)setExposureHoldCurrent:(CS_Status*)status {
+  *status = CS_INVALID_PROPERTY;
+}
+- (void)setExposureManual:(int)value status:(CS_Status*)status {
+  *status = CS_INVALID_PROPERTY;
+}
+
+- (bool)setVideoMode:(const cs::VideoMode&)mode status:(CS_Status*)status {
+  dispatch_async_and_wait(self.sessionQueue, ^{
+    auto sharedThis = self.cppImpl.lock();
+    if (!sharedThis) {
+      *status = CS_READ_FAILED;
+      return;
+    }
+
+    [self internalSetMode:mode status:status];
+  });
+  return true;
+}
+- (bool)setPixelFormat:(cs::VideoMode::PixelFormat)pixelFormat
+                status:(CS_Status*)status {
+  dispatch_async_and_wait(self.sessionQueue, ^{
+    auto sharedThis = self.cppImpl.lock();
+    if (!sharedThis) {
+      *status = CS_READ_FAILED;
+      return;
+    }
+    VideoMode newMode;
+    newMode = sharedThis->objcGetVideoMode();
+    newMode.pixelFormat = pixelFormat;
+
+    [self internalSetMode:newMode status:status];
+  });
+  return true;
+}
+- (bool)setResolutionWidth:(int)width
+                withHeight:(int)height
+                    status:(CS_Status*)status {
+  dispatch_async_and_wait(self.sessionQueue, ^{
+    auto sharedThis = self.cppImpl.lock();
+    if (!sharedThis) {
+      *status = CS_READ_FAILED;
+      return;
+    }
+    VideoMode newMode;
+    newMode = sharedThis->objcGetVideoMode();
+    newMode.width = width;
+    newMode.height = height;
+
+    [self internalSetMode:newMode status:status];
+  });
+  return true;
+}
+
+- (void)internalSetMode:(const cs::VideoMode&)newMode
+                 status:(CS_Status*)status {
+  auto sharedThis = self.cppImpl.lock();
+  if (!sharedThis) {
+    *status = CS_READ_FAILED;
+    return;
+  }
+  // If device is not connected, just apply and leave.
+  if (!self.propertiesCached) {
+    sharedThis->objcSetVideoMode(newMode);
+    *status = CS_OK;
+    return;
+  }
+
+  if (newMode != sharedThis->objcGetVideoMode()) {
+    OBJCDEBUG3("Trying Mode {} {} {} {}", newMode.pixelFormat, newMode.width,
+               newMode.height, newMode.fps);
+    int localFPS = 0;
+    AVCaptureDeviceFormat* newModeType = [self deviceCheckModeValid:&newMode
+                                                            withFps:&localFPS];
+    if (newModeType == nil) {
+      *status = CS_UNSUPPORTED_MODE;
+      return;
+    }
+
+    self.currentFormat = newModeType;
+    self.currentFPS = localFPS;
+    sharedThis->objcSetVideoMode(newMode);
+    [self deviceDisconnect];
+    [self deviceConnect];
+    sharedThis->objcGetNotifier().NotifySourceVideoMode(*sharedThis, newMode);
+  }
+  *status = CS_OK;
+}
+
+- (bool)setFPS:(int)fps status:(CS_Status*)status {
+  dispatch_async_and_wait(self.sessionQueue, ^{
+    auto sharedThis = self.cppImpl.lock();
+    if (!sharedThis) {
+      *status = CS_READ_FAILED;
+      return;
+    }
+    VideoMode newMode;
+    newMode = sharedThis->objcGetVideoMode();
+    newMode.fps = fps;
+
+    [self internalSetMode:newMode status:status];
+  });
+  return true;
+}
+
+- (void)numSinksChanged {
+  dispatch_async(self.sessionQueue, ^{
+    auto sharedThis = self.cppImpl.lock();
+    if (!sharedThis) {
+      return;
+    }
+    if (!sharedThis->IsEnabled()) {
+      [self deviceStreamOff];
+    } else if (!self.streaming && sharedThis->IsEnabled()) {
+      [self deviceStreamOn];
+    }
+  });
+}
+- (void)numSinksEnabledChanged {
+  [self numSinksChanged];
+}
+
+// All above is direct forwarders from C++, must always dispatch to loop
+
+- (void)getCurrentCameraPath:(std::string*)path {
+  dispatch_async_and_wait(self.sessionQueue, ^{
+    if (self.videoDevice == nil) {
+      return;
+    }
+    *path = [self.videoDevice.uniqueID UTF8String];
+  });
+}
+
+- (void)getCameraName:(std::string*)name {
+  dispatch_async_and_wait(self.sessionQueue, ^{
+    if (self.videoDevice == nil) {
+      return;
+    }
+    *name = [self.videoDevice.localizedName UTF8String];
+  });
+}
+
+- (void)setNewCameraPath:(std::string_view*)path {
+  dispatch_async_and_wait(self.sessionQueue, ^{
+    NSString* nsPath = [[NSString alloc] initWithBytes:path->data()
+                                                length:path->size()
+                                              encoding:NSUTF8StringEncoding];
+    if (self.path != nil && [self.path isEqualToString:nsPath]) {
+      return;
+    }
+    self.path = nsPath;
+    [self deviceDisconnect];
+    [self deviceConnect];
+  });
+}
+
+// All above are called from C++, must always dispatch to loop
+
+- (void)deviceCacheProperties {
+  if (self.session == nil) {
+    return;
+  }
+}
+
+static cs::VideoMode::PixelFormat FourCCToPixelFormat(FourCharCode fourcc) {
+  switch (fourcc) {
+    case kCVPixelFormatType_422YpCbCr8_yuvs:
+    case kCVPixelFormatType_422YpCbCr8FullRange:
+      return cs::VideoMode::PixelFormat::kYUYV;
+    default:
+      return cs::VideoMode::PixelFormat::kBGR;
+  }
+}
+
+- (void)deviceCacheVideoModes {
+  if (self.session == nil) {
+    return;
+  }
+
+  auto sharedThis = self.cppImpl.lock();
+  if (!sharedThis) {
+    return;
+  }
+  std::vector<CameraModeStore>& platformModes =
+      sharedThis->objcGetPlatformVideoModes();
+  platformModes.clear();
+
+  std::vector<VideoMode> modes;
+  @autoreleasepool {
+    NSArray<AVCaptureDeviceFormat*>* formats = self.videoDevice.formats;
+
+    int count = 0;
+
+    for (AVCaptureDeviceFormat* format in formats) {
+      CMFormatDescriptionRef cmformat = format.formatDescription;
+      CMVideoDimensions s1 = CMVideoFormatDescriptionGetDimensions(cmformat);
+
+      FourCharCode fourcc = CMFormatDescriptionGetMediaSubType(cmformat);
+      auto videoFormat = FourCCToPixelFormat(fourcc);
+
+      NSArray<AVFrameRateRange*>* frameRates =
+          format.videoSupportedFrameRateRanges;
+
+      CameraModeStore store;
+      store.mode.pixelFormat = videoFormat;
+      store.mode.width = static_cast<int>(s1.width);
+      store.mode.height = static_cast<int>(s1.height);
+      store.format = format;
+      int maxFps = 0;
+
+      for (AVFrameRateRange* rate in frameRates) {
+        CMTime highest = rate.minFrameDuration;
+        CMTime lowest = rate.maxFrameDuration;
+
+        int highestFps = highest.timescale / static_cast<double>(highest.value);
+        int lowestFps = lowest.timescale / static_cast<double>(lowest.value);
+
+        store.fpsRanges.emplace_back(CameraFPSRange{lowestFps, highestFps});
+        if (highestFps > maxFps) {
+          maxFps = highestFps;
+        }
+      }
+      store.mode.fps = maxFps;
+
+      modes.emplace_back(store.mode);
+      platformModes.emplace_back(store);
+      count++;
+    }
+  }
+
+  sharedThis->objcSwapVideoModes(modes);
+  sharedThis->objcGetNotifier().NotifySource(*sharedThis,
+                                             CS_SOURCE_VIDEOMODES_UPDATED);
+}
+
+- (AVCaptureDeviceFormat*)deviceCheckModeValid:(const cs::VideoMode*)toCheck
+                                       withFps:(int*)fps {
+  auto sharedThis = self.cppImpl.lock();
+  if (!sharedThis) {
+    return nil;
+  }
+
+  OBJCDEBUG3("Checking mode {} {} {} {}", toCheck->pixelFormat, toCheck->width,
+             toCheck->height, toCheck->fps);
+  std::vector<CameraModeStore>& platformModes =
+      sharedThis->objcGetPlatformVideoModes();
+  // Find the matching mode
+  auto match = std::find_if(platformModes.begin(), platformModes.end(),
+                            [&](CameraModeStore& input) {
+                              return input.mode.CompareWithoutFps(*toCheck);
+                            });
+
+  if (match == platformModes.end()) {
+    return nil;
+  }
+
+  // Check FPS
+  for (CameraFPSRange& range : match->fpsRanges) {
+    OBJCDEBUG3("Checking Range {} {}", range.min, range.max);
+    if (range.IsWithinRange(toCheck->fps)) {
+      *fps = toCheck->fps;
+      return match->format;
+    }
+  }
+
+  return nil;
+}
+
+- (void)deviceCacheMode {
+  if (!self.session) {
+    return;
+  }
+
+  auto sharedThis = self.cppImpl.lock();
+  if (!sharedThis) {
+    return;
+  }
+
+  std::vector<CameraModeStore>& platformModes =
+      sharedThis->objcGetPlatformVideoModes();
+
+  if (platformModes.size() == 0) {
+    return;
+  }
+
+  if (self.currentFormat == nil) {
+    int localFps = 0;
+    self.currentFormat =
+        [self deviceCheckModeValid:&sharedThis->objcGetVideoMode()
+                           withFps:&localFps];
+    if (self.currentFormat == nil) {
+      self.currentFormat = self.videoDevice.activeFormat;
+      auto result = std::find_if(platformModes.begin(), platformModes.end(),
+                                 [f = self.currentFormat](CameraModeStore& i) {
+                                   return [f isEqual:i.format];
+                                 });
+      if (result == platformModes.end()) {
+        auto& firstSupported = platformModes[0];
+        self.currentFormat = firstSupported.format;
+        self.currentFPS = firstSupported.mode.fps;
+        sharedThis->objcSetVideoMode(firstSupported.mode);
+      } else {
+        self.currentFPS = result->mode.fps;
+        sharedThis->objcSetVideoMode(result->mode);
+      }
+    } else {
+      self.currentFPS = localFps;
+    }
+  }
+
+  [self deviceSetMode];
+
+  sharedThis->objcGetNotifier().NotifySourceVideoMode(
+      *sharedThis, sharedThis->objcGetVideoMode());
+}
+
+- (void)deviceSetMode {
+  self.deviceValid = true;
+}
+
+- (bool)deviceStreamOn {
+  if (self.streaming) {
+    return false;
+  }
+  if (!self.deviceValid) {
+    return false;
+  }
+  self.streaming = true;
+
+  [self.session startRunning];
+
+  if ([self.videoDevice lockForConfiguration:nil]) {
+    if (self.currentFormat != nil) {
+      self.videoDevice.activeFormat = self.currentFormat;
+    }
+    if (self.currentFPS != 0) {
+      self.videoDevice.activeVideoMinFrameDuration =
+          CMTimeMake(1, self.currentFPS);
+      self.videoDevice.activeVideoMaxFrameDuration =
+          CMTimeMake(1, self.currentFPS);
+    }
+    [self.videoDevice unlockForConfiguration];
+  } else {
+    OBJCERROR("Failed to lock for configuration");
+  }
+
+  return true;
+}
+
+- (bool)deviceStreamOff {
+  if (self.streaming) {
+    [self.session stopRunning];
+  }
+  self.streaming = false;
+  return true;
+}
+
+- (id)init {
+  self = [super init];
+  // TODO pass in name, make this queue specific
+  self.sessionQueue =
+      dispatch_queue_create("session queue", DISPATCH_QUEUE_SERIAL);
+  return self;
+}
+
+- (void)deviceDisconnect {
+  std::string pathStr = [self.path UTF8String];
+  OBJCINFO("Disconnected from {}", pathStr);
+
+  [self deviceStreamOff];
+  self.session = nil;
+  self.videoOutput = nil;
+  self.callback = nil;
+  self.videoInput = nil;
+  self.videoDevice = nil;
+  self.streaming = false;
+  auto sharedThis = self.cppImpl.lock();
+  if (!sharedThis) {
+    return;
+  }
+  sharedThis->SetConnected(false);
+}
+
+- (bool)deviceConnect {
+  if (!self.isAuthorized) {
+    OBJCERROR(
+        "Camera access not authorized for application. No cameras are "
+        "accessable");
+    return false;
+  }
+
+  OSType pixelFormat = kCVPixelFormatType_32BGRA;
+
+  NSDictionary* pixelBufferOptions =
+      @{(id)kCVPixelBufferPixelFormatTypeKey : @(pixelFormat)};
+
+  if (self.session != nil) {
+    return true;
+  }
+
+  auto sharedThis = self.cppImpl.lock();
+  if (!sharedThis) {
+    return false;
+  }
+
+  if (self.path == nil) {
+    OBJCINFO("Starting for device id {}", self.deviceId);
+    // Enumerate Devices
+    CS_Status status = 0;
+    auto cameras = cs::EnumerateUsbCameras(&status);
+    if (static_cast<int>(cameras.size()) <= self.deviceId) {
+      return false;
+    }
+    std::string& path = cameras[self.deviceId].path;
+    self.path = [[NSString alloc] initWithBytes:path.data()
+                                         length:path.size()
+                                       encoding:NSUTF8StringEncoding];
+  }
+
+  std::string pathStr = [self.path UTF8String];
+  OBJCINFO("Connecting to USB camera on {}", pathStr);
+
+  self.videoDevice = [AVCaptureDevice deviceWithUniqueID:self.path];
+  if (self.videoDevice == nil) {
+    OBJCWARNING("Device Not found");
+    goto err;
+  }
+
+  self.videoInput = [AVCaptureDeviceInput deviceInputWithDevice:self.videoDevice
+                                                          error:nil];
+  if (self.videoInput == nil) {
+    OBJCWARNING("Creating AVCaptureDeviceInput failed");
+    goto err;
+  }
+
+  self.callback = [[UsbCameraDelegate alloc] init];
+  if (self.callback == nil) {
+    OBJCWARNING("Creating Camera Callback failed");
+    goto err;
+  }
+  self.callback.cppImpl = self.cppImpl;
+
+  self.videoOutput = [[AVCaptureVideoDataOutput alloc] init];
+  if (self.videoOutput == nil) {
+    OBJCWARNING("Creating AVCaptureVideoDataOutput failed");
+    goto err;
+  }
+
+  [self.videoOutput setSampleBufferDelegate:self.callback
+                                      queue:self.sessionQueue];
+
+  self.videoOutput.videoSettings = pixelBufferOptions;
+  self.videoOutput.alwaysDiscardsLateVideoFrames = YES;
+
+  self.session = [[AVCaptureSession alloc] init];
+  if (self.session == nil) {
+    OBJCWARNING("Creating AVCaptureSession failed");
+    goto err;
+  }
+
+  [[NSNotificationCenter defaultCenter]
+      addObserver:self
+         selector:@selector(sessionRuntimeError:)
+             name:AVCaptureSessionRuntimeErrorNotification
+           object:self.session];
+
+  [self.session addInput:self.videoInput];
+  [self.session addOutput:self.videoOutput];
+
+  sharedThis->SetDescription([self.videoDevice.localizedName UTF8String]);
+
+  if (!self.propertiesCached) {
+    OBJCDEBUG3("Caching properties");
+    [self deviceCacheProperties];
+    [self deviceCacheVideoModes];
+    [self deviceCacheMode];
+    self.propertiesCached = true;
+  } else {
+    OBJCDEBUG3("Restoring Video Mode");
+    [self deviceSetMode];
+  }
+
+  sharedThis->SetConnected(true);
+
+  if (sharedThis->IsEnabled()) {
+    [self deviceStreamOn];
+  }
+
+  return true;
+
+err:
+  self.session = nil;
+  self.videoOutput = nil;
+  self.callback = nil;
+  self.videoInput = nil;
+  self.videoDevice = nil;
+  return false;
+}
+
+// Helpers
+- (void)sessionRuntimeError:(NSNotification*)notification {
+  @autoreleasepool {
+    NSError* error = notification.userInfo[AVCaptureSessionErrorKey];
+    const char* str = [error.description UTF8String];
+    if (str) {
+      std::string errorStr = str;
+      OBJCERROR("Capture session runtime error: {}", errorStr);
+    }
+  }
+}
+
+- (void)cameraDisconnected:(NSNotification*)notification {
+  AVCaptureDevice* device = notification.object;
+  dispatch_async(self.sessionQueue, ^{
+    if (self.path != nil && [device.uniqueID isEqualToString:self.path]) {
+      [self deviceDisconnect];
+    }
+  });
+}
+
+- (void)cameraConnected:(NSNotification*)notification {
+  AVCaptureDevice* device = notification.object;
+  dispatch_async(self.sessionQueue, ^{
+    if (self.path == nil || [device.uniqueID isEqualToString:self.path]) {
+      [self deviceConnect];
+    }
+  });
+}
+
+@end
diff --git a/third_party/allwpilib/cscore/src/main/native/objcpp/UsbCameraListener.mm b/third_party/allwpilib/cscore/src/main/native/objcpp/UsbCameraListener.mm
new file mode 100644
index 0000000..b6b59d3
--- /dev/null
+++ b/third_party/allwpilib/cscore/src/main/native/objcpp/UsbCameraListener.mm
@@ -0,0 +1,111 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#import <AVFoundation/AVFoundation.h>
+#include "UsbCameraListener.h"
+
+#pragma GCC diagnostic ignored "-Wunused-parameter"
+#include "Notifier.h"
+
+using namespace cs;
+
+@interface UsbCameraListenerImpl : NSObject
+@property(nonatomic) Notifier* notifier;
+@property BOOL started;
+@property(nonatomic) dispatch_queue_t sessionQueue;
+
+- (void)start;
+- (void)stop;
+
+@end
+
+@implementation UsbCameraListenerImpl
+
+- (id)init {
+  self = [super init];
+  self.sessionQueue =
+      dispatch_queue_create("Camera Listener", DISPATCH_QUEUE_SERIAL);
+  return self;
+}
+
+- (void)start {
+  dispatch_async(self.sessionQueue, ^{
+    if (self.started) {
+      return;
+    }
+    self.started = YES;
+    [[NSNotificationCenter defaultCenter]
+        addObserver:self
+           selector:@selector(camerasChanged:)
+               name:AVCaptureDeviceWasConnectedNotification
+             object:nil];
+    [[NSNotificationCenter defaultCenter]
+        addObserver:self
+           selector:@selector(camerasChanged:)
+               name:AVCaptureDeviceWasDisconnectedNotification
+             object:nil];
+  });
+}
+
+- (void)stop {
+  dispatch_async_and_wait(self.sessionQueue, ^{
+    if (!self.started) {
+      return;
+    }
+    self.started = NO;
+    [[NSNotificationCenter defaultCenter]
+        removeObserver:self
+                  name:AVCaptureDeviceWasConnectedNotification
+                object:nil];
+    [[NSNotificationCenter defaultCenter]
+        removeObserver:self
+                  name:AVCaptureDeviceWasDisconnectedNotification
+                object:nil];
+  });
+}
+
+- (void)camerasChanged:(NSNotification*)notification {
+  @autoreleasepool {
+    dispatch_async(self.sessionQueue, ^{
+      if (!self.started) {
+        return;
+      }
+
+      AVCaptureDevice* device = notification.object;
+      if ([device.deviceType
+              isEqualToString:AVCaptureDeviceTypeBuiltInWideAngleCamera] ||
+          [device.deviceType
+              isEqualToString:AVCaptureDeviceTypeExternalUnknown]) {
+        self.notifier->NotifyUsbCamerasChanged();
+      }
+    });
+  }
+}
+
+@end
+
+class UsbCameraListener::Impl {
+ public:
+  UsbCameraListenerImpl* listener;
+
+  explicit Impl(Notifier& notifier) {
+    listener = [[UsbCameraListenerImpl alloc] init];
+    listener.notifier = &notifier;
+  }
+};
+
+UsbCameraListener::UsbCameraListener(wpi::Logger&, Notifier& notifier)
+    : m_impl{std::make_unique<Impl>(notifier)} {}
+
+UsbCameraListener::~UsbCameraListener() {
+  Stop();
+}
+
+void UsbCameraListener::Start() {
+  [m_impl->listener start];
+}
+
+void UsbCameraListener::Stop() {
+  [m_impl->listener stop];
+}
diff --git a/third_party/allwpilib/cscore/src/main/native/objcpp/objcpptemp.mm b/third_party/allwpilib/cscore/src/main/native/objcpp/objcpptemp.mm
deleted file mode 100644
index 27aaaff..0000000
--- a/third_party/allwpilib/cscore/src/main/native/objcpp/objcpptemp.mm
+++ /dev/null
@@ -1,12 +0,0 @@
-#import <Foundation/Foundation.h>
-
-@interface XYZPerson : NSObject
-- (void)sayHello;
-@end
-
-
-@implementation XYZPerson
-- (void)sayHello {
-    NSLog(@"Hello, World!");
-}
-@end
diff --git a/third_party/allwpilib/cscore/src/main/native/osx/UsbCameraImpl.cpp b/third_party/allwpilib/cscore/src/main/native/osx/UsbCameraImpl.cpp
deleted file mode 100644
index 3b5d821..0000000
--- a/third_party/allwpilib/cscore/src/main/native/osx/UsbCameraImpl.cpp
+++ /dev/null
@@ -1,41 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "cscore_cpp.h"
-
-namespace cs {
-
-CS_Source CreateUsbCameraDev(std::string_view name, int dev,
-                             CS_Status* status) {
-  *status = CS_INVALID_HANDLE;
-  return 0;
-}
-
-CS_Source CreateUsbCameraPath(std::string_view name, std::string_view path,
-                              CS_Status* status) {
-  *status = CS_INVALID_HANDLE;
-  return 0;
-}
-
-void SetUsbCameraPath(CS_Source source, std::string_view path,
-                      CS_Status* status) {
-  *status = CS_INVALID_HANDLE;
-}
-
-std::string GetUsbCameraPath(CS_Source source, CS_Status* status) {
-  *status = CS_INVALID_HANDLE;
-  return std::string{};
-}
-
-UsbCameraInfo GetUsbCameraInfo(CS_Source source, CS_Status* status) {
-  *status = CS_INVALID_HANDLE;
-  return UsbCameraInfo{};
-}
-
-std::vector<UsbCameraInfo> EnumerateUsbCameras(CS_Status* status) {
-  *status = CS_INVALID_HANDLE;
-  return std::vector<UsbCameraInfo>{};
-}
-
-}  // namespace cs
diff --git a/third_party/allwpilib/cscore/src/main/native/osx/UsbCameraListener.cpp b/third_party/allwpilib/cscore/src/main/native/osx/UsbCameraListener.cpp
deleted file mode 100644
index b83663d..0000000
--- a/third_party/allwpilib/cscore/src/main/native/osx/UsbCameraListener.cpp
+++ /dev/null
@@ -1,17 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "UsbCameraListener.h"
-
-using namespace cs;
-
-class UsbCameraListener::Impl {};
-
-UsbCameraListener::UsbCameraListener(wpi::Logger& logger, Notifier& notifier) {}
-
-UsbCameraListener::~UsbCameraListener() = default;
-
-void UsbCameraListener::Start() {}
-
-void UsbCameraListener::Stop() {}
diff --git a/third_party/allwpilib/cscore/src/main/native/windows/RunLoopHelpers.cpp b/third_party/allwpilib/cscore/src/main/native/windows/RunLoopHelpers.cpp
new file mode 100644
index 0000000..cfed76e
--- /dev/null
+++ b/third_party/allwpilib/cscore/src/main/native/windows/RunLoopHelpers.cpp
@@ -0,0 +1,38 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <wpi/Synchronization.h>
+
+#include "cscore_runloop.h"
+
+static wpi::Event& GetInstance() {
+  static wpi::Event event;
+  return event;
+}
+
+namespace cs {
+void RunMainRunLoop() {
+  wpi::Event& event = GetInstance();
+  wpi::WaitForObject(event.GetHandle());
+}
+
+int RunMainRunLoopTimeout(double timeoutSeconds) {
+  wpi::Event& event = GetInstance();
+  bool timedOut = false;
+  bool signaled =
+      wpi::WaitForObject(event.GetHandle(), timeoutSeconds, &timedOut);
+  if (timedOut) {
+    return 3;
+  }
+  if (signaled) {
+    return 2;
+  }
+  return 1;
+}
+
+void StopMainRunLoop() {
+  wpi::Event& event = GetInstance();
+  event.Set();
+}
+}  // namespace cs
diff --git a/third_party/allwpilib/cscore/src/main/native/windows/UsbCameraImpl.cpp b/third_party/allwpilib/cscore/src/main/native/windows/UsbCameraImpl.cpp
index efabf15..c6a8985 100644
--- a/third_party/allwpilib/cscore/src/main/native/windows/UsbCameraImpl.cpp
+++ b/third_party/allwpilib/cscore/src/main/native/windows/UsbCameraImpl.cpp
@@ -279,19 +279,23 @@
 
 void UsbCameraImpl::ProcessFrame(IMFSample* videoSample,
                                  const VideoMode& mode) {
-  if (!videoSample)
+  if (!videoSample) {
     return;
+  }
 
   ComPtr<IMFMediaBuffer> buf;
 
   if (!SUCCEEDED(videoSample->ConvertToContiguousBuffer(buf.GetAddressOf()))) {
     DWORD bcnt = 0;
-    if (!SUCCEEDED(videoSample->GetBufferCount(&bcnt)))
+    if (!SUCCEEDED(videoSample->GetBufferCount(&bcnt))) {
       return;
-    if (bcnt == 0)
+    }
+    if (bcnt == 0) {
       return;
-    if (!SUCCEEDED(videoSample->GetBufferByIndex(0, buf.GetAddressOf())))
+    }
+    if (!SUCCEEDED(videoSample->GetBufferByIndex(0, buf.GetAddressOf()))) {
       return;
+    }
   }
 
   BYTE* ptr = NULL;
@@ -352,6 +356,12 @@
                         tmpMat.total());
       tmpMat.copyTo(dest->AsMat());
       break;
+    case cs::VideoMode::PixelFormat::kY16:
+      tmpMat = cv::Mat(mode.height, mode.width, CV_8UC2, ptr, pitch);
+      dest =
+          AllocImage(VideoMode::kY16, tmpMat.cols, tmpMat.rows, tmpMat.total());
+      tmpMat.copyTo(dest->AsMat());
+      break;
     case cs::VideoMode::PixelFormat::kBGR:
       tmpMat = cv::Mat(mode.height, mode.width, CV_8UC3, ptr, pitch);
       dest = AllocImage(VideoMode::kBGR, tmpMat.cols, tmpMat.rows,
@@ -364,6 +374,12 @@
                         tmpMat.total() * 2);
       tmpMat.copyTo(dest->AsMat());
       break;
+    case cs::VideoMode::PixelFormat::kUYVY:
+      tmpMat = cv::Mat(mode.height, mode.width, CV_8UC2, ptr, pitch);
+      dest = AllocImage(VideoMode::kUYVY, tmpMat.cols, tmpMat.rows,
+                        tmpMat.total() * 2);
+      tmpMat.copyTo(dest->AsMat());
+      break;
     default:
       doFinalSet = false;
       break;
@@ -457,9 +473,10 @@
 
 static cs::VideoMode::PixelFormat GetFromGUID(const GUID& guid) {
   // Compare GUID to one of the supported ones
-  if (IsEqualGUID(guid, MFVideoFormat_NV12)) {
-    // GrayScale
+  if (IsEqualGUID(guid, MFVideoFormat_L8)) {
     return cs::VideoMode::PixelFormat::kGray;
+  } else if (IsEqualGUID(guid, MFVideoFormat_L16)) {
+    return cs::VideoMode::PixelFormat::kY16;
   } else if (IsEqualGUID(guid, MFVideoFormat_YUY2)) {
     return cs::VideoMode::PixelFormat::kYUYV;
   } else if (IsEqualGUID(guid, MFVideoFormat_RGB24)) {
@@ -468,19 +485,23 @@
     return cs::VideoMode::PixelFormat::kMJPEG;
   } else if (IsEqualGUID(guid, MFVideoFormat_RGB565)) {
     return cs::VideoMode::PixelFormat::kRGB565;
+  } else if (IsEqualGUID(guid, MFVideoFormat_UYVY)) {
+    return cs::VideoMode::PixelFormat::kUYVY;
   } else {
     return cs::VideoMode::PixelFormat::kUnknown;
   }
 }
 
 bool UsbCameraImpl::DeviceConnect() {
-  if (m_mediaSource && m_sourceReader)
+  if (m_mediaSource && m_sourceReader) {
     return true;
+  }
 
-  if (m_connectVerbose)
+  if (m_connectVerbose) {
     SINFO("Connecting to USB camera on {}", m_path);
+  }
 
-  SDEBUG3("{}", "opening device");
+  SDEBUG3("opening device");
 
   const wchar_t* path = m_widePath.c_str();
   m_mediaSource = CreateVideoCaptureDevice(path);
@@ -514,13 +535,13 @@
   }
 
   if (!m_properties_cached) {
-    SDEBUG3("{}", "caching properties");
+    SDEBUG3("caching properties");
     DeviceCacheProperties();
     DeviceCacheVideoModes();
     DeviceCacheMode();
     m_properties_cached = true;
   } else {
-    SDEBUG3("{}", "restoring video mode");
+    SDEBUG3("restoring video mode");
     DeviceSetMode();
   }
 
@@ -580,8 +601,9 @@
   DeviceAddProperty(#val, CameraControl_##val, pCamControl);
 
 void UsbCameraImpl::DeviceCacheProperties() {
-  if (!m_sourceReader)
+  if (!m_sourceReader) {
     return;
+  }
 
   IAMVideoProcAmp* pProcAmp = NULL;
 
@@ -778,22 +800,25 @@
 
   // Look up
   auto prop = static_cast<UsbCameraProperty*>(GetProperty(property));
-  if (!prop)
+  if (!prop) {
     return CS_INVALID_PROPERTY;
+  }
 
   // If setting before we get, guess initial type based on set
   if (prop->propKind == CS_PROP_NONE) {
-    if (setString)
+    if (setString) {
       prop->propKind = CS_PROP_STRING;
-    else
+    } else {
       prop->propKind = CS_PROP_INTEGER;
+    }
   }
 
   // Check kind match
   if ((setString && prop->propKind != CS_PROP_STRING) ||
-      (!setString && (prop->propKind &
-                      (CS_PROP_BOOLEAN | CS_PROP_INTEGER | CS_PROP_ENUM)) == 0))
+      (!setString && (prop->propKind & (CS_PROP_BOOLEAN | CS_PROP_INTEGER |
+                                        CS_PROP_ENUM)) == 0)) {
     return CS_WRONG_PROPERTY_TYPE;
+  }
 
   // Handle percentage property
   int percentageProperty = prop->propPair;
@@ -810,8 +835,9 @@
 
   // Actually set the new value on the device (if possible)
   if (!prop->device) {
-    if (prop->id == kPropConnectVerboseId)
+    if (prop->id == kPropConnectVerboseId) {
       m_connectVerbose = value;
+    }
   } else {
     if (!prop->DeviceSet(lock, m_sourceReader.Get())) {
       return CS_PROPERTY_WRITE_FAILED;
@@ -913,11 +939,13 @@
 }
 
 void UsbCameraImpl::DeviceCacheMode() {
-  if (!m_sourceReader)
+  if (!m_sourceReader) {
     return;
+  }
 
-  if (m_windowsVideoModes.size() == 0)
+  if (m_windowsVideoModes.size() == 0) {
     return;
+  }
 
   if (!m_currentMode) {
     // First, see if our set mode is valid
@@ -982,8 +1010,9 @@
 }
 
 void UsbCameraImpl::DeviceCacheVideoModes() {
-  if (!m_sourceReader)
+  if (!m_sourceReader) {
     return;
+  }
 
   std::vector<VideoMode> modes;
   m_windowsVideoModes.clear();
@@ -1098,13 +1127,13 @@
                             sizeof(buf) / sizeof(WCHAR), &characters);
     storage.clear();
     wpi::sys::windows::UTF16ToUTF8(buf, characters, storage);
-    info.name = storage.string();
+    info.name = std::string{storage};
     ppDevices[i]->GetString(
         MF_DEVSOURCE_ATTRIBUTE_SOURCE_TYPE_VIDCAP_SYMBOLIC_LINK, buf,
         sizeof(buf) / sizeof(WCHAR), &characters);
     storage.clear();
     wpi::sys::windows::UTF16ToUTF8(buf, characters, storage);
-    info.path = storage.string();
+    info.path = std::string{storage};
 
     // Try to parse path from symbolic link
     ParseVidAndPid(info.path, &info.productId, &info.vendorId);
diff --git a/third_party/allwpilib/cscore/src/main/native/windows/UsbCameraImpl.h b/third_party/allwpilib/cscore/src/main/native/windows/UsbCameraImpl.h
index ea6c104..c71aa06 100644
--- a/third_party/allwpilib/cscore/src/main/native/windows/UsbCameraImpl.h
+++ b/third_party/allwpilib/cscore/src/main/native/windows/UsbCameraImpl.h
@@ -96,10 +96,10 @@
     };
 
     explicit Message(Kind kind_)
-        : kind(kind_), data{0}, from(std::this_thread::get_id()) {}
+        : kind(kind_), from(std::this_thread::get_id()) {}
 
     Kind kind;
-    int data[4];
+    int data[4]{0};
     std::string dataStr;
     std::thread::id from;
   };
diff --git a/third_party/allwpilib/cscore/src/main/native/windows/UsbCameraProperty.cpp b/third_party/allwpilib/cscore/src/main/native/windows/UsbCameraProperty.cpp
index 5ddeebf..534d8d2 100644
--- a/third_party/allwpilib/cscore/src/main/native/windows/UsbCameraProperty.cpp
+++ b/third_party/allwpilib/cscore/src/main/native/windows/UsbCameraProperty.cpp
@@ -40,8 +40,9 @@
 
 bool UsbCameraProperty::DeviceGet(std::unique_lock<wpi::mutex>& lock,
                                   IAMVideoProcAmp* pProcAmp) {
-  if (!pProcAmp)
+  if (!pProcAmp) {
     return true;
+  }
 
   lock.unlock();
   long newValue = 0, paramFlag = 0;  // NOLINT(runtime/int)
@@ -60,8 +61,9 @@
 bool UsbCameraProperty::DeviceSet(std::unique_lock<wpi::mutex>& lock,
                                   IAMVideoProcAmp* pProcAmp,
                                   int newValue) const {
-  if (!pProcAmp)
+  if (!pProcAmp) {
     return true;
+  }
 
   lock.unlock();
   if (SUCCEEDED(
@@ -104,8 +106,9 @@
 
 bool UsbCameraProperty::DeviceGet(std::unique_lock<wpi::mutex>& lock,
                                   IAMCameraControl* pProcAmp) {
-  if (!pProcAmp)
+  if (!pProcAmp) {
     return true;
+  }
 
   lock.unlock();
   long newValue = 0, paramFlag = 0;  // NOLINT(runtime/int)
@@ -124,8 +127,9 @@
 bool UsbCameraProperty::DeviceSet(std::unique_lock<wpi::mutex>& lock,
                                   IAMCameraControl* pProcAmp,
                                   int newValue) const {
-  if (!pProcAmp)
+  if (!pProcAmp) {
     return true;
+  }
 
   lock.unlock();
   if (SUCCEEDED(pProcAmp->Set(tagCameraControl, newValue,
@@ -139,8 +143,9 @@
 
 bool UsbCameraProperty::DeviceGet(std::unique_lock<wpi::mutex>& lock,
                                   IMFSourceReader* sourceReader) {
-  if (!sourceReader)
+  if (!sourceReader) {
     return true;
+  }
 
   if (isControlProperty) {
     ComPtr<IAMCameraControl> pProcAmp;
@@ -169,8 +174,9 @@
 bool UsbCameraProperty::DeviceSet(std::unique_lock<wpi::mutex>& lock,
                                   IMFSourceReader* sourceReader,
                                   int newValue) const {
-  if (!sourceReader)
+  if (!sourceReader) {
     return true;
+  }
 
   if (isControlProperty) {
     ComPtr<IAMCameraControl> pProcAmp;
diff --git a/third_party/allwpilib/datalogtool/.styleguide b/third_party/allwpilib/datalogtool/.styleguide
new file mode 100644
index 0000000..87142fb
--- /dev/null
+++ b/third_party/allwpilib/datalogtool/.styleguide
@@ -0,0 +1,29 @@
+cppHeaderFileInclude {
+  \.h$
+  \.inc$
+  \.inl$
+}
+
+cppSrcFileInclude {
+  \.cpp$
+}
+
+generatedFileExclude {
+  src/main/native/resources/
+  src/main/native/win/datalogtool.ico
+  src/main/native/mac/datalogtool.icns
+}
+
+repoRootNameOverride {
+  datalogtool
+}
+
+includeOtherLibs {
+  ^GLFW
+  ^fmt/
+  ^glass/
+  ^imgui
+  ^portable-file-dialog
+  ^wpi/
+  ^wpigui
+}
diff --git a/third_party/allwpilib/datalogtool/CMakeLists.txt b/third_party/allwpilib/datalogtool/CMakeLists.txt
new file mode 100644
index 0000000..f3baa1d
--- /dev/null
+++ b/third_party/allwpilib/datalogtool/CMakeLists.txt
@@ -0,0 +1,29 @@
+project(datalogtool)
+
+include(CompileWarnings)
+include(GenResources)
+include(LinkMacOSGUI)
+
+configure_file(src/main/generate/WPILibVersion.cpp.in WPILibVersion.cpp)
+GENERATE_RESOURCES(src/main/native/resources generated/main/cpp DLT dlt datalogtool_resources_src)
+
+file(GLOB datalogtool_src src/main/native/cpp/*.cpp ${CMAKE_CURRENT_BINARY_DIR}/WPILibVersion.cpp)
+
+if (WIN32)
+    set(datalogtool_rc src/main/native/win/datalogtool.rc)
+elseif(APPLE)
+    set(MACOSX_BUNDLE_ICON_FILE datalogtool.icns)
+    set(APP_ICON_MACOSX src/main/native/mac/datalogtool.icns)
+    set_source_files_properties(${APP_ICON_MACOSX} PROPERTIES MACOSX_PACKAGE_LOCATION "Resources")
+endif()
+
+add_executable(datalogtool ${datalogtool_src} ${datalogtool_resources_src} ${datalogtool_rc} ${APP_ICON_MACOSX})
+wpilib_link_macos_gui(datalogtool)
+target_link_libraries(datalogtool libglass ${LIBSSH_LIBRARIES})
+target_include_directories(datalogtool SYSTEM PRIVATE ${LIBSSH_INCLUDE_DIRS})
+
+if (WIN32)
+    set_target_properties(datalogtool PROPERTIES WIN32_EXECUTABLE YES)
+elseif(APPLE)
+    set_target_properties(datalogtool PROPERTIES MACOSX_BUNDLE YES OUTPUT_NAME "datalogTool")
+endif()
diff --git a/third_party/allwpilib/datalogtool/Info.plist b/third_party/allwpilib/datalogtool/Info.plist
new file mode 100644
index 0000000..db23e09
--- /dev/null
+++ b/third_party/allwpilib/datalogtool/Info.plist
@@ -0,0 +1,32 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<!DOCTYPE plist PUBLIC "-//Apple//DTD PLIST 1.0//EN" "http://www.apple.com/DTDs/PropertyList-1.0.dtd">
+<plist version="1.0">
+<dict>
+	<key>CFBundleName</key>
+	<string>datalogTool</string>
+	<key>CFBundleExecutable</key>
+	<string>datalogtool</string>
+	<key>CFBundleDisplayName</key>
+	<string>datalogTool</string>
+	<key>CFBundleIdentifier</key>
+	<string>edu.wpi.first.tools.datalogTool</string>
+	<key>CFBundleIconFile</key>
+	<string>datalogtool.icns</string>
+	<key>CFBundlePackageType</key>
+	<string>APPL</string>
+	<key>CFBundleSupportedPlatforms</key>
+	<array>
+		<string>MacOSX</string>
+	</array>
+	<key>CFBundleInfoDictionaryVersion</key>
+	<string>6.0</string>
+	<key>CFBundleShortVersionString</key>
+	<string>2021</string>
+	<key>CFBundleVersion</key>
+	<string>2021</string>
+	<key>LSMinimumSystemVersion</key>
+	<string>10.11</string>
+	<key>NSHighResolutionCapable</key>
+	<true/>
+</dict>
+</plist>
diff --git a/third_party/allwpilib/datalogtool/build.gradle b/third_party/allwpilib/datalogtool/build.gradle
new file mode 100644
index 0000000..46452a9
--- /dev/null
+++ b/third_party/allwpilib/datalogtool/build.gradle
@@ -0,0 +1,126 @@
+import org.gradle.internal.os.OperatingSystem
+
+if (!project.hasProperty('onlylinuxathena')) {
+
+    description = "roboRIO Team Number Setter"
+
+    apply plugin: 'cpp'
+    apply plugin: 'c'
+    apply plugin: 'google-test-test-suite'
+    apply plugin: 'visual-studio'
+    apply plugin: 'edu.wpi.first.NativeUtils'
+
+    if (OperatingSystem.current().isWindows()) {
+        apply plugin: 'windows-resources'
+    }
+
+    ext {
+        nativeName = 'datalogtool'
+    }
+
+    apply from: "${rootDir}/shared/resources.gradle"
+    apply from: "${rootDir}/shared/config.gradle"
+
+    def wpilibVersionFileInput = file("src/main/generate/WPILibVersion.cpp.in")
+    def wpilibVersionFileOutput = file("$buildDir/generated/main/cpp/WPILibVersion.cpp")
+
+    apply from: "${rootDir}/shared/libssh.gradle"
+    apply from: "${rootDir}/shared/imgui.gradle"
+
+    task generateCppVersion() {
+        description = 'Generates the wpilib version class'
+        group = 'WPILib'
+
+        outputs.file wpilibVersionFileOutput
+        inputs.file wpilibVersionFileInput
+
+        if (wpilibVersioning.releaseMode) {
+            outputs.upToDateWhen { false }
+        }
+
+        // We follow a simple set of checks to determine whether we should generate a new version file:
+        // 1. If the release type is not development, we generate a new version file
+        // 2. If there is no generated version number, we generate a new version file
+        // 3. If there is a generated build number, and the release type is development, then we will
+        //    only generate if the publish task is run.
+        doLast {
+            def version = wpilibVersioning.version.get()
+            println "Writing version ${version} to $wpilibVersionFileOutput"
+
+            if (wpilibVersionFileOutput.exists()) {
+                wpilibVersionFileOutput.delete()
+            }
+            def read = wpilibVersionFileInput.text.replace('${wpilib_version}', version)
+            wpilibVersionFileOutput.write(read)
+        }
+    }
+
+    gradle.taskGraph.addTaskExecutionGraphListener { graph ->
+        def willPublish = graph.hasTask(publish)
+        if (willPublish) {
+            generateCppVersion.outputs.upToDateWhen { false }
+        }
+    }
+
+    def generateTask = createGenerateResourcesTask('main', 'DLT', 'dlt', project)
+
+    project(':').libraryBuild.dependsOn build
+    tasks.withType(CppCompile) {
+        dependsOn generateTask
+        dependsOn generateCppVersion
+    }
+
+    model {
+        components {
+            // By default, a development executable will be generated. This is to help the case of
+            // testing specific functionality of the library.
+            "${nativeName}"(NativeExecutableSpec) {
+                baseName = 'datalogtool'
+                sources {
+                    cpp {
+                        source {
+                            srcDirs 'src/main/native/cpp', "$buildDir/generated/main/cpp"
+                            include '**/*.cpp'
+                        }
+                        exportedHeaders {
+                            srcDirs 'src/main/native/include'
+                        }
+                    }
+                    if (OperatingSystem.current().isWindows()) {
+                        rc {
+                            source {
+                                srcDirs 'src/main/native/win'
+                                include '*.rc'
+                            }
+                        }
+                    }
+                }
+                binaries.all {
+                    if (it.targetPlatform.name == nativeUtils.wpi.platforms.roborio) {
+                        it.buildable = false
+                        return
+                    }
+                    it.cppCompiler.define("LIBSSH_STATIC")
+                    lib project: ':glass', library: 'glass', linkage: 'static'
+                    lib project: ':wpiutil', library: 'wpiutil', linkage: 'static'
+                    lib project: ':wpigui', library: 'wpigui', linkage: 'static'
+                    nativeUtils.useRequiredLibrary(it, 'imgui', 'libssh')
+                    if (it.targetPlatform.operatingSystem.isWindows()) {
+                        it.linker.args << 'Gdi32.lib' << 'Shell32.lib' << 'd3d11.lib' << 'd3dcompiler.lib'
+                        it.linker.args << 'ws2_32.lib' << 'advapi32.lib' << 'crypt32.lib' << 'user32.lib'
+                    } else if (it.targetPlatform.operatingSystem.isMacOsX()) {
+                        it.linker.args << '-framework' << 'Metal' << '-framework' << 'MetalKit' << '-framework' << 'Cocoa' << '-framework' << 'IOKit' << '-framework' << 'CoreFoundation' << '-framework' << 'CoreVideo' << '-framework' << 'QuartzCore'
+                        it.linker.args << '-framework' << 'Kerberos'
+                    } else {
+                        it.linker.args << '-lX11'
+                        if (it.targetPlatform.name.startsWith('linuxarm')) {
+                            it.linker.args << '-lGL'
+                        }
+                    }
+                }
+            }
+        }
+    }
+
+    apply from: 'publish.gradle'
+}
diff --git a/third_party/allwpilib/datalogtool/publish.gradle b/third_party/allwpilib/datalogtool/publish.gradle
new file mode 100644
index 0000000..e822842
--- /dev/null
+++ b/third_party/allwpilib/datalogtool/publish.gradle
@@ -0,0 +1,109 @@
+apply plugin: 'maven-publish'
+
+def baseArtifactId = 'DataLogTool'
+def artifactGroupId = 'edu.wpi.first.tools'
+def zipBaseName = '_GROUP_edu_wpi_first_tools_ID_DataLogTool_CLS'
+
+def outputsFolder = file("$project.buildDir/outputs")
+
+model {
+    tasks {
+        // Create the run task.
+        $.components.datalogtool.binaries.each { bin ->
+            if (bin.buildable && bin.name.toLowerCase().contains("debug") && nativeUtils.isNativeDesktopPlatform(bin.targetPlatform)) {
+                Task run = project.tasks.create("run", Exec) {
+                    commandLine bin.tasks.install.runScriptFile.get().asFile.toString()
+                }
+                run.dependsOn bin.tasks.install
+            }
+        }
+    }
+    publishing {
+        def dataLogToolTaskList = []
+        $.components.each { component ->
+            component.binaries.each { binary ->
+                if (binary in NativeExecutableBinarySpec && binary.component.name.contains("datalogtool")) {
+                    if (binary.buildable && (binary.name.contains('Release') || binary.name.contains('release'))) {
+                        // We are now in the binary that we want.
+                        // This is the default application path for the ZIP task.
+                        def applicationPath = binary.executable.file
+                        def icon = file("$project.projectDir/src/main/native/mac/datalogtool.icns")
+
+                        // Create the macOS bundle.
+                        def bundleTask = project.tasks.create("bundleDataLogToolOsxApp" + binary.targetPlatform.architecture.name, Copy) {
+                            description("Creates a macOS application bundle for DataLogTool")
+                            from(file("$project.projectDir/Info.plist"))
+                            into(file("$project.buildDir/outputs/bundles/$binary.targetPlatform.architecture.name/DataLogTool.app/Contents"))
+                            into("MacOS") { with copySpec { from binary.executable.file } }
+                            into("Resources") { with copySpec { from icon } }
+
+                            inputs.property "HasDeveloperId", project.hasProperty("developerID")
+
+                            doLast {
+                                if (project.hasProperty("developerID")) {
+                                    // Get path to binary.
+                                    exec {
+                                        workingDir rootDir
+                                        def args = [
+                                            "sh",
+                                            "-c",
+                                            "codesign --force --strict --deep " +
+                                            "--timestamp --options=runtime " +
+                                            "--verbose -s ${project.findProperty("developerID")} " +
+                                            "$project.buildDir/outputs/bundles/$binary.targetPlatform.architecture.name/DataLogTool.app/"
+                                        ]
+                                        commandLine args
+                                    }
+                                }
+                            }
+                        }
+
+                        // Reset the application path if we are creating a bundle.
+                        if (binary.targetPlatform.operatingSystem.isMacOsX()) {
+                            applicationPath = file("$project.buildDir/outputs/bundles/$binary.targetPlatform.architecture.name")
+                            project.build.dependsOn bundleTask
+                        }
+
+                        // Create the ZIP.
+                        def task = project.tasks.create("copyDataLogToolExecutable" + binary.targetPlatform.architecture.name, Zip) {
+                            description("Copies the DataLogTool executable to the outputs directory.")
+                            destinationDirectory = outputsFolder
+
+                            archiveBaseName = '_M_' + zipBaseName
+                            duplicatesStrategy = 'exclude'
+                            classifier = nativeUtils.getPublishClassifier(binary)
+
+                            from(licenseFile) {
+                                into '/'
+                            }
+
+                            from(applicationPath)
+                            into(nativeUtils.getPlatformPath(binary))
+                        }
+
+                        if (binary.targetPlatform.operatingSystem.isMacOsX()) {
+                            bundleTask.dependsOn binary.tasks.link
+                            task.dependsOn(bundleTask)
+                        }
+
+                        task.dependsOn binary.tasks.link
+                        dataLogToolTaskList.add(task)
+                        project.build.dependsOn task
+                        project.artifacts { task }
+                        addTaskToCopyAllOutputs(task)
+                    }
+                }
+            }
+        }
+
+        publications {
+            datalogtool(MavenPublication) {
+                dataLogToolTaskList.each { artifact it }
+
+                artifactId = baseArtifactId
+                groupId = artifactGroupId
+                version wpilibVersioning.version.get()
+            }
+        }
+    }
+}
diff --git a/third_party/allwpilib/datalogtool/src/main/generate/WPILibVersion.cpp.in b/third_party/allwpilib/datalogtool/src/main/generate/WPILibVersion.cpp.in
new file mode 100644
index 0000000..b0a4490
--- /dev/null
+++ b/third_party/allwpilib/datalogtool/src/main/generate/WPILibVersion.cpp.in
@@ -0,0 +1,7 @@
+/*
+ * Autogenerated file! Do not manually edit this file. This version is regenerated
+ * any time the publish task is run, or when this file is deleted.
+ */
+const char* GetWPILibVersion() {
+  return "${wpilib_version}";
+}
diff --git a/third_party/allwpilib/datalogtool/src/main/native/cpp/App.cpp b/third_party/allwpilib/datalogtool/src/main/native/cpp/App.cpp
new file mode 100644
index 0000000..a4b466b
--- /dev/null
+++ b/third_party/allwpilib/datalogtool/src/main/native/cpp/App.cpp
@@ -0,0 +1,156 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "App.h"
+
+#include <libssh/libssh.h>
+
+#include <memory>
+#include <string_view>
+
+#define IMGUI_DEFINE_MATH_OPERATORS
+
+#include <glass/Context.h>
+#include <glass/MainMenuBar.h>
+#include <glass/Storage.h>
+#include <imgui.h>
+#include <imgui_internal.h>
+#include <wpigui.h>
+
+#include "Downloader.h"
+#include "Exporter.h"
+
+namespace gui = wpi::gui;
+
+const char* GetWPILibVersion();
+
+namespace dlt {
+std::string_view GetResource_dlt_16_png();
+std::string_view GetResource_dlt_32_png();
+std::string_view GetResource_dlt_48_png();
+std::string_view GetResource_dlt_64_png();
+std::string_view GetResource_dlt_128_png();
+std::string_view GetResource_dlt_256_png();
+std::string_view GetResource_dlt_512_png();
+}  // namespace dlt
+
+bool gShutdown = false;
+
+static std::unique_ptr<Downloader> gDownloader;
+static bool* gDownloadVisible;
+static float gDefaultScale = 1.0;
+
+void SetNextWindowPos(const ImVec2& pos, ImGuiCond cond, const ImVec2& pivot) {
+  if ((cond & ImGuiCond_FirstUseEver) != 0) {
+    ImGui::SetNextWindowPos(pos * gDefaultScale, cond, pivot);
+  } else {
+    ImGui::SetNextWindowPos(pos, cond, pivot);
+  }
+}
+
+void SetNextWindowSize(const ImVec2& size, ImGuiCond cond) {
+  if ((cond & ImGuiCond_FirstUseEver) != 0) {
+    ImGui::SetNextWindowSize(size * gDefaultScale, cond);
+  } else {
+    ImGui::SetNextWindowPos(size, cond);
+  }
+}
+
+static void DisplayDownload() {
+  if (!*gDownloadVisible) {
+    return;
+  }
+  SetNextWindowPos(ImVec2{0, 250}, ImGuiCond_FirstUseEver);
+  SetNextWindowSize(ImVec2{375, 260}, ImGuiCond_FirstUseEver);
+  if (ImGui::Begin("Download", gDownloadVisible)) {
+    if (!gDownloader) {
+      gDownloader = std::make_unique<Downloader>(
+          glass::GetStorageRoot().GetChild("download"));
+    }
+    gDownloader->Display();
+  }
+  ImGui::End();
+}
+
+static void DisplayMainMenu() {
+  ImGui::BeginMainMenuBar();
+
+  static glass::MainMenuBar mainMenu;
+  mainMenu.WorkspaceMenu();
+  gui::EmitViewMenu();
+
+  if (ImGui::BeginMenu("Window")) {
+    ImGui::MenuItem("Download", nullptr, gDownloadVisible);
+    ImGui::EndMenu();
+  }
+
+  bool about = false;
+  if (ImGui::BeginMenu("Info")) {
+    if (ImGui::MenuItem("About")) {
+      about = true;
+    }
+    ImGui::EndMenu();
+  }
+
+  ImGui::EndMainMenuBar();
+
+  if (about) {
+    ImGui::OpenPopup("About");
+  }
+  if (ImGui::BeginPopupModal("About")) {
+    ImGui::Text("Datalog Tool");
+    ImGui::Separator();
+    ImGui::Text("v%s", GetWPILibVersion());
+    ImGui::Separator();
+    ImGui::Text("Save location: %s", glass::GetStorageDir().c_str());
+    if (ImGui::Button("Close")) {
+      ImGui::CloseCurrentPopup();
+    }
+    ImGui::EndPopup();
+  }
+}
+
+static void DisplayGui() {
+  DisplayMainMenu();
+  DisplayInputFiles();
+  DisplayEntries();
+  DisplayOutput(glass::GetStorageRoot().GetChild("output"));
+  DisplayDownload();
+}
+
+void Application(std::string_view saveDir) {
+  ssh_init();
+
+  gui::CreateContext();
+  glass::CreateContext();
+
+  // Add icons
+  gui::AddIcon(dlt::GetResource_dlt_16_png());
+  gui::AddIcon(dlt::GetResource_dlt_32_png());
+  gui::AddIcon(dlt::GetResource_dlt_48_png());
+  gui::AddIcon(dlt::GetResource_dlt_64_png());
+  gui::AddIcon(dlt::GetResource_dlt_128_png());
+  gui::AddIcon(dlt::GetResource_dlt_256_png());
+  gui::AddIcon(dlt::GetResource_dlt_512_png());
+
+  glass::SetStorageName("datalogtool");
+  glass::SetStorageDir(saveDir.empty() ? gui::GetPlatformSaveFileDir()
+                                       : saveDir);
+
+  gui::AddWindowScaler([](float scale) { gDefaultScale = scale; });
+  gui::AddLateExecute(DisplayGui);
+  gui::Initialize("Datalog Tool", 925, 510);
+
+  gDownloadVisible =
+      &glass::GetStorageRoot().GetChild("download").GetBool("visible", true);
+
+  gui::Main();
+
+  gShutdown = true;
+  glass::DestroyContext();
+  gui::DestroyContext();
+
+  gDownloader.reset();
+  ssh_finalize();
+}
diff --git a/third_party/allwpilib/datalogtool/src/main/native/cpp/App.h b/third_party/allwpilib/datalogtool/src/main/native/cpp/App.h
new file mode 100644
index 0000000..9d1520c
--- /dev/null
+++ b/third_party/allwpilib/datalogtool/src/main/native/cpp/App.h
@@ -0,0 +1,11 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <imgui.h>
+
+void SetNextWindowPos(const ImVec2& pos, ImGuiCond cond = 0,
+                      const ImVec2& pivot = ImVec2(0, 0));
+void SetNextWindowSize(const ImVec2& size, ImGuiCond cond = 0);
diff --git a/third_party/allwpilib/datalogtool/src/main/native/cpp/DataLogThread.cpp b/third_party/allwpilib/datalogtool/src/main/native/cpp/DataLogThread.cpp
new file mode 100644
index 0000000..90c8b19
--- /dev/null
+++ b/third_party/allwpilib/datalogtool/src/main/native/cpp/DataLogThread.cpp
@@ -0,0 +1,72 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "DataLogThread.h"
+
+#include <fmt/format.h>
+
+DataLogThread::~DataLogThread() {
+  if (m_thread.joinable()) {
+    m_active = false;
+    m_thread.join();
+  }
+}
+
+void DataLogThread::ReadMain() {
+  for (auto record : m_reader) {
+    if (!m_active) {
+      break;
+    }
+    ++m_numRecords;
+    if (record.IsStart()) {
+      wpi::log::StartRecordData data;
+      if (record.GetStartData(&data)) {
+        std::scoped_lock lock{m_mutex};
+        if (m_entries.find(data.entry) != m_entries.end()) {
+          fmt::print("...DUPLICATE entry ID, overriding\n");
+        }
+        m_entries[data.entry] = data;
+        m_entryNames.emplace(data.name, data);
+        sigEntryAdded(data);
+      } else {
+        fmt::print("Start(INVALID)\n");
+      }
+    } else if (record.IsFinish()) {
+      int entry;
+      if (record.GetFinishEntry(&entry)) {
+        std::scoped_lock lock{m_mutex};
+        auto it = m_entries.find(entry);
+        if (it == m_entries.end()) {
+          fmt::print("...ID not found\n");
+        } else {
+          m_entries.erase(it);
+        }
+      } else {
+        fmt::print("Finish(INVALID)\n");
+      }
+    } else if (record.IsSetMetadata()) {
+      wpi::log::MetadataRecordData data;
+      if (record.GetSetMetadataData(&data)) {
+        std::scoped_lock lock{m_mutex};
+        auto it = m_entries.find(data.entry);
+        if (it == m_entries.end()) {
+          fmt::print("...ID not found\n");
+        } else {
+          it->second.metadata = data.metadata;
+          auto nameIt = m_entryNames.find(it->second.name);
+          if (nameIt != m_entryNames.end()) {
+            nameIt->second.metadata = data.metadata;
+          }
+        }
+      } else {
+        fmt::print("SetMetadata(INVALID)\n");
+      }
+    } else if (record.IsControl()) {
+      fmt::print("Unrecognized control record\n");
+    }
+  }
+
+  sigDone();
+  m_done = true;
+}
diff --git a/third_party/allwpilib/datalogtool/src/main/native/cpp/DataLogThread.h b/third_party/allwpilib/datalogtool/src/main/native/cpp/DataLogThread.h
new file mode 100644
index 0000000..267aa1f
--- /dev/null
+++ b/third_party/allwpilib/datalogtool/src/main/native/cpp/DataLogThread.h
@@ -0,0 +1,71 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <atomic>
+#include <functional>
+#include <map>
+#include <string>
+#include <string_view>
+#include <thread>
+#include <utility>
+
+#include <wpi/DataLogReader.h>
+#include <wpi/DenseMap.h>
+#include <wpi/Signal.h>
+#include <wpi/mutex.h>
+
+class DataLogThread {
+ public:
+  explicit DataLogThread(wpi::log::DataLogReader reader)
+      : m_reader{std::move(reader)}, m_thread{[=, this] { ReadMain(); }} {}
+  ~DataLogThread();
+
+  bool IsDone() const { return m_done; }
+  std::string_view GetBufferIdentifier() const {
+    return m_reader.GetBufferIdentifier();
+  }
+  unsigned int GetNumRecords() const { return m_numRecords; }
+  unsigned int GetNumEntries() const {
+    std::scoped_lock lock{m_mutex};
+    return m_entryNames.size();
+  }
+
+  // Passes wpi::log::StartRecordData to func
+  template <typename T>
+  void ForEachEntryName(T&& func) {
+    std::scoped_lock lock{m_mutex};
+    for (auto&& kv : m_entryNames) {
+      func(kv.second);
+    }
+  }
+
+  wpi::log::StartRecordData GetEntry(std::string_view name) const {
+    std::scoped_lock lock{m_mutex};
+    auto it = m_entryNames.find(name);
+    if (it == m_entryNames.end()) {
+      return {};
+    }
+    return it->second;
+  }
+
+  const wpi::log::DataLogReader& GetReader() const { return m_reader; }
+
+  // note: these are called on separate thread
+  wpi::sig::Signal_mt<const wpi::log::StartRecordData&> sigEntryAdded;
+  wpi::sig::Signal_mt<> sigDone;
+
+ private:
+  void ReadMain();
+
+  wpi::log::DataLogReader m_reader;
+  mutable wpi::mutex m_mutex;
+  std::atomic_bool m_active{true};
+  std::atomic_bool m_done{false};
+  std::atomic<unsigned int> m_numRecords{0};
+  std::map<std::string, wpi::log::StartRecordData, std::less<>> m_entryNames;
+  wpi::DenseMap<int, wpi::log::StartRecordData> m_entries;
+  std::thread m_thread;
+};
diff --git a/third_party/allwpilib/datalogtool/src/main/native/cpp/Downloader.cpp b/third_party/allwpilib/datalogtool/src/main/native/cpp/Downloader.cpp
new file mode 100644
index 0000000..3d19738
--- /dev/null
+++ b/third_party/allwpilib/datalogtool/src/main/native/cpp/Downloader.cpp
@@ -0,0 +1,407 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "Downloader.h"
+
+#include <libssh/sftp.h>
+
+#ifdef _WIN32
+#include <fcntl.h>
+#include <io.h>
+#else
+#include <sys/fcntl.h>
+#endif
+
+#include <algorithm>
+#include <filesystem>
+
+#include <fmt/format.h>
+#include <glass/Storage.h>
+#include <imgui.h>
+#include <imgui_stdlib.h>
+#include <portable-file-dialogs.h>
+#include <wpi/StringExtras.h>
+#include <wpi/fs.h>
+
+#include "Sftp.h"
+
+Downloader::Downloader(glass::Storage& storage)
+    : m_serverTeam{storage.GetString("serverTeam")},
+      m_remoteDir{storage.GetString("remoteDir", "/home/lvuser")},
+      m_username{storage.GetString("username", "lvuser")},
+      m_localDir{storage.GetString("localDir")},
+      m_deleteAfter{storage.GetBool("deleteAfter", true)},
+      m_thread{[this] { ThreadMain(); }} {}
+
+Downloader::~Downloader() {
+  {
+    std::scoped_lock lock{m_mutex};
+    m_state = kExit;
+  }
+  m_cv.notify_all();
+  m_thread.join();
+}
+
+void Downloader::DisplayConnect() {
+  // IP or Team Number text box
+  ImGui::SetNextItemWidth(ImGui::GetFontSize() * 12);
+  ImGui::InputText("Team Number / Address", &m_serverTeam);
+
+  // Username/password
+  ImGui::SetNextItemWidth(ImGui::GetFontSize() * 12);
+  ImGui::InputText("Username", &m_username);
+  ImGui::SetNextItemWidth(ImGui::GetFontSize() * 12);
+  ImGui::InputText("Password", &m_password, ImGuiInputTextFlags_Password);
+
+  // Connect button
+  if (ImGui::Button("Connect")) {
+    m_state = kConnecting;
+    m_cv.notify_all();
+  }
+}
+
+void Downloader::DisplayDisconnectButton() {
+  if (ImGui::Button("Disconnect")) {
+    m_state = kDisconnecting;
+    m_cv.notify_all();
+  }
+}
+
+void Downloader::DisplayRemoteDirSelector() {
+  ImGui::SameLine();
+  if (ImGui::Button("Refresh")) {
+    m_state = kGetFiles;
+    m_cv.notify_all();
+  }
+
+  ImGui::SameLine();
+  if (ImGui::Button("Deselect All")) {
+    for (auto&& download : m_downloadList) {
+      download.enabled = false;
+    }
+  }
+
+  ImGui::SameLine();
+  if (ImGui::Button("Select All")) {
+    for (auto&& download : m_downloadList) {
+      download.enabled = true;
+    }
+  }
+
+  // Remote directory text box
+  ImGui::SetNextItemWidth(ImGui::GetFontSize() * 20);
+  if (ImGui::InputText("Remote Dir", &m_remoteDir,
+                       ImGuiInputTextFlags_EnterReturnsTrue)) {
+    m_state = kGetFiles;
+    m_cv.notify_all();
+  }
+
+  // List directories
+  for (auto&& dir : m_dirList) {
+    if (ImGui::Selectable(dir.c_str())) {
+      if (dir == "..") {
+        if (wpi::ends_with(m_remoteDir, '/')) {
+          m_remoteDir.resize(m_remoteDir.size() - 1);
+        }
+        m_remoteDir = wpi::rsplit(m_remoteDir, '/').first;
+        if (m_remoteDir.empty()) {
+          m_remoteDir = "/";
+        }
+      } else {
+        if (!wpi::ends_with(m_remoteDir, '/')) {
+          m_remoteDir += '/';
+        }
+        m_remoteDir += dir;
+      }
+      m_state = kGetFiles;
+      m_cv.notify_all();
+    }
+  }
+}
+
+void Downloader::DisplayLocalDirSelector() {
+  // Local directory text / select button
+  if (ImGui::Button("Select Download Folder...")) {
+    m_localDirSelector =
+        std::make_unique<pfd::select_folder>("Select Download Folder");
+  }
+  ImGui::TextUnformatted(m_localDir.c_str());
+
+  // Delete after download (checkbox)
+  ImGui::Checkbox("Delete after download", &m_deleteAfter);
+
+  // Download button
+  if (!m_localDir.empty()) {
+    if (ImGui::Button("Download")) {
+      m_state = kDownload;
+      m_cv.notify_all();
+    }
+  }
+}
+
+size_t Downloader::DisplayFiles() {
+  // List of files (multi-select) (changes to progress bar for downloading)
+  size_t fileCount = 0;
+  if (ImGui::BeginTable(
+          "files", 3,
+          ImGuiTableFlags_Borders | ImGuiTableFlags_SizingStretchProp)) {
+    ImGui::TableSetupColumn("File");
+    ImGui::TableSetupColumn("Size");
+    ImGui::TableSetupColumn("Download");
+    ImGui::TableHeadersRow();
+    for (auto&& download : m_downloadList) {
+      if ((m_state == kDownload || m_state == kDownloadDone) &&
+          !download.enabled) {
+        continue;
+      }
+
+      ++fileCount;
+
+      ImGui::TableNextRow();
+      ImGui::TableNextColumn();
+      ImGui::TextUnformatted(download.name.c_str());
+      ImGui::TableNextColumn();
+      auto sizeText = fmt::format("{}", download.size);
+      ImGui::TextUnformatted(sizeText.c_str());
+      ImGui::TableNextColumn();
+      if (m_state == kDownload || m_state == kDownloadDone) {
+        if (!download.status.empty()) {
+          ImGui::TextUnformatted(download.status.c_str());
+        } else {
+          ImGui::ProgressBar(download.complete);
+        }
+      } else {
+        auto checkboxLabel = fmt::format("##{}", download.name);
+        ImGui::Checkbox(checkboxLabel.c_str(), &download.enabled);
+      }
+    }
+    ImGui::EndTable();
+  }
+
+  return fileCount;
+}
+
+void Downloader::Display() {
+  if (m_localDirSelector && m_localDirSelector->ready(0)) {
+    m_localDir = m_localDirSelector->result();
+    m_localDirSelector.reset();
+  }
+
+  std::scoped_lock lock{m_mutex};
+
+  if (!m_error.empty()) {
+    ImGui::TextUnformatted(m_error.c_str());
+  }
+
+  switch (m_state) {
+    case kDisconnected:
+      DisplayConnect();
+      break;
+    case kConnecting:
+      DisplayDisconnectButton();
+      ImGui::Text("Connecting to %s...", m_serverTeam.c_str());
+      break;
+    case kDisconnecting:
+      ImGui::TextUnformatted("Disconnecting...");
+      break;
+    case kConnected:
+    case kGetFiles:
+      DisplayDisconnectButton();
+      DisplayRemoteDirSelector();
+      if (DisplayFiles() > 0) {
+        DisplayLocalDirSelector();
+      }
+      break;
+    case kDownload:
+    case kDownloadDone:
+      DisplayDisconnectButton();
+      DisplayFiles();
+      if (m_state == kDownloadDone) {
+        if (ImGui::Button("Download complete!")) {
+          m_state = kGetFiles;
+          m_cv.notify_all();
+        }
+      }
+      break;
+    default:
+      break;
+  }
+}
+
+void Downloader::ThreadMain() {
+  std::unique_ptr<sftp::Session> session;
+
+  static constexpr size_t kBufSize = 32 * 1024;
+  std::unique_ptr<uint8_t[]> copyBuf = std::make_unique<uint8_t[]>(kBufSize);
+
+  std::unique_lock lock{m_mutex};
+  while (m_state != kExit) {
+    State prev = m_state;
+    m_cv.wait(lock, [&] { return m_state != prev; });
+    m_error.clear();
+    try {
+      switch (m_state) {
+        case kConnecting:
+          if (auto team = wpi::parse_integer<unsigned int>(m_serverTeam, 10)) {
+            // team number
+            session = std::make_unique<sftp::Session>(
+                fmt::format("roborio-{}-frc.local", team.value()), 22,
+                m_username, m_password);
+          } else {
+            session = std::make_unique<sftp::Session>(m_serverTeam, 22,
+                                                      m_username, m_password);
+          }
+          lock.unlock();
+          try {
+            session->Connect();
+          } catch (...) {
+            lock.lock();
+            throw;
+          }
+          lock.lock();
+          // FALLTHROUGH
+        case kGetFiles: {
+          std::string dir = m_remoteDir;
+          std::vector<sftp::Attributes> fileList;
+          lock.unlock();
+          try {
+            fileList = session->ReadDir(dir);
+          } catch (sftp::Exception& ex) {
+            lock.lock();
+            if (ex.err == SSH_FX_OK || ex.err == SSH_FX_CONNECTION_LOST) {
+              throw;
+            }
+            m_error = ex.what();
+            m_dirList.clear();
+            m_downloadList.clear();
+            m_state = kConnected;
+            break;
+          }
+          std::sort(
+              fileList.begin(), fileList.end(),
+              [](const auto& l, const auto& r) { return l.name < r.name; });
+          lock.lock();
+
+          m_dirList.clear();
+          m_downloadList.clear();
+          for (auto&& attr : fileList) {
+            if (attr.type == SSH_FILEXFER_TYPE_DIRECTORY) {
+              if (attr.name != ".") {
+                m_dirList.emplace_back(attr.name);
+              }
+            } else if (attr.type == SSH_FILEXFER_TYPE_REGULAR &&
+                       (attr.flags & SSH_FILEXFER_ATTR_SIZE) != 0 &&
+                       wpi::ends_with(attr.name, ".wpilog")) {
+              m_downloadList.emplace_back(attr.name, attr.size);
+            }
+          }
+
+          m_state = kConnected;
+          break;
+        }
+        case kDisconnecting:
+          session.reset();
+          m_state = kDisconnected;
+          break;
+        case kDownload: {
+          for (auto&& download : m_downloadList) {
+            if (m_state != kDownload) {
+              // user aborted
+              break;
+            }
+            if (!download.enabled) {
+              continue;
+            }
+
+            auto remoteFilename = fmt::format(
+                "{}{}{}", m_remoteDir,
+                wpi::ends_with(m_remoteDir, '/') ? "" : "/", download.name);
+            auto localFilename = fs::path{m_localDir} / download.name;
+            uint64_t fileSize = download.size;
+
+            lock.unlock();
+
+            // open local file
+            std::error_code ec;
+            fs::file_t of = fs::OpenFileForWrite(localFilename, ec,
+                                                 fs::CD_CreateNew, fs::OF_None);
+            if (ec) {
+              // failed to open
+              lock.lock();
+              download.status = ec.message();
+              continue;
+            }
+            int ofd = fs::FileToFd(of, ec, fs::OF_None);
+            if (ofd == -1 || ec) {
+              // failed to convert to fd
+              lock.lock();
+              download.status = ec.message();
+              continue;
+            }
+
+            try {
+              // open remote file
+              sftp::File f = session->Open(remoteFilename, O_RDONLY, 0);
+
+              // copy in chunks
+              uint64_t total = 0;
+              while (total < fileSize) {
+                uint64_t toCopy = (std::min)(fileSize - total,
+                                             static_cast<uint64_t>(kBufSize));
+                auto copied = f.Read(copyBuf.get(), toCopy);
+                if (write(ofd, copyBuf.get(), copied) !=
+                    static_cast<int64_t>(copied)) {
+                  // error writing
+                  close(ofd);
+                  fs::remove(localFilename, ec);
+                  lock.lock();
+                  download.status = "error writing local file";
+                  goto err;
+                }
+                total += copied;
+                lock.lock();
+                download.complete = static_cast<float>(total) / fileSize;
+                lock.unlock();
+              }
+
+              // close local file
+              close(ofd);
+              ofd = -1;
+
+              // delete remote file (if enabled)
+              if (m_deleteAfter) {
+                f = sftp::File{};
+                session->Unlink(remoteFilename);
+              }
+            } catch (sftp::Exception& ex) {
+              if (ofd != -1) {
+                // close local file and delete it (due to failure)
+                close(ofd);
+                fs::remove(localFilename, ec);
+              }
+              lock.lock();
+              download.status = ex.what();
+              if (ex.err == SSH_FX_OK || ex.err == SSH_FX_CONNECTION_LOST) {
+                throw;
+              }
+              continue;
+            }
+            lock.lock();
+          err : {}
+          }
+          if (m_state == kDownload) {
+            m_state = kDownloadDone;
+          }
+          break;
+        }
+        default:
+          break;
+      }
+    } catch (sftp::Exception& ex) {
+      m_error = ex.what();
+      session.reset();
+      m_state = kDisconnected;
+    }
+  }
+}
diff --git a/third_party/allwpilib/datalogtool/src/main/native/cpp/Downloader.h b/third_party/allwpilib/datalogtool/src/main/native/cpp/Downloader.h
new file mode 100644
index 0000000..f9bb32f
--- /dev/null
+++ b/third_party/allwpilib/datalogtool/src/main/native/cpp/Downloader.h
@@ -0,0 +1,78 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <memory>
+#include <string>
+#include <thread>
+#include <vector>
+
+#include <wpi/condition_variable.h>
+#include <wpi/mutex.h>
+
+namespace glass {
+class Storage;
+}  // namespace glass
+
+namespace pfd {
+class select_folder;
+}  // namespace pfd
+
+class Downloader {
+ public:
+  explicit Downloader(glass::Storage& storage);
+  ~Downloader();
+
+  void Display();
+
+ private:
+  void DisplayConnect();
+  void DisplayDisconnectButton();
+  void DisplayRemoteDirSelector();
+  void DisplayLocalDirSelector();
+  size_t DisplayFiles();
+
+  void ThreadMain();
+
+  wpi::mutex m_mutex;
+  enum State {
+    kDisconnected,
+    kConnecting,
+    kConnected,
+    kDisconnecting,
+    kGetFiles,
+    kDownload,
+    kDownloadDone,
+    kExit
+  } m_state = kDisconnected;
+  std::condition_variable m_cv;
+
+  std::string& m_serverTeam;
+  std::string& m_remoteDir;
+  std::string& m_username;
+  std::string m_password;
+
+  std::string& m_localDir;
+  std::unique_ptr<pfd::select_folder> m_localDirSelector;
+
+  bool& m_deleteAfter;
+
+  std::vector<std::string> m_dirList;
+  struct DownloadState {
+    DownloadState(std::string_view name, uint64_t size)
+        : name{name}, size{size} {}
+
+    std::string name;
+    uint64_t size;
+    bool enabled = true;
+    float complete = 0.0;
+    std::string status;
+  };
+  std::vector<DownloadState> m_downloadList;
+
+  std::string m_error;
+
+  std::thread m_thread;
+};
diff --git a/third_party/allwpilib/datalogtool/src/main/native/cpp/Exporter.cpp b/third_party/allwpilib/datalogtool/src/main/native/cpp/Exporter.cpp
new file mode 100644
index 0000000..f28545f
--- /dev/null
+++ b/third_party/allwpilib/datalogtool/src/main/native/cpp/Exporter.cpp
@@ -0,0 +1,661 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "Exporter.h"
+
+#include <atomic>
+#include <ctime>
+#include <future>
+#include <map>
+#include <memory>
+#include <set>
+#include <string>
+#include <string_view>
+#include <vector>
+
+#include <fmt/chrono.h>
+#include <fmt/format.h>
+#include <glass/Storage.h>
+#include <imgui.h>
+#include <imgui_internal.h>
+#include <imgui_stdlib.h>
+#include <portable-file-dialogs.h>
+#include <wpi/DenseMap.h>
+#include <wpi/MemoryBuffer.h>
+#include <wpi/SmallVector.h>
+#include <wpi/SpanExtras.h>
+#include <wpi/StringExtras.h>
+#include <wpi/fmt/raw_ostream.h>
+#include <wpi/fs.h>
+#include <wpi/mutex.h>
+#include <wpi/raw_ostream.h>
+
+#include "App.h"
+#include "DataLogThread.h"
+
+namespace {
+struct InputFile {
+  explicit InputFile(std::unique_ptr<DataLogThread> datalog);
+
+  InputFile(std::string_view filename, std::string_view status)
+      : filename{filename},
+        stem{fs::path{filename}.stem().string()},
+        status{status} {}
+
+  ~InputFile();
+
+  std::string filename;
+  std::string stem;
+  std::unique_ptr<DataLogThread> datalog;
+  std::string status;
+  bool highlight = false;
+};
+
+struct Entry {
+  explicit Entry(const wpi::log::StartRecordData& srd)
+      : name{srd.name}, type{srd.type}, metadata{srd.metadata} {}
+
+  std::string name;
+  std::string type;
+  std::string metadata;
+  std::set<InputFile*> inputFiles;
+  bool typeConflict = false;
+  bool metadataConflict = false;
+  bool selected = true;
+
+  // used only during export
+  int column = -1;
+};
+
+struct EntryTreeNode {
+  explicit EntryTreeNode(std::string_view name) : name{name} {}
+  std::string name;  // name of just this node
+  std::string path;  // full path if entry is nullptr
+  Entry* entry = nullptr;
+  std::vector<EntryTreeNode> children;  // children, sorted by name
+  int selected = 1;
+};
+}  // namespace
+
+static std::map<std::string, std::unique_ptr<InputFile>, std::less<>>
+    gInputFiles;
+static wpi::mutex gEntriesMutex;
+static std::map<std::string, std::unique_ptr<Entry>, std::less<>> gEntries;
+static std::vector<EntryTreeNode> gEntryTree;
+std::atomic_int gExportCount{0};
+
+// must be called with gEntriesMutex held
+static void RebuildEntryTree() {
+  gEntryTree.clear();
+  wpi::SmallVector<std::string_view, 16> parts;
+  for (auto& kv : gEntries) {
+    parts.clear();
+    // split on first : if one is present
+    auto [prefix, mainpart] = wpi::split(kv.first, ':');
+    if (mainpart.empty() || wpi::contains(prefix, '/')) {
+      mainpart = kv.first;
+    } else {
+      parts.emplace_back(prefix);
+    }
+    wpi::split(mainpart, parts, '/', -1, false);
+
+    // ignore a raw "/" key
+    if (parts.empty()) {
+      continue;
+    }
+
+    // get to leaf
+    auto nodes = &gEntryTree;
+    for (auto part : wpi::drop_back(std::span{parts.begin(), parts.end()})) {
+      auto it =
+          std::find_if(nodes->begin(), nodes->end(),
+                       [&](const auto& node) { return node.name == part; });
+      if (it == nodes->end()) {
+        nodes->emplace_back(part);
+        // path is from the beginning of the string to the end of the current
+        // part; this works because part is a reference to the internals of
+        // kv.first
+        nodes->back().path.assign(kv.first.data(),
+                                  part.data() + part.size() - kv.first.data());
+        it = nodes->end() - 1;
+      }
+      nodes = &it->children;
+    }
+
+    auto it = std::find_if(nodes->begin(), nodes->end(), [&](const auto& node) {
+      return node.name == parts.back();
+    });
+    if (it == nodes->end()) {
+      nodes->emplace_back(parts.back());
+      // no need to set path, as it's identical to kv.first
+      it = nodes->end() - 1;
+    }
+    it->entry = kv.second.get();
+  }
+}
+
+InputFile::InputFile(std::unique_ptr<DataLogThread> datalog_)
+    : filename{datalog_->GetBufferIdentifier()},
+      stem{fs::path{filename}.stem().string()},
+      datalog{std::move(datalog_)} {
+  datalog->sigEntryAdded.connect([this](const wpi::log::StartRecordData& srd) {
+    std::scoped_lock lock{gEntriesMutex};
+    auto it = gEntries.find(srd.name);
+    if (it == gEntries.end()) {
+      it = gEntries.emplace(srd.name, std::make_unique<Entry>(srd)).first;
+      RebuildEntryTree();
+    } else {
+      if (it->second->type != srd.type) {
+        it->second->typeConflict = true;
+      }
+      if (it->second->metadata != srd.metadata) {
+        it->second->metadataConflict = true;
+      }
+    }
+    it->second->inputFiles.emplace(this);
+  });
+}
+
+InputFile::~InputFile() {
+  if (gShutdown || !datalog) {
+    return;
+  }
+  std::scoped_lock lock{gEntriesMutex};
+  bool changed = false;
+  for (auto it = gEntries.begin(); it != gEntries.end();) {
+    it->second->inputFiles.erase(this);
+    if (it->second->inputFiles.empty()) {
+      it = gEntries.erase(it);
+      changed = true;
+    } else {
+      ++it;
+    }
+  }
+  if (changed) {
+    RebuildEntryTree();
+  }
+}
+
+static std::unique_ptr<InputFile> LoadDataLog(std::string_view filename) {
+  std::error_code ec;
+  auto buf = wpi::MemoryBuffer::GetFile(filename, ec);
+  std::string fn{filename};
+  if (ec) {
+    return std::make_unique<InputFile>(
+        fn, fmt::format("Could not open file: {}", ec.message()));
+  }
+
+  wpi::log::DataLogReader reader{std::move(buf)};
+  if (!reader.IsValid()) {
+    return std::make_unique<InputFile>(fn, "Not a valid datalog file");
+  }
+
+  return std::make_unique<InputFile>(
+      std::make_unique<DataLogThread>(std::move(reader)));
+}
+
+void DisplayInputFiles() {
+  static std::unique_ptr<pfd::open_file> dataFileSelector;
+
+  SetNextWindowPos(ImVec2{0, 20}, ImGuiCond_FirstUseEver);
+  SetNextWindowSize(ImVec2{375, 230}, ImGuiCond_FirstUseEver);
+  if (ImGui::Begin("Input Files")) {
+    if (ImGui::Button("Open File(s)...")) {
+      dataFileSelector = std::make_unique<pfd::open_file>(
+          "Select Data Log", "",
+          std::vector<std::string>{"DataLog Files", "*.wpilog"},
+          pfd::opt::multiselect);
+    }
+    ImGui::BeginTable(
+        "Input Files", 3,
+        ImGuiTableFlags_Borders | ImGuiTableFlags_SizingStretchProp);
+    ImGui::TableSetupColumn("File");
+    ImGui::TableSetupColumn("Status");
+    ImGui::TableSetupColumn("X", ImGuiTableColumnFlags_WidthFixed |
+                                     ImGuiTableColumnFlags_NoHeaderLabel |
+                                     ImGuiTableColumnFlags_NoHeaderWidth);
+    ImGui::TableHeadersRow();
+    for (auto it = gInputFiles.begin(); it != gInputFiles.end();) {
+      ImGui::TableNextRow();
+      ImGui::TableNextColumn();
+      if (it->second->highlight) {
+        ImGui::TableSetBgColor(ImGuiTableBgTarget_RowBg0,
+                               IM_COL32(0, 64, 0, 255));
+        it->second->highlight = false;
+      }
+      ImGui::TextUnformatted(it->first.c_str());
+      if (ImGui::IsItemHovered()) {
+        ImGui::SetTooltip("%s", it->second->filename.c_str());
+      }
+
+      ImGui::TableNextColumn();
+      if (it->second->datalog) {
+        ImGui::Text("%u records, %u entries%s",
+                    it->second->datalog->GetNumRecords(),
+                    it->second->datalog->GetNumEntries(),
+                    it->second->datalog->IsDone() ? "" : " (working)");
+      } else {
+        ImGui::TextUnformatted(it->second->status.c_str());
+      }
+
+      ImGui::TableNextColumn();
+      ImGui::PushID(it->first.c_str());
+      if (ImGui::SmallButton("X")) {
+        it = gInputFiles.erase(it);
+        gExportCount = 0;
+      } else {
+        ++it;
+      }
+      ImGui::PopID();
+    }
+    ImGui::EndTable();
+  }
+  ImGui::End();
+
+  // Load data file(s)
+  if (dataFileSelector && dataFileSelector->ready(0)) {
+    auto result = dataFileSelector->result();
+    for (auto&& filename : result) {
+      // don't allow duplicates
+      std::string stem = fs::path{filename}.stem().string();
+      auto it = gInputFiles.find(stem);
+      if (it == gInputFiles.end()) {
+        gInputFiles.emplace(std::move(stem), LoadDataLog(filename));
+        gExportCount = 0;
+      }
+    }
+    dataFileSelector.reset();
+  }
+}
+
+static bool EmitEntry(const std::string& name, Entry& entry) {
+  ImGui::TableNextColumn();
+  bool rv = ImGui::Checkbox(name.c_str(), &entry.selected);
+  if (ImGui::IsItemHovered() && gInputFiles.size() > 1) {
+    for (auto inputFile : entry.inputFiles) {
+      inputFile->highlight = true;
+    }
+  }
+
+  ImGui::TableNextColumn();
+  if (entry.typeConflict) {
+    ImGui::TextUnformatted("(Inconsistent)");
+    if (ImGui::IsItemHovered()) {
+      ImGui::BeginTooltip();
+      for (auto inputFile : entry.inputFiles) {
+        ImGui::Text(
+            "%s: %s", inputFile->stem.c_str(),
+            std::string{inputFile->datalog->GetEntry(entry.name).type}.c_str());
+      }
+      ImGui::EndTooltip();
+    }
+  } else {
+    ImGui::TextUnformatted(entry.type.c_str());
+  }
+
+  ImGui::TableNextColumn();
+  if (entry.metadataConflict) {
+    ImGui::TextUnformatted("(Inconsistent)");
+    if (ImGui::IsItemHovered()) {
+      ImGui::BeginTooltip();
+      for (auto inputFile : entry.inputFiles) {
+        ImGui::Text(
+            "%s: %s", inputFile->stem.c_str(),
+            std::string{inputFile->datalog->GetEntry(entry.name).metadata}
+                .c_str());
+      }
+      ImGui::EndTooltip();
+    }
+  } else {
+    ImGui::TextUnformatted(entry.metadata.c_str());
+  }
+  return rv;
+}
+
+static bool EmitEntryTree(std::vector<EntryTreeNode>& tree) {
+  bool rv = false;
+  for (auto&& node : tree) {
+    if (node.entry) {
+      if (EmitEntry(node.name, *node.entry)) {
+        rv = true;
+      }
+    }
+
+    if (!node.children.empty()) {
+      ImGui::TableNextColumn();
+      auto label = fmt::format("##check_{}", node.name);
+      if (node.selected == -1) {
+        ImGui::PushItemFlag(ImGuiItemFlags_MixedValue, true);
+        bool b = false;
+        if (ImGui::Checkbox(label.c_str(), &b)) {
+          node.selected = 3;  // 3 = enable group
+          rv = true;
+        }
+        ImGui::PopItemFlag();
+      } else {
+        bool b = node.selected == 1 || node.selected == 3;
+        if (ImGui::Checkbox(label.c_str(), &b)) {
+          node.selected = b ? 3 : 2;  // 2 = disable group
+          rv = true;
+        }
+      }
+      ImGui::SameLine();
+      bool open = ImGui::TreeNodeEx(node.name.c_str(),
+                                    ImGuiTreeNodeFlags_SpanFullWidth);
+      ImGui::TableNextColumn();
+      ImGui::TableNextColumn();
+      if (open) {
+        if (EmitEntryTree(node.children)) {
+          rv = true;
+        }
+        ImGui::TreePop();
+      }
+    }
+  }
+  return rv;
+}
+
+static void RefreshTreeCheckboxes(std::vector<EntryTreeNode>& tree,
+                                  int* selected) {
+  bool first = true;
+  for (auto&& node : tree) {
+    if (node.entry) {
+      if (first && *selected == -1) {
+        *selected = node.entry->selected ? 1 : 0;
+      }
+      if ((*selected == 0 && node.entry->selected) ||
+          (*selected == 1 && !node.entry->selected)) {
+        *selected = -1;             // inconsistent
+      } else if (*selected == 2) {  // disable group
+        node.entry->selected = false;
+      } else if (*selected == 3) {  // enable group
+        node.entry->selected = true;
+      }
+    }
+
+    if (!node.children.empty()) {
+      if (*selected == 2) {  // disable group
+        node.selected = 2;
+      } else if (*selected == 3) {  // enable group
+        node.selected = 3;
+      }
+      RefreshTreeCheckboxes(node.children, &node.selected);
+      if (node.selected == 2) {
+        node.selected = 0;
+      } else if (node.selected == 3) {
+        node.selected = 1;
+      }
+      if (first && *selected == -1) {
+        *selected = node.selected;
+      } else if (node.selected == -1 ||
+                 (*selected == 0 && node.selected == 1) ||
+                 (*selected == 1 && node.selected == 0)) {
+        *selected = -1;  // inconsistent
+      }
+    }
+
+    first = false;
+  }
+}
+
+void DisplayEntries() {
+  SetNextWindowPos(ImVec2{380, 20}, ImGuiCond_FirstUseEver);
+  SetNextWindowSize(ImVec2{540, 365}, ImGuiCond_FirstUseEver);
+  if (ImGui::Begin("Entries")) {
+    static bool treeView = true;
+    if (ImGui::BeginPopupContextItem()) {
+      ImGui::MenuItem("Tree View", "", &treeView);
+      ImGui::EndPopup();
+    }
+    std::scoped_lock lock{gEntriesMutex};
+    ImGui::BeginTable(
+        "Entries", 3,
+        ImGuiTableFlags_Borders | ImGuiTableFlags_SizingStretchProp);
+    ImGui::TableSetupColumn("Name");
+    ImGui::TableSetupColumn("Type");
+    ImGui::TableSetupColumn("Metadata");
+    ImGui::TableHeadersRow();
+    if (treeView) {
+      if (EmitEntryTree(gEntryTree)) {
+        int selected = -1;
+        RefreshTreeCheckboxes(gEntryTree, &selected);
+      }
+    } else {
+      for (auto&& kv : gEntries) {
+        EmitEntry(kv.first, *kv.second);
+      }
+    }
+    ImGui::EndTable();
+  }
+  ImGui::End();
+}
+
+static wpi::mutex gExportMutex;
+static std::vector<std::string> gExportErrors;
+
+static void PrintEscapedCsvString(wpi::raw_ostream& os, std::string_view str) {
+  auto s = str;
+  while (!s.empty()) {
+    std::string_view fragment;
+    std::tie(fragment, s) = wpi::split(s, '"');
+    os << fragment;
+    if (!s.empty()) {
+      os << '"' << '"';
+    }
+  }
+  if (wpi::ends_with(str, '"')) {
+    os << '"' << '"';
+  }
+}
+
+static void ValueToCsv(wpi::raw_ostream& os, const Entry& entry,
+                       const wpi::log::DataLogRecord& record) {
+  // handle systemTime specially
+  if (entry.name == "systemTime" && entry.type == "int64") {
+    int64_t val;
+    if (record.GetInteger(&val)) {
+      std::time_t timeval = val / 1000000;
+      fmt::print(os, "{:%Y-%m-%d %H:%M:%S}.{:06}", *std::localtime(&timeval),
+                 val % 1000000);
+      return;
+    }
+  } else if (entry.type == "double") {
+    double val;
+    if (record.GetDouble(&val)) {
+      fmt::print(os, "{}", val);
+      return;
+    }
+  } else if (entry.type == "int64") {
+    int64_t val;
+    if (record.GetInteger(&val)) {
+      fmt::print(os, "{}", val);
+      return;
+    }
+  } else if (entry.type == "string" || entry.type == "json") {
+    std::string_view val;
+    record.GetString(&val);
+    os << '"';
+    PrintEscapedCsvString(os, val);
+    os << '"';
+    return;
+  } else if (entry.type == "boolean") {
+    bool val;
+    if (record.GetBoolean(&val)) {
+      fmt::print(os, "{}", val);
+      return;
+    }
+  } else if (entry.type == "boolean[]") {
+    std::vector<int> val;
+    if (record.GetBooleanArray(&val)) {
+      fmt::print(os, "{}", fmt::join(val, ";"));
+      return;
+    }
+  } else if (entry.type == "double[]") {
+    std::vector<double> val;
+    if (record.GetDoubleArray(&val)) {
+      fmt::print(os, "{}", fmt::join(val, ";"));
+      return;
+    }
+  } else if (entry.type == "float[]") {
+    std::vector<float> val;
+    if (record.GetFloatArray(&val)) {
+      fmt::print(os, "{}", fmt::join(val, ";"));
+      return;
+    }
+  } else if (entry.type == "int64[]") {
+    std::vector<int64_t> val;
+    if (record.GetIntegerArray(&val)) {
+      fmt::print(os, "{}", fmt::join(val, ";"));
+      return;
+    }
+  } else if (entry.type == "string[]") {
+    std::vector<std::string_view> val;
+    if (record.GetStringArray(&val)) {
+      os << '"';
+      bool first = true;
+      for (auto&& v : val) {
+        if (!first) {
+          os << ';';
+        }
+        first = false;
+        PrintEscapedCsvString(os, v);
+      }
+      os << '"';
+      return;
+    }
+  }
+  fmt::print(os, "<invalid>");
+}
+
+static void ExportCsvFile(InputFile& f, wpi::raw_ostream& os, int style) {
+  // header
+  if (style == 0) {
+    os << "Timestamp,Name,Value\n";
+  } else if (style == 1) {
+    // scan for exported fields for this file to print header and assign columns
+    os << "Timestamp";
+    int columnNum = 0;
+    for (auto&& entry : gEntries) {
+      if (entry.second->selected &&
+          entry.second->inputFiles.find(&f) != entry.second->inputFiles.end()) {
+        os << ',' << '"';
+        PrintEscapedCsvString(os, entry.first);
+        os << '"';
+        entry.second->column = columnNum++;
+      } else {
+        entry.second->column = -1;
+      }
+    }
+    os << '\n';
+  }
+
+  wpi::DenseMap<int, Entry*> nameMap;
+  for (auto&& record : f.datalog->GetReader()) {
+    if (record.IsStart()) {
+      wpi::log::StartRecordData data;
+      if (record.GetStartData(&data)) {
+        auto it = gEntries.find(data.name);
+        if (it != gEntries.end() && it->second->selected) {
+          nameMap[data.entry] = it->second.get();
+        }
+      }
+    } else if (record.IsFinish()) {
+      int entry;
+      if (record.GetFinishEntry(&entry)) {
+        nameMap.erase(entry);
+      }
+    } else if (!record.IsControl()) {
+      auto entryIt = nameMap.find(record.GetEntry());
+      if (entryIt == nameMap.end()) {
+        continue;
+      }
+      Entry* entry = entryIt->second;
+
+      if (style == 0) {
+        fmt::print(os, "{},\"", record.GetTimestamp() / 1000000.0);
+        PrintEscapedCsvString(os, entry->name);
+        os << '"' << ',';
+        ValueToCsv(os, *entry, record);
+        os << '\n';
+      } else if (style == 1 && entry->column != -1) {
+        fmt::print(os, "{},", record.GetTimestamp() / 1000000.0);
+        for (int i = 0; i < entry->column; ++i) {
+          os << ',';
+        }
+        ValueToCsv(os, *entry, record);
+        os << '\n';
+      }
+    }
+  }
+}
+
+static void ExportCsv(std::string_view outputFolder, int style) {
+  fs::path outPath{outputFolder};
+  for (auto&& f : gInputFiles) {
+    if (f.second->datalog) {
+      std::error_code ec;
+      auto of = fs::OpenFileForWrite(
+          outPath / fs::path{f.first}.replace_extension("csv"), ec,
+          fs::CD_CreateNew, fs::OF_Text);
+      if (ec) {
+        std::scoped_lock lock{gExportMutex};
+        gExportErrors.emplace_back(
+            fmt::format("{}: {}", f.first, ec.message()));
+        ++gExportCount;
+        continue;
+      }
+      wpi::raw_fd_ostream os{fs::FileToFd(of, ec, fs::OF_Text), true};
+      ExportCsvFile(*f.second, os, style);
+    }
+    ++gExportCount;
+  }
+}
+
+void DisplayOutput(glass::Storage& storage) {
+  static std::string& outputFolder = storage.GetString("outputFolder");
+  static std::unique_ptr<pfd::select_folder> outputFolderSelector;
+
+  SetNextWindowPos(ImVec2{380, 390}, ImGuiCond_FirstUseEver);
+  SetNextWindowSize(ImVec2{540, 120}, ImGuiCond_FirstUseEver);
+  if (ImGui::Begin("Output")) {
+    if (ImGui::Button("Select Output Folder...")) {
+      outputFolderSelector =
+          std::make_unique<pfd::select_folder>("Select Output Folder");
+    }
+    ImGui::TextUnformatted(outputFolder.c_str());
+
+    static const char* const options[] = {"List", "Table"};
+    static int style = 0;
+    ImGui::SetNextItemWidth(ImGui::GetFontSize() * 8);
+    ImGui::Combo("Style", &style, options,
+                 sizeof(options) / sizeof(const char*));
+
+    static std::future<void> exporter;
+    if (!gInputFiles.empty() && !outputFolder.empty() &&
+        ImGui::Button("Export CSV") &&
+        (gExportCount == 0 ||
+         gExportCount == static_cast<int>(gInputFiles.size()))) {
+      gExportCount = 0;
+      gExportErrors.clear();
+      exporter = std::async(std::launch::async, ExportCsv, outputFolder, style);
+    }
+    if (exporter.valid()) {
+      ImGui::SameLine();
+      ImGui::Text("Exported %d/%d", gExportCount.load(),
+                  static_cast<int>(gInputFiles.size()));
+    }
+    {
+      std::scoped_lock lock{gExportMutex};
+      for (auto&& err : gExportErrors) {
+        ImGui::TextUnformatted(err.c_str());
+      }
+    }
+  }
+  ImGui::End();
+
+  if (outputFolderSelector && outputFolderSelector->ready(0)) {
+    outputFolder = outputFolderSelector->result();
+    outputFolderSelector.reset();
+  }
+}
diff --git a/third_party/allwpilib/datalogtool/src/main/native/cpp/Exporter.h b/third_party/allwpilib/datalogtool/src/main/native/cpp/Exporter.h
new file mode 100644
index 0000000..8078243
--- /dev/null
+++ b/third_party/allwpilib/datalogtool/src/main/native/cpp/Exporter.h
@@ -0,0 +1,15 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+namespace glass {
+class Storage;
+}  // namespace glass
+
+void DisplayInputFiles();
+void DisplayEntries();
+void DisplayOutput(glass::Storage& storage);
+
+extern bool gShutdown;
diff --git a/third_party/allwpilib/datalogtool/src/main/native/cpp/Sftp.cpp b/third_party/allwpilib/datalogtool/src/main/native/cpp/Sftp.cpp
new file mode 100644
index 0000000..3a33d13
--- /dev/null
+++ b/third_party/allwpilib/datalogtool/src/main/native/cpp/Sftp.cpp
@@ -0,0 +1,215 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "Sftp.h"
+
+#include <fmt/format.h>
+
+using namespace sftp;
+
+Attributes::Attributes(sftp_attributes&& attr)
+    : name{attr->name}, flags{attr->flags}, type{attr->type}, size{attr->size} {
+  sftp_attributes_free(attr);
+}
+
+static std::string GetError(sftp_session sftp) {
+  switch (sftp_get_error(sftp)) {
+    case SSH_FX_EOF:
+      return "end of file";
+    case SSH_FX_NO_SUCH_FILE:
+      return "no such file";
+    case SSH_FX_PERMISSION_DENIED:
+      return "permission denied";
+    case SSH_FX_FAILURE:
+      return "SFTP failure";
+    case SSH_FX_BAD_MESSAGE:
+      return "SFTP bad message";
+    case SSH_FX_NO_CONNECTION:
+      return "SFTP no connection";
+    case SSH_FX_CONNECTION_LOST:
+      return "SFTP connection lost";
+    case SSH_FX_OP_UNSUPPORTED:
+      return "SFTP operation unsupported";
+    case SSH_FX_INVALID_HANDLE:
+      return "SFTP invalid handle";
+    case SSH_FX_NO_SUCH_PATH:
+      return "no such path";
+    case SSH_FX_FILE_ALREADY_EXISTS:
+      return "file already exists";
+    case SSH_FX_WRITE_PROTECT:
+      return "write protected filesystem";
+    case SSH_FX_NO_MEDIA:
+      return "no media inserted";
+    default:
+      return ssh_get_error(sftp->session);
+  }
+}
+
+Exception::Exception(sftp_session sftp)
+    : runtime_error{GetError(sftp)}, err{sftp_get_error(sftp)} {}
+
+File::~File() {
+  if (m_handle) {
+    sftp_close(m_handle);
+  }
+}
+
+Attributes File::Stat() const {
+  sftp_attributes attr = sftp_fstat(m_handle);
+  if (!attr) {
+    throw Exception{m_handle->sftp};
+  }
+  return Attributes{std::move(attr)};
+}
+
+size_t File::Read(void* buf, uint32_t count) {
+  auto rv = sftp_read(m_handle, buf, count);
+  if (rv < 0) {
+    throw Exception{m_handle->sftp};
+  }
+  return rv;
+}
+
+File::AsyncId File::AsyncReadBegin(uint32_t len) const {
+  int rv = sftp_async_read_begin(m_handle, len);
+  if (rv < 0) {
+    throw Exception{m_handle->sftp};
+  }
+  return rv;
+}
+
+size_t File::AsyncRead(void* data, uint32_t len, AsyncId id) {
+  auto rv = sftp_async_read(m_handle, data, len, id);
+  if (rv == SSH_ERROR) {
+    throw Exception{ssh_get_error(m_handle->sftp->session)};
+  }
+  if (rv == SSH_AGAIN) {
+    return 0;
+  }
+  return rv;
+}
+
+size_t File::Write(std::span<const uint8_t> data) {
+  auto rv = sftp_write(m_handle, data.data(), data.size());
+  if (rv < 0) {
+    throw Exception{m_handle->sftp};
+  }
+  return rv;
+}
+
+void File::Seek(uint64_t offset) {
+  if (sftp_seek64(m_handle, offset) < 0) {
+    throw Exception{m_handle->sftp};
+  }
+}
+
+uint64_t File::Tell() const {
+  return sftp_tell64(m_handle);
+}
+
+void File::Rewind() {
+  sftp_rewind(m_handle);
+}
+
+void File::Sync() {
+  if (sftp_fsync(m_handle) < 0) {
+    throw Exception{m_handle->sftp};
+  }
+}
+
+Session::Session(std::string_view host, int port, std::string_view user,
+                 std::string_view pass)
+    : m_host{host}, m_port{port}, m_username{user}, m_password{pass} {
+  // Create a new SSH session.
+  m_session = ssh_new();
+  if (!m_session) {
+    throw Exception{"The SSH session could not be allocated."};
+  }
+
+  // Set the host, user, and port.
+  ssh_options_set(m_session, SSH_OPTIONS_HOST, m_host.c_str());
+  ssh_options_set(m_session, SSH_OPTIONS_USER, m_username.c_str());
+  ssh_options_set(m_session, SSH_OPTIONS_PORT, &m_port);
+
+  // Set timeout to 3 seconds.
+  int64_t timeout = 3L;
+  ssh_options_set(m_session, SSH_OPTIONS_TIMEOUT, &timeout);
+
+  // Set other miscellaneous options.
+  ssh_options_set(m_session, SSH_OPTIONS_STRICTHOSTKEYCHECK, "no");
+}
+
+Session::~Session() {
+  if (m_sftp) {
+    sftp_free(m_sftp);
+  }
+  if (m_session) {
+    ssh_free(m_session);
+  }
+}
+
+void Session::Connect() {
+  // Connect to the server.
+  int rc = ssh_connect(m_session);
+  if (rc != SSH_OK) {
+    throw Exception{ssh_get_error(m_session)};
+  }
+
+  // Authenticate with password.
+  rc = ssh_userauth_password(m_session, nullptr, m_password.c_str());
+  if (rc != SSH_AUTH_SUCCESS) {
+    throw Exception{ssh_get_error(m_session)};
+  }
+
+  // Allocate the SFTP session.
+  m_sftp = sftp_new(m_session);
+  if (!m_sftp) {
+    throw Exception{ssh_get_error(m_session)};
+  }
+
+  // Initialize.
+  rc = sftp_init(m_sftp);
+  if (rc != SSH_OK) {
+    sftp_free(m_sftp);
+    m_sftp = nullptr;
+    throw Exception{ssh_get_error(m_session)};
+  }
+}
+
+void Session::Disconnect() {
+  if (m_sftp) {
+    sftp_free(m_sftp);
+    m_sftp = nullptr;
+  }
+  ssh_disconnect(m_session);
+}
+
+std::vector<Attributes> Session::ReadDir(const std::string& path) {
+  sftp_dir dir = sftp_opendir(m_sftp, path.c_str());
+  if (!dir) {
+    throw Exception{m_sftp};
+  }
+
+  std::vector<Attributes> rv;
+  while (sftp_attributes attr = sftp_readdir(m_sftp, dir)) {
+    rv.emplace_back(std::move(attr));
+  }
+
+  sftp_closedir(dir);
+  return rv;
+}
+
+void Session::Unlink(const std::string& filename) {
+  if (sftp_unlink(m_sftp, filename.c_str()) < 0) {
+    throw Exception{m_sftp};
+  }
+}
+
+File Session::Open(const std::string& filename, int accesstype, mode_t mode) {
+  sftp_file f = sftp_open(m_sftp, filename.c_str(), accesstype, mode);
+  if (!f) {
+    throw Exception{m_sftp};
+  }
+  return File{std::move(f)};
+}
diff --git a/third_party/allwpilib/datalogtool/src/main/native/cpp/Sftp.h b/third_party/allwpilib/datalogtool/src/main/native/cpp/Sftp.h
new file mode 100644
index 0000000..e6fec4a
--- /dev/null
+++ b/third_party/allwpilib/datalogtool/src/main/native/cpp/Sftp.h
@@ -0,0 +1,143 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <libssh/libssh.h>
+#include <libssh/sftp.h>
+
+#include <span>
+#include <stdexcept>
+#include <string>
+#include <string_view>
+#include <vector>
+
+namespace sftp {
+
+struct Attributes {
+  Attributes() = default;
+  explicit Attributes(sftp_attributes&& attr);
+
+  std::string name;
+  uint32_t flags = 0;
+  uint8_t type = 0;
+  uint64_t size = 0;
+};
+
+/**
+ * This is the exception that will be thrown if something goes wrong.
+ */
+class Exception : public std::runtime_error {
+ public:
+  explicit Exception(const std::string& msg) : std::runtime_error{msg} {}
+  explicit Exception(sftp_session sftp);
+
+  int err = 0;
+};
+
+class File {
+ public:
+  File() = default;
+  explicit File(sftp_file&& handle) : m_handle{handle} {}
+  ~File();
+
+  Attributes Stat() const;
+
+  void SetNonblocking() { sftp_file_set_nonblocking(m_handle); }
+  void SetBlocking() { sftp_file_set_blocking(m_handle); }
+
+  using AsyncId = uint32_t;
+
+  size_t Read(void* buf, uint32_t count);
+  AsyncId AsyncReadBegin(uint32_t len) const;
+  size_t AsyncRead(void* data, uint32_t len, AsyncId id);
+  size_t Write(std::span<const uint8_t> data);
+
+  void Seek(uint64_t offset);
+  uint64_t Tell() const;
+  void Rewind();
+
+  void Sync();
+
+  std::string_view GetName() const { return m_handle->name; }
+  uint64_t GetOffset() const { return m_handle->offset; }
+  bool IsEof() const { return m_handle->eof; }
+  bool IsNonblocking() const { return m_handle->nonblocking; }
+
+ private:
+  sftp_file m_handle{nullptr};
+};
+
+/**
+ * This class is a C++ implementation of the SshSessionController in
+ * wpilibsuite/deploy-utils. It handles connecting to an SSH server, running
+ * commands, and transferring files.
+ */
+class Session {
+ public:
+  /**
+   * Constructs a new session controller.
+   *
+   * @param host The hostname of the server to connect to.
+   * @param port The port that the sshd server is operating on.
+   * @param user The username to login as.
+   * @param pass The password for the given username.
+   */
+  Session(std::string_view host, int port, std::string_view user,
+          std::string_view pass);
+
+  /**
+   * Destroys the controller object. This also disconnects the session from the
+   * server.
+   */
+  ~Session();
+
+  /**
+   * Opens the SSH connection to the given host.
+   */
+  void Connect();
+
+  /**
+   * Disconnects the SSH connection.
+   */
+  void Disconnect();
+
+  /**
+   * Reads directory entries
+   *
+   * @param path remote path
+   * @return vector of file attributes
+   */
+  std::vector<Attributes> ReadDir(const std::string& path);
+
+  /**
+   * Unlinks (deletes) a file.
+   *
+   * @param filename filename
+   */
+  void Unlink(const std::string& filename);
+
+  /**
+   * Opens a file.
+   *
+   * @param filename filename
+   * @param accesstype O_RDONLY, O_WRONLY, or O_RDWR, combined with O_CREAT,
+   *                   O_EXCL, or O_TRUNC
+   * @param mode permissions to use if a new file is created
+   * @return File
+   */
+  File Open(const std::string& filename, int accesstype, mode_t mode);
+
+ private:
+  ssh_session m_session{nullptr};
+  sftp_session m_sftp{nullptr};
+  std::string m_host;
+
+  int m_port;
+
+  std::string m_username;
+  std::string m_password;
+};
+
+}  // namespace sftp
diff --git a/third_party/allwpilib/datalogtool/src/main/native/cpp/main.cpp b/third_party/allwpilib/datalogtool/src/main/native/cpp/main.cpp
new file mode 100644
index 0000000..5f1261b
--- /dev/null
+++ b/third_party/allwpilib/datalogtool/src/main/native/cpp/main.cpp
@@ -0,0 +1,25 @@
+// Copyright (c) FIRST and other WPILib contributors.

+// Open Source Software; you can modify and/or share it under the terms of

+// the WPILib BSD license file in the root directory of this project.

+

+#include <string_view>

+

+void Application(std::string_view saveDir);

+

+#ifdef _WIN32

+int __stdcall WinMain(void* hInstance, void* hPrevInstance, char* pCmdLine,

+                      int nCmdShow) {

+  int argc = __argc;

+  char** argv = __argv;

+#else

+int main(int argc, char** argv) {

+#endif

+  std::string_view saveDir;

+  if (argc == 2) {

+    saveDir = argv[1];

+  }

+

+  Application(saveDir);

+

+  return 0;

+}

diff --git a/third_party/allwpilib/datalogtool/src/main/native/mac/datalogtool.icns b/third_party/allwpilib/datalogtool/src/main/native/mac/datalogtool.icns
new file mode 100644
index 0000000..583eaab
--- /dev/null
+++ b/third_party/allwpilib/datalogtool/src/main/native/mac/datalogtool.icns
Binary files differ
diff --git a/third_party/allwpilib/datalogtool/src/main/native/resources/dlt-128.png b/third_party/allwpilib/datalogtool/src/main/native/resources/dlt-128.png
new file mode 100644
index 0000000..b2ebf51
--- /dev/null
+++ b/third_party/allwpilib/datalogtool/src/main/native/resources/dlt-128.png
Binary files differ
diff --git a/third_party/allwpilib/datalogtool/src/main/native/resources/dlt-16.png b/third_party/allwpilib/datalogtool/src/main/native/resources/dlt-16.png
new file mode 100644
index 0000000..f7439c6
--- /dev/null
+++ b/third_party/allwpilib/datalogtool/src/main/native/resources/dlt-16.png
Binary files differ
diff --git a/third_party/allwpilib/datalogtool/src/main/native/resources/dlt-256.png b/third_party/allwpilib/datalogtool/src/main/native/resources/dlt-256.png
new file mode 100644
index 0000000..c1a40d2
--- /dev/null
+++ b/third_party/allwpilib/datalogtool/src/main/native/resources/dlt-256.png
Binary files differ
diff --git a/third_party/allwpilib/datalogtool/src/main/native/resources/dlt-32.png b/third_party/allwpilib/datalogtool/src/main/native/resources/dlt-32.png
new file mode 100644
index 0000000..1d9a212
--- /dev/null
+++ b/third_party/allwpilib/datalogtool/src/main/native/resources/dlt-32.png
Binary files differ
diff --git a/third_party/allwpilib/datalogtool/src/main/native/resources/dlt-48.png b/third_party/allwpilib/datalogtool/src/main/native/resources/dlt-48.png
new file mode 100644
index 0000000..119d054
--- /dev/null
+++ b/third_party/allwpilib/datalogtool/src/main/native/resources/dlt-48.png
Binary files differ
diff --git a/third_party/allwpilib/datalogtool/src/main/native/resources/dlt-512.png b/third_party/allwpilib/datalogtool/src/main/native/resources/dlt-512.png
new file mode 100644
index 0000000..6dfd821
--- /dev/null
+++ b/third_party/allwpilib/datalogtool/src/main/native/resources/dlt-512.png
Binary files differ
diff --git a/third_party/allwpilib/datalogtool/src/main/native/resources/dlt-64.png b/third_party/allwpilib/datalogtool/src/main/native/resources/dlt-64.png
new file mode 100644
index 0000000..4ad82c7
--- /dev/null
+++ b/third_party/allwpilib/datalogtool/src/main/native/resources/dlt-64.png
Binary files differ
diff --git a/third_party/allwpilib/datalogtool/src/main/native/win/datalogtool.ico b/third_party/allwpilib/datalogtool/src/main/native/win/datalogtool.ico
new file mode 100644
index 0000000..1b90647
--- /dev/null
+++ b/third_party/allwpilib/datalogtool/src/main/native/win/datalogtool.ico
Binary files differ
diff --git a/third_party/allwpilib/datalogtool/src/main/native/win/datalogtool.rc b/third_party/allwpilib/datalogtool/src/main/native/win/datalogtool.rc
new file mode 100644
index 0000000..d0a5fb4
--- /dev/null
+++ b/third_party/allwpilib/datalogtool/src/main/native/win/datalogtool.rc
@@ -0,0 +1 @@
+IDI_ICON1 ICON "datalogtool.ico"
diff --git a/third_party/allwpilib/docs/build.gradle b/third_party/allwpilib/docs/build.gradle
index dd06239..e00e0f3 100644
--- a/third_party/allwpilib/docs/build.gradle
+++ b/third_party/allwpilib/docs/build.gradle
@@ -3,16 +3,17 @@
     id "org.ysb33r.doxygen" version "0.7.0"
 }
 
-evaluationDependsOn(':wpiutil')
-evaluationDependsOn(':ntcore')
+evaluationDependsOn(':apriltag')
+evaluationDependsOn(':cameraserver')
 evaluationDependsOn(':cscore')
 evaluationDependsOn(':hal')
-evaluationDependsOn(':cameraserver')
-evaluationDependsOn(':wpimath')
+evaluationDependsOn(':ntcore')
+evaluationDependsOn(':wpilibNewCommands')
 evaluationDependsOn(':wpilibc')
 evaluationDependsOn(':wpilibj')
-evaluationDependsOn(':wpilibOldCommands')
-evaluationDependsOn(':wpilibNewCommands')
+evaluationDependsOn(':wpimath')
+evaluationDependsOn(':wpinet')
+evaluationDependsOn(':wpiutil')
 
 def baseArtifactIdCpp = 'documentation'
 def artifactGroupIdCpp = 'edu.wpi.first.wpilibc'
@@ -27,20 +28,28 @@
 def cppProjectZips = []
 def cppIncludeRoots = []
 
-cppProjectZips.add(project(':hal').cppHeadersZip)
-cppProjectZips.add(project(':wpiutil').cppHeadersZip)
-cppProjectZips.add(project(':ntcore').cppHeadersZip)
-cppProjectZips.add(project(':cscore').cppHeadersZip)
+cppProjectZips.add(project(':apriltag').cppHeadersZip)
 cppProjectZips.add(project(':cameraserver').cppHeadersZip)
-cppProjectZips.add(project(':wpimath').cppHeadersZip)
-cppProjectZips.add(project(':wpilibc').cppHeadersZip)
-cppProjectZips.add(project(':wpilibOldCommands').cppHeadersZip)
+cppProjectZips.add(project(':cscore').cppHeadersZip)
+cppProjectZips.add(project(':hal').cppHeadersZip)
+cppProjectZips.add(project(':ntcore').cppHeadersZip)
 cppProjectZips.add(project(':wpilibNewCommands').cppHeadersZip)
+cppProjectZips.add(project(':wpilibc').cppHeadersZip)
+cppProjectZips.add(project(':wpimath').cppHeadersZip)
+cppProjectZips.add(project(':wpinet').cppHeadersZip)
+cppProjectZips.add(project(':wpiutil').cppHeadersZip)
 
 doxygen {
-    executables {
-        doxygen version : '1.9.2',
-        baseURI : 'https://frcmaven.wpi.edu/artifactory/generic-release-mirror/doxygen'
+    // Doxygen binaries are only provided for x86_64 platforms
+    // Other platforms will need to provide doxygen via their system
+    // See below maven and https://doxygen.nl/download.html for provided binaries
+
+    String arch = System.getProperty("os.arch");
+    if (arch.equals("x86_64") || arch.equals("amd64")) {
+        executables {
+            doxygen version : '1.9.4',
+            baseURI : 'https://frcmaven.wpi.edu/artifactory/generic-release-mirror/doxygen'
+        }
     }
 }
 
@@ -59,7 +68,6 @@
     if (project.hasProperty('docWarningsAsErrors')) {
         // C++20 shims
         exclude 'wpi/ghc/filesystem.hpp'
-        exclude 'wpi/span.h'
 
         // Drake
         exclude 'drake/common/**'
@@ -112,11 +120,14 @@
         // libuv
         exclude 'uv.h'
         exclude 'uv/**'
-        exclude 'wpi/uv/**'
+        exclude 'wpinet/uv/**'
 
         // json
         exclude 'wpi/json.h'
 
+        // memory
+        exclude 'wpi/memory/**'
+
         // mpack
         exclude 'wpi/mpack.h'
 
@@ -124,6 +135,15 @@
         exclude 'units/**'
     }
 
+    //TODO: building memory docs causes search to break
+    exclude 'wpi/memory/**'
+
+    aliases 'effects=\\par <i>Effects:</i>^^',
+            'notes=\\par <i>Notes:</i>^^',
+            'requires=\\par <i>Requires:</i>^^',
+            'requiredbe=\\par <i>Required Behavior:</i>^^',
+            'concept{2}=<a href=\"md_doc_concepts.html#\1\">\2</a>',
+            'defaultbe=\\par <i>Default Behavior:</i>^^'
     case_sense_names false
     extension_mapping 'inc=C++', 'no_extension=C++'
     extract_all true
@@ -150,7 +170,7 @@
     warn_if_undocumented false
     warn_no_paramdoc true
 
-    //enable doxygen preprocessor expansion of WPI_DEPRECATED to fix SpeedController docs
+    //enable doxygen preprocessor expansion of WPI_DEPRECATED to fix MotorController docs
     enable_preprocessing true
     macro_expansion true
     expand_only_predef true
@@ -194,18 +214,20 @@
     options.addBooleanOption("Xdoclint:html,missing,reference,syntax", true)
     options.addBooleanOption('html5', true)
     options.linkSource(true)
-    dependsOn project(':wpilibj').generateJavaVersion
     dependsOn project(':hal').generateUsageReporting
+    dependsOn project(':ntcore').ntcoreGenerateJavaTypes
+    dependsOn project(':wpilibj').generateJavaVersion
     dependsOn project(':wpimath').generateNat
-    source project(':hal').sourceSets.main.java
-    source project(':wpiutil').sourceSets.main.java
-    source project(':cscore').sourceSets.main.java
-    source project(':ntcore').sourceSets.main.java
-    source project(':wpimath').sourceSets.main.java
-    source project(':wpilibj').sourceSets.main.java
+    source project(':apriltag').sourceSets.main.java
     source project(':cameraserver').sourceSets.main.java
-    source project(':wpilibOldCommands').sourceSets.main.java
+    source project(':cscore').sourceSets.main.java
+    source project(':hal').sourceSets.main.java
+    source project(':ntcore').sourceSets.main.java
     source project(':wpilibNewCommands').sourceSets.main.java
+    source project(':wpilibj').sourceSets.main.java
+    source project(':wpimath').sourceSets.main.java
+    source project(':wpinet').sourceSets.main.java
+    source project(':wpiutil').sourceSets.main.java
     source configurations.javaSource.collect { zipTree(it) }
     include '**/*.java'
     failOnError = true
diff --git a/third_party/allwpilib/fieldImages/CMakeLists.txt b/third_party/allwpilib/fieldImages/CMakeLists.txt
index efe6d4d..bf02505 100644
--- a/third_party/allwpilib/fieldImages/CMakeLists.txt
+++ b/third_party/allwpilib/fieldImages/CMakeLists.txt
@@ -7,6 +7,9 @@
     find_package(Java REQUIRED)
     include(UseJava)
 
+    file(GLOB JACKSON_JARS "${WPILIB_BINARY_DIR}/wpiutil/thirdparty/jackson/*.jar")
+    set(CMAKE_JAVA_INCLUDE_PATH fieldImages.jar ${JACKSON_JARS})
+
     file(GLOB_RECURSE JAVA_SOURCES src/main/java/*.java)
     file(GLOB_RECURSE JAVA_RESOURCES src/main/native/resources/*.json src/main/native/resources/*.png src/main/native/resources/*.jpg)
     add_jar(field_images_jar SOURCES ${JAVA_SOURCES} RESOURCES NAMESPACE "edu/wpi/first/fields" ${JAVA_RESOURCES} OUTPUT_NAME fieldImages)
@@ -26,7 +29,7 @@
 set_target_properties(fieldImages PROPERTIES DEBUG_POSTFIX "d")
 
 set_property(TARGET fieldImages PROPERTY FOLDER "libraries")
-target_compile_features(fieldImages PUBLIC cxx_std_17)
+target_compile_features(fieldImages PUBLIC cxx_std_20)
 if (MSVC)
     target_compile_options(fieldImages PUBLIC /bigobj)
 endif()
diff --git a/third_party/allwpilib/fieldImages/build.gradle b/third_party/allwpilib/fieldImages/build.gradle
index 476dd3c..123e89d 100644
--- a/third_party/allwpilib/fieldImages/build.gradle
+++ b/third_party/allwpilib/fieldImages/build.gradle
@@ -1,6 +1,6 @@
 import org.gradle.internal.os.OperatingSystem
 
-if (!project.hasProperty('onlylinuxathena') && !project.hasProperty('onlylinuxraspbian') && !project.hasProperty('onlylinuxaarch64bionic')) {
+if (!project.hasProperty('onlylinuxathena')) {
 
     apply plugin: 'cpp'
     apply plugin: 'c'
@@ -13,6 +13,12 @@
         apply plugin: 'windows-resources'
     }
 
+    dependencies {
+        implementation "com.fasterxml.jackson.core:jackson-annotations:2.12.4"
+        implementation "com.fasterxml.jackson.core:jackson-core:2.12.4"
+        implementation "com.fasterxml.jackson.core:jackson-databind:2.12.4"
+    }
+
     ext {
         nativeName = 'fieldImages'
         baseId = nativeName
diff --git a/third_party/allwpilib/fieldImages/src/main/java/edu/wpi/fields/FieldConfig.java b/third_party/allwpilib/fieldImages/src/main/java/edu/wpi/fields/FieldConfig.java
new file mode 100644
index 0000000..a8dd087
--- /dev/null
+++ b/third_party/allwpilib/fieldImages/src/main/java/edu/wpi/fields/FieldConfig.java
@@ -0,0 +1,90 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.fields;
+
+import com.fasterxml.jackson.annotation.JsonProperty;
+import com.fasterxml.jackson.databind.ObjectMapper;
+import java.io.BufferedReader;
+import java.io.IOException;
+import java.io.InputStream;
+import java.io.InputStreamReader;
+import java.net.URL;
+import java.nio.file.Files;
+import java.nio.file.Path;
+
+public class FieldConfig {
+  public static class Corners {
+    @JsonProperty("top-left")
+    public double[] m_topLeft;
+
+    @JsonProperty("bottom-right")
+    public double[] m_bottomRight;
+  }
+
+  @JsonProperty("game")
+  public String m_game;
+
+  @JsonProperty("field-image")
+  public String m_fieldImage;
+
+  @JsonProperty("field-corners")
+  public Corners m_fieldCorners;
+
+  @JsonProperty("field-size")
+  public double[] m_fieldSize;
+
+  @JsonProperty("field-unit")
+  public String m_fieldUnit;
+
+  public FieldConfig() {}
+
+  @SuppressWarnings("deprecation")
+  public URL getImageUrl() {
+    return getClass().getResource(Fields.kBaseResourceDir + m_fieldImage);
+  }
+
+  @SuppressWarnings("deprecation")
+  public InputStream getImageAsStream() {
+    return getClass().getResourceAsStream(Fields.kBaseResourceDir + m_fieldImage);
+  }
+
+  /**
+   * Loads a predefined field configuration from a resource file.
+   *
+   * @param field The predefined field
+   * @return The field configuration
+   * @throws IOException Throws if the file could not be loaded
+   */
+  public static FieldConfig loadField(Fields field) throws IOException {
+    return loadFromResource(field.m_resourceFile);
+  }
+
+  /**
+   * Loads a field configuration from a file on disk.
+   *
+   * @param file The json file to load
+   * @return The field configuration
+   * @throws IOException Throws if the file could not be loaded
+   */
+  public static FieldConfig loadFromFile(Path file) throws IOException {
+    try (BufferedReader reader = Files.newBufferedReader(file)) {
+      return new ObjectMapper().readerFor(FieldConfig.class).readValue(reader);
+    }
+  }
+
+  /**
+   * Loads a field configuration from a resource file located inside the programs jar file.
+   *
+   * @param resourcePath The path to the resource file
+   * @return The field configuration
+   * @throws IOException Throws if the resoure could not be loaded
+   */
+  public static FieldConfig loadFromResource(String resourcePath) throws IOException {
+    try (InputStream stream = FieldConfig.class.getResourceAsStream(resourcePath);
+        InputStreamReader reader = new InputStreamReader(stream)) {
+      return new ObjectMapper().readerFor(FieldConfig.class).readValue(reader);
+    }
+  }
+}
diff --git a/third_party/allwpilib/fieldImages/src/main/java/edu/wpi/fields/FieldImages.java b/third_party/allwpilib/fieldImages/src/main/java/edu/wpi/fields/FieldImages.java
deleted file mode 100644
index f482478..0000000
--- a/third_party/allwpilib/fieldImages/src/main/java/edu/wpi/fields/FieldImages.java
+++ /dev/null
@@ -1,25 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.fields;
-
-public class FieldImages {
-  public static final String k2018PowerUpFieldConfig = "/edu/wpi/first/fields/2018-powerup.json";
-  public static final String k2019DeepSpaceFieldConfig =
-      "/edu/wpi/first/fields/2019-deepspace.json";
-  public static final String k2020InfiniteRechargeFieldConfig =
-      "/edu/wpi/first/fields/2020-infiniterecharge.json";
-  public static final String k2021InfiniteRechargeFieldConfig =
-      "/edu/wpi/first/fields/2021-infiniterecharge.json";
-  public static final String k2021BarrelFieldConfig =
-      "/edu/wpi/first/fields/2021-barrelracingpath.json";
-  public static final String k2021BounceFieldConfig = "/edu/wpi/first/fields/2021-bouncepath.json";
-  public static final String k2021GalacticSearchAFieldConfig =
-      "/edu/wpi/first/fields/2021-galacticsearcha.json";
-  public static final String k2021GalacticSearchBFieldConfig =
-      "/edu/wpi/first/fields/2021-galacticsearchb.json";
-  public static final String k2021SlalomFieldConfig = "/edu/wpi/first/fields/2021-slalompath.json";
-  public static final String k2022RapidReactFieldConfig =
-      "/edu/wpi/first/fields/2022-rapidreact.json";
-}
diff --git a/third_party/allwpilib/fieldImages/src/main/java/edu/wpi/fields/Fields.java b/third_party/allwpilib/fieldImages/src/main/java/edu/wpi/fields/Fields.java
new file mode 100644
index 0000000..4fc3508
--- /dev/null
+++ b/third_party/allwpilib/fieldImages/src/main/java/edu/wpi/fields/Fields.java
@@ -0,0 +1,29 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.fields;
+
+public enum Fields {
+  k2018PowerUp("2018-powerup.json"),
+  k2019DeepSpace("2019-deepspace.json"),
+  k2020InfiniteRecharge("2020-infiniterecharge.json"),
+  k2021InfiniteRecharge("2021-infiniterecharge.json"),
+  k2021Barrel("2021-barrelracingpath.json"),
+  k2021Bounce("2021-bouncepath.json"),
+  k2021GalacticSearchA("2021-galacticsearcha.json"),
+  k2021GalacticSearchB("2021-galacticsearchb.json"),
+  k2021Slalom("2021-slalompath.json"),
+  k2022RapidReact("2022-rapidreact.json");
+
+  public static final String kBaseResourceDir = "/edu/wpi/first/fields/";
+
+  /** Alias to the current game. */
+  public static final Fields kDefaultField = k2022RapidReact;
+
+  public final String m_resourceFile;
+
+  Fields(String resourceFile) {
+    m_resourceFile = kBaseResourceDir + resourceFile;
+  }
+}
diff --git a/third_party/allwpilib/fieldImages/src/test/java/edu/wpi/fields/LoadConfigTest.java b/third_party/allwpilib/fieldImages/src/test/java/edu/wpi/fields/LoadConfigTest.java
new file mode 100644
index 0000000..f4f1621
--- /dev/null
+++ b/third_party/allwpilib/fieldImages/src/test/java/edu/wpi/fields/LoadConfigTest.java
@@ -0,0 +1,19 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.fields;
+
+import org.junit.jupiter.api.Assertions;
+import org.junit.jupiter.params.ParameterizedTest;
+import org.junit.jupiter.params.provider.EnumSource;
+
+class LoadConfigTest {
+  @ParameterizedTest
+  @EnumSource(Fields.class)
+  void testLoad(Fields field) {
+    FieldConfig config = Assertions.assertDoesNotThrow(() -> FieldConfig.loadField(field));
+
+    Assertions.assertNotNull(config.getImageUrl());
+  }
+}
diff --git a/third_party/allwpilib/glass/.styleguide b/third_party/allwpilib/glass/.styleguide
index d555d5a..c2a291a 100644
--- a/third_party/allwpilib/glass/.styleguide
+++ b/third_party/allwpilib/glass/.styleguide
@@ -24,6 +24,7 @@
   ^fmt/
   ^frc/
   ^imgui
+  ^networktables/
   ^ntcore
   ^wpi/
   ^wpigui
diff --git a/third_party/allwpilib/glass/build.gradle b/third_party/allwpilib/glass/build.gradle
index cd77f45..47b943c 100644
--- a/third_party/allwpilib/glass/build.gradle
+++ b/third_party/allwpilib/glass/build.gradle
@@ -1,6 +1,6 @@
 import org.gradle.internal.os.OperatingSystem
 
-if (!project.hasProperty('onlylinuxathena') && !project.hasProperty('onlylinuxraspbian') && !project.hasProperty('onlylinuxaarch64bionic')) {
+if (!project.hasProperty('onlylinuxathena')) {
 
     description = "A different kind of dashboard"
 
@@ -24,6 +24,8 @@
     def wpilibVersionFileInput = file("src/app/generate/WPILibVersion.cpp.in")
     def wpilibVersionFileOutput = file("$buildDir/generated/app/cpp/WPILibVersion.cpp")
 
+    apply from: "${rootDir}/shared/imgui.gradle"
+
     task generateCppVersion() {
         description = 'Generates the wpilib version class'
         group = 'WPILib'
@@ -69,19 +71,6 @@
 
     nativeUtils.exportsConfigs {
         glass {
-            x86ExcludeSymbols = [
-                '_CT??_R0?AV_System_error',
-                '_CT??_R0?AVexception',
-                '_CT??_R0?AVfailure',
-                '_CT??_R0?AVruntime_error',
-                '_CT??_R0?AVsystem_error',
-                '_CTA5?AVfailure',
-                '_TI5?AVfailure',
-                '_CT??_R0?AVout_of_range',
-                '_CTA3?AVout_of_range',
-                '_TI3?AVout_of_range',
-                '_CT??_R0?AVbad_cast'
-            ]
             x64ExcludeSymbols = [
                 '_CT??_R0?AV_System_error',
                 '_CT??_R0?AVexception',
@@ -113,7 +102,7 @@
                     }
                 }
                 binaries.all {
-                    if (it.targetPlatform.name == nativeUtils.wpi.platforms.roborio || it.targetPlatform.name == nativeUtils.wpi.platforms.raspbian || it.targetPlatform.name == nativeUtils.wpi.platforms.aarch64bionic) {
+                    if (it.targetPlatform.name == nativeUtils.wpi.platforms.roborio) {
                         it.buildable = false
                         return
                     }
@@ -124,7 +113,7 @@
                     lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
                     lib project: ':wpimath', library: 'wpimath', linkage: 'shared'
                     lib project: ':wpigui', library: 'wpigui', linkage: 'static'
-                    nativeUtils.useRequiredLibrary(it, 'imgui_static')
+                    nativeUtils.useRequiredLibrary(it, 'imgui')
                 }
                 appendDebugPathToBinaries(binaries)
             }
@@ -141,7 +130,7 @@
                     }
                 }
                 binaries.all {
-                    if (it.targetPlatform.name == nativeUtils.wpi.platforms.roborio || it.targetPlatform.name == nativeUtils.wpi.platforms.raspbian || it.targetPlatform.name == nativeUtils.wpi.platforms.aarch64bionic) {
+                    if (it.targetPlatform.name == nativeUtils.wpi.platforms.roborio) {
                         it.buildable = false
                         return
                     }
@@ -150,11 +139,12 @@
                         return
                     }
                     lib library: nativeName, linkage: 'static'
-                    lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
+                    project(':ntcore').addNtcoreDependency(it, 'shared')
+                    lib project: ':wpinet', library: 'wpinet', linkage: 'shared'
                     lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
                     lib project: ':wpimath', library: 'wpimath', linkage: 'shared'
                     lib project: ':wpigui', library: 'wpigui', linkage: 'static'
-                    nativeUtils.useRequiredLibrary(it, 'imgui_static')
+                    nativeUtils.useRequiredLibrary(it, 'imgui')
                 }
                 appendDebugPathToBinaries(binaries)
             }
@@ -181,19 +171,20 @@
                     }
                 }
                 binaries.all {
-                    if (it.targetPlatform.name == nativeUtils.wpi.platforms.roborio || it.targetPlatform.name == nativeUtils.wpi.platforms.raspbian || it.targetPlatform.name == nativeUtils.wpi.platforms.aarch64bionic) {
+                    if (it.targetPlatform.name == nativeUtils.wpi.platforms.roborio) {
                         it.buildable = false
                         return
                     }
                     lib project: ':cscore', library: 'cscore', linkage: 'static'
                     lib library: 'glassnt', linkage: 'static'
                     lib library: nativeName, linkage: 'static'
-                    lib project: ':ntcore', library: 'ntcore', linkage: 'static'
+                    project(':ntcore').addNtcoreDependency(it, 'static')
+                    lib project: ':wpinet', library: 'wpinet', linkage: 'static'
                     lib project: ':wpiutil', library: 'wpiutil', linkage: 'static'
                     lib project: ':wpimath', library: 'wpimath', linkage: 'static'
                     lib project: ':wpigui', library: 'wpigui', linkage: 'static'
                     nativeUtils.useRequiredLibrary(it, 'opencv_static')
-                    nativeUtils.useRequiredLibrary(it, 'imgui_static')
+                    nativeUtils.useRequiredLibrary(it, 'imgui')
                     if (it.targetPlatform.operatingSystem.isWindows()) {
                         it.linker.args << 'Gdi32.lib' << 'Shell32.lib' << 'd3d11.lib' << 'd3dcompiler.lib'
                         it.linker.args << '/DELAYLOAD:MF.dll' << '/DELAYLOAD:MFReadWrite.dll' << '/DELAYLOAD:MFPlat.dll' << '/delay:nobind'
@@ -201,6 +192,9 @@
                         it.linker.args << '-framework' << 'Metal' << '-framework' << 'MetalKit' << '-framework' << 'Cocoa' << '-framework' << 'IOKit' << '-framework' << 'CoreFoundation' << '-framework' << 'CoreVideo' << '-framework' << 'QuartzCore'
                     } else {
                         it.linker.args << '-lX11'
+                        if (it.targetPlatform.name.startsWith('linuxarm')) {
+                            it.linker.args << '-lGL'
+                        }
                     }
                 }
             }
diff --git a/third_party/allwpilib/glass/publish.gradle b/third_party/allwpilib/glass/publish.gradle
index f2e3da7..5e7cbaf 100644
--- a/third_party/allwpilib/glass/publish.gradle
+++ b/third_party/allwpilib/glass/publish.gradle
@@ -64,7 +64,8 @@
     tasks {
         // Create the run task.
         $.components.glassApp.binaries.each { bin ->
-            if (bin.buildable && bin.name.toLowerCase().contains("debug")) {
+            if (bin.buildable && bin.name.toLowerCase().contains("debug") && nativeUtils.isNativeDesktopPlatform(bin.targetPlatform)) {
+
                 Task run = project.tasks.create("run", Exec) {
                     commandLine bin.tasks.install.runScriptFile.get().asFile.toString()
                 }
@@ -77,20 +78,22 @@
         $.components.each { component ->
             component.binaries.each { binary ->
                 if (binary in NativeExecutableBinarySpec && binary.component.name.contains("glassApp")) {
-                    if (binary.buildable && binary.name.contains("Release")) {
+                    if (binary.buildable && (binary.name.contains('Release') || binary.name.contains('release'))) {
                         // We are now in the binary that we want.
                         // This is the default application path for the ZIP task.
                         def applicationPath = binary.executable.file
                         def icon = file("$project.projectDir/src/app/native/mac/glass.icns")
 
                         // Create the macOS bundle.
-                        def bundleTask = project.tasks.create("bundleGlassOsxApp", Copy) {
+                        def bundleTask = project.tasks.create("bundleGlassOsxApp" + binary.targetPlatform.architecture.name, Copy) {
                             description("Creates a macOS application bundle for Glass")
                             from(file("$project.projectDir/Info.plist"))
-                            into(file("$project.buildDir/outputs/bundles/Glass.app/Contents"))
+                            into(file("$project.buildDir/outputs/bundles/$binary.targetPlatform.architecture.name/Glass.app/Contents"))
                             into("MacOS") { with copySpec { from binary.executable.file } }
                             into("Resources") { with copySpec { from icon } }
 
+                            inputs.property "HasDeveloperId", project.hasProperty("developerID")
+
                             doLast {
                                 if (project.hasProperty("developerID")) {
                                     // Get path to binary.
@@ -102,7 +105,7 @@
                                             "codesign --force --strict --deep " +
                                             "--timestamp --options=runtime " +
                                             "--verbose -s ${project.findProperty("developerID")} " +
-                                            "$project.buildDir/outputs/bundles/Glass.app/"
+                                            "$project.buildDir/outputs/bundles/$binary.targetPlatform.architecture.name/Glass.app/"
                                         ]
                                         commandLine args
                                     }
@@ -112,12 +115,12 @@
 
                         // Reset the application path if we are creating a bundle.
                         if (binary.targetPlatform.operatingSystem.isMacOsX()) {
-                            applicationPath = file("$project.buildDir/outputs/bundles")
+                            applicationPath = file("$project.buildDir/outputs/bundles/$binary.targetPlatform.architecture.name")
                             project.build.dependsOn bundleTask
                         }
 
                         // Create the ZIP.
-                        def task = project.tasks.create("copyGlassExecutable", Zip) {
+                        def task = project.tasks.create("copyGlassExecutable" + binary.targetPlatform.architecture.name, Zip) {
                             description("Copies the Glass executable to the outputs directory.")
                             destinationDirectory = outputsFolder
 
diff --git a/third_party/allwpilib/glass/src/app/native/cpp/main.cpp b/third_party/allwpilib/glass/src/app/native/cpp/main.cpp
index b1569b8..a20ff8b 100644
--- a/third_party/allwpilib/glass/src/app/native/cpp/main.cpp
+++ b/third_party/allwpilib/glass/src/app/native/cpp/main.cpp
@@ -42,6 +42,7 @@
 static std::unique_ptr<glass::NetworkTablesSettings> gNetworkTablesSettings;
 static glass::LogData gNetworkTablesLog;
 static std::unique_ptr<glass::Window> gNetworkTablesWindow;
+static std::unique_ptr<glass::Window> gNetworkTablesInfoWindow;
 static std::unique_ptr<glass::Window> gNetworkTablesSettingsWindow;
 static std::unique_ptr<glass::Window> gNetworkTablesLogWindow;
 
@@ -49,48 +50,61 @@
 static bool gAbout = false;
 static bool gSetEnterKey = false;
 static bool gKeyEdit = false;
+static int* gEnterKey;
+static void (*gPrevKeyCallback)(GLFWwindow*, int, int, int, int);
+
+static void RemapEnterKeyCallback(GLFWwindow* window, int key, int scancode,
+                                  int action, int mods) {
+  if (action == GLFW_PRESS || action == GLFW_RELEASE) {
+    if (gKeyEdit) {
+      *gEnterKey = key;
+      gKeyEdit = false;
+    } else if (*gEnterKey == key) {
+      key = GLFW_KEY_ENTER;
+    }
+  }
+
+  if (gPrevKeyCallback) {
+    gPrevKeyCallback(window, key, scancode, action, mods);
+  }
+}
 
 static void NtInitialize() {
-  // update window title when connection status changes
   auto inst = nt::GetDefaultInstance();
-  auto poller = nt::CreateConnectionListenerPoller(inst);
-  nt::AddPolledConnectionListener(poller, true);
+  auto poller = nt::CreateListenerPoller(inst);
+  nt::AddPolledListener(
+      poller, inst,
+      NT_EVENT_CONNECTION | NT_EVENT_IMMEDIATE | NT_EVENT_LOGMESSAGE);
   gui::AddEarlyExecute([poller] {
     auto win = gui::GetSystemWindow();
     if (!win) {
       return;
     }
-    bool timedOut;
-    for (auto&& event : nt::PollConnectionListener(poller, 0, &timedOut)) {
-      if (event.connected) {
-        glfwSetWindowTitle(
-            win, fmt::format("Glass - Connected ({})", event.conn.remote_ip)
-                     .c_str());
-      } else {
-        glfwSetWindowTitle(win, "Glass - DISCONNECTED");
+    for (auto&& event : nt::ReadListenerQueue(poller)) {
+      if (auto connInfo = event.GetConnectionInfo()) {
+        // update window title when connection status changes
+        if ((event.flags & NT_EVENT_CONNECTED) != 0) {
+          glfwSetWindowTitle(
+              win, fmt::format("Glass - Connected ({})", connInfo->remote_ip)
+                       .c_str());
+        } else {
+          glfwSetWindowTitle(win, "Glass - DISCONNECTED");
+        }
+      } else if (auto msg = event.GetLogMessage()) {
+        const char* level = "";
+        if (msg->level >= NT_LOG_CRITICAL) {
+          level = "CRITICAL: ";
+        } else if (msg->level >= NT_LOG_ERROR) {
+          level = "ERROR: ";
+        } else if (msg->level >= NT_LOG_WARNING) {
+          level = "WARNING: ";
+        }
+        gNetworkTablesLog.Append(fmt::format(
+            "{}{} ({}:{})\n", level, msg->message, msg->filename, msg->line));
       }
     }
   });
 
-  // handle NetworkTables log messages
-  auto logPoller = nt::CreateLoggerPoller(inst);
-  nt::AddPolledLogger(logPoller, NT_LOG_INFO, 100);
-  gui::AddEarlyExecute([logPoller] {
-    bool timedOut;
-    for (auto&& msg : nt::PollLogger(logPoller, 0, &timedOut)) {
-      const char* level = "";
-      if (msg.level >= NT_LOG_CRITICAL) {
-        level = "CRITICAL: ";
-      } else if (msg.level >= NT_LOG_ERROR) {
-        level = "ERROR: ";
-      } else if (msg.level >= NT_LOG_WARNING) {
-        level = "WARNING: ";
-      }
-      gNetworkTablesLog.Append(fmt::format("{}{} ({}:{})\n", level, msg.message,
-                                           msg.filename, msg.line));
-    }
-  });
-
   gNetworkTablesLogWindow = std::make_unique<glass::Window>(
       glass::GetStorageRoot().GetChild("NetworkTables Log"),
       "NetworkTables Log", glass::Window::kHide);
@@ -114,9 +128,21 @@
   gNetworkTablesWindow->DisableRenamePopup();
   gui::AddLateExecute([] { gNetworkTablesWindow->Display(); });
 
+  // NetworkTables info window
+  gNetworkTablesInfoWindow = std::make_unique<glass::Window>(
+      glass::GetStorageRoot().GetChild("NetworkTables Info"),
+      "NetworkTables Info");
+  gNetworkTablesInfoWindow->SetView(glass::MakeFunctionView(
+      [&] { glass::DisplayNetworkTablesInfo(gNetworkTablesModel.get()); }));
+  gNetworkTablesInfoWindow->SetDefaultPos(250, 130);
+  gNetworkTablesInfoWindow->SetDefaultSize(750, 145);
+  gNetworkTablesInfoWindow->SetDefaultVisibility(glass::Window::kHide);
+  gNetworkTablesInfoWindow->DisableRenamePopup();
+  gui::AddLateExecute([] { gNetworkTablesInfoWindow->Display(); });
+
   // NetworkTables settings window
   gNetworkTablesSettings = std::make_unique<glass::NetworkTablesSettings>(
-      glass::GetStorageRoot().GetChild("NetworkTables Settings"));
+      "glass", glass::GetStorageRoot().GetChild("NetworkTables Settings"));
   gui::AddEarlyExecute([] { gNetworkTablesSettings->Update(); });
 
   gNetworkTablesSettingsWindow = std::make_unique<glass::Window>(
@@ -161,6 +187,11 @@
   gui::AddIcon(glass::GetResource_glass_256_png());
   gui::AddIcon(glass::GetResource_glass_512_png());
 
+  gui::AddEarlyExecute(
+      [] { ImGui::DockSpaceOverViewport(ImGui::GetMainViewport()); });
+
+  gui::AddInit([] { ImGui::GetIO().ConfigDockingWithShift = true; });
+
   gPlotProvider = std::make_unique<glass::PlotProvider>(
       glass::GetStorageRoot().GetChild("Plots"));
   gNtProvider = std::make_unique<glass::NetworkTablesProvider>(
@@ -195,6 +226,9 @@
       if (gNetworkTablesWindow) {
         gNetworkTablesWindow->DisplayMenuItem("NetworkTables View");
       }
+      if (gNetworkTablesInfoWindow) {
+        gNetworkTablesInfoWindow->DisplayMenuItem("NetworkTables Info");
+      }
       if (gNetworkTablesLogWindow) {
         gNetworkTablesLogWindow->DisplayMenuItem("NetworkTables Log");
       }
@@ -237,11 +271,6 @@
       ImGui::EndPopup();
     }
 
-    int& enterKey = glass::GetStorageRoot().GetInt("enterKey", GLFW_KEY_ENTER);
-
-    ImGuiIO& io = ImGui::GetIO();
-    io.KeyMap[ImGuiKey_Enter] = enterKey;
-
     if (gSetEnterKey) {
       ImGui::OpenPopup("Set Enter Key");
       gSetEnterKey = false;
@@ -251,24 +280,13 @@
       ImGui::Text("This is useful to edit values without the DS disabling");
       ImGui::Separator();
 
-      if (gKeyEdit) {
-        for (int i = 0; i < IM_ARRAYSIZE(io.KeysDown); ++i) {
-          if (io.KeysDown[i]) {
-            // remove all other uses
-            enterKey = i;
-            gKeyEdit = false;
-            break;
-          }
-        }
-      }
-
       ImGui::Text("Key:");
       ImGui::SameLine();
       char editLabel[40];
       char nameBuf[32];
-      const char* name = glfwGetKeyName(enterKey, 0);
+      const char* name = glfwGetKeyName(*gEnterKey, 0);
       if (!name) {
-        std::snprintf(nameBuf, sizeof(nameBuf), "%d", enterKey);
+        std::snprintf(nameBuf, sizeof(nameBuf), "%d", *gEnterKey);
         name = nameBuf;
       }
       std::snprintf(editLabel, sizeof(editLabel), "%s###edit",
@@ -278,7 +296,7 @@
       }
       ImGui::SameLine();
       if (ImGui::SmallButton("Reset")) {
-        enterKey = GLFW_KEY_ENTER;
+        *gEnterKey = GLFW_KEY_ENTER;
       }
 
       if (ImGui::Button("Close")) {
@@ -289,7 +307,12 @@
     }
   });
 
-  gui::Initialize("Glass - DISCONNECTED", 1024, 768);
+  gui::Initialize("Glass - DISCONNECTED", 1024, 768,
+                  ImGuiConfigFlags_DockingEnable);
+  gEnterKey = &glass::GetStorageRoot().GetInt("enterKey", GLFW_KEY_ENTER);
+  if (auto win = gui::GetSystemWindow()) {
+    gPrevKeyCallback = glfwSetKeyCallback(win, RemapEnterKeyCallback);
+  }
   gui::Main();
 
   gNetworkTablesSettingsWindow.reset();
diff --git a/third_party/allwpilib/glass/src/lib/native/cpp/Context.cpp b/third_party/allwpilib/glass/src/lib/native/cpp/Context.cpp
index 1de4af8..a55cf82 100644
--- a/third_party/allwpilib/glass/src/lib/native/cpp/Context.cpp
+++ b/third_party/allwpilib/glass/src/lib/native/cpp/Context.cpp
@@ -69,6 +69,9 @@
   wpi::raw_string_ostream ini{iniStr};
 
   for (auto&& jsection : jfile.items()) {
+    if (jsection.key() == "Docking") {
+      continue;
+    }
     if (!jsection.value().is_object()) {
       ImGui::LogText("%s section %s is not object", filename,
                      jsection.key().c_str());
@@ -95,6 +98,31 @@
       ini << '\n';
     }
   }
+
+  // emit Docking section last
+  auto docking = jfile.find("Docking");
+  if (docking != jfile.end()) {
+    for (auto&& jsubsection : docking->items()) {
+      if (!jsubsection.value().is_array()) {
+        ImGui::LogText("%s section %s subsection %s is not array", filename,
+                       "Docking", jsubsection.key().c_str());
+        return false;
+      }
+      ini << "[Docking][" << jsubsection.key() << "]\n";
+      for (auto&& jv : jsubsection.value()) {
+        try {
+          auto& value = jv.get_ref<const std::string&>();
+          ini << value << "\n";
+        } catch (wpi::json::exception&) {
+          ImGui::LogText("%s section %s subsection %s value is not string",
+                         filename, "Docking", jsubsection.key().c_str());
+          return false;
+        }
+      }
+      ini << '\n';
+    }
+  }
+
   ini.flush();
 
   ImGui::LoadIniSettingsFromMemory(iniStr.data(), iniStr.size());
@@ -204,7 +232,11 @@
       }
       curSection = &jsection[subsection];
       if (curSection->is_null()) {
-        *curSection = wpi::json::object();
+        if (section == "Docking") {
+          *curSection = wpi::json::array();
+        } else {
+          *curSection = wpi::json::object();
+        }
       }
     } else {
       // value
@@ -212,7 +244,11 @@
         continue;  // shouldn't happen, but just in case
       }
       auto [name, value] = wpi::split(line, '=');
-      (*curSection)[name] = value;
+      if (curSection->is_object()) {
+        (*curSection)[name] = value;
+      } else if (curSection->is_array()) {
+        curSection->emplace_back(line);
+      }
     }
   }
 
@@ -510,15 +546,24 @@
 bool glass::PopupEditName(const char* label, std::string* name) {
   bool rv = false;
   if (ImGui::BeginPopupContextItem(label)) {
-    ImGui::Text("Edit name:");
-    if (ImGui::InputText("##editname", name)) {
-      rv = true;
-    }
-    if (ImGui::Button("Close") || ImGui::IsKeyPressedMap(ImGuiKey_Enter) ||
-        ImGui::IsKeyPressedMap(ImGuiKey_KeyPadEnter)) {
-      ImGui::CloseCurrentPopup();
-    }
+    rv = ItemEditName(name);
+
     ImGui::EndPopup();
   }
   return rv;
 }
+
+bool glass::ItemEditName(std::string* name) {
+  bool rv = false;
+
+  ImGui::Text("Edit name:");
+  if (ImGui::InputText("##editname", name)) {
+    rv = true;
+  }
+  if (ImGui::Button("Close") || ImGui::IsKeyPressedMap(ImGuiKey_Enter) ||
+      ImGui::IsKeyPressedMap(ImGuiKey_KeyPadEnter)) {
+    ImGui::CloseCurrentPopup();
+  }
+
+  return rv;
+}
diff --git a/third_party/allwpilib/glass/src/lib/native/cpp/Storage.cpp b/third_party/allwpilib/glass/src/lib/native/cpp/Storage.cpp
index 28af20b..add6203 100644
--- a/third_party/allwpilib/glass/src/lib/native/cpp/Storage.cpp
+++ b/third_party/allwpilib/glass/src/lib/native/cpp/Storage.cpp
@@ -254,7 +254,7 @@
   }                                                                            \
                                                                                \
   std::vector<ArrCType>& Storage::Get##CapsName##Array(                        \
-      std::string_view key, wpi::span<const ArrCType> defaultVal) {            \
+      std::string_view key, std::span<const ArrCType> defaultVal) {            \
     auto& valuePtr = m_values[key];                                            \
     bool setValue = false;                                                     \
     if (!valuePtr) {                                                           \
diff --git a/third_party/allwpilib/glass/src/lib/native/cpp/View.cpp b/third_party/allwpilib/glass/src/lib/native/cpp/View.cpp
index e01c4df..3f28200 100644
--- a/third_party/allwpilib/glass/src/lib/native/cpp/View.cpp
+++ b/third_party/allwpilib/glass/src/lib/native/cpp/View.cpp
@@ -25,3 +25,9 @@
 }
 
 void View::Hidden() {}
+
+void View::Settings() {}
+
+bool View::HasSettings() {
+  return false;
+}
diff --git a/third_party/allwpilib/glass/src/lib/native/cpp/Window.cpp b/third_party/allwpilib/glass/src/lib/native/cpp/Window.cpp
index 6296fab..f43c0ee 100644
--- a/third_party/allwpilib/glass/src/lib/native/cpp/Window.cpp
+++ b/third_party/allwpilib/glass/src/lib/native/cpp/Window.cpp
@@ -4,11 +4,13 @@
 
 #include "glass/Window.h"
 
+#include <imgui.h>
 #include <imgui_internal.h>
 #include <wpi/StringExtras.h>
 
 #include "glass/Context.h"
 #include "glass/Storage.h"
+#include "glass/support/ExtraGuiWidgets.h"
 
 using namespace glass;
 
@@ -59,9 +61,57 @@
                 m_id.c_str());
 
   if (Begin(label, &m_visible, m_flags)) {
-    if (m_renamePopupEnabled) {
-      PopupEditName(nullptr, &m_name);
+    if (m_renamePopupEnabled || m_view->HasSettings()) {
+      bool isClicked = (ImGui::IsMouseReleased(ImGuiMouseButton_Right) &&
+                        ImGui::IsItemHovered());
+      ImGuiWindow* window = ImGui::GetCurrentWindow();
+
+      bool settingsButtonClicked = false;
+      // Not docked, and window has just enough for the circles not to be
+      // touching
+      if (!ImGui::IsWindowDocked() &&
+          ImGui::GetWindowWidth() > (ImGui::GetFontSize() + 2) * 3 +
+                                        ImGui::GetStyle().FramePadding.x * 2) {
+        const ImGuiItemFlags itemFlagsRestore =
+            ImGui::GetCurrentContext()->CurrentItemFlags;
+
+        ImGui::GetCurrentContext()->CurrentItemFlags |=
+            ImGuiItemFlags_NoNavDefaultFocus;
+        window->DC.NavLayerCurrent = ImGuiNavLayer_Menu;
+
+        // Allow to draw outside of normal window
+        ImGui::PushClipRect(window->OuterRectClipped.Min,
+                            window->OuterRectClipped.Max, false);
+
+        const ImRect titleBarRect = ImGui::GetCurrentWindow()->TitleBarRect();
+        const ImVec2 position = {titleBarRect.Max.x -
+                                     (ImGui::GetStyle().FramePadding.x * 3) -
+                                     (ImGui::GetFontSize() * 2),
+                                 titleBarRect.Min.y};
+        settingsButtonClicked =
+            HamburgerButton(ImGui::GetID("#SETTINGS"), position);
+
+        ImGui::PopClipRect();
+
+        ImGui::GetCurrentContext()->CurrentItemFlags = itemFlagsRestore;
+      }
+      if (settingsButtonClicked || isClicked) {
+        ImGui::OpenPopup(window->ID);
+      }
+
+      if (ImGui::BeginPopupEx(window->ID,
+                              ImGuiWindowFlags_AlwaysAutoResize |
+                                  ImGuiWindowFlags_NoTitleBar |
+                                  ImGuiWindowFlags_NoSavedSettings)) {
+        if (m_renamePopupEnabled) {
+          ItemEditName(&m_name);
+        }
+        m_view->Settings();
+
+        ImGui::EndPopup();
+      }
     }
+
     m_view->Display();
   } else {
     m_view->Hidden();
diff --git a/third_party/allwpilib/glass/src/lib/native/cpp/hardware/Gyro.cpp b/third_party/allwpilib/glass/src/lib/native/cpp/hardware/Gyro.cpp
index 36a3525..607b251 100644
--- a/third_party/allwpilib/glass/src/lib/native/cpp/hardware/Gyro.cpp
+++ b/third_party/allwpilib/glass/src/lib/native/cpp/hardware/Gyro.cpp
@@ -10,7 +10,7 @@
 
 #include <imgui.h>
 #include <imgui_internal.h>
-#include <wpi/numbers>
+#include <numbers>
 
 #include "glass/Context.h"
 #include "glass/DataSource.h"
@@ -54,7 +54,7 @@
 
   // Draw the spokes at every 5 degrees and a "major" spoke every 45 degrees.
   for (int i = -175; i <= 180; i += 5) {
-    double radians = i * 2 * wpi::numbers::pi / 360.0;
+    double radians = i * 2 * std::numbers::pi / 360.0;
     ImVec2 direction(std::sin(radians), -std::cos(radians));
 
     bool major = i % 45 == 0;
@@ -74,7 +74,7 @@
 
   draw->AddCircleFilled(center, radius * 0.075, secondaryColor, 50);
 
-  double radians = value * 2 * wpi::numbers::pi / 360.0;
+  double radians = value * 2 * std::numbers::pi / 360.0;
   draw->AddLine(
       center - ImVec2(1, 0),
       center + ImVec2(std::sin(radians), -std::cos(radians)) * radius * 0.95f,
diff --git a/third_party/allwpilib/glass/src/lib/native/cpp/hardware/MotorController.cpp b/third_party/allwpilib/glass/src/lib/native/cpp/hardware/MotorController.cpp
new file mode 100644
index 0000000..96181b2
--- /dev/null
+++ b/third_party/allwpilib/glass/src/lib/native/cpp/hardware/MotorController.cpp
@@ -0,0 +1,50 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "glass/hardware/MotorController.h"
+
+#include <imgui.h>
+#include <imgui_internal.h>
+
+#include "glass/Context.h"
+#include "glass/DataSource.h"
+
+using namespace glass;
+
+void glass::DisplayMotorController(MotorControllerModel* m) {
+  // Get duty cycle data from the model and do not display anything if the data
+  // is null.
+  auto dc = m->GetPercentData();
+  if (!dc || !m->Exists()) {
+    ImGui::PushStyleColor(ImGuiCol_Text, IM_COL32(96, 96, 96, 255));
+    ImGui::Text("Unknown MotorController");
+    ImGui::PopStyleColor();
+    return;
+  }
+
+  // Set the buttons and sliders to read-only if the model is read-only.
+  if (m->IsReadOnly()) {
+    ImGui::PushItemFlag(ImGuiItemFlags_Disabled, true);
+    ImGui::PushStyleColor(ImGuiCol_Text, IM_COL32(210, 210, 210, 255));
+  }
+
+  // Add button to zero output.
+  if (ImGui::Button("Zero")) {
+    m->SetPercent(0.0);
+  }
+  ImGui::SameLine();
+
+  // Display a slider for the data.
+  float value = dc->GetValue();
+  ImGui::SetNextItemWidth(ImGui::GetFontSize() * 8);
+
+  if (dc->SliderFloat("% Output", &value, -1.0f, 1.0f)) {
+    m->SetPercent(value);
+  }
+
+  if (m->IsReadOnly()) {
+    ImGui::PopStyleColor();
+    ImGui::PopItemFlag();
+  }
+}
diff --git a/third_party/allwpilib/glass/src/lib/native/cpp/hardware/SpeedController.cpp b/third_party/allwpilib/glass/src/lib/native/cpp/hardware/SpeedController.cpp
deleted file mode 100644
index b278401..0000000
--- a/third_party/allwpilib/glass/src/lib/native/cpp/hardware/SpeedController.cpp
+++ /dev/null
@@ -1,50 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "glass/hardware/SpeedController.h"
-
-#include <imgui.h>
-#include <imgui_internal.h>
-
-#include "glass/Context.h"
-#include "glass/DataSource.h"
-
-using namespace glass;
-
-void glass::DisplaySpeedController(SpeedControllerModel* m) {
-  // Get duty cycle data from the model and do not display anything if the data
-  // is null.
-  auto dc = m->GetPercentData();
-  if (!dc || !m->Exists()) {
-    ImGui::PushStyleColor(ImGuiCol_Text, IM_COL32(96, 96, 96, 255));
-    ImGui::Text("Unknown SpeedController");
-    ImGui::PopStyleColor();
-    return;
-  }
-
-  // Set the buttons and sliders to read-only if the model is read-only.
-  if (m->IsReadOnly()) {
-    ImGui::PushItemFlag(ImGuiItemFlags_Disabled, true);
-    ImGui::PushStyleColor(ImGuiCol_Text, IM_COL32(210, 210, 210, 255));
-  }
-
-  // Add button to zero output.
-  if (ImGui::Button("Zero")) {
-    m->SetPercent(0.0);
-  }
-  ImGui::SameLine();
-
-  // Display a slider for the data.
-  float value = dc->GetValue();
-  ImGui::SetNextItemWidth(ImGui::GetFontSize() * 8);
-
-  if (dc->SliderFloat("% Output", &value, -1.0f, 1.0f)) {
-    m->SetPercent(value);
-  }
-
-  if (m->IsReadOnly()) {
-    ImGui::PopStyleColor();
-    ImGui::PopItemFlag();
-  }
-}
diff --git a/third_party/allwpilib/glass/src/lib/native/cpp/other/Drive.cpp b/third_party/allwpilib/glass/src/lib/native/cpp/other/Drive.cpp
index a73c6de..d54b2da 100644
--- a/third_party/allwpilib/glass/src/lib/native/cpp/other/Drive.cpp
+++ b/third_party/allwpilib/glass/src/lib/native/cpp/other/Drive.cpp
@@ -11,7 +11,7 @@
 
 #include <imgui.h>
 #include <imgui_internal.h>
-#include <wpi/numbers>
+#include <numbers>
 
 #include "glass/Context.h"
 #include "glass/DataSource.h"
@@ -55,11 +55,11 @@
     draw->AddTriangleFilled(
         arrowPos,
         arrowPos + ImRotate(ImVec2(0.0f, 7.5f),
-                            std::cos(angle + wpi::numbers::pi / 4),
-                            std::sin(angle + wpi::numbers::pi / 4)),
+                            std::cos(angle + std::numbers::pi / 4),
+                            std::sin(angle + std::numbers::pi / 4)),
         arrowPos + ImRotate(ImVec2(0.0f, 7.5f),
-                            std::cos(angle - wpi::numbers::pi / 4),
-                            std::sin(angle - wpi::numbers::pi / 4)),
+                            std::cos(angle - std::numbers::pi / 4),
+                            std::sin(angle - std::numbers::pi / 4)),
         color);
   };
 
@@ -88,30 +88,30 @@
   if (rotation != 0) {
     float radius = 60.0f;
     double a1 = 0.0;
-    double a2 = wpi::numbers::pi / 2 * rotation;
+    double a2 = std::numbers::pi / 2 * rotation;
 
     // PathArcTo requires a_min <= a_max, and rotation can be negative
     if (a1 > a2) {
       draw->PathArcTo(center, radius, a2, a1, 20);
       draw->PathStroke(color, false);
-      draw->PathArcTo(center, radius, a2 + wpi::numbers::pi,
-                      a1 + wpi::numbers::pi, 20);
+      draw->PathArcTo(center, radius, a2 + std::numbers::pi,
+                      a1 + std::numbers::pi, 20);
       draw->PathStroke(color, false);
     } else {
       draw->PathArcTo(center, radius, a1, a2, 20);
       draw->PathStroke(color, false);
-      draw->PathArcTo(center, radius, a1 + wpi::numbers::pi,
-                      a2 + wpi::numbers::pi, 20);
+      draw->PathArcTo(center, radius, a1 + std::numbers::pi,
+                      a2 + std::numbers::pi, 20);
       draw->PathStroke(color, false);
     }
 
-    double adder = rotation < 0 ? wpi::numbers::pi : 0;
+    double adder = rotation < 0 ? std::numbers::pi : 0;
 
     auto arrowPos =
         center + ImVec2(radius * -std::cos(a2), radius * -std::sin(a2));
     drawArrow(arrowPos, a2 + adder);
 
-    a2 += wpi::numbers::pi;
+    a2 += std::numbers::pi;
     arrowPos = center + ImVec2(radius * -std::cos(a2), radius * -std::sin(a2));
     drawArrow(arrowPos, a2 + adder);
   }
diff --git a/third_party/allwpilib/glass/src/lib/native/cpp/other/Field2D.cpp b/third_party/allwpilib/glass/src/lib/native/cpp/other/Field2D.cpp
index c3ef860..66e90b1 100644
--- a/third_party/allwpilib/glass/src/lib/native/cpp/other/Field2D.cpp
+++ b/third_party/allwpilib/glass/src/lib/native/cpp/other/Field2D.cpp
@@ -93,7 +93,7 @@
 
   SelectedTargetInfo* GetTarget() { return &m_target; }
   FieldObjectModel* GetInsertModel() { return m_insertModel; }
-  wpi::span<const frc::Pose2d> GetInsertPoses() const { return m_insertPoses; }
+  std::span<const frc::Pose2d> GetInsertPoses() const { return m_insertPoses; }
 
   void Display(Field2DModel* model, const FieldFrameData& ffd);
 
@@ -113,7 +113,7 @@
 struct DisplayOptions {
   explicit DisplayOptions(const gui::Texture& texture) : texture{texture} {}
 
-  enum Style { kBoxImage = 0, kLine, kLineClosed, kTrack };
+  enum Style { kBoxImage = 0, kLine, kLineClosed, kTrack, kHidden };
 
   static constexpr Style kDefaultStyle = kBoxImage;
   static constexpr float kDefaultWeight = 4.0f;
@@ -189,7 +189,7 @@
 
   DisplayOptions GetDisplayOptions() const;
   void DisplaySettings();
-  void DrawLine(ImDrawList* drawList, wpi::span<const ImVec2> points) const;
+  void DrawLine(ImDrawList* drawList, std::span<const ImVec2> points) const;
 
   void LoadImage();
   const gui::Texture& GetTexture() const { return m_texture; }
@@ -547,7 +547,7 @@
                                 DisplayOptions::kDefaultLength.to<float>())},
       m_style{storage.GetString("style"),
               DisplayOptions::kDefaultStyle,
-              {"Box/Image", "Line", "Line (Closed)", "Track"}},
+              {"Box/Image", "Line", "Line (Closed)", "Track", "Hidden"}},
       m_weight{storage.GetFloat("weight", DisplayOptions::kDefaultWeight)},
       m_color{
           storage.GetFloatArray("color", DisplayOptions::kDefaultColorFloat)},
@@ -617,7 +617,7 @@
 }
 
 void ObjectInfo::DrawLine(ImDrawList* drawList,
-                          wpi::span<const ImVec2> points) const {
+                          std::span<const ImVec2> points) const {
   if (points.empty()) {
     return;
   }
@@ -840,6 +840,8 @@
       left->emplace_back(m_corners[4]);
       right->emplace_back(m_corners[5]);
       break;
+    case DisplayOptions::kHidden:
+      break;
   }
 
   if (m_displayOptions.arrows) {
@@ -1215,10 +1217,14 @@
 }
 
 void Field2DView::Display() {
-  if (ImGui::BeginPopupContextItem()) {
-    DisplayField2DSettings(m_model);
-    ImGui::EndPopup();
-  }
   DisplayField2D(m_model, ImGui::GetWindowContentRegionMax() -
                               ImGui::GetWindowContentRegionMin());
 }
+
+void Field2DView::Settings() {
+  DisplayField2DSettings(m_model);
+}
+
+bool Field2DView::HasSettings() {
+  return true;
+}
diff --git a/third_party/allwpilib/glass/src/lib/native/cpp/other/Log.cpp b/third_party/allwpilib/glass/src/lib/native/cpp/other/Log.cpp
index 9a1d2c5..accf024 100644
--- a/third_party/allwpilib/glass/src/lib/native/cpp/other/Log.cpp
+++ b/third_party/allwpilib/glass/src/lib/native/cpp/other/Log.cpp
@@ -62,18 +62,21 @@
 }
 
 void LogView::Display() {
-  if (ImGui::BeginPopupContextItem()) {
-    ImGui::Checkbox("Auto-scroll", &m_autoScroll);
-    if (ImGui::Selectable("Clear")) {
-      m_data->Clear();
-    }
-    const auto& buf = m_data->GetBuffer();
-    if (ImGui::Selectable("Copy to Clipboard", false,
-                          buf.empty() ? ImGuiSelectableFlags_Disabled : 0)) {
-      ImGui::SetClipboardText(buf.c_str());
-    }
-    ImGui::EndPopup();
-  }
-
   DisplayLog(m_data, m_autoScroll);
 }
+
+void LogView::Settings() {
+  ImGui::Checkbox("Auto-scroll", &m_autoScroll);
+  if (ImGui::Selectable("Clear")) {
+    m_data->Clear();
+  }
+  const auto& buf = m_data->GetBuffer();
+  if (ImGui::Selectable("Copy to Clipboard", false,
+                        buf.empty() ? ImGuiSelectableFlags_Disabled : 0)) {
+    ImGui::SetClipboardText(buf.c_str());
+  }
+}
+
+bool LogView::HasSettings() {
+  return true;
+}
diff --git a/third_party/allwpilib/glass/src/lib/native/cpp/other/Mechanism2D.cpp b/third_party/allwpilib/glass/src/lib/native/cpp/other/Mechanism2D.cpp
index aa801a7..722585b 100644
--- a/third_party/allwpilib/glass/src/lib/native/cpp/other/Mechanism2D.cpp
+++ b/third_party/allwpilib/glass/src/lib/native/cpp/other/Mechanism2D.cpp
@@ -249,10 +249,14 @@
 }
 
 void Mechanism2DView::Display() {
-  if (ImGui::BeginPopupContextItem()) {
-    DisplayMechanism2DSettings(m_model);
-    ImGui::EndPopup();
-  }
   DisplayMechanism2D(m_model, ImGui::GetWindowContentRegionMax() -
                                   ImGui::GetWindowContentRegionMin());
 }
+
+void Mechanism2DView::Settings() {
+  DisplayMechanism2DSettings(m_model);
+}
+
+bool Mechanism2DView::HasSettings() {
+  return true;
+}
diff --git a/third_party/allwpilib/glass/src/lib/native/cpp/other/Plot.cpp b/third_party/allwpilib/glass/src/lib/native/cpp/other/Plot.cpp
index bff55b7..13d7c96 100644
--- a/third_party/allwpilib/glass/src/lib/native/cpp/other/Plot.cpp
+++ b/third_party/allwpilib/glass/src/lib/native/cpp/other/Plot.cpp
@@ -53,11 +53,12 @@
 };
 
 class PlotSeries {
-  explicit PlotSeries(Storage& storage, int yAxis = 0);
+  explicit PlotSeries(Storage& storage);
 
  public:
   PlotSeries(Storage& storage, std::string_view id);
-  PlotSeries(Storage& storage, DataSource* source, int yAxis = 0);
+  PlotSeries(Storage& storage, DataSource* source);
+  PlotSeries(Storage& storage, DataSource* source, int yAxis);
 
   const std::string& GetId() const { return m_id; }
 
@@ -83,7 +84,7 @@
     return m_digital.GetValue() == kDigital ||
            (m_digital.GetValue() == kAuto && m_source && m_source->IsDigital());
   }
-  void AppendValue(double value, uint64_t time);
+  void AppendValue(double value, int64_t time);
 
   // source linkage
   DataSource* m_source = nullptr;
@@ -149,7 +150,6 @@
   bool& m_legendHorizontal;
   int& m_legendLocation;
   bool& m_crosshairs;
-  bool& m_antialiased;
   bool& m_mousePosition;
   bool& m_yAxis2;
   bool& m_yAxis3;
@@ -182,6 +182,8 @@
   PlotView(PlotProvider* provider, Storage& storage);
 
   void Display() override;
+  void Settings() override;
+  bool HasSettings() override;
 
   void MovePlot(PlotView* fromView, size_t fromIndex, size_t toIndex);
 
@@ -196,7 +198,7 @@
 
 }  // namespace
 
-PlotSeries::PlotSeries(Storage& storage, int yAxis)
+PlotSeries::PlotSeries(Storage& storage)
     : m_id{storage.GetString("id")},
       m_name{storage.GetString("name")},
       m_yAxis{storage.GetInt("yAxis", 0)},
@@ -209,12 +211,10 @@
       m_digital{
           storage.GetString("digital"), kAuto, {"Auto", "Digital", "Analog"}},
       m_digitalBitHeight{storage.GetInt("digitalBitHeight", 8)},
-      m_digitalBitGap{storage.GetInt("digitalBitGap", 4)} {
-  m_yAxis = yAxis;
-}
+      m_digitalBitGap{storage.GetInt("digitalBitGap", 4)} {}
 
 PlotSeries::PlotSeries(Storage& storage, std::string_view id)
-    : PlotSeries{storage, 0} {
+    : PlotSeries{storage} {
   m_id = id;
   if (DataSource* source = DataSource::Find(id)) {
     SetSource(source);
@@ -223,12 +223,17 @@
   CheckSource();
 }
 
-PlotSeries::PlotSeries(Storage& storage, DataSource* source, int yAxis)
-    : PlotSeries{storage, yAxis} {
+PlotSeries::PlotSeries(Storage& storage, DataSource* source)
+    : PlotSeries{storage} {
   SetSource(source);
   m_id = source->GetId();
 }
 
+PlotSeries::PlotSeries(Storage& storage, DataSource* source, int yAxis)
+    : PlotSeries{storage, source} {
+  m_yAxis = yAxis;
+}
+
 void PlotSeries::CheckSource() {
   if (!m_newValueConn.connected() && !m_sourceCreatedConn.connected()) {
     m_source = nullptr;
@@ -249,10 +254,10 @@
   AppendValue(source->GetValue(), 0);
 
   m_newValueConn = source->valueChanged.connect_connection(
-      [this](double value, uint64_t time) { AppendValue(value, time); });
+      [this](double value, int64_t time) { AppendValue(value, time); });
 }
 
-void PlotSeries::AppendValue(double value, uint64_t timeUs) {
+void PlotSeries::AppendValue(double value, int64_t timeUs) {
   double time = (timeUs != 0 ? timeUs : wpi::Now()) * 1.0e-6;
   if (IsDigital()) {
     if (m_size < kMaxSize) {
@@ -327,7 +332,7 @@
     int offset;
   };
   GetterData getterData = {now, GetZeroTime() * 1.0e-6, m_data, size, offset};
-  auto getter = [](void* data, int idx) {
+  auto getter = [](int idx, void* data) {
     auto d = static_cast<GetterData*>(data);
     if (idx == d->size) {
       return ImPlotPoint{
@@ -487,7 +492,6 @@
       m_legendLocation{
           storage.GetInt("legendLocation", ImPlotLocation_NorthWest)},
       m_crosshairs{storage.GetBool("crosshairs", false)},
-      m_antialiased{storage.GetBool("antialiased", false)},
       m_mousePosition{storage.GetBool("mousePosition", true)},
       m_yAxis2{storage.GetBool("yaxis2", false)},
       m_yAxis3{storage.GetBool("yaxis3", false)},
@@ -573,7 +577,6 @@
                 static_cast<int>(i));
   ImPlotFlags plotFlags = (m_legend ? 0 : ImPlotFlags_NoLegend) |
                           (m_crosshairs ? ImPlotFlags_Crosshairs : 0) |
-                          (m_antialiased ? ImPlotFlags_AntiAliased : 0) |
                           (m_mousePosition ? 0 : ImPlotFlags_NoMouseText);
 
   if (ImPlot::BeginPlot(label, ImVec2(-1, m_height), plotFlags)) {
@@ -608,7 +611,6 @@
           (m_axis[i].lockMin ? ImPlotAxisFlags_LockMin : 0) |
           (m_axis[i].lockMax ? ImPlotAxisFlags_LockMax : 0) |
           (m_axis[i].autoFit ? ImPlotAxisFlags_AutoFit : 0) |
-          (m_axis[i].logScale ? ImPlotAxisFlags_AutoFit : 0) |
           (m_axis[i].invert ? ImPlotAxisFlags_Invert : 0) |
           (m_axis[i].opposite ? ImPlotAxisFlags_Opposite : 0) |
           (m_axis[i].gridLines ? 0 : ImPlotAxisFlags_NoGridLines) |
@@ -620,6 +622,9 @@
       ImPlot::SetupAxisLimits(
           ImAxis_Y1 + i, m_axis[i].min, m_axis[i].max,
           m_axis[i].apply ? ImGuiCond_Always : ImGuiCond_Once);
+      ImPlot::SetupAxisScale(ImAxis_Y1 + i, m_axis[i].logScale
+                                                ? ImPlotScale_Log10
+                                                : ImPlotScale_Linear);
       m_axis[i].apply = false;
     }
 
@@ -656,7 +661,6 @@
     // copy plot settings back to storage
     m_legend = (plot->Flags & ImPlotFlags_NoLegend) == 0;
     m_crosshairs = (plot->Flags & ImPlotFlags_Crosshairs) != 0;
-    m_antialiased = (plot->Flags & ImPlotFlags_AntiAliased) != 0;
     m_legendOutside =
         (plot->Items.Legend.Flags & ImPlotLegendFlags_Outside) != 0;
     m_legendHorizontal =
@@ -671,12 +675,12 @@
       m_axis[i].lockMin = (flags & ImPlotAxisFlags_LockMin) != 0;
       m_axis[i].lockMax = (flags & ImPlotAxisFlags_LockMax) != 0;
       m_axis[i].autoFit = (flags & ImPlotAxisFlags_AutoFit) != 0;
-      m_axis[i].logScale = (flags & ImPlotAxisFlags_LogScale) != 0;
       m_axis[i].invert = (flags & ImPlotAxisFlags_Invert) != 0;
       m_axis[i].opposite = (flags & ImPlotAxisFlags_Opposite) != 0;
       m_axis[i].gridLines = (flags & ImPlotAxisFlags_NoGridLines) == 0;
       m_axis[i].tickMarks = (flags & ImPlotAxisFlags_NoTickMarks) == 0;
       m_axis[i].tickLabels = (flags & ImPlotAxisFlags_NoTickLabels) == 0;
+      m_axis[i].logScale = plot->Axes[ImAxis_Y1 + i].Scale == ImPlotScale_Log10;
     }
   }
 }
@@ -765,71 +769,6 @@
 }
 
 void PlotView::Display() {
-  if (ImGui::BeginPopupContextItem()) {
-    if (ImGui::Button("Add plot")) {
-      m_plotsStorage.emplace_back(std::make_unique<Storage>());
-      m_plots.emplace_back(std::make_unique<Plot>(*m_plotsStorage.back()));
-    }
-
-    for (size_t i = 0; i < m_plots.size(); ++i) {
-      auto& plot = m_plots[i];
-      ImGui::PushID(i);
-
-      char name[64];
-      if (!plot->GetName().empty()) {
-        std::snprintf(name, sizeof(name), "%s", plot->GetName().c_str());
-      } else {
-        std::snprintf(name, sizeof(name), "Plot %d", static_cast<int>(i));
-      }
-
-      char label[90];
-      std::snprintf(label, sizeof(label), "%s###header%d", name,
-                    static_cast<int>(i));
-
-      bool open = ImGui::CollapsingHeader(label);
-
-      // DND source and target for Plot
-      if (ImGui::BeginDragDropSource()) {
-        PlotSeriesRef ref = {this, i, 0};
-        ImGui::SetDragDropPayload("Plot", &ref, sizeof(ref));
-        ImGui::TextUnformatted(name);
-        ImGui::EndDragDropSource();
-      }
-      plot->DragDropTarget(*this, i, false);
-
-      if (open) {
-        if (ImGui::Button("Move Up")) {
-          if (i > 0) {
-            std::swap(m_plotsStorage[i - 1], m_plotsStorage[i]);
-            std::swap(m_plots[i - 1], plot);
-          }
-        }
-
-        ImGui::SameLine();
-        if (ImGui::Button("Move Down")) {
-          if (i < (m_plots.size() - 1)) {
-            std::swap(m_plotsStorage[i], m_plotsStorage[i + 1]);
-            std::swap(plot, m_plots[i + 1]);
-          }
-        }
-
-        ImGui::SameLine();
-        if (ImGui::Button("Delete")) {
-          m_plotsStorage.erase(m_plotsStorage.begin() + i);
-          m_plots.erase(m_plots.begin() + i);
-          ImGui::PopID();
-          continue;
-        }
-
-        plot->EmitSettings(i);
-      }
-
-      ImGui::PopID();
-    }
-
-    ImGui::EndPopup();
-  }
-
   if (m_plots.empty()) {
     if (ImGui::Button("Add plot")) {
       m_plotsStorage.emplace_back(std::make_unique<Storage>());
@@ -966,6 +905,73 @@
   });
 }
 
+void PlotView::Settings() {
+  if (ImGui::Button("Add plot")) {
+    m_plotsStorage.emplace_back(std::make_unique<Storage>());
+    m_plots.emplace_back(std::make_unique<Plot>(*m_plotsStorage.back()));
+  }
+
+  for (size_t i = 0; i < m_plots.size(); ++i) {
+    auto& plot = m_plots[i];
+    ImGui::PushID(i);
+
+    char name[64];
+    if (!plot->GetName().empty()) {
+      std::snprintf(name, sizeof(name), "%s", plot->GetName().c_str());
+    } else {
+      std::snprintf(name, sizeof(name), "Plot %d", static_cast<int>(i));
+    }
+
+    char label[90];
+    std::snprintf(label, sizeof(label), "%s###header%d", name,
+                  static_cast<int>(i));
+
+    bool open = ImGui::CollapsingHeader(label);
+
+    // DND source and target for Plot
+    if (ImGui::BeginDragDropSource()) {
+      PlotSeriesRef ref = {this, i, 0};
+      ImGui::SetDragDropPayload("Plot", &ref, sizeof(ref));
+      ImGui::TextUnformatted(name);
+      ImGui::EndDragDropSource();
+    }
+    plot->DragDropTarget(*this, i, false);
+
+    if (open) {
+      if (ImGui::Button("Move Up")) {
+        if (i > 0) {
+          std::swap(m_plotsStorage[i - 1], m_plotsStorage[i]);
+          std::swap(m_plots[i - 1], plot);
+        }
+      }
+
+      ImGui::SameLine();
+      if (ImGui::Button("Move Down")) {
+        if (i < (m_plots.size() - 1)) {
+          std::swap(m_plotsStorage[i], m_plotsStorage[i + 1]);
+          std::swap(plot, m_plots[i + 1]);
+        }
+      }
+
+      ImGui::SameLine();
+      if (ImGui::Button("Delete")) {
+        m_plotsStorage.erase(m_plotsStorage.begin() + i);
+        m_plots.erase(m_plots.begin() + i);
+        ImGui::PopID();
+        continue;
+      }
+
+      plot->EmitSettings(i);
+    }
+
+    ImGui::PopID();
+  }
+}
+
+bool PlotView::HasSettings() {
+  return true;
+}
+
 PlotProvider::~PlotProvider() = default;
 
 void PlotProvider::DisplayMenu() {
@@ -989,7 +995,7 @@
     for (size_t i = 0; i <= numWindows; ++i) {
       std::snprintf(id, sizeof(id), "Plot <%d>", static_cast<int>(i));
       bool match = false;
-      for (size_t j = i; j < numWindows; ++j) {
+      for (size_t j = 0; j < numWindows; ++j) {
         if (m_windows[j]->GetId() == id) {
           match = true;
           break;
diff --git a/third_party/allwpilib/glass/src/lib/native/cpp/support/EnumSetting.cpp b/third_party/allwpilib/glass/src/lib/native/cpp/support/EnumSetting.cpp
index 848b588..b863b70 100644
--- a/third_party/allwpilib/glass/src/lib/native/cpp/support/EnumSetting.cpp
+++ b/third_party/allwpilib/glass/src/lib/native/cpp/support/EnumSetting.cpp
@@ -10,16 +10,13 @@
 
 EnumSetting::EnumSetting(std::string& str, int defaultValue,
                          std::initializer_list<const char*> choices)
-    : m_str{str}, m_choices{choices}, m_value{defaultValue} {
-  // override default value if str is one of the choices
-  int i = 0;
-  for (auto choice : choices) {
-    if (str == choice) {
-      m_value = i;
-      break;
-    }
-    ++i;
+    : m_str{str}, m_choices{choices}, m_defaultValue{defaultValue} {}
+
+int EnumSetting::GetValue() const {
+  if (m_value == -1) {
+    UpdateValue();
   }
+  return m_value;
 }
 
 void EnumSetting::SetValue(int value) {
@@ -29,6 +26,9 @@
 
 bool EnumSetting::Combo(const char* label, int numOptions,
                         int popup_max_height_in_items) {
+  if (m_value == -1) {
+    UpdateValue();
+  }
   if (ImGui::Combo(
           label, &m_value, m_choices.data(),
           numOptions < 0 ? m_choices.size() : static_cast<size_t>(numOptions),
@@ -38,3 +38,17 @@
   }
   return false;
 }
+
+void EnumSetting::UpdateValue() const {
+  // override default value if str is one of the choices
+  int i = 0;
+  for (auto choice : m_choices) {
+    if (m_str == choice) {
+      m_value = i;
+      return;
+    }
+    ++i;
+  }
+  // no match, default it
+  m_value = m_defaultValue;
+}
diff --git a/third_party/allwpilib/glass/src/lib/native/cpp/support/ExtraGuiWidgets.cpp b/third_party/allwpilib/glass/src/lib/native/cpp/support/ExtraGuiWidgets.cpp
index 56f4e77..191634e 100644
--- a/third_party/allwpilib/glass/src/lib/native/cpp/support/ExtraGuiWidgets.cpp
+++ b/third_party/allwpilib/glass/src/lib/native/cpp/support/ExtraGuiWidgets.cpp
@@ -4,6 +4,8 @@
 
 #include "glass/support/ExtraGuiWidgets.h"
 
+#include <imgui.h>
+
 #define IMGUI_DEFINE_MATH_OPERATORS
 #include <imgui_internal.h>
 
@@ -174,4 +176,46 @@
   return rv;
 }
 
+bool HamburgerButton(const ImGuiID id, const ImVec2 position) {
+  const ImGuiStyle& style = ImGui::GetStyle();
+
+  ImGuiWindow* window = ImGui::GetCurrentWindow();
+
+  // Frame padding on both sides, then one character in the middle
+  const ImRect bb{
+      position, position + ImVec2(ImGui::GetFontSize(), ImGui::GetFontSize()) +
+                    style.FramePadding * 2.0f};
+
+  ImGui::ItemAdd(bb, id);
+
+  bool hovered, held;
+  bool pressed = ImGui::ButtonBehavior(bb, id, &hovered, &held);
+
+  const ImU32 bgCol =
+      ImGui::GetColorU32(held ? ImGuiCol_ButtonActive : ImGuiCol_ButtonHovered);
+  const ImVec2 center = bb.GetCenter();
+  if (hovered) {
+    window->DrawList->AddCircleFilled(
+        center, ImMax(2.0f, ImGui::GetFontSize() * 0.5f + 1.0f), bgCol, 12);
+  }
+
+  const ImU32 fgCol = ImGui::GetColorU32(ImGuiCol_Text);
+
+  const float halfLineWidth = ImGui::GetFontSize() * 0.5 * 0.7071;
+  const float halfTotalHeight = halfLineWidth * 0.875;
+  ImVec2 lineStart = {center.x - halfLineWidth, center.y - halfTotalHeight};
+  ImVec2 lineEnd = {center.x + halfLineWidth, center.y - halfTotalHeight};
+
+  ImVec2 increment = {0.0, halfTotalHeight};
+
+  for (int i = 0; i < 3; i++) {
+    window->DrawList->AddLine(lineStart, lineEnd, fgCol);
+
+    lineStart += increment;
+    lineEnd += increment;
+  }
+
+  return pressed;
+}
+
 }  // namespace glass
diff --git a/third_party/allwpilib/glass/src/lib/native/include/glass/Context.h b/third_party/allwpilib/glass/src/lib/native/include/glass/Context.h
index 14ade2c..e8dada3 100644
--- a/third_party/allwpilib/glass/src/lib/native/include/glass/Context.h
+++ b/third_party/allwpilib/glass/src/lib/native/include/glass/Context.h
@@ -201,4 +201,6 @@
 
 bool PopupEditName(const char* label, std::string* name);
 
+bool ItemEditName(std::string* name);
+
 }  // namespace glass
diff --git a/third_party/allwpilib/glass/src/lib/native/include/glass/DataSource.h b/third_party/allwpilib/glass/src/lib/native/include/glass/DataSource.h
index 5eebb3c..7e0c673 100644
--- a/third_party/allwpilib/glass/src/lib/native/include/glass/DataSource.h
+++ b/third_party/allwpilib/glass/src/lib/native/include/glass/DataSource.h
@@ -6,7 +6,6 @@
 
 #include <stdint.h>
 
-#include <atomic>
 #include <string>
 #include <string_view>
 
@@ -38,11 +37,22 @@
   void SetDigital(bool digital) { m_digital = digital; }
   bool IsDigital() const { return m_digital; }
 
-  void SetValue(double value, uint64_t time = 0) {
+  void SetValue(double value, int64_t time = 0) {
+    std::scoped_lock lock{m_valueMutex};
     m_value = value;
+    m_valueTime = time;
     valueChanged(value, time);
   }
-  double GetValue() const { return m_value; }
+
+  double GetValue() const {
+    std::scoped_lock lock{m_valueMutex};
+    return m_value;
+  }
+
+  int64_t GetValueTime() const {
+    std::scoped_lock lock{m_valueMutex};
+    return m_valueTime;
+  }
 
   // drag source helpers
   void LabelText(const char* label, const char* fmt, ...) const IM_FMTARGS(3);
@@ -59,7 +69,7 @@
                 ImGuiInputTextFlags flags = 0) const;
   void EmitDrag(ImGuiDragDropFlags flags = 0) const;
 
-  wpi::sig::SignalBase<wpi::spinlock, double, uint64_t> valueChanged;
+  wpi::sig::SignalBase<wpi::spinlock, double, int64_t> valueChanged;
 
   static DataSource* Find(std::string_view id);
 
@@ -69,7 +79,9 @@
   std::string m_id;
   std::string& m_name;
   bool m_digital = false;
-  std::atomic<double> m_value = 0;
+  mutable wpi::spinlock m_valueMutex;
+  double m_value = 0;
+  int64_t m_valueTime = 0;
 };
 
 }  // namespace glass
diff --git a/third_party/allwpilib/glass/src/lib/native/include/glass/Storage.h b/third_party/allwpilib/glass/src/lib/native/include/glass/Storage.h
index 004b8b4..7ebfa6d 100644
--- a/third_party/allwpilib/glass/src/lib/native/include/glass/Storage.h
+++ b/third_party/allwpilib/glass/src/lib/native/include/glass/Storage.h
@@ -8,6 +8,7 @@
 
 #include <functional>
 #include <memory>
+#include <span>
 #include <string>
 #include <string_view>
 #include <utility>
@@ -15,7 +16,6 @@
 
 #include <wpi/StringMap.h>
 #include <wpi/iterator_range.h>
-#include <wpi/span.h>
 
 namespace wpi {
 class json;
@@ -137,17 +137,17 @@
                          std::string_view defaultVal = {});
 
   std::vector<int>& GetIntArray(std::string_view key,
-                                wpi::span<const int> defaultVal = {});
+                                std::span<const int> defaultVal = {});
   std::vector<int64_t>& GetInt64Array(std::string_view key,
-                                      wpi::span<const int64_t> defaultVal = {});
+                                      std::span<const int64_t> defaultVal = {});
   std::vector<int>& GetBoolArray(std::string_view key,
-                                 wpi::span<const int> defaultVal = {});
+                                 std::span<const int> defaultVal = {});
   std::vector<float>& GetFloatArray(std::string_view key,
-                                    wpi::span<const float> defaultVal = {});
+                                    std::span<const float> defaultVal = {});
   std::vector<double>& GetDoubleArray(std::string_view key,
-                                      wpi::span<const double> defaultVal = {});
+                                      std::span<const double> defaultVal = {});
   std::vector<std::string>& GetStringArray(
-      std::string_view key, wpi::span<const std::string> defaultVal = {});
+      std::string_view key, std::span<const std::string> defaultVal = {});
   std::vector<std::unique_ptr<Storage>>& GetChildArray(std::string_view key);
 
   Value* FindValue(std::string_view key);
diff --git a/third_party/allwpilib/glass/src/lib/native/include/glass/View.h b/third_party/allwpilib/glass/src/lib/native/include/glass/View.h
index 886c29e..f52ebc6 100644
--- a/third_party/allwpilib/glass/src/lib/native/include/glass/View.h
+++ b/third_party/allwpilib/glass/src/lib/native/include/glass/View.h
@@ -35,6 +35,17 @@
    * ImGui::Begin() returns false).
    */
   virtual void Hidden();
+
+  /**
+   * Called from within ImGui::BeginContextPopupItem() and ImGui::EndPopup().
+   * Used to display the settings for the view
+   */
+  virtual void Settings();
+
+  /**
+   * If the view has settings and if the result of Settings should be displayed.
+   */
+  virtual bool HasSettings();
 };
 
 /**
diff --git a/third_party/allwpilib/glass/src/lib/native/include/glass/hardware/LEDDisplay.h b/third_party/allwpilib/glass/src/lib/native/include/glass/hardware/LEDDisplay.h
index ddd3c27..3aee6ae 100644
--- a/third_party/allwpilib/glass/src/lib/native/include/glass/hardware/LEDDisplay.h
+++ b/third_party/allwpilib/glass/src/lib/native/include/glass/hardware/LEDDisplay.h
@@ -4,8 +4,9 @@
 
 #pragma once
 
+#include <span>
+
 #include <wpi/function_ref.h>
-#include <wpi/span.h>
 
 #include "glass/Model.h"
 
@@ -27,7 +28,7 @@
 
   virtual bool IsRunning() = 0;
 
-  virtual wpi::span<const Data> GetData(wpi::SmallVectorImpl<Data>& buf) = 0;
+  virtual std::span<const Data> GetData(wpi::SmallVectorImpl<Data>& buf) = 0;
 };
 
 class LEDDisplaysModel : public glass::Model {
diff --git a/third_party/allwpilib/glass/src/lib/native/include/glass/hardware/MotorController.h b/third_party/allwpilib/glass/src/lib/native/include/glass/hardware/MotorController.h
new file mode 100644
index 0000000..5fc831f
--- /dev/null
+++ b/third_party/allwpilib/glass/src/lib/native/include/glass/hardware/MotorController.h
@@ -0,0 +1,19 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include "glass/Model.h"
+
+namespace glass {
+class DataSource;
+class MotorControllerModel : public Model {
+ public:
+  virtual const char* GetName() const = 0;
+  virtual const char* GetSimDevice() const = 0;
+  virtual DataSource* GetPercentData() = 0;
+  virtual void SetPercent(double value) = 0;
+};
+void DisplayMotorController(MotorControllerModel* m);
+}  // namespace glass
diff --git a/third_party/allwpilib/glass/src/lib/native/include/glass/hardware/SpeedController.h b/third_party/allwpilib/glass/src/lib/native/include/glass/hardware/SpeedController.h
deleted file mode 100644
index 033f27d..0000000
--- a/third_party/allwpilib/glass/src/lib/native/include/glass/hardware/SpeedController.h
+++ /dev/null
@@ -1,19 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include "glass/Model.h"
-
-namespace glass {
-class DataSource;
-class SpeedControllerModel : public Model {
- public:
-  virtual const char* GetName() const = 0;
-  virtual const char* GetSimDevice() const = 0;
-  virtual DataSource* GetPercentData() = 0;
-  virtual void SetPercent(double value) = 0;
-};
-void DisplaySpeedController(SpeedControllerModel* m);
-}  // namespace glass
diff --git a/third_party/allwpilib/glass/src/lib/native/include/glass/other/FMS.h b/third_party/allwpilib/glass/src/lib/native/include/glass/other/FMS.h
index a920f96..5970e93 100644
--- a/third_party/allwpilib/glass/src/lib/native/include/glass/other/FMS.h
+++ b/third_party/allwpilib/glass/src/lib/native/include/glass/other/FMS.h
@@ -38,7 +38,7 @@
   virtual void SetEnabled(bool val) = 0;
   virtual void SetTest(bool val) = 0;
   virtual void SetAutonomous(bool val) = 0;
-  virtual void SetGameSpecificMessage(const char* val) = 0;
+  virtual void SetGameSpecificMessage(std::string_view val) = 0;
 };
 
 /**
diff --git a/third_party/allwpilib/glass/src/lib/native/include/glass/other/Field2D.h b/third_party/allwpilib/glass/src/lib/native/include/glass/other/Field2D.h
index 9399876..9c9f72a 100644
--- a/third_party/allwpilib/glass/src/lib/native/include/glass/other/Field2D.h
+++ b/third_party/allwpilib/glass/src/lib/native/include/glass/other/Field2D.h
@@ -4,6 +4,7 @@
 
 #pragma once
 
+#include <span>
 #include <string_view>
 
 #include <frc/geometry/Pose2d.h>
@@ -11,7 +12,6 @@
 #include <frc/geometry/Translation2d.h>
 #include <imgui.h>
 #include <wpi/function_ref.h>
-#include <wpi/span.h>
 
 #include "glass/Model.h"
 #include "glass/View.h"
@@ -22,8 +22,8 @@
  public:
   virtual const char* GetName() const = 0;
 
-  virtual wpi::span<const frc::Pose2d> GetPoses() = 0;
-  virtual void SetPoses(wpi::span<const frc::Pose2d> poses) = 0;
+  virtual std::span<const frc::Pose2d> GetPoses() = 0;
+  virtual void SetPoses(std::span<const frc::Pose2d> poses) = 0;
   virtual void SetPose(size_t i, frc::Pose2d pose) = 0;
   virtual void SetPosition(size_t i, frc::Translation2d pos) = 0;
   virtual void SetRotation(size_t i, frc::Rotation2d rot) = 0;
@@ -46,6 +46,8 @@
   explicit Field2DView(Field2DModel* model) : m_model{model} {}
 
   void Display() override;
+  void Settings() override;
+  bool HasSettings() override;
 
  private:
   Field2DModel* m_model;
diff --git a/third_party/allwpilib/glass/src/lib/native/include/glass/other/Log.h b/third_party/allwpilib/glass/src/lib/native/include/glass/other/Log.h
index 3d9c59b..f054e66 100644
--- a/third_party/allwpilib/glass/src/lib/native/include/glass/other/Log.h
+++ b/third_party/allwpilib/glass/src/lib/native/include/glass/other/Log.h
@@ -35,6 +35,8 @@
   explicit LogView(LogData* data) : m_data{data} {}
 
   void Display() override;
+  void Settings() override;
+  bool HasSettings() override;
 
  private:
   LogData* m_data;
diff --git a/third_party/allwpilib/glass/src/lib/native/include/glass/other/Mechanism2D.h b/third_party/allwpilib/glass/src/lib/native/include/glass/other/Mechanism2D.h
index 7617e6f..ab5ccdc 100644
--- a/third_party/allwpilib/glass/src/lib/native/include/glass/other/Mechanism2D.h
+++ b/third_party/allwpilib/glass/src/lib/native/include/glass/other/Mechanism2D.h
@@ -55,6 +55,8 @@
   explicit Mechanism2DView(Mechanism2DModel* model) : m_model{model} {}
 
   void Display() override;
+  void Settings() override;
+  bool HasSettings() override;
 
  private:
   Mechanism2DModel* m_model;
diff --git a/third_party/allwpilib/glass/src/lib/native/include/glass/other/StringChooser.h b/third_party/allwpilib/glass/src/lib/native/include/glass/other/StringChooser.h
index 77f9ac2..066c444 100644
--- a/third_party/allwpilib/glass/src/lib/native/include/glass/other/StringChooser.h
+++ b/third_party/allwpilib/glass/src/lib/native/include/glass/other/StringChooser.h
@@ -8,8 +8,6 @@
 #include <string_view>
 #include <vector>
 
-#include <wpi/span.h>
-
 #include "glass/Model.h"
 
 namespace glass {
@@ -21,10 +19,7 @@
   virtual const std::string& GetActive() = 0;
   virtual const std::vector<std::string>& GetOptions() = 0;
 
-  virtual void SetDefault(std::string_view val) = 0;
   virtual void SetSelected(std::string_view val) = 0;
-  virtual void SetActive(std::string_view val) = 0;
-  virtual void SetOptions(wpi::span<const std::string> val) = 0;
 };
 
 void DisplayStringChooser(StringChooserModel* model);
diff --git a/third_party/allwpilib/glass/src/lib/native/include/glass/support/EnumSetting.h b/third_party/allwpilib/glass/src/lib/native/include/glass/support/EnumSetting.h
index c4f0c26..eaf308f 100644
--- a/third_party/allwpilib/glass/src/lib/native/include/glass/support/EnumSetting.h
+++ b/third_party/allwpilib/glass/src/lib/native/include/glass/support/EnumSetting.h
@@ -15,7 +15,7 @@
   EnumSetting(std::string& str, int defaultValue,
               std::initializer_list<const char*> choices);
 
-  int GetValue() const { return m_value; }
+  int GetValue() const;
   void SetValue(int value);
 
   // updates internal value, returns true on change
@@ -23,9 +23,12 @@
              int popup_max_height_in_items = -1);
 
  private:
+  void UpdateValue() const;
+
   std::string& m_str;
   wpi::SmallVector<const char*, 8> m_choices;
-  int m_value;
+  int m_defaultValue;
+  mutable int m_value = -1;
 };
 
 }  // namespace glass
diff --git a/third_party/allwpilib/glass/src/lib/native/include/glass/support/ExtraGuiWidgets.h b/third_party/allwpilib/glass/src/lib/native/include/glass/support/ExtraGuiWidgets.h
index 3a35335..6788434 100644
--- a/third_party/allwpilib/glass/src/lib/native/include/glass/support/ExtraGuiWidgets.h
+++ b/third_party/allwpilib/glass/src/lib/native/include/glass/support/ExtraGuiWidgets.h
@@ -93,4 +93,9 @@
  */
 bool HeaderDeleteButton(const char* label);
 
+/**
+ * Settings button similar to ImGui::CloseButton.
+ */
+bool HamburgerButton(const ImGuiID id, const ImVec2 position);
+
 }  // namespace glass
diff --git a/third_party/allwpilib/glass/src/libnt/native/cpp/NTCommandScheduler.cpp b/third_party/allwpilib/glass/src/libnt/native/cpp/NTCommandScheduler.cpp
index ccc6412..26a5740 100644
--- a/third_party/allwpilib/glass/src/libnt/native/cpp/NTCommandScheduler.cpp
+++ b/third_party/allwpilib/glass/src/libnt/native/cpp/NTCommandScheduler.cpp
@@ -10,49 +10,38 @@
 using namespace glass;
 
 NTCommandSchedulerModel::NTCommandSchedulerModel(std::string_view path)
-    : NTCommandSchedulerModel(nt::GetDefaultInstance(), path) {}
+    : NTCommandSchedulerModel(nt::NetworkTableInstance::GetDefault(), path) {}
 
-NTCommandSchedulerModel::NTCommandSchedulerModel(NT_Inst instance,
+NTCommandSchedulerModel::NTCommandSchedulerModel(nt::NetworkTableInstance inst,
                                                  std::string_view path)
-    : m_nt(instance),
-      m_name(m_nt.GetEntry(fmt::format("{}/.name", path))),
-      m_commands(m_nt.GetEntry(fmt::format("{}/Names", path))),
-      m_ids(m_nt.GetEntry(fmt::format("{}/Ids", path))),
-      m_cancel(m_nt.GetEntry(fmt::format("{}/Cancel", path))),
-      m_nameValue(wpi::rsplit(path, '/').second) {
-  m_nt.AddListener(m_name);
-  m_nt.AddListener(m_commands);
-  m_nt.AddListener(m_ids);
-  m_nt.AddListener(m_cancel);
-}
+    : m_inst{inst},
+      m_name{inst.GetStringTopic(fmt::format("{}/.name", path)).Subscribe("")},
+      m_commands{inst.GetStringArrayTopic(fmt::format("{}/Names", path))
+                     .Subscribe({})},
+      m_ids{
+          inst.GetIntegerArrayTopic(fmt::format("{}/Ids", path)).Subscribe({})},
+      m_cancel{
+          inst.GetIntegerArrayTopic(fmt::format("{}/Cancel", path)).Publish()},
+      m_nameValue{wpi::rsplit(path, '/').second} {}
 
 void NTCommandSchedulerModel::CancelCommand(size_t index) {
   if (index < m_idsValue.size()) {
-    nt::SetEntryValue(
-        m_cancel, nt::NetworkTableValue::MakeDoubleArray({m_idsValue[index]}));
+    m_cancel.Set({{m_idsValue[index]}});
   }
 }
 
 void NTCommandSchedulerModel::Update() {
-  for (auto&& event : m_nt.PollListener()) {
-    if (event.entry == m_name) {
-      if (event.value && event.value->IsString()) {
-        m_nameValue = event.value->GetString();
-      }
-    } else if (event.entry == m_commands) {
-      if (event.value && event.value->IsStringArray()) {
-        auto arr = event.value->GetStringArray();
-        m_commandsValue.assign(arr.begin(), arr.end());
-      }
-    } else if (event.entry == m_ids) {
-      if (event.value && event.value->IsDoubleArray()) {
-        auto arr = event.value->GetDoubleArray();
-        m_idsValue.assign(arr.begin(), arr.end());
-      }
-    }
+  for (auto&& v : m_name.ReadQueue()) {
+    m_nameValue = std::move(v.value);
+  }
+  for (auto&& v : m_commands.ReadQueue()) {
+    m_commandsValue = std::move(v.value);
+  }
+  for (auto&& v : m_ids.ReadQueue()) {
+    m_idsValue = std::move(v.value);
   }
 }
 
 bool NTCommandSchedulerModel::Exists() {
-  return m_nt.IsConnected() && nt::GetEntryType(m_commands) != NT_UNASSIGNED;
+  return m_commands.Exists();
 }
diff --git a/third_party/allwpilib/glass/src/libnt/native/cpp/NTCommandSelector.cpp b/third_party/allwpilib/glass/src/libnt/native/cpp/NTCommandSelector.cpp
index efcbac2..64c616e 100644
--- a/third_party/allwpilib/glass/src/libnt/native/cpp/NTCommandSelector.cpp
+++ b/third_party/allwpilib/glass/src/libnt/native/cpp/NTCommandSelector.cpp
@@ -10,38 +10,32 @@
 using namespace glass;
 
 NTCommandSelectorModel::NTCommandSelectorModel(std::string_view path)
-    : NTCommandSelectorModel(nt::GetDefaultInstance(), path) {}
+    : NTCommandSelectorModel(nt::NetworkTableInstance::GetDefault(), path) {}
 
-NTCommandSelectorModel::NTCommandSelectorModel(NT_Inst instance,
+NTCommandSelectorModel::NTCommandSelectorModel(nt::NetworkTableInstance inst,
                                                std::string_view path)
-    : m_nt(instance),
-      m_running(m_nt.GetEntry(fmt::format("{}/running", path))),
-      m_name(m_nt.GetEntry(fmt::format("{}/.name", path))),
-      m_runningData(fmt::format("NTCmd:{}", path)),
-      m_nameValue(wpi::rsplit(path, '/').second) {
+    : m_inst{inst},
+      m_running{inst.GetBooleanTopic(fmt::format("{}/running", path))
+                    .GetEntry(false)},
+      m_name{inst.GetStringTopic(fmt::format("{}/.name", path)).Subscribe("")},
+      m_runningData{fmt::format("NTCmd:{}", path)},
+      m_nameValue{wpi::rsplit(path, '/').second} {
   m_runningData.SetDigital(true);
-  m_nt.AddListener(m_running);
-  m_nt.AddListener(m_name);
 }
 
 void NTCommandSelectorModel::SetRunning(bool run) {
-  nt::SetEntryValue(m_running, nt::NetworkTableValue::MakeBoolean(run));
+  m_running.Set(run);
 }
 
 void NTCommandSelectorModel::Update() {
-  for (auto&& event : m_nt.PollListener()) {
-    if (event.entry == m_running) {
-      if (event.value && event.value->IsBoolean()) {
-        m_runningData.SetValue(event.value->GetBoolean());
-      }
-    } else if (event.entry == m_name) {
-      if (event.value && event.value->IsString()) {
-        m_nameValue = event.value->GetString();
-      }
-    }
+  for (auto&& v : m_running.ReadQueue()) {
+    m_runningData.SetValue(v.value, v.time);
+  }
+  for (auto&& v : m_name.ReadQueue()) {
+    m_nameValue = std::move(v.value);
   }
 }
 
 bool NTCommandSelectorModel::Exists() {
-  return m_nt.IsConnected() && nt::GetEntryType(m_running) != NT_UNASSIGNED;
+  return m_running.Exists();
 }
diff --git a/third_party/allwpilib/glass/src/libnt/native/cpp/NTDifferentialDrive.cpp b/third_party/allwpilib/glass/src/libnt/native/cpp/NTDifferentialDrive.cpp
index b44ea07..57d1fa8 100644
--- a/third_party/allwpilib/glass/src/libnt/native/cpp/NTDifferentialDrive.cpp
+++ b/third_party/allwpilib/glass/src/libnt/native/cpp/NTDifferentialDrive.cpp
@@ -12,46 +12,40 @@
 using namespace glass;
 
 NTDifferentialDriveModel::NTDifferentialDriveModel(std::string_view path)
-    : NTDifferentialDriveModel(nt::GetDefaultInstance(), path) {}
+    : NTDifferentialDriveModel(nt::NetworkTableInstance::GetDefault(), path) {}
 
-NTDifferentialDriveModel::NTDifferentialDriveModel(NT_Inst instance,
-                                                   std::string_view path)
-    : m_nt(instance),
-      m_name(m_nt.GetEntry(fmt::format("{}/.name", path))),
-      m_controllable(m_nt.GetEntry(fmt::format("{}/.controllable", path))),
-      m_lPercent(m_nt.GetEntry(fmt::format("{}/Left Motor Speed", path))),
-      m_rPercent(m_nt.GetEntry(fmt::format("{}/Right Motor Speed", path))),
-      m_nameValue(wpi::rsplit(path, '/').second),
-      m_lPercentData(fmt::format("NTDiffDriveL:{}", path)),
-      m_rPercentData(fmt::format("NTDiffDriveR:{}", path)) {
-  m_nt.AddListener(m_name);
-  m_nt.AddListener(m_controllable);
-  m_nt.AddListener(m_lPercent);
-  m_nt.AddListener(m_rPercent);
+NTDifferentialDriveModel::NTDifferentialDriveModel(
+    nt::NetworkTableInstance inst, std::string_view path)
+    : m_inst{inst},
+      m_name{inst.GetStringTopic(fmt::format("{}/.name", path)).Subscribe("")},
+      m_controllable{inst.GetBooleanTopic(fmt::format("{}/.controllable", path))
+                         .Subscribe(false)},
+      m_lPercent{inst.GetDoubleTopic(fmt::format("{}/Left Motor Speed", path))
+                     .GetEntry(0)},
+      m_rPercent{inst.GetDoubleTopic(fmt::format("{}/Right Motor Speed", path))
+                     .GetEntry(0)},
+      m_nameValue{wpi::rsplit(path, '/').second},
+      m_lPercentData{fmt::format("NTDiffDriveL:{}", path)},
+      m_rPercentData{fmt::format("NTDiffDriveR:{}", path)} {
+  m_wheels.emplace_back("L % Output", &m_lPercentData,
+                        [this](auto value) { m_lPercent.Set(value); });
 
-  m_wheels.emplace_back("L % Output", &m_lPercentData, [this](auto value) {
-    nt::SetEntryValue(m_lPercent, nt::NetworkTableValue::MakeDouble(value));
-  });
-
-  m_wheels.emplace_back("R % Output", &m_rPercentData, [this](auto value) {
-    nt::SetEntryValue(m_rPercent, nt::NetworkTableValue::MakeDouble(value));
-  });
+  m_wheels.emplace_back("R % Output", &m_rPercentData,
+                        [this](auto value) { m_rPercent.Set(value); });
 }
 
 void NTDifferentialDriveModel::Update() {
-  for (auto&& event : m_nt.PollListener()) {
-    if (event.entry == m_name && event.value && event.value->IsString()) {
-      m_nameValue = event.value->GetString();
-    } else if (event.entry == m_lPercent && event.value &&
-               event.value->IsDouble()) {
-      m_lPercentData.SetValue(event.value->GetDouble());
-    } else if (event.entry == m_rPercent && event.value &&
-               event.value->IsDouble()) {
-      m_rPercentData.SetValue(event.value->GetDouble());
-    } else if (event.entry == m_controllable && event.value &&
-               event.value->IsBoolean()) {
-      m_controllableValue = event.value->GetBoolean();
-    }
+  for (auto&& v : m_name.ReadQueue()) {
+    m_nameValue = std::move(v.value);
+  }
+  for (auto&& v : m_lPercent.ReadQueue()) {
+    m_lPercentData.SetValue(v.value, v.time);
+  }
+  for (auto&& v : m_rPercent.ReadQueue()) {
+    m_rPercentData.SetValue(v.value, v.time);
+  }
+  for (auto&& v : m_controllable.ReadQueue()) {
+    m_controllableValue = v.value;
   }
 
   double l = m_lPercentData.GetValue();
@@ -62,5 +56,5 @@
 }
 
 bool NTDifferentialDriveModel::Exists() {
-  return m_nt.IsConnected() && nt::GetEntryType(m_lPercent) != NT_UNASSIGNED;
+  return m_lPercent.Exists();
 }
diff --git a/third_party/allwpilib/glass/src/libnt/native/cpp/NTDigitalInput.cpp b/third_party/allwpilib/glass/src/libnt/native/cpp/NTDigitalInput.cpp
index 5de6c29..28b916c 100644
--- a/third_party/allwpilib/glass/src/libnt/native/cpp/NTDigitalInput.cpp
+++ b/third_party/allwpilib/glass/src/libnt/native/cpp/NTDigitalInput.cpp
@@ -10,34 +10,28 @@
 using namespace glass;
 
 NTDigitalInputModel::NTDigitalInputModel(std::string_view path)
-    : NTDigitalInputModel{nt::GetDefaultInstance(), path} {}
+    : NTDigitalInputModel{nt::NetworkTableInstance::GetDefault(), path} {}
 
-NTDigitalInputModel::NTDigitalInputModel(NT_Inst inst, std::string_view path)
-    : m_nt{inst},
-      m_value{m_nt.GetEntry(fmt::format("{}/Value", path))},
-      m_name{m_nt.GetEntry(fmt::format("{}/.name", path))},
+NTDigitalInputModel::NTDigitalInputModel(nt::NetworkTableInstance inst,
+                                         std::string_view path)
+    : m_inst{inst},
+      m_value{
+          inst.GetBooleanTopic(fmt::format("{}/Value", path)).Subscribe(false)},
+      m_name{inst.GetStringTopic(fmt::format("{}/.name", path)).Subscribe("")},
       m_valueData{fmt::format("NT_DIn:{}", path)},
       m_nameValue{wpi::rsplit(path, '/').second} {
-  m_nt.AddListener(m_value);
-  m_nt.AddListener(m_name);
-
   m_valueData.SetDigital(true);
 }
 
 void NTDigitalInputModel::Update() {
-  for (auto&& event : m_nt.PollListener()) {
-    if (event.entry == m_value) {
-      if (event.value && event.value->IsBoolean()) {
-        m_valueData.SetValue(event.value->GetBoolean());
-      }
-    } else if (event.entry == m_name) {
-      if (event.value && event.value->IsString()) {
-        m_nameValue = event.value->GetString();
-      }
-    }
+  for (auto&& v : m_value.ReadQueue()) {
+    m_valueData.SetValue(v.value, v.time);
+  }
+  for (auto&& v : m_name.ReadQueue()) {
+    m_nameValue = std::move(v.value);
   }
 }
 
 bool NTDigitalInputModel::Exists() {
-  return m_nt.IsConnected() && nt::GetEntryType(m_value) != NT_UNASSIGNED;
+  return m_value.Exists();
 }
diff --git a/third_party/allwpilib/glass/src/libnt/native/cpp/NTDigitalOutput.cpp b/third_party/allwpilib/glass/src/libnt/native/cpp/NTDigitalOutput.cpp
index a09d424..aa9200d 100644
--- a/third_party/allwpilib/glass/src/libnt/native/cpp/NTDigitalOutput.cpp
+++ b/third_party/allwpilib/glass/src/libnt/native/cpp/NTDigitalOutput.cpp
@@ -9,43 +9,36 @@
 using namespace glass;
 
 NTDigitalOutputModel::NTDigitalOutputModel(std::string_view path)
-    : NTDigitalOutputModel{nt::GetDefaultInstance(), path} {}
+    : NTDigitalOutputModel{nt::NetworkTableInstance::GetDefault(), path} {}
 
-NTDigitalOutputModel::NTDigitalOutputModel(NT_Inst inst, std::string_view path)
-    : m_nt{inst},
-      m_value{m_nt.GetEntry(fmt::format("{}/Value", path))},
-      m_name{m_nt.GetEntry(fmt::format("{}/.name", path))},
-      m_controllable{m_nt.GetEntry(fmt::format("{}/.controllable", path))},
+NTDigitalOutputModel::NTDigitalOutputModel(nt::NetworkTableInstance inst,
+                                           std::string_view path)
+    : m_inst{inst},
+      m_value{
+          inst.GetBooleanTopic(fmt::format("{}/Value", path)).GetEntry(false)},
+      m_name{inst.GetStringTopic(fmt::format("{}/.name", path)).Subscribe("")},
+      m_controllable{inst.GetBooleanTopic(fmt::format("{}/.controllable", path))
+                         .Subscribe(false)},
       m_valueData{fmt::format("NT_DOut:{}", path)} {
-  m_nt.AddListener(m_value);
-  m_nt.AddListener(m_name);
-  m_nt.AddListener(m_controllable);
-
   m_valueData.SetDigital(true);
 }
 
 void NTDigitalOutputModel::SetValue(bool val) {
-  nt::SetEntryValue(m_value, nt::Value::MakeBoolean(val));
+  m_value.Set(val);
 }
 
 void NTDigitalOutputModel::Update() {
-  for (auto&& event : m_nt.PollListener()) {
-    if (event.entry == m_value) {
-      if (event.value && event.value->IsBoolean()) {
-        m_valueData.SetValue(event.value->GetBoolean());
-      }
-    } else if (event.entry == m_name) {
-      if (event.value && event.value->IsString()) {
-        m_nameValue = event.value->GetString();
-      }
-    } else if (event.entry == m_controllable) {
-      if (event.value && event.value->IsBoolean()) {
-        m_controllableValue = event.value->GetBoolean();
-      }
-    }
+  for (auto&& v : m_value.ReadQueue()) {
+    m_valueData.SetValue(v.value, v.time);
+  }
+  for (auto&& v : m_name.ReadQueue()) {
+    m_nameValue = std::move(v.value);
+  }
+  for (auto&& v : m_controllable.ReadQueue()) {
+    m_controllableValue = v.value;
   }
 }
 
 bool NTDigitalOutputModel::Exists() {
-  return m_nt.IsConnected() && nt::GetEntryType(m_value) != NT_UNASSIGNED;
+  return m_value.Exists();
 }
diff --git a/third_party/allwpilib/glass/src/libnt/native/cpp/NTFMS.cpp b/third_party/allwpilib/glass/src/libnt/native/cpp/NTFMS.cpp
index 84c1ce7..65ffa6a 100644
--- a/third_party/allwpilib/glass/src/libnt/native/cpp/NTFMS.cpp
+++ b/third_party/allwpilib/glass/src/libnt/native/cpp/NTFMS.cpp
@@ -13,15 +13,19 @@
 using namespace glass;
 
 NTFMSModel::NTFMSModel(std::string_view path)
-    : NTFMSModel{nt::GetDefaultInstance(), path} {}
+    : NTFMSModel{nt::NetworkTableInstance::GetDefault(), path} {}
 
-NTFMSModel::NTFMSModel(NT_Inst inst, std::string_view path)
-    : m_nt{inst},
+NTFMSModel::NTFMSModel(nt::NetworkTableInstance inst, std::string_view path)
+    : m_inst{inst},
       m_gameSpecificMessage{
-          m_nt.GetEntry(fmt::format("{}/GameSpecificMessage", path))},
-      m_alliance{m_nt.GetEntry(fmt::format("{}/IsRedAlliance", path))},
-      m_station{m_nt.GetEntry(fmt::format("{}/StationNumber", path))},
-      m_controlWord{m_nt.GetEntry(fmt::format("{}/FMSControlData", path))},
+          inst.GetStringTopic(fmt::format("{}/GameSpecificMessage", path))
+              .Subscribe("")},
+      m_alliance{inst.GetBooleanTopic(fmt::format("{}/IsRedAlliance", path))
+                     .Subscribe(false)},
+      m_station{inst.GetIntegerTopic(fmt::format("{}/StationNumber", path))
+                    .Subscribe(0)},
+      m_controlWord{inst.GetIntegerTopic(fmt::format("{}/FMSControlData", path))
+                        .Subscribe(0)},
       m_fmsAttached{fmt::format("NT_FMS:FMSAttached:{}", path)},
       m_dsAttached{fmt::format("NT_FMS:DSAttached:{}", path)},
       m_allianceStationId{fmt::format("NT_FMS:AllianceStationID:{}", path)},
@@ -29,10 +33,6 @@
       m_enabled{fmt::format("NT_FMS:RobotEnabled:{}", path)},
       m_test{fmt::format("NT_FMS:TestMode:{}", path)},
       m_autonomous{fmt::format("NT_FMS:AutonomousMode:{}", path)} {
-  m_nt.AddListener(m_alliance);
-  m_nt.AddListener(m_station);
-  m_nt.AddListener(m_controlWord);
-
   m_fmsAttached.SetDigital(true);
   m_dsAttached.SetDigital(true);
   m_estop.SetDigital(true);
@@ -43,49 +43,35 @@
 
 std::string_view NTFMSModel::GetGameSpecificMessage(
     wpi::SmallVectorImpl<char>& buf) {
-  buf.clear();
-  auto value = nt::GetEntryValue(m_gameSpecificMessage);
-  if (value && value->IsString()) {
-    auto str = value->GetString();
-    buf.append(str.begin(), str.end());
-  }
-  return std::string_view{buf.data(), buf.size()};
+  return m_gameSpecificMessage.Get(buf, "");
 }
 
 void NTFMSModel::Update() {
-  for (auto&& event : m_nt.PollListener()) {
-    if (event.entry == m_alliance) {
-      if (event.value && event.value->IsBoolean()) {
-        int allianceStationId = m_allianceStationId.GetValue();
-        allianceStationId %= 3;
-        // true if red
-        allianceStationId += 3 * (event.value->GetBoolean() ? 0 : 1);
-        m_allianceStationId.SetValue(allianceStationId);
-      }
-    } else if (event.entry == m_station) {
-      if (event.value && event.value->IsDouble()) {
-        int allianceStationId = m_allianceStationId.GetValue();
-        bool isRed = (allianceStationId < 3);
-        // the NT value is 1-indexed
-        m_allianceStationId.SetValue(event.value->GetDouble() - 1 +
-                                     3 * (isRed ? 0 : 1));
-      }
-    } else if (event.entry == m_controlWord) {
-      if (event.value && event.value->IsDouble()) {
-        uint32_t controlWord = event.value->GetDouble();
-        // See HAL_ControlWord definition
-        auto time = wpi::Now();
-        m_enabled.SetValue(((controlWord & 0x01) != 0) ? 1 : 0, time);
-        m_autonomous.SetValue(((controlWord & 0x02) != 0) ? 1 : 0, time);
-        m_test.SetValue(((controlWord & 0x04) != 0) ? 1 : 0, time);
-        m_estop.SetValue(((controlWord & 0x08) != 0) ? 1 : 0, time);
-        m_fmsAttached.SetValue(((controlWord & 0x10) != 0) ? 1 : 0, time);
-        m_dsAttached.SetValue(((controlWord & 0x20) != 0) ? 1 : 0, time);
-      }
-    }
+  for (auto&& v : m_alliance.ReadQueue()) {
+    int allianceStationId = m_allianceStationId.GetValue();
+    allianceStationId %= 3;
+    // true if red
+    allianceStationId += 3 * (v.value ? 0 : 1);
+    m_allianceStationId.SetValue(allianceStationId, v.time);
+  }
+  for (auto&& v : m_station.ReadQueue()) {
+    int allianceStationId = m_allianceStationId.GetValue();
+    bool isRed = (allianceStationId < 3);
+    // the NT value is 1-indexed
+    m_allianceStationId.SetValue(v.value - 1 + 3 * (isRed ? 0 : 1), v.time);
+  }
+  for (auto&& v : m_controlWord.ReadQueue()) {
+    uint32_t controlWord = v.value;
+    // See HAL_ControlWord definition
+    m_enabled.SetValue(((controlWord & 0x01) != 0) ? 1 : 0, v.time);
+    m_autonomous.SetValue(((controlWord & 0x02) != 0) ? 1 : 0, v.time);
+    m_test.SetValue(((controlWord & 0x04) != 0) ? 1 : 0, v.time);
+    m_estop.SetValue(((controlWord & 0x08) != 0) ? 1 : 0, v.time);
+    m_fmsAttached.SetValue(((controlWord & 0x10) != 0) ? 1 : 0, v.time);
+    m_dsAttached.SetValue(((controlWord & 0x20) != 0) ? 1 : 0, v.time);
   }
 }
 
 bool NTFMSModel::Exists() {
-  return m_nt.IsConnected() && nt::GetEntryType(m_controlWord) != NT_UNASSIGNED;
+  return m_controlWord.Exists();
 }
diff --git a/third_party/allwpilib/glass/src/libnt/native/cpp/NTField2D.cpp b/third_party/allwpilib/glass/src/libnt/native/cpp/NTField2D.cpp
index 47fa9a7..745e9e2 100644
--- a/third_party/allwpilib/glass/src/libnt/native/cpp/NTField2D.cpp
+++ b/third_party/allwpilib/glass/src/libnt/native/cpp/NTField2D.cpp
@@ -8,6 +8,8 @@
 #include <vector>
 
 #include <fmt/format.h>
+#include <networktables/DoubleArrayTopic.h>
+#include <networktables/MultiSubscriber.h>
 #include <ntcore_cpp.h>
 #include <wpi/Endian.h>
 #include <wpi/MathExtras.h>
@@ -18,24 +20,20 @@
 
 class NTField2DModel::ObjectModel : public FieldObjectModel {
  public:
-  ObjectModel(std::string_view name, NT_Entry entry)
-      : m_name{name}, m_entry{entry} {}
+  ObjectModel(std::string_view name, nt::DoubleArrayTopic topic)
+      : m_name{name}, m_topic{topic} {}
 
   const char* GetName() const override { return m_name.c_str(); }
-  NT_Entry GetEntry() const { return m_entry; }
+  nt::DoubleArrayTopic GetTopic() const { return m_topic; }
 
   void NTUpdate(const nt::Value& value);
 
-  void Update() override {
-    if (auto value = nt::GetEntryValue(m_entry)) {
-      NTUpdate(*value);
-    }
-  }
-  bool Exists() override { return nt::GetEntryType(m_entry) != NT_UNASSIGNED; }
+  void Update() override {}
+  bool Exists() override { return m_topic.Exists(); }
   bool IsReadOnly() override { return false; }
 
-  wpi::span<const frc::Pose2d> GetPoses() override { return m_poses; }
-  void SetPoses(wpi::span<const frc::Pose2d> poses) override;
+  std::span<const frc::Pose2d> GetPoses() override { return m_poses; }
+  void SetPoses(std::span<const frc::Pose2d> poses) override;
   void SetPose(size_t i, frc::Pose2d pose) override;
   void SetPosition(size_t i, frc::Translation2d pos) override;
   void SetRotation(size_t i, frc::Rotation2d rot) override;
@@ -44,7 +42,8 @@
   void UpdateNT();
 
   std::string m_name;
-  NT_Entry m_entry;
+  nt::DoubleArrayTopic m_topic;
+  nt::DoubleArrayPublisher m_pub;
 
   std::vector<frc::Pose2d> m_poses;
 };
@@ -62,66 +61,24 @@
           units::meter_t{arr[i * 3 + 0]}, units::meter_t{arr[i * 3 + 1]},
           frc::Rotation2d{units::degree_t{arr[i * 3 + 2]}}};
     }
-  } else if (value.IsRaw()) {
-    // treat it simply as an array of doubles
-    std::string_view data = value.GetRaw();
-
-    // must be triples of doubles
-    auto size = data.size();
-    if ((size % (3 * 8)) != 0) {
-      return;
-    }
-    m_poses.resize(size / (3 * 8));
-    const char* p = data.data();
-    for (size_t i = 0; i < size / (3 * 8); ++i) {
-      double x = wpi::BitsToDouble(
-          wpi::support::endian::readNext<uint64_t, wpi::support::big,
-                                         wpi::support::unaligned>(p));
-      double y = wpi::BitsToDouble(
-          wpi::support::endian::readNext<uint64_t, wpi::support::big,
-                                         wpi::support::unaligned>(p));
-      double rot = wpi::BitsToDouble(
-          wpi::support::endian::readNext<uint64_t, wpi::support::big,
-                                         wpi::support::unaligned>(p));
-      m_poses[i] = frc::Pose2d{units::meter_t{x}, units::meter_t{y},
-                               frc::Rotation2d{units::degree_t{rot}}};
-    }
   }
 }
 
 void NTField2DModel::ObjectModel::UpdateNT() {
-  if (m_poses.size() < (255 / 3)) {
-    wpi::SmallVector<double, 9> arr;
-    for (auto&& pose : m_poses) {
-      auto& translation = pose.Translation();
-      arr.push_back(translation.X().value());
-      arr.push_back(translation.Y().value());
-      arr.push_back(pose.Rotation().Degrees().value());
-    }
-    nt::SetEntryTypeValue(m_entry, nt::Value::MakeDoubleArray(arr));
-  } else {
-    // send as raw array of doubles if too big for NT array
-    std::vector<char> arr;
-    arr.resize(m_poses.size() * 3 * 8);
-    char* p = arr.data();
-    for (auto&& pose : m_poses) {
-      auto& translation = pose.Translation();
-      wpi::support::endian::write64be(
-          p, wpi::DoubleToBits(translation.X().value()));
-      p += 8;
-      wpi::support::endian::write64be(
-          p, wpi::DoubleToBits(translation.Y().value()));
-      p += 8;
-      wpi::support::endian::write64be(
-          p, wpi::DoubleToBits(pose.Rotation().Degrees().value()));
-      p += 8;
-    }
-    nt::SetEntryTypeValue(m_entry,
-                          nt::Value::MakeRaw({arr.data(), arr.size()}));
+  wpi::SmallVector<double, 9> arr;
+  for (auto&& pose : m_poses) {
+    auto& translation = pose.Translation();
+    arr.push_back(translation.X().value());
+    arr.push_back(translation.Y().value());
+    arr.push_back(pose.Rotation().Degrees().value());
   }
+  if (!m_pub) {
+    m_pub = m_topic.Publish();
+  }
+  m_pub.Set(arr);
 }
 
-void NTField2DModel::ObjectModel::SetPoses(wpi::span<const frc::Pose2d> poses) {
+void NTField2DModel::ObjectModel::SetPoses(std::span<const frc::Pose2d> poses) {
   m_poses.assign(poses.begin(), poses.end());
   UpdateNT();
 }
@@ -149,69 +106,69 @@
 }
 
 NTField2DModel::NTField2DModel(std::string_view path)
-    : NTField2DModel{nt::GetDefaultInstance(), path} {}
+    : NTField2DModel{nt::NetworkTableInstance::GetDefault(), path} {}
 
-NTField2DModel::NTField2DModel(NT_Inst inst, std::string_view path)
-    : m_nt{inst},
-      m_path{fmt::format("{}/", path)},
-      m_name{m_nt.GetEntry(fmt::format("{}/.name", path))} {
-  m_nt.AddListener(m_path, NT_NOTIFY_LOCAL | NT_NOTIFY_NEW | NT_NOTIFY_DELETE |
-                               NT_NOTIFY_UPDATE | NT_NOTIFY_IMMEDIATE);
+NTField2DModel::NTField2DModel(nt::NetworkTableInstance inst,
+                               std::string_view path)
+    : m_path{fmt::format("{}/", path)},
+      m_inst{inst},
+      m_tableSub{inst, {{m_path}}, {.periodic = 0.05, .sendAll = true}},
+      m_nameTopic{inst.GetTopic(fmt::format("{}/.name", path))},
+      m_poller{inst} {
+  m_poller.AddListener(m_tableSub, nt::EventFlags::kTopic |
+                                       nt::EventFlags::kValueAll |
+                                       nt::EventFlags::kImmediate);
 }
 
 NTField2DModel::~NTField2DModel() = default;
 
 void NTField2DModel::Update() {
-  for (auto&& event : m_nt.PollListener()) {
-    // .name
-    if (event.entry == m_name) {
-      if (event.value && event.value->IsString()) {
-        m_nameValue = event.value->GetString();
-      }
-      continue;
-    }
-
-    // common case: update of existing entry; search by entry
-    if (event.flags & NT_NOTIFY_UPDATE) {
-      auto it = std::find_if(
-          m_objects.begin(), m_objects.end(),
-          [&](const auto& e) { return e->GetEntry() == event.entry; });
-      if (it != m_objects.end()) {
-        (*it)->NTUpdate(*event.value);
-        continue;
-      }
-    }
-
-    // handle create/delete
-    std::string_view name = event.name;
-    if (wpi::starts_with(name, m_path)) {
-      name.remove_prefix(m_path.size());
+  for (auto&& event : m_poller.ReadQueue()) {
+    if (auto info = event.GetTopicInfo()) {
+      // handle publish/unpublish
+      auto name = wpi::drop_front(info->name, m_path.size());
       if (name.empty() || name[0] == '.') {
         continue;
       }
-      auto [it, match] = Find(event.name);
-      if (event.flags & NT_NOTIFY_DELETE) {
+      auto [it, match] = Find(info->name);
+      if (event.flags & nt::EventFlags::kUnpublish) {
         if (match) {
           m_objects.erase(it);
         }
         continue;
-      } else if (event.flags & NT_NOTIFY_NEW) {
+      } else if (event.flags & nt::EventFlags::kPublish) {
         if (!match) {
           it = m_objects.emplace(
-              it, std::make_unique<ObjectModel>(event.name, event.entry));
+              it, std::make_unique<ObjectModel>(
+                      info->name, nt::DoubleArrayTopic{info->topic}));
         }
       } else if (!match) {
         continue;
       }
-      if (event.flags & (NT_NOTIFY_NEW | NT_NOTIFY_UPDATE)) {
-        (*it)->NTUpdate(*event.value);
+    } else if (auto valueData = event.GetValueEventData()) {
+      // update values
+      // .name
+      if (valueData->topic == m_nameTopic.GetHandle()) {
+        if (valueData->value && valueData->value.IsString()) {
+          m_nameValue = valueData->value.GetString();
+        }
+        continue;
+      }
+
+      auto it =
+          std::find_if(m_objects.begin(), m_objects.end(), [&](const auto& e) {
+            return e->GetTopic().GetHandle() == valueData->topic;
+          });
+      if (it != m_objects.end()) {
+        (*it)->NTUpdate(valueData->value);
+        continue;
       }
     }
   }
 }
 
 bool NTField2DModel::Exists() {
-  return m_nt.IsConnected() && nt::GetEntryType(m_name) != NT_UNASSIGNED;
+  return m_nameTopic.Exists();
 }
 
 bool NTField2DModel::IsReadOnly() {
@@ -222,8 +179,9 @@
   auto fullName = fmt::format("{}{}", m_path, name);
   auto [it, match] = Find(fullName);
   if (!match) {
-    it = m_objects.emplace(
-        it, std::make_unique<ObjectModel>(fullName, m_nt.GetEntry(fullName)));
+    it = m_objects.emplace(it,
+                           std::make_unique<ObjectModel>(
+                               fullName, m_inst.GetDoubleArrayTopic(fullName)));
   }
   return it->get();
 }
@@ -231,7 +189,6 @@
 void NTField2DModel::RemoveFieldObject(std::string_view name) {
   auto [it, match] = Find(fmt::format("{}{}", m_path, name));
   if (match) {
-    nt::DeleteEntry((*it)->GetEntry());
     m_objects.erase(it);
   }
 }
diff --git a/third_party/allwpilib/glass/src/libnt/native/cpp/NTGyro.cpp b/third_party/allwpilib/glass/src/libnt/native/cpp/NTGyro.cpp
index 7651d2c..a036b39 100644
--- a/third_party/allwpilib/glass/src/libnt/native/cpp/NTGyro.cpp
+++ b/third_party/allwpilib/glass/src/libnt/native/cpp/NTGyro.cpp
@@ -10,32 +10,24 @@
 using namespace glass;
 
 NTGyroModel::NTGyroModel(std::string_view path)
-    : NTGyroModel(nt::GetDefaultInstance(), path) {}
+    : NTGyroModel(nt::NetworkTableInstance::GetDefault(), path) {}
 
-NTGyroModel::NTGyroModel(NT_Inst instance, std::string_view path)
-    : m_nt(instance),
-      m_angle(m_nt.GetEntry(fmt::format("{}/Value", path))),
-      m_name(m_nt.GetEntry(fmt::format("{}/.name", path))),
-      m_angleData(fmt::format("NT_Gyro:{}", path)),
-      m_nameValue(wpi::rsplit(path, '/').second) {
-  m_nt.AddListener(m_angle);
-  m_nt.AddListener(m_name);
-}
+NTGyroModel::NTGyroModel(nt::NetworkTableInstance inst, std::string_view path)
+    : m_inst{inst},
+      m_angle{inst.GetDoubleTopic(fmt::format("{}/Value", path)).Subscribe(0)},
+      m_name{inst.GetStringTopic(fmt::format("{}/.name", path)).Subscribe({})},
+      m_angleData{fmt::format("NT_Gyro:{}", path)},
+      m_nameValue{wpi::rsplit(path, '/').second} {}
 
 void NTGyroModel::Update() {
-  for (auto&& event : m_nt.PollListener()) {
-    if (event.entry == m_angle) {
-      if (event.value && event.value->IsDouble()) {
-        m_angleData.SetValue(event.value->GetDouble());
-      }
-    } else if (event.entry == m_name) {
-      if (event.value && event.value->IsString()) {
-        m_nameValue = event.value->GetString();
-      }
-    }
+  for (auto&& v : m_name.ReadQueue()) {
+    m_nameValue = std::move(v.value);
+  }
+  for (auto&& v : m_angle.ReadQueue()) {
+    m_angleData.SetValue(v.value, v.time);
   }
 }
 
 bool NTGyroModel::Exists() {
-  return m_nt.IsConnected() && nt::GetEntryType(m_angle) != NT_UNASSIGNED;
+  return m_angle.Exists();
 }
diff --git a/third_party/allwpilib/glass/src/libnt/native/cpp/NTMecanumDrive.cpp b/third_party/allwpilib/glass/src/libnt/native/cpp/NTMecanumDrive.cpp
index 28c0a67..cb564e8 100644
--- a/third_party/allwpilib/glass/src/libnt/native/cpp/NTMecanumDrive.cpp
+++ b/third_party/allwpilib/glass/src/libnt/native/cpp/NTMecanumDrive.cpp
@@ -12,69 +12,62 @@
 using namespace glass;
 
 NTMecanumDriveModel::NTMecanumDriveModel(std::string_view path)
-    : NTMecanumDriveModel(nt::GetDefaultInstance(), path) {}
+    : NTMecanumDriveModel(nt::NetworkTableInstance::GetDefault(), path) {}
 
-NTMecanumDriveModel::NTMecanumDriveModel(NT_Inst instance,
+NTMecanumDriveModel::NTMecanumDriveModel(nt::NetworkTableInstance inst,
                                          std::string_view path)
-    : m_nt(instance),
-      m_name(m_nt.GetEntry(fmt::format("{}/.name", path))),
-      m_controllable(m_nt.GetEntry(fmt::format("{}/.controllable", path))),
-      m_flPercent(
-          m_nt.GetEntry(fmt::format("{}/Front Left Motor Speed", path))),
-      m_frPercent(
-          m_nt.GetEntry(fmt::format("{}/Front Right Motor Speed", path))),
-      m_rlPercent(m_nt.GetEntry(fmt::format("{}/Rear Left Motor Speed", path))),
-      m_rrPercent(
-          m_nt.GetEntry(fmt::format("{}/Rear Right Motor Speed", path))),
-      m_nameValue(wpi::rsplit(path, '/').second),
-      m_flPercentData(fmt::format("NTMcnmDriveFL:{}", path)),
-      m_frPercentData(fmt::format("NTMcnmDriveFR:{}", path)),
-      m_rlPercentData(fmt::format("NTMcnmDriveRL:{}", path)),
-      m_rrPercentData(fmt::format("NTMcnmDriveRR:{}", path)) {
-  m_nt.AddListener(m_name);
-  m_nt.AddListener(m_controllable);
-  m_nt.AddListener(m_flPercent);
-  m_nt.AddListener(m_frPercent);
-  m_nt.AddListener(m_rlPercent);
-  m_nt.AddListener(m_rrPercent);
+    : m_inst{inst},
+      m_name{inst.GetStringTopic(fmt::format("{}/.name", path)).Subscribe("")},
+      m_controllable{inst.GetBooleanTopic(fmt::format("{}/.controllable", path))
+                         .Subscribe(0)},
+      m_flPercent{
+          inst.GetDoubleTopic(fmt::format("{}/Front Left Motor Speed", path))
+              .GetEntry(0)},
+      m_frPercent{
+          inst.GetDoubleTopic(fmt::format("{}/Front Right Motor Speed", path))
+              .GetEntry(0)},
+      m_rlPercent{
+          inst.GetDoubleTopic(fmt::format("{}/Rear Left Motor Speed", path))
+              .GetEntry(0)},
+      m_rrPercent{
+          inst.GetDoubleTopic(fmt::format("{}/Rear Right Motor Speed", path))
+              .GetEntry(0)},
+      m_nameValue{wpi::rsplit(path, '/').second},
+      m_flPercentData{fmt::format("NTMcnmDriveFL:{}", path)},
+      m_frPercentData{fmt::format("NTMcnmDriveFR:{}", path)},
+      m_rlPercentData{fmt::format("NTMcnmDriveRL:{}", path)},
+      m_rrPercentData{fmt::format("NTMcnmDriveRR:{}", path)} {
+  m_wheels.emplace_back("FL % Output", &m_flPercentData,
+                        [this](auto value) { m_flPercent.Set(value); });
 
-  m_wheels.emplace_back("FL % Output", &m_flPercentData, [this](auto value) {
-    nt::SetEntryValue(m_flPercent, nt::NetworkTableValue::MakeDouble(value));
-  });
+  m_wheels.emplace_back("FR % Output", &m_frPercentData,
+                        [this](auto value) { m_frPercent.Set(value); });
 
-  m_wheels.emplace_back("FR % Output", &m_frPercentData, [this](auto value) {
-    nt::SetEntryValue(m_frPercent, nt::NetworkTableValue::MakeDouble(value));
-  });
+  m_wheels.emplace_back("RL % Output", &m_rlPercentData,
+                        [this](auto value) { m_rlPercent.Set(value); });
 
-  m_wheels.emplace_back("RL % Output", &m_rlPercentData, [this](auto value) {
-    nt::SetEntryValue(m_rlPercent, nt::NetworkTableValue::MakeDouble(value));
-  });
-
-  m_wheels.emplace_back("RR % Output", &m_rrPercentData, [this](auto value) {
-    nt::SetEntryValue(m_rrPercent, nt::NetworkTableValue::MakeDouble(value));
-  });
+  m_wheels.emplace_back("RR % Output", &m_rrPercentData,
+                        [this](auto value) { m_rrPercent.Set(value); });
 }
 
 void NTMecanumDriveModel::Update() {
-  for (auto&& event : m_nt.PollListener()) {
-    if (event.entry == m_name && event.value && event.value->IsString()) {
-      m_nameValue = event.value->GetString();
-    } else if (event.entry == m_flPercent && event.value &&
-               event.value->IsDouble()) {
-      m_flPercentData.SetValue(event.value->GetDouble());
-    } else if (event.entry == m_frPercent && event.value &&
-               event.value->IsDouble()) {
-      m_frPercentData.SetValue(event.value->GetDouble());
-    } else if (event.entry == m_rlPercent && event.value &&
-               event.value->IsDouble()) {
-      m_rlPercentData.SetValue(event.value->GetDouble());
-    } else if (event.entry == m_rrPercent && event.value &&
-               event.value->IsDouble()) {
-      m_rrPercentData.SetValue(event.value->GetDouble());
-    } else if (event.entry == m_controllable && event.value &&
-               event.value->IsBoolean()) {
-      m_controllableValue = event.value->GetBoolean();
-    }
+  for (auto&& v : m_name.ReadQueue()) {
+    m_nameValue = std::move(v.value);
+  }
+  for (auto&& v : m_flPercent.ReadQueue()) {
+    m_flPercentData.SetValue(v.value, v.time);
+  }
+  for (auto&& v : m_frPercent.ReadQueue()) {
+    m_frPercentData.SetValue(v.value, v.time);
+  }
+  for (auto&& v : m_rlPercent.ReadQueue()) {
+    m_rlPercentData.SetValue(v.value, v.time);
+  }
+  for (auto&& v : m_rrPercent.ReadQueue()) {
+    m_rrPercentData.SetValue(v.value, v.time);
+  }
+  for (auto&& v : m_controllable.ReadQueue()) {
+    m_controllableValue = v.value;
   }
 
   double fl = m_flPercentData.GetValue();
@@ -88,5 +81,5 @@
 }
 
 bool NTMecanumDriveModel::Exists() {
-  return m_nt.IsConnected() && nt::GetEntryType(m_flPercent) != NT_UNASSIGNED;
+  return m_flPercent.Exists();
 }
diff --git a/third_party/allwpilib/glass/src/libnt/native/cpp/NTMechanism2D.cpp b/third_party/allwpilib/glass/src/libnt/native/cpp/NTMechanism2D.cpp
index 9c73af2..32ed276 100644
--- a/third_party/allwpilib/glass/src/libnt/native/cpp/NTMechanism2D.cpp
+++ b/third_party/allwpilib/glass/src/libnt/native/cpp/NTMechanism2D.cpp
@@ -34,16 +34,17 @@
 
 class NTMechanismGroupImpl final {
  public:
-  NTMechanismGroupImpl(NT_Inst inst, std::string_view path,
+  NTMechanismGroupImpl(nt::NetworkTableInstance inst, std::string_view path,
                        std::string_view name)
       : m_inst{inst}, m_path{path}, m_name{name} {}
 
   const char* GetName() const { return m_name.c_str(); }
   void ForEachObject(wpi::function_ref<void(MechanismObjectModel& model)> func);
-  void NTUpdate(const nt::EntryNotification& event, std::string_view name);
+
+  void NTUpdate(const nt::Event& event, std::string_view name);
 
  protected:
-  NT_Inst m_inst;
+  nt::NetworkTableInstance m_inst;
   std::string m_path;
   std::string m_name;
   std::vector<std::unique_ptr<NTMechanismObjectModel>> m_objects;
@@ -51,14 +52,14 @@
 
 class NTMechanismObjectModel final : public MechanismObjectModel {
  public:
-  NTMechanismObjectModel(NT_Inst inst, std::string_view path,
+  NTMechanismObjectModel(nt::NetworkTableInstance inst, std::string_view path,
                          std::string_view name)
       : m_group{inst, path, name},
-        m_type{nt::GetEntry(inst, fmt::format("{}/.type", path))},
-        m_color{nt::GetEntry(inst, fmt::format("{}/color", path))},
-        m_weight{nt::GetEntry(inst, fmt::format("{}/weight", path))},
-        m_angle{nt::GetEntry(inst, fmt::format("{}/angle", path))},
-        m_length{nt::GetEntry(inst, fmt::format("{}/length", path))} {}
+        m_typeTopic{inst.GetTopic(fmt::format("{}/.type", path))},
+        m_colorTopic{inst.GetTopic(fmt::format("{}/color", path))},
+        m_weightTopic{inst.GetTopic(fmt::format("{}/weight", path))},
+        m_angleTopic{inst.GetTopic(fmt::format("{}/angle", path))},
+        m_lengthTopic{inst.GetTopic(fmt::format("{}/length", path))} {}
 
   const char* GetName() const final { return m_group.GetName(); }
   void ForEachObject(
@@ -72,16 +73,16 @@
   frc::Rotation2d GetAngle() const final { return m_angleValue; }
   units::meter_t GetLength() const final { return m_lengthValue; }
 
-  bool NTUpdate(const nt::EntryNotification& event, std::string_view childName);
+  bool NTUpdate(const nt::Event& event, std::string_view name);
 
  private:
   NTMechanismGroupImpl m_group;
 
-  NT_Entry m_type;
-  NT_Entry m_color;
-  NT_Entry m_weight;
-  NT_Entry m_angle;
-  NT_Entry m_length;
+  nt::Topic m_typeTopic;
+  nt::Topic m_colorTopic;
+  nt::Topic m_weightTopic;
+  nt::Topic m_angleTopic;
+  nt::Topic m_lengthTopic;
 
   std::string m_typeValue;
   ImU32 m_colorValue = IM_COL32_WHITE;
@@ -99,7 +100,7 @@
   }
 }
 
-void NTMechanismGroupImpl::NTUpdate(const nt::EntryNotification& event,
+void NTMechanismGroupImpl::NTUpdate(const nt::Event& event,
                                     std::string_view name) {
   if (name.empty()) {
     return;
@@ -115,58 +116,76 @@
       [](const auto& e, std::string_view name) { return e->GetName() < name; });
   bool match = it != m_objects.end() && (*it)->GetName() == name;
 
-  if (event.flags & NT_NOTIFY_NEW) {
-    if (!match) {
-      it = m_objects.emplace(
-          it, std::make_unique<NTMechanismObjectModel>(
-                  m_inst, fmt::format("{}/{}", m_path, name), name));
-      match = true;
+  if (event.GetTopicInfo()) {
+    if (event.flags & nt::EventFlags::kPublish) {
+      if (!match) {
+        it = m_objects.emplace(
+            it, std::make_unique<NTMechanismObjectModel>(
+                    m_inst, fmt::format("{}/{}", m_path, name), name));
+        match = true;
+      }
     }
-  }
-  if (match) {
-    if ((*it)->NTUpdate(event, childName)) {
-      m_objects.erase(it);
+
+    if (match) {
+      if ((*it)->NTUpdate(event, childName)) {
+        m_objects.erase(it);
+      }
+    }
+  } else if (event.GetValueEventData()) {
+    if (match) {
+      (*it)->NTUpdate(event, childName);
     }
   }
 }
 
-bool NTMechanismObjectModel::NTUpdate(const nt::EntryNotification& event,
+bool NTMechanismObjectModel::NTUpdate(const nt::Event& event,
                                       std::string_view childName) {
-  if (event.entry == m_type) {
-    if ((event.flags & NT_NOTIFY_DELETE) != 0) {
-      return true;
+  if (auto info = event.GetTopicInfo()) {
+    if (info->topic == m_typeTopic.GetHandle()) {
+      if (event.flags & nt::EventFlags::kUnpublish) {
+        return true;
+      }
+    } else if (info->topic != m_colorTopic.GetHandle() &&
+               info->topic != m_weightTopic.GetHandle() &&
+               info->topic != m_angleTopic.GetHandle() &&
+               info->topic != m_lengthTopic.GetHandle()) {
+      m_group.NTUpdate(event, childName);
     }
-    if (event.value && event.value->IsString()) {
-      m_typeValue = event.value->GetString();
+  } else if (auto valueData = event.GetValueEventData()) {
+    if (valueData->topic == m_typeTopic.GetHandle()) {
+      if (valueData->value && valueData->value.IsString()) {
+        m_typeValue = valueData->value.GetString();
+      }
+    } else if (valueData->topic == m_colorTopic.GetHandle()) {
+      if (valueData->value && valueData->value.IsString()) {
+        ConvertColor(valueData->value.GetString(), &m_colorValue);
+      }
+    } else if (valueData->topic == m_weightTopic.GetHandle()) {
+      if (valueData->value && valueData->value.IsDouble()) {
+        m_weightValue = valueData->value.GetDouble();
+      }
+    } else if (valueData->topic == m_angleTopic.GetHandle()) {
+      if (valueData->value && valueData->value.IsDouble()) {
+        m_angleValue = units::degree_t{valueData->value.GetDouble()};
+      }
+    } else if (valueData->topic == m_lengthTopic.GetHandle()) {
+      if (valueData->value && valueData->value.IsDouble()) {
+        m_lengthValue = units::meter_t{valueData->value.GetDouble()};
+      }
+    } else {
+      m_group.NTUpdate(event, childName);
     }
-  } else if (event.entry == m_color) {
-    if (event.value && event.value->IsString()) {
-      ConvertColor(event.value->GetString(), &m_colorValue);
-    }
-  } else if (event.entry == m_weight) {
-    if (event.value && event.value->IsDouble()) {
-      m_weightValue = event.value->GetDouble();
-    }
-  } else if (event.entry == m_angle) {
-    if (event.value && event.value->IsDouble()) {
-      m_angleValue = units::degree_t{event.value->GetDouble()};
-    }
-  } else if (event.entry == m_length) {
-    if (event.value && event.value->IsDouble()) {
-      m_lengthValue = units::meter_t{event.value->GetDouble()};
-    }
-  } else {
-    m_group.NTUpdate(event, childName);
   }
   return false;
 }
 
 class NTMechanism2DModel::RootModel final : public MechanismRootModel {
  public:
-  RootModel(NT_Inst inst, std::string_view path, std::string_view name)
+  RootModel(nt::NetworkTableInstance inst, std::string_view path,
+            std::string_view name)
       : m_group{inst, path, name},
-        m_x{nt::GetEntry(inst, fmt::format("{}/x", path))},
-        m_y{nt::GetEntry(inst, fmt::format("{}/y", path))} {}
+        m_xTopic{inst.GetTopic(fmt::format("{}/x", path))},
+        m_yTopic{inst.GetTopic(fmt::format("{}/y", path))} {}
 
   const char* GetName() const final { return m_group.GetName(); }
   void ForEachObject(
@@ -174,85 +193,70 @@
     m_group.ForEachObject(func);
   }
 
-  bool NTUpdate(const nt::EntryNotification& event, std::string_view childName);
+  bool NTUpdate(const nt::Event& event, std::string_view childName);
 
   frc::Translation2d GetPosition() const override { return m_pos; };
 
  private:
   NTMechanismGroupImpl m_group;
-  NT_Entry m_x;
-  NT_Entry m_y;
+  nt::Topic m_xTopic;
+  nt::Topic m_yTopic;
   frc::Translation2d m_pos;
 };
 
-bool NTMechanism2DModel::RootModel::NTUpdate(const nt::EntryNotification& event,
+bool NTMechanism2DModel::RootModel::NTUpdate(const nt::Event& event,
                                              std::string_view childName) {
-  if ((event.flags & NT_NOTIFY_DELETE) != 0 &&
-      (event.entry == m_x || event.entry == m_y)) {
-    return true;
-  } else if (event.entry == m_x) {
-    if (event.value && event.value->IsDouble()) {
-      m_pos = frc::Translation2d{units::meter_t{event.value->GetDouble()},
-                                 m_pos.Y()};
+  if (auto info = event.GetTopicInfo()) {
+    if (info->topic == m_xTopic.GetHandle() ||
+        info->topic == m_yTopic.GetHandle()) {
+      if (event.flags & nt::EventFlags::kUnpublish) {
+        return true;
+      }
+    } else {
+      m_group.NTUpdate(event, childName);
     }
-  } else if (event.entry == m_y) {
-    if (event.value && event.value->IsDouble()) {
-      m_pos = frc::Translation2d{m_pos.X(),
-                                 units::meter_t{event.value->GetDouble()}};
+  } else if (auto valueData = event.GetValueEventData()) {
+    if (valueData->topic == m_xTopic.GetHandle()) {
+      if (valueData->value && valueData->value.IsDouble()) {
+        m_pos = frc::Translation2d{units::meter_t{valueData->value.GetDouble()},
+                                   m_pos.Y()};
+      }
+    } else if (valueData->topic == m_yTopic.GetHandle()) {
+      if (valueData->value && valueData->value.IsDouble()) {
+        m_pos = frc::Translation2d{
+            m_pos.X(), units::meter_t{valueData->value.GetDouble()}};
+      }
+    } else {
+      m_group.NTUpdate(event, childName);
     }
-  } else {
-    m_group.NTUpdate(event, childName);
   }
   return false;
 }
 
 NTMechanism2DModel::NTMechanism2DModel(std::string_view path)
-    : NTMechanism2DModel{nt::GetDefaultInstance(), path} {}
+    : NTMechanism2DModel{nt::NetworkTableInstance::GetDefault(), path} {}
 
-NTMechanism2DModel::NTMechanism2DModel(NT_Inst inst, std::string_view path)
-    : m_nt{inst},
+NTMechanism2DModel::NTMechanism2DModel(nt::NetworkTableInstance inst,
+                                       std::string_view path)
+    : m_inst{inst},
       m_path{fmt::format("{}/", path)},
-      m_name{m_nt.GetEntry(fmt::format("{}/.name", path))},
-      m_dimensions{m_nt.GetEntry(fmt::format("{}/dims", path))},
-      m_bgColor{m_nt.GetEntry(fmt::format("{}/backgroundColor", path))},
+      m_tableSub{inst, {{m_path}}, {.periodic = 0.05, .sendAll = true}},
+      m_nameTopic{m_inst.GetTopic(fmt::format("{}/.name", path))},
+      m_dimensionsTopic{m_inst.GetTopic(fmt::format("{}/dims", path))},
+      m_bgColorTopic{m_inst.GetTopic(fmt::format("{}/backgroundColor", path))},
+      m_poller{m_inst},
       m_dimensionsValue{1_m, 1_m} {
-  m_nt.AddListener(m_path, NT_NOTIFY_LOCAL | NT_NOTIFY_NEW | NT_NOTIFY_DELETE |
-                               NT_NOTIFY_UPDATE | NT_NOTIFY_IMMEDIATE);
+  m_poller.AddListener(m_tableSub, nt::EventFlags::kTopic |
+                                       nt::EventFlags::kValueAll |
+                                       nt::EventFlags::kImmediate);
 }
 
 NTMechanism2DModel::~NTMechanism2DModel() = default;
 
 void NTMechanism2DModel::Update() {
-  for (auto&& event : m_nt.PollListener()) {
-    // .name
-    if (event.entry == m_name) {
-      if (event.value && event.value->IsString()) {
-        m_nameValue = event.value->GetString();
-      }
-      continue;
-    }
-
-    // dims
-    if (event.entry == m_dimensions) {
-      if (event.value && event.value->IsDoubleArray()) {
-        auto arr = event.value->GetDoubleArray();
-        if (arr.size() == 2) {
-          m_dimensionsValue = frc::Translation2d{units::meter_t{arr[0]},
-                                                 units::meter_t{arr[1]}};
-        }
-      }
-    }
-
-    // backgroundColor
-    if (event.entry == m_bgColor) {
-      if (event.value && event.value->IsString()) {
-        ConvertColor(event.value->GetString(), &m_bgColorValue);
-      }
-    }
-
-    std::string_view name = event.name;
-    if (wpi::starts_with(name, m_path)) {
-      name.remove_prefix(m_path.size());
+  for (auto&& event : m_poller.ReadQueue()) {
+    if (auto info = event.GetTopicInfo()) {
+      auto name = wpi::drop_front(info->name, m_path.size());
       if (name.empty() || name[0] == '.') {
         continue;
       }
@@ -268,12 +272,11 @@
                                  });
       bool match = it != m_roots.end() && (*it)->GetName() == name;
 
-      if (event.flags & NT_NOTIFY_NEW) {
+      if (event.flags & nt::EventFlags::kPublish) {
         if (!match) {
           it = m_roots.emplace(
-              it,
-              std::make_unique<RootModel>(
-                  m_nt.GetInstance(), fmt::format("{}{}", m_path, name), name));
+              it, std::make_unique<RootModel>(
+                      m_inst, fmt::format("{}{}", m_path, name), name));
           match = true;
         }
       }
@@ -282,12 +285,54 @@
           m_roots.erase(it);
         }
       }
+    } else if (auto valueData = event.GetValueEventData()) {
+      if (valueData->topic == m_nameTopic.GetHandle()) {
+        // .name
+        if (valueData->value && valueData->value.IsString()) {
+          m_nameValue = valueData->value.GetString();
+        }
+      } else if (valueData->topic == m_dimensionsTopic.GetHandle()) {
+        // dims
+        if (valueData->value && valueData->value.IsDoubleArray()) {
+          auto arr = valueData->value.GetDoubleArray();
+          if (arr.size() == 2) {
+            m_dimensionsValue = frc::Translation2d{units::meter_t{arr[0]},
+                                                   units::meter_t{arr[1]}};
+          }
+        }
+      } else if (valueData->topic == m_bgColorTopic.GetHandle()) {
+        // backgroundColor
+        if (valueData->value && valueData->value.IsString()) {
+          ConvertColor(valueData->value.GetString(), &m_bgColorValue);
+        }
+      } else {
+        auto fullName = nt::Topic{valueData->topic}.GetName();
+        auto name = wpi::drop_front(fullName, m_path.size());
+        if (name.empty() || name[0] == '.') {
+          continue;
+        }
+        std::string_view childName;
+        std::tie(name, childName) = wpi::split(name, '/');
+        if (childName.empty()) {
+          continue;
+        }
+
+        auto it = std::lower_bound(m_roots.begin(), m_roots.end(), name,
+                                   [](const auto& e, std::string_view name) {
+                                     return e->GetName() < name;
+                                   });
+        if (it != m_roots.end() && (*it)->GetName() == name) {
+          if ((*it)->NTUpdate(event, childName)) {
+            m_roots.erase(it);
+          }
+        }
+      }
     }
   }
 }
 
 bool NTMechanism2DModel::Exists() {
-  return m_nt.IsConnected() && nt::GetEntryType(m_name) != NT_UNASSIGNED;
+  return m_nameTopic.Exists();
 }
 
 bool NTMechanism2DModel::IsReadOnly() {
diff --git a/third_party/allwpilib/glass/src/libnt/native/cpp/NTMotorController.cpp b/third_party/allwpilib/glass/src/libnt/native/cpp/NTMotorController.cpp
new file mode 100644
index 0000000..1de6714
--- /dev/null
+++ b/third_party/allwpilib/glass/src/libnt/native/cpp/NTMotorController.cpp
@@ -0,0 +1,43 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "glass/networktables/NTMotorController.h"
+
+#include <fmt/format.h>
+#include <wpi/StringExtras.h>
+
+using namespace glass;
+
+NTMotorControllerModel::NTMotorControllerModel(std::string_view path)
+    : NTMotorControllerModel(nt::NetworkTableInstance::GetDefault(), path) {}
+
+NTMotorControllerModel::NTMotorControllerModel(nt::NetworkTableInstance inst,
+                                               std::string_view path)
+    : m_inst{inst},
+      m_value{inst.GetDoubleTopic(fmt::format("{}/Value", path)).GetEntry(0)},
+      m_name{inst.GetStringTopic(fmt::format("{}/.name", path)).Subscribe("")},
+      m_controllable{inst.GetBooleanTopic(fmt::format("{}/.controllable", path))
+                         .Subscribe(false)},
+      m_valueData{fmt::format("NT_SpdCtrl:{}", path)},
+      m_nameValue{wpi::rsplit(path, '/').second} {}
+
+void NTMotorControllerModel::SetPercent(double value) {
+  m_value.Set(value);
+}
+
+void NTMotorControllerModel::Update() {
+  for (auto&& v : m_value.ReadQueue()) {
+    m_valueData.SetValue(v.value, v.time);
+  }
+  for (auto&& v : m_name.ReadQueue()) {
+    m_nameValue = std::move(v.value);
+  }
+  for (auto&& v : m_controllable.ReadQueue()) {
+    m_controllableValue = v.value;
+  }
+}
+
+bool NTMotorControllerModel::Exists() {
+  return m_value.Exists();
+}
diff --git a/third_party/allwpilib/glass/src/libnt/native/cpp/NTPIDController.cpp b/third_party/allwpilib/glass/src/libnt/native/cpp/NTPIDController.cpp
index 7936057..1dde27d 100644
--- a/third_party/allwpilib/glass/src/libnt/native/cpp/NTPIDController.cpp
+++ b/third_party/allwpilib/glass/src/libnt/native/cpp/NTPIDController.cpp
@@ -10,76 +10,62 @@
 using namespace glass;
 
 NTPIDControllerModel::NTPIDControllerModel(std::string_view path)
-    : NTPIDControllerModel(nt::GetDefaultInstance(), path) {}
+    : NTPIDControllerModel(nt::NetworkTableInstance::GetDefault(), path) {}
 
-NTPIDControllerModel::NTPIDControllerModel(NT_Inst instance,
+NTPIDControllerModel::NTPIDControllerModel(nt::NetworkTableInstance inst,
                                            std::string_view path)
-    : m_nt(instance),
-      m_name(m_nt.GetEntry(fmt::format("{}/.name", path))),
-      m_controllable(m_nt.GetEntry(fmt::format("{}/.controllable", path))),
-      m_p(m_nt.GetEntry(fmt::format("{}/p", path))),
-      m_i(m_nt.GetEntry(fmt::format("{}/i", path))),
-      m_d(m_nt.GetEntry(fmt::format("{}/d", path))),
-      m_setpoint(m_nt.GetEntry(fmt::format("{}/setpoint", path))),
-      m_pData(fmt::format("NTPIDCtrlP:{}", path)),
-      m_iData(fmt::format("NTPIDCtrlI:{}", path)),
-      m_dData(fmt::format("NTPIDCtrlD:{}", path)),
-      m_setpointData(fmt::format("NTPIDCtrlStpt:{}", path)),
-      m_nameValue(wpi::rsplit(path, '/').second) {
-  m_nt.AddListener(m_name);
-  m_nt.AddListener(m_controllable);
-  m_nt.AddListener(m_p);
-  m_nt.AddListener(m_i);
-  m_nt.AddListener(m_d);
-  m_nt.AddListener(m_setpoint);
-}
+    : m_inst{inst},
+      m_name{inst.GetStringTopic(fmt::format("{}/.name", path)).Subscribe("")},
+      m_controllable{inst.GetBooleanTopic(fmt::format("{}/.controllable", path))
+                         .Subscribe(false)},
+      m_p{inst.GetDoubleTopic(fmt::format("{}/p", path)).GetEntry(0)},
+      m_i{inst.GetDoubleTopic(fmt::format("{}/i", path)).GetEntry(0)},
+      m_d{inst.GetDoubleTopic(fmt::format("{}/d", path)).GetEntry(0)},
+      m_setpoint{
+          inst.GetDoubleTopic(fmt::format("{}/setpoint", path)).GetEntry(0)},
+      m_pData{fmt::format("NTPIDCtrlP:{}", path)},
+      m_iData{fmt::format("NTPIDCtrlI:{}", path)},
+      m_dData{fmt::format("NTPIDCtrlD:{}", path)},
+      m_setpointData{fmt::format("NTPIDCtrlStpt:{}", path)},
+      m_nameValue{wpi::rsplit(path, '/').second} {}
 
 void NTPIDControllerModel::SetP(double value) {
-  nt::SetEntryValue(m_p, nt::NetworkTableValue::MakeDouble(value));
+  m_p.Set(value);
 }
 
 void NTPIDControllerModel::SetI(double value) {
-  nt::SetEntryValue(m_i, nt::NetworkTableValue::MakeDouble(value));
+  m_i.Set(value);
 }
 
 void NTPIDControllerModel::SetD(double value) {
-  nt::SetEntryValue(m_d, nt::NetworkTableValue::MakeDouble(value));
+  m_d.Set(value);
 }
 
 void NTPIDControllerModel::SetSetpoint(double value) {
-  nt::SetEntryValue(m_setpoint, nt::NetworkTableValue::MakeDouble(value));
+  m_setpoint.Set(value);
 }
 
 void NTPIDControllerModel::Update() {
-  for (auto&& event : m_nt.PollListener()) {
-    if (event.entry == m_name) {
-      if (event.value && event.value->IsString()) {
-        m_nameValue = event.value->GetString();
-      }
-    } else if (event.entry == m_p) {
-      if (event.value && event.value->IsDouble()) {
-        m_pData.SetValue(event.value->GetDouble());
-      }
-    } else if (event.entry == m_i) {
-      if (event.value && event.value->IsDouble()) {
-        m_iData.SetValue(event.value->GetDouble());
-      }
-    } else if (event.entry == m_d) {
-      if (event.value && event.value->IsDouble()) {
-        m_dData.SetValue(event.value->GetDouble());
-      }
-    } else if (event.entry == m_setpoint) {
-      if (event.value && event.value->IsDouble()) {
-        m_setpointData.SetValue(event.value->GetDouble());
-      }
-    } else if (event.entry == m_controllable) {
-      if (event.value && event.value->IsBoolean()) {
-        m_controllableValue = event.value->GetBoolean();
-      }
-    }
+  for (auto&& v : m_name.ReadQueue()) {
+    m_nameValue = std::move(v.value);
+  }
+  for (auto&& v : m_p.ReadQueue()) {
+    m_pData.SetValue(v.value, v.time);
+  }
+  for (auto&& v : m_i.ReadQueue()) {
+    m_iData.SetValue(v.value, v.time);
+  }
+  for (auto&& v : m_d.ReadQueue()) {
+    m_dData.SetValue(v.value, v.time);
+  }
+  for (auto&& v : m_setpoint.ReadQueue()) {
+    m_setpointData.SetValue(v.value, v.time);
+  }
+  for (auto&& v : m_controllable.ReadQueue()) {
+    m_controllableValue = v.value;
   }
 }
 
 bool NTPIDControllerModel::Exists() {
-  return m_nt.IsConnected() && nt::GetEntryType(m_setpoint) != NT_UNASSIGNED;
+  return m_setpoint.Exists();
 }
diff --git a/third_party/allwpilib/glass/src/libnt/native/cpp/NTSpeedController.cpp b/third_party/allwpilib/glass/src/libnt/native/cpp/NTSpeedController.cpp
deleted file mode 100644
index 3dc351a..0000000
--- a/third_party/allwpilib/glass/src/libnt/native/cpp/NTSpeedController.cpp
+++ /dev/null
@@ -1,52 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "glass/networktables/NTSpeedController.h"
-
-#include <fmt/format.h>
-#include <wpi/StringExtras.h>
-
-using namespace glass;
-
-NTSpeedControllerModel::NTSpeedControllerModel(std::string_view path)
-    : NTSpeedControllerModel(nt::GetDefaultInstance(), path) {}
-
-NTSpeedControllerModel::NTSpeedControllerModel(NT_Inst instance,
-                                               std::string_view path)
-    : m_nt(instance),
-      m_value(m_nt.GetEntry(fmt::format("{}/Value", path))),
-      m_name(m_nt.GetEntry(fmt::format("{}/.name", path))),
-      m_controllable(m_nt.GetEntry(fmt::format("{}/.controllable", path))),
-      m_valueData(fmt::format("NT_SpdCtrl:{}", path)),
-      m_nameValue(wpi::rsplit(path, '/').second) {
-  m_nt.AddListener(m_value);
-  m_nt.AddListener(m_name);
-  m_nt.AddListener(m_controllable);
-}
-
-void NTSpeedControllerModel::SetPercent(double value) {
-  nt::SetEntryValue(m_value, nt::NetworkTableValue::MakeDouble(value));
-}
-
-void NTSpeedControllerModel::Update() {
-  for (auto&& event : m_nt.PollListener()) {
-    if (event.entry == m_value) {
-      if (event.value && event.value->IsDouble()) {
-        m_valueData.SetValue(event.value->GetDouble());
-      }
-    } else if (event.entry == m_name) {
-      if (event.value && event.value->IsString()) {
-        m_nameValue = event.value->GetString();
-      }
-    } else if (event.entry == m_controllable) {
-      if (event.value && event.value->IsBoolean()) {
-        m_controllableValue = event.value->GetBoolean();
-      }
-    }
-  }
-}
-
-bool NTSpeedControllerModel::Exists() {
-  return m_nt.IsConnected() && nt::GetEntryType(m_value) != NT_UNASSIGNED;
-}
diff --git a/third_party/allwpilib/glass/src/libnt/native/cpp/NTStringChooser.cpp b/third_party/allwpilib/glass/src/libnt/native/cpp/NTStringChooser.cpp
index e6a97fa..b892a2c 100644
--- a/third_party/allwpilib/glass/src/libnt/native/cpp/NTStringChooser.cpp
+++ b/third_party/allwpilib/glass/src/libnt/native/cpp/NTStringChooser.cpp
@@ -9,67 +9,56 @@
 using namespace glass;
 
 NTStringChooserModel::NTStringChooserModel(std::string_view path)
-    : NTStringChooserModel{nt::GetDefaultInstance(), path} {}
+    : NTStringChooserModel{nt::NetworkTableInstance::GetDefault(), path} {}
 
-NTStringChooserModel::NTStringChooserModel(NT_Inst inst, std::string_view path)
-    : m_nt{inst},
-      m_default{m_nt.GetEntry(fmt::format("{}/default", path))},
-      m_selected{m_nt.GetEntry(fmt::format("{}/selected", path))},
-      m_active{m_nt.GetEntry(fmt::format("{}/active", path))},
-      m_options{m_nt.GetEntry(fmt::format("{}/options", path))} {
-  m_nt.AddListener(m_default);
-  m_nt.AddListener(m_selected);
-  m_nt.AddListener(m_active);
-  m_nt.AddListener(m_options);
-}
-
-void NTStringChooserModel::SetDefault(std::string_view val) {
-  nt::SetEntryValue(m_default, nt::Value::MakeString(val));
+NTStringChooserModel::NTStringChooserModel(nt::NetworkTableInstance inst,
+                                           std::string_view path)
+    : m_inst{inst},
+      m_default{
+          m_inst.GetStringTopic(fmt::format("{}/default", path)).Subscribe("")},
+      m_selected{
+          m_inst.GetStringTopic(fmt::format("{}/selected", path)).GetEntry("")},
+      m_active{
+          m_inst.GetStringTopic(fmt::format("{}/active", path)).Subscribe("")},
+      m_options{m_inst.GetStringArrayTopic(fmt::format("{}/options", path))
+                    .Subscribe({})} {
+  m_selected.GetTopic().SetRetained(true);
 }
 
 void NTStringChooserModel::SetSelected(std::string_view val) {
-  nt::SetEntryValue(m_selected, nt::Value::MakeString(val));
-}
-
-void NTStringChooserModel::SetActive(std::string_view val) {
-  nt::SetEntryValue(m_active, nt::Value::MakeString(val));
-}
-
-void NTStringChooserModel::SetOptions(wpi::span<const std::string> val) {
-  nt::SetEntryValue(m_options, nt::Value::MakeStringArray(val));
+  m_selected.Set(val);
 }
 
 void NTStringChooserModel::Update() {
-  for (auto&& event : m_nt.PollListener()) {
-    if (event.entry == m_default) {
-      if ((event.flags & NT_NOTIFY_DELETE) != 0) {
-        m_defaultValue.clear();
-      } else if (event.value && event.value->IsString()) {
-        m_defaultValue = event.value->GetString();
-      }
-    } else if (event.entry == m_selected) {
-      if ((event.flags & NT_NOTIFY_DELETE) != 0) {
-        m_selectedValue.clear();
-      } else if (event.value && event.value->IsString()) {
-        m_selectedValue = event.value->GetString();
-      }
-    } else if (event.entry == m_active) {
-      if ((event.flags & NT_NOTIFY_DELETE) != 0) {
-        m_activeValue.clear();
-      } else if (event.value && event.value->IsString()) {
-        m_activeValue = event.value->GetString();
-      }
-    } else if (event.entry == m_options) {
-      if ((event.flags & NT_NOTIFY_DELETE) != 0) {
-        m_optionsValue.clear();
-      } else if (event.value && event.value->IsStringArray()) {
-        auto arr = event.value->GetStringArray();
-        m_optionsValue.assign(arr.begin(), arr.end());
-      }
-    }
+  if (!m_default.Exists()) {
+    m_defaultValue.clear();
+  }
+  for (auto&& v : m_default.ReadQueue()) {
+    m_defaultValue = std::move(v.value);
+  }
+
+  if (!m_selected.Exists()) {
+    m_selectedValue.clear();
+  }
+  for (auto&& v : m_selected.ReadQueue()) {
+    m_selectedValue = std::move(v.value);
+  }
+
+  if (!m_active.Exists()) {
+    m_activeValue.clear();
+  }
+  for (auto&& v : m_active.ReadQueue()) {
+    m_activeValue = std::move(v.value);
+  }
+
+  if (!m_options.Exists()) {
+    m_optionsValue.clear();
+  }
+  for (auto&& v : m_options.ReadQueue()) {
+    m_optionsValue = std::move(v.value);
   }
 }
 
 bool NTStringChooserModel::Exists() {
-  return m_nt.IsConnected() && nt::GetEntryType(m_options) != NT_UNASSIGNED;
+  return m_options.Exists();
 }
diff --git a/third_party/allwpilib/glass/src/libnt/native/cpp/NTSubsystem.cpp b/third_party/allwpilib/glass/src/libnt/native/cpp/NTSubsystem.cpp
index b2bdf8c..3078f87 100644
--- a/third_party/allwpilib/glass/src/libnt/native/cpp/NTSubsystem.cpp
+++ b/third_party/allwpilib/glass/src/libnt/native/cpp/NTSubsystem.cpp
@@ -9,37 +9,30 @@
 using namespace glass;
 
 NTSubsystemModel::NTSubsystemModel(std::string_view path)
-    : NTSubsystemModel(nt::GetDefaultInstance(), path) {}
+    : NTSubsystemModel(nt::NetworkTableInstance::GetDefault(), path) {}
 
-NTSubsystemModel::NTSubsystemModel(NT_Inst instance, std::string_view path)
-    : m_nt(instance),
-      m_name(m_nt.GetEntry(fmt::format("{}/.name", path))),
-      m_defaultCommand(m_nt.GetEntry(fmt::format("{}/.default", path))),
-      m_currentCommand(m_nt.GetEntry(fmt::format("{}/.command", path))) {
-  m_nt.AddListener(m_name);
-  m_nt.AddListener(m_defaultCommand);
-  m_nt.AddListener(m_currentCommand);
+NTSubsystemModel::NTSubsystemModel(nt::NetworkTableInstance inst,
+                                   std::string_view path)
+    : m_inst{inst},
+      m_name{inst.GetStringTopic(fmt::format("{}/.name", path)).Subscribe("")},
+      m_defaultCommand{
+          inst.GetStringTopic(fmt::format("{}/.default", path)).Subscribe("")},
+      m_currentCommand{
+          inst.GetStringTopic(fmt::format("{}/.command", path)).Subscribe("")} {
 }
 
 void NTSubsystemModel::Update() {
-  for (auto&& event : m_nt.PollListener()) {
-    if (event.entry == m_name) {
-      if (event.value && event.value->IsString()) {
-        m_nameValue = event.value->GetString();
-      }
-    } else if (event.entry == m_defaultCommand) {
-      if (event.value && event.value->IsString()) {
-        m_defaultCommandValue = event.value->GetString();
-      }
-    } else if (event.entry == m_currentCommand) {
-      if (event.value && event.value->IsString()) {
-        m_currentCommandValue = event.value->GetString();
-      }
-    }
+  for (auto&& v : m_name.ReadQueue()) {
+    m_nameValue = std::move(v.value);
+  }
+  for (auto&& v : m_defaultCommand.ReadQueue()) {
+    m_defaultCommandValue = std::move(v.value);
+  }
+  for (auto&& v : m_currentCommand.ReadQueue()) {
+    m_currentCommandValue = std::move(v.value);
   }
 }
 
 bool NTSubsystemModel::Exists() {
-  return m_nt.IsConnected() &&
-         nt::GetEntryType(m_defaultCommand) != NT_UNASSIGNED;
+  return m_defaultCommand.Exists();
 }
diff --git a/third_party/allwpilib/glass/src/libnt/native/cpp/NetworkTables.cpp b/third_party/allwpilib/glass/src/libnt/native/cpp/NetworkTables.cpp
index bce2b0a..d368359 100644
--- a/third_party/allwpilib/glass/src/libnt/native/cpp/NetworkTables.cpp
+++ b/third_party/allwpilib/glass/src/libnt/native/cpp/NetworkTables.cpp
@@ -4,32 +4,61 @@
 
 #include "glass/networktables/NetworkTables.h"
 
-#include <networktables/NetworkTableValue.h>
-
 #include <cinttypes>
 #include <cstdio>
 #include <cstring>
 #include <initializer_list>
 #include <memory>
+#include <span>
 #include <string_view>
 #include <vector>
 
 #include <fmt/format.h>
 #include <imgui.h>
+#include <networktables/NetworkTableInstance.h>
+#include <networktables/NetworkTableValue.h>
+#include <ntcore_c.h>
 #include <ntcore_cpp.h>
+#include <ntcore_cpp_types.h>
+#include <wpi/MessagePack.h>
 #include <wpi/SmallString.h>
 #include <wpi/SpanExtras.h>
 #include <wpi/StringExtras.h>
+#include <wpi/mpack.h>
 #include <wpi/raw_ostream.h>
-#include <wpi/span.h>
 
 #include "glass/Context.h"
 #include "glass/DataSource.h"
 #include "glass/Storage.h"
 
 using namespace glass;
+using namespace mpack;
 
-static std::string BooleanArrayToString(wpi::span<const int> in) {
+namespace {
+enum ShowCategory {
+  ShowPersistent,
+  ShowRetained,
+  ShowTransitory,
+  ShowAll,
+};
+}  // namespace
+
+static bool IsVisible(ShowCategory category, bool persistent, bool retained) {
+  switch (category) {
+    case ShowPersistent:
+      return persistent;
+    case ShowRetained:
+      return retained && !persistent;
+    case ShowTransitory:
+      return !retained && !persistent;
+    case ShowAll:
+      return true;
+    default:
+      return false;
+  }
+}
+
+static std::string BooleanArrayToString(std::span<const int> in) {
   std::string rv;
   wpi::raw_string_ostream os{rv};
   os << '[';
@@ -49,11 +78,17 @@
   return rv;
 }
 
-static std::string DoubleArrayToString(wpi::span<const double> in) {
+static std::string IntegerArrayToString(std::span<const int64_t> in) {
+  return fmt::format("[{:d}]", fmt::join(in, ","));
+}
+
+template <typename T>
+static std::string FloatArrayToString(std::span<const T> in) {
+  static_assert(std::is_same_v<T, float> || std::is_same_v<T, double>);
   return fmt::format("[{:.6f}]", fmt::join(in, ","));
 }
 
-static std::string StringArrayToString(wpi::span<const std::string> in) {
+static std::string StringArrayToString(std::span<const std::string> in) {
   std::string rv;
   wpi::raw_string_ostream os{rv};
   os << '[';
@@ -72,91 +107,399 @@
 }
 
 NetworkTablesModel::NetworkTablesModel()
-    : NetworkTablesModel{nt::GetDefaultInstance()} {}
+    : NetworkTablesModel{nt::NetworkTableInstance::GetDefault()} {}
 
-NetworkTablesModel::NetworkTablesModel(NT_Inst inst)
-    : m_inst{inst}, m_poller{nt::CreateEntryListenerPoller(inst)} {
-  nt::AddPolledEntryListener(m_poller, "",
-                             NT_NOTIFY_LOCAL | NT_NOTIFY_NEW |
-                                 NT_NOTIFY_UPDATE | NT_NOTIFY_DELETE |
-                                 NT_NOTIFY_FLAGS | NT_NOTIFY_IMMEDIATE);
+NetworkTablesModel::NetworkTablesModel(nt::NetworkTableInstance inst)
+    : m_inst{inst}, m_poller{inst} {
+  m_poller.AddListener({{"", "$"}}, nt::EventFlags::kTopic |
+                                        nt::EventFlags::kValueAll |
+                                        nt::EventFlags::kImmediate);
 }
 
-NetworkTablesModel::~NetworkTablesModel() {
-  nt::DestroyEntryListenerPoller(m_poller);
+NetworkTablesModel::Entry::~Entry() {
+  if (publisher != 0) {
+    nt::Unpublish(publisher);
+  }
 }
 
-NetworkTablesModel::Entry::Entry(nt::EntryNotification&& event)
-    : entry{event.entry},
-      name{std::move(event.name)},
-      value{std::move(event.value)},
-      flags{nt::GetEntryFlags(event.entry)} {
-  UpdateValue();
+void NetworkTablesModel::Entry::UpdateInfo(nt::TopicInfo&& info_) {
+  info = std::move(info_);
+  properties = info.GetProperties();
+
+  persistent = false;
+  auto it = properties.find("persistent");
+  if (it != properties.end()) {
+    if (auto v = it->get_ptr<const bool*>()) {
+      persistent = *v;
+    }
+  }
+
+  retained = false;
+  it = properties.find("retained");
+  if (it != properties.end()) {
+    if (auto v = it->get_ptr<const bool*>()) {
+      retained = *v;
+    }
+  }
 }
 
-void NetworkTablesModel::Entry::UpdateValue() {
-  switch (value->type()) {
+static void UpdateMsgpackValueSource(NetworkTablesModel::ValueSource* out,
+                                     mpack_reader_t& r, std::string_view name,
+                                     int64_t time) {
+  mpack_tag_t tag = mpack_read_tag(&r);
+  switch (mpack_tag_type(&tag)) {
+    case mpack::mpack_type_bool:
+      out->UpdateFromValue(
+          nt::Value::MakeBoolean(mpack_tag_bool_value(&tag), time), name, "");
+      break;
+    case mpack::mpack_type_int:
+      out->UpdateFromValue(
+          nt::Value::MakeInteger(mpack_tag_int_value(&tag), time), name, "");
+      break;
+    case mpack::mpack_type_uint:
+      out->UpdateFromValue(
+          nt::Value::MakeInteger(mpack_tag_uint_value(&tag), time), name, "");
+      break;
+    case mpack::mpack_type_float:
+      out->UpdateFromValue(
+          nt::Value::MakeFloat(mpack_tag_float_value(&tag), time), name, "");
+      break;
+    case mpack::mpack_type_double:
+      out->UpdateFromValue(
+          nt::Value::MakeDouble(mpack_tag_double_value(&tag), time), name, "");
+      break;
+    case mpack::mpack_type_str: {
+      std::string str;
+      mpack_read_str(&r, &tag, &str);
+      out->UpdateFromValue(nt::Value::MakeString(std::move(str), time), name,
+                           "");
+      break;
+    }
+    case mpack::mpack_type_bin:
+      // just skip it
+      mpack_skip_bytes(&r, mpack_tag_bin_length(&tag));
+      mpack_done_bin(&r);
+      break;
+    case mpack::mpack_type_array: {
+      if (out->valueChildrenMap) {
+        out->valueChildren.clear();
+        out->valueChildrenMap = false;
+      }
+      out->valueChildren.resize(mpack_tag_array_count(&tag));
+      unsigned int i = 0;
+      for (auto&& child : out->valueChildren) {
+        if (child.name.empty()) {
+          child.name = fmt::format("[{}]", i);
+          child.path = fmt::format("{}{}", name, child.name);
+        }
+        ++i;
+        UpdateMsgpackValueSource(&child, r, child.path, time);  // recurse
+      }
+      mpack_done_array(&r);
+      break;
+    }
+    case mpack::mpack_type_map: {
+      if (!out->valueChildrenMap) {
+        out->valueChildren.clear();
+        out->valueChildrenMap = true;
+      }
+      wpi::StringMap<size_t> elems;
+      for (size_t i = 0, size = out->valueChildren.size(); i < size; ++i) {
+        elems[out->valueChildren[i].name] = i;
+      }
+      bool added = false;
+      uint32_t count = mpack_tag_map_count(&tag);
+      for (uint32_t i = 0; i < count; ++i) {
+        std::string key;
+        if (mpack_expect_str(&r, &key) == mpack_ok) {
+          auto it = elems.find(key);
+          if (it != elems.end()) {
+            auto& child = out->valueChildren[it->second];
+            UpdateMsgpackValueSource(&child, r, child.path, time);
+            elems.erase(it);
+          } else {
+            added = true;
+            out->valueChildren.emplace_back();
+            auto& child = out->valueChildren.back();
+            child.name = std::move(key);
+            child.path = fmt::format("{}/{}", name, child.name);
+            UpdateMsgpackValueSource(&child, r, child.path, time);
+          }
+        }
+      }
+      // erase unmatched keys
+      out->valueChildren.erase(
+          std::remove_if(
+              out->valueChildren.begin(), out->valueChildren.end(),
+              [&](const auto& child) { return elems.count(child.name) > 0; }),
+          out->valueChildren.end());
+      if (added) {
+        // sort by name
+        std::sort(out->valueChildren.begin(), out->valueChildren.end(),
+                  [](const auto& a, const auto& b) { return a.name < b.name; });
+      }
+      mpack_done_map(&r);
+      break;
+    }
+    default:
+      out->value = {};
+      mpack_done_type(&r, mpack_tag_type(&tag));
+      break;
+  }
+}
+
+static void UpdateJsonValueSource(NetworkTablesModel::ValueSource* out,
+                                  const wpi::json& j, std::string_view name,
+                                  int64_t time) {
+  switch (j.type()) {
+    case wpi::json::value_t::object: {
+      if (!out->valueChildrenMap) {
+        out->valueChildren.clear();
+        out->valueChildrenMap = true;
+      }
+      wpi::StringMap<size_t> elems;
+      for (size_t i = 0, size = out->valueChildren.size(); i < size; ++i) {
+        elems[out->valueChildren[i].name] = i;
+      }
+      bool added = false;
+      for (auto&& kv : j.items()) {
+        auto it = elems.find(kv.key());
+        if (it != elems.end()) {
+          auto& child = out->valueChildren[it->second];
+          UpdateJsonValueSource(&child, kv.value(), child.path, time);
+          elems.erase(it);
+        } else {
+          added = true;
+          out->valueChildren.emplace_back();
+          auto& child = out->valueChildren.back();
+          child.name = kv.key();
+          child.path = fmt::format("{}/{}", name, child.name);
+          UpdateJsonValueSource(&child, kv.value(), child.path, time);
+        }
+      }
+      // erase unmatched keys
+      out->valueChildren.erase(
+          std::remove_if(
+              out->valueChildren.begin(), out->valueChildren.end(),
+              [&](const auto& child) { return elems.count(child.name) > 0; }),
+          out->valueChildren.end());
+      if (added) {
+        // sort by name
+        std::sort(out->valueChildren.begin(), out->valueChildren.end(),
+                  [](const auto& a, const auto& b) { return a.name < b.name; });
+      }
+      break;
+    }
+    case wpi::json::value_t::array: {
+      if (out->valueChildrenMap) {
+        out->valueChildren.clear();
+        out->valueChildrenMap = false;
+      }
+      out->valueChildren.resize(j.size());
+      unsigned int i = 0;
+      for (auto&& child : out->valueChildren) {
+        if (child.name.empty()) {
+          child.name = fmt::format("[{}]", i);
+          child.path = fmt::format("{}{}", name, child.name);
+        }
+        ++i;
+        UpdateJsonValueSource(&child, j[i], child.path, time);  // recurse
+      }
+      break;
+    }
+    case wpi::json::value_t::string:
+      out->UpdateFromValue(
+          nt::Value::MakeString(j.get_ref<const std::string&>(), time), name,
+          "");
+      break;
+    case wpi::json::value_t::boolean:
+      out->UpdateFromValue(nt::Value::MakeBoolean(j.get<bool>(), time), name,
+                           "");
+      break;
+    case wpi::json::value_t::number_integer:
+      out->UpdateFromValue(nt::Value::MakeInteger(j.get<int64_t>(), time), name,
+                           "");
+      break;
+    case wpi::json::value_t::number_unsigned:
+      out->UpdateFromValue(nt::Value::MakeInteger(j.get<uint64_t>(), time),
+                           name, "");
+      break;
+    case wpi::json::value_t::number_float:
+      out->UpdateFromValue(nt::Value::MakeDouble(j.get<double>(), time), name,
+                           "");
+      break;
+    default:
+      out->value = {};
+      break;
+  }
+}
+
+void NetworkTablesModel::ValueSource::UpdateFromValue(
+    nt::Value&& v, std::string_view name, std::string_view typeStr) {
+  value = v;
+  switch (value.type()) {
     case NT_BOOLEAN:
+      valueChildren.clear();
       if (!source) {
         source = std::make_unique<DataSource>(fmt::format("NT:{}", name));
       }
-      source->SetValue(value->GetBoolean() ? 1 : 0);
+      source->SetValue(value.GetBoolean() ? 1 : 0, value.last_change());
       source->SetDigital(true);
       break;
-    case NT_DOUBLE:
+    case NT_INTEGER:
+      valueChildren.clear();
       if (!source) {
         source = std::make_unique<DataSource>(fmt::format("NT:{}", name));
       }
-      source->SetValue(value->GetDouble());
+      source->SetValue(value.GetInteger(), value.last_change());
+      source->SetDigital(false);
+      break;
+    case NT_FLOAT:
+      valueChildren.clear();
+      if (!source) {
+        source = std::make_unique<DataSource>(fmt::format("NT:{}", name));
+      }
+      source->SetValue(value.GetFloat(), value.last_change());
+      source->SetDigital(false);
+      break;
+    case NT_DOUBLE:
+      valueChildren.clear();
+      if (!source) {
+        source = std::make_unique<DataSource>(fmt::format("NT:{}", name));
+      }
+      source->SetValue(value.GetDouble(), value.last_change());
       source->SetDigital(false);
       break;
     case NT_BOOLEAN_ARRAY:
-      valueStr = BooleanArrayToString(value->GetBooleanArray());
+      valueChildren.clear();
+      valueStr = BooleanArrayToString(value.GetBooleanArray());
+      break;
+    case NT_INTEGER_ARRAY:
+      valueChildren.clear();
+      valueStr = IntegerArrayToString(value.GetIntegerArray());
+      break;
+    case NT_FLOAT_ARRAY:
+      valueChildren.clear();
+      valueStr = FloatArrayToString(value.GetFloatArray());
       break;
     case NT_DOUBLE_ARRAY:
-      valueStr = DoubleArrayToString(value->GetDoubleArray());
+      valueChildren.clear();
+      valueStr = FloatArrayToString(value.GetDoubleArray());
       break;
     case NT_STRING_ARRAY:
-      valueStr = StringArrayToString(value->GetStringArray());
+      valueChildren.clear();
+      valueStr = StringArrayToString(value.GetStringArray());
+      break;
+    case NT_STRING:
+      if (typeStr == "json") {
+        try {
+          UpdateJsonValueSource(this, wpi::json::parse(value.GetString()), name,
+                                value.last_change());
+        } catch (wpi::json::exception&) {
+          // ignore
+        }
+      } else {
+        valueChildren.clear();
+      }
+      break;
+    case NT_RAW:
+      if (typeStr == "msgpack") {
+        mpack_reader_t r;
+        mpack_reader_init_data(&r, value.GetRaw());
+        UpdateMsgpackValueSource(this, r, name, value.last_change());
+
+        mpack_reader_destroy(&r);
+      } else {
+        valueChildren.clear();
+      }
       break;
     default:
+      valueChildren.clear();
       break;
   }
 }
 
 void NetworkTablesModel::Update() {
-  bool timedOut = false;
   bool updateTree = false;
-  for (auto&& event : nt::PollEntryListener(m_poller, 0, &timedOut)) {
-    auto& entry = m_entries[event.entry];
-    if (event.flags & NT_NOTIFY_NEW) {
-      if (!entry) {
-        entry = std::make_unique<Entry>(std::move(event));
-        m_sortedEntries.emplace_back(entry.get());
+  for (auto&& event : m_poller.ReadQueue()) {
+    if (auto info = event.GetTopicInfo()) {
+      auto& entry = m_entries[info->topic];
+      if (event.flags & nt::EventFlags::kPublish) {
+        if (!entry) {
+          entry = std::make_unique<Entry>();
+          m_sortedEntries.emplace_back(entry.get());
+          updateTree = true;
+        }
+      }
+      if (event.flags & nt::EventFlags::kUnpublish) {
+        // meta topic handling
+        if (wpi::starts_with(info->name, '$')) {
+          // meta topic handling
+          if (info->name == "$clients") {
+            m_clients.clear();
+          } else if (info->name == "$serverpub") {
+            m_server.publishers.clear();
+          } else if (info->name == "$serversub") {
+            m_server.subscribers.clear();
+          } else if (wpi::starts_with(info->name, "$clientpub$")) {
+            auto it = m_clients.find(wpi::drop_front(info->name, 11));
+            if (it != m_clients.end()) {
+              it->second.publishers.clear();
+            }
+          } else if (wpi::starts_with(info->name, "$clientsub$")) {
+            auto it = m_clients.find(wpi::drop_front(info->name, 11));
+            if (it != m_clients.end()) {
+              it->second.subscribers.clear();
+            }
+          }
+        }
+        auto it = std::find(m_sortedEntries.begin(), m_sortedEntries.end(),
+                            entry.get());
+        // will be removed completely below
+        if (it != m_sortedEntries.end()) {
+          *it = nullptr;
+        }
+        m_entries.erase(info->topic);
         updateTree = true;
         continue;
       }
-    }
-    if (!entry) {
-      continue;
-    }
-    if (event.flags & NT_NOTIFY_DELETE) {
-      auto it = std::find(m_sortedEntries.begin(), m_sortedEntries.end(),
-                          entry.get());
-      // will be removed completely below
-      if (it != m_sortedEntries.end()) {
-        *it = nullptr;
+      if (event.flags & nt::EventFlags::kProperties) {
+        updateTree = true;
       }
-      m_entries.erase(event.entry);
-      updateTree = true;
-      continue;
-    }
-    if (event.flags & NT_NOTIFY_UPDATE) {
-      entry->value = std::move(event.value);
-      entry->UpdateValue();
-    }
-    if (event.flags & NT_NOTIFY_FLAGS) {
-      entry->flags = nt::GetEntryFlags(event.entry);
+      if (entry) {
+        entry->UpdateTopic(std::move(event));
+      }
+    } else if (auto valueData = event.GetValueEventData()) {
+      auto& entry = m_entries[valueData->topic];
+      if (entry) {
+        entry->UpdateFromValue(std::move(valueData->value), entry->info.name,
+                               entry->info.type_str);
+        if (wpi::starts_with(entry->info.name, '$') && entry->value.IsRaw() &&
+            entry->info.type_str == "msgpack") {
+          // meta topic handling
+          if (entry->info.name == "$clients") {
+            // need to remove deleted entries as UpdateClients() uses GetEntry()
+            if (updateTree) {
+              std::erase(m_sortedEntries, nullptr);
+            }
+            UpdateClients(entry->value.GetRaw());
+          } else if (entry->info.name == "$serverpub") {
+            m_server.UpdatePublishers(entry->value.GetRaw());
+          } else if (entry->info.name == "$serversub") {
+            m_server.UpdateSubscribers(entry->value.GetRaw());
+          } else if (wpi::starts_with(entry->info.name, "$clientpub$")) {
+            auto it = m_clients.find(wpi::drop_front(entry->info.name, 11));
+            if (it != m_clients.end()) {
+              it->second.UpdatePublishers(entry->value.GetRaw());
+            }
+          } else if (wpi::starts_with(entry->info.name, "$clientsub$")) {
+            auto it = m_clients.find(wpi::drop_front(entry->info.name, 11));
+            if (it != m_clients.end()) {
+              it->second.UpdateSubscribers(entry->value.GetRaw());
+            }
+          }
+        }
+      }
     }
   }
 
@@ -166,20 +509,34 @@
   }
 
   // remove deleted entries
-  m_sortedEntries.erase(
-      std::remove(m_sortedEntries.begin(), m_sortedEntries.end(), nullptr),
-      m_sortedEntries.end());
+  std::erase(m_sortedEntries, nullptr);
 
+  RebuildTree();
+}
+
+void NetworkTablesModel::RebuildTree() {
   // sort by name
-  std::sort(m_sortedEntries.begin(), m_sortedEntries.end(),
-            [](const auto& a, const auto& b) { return a->name < b->name; });
+  std::sort(
+      m_sortedEntries.begin(), m_sortedEntries.end(),
+      [](const auto& a, const auto& b) { return a->info.name < b->info.name; });
 
-  // rebuild tree
-  m_root.clear();
+  RebuildTreeImpl(&m_root, ShowAll);
+  RebuildTreeImpl(&m_persistentRoot, ShowPersistent);
+  RebuildTreeImpl(&m_retainedRoot, ShowRetained);
+  RebuildTreeImpl(&m_transitoryRoot, ShowTransitory);
+}
+
+void NetworkTablesModel::RebuildTreeImpl(std::vector<TreeNode>* tree,
+                                         int category) {
+  tree->clear();
   wpi::SmallVector<std::string_view, 16> parts;
   for (auto& entry : m_sortedEntries) {
+    if (!IsVisible(static_cast<ShowCategory>(category), entry->persistent,
+                   entry->retained)) {
+      continue;
+    }
     parts.clear();
-    wpi::split(entry->name, parts, '/', -1, false);
+    wpi::split(entry->info.name, parts, '/', -1, false);
 
     // ignore a raw "/" key
     if (parts.empty()) {
@@ -187,8 +544,8 @@
     }
 
     // get to leaf
-    auto nodes = &m_root;
-    for (auto part : wpi::drop_back(wpi::span{parts.begin(), parts.end()})) {
+    auto nodes = tree;
+    for (auto part : wpi::drop_back(std::span{parts.begin(), parts.end()})) {
       auto it =
           std::find_if(nodes->begin(), nodes->end(),
                        [&](const auto& node) { return node.name == part; });
@@ -196,9 +553,10 @@
         nodes->emplace_back(part);
         // path is from the beginning of the string to the end of the current
         // part; this works because part is a reference to the internals of
-        // entry->name
+        // entry->info.name
         nodes->back().path.assign(
-            entry->name.data(), part.data() + part.size() - entry->name.data());
+            entry->info.name.data(),
+            part.data() + part.size() - entry->info.name.data());
         it = nodes->end() - 1;
       }
       nodes = &it->children;
@@ -217,14 +575,97 @@
 }
 
 bool NetworkTablesModel::Exists() {
-  return nt::IsConnected(m_inst);
+  return true;
 }
 
-static std::shared_ptr<nt::Value> StringToBooleanArray(std::string_view in) {
+NetworkTablesModel::Entry* NetworkTablesModel::GetEntry(std::string_view name) {
+  auto entryIt = std::lower_bound(
+      m_sortedEntries.begin(), m_sortedEntries.end(), name,
+      [](auto&& entry, auto&& name) { return entry->info.name < name; });
+  if (entryIt == m_sortedEntries.end() || (*entryIt)->info.name != name) {
+    return nullptr;
+  }
+  return *entryIt;
+}
+
+NetworkTablesModel::Entry* NetworkTablesModel::AddEntry(NT_Topic topic) {
+  auto& entry = m_entries[topic];
+  if (!entry) {
+    entry = std::make_unique<Entry>();
+    entry->info = nt::GetTopicInfo(topic);
+    entry->properties = entry->info.GetProperties();
+    m_sortedEntries.emplace_back(entry.get());
+  }
+  RebuildTree();
+  return entry.get();
+}
+
+NetworkTablesModel::Client::Subscriber::Subscriber(
+    nt::meta::ClientSubscriber&& oth)
+    : ClientSubscriber{std::move(oth)},
+      topicsStr{StringArrayToString(topics)} {}
+
+void NetworkTablesModel::Client::UpdatePublishers(
+    std::span<const uint8_t> data) {
+  if (auto pubs = nt::meta::DecodeClientPublishers(data)) {
+    publishers = std::move(*pubs);
+  } else {
+    fmt::print(stderr, "Failed to update publishers\n");
+  }
+}
+
+void NetworkTablesModel::Client::UpdateSubscribers(
+    std::span<const uint8_t> data) {
+  if (auto subs = nt::meta::DecodeClientSubscribers(data)) {
+    subscribers.clear();
+    subscribers.reserve(subs->size());
+    for (auto&& sub : *subs) {
+      subscribers.emplace_back(std::move(sub));
+    }
+  } else {
+    fmt::print(stderr, "Failed to update subscribers\n");
+  }
+}
+
+void NetworkTablesModel::UpdateClients(std::span<const uint8_t> data) {
+  auto clientsArr = nt::meta::DecodeClients(data);
+  if (!clientsArr) {
+    return;
+  }
+
+  // we need to create a new map so deletions are reflected
+  std::map<std::string, Client, std::less<>> newClients;
+  for (auto&& client : *clientsArr) {
+    auto& newClient = newClients[client.id];
+    newClient = std::move(client);
+    auto it = m_clients.find(newClient.id);
+    if (it != m_clients.end()) {
+      // transfer from existing
+      newClient.publishers = std::move(it->second.publishers);
+      newClient.subscribers = std::move(it->second.subscribers);
+    } else {
+      // initially populate
+      if (Entry* entry = GetEntry(fmt::format("$clientpub${}", newClient.id))) {
+        if (entry->value.IsRaw() && entry->info.type_str == "msgpack") {
+          newClient.UpdatePublishers(entry->value.GetRaw());
+        }
+      }
+      if (Entry* entry = GetEntry(fmt::format("$clientsub${}", newClient.id))) {
+        if (entry->value.IsRaw() && entry->info.type_str == "msgpack") {
+          newClient.UpdateSubscribers(entry->value.GetRaw());
+        }
+      }
+    }
+  }
+
+  // replace map
+  m_clients = std::move(newClients);
+}
+
+static bool StringToBooleanArray(std::string_view in, std::vector<int>* out) {
   in = wpi::trim(in);
   if (in.empty()) {
-    return nt::NetworkTableValue::MakeBooleanArray(
-        std::initializer_list<bool>{});
+    return false;
   }
   if (in.front() == '[') {
     in.remove_prefix(1);
@@ -235,30 +676,29 @@
   in = wpi::trim(in);
 
   wpi::SmallVector<std::string_view, 16> inSplit;
-  wpi::SmallVector<int, 16> out;
 
   wpi::split(in, inSplit, ',', -1, false);
   for (auto val : inSplit) {
     val = wpi::trim(val);
     if (wpi::equals_lower(val, "true")) {
-      out.emplace_back(1);
+      out->emplace_back(1);
     } else if (wpi::equals_lower(val, "false")) {
-      out.emplace_back(0);
+      out->emplace_back(0);
     } else {
       fmt::print(stderr,
                  "GUI: NetworkTables: Could not understand value '{}'\n", val);
-      return nullptr;
+      return false;
     }
   }
 
-  return nt::NetworkTableValue::MakeBooleanArray(out);
+  return true;
 }
 
-static std::shared_ptr<nt::Value> StringToDoubleArray(std::string_view in) {
+static bool StringToIntegerArray(std::string_view in,
+                                 std::vector<int64_t>* out) {
   in = wpi::trim(in);
   if (in.empty()) {
-    return nt::NetworkTableValue::MakeDoubleArray(
-        std::initializer_list<double>{});
+    return false;
   }
   if (in.front() == '[') {
     in.remove_prefix(1);
@@ -269,75 +709,27 @@
   in = wpi::trim(in);
 
   wpi::SmallVector<std::string_view, 16> inSplit;
-  wpi::SmallVector<double, 16> out;
 
   wpi::split(in, inSplit, ',', -1, false);
   for (auto val : inSplit) {
-    if (auto num = wpi::parse_float<double>(wpi::trim(val))) {
-      out.emplace_back(num.value());
+    if (auto num = wpi::parse_integer<int64_t>(wpi::trim(val), 0)) {
+      out->emplace_back(num.value());
     } else {
       fmt::print(stderr,
                  "GUI: NetworkTables: Could not understand value '{}'\n", val);
-      return nullptr;
+      return false;
     }
   }
 
-  return nt::NetworkTableValue::MakeDoubleArray(out);
+  return true;
 }
 
-static int fromxdigit(char ch) {
-  if (ch >= 'a' && ch <= 'f') {
-    return (ch - 'a' + 10);
-  } else if (ch >= 'A' && ch <= 'F') {
-    return (ch - 'A' + 10);
-  } else {
-    return ch - '0';
-  }
-}
-
-static std::string_view UnescapeString(std::string_view source,
-                                       wpi::SmallVectorImpl<char>& buf) {
-  assert(source.size() >= 2 && source.front() == '"' && source.back() == '"');
-  buf.clear();
-  buf.reserve(source.size() - 2);
-  for (auto s = source.begin() + 1, end = source.end() - 1; s != end; ++s) {
-    if (*s != '\\') {
-      buf.push_back(*s);
-      continue;
-    }
-    switch (*++s) {
-      case 't':
-        buf.push_back('\t');
-        break;
-      case 'n':
-        buf.push_back('\n');
-        break;
-      case 'x': {
-        if (!isxdigit(*(s + 1))) {
-          buf.push_back('x');  // treat it like a unknown escape
-          break;
-        }
-        int ch = fromxdigit(*++s);
-        if (std::isxdigit(*(s + 1))) {
-          ch <<= 4;
-          ch |= fromxdigit(*++s);
-        }
-        buf.push_back(static_cast<char>(ch));
-        break;
-      }
-      default:
-        buf.push_back(*s);
-        break;
-    }
-  }
-  return {buf.data(), buf.size()};
-}
-
-static std::shared_ptr<nt::Value> StringToStringArray(std::string_view in) {
+template <typename T>
+static bool StringToFloatArray(std::string_view in, std::vector<T>* out) {
+  static_assert(std::is_same_v<T, float> || std::is_same_v<T, double>);
   in = wpi::trim(in);
   if (in.empty()) {
-    return nt::NetworkTableValue::MakeStringArray(
-        std::initializer_list<std::string>{});
+    return false;
   }
   if (in.front() == '[') {
     in.remove_prefix(1);
@@ -348,7 +740,36 @@
   in = wpi::trim(in);
 
   wpi::SmallVector<std::string_view, 16> inSplit;
-  std::vector<std::string> out;
+
+  wpi::split(in, inSplit, ',', -1, false);
+  for (auto val : inSplit) {
+    if (auto num = wpi::parse_float<T>(wpi::trim(val))) {
+      out->emplace_back(num.value());
+    } else {
+      fmt::print(stderr,
+                 "GUI: NetworkTables: Could not understand value '{}'\n", val);
+      return false;
+    }
+  }
+
+  return true;
+}
+
+static bool StringToStringArray(std::string_view in,
+                                std::vector<std::string>* out) {
+  in = wpi::trim(in);
+  if (in.empty()) {
+    return false;
+  }
+  if (in.front() == '[') {
+    in.remove_prefix(1);
+  }
+  if (in.back() == ']') {
+    in.remove_suffix(1);
+  }
+  in = wpi::trim(in);
+
+  wpi::SmallVector<std::string_view, 16> inSplit;
   wpi::SmallString<32> buf;
 
   wpi::split(in, inSplit, ',', -1, false);
@@ -360,49 +781,81 @@
     if (val.front() != '"' || val.back() != '"') {
       fmt::print(stderr,
                  "GUI: NetworkTables: Could not understand value '{}'\n", val);
-      return nullptr;
+      return false;
     }
-    out.emplace_back(UnescapeString(val, buf));
+    val.remove_prefix(1);
+    val.remove_suffix(1);
+    out->emplace_back(wpi::UnescapeCString(val, buf).first);
   }
 
-  return nt::NetworkTableValue::MakeStringArray(std::move(out));
+  return true;
 }
 
-static void EmitEntryValueReadonly(NetworkTablesModel::Entry& entry) {
+static void EmitEntryValueReadonly(const NetworkTablesModel::ValueSource& entry,
+                                   const char* typeStr,
+                                   NetworkTablesFlags flags) {
   auto& val = entry.value;
   if (!val) {
     return;
   }
 
-  switch (val->type()) {
+  switch (val.type()) {
     case NT_BOOLEAN:
-      ImGui::LabelText("boolean", "%s", val->GetBoolean() ? "true" : "false");
+      ImGui::LabelText(typeStr ? typeStr : "boolean", "%s",
+                       val.GetBoolean() ? "true" : "false");
       break;
-    case NT_DOUBLE:
-      ImGui::LabelText("double", "%.6f", val->GetDouble());
+    case NT_INTEGER:
+      ImGui::LabelText(typeStr ? typeStr : "int", "%" PRId64, val.GetInteger());
       break;
+    case NT_FLOAT:
+      ImGui::LabelText(typeStr ? typeStr : "double", "%.6f", val.GetFloat());
+      break;
+    case NT_DOUBLE: {
+      unsigned char precision = (flags & NetworkTablesFlags_Precision) >>
+                                kNetworkTablesFlags_PrecisionBitShift;
+#ifdef __GNUC__
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Wformat-nonliteral"
+#endif
+      ImGui::LabelText(typeStr ? typeStr : "double",
+                       fmt::format("%.{}f", precision).c_str(),
+                       val.GetDouble());
+#ifdef __GNUC__
+#pragma GCC diagnostic pop
+#endif
+      break;
+    }
     case NT_STRING: {
       // GetString() comes from a std::string, so it's null terminated
-      ImGui::LabelText("string", "%s", val->GetString().data());
+      ImGui::LabelText(typeStr ? typeStr : "string", "%s",
+                       val.GetString().data());
       break;
     }
     case NT_BOOLEAN_ARRAY:
-      ImGui::LabelText("boolean[]", "%s", entry.valueStr.c_str());
+      ImGui::LabelText(typeStr ? typeStr : "boolean[]", "%s",
+                       entry.valueStr.c_str());
+      break;
+    case NT_INTEGER_ARRAY:
+      ImGui::LabelText(typeStr ? typeStr : "int[]", "%s",
+                       entry.valueStr.c_str());
+      break;
+    case NT_FLOAT_ARRAY:
+      ImGui::LabelText(typeStr ? typeStr : "float[]", "%s",
+                       entry.valueStr.c_str());
       break;
     case NT_DOUBLE_ARRAY:
-      ImGui::LabelText("double[]", "%s", entry.valueStr.c_str());
+      ImGui::LabelText(typeStr ? typeStr : "double[]", "%s",
+                       entry.valueStr.c_str());
       break;
     case NT_STRING_ARRAY:
-      ImGui::LabelText("string[]", "%s", entry.valueStr.c_str());
+      ImGui::LabelText(typeStr ? typeStr : "string[]", "%s",
+                       entry.valueStr.c_str());
       break;
     case NT_RAW:
-      ImGui::LabelText("raw", "[...]");
-      break;
-    case NT_RPC:
-      ImGui::LabelText("rpc", "[...]");
+      ImGui::LabelText(typeStr ? typeStr : "raw", "[...]");
       break;
     default:
-      ImGui::LabelText("other", "?");
+      ImGui::LabelText(typeStr ? typeStr : "other", "?");
       break;
   }
 }
@@ -417,85 +870,188 @@
   return textBuffer;
 }
 
-static void EmitEntryValueEditable(NetworkTablesModel::Entry& entry) {
+static void EmitEntryValueEditable(NetworkTablesModel::Entry& entry,
+                                   NetworkTablesFlags flags) {
   auto& val = entry.value;
   if (!val) {
     return;
   }
 
-  ImGui::PushID(entry.name.c_str());
-  switch (val->type()) {
+  const char* typeStr =
+      entry.info.type_str.empty() ? nullptr : entry.info.type_str.c_str();
+  ImGui::PushID(entry.info.name.c_str());
+  switch (val.type()) {
     case NT_BOOLEAN: {
       static const char* boolOptions[] = {"false", "true"};
-      int v = val->GetBoolean() ? 1 : 0;
-      if (ImGui::Combo("boolean", &v, boolOptions, 2)) {
-        nt::SetEntryValue(entry.entry, nt::NetworkTableValue::MakeBoolean(v));
+      int v = val.GetBoolean() ? 1 : 0;
+      if (ImGui::Combo(typeStr ? typeStr : "boolean", &v, boolOptions, 2)) {
+        if (entry.publisher == 0) {
+          entry.publisher =
+              nt::Publish(entry.info.topic, NT_BOOLEAN, "boolean");
+        }
+        nt::SetBoolean(entry.publisher, v);
+      }
+      break;
+    }
+    case NT_INTEGER: {
+      int64_t v = val.GetInteger();
+      if (ImGui::InputScalar(typeStr ? typeStr : "int", ImGuiDataType_S64, &v,
+                             nullptr, nullptr, nullptr,
+                             ImGuiInputTextFlags_EnterReturnsTrue)) {
+        if (entry.publisher == 0) {
+          entry.publisher = nt::Publish(entry.info.topic, NT_INTEGER, "int");
+        }
+        nt::SetInteger(entry.publisher, v);
+      }
+      break;
+    }
+    case NT_FLOAT: {
+      float v = val.GetFloat();
+      if (ImGui::InputFloat(typeStr ? typeStr : "float", &v, 0, 0, "%.6f",
+                            ImGuiInputTextFlags_EnterReturnsTrue)) {
+        if (entry.publisher == 0) {
+          entry.publisher = nt::Publish(entry.info.topic, NT_FLOAT, "float");
+        }
+        nt::SetFloat(entry.publisher, v);
       }
       break;
     }
     case NT_DOUBLE: {
-      double v = val->GetDouble();
-      if (ImGui::InputDouble("double", &v, 0, 0, "%.6f",
+      double v = val.GetDouble();
+      unsigned char precision = (flags & NetworkTablesFlags_Precision) >>
+                                kNetworkTablesFlags_PrecisionBitShift;
+#ifdef __GNUC__
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Wformat-nonliteral"
+#endif
+      if (ImGui::InputDouble(typeStr ? typeStr : "double", &v, 0, 0,
+                             fmt::format("%.{}f", precision).c_str(),
                              ImGuiInputTextFlags_EnterReturnsTrue)) {
-        nt::SetEntryValue(entry.entry, nt::NetworkTableValue::MakeDouble(v));
+        if (entry.publisher == 0) {
+          entry.publisher = nt::Publish(entry.info.topic, NT_DOUBLE, "double");
+        }
+        nt::SetDouble(entry.publisher, v);
       }
+#ifdef __GNUC__
+#pragma GCC diagnostic pop
+#endif
       break;
     }
     case NT_STRING: {
-      char* v = GetTextBuffer(val->GetString());
-      if (ImGui::InputText("string", v, kTextBufferSize,
+      char* v = GetTextBuffer(val.GetString());
+      if (ImGui::InputText(typeStr ? typeStr : "string", v, kTextBufferSize,
                            ImGuiInputTextFlags_EnterReturnsTrue)) {
-        nt::SetEntryValue(entry.entry, nt::NetworkTableValue::MakeString(v));
+        if (entry.publisher == 0) {
+          entry.publisher = nt::Publish(entry.info.topic, NT_STRING, "string");
+        }
+        nt::SetString(entry.publisher, v);
       }
       break;
     }
     case NT_BOOLEAN_ARRAY: {
       char* v = GetTextBuffer(entry.valueStr);
-      if (ImGui::InputText("boolean[]", v, kTextBufferSize,
+      if (ImGui::InputText(typeStr ? typeStr : "boolean[]", v, kTextBufferSize,
                            ImGuiInputTextFlags_EnterReturnsTrue)) {
-        if (auto outv = StringToBooleanArray(v)) {
-          nt::SetEntryValue(entry.entry, std::move(outv));
+        std::vector<int> outv;
+        if (StringToBooleanArray(v, &outv)) {
+          if (entry.publisher == 0) {
+            entry.publisher =
+                nt::Publish(entry.info.topic, NT_BOOLEAN_ARRAY, "boolean[]");
+          }
+          nt::SetBooleanArray(entry.publisher, outv);
+        }
+      }
+      break;
+    }
+    case NT_INTEGER_ARRAY: {
+      char* v = GetTextBuffer(entry.valueStr);
+      if (ImGui::InputText(typeStr ? typeStr : "int[]", v, kTextBufferSize,
+                           ImGuiInputTextFlags_EnterReturnsTrue)) {
+        std::vector<int64_t> outv;
+        if (StringToIntegerArray(v, &outv)) {
+          if (entry.publisher == 0) {
+            entry.publisher =
+                nt::Publish(entry.info.topic, NT_INTEGER_ARRAY, "int[]");
+          }
+          nt::SetIntegerArray(entry.publisher, outv);
+        }
+      }
+      break;
+    }
+    case NT_FLOAT_ARRAY: {
+      char* v = GetTextBuffer(entry.valueStr);
+      if (ImGui::InputText(typeStr ? typeStr : "float[]", v, kTextBufferSize,
+                           ImGuiInputTextFlags_EnterReturnsTrue)) {
+        std::vector<float> outv;
+        if (StringToFloatArray(v, &outv)) {
+          if (entry.publisher == 0) {
+            entry.publisher =
+                nt::Publish(entry.info.topic, NT_DOUBLE_ARRAY, "float[]");
+          }
+          nt::SetFloatArray(entry.publisher, outv);
         }
       }
       break;
     }
     case NT_DOUBLE_ARRAY: {
       char* v = GetTextBuffer(entry.valueStr);
-      if (ImGui::InputText("double[]", v, kTextBufferSize,
+      if (ImGui::InputText(typeStr ? typeStr : "double[]", v, kTextBufferSize,
                            ImGuiInputTextFlags_EnterReturnsTrue)) {
-        if (auto outv = StringToDoubleArray(v)) {
-          nt::SetEntryValue(entry.entry, std::move(outv));
+        std::vector<double> outv;
+        if (StringToFloatArray(v, &outv)) {
+          if (entry.publisher == 0) {
+            entry.publisher =
+                nt::Publish(entry.info.topic, NT_DOUBLE_ARRAY, "double[]");
+          }
+          nt::SetDoubleArray(entry.publisher, outv);
         }
       }
       break;
     }
     case NT_STRING_ARRAY: {
       char* v = GetTextBuffer(entry.valueStr);
-      if (ImGui::InputText("string[]", v, kTextBufferSize,
+      if (ImGui::InputText(typeStr ? typeStr : "string[]", v, kTextBufferSize,
                            ImGuiInputTextFlags_EnterReturnsTrue)) {
-        if (auto outv = StringToStringArray(v)) {
-          nt::SetEntryValue(entry.entry, std::move(outv));
+        std::vector<std::string> outv;
+        if (StringToStringArray(v, &outv)) {
+          if (entry.publisher == 0) {
+            entry.publisher =
+                nt::Publish(entry.info.topic, NT_STRING_ARRAY, "string[]");
+          }
+          nt::SetStringArray(entry.publisher, outv);
         }
       }
       break;
     }
     case NT_RAW:
-      ImGui::LabelText("raw", "[...]");
+      ImGui::LabelText(typeStr ? typeStr : "raw",
+                       val.GetRaw().empty() ? "[]" : "[...]");
       break;
     case NT_RPC:
-      ImGui::LabelText("rpc", "[...]");
+      ImGui::LabelText(typeStr ? typeStr : "rpc", "[...]");
       break;
     default:
-      ImGui::LabelText("other", "?");
+      ImGui::LabelText(typeStr ? typeStr : "other", "?");
       break;
   }
   ImGui::PopID();
 }
 
-static void EmitParentContextMenu(const std::string& path,
+static void CreateTopicMenuItem(NetworkTablesModel* model,
+                                std::string_view path, NT_Type type,
+                                const char* typeStr, bool enabled) {
+  if (ImGui::MenuItem(typeStr, nullptr, false, enabled)) {
+    auto entry =
+        model->AddEntry(nt::GetTopic(model->GetInstance().GetHandle(), path));
+    if (entry->publisher == 0) {
+      entry->publisher = nt::Publish(entry->info.topic, type, typeStr);
+    }
+  }
+}
+
+static void EmitParentContextMenu(NetworkTablesModel* model,
+                                  const std::string& path,
                                   NetworkTablesFlags flags) {
-  // Workaround https://github.com/ocornut/imgui/issues/331
-  bool openWarningPopup = false;
   static char nameBuffer[kTextBufferSize];
   if (ImGui::BeginPopupContextItem(path.c_str())) {
     ImGui::Text("%s", path.c_str());
@@ -517,216 +1073,367 @@
 
       ImGui::Text("Adding: %s", fullNewPath.c_str());
       ImGui::Separator();
-      auto entry = nt::GetEntry(nt::GetDefaultInstance(), fullNewPath);
+      auto entry = model->GetEntry(fullNewPath);
+      bool exists = entry && entry->info.type != NT_Type::NT_UNASSIGNED;
       bool enabled = (flags & NetworkTablesFlags_CreateNoncanonicalKeys ||
                       nameBuffer[0] != '\0') &&
-                     nt::GetEntryType(entry) == NT_Type::NT_UNASSIGNED;
-      if (ImGui::MenuItem("string", nullptr, false, enabled)) {
-        if (!nt::SetEntryValue(entry, nt::Value::MakeString(""))) {
-          openWarningPopup = true;
-        }
-      }
-      if (ImGui::MenuItem("double", nullptr, false, enabled)) {
-        if (!nt::SetEntryValue(entry, nt::Value::MakeDouble(0.0))) {
-          openWarningPopup = true;
-        }
-      }
-      if (ImGui::MenuItem("boolean", nullptr, false, enabled)) {
-        if (!nt::SetEntryValue(entry, nt::Value::MakeBoolean(false))) {
-          openWarningPopup = true;
-        }
-      }
-      if (ImGui::MenuItem("string[]", nullptr, false, enabled)) {
-        if (!nt::SetEntryValue(entry, nt::Value::MakeStringArray({""}))) {
-          openWarningPopup = true;
-        }
-      }
-      if (ImGui::MenuItem("double[]", nullptr, false, enabled)) {
-        if (!nt::SetEntryValue(entry, nt::Value::MakeDoubleArray({0.0}))) {
-          openWarningPopup = true;
-        }
-      }
-      if (ImGui::MenuItem("boolean[]", nullptr, false, enabled)) {
-        if (!nt::SetEntryValue(entry, nt::Value::MakeBooleanArray({false}))) {
-          openWarningPopup = true;
-        }
-      }
+                     !exists;
+
+      CreateTopicMenuItem(model, fullNewPath, NT_STRING, "string", enabled);
+      CreateTopicMenuItem(model, fullNewPath, NT_INTEGER, "int", enabled);
+      CreateTopicMenuItem(model, fullNewPath, NT_FLOAT, "float", enabled);
+      CreateTopicMenuItem(model, fullNewPath, NT_DOUBLE, "double", enabled);
+      CreateTopicMenuItem(model, fullNewPath, NT_BOOLEAN, "boolean", enabled);
+      CreateTopicMenuItem(model, fullNewPath, NT_STRING_ARRAY, "string[]",
+                          enabled);
+      CreateTopicMenuItem(model, fullNewPath, NT_INTEGER_ARRAY, "int[]",
+                          enabled);
+      CreateTopicMenuItem(model, fullNewPath, NT_FLOAT_ARRAY, "float[]",
+                          enabled);
+      CreateTopicMenuItem(model, fullNewPath, NT_DOUBLE_ARRAY, "double[]",
+                          enabled);
+      CreateTopicMenuItem(model, fullNewPath, NT_BOOLEAN_ARRAY, "boolean[]",
+                          enabled);
 
       ImGui::EndMenu();
     }
 
-    ImGui::Separator();
-    if (ImGui::MenuItem("Remove All")) {
-      for (auto&& entry : nt::GetEntries(nt::GetDefaultInstance(), path, 0)) {
-        nt::DeleteEntry(entry);
-      }
-    }
-    ImGui::EndPopup();
-  }
-
-  // Workaround https://github.com/ocornut/imgui/issues/331
-  if (openWarningPopup) {
-    ImGui::OpenPopup("Value exists");
-  }
-  if (ImGui::BeginPopupModal("Value exists", nullptr,
-                             ImGuiWindowFlags_AlwaysAutoResize)) {
-    ImGui::Text("The provided name %s already exists in the tree!", nameBuffer);
-    ImGui::Separator();
-
-    if (ImGui::Button("OK", ImVec2(120, 0))) {
-      ImGui::CloseCurrentPopup();
-    }
-    ImGui::SetItemDefaultFocus();
     ImGui::EndPopup();
   }
 }
 
-static void EmitEntry(NetworkTablesModel::Entry& entry, const char* name,
-                      NetworkTablesFlags flags) {
-  if (entry.source) {
+static void EmitValueName(DataSource* source, const char* name,
+                          const char* path) {
+  if (source) {
     ImGui::Selectable(name);
-    entry.source->EmitDrag();
+    source->EmitDrag();
   } else {
-    ImGui::Text("%s", name);
+    ImGui::TextUnformatted(name);
   }
-  if (ImGui::BeginPopupContextItem(entry.name.c_str())) {
-    ImGui::Text("%s", entry.name.c_str());
-    ImGui::Separator();
-    if (ImGui::MenuItem("Remove")) {
-      nt::DeleteEntry(entry.entry);
-    }
+  if (ImGui::BeginPopupContextItem(path)) {
+    ImGui::TextUnformatted(path);
     ImGui::EndPopup();
   }
-  ImGui::NextColumn();
+}
 
-  if (flags & NetworkTablesFlags_ReadOnly) {
-    EmitEntryValueReadonly(entry);
-  } else {
-    EmitEntryValueEditable(entry);
-  }
-  ImGui::NextColumn();
-
-  if (flags & NetworkTablesFlags_ShowFlags) {
-    if ((entry.flags & NT_PERSISTENT) != 0) {
-      ImGui::Text("Persistent");
-    } else if (entry.flags != 0) {
-      ImGui::Text("%02x", entry.flags);
+static void EmitValueTree(
+    const std::vector<NetworkTablesModel::EntryValueTreeNode>& children,
+    NetworkTablesFlags flags) {
+  for (auto&& child : children) {
+    ImGui::TableNextRow();
+    ImGui::TableNextColumn();
+    EmitValueName(child.source.get(), child.name.c_str(), child.path.c_str());
+    ImGui::TableNextColumn();
+    if (!child.valueChildren.empty()) {
+      char label[64];
+      std::snprintf(label, sizeof(label),
+                    child.valueChildrenMap ? "{...}##v_%s" : "[...]##v_%s",
+                    child.name.c_str());
+      if (TreeNodeEx(label, ImGuiTreeNodeFlags_SpanFullWidth)) {
+        EmitValueTree(child.valueChildren, flags);
+        TreePop();
+      }
+    } else {
+      EmitEntryValueReadonly(child, nullptr, flags);
     }
-    ImGui::NextColumn();
+  }
+}
+
+static void EmitEntry(NetworkTablesModel* model,
+                      NetworkTablesModel::Entry& entry, const char* name,
+                      NetworkTablesFlags flags, ShowCategory category) {
+  if (!IsVisible(category, entry.persistent, entry.retained)) {
+    return;
+  }
+
+  bool valueChildrenOpen = false;
+  ImGui::TableNextRow();
+  ImGui::TableNextColumn();
+  EmitValueName(entry.source.get(), name, entry.info.name.c_str());
+
+  ImGui::TableNextColumn();
+  if (!entry.valueChildren.empty()) {
+    auto pos = ImGui::GetCursorPos();
+    char label[64];
+    std::snprintf(label, sizeof(label),
+                  entry.valueChildrenMap ? "{...}##v_%s" : "[...]##v_%s",
+                  entry.info.name.c_str());
+    valueChildrenOpen =
+        TreeNodeEx(label, ImGuiTreeNodeFlags_SpanFullWidth |
+                              ImGuiTreeNodeFlags_AllowItemOverlap);
+    // make it look like a normal label w/type
+    ImGui::SetCursorPos(pos);
+    ImGui::LabelText(entry.info.type_str.c_str(), "%s", "");
+  } else if (flags & NetworkTablesFlags_ReadOnly) {
+    EmitEntryValueReadonly(
+        entry,
+        entry.info.type_str.empty() ? nullptr : entry.info.type_str.c_str(),
+        flags);
+  } else {
+    EmitEntryValueEditable(entry, flags);
+  }
+
+  if (flags & NetworkTablesFlags_ShowProperties) {
+    ImGui::TableNextColumn();
+    ImGui::Text("%s", entry.info.properties.c_str());
+    if (ImGui::BeginPopupContextItem(entry.info.name.c_str())) {
+      if (ImGui::Checkbox("persistent", &entry.persistent)) {
+        nt::SetTopicPersistent(entry.info.topic, entry.persistent);
+      }
+      if (ImGui::Checkbox("retained", &entry.retained)) {
+        if (entry.retained) {
+          nt::SetTopicProperty(entry.info.topic, "retained", true);
+        } else {
+          nt::DeleteTopicProperty(entry.info.topic, "retained");
+        }
+      }
+      ImGui::EndPopup();
+    }
   }
 
   if (flags & NetworkTablesFlags_ShowTimestamp) {
+    ImGui::TableNextColumn();
     if (entry.value) {
-      ImGui::Text("%f", (entry.value->last_change() * 1.0e-6) -
+      ImGui::Text("%f", (entry.value.last_change() * 1.0e-6) -
                             (GetZeroTime() * 1.0e-6));
     } else {
       ImGui::TextUnformatted("");
     }
-    ImGui::NextColumn();
   }
-  ImGui::Separator();
+
+  if (flags & NetworkTablesFlags_ShowServerTimestamp) {
+    ImGui::TableNextColumn();
+    if (entry.value && entry.value.server_time() != 0) {
+      if (entry.value.server_time() == 1) {
+        ImGui::TextUnformatted("---");
+      } else {
+        ImGui::Text("%f", entry.value.server_time() * 1.0e-6);
+      }
+    } else {
+      ImGui::TextUnformatted("");
+    }
+  }
+
+  if (valueChildrenOpen) {
+    EmitValueTree(entry.valueChildren, flags);
+    TreePop();
+  }
 }
 
-static void EmitTree(const std::vector<NetworkTablesModel::TreeNode>& tree,
-                     NetworkTablesFlags flags) {
+static void EmitTree(NetworkTablesModel* model,
+                     const std::vector<NetworkTablesModel::TreeNode>& tree,
+                     NetworkTablesFlags flags, ShowCategory category,
+                     bool root) {
   for (auto&& node : tree) {
+    if (root && (flags & NetworkTablesFlags_ShowSpecial) == 0 &&
+        wpi::starts_with(node.name, '$')) {
+      continue;
+    }
     if (node.entry) {
-      EmitEntry(*node.entry, node.name.c_str(), flags);
+      EmitEntry(model, *node.entry, node.name.c_str(), flags, category);
     }
 
     if (!node.children.empty()) {
+      ImGui::TableNextRow();
+      ImGui::TableNextColumn();
       bool open =
           TreeNodeEx(node.name.c_str(), ImGuiTreeNodeFlags_SpanFullWidth);
-      EmitParentContextMenu(node.path, flags);
-      ImGui::NextColumn();
-      ImGui::NextColumn();
-      if (flags & NetworkTablesFlags_ShowFlags) {
-        ImGui::NextColumn();
-      }
-      if (flags & NetworkTablesFlags_ShowTimestamp) {
-        ImGui::NextColumn();
-      }
-      ImGui::Separator();
+      EmitParentContextMenu(model, node.path, flags);
       if (open) {
-        EmitTree(node.children, flags);
+        EmitTree(model, node.children, flags, category, false);
         TreePop();
       }
     }
   }
 }
 
-void glass::DisplayNetworkTables(NetworkTablesModel* model,
-                                 NetworkTablesFlags flags) {
-  auto inst = model->GetInstance();
-
-  if (flags & NetworkTablesFlags_ShowConnections) {
-    if (CollapsingHeader("Connections")) {
-      ImGui::Columns(4, "connections");
-      ImGui::Text("Id");
-      ImGui::NextColumn();
-      ImGui::Text("Address");
-      ImGui::NextColumn();
-      ImGui::Text("Updated");
-      ImGui::NextColumn();
-      ImGui::Text("Proto");
-      ImGui::NextColumn();
-      ImGui::Separator();
-      for (auto&& i : nt::GetConnections(inst)) {
-        ImGui::Text("%s", i.remote_id.c_str());
-        ImGui::NextColumn();
-        ImGui::Text("%s", i.remote_ip.c_str());
-        ImGui::NextColumn();
-        ImGui::Text("%llu",
-                    static_cast<unsigned long long>(  // NOLINT(runtime/int)
-                        i.last_update));
-        ImGui::NextColumn();
-        ImGui::Text("%d.%d", i.protocol_version >> 8,
-                    i.protocol_version & 0xff);
-        ImGui::NextColumn();
-      }
-      ImGui::Columns();
-    }
-
-    if (!CollapsingHeader("Values", ImGuiTreeNodeFlags_DefaultOpen)) {
-      return;
-    }
+static void DisplayTable(NetworkTablesModel* model,
+                         const std::vector<NetworkTablesModel::TreeNode>& tree,
+                         NetworkTablesFlags flags, ShowCategory category) {
+  if (tree.empty()) {
+    return;
   }
 
-  const bool showFlags = (flags & NetworkTablesFlags_ShowFlags);
+  const bool showProperties = (flags & NetworkTablesFlags_ShowProperties);
   const bool showTimestamp = (flags & NetworkTablesFlags_ShowTimestamp);
+  const bool showServerTimestamp =
+      (flags & NetworkTablesFlags_ShowServerTimestamp);
 
-  static bool first = true;
-  ImGui::Columns(2 + (showFlags ? 1 : 0) + (showTimestamp ? 1 : 0), "values");
-  if (first) {
-    ImGui::SetColumnWidth(-1, 0.5f * ImGui::GetWindowWidth());
-  }
-  ImGui::Text("Name");
-  EmitParentContextMenu("/", flags);
-  ImGui::NextColumn();
-  ImGui::Text("Value");
-  ImGui::NextColumn();
-  if (showFlags) {
-    if (first) {
-      ImGui::SetColumnWidth(-1, 12 * ImGui::GetFontSize());
-    }
-    ImGui::Text("Flags");
-    ImGui::NextColumn();
+  ImGui::BeginTable("values",
+                    2 + (showProperties ? 1 : 0) + (showTimestamp ? 1 : 0) +
+                        (showServerTimestamp ? 1 : 0),
+                    ImGuiTableFlags_Resizable | ImGuiTableFlags_SizingFixedFit |
+                        ImGuiTableFlags_BordersInner);
+  ImGui::TableSetupColumn("Name", ImGuiTableColumnFlags_WidthFixed,
+                          0.35f * ImGui::GetWindowWidth());
+  ImGui::TableSetupColumn("Value", ImGuiTableColumnFlags_WidthFixed,
+                          12 * ImGui::GetFontSize());
+  if (showProperties) {
+    ImGui::TableSetupColumn("Properties", ImGuiTableColumnFlags_WidthFixed,
+                            12 * ImGui::GetFontSize());
   }
   if (showTimestamp) {
-    ImGui::Text("Changed");
-    ImGui::NextColumn();
+    ImGui::TableSetupColumn("Time");
   }
-  ImGui::Separator();
-  first = false;
+  if (showServerTimestamp) {
+    ImGui::TableSetupColumn("Server Time");
+  }
+  ImGui::TableHeadersRow();
 
+  // EmitParentContextMenu(model, "/", flags);
   if (flags & NetworkTablesFlags_TreeView) {
-    EmitTree(model->GetTreeRoot(), flags);
+    switch (category) {
+      case ShowPersistent:
+        PushID("persistent");
+        break;
+      case ShowRetained:
+        PushID("retained");
+        break;
+      case ShowTransitory:
+        PushID("transitory");
+        break;
+      default:
+        break;
+    }
+    EmitTree(model, tree, flags, category, true);
+    if (category != ShowAll) {
+      PopID();
+    }
   } else {
     for (auto entry : model->GetEntries()) {
-      EmitEntry(*entry, entry->name.c_str(), flags);
+      if ((flags & NetworkTablesFlags_ShowSpecial) != 0 ||
+          !wpi::starts_with(entry->info.name, '$')) {
+        EmitEntry(model, *entry, entry->info.name.c_str(), flags, category);
+      }
     }
   }
-  ImGui::Columns();
+  ImGui::EndTable();
+}
+
+static void DisplayClient(const NetworkTablesModel::Client& client) {
+  if (CollapsingHeader("Publishers")) {
+    ImGui::BeginTable("publishers", 2, ImGuiTableFlags_Resizable);
+    ImGui::TableSetupColumn("UID", ImGuiTableColumnFlags_WidthFixed,
+                            10 * ImGui::GetFontSize());
+    ImGui::TableSetupColumn("Topic");
+    ImGui::TableHeadersRow();
+    for (auto&& pub : client.publishers) {
+      ImGui::TableNextRow();
+      ImGui::TableNextColumn();
+      ImGui::Text("%" PRId64, pub.uid);
+      ImGui::TableNextColumn();
+      ImGui::Text("%s", pub.topic.c_str());
+    }
+    ImGui::EndTable();
+  }
+  if (CollapsingHeader("Subscribers")) {
+    ImGui::BeginTable(
+        "subscribers", 6,
+        ImGuiTableFlags_Resizable | ImGuiTableFlags_SizingStretchProp);
+    ImGui::TableSetupColumn("UID", ImGuiTableColumnFlags_WidthFixed,
+                            10 * ImGui::GetFontSize());
+    ImGui::TableSetupColumn("Topics", ImGuiTableColumnFlags_WidthStretch, 6.0f);
+    ImGui::TableSetupColumn("Periodic", ImGuiTableColumnFlags_WidthStretch,
+                            1.0f);
+    ImGui::TableSetupColumn("Topics Only", ImGuiTableColumnFlags_WidthStretch,
+                            1.0f);
+    ImGui::TableSetupColumn("Send All", ImGuiTableColumnFlags_WidthStretch,
+                            1.0f);
+    ImGui::TableSetupColumn("Prefix Match", ImGuiTableColumnFlags_WidthStretch,
+                            1.0f);
+    ImGui::TableHeadersRow();
+    for (auto&& sub : client.subscribers) {
+      ImGui::TableNextRow();
+      ImGui::TableNextColumn();
+      ImGui::Text("%" PRId64, sub.uid);
+      ImGui::TableNextColumn();
+      ImGui::Text("%s", sub.topicsStr.c_str());
+      ImGui::TableNextColumn();
+      ImGui::Text("%0.3f", sub.options.periodic);
+      ImGui::TableNextColumn();
+      ImGui::Text(sub.options.topicsOnly ? "Yes" : "No");
+      ImGui::TableNextColumn();
+      ImGui::Text(sub.options.sendAll ? "Yes" : "No");
+      ImGui::TableNextColumn();
+      ImGui::Text(sub.options.prefixMatch ? "Yes" : "No");
+    }
+    ImGui::EndTable();
+  }
+}
+
+void glass::DisplayNetworkTablesInfo(NetworkTablesModel* model) {
+  auto inst = model->GetInstance();
+
+  if (CollapsingHeader("Connections")) {
+    ImGui::BeginTable("connections", 4, ImGuiTableFlags_Resizable);
+    ImGui::TableSetupColumn("Id");
+    ImGui::TableSetupColumn("Address");
+    ImGui::TableSetupColumn("Updated");
+    ImGui::TableSetupColumn("Proto");
+    ImGui::TableSetupScrollFreeze(1, 0);
+    ImGui::TableHeadersRow();
+    for (auto&& i : inst.GetConnections()) {
+      ImGui::TableNextRow();
+      ImGui::TableNextColumn();
+      ImGui::Text("%s", i.remote_id.c_str());
+      ImGui::TableNextColumn();
+      ImGui::Text("%s", i.remote_ip.c_str());
+      ImGui::TableNextColumn();
+      ImGui::Text("%llu",
+                  static_cast<unsigned long long>(  // NOLINT(runtime/int)
+                      i.last_update));
+      ImGui::TableNextColumn();
+      ImGui::Text("%d.%d", i.protocol_version >> 8, i.protocol_version & 0xff);
+    }
+    ImGui::EndTable();
+  }
+
+  auto netMode = inst.GetNetworkMode();
+  if (netMode == NT_NET_MODE_SERVER || netMode == NT_NET_MODE_CLIENT4) {
+    if (CollapsingHeader("Server")) {
+      PushID("Server");
+      ImGui::Indent();
+      DisplayClient(model->GetServer());
+      ImGui::Unindent();
+      PopID();
+    }
+    if (CollapsingHeader("Clients")) {
+      ImGui::Indent();
+      for (auto&& client : model->GetClients()) {
+        if (CollapsingHeader(client.second.id.c_str())) {
+          PushID(client.second.id.c_str());
+          ImGui::Indent();
+          ImGui::Text("%s (version %u.%u)", client.second.conn.c_str(),
+                      client.second.version >> 8, client.second.version & 0xff);
+          DisplayClient(client.second);
+          ImGui::Unindent();
+          PopID();
+        }
+      }
+      ImGui::Unindent();
+    }
+  }
+}
+
+void glass::DisplayNetworkTables(NetworkTablesModel* model,
+                                 NetworkTablesFlags flags) {
+  if (flags & NetworkTablesFlags_CombinedView) {
+    DisplayTable(model, model->GetTreeRoot(), flags, ShowAll);
+  } else {
+    if (CollapsingHeader("Persistent Values", ImGuiTreeNodeFlags_DefaultOpen)) {
+      DisplayTable(model, model->GetPersistentTreeRoot(), flags,
+                   ShowPersistent);
+    }
+
+    if (CollapsingHeader("Retained Values", ImGuiTreeNodeFlags_DefaultOpen)) {
+      DisplayTable(model, model->GetRetainedTreeRoot(), flags, ShowRetained);
+    }
+
+    if (CollapsingHeader("Transitory Values", ImGuiTreeNodeFlags_DefaultOpen)) {
+      DisplayTable(model, model->GetTransitoryTreeRoot(), flags,
+                   ShowTransitory);
+    }
+  }
 }
 
 void NetworkTablesFlagsSettings::Update() {
@@ -734,28 +1441,41 @@
     auto& storage = GetStorage();
     m_pTreeView =
         &storage.GetBool("tree", m_defaultFlags & NetworkTablesFlags_TreeView);
-    m_pShowConnections = &storage.GetBool(
-        "connections", m_defaultFlags & NetworkTablesFlags_ShowConnections);
-    m_pShowFlags = &storage.GetBool(
-        "flags", m_defaultFlags & NetworkTablesFlags_ShowFlags);
+    m_pCombinedView = &storage.GetBool(
+        "combined", m_defaultFlags & NetworkTablesFlags_CombinedView);
+    m_pShowSpecial = &storage.GetBool(
+        "special", m_defaultFlags & NetworkTablesFlags_ShowSpecial);
+    m_pShowProperties = &storage.GetBool(
+        "properties", m_defaultFlags & NetworkTablesFlags_ShowProperties);
     m_pShowTimestamp = &storage.GetBool(
         "timestamp", m_defaultFlags & NetworkTablesFlags_ShowTimestamp);
+    m_pShowServerTimestamp = &storage.GetBool(
+        "serverTimestamp",
+        m_defaultFlags & NetworkTablesFlags_ShowServerTimestamp);
     m_pCreateNoncanonicalKeys = &storage.GetBool(
         "createNonCanonical",
         m_defaultFlags & NetworkTablesFlags_CreateNoncanonicalKeys);
+    m_pPrecision = &storage.GetInt(
+        "precision", (m_defaultFlags & NetworkTablesFlags_Precision) >>
+                         kNetworkTablesFlags_PrecisionBitShift);
   }
 
-  m_flags &=
-      ~(NetworkTablesFlags_TreeView | NetworkTablesFlags_ShowConnections |
-        NetworkTablesFlags_ShowFlags | NetworkTablesFlags_ShowTimestamp |
-        NetworkTablesFlags_CreateNoncanonicalKeys);
+  m_flags &= ~(
+      NetworkTablesFlags_TreeView | NetworkTablesFlags_CombinedView |
+      NetworkTablesFlags_ShowSpecial | NetworkTablesFlags_ShowProperties |
+      NetworkTablesFlags_ShowTimestamp |
+      NetworkTablesFlags_ShowServerTimestamp |
+      NetworkTablesFlags_CreateNoncanonicalKeys | NetworkTablesFlags_Precision);
   m_flags |=
       (*m_pTreeView ? NetworkTablesFlags_TreeView : 0) |
-      (*m_pShowConnections ? NetworkTablesFlags_ShowConnections : 0) |
-      (*m_pShowFlags ? NetworkTablesFlags_ShowFlags : 0) |
+      (*m_pCombinedView ? NetworkTablesFlags_CombinedView : 0) |
+      (*m_pShowSpecial ? NetworkTablesFlags_ShowSpecial : 0) |
+      (*m_pShowProperties ? NetworkTablesFlags_ShowProperties : 0) |
       (*m_pShowTimestamp ? NetworkTablesFlags_ShowTimestamp : 0) |
+      (*m_pShowServerTimestamp ? NetworkTablesFlags_ShowServerTimestamp : 0) |
       (*m_pCreateNoncanonicalKeys ? NetworkTablesFlags_CreateNoncanonicalKeys
-                                  : 0);
+                                  : 0) |
+      (*m_pPrecision << kNetworkTablesFlags_PrecisionBitShift);
 }
 
 void NetworkTablesFlagsSettings::DisplayMenu() {
@@ -763,9 +1483,22 @@
     return;
   }
   ImGui::MenuItem("Tree View", "", m_pTreeView);
-  ImGui::MenuItem("Show Connections", "", m_pShowConnections);
-  ImGui::MenuItem("Show Flags", "", m_pShowFlags);
+  ImGui::MenuItem("Combined View", "", m_pCombinedView);
+  ImGui::MenuItem("Show Special", "", m_pShowSpecial);
+  ImGui::MenuItem("Show Properties", "", m_pShowProperties);
   ImGui::MenuItem("Show Timestamp", "", m_pShowTimestamp);
+  ImGui::MenuItem("Show Server Timestamp", "", m_pShowServerTimestamp);
+  if (ImGui::BeginMenu("Decimal Precision")) {
+    static const char* precisionOptions[] = {"1", "2", "3", "4", "5",
+                                             "6", "7", "8", "9", "10"};
+    for (int i = 1; i <= 10; i++) {
+      if (ImGui::MenuItem(precisionOptions[i - 1], nullptr,
+                          i == *m_pPrecision)) {
+        *m_pPrecision = i;
+      }
+    }
+    ImGui::EndMenu();
+  }
   ImGui::Separator();
   ImGui::MenuItem("Allow creation of non-canonical keys", "",
                   m_pCreateNoncanonicalKeys);
@@ -773,9 +1506,13 @@
 
 void NetworkTablesView::Display() {
   m_flags.Update();
-  if (ImGui::BeginPopupContextItem()) {
-    m_flags.DisplayMenu();
-    ImGui::EndPopup();
-  }
   DisplayNetworkTables(m_model, m_flags.GetFlags());
 }
+
+void NetworkTablesView::Settings() {
+  m_flags.DisplayMenu();
+}
+
+bool NetworkTablesView::HasSettings() {
+  return true;
+}
diff --git a/third_party/allwpilib/glass/src/libnt/native/cpp/NetworkTablesHelper.cpp b/third_party/allwpilib/glass/src/libnt/native/cpp/NetworkTablesHelper.cpp
deleted file mode 100644
index 5cb5bbc..0000000
--- a/third_party/allwpilib/glass/src/libnt/native/cpp/NetworkTablesHelper.cpp
+++ /dev/null
@@ -1,19 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "glass/networktables/NetworkTablesHelper.h"
-
-using namespace glass;
-
-NetworkTablesHelper::NetworkTablesHelper(NT_Inst inst)
-    : m_inst{inst}, m_poller{nt::CreateEntryListenerPoller(inst)} {}
-
-NetworkTablesHelper::~NetworkTablesHelper() {
-  nt::DestroyEntryListenerPoller(m_poller);
-}
-
-bool NetworkTablesHelper::IsConnected() const {
-  return nt::GetNetworkMode(m_inst) == NT_NET_MODE_SERVER ||
-         nt::IsConnected(m_inst);
-}
diff --git a/third_party/allwpilib/glass/src/libnt/native/cpp/NetworkTablesProvider.cpp b/third_party/allwpilib/glass/src/libnt/native/cpp/NetworkTablesProvider.cpp
index 9ccbb2e..413899e 100644
--- a/third_party/allwpilib/glass/src/libnt/native/cpp/NetworkTablesProvider.cpp
+++ b/third_party/allwpilib/glass/src/libnt/native/cpp/NetworkTablesProvider.cpp
@@ -17,16 +17,16 @@
 using namespace glass;
 
 NetworkTablesProvider::NetworkTablesProvider(Storage& storage)
-    : NetworkTablesProvider{storage, nt::GetDefaultInstance()} {}
+    : NetworkTablesProvider{storage, nt::NetworkTableInstance::GetDefault()} {}
 
-NetworkTablesProvider::NetworkTablesProvider(Storage& storage, NT_Inst inst)
+NetworkTablesProvider::NetworkTablesProvider(Storage& storage,
+                                             nt::NetworkTableInstance inst)
     : Provider{storage.GetChild("windows")},
-      m_nt{inst},
+      m_inst{inst},
+      m_poller{inst},
       m_typeCache{storage.GetChild("types")} {
   storage.SetCustomApply([this] {
-    m_listener =
-        m_nt.AddListener("", NT_NOTIFY_LOCAL | NT_NOTIFY_NEW |
-                                 NT_NOTIFY_DELETE | NT_NOTIFY_IMMEDIATE);
+    m_listener = m_poller.AddListener({{""}}, nt::EventFlags::kTopic);
     for (auto&& childIt : m_storage.GetChildren()) {
       auto id = childIt.key();
       auto typePtr = m_typeCache.FindValue(id);
@@ -41,15 +41,14 @@
       }
 
       auto entry = GetOrCreateView(
-          builderIt->second,
-          nt::GetEntry(m_nt.GetInstance(), fmt::format("{}/.type", id)), id);
+          builderIt->second, m_inst.GetTopic(fmt::format("{}/.type", id)), id);
       if (entry) {
         Show(entry, nullptr);
       }
     }
   });
   storage.SetCustomClear([this, &storage] {
-    nt::RemoveEntryListener(m_listener);
+    m_poller.RemoveListener(m_listener);
     m_listener = 0;
     for (auto&& modelEntry : m_modelEntries) {
       modelEntry->model.reset();
@@ -100,35 +99,58 @@
 void NetworkTablesProvider::Update() {
   Provider::Update();
 
-  // add/remove entries from NT changes
-  for (auto&& event : m_nt.PollListener()) {
-    // look for .type fields
-    std::string_view eventName{event.name};
-    if (!wpi::ends_with(eventName, "/.type") || !event.value ||
-        !event.value->IsString()) {
-      continue;
-    }
-    auto tableName = wpi::drop_back(eventName, 6);
-
-    // only handle ones where we have a builder
-    auto builderIt = m_typeMap.find(event.value->GetString());
-    if (builderIt == m_typeMap.end()) {
-      continue;
-    }
-
-    if (event.flags & NT_NOTIFY_DELETE) {
-      auto it = std::find_if(
-          m_viewEntries.begin(), m_viewEntries.end(), [&](const auto& elem) {
-            return static_cast<Entry*>(elem->modelEntry)->typeEntry ==
-                   event.entry;
-          });
-      if (it != m_viewEntries.end()) {
-        m_viewEntries.erase(it);
+  for (auto&& event : m_poller.ReadQueue()) {
+    if (auto info = event.GetTopicInfo()) {
+      // add/remove entries from NT changes
+      // look for .type fields
+      if (!wpi::ends_with(info->name, "/.type") || info->type != NT_STRING ||
+          info->type_str != "string") {
+        continue;
       }
-    } else if (event.flags & NT_NOTIFY_NEW) {
-      GetOrCreateView(builderIt->second, event.entry, tableName);
+
+      if (event.flags & nt::EventFlags::kUnpublish) {
+        auto it = m_topicMap.find(info->topic);
+        if (it != m_topicMap.end()) {
+          m_poller.RemoveListener(it->second.listener);
+          m_topicMap.erase(it);
+        }
+
+        auto it2 = std::find_if(
+            m_viewEntries.begin(), m_viewEntries.end(), [&](const auto& elem) {
+              return static_cast<Entry*>(elem->modelEntry)
+                         ->typeTopic.GetHandle() == info->topic;
+            });
+        if (it2 != m_viewEntries.end()) {
+          m_viewEntries.erase(it2);
+        }
+      } else if (event.flags & nt::EventFlags::kPublish) {
+        // subscribe to it; use a subscriber so we only get string values
+        SubListener sublistener;
+        sublistener.subscriber = nt::StringTopic{info->topic}.Subscribe("");
+        sublistener.listener = m_poller.AddListener(
+            sublistener.subscriber,
+            nt::EventFlags::kValueAll | nt::EventFlags::kImmediate);
+        m_topicMap.try_emplace(info->topic, std::move(sublistener));
+      }
+    } else if (auto valueData = event.GetValueEventData()) {
+      // handle actual .type strings
+      if (!valueData->value.IsString()) {
+        continue;
+      }
+
+      // only handle ones where we have a builder
+      auto builderIt = m_typeMap.find(valueData->value.GetString());
+      if (builderIt == m_typeMap.end()) {
+        continue;
+      }
+
+      auto topicName = nt::GetTopicName(valueData->topic);
+      auto tableName = wpi::drop_back(topicName, 6);
+
+      GetOrCreateView(builderIt->second, nt::Topic{valueData->topic},
+                      tableName);
       // cache the type
-      m_typeCache.SetString(tableName, event.value->GetString());
+      m_typeCache.SetString(tableName, valueData->value.GetString());
     }
   }
 }
@@ -149,7 +171,7 @@
   // get or create model
   if (!entry->modelEntry->model) {
     entry->modelEntry->model =
-        entry->modelEntry->createModel(m_nt.GetInstance(), entry->name.c_str());
+        entry->modelEntry->createModel(m_inst, entry->name.c_str());
   }
   if (!entry->modelEntry->model) {
     return;
@@ -180,22 +202,22 @@
 }
 
 NetworkTablesProvider::ViewEntry* NetworkTablesProvider::GetOrCreateView(
-    const Builder& builder, NT_Entry typeEntry, std::string_view name) {
+    const Builder& builder, nt::Topic typeTopic, std::string_view name) {
   // get view entry if it already exists
   auto viewIt = FindViewEntry(name);
   if (viewIt != m_viewEntries.end() && (*viewIt)->name == name) {
     // make sure typeEntry is set in model
-    static_cast<Entry*>((*viewIt)->modelEntry)->typeEntry = typeEntry;
+    static_cast<Entry*>((*viewIt)->modelEntry)->typeTopic = typeTopic;
     return viewIt->get();
   }
 
   // get or create model entry
   auto modelIt = FindModelEntry(name);
   if (modelIt != m_modelEntries.end() && (*modelIt)->name == name) {
-    static_cast<Entry*>(modelIt->get())->typeEntry = typeEntry;
+    static_cast<Entry*>(modelIt->get())->typeTopic = typeTopic;
   } else {
     modelIt = m_modelEntries.emplace(
-        modelIt, std::make_unique<Entry>(typeEntry, name, builder));
+        modelIt, std::make_unique<Entry>(typeTopic, name, builder));
   }
 
   // create new view entry
diff --git a/third_party/allwpilib/glass/src/libnt/native/cpp/NetworkTablesSettings.cpp b/third_party/allwpilib/glass/src/libnt/native/cpp/NetworkTablesSettings.cpp
index d1fb341..fd6bd52 100644
--- a/third_party/allwpilib/glass/src/libnt/native/cpp/NetworkTablesSettings.cpp
+++ b/third_party/allwpilib/glass/src/libnt/native/cpp/NetworkTablesSettings.cpp
@@ -43,50 +43,66 @@
 
       // if just changing servers in client mode, no need to stop and restart
       unsigned int curMode = nt::GetNetworkMode(m_inst);
-      if (mode != 1 || (curMode & NT_NET_MODE_SERVER) != 0) {
+      if ((mode == 0 || mode == 3) ||
+          (mode == 1 && (curMode & NT_NET_MODE_CLIENT4) == 0) ||
+          (mode == 2 && (curMode & NT_NET_MODE_CLIENT3) == 0)) {
         nt::StopClient(m_inst);
         nt::StopServer(m_inst);
         nt::StopLocal(m_inst);
       }
 
-      if (m_mode != 1 || !dsClient) {
+      if ((m_mode == 0 || m_mode == 3) || !dsClient) {
         nt::StopDSClient(m_inst);
       }
 
       lock.lock();
     } while (mode != m_mode || dsClient != m_dsClient);
 
-    if (m_mode == 1) {
+    if (m_mode == 1 || m_mode == 2) {
       std::string_view serverTeam{m_serverTeam};
       std::optional<unsigned int> team;
+      if (m_mode == 1) {
+        nt::StartClient4(m_inst, m_clientName);
+      } else if (m_mode == 2) {
+        nt::StartClient3(m_inst, m_clientName);
+      }
+
+      unsigned int port = m_mode == 1 ? m_port4 : m_port3;
       if (!wpi::contains(serverTeam, '.') &&
           (team = wpi::parse_integer<unsigned int>(serverTeam, 10))) {
-        nt::StartClientTeam(m_inst, team.value(), NT_DEFAULT_PORT);
+        nt::SetServerTeam(m_inst, team.value(), port);
       } else {
         wpi::SmallVector<std::string_view, 4> serverNames;
-        wpi::SmallVector<std::pair<std::string_view, unsigned int>, 4> servers;
+        std::vector<std::pair<std::string_view, unsigned int>> servers;
         wpi::split(serverTeam, serverNames, ',', -1, false);
         for (auto&& serverName : serverNames) {
-          servers.emplace_back(serverName, NT_DEFAULT_PORT);
+          servers.emplace_back(serverName, port);
         }
-        nt::StartClient(m_inst, servers);
+        nt::SetServer(m_inst, servers);
       }
 
       if (m_dsClient) {
-        nt::StartDSClient(m_inst, NT_DEFAULT_PORT);
+        nt::StartDSClient(m_inst, port);
       }
-    } else if (m_mode == 2) {
+    } else if (m_mode == 3) {
       nt::StartServer(m_inst, m_iniName.c_str(), m_listenAddress.c_str(),
-                      NT_DEFAULT_PORT);
+                      m_port3, m_port4);
     }
   }
 }
 
-NetworkTablesSettings::NetworkTablesSettings(Storage& storage, NT_Inst inst)
-    : m_mode{storage.GetString("mode"), 0, {"Disabled", "Client", "Server"}},
-      m_iniName{storage.GetString("iniName", "networktables.ini")},
+NetworkTablesSettings::NetworkTablesSettings(std::string_view clientName,
+                                             Storage& storage, NT_Inst inst)
+    : m_mode{storage.GetString("mode"),
+             0,
+             {"Disabled", "Client (NT4)", "Client (NT3)", "Server"}},
+      m_persistentFilename{
+          storage.GetString("persistentFilename", "networktables.json")},
       m_serverTeam{storage.GetString("serverTeam")},
       m_listenAddress{storage.GetString("listenAddress")},
+      m_clientName{storage.GetString("clientName", clientName)},
+      m_port3{storage.GetInt("port3", NT_DEFAULT_PORT3)},
+      m_port4{storage.GetInt("port4", NT_DEFAULT_PORT4)},
       m_dsClient{storage.GetBool("dsClient", true)} {
   m_thread.Start(inst);
 }
@@ -101,23 +117,59 @@
   auto thr = m_thread.GetThread();
   thr->m_restart = true;
   thr->m_mode = m_mode.GetValue();
-  thr->m_iniName = m_iniName;
+  thr->m_iniName = m_persistentFilename;
   thr->m_serverTeam = m_serverTeam;
   thr->m_listenAddress = m_listenAddress;
+  thr->m_clientName = m_clientName;
+  thr->m_port3 = m_port3;
+  thr->m_port4 = m_port4;
   thr->m_dsClient = m_dsClient;
   thr->m_cond.notify_one();
 }
 
+static void LimitPortRange(int* port) {
+  if (*port < 0) {
+    *port = 0;
+  } else if (*port > 65535) {
+    *port = 65535;
+  }
+}
+
 bool NetworkTablesSettings::Display() {
-  m_mode.Combo("Mode", m_serverOption ? 3 : 2);
+  m_mode.Combo("Mode", m_serverOption ? 4 : 3);
   switch (m_mode.GetValue()) {
     case 1:
+    case 2: {
       ImGui::InputText("Team/IP", &m_serverTeam);
+      int* port = m_mode.GetValue() == 1 ? &m_port4 : &m_port3;
+      if (ImGui::InputInt("Port", port)) {
+        LimitPortRange(port);
+      }
+      ImGui::SameLine();
+      if (ImGui::SmallButton("Default")) {
+        *port = m_mode.GetValue() == 1 ? NT_DEFAULT_PORT4 : NT_DEFAULT_PORT3;
+      }
+      ImGui::InputText("Network Identity", &m_clientName);
       ImGui::Checkbox("Get Address from DS", &m_dsClient);
       break;
-    case 2:
+    }
+    case 3:
       ImGui::InputText("Listen Address", &m_listenAddress);
-      ImGui::InputText("ini Filename", &m_iniName);
+      if (ImGui::InputInt("NT3 port", &m_port3)) {
+        LimitPortRange(&m_port3);
+      }
+      ImGui::SameLine();
+      if (ImGui::SmallButton("Default##default3")) {
+        m_port3 = NT_DEFAULT_PORT3;
+      }
+      if (ImGui::InputInt("NT4 port", &m_port4)) {
+        LimitPortRange(&m_port4);
+      }
+      ImGui::SameLine();
+      if (ImGui::SmallButton("Default##default4")) {
+        m_port4 = NT_DEFAULT_PORT4;
+      }
+      ImGui::InputText("Persistent Filename", &m_persistentFilename);
       break;
     default:
       break;
diff --git a/third_party/allwpilib/glass/src/libnt/native/cpp/StandardNetworkTables.cpp b/third_party/allwpilib/glass/src/libnt/native/cpp/StandardNetworkTables.cpp
index 0a5f234..ef61025 100644
--- a/third_party/allwpilib/glass/src/libnt/native/cpp/StandardNetworkTables.cpp
+++ b/third_party/allwpilib/glass/src/libnt/native/cpp/StandardNetworkTables.cpp
@@ -12,8 +12,8 @@
 #include "glass/networktables/NTGyro.h"
 #include "glass/networktables/NTMecanumDrive.h"
 #include "glass/networktables/NTMechanism2D.h"
+#include "glass/networktables/NTMotorController.h"
 #include "glass/networktables/NTPIDController.h"
-#include "glass/networktables/NTSpeedController.h"
 #include "glass/networktables/NTStringChooser.h"
 #include "glass/networktables/NTSubsystem.h"
 #include "glass/networktables/NetworkTablesProvider.h"
@@ -23,7 +23,7 @@
 void glass::AddStandardNetworkTablesViews(NetworkTablesProvider& provider) {
   provider.Register(
       NTCommandSchedulerModel::kType,
-      [](NT_Inst inst, const char* path) {
+      [](nt::NetworkTableInstance inst, const char* path) {
         return std::make_unique<NTCommandSchedulerModel>(inst, path);
       },
       [](Window* win, Model* model, const char*) {
@@ -34,7 +34,7 @@
       });
   provider.Register(
       NTCommandSelectorModel::kType,
-      [](NT_Inst inst, const char* path) {
+      [](nt::NetworkTableInstance inst, const char* path) {
         return std::make_unique<NTCommandSelectorModel>(inst, path);
       },
       [](Window* win, Model* model, const char*) {
@@ -45,7 +45,7 @@
       });
   provider.Register(
       NTDifferentialDriveModel::kType,
-      [](NT_Inst inst, const char* path) {
+      [](nt::NetworkTableInstance inst, const char* path) {
         return std::make_unique<NTDifferentialDriveModel>(inst, path);
       },
       [](Window* win, Model* model, const char*) {
@@ -56,7 +56,7 @@
       });
   provider.Register(
       NTFMSModel::kType,
-      [](NT_Inst inst, const char* path) {
+      [](nt::NetworkTableInstance inst, const char* path) {
         return std::make_unique<NTFMSModel>(inst, path);
       },
       [](Window* win, Model* model, const char*) {
@@ -66,7 +66,7 @@
       });
   provider.Register(
       NTDigitalInputModel::kType,
-      [](NT_Inst inst, const char* path) {
+      [](nt::NetworkTableInstance inst, const char* path) {
         return std::make_unique<NTDigitalInputModel>(inst, path);
       },
       [](Window* win, Model* model, const char*) {
@@ -77,7 +77,7 @@
       });
   provider.Register(
       NTDigitalOutputModel::kType,
-      [](NT_Inst inst, const char* path) {
+      [](nt::NetworkTableInstance inst, const char* path) {
         return std::make_unique<NTDigitalOutputModel>(inst, path);
       },
       [](Window* win, Model* model, const char*) {
@@ -88,7 +88,7 @@
       });
   provider.Register(
       NTField2DModel::kType,
-      [](NT_Inst inst, const char* path) {
+      [](nt::NetworkTableInstance inst, const char* path) {
         return std::make_unique<NTField2DModel>(inst, path);
       },
       [=](Window* win, Model* model, const char* path) {
@@ -100,7 +100,7 @@
       });
   provider.Register(
       NTGyroModel::kType,
-      [](NT_Inst inst, const char* path) {
+      [](nt::NetworkTableInstance inst, const char* path) {
         return std::make_unique<NTGyroModel>(inst, path);
       },
       [](Window* win, Model* model, const char* path) {
@@ -110,7 +110,7 @@
       });
   provider.Register(
       NTMecanumDriveModel::kType,
-      [](NT_Inst inst, const char* path) {
+      [](nt::NetworkTableInstance inst, const char* path) {
         return std::make_unique<NTMecanumDriveModel>(inst, path);
       },
       [](Window* win, Model* model, const char*) {
@@ -120,7 +120,7 @@
       });
   provider.Register(
       NTMechanism2DModel::kType,
-      [](NT_Inst inst, const char* path) {
+      [](nt::NetworkTableInstance inst, const char* path) {
         return std::make_unique<NTMechanism2DModel>(inst, path);
       },
       [=](Window* win, Model* model, const char* path) {
@@ -132,7 +132,7 @@
       });
   provider.Register(
       NTPIDControllerModel::kType,
-      [](NT_Inst inst, const char* path) {
+      [](nt::NetworkTableInstance inst, const char* path) {
         return std::make_unique<NTPIDControllerModel>(inst, path);
       },
       [](Window* win, Model* model, const char* path) {
@@ -142,19 +142,19 @@
         });
       });
   provider.Register(
-      NTSpeedControllerModel::kType,
-      [](NT_Inst inst, const char* path) {
-        return std::make_unique<NTSpeedControllerModel>(inst, path);
+      NTMotorControllerModel::kType,
+      [](nt::NetworkTableInstance inst, const char* path) {
+        return std::make_unique<NTMotorControllerModel>(inst, path);
       },
       [](Window* win, Model* model, const char* path) {
         win->SetFlags(ImGuiWindowFlags_AlwaysAutoResize);
         return MakeFunctionView([=] {
-          DisplaySpeedController(static_cast<NTSpeedControllerModel*>(model));
+          DisplayMotorController(static_cast<NTMotorControllerModel*>(model));
         });
       });
   provider.Register(
       NTStringChooserModel::kType,
-      [](NT_Inst inst, const char* path) {
+      [](nt::NetworkTableInstance inst, const char* path) {
         return std::make_unique<NTStringChooserModel>(inst, path);
       },
       [](Window* win, Model* model, const char*) {
@@ -165,7 +165,7 @@
       });
   provider.Register(
       NTSubsystemModel::kType,
-      [](NT_Inst inst, const char* path) {
+      [](nt::NetworkTableInstance inst, const char* path) {
         return std::make_unique<NTSubsystemModel>(inst, path);
       },
       [](Window* win, Model* model, const char*) {
diff --git a/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTCommandScheduler.h b/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTCommandScheduler.h
index 54dc778..980e1f5 100644
--- a/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTCommandScheduler.h
+++ b/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTCommandScheduler.h
@@ -4,14 +4,18 @@
 
 #pragma once
 
+#include <stdint.h>
+
 #include <string>
 #include <string_view>
 #include <vector>
 
-#include <ntcore_cpp.h>
+#include <networktables/IntegerArrayTopic.h>
+#include <networktables/NetworkTableInstance.h>
+#include <networktables/StringArrayTopic.h>
+#include <networktables/StringTopic.h>
 
 #include "glass/DataSource.h"
-#include "glass/networktables/NetworkTablesHelper.h"
 #include "glass/other/CommandScheduler.h"
 
 namespace glass {
@@ -20,7 +24,7 @@
   static constexpr const char* kType = "Scheduler";
 
   explicit NTCommandSchedulerModel(std::string_view path);
-  NTCommandSchedulerModel(NT_Inst instance, std::string_view path);
+  NTCommandSchedulerModel(nt::NetworkTableInstance inst, std::string_view path);
 
   const char* GetName() const override { return m_nameValue.c_str(); }
   const std::vector<std::string>& GetCurrentCommands() override {
@@ -34,14 +38,14 @@
   bool IsReadOnly() override { return false; }
 
  private:
-  NetworkTablesHelper m_nt;
-  NT_Entry m_name;
-  NT_Entry m_commands;
-  NT_Entry m_ids;
-  NT_Entry m_cancel;
+  nt::NetworkTableInstance m_inst;
+  nt::StringSubscriber m_name;
+  nt::StringArraySubscriber m_commands;
+  nt::IntegerArraySubscriber m_ids;
+  nt::IntegerArrayPublisher m_cancel;
 
   std::string m_nameValue;
   std::vector<std::string> m_commandsValue;
-  std::vector<double> m_idsValue;
+  std::vector<int64_t> m_idsValue;
 };
 }  // namespace glass
diff --git a/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTCommandSelector.h b/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTCommandSelector.h
index c936665..ab35484 100644
--- a/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTCommandSelector.h
+++ b/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTCommandSelector.h
@@ -7,10 +7,11 @@
 #include <string>
 #include <string_view>
 
-#include <ntcore_cpp.h>
+#include <networktables/BooleanTopic.h>
+#include <networktables/NetworkTableInstance.h>
+#include <networktables/StringTopic.h>
 
 #include "glass/DataSource.h"
-#include "glass/networktables/NetworkTablesHelper.h"
 #include "glass/other/CommandSelector.h"
 
 namespace glass {
@@ -19,7 +20,7 @@
   static constexpr const char* kType = "Command";
 
   explicit NTCommandSelectorModel(std::string_view path);
-  NTCommandSelectorModel(NT_Inst instance, std::string_view path);
+  NTCommandSelectorModel(nt::NetworkTableInstance inst, std::string_view path);
 
   const char* GetName() const override { return m_nameValue.c_str(); }
   DataSource* GetRunningData() override { return &m_runningData; }
@@ -30,9 +31,9 @@
   bool IsReadOnly() override { return false; }
 
  private:
-  NetworkTablesHelper m_nt;
-  NT_Entry m_running;
-  NT_Entry m_name;
+  nt::NetworkTableInstance m_inst;
+  nt::BooleanEntry m_running;
+  nt::StringSubscriber m_name;
 
   DataSource m_runningData;
   std::string m_nameValue;
diff --git a/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTDifferentialDrive.h b/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTDifferentialDrive.h
index 49b3eb0..5e34669 100644
--- a/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTDifferentialDrive.h
+++ b/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTDifferentialDrive.h
@@ -8,10 +8,12 @@
 #include <string_view>
 #include <vector>
 
-#include <ntcore_cpp.h>
+#include <networktables/BooleanTopic.h>
+#include <networktables/DoubleTopic.h>
+#include <networktables/NetworkTableInstance.h>
+#include <networktables/StringTopic.h>
 
 #include "glass/DataSource.h"
-#include "glass/networktables/NetworkTablesHelper.h"
 #include "glass/other/Drive.h"
 
 namespace glass {
@@ -20,7 +22,8 @@
   static constexpr const char* kType = "DifferentialDrive";
 
   explicit NTDifferentialDriveModel(std::string_view path);
-  NTDifferentialDriveModel(NT_Inst instance, std::string_view path);
+  NTDifferentialDriveModel(nt::NetworkTableInstance instance,
+                           std::string_view path);
 
   const char* GetName() const override { return m_nameValue.c_str(); }
   const std::vector<DriveModel::WheelInfo>& GetWheels() const override {
@@ -35,11 +38,11 @@
   bool IsReadOnly() override { return !m_controllableValue; }
 
  private:
-  NetworkTablesHelper m_nt;
-  NT_Entry m_name;
-  NT_Entry m_controllable;
-  NT_Entry m_lPercent;
-  NT_Entry m_rPercent;
+  nt::NetworkTableInstance m_inst;
+  nt::StringSubscriber m_name;
+  nt::BooleanSubscriber m_controllable;
+  nt::DoubleEntry m_lPercent;
+  nt::DoubleEntry m_rPercent;
 
   std::string m_nameValue;
   bool m_controllableValue = false;
diff --git a/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTDigitalInput.h b/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTDigitalInput.h
index cd3dfeb..7aa9234 100644
--- a/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTDigitalInput.h
+++ b/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTDigitalInput.h
@@ -7,11 +7,12 @@
 #include <string>
 #include <string_view>
 
-#include <ntcore_cpp.h>
+#include <networktables/BooleanTopic.h>
+#include <networktables/NetworkTableInstance.h>
+#include <networktables/StringTopic.h>
 
 #include "glass/DataSource.h"
 #include "glass/hardware/DIO.h"
-#include "glass/networktables/NetworkTablesHelper.h"
 
 namespace glass {
 
@@ -21,7 +22,7 @@
 
   // path is to the table containing ".type", excluding the trailing /
   explicit NTDigitalInputModel(std::string_view path);
-  NTDigitalInputModel(NT_Inst inst, std::string_view path);
+  NTDigitalInputModel(nt::NetworkTableInstance inst, std::string_view path);
 
   const char* GetName() const override { return m_nameValue.c_str(); }
 
@@ -42,9 +43,9 @@
   bool IsReadOnly() override { return true; }
 
  private:
-  NetworkTablesHelper m_nt;
-  NT_Entry m_value;
-  NT_Entry m_name;
+  nt::NetworkTableInstance m_inst;
+  nt::BooleanSubscriber m_value;
+  nt::StringSubscriber m_name;
 
   DataSource m_valueData;
   std::string m_nameValue;
diff --git a/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTDigitalOutput.h b/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTDigitalOutput.h
index 8ed1ee7..fb6a151 100644
--- a/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTDigitalOutput.h
+++ b/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTDigitalOutput.h
@@ -7,11 +7,12 @@
 #include <string>
 #include <string_view>
 
-#include <ntcore_cpp.h>
+#include <networktables/BooleanTopic.h>
+#include <networktables/NetworkTableInstance.h>
+#include <networktables/StringTopic.h>
 
 #include "glass/DataSource.h"
 #include "glass/hardware/DIO.h"
-#include "glass/networktables/NetworkTablesHelper.h"
 
 namespace glass {
 
@@ -21,7 +22,7 @@
 
   // path is to the table containing ".type", excluding the trailing /
   explicit NTDigitalOutputModel(std::string_view path);
-  NTDigitalOutputModel(NT_Inst inst, std::string_view path);
+  NTDigitalOutputModel(nt::NetworkTableInstance inst, std::string_view path);
 
   const char* GetName() const override { return m_nameValue.c_str(); }
 
@@ -42,10 +43,10 @@
   bool IsReadOnly() override { return !m_controllableValue; }
 
  private:
-  NetworkTablesHelper m_nt;
-  NT_Entry m_value;
-  NT_Entry m_name;
-  NT_Entry m_controllable;
+  nt::NetworkTableInstance m_inst;
+  nt::BooleanEntry m_value;
+  nt::StringSubscriber m_name;
+  nt::BooleanSubscriber m_controllable;
 
   DataSource m_valueData;
   std::string m_nameValue;
diff --git a/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTFMS.h b/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTFMS.h
index b19a9f0..5898080 100644
--- a/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTFMS.h
+++ b/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTFMS.h
@@ -6,10 +6,12 @@
 
 #include <string_view>
 
-#include <ntcore_cpp.h>
+#include <networktables/BooleanTopic.h>
+#include <networktables/IntegerTopic.h>
+#include <networktables/NetworkTableInstance.h>
+#include <networktables/StringTopic.h>
 
 #include "glass/DataSource.h"
-#include "glass/networktables/NetworkTablesHelper.h"
 #include "glass/other/FMS.h"
 
 namespace glass {
@@ -20,7 +22,7 @@
 
   // path is to the table containing ".type", excluding the trailing /
   explicit NTFMSModel(std::string_view path);
-  NTFMSModel(NT_Inst inst, std::string_view path);
+  NTFMSModel(nt::NetworkTableInstance inst, std::string_view path);
 
   DataSource* GetFmsAttachedData() override { return &m_fmsAttached; }
   DataSource* GetDsAttachedData() override { return &m_dsAttached; }
@@ -45,18 +47,18 @@
   void SetEnabled(bool val) override {}
   void SetTest(bool val) override {}
   void SetAutonomous(bool val) override {}
-  void SetGameSpecificMessage(const char* val) override {}
+  void SetGameSpecificMessage(std::string_view val) override {}
 
   void Update() override;
   bool Exists() override;
   bool IsReadOnly() override { return true; }
 
  private:
-  NetworkTablesHelper m_nt;
-  NT_Entry m_gameSpecificMessage;
-  NT_Entry m_alliance;
-  NT_Entry m_station;
-  NT_Entry m_controlWord;
+  nt::NetworkTableInstance m_inst;
+  nt::StringSubscriber m_gameSpecificMessage;
+  nt::BooleanSubscriber m_alliance;
+  nt::IntegerSubscriber m_station;
+  nt::IntegerSubscriber m_controlWord;
 
   DataSource m_fmsAttached;
   DataSource m_dsAttached;
diff --git a/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTField2D.h b/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTField2D.h
index f966e0f..40265ed 100644
--- a/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTField2D.h
+++ b/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTField2D.h
@@ -10,9 +10,12 @@
 #include <utility>
 #include <vector>
 
+#include <networktables/MultiSubscriber.h>
+#include <networktables/NetworkTableInstance.h>
+#include <networktables/NetworkTableListener.h>
+#include <networktables/StringTopic.h>
 #include <ntcore_cpp.h>
 
-#include "glass/networktables/NetworkTablesHelper.h"
 #include "glass/other/Field2D.h"
 
 namespace glass {
@@ -23,7 +26,7 @@
 
   // path is to the table containing ".type", excluding the trailing /
   explicit NTField2DModel(std::string_view path);
-  NTField2DModel(NT_Inst inst, std::string_view path);
+  NTField2DModel(nt::NetworkTableInstance inst, std::string_view path);
   ~NTField2DModel() override;
 
   const char* GetPath() const { return m_path.c_str(); }
@@ -40,9 +43,11 @@
           func) override;
 
  private:
-  NetworkTablesHelper m_nt;
   std::string m_path;
-  NT_Entry m_name;
+  nt::NetworkTableInstance m_inst;
+  nt::MultiSubscriber m_tableSub;
+  nt::StringTopic m_nameTopic;
+  nt::NetworkTableListenerPoller m_poller;
   std::string m_nameValue;
 
   class ObjectModel;
diff --git a/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTGyro.h b/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTGyro.h
index db303a5..dc91acc 100644
--- a/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTGyro.h
+++ b/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTGyro.h
@@ -7,11 +7,12 @@
 #include <string>
 #include <string_view>
 
-#include <ntcore_cpp.h>
+#include <networktables/DoubleTopic.h>
+#include <networktables/NetworkTableInstance.h>
+#include <networktables/StringTopic.h>
 
 #include "glass/DataSource.h"
 #include "glass/hardware/Gyro.h"
-#include "glass/networktables/NetworkTablesHelper.h"
 
 namespace glass {
 class NTGyroModel : public GyroModel {
@@ -19,7 +20,7 @@
   static constexpr const char* kType = "Gyro";
 
   explicit NTGyroModel(std::string_view path);
-  NTGyroModel(NT_Inst instance, std::string_view path);
+  NTGyroModel(nt::NetworkTableInstance inst, std::string_view path);
 
   const char* GetName() const override { return m_nameValue.c_str(); }
   const char* GetSimDevice() const override { return nullptr; }
@@ -32,9 +33,9 @@
   bool IsReadOnly() override { return true; }
 
  private:
-  NetworkTablesHelper m_nt;
-  NT_Entry m_angle;
-  NT_Entry m_name;
+  nt::NetworkTableInstance m_inst;
+  nt::DoubleSubscriber m_angle;
+  nt::StringSubscriber m_name;
 
   DataSource m_angleData;
   std::string m_nameValue;
diff --git a/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTMecanumDrive.h b/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTMecanumDrive.h
index ce7d234..38895bc 100644
--- a/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTMecanumDrive.h
+++ b/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTMecanumDrive.h
@@ -8,10 +8,12 @@
 #include <string_view>
 #include <vector>
 
-#include <ntcore_cpp.h>
+#include <networktables/BooleanTopic.h>
+#include <networktables/DoubleTopic.h>
+#include <networktables/NetworkTableInstance.h>
+#include <networktables/StringTopic.h>
 
 #include "glass/DataSource.h"
-#include "glass/networktables/NetworkTablesHelper.h"
 #include "glass/other/Drive.h"
 
 namespace glass {
@@ -20,7 +22,7 @@
   static constexpr const char* kType = "MecanumDrive";
 
   explicit NTMecanumDriveModel(std::string_view path);
-  NTMecanumDriveModel(NT_Inst instance, std::string_view path);
+  NTMecanumDriveModel(nt::NetworkTableInstance inst, std::string_view path);
 
   const char* GetName() const override { return m_nameValue.c_str(); }
   const std::vector<DriveModel::WheelInfo>& GetWheels() const override {
@@ -35,13 +37,13 @@
   bool IsReadOnly() override { return !m_controllableValue; }
 
  private:
-  NetworkTablesHelper m_nt;
-  NT_Entry m_name;
-  NT_Entry m_controllable;
-  NT_Entry m_flPercent;
-  NT_Entry m_frPercent;
-  NT_Entry m_rlPercent;
-  NT_Entry m_rrPercent;
+  nt::NetworkTableInstance m_inst;
+  nt::StringSubscriber m_name;
+  nt::BooleanSubscriber m_controllable;
+  nt::DoubleEntry m_flPercent;
+  nt::DoubleEntry m_frPercent;
+  nt::DoubleEntry m_rlPercent;
+  nt::DoubleEntry m_rrPercent;
 
   std::string m_nameValue;
   bool m_controllableValue = false;
diff --git a/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTMechanism2D.h b/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTMechanism2D.h
index 81f7df1..e8ffa9d 100644
--- a/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTMechanism2D.h
+++ b/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTMechanism2D.h
@@ -11,9 +11,10 @@
 #include <vector>
 
 #include <frc/geometry/Translation2d.h>
-#include <ntcore_cpp.h>
+#include <networktables/MultiSubscriber.h>
+#include <networktables/NetworkTableInstance.h>
+#include <networktables/NetworkTableListener.h>
 
-#include "glass/networktables/NetworkTablesHelper.h"
 #include "glass/other/Mechanism2D.h"
 
 namespace glass {
@@ -24,7 +25,7 @@
 
   // path is to the table containing ".type", excluding the trailing /
   explicit NTMechanism2DModel(std::string_view path);
-  NTMechanism2DModel(NT_Inst inst, std::string_view path);
+  NTMechanism2DModel(nt::NetworkTableInstance inst, std::string_view path);
   ~NTMechanism2DModel() override;
 
   const char* GetPath() const { return m_path.c_str(); }
@@ -42,12 +43,13 @@
       wpi::function_ref<void(MechanismRootModel& model)> func) override;
 
  private:
-  NetworkTablesHelper m_nt;
+  nt::NetworkTableInstance m_inst;
   std::string m_path;
-
-  NT_Entry m_name;
-  NT_Entry m_dimensions;
-  NT_Entry m_bgColor;
+  nt::MultiSubscriber m_tableSub;
+  nt::Topic m_nameTopic;
+  nt::Topic m_dimensionsTopic;
+  nt::Topic m_bgColorTopic;
+  nt::NetworkTableListenerPoller m_poller;
 
   std::string m_nameValue;
   frc::Translation2d m_dimensionsValue;
diff --git a/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTMotorController.h b/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTMotorController.h
new file mode 100644
index 0000000..574a55b
--- /dev/null
+++ b/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTMotorController.h
@@ -0,0 +1,46 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <string>
+#include <string_view>
+
+#include <networktables/BooleanTopic.h>
+#include <networktables/DoubleTopic.h>
+#include <networktables/NetworkTableInstance.h>
+#include <networktables/StringTopic.h>
+
+#include "glass/DataSource.h"
+#include "glass/hardware/MotorController.h"
+
+namespace glass {
+class NTMotorControllerModel : public MotorControllerModel {
+ public:
+  static constexpr const char* kType = "Motor Controller";
+
+  explicit NTMotorControllerModel(std::string_view path);
+  NTMotorControllerModel(nt::NetworkTableInstance inst, std::string_view path);
+
+  const char* GetName() const override { return m_nameValue.c_str(); }
+  const char* GetSimDevice() const override { return nullptr; }
+
+  DataSource* GetPercentData() override { return &m_valueData; }
+  void SetPercent(double value) override;
+
+  void Update() override;
+  bool Exists() override;
+  bool IsReadOnly() override { return !m_controllableValue; }
+
+ private:
+  nt::NetworkTableInstance m_inst;
+  nt::DoubleEntry m_value;
+  nt::StringSubscriber m_name;
+  nt::BooleanSubscriber m_controllable;
+
+  DataSource m_valueData;
+  std::string m_nameValue;
+  bool m_controllableValue = false;
+};
+}  // namespace glass
diff --git a/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTPIDController.h b/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTPIDController.h
index b975641..f901f72 100644
--- a/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTPIDController.h
+++ b/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTPIDController.h
@@ -7,10 +7,12 @@
 #include <string>
 #include <string_view>
 
-#include <ntcore_cpp.h>
+#include <networktables/BooleanTopic.h>
+#include <networktables/DoubleTopic.h>
+#include <networktables/NetworkTableInstance.h>
+#include <networktables/StringTopic.h>
 
 #include "glass/DataSource.h"
-#include "glass/networktables/NetworkTablesHelper.h"
 #include "glass/other/PIDController.h"
 
 namespace glass {
@@ -19,7 +21,7 @@
   static constexpr const char* kType = "PIDController";
 
   explicit NTPIDControllerModel(std::string_view path);
-  NTPIDControllerModel(NT_Inst instance, std::string_view path);
+  NTPIDControllerModel(nt::NetworkTableInstance inst, std::string_view path);
 
   const char* GetName() const override { return m_nameValue.c_str(); }
 
@@ -38,13 +40,13 @@
   bool IsReadOnly() override { return !m_controllableValue; }
 
  private:
-  NetworkTablesHelper m_nt;
-  NT_Entry m_name;
-  NT_Entry m_controllable;
-  NT_Entry m_p;
-  NT_Entry m_i;
-  NT_Entry m_d;
-  NT_Entry m_setpoint;
+  nt::NetworkTableInstance m_inst;
+  nt::StringSubscriber m_name;
+  nt::BooleanSubscriber m_controllable;
+  nt::DoubleEntry m_p;
+  nt::DoubleEntry m_i;
+  nt::DoubleEntry m_d;
+  nt::DoubleEntry m_setpoint;
 
   DataSource m_pData;
   DataSource m_iData;
diff --git a/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTSpeedController.h b/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTSpeedController.h
deleted file mode 100644
index a79c266..0000000
--- a/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTSpeedController.h
+++ /dev/null
@@ -1,44 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <string>
-#include <string_view>
-
-#include <ntcore_cpp.h>
-
-#include "glass/DataSource.h"
-#include "glass/hardware/SpeedController.h"
-#include "glass/networktables/NetworkTablesHelper.h"
-
-namespace glass {
-class NTSpeedControllerModel : public SpeedControllerModel {
- public:
-  static constexpr const char* kType = "Motor Controller";
-
-  explicit NTSpeedControllerModel(std::string_view path);
-  NTSpeedControllerModel(NT_Inst instance, std::string_view path);
-
-  const char* GetName() const override { return m_nameValue.c_str(); }
-  const char* GetSimDevice() const override { return nullptr; }
-
-  DataSource* GetPercentData() override { return &m_valueData; }
-  void SetPercent(double value) override;
-
-  void Update() override;
-  bool Exists() override;
-  bool IsReadOnly() override { return !m_controllableValue; }
-
- private:
-  NetworkTablesHelper m_nt;
-  NT_Entry m_value;
-  NT_Entry m_name;
-  NT_Entry m_controllable;
-
-  DataSource m_valueData;
-  std::string m_nameValue;
-  bool m_controllableValue = false;
-};
-}  // namespace glass
diff --git a/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTStringChooser.h b/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTStringChooser.h
index 2d806c9..d770a74 100644
--- a/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTStringChooser.h
+++ b/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTStringChooser.h
@@ -7,9 +7,10 @@
 #include <string>
 #include <vector>
 
-#include <ntcore_cpp.h>
+#include <networktables/NetworkTableInstance.h>
+#include <networktables/StringArrayTopic.h>
+#include <networktables/StringTopic.h>
 
-#include "glass/networktables/NetworkTablesHelper.h"
 #include "glass/other/StringChooser.h"
 
 namespace glass {
@@ -20,7 +21,7 @@
 
   // path is to the table containing ".type", excluding the trailing /
   explicit NTStringChooserModel(std::string_view path);
-  NTStringChooserModel(NT_Inst inst, std::string_view path);
+  NTStringChooserModel(nt::NetworkTableInstance inst, std::string_view path);
 
   const std::string& GetDefault() override { return m_defaultValue; }
   const std::string& GetSelected() override { return m_selectedValue; }
@@ -29,21 +30,18 @@
     return m_optionsValue;
   }
 
-  void SetDefault(std::string_view val) override;
   void SetSelected(std::string_view val) override;
-  void SetActive(std::string_view val) override;
-  void SetOptions(wpi::span<const std::string> val) override;
 
   void Update() override;
   bool Exists() override;
   bool IsReadOnly() override { return false; }
 
  private:
-  NetworkTablesHelper m_nt;
-  NT_Entry m_default;
-  NT_Entry m_selected;
-  NT_Entry m_active;
-  NT_Entry m_options;
+  nt::NetworkTableInstance m_inst;
+  nt::StringSubscriber m_default;
+  nt::StringEntry m_selected;
+  nt::StringSubscriber m_active;
+  nt::StringArraySubscriber m_options;
 
   std::string m_defaultValue;
   std::string m_selectedValue;
diff --git a/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTSubsystem.h b/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTSubsystem.h
index c5862cf..6c1ee3a 100644
--- a/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTSubsystem.h
+++ b/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NTSubsystem.h
@@ -7,10 +7,10 @@
 #include <string>
 #include <string_view>
 
-#include <ntcore_cpp.h>
+#include <networktables/NetworkTableInstance.h>
+#include <networktables/StringTopic.h>
 
 #include "glass/DataSource.h"
-#include "glass/networktables/NetworkTablesHelper.h"
 #include "glass/other/Subsystem.h"
 
 namespace glass {
@@ -19,7 +19,7 @@
   static constexpr const char* kType = "Subsystem";
 
   explicit NTSubsystemModel(std::string_view path);
-  NTSubsystemModel(NT_Inst instance, std::string_view path);
+  NTSubsystemModel(nt::NetworkTableInstance inst, std::string_view path);
 
   const char* GetName() const override { return m_nameValue.c_str(); }
   const char* GetDefaultCommand() const override {
@@ -34,10 +34,10 @@
   bool IsReadOnly() override { return true; }
 
  private:
-  NetworkTablesHelper m_nt;
-  NT_Entry m_name;
-  NT_Entry m_defaultCommand;
-  NT_Entry m_currentCommand;
+  nt::NetworkTableInstance m_inst;
+  nt::StringSubscriber m_name;
+  nt::StringSubscriber m_defaultCommand;
+  nt::StringSubscriber m_currentCommand;
 
   std::string m_nameValue;
   std::string m_defaultCommandValue;
diff --git a/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NetworkTables.h b/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NetworkTables.h
index 8538eaa..a7aa514 100644
--- a/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NetworkTables.h
+++ b/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NetworkTables.h
@@ -4,13 +4,20 @@
 
 #pragma once
 
+#include <functional>
+#include <map>
 #include <memory>
+#include <span>
 #include <string>
 #include <string_view>
+#include <utility>
 #include <vector>
 
+#include <networktables/NetworkTableInstance.h>
+#include <networktables/NetworkTableListener.h>
 #include <ntcore_cpp.h>
 #include <wpi/DenseMap.h>
+#include <wpi/json.h>
 
 #include "glass/Model.h"
 #include "glass/View.h"
@@ -21,28 +28,64 @@
 
 class NetworkTablesModel : public Model {
  public:
-  struct Entry {
-    explicit Entry(nt::EntryNotification&& event);
+  struct EntryValueTreeNode;
 
-    void UpdateValue();
+  struct ValueSource {
+    void UpdateFromValue(nt::Value&& v, std::string_view name,
+                         std::string_view typeStr);
 
-    /** Entry handle. */
-    NT_Entry entry;
-
-    /** Entry name. */
-    std::string name;
-
-    /** The value. */
-    std::shared_ptr<nt::Value> value;
-
-    /** Flags. */
-    unsigned int flags = 0;
+    /** The latest value. */
+    nt::Value value;
 
     /** String representation of the value (for arrays / complex values). */
     std::string valueStr;
 
     /** Data source (for numeric values). */
     std::unique_ptr<DataSource> source;
+
+    /** Children of this node, sorted by name/index */
+    std::vector<EntryValueTreeNode> valueChildren;
+
+    /** Whether or not the children represent a map */
+    bool valueChildrenMap = false;
+  };
+
+  struct EntryValueTreeNode : public ValueSource {
+    /** Short name (e.g. of just this node) */
+    std::string name;
+
+    /** Full path */
+    std::string path;
+  };
+
+  struct Entry : public ValueSource {
+    Entry() = default;
+    Entry(const Entry&) = delete;
+    Entry& operator=(const Entry&) = delete;
+    ~Entry();
+
+    void UpdateTopic(nt::Event&& event) {
+      if (std::holds_alternative<nt::TopicInfo>(event.data)) {
+        UpdateInfo(std::get<nt::TopicInfo>(std::move(event.data)));
+      }
+    }
+    void UpdateInfo(nt::TopicInfo&& info_);
+
+    /** Topic information. */
+    nt::TopicInfo info;
+
+    /** JSON representation of the topic properties. */
+    wpi::json properties;
+
+    /** Specific common property flags. */
+    bool persistent{false};
+    bool retained{false};
+
+    /** Publisher (created when the value changes). */
+    NT_Publisher publisher{0};
+
+    std::vector<nt::meta::TopicPublisher> publishers;
+    std::vector<nt::meta::TopicSubscriber> subscribers;
   };
 
   struct TreeNode {
@@ -64,41 +107,89 @@
     std::vector<TreeNode> children;
   };
 
+  struct Client : public nt::meta::Client {
+    Client() = default;
+    /*implicit*/ Client(nt::meta::Client&& oth)  // NOLINT
+        : nt::meta::Client{std::move(oth)} {}
+
+    struct Subscriber : public nt::meta::ClientSubscriber {
+      /*implicit*/ Subscriber(nt::meta::ClientSubscriber&& oth);  // NOLINT
+      std::string topicsStr;
+    };
+
+    std::vector<nt::meta::ClientPublisher> publishers;
+    std::vector<Subscriber> subscribers;
+
+    void UpdatePublishers(std::span<const uint8_t> data);
+    void UpdateSubscribers(std::span<const uint8_t> data);
+  };
+
   NetworkTablesModel();
-  explicit NetworkTablesModel(NT_Inst inst);
-  ~NetworkTablesModel() override;
+  explicit NetworkTablesModel(nt::NetworkTableInstance inst);
 
   void Update() override;
   bool Exists() override;
 
-  NT_Inst GetInstance() { return m_inst; }
-  const std::vector<Entry*>& GetEntries() { return m_sortedEntries; }
-  const std::vector<TreeNode>& GetTreeRoot() { return m_root; }
+  nt::NetworkTableInstance GetInstance() { return m_inst; }
+  const std::vector<Entry*>& GetEntries() const { return m_sortedEntries; }
+  const std::vector<TreeNode>& GetTreeRoot() const { return m_root; }
+  const std::vector<TreeNode>& GetPersistentTreeRoot() const {
+    return m_persistentRoot;
+  }
+  const std::vector<TreeNode>& GetRetainedTreeRoot() const {
+    return m_retainedRoot;
+  }
+  const std::vector<TreeNode>& GetTransitoryTreeRoot() const {
+    return m_transitoryRoot;
+  }
+  const std::map<std::string, Client, std::less<>>& GetClients() const {
+    return m_clients;
+  }
+  const Client& GetServer() const { return m_server; }
+  Entry* GetEntry(std::string_view name);
+  Entry* AddEntry(NT_Topic topic);
 
  private:
-  NT_Inst m_inst;
-  NT_EntryListenerPoller m_poller;
-  wpi::DenseMap<NT_Entry, std::unique_ptr<Entry>> m_entries;
+  void RebuildTree();
+  void RebuildTreeImpl(std::vector<TreeNode>* tree, int category);
+  void UpdateClients(std::span<const uint8_t> data);
+
+  nt::NetworkTableInstance m_inst;
+  nt::NetworkTableListenerPoller m_poller;
+  wpi::DenseMap<NT_Topic, std::unique_ptr<Entry>> m_entries;
 
   // sorted by name
   std::vector<Entry*> m_sortedEntries;
 
   std::vector<TreeNode> m_root;
+  std::vector<TreeNode> m_persistentRoot;
+  std::vector<TreeNode> m_retainedRoot;
+  std::vector<TreeNode> m_transitoryRoot;
+
+  std::map<std::string, Client, std::less<>> m_clients;
+  Client m_server;
 };
 
 using NetworkTablesFlags = int;
 
+static constexpr const int kNetworkTablesFlags_PrecisionBitShift = 9;
+
 enum NetworkTablesFlags_ {
   NetworkTablesFlags_TreeView = 1 << 0,
-  NetworkTablesFlags_ReadOnly = 1 << 1,
-  NetworkTablesFlags_ShowConnections = 1 << 2,
-  NetworkTablesFlags_ShowFlags = 1 << 3,
-  NetworkTablesFlags_ShowTimestamp = 1 << 4,
-  NetworkTablesFlags_CreateNoncanonicalKeys = 1 << 5,
-  NetworkTablesFlags_Default = 1 & ~NetworkTablesFlags_ReadOnly &
-                               ~NetworkTablesFlags_CreateNoncanonicalKeys
+  NetworkTablesFlags_CombinedView = 1 << 1,
+  NetworkTablesFlags_ReadOnly = 1 << 2,
+  NetworkTablesFlags_ShowSpecial = 1 << 3,
+  NetworkTablesFlags_ShowProperties = 1 << 4,
+  NetworkTablesFlags_ShowTimestamp = 1 << 5,
+  NetworkTablesFlags_ShowServerTimestamp = 1 << 6,
+  NetworkTablesFlags_CreateNoncanonicalKeys = 1 << 7,
+  NetworkTablesFlags_Precision = 0xff << kNetworkTablesFlags_PrecisionBitShift,
+  NetworkTablesFlags_Default = NetworkTablesFlags_TreeView |
+                               (6 << kNetworkTablesFlags_PrecisionBitShift),
 };
 
+void DisplayNetworkTablesInfo(NetworkTablesModel* model);
+
 void DisplayNetworkTables(
     NetworkTablesModel* model,
     NetworkTablesFlags flags = NetworkTablesFlags_Default);
@@ -116,10 +207,13 @@
 
  private:
   bool* m_pTreeView = nullptr;
-  bool* m_pShowConnections = nullptr;
-  bool* m_pShowFlags = nullptr;
+  bool* m_pCombinedView = nullptr;
+  bool* m_pShowSpecial = nullptr;
+  bool* m_pShowProperties = nullptr;
   bool* m_pShowTimestamp = nullptr;
+  bool* m_pShowServerTimestamp = nullptr;
   bool* m_pCreateNoncanonicalKeys = nullptr;
+  int* m_pPrecision = nullptr;
   NetworkTablesFlags m_defaultFlags;  // NOLINT
   NetworkTablesFlags m_flags;         // NOLINT
 };
@@ -132,6 +226,8 @@
       : m_model{model}, m_flags{defaultFlags} {}
 
   void Display() override;
+  void Settings() override;
+  bool HasSettings() override;
 
  private:
   NetworkTablesModel* m_model;
diff --git a/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NetworkTablesHelper.h b/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NetworkTablesHelper.h
deleted file mode 100644
index aba3252..0000000
--- a/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NetworkTablesHelper.h
+++ /dev/null
@@ -1,55 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <string_view>
-#include <vector>
-
-#include <ntcore_cpp.h>
-
-namespace glass {
-
-class NetworkTablesHelper {
- public:
-  explicit NetworkTablesHelper(NT_Inst inst);
-  ~NetworkTablesHelper();
-
-  NetworkTablesHelper(const NetworkTablesHelper&) = delete;
-  NetworkTablesHelper& operator=(const NetworkTablesHelper&) = delete;
-
-  NT_Inst GetInstance() const { return m_inst; }
-  NT_EntryListenerPoller GetPoller() const { return m_poller; }
-
-  NT_Entry GetEntry(std::string_view name) const {
-    return nt::GetEntry(m_inst, name);
-  }
-
-  static constexpr int kDefaultListenerFlags =
-      NT_NOTIFY_LOCAL | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE | NT_NOTIFY_DELETE |
-      NT_NOTIFY_IMMEDIATE;
-
-  NT_EntryListener AddListener(NT_Entry entry,
-                               unsigned int flags = kDefaultListenerFlags) {
-    return nt::AddPolledEntryListener(m_poller, entry, flags);
-  }
-
-  NT_EntryListener AddListener(std::string_view prefix,
-                               unsigned int flags = kDefaultListenerFlags) {
-    return nt::AddPolledEntryListener(m_poller, prefix, flags);
-  }
-
-  std::vector<nt::EntryNotification> PollListener() {
-    bool timedOut = false;
-    return nt::PollEntryListener(m_poller, 0, &timedOut);
-  }
-
-  bool IsConnected() const;
-
- private:
-  NT_Inst m_inst;
-  NT_EntryListenerPoller m_poller;
-};
-
-}  // namespace glass
diff --git a/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NetworkTablesProvider.h b/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NetworkTablesProvider.h
index a8f0f9b..cba34cc 100644
--- a/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NetworkTablesProvider.h
+++ b/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NetworkTablesProvider.h
@@ -9,13 +9,15 @@
 #include <string_view>
 #include <vector>
 
-#include <ntcore_c.h>
-#include <ntcore_cpp.h>
+#include <networktables/NetworkTableInstance.h>
+#include <networktables/NetworkTableListener.h>
+#include <networktables/StringTopic.h>
+#include <networktables/Topic.h>
+#include <wpi/DenseMap.h>
 #include <wpi/StringMap.h>
 
 #include "glass/Model.h"
 #include "glass/Provider.h"
-#include "glass/networktables/NetworkTablesHelper.h"
 
 namespace glass {
 
@@ -23,9 +25,10 @@
 
 namespace detail {
 struct NTProviderFunctions {
-  using Exists = std::function<bool(NT_Inst inst, const char* path)>;
-  using CreateModel =
-      std::function<std::unique_ptr<Model>(NT_Inst inst, const char* path)>;
+  using Exists =
+      std::function<bool(nt::NetworkTableInstance inst, const char* path)>;
+  using CreateModel = std::function<std::unique_ptr<Model>(
+      nt::NetworkTableInstance inst, const char* path)>;
   using ViewExists = std::function<bool(Model*, const char* path)>;
   using CreateView =
       std::function<std::unique_ptr<View>(Window*, Model*, const char* path)>;
@@ -41,14 +44,14 @@
   using Provider::CreateViewFunc;
 
   explicit NetworkTablesProvider(Storage& storage);
-  NetworkTablesProvider(Storage& storage, NT_Inst inst);
+  NetworkTablesProvider(Storage& storage, nt::NetworkTableInstance inst);
 
   /**
    * Get the NetworkTables instance being used for this provider.
    *
    * @return NetworkTables instance
    */
-  NT_Inst GetInstance() const { return m_nt.GetInstance(); }
+  nt::NetworkTableInstance GetInstance() const { return m_inst; }
 
   /**
    * Perform global initialization.  This should be called prior to
@@ -74,8 +77,9 @@
  private:
   void Update() override;
 
-  NetworkTablesHelper m_nt;
-  NT_EntryListener m_listener{0};
+  nt::NetworkTableInstance m_inst;
+  nt::NetworkTableListenerPoller m_poller;
+  NT_Listener m_listener{0};
 
   // cached mapping from table name to type string
   Storage& m_typeCache;
@@ -88,17 +92,25 @@
   // mapping from .type string to model/view creators
   wpi::StringMap<Builder> m_typeMap;
 
+  struct SubListener {
+    nt::StringSubscriber subscriber;
+    NT_Listener listener;
+  };
+
+  // mapping from .type topic to subscriber/listener
+  wpi::DenseMap<NT_Topic, SubListener> m_topicMap;
+
   struct Entry : public ModelEntry {
-    Entry(NT_Entry typeEntry, std::string_view name, const Builder& builder)
-        : ModelEntry{name, [](NT_Inst, const char*) { return true; },
+    Entry(nt::Topic typeTopic, std::string_view name, const Builder& builder)
+        : ModelEntry{name, [](auto, const char*) { return true; },
                      builder.createModel},
-          typeEntry{typeEntry} {}
-    NT_Entry typeEntry;
+          typeTopic{typeTopic} {}
+    nt::Topic typeTopic;
   };
 
   void Show(ViewEntry* entry, Window* window) override;
 
-  ViewEntry* GetOrCreateView(const Builder& builder, NT_Entry typeEntry,
+  ViewEntry* GetOrCreateView(const Builder& builder, nt::Topic typeTopic,
                              std::string_view name);
 };
 
diff --git a/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NetworkTablesSettings.h b/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NetworkTablesSettings.h
index a1a1c93..5f2ea19 100644
--- a/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NetworkTablesSettings.h
+++ b/third_party/allwpilib/glass/src/libnt/native/include/glass/networktables/NetworkTablesSettings.h
@@ -22,7 +22,7 @@
 
 class NetworkTablesSettings {
  public:
-  explicit NetworkTablesSettings(Storage& storage,
+  explicit NetworkTablesSettings(std::string_view clientName, Storage& storage,
                                  NT_Inst inst = nt::GetDefaultInstance());
 
   /**
@@ -37,9 +37,12 @@
   bool m_restart = true;
   bool m_serverOption = true;
   EnumSetting m_mode;
-  std::string& m_iniName;
+  std::string& m_persistentFilename;
   std::string& m_serverTeam;
   std::string& m_listenAddress;
+  std::string& m_clientName;
+  int& m_port3;
+  int& m_port4;
   bool& m_dsClient;
 
   class Thread : public wpi::SafeThread {
@@ -54,6 +57,9 @@
     std::string m_iniName;
     std::string m_serverTeam;
     std::string m_listenAddress;
+    std::string m_clientName;
+    int m_port3;
+    int m_port4;
     bool m_dsClient;
   };
   wpi::SafeThreadOwner<Thread> m_thread;
diff --git a/third_party/allwpilib/googletest/CMakeLists.txt b/third_party/allwpilib/googletest/CMakeLists.txt
index b06e326..bd6e588 100644
--- a/third_party/allwpilib/googletest/CMakeLists.txt
+++ b/third_party/allwpilib/googletest/CMakeLists.txt
@@ -1,27 +1,21 @@
-# Download and unpack googletest at configure time
-configure_file(CMakeLists.txt.in googletest-download/CMakeLists.txt)
-execute_process(COMMAND ${CMAKE_COMMAND} -G "${CMAKE_GENERATOR}" .
-  RESULT_VARIABLE result
-  WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/googletest-download )
-if(result)
-  message(FATAL_ERROR "CMake step for googletest failed: ${result}")
-endif()
-execute_process(COMMAND ${CMAKE_COMMAND} --build .
-  RESULT_VARIABLE result
-  WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/googletest-download )
-if(result)
-  message(FATAL_ERROR "Build step for googletest failed: ${result}")
+include(FetchContent)
+
+FetchContent_Declare(
+    googletest
+    GIT_REPOSITORY  https://github.com/google/googletest.git
+    GIT_TAG         58d77fa8070e8cec2dc1ed015d66b454c8d78850 # 1.12.1
+)
+
+FetchContent_GetProperties(googletest)
+if(NOT googletest_POPULATED)
+    FetchContent_Populate(googletest)
+
+    # Prevent overriding the parent project's compiler/linker
+    # settings on Windows
+    set(gtest_force_shared_crt ON CACHE BOOL "" FORCE)
+
+    add_subdirectory(${googletest_SOURCE_DIR} ${googletest_BINARY_DIR} EXCLUDE_FROM_ALL)
 endif()
 
-# Prevent overriding the parent project's compiler/linker
-# settings on Windows
-set(gtest_force_shared_crt ON CACHE BOOL "" FORCE)
-
-# Add googletest directly to our build. This defines
-# the gtest and gtest_main targets.
-add_subdirectory(${CMAKE_CURRENT_BINARY_DIR}/googletest-src
-                 ${CMAKE_CURRENT_BINARY_DIR}/googletest-build
-                 EXCLUDE_FROM_ALL)
-
-target_compile_features(gtest PUBLIC cxx_std_17)
-target_compile_features(gtest_main PUBLIC cxx_std_17)
+target_compile_features(gtest PUBLIC cxx_std_20)
+target_compile_features(gtest_main PUBLIC cxx_std_20)
diff --git a/third_party/allwpilib/googletest/CMakeLists.txt.in b/third_party/allwpilib/googletest/CMakeLists.txt.in
deleted file mode 100644
index 196b3b6..0000000
--- a/third_party/allwpilib/googletest/CMakeLists.txt.in
+++ /dev/null
@@ -1,15 +0,0 @@
-cmake_minimum_required(VERSION 2.8.2)
-
-project(googletest-download NONE)
-
-include(ExternalProject)
-ExternalProject_Add(googletest
-  GIT_REPOSITORY    https://github.com/google/googletest.git
-  GIT_TAG           e2239ee6043f73722e7aa812a459f54a28552929 # 1.11.0
-  SOURCE_DIR        "${CMAKE_CURRENT_BINARY_DIR}/googletest-src"
-  BINARY_DIR        "${CMAKE_CURRENT_BINARY_DIR}/googletest-build"
-  CONFIGURE_COMMAND ""
-  BUILD_COMMAND     ""
-  INSTALL_COMMAND   ""
-  TEST_COMMAND      ""
-)
diff --git a/third_party/allwpilib/gradle.properties b/third_party/allwpilib/gradle.properties
index dd4aa68..d7a34a5 100644
--- a/third_party/allwpilib/gradle.properties
+++ b/third_party/allwpilib/gradle.properties
@@ -1,8 +1 @@
-# The --add-exports flags work around a bug with spotless and JDK 17
-# https://github.com/diffplug/spotless/issues/834
-org.gradle.jvmargs=-Xmx1g \
-  --add-exports jdk.compiler/com.sun.tools.javac.api=ALL-UNNAMED \
-  --add-exports jdk.compiler/com.sun.tools.javac.file=ALL-UNNAMED \
-  --add-exports jdk.compiler/com.sun.tools.javac.parser=ALL-UNNAMED \
-  --add-exports jdk.compiler/com.sun.tools.javac.tree=ALL-UNNAMED \
-  --add-exports jdk.compiler/com.sun.tools.javac.util=ALL-UNNAMED
+org.gradle.jvmargs=-Xmx2g
diff --git a/third_party/allwpilib/gradle/wrapper/gradle-wrapper.jar b/third_party/allwpilib/gradle/wrapper/gradle-wrapper.jar
index 7454180..249e583 100644
--- a/third_party/allwpilib/gradle/wrapper/gradle-wrapper.jar
+++ b/third_party/allwpilib/gradle/wrapper/gradle-wrapper.jar
Binary files differ
diff --git a/third_party/allwpilib/gradle/wrapper/gradle-wrapper.properties b/third_party/allwpilib/gradle/wrapper/gradle-wrapper.properties
index 2e6e589..ae04661 100644
--- a/third_party/allwpilib/gradle/wrapper/gradle-wrapper.properties
+++ b/third_party/allwpilib/gradle/wrapper/gradle-wrapper.properties
@@ -1,5 +1,5 @@
 distributionBase=GRADLE_USER_HOME
 distributionPath=wrapper/dists
-distributionUrl=https\://services.gradle.org/distributions/gradle-7.3.3-bin.zip
+distributionUrl=https\://services.gradle.org/distributions/gradle-7.5.1-bin.zip
 zipStoreBase=GRADLE_USER_HOME
 zipStorePath=wrapper/dists
diff --git a/third_party/allwpilib/gradlew b/third_party/allwpilib/gradlew
index 1b6c787..a69d9cb 100755
--- a/third_party/allwpilib/gradlew
+++ b/third_party/allwpilib/gradlew
@@ -205,6 +205,12 @@
         org.gradle.wrapper.GradleWrapperMain \
         "$@"
 
+# Stop when "xargs" is not available.
+if ! command -v xargs >/dev/null 2>&1
+then
+    die "xargs is not available"
+fi
+
 # Use "xargs" to parse quoted args.
 #
 # With -n1 it outputs one arg per line, with the quotes and backslashes removed.
diff --git a/third_party/allwpilib/gradlew.bat b/third_party/allwpilib/gradlew.bat
index ac1b06f..53a6b23 100644
--- a/third_party/allwpilib/gradlew.bat
+++ b/third_party/allwpilib/gradlew.bat
@@ -14,7 +14,7 @@
 @rem limitations under the License.

 @rem

 

-@if "%DEBUG%" == "" @echo off

+@if "%DEBUG%"=="" @echo off

 @rem ##########################################################################

 @rem

 @rem  Gradle startup script for Windows

@@ -25,7 +25,7 @@
 if "%OS%"=="Windows_NT" setlocal

 

 set DIRNAME=%~dp0

-if "%DIRNAME%" == "" set DIRNAME=.

+if "%DIRNAME%"=="" set DIRNAME=.

 set APP_BASE_NAME=%~n0

 set APP_HOME=%DIRNAME%

 

@@ -40,7 +40,7 @@
 

 set JAVA_EXE=java.exe

 %JAVA_EXE% -version >NUL 2>&1

-if "%ERRORLEVEL%" == "0" goto execute

+if %ERRORLEVEL% equ 0 goto execute

 

 echo.

 echo ERROR: JAVA_HOME is not set and no 'java' command could be found in your PATH.

@@ -75,13 +75,15 @@
 

 :end

 @rem End local scope for the variables with windows NT shell

-if "%ERRORLEVEL%"=="0" goto mainEnd

+if %ERRORLEVEL% equ 0 goto mainEnd

 

 :fail

 rem Set variable GRADLE_EXIT_CONSOLE if you need the _script_ return code instead of

 rem the _cmd.exe /c_ return code!

-if  not "" == "%GRADLE_EXIT_CONSOLE%" exit 1

-exit /b 1

+set EXIT_CODE=%ERRORLEVEL%

+if %EXIT_CODE% equ 0 set EXIT_CODE=1

+if not ""=="%GRADLE_EXIT_CONSOLE%" exit %EXIT_CODE%

+exit /b %EXIT_CODE%

 

 :mainEnd

 if "%OS%"=="Windows_NT" endlocal

diff --git a/third_party/allwpilib/hal/build.gradle b/third_party/allwpilib/hal/build.gradle
index ed67125..03d07a0 100644
--- a/third_party/allwpilib/hal/build.gradle
+++ b/third_party/allwpilib/hal/build.gradle
@@ -100,6 +100,11 @@
             }
         }
     }
+    exeSplitSetup = {
+        if (it.targetPlatform.name == nativeUtils.wpi.platforms.roborio) {
+            nativeUtils.useRequiredLibrary(it, 'ni_link_libraries', 'ni_runtime_libraries')
+        }
+    }
 }
 
 apply from: "${rootDir}/shared/jni/setupBuild.gradle"
@@ -133,19 +138,6 @@
 
 nativeUtils.exportsConfigs {
     hal {
-        x86ExcludeSymbols = [
-            '_CT??_R0?AV_System_error',
-            '_CT??_R0?AVexception',
-            '_CT??_R0?AVfailure',
-            '_CT??_R0?AVruntime_error',
-            '_CT??_R0?AVsystem_error',
-            '_CTA5?AVfailure',
-            '_TI5?AVfailure',
-            '_CT??_R0?AVout_of_range',
-            '_CTA3?AVout_of_range',
-            '_TI3?AVout_of_range',
-            '_CT??_R0?AVbad_cast'
-        ]
         x64ExcludeSymbols = [
             '_CT??_R0?AV_System_error',
             '_CT??_R0?AVexception',
@@ -161,7 +153,6 @@
         ]
     }
     halJNI {
-        x86SymbolFilter = symbolFilter
         x64SymbolFilter = symbolFilter
     }
 }
diff --git a/third_party/allwpilib/hal/src/dev/native/cpp/main.cpp b/third_party/allwpilib/hal/src/dev/native/cpp/main.cpp
index 721c0f6..8614aba 100644
--- a/third_party/allwpilib/hal/src/dev/native/cpp/main.cpp
+++ b/third_party/allwpilib/hal/src/dev/native/cpp/main.cpp
@@ -8,5 +8,5 @@
 
 int main() {
   fmt::print("Hello World\n");
-  fmt::print("{}\n", HAL_GetRuntimeType());
+  fmt::print("{}\n", static_cast<int32_t>(HAL_GetRuntimeType()));
 }
diff --git a/third_party/allwpilib/hal/src/generate/FRCNetComm.java.in b/third_party/allwpilib/hal/src/generate/FRCNetComm.java.in
index ce21889..703e034 100644
--- a/third_party/allwpilib/hal/src/generate/FRCNetComm.java.in
+++ b/third_party/allwpilib/hal/src/generate/FRCNetComm.java.in
@@ -7,7 +7,6 @@
 /**
  * JNI wrapper for library <b>FRC_NetworkCommunication</b><br>.
  */
-@SuppressWarnings({"MethodName", "LineLength"})
 public class FRCNetComm {
   /**
    * Resource type from UsageReporting.
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/AccumulatorResult.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/AccumulatorResult.java
index 9340748..441ce9f 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/AccumulatorResult.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/AccumulatorResult.java
@@ -5,12 +5,11 @@
 package edu.wpi.first.hal;
 
 /** Structure for holding the values stored in an accumulator. */
+@SuppressWarnings("MemberName")
 public class AccumulatorResult {
   /** The total value accumulated. */
-  @SuppressWarnings("MemberName")
   public long value;
   /** The number of sample value was accumulated over. */
-  @SuppressWarnings("MemberName")
   public long count;
 
   /**
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/AddressableLEDJNI.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/AddressableLEDJNI.java
index c732ec6..1dd80a7 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/AddressableLEDJNI.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/AddressableLEDJNI.java
@@ -4,7 +4,6 @@
 
 package edu.wpi.first.hal;
 
-@SuppressWarnings("AbbreviationAsWordInName")
 public class AddressableLEDJNI extends JNIWrapper {
   public static native int initialize(int pwmHandle);
 
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/AnalogJNI.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/AnalogJNI.java
index e2deadd..b80388d 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/AnalogJNI.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/AnalogJNI.java
@@ -111,6 +111,5 @@
 
   public static native boolean getAnalogTriggerOutput(int analogTriggerHandle, int type);
 
-  @SuppressWarnings("AbbreviationAsWordInName")
   public static native int getAnalogTriggerFPGAIndex(int analogTriggerHandle);
 }
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/CANAPIJNI.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/CANAPIJNI.java
index 31cf973..227da4d 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/CANAPIJNI.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/CANAPIJNI.java
@@ -4,7 +4,6 @@
 
 package edu.wpi.first.hal;
 
-@SuppressWarnings("AbbreviationAsWordInName")
 public class CANAPIJNI extends JNIWrapper {
   public static native int initializeCAN(int manufacturer, int deviceId, int deviceType);
 
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/CANData.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/CANData.java
index 94e9f57..0a644f6 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/CANData.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/CANData.java
@@ -4,14 +4,10 @@
 
 package edu.wpi.first.hal;
 
+@SuppressWarnings("MemberName")
 public class CANData {
-  @SuppressWarnings("MemberName")
   public final byte[] data = new byte[8];
-
-  @SuppressWarnings("MemberName")
   public int length;
-
-  @SuppressWarnings("MemberName")
   public long timestamp;
 
   /**
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/CANStreamMessage.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/CANStreamMessage.java
new file mode 100644
index 0000000..bdb2112
--- /dev/null
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/CANStreamMessage.java
@@ -0,0 +1,35 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.hal;
+
+public class CANStreamMessage {
+  @SuppressWarnings("MemberName")
+  public final byte[] data = new byte[8];
+
+  @SuppressWarnings("MemberName")
+  public int length;
+
+  @SuppressWarnings("MemberName")
+  public long timestamp;
+
+  @SuppressWarnings("MemberName")
+  public int messageID;
+
+  /**
+   * API used from JNI to set the data.
+   *
+   * @param length Length of packet in bytes.
+   * @param messageID CAN message ID of the message.
+   * @param timestamp CAN frame timestamp in microseconds.
+   * @return Buffer containing CAN frame.
+   */
+  @SuppressWarnings("PMD.MethodReturnsInternalArray")
+  public byte[] setStreamData(int length, int messageID, long timestamp) {
+    this.messageID = messageID;
+    this.length = length;
+    this.timestamp = timestamp;
+    return data;
+  }
+}
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/CTREPCMJNI.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/CTREPCMJNI.java
index 20d5cb8..e94b183 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/CTREPCMJNI.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/CTREPCMJNI.java
@@ -4,7 +4,6 @@
 
 package edu.wpi.first.hal;
 
-@SuppressWarnings("AbbreviationAsWordInName")
 public class CTREPCMJNI extends JNIWrapper {
   public static native int initialize(int module);
 
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/DIOJNI.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/DIOJNI.java
index dab1aaf..689a95e 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/DIOJNI.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/DIOJNI.java
@@ -4,7 +4,6 @@
 
 package edu.wpi.first.hal;
 
-@SuppressWarnings("AbbreviationAsWordInName")
 public class DIOJNI extends JNIWrapper {
   public static native int initializeDIOPort(int halPortHandle, boolean input);
 
@@ -22,7 +21,9 @@
 
   public static native boolean getDIODirection(int dioPortHandle);
 
-  public static native void pulse(int dioPortHandle, double pulseLength);
+  public static native void pulse(int dioPortHandle, double pulseLengthSeconds);
+
+  public static native void pulseMultiple(long channelMask, double pulseLengthSeconds);
 
   public static native boolean isPulsing(int dioPortHandle);
 
@@ -38,5 +39,7 @@
 
   public static native void setDigitalPWMDutyCycle(int pwmGenerator, double dutyCycle);
 
+  public static native void setDigitalPWMPPS(int pwmGenerator, double dutyCycle);
+
   public static native void setDigitalPWMOutputChannel(int pwmGenerator, int channel);
 }
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/DMAJNI.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/DMAJNI.java
index 21c06f1..9a0cfeb 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/DMAJNI.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/DMAJNI.java
@@ -4,7 +4,6 @@
 
 package edu.wpi.first.hal;
 
-@SuppressWarnings("AbbreviationAsWordInName")
 public class DMAJNI extends JNIWrapper {
   public static native int initialize();
 
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/DMAJNISample.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/DMAJNISample.java
index 78a0e99..22f21c8 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/DMAJNISample.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/DMAJNISample.java
@@ -7,7 +7,6 @@
 import java.util.HashMap;
 import java.util.Map;
 
-@SuppressWarnings("AbbreviationAsWordInName")
 public class DMAJNISample {
   private static final int kEnable_Accumulator0 = 8;
   private static final int kEnable_Accumulator1 = 9;
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/DriverStationJNI.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/DriverStationJNI.java
new file mode 100644
index 0000000..f40a38c
--- /dev/null
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/DriverStationJNI.java
@@ -0,0 +1,137 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.hal;
+
+import java.nio.ByteBuffer;
+
+public class DriverStationJNI extends JNIWrapper {
+  public static native void observeUserProgramStarting();
+
+  public static native void observeUserProgramDisabled();
+
+  public static native void observeUserProgramAutonomous();
+
+  public static native void observeUserProgramTeleop();
+
+  public static native void observeUserProgramTest();
+
+  public static void report(int resource, int instanceNumber) {
+    report(resource, instanceNumber, 0, "");
+  }
+
+  public static void report(int resource, int instanceNumber, int context) {
+    report(resource, instanceNumber, context, "");
+  }
+
+  /**
+   * Report the usage of a resource of interest.
+   *
+   * <p>Original signature: <code>uint32_t report(tResourceType, uint8_t, uint8_t, const
+   * char*)</code>
+   *
+   * @param resource one of the values in the tResourceType above (max value 51).
+   * @param instanceNumber an index that identifies the resource instance.
+   * @param context an optional additional context number for some cases (such as module number).
+   *     Set to 0 to omit.
+   * @param feature a string to be included describing features in use on a specific resource.
+   *     Setting the same resource more than once allows you to change the feature string.
+   * @return TODO
+   */
+  public static native int report(int resource, int instanceNumber, int context, String feature);
+
+  public static native int nativeGetControlWord();
+
+  @SuppressWarnings("MissingJavadocMethod")
+  public static void getControlWord(ControlWord controlWord) {
+    int word = nativeGetControlWord();
+    controlWord.update(
+        (word & 1) != 0,
+        ((word >> 1) & 1) != 0,
+        ((word >> 2) & 1) != 0,
+        ((word >> 3) & 1) != 0,
+        ((word >> 4) & 1) != 0,
+        ((word >> 5) & 1) != 0);
+  }
+
+  private static native int nativeGetAllianceStation();
+
+  public static final int kRed1AllianceStation = 0;
+  public static final int kRed2AllianceStation = 1;
+  public static final int kRed3AllianceStation = 2;
+  public static final int kBlue1AllianceStation = 3;
+  public static final int kBlue2AllianceStation = 4;
+  public static final int kBlue3AllianceStation = 5;
+
+  @SuppressWarnings("MissingJavadocMethod")
+  public static AllianceStationID getAllianceStation() {
+    switch (nativeGetAllianceStation()) {
+      case kRed1AllianceStation:
+        return AllianceStationID.Red1;
+      case kRed2AllianceStation:
+        return AllianceStationID.Red2;
+      case kRed3AllianceStation:
+        return AllianceStationID.Red3;
+      case kBlue1AllianceStation:
+        return AllianceStationID.Blue1;
+      case kBlue2AllianceStation:
+        return AllianceStationID.Blue2;
+      case kBlue3AllianceStation:
+        return AllianceStationID.Blue3;
+      default:
+        return null;
+    }
+  }
+
+  public static final int kMaxJoystickAxes = 12;
+  public static final int kMaxJoystickPOVs = 12;
+  public static final int kMaxJoysticks = 6;
+
+  public static native int getJoystickAxes(byte joystickNum, float[] axesArray);
+
+  public static native int getJoystickAxesRaw(byte joystickNum, int[] rawAxesArray);
+
+  public static native int getJoystickPOVs(byte joystickNum, short[] povsArray);
+
+  public static native int getJoystickButtons(byte joystickNum, ByteBuffer count);
+
+  public static native void getAllJoystickData(
+      float[] axesArray, byte[] rawAxesArray, short[] povsArray, long[] buttonsAndMetadata);
+
+  public static native int setJoystickOutputs(
+      byte joystickNum, int outputs, short leftRumble, short rightRumble);
+
+  public static native int getJoystickIsXbox(byte joystickNum);
+
+  public static native int getJoystickType(byte joystickNum);
+
+  public static native String getJoystickName(byte joystickNum);
+
+  public static native int getJoystickAxisType(byte joystickNum, byte axis);
+
+  public static native double getMatchTime();
+
+  public static native int getMatchInfo(MatchInfoData info);
+
+  public static native int sendError(
+      boolean isError,
+      int errorCode,
+      boolean isLVCode,
+      String details,
+      String location,
+      String callStack,
+      boolean printMsg);
+
+  public static native int sendConsoleLine(String line);
+
+  public static native void refreshDSData();
+
+  public static native void provideNewDataEventHandle(int handle);
+
+  public static native void removeNewDataEventHandle(int handle);
+
+  public static native boolean getOutputsActive();
+
+  private DriverStationJNI() {}
+}
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/DutyCycleJNI.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/DutyCycleJNI.java
index a1bba6f..f2737d8 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/DutyCycleJNI.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/DutyCycleJNI.java
@@ -13,10 +13,9 @@
 
   public static native double getOutput(int handle);
 
-  public static native int getOutputRaw(int handle);
+  public static native int getHighTime(int handle);
 
   public static native int getOutputScaleFactor(int handle);
 
-  @SuppressWarnings("AbbreviationAsWordInName")
   public static native int getFPGAIndex(int handle);
 }
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/EncoderJNI.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/EncoderJNI.java
index f67e3a5..50ecc91 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/EncoderJNI.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/EncoderJNI.java
@@ -50,7 +50,6 @@
   public static native void setEncoderIndexSource(
       int encoderHandle, int digitalSourceHandle, int analogTriggerType, int indexingType);
 
-  @SuppressWarnings("AbbreviationAsWordInName")
   public static native int getEncoderFPGAIndex(int encoderHandle);
 
   public static native int getEncoderEncodingScale(int encoderHandle);
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/HAL.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/HAL.java
index 53198e0..68e6ec8 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/HAL.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/HAL.java
@@ -4,7 +4,6 @@
 
 package edu.wpi.first.hal;
 
-import java.nio.ByteBuffer;
 import java.util.ArrayList;
 import java.util.List;
 
@@ -12,10 +11,7 @@
  * JNI Wrapper for HAL<br>
  * .
  */
-@SuppressWarnings({"AbbreviationAsWordInName", "MethodName"})
 public final class HAL extends JNIWrapper {
-  public static native void waitForDSData();
-
   public static native boolean initialize(int timeout, int mode);
 
   public static native void shutdown();
@@ -117,15 +113,13 @@
     }
   }
 
-  public static native void observeUserProgramStarting();
+  public static native boolean getBrownedOut();
 
-  public static native void observeUserProgramDisabled();
+  public static native boolean getSystemActive();
 
-  public static native void observeUserProgramAutonomous();
+  public static native int getPortWithModule(byte module, byte channel);
 
-  public static native void observeUserProgramTeleop();
-
-  public static native void observeUserProgramTest();
+  public static native int getPort(byte channel);
 
   public static void report(int resource, int instanceNumber) {
     report(resource, instanceNumber, 0, "");
@@ -135,109 +129,9 @@
     report(resource, instanceNumber, context, "");
   }
 
-  /**
-   * Report the usage of a resource of interest.
-   *
-   * <p>Original signature: <code>uint32_t report(tResourceType, uint8_t, uint8_t, const
-   * char*)</code>
-   *
-   * @param resource one of the values in the tResourceType above (max value 51).
-   * @param instanceNumber an index that identifies the resource instance.
-   * @param context an optional additional context number for some cases (such as module number).
-   *     Set to 0 to omit.
-   * @param feature a string to be included describing features in use on a specific resource.
-   *     Setting the same resource more than once allows you to change the feature string.
-   * @return TODO
-   */
-  public static native int report(int resource, int instanceNumber, int context, String feature);
-
-  public static native int nativeGetControlWord();
-
-  @SuppressWarnings("MissingJavadocMethod")
-  public static void getControlWord(ControlWord controlWord) {
-    int word = nativeGetControlWord();
-    controlWord.update(
-        (word & 1) != 0,
-        ((word >> 1) & 1) != 0,
-        ((word >> 2) & 1) != 0,
-        ((word >> 3) & 1) != 0,
-        ((word >> 4) & 1) != 0,
-        ((word >> 5) & 1) != 0);
+  public static int report(int resource, int instanceNumber, int context, String feature) {
+    return DriverStationJNI.report(resource, instanceNumber, context, feature);
   }
 
-  private static native int nativeGetAllianceStation();
-
-  @SuppressWarnings("MissingJavadocMethod")
-  public static AllianceStationID getAllianceStation() {
-    switch (nativeGetAllianceStation()) {
-      case 0:
-        return AllianceStationID.Red1;
-      case 1:
-        return AllianceStationID.Red2;
-      case 2:
-        return AllianceStationID.Red3;
-      case 3:
-        return AllianceStationID.Blue1;
-      case 4:
-        return AllianceStationID.Blue2;
-      case 5:
-        return AllianceStationID.Blue3;
-      default:
-        return null;
-    }
-  }
-
-  @SuppressWarnings("MissingJavadocMethod")
-  public static native boolean isNewControlData();
-
-  @SuppressWarnings("MissingJavadocMethod")
-  public static native void releaseDSMutex();
-
-  @SuppressWarnings("MissingJavadocMethod")
-  public static native boolean waitForDSDataTimeout(double timeout);
-
-  public static final int kMaxJoystickAxes = 12;
-  public static final int kMaxJoystickPOVs = 12;
-
-  public static native short getJoystickAxes(byte joystickNum, float[] axesArray);
-
-  public static native short getJoystickPOVs(byte joystickNum, short[] povsArray);
-
-  public static native int getJoystickButtons(byte joystickNum, ByteBuffer count);
-
-  public static native int setJoystickOutputs(
-      byte joystickNum, int outputs, short leftRumble, short rightRumble);
-
-  public static native int getJoystickIsXbox(byte joystickNum);
-
-  public static native int getJoystickType(byte joystickNum);
-
-  public static native String getJoystickName(byte joystickNum);
-
-  public static native int getJoystickAxisType(byte joystickNum, byte axis);
-
-  public static native double getMatchTime();
-
-  public static native boolean getSystemActive();
-
-  public static native boolean getBrownedOut();
-
-  public static native int getMatchInfo(MatchInfoData info);
-
-  public static native int sendError(
-      boolean isError,
-      int errorCode,
-      boolean isLVCode,
-      String details,
-      String location,
-      String callStack,
-      boolean printMsg);
-
-  public static native int sendConsoleLine(String line);
-
-  public static native int getPortWithModule(byte module, byte channel);
-
-  public static native int getPort(byte channel);
-
   private HAL() {}
 }
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/HALUtil.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/HALUtil.java
index 4da20a2..7c0f41a 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/HALUtil.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/HALUtil.java
@@ -4,7 +4,6 @@
 
 package edu.wpi.first.hal;
 
-@SuppressWarnings("AbbreviationAsWordInName")
 public final class HALUtil extends JNIWrapper {
   public static final int NULL_PARAMETER = -1005;
   public static final int SAMPLE_RATE_TOO_HIGH = 1001;
@@ -23,6 +22,10 @@
 
   public static native int getFPGARevision();
 
+  public static native String getSerialNumber();
+
+  public static native String getComments();
+
   public static native long getFPGATime();
 
   public static native int getHALRuntimeType();
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/HALValue.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/HALValue.java
index ded57de..5f5441c 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/HALValue.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/HALValue.java
@@ -4,7 +4,6 @@
 
 package edu.wpi.first.hal;
 
-@SuppressWarnings("AbbreviationAsWordInName")
 public final class HALValue {
   public static final int kUnassigned = 0;
   public static final int kBoolean = 0x01;
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/I2CJNI.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/I2CJNI.java
index 821c89b..63f32a0 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/I2CJNI.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/I2CJNI.java
@@ -6,7 +6,6 @@
 
 import java.nio.ByteBuffer;
 
-@SuppressWarnings("AbbreviationAsWordInName")
 public class I2CJNI extends JNIWrapper {
   public static native void i2CInitialize(int port);
 
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/InterruptJNI.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/InterruptJNI.java
index a47a364..7dc2e6d 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/InterruptJNI.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/InterruptJNI.java
@@ -11,9 +11,12 @@
 
   public static native void cleanInterrupts(int interruptHandle);
 
-  public static native int waitForInterrupt(
+  public static native long waitForInterrupt(
       int interruptHandle, double timeout, boolean ignorePrevious);
 
+  public static native long waitForMultipleInterrupts(
+      int interruptHandle, long mask, double timeout, boolean ignorePrevious);
+
   public static native long readInterruptRisingTimestamp(int interruptHandle);
 
   public static native long readInterruptFallingTimestamp(int interruptHandle);
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/MatchInfoData.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/MatchInfoData.java
index 6737c58..699ecc5 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/MatchInfoData.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/MatchInfoData.java
@@ -5,25 +5,21 @@
 package edu.wpi.first.hal;
 
 /** Structure for holding the match info data request. */
+@SuppressWarnings("MemberName")
 public class MatchInfoData {
   /** Stores the event name. */
-  @SuppressWarnings("MemberName")
   public String eventName = "";
 
   /** Stores the game specific message. */
-  @SuppressWarnings("MemberName")
   public String gameSpecificMessage = "";
 
   /** Stores the match number. */
-  @SuppressWarnings("MemberName")
   public int matchNumber;
 
   /** Stores the replay number. */
-  @SuppressWarnings("MemberName")
   public int replayNumber;
 
   /** Stores the match type. */
-  @SuppressWarnings("MemberName")
   public int matchType;
 
   /**
@@ -35,7 +31,6 @@
    * @param replayNumber Replay number.
    * @param matchType Match type.
    */
-  @SuppressWarnings("MissingJavadocMethod")
   public void setData(
       String eventName,
       String gameSpecificMessage,
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/NotifierJNI.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/NotifierJNI.java
index c8f4eef..648e8a2 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/NotifierJNI.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/NotifierJNI.java
@@ -52,7 +52,7 @@
   public static native void cleanNotifier(int notifierHandle);
 
   /**
-   * Sets the notifier to wakeup the waiter in another triggerTime microseconds.
+   * Sets the notifier to wake up the waiter at triggerTime microseconds.
    *
    * @param notifierHandle Notifier handle.
    * @param triggerTime Trigger time in microseconds.
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/PWMConfigDataResult.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/PWMConfigDataResult.java
index e64d6da..ac3c8f94 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/PWMConfigDataResult.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/PWMConfigDataResult.java
@@ -5,6 +5,7 @@
 package edu.wpi.first.hal;
 
 /** Structure for holding the config data result for PWM. */
+@SuppressWarnings("MemberName")
 public class PWMConfigDataResult {
   PWMConfigDataResult(int max, int deadbandMax, int center, int deadbandMin, int min) {
     this.max = max;
@@ -15,22 +16,17 @@
   }
 
   /** The maximum PWM value. */
-  @SuppressWarnings("MemberName")
   public int max;
 
   /** The deadband maximum PWM value. */
-  @SuppressWarnings("MemberName")
   public int deadbandMax;
 
   /** The center PWM value. */
-  @SuppressWarnings("MemberName")
   public int center;
 
   /** The deadband minimum PWM value. */
-  @SuppressWarnings("MemberName")
   public int deadbandMin;
 
   /** The minimum PWM value. */
-  @SuppressWarnings("MemberName")
   public int min;
 }
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/PWMJNI.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/PWMJNI.java
index 946ad07..1ed562c 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/PWMJNI.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/PWMJNI.java
@@ -4,7 +4,6 @@
 
 package edu.wpi.first.hal;
 
-@SuppressWarnings("AbbreviationAsWordInName")
 public class PWMJNI extends DIOJNI {
   public static native int initializePWMPort(int halPortHandle);
 
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/PortsJNI.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/PortsJNI.java
index 6a06ff9..b4bd6cf 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/PortsJNI.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/PortsJNI.java
@@ -4,7 +4,6 @@
 
 package edu.wpi.first.hal;
 
-@SuppressWarnings("AbbreviationAsWordInName")
 public class PortsJNI extends JNIWrapper {
   public static native int getNumAccumulators();
 
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/PowerDistributionFaults.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/PowerDistributionFaults.java
index bdff599..aa2cac5 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/PowerDistributionFaults.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/PowerDistributionFaults.java
@@ -4,86 +4,60 @@
 
 package edu.wpi.first.hal;
 
+@SuppressWarnings("MemberName")
 public class PowerDistributionFaults {
-  @SuppressWarnings("MemberName")
   public final boolean Channel0BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel1BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel2BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel3BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel4BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel5BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel6BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel7BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel8BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel9BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel10BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel11BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel12BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel13BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel14BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel15BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel16BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel17BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel18BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel19BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel20BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel21BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel22BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel23BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Brownout;
 
-  @SuppressWarnings("MemberName")
   public final boolean CanWarning;
 
-  @SuppressWarnings("MemberName")
   public final boolean HardwareFault;
 
   /**
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/PowerDistributionJNI.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/PowerDistributionJNI.java
index 00c4dd1..8280f93 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/PowerDistributionJNI.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/PowerDistributionJNI.java
@@ -4,7 +4,6 @@
 
 package edu.wpi.first.hal;
 
-@SuppressWarnings("AbbreviationAsWordInName")
 public class PowerDistributionJNI extends JNIWrapper {
   public static final int AUTOMATIC_TYPE = 0;
   public static final int CTRE_TYPE = 1;
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/PowerDistributionStickyFaults.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/PowerDistributionStickyFaults.java
index 0eb4a69..f60f8df 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/PowerDistributionStickyFaults.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/PowerDistributionStickyFaults.java
@@ -4,89 +4,62 @@
 
 package edu.wpi.first.hal;
 
+@SuppressWarnings("MemberName")
 public class PowerDistributionStickyFaults {
-  @SuppressWarnings("MemberName")
   public final boolean Channel0BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel1BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel2BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel3BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel4BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel5BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel6BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel7BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel8BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel9BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel10BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel11BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel12BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel13BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel14BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel15BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel16BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel17BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel18BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel19BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel20BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel21BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel22BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel23BreakerFault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Brownout;
 
-  @SuppressWarnings("MemberName")
   public final boolean CanWarning;
 
-  @SuppressWarnings("MemberName")
   public final boolean CanBusOff;
 
-  @SuppressWarnings("MemberName")
   public final boolean HasReset;
 
   /**
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/PowerDistributionVersion.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/PowerDistributionVersion.java
index 0c733a2..fdd1233 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/PowerDistributionVersion.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/PowerDistributionVersion.java
@@ -4,23 +4,18 @@
 
 package edu.wpi.first.hal;
 
+@SuppressWarnings("MemberName")
 public class PowerDistributionVersion {
-  @SuppressWarnings("MemberName")
   public final int firmwareMajor;
 
-  @SuppressWarnings("MemberName")
   public final int firmwareMinor;
 
-  @SuppressWarnings("MemberName")
   public final int firmwareFix;
 
-  @SuppressWarnings("MemberName")
   public final int hardwareMinor;
 
-  @SuppressWarnings("MemberName")
   public final int hardwareMajor;
 
-  @SuppressWarnings("MemberName")
   public final int uniqueId;
 
   /**
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/REVPHFaults.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/REVPHFaults.java
index f71ef69..3419810 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/REVPHFaults.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/REVPHFaults.java
@@ -4,72 +4,50 @@
 
 package edu.wpi.first.hal;
 
-@SuppressWarnings("AbbreviationAsWordInName")
+@SuppressWarnings("MemberName")
 public class REVPHFaults {
-  @SuppressWarnings("MemberName")
   public final boolean Channel0Fault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel1Fault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel2Fault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel3Fault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel4Fault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel5Fault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel6Fault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel7Fault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel8Fault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel9Fault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel10Fault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel11Fault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel12Fault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel13Fault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel14Fault;
 
-  @SuppressWarnings("MemberName")
   public final boolean Channel15Fault;
 
-  @SuppressWarnings("MemberName")
   public final boolean CompressorOverCurrent;
 
-  @SuppressWarnings("MemberName")
   public final boolean CompressorOpen;
 
-  @SuppressWarnings("MemberName")
   public final boolean SolenoidOverCurrent;
 
-  @SuppressWarnings("MemberName")
   public final boolean Brownout;
 
-  @SuppressWarnings("MemberName")
   public final boolean CanWarning;
 
-  @SuppressWarnings("MemberName")
   public final boolean HardwareFault;
 
   /**
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/REVPHJNI.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/REVPHJNI.java
index 17f0323..44c67a8 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/REVPHJNI.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/REVPHJNI.java
@@ -4,7 +4,6 @@
 
 package edu.wpi.first.hal;
 
-@SuppressWarnings("AbbreviationAsWordInName")
 public class REVPHJNI extends JNIWrapper {
   public static final int COMPRESSOR_CONFIG_TYPE_DISABLED = 0;
   public static final int COMPRESSOR_CONFIG_TYPE_DIGITAL = 1;
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/REVPHStickyFaults.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/REVPHStickyFaults.java
index 6bf9f4f..614389e 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/REVPHStickyFaults.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/REVPHStickyFaults.java
@@ -4,27 +4,20 @@
 
 package edu.wpi.first.hal;
 
-@SuppressWarnings("AbbreviationAsWordInName")
+@SuppressWarnings("MemberName")
 public class REVPHStickyFaults {
-  @SuppressWarnings("MemberName")
   public final boolean CompressorOverCurrent;
 
-  @SuppressWarnings("MemberName")
   public final boolean CompressorOpen;
 
-  @SuppressWarnings("MemberName")
   public final boolean SolenoidOverCurrent;
 
-  @SuppressWarnings("MemberName")
   public final boolean Brownout;
 
-  @SuppressWarnings("MemberName")
   public final boolean CanWarning;
 
-  @SuppressWarnings("MemberName")
   public final boolean CanBusOff;
 
-  @SuppressWarnings("MemberName")
   public final boolean HasReset;
 
   /**
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/REVPHVersion.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/REVPHVersion.java
index 13471e7..86d0743 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/REVPHVersion.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/REVPHVersion.java
@@ -4,24 +4,18 @@
 
 package edu.wpi.first.hal;
 
-@SuppressWarnings("AbbreviationAsWordInName")
+@SuppressWarnings("MemberName")
 public class REVPHVersion {
-  @SuppressWarnings("MemberName")
   public final int firmwareMajor;
 
-  @SuppressWarnings("MemberName")
   public final int firmwareMinor;
 
-  @SuppressWarnings("MemberName")
   public final int firmwareFix;
 
-  @SuppressWarnings("MemberName")
   public final int hardwareMinor;
 
-  @SuppressWarnings("MemberName")
   public final int hardwareMajor;
 
-  @SuppressWarnings("MemberName")
   public final int uniqueId;
 
   /**
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/SPIJNI.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/SPIJNI.java
index 05ac08a..053f192 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/SPIJNI.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/SPIJNI.java
@@ -6,8 +6,19 @@
 
 import java.nio.ByteBuffer;
 
-@SuppressWarnings("AbbreviationAsWordInName")
 public class SPIJNI extends JNIWrapper {
+  public static final int INVALID_PORT = -1;
+  public static final int ONBOARD_CS0_PORT = 0;
+  public static final int ONBOARD_CS1_PORT = 1;
+  public static final int ONBOARD_CS2_PORT = 2;
+  public static final int ONBOARD_CS3_PORT = 3;
+  public static final int MXP_PORT = 4;
+
+  public static final int SPI_MODE0 = 0;
+  public static final int SPI_MODE1 = 1;
+  public static final int SPI_MODE2 = 2;
+  public static final int SPI_MODE3 = 3;
+
   public static native void spiInitialize(int port);
 
   public static native int spiTransaction(
@@ -28,8 +39,9 @@
 
   public static native void spiSetSpeed(int port, int speed);
 
-  public static native void spiSetOpts(
-      int port, int msbFirst, int sampleOnTrailing, int clkIdleHigh);
+  public static native void spiSetMode(int port, int mode);
+
+  public static native int spiGetMode(int port);
 
   public static native void spiSetChipSelectActiveHigh(int port);
 
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/SimDevice.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/SimDevice.java
index 67c39fe..db3a587 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/SimDevice.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/SimDevice.java
@@ -112,22 +112,6 @@
    * <p>Returns null if not in simulation.
    *
    * @param name value name
-   * @param readonly if the value should not be written from simulation side
-   * @param initialValue initial value
-   * @return simulated value object
-   * @deprecated Use direction function instead
-   */
-  @Deprecated
-  public SimValue createValue(String name, boolean readonly, HALValue initialValue) {
-    return createValue(name, readonly ? Direction.kOutput : Direction.kInput, initialValue);
-  }
-
-  /**
-   * Creates a value on the simulated device.
-   *
-   * <p>Returns null if not in simulation.
-   *
-   * @param name value name
    * @param direction input/output/bidir (from perspective of user code)
    * @param initialValue initial value
    * @return simulated value object
@@ -182,22 +166,6 @@
    * <p>Returns null if not in simulation.
    *
    * @param name value name
-   * @param readonly if the value should not be written from simulation side
-   * @param initialValue initial value
-   * @return simulated double value object
-   * @deprecated Use direction function instead
-   */
-  @Deprecated
-  public SimDouble createDouble(String name, boolean readonly, double initialValue) {
-    return createDouble(name, readonly ? Direction.kOutput : Direction.kInput, initialValue);
-  }
-
-  /**
-   * Creates a double value on the simulated device.
-   *
-   * <p>Returns null if not in simulation.
-   *
-   * @param name value name
    * @param direction input/output/bidir (from perspective of user code)
    * @param initialValue initial value
    * @return simulated double value object
@@ -218,25 +186,6 @@
    * <p>Returns null if not in simulation.
    *
    * @param name value name
-   * @param readonly if the value should not be written from simulation side
-   * @param options array of option descriptions
-   * @param initialValue initial value (selection)
-   * @return simulated enum value object
-   * @deprecated Use direction function instead
-   */
-  @Deprecated
-  public SimEnum createEnum(String name, boolean readonly, String[] options, int initialValue) {
-    return createEnum(name, readonly ? Direction.kOutput : Direction.kInput, options, initialValue);
-  }
-
-  /**
-   * Creates an enumerated value on the simulated device.
-   *
-   * <p>Enumerated values are always in the range 0 to numOptions-1.
-   *
-   * <p>Returns null if not in simulation.
-   *
-   * @param name value name
    * @param direction input/output/bidir (from perspective of user code)
    * @param options array of option descriptions
    * @param initialValue initial value (selection)
@@ -282,22 +231,6 @@
    * <p>Returns null if not in simulation.
    *
    * @param name value name
-   * @param readonly if the value should not be written from simulation side
-   * @param initialValue initial value
-   * @return simulated boolean value object
-   * @deprecated Use direction function instead
-   */
-  @Deprecated
-  public SimBoolean createBoolean(String name, boolean readonly, boolean initialValue) {
-    return createBoolean(name, readonly ? Direction.kOutput : Direction.kInput, initialValue);
-  }
-
-  /**
-   * Creates a boolean value on the simulated device.
-   *
-   * <p>Returns null if not in simulation.
-   *
-   * @param name value name
    * @param direction input/output/bidir (from perspective of user code)
    * @param initialValue initial value
    * @return simulated boolean value object
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/SimDeviceJNI.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/SimDeviceJNI.java
index 4279916..8723cd3 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/SimDeviceJNI.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/SimDeviceJNI.java
@@ -43,30 +43,6 @@
    *
    * @param device simulated device handle
    * @param name value name
-   * @param readonly if the value should not be written from simulation side
-   * @param initialValue initial value
-   * @return simulated value handle
-   * @deprecated Use direction-taking function instead
-   */
-  @Deprecated
-  public static int createSimValue(
-      int device, String name, boolean readonly, HALValue initialValue) {
-    return createSimValueNative(
-        device,
-        name,
-        readonly ? kOutput : kInput,
-        initialValue.getType(),
-        initialValue.getNativeLong(),
-        initialValue.getNativeDouble());
-  }
-
-  /**
-   * Creates a value on a simulated device.
-   *
-   * <p>Returns 0 if not in simulation; this can be used to avoid calls to Set/Get functions.
-   *
-   * @param device simulated device handle
-   * @param name value name
    * @param direction input/output/bidir (from perspective of user code)
    * @param initialValue initial value
    * @return simulated value handle
@@ -118,25 +94,6 @@
    *
    * @param device simulated device handle
    * @param name value name
-   * @param readonly if the value should not be written from simulation side
-   * @param initialValue initial value
-   * @return simulated value handle
-   * @deprecated Use direction-taking function instead
-   */
-  @Deprecated
-  public static int createSimValueDouble(
-      int device, String name, boolean readonly, double initialValue) {
-    return createSimValueNative(
-        device, name, readonly ? kOutput : kInput, HALValue.kDouble, 0, initialValue);
-  }
-
-  /**
-   * Creates a double value on a simulated device.
-   *
-   * <p>Returns 0 if not in simulation; this can be used to avoid calls to Set/Get functions.
-   *
-   * @param device simulated device handle
-   * @param name value name
    * @param direction input/output/bidir (from perspective of user code)
    * @param initialValue initial value
    * @return simulated value handle
@@ -155,27 +112,6 @@
    *
    * @param device simulated device handle
    * @param name value name
-   * @param readonly if the value should not be written from simulation side
-   * @param options array of option descriptions
-   * @param initialValue initial value (selection)
-   * @return simulated value handle
-   * @deprecated Use direction-taking function instead
-   */
-  @Deprecated
-  public static int createSimValueEnum(
-      int device, String name, boolean readonly, String[] options, int initialValue) {
-    return createSimValueEnum(device, name, readonly ? kOutput : kInput, options, initialValue);
-  }
-
-  /**
-   * Creates an enumerated value on a simulated device.
-   *
-   * <p>Enumerated values are always in the range 0 to numOptions-1.
-   *
-   * <p>Returns 0 if not in simulation; this can be used to avoid calls to Set/Get functions.
-   *
-   * @param device simulated device handle
-   * @param name value name
    * @param direction input/output/bidir (from perspective of user code)
    * @param options array of option descriptions
    * @param initialValue initial value (selection)
@@ -214,25 +150,6 @@
    *
    * @param device simulated device handle
    * @param name value name
-   * @param readonly if the value should not be written from simulation side
-   * @param initialValue initial value
-   * @return simulated value handle
-   * @deprecated Use direction-taking function instead
-   */
-  @Deprecated
-  public static int createSimValueBoolean(
-      int device, String name, boolean readonly, boolean initialValue) {
-    return createSimValueNative(
-        device, name, readonly ? kOutput : kInput, HALValue.kBoolean, initialValue ? 1 : 0, 0.0);
-  }
-
-  /**
-   * Creates a boolean value on a simulated device.
-   *
-   * <p>Returns 0 if not in simulation; this can be used to avoid calls to Set/Get functions.
-   *
-   * @param device simulated device handle
-   * @param name value name
    * @param direction input/output/bidir (from perspective of user code)
    * @param initialValue initial value
    * @return simulated value handle
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/can/CANJNI.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/can/CANJNI.java
index b4f344f..e0734dd 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/can/CANJNI.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/can/CANJNI.java
@@ -4,11 +4,12 @@
 
 package edu.wpi.first.hal.can;
 
+import edu.wpi.first.hal.CANStreamMessage;
 import edu.wpi.first.hal.JNIWrapper;
 import java.nio.ByteBuffer;
 import java.nio.IntBuffer;
 
-@SuppressWarnings("AbbreviationAsWordInName")
+@SuppressWarnings("MethodName")
 public class CANJNI extends JNIWrapper {
   public static final int CAN_SEND_PERIOD_NO_REPEAT = 0;
   public static final int CAN_SEND_PERIOD_STOP_REPEATING = -1;
@@ -17,14 +18,18 @@
   public static final int CAN_IS_FRAME_REMOTE = 0x80000000;
   public static final int CAN_IS_FRAME_11BIT = 0x40000000;
 
-  @SuppressWarnings("MethodName")
   public static native void FRCNetCommCANSessionMuxSendMessage(
       int messageID, byte[] data, int periodMs);
 
-  @SuppressWarnings("MethodName")
   public static native byte[] FRCNetCommCANSessionMuxReceiveMessage(
       IntBuffer messageID, int messageIDMask, ByteBuffer timeStamp);
 
-  @SuppressWarnings("MethodName")
   public static native void getCANStatus(CANStatus status);
+
+  public static native int openCANStreamSession(int messageID, int messageIDMask, int maxMessages);
+
+  public static native void closeCANStreamSession(int sessionHandle);
+
+  public static native int readCANStreamSession(
+      int sessionHandle, CANStreamMessage[] messages, int messagesToRead);
 }
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/can/CANStatus.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/can/CANStatus.java
index 62df8e8..8ec89f7 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/can/CANStatus.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/can/CANStatus.java
@@ -5,28 +5,32 @@
 package edu.wpi.first.hal.can;
 
 /** Structure for holding the result of a CAN Status request. */
+@SuppressWarnings("MemberName")
 public class CANStatus {
   /** The utilization of the CAN Bus. */
-  @SuppressWarnings("MemberName")
   public double percentBusUtilization;
 
   /** The CAN Bus off count. */
-  @SuppressWarnings("MemberName")
   public int busOffCount;
 
   /** The CAN Bus TX full count. */
-  @SuppressWarnings("MemberName")
   public int txFullCount;
 
   /** The CAN Bus receive error count. */
-  @SuppressWarnings("MemberName")
   public int receiveErrorCount;
 
   /** The CAN Bus transmit error count. */
-  @SuppressWarnings("MemberName")
   public int transmitErrorCount;
 
-  @SuppressWarnings("MissingJavadocMethod")
+  /**
+   * Set CAN bus status.
+   *
+   * @param percentBusUtilization CAN bus utilization as a percent.
+   * @param busOffCount Bus off event count.
+   * @param txFullCount TX buffer full event count.
+   * @param receiveErrorCount Receive error event count.
+   * @param transmitErrorCount Transmit error event count.
+   */
   public void setStatus(
       double percentBusUtilization,
       int busOffCount,
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/simulation/CTREPCMDataJNI.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/simulation/CTREPCMDataJNI.java
index 9f60e7e..6d94438 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/simulation/CTREPCMDataJNI.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/simulation/CTREPCMDataJNI.java
@@ -6,7 +6,6 @@
 
 import edu.wpi.first.hal.JNIWrapper;
 
-@SuppressWarnings("AbbreviationAsWordInName")
 public class CTREPCMDataJNI extends JNIWrapper {
   public static native int registerInitializedCallback(
       int index, NotifyCallback callback, boolean initialNotify);
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/simulation/REVPHDataJNI.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/simulation/REVPHDataJNI.java
index ee801f3..96b9701 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/simulation/REVPHDataJNI.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/simulation/REVPHDataJNI.java
@@ -6,7 +6,6 @@
 
 import edu.wpi.first.hal.JNIWrapper;
 
-@SuppressWarnings("AbbreviationAsWordInName")
 public class REVPHDataJNI extends JNIWrapper {
   public static native int registerInitializedCallback(
       int index, NotifyCallback callback, boolean initialNotify);
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/simulation/RoboRioDataJNI.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/simulation/RoboRioDataJNI.java
index a822ede..ef06067 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/simulation/RoboRioDataJNI.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/simulation/RoboRioDataJNI.java
@@ -7,17 +7,13 @@
 import edu.wpi.first.hal.JNIWrapper;
 
 public class RoboRioDataJNI extends JNIWrapper {
-  @SuppressWarnings("AbbreviationAsWordInName")
   public static native int registerFPGAButtonCallback(
       NotifyCallback callback, boolean initialNotify);
 
-  @SuppressWarnings("AbbreviationAsWordInName")
   public static native void cancelFPGAButtonCallback(int uid);
 
-  @SuppressWarnings("AbbreviationAsWordInName")
   public static native boolean getFPGAButton();
 
-  @SuppressWarnings("AbbreviationAsWordInName")
   public static native void setFPGAButton(boolean fPGAButton);
 
   public static native int registerVInVoltageCallback(
@@ -155,5 +151,13 @@
 
   public static native void setBrownoutVoltage(double brownoutVoltage);
 
+  public static native String getSerialNumber();
+
+  public static native void setSerialNumber(String serialNumber);
+
+  public static native String getComments();
+
+  public static native void setComments(String comments);
+
   public static native void resetData();
 }
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/simulation/SimDeviceDataJNI.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/simulation/SimDeviceDataJNI.java
index ef6536a..092b955 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/simulation/SimDeviceDataJNI.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/simulation/SimDeviceDataJNI.java
@@ -28,18 +28,21 @@
 
   public static native int getSimValueDeviceHandle(int handle);
 
+  @SuppressWarnings("MemberName")
   public static class SimDeviceInfo {
-    @SuppressWarnings("JavadocMethod")
+    public String name;
+    public int handle;
+
+    /**
+     * SimDeviceInfo constructor.
+     *
+     * @param name SimDevice name.
+     * @param handle SimDevice handle.
+     */
     public SimDeviceInfo(String name, int handle) {
       this.name = name;
       this.handle = handle;
     }
-
-    @SuppressWarnings("MemberName")
-    public String name;
-
-    @SuppressWarnings("MemberName")
-    public int handle;
   }
 
   public static native SimDeviceInfo[] enumerateSimDevices(String prefix);
@@ -70,32 +73,30 @@
 
   public static native int getSimValueHandle(int device, String name);
 
+  @SuppressWarnings("MemberName")
   public static class SimValueInfo {
-    @SuppressWarnings("JavadocMethod")
+    public String name;
+    public int handle;
+    public int direction;
+    public HALValue value;
+
+    /**
+     * SimValueInfo constructor.
+     *
+     * @param name SimValue name.
+     * @param handle SimValue handle.
+     * @param direction SimValue direction.
+     * @param type SimValue type.
+     * @param value1 Value 1.
+     * @param value2 Value 2.
+     */
     public SimValueInfo(
         String name, int handle, int direction, int type, long value1, double value2) {
       this.name = name;
       this.handle = handle;
-      this.readonly = direction == 1;
       this.direction = direction;
       this.value = HALValue.fromNative(type, value1, value2);
     }
-
-    @SuppressWarnings("MemberName")
-    public String name;
-
-    @SuppressWarnings("MemberName")
-    public int handle;
-
-    @SuppressWarnings("MemberName")
-    @Deprecated
-    public boolean readonly;
-
-    @SuppressWarnings("MemberName")
-    public int direction;
-
-    @SuppressWarnings("MemberName")
-    public HALValue value;
   }
 
   public static native SimValueInfo[] enumerateSimValues(int device);
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/util/AllocationException.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/util/AllocationException.java
index e9f9a91..3591a5f 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/util/AllocationException.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/util/AllocationException.java
@@ -5,7 +5,6 @@
 package edu.wpi.first.hal.util;
 
 /** Exception indicating that the resource is already allocated. */
-@SuppressWarnings("serial")
 public class AllocationException extends RuntimeException {
   /**
    * Create a new AllocationException.
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/util/BoundaryException.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/util/BoundaryException.java
index 683980d..bbecbbe 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/util/BoundaryException.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/util/BoundaryException.java
@@ -7,7 +7,6 @@
 /**
  * This exception represents an error in which a lower limit was set as higher than an upper limit.
  */
-@SuppressWarnings("serial")
 public class BoundaryException extends RuntimeException {
   /**
    * Create a new exception with the given message.
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/util/CheckedAllocationException.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/util/CheckedAllocationException.java
index 6155f17..81de150 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/util/CheckedAllocationException.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/util/CheckedAllocationException.java
@@ -8,7 +8,6 @@
  * Exception indicating that the resource is already allocated This is meant to be thrown by the
  * resource class.
  */
-@SuppressWarnings("serial")
 public class CheckedAllocationException extends Exception {
   /**
    * Create a new CheckedAllocationException.
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/util/HalHandleException.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/util/HalHandleException.java
index 65c11f5..aee93bb 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/util/HalHandleException.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/util/HalHandleException.java
@@ -5,7 +5,6 @@
 package edu.wpi.first.hal.util;
 
 /** Exception indicating that an error has occurred with a HAL Handle. */
-@SuppressWarnings("serial")
 public class HalHandleException extends RuntimeException {
   /**
    * Create a new HalHandleException.
diff --git a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/util/UncleanStatusException.java b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/util/UncleanStatusException.java
index 90650fc..7be73b4 100644
--- a/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/util/UncleanStatusException.java
+++ b/third_party/allwpilib/hal/src/main/java/edu/wpi/first/hal/util/UncleanStatusException.java
@@ -5,7 +5,6 @@
 package edu.wpi.first.hal.util;
 
 /** Exception for bad status codes from the chip object. */
-@SuppressWarnings("serial")
 public final class UncleanStatusException extends IllegalStateException {
   private final int m_statusCode;
 
diff --git a/third_party/allwpilib/hal/src/main/native/athena/Accelerometer.cpp b/third_party/allwpilib/hal/src/main/native/athena/Accelerometer.cpp
index 73b1357..b8cc832 100644
--- a/third_party/allwpilib/hal/src/main/native/athena/Accelerometer.cpp
+++ b/third_party/allwpilib/hal/src/main/native/athena/Accelerometer.cpp
@@ -121,8 +121,9 @@
   // Execute and wait until it's done (up to a millisecond)
   initialTime = HAL_GetFPGATime(&status);
   while (accel->readSTAT(&status) & 1) {
-    if (HAL_GetFPGATime(&status) > initialTime + 1000)
+    if (HAL_GetFPGATime(&status) > initialTime + 1000) {
       break;
+    }
   }
 
   // Send a stop transmit/receive message with the data
@@ -133,8 +134,9 @@
   // Execute and wait until it's done (up to a millisecond)
   initialTime = HAL_GetFPGATime(&status);
   while (accel->readSTAT(&status) & 1) {
-    if (HAL_GetFPGATime(&status) > initialTime + 1000)
+    if (HAL_GetFPGATime(&status) > initialTime + 1000) {
       break;
+    }
   }
 }
 
@@ -151,8 +153,9 @@
   // Execute and wait until it's done (up to a millisecond)
   initialTime = HAL_GetFPGATime(&status);
   while (accel->readSTAT(&status) & 1) {
-    if (HAL_GetFPGATime(&status) > initialTime + 1000)
+    if (HAL_GetFPGATime(&status) > initialTime + 1000) {
       break;
+    }
   }
 
   // Receive a message with the data and stop
@@ -163,8 +166,9 @@
   // Execute and wait until it's done (up to a millisecond)
   initialTime = HAL_GetFPGATime(&status);
   while (accel->readSTAT(&status) & 1) {
-    if (HAL_GetFPGATime(&status) > initialTime + 1000)
+    if (HAL_GetFPGATime(&status) > initialTime + 1000) {
       break;
+    }
   }
 
   return accel->readDATI(&status);
diff --git a/third_party/allwpilib/hal/src/main/native/athena/AddressableLED.cpp b/third_party/allwpilib/hal/src/main/native/athena/AddressableLED.cpp
index 74a323a..5e55c93 100644
--- a/third_party/allwpilib/hal/src/main/native/athena/AddressableLED.cpp
+++ b/third_party/allwpilib/hal/src/main/native/athena/AddressableLED.cpp
@@ -6,11 +6,11 @@
 
 #include <cstring>
 
-#include <FRC_FPGA_ChipObject/fpgainterfacecapi/NiFpga_HMB.h>
 #include <fmt/format.h>
 
 #include "ConstantsInternal.h"
 #include "DigitalInternal.h"
+#include "FPGACalls.h"
 #include "HALInitializer.h"
 #include "HALInternal.h"
 #include "PortsInternal.h"
@@ -44,6 +44,8 @@
 }
 }  // namespace hal::init
 
+static constexpr const char* HmbName = "HMB_0_LED";
+
 extern "C" {
 
 HAL_AddressableLEDHandle HAL_InitializeAddressableLED(
@@ -101,8 +103,8 @@
 
   uint32_t session = led->led->getSystemInterface()->getHandle();
 
-  *status = NiFpga_OpenHostMemoryBuffer(session, "HMB_0_LED", &led->ledBuffer,
-                                        &led->ledBufferSize);
+  *status = hal::HAL_NiFpga_OpenHmb(session, HmbName, &led->ledBufferSize,
+                                    &led->ledBuffer);
 
   if (*status != 0) {
     addressableLEDHandles->Free(handle);
@@ -113,6 +115,12 @@
 }
 
 void HAL_FreeAddressableLED(HAL_AddressableLEDHandle handle) {
+  auto led = addressableLEDHandles->Get(handle);
+  if (!led) {
+    return;
+  }
+  uint32_t session = led->led->getSystemInterface()->getHandle();
+  hal::HAL_NiFpga_CloseHmb(session, HmbName);
   addressableLEDHandles->Free(handle);
 }
 
diff --git a/third_party/allwpilib/hal/src/main/native/athena/AnalogAccumulator.cpp b/third_party/allwpilib/hal/src/main/native/athena/AnalogAccumulator.cpp
index 7ff7d47..32688a0 100644
--- a/third_party/allwpilib/hal/src/main/native/athena/AnalogAccumulator.cpp
+++ b/third_party/allwpilib/hal/src/main/native/athena/AnalogAccumulator.cpp
@@ -23,8 +23,9 @@
     return false;
   }
   for (int32_t i = 0; i < kNumAccumulators; i++) {
-    if (port->channel == kAccumulatorChannels[i])
+    if (port->channel == kAccumulatorChannels[i]) {
       return true;
+    }
   }
   return false;
 }
diff --git a/third_party/allwpilib/hal/src/main/native/athena/AnalogTrigger.cpp b/third_party/allwpilib/hal/src/main/native/athena/AnalogTrigger.cpp
index d9e2b92..47ef4f2 100644
--- a/third_party/allwpilib/hal/src/main/native/athena/AnalogTrigger.cpp
+++ b/third_party/allwpilib/hal/src/main/native/athena/AnalogTrigger.cpp
@@ -5,6 +5,7 @@
 #include "hal/AnalogTrigger.h"
 
 #include "AnalogInternal.h"
+#include "ConstantsInternal.h"
 #include "DutyCycleInternal.h"
 #include "HALInitializer.h"
 #include "HALInternal.h"
@@ -147,16 +148,10 @@
     return;
   }
 
-  int32_t scaleFactor =
-      HAL_GetDutyCycleOutputScaleFactor(trigger->handle, status);
-  if (*status != 0) {
-    return;
-  }
-
-  trigger->trigger->writeLowerLimit(static_cast<int32_t>(scaleFactor * lower),
-                                    status);
-  trigger->trigger->writeUpperLimit(static_cast<int32_t>(scaleFactor * upper),
-                                    status);
+  trigger->trigger->writeLowerLimit(
+      static_cast<int32_t>(kDutyCycleScaleFactor * lower), status);
+  trigger->trigger->writeUpperLimit(
+      static_cast<int32_t>(kDutyCycleScaleFactor * upper), status);
 }
 
 void HAL_SetAnalogTriggerLimitsVoltage(
diff --git a/third_party/allwpilib/hal/src/main/native/athena/CANAPI.cpp b/third_party/allwpilib/hal/src/main/native/athena/CANAPI.cpp
index a7c5b37..a3e4904 100644
--- a/third_party/allwpilib/hal/src/main/native/athena/CANAPI.cpp
+++ b/third_party/allwpilib/hal/src/main/native/athena/CANAPI.cpp
@@ -85,6 +85,9 @@
 
 void HAL_CleanCAN(HAL_CANHandle handle) {
   auto data = canHandles->Free(handle);
+  if (data == nullptr) {
+    return;
+  }
 
   std::scoped_lock lock(data->mapMutex);
 
diff --git a/third_party/allwpilib/hal/src/main/native/athena/CTREPCM.cpp b/third_party/allwpilib/hal/src/main/native/athena/CTREPCM.cpp
index 37faf69..79c1ae3 100644
--- a/third_party/allwpilib/hal/src/main/native/athena/CTREPCM.cpp
+++ b/third_party/allwpilib/hal/src/main/native/athena/CTREPCM.cpp
@@ -233,9 +233,11 @@
     return;
   }
 
+  int32_t can_status = 0;
+
   std::scoped_lock lock{pcm->lock};
   pcm->control.bits.closedLoopEnable = enabled ? 1 : 0;
-  SendControl(pcm.get(), status);
+  SendControl(pcm.get(), &can_status);
 }
 
 HAL_Bool HAL_GetCTREPCMClosedLoopControl(HAL_CTREPCMHandle handle,
@@ -394,9 +396,8 @@
   }
 
   std::scoped_lock lock{pcm->lock};
-  pcm->oneShot.sol10MsPerUnit[index] =
-      (std::min)(static_cast<uint32_t>(durMs) / 10,
-                 static_cast<uint32_t>(0xFF));
+  pcm->oneShot.sol10MsPerUnit[index] = (std::min)(
+      static_cast<uint32_t>(durMs) / 10, static_cast<uint32_t>(0xFF));
   HAL_WriteCANPacketRepeating(pcm->canHandle, pcm->oneShot.sol10MsPerUnit, 8,
                               Control3, SendPeriod, status);
 }
diff --git a/third_party/allwpilib/hal/src/main/native/athena/ConstantsInternal.h b/third_party/allwpilib/hal/src/main/native/athena/ConstantsInternal.h
index 21fece4..ca7241c 100644
--- a/third_party/allwpilib/hal/src/main/native/athena/ConstantsInternal.h
+++ b/third_party/allwpilib/hal/src/main/native/athena/ConstantsInternal.h
@@ -9,5 +9,6 @@
 namespace hal {
 
 constexpr int32_t kSystemClockTicksPerMicrosecond = 40;
+constexpr int32_t kDutyCycleScaleFactor = 4e7 - 1;
 
 }  // namespace hal
diff --git a/third_party/allwpilib/hal/src/main/native/athena/DIO.cpp b/third_party/allwpilib/hal/src/main/native/athena/DIO.cpp
index 7b26dd1..e6308fb 100644
--- a/third_party/allwpilib/hal/src/main/native/athena/DIO.cpp
+++ b/third_party/allwpilib/hal/src/main/native/athena/DIO.cpp
@@ -133,8 +133,9 @@
 void HAL_FreeDIOPort(HAL_DigitalHandle dioPortHandle) {
   auto port = digitalChannelHandles->Get(dioPortHandle, HAL_HandleEnum::DIO);
   // no status, so no need to check for a proper free.
-  if (port == nullptr)
+  if (port == nullptr) {
     return;
+  }
   digitalChannelHandles->Free(dioPortHandle, HAL_HandleEnum::DIO);
 
   // Wait for no other object to hold this handle.
@@ -239,6 +240,30 @@
   }
 }
 
+void HAL_SetDigitalPWMPPS(HAL_DigitalPWMHandle pwmGenerator, double dutyCycle,
+                          int32_t* status) {
+  auto port = digitalPWMHandles->Get(pwmGenerator);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  int32_t id = *port;
+  digitalSystem->writePWMPeriodPower(0xffff, status);
+  double rawDutyCycle = 31.0 * dutyCycle;
+  if (rawDutyCycle > 30.5) {
+    rawDutyCycle = 30.5;
+  }
+  {
+    std::scoped_lock lock(digitalPwmMutex);
+    if (id < 4)
+      digitalSystem->writePWMDutyCycleA(id, static_cast<uint8_t>(rawDutyCycle),
+                                        status);
+    else
+      digitalSystem->writePWMDutyCycleB(
+          id - 4, static_cast<uint8_t>(rawDutyCycle), status);
+  }
+}
+
 void HAL_SetDigitalPWMOutputChannel(HAL_DigitalPWMHandle pwmGenerator,
                                     int32_t channel, int32_t* status) {
   auto port = digitalPWMHandles->Get(pwmGenerator);
@@ -407,13 +432,24 @@
   }
 }
 
-void HAL_Pulse(HAL_DigitalHandle dioPortHandle, double pulseLength,
+void HAL_Pulse(HAL_DigitalHandle dioPortHandle, double pulseLengthSeconds,
                int32_t* status) {
   auto port = digitalChannelHandles->Get(dioPortHandle, HAL_HandleEnum::DIO);
   if (port == nullptr) {
     *status = HAL_HANDLE_ERROR;
     return;
   }
+
+  uint32_t pulseLengthMicroseconds =
+      static_cast<uint32_t>(pulseLengthSeconds * 1e6);
+
+  if (pulseLengthMicroseconds <= 0 || pulseLengthMicroseconds > 0xFFFF) {
+    *status = PARAMETER_OUT_OF_RANGE;
+    hal::SetLastError(status,
+                      "Length must be between 1 and 65535 microseconds");
+    return;
+  }
+
   tDIO::tPulse pulse;
 
   if (port->channel >= kNumDigitalHeaders + kNumDigitalMXPChannels) {
@@ -425,9 +461,29 @@
   }
 
   digitalSystem->writePulseLength(
-      static_cast<uint16_t>(1.0e9 * pulseLength /
-                            (pwmSystem->readLoopTiming(status) * 25)),
-      status);
+      static_cast<uint16_t>(pulseLengthMicroseconds), status);
+  digitalSystem->writePulse(pulse, status);
+}
+
+void HAL_PulseMultiple(uint32_t channelMask, double pulseLengthSeconds,
+                       int32_t* status) {
+  uint32_t pulseLengthMicroseconds =
+      static_cast<uint32_t>(pulseLengthSeconds * 1e6);
+
+  if (pulseLengthMicroseconds <= 0 || pulseLengthMicroseconds > 0xFFFF) {
+    *status = PARAMETER_OUT_OF_RANGE;
+    hal::SetLastError(status,
+                      "Length must be between 1 and 65535 microseconds");
+    return;
+  }
+
+  tDIO::tPulse pulse;
+  pulse.Headers = channelMask & 0x2FF;
+  pulse.MXP = (channelMask & 0xFFFF) >> 10;
+  pulse.SPIPort = (channelMask & 0x1F) >> 26;
+
+  digitalSystem->writePulseLength(
+      static_cast<uint16_t>(pulseLengthMicroseconds), status);
   digitalSystem->writePulse(pulse, status);
 }
 
diff --git a/third_party/allwpilib/hal/src/main/native/athena/DMA.cpp b/third_party/allwpilib/hal/src/main/native/athena/DMA.cpp
index 8fa47e7..0f55d7e 100644
--- a/third_party/allwpilib/hal/src/main/native/athena/DMA.cpp
+++ b/third_party/allwpilib/hal/src/main/native/athena/DMA.cpp
@@ -130,8 +130,9 @@
   auto dma = dmaHandles->Get(handle);
   dmaHandles->Free(handle);
 
-  if (!dma)
+  if (!dma) {
     return;
+  }
 
   int32_t status = 0;
   if (dma->manager) {
@@ -709,6 +710,9 @@
 
 void* HAL_GetDMADirectPointer(HAL_DMAHandle handle) {
   auto dma = dmaHandles->Get(handle);
+  if (dma == nullptr) {
+    return nullptr;
+  }
   return dma.get();
 }
 
diff --git a/third_party/allwpilib/hal/src/main/native/athena/DigitalInternal.cpp b/third_party/allwpilib/hal/src/main/native/athena/DigitalInternal.cpp
index 63ea0aa..b9339ee 100644
--- a/third_party/allwpilib/hal/src/main/native/athena/DigitalInternal.cpp
+++ b/third_party/allwpilib/hal/src/main/native/athena/DigitalInternal.cpp
@@ -98,8 +98,9 @@
 
   // Make sure that the 9403 IONode has had a chance to initialize before
   // continuing.
-  while (pwmSystem->readLoopTiming(status) == 0)
+  while (pwmSystem->readLoopTiming(status) == 0) {
     std::this_thread::yield();
+  }
 
   if (pwmSystem->readLoopTiming(status) != kExpectedLoopTiming) {
     *status = LOOP_TIMING_ERROR;  // NOTE: Doesn't display the error
diff --git a/third_party/allwpilib/hal/src/main/native/athena/DigitalInternal.h b/third_party/allwpilib/hal/src/main/native/athena/DigitalInternal.h
index 6b1e909..685987a 100644
--- a/third_party/allwpilib/hal/src/main/native/athena/DigitalInternal.h
+++ b/third_party/allwpilib/hal/src/main/native/athena/DigitalInternal.h
@@ -38,7 +38,7 @@
  *   reliably down to 10.0 ms; starting at about 8.5ms, the servo sometimes hums
  *   and get hot; by 5.0ms the hum is nearly continuous
  * - 10ms periods work well for Victor 884
- * - 5ms periods allows higher update rates for Luminary Micro Jaguar speed
+ * - 5ms periods allows higher update rates for Luminary Micro Jaguar motor
  *   controllers. Due to the shipping firmware on the Jaguar, we can't run the
  *   update period less than 5.05 ms.
  *
diff --git a/third_party/allwpilib/hal/src/main/native/athena/DutyCycle.cpp b/third_party/allwpilib/hal/src/main/native/athena/DutyCycle.cpp
index 6d70570..4df14cb 100644
--- a/third_party/allwpilib/hal/src/main/native/athena/DutyCycle.cpp
+++ b/third_party/allwpilib/hal/src/main/native/athena/DutyCycle.cpp
@@ -6,6 +6,7 @@
 
 #include <memory>
 
+#include "ConstantsInternal.h"
 #include "DigitalInternal.h"
 #include "DutyCycleInternal.h"
 #include "HALInitializer.h"
@@ -30,8 +31,6 @@
 }  // namespace init
 }  // namespace hal
 
-static constexpr int32_t kScaleFactor = 4e7 - 1;
-
 extern "C" {
 HAL_DutyCycleHandle HAL_InitializeDutyCycle(HAL_Handle digitalSourceHandle,
                                             HAL_AnalogTriggerType triggerType,
@@ -90,12 +89,6 @@
 
 double HAL_GetDutyCycleOutput(HAL_DutyCycleHandle dutyCycleHandle,
                               int32_t* status) {
-  return HAL_GetDutyCycleOutputRaw(dutyCycleHandle, status) /
-         static_cast<double>(kScaleFactor);
-}
-
-int32_t HAL_GetDutyCycleOutputRaw(HAL_DutyCycleHandle dutyCycleHandle,
-                                  int32_t* status) {
   auto dutyCycle = dutyCycleHandles->Get(dutyCycleHandle);
   if (!dutyCycle) {
     *status = HAL_HANDLE_ERROR;
@@ -104,12 +97,31 @@
 
   // TODO Handle Overflow
   unsigned char overflow = 0;
-  return dutyCycle->dutyCycle->readOutput(&overflow, status);
+  uint32_t output = dutyCycle->dutyCycle->readOutput(&overflow, status);
+  return output / static_cast<double>(kDutyCycleScaleFactor);
+}
+
+int32_t HAL_GetDutyCycleHighTime(HAL_DutyCycleHandle dutyCycleHandle,
+                                 int32_t* status) {
+  auto dutyCycle = dutyCycleHandles->Get(dutyCycleHandle);
+  if (!dutyCycle) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+
+  // TODO Handle Overflow
+  unsigned char overflow = 0;
+  uint32_t highTime = dutyCycle->dutyCycle->readHighTicks(&overflow, status);
+  if (*status != 0) {
+    return 0;
+  }
+  // Output will be at max 4e7, so x25 will still fit in a 32 bit signed int.
+  return highTime * 25;
 }
 
 int32_t HAL_GetDutyCycleOutputScaleFactor(HAL_DutyCycleHandle dutyCycleHandle,
                                           int32_t* status) {
-  return kScaleFactor;
+  return kDutyCycleScaleFactor;
 }
 
 int32_t HAL_GetDutyCycleFPGAIndex(HAL_DutyCycleHandle dutyCycleHandle,
diff --git a/third_party/allwpilib/hal/src/main/native/athena/FPGACalls.cpp b/third_party/allwpilib/hal/src/main/native/athena/FPGACalls.cpp
new file mode 100644
index 0000000..0b04019
--- /dev/null
+++ b/third_party/allwpilib/hal/src/main/native/athena/FPGACalls.cpp
@@ -0,0 +1,66 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "FPGACalls.h"
+
+#include <cerrno>
+
+#include "dlfcn.h"
+#include "hal/Errors.h"
+
+static void* NiFpgaLibrary = nullptr;
+
+namespace hal {
+HAL_NiFpga_ReserveIrqContextFunc HAL_NiFpga_ReserveIrqContext;
+HAL_NiFpga_UnreserveIrqContextFunc HAL_NiFpga_UnreserveIrqContext;
+HAL_NiFpga_WaitOnIrqsFunc HAL_NiFpga_WaitOnIrqs;
+HAL_NiFpga_AcknowledgeIrqsFunc HAL_NiFpga_AcknowledgeIrqs;
+HAL_NiFpga_OpenHmbFunc HAL_NiFpga_OpenHmb;
+HAL_NiFpga_CloseHmbFunc HAL_NiFpga_CloseHmb;
+
+namespace init {
+int InitializeFPGA() {
+  NiFpgaLibrary = dlopen("libNiFpga.so", RTLD_LAZY);
+  if (!NiFpgaLibrary) {
+    return errno;
+  }
+
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Wpedantic"
+  HAL_NiFpga_ReserveIrqContext =
+      reinterpret_cast<HAL_NiFpga_ReserveIrqContextFunc>(
+          dlsym(NiFpgaLibrary, "NiFpgaDll_ReserveIrqContext"));
+  HAL_NiFpga_UnreserveIrqContext =
+      reinterpret_cast<HAL_NiFpga_UnreserveIrqContextFunc>(
+          dlsym(NiFpgaLibrary, "NiFpgaDll_UnreserveIrqContext"));
+  HAL_NiFpga_WaitOnIrqs = reinterpret_cast<HAL_NiFpga_WaitOnIrqsFunc>(
+      dlsym(NiFpgaLibrary, "NiFpgaDll_WaitOnIrqs"));
+  HAL_NiFpga_AcknowledgeIrqs = reinterpret_cast<HAL_NiFpga_AcknowledgeIrqsFunc>(
+      dlsym(NiFpgaLibrary, "NiFpgaDll_AcknowledgeIrqs"));
+  HAL_NiFpga_OpenHmb = reinterpret_cast<HAL_NiFpga_OpenHmbFunc>(
+      dlsym(NiFpgaLibrary, "NiFpgaDll_OpenHmb"));
+  HAL_NiFpga_CloseHmb = reinterpret_cast<HAL_NiFpga_CloseHmbFunc>(
+      dlsym(NiFpgaLibrary, "NiFpgaDll_CloseHmb"));
+#pragma GCC diagnostic pop
+
+  if (HAL_NiFpga_ReserveIrqContext == nullptr ||
+      HAL_NiFpga_UnreserveIrqContext == nullptr ||
+      HAL_NiFpga_WaitOnIrqs == nullptr ||
+      HAL_NiFpga_AcknowledgeIrqs == nullptr || HAL_NiFpga_OpenHmb == nullptr ||
+      HAL_NiFpga_CloseHmb == nullptr) {
+    HAL_NiFpga_ReserveIrqContext = nullptr;
+    HAL_NiFpga_UnreserveIrqContext = nullptr;
+    HAL_NiFpga_WaitOnIrqs = nullptr;
+    HAL_NiFpga_AcknowledgeIrqs = nullptr;
+    HAL_NiFpga_OpenHmb = nullptr;
+    HAL_NiFpga_CloseHmb = nullptr;
+    dlclose(NiFpgaLibrary);
+    NiFpgaLibrary = nullptr;
+    return NO_AVAILABLE_RESOURCES;
+  }
+
+  return HAL_SUCCESS;
+}
+}  // namespace init
+}  // namespace hal
diff --git a/third_party/allwpilib/hal/src/main/native/athena/FPGACalls.h b/third_party/allwpilib/hal/src/main/native/athena/FPGACalls.h
new file mode 100644
index 0000000..46e8ac4
--- /dev/null
+++ b/third_party/allwpilib/hal/src/main/native/athena/FPGACalls.h
@@ -0,0 +1,46 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <FRC_FPGA_ChipObject/fpgainterfacecapi/NiFpga.h>
+
+namespace hal {
+namespace init {
+[[nodiscard]] int InitializeFPGA();
+}  // namespace init
+
+using HAL_NiFpga_ReserveIrqContextFunc =
+    NiFpga_Status (*)(NiFpga_Session session, NiFpga_IrqContext* context);
+
+extern HAL_NiFpga_ReserveIrqContextFunc HAL_NiFpga_ReserveIrqContext;
+
+using HAL_NiFpga_UnreserveIrqContextFunc =
+    NiFpga_Status (*)(NiFpga_Session session, NiFpga_IrqContext context);
+
+extern HAL_NiFpga_UnreserveIrqContextFunc HAL_NiFpga_UnreserveIrqContext;
+
+using HAL_NiFpga_WaitOnIrqsFunc = NiFpga_Status (*)(
+    NiFpga_Session session, NiFpga_IrqContext context, uint32_t irqs,
+    uint32_t timeout, uint32_t* irqsAsserted, NiFpga_Bool* timedOut);
+
+extern HAL_NiFpga_WaitOnIrqsFunc HAL_NiFpga_WaitOnIrqs;
+
+using HAL_NiFpga_AcknowledgeIrqsFunc = NiFpga_Status (*)(NiFpga_Session session,
+                                                         uint32_t irqs);
+
+extern HAL_NiFpga_AcknowledgeIrqsFunc HAL_NiFpga_AcknowledgeIrqs;
+
+using HAL_NiFpga_OpenHmbFunc = NiFpga_Status (*)(const NiFpga_Session session,
+                                                 const char* memoryName,
+                                                 size_t* memorySize,
+                                                 void** virtualAddress);
+
+extern HAL_NiFpga_OpenHmbFunc HAL_NiFpga_OpenHmb;
+
+using HAL_NiFpga_CloseHmbFunc = NiFpga_Status (*)(const NiFpga_Session session,
+                                                  const char* memoryName);
+
+extern HAL_NiFpga_CloseHmbFunc HAL_NiFpga_CloseHmb;
+}  // namespace hal
diff --git a/third_party/allwpilib/hal/src/main/native/athena/FRCDriverStation.cpp b/third_party/allwpilib/hal/src/main/native/athena/FRCDriverStation.cpp
index e7ef194..e8db9a5 100644
--- a/third_party/allwpilib/hal/src/main/native/athena/FRCDriverStation.cpp
+++ b/third_party/allwpilib/hal/src/main/native/athena/FRCDriverStation.cpp
@@ -13,39 +13,65 @@
 #include <FRC_NetworkCommunication/FRCComm.h>
 #include <FRC_NetworkCommunication/NetCommRPCProxy_Occur.h>
 #include <fmt/format.h>
+#include <wpi/EventVector.h>
 #include <wpi/SafeThread.h>
+#include <wpi/SmallVector.h>
 #include <wpi/condition_variable.h>
 #include <wpi/mutex.h>
 
+#include "HALInitializer.h"
 #include "hal/DriverStation.h"
+#include "hal/Errors.h"
 
 static_assert(sizeof(int32_t) >= sizeof(int),
               "FRC_NetworkComm status variable is larger than 32 bits");
 
+namespace {
 struct HAL_JoystickAxesInt {
   int16_t count;
   int16_t axes[HAL_kMaxJoystickAxes];
 };
+}  // namespace
 
-static constexpr int kJoystickPorts = 6;
+namespace {
+struct JoystickDataCache {
+  JoystickDataCache() { std::memset(this, 0, sizeof(*this)); }
+  void Update();
+
+  HAL_JoystickAxes axes[HAL_kMaxJoysticks];
+  HAL_JoystickPOVs povs[HAL_kMaxJoysticks];
+  HAL_JoystickButtons buttons[HAL_kMaxJoysticks];
+  HAL_AllianceStationID allianceStation;
+  float matchTime;
+};
+static_assert(std::is_standard_layout_v<JoystickDataCache>);
+// static_assert(std::is_trivial_v<JoystickDataCache>);
+
+struct FRCDriverStation {
+  wpi::EventVector newDataEvents;
+};
+}  // namespace
+
+static ::FRCDriverStation* driverStation;
 
 // Message and Data variables
 static wpi::mutex msgMutex;
 
 static int32_t HAL_GetJoystickAxesInternal(int32_t joystickNum,
                                            HAL_JoystickAxes* axes) {
-  HAL_JoystickAxesInt axesInt;
+  HAL_JoystickAxesInt netcommAxes;
 
   int retVal = FRC_NetworkCommunication_getJoystickAxes(
-      joystickNum, reinterpret_cast<JoystickAxes_t*>(&axesInt),
+      joystickNum, reinterpret_cast<JoystickAxes_t*>(&netcommAxes),
       HAL_kMaxJoystickAxes);
 
   // copy integer values to double values
-  axes->count = axesInt.count;
+  axes->count = netcommAxes.count;
   // current scaling is -128 to 127, can easily be patched in the future by
   // changing this function.
-  for (int32_t i = 0; i < axesInt.count; i++) {
-    int8_t value = axesInt.axes[i];
+  for (int32_t i = 0; i < netcommAxes.count; i++) {
+    int8_t value = netcommAxes.axes[i];
+    axes->raw[i] = value;
     if (value < 0) {
       axes->axes[i] = value / 128.0;
     } else {
@@ -68,6 +94,32 @@
   return FRC_NetworkCommunication_getJoystickButtons(
       joystickNum, &buttons->buttons, &buttons->count);
 }
+
+void JoystickDataCache::Update() {
+  for (int i = 0; i < HAL_kMaxJoysticks; i++) {
+    HAL_GetJoystickAxesInternal(i, &axes[i]);
+    HAL_GetJoystickPOVsInternal(i, &povs[i]);
+    HAL_GetJoystickButtonsInternal(i, &buttons[i]);
+  }
+  FRC_NetworkCommunication_getAllianceStation(
+      reinterpret_cast<AllianceStationID_t*>(&allianceStation));
+  FRC_NetworkCommunication_getMatchTime(&matchTime);
+}
+
+#define CHECK_JOYSTICK_NUMBER(stickNum)                  \
+  if ((stickNum) < 0 || (stickNum) >= HAL_kMaxJoysticks) \
+  return PARAMETER_OUT_OF_RANGE
+
+static HAL_ControlWord newestControlWord;
+static JoystickDataCache caches[3];
+static JoystickDataCache* currentRead = &caches[0];
+static JoystickDataCache* currentReadLocal = &caches[0];
+static std::atomic<JoystickDataCache*> currentCache{&caches[1]};
+static JoystickDataCache* lastGiven = &caches[1];
+static JoystickDataCache* cacheToUpdate = &caches[2];
+
+static wpi::mutex cacheMutex;
+
 /**
  * Retrieve the Joystick Descriptor for particular slot.
  *
@@ -102,12 +154,6 @@
   return retval;
 }
 
-static int32_t HAL_GetControlWordInternal(HAL_ControlWord* controlWord) {
-  std::memset(controlWord, 0, sizeof(HAL_ControlWord));
-  return FRC_NetworkCommunication_getControlWord(
-      reinterpret_cast<ControlWord_t*>(controlWord));
-}
-
 static int32_t HAL_GetMatchInfoInternal(HAL_MatchInfo* info) {
   MatchType_t matchType = MatchType_t::kMatchType_none;
   info->gameSpecificMessageSize = sizeof(info->gameSpecificMessage);
@@ -126,19 +172,55 @@
   return status;
 }
 
-static wpi::mutex* newDSDataAvailableMutex;
-static wpi::condition_variable* newDSDataAvailableCond;
-static int newDSDataAvailableCounter{0};
+namespace {
+struct TcpCache {
+  TcpCache() { std::memset(this, 0, sizeof(*this)); }
+  void Update(uint32_t mask);
+  void CloneTo(TcpCache* other) { std::memcpy(other, this, sizeof(*this)); }
+
+  HAL_MatchInfo matchInfo;
+  HAL_JoystickDescriptor descriptors[HAL_kMaxJoysticks];
+};
+static_assert(std::is_standard_layout_v<TcpCache>);
+}  // namespace
+
+static std::atomic_uint32_t tcpMask{0xFFFFFFFF};
+static TcpCache tcpCache;
+static TcpCache tcpCurrent;
+static wpi::mutex tcpCacheMutex;
+
+constexpr uint32_t combinedMatchInfoMask = kTcpRecvMask_MatchInfoOld |
+                                           kTcpRecvMask_MatchInfo |
+                                           kTcpRecvMask_GameSpecific;
+
+void TcpCache::Update(uint32_t mask) {
+  if ((mask & combinedMatchInfoMask) != 0) {
+    HAL_GetMatchInfoInternal(&matchInfo);
+  }
+  for (int i = 0; i < HAL_kMaxJoysticks; i++) {
+    if ((mask & (1 << i)) != 0) {
+      HAL_GetJoystickDescriptorInternal(i, &descriptors[i]);
+    }
+  }
+}
 
 namespace hal::init {
 void InitializeFRCDriverStation() {
-  static wpi::mutex newMutex;
-  newDSDataAvailableMutex = &newMutex;
-  static wpi::condition_variable newCond;
-  newDSDataAvailableCond = &newCond;
+  std::memset(&newestControlWord, 0, sizeof(newestControlWord));
+  static FRCDriverStation ds;
+  driverStation = &ds;
 }
 }  // namespace hal::init
 
+namespace hal {
+static void DefaultPrintErrorImpl(const char* line, size_t size) {
+  std::fwrite(line, size, 1, stderr);
+}
+}  // namespace hal
+
+static std::atomic<void (*)(const char* line, size_t size)> gPrintErrorImpl{
+    hal::DefaultPrintErrorImpl};
+
 extern "C" {
 
 int32_t HAL_SendError(HAL_Bool isError, int32_t errorCode, HAL_Bool isLVCode,
@@ -216,7 +298,8 @@
       if (callStack && callStack[0] != '\0') {
         fmt::format_to(fmt::appender{buf}, "{}\n", callStack);
       }
-      std::fwrite(buf.data(), buf.size(), 1, stderr);
+      auto printError = gPrintErrorImpl.load();
+      printError(buf.data(), buf.size());
     }
     if (i == KEEP_MSGS) {
       // replace the oldest one
@@ -235,6 +318,10 @@
   return retval;
 }
 
+void HAL_SetPrintErrorImpl(void (*func)(const char* line, size_t size)) {
+  gPrintErrorImpl.store(func ? func : hal::DefaultPrintErrorImpl);
+}
+
 int32_t HAL_SendConsoleLine(const char* line) {
   std::string_view lineRef{line};
   if (lineRef.size() <= 65535) {
@@ -248,36 +335,58 @@
 }
 
 int32_t HAL_GetControlWord(HAL_ControlWord* controlWord) {
-  return HAL_GetControlWordInternal(controlWord);
+  std::scoped_lock lock{cacheMutex};
+  *controlWord = newestControlWord;
+  return 0;
 }
 
 int32_t HAL_GetJoystickAxes(int32_t joystickNum, HAL_JoystickAxes* axes) {
-  return HAL_GetJoystickAxesInternal(joystickNum, axes);
+  CHECK_JOYSTICK_NUMBER(joystickNum);
+  std::scoped_lock lock{cacheMutex};
+  *axes = currentRead->axes[joystickNum];
+  return 0;
 }
 
 int32_t HAL_GetJoystickPOVs(int32_t joystickNum, HAL_JoystickPOVs* povs) {
-  return HAL_GetJoystickPOVsInternal(joystickNum, povs);
+  CHECK_JOYSTICK_NUMBER(joystickNum);
+  std::scoped_lock lock{cacheMutex};
+  *povs = currentRead->povs[joystickNum];
+  return 0;
 }
 
 int32_t HAL_GetJoystickButtons(int32_t joystickNum,
                                HAL_JoystickButtons* buttons) {
-  return HAL_GetJoystickButtonsInternal(joystickNum, buttons);
+  CHECK_JOYSTICK_NUMBER(joystickNum);
+  std::scoped_lock lock{cacheMutex};
+  *buttons = currentRead->buttons[joystickNum];
+  return 0;
+}
+
+void HAL_GetAllJoystickData(HAL_JoystickAxes* axes, HAL_JoystickPOVs* povs,
+                            HAL_JoystickButtons* buttons) {
+  std::scoped_lock lock{cacheMutex};
+  std::memcpy(axes, currentRead->axes, sizeof(currentRead->axes));
+  std::memcpy(povs, currentRead->povs, sizeof(currentRead->povs));
+  std::memcpy(buttons, currentRead->buttons, sizeof(currentRead->buttons));
 }
 
 int32_t HAL_GetJoystickDescriptor(int32_t joystickNum,
                                   HAL_JoystickDescriptor* desc) {
-  return HAL_GetJoystickDescriptorInternal(joystickNum, desc);
+  CHECK_JOYSTICK_NUMBER(joystickNum);
+  std::scoped_lock lock{tcpCacheMutex};
+  *desc = tcpCurrent.descriptors[joystickNum];
+  return 0;
 }
 
 int32_t HAL_GetMatchInfo(HAL_MatchInfo* info) {
-  return HAL_GetMatchInfoInternal(info);
+  std::scoped_lock lock{tcpCacheMutex};
+  *info = tcpCurrent.matchInfo;
+  return 0;
 }
 
 HAL_AllianceStationID HAL_GetAllianceStation(int32_t* status) {
-  HAL_AllianceStationID allianceStation;
-  *status = FRC_NetworkCommunication_getAllianceStation(
-      reinterpret_cast<AllianceStationID_t*>(&allianceStation));
-  return allianceStation;
+  std::scoped_lock lock{cacheMutex};
+  return currentRead->allianceStation;
 }
 
 HAL_Bool HAL_GetJoystickIsXbox(int32_t joystickNum) {
@@ -327,14 +436,14 @@
 
 int32_t HAL_SetJoystickOutputs(int32_t joystickNum, int64_t outputs,
                                int32_t leftRumble, int32_t rightRumble) {
+  CHECK_JOYSTICK_NUMBER(joystickNum);
   return FRC_NetworkCommunication_setJoystickOutputs(joystickNum, outputs,
                                                      leftRumble, rightRumble);
 }
 
 double HAL_GetMatchTime(int32_t* status) {
-  float matchTime;
-  *status = FRC_NetworkCommunication_getMatchTime(&matchTime);
-  return matchTime;
+  std::scoped_lock lock{cacheMutex};
+  return currentRead->matchTime;
 }
 
 void HAL_ObserveUserProgramStarting(void) {
@@ -357,103 +466,89 @@
   FRC_NetworkCommunication_observeUserProgramTest();
 }
 
-static int& GetThreadLocalLastCount() {
-  // There is a rollover error condition here. At Packet# = n * (uintmax), this
-  // will return false when instead it should return true. However, this at a
-  // 20ms rate occurs once every 2.7 years of DS connected runtime, so not
-  // worth the cycles to check.
-  thread_local int lastCount{0};
-  return lastCount;
-}
-
-HAL_Bool HAL_IsNewControlData(void) {
-  std::scoped_lock lock{*newDSDataAvailableMutex};
-  int& lastCount = GetThreadLocalLastCount();
-  int currentCount = newDSDataAvailableCounter;
-  if (lastCount == currentCount) {
-    return false;
-  }
-  lastCount = currentCount;
-  return true;
-}
-
-void HAL_WaitForDSData(void) {
-  HAL_WaitForDSDataTimeout(0);
-}
-
-HAL_Bool HAL_WaitForDSDataTimeout(double timeout) {
-  std::unique_lock lock{*newDSDataAvailableMutex};
-  int& lastCount = GetThreadLocalLastCount();
-  int currentCount = newDSDataAvailableCounter;
-  if (lastCount != currentCount) {
-    lastCount = currentCount;
-    return true;
-  }
-  auto timeoutTime =
-      std::chrono::steady_clock::now() + std::chrono::duration<double>(timeout);
-
-  while (newDSDataAvailableCounter == currentCount) {
-    if (timeout > 0) {
-      auto timedOut = newDSDataAvailableCond->wait_until(lock, timeoutTime);
-      if (timedOut == std::cv_status::timeout) {
-        return false;
-      }
-    } else {
-      newDSDataAvailableCond->wait(lock);
-    }
-  }
-  lastCount = newDSDataAvailableCounter;
-  return true;
-}
-
 // Constant number to be used for our occur handle
 constexpr int32_t refNumber = 42;
+constexpr int32_t tcpRefNumber = 94;
 
-static void newDataOccur(uint32_t refNum) {
-  // Since we could get other values, require our specific handle
-  // to signal our threads
-  if (refNum != refNumber) {
-    return;
-  }
-  std::scoped_lock lock{*newDSDataAvailableMutex};
-  // Notify all threads
-  ++newDSDataAvailableCounter;
-  newDSDataAvailableCond->notify_all();
+static void tcpOccur(void) {
+  uint32_t mask = FRC_NetworkCommunication_getNewTcpRecvMask();
+  tcpMask.fetch_or(mask);
 }
 
-/*
- * Call this to initialize the driver station communication. This will properly
- * handle multiple calls. However note that this CANNOT be called from a library
- * that interfaces with LabVIEW.
- */
-void HAL_InitializeDriverStation(void) {
-  static std::atomic_bool initialized{false};
-  static wpi::mutex initializeMutex;
-  // Initial check, as if it's true initialization has finished
-  if (initialized) {
-    return;
-  }
+static void udpOccur(void) {
+  cacheToUpdate->Update();
 
-  std::scoped_lock lock(initializeMutex);
-  // Second check in case another thread was waiting
-  if (initialized) {
-    return;
+  JoystickDataCache* given = cacheToUpdate;
+  JoystickDataCache* prev = currentCache.exchange(cacheToUpdate);
+  if (prev == nullptr) {
+    cacheToUpdate = currentReadLocal;
+    currentReadLocal = lastGiven;
+  } else {
+    // Current read local does not update
+    cacheToUpdate = prev;
   }
+  lastGiven = given;
 
+  driverStation->newDataEvents.Wakeup();
+}
+
+static void newDataOccur(uint32_t refNum) {
+  switch (refNum) {
+    case refNumber:
+      udpOccur();
+      break;
+
+    case tcpRefNumber:
+      tcpOccur();
+      break;
+
+    default:
+      std::printf("Unknown occur %u\n", refNum);
+      break;
+  }
+}
+
+void HAL_RefreshDSData(void) {
+  HAL_ControlWord controlWord;
+  std::memset(&controlWord, 0, sizeof(controlWord));
+  FRC_NetworkCommunication_getControlWord(
+      reinterpret_cast<ControlWord_t*>(&controlWord));
+  std::scoped_lock lock{cacheMutex};
+  JoystickDataCache* prev = currentCache.exchange(nullptr);
+  if (prev != nullptr) {
+    currentRead = prev;
+  }
+  newestControlWord = controlWord;
+
+  uint32_t mask = tcpMask.exchange(0);
+  if (mask != 0) {
+    tcpCache.Update(mask);
+    std::scoped_lock tcpLock(tcpCacheMutex);
+    tcpCache.CloneTo(&tcpCurrent);
+  }
+}
+
+void HAL_ProvideNewDataEventHandle(WPI_EventHandle handle) {
+  hal::init::CheckInit();
+  driverStation->newDataEvents.Add(handle);
+}
+
+void HAL_RemoveNewDataEventHandle(WPI_EventHandle handle) {
+  driverStation->newDataEvents.Remove(handle);
+}
+
+HAL_Bool HAL_GetOutputsEnabled(void) {
+  return FRC_NetworkCommunication_getWatchdogActive();
+}
+
+}  // extern "C"
+
+namespace hal {
+void InitializeDriverStation() {
   // Set up the occur function internally with NetComm
   NetCommRPCProxy_SetOccurFuncPointer(newDataOccur);
   // Set up our occur reference number
   setNewDataOccurRef(refNumber);
-
-  initialized = true;
+  FRC_NetworkCommunication_setNewTcpDataOccurRef(tcpRefNumber);
 }
-
-/*
- * Releases the DS Mutex to allow proper shutdown of any threads that are
- * waiting on it.
- */
-void HAL_ReleaseDSMutex(void) {
-  newDataOccur(refNumber);
-}
-
-}  // extern "C"
+}  // namespace hal
diff --git a/third_party/allwpilib/hal/src/main/native/athena/HAL.cpp b/third_party/allwpilib/hal/src/main/native/athena/HAL.cpp
index edff3fc..5977724 100644
--- a/third_party/allwpilib/hal/src/main/native/athena/HAL.cpp
+++ b/third_party/allwpilib/hal/src/main/native/athena/HAL.cpp
@@ -18,9 +18,14 @@
 #include <FRC_NetworkCommunication/LoadOut.h>
 #include <FRC_NetworkCommunication/UsageReporting.h>
 #include <fmt/format.h>
+#include <wpi/MemoryBuffer.h>
+#include <wpi/SmallString.h>
+#include <wpi/StringExtras.h>
+#include <wpi/fs.h>
 #include <wpi/mutex.h>
 #include <wpi/timestamp.h>
 
+#include "FPGACalls.h"
 #include "HALInitializer.h"
 #include "HALInternal.h"
 #include "hal/ChipObject.h"
@@ -28,6 +33,8 @@
 #include "hal/Errors.h"
 #include "hal/Notifier.h"
 #include "hal/handles/HandlesInternal.h"
+#include "hal/roborio/InterruptManager.h"
+#include "visa/visa.h"
 
 using namespace hal;
 
@@ -35,9 +42,14 @@
 static std::unique_ptr<tSysWatchdog> watchdog;
 static uint64_t dsStartTime;
 
+static char roboRioCommentsString[64];
+static size_t roboRioCommentsStringSize;
+static bool roboRioCommentsStringInitialized;
+
 using namespace hal;
 
 namespace hal {
+void InitializeDriverStation();
 namespace init {
 void InitializeHAL() {
   InitializeCTREPCM();
@@ -76,6 +88,7 @@
 }  // namespace init
 
 void ReleaseFPGAInterrupt(int32_t interruptNumber) {
+  hal::init::CheckInit();
   if (!global) {
     return;
   }
@@ -222,6 +235,7 @@
 }
 
 int32_t HAL_GetFPGAVersion(int32_t* status) {
+  hal::init::CheckInit();
   if (!global) {
     *status = NiFpga_Status_ResourceNotInitialized;
     return 0;
@@ -230,6 +244,7 @@
 }
 
 int64_t HAL_GetFPGARevision(int32_t* status) {
+  hal::init::CheckInit();
   if (!global) {
     *status = NiFpga_Status_ResourceNotInitialized;
     return 0;
@@ -237,7 +252,83 @@
   return global->readRevision(status);
 }
 
+size_t HAL_GetSerialNumber(char* buffer, size_t size) {
+  const char* serialNum = std::getenv("serialnum");
+  if (serialNum) {
+    std::strncpy(buffer, serialNum, size);
+    buffer[size - 1] = '\0';
+    return std::strlen(buffer);
+  } else {
+    if (size > 0) {
+      buffer[0] = '\0';
+    }
+    return 0;
+  }
+}
+
+void InitializeRoboRioComments(void) {
+  if (!roboRioCommentsStringInitialized) {
+    std::error_code ec;
+    std::unique_ptr<wpi::MemoryBuffer> fileBuffer =
+        wpi::MemoryBuffer::GetFile("/etc/machine-info", ec);
+
+    std::string_view fileContents;
+    if (fileBuffer && !ec) {
+      fileContents =
+          std::string_view(reinterpret_cast<const char*>(fileBuffer->begin()),
+                           fileBuffer->size());
+    } else {
+      roboRioCommentsStringSize = 0;
+      roboRioCommentsStringInitialized = true;
+      return;
+    }
+    std::string_view searchString = "PRETTY_HOSTNAME=\"";
+
+    size_t start = fileContents.find(searchString);
+    if (start == std::string_view::npos) {
+      roboRioCommentsStringSize = 0;
+      roboRioCommentsStringInitialized = true;
+      return;
+    }
+    start += searchString.size();
+    size_t end = fileContents.find("\"", start);
+    if (end == std::string_view::npos) {
+      end = fileContents.size();
+    }
+    std::string_view escapedComments = wpi::slice(fileContents, start, end);
+    wpi::SmallString<64> buf;
+    auto [unescapedComments, rem] = wpi::UnescapeCString(escapedComments, buf);
+    unescapedComments.copy(roboRioCommentsString,
+                           sizeof(roboRioCommentsString));
+
+    if (unescapedComments.size() > sizeof(roboRioCommentsString)) {
+      roboRioCommentsStringSize = sizeof(roboRioCommentsString);
+    } else {
+      roboRioCommentsStringSize = unescapedComments.size();
+    }
+    roboRioCommentsStringInitialized = true;
+  }
+}
+
+size_t HAL_GetComments(char* buffer, size_t size) {
+  if (!roboRioCommentsStringInitialized) {
+    InitializeRoboRioComments();
+  }
+  size_t toCopy = size;
+  if (size > roboRioCommentsStringSize) {
+    toCopy = roboRioCommentsStringSize;
+  }
+  std::memcpy(buffer, roboRioCommentsString, toCopy);
+  if (toCopy < size) {
+    buffer[toCopy] = '\0';
+  } else {
+    buffer[toCopy - 1] = '\0';
+  }
+  return toCopy;
+}
+
 uint64_t HAL_GetFPGATime(int32_t* status) {
+  hal::init::CheckInit();
   if (!global) {
     *status = NiFpga_Status_ResourceNotInitialized;
     return 0;
@@ -284,6 +375,7 @@
 }
 
 HAL_Bool HAL_GetFPGAButton(int32_t* status) {
+  hal::init::CheckInit();
   if (!global) {
     *status = NiFpga_Status_ResourceNotInitialized;
     return false;
@@ -292,6 +384,7 @@
 }
 
 HAL_Bool HAL_GetSystemActive(int32_t* status) {
+  hal::init::CheckInit();
   if (!watchdog) {
     *status = NiFpga_Status_ResourceNotInitialized;
     return false;
@@ -300,6 +393,7 @@
 }
 
 HAL_Bool HAL_GetBrownedOut(int32_t* status) {
+  hal::init::CheckInit();
   if (!watchdog) {
     *status = NiFpga_Status_ResourceNotInitialized;
     return false;
@@ -365,6 +459,11 @@
     return true;
   }
 
+  int fpgaInit = hal::init::InitializeFPGA();
+  if (fpgaInit != HAL_SUCCESS) {
+    return false;
+  }
+
   hal::init::InitializeHAL();
 
   hal::init::HAL_IsInitialized.store(true);
@@ -397,7 +496,9 @@
     return false;
   }
 
-  HAL_InitializeDriverStation();
+  InterruptManager::Initialize(global->getSystemInterface());
+
+  hal::InitializeDriverStation();
 
   dsStartTime = HAL_GetFPGATime(&status);
   if (status != 0) {
diff --git a/third_party/allwpilib/hal/src/main/native/athena/InterruptManager.cpp b/third_party/allwpilib/hal/src/main/native/athena/InterruptManager.cpp
new file mode 100644
index 0000000..420f806
--- /dev/null
+++ b/third_party/allwpilib/hal/src/main/native/athena/InterruptManager.cpp
@@ -0,0 +1,72 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "hal/roborio/InterruptManager.h"
+
+#include <fmt/format.h>
+
+#include "FPGACalls.h"
+#include "HALInternal.h"
+#include "dlfcn.h"
+#include "hal/Errors.h"
+
+using namespace hal;
+
+InterruptManager& InterruptManager::GetInstance() {
+  static InterruptManager manager;
+  return manager;
+}
+
+void InterruptManager::Initialize(tSystemInterface* baseSystem) {
+  auto& manager = GetInstance();
+  manager.fpgaSession = baseSystem->getHandle();
+}
+
+NiFpga_IrqContext InterruptManager::GetContext() noexcept {
+  NiFpga_IrqContext context;
+  HAL_NiFpga_ReserveIrqContext(fpgaSession, &context);
+  return context;
+}
+
+void InterruptManager::ReleaseContext(NiFpga_IrqContext context) noexcept {
+  HAL_NiFpga_UnreserveIrqContext(fpgaSession, context);
+}
+
+uint32_t InterruptManager::WaitForInterrupt(NiFpga_IrqContext context,
+                                            uint32_t mask, bool ignorePrevious,
+                                            uint32_t timeoutMs,
+                                            int32_t* status) {
+  {
+    // Make sure we can safely use this
+    std::scoped_lock lock(currentMaskMutex);
+    if ((currentMask & mask) != 0) {
+      *status = PARAMETER_OUT_OF_RANGE;
+      hal::SetLastError(
+          status, fmt::format("Interrupt mask {} has bits {} already in use",
+                              mask, (currentMask & mask)));
+      return 0;
+    }
+    currentMask |= mask;
+  }
+
+  if (ignorePrevious) {
+    HAL_NiFpga_AcknowledgeIrqs(fpgaSession, mask);
+  }
+
+  uint32_t irqsAsserted = 0;
+  NiFpga_Bool timedOut = 0;
+  *status = HAL_NiFpga_WaitOnIrqs(fpgaSession, context, mask, timeoutMs,
+                                  &irqsAsserted, &timedOut);
+
+  if (!timedOut) {
+    HAL_NiFpga_AcknowledgeIrqs(fpgaSession, irqsAsserted);
+  }
+
+  {
+    std::scoped_lock lock(currentMaskMutex);
+    currentMask &= ~mask;
+  }
+
+  return irqsAsserted;
+}
diff --git a/third_party/allwpilib/hal/src/main/native/athena/Interrupts.cpp b/third_party/allwpilib/hal/src/main/native/athena/Interrupts.cpp
index 943a1aa..e40c6f4 100644
--- a/third_party/allwpilib/hal/src/main/native/athena/Interrupts.cpp
+++ b/third_party/allwpilib/hal/src/main/native/athena/Interrupts.cpp
@@ -17,6 +17,7 @@
 #include "hal/HALBase.h"
 #include "hal/handles/HandlesInternal.h"
 #include "hal/handles/LimitedHandleResource.h"
+#include "hal/roborio/InterruptManager.h"
 
 using namespace hal;
 
@@ -24,7 +25,9 @@
 
 struct Interrupt {
   std::unique_ptr<tInterrupt> anInterrupt;
-  std::unique_ptr<tInterruptManager> manager;
+  InterruptManager& manager = InterruptManager::GetInstance();
+  NiFpga_IrqContext irqContext = nullptr;
+  uint32_t mask;
 };
 
 }  // namespace
@@ -55,8 +58,8 @@
   // Expects the calling leaf class to allocate an interrupt index.
   anInterrupt->anInterrupt.reset(tInterrupt::create(interruptIndex, status));
   anInterrupt->anInterrupt->writeConfig_WaitForAck(false, status);
-  anInterrupt->manager = std::make_unique<tInterruptManager>(
-      (1u << interruptIndex) | (1u << (interruptIndex + 8u)), true, status);
+  anInterrupt->irqContext = anInterrupt->manager.GetContext();
+  anInterrupt->mask = (1u << interruptIndex) | (1u << (interruptIndex + 8u));
   return handle;
 }
 
@@ -66,6 +69,9 @@
   if (anInterrupt == nullptr) {
     return;
   }
+  if (anInterrupt->irqContext) {
+    anInterrupt->manager.ReleaseContext(anInterrupt->irqContext);
+  }
 }
 
 int64_t HAL_WaitForInterrupt(HAL_InterruptHandle interruptHandle,
@@ -78,8 +84,33 @@
     return 0;
   }
 
-  result = anInterrupt->manager->watch(static_cast<int32_t>(timeout * 1e3),
-                                       ignorePrevious, status);
+  result = anInterrupt->manager.WaitForInterrupt(
+      anInterrupt->irqContext, anInterrupt->mask, ignorePrevious,
+      static_cast<uint32_t>(timeout * 1e3), status);
+
+  // Don't report a timeout as an error - the return code is enough to tell
+  // that a timeout happened.
+  if (*status == -NiFpga_Status_IrqTimeout) {
+    *status = NiFpga_Status_Success;
+  }
+
+  return result;
+}
+
+int64_t HAL_WaitForMultipleInterrupts(HAL_InterruptHandle interruptHandle,
+                                      int64_t mask, double timeout,
+                                      HAL_Bool ignorePrevious,
+                                      int32_t* status) {
+  uint32_t result;
+  auto anInterrupt = interruptHandles->Get(interruptHandle);
+  if (anInterrupt == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+
+  result = anInterrupt->manager.WaitForInterrupt(
+      anInterrupt->irqContext, mask, ignorePrevious,
+      static_cast<uint32_t>(timeout * 1e3), status);
 
   // Don't report a timeout as an error - the return code is enough to tell
   // that a timeout happened.
diff --git a/third_party/allwpilib/hal/src/main/native/athena/Notifier.cpp b/third_party/allwpilib/hal/src/main/native/athena/Notifier.cpp
index d684031..9c818d8 100644
--- a/third_party/allwpilib/hal/src/main/native/athena/Notifier.cpp
+++ b/third_party/allwpilib/hal/src/main/native/athena/Notifier.cpp
@@ -20,6 +20,7 @@
 #include "hal/HAL.h"
 #include "hal/Threads.h"
 #include "hal/handles/UnlimitedHandleResource.h"
+#include "hal/roborio/InterruptManager.h"
 
 using namespace hal;
 
@@ -106,15 +107,21 @@
 }
 
 static void notifierThreadMain() {
-  tRioStatusCode status = 0;
-  tInterruptManager manager{1 << kTimerInterruptNumber, true, &status};
+  InterruptManager& manager = InterruptManager::GetInstance();
+  NiFpga_IrqContext context = manager.GetContext();
+  uint32_t mask = 1 << kTimerInterruptNumber;
+  int32_t status = 0;
+
   while (notifierRunning) {
-    auto triggeredMask = manager.watch(10000, false, &status);
+    status = 0;
+    auto triggeredMask =
+        manager.WaitForInterrupt(context, mask, false, 10000, &status);
     if (!notifierRunning) {
       break;
     }
-    if (triggeredMask == 0)
+    if (triggeredMask == 0) {
       continue;
+    }
     alarmCallback();
   }
 }
@@ -195,8 +202,9 @@
 
 void HAL_StopNotifier(HAL_NotifierHandle notifierHandle, int32_t* status) {
   auto notifier = notifierHandles->Get(notifierHandle);
-  if (!notifier)
+  if (!notifier) {
     return;
+  }
 
   {
     std::scoped_lock lock(notifier->mutex);
@@ -209,8 +217,9 @@
 
 void HAL_CleanNotifier(HAL_NotifierHandle notifierHandle, int32_t* status) {
   auto notifier = notifierHandles->Free(notifierHandle);
-  if (!notifier)
+  if (!notifier) {
     return;
+  }
 
   // Just in case HAL_StopNotifier() wasn't called...
   {
@@ -244,8 +253,9 @@
 void HAL_UpdateNotifierAlarm(HAL_NotifierHandle notifierHandle,
                              uint64_t triggerTime, int32_t* status) {
   auto notifier = notifierHandles->Get(notifierHandle);
-  if (!notifier)
+  if (!notifier) {
     return;
+  }
 
   {
     std::scoped_lock lock(notifier->mutex);
@@ -270,8 +280,9 @@
 void HAL_CancelNotifierAlarm(HAL_NotifierHandle notifierHandle,
                              int32_t* status) {
   auto notifier = notifierHandles->Get(notifierHandle);
-  if (!notifier)
+  if (!notifier) {
     return;
+  }
 
   {
     std::scoped_lock lock(notifier->mutex);
@@ -282,8 +293,9 @@
 uint64_t HAL_WaitForNotifierAlarm(HAL_NotifierHandle notifierHandle,
                                   int32_t* status) {
   auto notifier = notifierHandles->Get(notifierHandle);
-  if (!notifier)
+  if (!notifier) {
     return 0;
+  }
   std::unique_lock lock(notifier->mutex);
   notifier->cond.wait(lock, [&] {
     return !notifier->active || notifier->triggeredTime != UINT64_MAX;
diff --git a/third_party/allwpilib/hal/src/main/native/athena/PortsInternal.h b/third_party/allwpilib/hal/src/main/native/athena/PortsInternal.h
index 18ce569..ab085dd 100644
--- a/third_party/allwpilib/hal/src/main/native/athena/PortsInternal.h
+++ b/third_party/allwpilib/hal/src/main/native/athena/PortsInternal.h
@@ -3,6 +3,8 @@
 // the WPILib BSD license file in the root directory of this project.
 
 #pragma once
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Wdeprecated-enum-enum-conversion"
 
 #include <stdint.h>
 
@@ -23,7 +25,8 @@
     kNumDigitalHeaders + kNumDigitalMXPChannels + kNumDigitalSPIPortChannels;
 constexpr int32_t kNumPWMChannels = tPWM::kNumMXPRegisters + kNumPWMHeaders;
 constexpr int32_t kNumDigitalPWMOutputs =
-    tDIO::kNumPWMDutyCycleAElements + tDIO::kNumPWMDutyCycleBElements;
+    static_cast<int32_t>(tDIO::kNumPWMDutyCycleAElements) +
+    static_cast<int32_t>(tDIO::kNumPWMDutyCycleBElements);
 constexpr int32_t kNumEncoders = tEncoder::kNumSystems;
 constexpr int32_t kNumInterrupts = tInterrupt::kNumSystems;
 constexpr int32_t kNumRelayChannels = 8;
@@ -40,3 +43,5 @@
 constexpr int32_t kNumREVPHChannels = 16;
 
 }  // namespace hal
+
+#pragma GCC diagnostic pop
diff --git a/third_party/allwpilib/hal/src/main/native/athena/REVPH.cpp b/third_party/allwpilib/hal/src/main/native/athena/REVPH.cpp
index 5b18de6..ae3f460 100644
--- a/third_party/allwpilib/hal/src/main/native/athena/REVPH.cpp
+++ b/third_party/allwpilib/hal/src/main/native/athena/REVPH.cpp
@@ -228,18 +228,19 @@
               sizeof(hph->desiredSolenoidsState));
   std::memset(&hph->versionInfo, 0, sizeof(hph->versionInfo));
 
+  int32_t can_status = 0;
+
   // Start closed-loop compressor control by starting solenoid state updates
-  HAL_SendREVPHSolenoidsState(hph.get(), status);
+  HAL_SendREVPHSolenoidsState(hph.get(), &can_status);
 
   return handle;
 }
 
 void HAL_FreeREVPH(HAL_REVPHHandle handle) {
   auto hph = REVPHHandles->Get(handle);
-  if (hph == nullptr)
-    return;
-
-  HAL_CleanCAN(hph->hcan);
+  if (hph) {
+    HAL_CleanCAN(hph->hcan);
+  }
 
   REVPHHandles->Free(handle);
 }
diff --git a/third_party/allwpilib/hal/src/main/native/athena/SPI.cpp b/third_party/allwpilib/hal/src/main/native/athena/SPI.cpp
index 5e628c8..3629eb6 100644
--- a/third_party/allwpilib/hal/src/main/native/athena/SPI.cpp
+++ b/third_party/allwpilib/hal/src/main/native/athena/SPI.cpp
@@ -125,8 +125,8 @@
       // CS0 is not a DIO port, so nothing to allocate
       handle = open("/dev/spidev0.0", O_RDWR);
       if (handle < 0) {
-        fmt::print("Failed to open SPI port {}: {}\n", port,
-                   std::strerror(errno));
+        fmt::print("Failed to open SPI port {}: {}\n",
+                   static_cast<int32_t>(port), std::strerror(errno));
         CommonSPIPortFree();
         return;
       }
@@ -147,8 +147,8 @@
       }
       handle = open("/dev/spidev0.1", O_RDWR);
       if (handle < 0) {
-        fmt::print("Failed to open SPI port {}: {}\n", port,
-                   std::strerror(errno));
+        fmt::print("Failed to open SPI port {}: {}\n",
+                   static_cast<int32_t>(port), std::strerror(errno));
         CommonSPIPortFree();
         HAL_FreeDIOPort(digitalHandles[0]);
         return;
@@ -170,8 +170,8 @@
       }
       handle = open("/dev/spidev0.2", O_RDWR);
       if (handle < 0) {
-        fmt::print("Failed to open SPI port {}: {}\n", port,
-                   std::strerror(errno));
+        fmt::print("Failed to open SPI port {}: {}\n",
+                   static_cast<int32_t>(port), std::strerror(errno));
         CommonSPIPortFree();
         HAL_FreeDIOPort(digitalHandles[1]);
         return;
@@ -193,8 +193,8 @@
       }
       handle = open("/dev/spidev0.3", O_RDWR);
       if (handle < 0) {
-        fmt::print("Failed to open SPI port {}: {}\n", port,
-                   std::strerror(errno));
+        fmt::print("Failed to open SPI port {}: {}\n",
+                   static_cast<int32_t>(port), std::strerror(errno));
         CommonSPIPortFree();
         HAL_FreeDIOPort(digitalHandles[2]);
         return;
@@ -240,8 +240,8 @@
           digitalSystem->readEnableMXPSpecialFunction(status) | 0x00F0, status);
       handle = open("/dev/spidev1.0", O_RDWR);
       if (handle < 0) {
-        fmt::print("Failed to open SPI port {}: {}\n", port,
-                   std::strerror(errno));
+        fmt::print("Failed to open SPI port {}: {}\n",
+                   static_cast<int32_t>(port), std::strerror(errno));
         HAL_FreeDIOPort(digitalHandles[5]);  // free the first port allocated
         HAL_FreeDIOPort(digitalHandles[6]);  // free the second port allocated
         HAL_FreeDIOPort(digitalHandles[7]);  // free the third port allocated
@@ -364,19 +364,27 @@
   ioctl(HAL_GetSPIHandle(port), SPI_IOC_WR_MAX_SPEED_HZ, &speed);
 }
 
-void HAL_SetSPIOpts(HAL_SPIPort port, HAL_Bool msbFirst,
-                    HAL_Bool sampleOnTrailing, HAL_Bool clkIdleHigh) {
+void HAL_SetSPIMode(HAL_SPIPort port, HAL_SPIMode mode) {
   if (port < 0 || port >= kSpiMaxHandles) {
     return;
   }
 
-  uint8_t mode = 0;
-  mode |= (!msbFirst ? 8 : 0);
-  mode |= (clkIdleHigh ? 2 : 0);
-  mode |= (sampleOnTrailing ? 1 : 0);
+  uint8_t mode8 = mode & SPI_MODE_3;
 
   std::scoped_lock lock(spiApiMutexes[port]);
-  ioctl(HAL_GetSPIHandle(port), SPI_IOC_WR_MODE, &mode);
+  ioctl(HAL_GetSPIHandle(port), SPI_IOC_WR_MODE, &mode8);
+}
+
+HAL_SPIMode HAL_GetSPIMode(HAL_SPIPort port) {
+  if (port < 0 || port >= kSpiMaxHandles) {
+    return HAL_SPI_kMode0;
+  }
+
+  uint8_t mode8 = 0;
+
+  std::scoped_lock lock(spiApiMutexes[port]);
+  ioctl(HAL_GetSPIHandle(port), SPI_IOC_RD_MODE, &mode8);
+  return static_cast<HAL_SPIMode>(mode8 & SPI_MODE_3);
 }
 
 void HAL_SetSPIChipSelectActiveHigh(HAL_SPIPort port, int32_t* status) {
diff --git a/third_party/allwpilib/hal/src/main/native/athena/cpp/SerialHelper.cpp b/third_party/allwpilib/hal/src/main/native/athena/cpp/SerialHelper.cpp
index 3831769..fef92d4 100644
--- a/third_party/allwpilib/hal/src/main/native/athena/cpp/SerialHelper.cpp
+++ b/third_party/allwpilib/hal/src/main/native/athena/cpp/SerialHelper.cpp
@@ -193,7 +193,7 @@
     ViSession vSession;
     *status = viOpen(m_resourceHandle, desc, VI_NULL, VI_NULL, &vSession);
     if (*status < 0)
-      goto done;
+      continue;
     *status = 0;
 
     *status = viGetAttribute(vSession, VI_ATTR_INTF_INST_NAME, &osName);
@@ -201,9 +201,9 @@
     // Use a separate close variable so we can check
     ViStatus closeStatus = viClose(vSession);
     if (*status < 0)
-      goto done;
+      continue;
     if (closeStatus < 0)
-      goto done;
+      continue;
     *status = 0;
 
     // split until (/dev/
diff --git a/third_party/allwpilib/hal/src/main/native/athena/mockdata/DriverStationData.cpp b/third_party/allwpilib/hal/src/main/native/athena/mockdata/DriverStationData.cpp
index ba519fc..76a8e8b 100644
--- a/third_party/allwpilib/hal/src/main/native/athena/mockdata/DriverStationData.cpp
+++ b/third_party/allwpilib/hal/src/main/native/athena/mockdata/DriverStationData.cpp
@@ -103,13 +103,13 @@
 
 void HALSIM_SetJoystickType(int32_t stick, int32_t type) {}
 
-void HALSIM_SetJoystickName(int32_t stick, const char* name) {}
+void HALSIM_SetJoystickName(int32_t stick, const char* name, size_t size) {}
 
 void HALSIM_SetJoystickAxisType(int32_t stick, int32_t axis, int32_t type) {}
 
-void HALSIM_SetGameSpecificMessage(const char* message) {}
+void HALSIM_SetGameSpecificMessage(const char* message, size_t size) {}
 
-void HALSIM_SetEventName(const char* name) {}
+void HALSIM_SetEventName(const char* name, size_t size) {}
 
 void HALSIM_SetMatchType(HAL_MatchType type) {}
 
diff --git a/third_party/allwpilib/hal/src/main/native/athena/mockdata/MockHooks.cpp b/third_party/allwpilib/hal/src/main/native/athena/mockdata/MockHooks.cpp
index 0ea05d0..a6a6804 100644
--- a/third_party/allwpilib/hal/src/main/native/athena/mockdata/MockHooks.cpp
+++ b/third_party/allwpilib/hal/src/main/native/athena/mockdata/MockHooks.cpp
@@ -48,4 +48,6 @@
 
 void HALSIM_CancelSimPeriodicAfterCallback(int32_t uid) {}
 
+void HALSIM_CancelAllSimPeriodicCallbacks(void) {}
+
 }  // extern "C"
diff --git a/third_party/allwpilib/hal/src/main/native/athena/mockdata/Reset.cpp b/third_party/allwpilib/hal/src/main/native/athena/mockdata/Reset.cpp
new file mode 100644
index 0000000..7cbeea3
--- /dev/null
+++ b/third_party/allwpilib/hal/src/main/native/athena/mockdata/Reset.cpp
@@ -0,0 +1,5 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+extern "C" void HALSIM_ResetAllSimData(void) {}
diff --git a/third_party/allwpilib/hal/src/main/native/athena/mockdata/RoboRioData.cpp b/third_party/allwpilib/hal/src/main/native/athena/mockdata/RoboRioData.cpp
index 9f6683a..9392fcb 100644
--- a/third_party/allwpilib/hal/src/main/native/athena/mockdata/RoboRioData.cpp
+++ b/third_party/allwpilib/hal/src/main/native/athena/mockdata/RoboRioData.cpp
@@ -29,6 +29,32 @@
 DEFINE_CAPI(int32_t, UserFaults3V3, 0)
 DEFINE_CAPI(double, BrownoutVoltage, 6.75)
 
+int32_t HALSIM_RegisterRoboRioSerialNumberCallback(
+    HAL_RoboRioStringCallback callback, void* param, HAL_Bool initialNotify) {
+  return 0;
+}
+void HALSIM_CancelRoboRioSerialNumberCallback(int32_t uid) {}
+size_t HALSIM_GetRoboRioSerialNumber(char* buffer, size_t size) {
+  if (size > 0) {
+    buffer[0] = '\0';
+  }
+  return 0;
+}
+void HALSIM_SetRoboRioSerialNumber(const char* buffer, size_t size) {}
+
+int32_t HALSIM_RegisterRoboRioCommentsCallback(
+    HAL_RoboRioStringCallback callback, void* param, HAL_Bool initialNotify) {
+  return 0;
+}
+void HALSIM_CancelRoboRioCommentsCallback(int32_t uid) {}
+size_t HALSIM_GetRoboRioComments(char* buffer, size_t size) {
+  if (size > 0) {
+    buffer[0] = '\0';
+  }
+  return 0;
+}
+void HALSIM_SetRoboRioComments(const char* buffer, size_t size) {}
+
 void HALSIM_RegisterRoboRioAllCallbacks(HAL_NotifyCallback callback,
                                         void* param, HAL_Bool initialNotify) {}
 }  // extern "C"
diff --git a/third_party/allwpilib/hal/src/main/native/cpp/jni/CANJNI.cpp b/third_party/allwpilib/hal/src/main/native/cpp/jni/CANJNI.cpp
index 968f656..4ad2a74 100644
--- a/third_party/allwpilib/hal/src/main/native/cpp/jni/CANJNI.cpp
+++ b/third_party/allwpilib/hal/src/main/native/cpp/jni/CANJNI.cpp
@@ -62,9 +62,7 @@
   if (!CheckCANStatus(env, status, *messageIDPtr)) {
     return nullptr;
   }
-  return MakeJByteArray(env,
-                        std::string_view{reinterpret_cast<const char*>(buffer),
-                                         static_cast<size_t>(dataSize)});
+  return MakeJByteArray(env, {buffer, static_cast<size_t>(dataSize)});
 }
 
 /*
@@ -93,4 +91,90 @@
                      txFullCount, receiveErrorCount, transmitErrorCount);
 }
 
+/*
+ * Class:     edu_wpi_first_hal_can_CANJNI
+ * Method:    openCANStreamSession
+ * Signature: (III)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_can_CANJNI_openCANStreamSession
+  (JNIEnv* env, jclass, jint messageID, jint messageIDMask, jint maxMessages)
+{
+  uint32_t handle = 0;
+  int32_t status = 0;
+  HAL_CAN_OpenStreamSession(&handle, static_cast<uint32_t>(messageID),
+                            static_cast<uint32_t>(messageIDMask),
+                            static_cast<uint32_t>(maxMessages), &status);
+
+  if (!CheckStatus(env, status)) {
+    return static_cast<jint>(0);
+  }
+
+  return static_cast<jint>(handle);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_can_CANJNI
+ * Method:    closeCANStreamSession
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_can_CANJNI_closeCANStreamSession
+  (JNIEnv* env, jclass, jint sessionHandle)
+{
+  HAL_CAN_CloseStreamSession(static_cast<uint32_t>(sessionHandle));
+}
+
+/*
+ * Class:     edu_wpi_first_hal_can_CANJNI
+ * Method:    readCANStreamSession
+ * Signature: (I[Ljava/lang/Object;I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_can_CANJNI_readCANStreamSession
+  (JNIEnv* env, jclass, jint sessionHandle, jobjectArray messages,
+   jint messagesToRead)
+{
+  uint32_t handle = static_cast<uint32_t>(sessionHandle);
+  uint32_t messagesRead = 0;
+
+  wpi::SmallVector<HAL_CANStreamMessage, 16> messageBuffer;
+  messageBuffer.resize_for_overwrite(messagesToRead);
+
+  int32_t status = 0;
+
+  HAL_CAN_ReadStreamSession(handle, messageBuffer.begin(),
+                            static_cast<uint32_t>(messagesToRead),
+                            &messagesRead, &status);
+
+  if (status == HAL_ERR_CANSessionMux_MessageNotFound || messagesRead == 0) {
+    return 0;
+  }
+
+  if (!CheckStatus(env, status)) {
+    return 0;
+  }
+
+  for (int i = 0; i < static_cast<int>(messagesRead); i++) {
+    struct HAL_CANStreamMessage* msg = &messageBuffer[i];
+    JLocal<jobject> elem{
+        env, static_cast<jstring>(env->GetObjectArrayElement(messages, i))};
+    if (!elem) {
+      // TODO decide if should throw
+      continue;
+    }
+    JLocal<jbyteArray> toSetArray{
+        env, SetCANStreamObject(env, elem, msg->dataSize, msg->messageID,
+                                msg->timeStamp)};
+    auto javaLen = env->GetArrayLength(toSetArray);
+    if (javaLen < msg->dataSize) {
+      msg->dataSize = javaLen;
+    }
+    env->SetByteArrayRegion(toSetArray, 0, msg->dataSize,
+                            reinterpret_cast<jbyte*>(msg->data));
+  }
+
+  return static_cast<jint>(messagesRead);
+}
+
 }  // extern "C"
diff --git a/third_party/allwpilib/hal/src/main/native/cpp/jni/DIOJNI.cpp b/third_party/allwpilib/hal/src/main/native/cpp/jni/DIOJNI.cpp
index 5cd6c2e..dee34c7 100644
--- a/third_party/allwpilib/hal/src/main/native/cpp/jni/DIOJNI.cpp
+++ b/third_party/allwpilib/hal/src/main/native/cpp/jni/DIOJNI.cpp
@@ -146,6 +146,20 @@
 
 /*
  * Class:     edu_wpi_first_hal_DIOJNI
+ * Method:    pulseMultiple
+ * Signature: (JD)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_DIOJNI_pulseMultiple
+  (JNIEnv* env, jclass, jlong channelMask, jdouble value)
+{
+  int32_t status = 0;
+  HAL_PulseMultiple(static_cast<uint32_t>(channelMask), value, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DIOJNI
  * Method:    isPulsing
  * Signature: (I)Z
  */
@@ -248,6 +262,20 @@
 
 /*
  * Class:     edu_wpi_first_hal_DIOJNI
+ * Method:    setDigitalPWMPPS
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_DIOJNI_setDigitalPWMPPS
+  (JNIEnv* env, jclass, jint id, jdouble value)
+{
+  int32_t status = 0;
+  HAL_SetDigitalPWMPPS((HAL_DigitalPWMHandle)id, value, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DIOJNI
  * Method:    setDigitalPWMOutputChannel
  * Signature: (II)V
  */
diff --git a/third_party/allwpilib/hal/src/main/native/cpp/jni/DriverStationJNI.cpp b/third_party/allwpilib/hal/src/main/native/cpp/jni/DriverStationJNI.cpp
new file mode 100644
index 0000000..f050f02
--- /dev/null
+++ b/third_party/allwpilib/hal/src/main/native/cpp/jni/DriverStationJNI.cpp
@@ -0,0 +1,450 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <jni.h>
+
+#include <cassert>
+
+#include <fmt/format.h>
+#include <wpi/jni_util.h>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_DriverStationJNI.h"
+#include "hal/DriverStation.h"
+#include "hal/FRCUsageReporting.h"
+#include "hal/HALBase.h"
+
+// TODO Static asserts
+
+using namespace hal;
+using namespace wpi::java;
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_DriverStationJNI
+ * Method:    observeUserProgramStarting
+ * Signature: ()V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_DriverStationJNI_observeUserProgramStarting
+  (JNIEnv*, jclass)
+{
+  HAL_ObserveUserProgramStarting();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DriverStationJNI
+ * Method:    observeUserProgramDisabled
+ * Signature: ()V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_DriverStationJNI_observeUserProgramDisabled
+  (JNIEnv*, jclass)
+{
+  HAL_ObserveUserProgramDisabled();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DriverStationJNI
+ * Method:    observeUserProgramAutonomous
+ * Signature: ()V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_DriverStationJNI_observeUserProgramAutonomous
+  (JNIEnv*, jclass)
+{
+  HAL_ObserveUserProgramAutonomous();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DriverStationJNI
+ * Method:    observeUserProgramTeleop
+ * Signature: ()V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_DriverStationJNI_observeUserProgramTeleop
+  (JNIEnv*, jclass)
+{
+  HAL_ObserveUserProgramTeleop();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DriverStationJNI
+ * Method:    observeUserProgramTest
+ * Signature: ()V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_DriverStationJNI_observeUserProgramTest
+  (JNIEnv*, jclass)
+{
+  HAL_ObserveUserProgramTest();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DriverStationJNI
+ * Method:    report
+ * Signature: (IIILjava/lang/String;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_DriverStationJNI_report
+  (JNIEnv* paramEnv, jclass, jint paramResource, jint paramInstanceNumber,
+   jint paramContext, jstring paramFeature)
+{
+  JStringRef featureStr{paramEnv, paramFeature};
+  jint returnValue = HAL_Report(paramResource, paramInstanceNumber,
+                                paramContext, featureStr.c_str());
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DriverStationJNI
+ * Method:    nativeGetControlWord
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_DriverStationJNI_nativeGetControlWord
+  (JNIEnv*, jclass)
+{
+  static_assert(sizeof(HAL_ControlWord) == sizeof(jint),
+                "Java int must match the size of control word");
+  HAL_ControlWord controlWord;
+  HAL_GetControlWord(&controlWord);
+  jint retVal = 0;
+  std::memcpy(&retVal, &controlWord, sizeof(HAL_ControlWord));
+  return retVal;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DriverStationJNI
+ * Method:    nativeGetAllianceStation
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_DriverStationJNI_nativeGetAllianceStation
+  (JNIEnv*, jclass)
+{
+  int32_t status = 0;
+  auto allianceStation = HAL_GetAllianceStation(&status);
+  return static_cast<jint>(allianceStation);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DriverStationJNI
+ * Method:    getJoystickAxesRaw
+ * Signature: (B[I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_DriverStationJNI_getJoystickAxesRaw
+  (JNIEnv* env, jclass, jbyte joystickNum, jintArray axesRawArray)
+{
+  HAL_JoystickAxes axes;
+  HAL_GetJoystickAxes(joystickNum, &axes);
+
+  jsize javaSize = env->GetArrayLength(axesRawArray);
+  if (axes.count > javaSize) {
+    ThrowIllegalArgumentException(
+        env,
+        fmt::format("Native array size larger then passed in java array "
+                    "size\nNative Size: {} Java Size: {}",
+                    static_cast<int>(axes.count), static_cast<int>(javaSize)));
+    return 0;
+  }
+
+  jint raw[HAL_kMaxJoystickAxes];
+  for (int16_t i = 0; i < axes.count; i++) {
+    raw[i] = axes.raw[i];
+  }
+  env->SetIntArrayRegion(axesRawArray, 0, axes.count, raw);
+
+  return axes.count;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DriverStationJNI
+ * Method:    getJoystickAxes
+ * Signature: (B[F)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_DriverStationJNI_getJoystickAxes
+  (JNIEnv* env, jclass, jbyte joystickNum, jfloatArray axesArray)
+{
+  HAL_JoystickAxes axes;
+  HAL_GetJoystickAxes(joystickNum, &axes);
+
+  jsize javaSize = env->GetArrayLength(axesArray);
+  if (axes.count > javaSize) {
+    ThrowIllegalArgumentException(
+        env,
+        fmt::format("Native array size larger then passed in java array "
+                    "size\nNative Size: {} Java Size: {}",
+                    static_cast<int>(axes.count), static_cast<int>(javaSize)));
+    return 0;
+  }
+
+  env->SetFloatArrayRegion(axesArray, 0, axes.count, axes.axes);
+
+  return axes.count;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DriverStationJNI
+ * Method:    getJoystickPOVs
+ * Signature: (B[S)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_DriverStationJNI_getJoystickPOVs
+  (JNIEnv* env, jclass, jbyte joystickNum, jshortArray povsArray)
+{
+  HAL_JoystickPOVs povs;
+  HAL_GetJoystickPOVs(joystickNum, &povs);
+
+  jsize javaSize = env->GetArrayLength(povsArray);
+  if (povs.count > javaSize) {
+    ThrowIllegalArgumentException(
+        env,
+        fmt::format("Native array size larger then passed in java array "
+                    "size\nNative Size: {} Java Size: {}",
+                    static_cast<int>(povs.count), static_cast<int>(javaSize)));
+    return 0;
+  }
+
+  env->SetShortArrayRegion(povsArray, 0, povs.count, povs.povs);
+
+  return povs.count;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DriverStationJNI
+ * Method:    getAllJoystickData
+ * Signature: ([F[B[S[J)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_DriverStationJNI_getAllJoystickData
+  (JNIEnv* env, jclass cls, jfloatArray axesArray, jbyteArray rawAxesArray,
+   jshortArray povsArray, jlongArray buttonsAndMetadataArray)
+{
+  HAL_JoystickAxes axes[HAL_kMaxJoysticks];
+  HAL_JoystickPOVs povs[HAL_kMaxJoysticks];
+  HAL_JoystickButtons buttons[HAL_kMaxJoysticks];
+
+  HAL_GetAllJoystickData(axes, povs, buttons);
+
+  CriticalJFloatArrayRef jAxes(env, axesArray);
+  CriticalJByteArrayRef jRawAxes(env, rawAxesArray);
+  CriticalJShortArrayRef jPovs(env, povsArray);
+  CriticalJLongArrayRef jButtons(env, buttonsAndMetadataArray);
+
+  static_assert(sizeof(jAxes[0]) == sizeof(axes[0].axes[0]));
+  static_assert(sizeof(jRawAxes[0]) == sizeof(axes[0].raw[0]));
+  static_assert(sizeof(jPovs[0]) == sizeof(povs[0].povs[0]));
+
+  for (size_t i = 0; i < HAL_kMaxJoysticks; i++) {
+    std::memcpy(&jAxes[i * HAL_kMaxJoystickAxes], axes[i].axes,
+                sizeof(axes[i].axes));
+    std::memcpy(&jRawAxes[i * HAL_kMaxJoystickAxes], axes[i].raw,
+                sizeof(axes[i].raw));
+    std::memcpy(&jPovs[i * HAL_kMaxJoystickPOVs], povs[i].povs,
+                sizeof(povs[i].povs));
+    jButtons[i * 4] = axes[i].count;
+    jButtons[(i * 4) + 1] = povs[i].count;
+    jButtons[(i * 4) + 2] = buttons[i].count;
+    jButtons[(i * 4) + 3] = buttons[i].buttons;
+  }
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DriverStationJNI
+ * Method:    getJoystickButtons
+ * Signature: (BLjava/lang/Object;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_DriverStationJNI_getJoystickButtons
+  (JNIEnv* env, jclass, jbyte joystickNum, jobject count)
+{
+  HAL_JoystickButtons joystickButtons;
+  HAL_GetJoystickButtons(joystickNum, &joystickButtons);
+  jbyte* countPtr =
+      reinterpret_cast<jbyte*>(env->GetDirectBufferAddress(count));
+  *countPtr = joystickButtons.count;
+  return joystickButtons.buttons;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DriverStationJNI
+ * Method:    setJoystickOutputs
+ * Signature: (BISS)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_DriverStationJNI_setJoystickOutputs
+  (JNIEnv*, jclass, jbyte port, jint outputs, jshort leftRumble,
+   jshort rightRumble)
+{
+  return HAL_SetJoystickOutputs(port, outputs, leftRumble, rightRumble);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DriverStationJNI
+ * Method:    getJoystickIsXbox
+ * Signature: (B)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_DriverStationJNI_getJoystickIsXbox
+  (JNIEnv*, jclass, jbyte port)
+{
+  return HAL_GetJoystickIsXbox(port);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DriverStationJNI
+ * Method:    getJoystickType
+ * Signature: (B)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_DriverStationJNI_getJoystickType
+  (JNIEnv*, jclass, jbyte port)
+{
+  return HAL_GetJoystickType(port);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DriverStationJNI
+ * Method:    getJoystickName
+ * Signature: (B)Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_first_hal_DriverStationJNI_getJoystickName
+  (JNIEnv* env, jclass, jbyte port)
+{
+  char* joystickName = HAL_GetJoystickName(port);
+  jstring str = MakeJString(env, joystickName);
+  HAL_FreeJoystickName(joystickName);
+  return str;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DriverStationJNI
+ * Method:    getJoystickAxisType
+ * Signature: (BB)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_DriverStationJNI_getJoystickAxisType
+  (JNIEnv*, jclass, jbyte joystickNum, jbyte axis)
+{
+  return HAL_GetJoystickAxisType(joystickNum, axis);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DriverStationJNI
+ * Method:    getMatchTime
+ * Signature: ()D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_DriverStationJNI_getMatchTime
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  return HAL_GetMatchTime(&status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DriverStationJNI
+ * Method:    getMatchInfo
+ * Signature: (Ljava/lang/Object;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_DriverStationJNI_getMatchInfo
+  (JNIEnv* env, jclass, jobject info)
+{
+  HAL_MatchInfo matchInfo;
+  auto status = HAL_GetMatchInfo(&matchInfo);
+  if (status == 0) {
+    SetMatchInfoObject(env, info, matchInfo);
+  }
+  return status;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DriverStationJNI
+ * Method:    sendError
+ * Signature: (ZIZLjava/lang/String;Ljava/lang/String;Ljava/lang/String;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_DriverStationJNI_sendError
+  (JNIEnv* env, jclass, jboolean isError, jint errorCode, jboolean isLVCode,
+   jstring details, jstring location, jstring callStack, jboolean printMsg)
+{
+  JStringRef detailsStr{env, details};
+  JStringRef locationStr{env, location};
+  JStringRef callStackStr{env, callStack};
+
+  jint returnValue =
+      HAL_SendError(isError, errorCode, isLVCode, detailsStr.c_str(),
+                    locationStr.c_str(), callStackStr.c_str(), printMsg);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DriverStationJNI
+ * Method:    sendConsoleLine
+ * Signature: (Ljava/lang/String;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_DriverStationJNI_sendConsoleLine
+  (JNIEnv* env, jclass, jstring line)
+{
+  JStringRef lineStr{env, line};
+
+  jint returnValue = HAL_SendConsoleLine(lineStr.c_str());
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DriverStationJNI
+ * Method:    refreshDSData
+ * Signature: ()V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_DriverStationJNI_refreshDSData
+  (JNIEnv*, jclass)
+{
+  HAL_RefreshDSData();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DriverStationJNI
+ * Method:    provideNewDataEventHandle
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_DriverStationJNI_provideNewDataEventHandle
+  (JNIEnv*, jclass, jint handle)
+{
+  HAL_ProvideNewDataEventHandle(handle);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DriverStationJNI
+ * Method:    removeNewDataEventHandle
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_DriverStationJNI_removeNewDataEventHandle
+  (JNIEnv*, jclass, jint handle)
+{
+  HAL_RemoveNewDataEventHandle(handle);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DriverStationJNI
+ * Method:    getOutputsActive
+ * Signature: ()Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_DriverStationJNI_getOutputsActive
+  (JNIEnv*, jclass)
+{
+  return HAL_GetOutputsEnabled();
+}
+}  // extern "C"
diff --git a/third_party/allwpilib/hal/src/main/native/cpp/jni/DutyCycleJNI.cpp b/third_party/allwpilib/hal/src/main/native/cpp/jni/DutyCycleJNI.cpp
index 96cc27b..f83e13c 100644
--- a/third_party/allwpilib/hal/src/main/native/cpp/jni/DutyCycleJNI.cpp
+++ b/third_party/allwpilib/hal/src/main/native/cpp/jni/DutyCycleJNI.cpp
@@ -74,15 +74,15 @@
 
 /*
  * Class:     edu_wpi_first_hal_DutyCycleJNI
- * Method:    getOutputRaw
+ * Method:    getHighTime
  * Signature: (I)I
  */
 JNIEXPORT jint JNICALL
-Java_edu_wpi_first_hal_DutyCycleJNI_getOutputRaw
+Java_edu_wpi_first_hal_DutyCycleJNI_getHighTime
   (JNIEnv* env, jclass, jint handle)
 {
   int32_t status = 0;
-  auto retVal = HAL_GetDutyCycleOutputRaw(
+  auto retVal = HAL_GetDutyCycleHighTime(
       static_cast<HAL_DutyCycleHandle>(handle), &status);
   CheckStatus(env, status);
   return retVal;
diff --git a/third_party/allwpilib/hal/src/main/native/cpp/jni/HAL.cpp b/third_party/allwpilib/hal/src/main/native/cpp/jni/HAL.cpp
index 4e26032..b603a76 100644
--- a/third_party/allwpilib/hal/src/main/native/cpp/jni/HAL.cpp
+++ b/third_party/allwpilib/hal/src/main/native/cpp/jni/HAL.cpp
@@ -108,310 +108,6 @@
 
 /*
  * Class:     edu_wpi_first_hal_HAL
- * Method:    observeUserProgramStarting
- * Signature: ()V
- */
-JNIEXPORT void JNICALL
-Java_edu_wpi_first_hal_HAL_observeUserProgramStarting
-  (JNIEnv*, jclass)
-{
-  HAL_ObserveUserProgramStarting();
-}
-
-/*
- * Class:     edu_wpi_first_hal_HAL
- * Method:    observeUserProgramDisabled
- * Signature: ()V
- */
-JNIEXPORT void JNICALL
-Java_edu_wpi_first_hal_HAL_observeUserProgramDisabled
-  (JNIEnv*, jclass)
-{
-  HAL_ObserveUserProgramDisabled();
-}
-
-/*
- * Class:     edu_wpi_first_hal_HAL
- * Method:    observeUserProgramAutonomous
- * Signature: ()V
- */
-JNIEXPORT void JNICALL
-Java_edu_wpi_first_hal_HAL_observeUserProgramAutonomous
-  (JNIEnv*, jclass)
-{
-  HAL_ObserveUserProgramAutonomous();
-}
-
-/*
- * Class:     edu_wpi_first_hal_HAL
- * Method:    observeUserProgramTeleop
- * Signature: ()V
- */
-JNIEXPORT void JNICALL
-Java_edu_wpi_first_hal_HAL_observeUserProgramTeleop
-  (JNIEnv*, jclass)
-{
-  HAL_ObserveUserProgramTeleop();
-}
-
-/*
- * Class:     edu_wpi_first_hal_HAL
- * Method:    observeUserProgramTest
- * Signature: ()V
- */
-JNIEXPORT void JNICALL
-Java_edu_wpi_first_hal_HAL_observeUserProgramTest
-  (JNIEnv*, jclass)
-{
-  HAL_ObserveUserProgramTest();
-}
-
-/*
- * Class:     edu_wpi_first_hal_HAL
- * Method:    report
- * Signature: (IIILjava/lang/String;)I
- */
-JNIEXPORT jint JNICALL
-Java_edu_wpi_first_hal_HAL_report
-  (JNIEnv* paramEnv, jclass, jint paramResource, jint paramInstanceNumber,
-   jint paramContext, jstring paramFeature)
-{
-  JStringRef featureStr{paramEnv, paramFeature};
-  jint returnValue = HAL_Report(paramResource, paramInstanceNumber,
-                                paramContext, featureStr.c_str());
-  return returnValue;
-}
-
-/*
- * Class:     edu_wpi_first_hal_HAL
- * Method:    nativeGetControlWord
- * Signature: ()I
- */
-JNIEXPORT jint JNICALL
-Java_edu_wpi_first_hal_HAL_nativeGetControlWord
-  (JNIEnv*, jclass)
-{
-  static_assert(sizeof(HAL_ControlWord) == sizeof(jint),
-                "Java int must match the size of control word");
-  HAL_ControlWord controlWord;
-  HAL_GetControlWord(&controlWord);
-  jint retVal = 0;
-  std::memcpy(&retVal, &controlWord, sizeof(HAL_ControlWord));
-  return retVal;
-}
-
-/*
- * Class:     edu_wpi_first_hal_HAL
- * Method:    nativeGetAllianceStation
- * Signature: ()I
- */
-JNIEXPORT jint JNICALL
-Java_edu_wpi_first_hal_HAL_nativeGetAllianceStation
-  (JNIEnv*, jclass)
-{
-  int32_t status = 0;
-  auto allianceStation = HAL_GetAllianceStation(&status);
-  return static_cast<jint>(allianceStation);
-}
-
-/*
- * Class:     edu_wpi_first_hal_HAL
- * Method:    getJoystickAxes
- * Signature: (B[F)S
- */
-JNIEXPORT jshort JNICALL
-Java_edu_wpi_first_hal_HAL_getJoystickAxes
-  (JNIEnv* env, jclass, jbyte joystickNum, jfloatArray axesArray)
-{
-  HAL_JoystickAxes axes;
-  HAL_GetJoystickAxes(joystickNum, &axes);
-
-  jsize javaSize = env->GetArrayLength(axesArray);
-  if (axes.count > javaSize) {
-    ThrowIllegalArgumentException(
-        env,
-        fmt::format("Native array size larger then passed in java array "
-                    "size\nNative Size: {} Java Size: {}",
-                    static_cast<int>(axes.count), static_cast<int>(javaSize)));
-    return 0;
-  }
-
-  env->SetFloatArrayRegion(axesArray, 0, axes.count, axes.axes);
-
-  return axes.count;
-}
-
-/*
- * Class:     edu_wpi_first_hal_HAL
- * Method:    getJoystickPOVs
- * Signature: (B[S)S
- */
-JNIEXPORT jshort JNICALL
-Java_edu_wpi_first_hal_HAL_getJoystickPOVs
-  (JNIEnv* env, jclass, jbyte joystickNum, jshortArray povsArray)
-{
-  HAL_JoystickPOVs povs;
-  HAL_GetJoystickPOVs(joystickNum, &povs);
-
-  jsize javaSize = env->GetArrayLength(povsArray);
-  if (povs.count > javaSize) {
-    ThrowIllegalArgumentException(
-        env,
-        fmt::format("Native array size larger then passed in java array "
-                    "size\nNative Size: {} Java Size: {}",
-                    static_cast<int>(povs.count), static_cast<int>(javaSize)));
-    return 0;
-  }
-
-  env->SetShortArrayRegion(povsArray, 0, povs.count, povs.povs);
-
-  return povs.count;
-}
-
-/*
- * Class:     edu_wpi_first_hal_HAL
- * Method:    getJoystickButtons
- * Signature: (BLjava/lang/Object;)I
- */
-JNIEXPORT jint JNICALL
-Java_edu_wpi_first_hal_HAL_getJoystickButtons
-  (JNIEnv* env, jclass, jbyte joystickNum, jobject count)
-{
-  HAL_JoystickButtons joystickButtons;
-  HAL_GetJoystickButtons(joystickNum, &joystickButtons);
-  jbyte* countPtr =
-      reinterpret_cast<jbyte*>(env->GetDirectBufferAddress(count));
-  *countPtr = joystickButtons.count;
-  return joystickButtons.buttons;
-}
-
-/*
- * Class:     edu_wpi_first_hal_HAL
- * Method:    setJoystickOutputs
- * Signature: (BISS)I
- */
-JNIEXPORT jint JNICALL
-Java_edu_wpi_first_hal_HAL_setJoystickOutputs
-  (JNIEnv*, jclass, jbyte port, jint outputs, jshort leftRumble,
-   jshort rightRumble)
-{
-  return HAL_SetJoystickOutputs(port, outputs, leftRumble, rightRumble);
-}
-
-/*
- * Class:     edu_wpi_first_hal_HAL
- * Method:    getJoystickIsXbox
- * Signature: (B)I
- */
-JNIEXPORT jint JNICALL
-Java_edu_wpi_first_hal_HAL_getJoystickIsXbox
-  (JNIEnv*, jclass, jbyte port)
-{
-  return HAL_GetJoystickIsXbox(port);
-}
-
-/*
- * Class:     edu_wpi_first_hal_HAL
- * Method:    getJoystickType
- * Signature: (B)I
- */
-JNIEXPORT jint JNICALL
-Java_edu_wpi_first_hal_HAL_getJoystickType
-  (JNIEnv*, jclass, jbyte port)
-{
-  return HAL_GetJoystickType(port);
-}
-
-/*
- * Class:     edu_wpi_first_hal_HAL
- * Method:    getJoystickName
- * Signature: (B)Ljava/lang/String;
- */
-JNIEXPORT jstring JNICALL
-Java_edu_wpi_first_hal_HAL_getJoystickName
-  (JNIEnv* env, jclass, jbyte port)
-{
-  char* joystickName = HAL_GetJoystickName(port);
-  jstring str = MakeJString(env, joystickName);
-  HAL_FreeJoystickName(joystickName);
-  return str;
-}
-
-/*
- * Class:     edu_wpi_first_hal_HAL
- * Method:    getJoystickAxisType
- * Signature: (BB)I
- */
-JNIEXPORT jint JNICALL
-Java_edu_wpi_first_hal_HAL_getJoystickAxisType
-  (JNIEnv*, jclass, jbyte joystickNum, jbyte axis)
-{
-  return HAL_GetJoystickAxisType(joystickNum, axis);
-}
-
-/*
- * Class:     edu_wpi_first_hal_HAL
- * Method:    isNewControlData
- * Signature: ()Z
- */
-JNIEXPORT jboolean JNICALL
-Java_edu_wpi_first_hal_HAL_isNewControlData
-  (JNIEnv*, jclass)
-{
-  return static_cast<jboolean>(HAL_IsNewControlData());
-}
-
-/*
- * Class:     edu_wpi_first_hal_HAL
- * Method:    waitForDSData
- * Signature: ()V
- */
-JNIEXPORT void JNICALL
-Java_edu_wpi_first_hal_HAL_waitForDSData
-  (JNIEnv* env, jclass)
-{
-  HAL_WaitForDSData();
-}
-
-/*
- * Class:     edu_wpi_first_hal_HAL
- * Method:    releaseDSMutex
- * Signature: ()V
- */
-JNIEXPORT void JNICALL
-Java_edu_wpi_first_hal_HAL_releaseDSMutex
-  (JNIEnv* env, jclass)
-{
-  HAL_ReleaseDSMutex();
-}
-
-/*
- * Class:     edu_wpi_first_hal_HAL
- * Method:    waitForDSDataTimeout
- * Signature: (D)Z
- */
-JNIEXPORT jboolean JNICALL
-Java_edu_wpi_first_hal_HAL_waitForDSDataTimeout
-  (JNIEnv*, jclass, jdouble timeout)
-{
-  return static_cast<jboolean>(HAL_WaitForDSDataTimeout(timeout));
-}
-
-/*
- * Class:     edu_wpi_first_hal_HAL
- * Method:    getMatchTime
- * Signature: ()D
- */
-JNIEXPORT jdouble JNICALL
-Java_edu_wpi_first_hal_HAL_getMatchTime
-  (JNIEnv* env, jclass)
-{
-  int32_t status = 0;
-  return HAL_GetMatchTime(&status);
-}
-
-/*
- * Class:     edu_wpi_first_hal_HAL
  * Method:    getSystemActive
  * Signature: ()Z
  */
@@ -442,58 +138,6 @@
 
 /*
  * Class:     edu_wpi_first_hal_HAL
- * Method:    getMatchInfo
- * Signature: (Ljava/lang/Object;)I
- */
-JNIEXPORT jint JNICALL
-Java_edu_wpi_first_hal_HAL_getMatchInfo
-  (JNIEnv* env, jclass, jobject info)
-{
-  HAL_MatchInfo matchInfo;
-  auto status = HAL_GetMatchInfo(&matchInfo);
-  if (status == 0) {
-    SetMatchInfoObject(env, info, matchInfo);
-  }
-  return status;
-}
-
-/*
- * Class:     edu_wpi_first_hal_HAL
- * Method:    sendError
- * Signature: (ZIZLjava/lang/String;Ljava/lang/String;Ljava/lang/String;Z)I
- */
-JNIEXPORT jint JNICALL
-Java_edu_wpi_first_hal_HAL_sendError
-  (JNIEnv* env, jclass, jboolean isError, jint errorCode, jboolean isLVCode,
-   jstring details, jstring location, jstring callStack, jboolean printMsg)
-{
-  JStringRef detailsStr{env, details};
-  JStringRef locationStr{env, location};
-  JStringRef callStackStr{env, callStack};
-
-  jint returnValue =
-      HAL_SendError(isError, errorCode, isLVCode, detailsStr.c_str(),
-                    locationStr.c_str(), callStackStr.c_str(), printMsg);
-  return returnValue;
-}
-
-/*
- * Class:     edu_wpi_first_hal_HAL
- * Method:    sendConsoleLine
- * Signature: (Ljava/lang/String;)I
- */
-JNIEXPORT jint JNICALL
-Java_edu_wpi_first_hal_HAL_sendConsoleLine
-  (JNIEnv* env, jclass, jstring line)
-{
-  JStringRef lineStr{env, line};
-
-  jint returnValue = HAL_SendConsoleLine(lineStr.c_str());
-  return returnValue;
-}
-
-/*
- * Class:     edu_wpi_first_hal_HAL
  * Method:    getPortWithModule
  * Signature: (BB)I
  */
diff --git a/third_party/allwpilib/hal/src/main/native/cpp/jni/HALUtil.cpp b/third_party/allwpilib/hal/src/main/native/cpp/jni/HALUtil.cpp
index 5d5a958..76c05f8 100644
--- a/third_party/allwpilib/hal/src/main/native/cpp/jni/HALUtil.cpp
+++ b/third_party/allwpilib/hal/src/main/native/cpp/jni/HALUtil.cpp
@@ -52,6 +52,7 @@
 static JClass matchInfoDataCls;
 static JClass accumulatorResultCls;
 static JClass canDataCls;
+static JClass canStreamMessageCls;
 static JClass halValueCls;
 static JClass baseStoreCls;
 static JClass revPHVersionCls;
@@ -64,6 +65,7 @@
     {"edu/wpi/first/hal/MatchInfoData", &matchInfoDataCls},
     {"edu/wpi/first/hal/AccumulatorResult", &accumulatorResultCls},
     {"edu/wpi/first/hal/CANData", &canDataCls},
+    {"edu/wpi/first/hal/CANStreamMessage", &canStreamMessageCls},
     {"edu/wpi/first/hal/HALValue", &halValueCls},
     {"edu/wpi/first/hal/DMAJNISample$BaseStore", &baseStoreCls},
     {"edu/wpi/first/hal/REVPHVersion", &revPHVersionCls}};
@@ -303,6 +305,18 @@
   return retVal;
 }
 
+jbyteArray SetCANStreamObject(JNIEnv* env, jobject canStreamData,
+                              int32_t length, uint32_t messageID,
+                              uint64_t timestamp) {
+  static jmethodID func =
+      env->GetMethodID(canStreamMessageCls, "setStreamData", "(IIJ)[B");
+
+  jbyteArray retVal = static_cast<jbyteArray>(env->CallObjectMethod(
+      canStreamData, func, static_cast<jint>(length),
+      static_cast<jint>(messageID), static_cast<jlong>(timestamp)));
+  return retVal;
+}
+
 jobject CreateHALValue(JNIEnv* env, const HAL_Value& value) {
   static jmethodID fromNative = env->GetStaticMethodID(
       halValueCls, "fromNative", "(IJD)Ledu/wpi/first/hal/HALValue;");
@@ -444,6 +458,34 @@
 
 /*
  * Class:     edu_wpi_first_hal_HALUtil
+ * Method:    getSerialNumber
+ * Signature: ()Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_first_hal_HALUtil_getSerialNumber
+  (JNIEnv* env, jclass)
+{
+  char serialNum[9];
+  size_t len = HAL_GetSerialNumber(serialNum, sizeof(serialNum));
+  return MakeJString(env, std::string_view(serialNum, len));
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HALUtil
+ * Method:    getComments
+ * Signature: ()Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_first_hal_HALUtil_getComments
+  (JNIEnv* env, jclass)
+{
+  char comments[65];
+  size_t len = HAL_GetComments(comments, sizeof(comments));
+  return MakeJString(env, std::string_view(comments, len));
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HALUtil
  * Method:    getFPGATime
  * Signature: ()J
  */
diff --git a/third_party/allwpilib/hal/src/main/native/cpp/jni/HALUtil.h b/third_party/allwpilib/hal/src/main/native/cpp/jni/HALUtil.h
index cf3956c..9c9487c 100644
--- a/third_party/allwpilib/hal/src/main/native/cpp/jni/HALUtil.h
+++ b/third_party/allwpilib/hal/src/main/native/cpp/jni/HALUtil.h
@@ -78,6 +78,10 @@
 jbyteArray SetCANDataObject(JNIEnv* env, jobject canData, int32_t length,
                             uint64_t timestamp);
 
+jbyteArray SetCANStreamObject(JNIEnv* env, jobject canStreamData,
+                              int32_t length, uint32_t messageID,
+                              uint64_t timestamp);
+
 jobject CreateHALValue(JNIEnv* env, const HAL_Value& value);
 
 jobject CreateDMABaseStore(JNIEnv* env, jint valueType, jint index);
diff --git a/third_party/allwpilib/hal/src/main/native/cpp/jni/I2CJNI.cpp b/third_party/allwpilib/hal/src/main/native/cpp/jni/I2CJNI.cpp
index b605b95..68b8442 100644
--- a/third_party/allwpilib/hal/src/main/native/cpp/jni/I2CJNI.cpp
+++ b/third_party/allwpilib/hal/src/main/native/cpp/jni/I2CJNI.cpp
@@ -64,6 +64,16 @@
   (JNIEnv* env, jclass, jint port, jbyte address, jbyteArray dataToSend,
    jbyte sendSize, jbyteArray dataReceived, jbyte receiveSize)
 {
+  if (sendSize < 0) {
+    ThrowIllegalArgumentException(env, "I2CJNI.i2cTransactionB() sendSize < 0");
+    return 0;
+  }
+  if (receiveSize < 0) {
+    ThrowIllegalArgumentException(env,
+                                  "I2CJNI.i2cTransactionB() receiveSize < 0");
+    return 0;
+  }
+
   wpi::SmallVector<uint8_t, 128> recvBuf;
   recvBuf.resize(receiveSize);
   jint returnValue =
@@ -142,6 +152,11 @@
   (JNIEnv* env, jclass, jint port, jbyte address, jbyteArray dataReceived,
    jbyte receiveSize)
 {
+  if (receiveSize < 0) {
+    ThrowIllegalArgumentException(env, "I2CJNI.i2cReadB() receiveSize < 0");
+    return 0;
+  }
+
   wpi::SmallVector<uint8_t, 128> recvBuf;
   recvBuf.resize(receiveSize);
   jint returnValue = HAL_ReadI2C(static_cast<HAL_I2CPort>(port), address,
diff --git a/third_party/allwpilib/hal/src/main/native/cpp/jni/InterruptJNI.cpp b/third_party/allwpilib/hal/src/main/native/cpp/jni/InterruptJNI.cpp
index ed56ce5..e220125 100644
--- a/third_party/allwpilib/hal/src/main/native/cpp/jni/InterruptJNI.cpp
+++ b/third_party/allwpilib/hal/src/main/native/cpp/jni/InterruptJNI.cpp
@@ -50,15 +50,15 @@
 /*
  * Class:     edu_wpi_first_hal_InterruptJNI
  * Method:    waitForInterrupt
- * Signature: (IDZ)I
+ * Signature: (IDZ)J
  */
-JNIEXPORT jint JNICALL
+JNIEXPORT jlong JNICALL
 Java_edu_wpi_first_hal_InterruptJNI_waitForInterrupt
   (JNIEnv* env, jclass, jint interruptHandle, jdouble timeout,
    jboolean ignorePrevious)
 {
   int32_t status = 0;
-  int32_t result = HAL_WaitForInterrupt((HAL_InterruptHandle)interruptHandle,
+  int64_t result = HAL_WaitForInterrupt((HAL_InterruptHandle)interruptHandle,
                                         timeout, ignorePrevious, &status);
 
   CheckStatus(env, status);
@@ -67,6 +67,25 @@
 
 /*
  * Class:     edu_wpi_first_hal_InterruptJNI
+ * Method:    waitForMultipleInterrupts
+ * Signature: (IJDZ)J
+ */
+JNIEXPORT jlong JNICALL
+Java_edu_wpi_first_hal_InterruptJNI_waitForMultipleInterrupts
+  (JNIEnv* env, jclass, jint interruptHandle, jlong mask, jdouble timeout,
+   jboolean ignorePrevious)
+{
+  int32_t status = 0;
+  int64_t result =
+      HAL_WaitForMultipleInterrupts((HAL_InterruptHandle)interruptHandle, mask,
+                                    timeout, ignorePrevious, &status);
+
+  CheckStatus(env, status);
+  return result;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_InterruptJNI
  * Method:    readInterruptRisingTimestamp
  * Signature: (I)J
  */
diff --git a/third_party/allwpilib/hal/src/main/native/cpp/jni/SPIJNI.cpp b/third_party/allwpilib/hal/src/main/native/cpp/jni/SPIJNI.cpp
index 67ef56d..4f1e556 100644
--- a/third_party/allwpilib/hal/src/main/native/cpp/jni/SPIJNI.cpp
+++ b/third_party/allwpilib/hal/src/main/native/cpp/jni/SPIJNI.cpp
@@ -15,6 +15,27 @@
 using namespace hal;
 using namespace wpi::java;
 
+static_assert(HAL_SPIPort::HAL_SPI_kInvalid ==
+              edu_wpi_first_hal_SPIJNI_INVALID_PORT);
+static_assert(HAL_SPIPort::HAL_SPI_kOnboardCS0 ==
+              edu_wpi_first_hal_SPIJNI_ONBOARD_CS0_PORT);
+static_assert(HAL_SPIPort::HAL_SPI_kOnboardCS1 ==
+              edu_wpi_first_hal_SPIJNI_ONBOARD_CS1_PORT);
+static_assert(HAL_SPIPort::HAL_SPI_kOnboardCS2 ==
+              edu_wpi_first_hal_SPIJNI_ONBOARD_CS2_PORT);
+static_assert(HAL_SPIPort::HAL_SPI_kOnboardCS3 ==
+              edu_wpi_first_hal_SPIJNI_ONBOARD_CS3_PORT);
+static_assert(HAL_SPIPort::HAL_SPI_kMXP == edu_wpi_first_hal_SPIJNI_MXP_PORT);
+
+static_assert(HAL_SPIMode::HAL_SPI_kMode0 ==
+              edu_wpi_first_hal_SPIJNI_SPI_MODE0);
+static_assert(HAL_SPIMode::HAL_SPI_kMode1 ==
+              edu_wpi_first_hal_SPIJNI_SPI_MODE1);
+static_assert(HAL_SPIMode::HAL_SPI_kMode2 ==
+              edu_wpi_first_hal_SPIJNI_SPI_MODE2);
+static_assert(HAL_SPIMode::HAL_SPI_kMode3 ==
+              edu_wpi_first_hal_SPIJNI_SPI_MODE3);
+
 extern "C" {
 
 /*
@@ -63,6 +84,11 @@
   (JNIEnv* env, jclass, jint port, jbyteArray dataToSend,
    jbyteArray dataReceived, jbyte size)
 {
+  if (size < 0) {
+    ThrowIllegalArgumentException(env, "SPIJNI.spiTransactionB() size < 0");
+    return 0;
+  }
+
   wpi::SmallVector<uint8_t, 128> recvBuf;
   recvBuf.resize(size);
   jint retVal =
@@ -120,6 +146,11 @@
   (JNIEnv* env, jclass, jint port, jboolean initiate, jobject dataReceived,
    jbyte size)
 {
+  if (size < 0) {
+    ThrowIllegalArgumentException(env, "SPIJNI.spiRead() size < 0");
+    return 0;
+  }
+
   uint8_t* dataReceivedPtr =
       reinterpret_cast<uint8_t*>(env->GetDirectBufferAddress(dataReceived));
   jint retVal;
@@ -145,6 +176,11 @@
   (JNIEnv* env, jclass, jint port, jboolean initiate, jbyteArray dataReceived,
    jbyte size)
 {
+  if (size < 0) {
+    ThrowIllegalArgumentException(env, "SPIJNI.spiReadB() size < 0");
+    return 0;
+  }
+
   jint retVal;
   wpi::SmallVector<uint8_t, 128> recvBuf;
   recvBuf.resize(size);
@@ -187,16 +223,27 @@
 
 /*
  * Class:     edu_wpi_first_hal_SPIJNI
- * Method:    spiSetOpts
- * Signature: (IIII)V
+ * Method:    spiSetMode
+ * Signature: (II)V
  */
 JNIEXPORT void JNICALL
-Java_edu_wpi_first_hal_SPIJNI_spiSetOpts
-  (JNIEnv*, jclass, jint port, jint msb_first, jint sample_on_trailing,
-   jint clk_idle_high)
+Java_edu_wpi_first_hal_SPIJNI_spiSetMode
+  (JNIEnv*, jclass, jint port, jint mode)
 {
-  HAL_SetSPIOpts(static_cast<HAL_SPIPort>(port), msb_first, sample_on_trailing,
-                 clk_idle_high);
+  HAL_SetSPIMode(static_cast<HAL_SPIPort>(port),
+                 static_cast<HAL_SPIMode>(mode));
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiGetMode
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiGetMode
+  (JNIEnv*, jclass, jint port)
+{
+  return static_cast<jint>(HAL_GetSPIMode(static_cast<HAL_SPIPort>(port)));
 }
 
 /*
@@ -361,6 +408,12 @@
   (JNIEnv* env, jclass, jint port, jintArray buffer, jint numToRead,
    jdouble timeout)
 {
+  if (numToRead < 0) {
+    ThrowIllegalArgumentException(
+        env, "SPIJNI.spiReadAutoReceivedData() numToRead < 0");
+    return 0;
+  }
+
   wpi::SmallVector<uint32_t, 128> recvBuf;
   recvBuf.resize(numToRead);
   int32_t status = 0;
diff --git a/third_party/allwpilib/hal/src/main/native/cpp/jni/simulation/AddressableLEDDataJNI.cpp b/third_party/allwpilib/hal/src/main/native/cpp/jni/simulation/AddressableLEDDataJNI.cpp
index e888bd3..70b31ab 100644
--- a/third_party/allwpilib/hal/src/main/native/cpp/jni/simulation/AddressableLEDDataJNI.cpp
+++ b/third_party/allwpilib/hal/src/main/native/cpp/jni/simulation/AddressableLEDDataJNI.cpp
@@ -257,7 +257,7 @@
       std::make_unique<HAL_AddressableLEDData[]>(HAL_kAddressableLEDMaxLength);
   int32_t length = HALSIM_GetAddressableLEDData(index, data.get());
   return MakeJByteArray(
-      env, wpi::span(reinterpret_cast<jbyte*>(data.get()), length * 4));
+      env, std::span(reinterpret_cast<jbyte*>(data.get()), length * 4));
 }
 
 /*
diff --git a/third_party/allwpilib/hal/src/main/native/cpp/jni/simulation/BufferCallbackStore.cpp b/third_party/allwpilib/hal/src/main/native/cpp/jni/simulation/BufferCallbackStore.cpp
index 265b363..f83ab62 100644
--- a/third_party/allwpilib/hal/src/main/native/cpp/jni/simulation/BufferCallbackStore.cpp
+++ b/third_party/allwpilib/hal/src/main/native/cpp/jni/simulation/BufferCallbackStore.cpp
@@ -57,9 +57,8 @@
     std::fflush(stdout);
   }
 
-  auto toCallbackArr = MakeJByteArray(
-      env, std::string_view{reinterpret_cast<const char*>(buffer),
-                            static_cast<size_t>(length)});
+  auto toCallbackArr =
+      MakeJByteArray(env, {buffer, static_cast<size_t>(length)});
 
   env->CallVoidMethod(m_call, sim::GetBufferCallback(), MakeJString(env, name),
                       toCallbackArr, static_cast<jint>(length));
@@ -124,6 +123,9 @@
 void sim::FreeBufferCallback(JNIEnv* env, SIM_JniHandle handle, jint index,
                              FreeBufferCallbackFunc freeCallback) {
   auto callback = callbackHandles->Free(handle);
+  if (callback == nullptr) {
+    return;
+  }
   freeCallback(index, callback->getCallbackId());
   callback->free(env);
 }
diff --git a/third_party/allwpilib/hal/src/main/native/cpp/jni/simulation/ConstBufferCallbackStore.cpp b/third_party/allwpilib/hal/src/main/native/cpp/jni/simulation/ConstBufferCallbackStore.cpp
index cba0a5b..af57803 100644
--- a/third_party/allwpilib/hal/src/main/native/cpp/jni/simulation/ConstBufferCallbackStore.cpp
+++ b/third_party/allwpilib/hal/src/main/native/cpp/jni/simulation/ConstBufferCallbackStore.cpp
@@ -58,9 +58,8 @@
     std::fflush(stdout);
   }
 
-  auto toCallbackArr = MakeJByteArray(
-      env, std::string_view{reinterpret_cast<const char*>(buffer),
-                            static_cast<size_t>(length)});
+  auto toCallbackArr =
+      MakeJByteArray(env, {buffer, static_cast<size_t>(length)});
 
   env->CallVoidMethod(m_call, sim::GetConstBufferCallback(),
                       MakeJString(env, name), toCallbackArr,
@@ -117,6 +116,9 @@
 void sim::FreeConstBufferCallback(JNIEnv* env, SIM_JniHandle handle, jint index,
                                   FreeConstBufferCallbackFunc freeCallback) {
   auto callback = callbackHandles->Free(handle);
+  if (callback == nullptr) {
+    return;
+  }
   freeCallback(index, callback->getCallbackId());
   callback->free(env);
 }
diff --git a/third_party/allwpilib/hal/src/main/native/cpp/jni/simulation/DriverStationDataJNI.cpp b/third_party/allwpilib/hal/src/main/native/cpp/jni/simulation/DriverStationDataJNI.cpp
index acecacb..c50b8e3 100644
--- a/third_party/allwpilib/hal/src/main/native/cpp/jni/simulation/DriverStationDataJNI.cpp
+++ b/third_party/allwpilib/hal/src/main/native/cpp/jni/simulation/DriverStationDataJNI.cpp
@@ -732,7 +732,8 @@
 Java_edu_wpi_first_hal_simulation_DriverStationDataJNI_setJoystickName
   (JNIEnv* env, jclass, jint stick, jstring name)
 {
-  HALSIM_SetJoystickName(stick, JStringRef{env, name}.c_str());
+  JStringRef nameJString{env, name};
+  HALSIM_SetJoystickName(stick, nameJString.c_str(), nameJString.size());
 }
 
 /*
@@ -756,7 +757,8 @@
 Java_edu_wpi_first_hal_simulation_DriverStationDataJNI_setGameSpecificMessage
   (JNIEnv* env, jclass, jstring message)
 {
-  HALSIM_SetGameSpecificMessage(JStringRef{env, message}.c_str());
+  JStringRef messageJString{env, message};
+  HALSIM_SetGameSpecificMessage(messageJString.c_str(), messageJString.size());
 }
 
 /*
@@ -768,7 +770,8 @@
 Java_edu_wpi_first_hal_simulation_DriverStationDataJNI_setEventName
   (JNIEnv* env, jclass, jstring name)
 {
-  HALSIM_SetEventName(JStringRef{env, name}.c_str());
+  JStringRef nameJString{env, name};
+  HALSIM_SetEventName(nameJString.c_str(), nameJString.size());
 }
 
 /*
diff --git a/third_party/allwpilib/hal/src/main/native/cpp/jni/simulation/RoboRioDataJNI.cpp b/third_party/allwpilib/hal/src/main/native/cpp/jni/simulation/RoboRioDataJNI.cpp
index 03bb0c5..5bcd114 100644
--- a/third_party/allwpilib/hal/src/main/native/cpp/jni/simulation/RoboRioDataJNI.cpp
+++ b/third_party/allwpilib/hal/src/main/native/cpp/jni/simulation/RoboRioDataJNI.cpp
@@ -4,11 +4,14 @@
 
 #include <jni.h>
 
+#include <wpi/jni_util.h>
+
 #include "CallbackStore.h"
 #include "edu_wpi_first_hal_simulation_RoboRioDataJNI.h"
 #include "hal/simulation/RoboRioData.h"
 
 using namespace hal;
+using namespace wpi::java;
 
 extern "C" {
 
@@ -827,6 +830,61 @@
 
 /*
  * Class:     edu_wpi_first_hal_simulation_RoboRioDataJNI
+ * Method:    getSerialNumber
+ * Signature: ()Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_first_hal_simulation_RoboRioDataJNI_getSerialNumber
+  (JNIEnv* env, jclass)
+{
+  char serialNum[9];
+  size_t len = HALSIM_GetRoboRioSerialNumber(serialNum, sizeof(serialNum));
+  return MakeJString(env, std::string_view(serialNum, len));
+}
+
+/*
+ * Class:     edu_wpi_first_hal_simulation_RoboRioDataJNI
+ * Method:    setSerialNumber
+ * Signature: (Ljava/lang/String;)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_simulation_RoboRioDataJNI_setSerialNumber
+  (JNIEnv* env, jclass, jstring serialNumber)
+{
+  JStringRef serialNumberJString{env, serialNumber};
+  HALSIM_SetRoboRioSerialNumber(serialNumberJString.c_str(),
+                                serialNumberJString.size());
+}
+
+/*
+ * Class:     edu_wpi_first_hal_simulation_RoboRioDataJNI
+ * Method:    getComments
+ * Signature: ()Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_first_hal_simulation_RoboRioDataJNI_getComments
+  (JNIEnv* env, jclass)
+{
+  char comments[65];
+  size_t len = HALSIM_GetRoboRioComments(comments, sizeof(comments));
+  return MakeJString(env, std::string_view(comments, len));
+}
+
+/*
+ * Class:     edu_wpi_first_hal_simulation_RoboRioDataJNI
+ * Method:    setComments
+ * Signature: (Ljava/lang/String;)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_simulation_RoboRioDataJNI_setComments
+  (JNIEnv* env, jclass, jstring comments)
+{
+  JStringRef commentsJString{env, comments};
+  HALSIM_SetRoboRioComments(commentsJString.c_str(), commentsJString.size());
+}
+
+/*
+ * Class:     edu_wpi_first_hal_simulation_RoboRioDataJNI
  * Method:    resetData
  * Signature: ()V
  */
diff --git a/third_party/allwpilib/hal/src/main/native/cpp/jni/simulation/SimDeviceDataJNI.cpp b/third_party/allwpilib/hal/src/main/native/cpp/jni/simulation/SimDeviceDataJNI.cpp
index 60ce0f7..c7c2a19 100644
--- a/third_party/allwpilib/hal/src/main/native/cpp/jni/simulation/SimDeviceDataJNI.cpp
+++ b/third_party/allwpilib/hal/src/main/native/cpp/jni/simulation/SimDeviceDataJNI.cpp
@@ -242,6 +242,9 @@
 static void FreeDeviceCallback(JNIEnv* env, SIM_JniHandle handle,
                                FreeDeviceCallbackFunc freeCallback) {
   auto callback = deviceCallbackHandles->Free(handle);
+  if (callback == nullptr) {
+    return;
+  }
   freeCallback(callback->getCallbackId());
   callback->free(env);
 }
@@ -296,6 +299,9 @@
 static void FreeValueCallback(JNIEnv* env, SIM_JniHandle handle,
                               FreeValueCallbackFunc freeCallback) {
   auto callback = valueCallbackHandles->Free(handle);
+  if (callback == nullptr) {
+    return;
+  }
   freeCallback(callback->getCallbackId());
   callback->free(env);
 }
@@ -668,7 +674,7 @@
 {
   int32_t numElems = 0;
   const double* elems = HALSIM_GetSimValueEnumDoubleValues(handle, &numElems);
-  return MakeJDoubleArray(env, wpi::span(elems, numElems));
+  return MakeJDoubleArray(env, std::span(elems, numElems));
 }
 
 /*
diff --git a/third_party/allwpilib/hal/src/main/native/cpp/jni/simulation/SpiReadAutoReceiveBufferCallbackStore.cpp b/third_party/allwpilib/hal/src/main/native/cpp/jni/simulation/SpiReadAutoReceiveBufferCallbackStore.cpp
index c20f607..5b2ff2b 100644
--- a/third_party/allwpilib/hal/src/main/native/cpp/jni/simulation/SpiReadAutoReceiveBufferCallbackStore.cpp
+++ b/third_party/allwpilib/hal/src/main/native/cpp/jni/simulation/SpiReadAutoReceiveBufferCallbackStore.cpp
@@ -59,7 +59,7 @@
   }
 
   auto toCallbackArr = MakeJIntArray(
-      env, wpi::span<const uint32_t>{buffer, static_cast<size_t>(numToRead)});
+      env, std::span<const uint32_t>{buffer, static_cast<size_t>(numToRead)});
 
   jint ret = env->CallIntMethod(m_call, sim::GetBufferCallback(),
                                 MakeJString(env, name), toCallbackArr,
@@ -127,6 +127,9 @@
 void sim::FreeSpiBufferCallback(JNIEnv* env, SIM_JniHandle handle, jint index,
                                 FreeSpiBufferCallbackFunc freeCallback) {
   auto callback = callbackHandles->Free(handle);
+  if (callback == nullptr) {
+    return;
+  }
   freeCallback(index, callback->getCallbackId());
   callback->free(env);
 }
diff --git a/third_party/allwpilib/hal/src/main/native/include/hal/AnalogGyro.h b/third_party/allwpilib/hal/src/main/native/include/hal/AnalogGyro.h
index 6e5a9c2..ed7c308 100644
--- a/third_party/allwpilib/hal/src/main/native/include/hal/AnalogGyro.h
+++ b/third_party/allwpilib/hal/src/main/native/include/hal/AnalogGyro.h
@@ -22,7 +22,7 @@
  * Initializes an analog gyro.
  *
  * @param[in] handle handle to the analog port
- * @param[in] allocationLocation the location where the allocation is occuring
+ * @param[in] allocationLocation the location where the allocation is occurring
  *                                (can be null)
  * @param[out] status the error code, or 0 for success
  * @return the initialized gyro handle
diff --git a/third_party/allwpilib/hal/src/main/native/include/hal/AnalogInput.h b/third_party/allwpilib/hal/src/main/native/include/hal/AnalogInput.h
index 956cd21..0a1a3c5 100644
--- a/third_party/allwpilib/hal/src/main/native/include/hal/AnalogInput.h
+++ b/third_party/allwpilib/hal/src/main/native/include/hal/AnalogInput.h
@@ -22,7 +22,7 @@
  * Initializes the analog input port using the given port object.
  *
  * @param[in] portHandle Handle to the port to initialize.
- * @param[in] allocationLocation the location where the allocation is occuring
+ * @param[in] allocationLocation the location where the allocation is occurring
  *                               (can be null)
  * @param[out] status the error code, or 0 for success
  * @return the created analog input handle
@@ -46,7 +46,7 @@
 HAL_Bool HAL_CheckAnalogModule(int32_t module);
 
 /**
- * Checks that the analog output channel number is value.
+ * Checks that the analog output channel number is valid.
  * Verifies that the analog channel number is one of the legal channel numbers.
  * Channel numbers are 0-based.
  *
diff --git a/third_party/allwpilib/hal/src/main/native/include/hal/AnalogOutput.h b/third_party/allwpilib/hal/src/main/native/include/hal/AnalogOutput.h
index 26e5231..f9a1f36 100644
--- a/third_party/allwpilib/hal/src/main/native/include/hal/AnalogOutput.h
+++ b/third_party/allwpilib/hal/src/main/native/include/hal/AnalogOutput.h
@@ -22,7 +22,7 @@
  * Initializes the analog output port using the given port object.
  *
  * @param[in] portHandle handle to the port
- * @param[in] allocationLocation the location where the allocation is occuring
+ * @param[in] allocationLocation the location where the allocation is occurring
  *                               (can be null)
  * @param[out] status Error status variable. 0 on success.
  * @return the created analog output handle
@@ -58,7 +58,7 @@
                            int32_t* status);
 
 /**
- * Checks that the analog output channel number is value.
+ * Checks that the analog output channel number is valid.
  *
  * Verifies that the analog channel number is one of the legal channel numbers.
  * Channel numbers are 0-based.
diff --git a/third_party/allwpilib/hal/src/main/native/include/hal/CANAPI.h b/third_party/allwpilib/hal/src/main/native/include/hal/CANAPI.h
index 29859cf..d5244b5 100644
--- a/third_party/allwpilib/hal/src/main/native/include/hal/CANAPI.h
+++ b/third_party/allwpilib/hal/src/main/native/include/hal/CANAPI.h
@@ -22,7 +22,8 @@
 /**
  * Initializes a CAN device.
  *
- * These follow the FIRST standard CAN layout. Link TBD
+ * These follow the FIRST standard CAN layout.
+ * https://docs.wpilib.org/en/stable/docs/software/can-devices/can-addressing.html
  *
  * @param[in] manufacturer the can manufacturer
  * @param[in] deviceId     the device ID (0-63)
diff --git a/third_party/allwpilib/hal/src/main/native/include/hal/CANAPITypes.h b/third_party/allwpilib/hal/src/main/native/include/hal/CANAPITypes.h
index 1be672e..404eecf 100644
--- a/third_party/allwpilib/hal/src/main/native/include/hal/CANAPITypes.h
+++ b/third_party/allwpilib/hal/src/main/native/include/hal/CANAPITypes.h
@@ -54,7 +54,8 @@
   HAL_CAN_Man_kKauaiLabs = 9,
   HAL_CAN_Man_kCopperforge = 10,
   HAL_CAN_Man_kPWF = 11,
-  HAL_CAN_Man_kStudica = 12
+  HAL_CAN_Man_kStudica = 12,
+  HAL_CAN_Man_kTheThriftyBot = 13
 };
 // clang-format on
 /** @} */
diff --git a/third_party/allwpilib/hal/src/main/native/include/hal/ChipObject.h b/third_party/allwpilib/hal/src/main/native/include/hal/ChipObject.h
index 4526a1a..23dcb38 100644
--- a/third_party/allwpilib/hal/src/main/native/include/hal/ChipObject.h
+++ b/third_party/allwpilib/hal/src/main/native/include/hal/ChipObject.h
@@ -34,7 +34,6 @@
 #include <FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tSysWatchdog.h>
 #include <FRC_FPGA_ChipObject/tDMAChannelDescriptor.h>
 #include <FRC_FPGA_ChipObject/tDMAManager.h>
-#include <FRC_FPGA_ChipObject/tInterruptManager.h>
 #include <FRC_FPGA_ChipObject/tSystem.h>
 #include <FRC_FPGA_ChipObject/tSystemInterface.h>
 
diff --git a/third_party/allwpilib/hal/src/main/native/include/hal/DIO.h b/third_party/allwpilib/hal/src/main/native/include/hal/DIO.h
index e094a0d..6b922b5 100644
--- a/third_party/allwpilib/hal/src/main/native/include/hal/DIO.h
+++ b/third_party/allwpilib/hal/src/main/native/include/hal/DIO.h
@@ -23,7 +23,7 @@
  *
  * @param[in] portHandle         the port handle to create from
  * @param[in] input              true for input, false for output
- * @param[in] allocationLocation the location where the allocation is occuring
+ * @param[in] allocationLocation the location where the allocation is occurring
  *                               (can be null)
  * @param[out] status            Error status variable. 0 on success.
  * @return the created digital handle
@@ -95,6 +95,16 @@
                                 double dutyCycle, int32_t* status);
 
 /**
+ * Configures the digital PWM to be a PPS signal with specified duty cycle.
+ *
+ * @param[in] pwmGenerator the digital PWM handle
+ * @param[in] dutyCycle    the percent duty cycle to output [0..1]
+ * @param[out] status      Error status variable. 0 on success.
+ */
+void HAL_SetDigitalPWMPPS(HAL_DigitalPWMHandle pwmGenerator, double dutyCycle,
+                          int32_t* status);
+
+/**
  * Configures which DO channel the PWM signal is output on.
  *
  * @param[in] pwmGenerator the digital PWM handle
@@ -150,13 +160,26 @@
  * single pulse going at any time.
  *
  * @param[in] dioPortHandle the digital port handle
- * @param[in] pulseLength   the active length of the pulse (in seconds)
+ * @param[in] pulseLengthSeconds   the active length of the pulse (in seconds)
  * @param[out] status       Error status variable. 0 on success.
  */
-void HAL_Pulse(HAL_DigitalHandle dioPortHandle, double pulseLength,
+void HAL_Pulse(HAL_DigitalHandle dioPortHandle, double pulseLengthSeconds,
                int32_t* status);
 
 /**
+ * Generates a single digital pulse on multiple channels.
+ *
+ * Write a pulse to the channels enabled by the mask. There can only be a
+ * single pulse going at any time.
+ *
+ * @param[in] channelMask the channel mask
+ * @param[in] pulseLengthSeconds   the active length of the pulse (in seconds)
+ * @param[out] status       Error status variable. 0 on success.
+ */
+void HAL_PulseMultiple(uint32_t channelMask, double pulseLengthSeconds,
+                       int32_t* status);
+
+/**
  * Checks a DIO line to see if it is currently generating a pulse.
  *
  * @param[in] dioPortHandle the digital port handle
diff --git a/third_party/allwpilib/hal/src/main/native/include/hal/DriverStation.h b/third_party/allwpilib/hal/src/main/native/include/hal/DriverStation.h
index 1839cfc..ae68b65 100644
--- a/third_party/allwpilib/hal/src/main/native/include/hal/DriverStation.h
+++ b/third_party/allwpilib/hal/src/main/native/include/hal/DriverStation.h
@@ -6,6 +6,8 @@
 
 #include <stdint.h>
 
+#include <wpi/Synchronization.h>
+
 #include "hal/DriverStationTypes.h"
 #include "hal/Types.h"
 
@@ -34,6 +36,14 @@
 int32_t HAL_SendError(HAL_Bool isError, int32_t errorCode, HAL_Bool isLVCode,
                       const char* details, const char* location,
                       const char* callStack, HAL_Bool printMsg);
+
+/**
+ * Set the print function used by HAL_SendError
+ *
+ * @param func Function called by HAL_SendError when stderr is printed
+ */
+void HAL_SetPrintErrorImpl(void (*func)(const char* line, size_t size));
+
 /**
  * Sends a line to the driver station console.
  *
@@ -87,6 +97,9 @@
 int32_t HAL_GetJoystickButtons(int32_t joystickNum,
                                HAL_JoystickButtons* buttons);
 
+void HAL_GetAllJoystickData(HAL_JoystickAxes* axes, HAL_JoystickPOVs* povs,
+                            HAL_JoystickButtons* buttons);
+
 /**
  * Retrieves the Joystick Descriptor for particular slot.
  *
@@ -184,6 +197,11 @@
 double HAL_GetMatchTime(int32_t* status);
 
 /**
+ * Gets if outputs are enabled by the control system.
+ */
+HAL_Bool HAL_GetOutputsEnabled(void);
+
+/**
  * Gets info about a specific match.
  *
  * @param[in] info the match info (output)
@@ -191,44 +209,10 @@
  */
 int32_t HAL_GetMatchInfo(HAL_MatchInfo* info);
 
-/**
- * Releases the DS Mutex to allow proper shutdown of any threads that are
- * waiting on it.
- */
-void HAL_ReleaseDSMutex(void);
+void HAL_RefreshDSData(void);
 
-/**
- * Has a new control packet from the driver station arrived since the last
- * time this function was called?
- *
- * @return true if the control data has been updated since the last call
- */
-HAL_Bool HAL_IsNewControlData(void);
-
-/**
- * Waits for the newest DS packet to arrive. Note that this is a blocking call.
- * Checks if new control data has arrived since the last HAL_WaitForDSData or
- * HAL_IsNewControlData call. If new data has not arrived, waits for new data
- * to arrive. Otherwise, returns immediately.
- */
-void HAL_WaitForDSData(void);
-
-/**
- * Waits for the newest DS packet to arrive. If timeout is <= 0, this will wait
- * forever. Otherwise, it will wait until either a new packet, or the timeout
- * time has passed.
- *
- * @param[in] timeout timeout in seconds
- * @return true for new data, false for timeout
- */
-HAL_Bool HAL_WaitForDSDataTimeout(double timeout);
-
-/**
- * Initializes the driver station communication. This will properly
- * handle multiple calls. However note that this CANNOT be called from a library
- * that interfaces with LabVIEW.
- */
-void HAL_InitializeDriverStation(void);
+void HAL_ProvideNewDataEventHandle(WPI_EventHandle handle);
+void HAL_RemoveNewDataEventHandle(WPI_EventHandle handle);
 
 /**
  * Sets the program starting flag in the DS.
diff --git a/third_party/allwpilib/hal/src/main/native/include/hal/DriverStationTypes.h b/third_party/allwpilib/hal/src/main/native/include/hal/DriverStationTypes.h
index 21f9088..277c286 100644
--- a/third_party/allwpilib/hal/src/main/native/include/hal/DriverStationTypes.h
+++ b/third_party/allwpilib/hal/src/main/native/include/hal/DriverStationTypes.h
@@ -69,6 +69,7 @@
 struct HAL_JoystickAxes {
   int16_t count;
   float axes[HAL_kMaxJoystickAxes];
+  uint8_t raw[HAL_kMaxJoystickAxes];
 };
 typedef struct HAL_JoystickAxes HAL_JoystickAxes;
 
diff --git a/third_party/allwpilib/hal/src/main/native/include/hal/DutyCycle.h b/third_party/allwpilib/hal/src/main/native/include/hal/DutyCycle.h
index 05b654b..90266fd 100644
--- a/third_party/allwpilib/hal/src/main/native/include/hal/DutyCycle.h
+++ b/third_party/allwpilib/hal/src/main/native/include/hal/DutyCycle.h
@@ -71,24 +71,21 @@
                               int32_t* status);
 
 /**
- * Get the raw output ratio of the duty cycle signal.
- *
- * <p> 0 means always low, an output equal to
- * GetOutputScaleFactor() means always high.
+ * Get the raw high time of the duty cycle signal.
  *
  * @param[in] dutyCycleHandle the duty cycle handle
  * @param[out] status Error status variable. 0 on success.
- * @return output ratio in raw units
+ * @return high time of last pulse in nanoseconds
  */
-int32_t HAL_GetDutyCycleOutputRaw(HAL_DutyCycleHandle dutyCycleHandle,
-                                  int32_t* status);
+int32_t HAL_GetDutyCycleHighTime(HAL_DutyCycleHandle dutyCycleHandle,
+                                 int32_t* status);
 
 /**
  * Get the scale factor of the output.
  *
  * <p> An output equal to this value is always high, and then linearly scales
- * down to 0. Divide the result of getOutputRaw by this in order to get the
- * percentage between 0 and 1.
+ * down to 0. Divide a raw result by this in order to get the
+ * percentage between 0 and 1. Used by DMA.
  *
  * @param[in] dutyCycleHandle the duty cycle handle
  * @param[out] status Error status variable. 0 on success.
diff --git a/third_party/allwpilib/hal/src/main/native/include/hal/Extensions.h b/third_party/allwpilib/hal/src/main/native/include/hal/Extensions.h
index ad3f733..6f64fdb 100644
--- a/third_party/allwpilib/hal/src/main/native/include/hal/Extensions.h
+++ b/third_party/allwpilib/hal/src/main/native/include/hal/Extensions.h
@@ -10,8 +10,7 @@
  * @defgroup hal_extensions Simulator Extensions
  * @ingroup hal_capi
  * HAL Simulator Extensions.  These are libraries that provide additional
- * simulator functionality, such as a Gazebo interface, or a more light weight
- * simulation.
+ * simulator functionality.
  *
  * An extension must expose the HALSIM_InitExtension entry point which is
  * invoked after the library is loaded.
diff --git a/third_party/allwpilib/hal/src/main/native/include/hal/HALBase.h b/third_party/allwpilib/hal/src/main/native/include/hal/HALBase.h
index b31ec75..1fe6b3a 100644
--- a/third_party/allwpilib/hal/src/main/native/include/hal/HALBase.h
+++ b/third_party/allwpilib/hal/src/main/native/include/hal/HALBase.h
@@ -6,6 +6,14 @@
 
 #include <stdint.h>
 
+#ifdef __cplusplus
+#include <cstddef>
+#else
+
+#include <stddef.h>  // NOLINT(build/include_order)
+
+#endif
+
 #include "hal/Types.h"
 
 /**
@@ -67,6 +75,24 @@
 int64_t HAL_GetFPGARevision(int32_t* status);
 
 /**
+ * Returns the serial number.
+ *
+ * @param[out] buffer The serial number.
+ * @param size The maximum characters to copy into buffer.
+ * @return Number of characters copied into buffer.
+ */
+size_t HAL_GetSerialNumber(char* buffer, size_t size);
+
+/**
+ * Returns the comments from the roboRIO web interface.
+ *
+ * @param[out] buffer The comments string.
+ * @param size The maximum characters to copy into buffer.
+ * @return Number of characters copied into buffer.
+ */
+size_t HAL_GetComments(char* buffer, size_t size);
+
+/**
  * Returns the runtime type of the HAL.
  *
  * @return HAL Runtime Type
diff --git a/third_party/allwpilib/hal/src/main/native/include/hal/Interrupts.h b/third_party/allwpilib/hal/src/main/native/include/hal/Interrupts.h
index def800c..2bccbe9 100644
--- a/third_party/allwpilib/hal/src/main/native/include/hal/Interrupts.h
+++ b/third_party/allwpilib/hal/src/main/native/include/hal/Interrupts.h
@@ -35,7 +35,7 @@
 void HAL_CleanInterrupts(HAL_InterruptHandle interruptHandle);
 
 /**
- * In synchronous mode, waits for the defined interrupt to occur.
+ * Waits for the defined interrupt to occur.
  *
  * @param[in] interruptHandle the interrupt handle
  * @param[in] timeout         timeout in seconds
@@ -49,6 +49,21 @@
                              int32_t* status);
 
 /**
+ * Waits for any interrupt covered by the mask to occur.
+ *
+ * @param[in] interruptHandle the interrupt handle to use for the context
+ * @param[in] mask            the mask of interrupts to wait for
+ * @param[in] timeout         timeout in seconds
+ * @param[in] ignorePrevious  if true, ignore interrupts that happened before
+ *                            waitForInterrupt was called
+ * @param[out] status         Error status variable. 0 on success.
+ * @return the mask of interrupts that fired
+ */
+int64_t HAL_WaitForMultipleInterrupts(HAL_InterruptHandle interruptHandle,
+                                      int64_t mask, double timeout,
+                                      HAL_Bool ignorePrevious, int32_t* status);
+
+/**
  * Returns the timestamp for the rising interrupt that occurred most recently.
  *
  * This is in the same time domain as HAL_GetFPGATime().  It only contains the
diff --git a/third_party/allwpilib/hal/src/main/native/include/hal/PWM.h b/third_party/allwpilib/hal/src/main/native/include/hal/PWM.h
index 7fd125e..df9020b 100644
--- a/third_party/allwpilib/hal/src/main/native/include/hal/PWM.h
+++ b/third_party/allwpilib/hal/src/main/native/include/hal/PWM.h
@@ -22,7 +22,7 @@
  * Initializes a PWM port.
  *
  * @param[in] portHandle the port to initialize
- * @param[in] allocationLocation  the location where the allocation is occuring
+ * @param[in] allocationLocation  the location where the allocation is occurring
  *                                (can be null)
  * @param[out] status             Error status variable. 0 on success.
  * @return the created pwm handle
diff --git a/third_party/allwpilib/hal/src/main/native/include/hal/PowerDistribution.h b/third_party/allwpilib/hal/src/main/native/include/hal/PowerDistribution.h
index 47cc9b2..7c2b582 100644
--- a/third_party/allwpilib/hal/src/main/native/include/hal/PowerDistribution.h
+++ b/third_party/allwpilib/hal/src/main/native/include/hal/PowerDistribution.h
@@ -37,7 +37,7 @@
  *
  * @param[in] moduleNumber       the module number to initialize
  * @param[in] type               the type of module to intialize
- * @param[in] allocationLocation the location where the allocation is occuring
+ * @param[in] allocationLocation the location where the allocation is occurring
  * @param[out] status            Error status variable. 0 on success.
  * @return the created PowerDistribution
  */
diff --git a/third_party/allwpilib/hal/src/main/native/include/hal/Relay.h b/third_party/allwpilib/hal/src/main/native/include/hal/Relay.h
index 7d711b2..9ee104b 100644
--- a/third_party/allwpilib/hal/src/main/native/include/hal/Relay.h
+++ b/third_party/allwpilib/hal/src/main/native/include/hal/Relay.h
@@ -27,7 +27,7 @@
  * @param[in] portHandle         the port handle to initialize
  * @param[in] fwd                true for the forward port, false for the
  *                               reverse port
- * @param[in] allocationLocation the location where the allocation is occuring
+ * @param[in] allocationLocation the location where the allocation is occurring
  *                               (can be null)
  * @param[out] status            Error status variable. 0 on success.
  * @return the created relay handle
diff --git a/third_party/allwpilib/hal/src/main/native/include/hal/SPI.h b/third_party/allwpilib/hal/src/main/native/include/hal/SPI.h
index 84cec5d..f3c7fdc 100644
--- a/third_party/allwpilib/hal/src/main/native/include/hal/SPI.h
+++ b/third_party/allwpilib/hal/src/main/native/include/hal/SPI.h
@@ -90,23 +90,27 @@
  *
  * @param port  The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for
  *              MXP
- * @param speed The speed in Hz (0-1MHz)
+ * @param speed The speed in Hz (500KHz-10MHz)
  */
 void HAL_SetSPISpeed(HAL_SPIPort port, int32_t speed);
 
 /**
- * Sets the SPI options.
+ * Sets the SPI Mode.
  *
- * @param port             The number of the port to use. 0-3 for Onboard
- *                         CS0-CS2, 4 for MXP
- * @param msbFirst         True to write the MSB first, False for LSB first
- * @param sampleOnTrailing True to sample on the trailing edge, False to sample
- *                         on the leading edge
- * @param clkIdleHigh      True to set the clock to active low, False to set the
- *                         clock active high
+ * @param port  The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for
+ * MXP
+ * @param mode  The SPI mode to use
  */
-void HAL_SetSPIOpts(HAL_SPIPort port, HAL_Bool msbFirst,
-                    HAL_Bool sampleOnTrailing, HAL_Bool clkIdleHigh);
+void HAL_SetSPIMode(HAL_SPIPort port, HAL_SPIMode mode);
+
+/**
+ * Gets the SPI Mode.
+ *
+ * @param port  The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for
+ * MXP
+ * @returns     The SPI mode currently set
+ */
+HAL_SPIMode HAL_GetSPIMode(HAL_SPIPort port);
 
 /**
  * Sets the CS Active high for a SPI port.
diff --git a/third_party/allwpilib/hal/src/main/native/include/hal/SPITypes.h b/third_party/allwpilib/hal/src/main/native/include/hal/SPITypes.h
index de66226..34b5d61 100644
--- a/third_party/allwpilib/hal/src/main/native/include/hal/SPITypes.h
+++ b/third_party/allwpilib/hal/src/main/native/include/hal/SPITypes.h
@@ -25,6 +25,15 @@
 };
 // clang-format on
 
+// clang-format off
+HAL_ENUM(HAL_SPIMode) {
+  HAL_SPI_kMode0 = 0,
+  HAL_SPI_kMode1 = 1,
+  HAL_SPI_kMode2 = 2,
+  HAL_SPI_kMode3 = 3,
+};
+// clang-format on
+
 #ifdef __cplusplus
 namespace hal {
 
diff --git a/third_party/allwpilib/hal/src/main/native/include/hal/SimDevice.h b/third_party/allwpilib/hal/src/main/native/include/hal/SimDevice.h
index 7c0cf2d..f90cb9b 100644
--- a/third_party/allwpilib/hal/src/main/native/include/hal/SimDevice.h
+++ b/third_party/allwpilib/hal/src/main/native/include/hal/SimDevice.h
@@ -8,8 +8,7 @@
 
 #ifdef __cplusplus
 #include <initializer_list>
-
-#include <wpi/span.h>
+#include <span>
 #endif
 
 #include "hal/Types.h"
@@ -832,7 +831,7 @@
    * @return simulated enum value object
    */
   SimEnum CreateEnum(const char* name, int32_t direction,
-                     wpi::span<const char* const> options,
+                     std::span<const char* const> options,
                      int32_t initialValue) {
     return HAL_CreateSimValueEnum(m_handle, name, direction, options.size(),
                                   const_cast<const char**>(options.data()),
@@ -885,8 +884,8 @@
    * @return simulated enum value object
    */
   SimEnum CreateEnumDouble(const char* name, int32_t direction,
-                           wpi::span<const char* const> options,
-                           wpi::span<const double> optionValues,
+                           std::span<const char* const> options,
+                           std::span<const double> optionValues,
                            int32_t initialValue) {
     if (options.size() != optionValues.size()) {
       return {};
diff --git a/third_party/allwpilib/hal/src/main/native/include/hal/cpp/UnsafeDIO.h b/third_party/allwpilib/hal/src/main/native/include/hal/cpp/UnsafeDIO.h
index eb7f231..c849fd0 100644
--- a/third_party/allwpilib/hal/src/main/native/include/hal/cpp/UnsafeDIO.h
+++ b/third_party/allwpilib/hal/src/main/native/include/hal/cpp/UnsafeDIO.h
@@ -18,6 +18,16 @@
  * outside of the UnsafeManipulateDIO callback.
  */
 struct DIOSetProxy {
+  DIOSetProxy(tDIO::tOutputEnable setOutputDirReg,
+              tDIO::tOutputEnable unsetOutputDirReg,
+              tDIO::tDO setOutputStateReg, tDIO::tDO unsetOutputStateReg,
+              tDIO* dio)
+      : m_setOutputDirReg{setOutputDirReg},
+        m_unsetOutputDirReg{unsetOutputDirReg},
+        m_setOutputStateReg{setOutputStateReg},
+        m_unsetOutputStateReg{unsetOutputStateReg},
+        m_dio{dio} {}
+
   DIOSetProxy(const DIOSetProxy&) = delete;
   DIOSetProxy(DIOSetProxy&&) = delete;
   DIOSetProxy& operator=(const DIOSetProxy&) = delete;
diff --git a/third_party/allwpilib/hal/src/main/native/include/hal/roborio/InterruptManager.h b/third_party/allwpilib/hal/src/main/native/include/hal/roborio/InterruptManager.h
new file mode 100644
index 0000000..36d904b
--- /dev/null
+++ b/third_party/allwpilib/hal/src/main/native/include/hal/roborio/InterruptManager.h
@@ -0,0 +1,33 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <FRC_FPGA_ChipObject/fpgainterfacecapi/NiFpga.h>
+#include <wpi/mutex.h>
+
+#include "hal/ChipObject.h"
+#include "hal/Types.h"
+
+namespace hal {
+class InterruptManager {
+ public:
+  static InterruptManager& GetInstance();
+  static void Initialize(tSystemInterface* baseSystem);
+
+  NiFpga_IrqContext GetContext() noexcept;
+  void ReleaseContext(NiFpga_IrqContext context) noexcept;
+
+  uint32_t WaitForInterrupt(NiFpga_IrqContext context, uint32_t mask,
+                            bool ignorePrevious, uint32_t timeoutInMs,
+                            int32_t* status);
+
+ private:
+  InterruptManager() = default;
+
+  wpi::priority_mutex currentMaskMutex;
+  uint32_t currentMask;
+  NiFpga_Session fpgaSession;
+};
+}  // namespace hal
diff --git a/third_party/allwpilib/hal/src/main/native/include/hal/simulation/DriverStationData.h b/third_party/allwpilib/hal/src/main/native/include/hal/simulation/DriverStationData.h
index 87223ec..b10cf03 100644
--- a/third_party/allwpilib/hal/src/main/native/include/hal/simulation/DriverStationData.h
+++ b/third_party/allwpilib/hal/src/main/native/include/hal/simulation/DriverStationData.h
@@ -4,6 +4,8 @@
 
 #pragma once
 
+#include <cstddef>
+
 #include "hal/DriverStationTypes.h"
 #include "hal/Types.h"
 #include "hal/simulation/NotifyListener.h"
@@ -145,11 +147,11 @@
 
 void HALSIM_SetJoystickIsXbox(int32_t stick, HAL_Bool isXbox);
 void HALSIM_SetJoystickType(int32_t stick, int32_t type);
-void HALSIM_SetJoystickName(int32_t stick, const char* name);
+void HALSIM_SetJoystickName(int32_t stick, const char* name, size_t size);
 void HALSIM_SetJoystickAxisType(int32_t stick, int32_t axis, int32_t type);
 
-void HALSIM_SetGameSpecificMessage(const char* message);
-void HALSIM_SetEventName(const char* name);
+void HALSIM_SetGameSpecificMessage(const char* message, size_t size);
+void HALSIM_SetEventName(const char* name, size_t size);
 void HALSIM_SetMatchType(HAL_MatchType type);
 void HALSIM_SetMatchNumber(int32_t matchNumber);
 void HALSIM_SetReplayNumber(int32_t replayNumber);
diff --git a/third_party/allwpilib/hal/src/main/native/include/hal/simulation/MockHooks.h b/third_party/allwpilib/hal/src/main/native/include/hal/simulation/MockHooks.h
index 330f72e..fe50656 100644
--- a/third_party/allwpilib/hal/src/main/native/include/hal/simulation/MockHooks.h
+++ b/third_party/allwpilib/hal/src/main/native/include/hal/simulation/MockHooks.h
@@ -36,4 +36,6 @@
     HALSIM_SimPeriodicCallback callback, void* param);
 void HALSIM_CancelSimPeriodicAfterCallback(int32_t uid);
 
+void HALSIM_CancelAllSimPeriodicCallbacks(void);
+
 }  // extern "C"
diff --git a/third_party/allwpilib/hal/src/main/native/include/hal/simulation/Reset.h b/third_party/allwpilib/hal/src/main/native/include/hal/simulation/Reset.h
new file mode 100644
index 0000000..447321c
--- /dev/null
+++ b/third_party/allwpilib/hal/src/main/native/include/hal/simulation/Reset.h
@@ -0,0 +1,7 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+extern "C" void HALSIM_ResetAllSimData(void);
diff --git a/third_party/allwpilib/hal/src/main/native/include/hal/simulation/RoboRioData.h b/third_party/allwpilib/hal/src/main/native/include/hal/simulation/RoboRioData.h
index 8f33bc5..864be5c 100644
--- a/third_party/allwpilib/hal/src/main/native/include/hal/simulation/RoboRioData.h
+++ b/third_party/allwpilib/hal/src/main/native/include/hal/simulation/RoboRioData.h
@@ -4,9 +4,14 @@
 
 #pragma once
 
+#include <cstddef>
+
 #include "hal/Types.h"
 #include "hal/simulation/NotifyListener.h"
 
+typedef void (*HAL_RoboRioStringCallback)(const char* name, void* param,
+                                          const char* str, size_t size);
+
 #ifdef __cplusplus
 extern "C" {
 #endif
@@ -121,6 +126,18 @@
 double HALSIM_GetRoboRioBrownoutVoltage(void);
 void HALSIM_SetRoboRioBrownoutVoltage(double brownoutVoltage);
 
+int32_t HALSIM_RegisterRoboRioSerialNumberCallback(
+    HAL_RoboRioStringCallback callback, void* param, HAL_Bool initialNotify);
+void HALSIM_CancelRoboRioSerialNumberCallback(int32_t uid);
+size_t HALSIM_GetRoboRioSerialNumber(char* buffer, size_t size);
+void HALSIM_SetRoboRioSerialNumber(const char* serialNumber, size_t size);
+
+int32_t HALSIM_RegisterRoboRioCommentsCallback(
+    HAL_RoboRioStringCallback callback, void* param, HAL_Bool initialNotify);
+void HALSIM_CancelRoboRioCommentsCallback(int32_t uid);
+size_t HALSIM_GetRoboRioComments(char* buffer, size_t size);
+void HALSIM_SetRoboRioComments(const char* comments, size_t size);
+
 void HALSIM_RegisterRoboRioAllCallbacks(HAL_NotifyCallback callback,
                                         void* param, HAL_Bool initialNotify);
 
diff --git a/third_party/allwpilib/hal/src/main/native/include/hal/simulation/SimDataValue.h b/third_party/allwpilib/hal/src/main/native/include/hal/simulation/SimDataValue.h
index 4368a10..0f0cde5 100644
--- a/third_party/allwpilib/hal/src/main/native/include/hal/simulation/SimDataValue.h
+++ b/third_party/allwpilib/hal/src/main/native/include/hal/simulation/SimDataValue.h
@@ -87,9 +87,21 @@
           T (*GetDefault)() = nullptr>
 class SimDataValue final : public impl::SimDataValueBase<T, MakeValue> {
  public:
+// FIXME: GCC 12.1 gives the false positive "the address of <GetDefault> will
+// never be NULL" because it doesn't realize the default template parameter can
+// make GetDefault nullptr. In C++20, replace "T (*GetDefault)() = nullptr" with
+// "T (*GetDefault)() = [] { return T(); }" and unconditionally call
+// GetDefault() to fix the warning.
+#if __GNUC__ >= 12
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Waddress"
+#endif  // __GNUC__ >= 12
   SimDataValue()
       : impl::SimDataValueBase<T, MakeValue>(
             GetDefault != nullptr ? GetDefault() : T()) {}
+#if __GNUC__ >= 12
+#pragma GCC diagnostic pop
+#endif  // __GNUC__ >= 12
   explicit SimDataValue(T value)
       : impl::SimDataValueBase<T, MakeValue>(value) {}
 
@@ -136,22 +148,24 @@
  * @param DATA the backing data array
  * @param LOWERNAME the lowercase name of the backing data variable
  */
-#define HAL_SIMDATAVALUE_DEFINE_CAPI(TYPE, NS, CAPINAME, DATA, LOWERNAME)  \
-  int32_t NS##_Register##CAPINAME##Callback(                               \
-      int32_t index, HAL_NotifyCallback callback, void* param,             \
-      HAL_Bool initialNotify) {                                            \
-    return DATA[index].LOWERNAME.RegisterCallback(callback, param,         \
-                                                  initialNotify);          \
-  }                                                                        \
-                                                                           \
-  void NS##_Cancel##CAPINAME##Callback(int32_t index, int32_t uid) {       \
-    DATA[index].LOWERNAME.CancelCallback(uid);                             \
-  }                                                                        \
-                                                                           \
-  TYPE NS##_Get##CAPINAME(int32_t index) { return DATA[index].LOWERNAME; } \
-                                                                           \
-  void NS##_Set##CAPINAME(int32_t index, TYPE LOWERNAME) {                 \
-    DATA[index].LOWERNAME = LOWERNAME;                                     \
+#define HAL_SIMDATAVALUE_DEFINE_CAPI(TYPE, NS, CAPINAME, DATA, LOWERNAME) \
+  int32_t NS##_Register##CAPINAME##Callback(                              \
+      int32_t index, HAL_NotifyCallback callback, void* param,            \
+      HAL_Bool initialNotify) {                                           \
+    return DATA[index].LOWERNAME.RegisterCallback(callback, param,        \
+                                                  initialNotify);         \
+  }                                                                       \
+                                                                          \
+  void NS##_Cancel##CAPINAME##Callback(int32_t index, int32_t uid) {      \
+    DATA[index].LOWERNAME.CancelCallback(uid);                            \
+  }                                                                       \
+                                                                          \
+  TYPE NS##_Get##CAPINAME(int32_t index) {                                \
+    return DATA[index].LOWERNAME;                                         \
+  }                                                                       \
+                                                                          \
+  void NS##_Set##CAPINAME(int32_t index, TYPE LOWERNAME) {                \
+    DATA[index].LOWERNAME = LOWERNAME;                                    \
   }
 
 /**
@@ -220,9 +234,13 @@
     DATA->LOWERNAME.CancelCallback(uid);                                     \
   }                                                                          \
                                                                              \
-  TYPE NS##_Get##CAPINAME(void) { return DATA->LOWERNAME; }                  \
+  TYPE NS##_Get##CAPINAME(void) {                                            \
+    return DATA->LOWERNAME;                                                  \
+  }                                                                          \
                                                                              \
-  void NS##_Set##CAPINAME(TYPE LOWERNAME) { DATA->LOWERNAME = LOWERNAME; }
+  void NS##_Set##CAPINAME(TYPE LOWERNAME) {                                  \
+    DATA->LOWERNAME = LOWERNAME;                                             \
+  }
 
 /**
  * Define a stub standard C API for simulation data.
@@ -249,7 +267,9 @@
                                                                       \
   void NS##_Cancel##CAPINAME##Callback(int32_t index, int32_t uid) {} \
                                                                       \
-  TYPE NS##_Get##CAPINAME(int32_t index) { return RETURN; }           \
+  TYPE NS##_Get##CAPINAME(int32_t index) {                            \
+    return RETURN;                                                    \
+  }                                                                   \
                                                                       \
   void NS##_Set##CAPINAME(int32_t index, TYPE) {}
 
@@ -269,18 +289,20 @@
  * @param CAPINAME the C API name (usually first letter capitalized)
  * @param RETURN what to return from the Get function
  */
-#define HAL_SIMDATAVALUE_STUB_CAPI_CHANNEL(TYPE, NS, CAPINAME, RETURN)       \
-  int32_t NS##_Register##CAPINAME##Callback(                                 \
-      int32_t index, int32_t channel, HAL_NotifyCallback callback,           \
-      void* param, HAL_Bool initialNotify) {                                 \
-    return 0;                                                                \
-  }                                                                          \
-                                                                             \
-  void NS##_Cancel##CAPINAME##Callback(int32_t index, int32_t channel,       \
-                                       int32_t uid) {}                       \
-                                                                             \
-  TYPE NS##_Get##CAPINAME(int32_t index, int32_t channel) { return RETURN; } \
-                                                                             \
+#define HAL_SIMDATAVALUE_STUB_CAPI_CHANNEL(TYPE, NS, CAPINAME, RETURN) \
+  int32_t NS##_Register##CAPINAME##Callback(                           \
+      int32_t index, int32_t channel, HAL_NotifyCallback callback,     \
+      void* param, HAL_Bool initialNotify) {                           \
+    return 0;                                                          \
+  }                                                                    \
+                                                                       \
+  void NS##_Cancel##CAPINAME##Callback(int32_t index, int32_t channel, \
+                                       int32_t uid) {}                 \
+                                                                       \
+  TYPE NS##_Get##CAPINAME(int32_t index, int32_t channel) {            \
+    return RETURN;                                                     \
+  }                                                                    \
+                                                                       \
   void NS##_Set##CAPINAME(int32_t index, int32_t channel, TYPE) {}
 
 /**
@@ -306,7 +328,9 @@
                                                                           \
   void NS##_Cancel##CAPINAME##Callback(int32_t uid) {}                    \
                                                                           \
-  TYPE NS##_Get##CAPINAME(void) { return RETURN; }                        \
+  TYPE NS##_Get##CAPINAME(void) {                                         \
+    return RETURN;                                                        \
+  }                                                                       \
                                                                           \
   void NS##_Set##CAPINAME(TYPE) {}
 
diff --git a/third_party/allwpilib/hal/src/main/native/sim/CANAPI.cpp b/third_party/allwpilib/hal/src/main/native/sim/CANAPI.cpp
index 4d733bb..38014bd 100644
--- a/third_party/allwpilib/hal/src/main/native/sim/CANAPI.cpp
+++ b/third_party/allwpilib/hal/src/main/native/sim/CANAPI.cpp
@@ -93,6 +93,9 @@
 
 void HAL_CleanCAN(HAL_CANHandle handle) {
   auto data = canHandles->Free(handle);
+  if (data == nullptr) {
+    return;
+  }
 
   std::scoped_lock lock(data->mapMutex);
 
diff --git a/third_party/allwpilib/hal/src/main/native/sim/DIO.cpp b/third_party/allwpilib/hal/src/main/native/sim/DIO.cpp
index 1b744a1..b611b35 100644
--- a/third_party/allwpilib/hal/src/main/native/sim/DIO.cpp
+++ b/third_party/allwpilib/hal/src/main/native/sim/DIO.cpp
@@ -151,6 +151,23 @@
   SimDigitalPWMData[id].dutyCycle = dutyCycle;
 }
 
+void HAL_SetDigitalPWMPPS(HAL_DigitalPWMHandle pwmGenerator, double dutyCycle,
+                          int32_t* status) {
+  auto port = digitalPWMHandles->Get(pwmGenerator);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  int32_t id = *port;
+  if (dutyCycle > 1.0) {
+    dutyCycle = 1.0;
+  }
+  if (dutyCycle < 0.0) {
+    dutyCycle = 0.0;
+  }
+  SimDigitalPWMData[id].dutyCycle = dutyCycle;
+}
+
 void HAL_SetDigitalPWMOutputChannel(HAL_DigitalPWMHandle pwmGenerator,
                                     int32_t channel, int32_t* status) {
   auto port = digitalPWMHandles->Get(pwmGenerator);
@@ -225,7 +242,7 @@
   return value;
 }
 
-void HAL_Pulse(HAL_DigitalHandle dioPortHandle, double pulseLength,
+void HAL_Pulse(HAL_DigitalHandle dioPortHandle, double pulseLengthSeconds,
                int32_t* status) {
   auto port = digitalChannelHandles->Get(dioPortHandle, HAL_HandleEnum::DIO);
   if (port == nullptr) {
@@ -235,6 +252,11 @@
   // TODO (Thad) Add this
 }
 
+void HAL_PulseMultiple(uint32_t channelMask, double pulseLengthSeconds,
+                       int32_t* status) {
+  // TODO (Thad) Add this
+}
+
 HAL_Bool HAL_IsPulsing(HAL_DigitalHandle dioPortHandle, int32_t* status) {
   auto port = digitalChannelHandles->Get(dioPortHandle, HAL_HandleEnum::DIO);
   if (port == nullptr) {
diff --git a/third_party/allwpilib/hal/src/main/native/sim/DigitalInternal.h b/third_party/allwpilib/hal/src/main/native/sim/DigitalInternal.h
index cd1ac5f..e7f531e 100644
--- a/third_party/allwpilib/hal/src/main/native/sim/DigitalInternal.h
+++ b/third_party/allwpilib/hal/src/main/native/sim/DigitalInternal.h
@@ -30,7 +30,7 @@
  *   reliably down to 10.0 ms; starting at about 8.5ms, the servo sometimes hums
  *   and get hot; by 5.0ms the hum is nearly continuous
  * - 10ms periods work well for Victor 884
- * - 5ms periods allows higher update rates for Luminary Micro Jaguar speed
+ * - 5ms periods allows higher update rates for Luminary Micro Jaguar motor
  *   controllers. Due to the shipping firmware on the Jaguar, we can't run the
  *   update period less than 5.05 ms.
  *
diff --git a/third_party/allwpilib/hal/src/main/native/sim/DriverStation.cpp b/third_party/allwpilib/hal/src/main/native/sim/DriverStation.cpp
index 723cdac..c99493d 100644
--- a/third_party/allwpilib/hal/src/main/native/sim/DriverStation.cpp
+++ b/third_party/allwpilib/hal/src/main/native/sim/DriverStation.cpp
@@ -8,37 +8,94 @@
 #include <pthread.h>
 #endif
 
+#include <atomic>
 #include <cstdio>
 #include <cstdlib>
 #include <cstring>
 #include <string>
 
 #include <fmt/format.h>
+#include <wpi/EventVector.h>
 #include <wpi/condition_variable.h>
 #include <wpi/mutex.h>
 
 #include "HALInitializer.h"
+#include "hal/Errors.h"
 #include "hal/cpp/fpga_clock.h"
 #include "hal/simulation/MockHooks.h"
 #include "mockdata/DriverStationDataInternal.h"
 
 static wpi::mutex msgMutex;
-static wpi::condition_variable* newDSDataAvailableCond;
-static wpi::mutex newDSDataAvailableMutex;
-static int newDSDataAvailableCounter{0};
-static std::atomic_bool isFinalized{false};
 static std::atomic<HALSIM_SendErrorHandler> sendErrorHandler{nullptr};
 static std::atomic<HALSIM_SendConsoleLineHandler> sendConsoleLineHandler{
     nullptr};
 
+using namespace hal;
+
+static constexpr int kJoystickPorts = 6;
+
+namespace {
+struct JoystickDataCache {
+  JoystickDataCache() { std::memset(this, 0, sizeof(*this)); }
+  void Update();
+
+  HAL_JoystickAxes axes[kJoystickPorts];
+  HAL_JoystickPOVs povs[kJoystickPorts];
+  HAL_JoystickButtons buttons[kJoystickPorts];
+  HAL_AllianceStationID allianceStation;
+  double matchTime;
+};
+static_assert(std::is_standard_layout_v<JoystickDataCache>);
+// static_assert(std::is_trivial_v<JoystickDataCache>);
+
+static std::atomic_bool gShutdown{false};
+
+struct FRCDriverStation {
+  ~FRCDriverStation() { gShutdown = true; }
+  wpi::EventVector newDataEvents;
+  wpi::mutex cacheMutex;
+};
+}  // namespace
+
+void JoystickDataCache::Update() {
+  for (int i = 0; i < kJoystickPorts; i++) {
+    SimDriverStationData->GetJoystickAxes(i, &axes[i]);
+    SimDriverStationData->GetJoystickPOVs(i, &povs[i]);
+    SimDriverStationData->GetJoystickButtons(i, &buttons[i]);
+  }
+  allianceStation = SimDriverStationData->allianceStationId;
+  matchTime = SimDriverStationData->matchTime;
+}
+
+#define CHECK_JOYSTICK_NUMBER(stickNum)                  \
+  if ((stickNum) < 0 || (stickNum) >= HAL_kMaxJoysticks) \
+  return PARAMETER_OUT_OF_RANGE
+
+static HAL_ControlWord newestControlWord;
+static JoystickDataCache caches[3];
+static JoystickDataCache* currentRead = &caches[0];
+static JoystickDataCache* currentReadLocal = &caches[0];
+static std::atomic<JoystickDataCache*> currentCache{&caches[1]};
+static JoystickDataCache* lastGiven = &caches[1];
+static JoystickDataCache* cacheToUpdate = &caches[2];
+
+static ::FRCDriverStation* driverStation;
+
 namespace hal::init {
 void InitializeDriverStation() {
-  static wpi::condition_variable nddaC;
-  newDSDataAvailableCond = &nddaC;
+  static FRCDriverStation ds;
+  driverStation = &ds;
 }
 }  // namespace hal::init
 
-using namespace hal;
+namespace hal {
+static void DefaultPrintErrorImpl(const char* line, size_t size) {
+  std::fwrite(line, size, 1, stderr);
+}
+}  // namespace hal
+
+static std::atomic<void (*)(const char* line, size_t size)> gPrintErrorImpl{
+    hal::DefaultPrintErrorImpl};
 
 extern "C" {
 
@@ -92,7 +149,8 @@
       if (callStack && callStack[0] != '\0') {
         fmt::format_to(fmt::appender{buf}, "{}\n", callStack);
       }
-      std::fwrite(buf.data(), buf.size(), 1, stderr);
+      auto printError = gPrintErrorImpl.load();
+      printError(buf.data(), buf.size());
     }
     if (i == KEEP_MSGS) {
       // replace the oldest one
@@ -111,6 +169,10 @@
   return retval;
 }
 
+void HAL_SetPrintErrorImpl(void (*func)(const char* line, size_t size)) {
+  gPrintErrorImpl.store(func ? func : hal::DefaultPrintErrorImpl);
+}
+
 int32_t HAL_SendConsoleLine(const char* line) {
   auto handler = sendConsoleLineHandler.load();
   if (handler) {
@@ -122,39 +184,67 @@
 }
 
 int32_t HAL_GetControlWord(HAL_ControlWord* controlWord) {
-  std::memset(controlWord, 0, sizeof(HAL_ControlWord));
-  controlWord->enabled = SimDriverStationData->enabled;
-  controlWord->autonomous = SimDriverStationData->autonomous;
-  controlWord->test = SimDriverStationData->test;
-  controlWord->eStop = SimDriverStationData->eStop;
-  controlWord->fmsAttached = SimDriverStationData->fmsAttached;
-  controlWord->dsAttached = SimDriverStationData->dsAttached;
+  if (gShutdown) {
+    return INCOMPATIBLE_STATE;
+  }
+  std::scoped_lock lock{driverStation->cacheMutex};
+  *controlWord = newestControlWord;
   return 0;
 }
 
 HAL_AllianceStationID HAL_GetAllianceStation(int32_t* status) {
-  *status = 0;
-  return SimDriverStationData->allianceStationId;
+  if (gShutdown) {
+    return HAL_AllianceStationID_kRed1;
+  }
+  std::scoped_lock lock{driverStation->cacheMutex};
+  return currentRead->allianceStation;
 }
 
 int32_t HAL_GetJoystickAxes(int32_t joystickNum, HAL_JoystickAxes* axes) {
-  SimDriverStationData->GetJoystickAxes(joystickNum, axes);
+  if (gShutdown) {
+    return INCOMPATIBLE_STATE;
+  }
+  CHECK_JOYSTICK_NUMBER(joystickNum);
+  std::scoped_lock lock{driverStation->cacheMutex};
+  *axes = currentRead->axes[joystickNum];
   return 0;
 }
 
 int32_t HAL_GetJoystickPOVs(int32_t joystickNum, HAL_JoystickPOVs* povs) {
-  SimDriverStationData->GetJoystickPOVs(joystickNum, povs);
+  if (gShutdown) {
+    return INCOMPATIBLE_STATE;
+  }
+  CHECK_JOYSTICK_NUMBER(joystickNum);
+  std::scoped_lock lock{driverStation->cacheMutex};
+  *povs = currentRead->povs[joystickNum];
   return 0;
 }
 
 int32_t HAL_GetJoystickButtons(int32_t joystickNum,
                                HAL_JoystickButtons* buttons) {
-  SimDriverStationData->GetJoystickButtons(joystickNum, buttons);
+  if (gShutdown) {
+    return INCOMPATIBLE_STATE;
+  }
+  CHECK_JOYSTICK_NUMBER(joystickNum);
+  std::scoped_lock lock{driverStation->cacheMutex};
+  *buttons = currentRead->buttons[joystickNum];
   return 0;
 }
 
+void HAL_GetAllJoystickData(HAL_JoystickAxes* axes, HAL_JoystickPOVs* povs,
+                            HAL_JoystickButtons* buttons) {
+  if (gShutdown) {
+    return;
+  }
+  std::scoped_lock lock{driverStation->cacheMutex};
+  std::memcpy(axes, currentRead->axes, sizeof(currentRead->axes));
+  std::memcpy(povs, currentRead->povs, sizeof(currentRead->povs));
+  std::memcpy(buttons, currentRead->buttons, sizeof(currentRead->buttons));
+}
+
 int32_t HAL_GetJoystickDescriptor(int32_t joystickNum,
                                   HAL_JoystickDescriptor* desc) {
+  CHECK_JOYSTICK_NUMBER(joystickNum);
   SimDriverStationData->GetJoystickDescriptor(joystickNum, desc);
   return 0;
 }
@@ -196,7 +286,11 @@
 }
 
 double HAL_GetMatchTime(int32_t* status) {
-  return SimDriverStationData->matchTime;
+  if (gShutdown) {
+    return 0;
+  }
+  std::scoped_lock lock{driverStation->cacheMutex};
+  return currentRead->matchTime;
 }
 
 int32_t HAL_GetMatchInfo(HAL_MatchInfo* info) {
@@ -224,103 +318,74 @@
   // TODO
 }
 
-static int& GetThreadLocalLastCount() {
-  // There is a rollover error condition here. At Packet# = n * (uintmax), this
-  // will return false when instead it should return true. However, this at a
-  // 20ms rate occurs once every 2.7 years of DS connected runtime, so not
-  // worth the cycles to check.
-  thread_local int lastCount{0};
-  return lastCount;
+void HAL_RefreshDSData(void) {
+  if (gShutdown) {
+    return;
+  }
+  HAL_ControlWord controlWord;
+  std::memset(&controlWord, 0, sizeof(controlWord));
+  controlWord.enabled = SimDriverStationData->enabled;
+  controlWord.autonomous = SimDriverStationData->autonomous;
+  controlWord.test = SimDriverStationData->test;
+  controlWord.eStop = SimDriverStationData->eStop;
+  controlWord.fmsAttached = SimDriverStationData->fmsAttached;
+  controlWord.dsAttached = SimDriverStationData->dsAttached;
+  std::scoped_lock lock{driverStation->cacheMutex};
+  JoystickDataCache* prev = currentCache.exchange(nullptr);
+  if (prev != nullptr) {
+    currentRead = prev;
+  }
+  newestControlWord = controlWord;
 }
 
-HAL_Bool HAL_IsNewControlData(void) {
-  std::scoped_lock lock(newDSDataAvailableMutex);
-  int& lastCount = GetThreadLocalLastCount();
-  int currentCount = newDSDataAvailableCounter;
-  if (lastCount == currentCount) {
-    return false;
+void HAL_ProvideNewDataEventHandle(WPI_EventHandle handle) {
+  if (gShutdown) {
+    return;
   }
-  lastCount = currentCount;
-  return true;
-}
-
-void HAL_WaitForDSData(void) {
-  HAL_WaitForDSDataTimeout(0);
-}
-
-HAL_Bool HAL_WaitForDSDataTimeout(double timeout) {
-  std::unique_lock lock(newDSDataAvailableMutex);
-  int& lastCount = GetThreadLocalLastCount();
-  int currentCount = newDSDataAvailableCounter;
-  if (lastCount != currentCount) {
-    lastCount = currentCount;
-    return true;
-  }
-
-  if (isFinalized.load()) {
-    return false;
-  }
-  auto timeoutTime =
-      std::chrono::steady_clock::now() + std::chrono::duration<double>(timeout);
-
-  while (newDSDataAvailableCounter == currentCount) {
-    if (timeout > 0) {
-      auto timedOut = newDSDataAvailableCond->wait_until(lock, timeoutTime);
-      if (timedOut == std::cv_status::timeout) {
-        return false;
-      }
-    } else {
-      newDSDataAvailableCond->wait(lock);
-    }
-  }
-  lastCount = newDSDataAvailableCounter;
-  return true;
-}
-
-// Constant number to be used for our occur handle
-constexpr int32_t refNumber = 42;
-
-static int32_t newDataOccur(uint32_t refNum) {
-  // Since we could get other values, require our specific handle
-  // to signal our threads
-  if (refNum != refNumber) {
-    return 0;
-  }
-  SimDriverStationData->CallNewDataCallbacks();
-  std::scoped_lock lock(newDSDataAvailableMutex);
-  // Nofify all threads
-  newDSDataAvailableCounter++;
-  newDSDataAvailableCond->notify_all();
-  return 0;
-}
-
-void HAL_InitializeDriverStation(void) {
   hal::init::CheckInit();
-  static std::atomic_bool initialized{false};
-  static wpi::mutex initializeMutex;
-  // Initial check, as if it's true initialization has finished
-  if (initialized) {
-    return;
-  }
-
-  std::scoped_lock lock(initializeMutex);
-  // Second check in case another thread was waiting
-  if (initialized) {
-    return;
-  }
-
-  SimDriverStationData->ResetData();
-
-  std::atexit([]() {
-    isFinalized.store(true);
-    HAL_ReleaseDSMutex();
-  });
-
-  initialized = true;
+  driverStation->newDataEvents.Add(handle);
 }
 
-void HAL_ReleaseDSMutex(void) {
-  newDataOccur(refNumber);
+void HAL_RemoveNewDataEventHandle(WPI_EventHandle handle) {
+  if (gShutdown) {
+    return;
+  }
+  driverStation->newDataEvents.Remove(handle);
+}
+
+HAL_Bool HAL_GetOutputsEnabled(void) {
+  if (gShutdown) {
+    return false;
+  }
+  std::scoped_lock lock{driverStation->cacheMutex};
+  return newestControlWord.enabled && newestControlWord.dsAttached;
 }
 
 }  // extern "C"
+
+namespace hal {
+void NewDriverStationData() {
+  if (gShutdown) {
+    return;
+  }
+  cacheToUpdate->Update();
+
+  JoystickDataCache* given = cacheToUpdate;
+  JoystickDataCache* prev = currentCache.exchange(cacheToUpdate);
+  if (prev == nullptr) {
+    cacheToUpdate = currentReadLocal;
+    currentReadLocal = lastGiven;
+  } else {
+    // Current read local does not update
+    cacheToUpdate = prev;
+  }
+  lastGiven = given;
+
+  driverStation->newDataEvents.Wakeup();
+  SimDriverStationData->CallNewDataCallbacks();
+}
+
+void InitializeDriverStation() {
+  SimDriverStationData->ResetData();
+}
+}  // namespace hal
diff --git a/third_party/allwpilib/hal/src/main/native/sim/DutyCycle.cpp b/third_party/allwpilib/hal/src/main/native/sim/DutyCycle.cpp
index 51c6506..f46d2da 100644
--- a/third_party/allwpilib/hal/src/main/native/sim/DutyCycle.cpp
+++ b/third_party/allwpilib/hal/src/main/native/sim/DutyCycle.cpp
@@ -84,6 +84,7 @@
   }
   return SimDutyCycleData[dutyCycle->index].frequency;
 }
+
 double HAL_GetDutyCycleOutput(HAL_DutyCycleHandle dutyCycleHandle,
                               int32_t* status) {
   auto dutyCycle = dutyCycleHandles->Get(dutyCycleHandle);
@@ -93,20 +94,29 @@
   }
   return SimDutyCycleData[dutyCycle->index].output;
 }
-int32_t HAL_GetDutyCycleOutputRaw(HAL_DutyCycleHandle dutyCycleHandle,
-                                  int32_t* status) {
+
+int32_t HAL_GetDutyCycleHighTime(HAL_DutyCycleHandle dutyCycleHandle,
+                                 int32_t* status) {
   auto dutyCycle = dutyCycleHandles->Get(dutyCycleHandle);
   if (dutyCycle == nullptr) {
     *status = HAL_HANDLE_ERROR;
     return 0;
   }
-  return SimDutyCycleData[dutyCycle->index].output *
-         HAL_GetDutyCycleOutputScaleFactor(dutyCycleHandle, status);
+
+  if (SimDutyCycleData[dutyCycle->index].frequency == 0) {
+    return 0;
+  }
+
+  double periodSeconds = 1.0 / SimDutyCycleData[dutyCycle->index].frequency;
+  double periodNanoSeconds = periodSeconds * 1e9;
+  return periodNanoSeconds * SimDutyCycleData[dutyCycle->index].output;
 }
+
 int32_t HAL_GetDutyCycleOutputScaleFactor(HAL_DutyCycleHandle dutyCycleHandle,
                                           int32_t* status) {
   return 4e7 - 1;
 }
+
 int32_t HAL_GetDutyCycleFPGAIndex(HAL_DutyCycleHandle dutyCycleHandle,
                                   int32_t* status) {
   auto dutyCycle = dutyCycleHandles->Get(dutyCycleHandle);
diff --git a/third_party/allwpilib/hal/src/main/native/sim/Encoder.cpp b/third_party/allwpilib/hal/src/main/native/sim/Encoder.cpp
index 78aa281..137ee78 100644
--- a/third_party/allwpilib/hal/src/main/native/sim/Encoder.cpp
+++ b/third_party/allwpilib/hal/src/main/native/sim/Encoder.cpp
@@ -53,7 +53,7 @@
                           HAL_FPGAEncoderHandle* fpgaHandle,
                           HAL_CounterHandle* counterHandle) {
   auto encoder = encoderHandles->Get(handle);
-  if (!handle) {
+  if (!encoder) {
     return false;
   }
 
diff --git a/third_party/allwpilib/hal/src/main/native/sim/HAL.cpp b/third_party/allwpilib/hal/src/main/native/sim/HAL.cpp
index 8d911df..82dd8c4 100644
--- a/third_party/allwpilib/hal/src/main/native/sim/HAL.cpp
+++ b/third_party/allwpilib/hal/src/main/native/sim/HAL.cpp
@@ -57,6 +57,10 @@
 static SimPeriodicCallbackRegistry gSimPeriodicBefore;
 static SimPeriodicCallbackRegistry gSimPeriodicAfter;
 
+namespace hal {
+void InitializeDriverStation();
+}  // namespace hal
+
 namespace hal::init {
 void InitializeHAL() {
   InitializeAccelerometerData();
@@ -276,6 +280,14 @@
   return 0;  // TODO: Find a better number to return;
 }
 
+size_t HAL_GetSerialNumber(char* buffer, size_t size) {
+  return HALSIM_GetRoboRioSerialNumber(buffer, size);
+}
+
+size_t HAL_GetComments(char* buffer, size_t size) {
+  return HALSIM_GetRoboRioComments(buffer, size);
+}
+
 uint64_t HAL_GetFPGATime(int32_t* status) {
   return hal::GetFPGATime();
 }
@@ -335,7 +347,7 @@
   hal::init::HAL_IsInitialized.store(true);
 
   hal::RestartTiming();
-  HAL_InitializeDriverStation();
+  hal::InitializeDriverStation();
 
   initialized = true;
 
@@ -409,6 +421,11 @@
   gSimPeriodicAfter.Cancel(uid);
 }
 
+void HALSIM_CancelAllSimPeriodicCallbacks(void) {
+  gSimPeriodicBefore.Reset();
+  gSimPeriodicAfter.Reset();
+}
+
 int64_t HAL_Report(int32_t resource, int32_t instanceNumber, int32_t context,
                    const char* feature) {
   return 0;  // Do nothing for now
diff --git a/third_party/allwpilib/hal/src/main/native/sim/Interrupts.cpp b/third_party/allwpilib/hal/src/main/native/sim/Interrupts.cpp
index e55316d..ac9f7f8 100644
--- a/third_party/allwpilib/hal/src/main/native/sim/Interrupts.cpp
+++ b/third_party/allwpilib/hal/src/main/native/sim/Interrupts.cpp
@@ -351,6 +351,26 @@
   }
 }
 
+int64_t HAL_WaitForMultipleInterrupts(HAL_InterruptHandle interruptHandle,
+                                      int64_t mask, double timeout,
+                                      HAL_Bool ignorePrevious,
+                                      int32_t* status) {
+  // TODO make this properly work, will require a decent rewrite
+  auto interrupt = interruptHandles->Get(interruptHandle);
+  if (interrupt == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return WaitResult::Timeout;
+  }
+
+  if (interrupt->isAnalog) {
+    return WaitForInterruptAnalog(interruptHandle, interrupt.get(), timeout,
+                                  ignorePrevious);
+  } else {
+    return WaitForInterruptDigital(interruptHandle, interrupt.get(), timeout,
+                                   ignorePrevious);
+  }
+}
+
 int64_t HAL_ReadInterruptRisingTimestamp(HAL_InterruptHandle interruptHandle,
                                          int32_t* status) {
   auto interrupt = interruptHandles->Get(interruptHandle);
diff --git a/third_party/allwpilib/hal/src/main/native/sim/MockHooks.cpp b/third_party/allwpilib/hal/src/main/native/sim/MockHooks.cpp
index 4e20c6a..93c385e 100644
--- a/third_party/allwpilib/hal/src/main/native/sim/MockHooks.cpp
+++ b/third_party/allwpilib/hal/src/main/native/sim/MockHooks.cpp
@@ -122,7 +122,7 @@
     int32_t status = 0;
     uint64_t curTime = HAL_GetFPGATime(&status);
     uint64_t nextTimeout = HALSIM_GetNextNotifierTimeout();
-    uint64_t step = std::min(delta, nextTimeout - curTime);
+    uint64_t step = (std::min)(delta, nextTimeout - curTime);
 
     StepTiming(step);
     delta -= step;
diff --git a/third_party/allwpilib/hal/src/main/native/sim/PowerDistribution.cpp b/third_party/allwpilib/hal/src/main/native/sim/PowerDistribution.cpp
index ddda420..22e4bba 100644
--- a/third_party/allwpilib/hal/src/main/native/sim/PowerDistribution.cpp
+++ b/third_party/allwpilib/hal/src/main/native/sim/PowerDistribution.cpp
@@ -147,11 +147,23 @@
 }
 double HAL_GetPowerDistributionTotalCurrent(HAL_PowerDistributionHandle handle,
                                             int32_t* status) {
-  return 0.0;
+  auto module = hal::can::GetCANModuleFromHandle(handle, status);
+  if (*status != 0) {
+    return 0.0;
+  }
+
+  double total = 0.0;
+  auto& data = SimPowerDistributionData[module];
+  for (int i = 0; i < kNumPDSimChannels; i++) {
+    total += data.current[i];
+  }
+  return total;
 }
 double HAL_GetPowerDistributionTotalPower(HAL_PowerDistributionHandle handle,
                                           int32_t* status) {
-  return 0.0;
+  double voltage = HAL_GetPowerDistributionVoltage(handle, status);
+  double current = HAL_GetPowerDistributionTotalCurrent(handle, status);
+  return voltage * current;
 }
 double HAL_GetPowerDistributionTotalEnergy(HAL_PowerDistributionHandle handle,
                                            int32_t* status) {
diff --git a/third_party/allwpilib/hal/src/main/native/sim/SPI.cpp b/third_party/allwpilib/hal/src/main/native/sim/SPI.cpp
index bf362a8..70e2bde 100644
--- a/third_party/allwpilib/hal/src/main/native/sim/SPI.cpp
+++ b/third_party/allwpilib/hal/src/main/native/sim/SPI.cpp
@@ -34,8 +34,10 @@
   SimSPIData[port].initialized = false;
 }
 void HAL_SetSPISpeed(HAL_SPIPort port, int32_t speed) {}
-void HAL_SetSPIOpts(HAL_SPIPort port, HAL_Bool msbFirst,
-                    HAL_Bool sampleOnTrailing, HAL_Bool clkIdleHigh) {}
+void HAL_SetSPIMode(HAL_SPIPort port, HAL_SPIMode mode) {}
+HAL_SPIMode HAL_GetSPIMode(HAL_SPIPort port) {
+  return HAL_SPI_kMode0;
+}
 void HAL_SetSPIChipSelectActiveHigh(HAL_SPIPort port, int32_t* status) {}
 void HAL_SetSPIChipSelectActiveLow(HAL_SPIPort port, int32_t* status) {}
 int32_t HAL_GetSPIHandle(HAL_SPIPort port) {
diff --git a/third_party/allwpilib/hal/src/main/native/sim/mockdata/DriverStationData.cpp b/third_party/allwpilib/hal/src/main/native/sim/mockdata/DriverStationData.cpp
index 1c76a7a..a0cae1c 100644
--- a/third_party/allwpilib/hal/src/main/native/sim/mockdata/DriverStationData.cpp
+++ b/third_party/allwpilib/hal/src/main/native/sim/mockdata/DriverStationData.cpp
@@ -216,8 +216,12 @@
   m_newDataCallbacks(&empty);
 }
 
+namespace hal {
+void NewDriverStationData();
+}  // namespace hal
+
 void DriverStationData::NotifyNewData() {
-  HAL_ReleaseDSMutex();
+  hal::NewDriverStationData();
 }
 
 void DriverStationData::SetJoystickButton(int32_t stick, int32_t button,
@@ -335,14 +339,17 @@
   m_joystickDescriptorCallbacks(stick, &m_joystickData[stick].descriptor);
 }
 
-void DriverStationData::SetJoystickName(int32_t stick, const char* name) {
+void DriverStationData::SetJoystickName(int32_t stick, const char* name,
+                                        size_t size) {
   if (stick < 0 || stick >= kNumJoysticks) {
     return;
   }
   std::scoped_lock lock(m_joystickDataMutex);
-  std::strncpy(m_joystickData[stick].descriptor.name, name,
-               sizeof(m_joystickData[stick].descriptor.name) - 1);
-  *(std::end(m_joystickData[stick].descriptor.name) - 1) = '\0';
+  if (size > sizeof(m_joystickData[stick].descriptor.name) - 1) {
+    size = sizeof(m_joystickData[stick].descriptor.name) - 1;
+  }
+  std::strncpy(m_joystickData[stick].descriptor.name, name, size);
+  m_joystickData[stick].descriptor.name[size] = '\0';
   m_joystickDescriptorCallbacks(stick, &m_joystickData[stick].descriptor);
 }
 
@@ -359,19 +366,27 @@
   m_joystickDescriptorCallbacks(stick, &m_joystickData[stick].descriptor);
 }
 
-void DriverStationData::SetGameSpecificMessage(const char* message) {
+void DriverStationData::SetGameSpecificMessage(const char* message,
+                                               size_t size) {
   std::scoped_lock lock(m_matchInfoMutex);
+  if (size > sizeof(m_matchInfo.gameSpecificMessage) - 1) {
+    size = sizeof(m_matchInfo.gameSpecificMessage) - 1;
+  }
   std::strncpy(reinterpret_cast<char*>(m_matchInfo.gameSpecificMessage),
-               message, sizeof(m_matchInfo.gameSpecificMessage) - 1);
-  *(std::end(m_matchInfo.gameSpecificMessage) - 1) = '\0';
-  m_matchInfo.gameSpecificMessageSize = std::strlen(message);
+               message, size);
+  m_matchInfo.gameSpecificMessage[size] = '\0';
+  m_matchInfo.gameSpecificMessageSize =
+      std::strlen(reinterpret_cast<char*>(m_matchInfo.gameSpecificMessage));
   m_matchInfoCallbacks(&m_matchInfo);
 }
 
-void DriverStationData::SetEventName(const char* name) {
+void DriverStationData::SetEventName(const char* name, size_t size) {
   std::scoped_lock lock(m_matchInfoMutex);
-  std::strncpy(m_matchInfo.eventName, name, sizeof(m_matchInfo.eventName) - 1);
-  *(std::end(m_matchInfo.eventName) - 1) = '\0';
+  if (size > sizeof(m_matchInfo.eventName) - 1) {
+    size = sizeof(m_matchInfo.eventName) - 1;
+  }
+  std::strncpy(m_matchInfo.eventName, name, size);
+  m_matchInfo.eventName[size] = '\0';
   m_matchInfoCallbacks(&m_matchInfo);
 }
 
@@ -536,20 +551,20 @@
   SimDriverStationData->SetJoystickType(stick, type);
 }
 
-void HALSIM_SetJoystickName(int32_t stick, const char* name) {
-  SimDriverStationData->SetJoystickName(stick, name);
+void HALSIM_SetJoystickName(int32_t stick, const char* name, size_t size) {
+  SimDriverStationData->SetJoystickName(stick, name, size);
 }
 
 void HALSIM_SetJoystickAxisType(int32_t stick, int32_t axis, int32_t type) {
   SimDriverStationData->SetJoystickAxisType(stick, axis, type);
 }
 
-void HALSIM_SetGameSpecificMessage(const char* message) {
-  SimDriverStationData->SetGameSpecificMessage(message);
+void HALSIM_SetGameSpecificMessage(const char* message, size_t size) {
+  SimDriverStationData->SetGameSpecificMessage(message, size);
 }
 
-void HALSIM_SetEventName(const char* name) {
-  SimDriverStationData->SetEventName(name);
+void HALSIM_SetEventName(const char* name, size_t size) {
+  SimDriverStationData->SetEventName(name, size);
 }
 
 void HALSIM_SetMatchType(HAL_MatchType type) {
diff --git a/third_party/allwpilib/hal/src/main/native/sim/mockdata/DriverStationDataInternal.h b/third_party/allwpilib/hal/src/main/native/sim/mockdata/DriverStationDataInternal.h
index 2470b04..763b465 100644
--- a/third_party/allwpilib/hal/src/main/native/sim/mockdata/DriverStationDataInternal.h
+++ b/third_party/allwpilib/hal/src/main/native/sim/mockdata/DriverStationDataInternal.h
@@ -107,11 +107,11 @@
 
   void SetJoystickIsXbox(int32_t stick, HAL_Bool isXbox);
   void SetJoystickType(int32_t stick, int32_t type);
-  void SetJoystickName(int32_t stick, const char* name);
+  void SetJoystickName(int32_t stick, const char* name, size_t size);
   void SetJoystickAxisType(int32_t stick, int32_t axis, int32_t type);
 
-  void SetGameSpecificMessage(const char* message);
-  void SetEventName(const char* name);
+  void SetGameSpecificMessage(const char* message, size_t size);
+  void SetEventName(const char* name, size_t size);
   void SetMatchType(HAL_MatchType type);
   void SetMatchNumber(int32_t matchNumber);
   void SetReplayNumber(int32_t replayNumber);
diff --git a/third_party/allwpilib/hal/src/main/native/sim/mockdata/Reset.cpp b/third_party/allwpilib/hal/src/main/native/sim/mockdata/Reset.cpp
new file mode 100644
index 0000000..bb83973
--- /dev/null
+++ b/third_party/allwpilib/hal/src/main/native/sim/mockdata/Reset.cpp
@@ -0,0 +1,109 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <hal/simulation/AccelerometerData.h>
+#include <hal/simulation/AddressableLEDData.h>
+#include <hal/simulation/AnalogGyroData.h>
+#include <hal/simulation/AnalogInData.h>
+#include <hal/simulation/AnalogOutData.h>
+#include <hal/simulation/AnalogTriggerData.h>
+#include <hal/simulation/CTREPCMData.h>
+#include <hal/simulation/CanData.h>
+#include <hal/simulation/DIOData.h>
+#include <hal/simulation/DigitalPWMData.h>
+#include <hal/simulation/DriverStationData.h>
+#include <hal/simulation/DutyCycleData.h>
+#include <hal/simulation/EncoderData.h>
+#include <hal/simulation/I2CData.h>
+#include <hal/simulation/PWMData.h>
+#include <hal/simulation/PowerDistributionData.h>
+#include <hal/simulation/REVPHData.h>
+#include <hal/simulation/RelayData.h>
+#include <hal/simulation/RoboRioData.h>
+#include <hal/simulation/SPIAccelerometerData.h>
+#include <hal/simulation/SPIData.h>
+#include <hal/simulation/SimDeviceData.h>
+
+#include "../PortsInternal.h"
+
+extern "C" void HALSIM_ResetAllSimData(void) {
+  for (int32_t i = 0; i < hal::kAccelerometers; i++) {
+    HALSIM_ResetAccelerometerData(i);
+  }
+
+  for (int32_t i = 0; i < hal::kNumAddressableLEDs; i++) {
+    HALSIM_ResetAddressableLEDData(i);
+  }
+
+  for (int32_t i = 0; i < hal::kNumAccumulators; i++) {
+    HALSIM_ResetAnalogGyroData(i);
+  }
+
+  for (int32_t i = 0; i < hal::kNumAnalogInputs; i++) {
+    HALSIM_ResetAnalogInData(i);
+  }
+
+  for (int32_t i = 0; i < hal::kNumAnalogOutputs; i++) {
+    HALSIM_ResetAnalogOutData(i);
+  }
+
+  for (int32_t i = 0; i < hal::kNumAnalogTriggers; i++) {
+    HALSIM_ResetAnalogTriggerData(i);
+  }
+
+  HALSIM_ResetCanData();
+
+  for (int32_t i = 0; i < hal::kNumCTREPCMModules; i++) {
+    HALSIM_ResetCTREPCMData(i);
+  }
+
+  for (int32_t i = 0; i < hal::kNumDigitalPWMOutputs; i++) {
+    HALSIM_ResetDigitalPWMData(i);
+  }
+
+  for (int32_t i = 0; i < hal::kNumDigitalChannels; i++) {
+    HALSIM_ResetDIOData(i);
+  }
+
+  HALSIM_ResetDriverStationData();
+
+  for (int32_t i = 0; i < hal::kNumDutyCycles; i++) {
+    HALSIM_ResetDutyCycleData(i);
+  }
+
+  for (int32_t i = 0; i < hal::kNumEncoders; i++) {
+    HALSIM_ResetEncoderData(i);
+  }
+
+  for (int32_t i = 0; i < hal::kI2CPorts; i++) {
+    HALSIM_ResetI2CData(i);
+  }
+
+  for (int32_t i = 0; i < hal::kNumPDSimModules; i++) {
+    HALSIM_ResetPowerDistributionData(i);
+  }
+
+  for (int32_t i = 0; i < hal::kNumPWMChannels; i++) {
+    HALSIM_ResetPWMData(i);
+  }
+
+  for (int32_t i = 0; i < hal::kNumRelayHeaders; i++) {
+    HALSIM_ResetRelayData(i);
+  }
+
+  for (int32_t i = 0; i < hal::kNumREVPHModules; i++) {
+    HALSIM_ResetREVPHData(i);
+  }
+
+  HALSIM_ResetRoboRioData();
+  HALSIM_ResetSimDeviceData();
+
+  for (int32_t i = 0; i < hal::kSPIAccelerometers; i++) {
+    HALSIM_ResetSPIAccelerometerData(i);
+  }
+
+  for (int32_t i = 0; i < hal::kSPIPorts; i++) {
+    HALSIM_ResetSPIData(i);
+  }
+}
diff --git a/third_party/allwpilib/hal/src/main/native/sim/mockdata/RoboRioData.cpp b/third_party/allwpilib/hal/src/main/native/sim/mockdata/RoboRioData.cpp
index 6932620..b73b0d9 100644
--- a/third_party/allwpilib/hal/src/main/native/sim/mockdata/RoboRioData.cpp
+++ b/third_party/allwpilib/hal/src/main/native/sim/mockdata/RoboRioData.cpp
@@ -32,6 +32,79 @@
   userFaults5V.Reset(0);
   userFaults3V3.Reset(0);
   brownoutVoltage.Reset(6.75);
+  m_serialNumber = "";
+  m_comments = "";
+}
+
+int32_t RoboRioData::RegisterSerialNumberCallback(
+    HAL_RoboRioStringCallback callback, void* param, HAL_Bool initialNotify) {
+  std::scoped_lock lock(m_serialNumberMutex);
+  int32_t uid = m_serialNumberCallbacks.Register(callback, param);
+  if (initialNotify) {
+    callback(GetSerialNumberName(), param, m_serialNumber.c_str(),
+             m_serialNumber.size());
+  }
+  return uid;
+}
+
+void RoboRioData::CancelSerialNumberCallback(int32_t uid) {
+  m_serialNumberCallbacks.Cancel(uid);
+}
+
+size_t RoboRioData::GetSerialNumber(char* buffer, size_t size) {
+  std::scoped_lock lock(m_serialNumberMutex);
+  size_t copied = m_serialNumber.copy(buffer, size);
+  // Null terminate
+  if (copied == size) {
+    copied -= 1;
+  }
+  buffer[copied] = '\0';
+  return copied;
+}
+
+void RoboRioData::SetSerialNumber(const char* serialNumber, size_t size) {
+  // Limit serial number to 8 characters internally- serialnum environment
+  // variable is always 8 characters
+  if (size > 8) {
+    size = 8;
+  }
+  std::scoped_lock lock(m_serialNumberMutex);
+  m_serialNumber = std::string(serialNumber, size);
+  m_serialNumberCallbacks(m_serialNumber.c_str(), m_serialNumber.size());
+}
+
+int32_t RoboRioData::RegisterCommentsCallback(
+    HAL_RoboRioStringCallback callback, void* param, HAL_Bool initialNotify) {
+  std::scoped_lock lock(m_commentsMutex);
+  int32_t uid = m_commentsCallbacks.Register(callback, param);
+  if (initialNotify) {
+    callback(GetCommentsName(), param, m_comments.c_str(),
+             m_serialNumber.size());
+  }
+  return uid;
+}
+
+void RoboRioData::CancelCommentsCallback(int32_t uid) {
+  m_commentsCallbacks.Cancel(uid);
+}
+
+size_t RoboRioData::GetComments(char* buffer, size_t size) {
+  std::scoped_lock lock(m_commentsMutex);
+  size_t copied = m_comments.copy(buffer, size);
+  // Null terminate if there is room
+  if (copied < size) {
+    buffer[copied] = '\0';
+  }
+  return copied;
+}
+
+void RoboRioData::SetComments(const char* comments, size_t size) {
+  if (size > 64) {
+    size = 64;
+  }
+  std::scoped_lock lock(m_commentsMutex);
+  m_comments = std::string(comments, size);
+  m_commentsCallbacks(m_comments.c_str(), m_comments.size());
 }
 
 extern "C" {
@@ -60,6 +133,39 @@
 DEFINE_CAPI(int32_t, UserFaults3V3, userFaults3V3)
 DEFINE_CAPI(double, BrownoutVoltage, brownoutVoltage)
 
+int32_t HALSIM_RegisterRoboRioSerialNumberCallback(
+    HAL_RoboRioStringCallback callback, void* param, HAL_Bool initialNotify) {
+  return SimRoboRioData->RegisterSerialNumberCallback(callback, param,
+                                                      initialNotify);
+}
+void HALSIM_CancelRoboRioSerialNumberCallback(int32_t uid) {
+  return SimRoboRioData->CancelSerialNumberCallback(uid);
+}
+size_t HALSIM_GetRoboRioSerialNumber(char* buffer, size_t size) {
+  return SimRoboRioData->GetSerialNumber(buffer, size);
+}
+void HALSIM_SetRoboRioSerialNumber(const char* serialNumber, size_t size) {
+  SimRoboRioData->SetSerialNumber(serialNumber, size);
+}
+
+int32_t HALSIM_RegisterRoboRioCommentsCallback(
+    HAL_RoboRioStringCallback callback, void* param, HAL_Bool initialNotify) {
+  return SimRoboRioData->RegisterCommentsCallback(callback, param,
+                                                  initialNotify);
+}
+void HALSIM_CancelRoboRioCommentsCallback(int32_t uid) {
+  SimRoboRioData->CancelCommentsCallback(uid);
+}
+size_t HALSIM_GetRoboRioComments(char* buffer, size_t size) {
+  return SimRoboRioData->GetComments(buffer, size);
+}
+void HALSIM_SetRoboRioComments(const char* comments, size_t size) {
+  SimRoboRioData->SetComments(comments, size);
+}
+
+void HALSIM_RegisterRoboRioAllCallbacks(HAL_NotifyCallback callback,
+                                        void* param, HAL_Bool initialNotify);
+
 #define REGISTER(NAME) \
   SimRoboRioData->NAME.RegisterCallback(callback, param, initialNotify)
 
diff --git a/third_party/allwpilib/hal/src/main/native/sim/mockdata/RoboRioDataInternal.h b/third_party/allwpilib/hal/src/main/native/sim/mockdata/RoboRioDataInternal.h
index 99e61ea..c3ff17a 100644
--- a/third_party/allwpilib/hal/src/main/native/sim/mockdata/RoboRioDataInternal.h
+++ b/third_party/allwpilib/hal/src/main/native/sim/mockdata/RoboRioDataInternal.h
@@ -4,6 +4,11 @@
 
 #pragma once
 
+#include <cstddef>
+#include <string>
+
+#include <wpi/spinlock.h>
+
 #include "hal/simulation/RoboRioData.h"
 #include "hal/simulation/SimDataValue.h"
 
@@ -26,6 +31,9 @@
   HAL_SIMDATAVALUE_DEFINE_NAME(UserFaults3V3)
   HAL_SIMDATAVALUE_DEFINE_NAME(BrownoutVoltage)
 
+  HAL_SIMCALLBACKREGISTRY_DEFINE_NAME(SerialNumber)
+  HAL_SIMCALLBACKREGISTRY_DEFINE_NAME(Comments);
+
  public:
   SimDataValue<HAL_Bool, HAL_MakeBoolean, GetFPGAButtonName> fpgaButton{false};
   SimDataValue<double, HAL_MakeDouble, GetVInVoltageName> vInVoltage{12.0};
@@ -50,7 +58,32 @@
   SimDataValue<double, HAL_MakeDouble, GetBrownoutVoltageName> brownoutVoltage{
       6.75};
 
+  int32_t RegisterSerialNumberCallback(HAL_RoboRioStringCallback callback,
+                                       void* param, HAL_Bool initialNotify);
+  void CancelSerialNumberCallback(int32_t uid);
+  size_t GetSerialNumber(char* buffer, size_t size);
+  void SetSerialNumber(const char* serialNumber, size_t size);
+
+  int32_t RegisterCommentsCallback(HAL_RoboRioStringCallback callback,
+                                   void* param, HAL_Bool initialNotify);
+  void CancelCommentsCallback(int32_t uid);
+  size_t GetComments(char* buffer, size_t size);
+  void SetComments(const char* comments, size_t size);
+
   virtual void ResetData();
+
+ private:
+  wpi::spinlock m_serialNumberMutex;
+  std::string m_serialNumber;
+
+  wpi::spinlock m_commentsMutex;
+  std::string m_comments;
+
+  SimCallbackRegistry<HAL_RoboRioStringCallback, GetSerialNumberName>
+      m_serialNumberCallbacks;
+
+  SimCallbackRegistry<HAL_RoboRioStringCallback, GetCommentsName>
+      m_commentsCallbacks;
 };
 extern RoboRioData* SimRoboRioData;
 }  // namespace hal
diff --git a/third_party/allwpilib/hal/src/test/java/edu/wpi/first/hal/JNITest.java b/third_party/allwpilib/hal/src/test/java/edu/wpi/first/hal/JNITest.java
new file mode 100644
index 0000000..49e201d
--- /dev/null
+++ b/third_party/allwpilib/hal/src/test/java/edu/wpi/first/hal/JNITest.java
@@ -0,0 +1,15 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.hal;
+
+import org.junit.jupiter.api.Test;
+
+public class JNITest {
+  @Test
+  void jniLinkTest() {
+    // Test to verify that the JNI test link works correctly.
+    HAL.initialize(500, 0);
+  }
+}
diff --git a/third_party/allwpilib/hal/src/test/native/cpp/mockdata/DriverStationDataTest.cpp b/third_party/allwpilib/hal/src/test/native/cpp/mockdata/DriverStationDataTest.cpp
index 4925e16..59658cb 100644
--- a/third_party/allwpilib/hal/src/test/native/cpp/mockdata/DriverStationDataTest.cpp
+++ b/third_party/allwpilib/hal/src/test/native/cpp/mockdata/DriverStationDataTest.cpp
@@ -61,6 +61,9 @@
   HALSIM_SetJoystickPOVs(joystickUnderTest, &set_povs);
   HALSIM_SetJoystickButtons(joystickUnderTest, &set_buttons);
 
+  HALSIM_NotifyDriverStationNewData();
+  HAL_RefreshDSData();
+
   // Check the set values
   HAL_GetJoystickAxes(joystickUnderTest, &axes);
   HAL_GetJoystickPOVs(joystickUnderTest, &povs);
@@ -89,6 +92,9 @@
 
   // Reset
   HALSIM_ResetDriverStationData();
+  HALSIM_NotifyDriverStationNewData();
+  HAL_RefreshDSData();
+
   for (int joystickNum = 0; joystickNum < 6; ++joystickNum) {
     HAL_GetJoystickAxes(joystickNum, &axes);
     HAL_GetJoystickPOVs(joystickNum, &povs);
diff --git a/third_party/allwpilib/imgui/.styleguide b/third_party/allwpilib/imgui/.styleguide
new file mode 100644
index 0000000..5e97ca4
--- /dev/null
+++ b/third_party/allwpilib/imgui/.styleguide
@@ -0,0 +1,20 @@
+cppHeaderFileInclude {
+  \.h$
+  \.inc$
+}
+
+cppSrcFileInclude {
+  \.cpp$
+}
+
+modifiableFileExclude {
+}
+
+generatedFileExclude {
+}
+
+repoRootNameOverride {
+}
+
+includeOtherLibs {
+}
diff --git a/third_party/allwpilib/imgui/CMakeLists.txt b/third_party/allwpilib/imgui/CMakeLists.txt
index 9f2ac74..17f6f64 100644
--- a/third_party/allwpilib/imgui/CMakeLists.txt
+++ b/third_party/allwpilib/imgui/CMakeLists.txt
@@ -1,74 +1,106 @@
-# Download and unpack imgui at configure time
-configure_file(CMakeLists.txt.in imgui-download/CMakeLists.txt)
+INCLUDE(FetchContent)
 
-execute_process(COMMAND ${CMAKE_COMMAND} -G "${CMAKE_GENERATOR}" .
-  RESULT_VARIABLE result
-  WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/imgui-download )
-if(result)
-  message(FATAL_ERROR "CMake step for imgui failed: ${result}")
-endif()
-execute_process(COMMAND ${CMAKE_COMMAND} --build .
-  RESULT_VARIABLE result
-  WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/imgui-download )
-if(result)
-  message(FATAL_ERROR "Build step for imgui failed: ${result}")
+FetchContent_Declare(
+    glfw3
+    GIT_REPOSITORY  https://github.com/glfw/glfw.git
+    GIT_TAG         6b57e08bb0078c9834889eab871bac2368198c15
+)
+FetchContent_Declare(
+    gl3w
+    GIT_REPOSITORY  https://github.com/skaslev/gl3w
+    GIT_TAG         5f8d7fd191ba22ff2b60c1106d7135bb9a335533
+)
+FetchContent_Declare(
+    imgui
+    GIT_REPOSITORY  https://github.com/ocornut/imgui.git
+    GIT_TAG         3ea0fad204e994d669f79ed29dcaf61cd5cb571d
+)
+FetchContent_Declare(
+    implot
+    GIT_REPOSITORY  https://github.com/epezent/implot.git
+    GIT_TAG         e80e42e8b4136ddb84ccfe04fa28d0c745828952
+)
+FetchContent_Declare(
+    fonts
+    URL         https://github.com/wpilibsuite/thirdparty-fonts/releases/download/v0.2/fonts.zip
+    URL_HASH    SHA256=cedf365657fab0770e11f72d49e4f0f889f564d2e635a4d214029d0ab6bcd324
+)
+FetchContent_Declare(
+    stb
+    GIT_REPOSITORY  https://github.com/nothings/stb.git
+    GIT_TAG         c9064e317699d2e495f36ba4f9ac037e88ee371a
+)
+
+FetchContent_MakeAvailable(
+    imgui
+    implot
+    fonts
+    stb
+)
+
+# Add glfw directly to our build.
+FetchContent_GetProperties(glfw3)
+if(NOT glfw3_POPULATED)
+    FetchContent_Populate(glfw3)
+    set(SAVE_BUILD_SHARED_LIBS ${BUILD_SHARED_LIBS})
+    set(BUILD_SHARED_LIBS OFF)
+    set(GLFW_INSTALL OFF)
+    add_subdirectory(${glfw3_SOURCE_DIR} ${glfw3_BINARY_DIR} EXCLUDE_FROM_ALL)
+    set_property(TARGET glfw PROPERTY POSITION_INDEPENDENT_CODE ON)
+    set(BUILD_SHARED_LIBS ${SAVE_BUILD_SHARED_LIBS})
 endif()
 
-# Build font
-add_executable(imgui_font_bin2c ${CMAKE_CURRENT_BINARY_DIR}/imgui-src/misc/fonts/binary_to_compressed_c.cpp)
-add_custom_command(OUTPUT ${CMAKE_CURRENT_BINARY_DIR}/ProggyDotted.inc
-  COMMAND imgui_font_bin2c
-  ARGS "${CMAKE_CURRENT_BINARY_DIR}/proggyfonts-src/ProggyDotted/ProggyDotted Regular.ttf" ProggyDotted > ${CMAKE_CURRENT_BINARY_DIR}/ProggyDotted.inc
-  WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}
-  MAIN_DEPENDENCY "${CMAKE_CURRENT_BINARY_DIR}/proggyfonts-src/ProggyDotted/ProggyDotted Regular.ttf"
-  VERBATIM
-)
-file(GENERATE OUTPUT ${CMAKE_CURRENT_BINARY_DIR}/imgui_ProggyDotted.cpp
-    CONTENT "#include \"imgui_ProggyDotted.h\"\n#include \"ProggyDotted.inc\"\nImFont* ImGui::AddFontProggyDotted(ImGuiIO& io, float size_pixels, const ImFontConfig* font_cfg, const ImWchar* glyph_ranges) {\n  return io.Fonts->AddFontFromMemoryCompressedTTF(ProggyDotted_compressed_data, ProggyDotted_compressed_size, size_pixels, font_cfg, glyph_ranges);\n}\n"
-)
-file(GENERATE OUTPUT ${CMAKE_CURRENT_BINARY_DIR}/imgui_ProggyDotted.h
-    CONTENT "#pragma once\n#include \"imgui.h\"\nnamespace ImGui {\nImFont* AddFontProggyDotted(ImGuiIO& io, float size_pixels, const ImFontConfig* font_cfg = nullptr, const ImWchar* glyph_ranges = nullptr);\n}\n"
-)
-set_source_files_properties(${CMAKE_CURRENT_BINARY_DIR}/imgui_ProggyDotted.cpp
-    PROPERTIES OBJECT_DEPENDS ${CMAKE_CURRENT_BINARY_DIR}/ProggyDotted.inc)
-
-# stb_image
-file(GENERATE OUTPUT ${CMAKE_CURRENT_BINARY_DIR}/stb_image.cpp
-    CONTENT "#define STBI_WINDOWS_UTF8\n#define STB_IMAGE_IMPLEMENTATION\n#include \"stb_image.h\"\n"
-)
+# Don't use gl3w CMakeLists.txt due to https://github.com/skaslev/gl3w/issues/66
+FetchContent_GetProperties(gl3w)
+if(NOT gl3w_POPULATED)
+    FetchContent_Populate(gl3w)
+endif()
+if(NOT EXISTS "${gl3w_BINARY_DIR}/src/gl3w.c")
+    find_package(Python COMPONENTS Interpreter Development REQUIRED)
+    execute_process(
+        COMMAND "${Python_EXECUTABLE}" ${gl3w_SOURCE_DIR}/gl3w_gen.py "--root=${gl3w_BINARY_DIR}"
+        WORKING_DIRECTORY ${gl3w_BINARY_DIR}
+    )
+endif()
 
 # Add imgui directly to our build.
-set(SAVE_BUILD_SHARED_LIBS ${BUILD_SHARED_LIBS})
-set(BUILD_SHARED_LIBS OFF)
-set(GLFW_INSTALL OFF)
-add_subdirectory(${CMAKE_CURRENT_BINARY_DIR}/glfw-src
-                 ${CMAKE_CURRENT_BINARY_DIR}/glfw-build
-                 EXCLUDE_FROM_ALL)
-set_property(TARGET glfw PROPERTY POSITION_INDEPENDENT_CODE ON)
-set(BUILD_SHARED_LIBS ${SAVE_BUILD_SHARED_LIBS})
-add_subdirectory(${CMAKE_CURRENT_BINARY_DIR}/gl3w-src
-                 ${CMAKE_CURRENT_BINARY_DIR}/gl3w-build
-                 EXCLUDE_FROM_ALL)
-
-set(imgui_srcdir ${CMAKE_CURRENT_BINARY_DIR}/imgui-src)
-file(GLOB imgui_sources ${imgui_srcdir}/*.cpp ${imgui_srcdir}/misc/cpp/*.cpp)
-set(implot_srcdir ${CMAKE_CURRENT_BINARY_DIR}/implot-src)
-file(GLOB implot_sources ${implot_srcdir}/*.cpp)
-add_library(imgui STATIC ${imgui_sources} ${implot_sources} ${imgui_srcdir}/backends/imgui_impl_glfw.cpp ${imgui_srcdir}/backends/imgui_impl_opengl3.cpp ${CMAKE_CURRENT_BINARY_DIR}/imgui_ProggyDotted.cpp ${CMAKE_CURRENT_BINARY_DIR}/stb_image.cpp)
+file(GLOB imgui_sources ${imgui_SOURCE_DIR}/*.cpp ${imgui_SOURCE_DIR}/misc/cpp/*.cpp)
+file(GLOB implot_sources ${implot_SOURCE_DIR}/*.cpp)
+file(GLOB fonts_sources ${fonts_SOURCE_DIR}/src/*.cpp)
+add_library(imgui STATIC
+    ${imgui_sources}
+    ${implot_sources}
+    ${imgui_SOURCE_DIR}/backends/imgui_impl_glfw.cpp
+    ${imgui_SOURCE_DIR}/backends/imgui_impl_opengl3.cpp
+    ${gl3w_BINARY_DIR}/src/gl3w.c
+    ${fonts_sources}
+    src/stb_image.cpp
+)
 target_compile_definitions(imgui PUBLIC IMGUI_IMPL_OPENGL_LOADER_GL3W)
 if (MSVC)
-    target_sources(imgui PRIVATE ${imgui_srcdir}/backends/imgui_impl_dx11.cpp)
+    target_sources(imgui PRIVATE ${imgui_SOURCE_DIR}/backends/imgui_impl_dx11.cpp)
 else()
     if (APPLE)
         target_compile_options(imgui PRIVATE -fobjc-arc)
         set_target_properties(imgui PROPERTIES LINK_FLAGS "-framework Metal -framework QuartzCore")
-        target_sources(imgui PRIVATE ${imgui_srcdir}/backends/imgui_impl_metal.mm)
+        target_sources(imgui PRIVATE ${imgui_SOURCE_DIR}/backends/imgui_impl_metal.mm)
     else()
-        #target_sources(imgui PRIVATE ${imgui_srcdir}/backends/imgui_impl_opengl3.cpp)
+        #target_sources(imgui PRIVATE ${imgui_SOURCE_DIR}/backends/imgui_impl_opengl3.cpp)
     endif()
 endif()
-target_link_libraries(imgui PUBLIC gl3w glfw)
-target_include_directories(imgui PUBLIC "$<BUILD_INTERFACE:${imgui_srcdir}>" "$<BUILD_INTERFACE:${imgui_srcdir}/misc/cpp>" "$<BUILD_INTERFACE:${implot_srcdir}>" "$<BUILD_INTERFACE:${imgui_srcdir}/backends>" "$<BUILD_INTERFACE:${CMAKE_CURRENT_BINARY_DIR}>" "$<BUILD_INTERFACE:${CMAKE_CURRENT_BINARY_DIR}/stb-src>")
+target_link_libraries(imgui PUBLIC glfw)
+target_include_directories(imgui
+    PUBLIC
+    "$<BUILD_INTERFACE:${imgui_SOURCE_DIR}>"
+    "$<BUILD_INTERFACE:${imgui_SOURCE_DIR}/misc/cpp>"
+    "$<BUILD_INTERFACE:${implot_SOURCE_DIR}>"
+    "$<BUILD_INTERFACE:${imgui_SOURCE_DIR}/backends>"
+    "$<BUILD_INTERFACE:${gl3w_BINARY_DIR}/include>"
+    "$<BUILD_INTERFACE:${fonts_SOURCE_DIR}/include>"
+    "$<BUILD_INTERFACE:${stb_SOURCE_DIR}>"
+    PRIVATE
+    "$<BUILD_INTERFACE:${CMAKE_CURRENT_BINARY_DIR}>"
+)
 
 set_property(TARGET imgui PROPERTY POSITION_INDEPENDENT_CODE ON)
-target_compile_features(imgui PUBLIC cxx_std_17)
+target_compile_features(imgui PUBLIC cxx_std_20)
diff --git a/third_party/allwpilib/imgui/CMakeLists.txt.in b/third_party/allwpilib/imgui/CMakeLists.txt.in
deleted file mode 100644
index 1e3cde4..0000000
--- a/third_party/allwpilib/imgui/CMakeLists.txt.in
+++ /dev/null
@@ -1,63 +0,0 @@
-cmake_minimum_required(VERSION 2.8.2)
-
-project(imgui-download NONE)
-
-include(ExternalProject)
-ExternalProject_Add(glfw3
-  GIT_REPOSITORY    https://github.com/glfw/glfw.git
-  GIT_TAG           3.3.6
-  SOURCE_DIR        "${CMAKE_CURRENT_BINARY_DIR}/glfw-src"
-  BINARY_DIR        "${CMAKE_CURRENT_BINARY_DIR}/glfw-build"
-  CONFIGURE_COMMAND ""
-  BUILD_COMMAND     ""
-  INSTALL_COMMAND   ""
-  TEST_COMMAND      ""
-)
-ExternalProject_Add(gl3w
-  GIT_REPOSITORY    https://github.com/skaslev/gl3w
-  GIT_TAG           3755745085ac2e865fd22270cfe9169c26640f70
-  SOURCE_DIR        "${CMAKE_CURRENT_BINARY_DIR}/gl3w-src"
-  BINARY_DIR        "${CMAKE_CURRENT_BINARY_DIR}/gl3w-build"
-  INSTALL_COMMAND   ""
-  TEST_COMMAND      ""
-)
-ExternalProject_Add(imgui
-  GIT_REPOSITORY    https://github.com/ocornut/imgui.git
-  GIT_TAG           v1.86
-  SOURCE_DIR        "${CMAKE_CURRENT_BINARY_DIR}/imgui-src"
-  BINARY_DIR        "${CMAKE_CURRENT_BINARY_DIR}/imgui-build"
-  CONFIGURE_COMMAND ""
-  BUILD_COMMAND     ""
-  INSTALL_COMMAND   ""
-  TEST_COMMAND      ""
-)
-ExternalProject_Add(implot
-  GIT_REPOSITORY    https://github.com/epezent/implot.git
-  GIT_TAG           4fcc6e01aca406ef17d5a2dabdcbc9e1bd962c0d
-  SOURCE_DIR        "${CMAKE_CURRENT_BINARY_DIR}/implot-src"
-  BINARY_DIR        "${CMAKE_CURRENT_BINARY_DIR}/implot-build"
-  CONFIGURE_COMMAND ""
-  BUILD_COMMAND     ""
-  INSTALL_COMMAND   ""
-  TEST_COMMAND      ""
-)
-ExternalProject_Add(proggyfonts
-  GIT_REPOSITORY    https://github.com/bluescan/proggyfonts.git
-  GIT_TAG           v1.1.5
-  SOURCE_DIR        "${CMAKE_CURRENT_BINARY_DIR}/proggyfonts-src"
-  BINARY_DIR        "${CMAKE_CURRENT_BINARY_DIR}/proggyfonts-build"
-  CONFIGURE_COMMAND ""
-  BUILD_COMMAND     ""
-  INSTALL_COMMAND   ""
-  TEST_COMMAND      ""
-)
-ExternalProject_Add(stb
-  GIT_REPOSITORY    https://github.com/nothings/stb.git
-  GIT_TAG           c9064e317699d2e495f36ba4f9ac037e88ee371a
-  SOURCE_DIR        "${CMAKE_CURRENT_BINARY_DIR}/stb-src"
-  BINARY_DIR        "${CMAKE_CURRENT_BINARY_DIR}/stb-build"
-  CONFIGURE_COMMAND ""
-  BUILD_COMMAND     ""
-  INSTALL_COMMAND   ""
-  TEST_COMMAND      ""
-)
diff --git a/third_party/allwpilib/imgui/src/stb_image.cpp b/third_party/allwpilib/imgui/src/stb_image.cpp
new file mode 100644
index 0000000..92a60b1
--- /dev/null
+++ b/third_party/allwpilib/imgui/src/stb_image.cpp
@@ -0,0 +1,7 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#define STBI_WINDOWS_UTF8
+#define STB_IMAGE_IMPLEMENTATION
+#include "stb_image.h"
diff --git a/third_party/allwpilib/msvcruntime/build.gradle b/third_party/allwpilib/msvcruntime/build.gradle
index 80dafa7..99e14ed 100644
--- a/third_party/allwpilib/msvcruntime/build.gradle
+++ b/third_party/allwpilib/msvcruntime/build.gradle
@@ -16,33 +16,31 @@
 
     def vsLocator = gradle.services.get(VisualStudioLocator)
 
-    def vsLocation = vsLocator.locateAllComponents().first()
+    def vsLocationResult = vsLocator.locateComponent(null)
+
+    if (!vsLocationResult.available) {
+        return
+    }
+
+    def vsLocation = vsLocationResult.component
 
     def visualCppVersion = vsLocation.visualCpp.version
 
     def vsDirectory = vsLocation.visualStudioDir
 
-    def runtimeLocation = file("$vsDirectory\\VC\\Redist\\MSVC")
+    def defaultRedistFile = file("$vsDirectory\\VC\\Auxiliary\\Build\\Microsoft.VCRedistVersion.default.txt")
 
-    def runtimeVerNumber = null
-
-    runtimeLocation.eachFile {
-        def verNumber =  VersionNumber.parse(it.name)
-        if (verNumber.major == visualCppVersion.major && verNumber.minor == visualCppVersion.minor) {
-            runtimeVerNumber = verNumber
-        }
+    if (!defaultRedistFile.exists()) {
+        logger.warn("Version file for VS Compiler not found")
+        logger.warn("Expected at $defaultRedistFile")
+        return
     }
 
-    if (runtimeVerNumber != null) {
-        runtimeLocation = file("$runtimeLocation\\$runtimeVerNumber")
+    def expectedVersion = VersionNumber.parse(defaultRedistFile.text.trim())
 
-        def x86Folder = null
+    def runtimeLocation = file("$vsDirectory\\VC\\Redist\\MSVC\\$expectedVersion")
 
-        file("$runtimeLocation\\x86").eachFile {
-            if (it.name.endsWith('.CRT')) {
-                x86Folder = it
-            }
-        }
+    if (runtimeLocation.exists()) {
 
         def x64Folder = null
 
@@ -52,14 +50,6 @@
             }
         }
 
-        def x86ZipTask = tasks.create('x86RuntimeZip', Zip) {
-            destinationDirectory = outputsFolder
-            archiveBaseName = zipBaseName
-            classifier = 'x86'
-
-            from x86Folder
-        }
-
         def x64ZipTask = tasks.create('x64RuntimeZip', Zip) {
             destinationDirectory = outputsFolder
             archiveBaseName = zipBaseName
@@ -68,17 +58,14 @@
             from x64Folder
         }
 
-        addTaskToCopyAllOutputs(x86ZipTask)
         addTaskToCopyAllOutputs(x64ZipTask)
 
-        build.dependsOn x86ZipTask
         build.dependsOn x64ZipTask
 
         publishing {
             publications {
 
                 runtime(MavenPublication) {
-                    artifact x86ZipTask
                     artifact x64ZipTask
 
                     artifactId = "${baseArtifactId}"
@@ -87,5 +74,7 @@
                 }
             }
         }
+    } else if (project.hasProperty('buildServer')) {
+        throw new GradleException("Must find a runtime in CI. Expected at $runtimeLocation")
     }
 }
diff --git a/third_party/allwpilib/myRobot/build.gradle b/third_party/allwpilib/myRobot/build.gradle
index d531161..d2e98e6 100644
--- a/third_party/allwpilib/myRobot/build.gradle
+++ b/third_party/allwpilib/myRobot/build.gradle
@@ -36,7 +36,9 @@
 apply plugin: 'com.github.johnrengelman.shadow'
 
 repositories {
-    mavenCentral()
+    maven {
+        url = 'https://frcmaven.wpi.edu/artifactory/ex-mvn'
+    }
 }
 
 dependencies {
@@ -44,19 +46,23 @@
     implementation project(':wpimath')
     implementation project(':hal')
     implementation project(':wpiutil')
+    implementation project(':wpinet')
     implementation project(':ntcore')
     implementation project(':cscore')
     implementation project(':cameraserver')
-    implementation project(':wpilibOldCommands')
     implementation project(':wpilibNewCommands')
 }
 
+tasks.withType(com.github.spotbugs.snom.SpotBugsTask).configureEach {
+    onlyIf { false }
+}
+
 def simProjects = ['halsim_gui']
 
 deploy {
     targets {
         roborio(RemoteTarget) {
-            directory = '/home/admin'
+            directory = '/home/lvuser'
             maxChannels = 4
             locations {
                 ssh(SshDeployLocation) {
@@ -76,7 +82,8 @@
             artifacts {
                 all {
                     predeploy << { ctx ->
-                        ctx.execute('/usr/local/frc/bin/frcKillRobot.sh -t')
+                        ctx.execute('. /etc/profile.d/natinst-path.sh; /usr/local/frc/bin/frcKillRobot.sh -t 2> /dev/null')
+                        ctx.execute("sed -i -e 's/\"exec /\"/' /usr/local/frc/bin/frcRunRobot.sh")
                     }
                     postdeploy << { ctx ->
                         ctx.execute("sync")
@@ -90,6 +97,9 @@
                     excludes.add('**/*.so.debug')
                     excludes.add('**/*.so.*.debug')
                     postdeploy << { ctx ->
+                        ctx.execute("echo '/home/lvuser/myRobotCpp' > /home/lvuser/robotCommand")
+                        ctx.execute("chmod +x /home/lvuser/robotCommand; chown lvuser /home/lvuser/robotCommand")
+                        ctx.execute("setcap cap_sys_nice+eip \"/home/lvuser/myRobotCpp\"")
                         ctx.execute('chmod +x myRobotCpp')
                     }
                 }
@@ -97,18 +107,28 @@
                 myRobotCppStatic(NativeExecutableArtifact) {
                     libraryDirectory = '/usr/local/frc/third-party/lib'
                     postdeploy << { ctx ->
+                        ctx.execute("echo '/home/lvuser/myRobotCppStatic' > /home/lvuser/robotCommand")
+                        ctx.execute("chmod +x /home/lvuser/robotCommand; chown lvuser /home/lvuser/robotCommand")
+                        ctx.execute("setcap cap_sys_nice+eip \"/home/lvuser/myRobotCppStatic\"")
                         ctx.execute('chmod +x myRobotCppStatic')
                     }
                 }
 
+                myRobotCppJava(NativeExecutableArtifact) {
+                    libraryDirectory = '/usr/local/frc/third-party/lib'
+                    def excludes = getLibraryFilter().getExcludes()
+                    excludes.add('**/*.so.debug')
+                    excludes.add('**/*.so.*.debug')
+                }
+
                 jre(WPIJREArtifact) {
                 }
 
                 myRobotJava(JavaArtifact) {
                     jarTask = shadowJar
                     postdeploy << { ctx ->
-                        ctx.execute("echo '/usr/local/frc/JRE/bin/java -XX:+UseConcMarkSweepGC -Djava.library.path=/usr/local/frc/third-party/lib -Djava.lang.invoke.stringConcat=BC_SB -jar /home/admin/myRobot-all.jar' > /home/admin/myRobotJavaRun")
-                        ctx.execute("chmod +x /home/admin/myRobotJavaRun; chown lvuser /home/admin/myRobotJavaRun")
+                        ctx.execute("echo '/usr/local/frc/JRE/bin/java -XX:+UseG1GC -XX:MaxGCPauseMillis=1 -XX:GCTimeRatio=1 -Djava.library.path=/usr/local/frc/third-party/lib -Djava.lang.invoke.stringConcat=BC_SB -jar /home/lvuser/myRobot-all.jar' > /home/lvuser/robotCommand")
+                        ctx.execute("chmod +x /home/lvuser/robotCommand; chown lvuser /home/lvuser/robotCommand")
                     }
                 }
             }
@@ -120,7 +140,7 @@
     try {
         dependsOn tasks.named('deployjreroborio')
         dependsOn tasks.named('deploymyRobotJavaroborio')
-        dependsOn tasks.named('deploymyRobotCpproborio') // Deploying shared C++ is how to get the Java shared libraries.
+        dependsOn tasks.named('deploymyRobotCppJavaroborio') // Deploying shared C++ is how to get the Java shared libraries.
     } catch (ignored) {
     }
 }
@@ -159,21 +179,23 @@
                 if (binary.targetPlatform.name == nativeUtils.wpi.platforms.roborio) {
                     if (binary.buildType.name == 'debug') {
                         deploy.targets.roborio.artifacts.myRobotCpp.binary = binary
+                        deploy.targets.roborio.artifacts.myRobotCppJava.binary = binary
                     }
                 }
-                lib project: ':wpilibOldCommands', library: 'wpilibOldCommands', linkage: 'shared'
                 lib project: ':wpilibNewCommands', library: 'wpilibNewCommands', linkage: 'shared'
                 lib project: ':wpilibc', library: 'wpilibc', linkage: 'shared'
                 lib project: ':wpimath', library: 'wpimath', linkage: 'shared'
                 lib project: ':cameraserver', library: 'cameraserver', linkage: 'shared'
-                lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
+                project(':ntcore').addNtcoreDependency(binary, 'shared')
+                project(':ntcore').addNtcoreJniDependency(binary)
                 lib project: ':cscore', library: 'cscore', linkage: 'shared'
-                lib project: ':ntcore', library: 'ntcoreJNIShared', linkage: 'shared'
                 lib project: ':cscore', library: 'cscoreJNIShared', linkage: 'shared'
                 lib project: ':wpimath', library: 'wpimathJNIShared', linkage: 'shared'
+                lib project: ':wpinet', library: 'wpinetJNIShared', linkage: 'shared'
                 lib project: ':wpiutil', library: 'wpiutilJNIShared', linkage: 'shared'
                 project(':hal').addHalDependency(binary, 'shared')
                 project(':hal').addHalJniDependency(binary)
+                lib project: ':wpinet', library: 'wpinet', linkage: 'shared'
                 lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
                 if (binary.targetPlatform.name == nativeUtils.wpi.platforms.roborio) {
                     nativeUtils.useRequiredLibrary(binary, 'ni_link_libraries', 'ni_runtime_libraries')
@@ -208,14 +230,14 @@
                         deploy.targets.roborio.artifacts.myRobotCppStatic.binary = binary
                     }
                 }
-                lib project: ':wpilibOldCommands', library: 'wpilibOldCommands', linkage: 'static'
                 lib project: ':wpilibNewCommands', library: 'wpilibNewCommands', linkage: 'static'
                 lib project: ':wpilibc', library: 'wpilibc', linkage: 'static'
                 lib project: ':wpimath', library: 'wpimath', linkage: 'static'
                 lib project: ':cameraserver', library: 'cameraserver', linkage: 'static'
-                lib project: ':ntcore', library: 'ntcore', linkage: 'static'
+                project(':ntcore').addNtcoreDependency(binary, 'static')
                 lib project: ':cscore', library: 'cscore', linkage: 'static'
                 project(':hal').addHalDependency(binary, 'static')
+                lib project: ':wpinet', library: 'wpinet', linkage: 'static'
                 lib project: ':wpiutil', library: 'wpiutil', linkage: 'static'
                 if (binary.targetPlatform.name == nativeUtils.wpi.platforms.roborio) {
                     nativeUtils.useRequiredLibrary(binary, 'ni_link_libraries', 'ni_runtime_libraries')
diff --git a/third_party/allwpilib/myRobot/src/main/java/frc/robot/MyRobot.java b/third_party/allwpilib/myRobot/src/main/java/frc/robot/MyRobot.java
index e62c345..a5f88bd 100644
--- a/third_party/allwpilib/myRobot/src/main/java/frc/robot/MyRobot.java
+++ b/third_party/allwpilib/myRobot/src/main/java/frc/robot/MyRobot.java
@@ -6,7 +6,6 @@
 
 import edu.wpi.first.wpilibj.TimedRobot;
 
-@SuppressWarnings("all")
 public class MyRobot extends TimedRobot {
   /**
    * This function is run when the robot is first started up and should be used for any
@@ -15,27 +14,27 @@
   @Override
   public void robotInit() {}
 
-  /** This function is run once each time the robot enters autonomous mode */
+  /** This function is run once each time the robot enters autonomous mode. */
   @Override
   public void autonomousInit() {}
 
-  /** This function is called periodically during autonomous */
+  /** This function is called periodically during autonomous. */
   @Override
   public void autonomousPeriodic() {}
 
-  /** This function is called once each time the robot enters tele-operated mode */
+  /** This function is called once each time the robot enters tele-operated mode. */
   @Override
   public void teleopInit() {}
 
-  /** This function is called periodically during operator control */
+  /** This function is called periodically during operator control. */
   @Override
   public void teleopPeriodic() {}
 
-  /** This function is called periodically during test mode */
+  /** This function is called periodically during test mode. */
   @Override
   public void testPeriodic() {}
 
-  /** This function is called periodically during all modes */
+  /** This function is called periodically during all modes. */
   @Override
   public void robotPeriodic() {}
 }
diff --git a/third_party/allwpilib/ntcore/.styleguide b/third_party/allwpilib/ntcore/.styleguide
index 8cf3a51..ef9cbb7 100644
--- a/third_party/allwpilib/ntcore/.styleguide
+++ b/third_party/allwpilib/ntcore/.styleguide
@@ -30,4 +30,5 @@
   ^fmt/
   ^support/
   ^wpi/
+  ^wpinet/
 }
diff --git a/third_party/allwpilib/ntcore/CMakeLists.txt b/third_party/allwpilib/ntcore/CMakeLists.txt
index 44992ef..cd4df28 100644
--- a/third_party/allwpilib/ntcore/CMakeLists.txt
+++ b/third_party/allwpilib/ntcore/CMakeLists.txt
@@ -3,23 +3,39 @@
 include(CompileWarnings)
 include(AddTest)
 
-file(GLOB
-    ntcore_native_src src/main/native/cpp/*.cpp
-    ntcore_native_src src/main/native/cpp/networktables/*.cpp
-    ntcore_native_src src/main/native/cpp/tables/*.cpp)
+execute_process(COMMAND python3 ${CMAKE_CURRENT_SOURCE_DIR}/generate_topics.py ${WPILIB_BINARY_DIR}/ntcore RESULT_VARIABLE generateResult)
+if(NOT (generateResult EQUAL "0"))
+  # Try python
+  execute_process(COMMAND python ${CMAKE_CURRENT_SOURCE_DIR}/generate_topics.py ${WPILIB_BINARY_DIR}/ntcore RESULT_VARIABLE generateResult)
+  if(NOT (generateResult EQUAL "0"))
+    message(FATAL_ERROR "python and python3 generate_topics.py failed")
+  endif()
+endif()
+
+file(GLOB ntcore_native_src
+    src/main/native/cpp/*.cpp
+    ${WPILIB_BINARY_DIR}/ntcore/generated/main/native/cpp/*.cpp
+    src/main/native/cpp/net/*.cpp
+    src/main/native/cpp/net3/*.cpp
+    src/main/native/cpp/networktables/*.cpp
+    src/main/native/cpp/tables/*.cpp)
 add_library(ntcore ${ntcore_native_src})
 set_target_properties(ntcore PROPERTIES DEBUG_POSTFIX "d")
-target_include_directories(ntcore PUBLIC
+target_include_directories(ntcore
+                PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/src/main/native/cpp
+                PUBLIC
                 $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/src/main/native/include>
+                $<BUILD_INTERFACE:${WPILIB_BINARY_DIR}/ntcore/generated/main/native/include>
                             $<INSTALL_INTERFACE:${include_dest}/ntcore>)
 wpilib_target_warnings(ntcore)
-target_compile_features(ntcore PUBLIC cxx_std_17)
-target_link_libraries(ntcore PUBLIC wpiutil)
+target_compile_features(ntcore PUBLIC cxx_std_20)
+target_link_libraries(ntcore PUBLIC wpinet wpiutil)
 
 set_property(TARGET ntcore PROPERTY FOLDER "libraries")
 
 install(TARGETS ntcore EXPORT ntcore DESTINATION "${main_lib_dest}")
 install(DIRECTORY src/main/native/include/ DESTINATION "${include_dest}/ntcore")
+install(DIRECTORY ${WPILIB_BINARY_DIR}/ntcore/generated/main/native/include/ DESTINATION "${include_dest}/ntcore")
 
 if (WITH_FLAT_INSTALL)
     set (ntcore_config_dir ${wpilib_dest})
@@ -38,10 +54,11 @@
     include(UseJava)
     set(CMAKE_JAVA_COMPILE_FLAGS "-encoding" "UTF8" "-Xlint:unchecked")
 
-    file(GLOB
-        ntcore_jni_src src/main/native/cpp/jni/NetworkTablesJNI.cpp)
+    file(GLOB ntcore_jni_src
+        src/main/native/cpp/jni/*.cpp
+        ${WPILIB_BINARY_DIR}/ntcore/generated/main/native/cpp/jni/*.cpp)
 
-    file(GLOB_RECURSE JAVA_SOURCES src/main/java/*.java)
+    file(GLOB_RECURSE JAVA_SOURCES src/main/java/*.java ${WPILIB_BINARY_DIR}/ntcore/generated/*.java)
     set(CMAKE_JNI_TARGET true)
 
     if(${CMAKE_VERSION} VERSION_LESS "3.11.0")
@@ -78,6 +95,9 @@
 
 endif()
 
+add_executable(ntcoredev src/dev/native/cpp/main.cpp)
+target_link_libraries(ntcoredev ntcore)
+
 if (WITH_TESTS)
     wpilib_add_test(ntcore src/test/native/cpp)
     target_include_directories(ntcore_test PRIVATE src/main/native/cpp)
diff --git a/third_party/allwpilib/ntcore/build.gradle b/third_party/allwpilib/ntcore/build.gradle
index 67674c6..c5464cc 100644
--- a/third_party/allwpilib/ntcore/build.gradle
+++ b/third_party/allwpilib/ntcore/build.gradle
@@ -1,29 +1,331 @@
+import groovy.json.JsonSlurper;
+import com.hubspot.jinjava.Jinjava;
+import com.hubspot.jinjava.JinjavaConfig;
+
+def ntcoreTypesInputFile = file("src/generate/types.json")
+def ntcoreJavaTypesInputDir = file("src/generate/java")
+def ntcoreJavaTypesOutputDir = file("$buildDir/generated/main/java/edu/wpi/first/networktables")
+
+task ntcoreGenerateJavaTypes() {
+    description = "Generates ntcore Java type classes"
+    group = "WPILib"
+
+    inputs.file ntcoreTypesInputFile
+    inputs.dir ntcoreJavaTypesInputDir
+    outputs.dir ntcoreJavaTypesOutputDir
+
+    doLast {
+        def jsonSlurper = new JsonSlurper()
+        def jsonTypes = jsonSlurper.parse(ntcoreTypesInputFile)
+
+        ntcoreJavaTypesOutputDir.deleteDir()
+        ntcoreJavaTypesOutputDir.mkdirs()
+
+        def config = new JinjavaConfig()
+        def jinjava = new Jinjava(config)
+
+        ntcoreJavaTypesInputDir.listFiles().each { File file ->
+            def template = file.text
+            def outfn = file.name.substring(0, file.name.length() - 6)
+            if (file.name.startsWith("NetworkTable") || file.name.startsWith("Generic")) {
+                def replacements = new HashMap<String,?>()
+                replacements.put("types", jsonTypes)
+                def output = jinjava.render(template, replacements)
+                new File(ntcoreJavaTypesOutputDir, outfn).write(output)
+            } else {
+                jsonTypes.each { Map<String,?> replacements ->
+                    def output = jinjava.render(template, replacements)
+                    def typename = replacements.get("TypeName")
+                    File outfile
+                    if (outfn == "Timestamped.java") {
+                        outfile = new File(ntcoreJavaTypesOutputDir, "Timestamped${typename}.java")
+                    } else {
+                        outfile = new File(ntcoreJavaTypesOutputDir, "${typename}${outfn}")
+                    }
+                    outfile.write(output)
+                }
+            }
+        }
+    }
+}
+
+def ntcoreCppTypesInputDir = file("src/generate/include/networktables")
+def ntcoreCppTypesOutputDir = file("$buildDir/generated/main/native/include/networktables")
+
+task ntcoreGenerateCppTypes() {
+    description = "Generates ntcore C++ type classes"
+    group = "WPILib"
+
+    inputs.file ntcoreTypesInputFile
+    inputs.dir ntcoreCppTypesInputDir
+    outputs.dir ntcoreCppTypesOutputDir
+
+    doLast {
+        def jsonSlurper = new JsonSlurper()
+        def jsonTypes = jsonSlurper.parse(ntcoreTypesInputFile)
+
+        ntcoreCppTypesOutputDir.deleteDir()
+        ntcoreCppTypesOutputDir.mkdirs()
+
+        def config = new JinjavaConfig()
+        def jinjava = new Jinjava(config)
+
+        ntcoreCppTypesInputDir.listFiles().each { File file ->
+            def template = file.text
+            def outfn = file.name.substring(0, file.name.length() - 6)
+            jsonTypes.each { Map<String,?> replacements ->
+                def output = jinjava.render(template, replacements)
+                def typename = replacements.get("TypeName")
+                def outfile = new File(ntcoreCppTypesOutputDir, "${typename}${outfn}")
+                outfile.write(output)
+            }
+        }
+    }
+}
+
+def ntcoreCppHandleSourceInputFile = file("src/generate/cpp/ntcore_cpp_types.cpp.jinja")
+def ntcoreCppHandleSourceOutputFile = file("$buildDir/generated/main/native/cpp/ntcore_cpp_types.cpp")
+
+task ntcoreGenerateCppHandleSource() {
+    description = "Generates ntcore C++ handle source"
+    group = "WPILib"
+
+    inputs.files([
+        ntcoreTypesInputFile,
+        ntcoreCppHandleSourceInputFile
+    ])
+    outputs.file ntcoreCppHandleSourceOutputFile
+
+    doLast {
+        def jsonSlurper = new JsonSlurper()
+        def jsonTypes = jsonSlurper.parse(ntcoreTypesInputFile)
+
+        ntcoreCppHandleSourceOutputFile.delete()
+
+        def config = new JinjavaConfig()
+        def jinjava = new Jinjava(config)
+
+        def template = ntcoreCppHandleSourceInputFile.text
+        def replacements = new HashMap<String,?>()
+        replacements.put("types", jsonTypes)
+        def output = jinjava.render(template, replacements)
+        ntcoreCppHandleSourceOutputFile.write(output)
+    }
+}
+
+def ntcoreCppHandleHeaderInputFile = file("src/generate/include/ntcore_cpp_types.h.jinja")
+def ntcoreCppHandleHeaderOutputFile = file("$buildDir/generated/main/native/include/ntcore_cpp_types.h")
+
+task ntcoreGenerateCppHandleHeader() {
+    description = "Generates ntcore C++ handle header"
+    group = "WPILib"
+
+    inputs.files([
+        ntcoreTypesInputFile,
+        ntcoreCppHandleHeaderInputFile
+    ])
+    outputs.file ntcoreCppHandleHeaderOutputFile
+
+    doLast {
+        def jsonSlurper = new JsonSlurper()
+        def jsonTypes = jsonSlurper.parse(ntcoreTypesInputFile)
+
+        ntcoreCppHandleHeaderOutputFile.delete()
+
+        def config = new JinjavaConfig()
+        def jinjava = new Jinjava(config)
+
+        def template = ntcoreCppHandleHeaderInputFile.text
+        def replacements = new HashMap<String,?>()
+        replacements.put("types", jsonTypes)
+        def output = jinjava.render(template, replacements)
+        ntcoreCppHandleHeaderOutputFile.write(output)
+    }
+}
+
+def ntcoreCHandleSourceInputFile = file("src/generate/cpp/ntcore_c_types.cpp.jinja")
+def ntcoreCHandleSourceOutputFile = file("$buildDir/generated/main/native/cpp/ntcore_c_types.cpp")
+
+task ntcoreGenerateCHandleSource() {
+    description = "Generates ntcore C handle source"
+    group = "WPILib"
+
+    inputs.files([
+        ntcoreTypesInputFile,
+        ntcoreCHandleSourceInputFile
+    ])
+    outputs.file ntcoreCHandleSourceOutputFile
+
+    doLast {
+        def jsonSlurper = new JsonSlurper()
+        def jsonTypes = jsonSlurper.parse(ntcoreTypesInputFile)
+
+        ntcoreCHandleSourceOutputFile.delete()
+
+        def config = new JinjavaConfig()
+        def jinjava = new Jinjava(config)
+
+        def template = ntcoreCHandleSourceInputFile.text
+        def replacements = new HashMap<String,?>()
+        replacements.put("types", jsonTypes)
+        def output = jinjava.render(template, replacements)
+        ntcoreCHandleSourceOutputFile.write(output)
+    }
+}
+
+def ntcoreCHandleHeaderInputFile = file("src/generate/include/ntcore_c_types.h.jinja")
+def ntcoreCHandleHeaderOutputFile = file("$buildDir/generated/main/native/include/ntcore_c_types.h")
+
+task ntcoreGenerateCHandleHeader() {
+    description = "Generates ntcore C handle header"
+    group = "WPILib"
+
+    inputs.files([
+        ntcoreTypesInputFile,
+        ntcoreCHandleHeaderInputFile
+    ])
+    outputs.file ntcoreCHandleHeaderOutputFile
+
+    doLast {
+        def jsonSlurper = new JsonSlurper()
+        def jsonTypes = jsonSlurper.parse(ntcoreTypesInputFile)
+
+        ntcoreCHandleHeaderOutputFile.delete()
+
+        def config = new JinjavaConfig()
+        def jinjava = new Jinjava(config)
+
+        def template = ntcoreCHandleHeaderInputFile.text
+        def replacements = new HashMap<String,?>()
+        replacements.put("types", jsonTypes)
+        def output = jinjava.render(template, replacements)
+        ntcoreCHandleHeaderOutputFile.write(output)
+    }
+}
+
+def ntcoreJniSourceInputFile = file("src/generate/cpp/jni/types_jni.cpp.jinja")
+def ntcoreJniSourceOutputFile = file("$buildDir/generated/main/native/cpp/jni/types_jni.cpp")
+
+task ntcoreGenerateJniSource() {
+    description = "Generates ntcore JNI types source"
+    group = "WPILib"
+
+    inputs.files([
+        ntcoreTypesInputFile,
+        ntcoreJniSourceInputFile
+    ])
+    outputs.file ntcoreJniSourceOutputFile
+
+    doLast {
+        def jsonSlurper = new JsonSlurper()
+        def jsonTypes = jsonSlurper.parse(ntcoreTypesInputFile)
+
+        ntcoreJniSourceOutputFile.delete()
+
+        def config = new JinjavaConfig()
+        def jinjava = new Jinjava(config)
+
+        def template = ntcoreJniSourceInputFile.text
+        def replacements = new HashMap<String,?>()
+        replacements.put("types", jsonTypes)
+        def output = jinjava.render(template, replacements)
+        ntcoreJniSourceOutputFile.write(output)
+    }
+}
+
 ext {
+    addNtcoreDependency = { binary, shared->
+        binary.tasks.withType(AbstractNativeSourceCompileTask) {
+            it.dependsOn ntcoreGenerateCppTypes
+            it.dependsOn ntcoreGenerateCppHandleHeader
+            it.dependsOn ntcoreGenerateCHandleHeader
+        }
+        binary.lib project: ':ntcore', library: 'ntcore', linkage: shared
+    }
+
+    addNtcoreJniDependency = { binary->
+        binary.tasks.withType(AbstractNativeSourceCompileTask) {
+            it.dependsOn ntcoreGenerateCppTypes
+            it.dependsOn ntcoreGenerateCppHandleHeader
+            it.dependsOn ntcoreGenerateCHandleHeader
+        }
+        binary.lib project: ':ntcore', library: 'ntcoreJNIShared', linkage: 'shared'
+    }
+
     nativeName = 'ntcore'
     devMain = 'edu.wpi.first.ntcore.DevMain'
+    generatedSources = "$buildDir/generated/main/native/cpp"
+    generatedHeaders = "$buildDir/generated/main/native/include"
+    jniSplitSetup = {
+        it.tasks.withType(CppCompile) {
+            it.dependsOn ntcoreGenerateCppTypes
+            it.dependsOn ntcoreGenerateCppHandleSource
+            it.dependsOn ntcoreGenerateCppHandleHeader
+            it.dependsOn ntcoreGenerateCHandleSource
+            it.dependsOn ntcoreGenerateCHandleHeader
+            it.dependsOn ntcoreGenerateJniSource
+        }
+    }
+    splitSetup = {
+        it.tasks.withType(CppCompile) {
+            it.dependsOn ntcoreGenerateCppTypes
+            it.dependsOn ntcoreGenerateCppHandleSource
+            it.dependsOn ntcoreGenerateCppHandleHeader
+            it.dependsOn ntcoreGenerateCHandleSource
+            it.dependsOn ntcoreGenerateCHandleHeader
+            it.dependsOn ntcoreGenerateJniSource
+            it.includes 'src/main/native/cpp'
+        }
+    }
+    exeSplitSetup = {
+        it.tasks.withType(CppCompile) {
+            it.dependsOn ntcoreGenerateCppTypes
+            it.dependsOn ntcoreGenerateCppHandleSource
+            it.dependsOn ntcoreGenerateCppHandleHeader
+            it.dependsOn ntcoreGenerateCHandleSource
+            it.dependsOn ntcoreGenerateCHandleHeader
+        }
+    }
 }
 
 apply from: "${rootDir}/shared/jni/setupBuild.gradle"
 
+model {
+    components {}
+    binaries {
+        all {
+            if (!it.buildable || !(it instanceof NativeBinarySpec)) {
+                return
+            }
+            if (it.component.name == "${nativeName}JNI") {
+                lib project: ':wpinet', library: 'wpinet', linkage: 'static'
+                lib project: ':wpiutil', library: 'wpiutil', linkage: 'static'
+            } else {
+                lib project: ':wpinet', library: 'wpinet', linkage: 'shared'
+                lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+            }
+        }
+    }
+}
+
+sourceSets.main.java.srcDir "${buildDir}/generated/main/java"
+compileJava.dependsOn ntcoreGenerateJavaTypes
+
+cppHeadersZip {
+    dependsOn ntcoreGenerateCppTypes
+    dependsOn ntcoreGenerateCppHandleHeader
+    dependsOn ntcoreGenerateCHandleHeader
+    from(generatedHeaders) {
+        into '/'
+    }
+}
+
 Action<List<String>> symbolFilter = { symbols ->
     symbols.removeIf({ !it.startsWith('NT_') })
 } as Action<List<String>>;
 
 nativeUtils.exportsConfigs {
     ntcore {
-        x86ExcludeSymbols = [
-            '_CT??_R0?AV_System_error',
-            '_CT??_R0?AVexception',
-            '_CT??_R0?AVfailure',
-            '_CT??_R0?AVruntime_error',
-            '_CT??_R0?AVsystem_error',
-            '_CTA5?AVfailure',
-            '_TI5?AVfailure',
-            '_CT??_R0?AVout_of_range',
-            '_CTA3?AVout_of_range',
-            '_TI3?AVout_of_range',
-            '_CT??_R0?AVbad_cast'
-        ]
         x64ExcludeSymbols = [
             '_CT??_R0?AV_System_error',
             '_CT??_R0?AVexception',
@@ -39,7 +341,6 @@
         ]
     }
     ntcoreJNI {
-        x86SymbolFilter = symbolFilter
         x64SymbolFilter = symbolFilter
     }
 }
diff --git a/third_party/allwpilib/ntcore/doc/networktables4.adoc b/third_party/allwpilib/ntcore/doc/networktables4.adoc
new file mode 100644
index 0000000..5384ebf
--- /dev/null
+++ b/third_party/allwpilib/ntcore/doc/networktables4.adoc
@@ -0,0 +1,819 @@
+= Network Tables Protocol Specification, Version 4.0
+WPILib Developers <wpilib@wpi.edu>
+Protocol Revision 4.0, 2/14/2021
+:toc:
+:toc-placement: preamble
+:sectanchors:
+
+A pub/sub WebSockets protocol based on NetworkTables concepts.
+
+[[motivation]]
+== Motivation
+
+Currently in NetworkTables there is no way to synchronize user value updates and NT update sweeps, and if user value updates occur more frequently than NT update sweeps, the intermediate values are lost.  This prevents NetworkTables from being a viable transport layer for seeing all value changes (e.g. for plotting) at rates higher than the NetworkTables update rate (e.g. for capturing high frequency PID changes).  While custom code can work around the second issue, it is more difficult to work around the first issue (unless full timestamps are also sent).
+
+Adding built-in support for capturing and communicating all timestamped data value changes with minimal additional user code changes will make it much easier for inexperienced teams to get high resolution, accurate data to dashboard displays with the minimal possible bandwidth and airtime usage.  Assuming the dashboard performs record and playback of NT updates, this also meets the desire to provide teams a robust data capture and playback mechanism.
+
+Migration to a pub/sub style protocol layer where the client can request only its desired topics and the frequency in which it wants to receive value changes provides some mitigation for increased network utilization due to other changes.
+
+Using WebSockets (RFC 6455) as the transport layer along with JSON and MessagePack data encoding enables browser-based dashboards and other web technologies to easily access the protocol and minimizes the amount of custom wire protocol implementation required.  Support for this protocol can easily be added in parallel to the existing NetworkTables protocol stack in order to maintain compatibility with older clients/servers and facilitate a gradual transition.
+
+[[references]]
+== References
+
+[[rfc6455,RFC6455,WebSocket]]
+* RFC 6455, The WebSocket Protocol, https://tools.ietf.org/html/rfc6455
+
+[[rfc7159,RFC7159,JSON]]
+* RFC 7159, The JavaScript Object Notation (JSON) Data Interchange Format, https://tools.ietf.org/html/rfc7159
+
+[[messagepack]]
+* MessagePack, MessagePack Specification, https://github.com/msgpack/msgpack/blob/master/spec.md
+
+[[networktables3]]
+* <<networktables3.adoc#, Network Tables Protocol Specification, Version 3.0>>
+
+[[cristians-algorithm]]
+* Cristian's algorithm, https://en.wikipedia.org/wiki/Cristian%27s_algorithm
+
+[[design]]
+== Design
+
+Both text and binary <<WebSocket,WebSocket>> frames are used for transport.  Text frames are <<JSON,JSON>>, and binary frames are <<messagepack,MessagePack>>.  JSON is used for control messages for human readability and ease of debugging.  MessagePack is used only for time and space efficient encoding of values, and the MessagePack subset used in this protocol is small enough that a custom encoder/decoder can be easily implemented for languages that lack good MessagePack libraries.
+
+Consistent with pub/sub nomenclature, this spec uses the term "topic" for what was called an "entry" or "key" in the <<networktables3,NT 3.0 spec>>.
+
+MessagePack messages use numeric IDs for topics to reduce data size; these IDs have a 1:1 mapping to a full topic name (a string).  This mapping is communicated via the JSON <<msg-announce>>.
+
+[[topic-names]]
+=== Topic Names
+
+Topic have UTF-8 string names.  Names starting with `$` are reserved for use by the server (see <<meta-topics>>).  Otherwise names are unrestricted, but convention is for them to start with `/` and be `/`-separated (without consecutive `//`) to make a Unix-path-like structure.
+
+[[timestamps]]
+=== Timestamps
+
+All MessagePack messages are timestamped.  Timestamps are specified in unsigned integer microseconds--for robot programs, microseconds are preferred as the FPGA provides time in microseconds, and integers result in a more compact wire encoding (in typical robot use, integer microseconds timestamps will be half the size of double timestamps until about T=70 minutes, and in the worst case will be no larger).
+
+Timestamps in messages always use the server time base.  The server time base is synchronized across the network by the means described in this section (an implementation of <<cristians-algorithm, Cristian's algorithm>>).
+
+Implementations should expose the actual timestamps for messages as well as provide methods to convert from server time base to local time to facilitate applications that prefer the server time base (e.g. a dashboard showing robot events might prefer to use server time instead of wall clock time).
+
+The topic ID of -1 is reserved for timestamp communication.  Clients shall periodically (e.g. every few seconds) send, in a manner that minimizes transmission delays, a MessagePack message with ID of -1, a timestamp of 0, and an implementation-selected type and data value (typically int or float 64) containing its (the client's) current local time.
+
+When the server receives an -1 ID message from a client, it shall respond to the client, in a manner that minimizes transmission delays, with a MessagePack message with ID=-1, a timestamp of its (the server's) current local time (in microseconds), and the client-provided data value.
+
+When the client receives an -1 ID message from the server, it shall compute the round trip time (RTT) from the delta between the message's data value and the current local time.  If the RTT is less than that from previous measurements, the client shall use the timestamp in the message plus ½ the RTT as the server time equivalent to the current local time, and use this equivalence to compute server time base timestamps from local time for future messages.
+
+Due to the fact there can be multiple publishers for a single topic and unpredictable network delays / clock drift, there is no global total order for timestamps either globally or on a per-topic basis.  While single publishers for real-time data will be the norm, and in that case the timestamps will usually be in order, applications that use timestamps need to be able to handle out-of-order timestamps.
+
+[[reconnection]]
+=== Caching and Reconnection Handling
+
+Servers shall keep a retained value for each topic for the purposes of <<msg-subscribe>> requests; the retained value shall be the value in the largest timestamp (greater-than or equal-to) message received for that topic.  This retained value is deleted if the topic is deleted (e.g. there are no more publishers).
+
+Clients may similarly keep a retained value for each topic for ease of use by user code.  If this is done, this retained value shall be updated by both locally published values and received messages for that topic with greater-than/equal-to timestamps, and the retained value shall be deleted when a <<msg-unannounce>> is received.
+
+Clients should support a "set default" operation for a topic.  This is a "weak" value update that publishes a value with a timestamp of 0 (thereby not causing the retained value of the server or other clients to be updated if they have a current value update with a timestamp > 0).  Typically the "set default" operation should also result in the retained property being set on the topic.
+
+Clients may accept application commands to publish and subscribe while disconnected.  If a client does so, in addition to maintaining a retained value as described above, it must keep track for each application-published topic whether any of the locally published values were "strong" (via a "set" operation), or all of them were "weak" (via a "set default" operation).  While disconnected, there is no reference clock; "strong" timestamps shall be set to 1 and "weak" timestamps shall be set to 0.
+
+When the client disconnects, the client shall delete any topics that are not published by the application and do not have the retained or persistent properties set.  The client shall also reset the application-published retained value timestamps to 0 and 1 as per the previous paragraph.
+
+When the connection to the server is established (either reconnect or initial connection), the client shall publish and send _only_ the retained values to the server that are in application-published topics (those with timestamps of 0 and 1, per above).  Only the values with timestamp 0 may be sent immediately upon reconnection.  The values with timestamp 1 must wait until the client clock is synchronized with the server clock; the timestamps for these values when sent to the server must be either the current server time or, if possible, an estimation of server time when the values were actually written.
+
+Note: the previous paragraphs enable offline, multi-publisher operation under network/server reboot conditions without creating zombie topics, assuming clients use "set default" and the retained property appropriately.  This is achieved mainly via the use of timestamps 0 and 1 to enable tie breaks such that normally-set values (timestamp X) are used in preference to retained values (timestamp 1), and retained values are used in preference to weakly set values (timestamp 0).  An example use case is as follows:
+
+* Server starts
+* Dashboard client connects
+* Coprocessor client connects
+* Coprocessor client publishes configuration topic, sends an initial value using "set default", and subscribes to the topic (to detect configuration changes)
+* Dashboard client sees configuration topic published and subscribes to it
+* Dashboard user changes configuration value--dashboard client publishes to the topic and sends the user value
+* Coprocessor receives the user value and updates its retained value
+* **Server reboots** (this also disconnects the dashboard and coprocessor clients)
+* If the dashboard reconnects first:
+** The user value was published and cached (retained value) on the dashboard client, so the dashboard client re-publishes and sends the cached data with timestamp 1.
+** The coprocessor client reconnects later.  It also published and cached, but it only ever called "set default" and sends the cached data (which is also the user value) with timestamp 0.  It receives the retained value from the server with timestamp 1, and updates locally.
+** The server propagates the timestamp 0 message, but since it has a retained value with timestamp 1, as do other clients, the retained value is not updated and the user value remains active.
+* If the coprocessor reconnects first:
+** The coprocessor client only ever called "set default", so it sends the cached data (the user-set value) with timestamp 0.
+** If the dashboard never reconnects, no new values are published, so the user-set value is active
+** If the dashboard reconnects, it sends a message with timestamp 1 ("strong" set).  This propagates but does not change the value (it's the same user-set as before).
+* If the dashboard updates the value while offline, it's still a "strong set" and wins the tie
+
+A second use case:
+
+* Server starts
+* Dashboard client connects
+* Dashboard client publishes configuration value with the retained property set, and publishes an initial value
+* Dashboard client disconnects.  The topic is *not* deleted on the server because the retained property is set.
+* Coprocessor client connects
+* Server sends announce message for topic and sends retained value (with timestamp 1)
+* Coprocessor client publishes, uses "set default", and subscribes to the topic.  Since "set default" uses a timestamp of 0, it loses to the retained value with timestamp 1, and the coprocessor subscriber will see the value previously set by the dashboard.
+* Dashboard client reconnects
+
+[[server]]
+=== Server Behavior
+
+Topic IDs may be common across all client connections or be connection-specific.  If they are common, the server needs to be careful regarding topic ID reuse due to deleted topics, as the protocol provides no way to change a client topic ID.  Requests (e.g. <<msg-subscribe,`subscribe`>> or <<msg-publish,`publish`>>) are always specific to a single client connection.
+
+The server shall keep a publisher count for each topic.  Persistent and retained topics have an additional implicit publisher.  When the publisher count reaches zero (which only happens for non-persistent and non-retained topics), the server shall delete the topic (including its retained value).  When a client connection is lost, the server shall handle that as an implicit <<msg-unpublish,`unpublish`>> for all topics currently published by that client.
+
+The server may operate in-process to an application (e.g. a robot program).  In this case, the application operationally behaves like a client (e.g. it sends publish requests and receives topic announcements), but of course does not need to estimate delta time, create JSON/MessagePack messages, etc, as all of the necessary operations can be performed programmatically within the same process.
+
+[[client]]
+=== Client Behavior
+
+Clients are responsible for keeping server connections established (e.g. via retries when a connection is lost).  Topic IDs must be treated as connection-specific; if the connection to the server is lost, the client is responsible for sending new <<msg-publish,`publish`>> and <<msg-subscribe,`subscribe`>> messages as required for the application when a new connection is established, and not using old topic IDs, but rather waiting for new <<msg-announce,`announce`>> messages to be received.
+
+Except for offline-published values with timestamps of 0, the client shall not send any other published values to the server until its clock is synchronized with the server per the <<timestamps>> section.
+
+Clients may publish a value at any time following clock synchronization.  Clients may subscribe to meta-topics to determine whether or not to publish a value change (e.g. based on whether there are any subscribers, or based on specific <<sub-options>>).
+
+[[meta-topics]]
+=== Server-Published Meta Topics
+
+The server shall publish a standard set of topics with information about server state.  Clients may subscribe to these topics for diagnostics purposes or to determine when to publish value changes.  These topics are hidden--they are not announced to subscribers to an empty prefix, only to subscribers that have subscribed to `"$"` or  longer prefixes.
+
+[cols="1,1,2", options="header"]
+|===
+|Topic Name|Data Type|Description
+|<<meta-clients,`$clients`>>|`msgpack`|Connected clients
+|<<meta-client-sub,`$clientsub$<client>`>>|`msgpack`|Client `<client>` subscriptions
+|<<meta-server-sub,`$serversub`>>|`msgpack`|Server subscriptions
+|<<meta-sub,`$sub$<topic>`>>|`msgpack`|Subscriptions to `<topic>`
+|<<meta-client-pub,`$clientpub$<client>`>>|`msgpack`|Client `<client>` publishers
+|<<meta-server-pub,`$serverpub`>>|`msgpack`|Server publishers
+|<<meta-pub,`$pub$<topic>`>>|`msgpack`|Publishers to `<topic>`
+|===
+
+[[meta-clients]]
+==== Connected Clients (`$clients`)
+
+The server shall update this topic when a client connects or disconnects.
+
+The MessagePack contents shall be an array of maps.  Each map in the array shall have the following contents:
+
+[cols="1,1,2,6",options="header"]
+|===
+|Key
+|Value type
+|Description
+|Notes
+
+|`id`
+|String
+|Client name
+|
+
+|`conn`
+|String
+|Connection info
+|Connection information about the client; typically host:port
+|===
+
+[[meta-client-sub]]
+==== Client Subscriptions (`$clientsub$<client>`)
+
+The server shall update this topic when the corresponding client subscribes or unsubscribes to any topic.
+
+The MessagePack contents shall be an array of maps.  Each map in the array shall have the following contents:
+
+[cols="1,2,2,6",options="header"]
+|===
+|Key
+|Value type
+|Description
+|Notes
+
+|`uid`
+|Integer
+|Subscription UID
+|A client-generated unique identifier for this subscription.
+
+|`topics`
+|Array of String
+|Array of topic names or prefixes
+|One or more topic names or prefixes (if the `prefix` option is true) that messages are sent for.
+
+|`options`
+|Map
+|Options
+|<<sub-options>>
+|===
+
+[[meta-server-sub]]
+==== Server Subscriptions (`$serversub`)
+
+Same as `$clientsub`, except it's updated when the server subscribes or unsubscribes to any topic.
+
+[[meta-sub]]
+==== Subscriptions (`$sub$<topic>`)
+
+The server shall update this topic when a client subscribes or unsubscribes to `<topic>`.
+
+The MessagePack contents shall be an array of maps.  Each map in the array shall have the following contents:
+
+[cols="1,2,2,6",options="header"]
+|===
+|Key
+|Value type
+|Description
+|Notes
+
+|`client`
+|String
+|Client name
+|Empty string for server subscriptions.
+
+|`subuid`
+|Integer
+|Subscription UID
+|A client-generated unique identifier for this subscription.
+
+|`options`
+|Map
+|Options
+|<<sub-options>>
+|===
+
+[[meta-client-pub]]
+==== Client Publishers (`$clientpub$<client>`)
+
+The server shall update this topic when the corresponding client publishes or unpublishes any topic.
+
+The MessagePack contents shall be an array of maps.  Each map in the array shall have the following contents:
+
+[cols="1,2,2,6",options="header"]
+|===
+|Key
+|Value type
+|Description
+|Notes
+
+|`uid`
+|Integer
+|Publisher UID
+|A client-generated unique identifier for this publisher.
+
+|`topic`
+|String
+|Topic name
+|
+|===
+
+[[meta-server-pub]]
+==== Server Publishers (`$serverpub`)
+
+Same as `$clientpub`, except it's updated when the server publishes or unpublishes any topic.
+
+[[meta-pub]]
+==== Publishers (`$pub$<topic>`)
+
+The server shall update this topic when a client publishes or unpublishes to `<topic>`.
+
+The MessagePack contents shall be an array of maps.  Each map in the array shall have the following contents:
+
+[cols="1,2,2,6",options="header"]
+|===
+|Key
+|Value type
+|Description
+|Notes
+
+|`client`
+|String
+|Client name
+|Empty string for server publishers.
+
+|`pubuid`
+|Integer
+|Publisher UID
+|A client-generated unique identifier for this publisher.
+|===
+
+[[websockets-config]]
+== WebSockets Protocol Configuration
+
+Both clients and servers shall support unsecure connections (`ws:`) and may support secure connections (`wss:`).  In a trusted network environment (e.g. a robot network), clients that support secure connections should fall back to an unsecure connection if a secure connection is not available.
+
+Servers shall support a resource name of `/nt/<name>`, where `<name>` is an arbitrary string representing the client name.  The client name does not need to be unique; multiple connections to the same name are allowed; the server shall ensure the name is unique (for the purposes of meta-topics) by appending a '@' and a unique number (if necessary).  To support this, the name provided by the client should not contain an embedded '@'.  Clients should provide a way to specify the resource name (in particular, the client name portion).
+
+Both clients and servers shall support/use subprotocol `networktables.first.wpi.edu` for this protocol. Clients and servers shall terminate the connection in accordance with the WebSocket protocol unless both sides support this subprotocol.
+
+The unsecure standard server port number shall be 5810, the secure standard port number shall be 5811.
+
+[[data-types]]
+== Supported Data Types
+
+The following data types are supported.  Note: implementations may map integer and float to double internally.  Any data type string not in the table below shall be handled in the binary protocol as data type 5 (binary); some specific binary examples are included in the table below.
+
+[cols="1,1,1,1,4",options="header"]
+|===
+|Data type|MessagePack format family|NT 3 data type|Data Type string
+|Notes
+
+|0|bool|Boolean|`boolean`
+|
+
+|1|float 64|Number (double)|`double`
+|
+
+|2|int|Number (double)|`int`
+.2+|Current NetworkTables protocol and user APIs only support double-precision float numeric values; implementations may choose to upgrade APIs to support integer and/or single-precision float values.
+
+|3|float 32|Number (double)|`float`
+
+.2+|4
+.2+|str
+.2+|String
+|`string`
+|
+
+|`json`
+|JSON data (e.g. structured data)
+
+.4+|5
+.4+|bin
+.4+|Raw
+|`raw`
+|Raw data, no specified format
+
+|`rpc`
+|For backwards compatibility with NT 3.0
+
+|`msgpack`
+|Nested MessagePack data (e.g. structured data)
+
+|`protobuf`
+|Google Protocol Buffers data (structured).  Uses property `protobuf` to communicate the data description.
+
+|16|array of all bool|Boolean Array|`boolean[]`
+|All elements of the array must be boolean
+
+|17|array of all float 64|Number Array|`double[]`
+|All elements of the array must be double-precision floats
+
+|18|array of all int|Number Array|`int[]`
+|All elements of the array must be integers.  See note on Number
+
+|19|array of all float 32|Number Array|`float[]`
+|All elements of the array must be single-precision floats.  See note on Number
+
+|20|array of all str|String Array|`string[]`
+|All elements of the array must be text strings
+|===
+
+[[properties]]
+== Properties
+
+Each published topic may also have properties associated to it.  Properties are represented in the protocol as JSON and thus property values may be any JSON type.  Property keys must be strings.  The following properties have a defined meaning in this spec.  Servers shall support arbitrary properties being set outside of this set.  Clients shall ignore properties they do not recognize.  Properties are initially set on publish and may be changed (by any client) using <<msg-setproperties>>.
+
+[cols="1,1,1,6",options="header"]
+|===
+|Property|Type|Description|Notes
+|`persistent`|boolean|Persistent Flag|If true, the last set value will be periodically saved to persistent storage on the server and be restored during server startup.  Topics with this property set to true will not be deleted by the server when the last publisher stops publishing.
+|`retained`|boolean|Retained Flag|Topics with this property set to true will not be deleted by the server when the last publisher stops publishing.
+|===
+
+[[sub-options]]
+== Subscription Options
+
+Each subscription may have options set.  The following options have a defined meaning in this spec.  Servers shall preserve arbitrary options, as servers and clients may support arbitrary options outside of this set.  Options are set using <<msg-subscribe>> and cannot be changed.
+
+[cols="1,1,2,6",options="header"]
+|===
+|Key
+|Value type
+|Description
+|Notes
+
+|`periodic` (optional)
+|Number
+|Periodic sweep time (in seconds)
+|How frequently the server should send changes.  The server may send more frequently than this (e.g. use a combined minimum period for all values) or apply a restricted range to this value. The default if unspecified is 100 ms (same as NT 3.0).
+
+|`all` (optional)
+|Boolean
+|All Changes Flag
+|If true, the server should send all value changes over the wire.  If false, only the most recent value is sent (same as NT 3.0 behavior).  If not specified, defaults to false.
+
+|`topicsonly` (optional)
+|Boolean
+|No Value Changes Flag
+|If true, the server should not send any value changes over the wire regardless of other options.  This is useful for only getting topic announcements.  If false, value changes are sent in accordance with other options.  If not specified, defaults to false.
+
+|`prefix` (optional)
+|Boolean
+|Prefix Flag
+|If true, any topic starting with the name in the subscription `topics` list is subscribed to, not just exact matches.  If not specified, defaults to false.
+|===
+
+[[text-frames]]
+== Text Data Frames
+
+Each WebSockets text data frame shall consist of a list of <<JSON,JSON>> objects ("JSON messages").
+
+Each JSON message shall be a JSON object with two keys: a `method` key containing a lowercase string value describing the type of message as per the following table, and a `params` key containing the message parameters as a JSON object.  The contents of the params object depends on the method; see the sections for each message for details.
+
+Clients and servers shall ignore JSON messages that:
+
+* are not objects
+* have no `method` key or `params` key
+* have a `method` value that is not a string
+* have a `params` value that is not an object
+* have a `method` value that is not listed in the below table
+
+[cols="1,2,2,3",options="header"]
+|===
+|Method
+|Description
+|Direction
+|Response
+
+4+|Publish Messages (Client to Server)
+
+|<<msg-publish,`publish`>>
+|Publish Request
+|Client to Server
+|<<msg-announce,`announce`>>
+
+|<<msg-unpublish,`unpublish`>>
+|Publish Release
+|Client to Server
+|<<msg-unannounce,`unannounce`>> (if topic deleted)
+
+|<<msg-setproperties,`setproperties`>>
+|Set Properties
+|Client to Server
+|<<msg-properties,`properties`>>
+
+4+|Value/Subscription Messages (Client to Server)
+
+|<<msg-subscribe,`subscribe`>>
+|Subscribe
+|Client to Server
+|<<binary-frames,MessagePack messages>> (once topic is announced)
+
+|<<msg-unsubscribe,`unsubscribe`>>
+|Unsubscribe
+|Client to Server
+|---
+
+4+|Announcement Messages (Server to Client)
+
+|<<msg-announce,`announce`>>
+|Topic Announcement
+|Server to Client
+|---
+
+|<<msg-unannounce,`unannounce`>>
+|Topic Removed
+|Server to Client
+|---
+
+|<<msg-properties,`properties`>>
+|Properties Update
+|Server to Client
+|---
+|===
+
+[[publish-messages]]
+=== Publish Messages (Client to Server)
+
+[[msg-publish]]
+==== Publish Request Message (`publish`)
+
+Sent from a client to the server to indicate the client wants to start publishing values at the given topic.  The server shall respond with a <<msg-announce>>, even if the topic was previously announced.  The client can start publishing data values via MessagePack messages immediately after sending this message, but the messages will be ignored by the server if the publisher data type does not match the topic data type.
+
+The `publish` JSON message shall contain the following parameters:
+
+[cols="1,1,2,6",options="header"]
+|===
+|Key
+|Value type
+|Description
+|Notes
+
+|`name`
+|String
+|Publish name
+|The topic name being published
+
+|`pubuid`
+|Integer
+|Publisher UID
+|A client-generated unique identifier for this publisher.  Use the same UID later to unpublish.  This is also the identifier that the client will use in MessagePack messages for this topic.
+
+|`type`
+|String
+|Type of data
+|The requested data type (as a string).
+
+If the topic is newly created (e.g. there are no other publishers) this sets the value type.  If the topic was previously published, this is ignored.  The <<msg-announce,`announce`>> message contains the actual topic value type that the client shall use when publishing values.
+
+Implementations should indicate an error if the user tries to publish an incompatible type to that already set for the topic.
+
+|`properties`
+|Map
+|Properties
+|Initial topic properties.
+
+If the topic is newly created (e.g. there are no other publishers) this sets the topic properties.  If the topic was previously published, this is ignored.  The <<msg-announce,`announce`>> message contains the actual topic properties.  Clients can use the <<msg-setproperties,`setproperties`>> message to change properties after topic creation.
+|===
+
+[[msg-unpublish]]
+==== Publish Release Message (`unpublish`)
+
+Sent from a client to the server to indicate the client wants to stop publishing values for the given topic and publisher.  The client should stop publishing data value updates via binary MessagePack messages for this publisher prior to sending this message.
+
+When there are no remaining publishers for a non-persistent topic, the server shall delete the topic and send a <<msg-unannounce>> to all clients who have been sent a previous <<msg-announce>> for the topic.
+
+The `unpublish` JSON message shall contain the following parameters:
+
+[cols="1,1,2,6",options="header"]
+|===
+|Key
+|Value type
+|Description
+|Notes
+
+|`pubuid`
+|Integer
+|Publisher UID
+|The same unique identifier passed to the <<msg-publish,`publish`>> message
+|===
+
+[[msg-setproperties]]
+==== Set Properties Message (`setproperties`)
+
+Sent from a client to the server to change properties (see <<properties>>) for a given topic.  The server will send a corresponding <<msg-properties>> to all subscribers to the topic (if the topic is published).  This message shall be ignored by the server if the topic is not published.
+
+The `setproperties` JSON message shall contain the following parameters:
+
+[cols="1,2,4",options="header"]
+|===
+|Key
+|Value type
+|Description
+
+|`name`
+|String
+|Topic name
+
+|`update`
+|Map
+|Properties to update
+|===
+
+If a property is not included in the update map, its value is not changed.  If a property is provided in the update map with a value of null, the property is deleted.
+
+[[subscription-messages]]
+=== Value/Subscription Messages (Client to Server)
+
+[[msg-subscribe]]
+==== Subscribe Message (`subscribe`)
+
+Sent from a client to the server to indicate the client wants to subscribe to value changes for the specified topics / groups of topics.  The server shall send MessagePack messages containing the current values for any existing topics upon receipt, and continue sending MessagePack messages for future value changes.  If a topic does not yet exist, no message is sent until it is created (via a publish), at which point a <<msg-announce>> will be sent and MessagePack messages will automatically follow as they are published.
+
+Subscriptions may overlap; only one MessagePack message is sent per value change regardless of the number of subscriptions.  Sending a `subscribe` message with the same subscription UID as a previous `subscribe` message results in updating the subscription (replacing the array of identifiers and updating any specified options).
+
+The `subscribe` JSON message shall contain the following parameters:
+
+[cols="1,2,2,6",options="header"]
+|===
+|Key
+|Value type
+|Description
+|Notes
+
+|`topics`
+|Array of String
+|Array of topic names or prefixes
+|One or more topic names or prefixes (if the `prefix` option is true) to start receiving messages for.
+
+|`subuid`
+|Integer
+|Subscription UID
+|A client-generated unique identifier for this subscription.  Use the same UID later to unsubscribe.
+
+|`options`
+|Map
+|Options
+|<<sub-options>>
+|===
+
+[[msg-unsubscribe]]
+==== Unsubscribe Message (`unsubscribe`)
+
+Sent from a client to the server to indicate the client wants to stop subscribing to messages for the given subscription.
+
+The `unsubscribe` JSON message shall contain the following parameters:
+
+[cols="1,1,2,6",options="header"]
+|===
+|Key
+|Value type
+|Description
+|Notes
+
+|`subuid`
+|Integer
+|Subscription UID
+|The same unique identifier passed to the <<msg-subscribe,`subscribe`>> message
+|===
+
+[[announcement-messages]]
+=== Announcement Messages (Server to Client)
+
+[[msg-announce]]
+==== Topic Announcement Message (`announce`)
+
+The server shall send this message for each of the following conditions:
+
+- To all clients subscribed to a matching prefix when a topic is created
+
+- To a client in response to an <<msg-publish>> from that client
+
+The `announce` JSON message shall contain the following parameters:
+
+[cols="1,2,2,6",options="header"]
+|===
+|Key
+|Value type
+|Description
+|Notes
+
+|`name`
+|String
+|Topic name
+|
+
+|`id`
+|Integer
+|Topic ID
+|The identifier that the server will use in MessagePack messages for this topic
+
+|`type`
+|String
+|Data type
+|The data type for the topic (as a string)
+
+|`pubuid` (optional)
+|Integer
+|Publisher UID
+|If this message was sent in response to a <<msg-publish,`publish`>> message, the Publisher UID provided in that message.  Otherwise absent.
+
+|`properties`
+|Map
+|Properties
+|Topic <<properties>>
+|===
+
+[[msg-unannounce]]
+==== Topic Removed Message (`unannounce`)
+
+The server shall send this message when a previously announced (via a <<msg-announce>>) topic is deleted.
+
+The `unannounce` JSON message shall contain the following parameters:
+
+[cols="1,1,2,6",options="header"]
+|===
+|Key
+|Value type
+|Description
+|Notes
+
+|`name`
+|String
+|Topic name
+|
+
+|`id`
+|Integer
+|Topic ID
+|The identifier that the server was using for value updates
+|===
+
+[[msg-properties]]
+==== Properties Update Message (`properties`)
+
+The server shall send this message when a previously announced (via a <<msg-announce>>) topic has its properties changed (via <<msg-setproperties>>).
+
+The `properties` JSON message shall contain the following parameters:
+
+[cols="1,1,2,6",options="header"]
+|===
+|Key
+|Value type
+|Description
+|Notes
+
+|`name`
+|String
+|Topic name
+|
+
+|`ack`
+|Boolean
+|Acknowledgement
+|True if this message is in response to a <<msg-setproperties,`setproperties`>> message from the same client.  Otherwise absent.
+
+|`update`
+|Map
+|Properties to update (from <<msg-setproperties,`setproperties`>>)
+|===
+
+The client shall handle the `update` value as follows.  If a property is not included in the update map, its value is not changed.  If a property is provided in the update map with a value of null, the property is deleted.
+
+[[binary-frames]]
+== Binary Data Frames
+
+Each WebSockets binary data frame shall consist of a <<messagepack,MessagePack>> data stream with one or more complete MessagePack arrays ("MessagePack messages").  MessagePack messages shall not span across WebSockets data frames.  It is up to implementations to decide how many MessagePack messages to put into each transmitted WebSockets data frame (as there is an efficiency/latency tradeoff).
+
+Each MessagePack message shall be a MessagePack array with 4 elements.  Implementations can either ignore other types of messages (e.g. non-arrays, other numbers of elements) or terminate the connection (allowing this enables use of simplified decoder implementations).
+
+Messages shall consist of (in this order):
+
+* Topic/Publisher ID: unsigned integer, or -1 (RTT measurement)
+* Timestamp: integer microseconds
+* Data type: unsigned integer
+* Data value (see below)
+
+Topic IDs are used for server to client messages.  Topic IDs shall be assigned via JSON <<msg-announce,`announce`>> messages.  Client implementations shall ignore messages with topic IDs they do not recognize.  Server implementations shall not send messages with topic IDs that were not assigned previously with a JSON message.
+
+Publisher IDs are used for client to server messages.  Publisher IDs shall be assigned by the client and be communicated to the server via JSON <<msg-publish,`publish`>> messages.  Server implementations shall ignore messages with publisher IDs they do not recognize.  Client implementations shall not send messages with publisher IDs that were not assigned previously with a JSON message.
+
+Implementations must ignore messages with data values they cannot decode (either by ignoring the message or by terminating the connection), and shall send messages with data values consistent with the above table.
+
+An example double value update would be 17 bytes:
+
+`94` (array with 4 elements)
+
+`32` (topic/publisher ID=50)
+
+`D2 07 27 0E 00` (timestamp of exactly 2 minutes in integer microseconds)
+
+`01` (data type: double-precision float)
+
+`CB 3F BF 97 24 74 53 8E F3` (double value of 0.1234)
+
+For comparison, a double value update in NT 3.0 is 14 bytes (and does not contain a timestamp).
+
+[[drawbacks]]
+== Drawbacks
+
+[[drawback-api]]
+=== API Changes
+
+While the server (robot) APIs can have minimal to no changes, the current NetworkTables API doesn’t directly map to a pub/sub approach, except for the listener API.  A new API will be required to take full advantage of the features of this protocol.  One big advantage of the current APIs is that the client and server APIs are the same, so if we update the client API it should work on the server as well.
+
+[[drawback-tcp]]
+=== TCP Only
+
+Everything is sent via the WebSockets pipe, which can result in latency spikes due to TCP retransmissions, even for timestamp updates.  Should there be a send-via-UDP option?  Web technologies generally can’t use UDP but this feature could be useful for other use cases.  However, adding this would add significant complexity and might be better left to MQTT or other full-stack alternatives.
+
+[[drawback-client-server]]
+=== No peer-to-peer client connections
+
+This protocol continues the previous NT approach of having all traffic go through the central NT server, rather than supporting direct peer to peer connections.  This adds latency but simplifies the overall protocol design and makes it possible to have clients that can’t set up servers (e.g. web browsers).
+
+[[alternatives]]
+== Alternatives
+
+[[alt-do-nothing]]
+=== Do nothing
+
+The major features in this proposal (accessibility to web technologies and timestamping and sending all changes) would not be made available to users.  Users would continue to need to deal with these issues manually or by using third-party workarounds.
+
+[[alt-raw-protocol]]
+=== Update the raw NetworkTables protocol (without using WebSockets)
+
+This does not provide one of the major benefits to moving to a WebSockets protocol, which is easy to use by browsers.  While current workarounds like pynetworktables2js exist, a protocol revision which does not address this need feels shortsighted.
+
+[[alt-encapsulation]]
+=== Encapsulate the current NT 3.0 protocol in WebSockets
+
+While this makes the current protocol more easily accessible to web technologies, the current protocol does not have integrated support for timestamping or sending all changes.  It also requires substantially more custom decoder implementation work than MessagePack, and does not offer human-readable control messages.
+
+[[alt-mqtt]]
+=== Use MQTT or another existing protocol
+
+MQTT requires running a separate server from the robot program, and the robot program to be a client to it (unlike NT, it has no means of doing value updates within the server itself).  MQTT natively does not use WebSockets (it’s a custom wire protocol like the current NetworkTables), although there is a WebSockets variant.  MQTT is a significantly more complicated protocol with support for things like full QOS.
+
+[[trades]]
+== Trades
+
+[[trade-json-updates]]
+=== JSON option for value updates (rejected)
+
+This was considered, but rejected for two reasons: encoding overhead and spec/implementation effort.  In benchmarking on desktop systems, JSON was 25% the speed of MessagePack when encoding doubles (due to text conversion), and in typical robot use, this overhead would largely land on the robot controller, which also has the fewest resources.  In addition, requiring implementation of both JSON and MessagePack encoding nearly doubles the amount of encode/decode implementation effort, particularly as JSON does not have good binary data support and would require Base64 or something similar to encode binary data as a string.
+
+[[trade-timestamp]]
+=== Timestamp format
+
+The spec uses integer microseconds.  This seems to be a reasonable enough resolution for FRC use and is common with the FPGA clock resolution.
+
+[[unresolved-questions]]
+== Unresolved Questions
diff --git a/third_party/allwpilib/ntcore/generate_topics.py b/third_party/allwpilib/ntcore/generate_topics.py
new file mode 100644
index 0000000..ece7df2
--- /dev/null
+++ b/third_party/allwpilib/ntcore/generate_topics.py
@@ -0,0 +1,121 @@
+import glob
+import os
+import sys
+from jinja2 import Environment, FileSystemLoader
+import json
+
+
+def Output(outPath, outfn, contents):
+    if not os.path.exists(outPath):
+        os.makedirs(outPath)
+
+    outpathname = f"{outPath}/{outfn}"
+
+    if os.path.exists(outpathname):
+        with open(outpathname, "r") as f:
+            if f.read() == contents:
+                return
+
+    # File either doesn't exist or has different contents
+    with open(outpathname, "w") as f:
+        f.write(contents)
+
+
+def main():
+    dirname, _ = os.path.split(os.path.abspath(__file__))
+    cmake_binary_dir = sys.argv[1]
+
+    with open(f"{dirname}/src/generate/types.json") as f:
+        types = json.load(f)
+
+    # Java files
+    env = Environment(
+        loader=FileSystemLoader(f"{dirname}/src/generate/java"), autoescape=False
+    )
+    rootPath = f"{cmake_binary_dir}/generated/main/java/edu/wpi/first/networktables"
+    for fn in glob.glob(f"{dirname}/src/generate/java/*.jinja"):
+        template = env.get_template(os.path.basename(fn))
+        outfn = os.path.basename(fn)[:-6]  # drop ".jinja"
+        if os.path.basename(fn).startswith("NetworkTable") or os.path.basename(
+            fn
+        ).startswith("Generic"):
+            output = template.render(types=types)
+            Output(rootPath, outfn, output)
+        else:
+            for replacements in types:
+                output = template.render(replacements)
+                if outfn == "Timestamped.java":
+                    outfn2 = f"Timestamped{replacements['TypeName']}.java"
+                else:
+                    outfn2 = f"{replacements['TypeName']}{outfn}"
+                Output(rootPath, outfn2, output)
+
+    # C++ classes
+    env = Environment(
+        loader=FileSystemLoader(f"{dirname}/src/generate/include/networktables"),
+        autoescape=False,
+    )
+    rootPath = f"{cmake_binary_dir}/generated/main/native/include/networktables"
+    for fn in glob.glob(f"{dirname}/src/generate/include/networktables/*.jinja"):
+        template = env.get_template(os.path.basename(fn))
+        outfn = os.path.basename(fn)[:-6]  # drop ".jinja"
+        for replacements in types:
+            output = template.render(replacements)
+            outfn2 = f"{replacements['TypeName']}{outfn}"
+            Output(rootPath, outfn2, output)
+
+    # C++ handle API (header)
+    env = Environment(
+        loader=FileSystemLoader(f"{dirname}/src/generate/include"), autoescape=False
+    )
+    template = env.get_template("ntcore_cpp_types.h.jinja")
+    output = template.render(types=types)
+    Output(
+        f"{cmake_binary_dir}/generated/main/native/include",
+        "ntcore_cpp_types.h",
+        output,
+    )
+
+    # C++ handle API (source)
+    env = Environment(
+        loader=FileSystemLoader(f"{dirname}/src/generate/cpp"), autoescape=False
+    )
+    template = env.get_template("ntcore_cpp_types.cpp.jinja")
+    output = template.render(types=types)
+    Output(
+        f"{cmake_binary_dir}/generated/main/native/cpp", "ntcore_cpp_types.cpp", output
+    )
+
+    # C handle API (header)
+    env = Environment(
+        loader=FileSystemLoader(f"{dirname}/src/generate/include"), autoescape=False
+    )
+    template = env.get_template("ntcore_c_types.h.jinja")
+    output = template.render(types=types)
+    Output(
+        f"{cmake_binary_dir}/generated/main/native/include",
+        "ntcore_c_types.h",
+        output,
+    )
+
+    # C handle API (source)
+    env = Environment(
+        loader=FileSystemLoader(f"{dirname}/src/generate/cpp"), autoescape=False
+    )
+    template = env.get_template("ntcore_c_types.cpp.jinja")
+    output = template.render(types=types)
+    Output(
+        f"{cmake_binary_dir}/generated/main/native/cpp", "ntcore_c_types.cpp", output
+    )
+
+    # JNI
+    env = Environment(
+        loader=FileSystemLoader(f"{dirname}/src/generate/cpp/jni"), autoescape=False
+    )
+    template = env.get_template("types_jni.cpp.jinja")
+    output = template.render(types=types)
+    Output(f"{cmake_binary_dir}/generated/main/native/cpp/jni", "types_jni.cpp", output)
+
+
+if __name__ == "__main__":
+    main()
diff --git a/third_party/allwpilib/ntcore/src/dev/native/cpp/main.cpp b/third_party/allwpilib/ntcore/src/dev/native/cpp/main.cpp
index f863018..fac64e7 100644
--- a/third_party/allwpilib/ntcore/src/dev/native/cpp/main.cpp
+++ b/third_party/allwpilib/ntcore/src/dev/native/cpp/main.cpp
@@ -2,14 +2,107 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
-#include <fmt/core.h>
+#include <algorithm>
+#include <chrono>
+#include <cmath>
+#include <cstdlib>
+#include <numeric>
+#include <string_view>
+#include <thread>
+
+#include <fmt/format.h>
+#include <wpi/Synchronization.h>
 
 #include "ntcore.h"
+#include "ntcore_cpp.h"
 
-int main() {
+void bench();
+
+int main(int argc, char* argv[]) {
+  if (argc == 2 && std::string_view{argv[1]} == "bench") {
+    bench();
+    return EXIT_SUCCESS;
+  }
   auto myValue = nt::GetEntry(nt::GetDefaultInstance(), "MyValue");
 
   nt::SetEntryValue(myValue, nt::Value::MakeString("Hello World"));
 
-  fmt::print("{}\n", nt::GetEntryValue(myValue)->GetString());
+  fmt::print("{}\n", nt::GetEntryValue(myValue).GetString());
+}
+
+void PrintTimes(std::vector<int64_t>& times) {
+  std::sort(times.begin(), times.end());
+  int64_t min = times[0];
+  int64_t max = times[times.size() - 1];
+  double mean =
+      static_cast<double>(std::accumulate(times.begin(), times.end(), 0)) /
+      times.size();
+  double sq_sum =
+      std::inner_product(times.begin(), times.end(), times.begin(), 0);
+  double stdev = std::sqrt(sq_sum / times.size() - mean * mean);
+
+  fmt::print("min: {} max: {}, mean: {}, stdev: {}\n", min, max, mean, stdev);
+  fmt::print("min 10: {}\n", fmt::join(times.begin(), times.begin() + 10, ","));
+  fmt::print("max 10: {}\n", fmt::join(times.end() - 10, times.end(), ","));
+}
+
+// benchmark
+void bench() {
+  // set up instances
+  auto client = nt::CreateInstance();
+  auto server = nt::CreateInstance();
+
+  // connect client and server
+  nt::StartServer(server, "bench.json", "127.0.0.1", 0, 10000);
+  nt::StartClient4(client, "client");
+  nt::SetServer(client, "127.0.0.1", 10000);
+
+  using namespace std::chrono_literals;
+  std::this_thread::sleep_for(1s);
+
+  // add "typical" set of subscribers on client and server
+  nt::SubscribeMultiple(client, {{std::string_view{}}});
+  nt::Subscribe(nt::GetTopic(client, "highrate"), NT_DOUBLE, "double",
+                {.sendAll = true, .keepDuplicates = true});
+  nt::SubscribeMultiple(server, {{std::string_view{}}});
+  auto pub = nt::Publish(nt::GetTopic(server, "highrate"), NT_DOUBLE, "double");
+  nt::SetDouble(pub, 0);
+
+  // warm up
+  for (int i = 1; i <= 10000; ++i) {
+    nt::SetDouble(pub, i * 0.01);
+    if (i % 2000 == 0) {
+      std::this_thread::sleep_for(0.02s);
+    }
+  }
+
+  std::vector<int64_t> flushTimes;
+  flushTimes.reserve(100);
+
+  std::vector<int64_t> times;
+  times.reserve(100001);
+
+  // benchmark
+  auto start = std::chrono::high_resolution_clock::now();
+  int64_t now = nt::Now();
+  for (int i = 1; i <= 100000; ++i) {
+    nt::SetDouble(pub, i * 0.01, now);
+    int64_t prev = now;
+    now = nt::Now();
+    times.emplace_back(now - prev);
+    if (i % 2000 == 0) {
+      nt::Flush(server);
+      flushTimes.emplace_back(nt::Now() - now);
+      std::this_thread::sleep_for(0.02s);
+      now = nt::Now();
+    }
+  }
+  auto stop = std::chrono::high_resolution_clock::now();
+
+  fmt::print("total time: {}us\n",
+             std::chrono::duration_cast<std::chrono::microseconds>(stop - start)
+                 .count());
+  PrintTimes(times);
+  fmt::print("-- Flush --\n");
+  PrintTimes(flushTimes);
 }
diff --git a/third_party/allwpilib/ntcore/src/generate/cpp/jni/types_jni.cpp.jinja b/third_party/allwpilib/ntcore/src/generate/cpp/jni/types_jni.cpp.jinja
new file mode 100644
index 0000000..a105278
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/generate/cpp/jni/types_jni.cpp.jinja
@@ -0,0 +1,245 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <jni.h>
+
+#include <wpi/jni_util.h>
+
+#include "edu_wpi_first_networktables_NetworkTablesJNI.h"
+#include "ntcore.h"
+
+using namespace wpi::java;
+
+//
+// Globals and load/unload
+//
+{% for t in types %}
+static JClass timestamped{{ t.TypeName }}Cls;
+{%- endfor %}
+{%- for t in types %}
+{%- if t.jni.ToJavaArray == "MakeJObjectArray" %}
+static JClass {{ t.jni.jtype }}Cls;
+{%- endif %}
+{%- endfor %}
+static JException nullPointerEx;
+
+static const JClassInit classes[] = {
+{%- for t in types %}
+    {"edu/wpi/first/networktables/Timestamped{{ t.TypeName }}", &timestamped{{ t.TypeName }}Cls},
+{%- endfor %}
+{%- for t in types %}
+{%- if t.jni.ToJavaArray == "MakeJObjectArray" %}
+    {"{{ t.jni.jtypestr }}", &{{ t.jni.jtype }}Cls},
+{%- endif %}
+{%- endfor %}
+};
+
+static const JExceptionInit exceptions[] = {
+    {"java/lang/NullPointerException", &nullPointerEx},
+};
+
+namespace nt {
+
+bool JNI_LoadTypes(JNIEnv* env) {
+  // Cache references to classes
+  for (auto& c : classes) {
+    *c.cls = JClass(env, c.name);
+    if (!*c.cls) {
+      return false;
+    }
+  }
+
+  for (auto& c : exceptions) {
+    *c.cls = JException(env, c.name);
+    if (!*c.cls) {
+      return false;
+    }
+  }
+
+  return true;
+}
+
+void JNI_UnloadTypes(JNIEnv* env) {
+  // Delete global references
+  for (auto& c : classes) {
+    c.cls->free(env);
+  }
+}
+
+}  // namespace nt
+
+static std::vector<int> FromJavaBooleanArray(JNIEnv* env, jbooleanArray jarr) {
+  CriticalJBooleanArrayRef ref{env, jarr};
+  if (!ref) {
+    return {};
+  }
+  std::span<const jboolean> elements{ref};
+  size_t len = elements.size();
+  std::vector<int> arr;
+  arr.reserve(len);
+  for (size_t i = 0; i < len; ++i) {
+    arr.push_back(elements[i]);
+  }
+  return arr;
+}
+
+static std::vector<std::string> FromJavaStringArray(JNIEnv* env, jobjectArray jarr) {
+  size_t len = env->GetArrayLength(jarr);
+  std::vector<std::string> arr;
+  arr.reserve(len);
+  for (size_t i = 0; i < len; ++i) {
+    JLocal<jstring> elem{
+        env, static_cast<jstring>(env->GetObjectArrayElement(jarr, i))};
+    if (!elem) {
+      return {};
+    }
+    arr.emplace_back(JStringRef{env, elem}.str());
+  }
+  return arr;
+}
+
+{% for t in types %}
+static jobject MakeJObject(JNIEnv* env, nt::Timestamped{{ t.TypeName }} value) {
+  static jmethodID constructor = env->GetMethodID(
+      timestamped{{ t.TypeName }}Cls, "<init>", "(JJ{{ t.jni.jtypestr }})V");
+{%- if t.jni.JavaObject %}
+  JLocal<{{ t.jni.jtype }}> val{env, {{ t.jni.ToJavaBegin }}value.value{{ t.jni.ToJavaEnd }}};
+  return env->NewObject(timestamped{{ t.TypeName }}Cls, constructor,
+                        static_cast<jlong>(value.time),
+                        static_cast<jlong>(value.serverTime), val.obj());
+{%- else %}
+  return env->NewObject(timestamped{{ t.TypeName }}Cls, constructor,
+                        static_cast<jlong>(value.time),
+                        static_cast<jlong>(value.serverTime),
+                        {{ t.jni.ToJavaBegin }}value.value{{ t.jni.ToJavaEnd }});
+{%- endif %}
+}
+{% endfor %}
+{%- for t in types %}
+static jobjectArray MakeJObject(JNIEnv* env,
+                                std::span<const nt::Timestamped{{ t.TypeName }}> arr) {
+  jobjectArray jarr =
+      env->NewObjectArray(arr.size(), timestamped{{ t.TypeName }}Cls, nullptr);
+  if (!jarr) {
+    return nullptr;
+  }
+  for (size_t i = 0; i < arr.size(); ++i) {
+    JLocal<jobject> elem{env, MakeJObject(env, arr[i])};
+    env->SetObjectArrayElement(jarr, i, elem.obj());
+  }
+  return jarr;
+}
+{% endfor %}
+{%- for t in types %}
+{%- if t.jni.ToJavaArray == "MakeJObjectArray" %}
+static jobjectArray MakeJObjectArray(JNIEnv* env, std::span<const {{ t.cpp.ValueType }}> arr) {
+  jobjectArray jarr =
+      env->NewObjectArray(arr.size(), {{ t.jni.jtype }}Cls, nullptr);
+  if (!jarr) {
+    return nullptr;
+  }
+  for (size_t i = 0; i < arr.size(); ++i) {
+    JLocal<jobject> elem{env, {{ t.jni.ToJavaBegin }}arr[i]{{ t.jni.ToJavaEnd }}};
+    env->SetObjectArrayElement(jarr, i, elem.obj());
+  }
+  return jarr;
+}
+{% endif %}
+{%- endfor %}
+
+extern "C" {
+{% for t in types %}
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    getAtomic{{ t.TypeName }}
+ * Signature: (I{{ t.jni.jtypestr }})Ledu/wpi/first/networktables/Timestamped{{ t.TypeName }};
+ */
+JNIEXPORT jobject JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getAtomic{{ t.TypeName }}
+  (JNIEnv* env, jclass, jint subentry, {{ t.jni.jtype }} defaultValue)
+{
+  return MakeJObject(env, nt::GetAtomic{{ t.TypeName }}(subentry, {{ t.jni.FromJavaBegin }}defaultValue{{ t.jni.FromJavaEnd }}));
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    readQueue{{ t.TypeName }}
+ * Signature: (I)[Ledu/wpi/first/networktables/Timestamped{{ t.TypeName }};
+ */
+JNIEXPORT jobjectArray JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_readQueue{{ t.TypeName }}
+  (JNIEnv* env, jclass, jint subentry)
+{
+  return MakeJObject(env, nt::ReadQueue{{ t.TypeName }}(subentry));
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    readQueueValues{{ t.TypeName }}
+ * Signature: (I)[{{ t.jni.jtypestr }}
+ */
+JNIEXPORT {% if t.jni.JavaObject %}jobject{% else %}{{ t.jni.jtype }}{% endif %}Array JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_readQueueValues{{ t.TypeName }}
+  (JNIEnv* env, jclass, jint subentry)
+{
+  return {{ t.jni.ToJavaArray }}(env, nt::ReadQueueValues{{ t.TypeName }}(subentry));
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    set{{ t.TypeName }}
+ * Signature: (IJ{{ t.jni.jtypestr }})Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_set{{ t.TypeName }}
+  (JNIEnv*{% if t.jni.JavaObject %} env{% endif %}, jclass, jint entry, jlong time, {{ t.jni.jtype }} value)
+{
+{%- if t.jni.JavaObject %}
+  if (!value) {
+    nullPointerEx.Throw(env, "value cannot be null");
+    return false;
+  }
+{%- endif %}
+  return nt::Set{{ t.TypeName }}(entry, {{ t.jni.FromJavaBegin }}value{{ t.jni.FromJavaEnd }}, time);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    get{{ t.TypeName }}
+ * Signature: (I{{ t.jni.jtypestr }}){{ t.jni.jtypestr }}
+ */
+JNIEXPORT {{ t.jni.jtype }} JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_get{{ t.TypeName }}
+  (JNIEnv*{% if t.jni.JavaObject %} env{% endif %}, jclass, jint entry, {{ t.jni.jtype }} defaultValue)
+{
+{%- if t.jni.JavaObject %}
+  auto val = nt::GetEntryValue(entry);
+  if (!val || !val.Is{{ t.TypeName }}()) {
+    return defaultValue;
+  }
+  return {{ t.jni.ToJavaBegin }}val.Get{{ t.TypeName }}(){{ t.jni.ToJavaEnd }};
+{%- else %}
+  return nt::Get{{ t.TypeName }}(entry, defaultValue);
+{%- endif %}
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    setDefault{{ t.TypeName }}
+ * Signature: (IJ{{ t.jni.jtypestr }})Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_setDefault{{ t.TypeName }}
+  (JNIEnv*{% if t.jni.JavaObject %} env{% endif %}, jclass, jint entry, jlong, {{ t.jni.jtype }} defaultValue)
+{
+{%- if t.jni.JavaObject %}
+  if (!defaultValue) {
+    nullPointerEx.Throw(env, "defaultValue cannot be null");
+    return false;
+  }
+{%- endif %}
+  return nt::SetDefault{{ t.TypeName }}(entry, {{ t.jni.FromJavaBegin }}defaultValue{{ t.jni.FromJavaEnd }});
+}
+{% endfor %}
+}  // extern "C"
diff --git a/third_party/allwpilib/ntcore/src/generate/cpp/ntcore_c_types.cpp.jinja b/third_party/allwpilib/ntcore/src/generate/cpp/ntcore_c_types.cpp.jinja
new file mode 100644
index 0000000..e74e5cf
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/generate/cpp/ntcore_c_types.cpp.jinja
@@ -0,0 +1,106 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "ntcore_c_types.h"
+
+#include "Value_internal.h"
+#include "ntcore_cpp.h"
+
+using namespace nt;
+
+template <typename T>
+static inline std::span<const T> ConvertFromC(const T* arr, size_t size) {
+  return {arr, size};
+}
+
+static inline std::string_view ConvertFromC(const char* arr, size_t size) {
+  return {arr, size};
+}
+
+static std::vector<std::string> ConvertFromC(const NT_String* arr, size_t size) {
+  std::vector<std::string> v;
+  v.reserve(size);
+  for (size_t i = 0; i < size; ++i) {
+    v.emplace_back(ConvertFromC(arr[i]));
+  }
+  return v;
+}
+
+{% for t in types %}
+static void ConvertToC(const nt::Timestamped{{ t.TypeName }}& in, NT_Timestamped{{ t.TypeName }}* out) {
+  out->time = in.time;
+  out->serverTime = in.serverTime;
+{%- if t.c.IsArray %}
+  out->value = ConvertToC<{{ t.c.ValueType[:-1] }}>(in.value, &out->len);
+{% else %}
+  out->value = in.value;
+{% endif -%}
+}
+{% endfor %}
+
+extern "C" {
+{% for t in types %}
+NT_Bool NT_Set{{ t.TypeName }}(NT_Handle pubentry, int64_t time, {{ t.c.ParamType }} value{% if t.c.IsArray %}, size_t len{% endif %}) {
+{%- if t.c.IsArray %}
+  return nt::Set{{ t.TypeName }}(pubentry, ConvertFromC(value, len), time);
+{%- else %}
+  return nt::Set{{ t.TypeName }}(pubentry, value, time);
+{%- endif %}
+}
+
+NT_Bool NT_SetDefault{{ t.TypeName }}(NT_Handle pubentry, {{ t.c.ParamType }} defaultValue{% if t.c.IsArray %}, size_t defaultValueLen{% endif %}) {
+{%- if t.c.IsArray %}
+  return nt::SetDefault{{ t.TypeName }}(pubentry, ConvertFromC(defaultValue, defaultValueLen));
+{%- else %}
+  return nt::SetDefault{{ t.TypeName }}(pubentry, defaultValue);
+{%- endif %}
+}
+
+{{ t.c.ValueType }} NT_Get{{ t.TypeName }}(NT_Handle subentry, {{ t.c.ParamType }} defaultValue{% if t.c.IsArray %}, size_t defaultValueLen, size_t* len{% endif %}) {
+{%- if t.c.IsArray %}
+  auto cppValue = nt::Get{{ t.TypeName }}(subentry, ConvertFromC(defaultValue, defaultValueLen));
+  return ConvertToC<{{ t.c.ValueType[:-1] }}>(cppValue, len);
+{%- else %}
+  return nt::Get{{ t.TypeName }}(subentry, defaultValue);
+{%- endif %}
+}
+
+void NT_GetAtomic{{ t.TypeName }}(NT_Handle subentry, {{ t.c.ParamType }} defaultValue{% if t.c.IsArray %}, size_t defaultValueLen{% endif %}, struct NT_Timestamped{{ t.TypeName }}* value) {
+{%- if t.c.IsArray %}
+  auto cppValue = nt::GetAtomic{{ t.TypeName }}(subentry, ConvertFromC(defaultValue, defaultValueLen));
+{%- else %}
+  auto cppValue = nt::GetAtomic{{ t.TypeName }}(subentry, defaultValue);
+{%- endif %}
+  ConvertToC(cppValue, value);
+}
+
+void NT_DisposeTimestamped{{ t.TypeName }}(struct NT_Timestamped{{ t.TypeName }}* value) {
+{%- if t.TypeName == "StringArray" %}
+  NT_FreeStringArray(value->value, value->len);
+{%- elif t.c.IsArray %}
+  std::free(value->value);
+{%- endif %}
+}
+
+struct NT_Timestamped{{ t.TypeName }}* NT_ReadQueue{{ t.TypeName }}(NT_Handle subentry, size_t* len) {
+  auto arr = nt::ReadQueue{{ t.TypeName }}(subentry);
+  return ConvertToC<NT_Timestamped{{ t.TypeName }}>(arr, len);
+}
+
+void NT_FreeQueue{{ t.TypeName }}(struct NT_Timestamped{{ t.TypeName }}* arr, size_t len) {
+  for (size_t i = 0; i < len; ++i) {
+    NT_DisposeTimestamped{{ t.TypeName }}(&arr[i]);
+  }
+  std::free(arr);
+}
+
+{%- if not t.c.IsArray %}
+{{ t.c.ValueType }}* NT_ReadQueueValues{{ t.TypeName }}(NT_Handle subentry, size_t* len) {
+  auto arr = nt::ReadQueueValues{{ t.TypeName }}(subentry);
+  return ConvertToC<{{ t.c.ValueType }}>(arr, len);
+}
+{%- endif %}
+
+{% endfor %}
+}  // extern "C"
diff --git a/third_party/allwpilib/ntcore/src/generate/cpp/ntcore_cpp_types.cpp.jinja b/third_party/allwpilib/ntcore/src/generate/cpp/ntcore_cpp_types.cpp.jinja
new file mode 100644
index 0000000..ba8bca7
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/generate/cpp/ntcore_cpp_types.cpp.jinja
@@ -0,0 +1,76 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "ntcore_cpp_types.h"
+
+#include "Handle.h"
+#include "InstanceImpl.h"
+
+namespace nt {
+{% for t in types %}
+bool Set{{ t.TypeName }}(NT_Handle pubentry, {{ t.cpp.ParamType }} value, int64_t time) {
+  if (auto ii = InstanceImpl::Get(Handle{pubentry}.GetInst())) {
+    return ii->localStorage.SetEntryValue(pubentry,
+        Value::Make{{ t.TypeName }}(value, time == 0 ? Now() : time));
+  } else {
+    return {};
+  }
+}
+
+bool SetDefault{{ t.TypeName }}(NT_Handle pubentry, {{ t.cpp.ParamType }} defaultValue) {
+  if (auto ii = InstanceImpl::Get(Handle{pubentry}.GetInst())) {
+    return ii->localStorage.SetDefaultEntryValue(pubentry,
+        Value::Make{{ t.TypeName }}(defaultValue, 1));
+  } else {
+    return {};
+  }
+}
+
+{{ t.cpp.ValueType }} Get{{ t.TypeName }}(NT_Handle subentry, {{ t.cpp.ParamType }} defaultValue) {
+  return GetAtomic{{ t.TypeName }}(subentry, defaultValue).value;
+}
+
+Timestamped{{ t.TypeName }} GetAtomic{{ t.TypeName }}(NT_Handle subentry, {{ t.cpp.ParamType }} defaultValue) {
+  if (auto ii = InstanceImpl::Get(Handle{subentry}.GetInst())) {
+    return ii->localStorage.GetAtomic{{ t.TypeName }}(subentry, defaultValue);
+  } else {
+    return {};
+  }
+}
+
+std::vector<Timestamped{{ t.TypeName }}> ReadQueue{{ t.TypeName }}(NT_Handle subentry) {
+  if (auto ii = InstanceImpl::Get(Handle{subentry}.GetInst())) {
+    return ii->localStorage.ReadQueue{{ t.TypeName }}(subentry);
+  } else {
+    return {};
+  }
+}
+
+std::vector<{% if t.cpp.ValueType == "bool" %}int{% else %}{{ t.cpp.ValueType }}{% endif %}> ReadQueueValues{{ t.TypeName }}(NT_Handle subentry) {
+  std::vector<{% if t.cpp.ValueType == "bool" %}int{% else %}{{ t.cpp.ValueType }}{% endif %}> rv;
+  auto arr = ReadQueue{{ t.TypeName }}(subentry);
+  rv.reserve(arr.size());
+  for (auto&& elem : arr) {
+    rv.emplace_back(std::move(elem.value));
+  }
+  return rv;
+}
+{% if t.cpp.SmallRetType and t.cpp.SmallElemType %}
+{{ t.cpp.SmallRetType }} Get{{ t.TypeName }}(NT_Handle subentry, wpi::SmallVectorImpl<{{ t.cpp.SmallElemType }}>& buf, {{ t.cpp.ParamType }} defaultValue) {
+  return GetAtomic{{ t.TypeName }}(subentry, buf, defaultValue).value;
+}
+
+Timestamped{{ t.TypeName }}View GetAtomic{{ t.TypeName }}(
+    NT_Handle subentry,
+    wpi::SmallVectorImpl<{{ t.cpp.SmallElemType }}>& buf,
+    {{ t.cpp.ParamType }} defaultValue) {
+  if (auto ii = InstanceImpl::Get(Handle{subentry}.GetInst())) {
+    return ii->localStorage.GetAtomic{{ t.TypeName }}(subentry, buf, defaultValue);
+  } else {
+    return {};
+  }
+}
+{% endif %}
+{% endfor %}
+}  // namespace nt
diff --git a/third_party/allwpilib/ntcore/src/generate/include/networktables/Topic.h.jinja b/third_party/allwpilib/ntcore/src/generate/include/networktables/Topic.h.jinja
new file mode 100644
index 0000000..84e80ec
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/generate/include/networktables/Topic.h.jinja
@@ -0,0 +1,436 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <stdint.h>
+
+{{ cpp.INCLUDES }}
+#include <span>
+#include <string_view>
+#include <vector>
+
+#include "networktables/Topic.h"
+
+namespace wpi {
+template <typename T>
+class SmallVectorImpl;
+class json;
+}  // namespace wpi
+
+namespace nt {
+
+class {{ TypeName }}Topic;
+
+/**
+ * NetworkTables {{ TypeName }} subscriber.
+ */
+class {{ TypeName }}Subscriber : public Subscriber {
+ public:
+  using TopicType = {{ TypeName }}Topic;
+  using ValueType = {{ cpp.ValueType }};
+  using ParamType = {{ cpp.ParamType }};
+  using TimestampedValueType = Timestamped{{ TypeName }};
+{% if cpp.SmallRetType and cpp.SmallElemType %}
+  using SmallRetType = {{ cpp.SmallRetType }};
+  using SmallElemType = {{ cpp.SmallElemType }};
+  using TimestampedValueViewType = Timestamped{{ TypeName }}View;
+{% endif %}
+
+  {{ TypeName }}Subscriber() = default;
+
+  /**
+   * Construct from a subscriber handle; recommended to use
+   * {{TypeName}}Topic::Subscribe() instead.
+   *
+   * @param handle Native handle
+   * @param defaultValue Default value
+   */
+  {{ TypeName }}Subscriber(NT_Subscriber handle, ParamType defaultValue);
+
+  /**
+   * Get the last published value.
+   * If no value has been published, returns the stored default value.
+   *
+   * @return value
+   */
+  ValueType Get() const;
+
+  /**
+   * Get the last published value.
+   * If no value has been published, returns the passed defaultValue.
+   *
+   * @param defaultValue default value to return if no value has been published
+   * @return value
+   */
+  ValueType Get(ParamType defaultValue) const;
+{% if cpp.SmallRetType and cpp.SmallElemType %}
+  /**
+   * Get the last published value.
+   * If no value has been published, returns the stored default value.
+   *
+   * @param buf storage for returned value
+   * @return value
+   */
+  SmallRetType Get(wpi::SmallVectorImpl<SmallElemType>& buf) const;
+
+  /**
+   * Get the last published value.
+   * If no value has been published, returns the passed defaultValue.
+   *
+   * @param buf storage for returned value
+   * @param defaultValue default value to return if no value has been published
+   * @return value
+   */
+  SmallRetType Get(wpi::SmallVectorImpl<SmallElemType>& buf, ParamType defaultValue) const;
+{% endif %}
+  /**
+   * Get the last published value along with its timestamp
+   * If no value has been published, returns the stored default value and a
+   * timestamp of 0.
+   *
+   * @return timestamped value
+   */
+  TimestampedValueType GetAtomic() const;
+
+  /**
+   * Get the last published value along with its timestamp.
+   * If no value has been published, returns the passed defaultValue and a
+   * timestamp of 0.
+   *
+   * @param defaultValue default value to return if no value has been published
+   * @return timestamped value
+   */
+  TimestampedValueType GetAtomic(ParamType defaultValue) const;
+{% if cpp.SmallRetType and cpp.SmallElemType %}
+  /**
+   * Get the last published value along with its timestamp.
+   * If no value has been published, returns the stored default value and a
+   * timestamp of 0.
+   *
+   * @param buf storage for returned value
+   * @return timestamped value
+   */
+  TimestampedValueViewType GetAtomic(
+      wpi::SmallVectorImpl<SmallElemType>& buf) const;
+
+  /**
+   * Get the last published value along with its timestamp.
+   * If no value has been published, returns the passed defaultValue and a
+   * timestamp of 0.
+   *
+   * @param buf storage for returned value
+   * @param defaultValue default value to return if no value has been published
+   * @return timestamped value
+   */
+  TimestampedValueViewType GetAtomic(
+      wpi::SmallVectorImpl<SmallElemType>& buf,
+      ParamType defaultValue) const;
+{% endif %}
+  /**
+   * Get an array of all value changes since the last call to ReadQueue.
+   * Also provides a timestamp for each value.
+   *
+   * @note The "poll storage" subscribe option can be used to set the queue
+   *     depth.
+   *
+   * @return Array of timestamped values; empty array if no new changes have
+   *     been published since the previous call.
+   */
+  std::vector<TimestampedValueType> ReadQueue();
+
+  /**
+   * Get the corresponding topic.
+   *
+   * @return Topic
+   */
+  TopicType GetTopic() const;
+
+ private:
+  ValueType m_defaultValue;
+};
+
+/**
+ * NetworkTables {{ TypeName }} publisher.
+ */
+class {{ TypeName }}Publisher : public Publisher {
+ public:
+  using TopicType = {{ TypeName }}Topic;
+  using ValueType = {{ cpp.ValueType }};
+  using ParamType = {{ cpp.ParamType }};
+{% if cpp.SmallRetType and cpp.SmallElemType %}
+  using SmallRetType = {{ cpp.SmallRetType }};
+  using SmallElemType = {{ cpp.SmallElemType }};
+{% endif %}
+  using TimestampedValueType = Timestamped{{ TypeName }};
+
+  {{ TypeName }}Publisher() = default;
+
+  /**
+   * Construct from a publisher handle; recommended to use
+   * {{TypeName}}Topic::Publish() instead.
+   *
+   * @param handle Native handle
+   */
+  explicit {{ TypeName }}Publisher(NT_Publisher handle);
+
+  /**
+   * Publish a new value.
+   *
+   * @param value value to publish
+   * @param time timestamp; 0 indicates current NT time should be used
+   */
+  void Set(ParamType value, int64_t time = 0);
+
+  /**
+   * Publish a default value.
+   * On reconnect, a default value will never be used in preference to a
+   * published value.
+   *
+   * @param value value
+   */
+  void SetDefault(ParamType value);
+
+  /**
+   * Get the corresponding topic.
+   *
+   * @return Topic
+   */
+  TopicType GetTopic() const;
+};
+
+/**
+ * NetworkTables {{ TypeName }} entry.
+ *
+ * @note Unlike NetworkTableEntry, the entry goes away when this is destroyed.
+ */
+class {{ TypeName }}Entry final : public {{ TypeName }}Subscriber,
+                                  public {{ TypeName }}Publisher {
+ public:
+  using SubscriberType = {{ TypeName }}Subscriber;
+  using PublisherType = {{ TypeName }}Publisher;
+  using TopicType = {{ TypeName }}Topic;
+  using ValueType = {{ cpp.ValueType }};
+  using ParamType = {{ cpp.ParamType }};
+{% if cpp.SmallRetType and cpp.SmallElemType %}
+  using SmallRetType = {{ cpp.SmallRetType }};
+  using SmallElemType = {{ cpp.SmallElemType }};
+{% endif %}
+  using TimestampedValueType = Timestamped{{ TypeName }};
+
+  {{ TypeName }}Entry() = default;
+
+  /**
+   * Construct from an entry handle; recommended to use
+   * {{TypeName}}Topic::GetEntry() instead.
+   *
+   * @param handle Native handle
+   * @param defaultValue Default value
+   */
+  {{ TypeName }}Entry(NT_Entry handle, ParamType defaultValue);
+
+  /**
+   * Determines if the native handle is valid.
+   *
+   * @return True if the native handle is valid, false otherwise.
+   */
+  explicit operator bool() const { return m_subHandle != 0; }
+
+  /**
+   * Gets the native handle for the entry.
+   *
+   * @return Native handle
+   */
+  NT_Entry GetHandle() const { return m_subHandle; }
+
+  /**
+   * Get the corresponding topic.
+   *
+   * @return Topic
+   */
+  TopicType GetTopic() const;
+
+  /**
+   * Stops publishing the entry if it's published.
+   */
+  void Unpublish();
+};
+
+/**
+ * NetworkTables {{ TypeName }} topic.
+ */
+class {{ TypeName }}Topic final : public Topic {
+ public:
+  using SubscriberType = {{ TypeName }}Subscriber;
+  using PublisherType = {{ TypeName }}Publisher;
+  using EntryType = {{ TypeName }}Entry;
+  using ValueType = {{ cpp.ValueType }};
+  using ParamType = {{ cpp.ParamType }};
+  using TimestampedValueType = Timestamped{{ TypeName }};
+{%- if TypeString %}
+  /** The default type string for this topic type. */
+  static constexpr std::string_view kTypeString = {{ TypeString }};
+{%- endif %}
+
+  {{ TypeName }}Topic() = default;
+
+  /**
+   * Construct from a topic handle; recommended to use
+   * NetworkTableInstance::Get{{TypeName}}Topic() instead.
+   *
+   * @param handle Native handle
+   */
+  explicit {{ TypeName }}Topic(NT_Topic handle) : Topic{handle} {}
+
+  /**
+   * Construct from a generic topic.
+   *
+   * @param topic Topic
+   */
+  explicit {{ TypeName }}Topic(Topic topic) : Topic{topic} {}
+
+  /**
+   * Create a new subscriber to the topic.
+   *
+   * <p>The subscriber is only active as long as the returned object
+   * is not destroyed.
+   *
+   * @note Subscribers that do not match the published data type do not return
+   *     any values. To determine if the data type matches, use the appropriate
+   *     Topic functions.
+   *
+{%- if not TypeString %}
+   * @param typeString type string
+{% endif %}
+   * @param defaultValue default value used when a default is not provided to a
+   *        getter function
+   * @param options subscribe options
+   * @return subscriber
+   */
+  [[nodiscard]]
+  SubscriberType Subscribe(
+      {% if not TypeString %}std::string_view typeString, {% endif %}ParamType defaultValue,
+      const PubSubOptions& options = kDefaultPubSubOptions);
+{%- if TypeString %}
+  /**
+   * Create a new subscriber to the topic, with specific type string.
+   *
+   * <p>The subscriber is only active as long as the returned object
+   * is not destroyed.
+   *
+   * @note Subscribers that do not match the published data type do not return
+   *     any values. To determine if the data type matches, use the appropriate
+   *     Topic functions.
+   *
+   * @param typeString type string
+   * @param defaultValue default value used when a default is not provided to a
+   *        getter function
+   * @param options subscribe options
+   * @return subscriber
+   */
+  [[nodiscard]]
+  SubscriberType SubscribeEx(
+      std::string_view typeString, ParamType defaultValue,
+      const PubSubOptions& options = kDefaultPubSubOptions);
+{% endif %}
+  /**
+   * Create a new publisher to the topic.
+   *
+   * The publisher is only active as long as the returned object
+   * is not destroyed.
+   *
+   * @note It is not possible to publish two different data types to the same
+   *     topic. Conflicts between publishers are typically resolved by the
+   *     server on a first-come, first-served basis. Any published values that
+   *     do not match the topic's data type are dropped (ignored). To determine
+   *     if the data type matches, use the appropriate Topic functions.
+   *
+{%- if not TypeString %}
+   * @param typeString type string
+{% endif %}
+   * @param options publish options
+   * @return publisher
+   */
+  [[nodiscard]]
+  PublisherType Publish({% if not TypeString %}std::string_view typeString, {% endif %}const PubSubOptions& options = kDefaultPubSubOptions);
+
+  /**
+   * Create a new publisher to the topic, with type string and initial
+   * properties.
+   *
+   * The publisher is only active as long as the returned object
+   * is not destroyed.
+   *
+   * @note It is not possible to publish two different data types to the same
+   *     topic. Conflicts between publishers are typically resolved by the
+   *     server on a first-come, first-served basis. Any published values that
+   *     do not match the topic's data type are dropped (ignored). To determine
+   *     if the data type matches, use the appropriate Topic functions.
+   *
+   * @param typeString type string
+   * @param properties JSON properties
+   * @param options publish options
+   * @return publisher
+   */
+  [[nodiscard]]
+  PublisherType PublishEx(std::string_view typeString,
+    const wpi::json& properties, const PubSubOptions& options = kDefaultPubSubOptions);
+
+  /**
+   * Create a new entry for the topic.
+   *
+   * Entries act as a combination of a subscriber and a weak publisher. The
+   * subscriber is active as long as the entry is not destroyed. The publisher
+   * is created when the entry is first written to, and remains active until
+   * either Unpublish() is called or the entry is destroyed.
+   *
+   * @note It is not possible to use two different data types with the same
+   *     topic. Conflicts between publishers are typically resolved by the
+   *     server on a first-come, first-served basis. Any published values that
+   *     do not match the topic's data type are dropped (ignored), and the entry
+   *     will show no new values if the data type does not match. To determine
+   *     if the data type matches, use the appropriate Topic functions.
+   *
+{%- if not TypeString %}
+   * @param typeString type string
+{% endif %}
+   * @param defaultValue default value used when a default is not provided to a
+   *        getter function
+   * @param options publish and/or subscribe options
+   * @return entry
+   */
+  [[nodiscard]]
+  EntryType GetEntry({% if not TypeString %}std::string_view typeString, {% endif %}ParamType defaultValue,
+                     const PubSubOptions& options = kDefaultPubSubOptions);
+{%- if TypeString %}
+  /**
+   * Create a new entry for the topic, with specific type string.
+   *
+   * Entries act as a combination of a subscriber and a weak publisher. The
+   * subscriber is active as long as the entry is not destroyed. The publisher
+   * is created when the entry is first written to, and remains active until
+   * either Unpublish() is called or the entry is destroyed.
+   *
+   * @note It is not possible to use two different data types with the same
+   *     topic. Conflicts between publishers are typically resolved by the
+   *     server on a first-come, first-served basis. Any published values that
+   *     do not match the topic's data type are dropped (ignored), and the entry
+   *     will show no new values if the data type does not match. To determine
+   *     if the data type matches, use the appropriate Topic functions.
+   *
+   * @param typeString type string
+   * @param defaultValue default value used when a default is not provided to a
+   *        getter function
+   * @param options publish and/or subscribe options
+   * @return entry
+   */
+  [[nodiscard]]
+  EntryType GetEntryEx(std::string_view typeString, ParamType defaultValue,
+                       const PubSubOptions& options = kDefaultPubSubOptions);
+{% endif %}
+};
+
+}  // namespace nt
+
+#include "networktables/{{ TypeName }}Topic.inc"
diff --git a/third_party/allwpilib/ntcore/src/generate/include/networktables/Topic.inc.jinja b/third_party/allwpilib/ntcore/src/generate/include/networktables/Topic.inc.jinja
new file mode 100644
index 0000000..4e7a167
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/generate/include/networktables/Topic.inc.jinja
@@ -0,0 +1,135 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include "networktables/{{ TypeName }}Topic.h"
+#include "networktables/NetworkTableType.h"
+#include "ntcore_cpp.h"
+
+namespace nt {
+
+inline {{ TypeName }}Subscriber::{{ TypeName }}Subscriber(
+    NT_Subscriber handle, {{ cpp.ParamType }} defaultValue)
+    : Subscriber{handle},
+      m_defaultValue{{ '{' }}{{ cpp.DefaultValueCopy|default('defaultValue') }}} {}
+
+inline {{ cpp.ValueType }} {{ TypeName }}Subscriber::Get() const {
+  return Get(m_defaultValue);
+}
+
+inline {{ cpp.ValueType }} {{ TypeName }}Subscriber::Get(
+    {{ cpp.ParamType }} defaultValue) const {
+  return ::nt::Get{{ TypeName }}(m_subHandle, defaultValue);
+}
+{% if cpp.SmallRetType and cpp.SmallElemType %}
+inline {{ cpp.SmallRetType }} {{ TypeName }}Subscriber::Get(wpi::SmallVectorImpl<{{ cpp.SmallElemType }}>& buf) const {
+  return Get(buf, m_defaultValue);
+}
+
+inline {{ cpp.SmallRetType }} {{ TypeName }}Subscriber::Get(wpi::SmallVectorImpl<{{ cpp.SmallElemType }}>& buf, {{ cpp.ParamType }} defaultValue) const {
+  return nt::Get{{ TypeName }}(m_subHandle, buf, defaultValue);
+}
+{% endif %}
+inline Timestamped{{ TypeName }} {{ TypeName }}Subscriber::GetAtomic() const {
+  return GetAtomic(m_defaultValue);
+}
+
+inline Timestamped{{ TypeName }} {{ TypeName }}Subscriber::GetAtomic(
+    {{ cpp.ParamType }} defaultValue) const {
+  return ::nt::GetAtomic{{ TypeName }}(m_subHandle, defaultValue);
+}
+{% if cpp.SmallRetType and cpp.SmallElemType %}
+inline Timestamped{{ TypeName }}View {{ TypeName }}Subscriber::GetAtomic(wpi::SmallVectorImpl<{{ cpp.SmallElemType }}>& buf) const {
+  return GetAtomic(buf, m_defaultValue);
+}
+
+inline Timestamped{{ TypeName }}View {{ TypeName }}Subscriber::GetAtomic(wpi::SmallVectorImpl<{{ cpp.SmallElemType }}>& buf, {{ cpp.ParamType }} defaultValue) const {
+  return nt::GetAtomic{{ TypeName }}(m_subHandle, buf, defaultValue);
+}
+{% endif %}
+inline std::vector<Timestamped{{ TypeName }}>
+{{ TypeName }}Subscriber::ReadQueue() {
+  return ::nt::ReadQueue{{ TypeName }}(m_subHandle);
+}
+
+inline {{ TypeName }}Topic {{ TypeName }}Subscriber::GetTopic() const {
+  return {{ TypeName }}Topic{::nt::GetTopicFromHandle(m_subHandle)};
+}
+
+inline {{ TypeName }}Publisher::{{ TypeName }}Publisher(NT_Publisher handle)
+    : Publisher{handle} {}
+
+inline void {{ TypeName }}Publisher::Set({{ cpp.ParamType }} value,
+                                         int64_t time) {
+  ::nt::Set{{ TypeName }}(m_pubHandle, value, time);
+}
+
+inline void {{ TypeName }}Publisher::SetDefault({{ cpp.ParamType }} value) {
+  ::nt::SetDefault{{ TypeName }}(m_pubHandle, value);
+}
+
+inline {{ TypeName }}Topic {{ TypeName }}Publisher::GetTopic() const {
+  return {{ TypeName }}Topic{::nt::GetTopicFromHandle(m_pubHandle)};
+}
+
+inline {{ TypeName }}Entry::{{ TypeName }}Entry(
+    NT_Entry handle, {{ cpp.ParamType }} defaultValue)
+    : {{ TypeName }}Subscriber{handle, defaultValue},
+      {{ TypeName }}Publisher{handle} {}
+
+inline {{ TypeName }}Topic {{ TypeName }}Entry::GetTopic() const {
+  return {{ TypeName }}Topic{::nt::GetTopicFromHandle(m_subHandle)};
+}
+
+inline void {{ TypeName }}Entry::Unpublish() {
+  ::nt::Unpublish(m_pubHandle);
+}
+
+inline {{ TypeName }}Subscriber {{ TypeName }}Topic::Subscribe(
+    {% if not TypeString %}std::string_view typeString, {% endif %}{{ cpp.ParamType }} defaultValue,
+    const PubSubOptions& options) {
+  return {{ TypeName }}Subscriber{
+      ::nt::Subscribe(m_handle, NT_{{ cpp.TYPE_NAME }}, {{ TypeString|default('typeString') }}, options),
+      defaultValue};
+}
+{%- if TypeString %}
+inline {{ TypeName }}Subscriber {{ TypeName }}Topic::SubscribeEx(
+    std::string_view typeString, {{ cpp.ParamType }} defaultValue,
+    const PubSubOptions& options) {
+  return {{ TypeName }}Subscriber{
+      ::nt::Subscribe(m_handle, NT_{{ cpp.TYPE_NAME }}, typeString, options),
+      defaultValue};
+}
+{% endif %}
+inline {{ TypeName }}Publisher {{ TypeName }}Topic::Publish(
+    {% if not TypeString %}std::string_view typeString, {% endif %}const PubSubOptions& options) {
+  return {{ TypeName }}Publisher{
+      ::nt::Publish(m_handle, NT_{{ cpp.TYPE_NAME }}, {{ TypeString|default('typeString') }}, options)};
+}
+
+inline {{ TypeName }}Publisher {{ TypeName }}Topic::PublishEx(
+    std::string_view typeString,
+    const wpi::json& properties, const PubSubOptions& options) {
+  return {{ TypeName }}Publisher{
+      ::nt::PublishEx(m_handle, NT_{{ cpp.TYPE_NAME }}, typeString, properties, options)};
+}
+
+inline {{ TypeName }}Entry {{ TypeName }}Topic::GetEntry(
+    {% if not TypeString %}std::string_view typeString, {% endif %}{{ cpp.ParamType }} defaultValue,
+    const PubSubOptions& options) {
+  return {{ TypeName }}Entry{
+      ::nt::GetEntry(m_handle, NT_{{ cpp.TYPE_NAME }}, {{ TypeString|default('typeString') }}, options),
+      defaultValue};
+}
+{%- if TypeString %}
+inline {{ TypeName }}Entry {{ TypeName }}Topic::GetEntryEx(
+    std::string_view typeString, {{ cpp.ParamType }} defaultValue,
+    const PubSubOptions& options) {
+  return {{ TypeName }}Entry{
+      ::nt::GetEntry(m_handle, NT_{{ cpp.TYPE_NAME }}, typeString, options),
+      defaultValue};
+}
+{% endif %}
+}  // namespace nt
diff --git a/third_party/allwpilib/ntcore/src/generate/include/ntcore_c_types.h.jinja b/third_party/allwpilib/ntcore/src/generate/include/ntcore_c_types.h.jinja
new file mode 100644
index 0000000..d5b2448
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/generate/include/ntcore_c_types.h.jinja
@@ -0,0 +1,151 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <stdint.h>
+
+#include "ntcore_c.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+{% for t in types %}
+/**
+ * Timestamped {{ t.TypeName }}.
+ * @ingroup ntcore_c_handle_api
+ */
+struct NT_Timestamped{{ t.TypeName }} {
+  /**
+   * Time in local time base.
+   */
+  int64_t time;
+
+  /**
+   * Time in server time base.  May be 0 or 1 for locally set values.
+   */
+  int64_t serverTime;
+
+  /**
+   * Value.
+   */
+  {{ t.c.ValueType }} value;
+{%- if t.c.IsArray %}
+  /**
+   * Value length.
+   */
+  size_t len;
+{% endif %}
+};
+
+/**
+ * @defgroup ntcore_{{ t.TypeName }}_cfunc {{ t.TypeName }} Functions
+ * @ingroup ntcore_c_handle_api
+ * @{
+ */
+
+/**
+ * Publish a new value.
+ *
+ * @param pubentry publisher or entry handle
+ * @param time timestamp; 0 indicates current NT time should be used
+ * @param value value to publish
+{%- if t.c.IsArray %}
+ * @param len length of value
+{% endif %}
+ */
+NT_Bool NT_Set{{ t.TypeName }}(NT_Handle pubentry, int64_t time, {{ t.c.ParamType }} value{% if t.c.IsArray %}, size_t len{% endif %});
+
+/**
+ * Publish a default value.
+ * On reconnect, a default value will never be used in preference to a
+ * published value.
+ *
+ * @param pubentry publisher or entry handle
+ * @param defaultValue default value
+{%- if t.c.IsArray %}
+ * @param defaultValueLen length of default value
+{% endif %}
+ */
+NT_Bool NT_SetDefault{{ t.TypeName }}(NT_Handle pubentry, {{ t.c.ParamType }} defaultValue{% if t.c.IsArray %}, size_t defaultValueLen{% endif %});
+
+/**
+ * Get the last published value.
+ * If no value has been published, returns the passed defaultValue.
+ *
+ * @param subentry subscriber or entry handle
+ * @param defaultValue default value to return if no value has been published
+{%- if t.c.IsArray %}
+ * @param defaultValueLen length of default value
+ * @param len length of returned value (output)
+{% endif %}
+ * @return value
+ */
+{{ t.c.ValueType }} NT_Get{{ t.TypeName }}(NT_Handle subentry, {{ t.c.ParamType }} defaultValue{% if t.c.IsArray %}, size_t defaultValueLen, size_t* len{% endif %});
+
+/**
+ * Get the last published value along with its timestamp.
+ * If no value has been published, returns the passed defaultValue and a
+ * timestamp of 0.
+ *
+ * @param subentry subscriber or entry handle
+ * @param defaultValue default value to return if no value has been published
+{%- if t.c.IsArray %}
+ * @param defaultValueLen length of default value
+{% endif %}
+ * @param value timestamped value (output)
+ */
+void NT_GetAtomic{{ t.TypeName }}(NT_Handle subentry, {{ t.c.ParamType }} defaultValue{% if t.c.IsArray %}, size_t defaultValueLen{% endif %}, struct NT_Timestamped{{ t.TypeName }}* value);
+
+/**
+ * Disposes a timestamped value (as returned by NT_GetAtomic{{ t.TypeName }}).
+ *
+ * @param value timestamped value
+ */
+void NT_DisposeTimestamped{{ t.TypeName }}(struct NT_Timestamped{{ t.TypeName }}* value);
+
+/**
+ * Get an array of all value changes since the last call to ReadQueue.
+ * Also provides a timestamp for each value.
+ *
+ * @note The "poll storage" subscribe option can be used to set the queue
+ *     depth.
+ *
+ * @param subentry subscriber or entry handle
+ * @param len length of returned array (output)
+ * @return Array of timestamped values; NULL if no new changes have
+ *     been published since the previous call.
+ */
+struct NT_Timestamped{{ t.TypeName }}* NT_ReadQueue{{ t.TypeName }}(NT_Handle subentry, size_t* len);
+
+/**
+ * Frees a timestamped array of values (as returned by NT_ReadQueue{{ t.TypeName }}).
+ *
+ * @param arr array
+ * @param len length of array
+ */
+void NT_FreeQueue{{ t.TypeName }}(struct NT_Timestamped{{ t.TypeName }}* arr, size_t len);
+
+{%- if not t.c.IsArray %}
+/**
+ * Get an array of all value changes since the last call to ReadQueue.
+ *
+ * @note The "poll storage" subscribe option can be used to set the queue
+ *     depth.
+ *
+ * @param subentry subscriber or entry handle
+ * @param len length of returned array (output)
+ * @return Array of values; NULL if no new changes have
+ *     been published since the previous call.
+ */
+{{ t.c.ValueType }}* NT_ReadQueueValues{{ t.TypeName }}(NT_Handle subentry, size_t* len);
+{%- endif %}
+
+/** @} */
+{% endfor %}
+
+#ifdef __cplusplus
+}  // extern "C"
+#endif
diff --git a/third_party/allwpilib/ntcore/src/generate/include/ntcore_cpp_types.h.jinja b/third_party/allwpilib/ntcore/src/generate/include/ntcore_cpp_types.h.jinja
new file mode 100644
index 0000000..e987186
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/generate/include/ntcore_cpp_types.h.jinja
@@ -0,0 +1,154 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <stdint.h>
+
+#include <span>
+#include <string>
+#include <string_view>
+#include <utility>
+#include <vector>
+
+#include "ntcore_c.h"
+
+namespace wpi {
+template <typename T>
+class SmallVectorImpl;
+}  // namespace wpi
+
+namespace nt {
+{% for t in types %}
+/**
+ * Timestamped {{ t.TypeName }}.
+ * @ingroup ntcore_cpp_handle_api
+ */
+struct Timestamped{{ t.TypeName }} {
+  Timestamped{{ t.TypeName }}() = default;
+  Timestamped{{ t.TypeName }}(int64_t time, int64_t serverTime, {{ t.cpp.ValueType }} value)
+    : time{time}, serverTime{serverTime}, value{std::move(value)} {}
+
+  /**
+   * Time in local time base.
+   */
+  int64_t time = 0;
+
+  /**
+   * Time in server time base.  May be 0 or 1 for locally set values.
+   */
+  int64_t serverTime = 0;
+
+  /**
+   * Value.
+   */
+  {{ t.cpp.ValueType }} value = {};
+};
+{% if t.cpp.SmallRetType %}
+/**
+ * Timestamped {{ t.TypeName }} view (for SmallVector-taking functions).
+ * @ingroup ntcore_cpp_handle_api
+ */
+struct Timestamped{{ t.TypeName }}View {
+  Timestamped{{ t.TypeName }}View() = default;
+  Timestamped{{ t.TypeName }}View(int64_t time, int64_t serverTime, {{ t.cpp.SmallRetType }} value)
+    : time{time}, serverTime{serverTime}, value{std::move(value)} {}
+
+  /**
+   * Time in local time base.
+   */
+  int64_t time = 0;
+
+  /**
+   * Time in server time base.  May be 0 or 1 for locally set values.
+   */
+  int64_t serverTime = 0;
+
+  /**
+   * Value.
+   */
+  {{ t.cpp.SmallRetType }} value = {};
+};
+{% endif %}
+/**
+ * @defgroup ntcore_{{ t.TypeName }}_func {{ t.TypeName }} Functions
+ * @ingroup ntcore_cpp_handle_api
+ * @{
+ */
+
+/**
+ * Publish a new value.
+ *
+ * @param pubentry publisher or entry handle
+ * @param value value to publish
+ * @param time timestamp; 0 indicates current NT time should be used
+ */
+bool Set{{ t.TypeName }}(NT_Handle pubentry, {{ t.cpp.ParamType }} value, int64_t time = 0);
+
+/**
+ * Publish a default value.
+ * On reconnect, a default value will never be used in preference to a
+ * published value.
+ *
+ * @param pubentry publisher or entry handle
+ * @param defaultValue default value
+ */
+bool SetDefault{{ t.TypeName }}(NT_Handle pubentry, {{ t.cpp.ParamType }} defaultValue);
+
+/**
+ * Get the last published value.
+ * If no value has been published, returns the passed defaultValue.
+ *
+ * @param subentry subscriber or entry handle
+ * @param defaultValue default value to return if no value has been published
+ * @return value
+ */
+{{ t.cpp.ValueType }} Get{{ t.TypeName }}(NT_Handle subentry, {{ t.cpp.ParamType }} defaultValue);
+
+/**
+ * Get the last published value along with its timestamp.
+ * If no value has been published, returns the passed defaultValue and a
+ * timestamp of 0.
+ *
+ * @param subentry subscriber or entry handle
+ * @param defaultValue default value to return if no value has been published
+ * @return timestamped value
+ */
+Timestamped{{ t.TypeName }} GetAtomic{{ t.TypeName}}(NT_Handle subentry, {{ t.cpp.ParamType }} defaultValue);
+
+/**
+ * Get an array of all value changes since the last call to ReadQueue.
+ * Also provides a timestamp for each value.
+ *
+ * @note The "poll storage" subscribe option can be used to set the queue
+ *     depth.
+ *
+ * @param subentry subscriber or entry handle
+ * @return Array of timestamped values; empty array if no new changes have
+ *     been published since the previous call.
+ */
+std::vector<Timestamped{{ t.TypeName }}> ReadQueue{{ t.TypeName }}(NT_Handle subentry);
+
+/**
+ * Get an array of all value changes since the last call to ReadQueue.
+ *
+ * @note The "poll storage" subscribe option can be used to set the queue
+ *     depth.
+ *
+ * @param subentry subscriber or entry handle
+ * @return Array of values; empty array if no new changes have
+ *     been published since the previous call.
+ */
+std::vector<{% if t.cpp.ValueType == "bool" %}int{% else %}{{ t.cpp.ValueType }}{% endif %}> ReadQueueValues{{ t.TypeName }}(NT_Handle subentry);
+{% if t.cpp.SmallRetType and t.cpp.SmallElemType %}
+{{ t.cpp.SmallRetType }} Get{{ t.TypeName }}(NT_Handle subentry, wpi::SmallVectorImpl<{{ t.cpp.SmallElemType }}>& buf, {{ t.cpp.ParamType }} defaultValue);
+
+Timestamped{{ t.TypeName }}View GetAtomic{{ t.TypeName }}(
+      NT_Handle subentry,
+      wpi::SmallVectorImpl<{{ t.cpp.SmallElemType }}>& buf,
+      {{ t.cpp.ParamType }} defaultValue);
+{% endif %}
+/** @} */
+{% endfor %}
+}  // namespace nt
diff --git a/third_party/allwpilib/ntcore/src/generate/java/Entry.java.jinja b/third_party/allwpilib/ntcore/src/generate/java/Entry.java.jinja
new file mode 100644
index 0000000..cbaa782
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/generate/java/Entry.java.jinja
@@ -0,0 +1,15 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.networktables;
+
+/**
+ * NetworkTables {{ TypeName }} entry.
+ *
+ * <p>Unlike NetworkTableEntry, the entry goes away when close() is called.
+ */
+public interface {{ TypeName }}Entry extends {{ TypeName }}Subscriber, {{ TypeName }}Publisher {
+  /** Stops publishing the entry if it's published. */
+  void unpublish();
+}
diff --git a/third_party/allwpilib/ntcore/src/generate/java/EntryImpl.java.jinja b/third_party/allwpilib/ntcore/src/generate/java/EntryImpl.java.jinja
new file mode 100644
index 0000000..43b31e4
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/generate/java/EntryImpl.java.jinja
@@ -0,0 +1,75 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.networktables;
+
+/** NetworkTables {{ TypeName }} implementation. */
+@SuppressWarnings("PMD.ArrayIsStoredDirectly")
+final class {{ TypeName }}EntryImpl extends EntryBase implements {{ TypeName }}Entry {
+  /**
+   * Constructor.
+   *
+   * @param topic Topic
+   * @param handle Native handle
+   * @param defaultValue Default value for get()
+   */
+  {{ TypeName }}EntryImpl({{ TypeName }}Topic topic, int handle, {{ java.ValueType }} defaultValue) {
+    super(handle);
+    m_topic = topic;
+    m_defaultValue = defaultValue;
+  }
+
+  @Override
+  public {{ TypeName }}Topic getTopic() {
+    return m_topic;
+  }
+
+  @Override
+  public {{ java.ValueType }} get() {
+    return NetworkTablesJNI.get{{ TypeName }}(m_handle, m_defaultValue);
+  }
+
+  @Override
+  public {{ java.ValueType }} get({{ java.ValueType }} defaultValue) {
+    return NetworkTablesJNI.get{{TypeName}}(m_handle, defaultValue);
+  }
+
+  @Override
+  public Timestamped{{ TypeName }} getAtomic() {
+    return NetworkTablesJNI.getAtomic{{ TypeName }}(m_handle, m_defaultValue);
+  }
+
+  @Override
+  public Timestamped{{ TypeName }} getAtomic({{ java.ValueType }} defaultValue) {
+    return NetworkTablesJNI.getAtomic{{ TypeName }}(m_handle, defaultValue);
+  }
+
+  @Override
+  public Timestamped{{ TypeName }}[] readQueue() {
+    return NetworkTablesJNI.readQueue{{ TypeName }}(m_handle);
+  }
+
+  @Override
+  public {{ java.ValueType }}[] readQueueValues() {
+    return NetworkTablesJNI.readQueueValues{{ TypeName }}(m_handle);
+  }
+
+  @Override
+  public void set({{ java.ValueType }} value, long time) {
+    NetworkTablesJNI.set{{ TypeName }}(m_handle, time, value);
+  }
+
+  @Override
+  public void setDefault({{ java.ValueType }} value) {
+    NetworkTablesJNI.setDefault{{ TypeName }}(m_handle, 0, value);
+  }
+
+  @Override
+  public void unpublish() {
+    NetworkTablesJNI.unpublish(m_handle);
+  }
+
+  private final {{ TypeName }}Topic m_topic;
+  private final {{ java.ValueType }} m_defaultValue;
+}
diff --git a/third_party/allwpilib/ntcore/src/generate/java/GenericEntryImpl.java.jinja b/third_party/allwpilib/ntcore/src/generate/java/GenericEntryImpl.java.jinja
new file mode 100644
index 0000000..e4296d7
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/generate/java/GenericEntryImpl.java.jinja
@@ -0,0 +1,317 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.networktables;
+
+/** NetworkTables generic implementation. */
+final class GenericEntryImpl extends EntryBase implements GenericEntry {
+  /**
+   * Constructor.
+   *
+   * @param topic Topic
+   * @param handle Native handle
+   */
+  GenericEntryImpl(Topic topic, int handle) {
+    super(handle);
+    m_topic = topic;
+  }
+
+  @Override
+  public Topic getTopic() {
+    return m_topic;
+  }
+
+  @Override
+  public NetworkTableValue get() {
+    return NetworkTablesJNI.getValue(m_handle);
+  }
+{% for t in types %}
+  /**
+   * Gets the entry's value as a {{ t.java.ValueType }}. If the entry does not exist or is of different type, it
+   * will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   */
+  @Override
+  public {{ t.java.ValueType }} get{{ t.TypeName }}({{ t.java.ValueType }} defaultValue) {
+    return NetworkTablesJNI.get{{ t.TypeName }}(m_handle, defaultValue);
+  }
+{% if t.java.WrapValueType %}
+  /**
+   * Gets the entry's value as a boolean array. If the entry does not exist or is of different type,
+   * it will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   */
+  @Override
+  public {{ t.java.WrapValueType }} get{{ t.TypeName }}({{ t.java.WrapValueType }} defaultValue) {
+    return NetworkTableValue.fromNative{{ t.TypeName }}(
+        get{{ t.TypeName }}(NetworkTableValue.toNative{{ t.TypeName }}(defaultValue)));
+  }
+{% endif -%}
+{% endfor %}
+  @Override
+  public NetworkTableValue[] readQueue() {
+    return NetworkTablesJNI.readQueueValue(m_handle);
+  }
+
+  @Override
+  public boolean set(NetworkTableValue value) {
+    long time = value.getTime();
+    Object otherValue = value.getValue();
+    switch (value.getType()) {
+      case kBoolean:
+        return NetworkTablesJNI.setBoolean(m_handle, time, (Boolean) otherValue);
+      case kInteger:
+        return NetworkTablesJNI.setInteger(
+            m_handle, time, ((Number) otherValue).longValue());
+      case kFloat:
+        return NetworkTablesJNI.setFloat(
+            m_handle, time, ((Number) otherValue).floatValue());
+      case kDouble:
+        return NetworkTablesJNI.setDouble(
+            m_handle, time, ((Number) otherValue).doubleValue());
+      case kString:
+        return NetworkTablesJNI.setString(m_handle, time, (String) otherValue);
+      case kRaw:
+        return NetworkTablesJNI.setRaw(m_handle, time, (byte[]) otherValue);
+      case kBooleanArray:
+        return NetworkTablesJNI.setBooleanArray(m_handle, time, (boolean[]) otherValue);
+      case kIntegerArray:
+        return NetworkTablesJNI.setIntegerArray(m_handle, time, (long[]) otherValue);
+      case kFloatArray:
+        return NetworkTablesJNI.setFloatArray(m_handle, time, (float[]) otherValue);
+      case kDoubleArray:
+        return NetworkTablesJNI.setDoubleArray(m_handle, time, (double[]) otherValue);
+      case kStringArray:
+        return NetworkTablesJNI.setStringArray(m_handle, time, (String[]) otherValue);
+      default:
+        return true;
+    }
+  }
+
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   * @throws IllegalArgumentException if the value is not a known type
+   */
+  @Override
+  public boolean setValue(Object value, long time) {
+    if (value instanceof NetworkTableValue) {
+      return set((NetworkTableValue) value);
+    } else if (value instanceof Boolean) {
+      return setBoolean((Boolean) value, time);
+    } else if (value instanceof Long) {
+      return setInteger((Long) value, time);
+    } else if (value instanceof Float) {
+      return setFloat((Float) value, time);
+    } else if (value instanceof Number) {
+      return setNumber((Number) value, time);
+    } else if (value instanceof String) {
+      return setString((String) value, time);
+    } else if (value instanceof byte[]) {
+      return setRaw((byte[]) value, time);
+    } else if (value instanceof boolean[]) {
+      return setBooleanArray((boolean[]) value, time);
+    } else if (value instanceof long[]) {
+      return setIntegerArray((long[]) value, time);
+    } else if (value instanceof float[]) {
+      return setFloatArray((float[]) value, time);
+    } else if (value instanceof double[]) {
+      return setDoubleArray((double[]) value, time);
+    } else if (value instanceof Boolean[]) {
+      return setBooleanArray((Boolean[]) value, time);
+    } else if (value instanceof Long[]) {
+      return setIntegerArray((Long[]) value, time);
+    } else if (value instanceof Float[]) {
+      return setFloatArray((Float[]) value, time);
+    } else if (value instanceof Number[]) {
+      return setNumberArray((Number[]) value, time);
+    } else if (value instanceof String[]) {
+      return setStringArray((String[]) value, time);
+    } else {
+      throw new IllegalArgumentException(
+          "Value of type " + value.getClass().getName() + " cannot be put into a table");
+    }
+  }
+{% for t in types %}
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @return False if the entry exists with a different type
+   */
+  @Override
+  public boolean set{{ t.TypeName }}({{ t.java.ValueType }} value, long time) {
+    return NetworkTablesJNI.set{{ t.TypeName }}(m_handle, time, value);
+  }
+{% if t.java.WrapValueType %}
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @return False if the entry exists with a different type
+   */
+  @Override
+  public boolean set{{ t.TypeName }}({{ t.java.WrapValueType }} value, long time) {
+    return set{{ t.TypeName }}(NetworkTableValue.toNative{{ t.TypeName }}(value), time);
+  }
+{% endif -%}
+{% endfor %}
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @return False if the entry exists with a different type
+   */
+  public boolean setNumber(Number value, long time) {
+    return setDouble(value.doubleValue(), time);
+  }
+
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @return False if the entry exists with a different type
+   */
+  public boolean setNumberArray(Number[] value, long time) {
+    return setDoubleArray(NetworkTableValue.toNativeDoubleArray(value), time);
+  }
+
+  @Override
+  public boolean setDefault(NetworkTableValue defaultValue) {
+    long time = defaultValue.getTime();
+    Object otherValue = defaultValue.getValue();
+    switch (defaultValue.getType()) {
+      case kBoolean:
+        return NetworkTablesJNI.setDefaultBoolean(m_handle, time, (Boolean) otherValue);
+      case kInteger:
+        return NetworkTablesJNI.setDefaultInteger(
+            m_handle, time, ((Number) otherValue).longValue());
+      case kFloat:
+        return NetworkTablesJNI.setDefaultFloat(
+            m_handle, time, ((Number) otherValue).floatValue());
+      case kDouble:
+        return NetworkTablesJNI.setDefaultDouble(
+            m_handle, time, ((Number) otherValue).doubleValue());
+      case kString:
+        return NetworkTablesJNI.setDefaultString(m_handle, time, (String) otherValue);
+      case kRaw:
+        return NetworkTablesJNI.setDefaultRaw(m_handle, time, (byte[]) otherValue);
+      case kBooleanArray:
+        return NetworkTablesJNI.setDefaultBooleanArray(m_handle, time, (boolean[]) otherValue);
+      case kIntegerArray:
+        return NetworkTablesJNI.setDefaultIntegerArray(m_handle, time, (long[]) otherValue);
+      case kFloatArray:
+        return NetworkTablesJNI.setDefaultFloatArray(m_handle, time, (float[]) otherValue);
+      case kDoubleArray:
+        return NetworkTablesJNI.setDefaultDoubleArray(m_handle, time, (double[]) otherValue);
+      case kStringArray:
+        return NetworkTablesJNI.setDefaultStringArray(m_handle, time, (String[]) otherValue);
+      default:
+        return true;
+    }
+  }
+
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   * @throws IllegalArgumentException if the value is not a known type
+   */
+  @Override
+  public boolean setDefaultValue(Object defaultValue) {
+    if (defaultValue instanceof NetworkTableValue) {
+      return setDefault((NetworkTableValue) defaultValue);
+    } else if (defaultValue instanceof Boolean) {
+      return setDefaultBoolean((Boolean) defaultValue);
+    } else if (defaultValue instanceof Integer) {
+      return setDefaultInteger((Integer) defaultValue);
+    } else if (defaultValue instanceof Float) {
+      return setDefaultFloat((Float) defaultValue);
+    } else if (defaultValue instanceof Number) {
+      return setDefaultNumber((Number) defaultValue);
+    } else if (defaultValue instanceof String) {
+      return setDefaultString((String) defaultValue);
+    } else if (defaultValue instanceof byte[]) {
+      return setDefaultRaw((byte[]) defaultValue);
+    } else if (defaultValue instanceof boolean[]) {
+      return setDefaultBooleanArray((boolean[]) defaultValue);
+    } else if (defaultValue instanceof long[]) {
+      return setDefaultIntegerArray((long[]) defaultValue);
+    } else if (defaultValue instanceof float[]) {
+      return setDefaultFloatArray((float[]) defaultValue);
+    } else if (defaultValue instanceof double[]) {
+      return setDefaultDoubleArray((double[]) defaultValue);
+    } else if (defaultValue instanceof Boolean[]) {
+      return setDefaultBooleanArray((Boolean[]) defaultValue);
+    } else if (defaultValue instanceof Long[]) {
+      return setDefaultIntegerArray((Long[]) defaultValue);
+    } else if (defaultValue instanceof Float[]) {
+      return setDefaultFloatArray((Float[]) defaultValue);
+    } else if (defaultValue instanceof Number[]) {
+      return setDefaultNumberArray((Number[]) defaultValue);
+    } else if (defaultValue instanceof String[]) {
+      return setDefaultStringArray((String[]) defaultValue);
+    } else {
+      throw new IllegalArgumentException(
+          "Value of type " + defaultValue.getClass().getName() + " cannot be put into a table");
+    }
+  }
+{% for t in types %}
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  @Override
+  public boolean setDefault{{ t.TypeName }}({{ t.java.ValueType }} defaultValue) {
+    return NetworkTablesJNI.setDefault{{ t.TypeName }}(m_handle, 0, defaultValue);
+  }
+{% if t.java.WrapValueType %}
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  @Override
+  public boolean setDefault{{ t.TypeName }}({{ t.java.WrapValueType }} defaultValue) {
+    return setDefault{{ t.TypeName }}(NetworkTableValue.toNative{{ t.TypeName }}(defaultValue));
+  }
+{% endif -%}
+{% endfor %}
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  public boolean setDefaultNumber(Number defaultValue) {
+    return setDefaultDouble(defaultValue.doubleValue());
+  }
+
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  public boolean setDefaultNumberArray(Number[] defaultValue) {
+    return setDefaultDoubleArray(NetworkTableValue.toNativeDoubleArray(defaultValue));
+  }
+
+  @Override
+  public void unpublish() {
+    NetworkTablesJNI.unpublish(m_handle);
+  }
+
+  private final Topic m_topic;
+}
diff --git a/third_party/allwpilib/ntcore/src/generate/java/GenericPublisher.java.jinja b/third_party/allwpilib/ntcore/src/generate/java/GenericPublisher.java.jinja
new file mode 100644
index 0000000..d747f17
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/generate/java/GenericPublisher.java.jinja
@@ -0,0 +1,119 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.networktables;
+
+import java.util.function.Consumer;
+
+/** NetworkTables generic publisher. */
+public interface GenericPublisher extends Publisher, Consumer<NetworkTableValue> {
+  /**
+   * Get the corresponding topic.
+   *
+   * @return Topic
+   */
+  @Override
+  Topic getTopic();
+
+  /**
+   * Publish a new value.
+   *
+   * @param value value to publish
+   * @return False if the topic already exists with a different type
+   */
+  boolean set(NetworkTableValue value);
+
+  /**
+   * Publish a new value.
+   *
+   * @param value value to publish
+   * @return False if the topic already exists with a different type
+   * @throws IllegalArgumentException if the value is not a known type
+   */
+  default boolean setValue(Object value) {
+    return setValue(value, 0);
+  }
+
+  /**
+   * Publish a new value.
+   *
+   * @param value value to publish
+   * @param time timestamp; 0 indicates current NT time should be used
+   * @return False if the topic already exists with a different type
+   * @throws IllegalArgumentException if the value is not a known type
+   */
+  boolean setValue(Object value, long time);
+{% for t in types %}
+  /**
+   * Publish a new value.
+   *
+   * @param value value to publish
+   * @return False if the topic already exists with a different type
+   */
+  default boolean set{{ t.TypeName }}({{ t.java.ValueType }} value) {
+    return set{{ t.TypeName }}(value, 0);
+  }
+
+  /**
+   * Publish a new value.
+   *
+   * @param value value to publish
+   * @param time timestamp; 0 indicates current NT time should be used
+   * @return False if the topic already exists with a different type
+   */
+  boolean set{{ t.TypeName }}({{ t.java.ValueType }} value, long time);
+{% if t.java.WrapValueType %}
+  /**
+   * Publish a new value.
+   *
+   * @param value value to publish
+   * @return False if the topic already exists with a different type
+   */
+  default boolean set{{ t.TypeName }}({{ t.java.WrapValueType }} value) {
+    return set{{ t.TypeName }}(value, 0);
+  }
+
+  /**
+   * Publish a new value.
+   *
+   * @param value value to publish
+   * @param time timestamp; 0 indicates current NT time should be used
+   * @return False if the topic already exists with a different type
+   */
+  boolean set{{ t.TypeName }}({{ t.java.WrapValueType }} value, long time);
+{% endif -%}
+{% endfor %}
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  boolean setDefault(NetworkTableValue defaultValue);
+
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   * @throws IllegalArgumentException if the value is not a known type
+   */
+  boolean setDefaultValue(Object defaultValue);
+{% for t in types %}
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  boolean setDefault{{ t.TypeName }}({{ t.java.ValueType }} defaultValue);
+{% if t.java.WrapValueType %}
+  boolean setDefault{{ t.TypeName }}({{ t.java.WrapValueType }} defaultValue);
+{% endif -%}
+{% endfor %}
+  @Override
+  default void accept(NetworkTableValue value) {
+    set(value);
+  }
+}
diff --git a/third_party/allwpilib/ntcore/src/generate/java/GenericSubscriber.java.jinja b/third_party/allwpilib/ntcore/src/generate/java/GenericSubscriber.java.jinja
new file mode 100644
index 0000000..63ecebc
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/generate/java/GenericSubscriber.java.jinja
@@ -0,0 +1,58 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.networktables;
+
+import java.util.function.Supplier;
+
+/** NetworkTables generic subscriber. */
+@SuppressWarnings("PMD.MissingOverride")
+public interface GenericSubscriber extends Subscriber, Supplier<NetworkTableValue> {
+  /**
+   * Get the corresponding topic.
+   *
+   * @return Topic
+   */
+  @Override
+  Topic getTopic();
+
+  /**
+   * Get the last published value.
+   * If no value has been published, returns a value with type NetworkTableType.kUnassigned.
+   *
+   * @return value
+   */
+  NetworkTableValue get();
+{% for t in types %}
+  /**
+   * Gets the entry's value as a {{ t.java.ValueType }}. If the entry does not exist or is of different type, it
+   * will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   */
+  {{ t.java.ValueType }} get{{ t.TypeName }}({{ t.java.ValueType }} defaultValue);
+{% if t.java.WrapValueType %}
+  /**
+   * Gets the entry's value as a boolean array. If the entry does not exist or is of different type,
+   * it will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   */
+  {{ t.java.WrapValueType }} get{{ t.TypeName }}({{ t.java.WrapValueType }} defaultValue);
+{% endif -%}
+{% endfor %}
+  /**
+   * Get an array of all value changes since the last call to readQueue.
+   * Also provides a timestamp for each value.
+   *
+   * <p>The "poll storage" subscribe option can be used to set the queue
+   * depth.
+   *
+   * @return Array of timestamped values; empty array if no new changes have
+   *     been published since the previous call.
+   */
+  NetworkTableValue[] readQueue();
+}
diff --git a/third_party/allwpilib/ntcore/src/generate/java/NetworkTableEntry.java.jinja b/third_party/allwpilib/ntcore/src/generate/java/NetworkTableEntry.java.jinja
new file mode 100644
index 0000000..783ec6f
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/generate/java/NetworkTableEntry.java.jinja
@@ -0,0 +1,537 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.networktables;
+
+/**
+ * NetworkTables Entry.
+ *
+ * <p>For backwards compatibility, the NetworkTableEntry close() does not release the entry.
+ */
+@SuppressWarnings("UnnecessaryParentheses")
+public final class NetworkTableEntry implements Publisher, Subscriber {
+  /**
+   * Flag values (as returned by {@link #getFlags()}).
+   *
+   * @deprecated Use isPersistent() instead.
+   */
+  @Deprecated(since = "2022", forRemoval = true)
+  public static final int kPersistent = 0x01;
+
+  /**
+   * Construct from native handle.
+   *
+   * @param inst Instance
+   * @param handle Native handle
+   */
+  public NetworkTableEntry(NetworkTableInstance inst, int handle) {
+    this(new Topic(inst, NetworkTablesJNI.getTopicFromHandle(handle)), handle);
+  }
+
+  /**
+   * Construct from native handle.
+   *
+   * @param topic Topic
+   * @param handle Native handle
+   */
+  public NetworkTableEntry(Topic topic, int handle) {
+    m_topic = topic;
+    m_handle = handle;
+  }
+
+  @Override
+  public void close() {}
+
+  /**
+   * Determines if the native handle is valid.
+   *
+   * @return True if the native handle is valid, false otherwise.
+   */
+  @Override
+  public boolean isValid() {
+    return m_handle != 0;
+  }
+
+  /**
+   * Gets the native handle for the entry.
+   *
+   * @return Native handle
+   */
+  @Override
+  public int getHandle() {
+    return m_handle;
+  }
+
+  /**
+   * Gets the subscribed-to / published-to topic.
+   *
+   * @return Topic
+   */
+  @Override
+  public Topic getTopic() {
+    return m_topic;
+  }
+
+  /**
+   * Gets the instance for the entry.
+   *
+   * @return Instance
+   */
+  public NetworkTableInstance getInstance() {
+    return m_topic.getInstance();
+  }
+
+  /**
+   * Determines if the entry currently exists.
+   *
+   * @return True if the entry exists, false otherwise.
+   */
+  @Override
+  public boolean exists() {
+    return NetworkTablesJNI.getType(m_handle) != 0;
+  }
+
+  /**
+   * Gets the name of the entry (the key).
+   *
+   * @return the entry's name
+   */
+  public String getName() {
+    return NetworkTablesJNI.getEntryName(m_handle);
+  }
+
+  /**
+   * Gets the type of the entry.
+   *
+   * @return the entry's type
+   */
+  public NetworkTableType getType() {
+    return NetworkTableType.getFromInt(NetworkTablesJNI.getType(m_handle));
+  }
+
+  /**
+   * Returns the flags.
+   *
+   * @return the flags (bitmask)
+   * @deprecated Use isPersistent() or topic properties instead
+   */
+  @Deprecated(since = "2022", forRemoval = true)
+  public int getFlags() {
+    return NetworkTablesJNI.getEntryFlags(m_handle);
+  }
+
+  /**
+   * Gets the last time the entry's value was changed.
+   *
+   * @return Entry last change time
+   */
+  @Override
+  public long getLastChange() {
+    return NetworkTablesJNI.getEntryLastChange(m_handle);
+  }
+
+  /**
+   * Gets the entry's value. Returns a value with type NetworkTableType.kUnassigned if the value
+   * does not exist.
+   *
+   * @return the entry's value
+   */
+  public NetworkTableValue getValue() {
+    return NetworkTablesJNI.getValue(m_handle);
+  }
+{% for t in types %}
+  /**
+   * Gets the entry's value as a {{ t.java.ValueType }}. If the entry does not exist or is of different type, it
+   * will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   */
+  public {{ t.java.ValueType }} get{{ t.TypeName }}({{ t.java.ValueType }} defaultValue) {
+    return NetworkTablesJNI.get{{ t.TypeName }}(m_handle, defaultValue);
+  }
+{% if t.java.WrapValueType %}
+  /**
+   * Gets the entry's value as a boolean array. If the entry does not exist or is of different type,
+   * it will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   */
+  public {{ t.java.WrapValueType }} get{{ t.TypeName }}({{ t.java.WrapValueType }} defaultValue) {
+    return NetworkTableValue.fromNative{{ t.TypeName }}(
+        get{{ t.TypeName }}(NetworkTableValue.toNative{{ t.TypeName }}(defaultValue)));
+  }
+{% endif -%}
+{% endfor %}
+  /**
+   * Gets the entry's value as a double. If the entry does not exist or is of different type, it
+   * will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   */
+  public Number getNumber(Number defaultValue) {
+    return getDouble(defaultValue.doubleValue());
+  }
+
+  /**
+   * Gets the entry's value as a double array. If the entry does not exist or is of different type,
+   * it will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   */
+  public Number[] getNumberArray(Number[] defaultValue) {
+    return NetworkTableValue.fromNativeDoubleArray(
+        getDoubleArray(NetworkTableValue.toNativeDoubleArray(defaultValue)));
+  }
+
+  /**
+   * Get an array of all value changes since the last call to readQueue.
+   *
+   * <p>The "poll storage" subscribe option can be used to set the queue
+   * depth.
+   *
+   * @return Array of values; empty array if no new changes have been
+   *     published since the previous call.
+   */
+  public NetworkTableValue[] readQueue() {
+    return NetworkTablesJNI.readQueueValue(m_handle);
+  }
+
+  /**
+   * Checks if a data value is of a type that can be placed in a NetworkTable entry.
+   *
+   * @param data the data to check
+   * @return true if the data can be placed in an entry, false if it cannot
+   */
+  public static boolean isValidDataType(Object data) {
+    return data instanceof Number
+        || data instanceof Boolean
+        || data instanceof String
+        || data instanceof long[]
+        || data instanceof Long[]
+        || data instanceof float[]
+        || data instanceof Float[]
+        || data instanceof double[]
+        || data instanceof Double[]
+        || data instanceof Number[]
+        || data instanceof boolean[]
+        || data instanceof Boolean[]
+        || data instanceof String[]
+        || data instanceof byte[]
+        || data instanceof Byte[];
+  }
+
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   * @throws IllegalArgumentException if the value is not a known type
+   */
+  public boolean setDefaultValue(Object defaultValue) {
+    if (defaultValue instanceof NetworkTableValue) {
+      long time = ((NetworkTableValue) defaultValue).getTime();
+      Object otherValue = ((NetworkTableValue) defaultValue).getValue();
+      switch (((NetworkTableValue) defaultValue).getType()) {
+        case kBoolean:
+          return NetworkTablesJNI.setDefaultBoolean(m_handle, time, (Boolean) otherValue);
+        case kInteger:
+          return NetworkTablesJNI.setDefaultInteger(
+              m_handle, time, ((Number) otherValue).longValue());
+        case kFloat:
+          return NetworkTablesJNI.setDefaultFloat(
+              m_handle, time, ((Number) otherValue).floatValue());
+        case kDouble:
+          return NetworkTablesJNI.setDefaultDouble(
+              m_handle, time, ((Number) otherValue).doubleValue());
+        case kString:
+          return NetworkTablesJNI.setDefaultString(m_handle, time, (String) otherValue);
+        case kRaw:
+          return NetworkTablesJNI.setDefaultRaw(m_handle, time, (byte[]) otherValue);
+        case kBooleanArray:
+          return NetworkTablesJNI.setDefaultBooleanArray(m_handle, time, (boolean[]) otherValue);
+        case kIntegerArray:
+          return NetworkTablesJNI.setDefaultIntegerArray(m_handle, time, (long[]) otherValue);
+        case kFloatArray:
+          return NetworkTablesJNI.setDefaultFloatArray(m_handle, time, (float[]) otherValue);
+        case kDoubleArray:
+          return NetworkTablesJNI.setDefaultDoubleArray(m_handle, time, (double[]) otherValue);
+        case kStringArray:
+          return NetworkTablesJNI.setDefaultStringArray(m_handle, time, (String[]) otherValue);
+        default:
+          return true;
+      }
+    } else if (defaultValue instanceof Boolean) {
+      return setDefaultBoolean((Boolean) defaultValue);
+    } else if (defaultValue instanceof Integer) {
+      return setDefaultInteger((Integer) defaultValue);
+    } else if (defaultValue instanceof Float) {
+      return setDefaultFloat((Float) defaultValue);
+    } else if (defaultValue instanceof Number) {
+      return setDefaultNumber((Number) defaultValue);
+    } else if (defaultValue instanceof String) {
+      return setDefaultString((String) defaultValue);
+    } else if (defaultValue instanceof byte[]) {
+      return setDefaultRaw((byte[]) defaultValue);
+    } else if (defaultValue instanceof boolean[]) {
+      return setDefaultBooleanArray((boolean[]) defaultValue);
+    } else if (defaultValue instanceof long[]) {
+      return setDefaultIntegerArray((long[]) defaultValue);
+    } else if (defaultValue instanceof float[]) {
+      return setDefaultFloatArray((float[]) defaultValue);
+    } else if (defaultValue instanceof double[]) {
+      return setDefaultDoubleArray((double[]) defaultValue);
+    } else if (defaultValue instanceof Boolean[]) {
+      return setDefaultBooleanArray((Boolean[]) defaultValue);
+    } else if (defaultValue instanceof Long[]) {
+      return setDefaultIntegerArray((Long[]) defaultValue);
+    } else if (defaultValue instanceof Float[]) {
+      return setDefaultFloatArray((Float[]) defaultValue);
+    } else if (defaultValue instanceof Number[]) {
+      return setDefaultNumberArray((Number[]) defaultValue);
+    } else if (defaultValue instanceof String[]) {
+      return setDefaultStringArray((String[]) defaultValue);
+    } else {
+      throw new IllegalArgumentException(
+          "Value of type " + defaultValue.getClass().getName() + " cannot be put into a table");
+    }
+  }
+{% for t in types %}
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  public boolean setDefault{{ t.TypeName }}({{ t.java.ValueType }} defaultValue) {
+    return NetworkTablesJNI.setDefault{{ t.TypeName }}(m_handle, 0, defaultValue);
+  }
+{% if t.java.WrapValueType %}
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  public boolean setDefault{{ t.TypeName }}({{ t.java.WrapValueType }} defaultValue) {
+    return setDefault{{ t.TypeName }}(NetworkTableValue.toNative{{ t.TypeName }}(defaultValue));
+  }
+{% endif -%}
+{% endfor %}
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  public boolean setDefaultNumber(Number defaultValue) {
+    return setDefaultDouble(defaultValue.doubleValue());
+  }
+
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  public boolean setDefaultNumberArray(Number[] defaultValue) {
+    return setDefaultDoubleArray(NetworkTableValue.toNativeDoubleArray(defaultValue));
+  }
+
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   * @throws IllegalArgumentException if the value is not a known type
+   */
+  public boolean setValue(Object value) {
+    if (value instanceof NetworkTableValue) {
+      long time = ((NetworkTableValue) value).getTime();
+      Object otherValue = ((NetworkTableValue) value).getValue();
+      switch (((NetworkTableValue) value).getType()) {
+        case kBoolean:
+          return NetworkTablesJNI.setBoolean(m_handle, time, (Boolean) otherValue);
+        case kInteger:
+          return NetworkTablesJNI.setInteger(
+              m_handle, time, ((Number) otherValue).longValue());
+        case kFloat:
+          return NetworkTablesJNI.setFloat(
+              m_handle, time, ((Number) otherValue).floatValue());
+        case kDouble:
+          return NetworkTablesJNI.setDouble(
+              m_handle, time, ((Number) otherValue).doubleValue());
+        case kString:
+          return NetworkTablesJNI.setString(m_handle, time, (String) otherValue);
+        case kRaw:
+          return NetworkTablesJNI.setRaw(m_handle, time, (byte[]) otherValue);
+        case kBooleanArray:
+          return NetworkTablesJNI.setBooleanArray(m_handle, time, (boolean[]) otherValue);
+        case kIntegerArray:
+          return NetworkTablesJNI.setIntegerArray(m_handle, time, (long[]) otherValue);
+        case kFloatArray:
+          return NetworkTablesJNI.setFloatArray(m_handle, time, (float[]) otherValue);
+        case kDoubleArray:
+          return NetworkTablesJNI.setDoubleArray(m_handle, time, (double[]) otherValue);
+        case kStringArray:
+          return NetworkTablesJNI.setStringArray(m_handle, time, (String[]) otherValue);
+        default:
+          return true;
+      }
+    } else if (value instanceof Boolean) {
+      return setBoolean((Boolean) value);
+    } else if (value instanceof Long) {
+      return setInteger((Long) value);
+    } else if (value instanceof Float) {
+      return setFloat((Float) value);
+    } else if (value instanceof Number) {
+      return setNumber((Number) value);
+    } else if (value instanceof String) {
+      return setString((String) value);
+    } else if (value instanceof byte[]) {
+      return setRaw((byte[]) value);
+    } else if (value instanceof boolean[]) {
+      return setBooleanArray((boolean[]) value);
+    } else if (value instanceof long[]) {
+      return setIntegerArray((long[]) value);
+    } else if (value instanceof float[]) {
+      return setFloatArray((float[]) value);
+    } else if (value instanceof double[]) {
+      return setDoubleArray((double[]) value);
+    } else if (value instanceof Boolean[]) {
+      return setBooleanArray((Boolean[]) value);
+    } else if (value instanceof Long[]) {
+      return setIntegerArray((Long[]) value);
+    } else if (value instanceof Float[]) {
+      return setFloatArray((Float[]) value);
+    } else if (value instanceof Number[]) {
+      return setNumberArray((Number[]) value);
+    } else if (value instanceof String[]) {
+      return setStringArray((String[]) value);
+    } else {
+      throw new IllegalArgumentException(
+          "Value of type " + value.getClass().getName() + " cannot be put into a table");
+    }
+  }
+{% for t in types %}
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @return False if the entry exists with a different type
+   */
+  public boolean set{{ t.TypeName }}({{ t.java.ValueType }} value) {
+    return NetworkTablesJNI.set{{ t.TypeName }}(m_handle, 0, value);
+  }
+{% if t.java.WrapValueType %}
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @return False if the entry exists with a different type
+   */
+  public boolean set{{ t.TypeName }}({{ t.java.WrapValueType }} value) {
+    return set{{ t.TypeName }}(NetworkTableValue.toNative{{ t.TypeName }}(value));
+  }
+{% endif -%}
+{% endfor %}
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @return False if the entry exists with a different type
+   */
+  public boolean setNumber(Number value) {
+    return setDouble(value.doubleValue());
+  }
+
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @return False if the entry exists with a different type
+   */
+  public boolean setNumberArray(Number[] value) {
+    return setDoubleArray(NetworkTableValue.toNativeDoubleArray(value));
+  }
+
+  /**
+   * Sets flags.
+   *
+   * @param flags the flags to set (bitmask)
+   * @deprecated Use setPersistent() or topic properties instead
+   */
+  @Deprecated(since = "2022", forRemoval = true)
+  public void setFlags(int flags) {
+    NetworkTablesJNI.setEntryFlags(m_handle, getFlags() | flags);
+  }
+
+  /**
+   * Clears flags.
+   *
+   * @param flags the flags to clear (bitmask)
+   * @deprecated Use setPersistent() or topic properties instead
+   */
+  @Deprecated(since = "2022", forRemoval = true)
+  public void clearFlags(int flags) {
+    NetworkTablesJNI.setEntryFlags(m_handle, getFlags() & ~flags);
+  }
+
+  /** Make value persistent through program restarts. */
+  public void setPersistent() {
+    NetworkTablesJNI.setTopicPersistent(m_topic.getHandle(), true);
+  }
+
+  /** Stop making value persistent through program restarts. */
+  public void clearPersistent() {
+    NetworkTablesJNI.setTopicPersistent(m_topic.getHandle(), false);
+  }
+
+  /**
+   * Returns whether the value is persistent through program restarts.
+   *
+   * @return True if the value is persistent.
+   */
+  public boolean isPersistent() {
+    return NetworkTablesJNI.getTopicPersistent(m_topic.getHandle());
+  }
+
+  /** Stops publishing the entry if it's been published. */
+  public void unpublish() {
+    NetworkTablesJNI.unpublish(m_handle);
+  }
+
+  /**
+   * Deletes the entry.
+   *
+   * @deprecated Use unpublish() instead.
+   */
+  @Deprecated(since = "2022", forRemoval = true)
+  public void delete() {
+    unpublish();
+  }
+
+  @Override
+  public boolean equals(Object other) {
+    if (other == this) {
+      return true;
+    }
+    if (!(other instanceof NetworkTableEntry)) {
+      return false;
+    }
+
+    return m_handle == ((NetworkTableEntry) other).m_handle;
+  }
+
+  @Override
+  public int hashCode() {
+    return m_handle;
+  }
+
+  private final Topic m_topic;
+  protected int m_handle;
+}
diff --git a/third_party/allwpilib/ntcore/src/generate/java/NetworkTableInstance.java.jinja b/third_party/allwpilib/ntcore/src/generate/java/NetworkTableInstance.java.jinja
new file mode 100644
index 0000000..ba5e33f
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/generate/java/NetworkTableInstance.java.jinja
@@ -0,0 +1,1064 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.networktables;
+
+import edu.wpi.first.util.WPIUtilJNI;
+import edu.wpi.first.util.concurrent.Event;
+import edu.wpi.first.util.datalog.DataLog;
+import java.util.EnumSet;
+import java.util.HashMap;
+import java.util.Map;
+import java.util.OptionalLong;
+import java.util.concurrent.ConcurrentHashMap;
+import java.util.concurrent.ConcurrentMap;
+import java.util.concurrent.TimeUnit;
+import java.util.concurrent.locks.Condition;
+import java.util.concurrent.locks.ReentrantLock;
+import java.util.function.Consumer;
+
+/**
+ * NetworkTables Instance.
+ *
+ * <p>Instances are completely independent from each other. Table operations on one instance will
+ * not be visible to other instances unless the instances are connected via the network. The main
+ * limitation on instances is that you cannot have two servers on the same network port. The main
+ * utility of instances is for unit testing, but they can also enable one program to connect to two
+ * different NetworkTables networks.
+ *
+ * <p>The global "default" instance (as returned by {@link #getDefault()}) is always available, and
+ * is intended for the common case when there is only a single NetworkTables instance being used in
+ * the program.
+ *
+ * <p>Additional instances can be created with the {@link #create()} function. A reference must be
+ * kept to the NetworkTableInstance returned by this function to keep it from being garbage
+ * collected.
+ */
+@SuppressWarnings("PMD.CouplingBetweenObjects")
+public final class NetworkTableInstance implements AutoCloseable {
+  /** Client/server mode flag values (as returned by {@link #getNetworkMode()}). */
+  public enum NetworkMode {
+    /** Running in server mode. */
+    kServer(0x01),
+
+    /** Running in NT3 client mode. */
+    kClient3(0x02),
+
+    /** Running in NT4 client mode. */
+    kClient4(0x04),
+
+    /** Currently starting up (either client or server). */
+    kStarting(0x08),
+
+    /** Running in local-only mode. */
+    kLocal(0x10);
+
+    private final int value;
+
+    NetworkMode(int value) {
+      this.value = value;
+    }
+
+    public int getValue() {
+      return value;
+    }
+  }
+
+  /** The default port that network tables operates on for NT3. */
+  public static final int kDefaultPort3 = 1735;
+
+  /** The default port that network tables operates on for NT4. */
+  public static final int kDefaultPort4 = 5810;
+
+  /**
+   * Construct from native handle.
+   *
+   * @param handle Native handle
+   */
+  private NetworkTableInstance(int handle) {
+    m_owned = false;
+    m_handle = handle;
+  }
+
+  /** Destroys the instance (if created by {@link #create()}). */
+  @Override
+  public synchronized void close() {
+    if (m_owned && m_handle != 0) {
+      m_listeners.close();
+      NetworkTablesJNI.destroyInstance(m_handle);
+      m_handle = 0;
+    }
+  }
+
+  /**
+   * Determines if the native handle is valid.
+   *
+   * @return True if the native handle is valid, false otherwise.
+   */
+  public boolean isValid() {
+    return m_handle != 0;
+  }
+
+  /* The default instance. */
+  private static NetworkTableInstance s_defaultInstance;
+
+  /**
+   * Get global default instance.
+   *
+   * @return Global default instance
+   */
+  public static synchronized NetworkTableInstance getDefault() {
+    if (s_defaultInstance == null) {
+      s_defaultInstance = new NetworkTableInstance(NetworkTablesJNI.getDefaultInstance());
+    }
+    return s_defaultInstance;
+  }
+
+  /**
+   * Create an instance. Note: A reference to the returned instance must be retained to ensure the
+   * instance is not garbage collected.
+   *
+   * @return Newly created instance
+   */
+  public static NetworkTableInstance create() {
+    NetworkTableInstance inst = new NetworkTableInstance(NetworkTablesJNI.createInstance());
+    inst.m_owned = true;
+    return inst;
+  }
+
+  /**
+   * Gets the native handle for the instance.
+   *
+   * @return Native handle
+   */
+  public int getHandle() {
+    return m_handle;
+  }
+
+  /**
+   * Get (generic) topic.
+   *
+   * @param name topic name
+   * @return Topic
+   */
+  public Topic getTopic(String name) {
+    Topic topic = m_topics.get(name);
+    if (topic == null) {
+      int handle = NetworkTablesJNI.getTopic(m_handle, name);
+      topic = new Topic(this, handle);
+      Topic oldTopic = m_topics.putIfAbsent(name, topic);
+      if (oldTopic != null) {
+        topic = oldTopic;
+      }
+      // also cache by handle
+      m_topicsByHandle.putIfAbsent(handle, topic);
+    }
+    return topic;
+  }
+{% for t in types %}
+  /**
+   * Get {{ t.java.ValueType }} topic.
+   *
+   * @param name topic name
+   * @return {{ t.TypeName }}Topic
+   */
+  public {{ t.TypeName }}Topic get{{ t.TypeName }}Topic(String name) {
+    Topic topic = m_topics.get(name);
+    if (topic instanceof {{ t.TypeName }}Topic) {
+      return ({{ t.TypeName }}Topic) topic;
+    }
+
+    int handle;
+    if (topic == null) {
+      handle = NetworkTablesJNI.getTopic(m_handle, name);
+    } else {
+      handle = topic.getHandle();
+    }
+
+    topic = new {{ t.TypeName }}Topic(this, handle);
+    m_topics.put(name, topic);
+
+    // also cache by handle
+    m_topicsByHandle.put(handle, topic);
+
+    return ({{ t.TypeName }}Topic) topic;
+  }
+{% endfor %}
+  private Topic[] topicHandlesToTopics(int[] handles) {
+    Topic[] topics = new Topic[handles.length];
+    for (int i = 0; i < handles.length; i++) {
+      topics[i] = getCachedTopic(handles[i]);
+    }
+    return topics;
+  }
+
+  /**
+   * Get all published topics.
+   *
+   * @return Array of topics.
+   */
+  public Topic[] getTopics() {
+    return topicHandlesToTopics(NetworkTablesJNI.getTopics(m_handle, "", 0));
+  }
+
+  /**
+   * Get published topics starting with the given prefix. The results are optionally filtered by
+   * string prefix to only return a subset of all topics.
+   *
+   * @param prefix topic name required prefix; only topics whose name starts with this string are
+   *     returned
+   * @return Array of topic information.
+   */
+  public Topic[] getTopics(String prefix) {
+    return topicHandlesToTopics(NetworkTablesJNI.getTopics(m_handle, prefix, 0));
+  }
+
+  /**
+   * Get published topics starting with the given prefix. The results are optionally filtered by
+   * string prefix and data type to only return a subset of all topics.
+   *
+   * @param prefix topic name required prefix; only topics whose name starts with this string are
+   *     returned
+   * @param types bitmask of data types; 0 is treated as a "don't care"
+   * @return Array of topic information.
+   */
+  public Topic[] getTopics(String prefix, int types) {
+    return topicHandlesToTopics(NetworkTablesJNI.getTopics(m_handle, prefix, types));
+  }
+
+  /**
+   * Get published topics starting with the given prefix. The results are optionally filtered by
+   * string prefix and data type to only return a subset of all topics.
+   *
+   * @param prefix topic name required prefix; only topics whose name starts with this string are
+   *     returned
+   * @param types array of data type strings
+   * @return Array of topic information.
+   */
+  public Topic[] getTopics(String prefix, String[] types) {
+    return topicHandlesToTopics(NetworkTablesJNI.getTopicsStr(m_handle, prefix, types));
+  }
+
+  /**
+   * Get information about all topics.
+   *
+   * @return Array of topic information.
+   */
+  public TopicInfo[] getTopicInfo() {
+    return NetworkTablesJNI.getTopicInfos(this, m_handle, "", 0);
+  }
+
+  /**
+   * Get information about topics starting with the given prefix. The results are optionally
+   * filtered by string prefix to only return a subset of all topics.
+   *
+   * @param prefix topic name required prefix; only topics whose name starts with this string are
+   *     returned
+   * @return Array of topic information.
+   */
+  public TopicInfo[] getTopicInfo(String prefix) {
+    return NetworkTablesJNI.getTopicInfos(this, m_handle, prefix, 0);
+  }
+
+  /**
+   * Get information about topics starting with the given prefix. The results are optionally
+   * filtered by string prefix and data type to only return a subset of all topics.
+   *
+   * @param prefix topic name required prefix; only topics whose name starts with this string are
+   *     returned
+   * @param types bitmask of data types; 0 is treated as a "don't care"
+   * @return Array of topic information.
+   */
+  public TopicInfo[] getTopicInfo(String prefix, int types) {
+    return NetworkTablesJNI.getTopicInfos(this, m_handle, prefix, types);
+  }
+
+  /**
+   * Get information about topics starting with the given prefix. The results are optionally
+   * filtered by string prefix and data type to only return a subset of all topics.
+   *
+   * @param prefix topic name required prefix; only topics whose name starts with this string are
+   *     returned
+   * @param types array of data type strings
+   * @return Array of topic information.
+   */
+  public TopicInfo[] getTopicInfo(String prefix, String[] types) {
+    return NetworkTablesJNI.getTopicInfosStr(this, m_handle, prefix, types);
+  }
+
+  /* Cache of created entries. */
+  private final ConcurrentMap<String, NetworkTableEntry> m_entries = new ConcurrentHashMap<>();
+
+  /**
+   * Gets the entry for a key.
+   *
+   * @param name Key
+   * @return Network table entry.
+   */
+  public NetworkTableEntry getEntry(String name) {
+    NetworkTableEntry entry = m_entries.get(name);
+    if (entry == null) {
+      entry = new NetworkTableEntry(this, NetworkTablesJNI.getEntry(m_handle, name));
+      NetworkTableEntry oldEntry = m_entries.putIfAbsent(name, entry);
+      if (oldEntry != null) {
+        entry = oldEntry;
+      }
+    }
+    return entry;
+  }
+
+  /* Cache of created topics. */
+  private final ConcurrentMap<String, Topic> m_topics = new ConcurrentHashMap<>();
+  private final ConcurrentMap<Integer, Topic> m_topicsByHandle = new ConcurrentHashMap<>();
+
+  Topic getCachedTopic(String name) {
+    Topic topic = m_topics.get(name);
+    if (topic == null) {
+      int handle = NetworkTablesJNI.getTopic(m_handle, name);
+      topic = new Topic(this, handle);
+      Topic oldTopic = m_topics.putIfAbsent(name, topic);
+      if (oldTopic != null) {
+        topic = oldTopic;
+      }
+      // also cache by handle
+      m_topicsByHandle.putIfAbsent(handle, topic);
+    }
+    return topic;
+  }
+
+  Topic getCachedTopic(int handle) {
+    Topic topic = m_topicsByHandle.get(handle);
+    if (topic == null) {
+      topic = new Topic(this, handle);
+      Topic oldTopic = m_topicsByHandle.putIfAbsent(handle, topic);
+      if (oldTopic != null) {
+        topic = oldTopic;
+      }
+    }
+    return topic;
+  }
+
+  /* Cache of created tables. */
+  private final ConcurrentMap<String, NetworkTable> m_tables = new ConcurrentHashMap<>();
+
+  /**
+   * Gets the table with the specified key.
+   *
+   * @param key the key name
+   * @return The network table
+   */
+  public NetworkTable getTable(String key) {
+    // prepend leading / if not present
+    String theKey;
+    if (key.isEmpty() || "/".equals(key)) {
+      theKey = "";
+    } else if (key.charAt(0) == NetworkTable.PATH_SEPARATOR) {
+      theKey = key;
+    } else {
+      theKey = NetworkTable.PATH_SEPARATOR + key;
+    }
+
+    // cache created tables
+    NetworkTable table = m_tables.get(theKey);
+    if (table == null) {
+      table = new NetworkTable(this, theKey);
+      NetworkTable oldTable = m_tables.putIfAbsent(theKey, table);
+      if (oldTable != null) {
+        table = oldTable;
+      }
+    }
+    return table;
+  }
+
+  /*
+   * Callback Creation Functions
+   */
+
+  private static class ListenerStorage implements AutoCloseable {
+    private final ReentrantLock m_lock = new ReentrantLock();
+    private final Map<Integer, Consumer<NetworkTableEvent>> m_listeners = new HashMap<>();
+    private Thread m_thread;
+    private int m_poller;
+    private boolean m_waitQueue;
+    private final Event m_waitQueueEvent = new Event();
+    private final Condition m_waitQueueCond = m_lock.newCondition();
+    private final NetworkTableInstance m_inst;
+
+    ListenerStorage(NetworkTableInstance inst) {
+      m_inst = inst;
+    }
+
+    int add(
+        String[] prefixes,
+        EnumSet<NetworkTableEvent.Kind> eventKinds,
+        Consumer<NetworkTableEvent> listener) {
+      m_lock.lock();
+      try {
+        if (m_poller == 0) {
+          m_poller = NetworkTablesJNI.createListenerPoller(m_inst.getHandle());
+          startThread();
+        }
+        int h = NetworkTablesJNI.addListener(m_poller, prefixes, eventKinds);
+        m_listeners.put(h, listener);
+        return h;
+      } finally {
+        m_lock.unlock();
+      }
+    }
+
+    int add(
+        int handle,
+        EnumSet<NetworkTableEvent.Kind> eventKinds,
+        Consumer<NetworkTableEvent> listener) {
+      m_lock.lock();
+      try {
+        if (m_poller == 0) {
+          m_poller = NetworkTablesJNI.createListenerPoller(m_inst.getHandle());
+          startThread();
+        }
+        int h = NetworkTablesJNI.addListener(m_poller, handle, eventKinds);
+        m_listeners.put(h, listener);
+        return h;
+      } finally {
+        m_lock.unlock();
+      }
+    }
+
+    int addLogger(int minLevel, int maxLevel, Consumer<NetworkTableEvent> listener) {
+      m_lock.lock();
+      try {
+        if (m_poller == 0) {
+          m_poller = NetworkTablesJNI.createListenerPoller(m_inst.getHandle());
+          startThread();
+        }
+        int h = NetworkTablesJNI.addLogger(m_poller, minLevel, maxLevel);
+        m_listeners.put(h, listener);
+        return h;
+      } finally {
+        m_lock.unlock();
+      }
+    }
+
+    void remove(int listener) {
+      m_lock.lock();
+      try {
+        m_listeners.remove(listener);
+      } finally {
+        m_lock.unlock();
+      }
+      NetworkTablesJNI.removeListener(listener);
+    }
+
+    @Override
+    public void close() {
+      if (m_poller != 0) {
+        NetworkTablesJNI.destroyListenerPoller(m_poller);
+      }
+      m_poller = 0;
+    }
+
+    private void startThread() {
+      m_thread =
+          new Thread(
+              () -> {
+                boolean wasInterrupted = false;
+                int[] handles = new int[] { m_poller, m_waitQueueEvent.getHandle() };
+                while (!Thread.interrupted()) {
+                  try {
+                    WPIUtilJNI.waitForObjects(handles);
+                  } catch (InterruptedException ex) {
+                    m_lock.lock();
+                    try {
+                      if (m_waitQueue) {
+                        m_waitQueue = false;
+                        m_waitQueueCond.signalAll();
+                      }
+                    } finally {
+                      m_lock.unlock();
+                    }
+                    Thread.currentThread().interrupt();
+                    // don't try to destroy poller, as its handle is likely no longer valid
+                    wasInterrupted = true;
+                    break;
+                  }
+                  for (NetworkTableEvent event :
+                      NetworkTablesJNI.readListenerQueue(m_inst, m_poller)) {
+                    Consumer<NetworkTableEvent> listener;
+                    m_lock.lock();
+                    try {
+                      listener = m_listeners.get(event.listener);
+                    } finally {
+                      m_lock.unlock();
+                    }
+                    if (listener != null) {
+                      try {
+                        listener.accept(event);
+                      } catch (Throwable throwable) {
+                        System.err.println(
+                            "Unhandled exception during listener callback: "
+                            + throwable.toString());
+                        throwable.printStackTrace();
+                      }
+                    }
+                  }
+                  m_lock.lock();
+                  try {
+                    if (m_waitQueue) {
+                      m_waitQueue = false;
+                      m_waitQueueCond.signalAll();
+                    }
+                  } finally {
+                    m_lock.unlock();
+                  }
+                }
+                m_lock.lock();
+                try {
+                  if (!wasInterrupted) {
+                    NetworkTablesJNI.destroyListenerPoller(m_poller);
+                  }
+                  m_poller = 0;
+                } finally {
+                  m_lock.unlock();
+                }
+              },
+              "NTListener");
+      m_thread.setDaemon(true);
+      m_thread.start();
+    }
+
+    boolean waitForQueue(double timeout) {
+      m_lock.lock();
+      try {
+        if (m_poller != 0) {
+          m_waitQueue = true;
+          m_waitQueueEvent.set();
+          while (m_waitQueue) {
+            try {
+              if (timeout < 0) {
+                m_waitQueueCond.await();
+              } else {
+                return m_waitQueueCond.await((long) (timeout * 1e9), TimeUnit.NANOSECONDS);
+              }
+            } catch (InterruptedException ex) {
+              Thread.currentThread().interrupt();
+              return true;
+            }
+          }
+        }
+      } finally {
+        m_lock.unlock();
+      }
+      return true;
+    }
+  }
+
+  private ListenerStorage m_listeners = new ListenerStorage(this);
+
+  /**
+   * Remove a connection listener.
+   *
+   * @param listener Listener handle to remove
+   */
+  public void removeListener(int listener) {
+    m_listeners.remove(listener);
+  }
+
+  /**
+   * Wait for the listener queue to be empty. This is primarily useful for deterministic
+   * testing. This blocks until either the listener queue is empty (e.g. there are no
+   * more events that need to be passed along to callbacks or poll queues) or the timeout expires.
+   *
+   * @param timeout timeout, in seconds. Set to 0 for non-blocking behavior, or a negative value to
+   *     block indefinitely
+   * @return False if timed out, otherwise true.
+   */
+  public boolean waitForListenerQueue(double timeout) {
+    return m_listeners.waitForQueue(timeout);
+  }
+
+  /**
+   * Add a connection listener. The callback function is called asynchronously on a separate
+   * thread, so it's important to use synchronization or atomics when accessing any shared state
+   * from the callback function.
+   *
+   * @param immediateNotify Notify listener of all existing connections
+   * @param listener Listener to add
+   * @return Listener handle
+   */
+  public int addConnectionListener(
+      boolean immediateNotify, Consumer<NetworkTableEvent> listener) {
+    EnumSet<NetworkTableEvent.Kind> eventKinds = EnumSet.of(NetworkTableEvent.Kind.kConnection);
+    if (immediateNotify) {
+      eventKinds.add(NetworkTableEvent.Kind.kImmediate);
+    }
+    return m_listeners.add(m_handle, eventKinds, listener);
+  }
+
+  /**
+   * Add a time synchronization listener. The callback function is called asynchronously on a
+   * separate thread, so it's important to use synchronization or atomics when accessing any shared
+   * state from the callback function.
+   *
+   * @param immediateNotify Notify listener of current time synchronization value
+   * @param listener Listener to add
+   * @return Listener handle
+   */
+  public int addTimeSyncListener(
+      boolean immediateNotify, Consumer<NetworkTableEvent> listener) {
+    EnumSet<NetworkTableEvent.Kind> eventKinds = EnumSet.of(NetworkTableEvent.Kind.kTimeSync);
+    if (immediateNotify) {
+      eventKinds.add(NetworkTableEvent.Kind.kImmediate);
+    }
+    return m_listeners.add(m_handle, eventKinds, listener);
+  }
+
+  /**
+   * Add a listener for changes on a particular topic. The callback function is called
+   * asynchronously on a separate thread, so it's important to use synchronization or atomics when
+   * accessing any shared state from the callback function.
+   *
+   * <p>This creates a corresponding internal subscriber with the lifetime of the
+   * listener.
+   *
+   * @param topic Topic
+   * @param eventKinds set of event kinds to listen to
+   * @param listener Listener function
+   * @return Listener handle
+   */
+  public int addListener(
+      Topic topic,
+      EnumSet<NetworkTableEvent.Kind> eventKinds,
+      Consumer<NetworkTableEvent> listener) {
+    if (topic.getInstance().getHandle() != m_handle) {
+      throw new IllegalArgumentException("topic is not from this instance");
+    }
+    return m_listeners.add(topic.getHandle(), eventKinds, listener);
+  }
+
+  /**
+   * Add a listener for changes on a subscriber. The callback function is called
+   * asynchronously on a separate thread, so it's important to use synchronization or atomics when
+   * accessing any shared state from the callback function. This does NOT keep the subscriber
+   * active.
+   *
+   * @param subscriber Subscriber
+   * @param eventKinds set of event kinds to listen to
+   * @param listener Listener function
+   * @return Listener handle
+   */
+  public int addListener(
+      Subscriber subscriber,
+      EnumSet<NetworkTableEvent.Kind> eventKinds,
+      Consumer<NetworkTableEvent> listener) {
+    if (subscriber.getTopic().getInstance().getHandle() != m_handle) {
+      throw new IllegalArgumentException("subscriber is not from this instance");
+    }
+    return m_listeners.add(subscriber.getHandle(), eventKinds, listener);
+  }
+
+  /**
+   * Add a listener for changes on a subscriber. The callback function is called
+   * asynchronously on a separate thread, so it's important to use synchronization or atomics when
+   * accessing any shared state from the callback function. This does NOT keep the subscriber
+   * active.
+   *
+   * @param subscriber Subscriber
+   * @param eventKinds set of event kinds to listen to
+   * @param listener Listener function
+   * @return Listener handle
+   */
+  public int addListener(
+      MultiSubscriber subscriber,
+      EnumSet<NetworkTableEvent.Kind> eventKinds,
+      Consumer<NetworkTableEvent> listener) {
+    if (subscriber.getInstance().getHandle() != m_handle) {
+      throw new IllegalArgumentException("subscriber is not from this instance");
+    }
+    return m_listeners.add(subscriber.getHandle(), eventKinds, listener);
+  }
+
+  /**
+   * Add a listener for changes on an entry. The callback function is called
+   * asynchronously on a separate thread, so it's important to use synchronization or atomics when
+   * accessing any shared state from the callback function.
+   *
+   * @param entry Entry
+   * @param eventKinds set of event kinds to listen to
+   * @param listener Listener function
+   * @return Listener handle
+   */
+  public int addListener(
+      NetworkTableEntry entry,
+      EnumSet<NetworkTableEvent.Kind> eventKinds,
+      Consumer<NetworkTableEvent> listener) {
+    if (entry.getTopic().getInstance().getHandle() != m_handle) {
+      throw new IllegalArgumentException("entry is not from this instance");
+    }
+    return m_listeners.add(entry.getHandle(), eventKinds, listener);
+  }
+
+  /**
+   * Add a listener for changes to topics with names that start with any of the given
+   * prefixes. The callback function is called asynchronously on a separate thread, so it's
+   * important to use synchronization or atomics when accessing any shared state from the callback
+   * function.
+   *
+   * <p>This creates a corresponding internal subscriber with the lifetime of the
+   * listener.
+   *
+   * @param prefixes Topic name string prefixes
+   * @param eventKinds set of event kinds to listen to
+   * @param listener Listener function
+   * @return Listener handle
+   */
+  public int addListener(
+      String[] prefixes,
+      EnumSet<NetworkTableEvent.Kind> eventKinds,
+      Consumer<NetworkTableEvent> listener) {
+    return m_listeners.add(prefixes, eventKinds, listener);
+  }
+
+  /*
+   * Client/Server Functions
+   */
+
+  /**
+   * Get the current network mode.
+   *
+   * @return Enum set of NetworkMode.
+   */
+  public EnumSet<NetworkMode> getNetworkMode() {
+    int flags = NetworkTablesJNI.getNetworkMode(m_handle);
+    EnumSet<NetworkMode> rv = EnumSet.noneOf(NetworkMode.class);
+    for (NetworkMode mode : NetworkMode.values()) {
+      if ((flags & mode.getValue()) != 0) {
+        rv.add(mode);
+      }
+    }
+    return rv;
+  }
+
+  /**
+   * Starts local-only operation. Prevents calls to startServer or startClient from taking effect.
+   * Has no effect if startServer or startClient has already been called.
+   */
+  public void startLocal() {
+    NetworkTablesJNI.startLocal(m_handle);
+  }
+
+  /**
+   * Stops local-only operation. startServer or startClient can be called after this call to start
+   * a server or client.
+   */
+  public void stopLocal() {
+    NetworkTablesJNI.stopLocal(m_handle);
+  }
+
+  /**
+   * Starts a server using the networktables.json as the persistent file, using the default
+   * listening address and port.
+   */
+  public void startServer() {
+    startServer("networktables.json");
+  }
+
+  /**
+   * Starts a server using the specified persistent filename, using the default listening address
+   * and port.
+   *
+   * @param persistFilename the name of the persist file to use
+   */
+  public void startServer(String persistFilename) {
+    startServer(persistFilename, "");
+  }
+
+  /**
+   * Starts a server using the specified filename and listening address, using the default port.
+   *
+   * @param persistFilename the name of the persist file to use
+   * @param listenAddress the address to listen on, or empty to listen on any address
+   */
+  public void startServer(String persistFilename, String listenAddress) {
+    startServer(persistFilename, listenAddress, kDefaultPort3, kDefaultPort4);
+  }
+
+  /**
+   * Starts a server using the specified filename, listening address, and port.
+   *
+   * @param persistFilename the name of the persist file to use
+   * @param listenAddress the address to listen on, or empty to listen on any address
+   * @param port3 port to communicate over (NT3)
+   */
+  public void startServer(String persistFilename, String listenAddress, int port3) {
+    startServer(persistFilename, listenAddress, port3, kDefaultPort4);
+  }
+
+  /**
+   * Starts a server using the specified filename, listening address, and port.
+   *
+   * @param persistFilename the name of the persist file to use
+   * @param listenAddress the address to listen on, or empty to listen on any address
+   * @param port3 port to communicate over (NT3)
+   * @param port4 port to communicate over (NT4)
+   */
+  public void startServer(String persistFilename, String listenAddress, int port3, int port4) {
+    NetworkTablesJNI.startServer(m_handle, persistFilename, listenAddress, port3, port4);
+  }
+
+  /** Stops the server if it is running. */
+  public void stopServer() {
+    NetworkTablesJNI.stopServer(m_handle);
+  }
+
+  /**
+   * Starts a NT3 client. Use SetServer or SetServerTeam to set the server name and port.
+   *
+   * @param identity network identity to advertise (cannot be empty string)
+   */
+  public void startClient3(String identity) {
+    NetworkTablesJNI.startClient3(m_handle, identity);
+  }
+
+  /**
+   * Starts a NT4 client. Use SetServer or SetServerTeam to set the server name and port.
+   *
+   * @param identity network identity to advertise (cannot be empty string)
+   */
+  public void startClient4(String identity) {
+    NetworkTablesJNI.startClient4(m_handle, identity);
+  }
+
+  /** Stops the client if it is running. */
+  public void stopClient() {
+    NetworkTablesJNI.stopClient(m_handle);
+  }
+
+  /**
+   * Sets server address and port for client (without restarting client). Changes the port to the
+   * default port.
+   *
+   * @param serverName server name
+   */
+  public void setServer(String serverName) {
+    setServer(serverName, 0);
+  }
+
+  /**
+   * Sets server address and port for client (without restarting client).
+   *
+   * @param serverName server name
+   * @param port port to communicate over (0=default)
+   */
+  public void setServer(String serverName, int port) {
+    NetworkTablesJNI.setServer(m_handle, serverName, port);
+  }
+
+  /**
+   * Sets server addresses and port for client (without restarting client). Changes the port to the
+   * default port. The client will attempt to connect to each server in round robin fashion.
+   *
+   * @param serverNames array of server names
+   */
+  public void setServer(String[] serverNames) {
+    setServer(serverNames, 0);
+  }
+
+  /**
+   * Sets server addresses and port for client (without restarting client). The client will attempt
+   * to connect to each server in round robin fashion.
+   *
+   * @param serverNames array of server names
+   * @param port port to communicate over (0=default)
+   */
+  public void setServer(String[] serverNames, int port) {
+    int[] ports = new int[serverNames.length];
+    for (int i = 0; i < serverNames.length; i++) {
+      ports[i] = port;
+    }
+    setServer(serverNames, ports);
+  }
+
+  /**
+   * Sets server addresses and ports for client (without restarting client). The client will
+   * attempt to connect to each server in round robin fashion.
+   *
+   * @param serverNames array of server names
+   * @param ports array of port numbers (0=default)
+   */
+  public void setServer(String[] serverNames, int[] ports) {
+    NetworkTablesJNI.setServer(m_handle, serverNames, ports);
+  }
+
+  /**
+   * Sets server addresses and port for client (without restarting client). Changes the port to the
+   * default port. The client will attempt to connect to each server in round robin fashion.
+   *
+   * @param team team number
+   */
+  public void setServerTeam(int team) {
+    setServerTeam(team, 0);
+  }
+
+  /**
+   * Sets server addresses and port for client (without restarting client). Connects using commonly
+   * known robot addresses for the specified team.
+   *
+   * @param team team number
+   * @param port port to communicate over (0=default)
+   */
+  public void setServerTeam(int team, int port) {
+    NetworkTablesJNI.setServerTeam(m_handle, team, port);
+  }
+
+  /**
+   * Starts requesting server address from Driver Station. This connects to the Driver Station
+   * running on localhost to obtain the server IP address, and connects with the default port.
+   */
+  public void startDSClient() {
+    startDSClient(0);
+  }
+
+  /**
+   * Starts requesting server address from Driver Station. This connects to the Driver Station
+   * running on localhost to obtain the server IP address.
+   *
+   * @param port server port to use in combination with IP from DS (0=default)
+   */
+  public void startDSClient(int port) {
+    NetworkTablesJNI.startDSClient(m_handle, port);
+  }
+
+  /** Stops requesting server address from Driver Station. */
+  public void stopDSClient() {
+    NetworkTablesJNI.stopDSClient(m_handle);
+  }
+
+  /**
+   * Flushes all updated values immediately to the local client/server. This does not flush to the
+   * network.
+   */
+  public void flushLocal() {
+    NetworkTablesJNI.flushLocal(m_handle);
+  }
+
+  /**
+   * Flushes all updated values immediately to the network. Note: This is rate-limited to protect
+   * the network from flooding. This is primarily useful for synchronizing network updates with
+   * user code.
+   */
+  public void flush() {
+    NetworkTablesJNI.flush(m_handle);
+  }
+
+  /**
+   * Gets information on the currently established network connections. If operating as a client,
+   * this will return either zero or one values.
+   *
+   * @return array of connection information
+   */
+  public ConnectionInfo[] getConnections() {
+    return NetworkTablesJNI.getConnections(m_handle);
+  }
+
+  /**
+   * Return whether or not the instance is connected to another node.
+   *
+   * @return True if connected.
+   */
+  public boolean isConnected() {
+    return NetworkTablesJNI.isConnected(m_handle);
+  }
+
+  /**
+   * Get the time offset between server time and local time. Add this value to local time to get
+   * the estimated equivalent server time. In server mode, this always returns 0. In client mode,
+   * this returns the time offset only if the client and server are connected and have exchanged
+   * synchronization messages. Note the time offset may change over time as it is periodically
+   * updated; to receive updates as events, add a listener to the "time sync" event.
+   *
+   * @return Time offset in microseconds (optional)
+   */
+  public OptionalLong getServerTimeOffset() {
+    return NetworkTablesJNI.getServerTimeOffset(m_handle);
+  }
+
+  /**
+   * Starts logging entry changes to a DataLog.
+   *
+   * @param log data log object; lifetime must extend until StopEntryDataLog is called or the
+   *     instance is destroyed
+   * @param prefix only store entries with names that start with this prefix; the prefix is not
+   *     included in the data log entry name
+   * @param logPrefix prefix to add to data log entry names
+   * @return Data logger handle
+   */
+  public int startEntryDataLog(DataLog log, String prefix, String logPrefix) {
+    return NetworkTablesJNI.startEntryDataLog(m_handle, log, prefix, logPrefix);
+  }
+
+  /**
+   * Stops logging entry changes to a DataLog.
+   *
+   * @param logger data logger handle
+   */
+  public static void stopEntryDataLog(int logger) {
+    NetworkTablesJNI.stopEntryDataLog(logger);
+  }
+
+  /**
+   * Starts logging connection changes to a DataLog.
+   *
+   * @param log data log object; lifetime must extend until StopConnectionDataLog is called or the
+   *     instance is destroyed
+   * @param name data log entry name
+   * @return Data logger handle
+   */
+  public int startConnectionDataLog(DataLog log, String name) {
+    return NetworkTablesJNI.startConnectionDataLog(m_handle, log, name);
+  }
+
+  /**
+   * Stops logging connection changes to a DataLog.
+   *
+   * @param logger data logger handle
+   */
+  public static void stopConnectionDataLog(int logger) {
+    NetworkTablesJNI.stopConnectionDataLog(logger);
+  }
+
+  /**
+   * Add logger callback function. By default, log messages are sent to stderr; this function sends
+   * log messages with the specified levels to the provided callback function instead. The callback
+   * function will only be called for log messages with level greater than or equal to minLevel and
+   * less than or equal to maxLevel; messages outside this range will be silently ignored.
+   *
+   * @param minLevel minimum log level
+   * @param maxLevel maximum log level
+   * @param func callback function
+   * @return Listener handle
+   */
+  public int addLogger(int minLevel, int maxLevel, Consumer<NetworkTableEvent> func) {
+    return m_listeners.addLogger(minLevel, maxLevel, func);
+  }
+
+  @Override
+  public boolean equals(Object other) {
+    if (other == this) {
+      return true;
+    }
+    if (!(other instanceof NetworkTableInstance)) {
+      return false;
+    }
+
+    return m_handle == ((NetworkTableInstance) other).m_handle;
+  }
+
+  @Override
+  public int hashCode() {
+    return m_handle;
+  }
+
+  private boolean m_owned;
+  private int m_handle;
+}
diff --git a/third_party/allwpilib/ntcore/src/generate/java/NetworkTableValue.java.jinja b/third_party/allwpilib/ntcore/src/generate/java/NetworkTableValue.java.jinja
new file mode 100644
index 0000000..d2c8d11
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/generate/java/NetworkTableValue.java.jinja
@@ -0,0 +1,248 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.networktables;
+
+import java.util.Objects;
+
+/** A network table entry value. */
+@SuppressWarnings({"UnnecessaryParentheses", "PMD.MethodReturnsInternalArray"})
+public final class NetworkTableValue {
+  NetworkTableValue(NetworkTableType type, Object value, long time, long serverTime) {
+    m_type = type;
+    m_value = value;
+    m_time = time;
+    m_serverTime = serverTime;
+  }
+
+  NetworkTableValue(NetworkTableType type, Object value, long time) {
+    this(type, value, time, time == 0 ? 0 : 1);
+  }
+
+  NetworkTableValue(NetworkTableType type, Object value) {
+    this(type, value, NetworkTablesJNI.now(), 1);
+  }
+
+  NetworkTableValue(int type, Object value, long time, long serverTime) {
+    this(NetworkTableType.getFromInt(type), value, time, serverTime);
+  }
+
+  /**
+   * Get the data type.
+   *
+   * @return The type.
+   */
+  public NetworkTableType getType() {
+    return m_type;
+  }
+
+  /**
+   * Get the data value stored.
+   *
+   * @return The type.
+   */
+  public Object getValue() {
+    return m_value;
+  }
+
+  /**
+   * Get the creation time of the value in local time.
+   *
+   * @return The time, in the units returned by NetworkTablesJNI.now().
+   */
+  public long getTime() {
+    return m_time;
+  }
+
+  /**
+   * Get the creation time of the value in server time.
+   *
+   * @return The server time.
+   */
+  public long getServerTime() {
+    return m_serverTime;
+  }
+
+  /*
+   * Type Checkers
+   */
+
+  /**
+   * Determine if entry value contains a value or is unassigned.
+   *
+   * @return True if the entry value contains a value.
+   */
+  public boolean isValid() {
+    return m_type != NetworkTableType.kUnassigned;
+  }
+{% for t in types %}
+  /**
+   * Determine if entry value contains a {{ t.java.ValueType }}.
+   *
+   * @return True if the entry value is of {{ t.java.ValueType }} type.
+   */
+  public boolean is{{ t.TypeName }}() {
+    return m_type == NetworkTableType.k{{ t.TypeName }};
+  }
+{% endfor %}
+  /*
+   * Type-Safe Getters
+   */
+{% for t in types %}
+  /**
+   * Get the {{ t.java.ValueType }} value.
+   *
+   * @return The {{ t.java.ValueType }} value.
+   * @throws ClassCastException if the entry value is not of {{ t.java.ValueType }} type.
+   */
+  public {{ t.java.ValueType }} get{{ t.TypeName }}() {
+    if (m_type != NetworkTableType.k{{ t.TypeName }}) {
+      throw new ClassCastException("cannot convert " + m_type + " to {{ t.java.ValueType }}");
+    }
+    return {{ t.java.FromStorageBegin }}m_value{{ t.java.FromStorageEnd }};
+  }
+{% endfor %}
+  /*
+   * Factory functions.
+   */
+{% for t in types %}
+  /**
+   * Creates a {{ t.java.ValueType }} value.
+   *
+   * @param value the value
+   * @return The entry value
+   */
+  public static NetworkTableValue make{{ t.TypeName }}({{ t.java.ValueType }} value) {
+    return new NetworkTableValue(NetworkTableType.k{{ t.TypeName }}, {{ t.java.ToWrapObject }}(value));
+  }
+
+  /**
+   * Creates a {{ t.java.ValueType }} value.
+   *
+   * @param value the value
+   * @param time the creation time to use (instead of the current time)
+   * @return The entry value
+   */
+  public static NetworkTableValue make{{ t.TypeName }}({{ t.java.ValueType }} value, long time) {
+    return new NetworkTableValue(NetworkTableType.k{{ t.TypeName }}, {{ t.java.ToWrapObject }}(value), time);
+  }
+{% if t.java.WrapValueType %}
+  /**
+   * Creates a {{ t.java.ValueType }} value.
+   *
+   * @param value the value
+   * @return The entry value
+   */
+  public static NetworkTableValue make{{ t.TypeName }}({{ t.java.WrapValueType }} value) {
+    return new NetworkTableValue(NetworkTableType.k{{ t.TypeName }}, toNative{{ t.TypeName }}(value));
+  }
+
+  /**
+   * Creates a {{ t.java.ValueType }} value.
+   *
+   * @param value the value
+   * @param time the creation time to use (instead of the current time)
+   * @return The entry value
+   */
+  public static NetworkTableValue make{{ t.TypeName }}({{ t.java.WrapValueType }} value, long time) {
+    return new NetworkTableValue(NetworkTableType.k{{ t.TypeName }}, toNative{{ t.TypeName }}(value), time);
+  }
+{% endif -%}
+{% endfor %}
+  @Override
+  public boolean equals(Object other) {
+    if (other == this) {
+      return true;
+    }
+    if (!(other instanceof NetworkTableValue)) {
+      return false;
+    }
+    NetworkTableValue ntOther = (NetworkTableValue) other;
+    return m_type == ntOther.m_type && m_value.equals(ntOther.m_value);
+  }
+
+  @Override
+  public int hashCode() {
+    return Objects.hash(m_type, m_value);
+  }
+
+  // arraycopy() doesn't know how to unwrap boxed values; this is a false positive in PMD
+  // (see https://sourceforge.net/p/pmd/bugs/804/)
+  @SuppressWarnings("PMD.AvoidArrayLoops")
+  static boolean[] toNativeBooleanArray(Boolean[] arr) {
+    boolean[] out = new boolean[arr.length];
+    for (int i = 0; i < arr.length; i++) {
+      out[i] = arr[i];
+    }
+    return out;
+  }
+
+  @SuppressWarnings("PMD.AvoidArrayLoops")
+  static double[] toNativeDoubleArray(Number[] arr) {
+    double[] out = new double[arr.length];
+    for (int i = 0; i < arr.length; i++) {
+      out[i] = arr[i].doubleValue();
+    }
+    return out;
+  }
+
+  @SuppressWarnings("PMD.AvoidArrayLoops")
+  static long[] toNativeIntegerArray(Number[] arr) {
+    long[] out = new long[arr.length];
+    for (int i = 0; i < arr.length; i++) {
+      out[i] = arr[i].longValue();
+    }
+    return out;
+  }
+
+  @SuppressWarnings("PMD.AvoidArrayLoops")
+  static float[] toNativeFloatArray(Number[] arr) {
+    float[] out = new float[arr.length];
+    for (int i = 0; i < arr.length; i++) {
+      out[i] = arr[i].floatValue();
+    }
+    return out;
+  }
+
+  @SuppressWarnings("PMD.AvoidArrayLoops")
+  static Boolean[] fromNativeBooleanArray(boolean[] arr) {
+    Boolean[] out = new Boolean[arr.length];
+    for (int i = 0; i < arr.length; i++) {
+      out[i] = arr[i];
+    }
+    return out;
+  }
+
+  @SuppressWarnings("PMD.AvoidArrayLoops")
+  static Long[] fromNativeIntegerArray(long[] arr) {
+    Long[] out = new Long[arr.length];
+    for (int i = 0; i < arr.length; i++) {
+      out[i] = arr[i];
+    }
+    return out;
+  }
+
+  @SuppressWarnings("PMD.AvoidArrayLoops")
+  static Float[] fromNativeFloatArray(float[] arr) {
+    Float[] out = new Float[arr.length];
+    for (int i = 0; i < arr.length; i++) {
+      out[i] = arr[i];
+    }
+    return out;
+  }
+
+  @SuppressWarnings("PMD.AvoidArrayLoops")
+  static Double[] fromNativeDoubleArray(double[] arr) {
+    Double[] out = new Double[arr.length];
+    for (int i = 0; i < arr.length; i++) {
+      out[i] = arr[i];
+    }
+    return out;
+  }
+
+  private NetworkTableType m_type;
+  private Object m_value;
+  private long m_time;
+  private long m_serverTime;
+}
diff --git a/third_party/allwpilib/ntcore/src/generate/java/NetworkTablesJNI.java.jinja b/third_party/allwpilib/ntcore/src/generate/java/NetworkTablesJNI.java.jinja
new file mode 100644
index 0000000..2f119fe
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/generate/java/NetworkTablesJNI.java.jinja
@@ -0,0 +1,287 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.networktables;
+
+import edu.wpi.first.util.RuntimeLoader;
+import edu.wpi.first.util.datalog.DataLog;
+import java.io.IOException;
+import java.util.EnumSet;
+import java.util.OptionalLong;
+import java.util.concurrent.atomic.AtomicBoolean;
+
+public final class NetworkTablesJNI {
+  static boolean libraryLoaded = false;
+  static RuntimeLoader<NetworkTablesJNI> loader = null;
+
+  public static class Helper {
+    private static AtomicBoolean extractOnStaticLoad = new AtomicBoolean(true);
+
+    public static boolean getExtractOnStaticLoad() {
+      return extractOnStaticLoad.get();
+    }
+
+    public static void setExtractOnStaticLoad(boolean load) {
+      extractOnStaticLoad.set(load);
+    }
+  }
+
+  static {
+    if (Helper.getExtractOnStaticLoad()) {
+      try {
+        loader =
+            new RuntimeLoader<>(
+                "ntcorejni", RuntimeLoader.getDefaultExtractionRoot(), NetworkTablesJNI.class);
+        loader.loadLibrary();
+      } catch (IOException ex) {
+        ex.printStackTrace();
+        System.exit(1);
+      }
+      libraryLoaded = true;
+    }
+  }
+
+  /**
+   * Force load the library.
+   *
+   * @throws IOException if the library fails to load
+   */
+  public static synchronized void forceLoad() throws IOException {
+    if (libraryLoaded) {
+      return;
+    }
+    loader =
+        new RuntimeLoader<>(
+            "ntcorejni", RuntimeLoader.getDefaultExtractionRoot(), NetworkTablesJNI.class);
+    loader.loadLibrary();
+    libraryLoaded = true;
+  }
+
+  private static PubSubOptions buildOptions(PubSubOption... options) {
+    if (options.length == 0) {
+      return null;  // optimize common case (JNI checks for null)
+    }
+    return new PubSubOptions(options);
+  }
+
+  public static native int getDefaultInstance();
+
+  public static native int createInstance();
+
+  public static native void destroyInstance(int inst);
+
+  public static native int getInstanceFromHandle(int handle);
+
+  private static native int getEntryImpl(
+      int topic, int type, String typeStr, PubSubOptions options);
+
+  public static native int getEntry(int inst, String key);
+
+  public static int getEntry(
+      int topic, int type, String typeStr, PubSubOptions options) {
+    return getEntryImpl(topic, type, typeStr, options);
+  }
+
+  public static int getEntry(
+      int topic, int type, String typeStr, PubSubOption... options) {
+    return getEntryImpl(topic, type, typeStr, buildOptions(options));
+  }
+
+  public static native String getEntryName(int entry);
+
+  public static native long getEntryLastChange(int entry);
+
+  public static native int getType(int entry);
+
+  /* Topic functions */
+
+  public static native int[] getTopics(int inst, String prefix, int types);
+
+  public static native int[] getTopicsStr(int inst, String prefix, String[] types);
+
+  public static native TopicInfo[] getTopicInfos(
+      NetworkTableInstance instObject, int inst, String prefix, int types);
+
+  public static native TopicInfo[] getTopicInfosStr(
+      NetworkTableInstance instObject, int inst, String prefix, String[] types);
+
+  public static native int getTopic(int inst, String name);
+
+  public static native String getTopicName(int topic);
+
+  public static native int getTopicType(int topic);
+
+  public static native void setTopicPersistent(int topic, boolean value);
+
+  public static native boolean getTopicPersistent(int topic);
+
+  public static native void setTopicRetained(int topic, boolean value);
+
+  public static native boolean getTopicRetained(int topic);
+
+  public static native String getTopicTypeString(int topic);
+
+  public static native boolean getTopicExists(int topic);
+
+  public static native String getTopicProperty(int topic, String name);
+
+  public static native void setTopicProperty(int topic, String name, String value);
+
+  public static native void deleteTopicProperty(int topic, String name);
+
+  public static native String getTopicProperties(int topic);
+
+  public static native void setTopicProperties(int topic, String properties);
+
+  public static native int subscribe(
+      int topic, int type, String typeStr, PubSubOptions options);
+
+  public static int subscribe(
+      int topic, int type, String typeStr, PubSubOption... options) {
+    return subscribe(topic, type, typeStr, buildOptions(options));
+  }
+
+  public static native void unsubscribe(int sub);
+
+  public static native int publish(
+      int topic, int type, String typeStr, PubSubOptions options);
+
+  public static int publish(
+      int topic, int type, String typeStr, PubSubOption... options) {
+    return publish(topic, type, typeStr, buildOptions(options));
+  }
+
+  public static native int publishEx(
+      int topic, int type, String typeStr, String properties, PubSubOptions options);
+
+  public static int publishEx(
+      int topic, int type, String typeStr, String properties, PubSubOption... options) {
+    return publishEx(topic, type, typeStr, properties, buildOptions(options));
+  }
+
+  public static native void unpublish(int pubentry);
+
+  public static native void releaseEntry(int entry);
+
+  public static native void release(int pubsubentry);
+
+  public static native int getTopicFromHandle(int pubsubentry);
+
+  public static native int subscribeMultiple(int inst, String[] prefixes, PubSubOptions options);
+
+  public static int subscribeMultiple(int inst, String[] prefixes, PubSubOption... options) {
+    return subscribeMultiple(inst, prefixes, buildOptions(options));
+  }
+
+  public static native void unsubscribeMultiple(int sub);
+{% for t in types %}
+  public static native Timestamped{{ t.TypeName }} getAtomic{{ t.TypeName }}(
+      int subentry, {{ t.java.ValueType }} defaultValue);
+
+  public static native Timestamped{{ t.TypeName }}[] readQueue{{ t.TypeName }}(int subentry);
+
+  public static native {{ t.java.ValueType }}[] readQueueValues{{ t.TypeName }}(int subentry);
+
+  public static native boolean set{{ t.TypeName }}(int entry, long time, {{ t.java.ValueType }} value);
+
+  public static native {{ t.java.ValueType }} get{{ t.TypeName }}(int entry, {{ t.java.ValueType }} defaultValue);
+
+  public static native boolean setDefault{{ t.TypeName }}(int entry, long time, {{ t.java.ValueType }} defaultValue);
+{% endfor %}
+  public static native NetworkTableValue[] readQueueValue(int subentry);
+
+  public static native NetworkTableValue getValue(int entry);
+
+  public static native void setEntryFlags(int entry, int flags);
+
+  public static native int getEntryFlags(int entry);
+
+  public static native TopicInfo getTopicInfo(NetworkTableInstance inst, int topic);
+
+  public static native int createListenerPoller(int inst);
+
+  public static native void destroyListenerPoller(int poller);
+
+  private static int kindsToMask(EnumSet<NetworkTableEvent.Kind> kinds) {
+    int mask = 0;
+    for (NetworkTableEvent.Kind kind : kinds) {
+      mask |= kind.getValue();
+    }
+    return mask;
+  }
+
+  public static int addListener(int poller, String[] prefixes, EnumSet<NetworkTableEvent.Kind> kinds) {
+    return addListener(poller, prefixes, kindsToMask(kinds));
+  }
+
+  public static int addListener(int poller, int handle, EnumSet<NetworkTableEvent.Kind> kinds) {
+    return addListener(poller, handle, kindsToMask(kinds));
+  }
+
+  public static native int addListener(int poller, String[] prefixes, int mask);
+
+  public static native int addListener(int poller, int handle, int mask);
+
+  public static native NetworkTableEvent[] readListenerQueue(
+      NetworkTableInstance inst, int poller);
+
+  public static native void removeListener(int listener);
+
+  public static native int getNetworkMode(int inst);
+
+  public static native void startLocal(int inst);
+
+  public static native void stopLocal(int inst);
+
+  public static native void startServer(
+      int inst, String persistFilename, String listenAddress, int port3, int port4);
+
+  public static native void stopServer(int inst);
+
+  public static native void startClient3(int inst, String identity);
+
+  public static native void startClient4(int inst, String identity);
+
+  public static native void stopClient(int inst);
+
+  public static native void setServer(int inst, String serverName, int port);
+
+  public static native void setServer(int inst, String[] serverNames, int[] ports);
+
+  public static native void setServerTeam(int inst, int team, int port);
+
+  public static native void startDSClient(int inst, int port);
+
+  public static native void stopDSClient(int inst);
+
+  public static native void flushLocal(int inst);
+
+  public static native void flush(int inst);
+
+  public static native ConnectionInfo[] getConnections(int inst);
+
+  public static native boolean isConnected(int inst);
+
+  public static native OptionalLong getServerTimeOffset(int inst);
+
+  public static native long now();
+
+  private static native int startEntryDataLog(int inst, long log, String prefix, String logPrefix);
+
+  public static int startEntryDataLog(int inst, DataLog log, String prefix, String logPrefix) {
+    return startEntryDataLog(inst, log.getImpl(), prefix, logPrefix);
+  }
+
+  public static native void stopEntryDataLog(int logger);
+
+  private static native int startConnectionDataLog(int inst, long log, String name);
+
+  public static int startConnectionDataLog(int inst, DataLog log, String name) {
+    return startConnectionDataLog(inst, log.getImpl(), name);
+  }
+
+  public static native void stopConnectionDataLog(int logger);
+
+  public static native int addLogger(int poller, int minLevel, int maxLevel);
+}
diff --git a/third_party/allwpilib/ntcore/src/generate/java/Publisher.java.jinja b/third_party/allwpilib/ntcore/src/generate/java/Publisher.java.jinja
new file mode 100644
index 0000000..19ead36
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/generate/java/Publisher.java.jinja
@@ -0,0 +1,49 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.networktables;
+
+import {{ java.ConsumerFunctionPackage|default('java.util.function') }}.{{ java.FunctionTypePrefix }}Consumer;
+
+/** NetworkTables {{ TypeName }} publisher. */
+public interface {{ TypeName }}Publisher extends Publisher, {{ java.FunctionTypePrefix }}Consumer{{ java.FunctionTypeSuffix }} {
+  /**
+   * Get the corresponding topic.
+   *
+   * @return Topic
+   */
+  @Override
+  {{ TypeName }}Topic getTopic();
+
+  /**
+   * Publish a new value using current NT time.
+   *
+   * @param value value to publish
+   */
+  default void set({{ java.ValueType }} value) {
+    set(value, 0);
+  }
+
+  /**
+   * Publish a new value.
+   *
+   * @param value value to publish
+   * @param time timestamp; 0 indicates current NT time should be used
+   */
+  void set({{ java.ValueType }} value, long time);
+
+  /**
+   * Publish a default value.
+   * On reconnect, a default value will never be used in preference to a
+   * published value.
+   *
+   * @param value value
+   */
+  void setDefault({{ java.ValueType }} value);
+
+  @Override
+  default void accept({{ java.ValueType }} value) {
+    set(value);
+  }
+}
diff --git a/third_party/allwpilib/ntcore/src/generate/java/Subscriber.java.jinja b/third_party/allwpilib/ntcore/src/generate/java/Subscriber.java.jinja
new file mode 100644
index 0000000..0ea09a3
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/generate/java/Subscriber.java.jinja
@@ -0,0 +1,83 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.networktables;
+
+import {{ java.SupplierFunctionPackage|default('java.util.function') }}.{{ java.FunctionTypePrefix }}Supplier;
+
+/** NetworkTables {{ TypeName }} subscriber. */
+@SuppressWarnings("PMD.MissingOverride")
+public interface {{ TypeName }}Subscriber extends Subscriber, {{ java.FunctionTypePrefix }}Supplier{{ java.FunctionTypeSuffix }} {
+  /**
+   * Get the corresponding topic.
+   *
+   * @return Topic
+   */
+  @Override
+  {{ TypeName }}Topic getTopic();
+
+  /**
+   * Get the last published value.
+   * If no value has been published, returns the stored default value.
+   *
+   * @return value
+   */
+  {{ java.ValueType }} get();
+
+  /**
+   * Get the last published value.
+   * If no value has been published, returns the passed defaultValue.
+   *
+   * @param defaultValue default value to return if no value has been published
+   * @return value
+   */
+  {{ java.ValueType }} get({{ java.ValueType }} defaultValue);
+{% if java.FunctionTypePrefix %}
+  @Override
+  default {{ java.ValueType }} getAs{{ java.FunctionTypePrefix }}() {
+    return get();
+  }
+{% endif %}
+  /**
+   * Get the last published value along with its timestamp
+   * If no value has been published, returns the stored default value and a
+   * timestamp of 0.
+   *
+   * @return timestamped value
+   */
+  Timestamped{{ TypeName }} getAtomic();
+
+  /**
+   * Get the last published value along with its timestamp
+   * If no value has been published, returns the passed defaultValue and a
+   * timestamp of 0.
+   *
+   * @param defaultValue default value to return if no value has been published
+   * @return timestamped value
+   */
+  Timestamped{{ TypeName }} getAtomic({{ java.ValueType }} defaultValue);
+
+  /**
+   * Get an array of all value changes since the last call to readQueue.
+   * Also provides a timestamp for each value.
+   *
+   * <p>The "poll storage" subscribe option can be used to set the queue
+   * depth.
+   *
+   * @return Array of timestamped values; empty array if no new changes have
+   *     been published since the previous call.
+   */
+  Timestamped{{ TypeName }}[] readQueue();
+
+  /**
+   * Get an array of all value changes since the last call to readQueue.
+   *
+   * <p>The "poll storage" subscribe option can be used to set the queue
+   * depth.
+   *
+   * @return Array of values; empty array if no new changes have been
+   *     published since the previous call.
+   */
+  {{ java.ValueType }}[] readQueueValues();
+}
diff --git a/third_party/allwpilib/ntcore/src/generate/java/Timestamped.java.jinja b/third_party/allwpilib/ntcore/src/generate/java/Timestamped.java.jinja
new file mode 100644
index 0000000..288af81
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/generate/java/Timestamped.java.jinja
@@ -0,0 +1,40 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.networktables;
+
+/** NetworkTables timestamped {{ TypeName }}. */
+@SuppressWarnings("PMD.ArrayIsStoredDirectly")
+public final class Timestamped{{ TypeName }} {
+  /**
+   * Create a timestamped value.
+   *
+   * @param timestamp timestamp in local time base
+   * @param serverTime timestamp in server time base
+   * @param value value
+   */
+  public Timestamped{{ TypeName }}(long timestamp, long serverTime, {{ java.ValueType }} value) {
+    this.timestamp = timestamp;
+    this.serverTime = serverTime;
+    this.value = value;
+  }
+
+  /**
+   * Timestamp in local time base.
+   */
+  @SuppressWarnings("MemberName")
+  public final long timestamp;
+
+  /**
+   * Timestamp in server time base.  May be 0 or 1 for locally set values.
+   */
+  @SuppressWarnings("MemberName")
+  public final long serverTime;
+
+  /**
+   * Value.
+   */
+  @SuppressWarnings("MemberName")
+  public final {{ java.ValueType }} value;
+}
diff --git a/third_party/allwpilib/ntcore/src/generate/java/Topic.java.jinja b/third_party/allwpilib/ntcore/src/generate/java/Topic.java.jinja
new file mode 100644
index 0000000..e22fa3b
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/generate/java/Topic.java.jinja
@@ -0,0 +1,223 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.networktables;
+
+/** NetworkTables {{ TypeName }} topic. */
+public final class {{ TypeName }}Topic extends Topic {
+{%- if TypeString %}
+  /** The default type string for this topic type. */
+  public static final String kTypeString = {{ TypeString }};
+{% endif %}
+  /**
+   * Construct from a generic topic.
+   *
+   * @param topic Topic
+   */
+  public {{ TypeName }}Topic(Topic topic) {
+    super(topic.m_inst, topic.m_handle);
+  }
+
+  /**
+   * Constructor; use NetworkTableInstance.get{{TypeName}}Topic() instead.
+   *
+   * @param inst Instance
+   * @param handle Native handle
+   */
+  public {{ TypeName }}Topic(NetworkTableInstance inst, int handle) {
+    super(inst, handle);
+  }
+
+  /**
+   * Create a new subscriber to the topic.
+   *
+   * <p>The subscriber is only active as long as the returned object
+   * is not closed.
+   *
+   * <p>Subscribers that do not match the published data type do not return
+   * any values. To determine if the data type matches, use the appropriate
+   * Topic functions.
+   *
+{%- if not TypeString %}
+   * @param typeString type string
+{% endif %}
+   * @param defaultValue default value used when a default is not provided to a
+   *        getter function
+   * @param options subscribe options
+   * @return subscriber
+   */
+  public {{ TypeName }}Subscriber subscribe(
+{%- if not TypeString %}
+      String typeString,
+{% endif %}
+      {{ java.ValueType }} defaultValue,
+      PubSubOption... options) {
+    return new {{ TypeName }}EntryImpl(
+        this,
+        NetworkTablesJNI.subscribe(
+            m_handle, NetworkTableType.k{{ TypeName }}.getValue(),
+            {{ TypeString|default('typeString') }}, options),
+        defaultValue);
+  }
+{% if TypeString %}
+  /**
+   * Create a new subscriber to the topic, with specified type string.
+   *
+   * <p>The subscriber is only active as long as the returned object
+   * is not closed.
+   *
+   * <p>Subscribers that do not match the published data type do not return
+   * any values. To determine if the data type matches, use the appropriate
+   * Topic functions.
+   *
+   * @param typeString type string
+   * @param defaultValue default value used when a default is not provided to a
+   *        getter function
+   * @param options subscribe options
+   * @return subscriber
+   */
+  public {{ TypeName }}Subscriber subscribeEx(
+      String typeString,
+      {{ java.ValueType }} defaultValue,
+      PubSubOption... options) {
+    return new {{ TypeName }}EntryImpl(
+        this,
+        NetworkTablesJNI.subscribe(
+            m_handle, NetworkTableType.k{{ TypeName }}.getValue(),
+            typeString, options),
+        defaultValue);
+  }
+{% endif %}
+  /**
+   * Create a new publisher to the topic.
+   *
+   * <p>The publisher is only active as long as the returned object
+   * is not closed.
+   *
+   * <p>It is not possible to publish two different data types to the same
+   * topic. Conflicts between publishers are typically resolved by the server on
+   * a first-come, first-served basis. Any published values that do not match
+   * the topic's data type are dropped (ignored). To determine if the data type
+   * matches, use the appropriate Topic functions.
+   *
+{%- if not TypeString %}
+   * @param typeString type string
+{% endif %}
+   * @param options publish options
+   * @return publisher
+   */
+  public {{ TypeName }}Publisher publish(
+{%- if not TypeString %}
+      String typeString,
+{% endif %}
+      PubSubOption... options) {
+    return new {{ TypeName }}EntryImpl(
+        this,
+        NetworkTablesJNI.publish(
+            m_handle, NetworkTableType.k{{ TypeName }}.getValue(),
+            {{ TypeString|default('typeString') }}, options),
+        {{ java.EmptyValue }});
+  }
+
+  /**
+   * Create a new publisher to the topic, with type string and initial properties.
+   *
+   * <p>The publisher is only active as long as the returned object
+   * is not closed.
+   *
+   * <p>It is not possible to publish two different data types to the same
+   * topic. Conflicts between publishers are typically resolved by the server on
+   * a first-come, first-served basis. Any published values that do not match
+   * the topic's data type are dropped (ignored). To determine if the data type
+   * matches, use the appropriate Topic functions.
+   *
+   * @param typeString type string
+   * @param properties JSON properties
+   * @param options publish options
+   * @return publisher
+   * @throws IllegalArgumentException if properties is not a JSON object
+   */
+  public {{ TypeName }}Publisher publishEx(
+      String typeString,
+      String properties,
+      PubSubOption... options) {
+    return new {{ TypeName }}EntryImpl(
+        this,
+        NetworkTablesJNI.publishEx(
+            m_handle, NetworkTableType.k{{ TypeName }}.getValue(),
+            typeString, properties, options),
+        {{ java.EmptyValue }});
+  }
+
+  /**
+   * Create a new entry for the topic.
+   *
+   * <p>Entries act as a combination of a subscriber and a weak publisher. The
+   * subscriber is active as long as the entry is not closed. The publisher is
+   * created when the entry is first written to, and remains active until either
+   * unpublish() is called or the entry is closed.
+   *
+   * <p>It is not possible to use two different data types with the same
+   * topic. Conflicts between publishers are typically resolved by the server on
+   * a first-come, first-served basis. Any published values that do not match
+   * the topic's data type are dropped (ignored), and the entry will show no new
+   * values if the data type does not match. To determine if the data type
+   * matches, use the appropriate Topic functions.
+   *
+{%- if not TypeString %}
+   * @param typeString type string
+{% endif %}
+   * @param defaultValue default value used when a default is not provided to a
+   *        getter function
+   * @param options publish and/or subscribe options
+   * @return entry
+   */
+  public {{ TypeName }}Entry getEntry(
+{%- if not TypeString %}
+      String typeString,
+{% endif %}
+      {{ java.ValueType }} defaultValue,
+      PubSubOption... options) {
+    return new {{ TypeName }}EntryImpl(
+        this,
+        NetworkTablesJNI.getEntry(
+            m_handle, NetworkTableType.k{{ TypeName }}.getValue(),
+            {{ TypeString|default('typeString') }}, options),
+        defaultValue);
+  }
+{% if TypeString %}
+  /**
+   * Create a new entry for the topic, with specified type string.
+   *
+   * <p>Entries act as a combination of a subscriber and a weak publisher. The
+   * subscriber is active as long as the entry is not closed. The publisher is
+   * created when the entry is first written to, and remains active until either
+   * unpublish() is called or the entry is closed.
+   *
+   * <p>It is not possible to use two different data types with the same
+   * topic. Conflicts between publishers are typically resolved by the server on
+   * a first-come, first-served basis. Any published values that do not match
+   * the topic's data type are dropped (ignored), and the entry will show no new
+   * values if the data type does not match. To determine if the data type
+   * matches, use the appropriate Topic functions.
+   *
+   * @param typeString type string
+   * @param defaultValue default value used when a default is not provided to a
+   *        getter function
+   * @param options publish and/or subscribe options
+   * @return entry
+   */
+  public {{ TypeName }}Entry getEntryEx(
+      String typeString,
+      {{ java.ValueType }} defaultValue,
+      PubSubOption... options) {
+    return new {{ TypeName }}EntryImpl(
+        this,
+        NetworkTablesJNI.getEntry(
+            m_handle, NetworkTableType.k{{ TypeName }}.getValue(),
+            typeString, options),
+        defaultValue);
+  }
+{% endif %}
+}
diff --git a/third_party/allwpilib/ntcore/src/generate/types.json b/third_party/allwpilib/ntcore/src/generate/types.json
new file mode 100644
index 0000000..31a71b3
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/generate/types.json
@@ -0,0 +1,366 @@
+[
+    {
+        "TypeName": "Boolean",
+        "TypeString": "\"boolean\"",
+        "c": {
+            "ValueType": "NT_Bool",
+            "ParamType": "NT_Bool"
+        },
+        "cpp": {
+            "ValueType": "bool",
+            "ParamType": "bool",
+            "TYPE_NAME": "BOOLEAN"
+        },
+        "java": {
+            "ValueType": "boolean",
+            "EmptyValue": "false",
+            "ConsumerFunctionPackage": "edu.wpi.first.util.function",
+            "FunctionTypePrefix": "Boolean",
+            "ToWrapObject": "Boolean.valueOf",
+            "FromStorageBegin": "(Boolean) "
+        },
+        "jni": {
+            "jtype": "jboolean",
+            "jtypestr": "Z",
+            "JavaObject": false,
+            "FromJavaBegin": "",
+            "FromJavaEnd": " != JNI_FALSE",
+            "ToJavaBegin": "static_cast<jboolean>(",
+            "ToJavaEnd": ")",
+            "ToJavaArray": "MakeJBooleanArray"
+        }
+    },
+    {
+        "TypeName": "Integer",
+        "TypeString": "\"int\"",
+        "c": {
+            "ValueType": "int64_t",
+            "ParamType": "int64_t"
+        },
+        "cpp": {
+            "ValueType": "int64_t",
+            "ParamType": "int64_t",
+            "TYPE_NAME": "INTEGER"
+        },
+        "java": {
+            "ValueType": "long",
+            "EmptyValue": "0",
+            "FunctionTypePrefix": "Long",
+            "ToWrapObject": "Long.valueOf",
+            "FromStorageBegin": "((Number) ",
+            "FromStorageEnd": ").longValue()"
+        },
+        "jni": {
+            "jtype": "jlong",
+            "jtypestr": "J",
+            "JavaObject": false,
+            "FromJavaBegin": "",
+            "FromJavaEnd": "",
+            "ToJavaBegin": "static_cast<jlong>(",
+            "ToJavaEnd": ")",
+            "ToJavaArray": "MakeJLongArray"
+        }
+    },
+    {
+        "TypeName": "Float",
+        "TypeString": "\"float\"",
+        "c": {
+            "ValueType": "float",
+            "ParamType": "float"
+        },
+        "cpp": {
+            "ValueType": "float",
+            "ParamType": "float",
+            "TYPE_NAME": "FLOAT"
+        },
+        "java": {
+            "ValueType": "float",
+            "EmptyValue": "0",
+            "ConsumerFunctionPackage": "edu.wpi.first.util.function",
+            "SupplierFunctionPackage": "edu.wpi.first.util.function",
+            "FunctionTypePrefix": "Float",
+            "ToWrapObject": "Float.valueOf",
+            "FromStorageBegin": "((Number) ",
+            "FromStorageEnd": ").floatValue()"
+        },
+        "jni": {
+            "jtype": "jfloat",
+            "jtypestr": "F",
+            "JavaObject": false,
+            "FromJavaBegin": "",
+            "FromJavaEnd": "",
+            "ToJavaBegin": "static_cast<jfloat>(",
+            "ToJavaEnd": ")",
+            "ToJavaArray": "MakeJFloatArray"
+        }
+    },
+    {
+        "TypeName": "Double",
+        "TypeString": "\"double\"",
+        "c": {
+            "ValueType": "double",
+            "ParamType": "double"
+        },
+        "cpp": {
+            "ValueType": "double",
+            "ParamType": "double",
+            "TYPE_NAME": "DOUBLE"
+        },
+        "java": {
+            "ValueType": "double",
+            "EmptyValue": "0",
+            "FunctionTypePrefix": "Double",
+            "ToWrapObject": "Double.valueOf",
+            "FromStorageBegin": "((Number) ",
+            "FromStorageEnd": ").doubleValue()"
+        },
+        "jni": {
+            "jtype": "jdouble",
+            "jtypestr": "D",
+            "JavaObject": false,
+            "FromJavaBegin": "",
+            "FromJavaEnd": "",
+            "ToJavaBegin": "static_cast<jdouble>(",
+            "ToJavaEnd": ")",
+            "ToJavaArray": "MakeJDoubleArray"
+        }
+    },
+    {
+        "TypeName": "String",
+        "TypeString": "\"string\"",
+        "c": {
+            "ValueType": "char*",
+            "ParamType": "const char*",
+            "IsArray": true
+        },
+        "cpp": {
+            "ValueType": "std::string",
+            "ParamType": "std::string_view",
+            "TYPE_NAME": "STRING",
+            "INCLUDES": "#include <string>\n#include <string_view>\n#include <utility>",
+            "SmallRetType": "std::string_view",
+            "SmallElemType": "char"
+        },
+        "java": {
+            "ValueType": "String",
+            "EmptyValue": "\"\"",
+            "FunctionTypeSuffix": "<String>",
+            "FromStorageBegin": "(String) "
+        },
+        "jni": {
+            "jtype": "jstring",
+            "jtypestr": "Ljava/lang/String;",
+            "JavaObject": true,
+            "FromJavaBegin": "JStringRef{env, ",
+            "FromJavaEnd": "}",
+            "ToJavaBegin": "MakeJString(env, ",
+            "ToJavaEnd": ")",
+            "ToJavaArray": "MakeJStringArray"
+        }
+    },
+    {
+        "TypeName": "Raw",
+        "c": {
+            "ValueType": "uint8_t*",
+            "ParamType": "const uint8_t*",
+            "IsArray": true
+        },
+        "cpp": {
+            "ValueType": "std::vector<uint8_t>",
+            "ParamType": "std::span<const uint8_t>",
+            "DefaultValueCopy": "defaultValue.begin(), defaultValue.end()",
+            "TYPE_NAME": "RAW",
+            "INCLUDES": "#include <utility>",
+            "SmallRetType": "std::span<uint8_t>",
+            "SmallElemType": "uint8_t"
+        },
+        "java": {
+            "ValueType": "byte[]",
+            "EmptyValue": "new byte[] {}",
+            "FunctionTypeSuffix": "<byte[]>",
+            "FromStorageBegin": "(byte[]) "
+        },
+        "jni": {
+            "jtype": "jbyteArray",
+            "jtypestr": "[B",
+            "JavaObject": true,
+            "FromJavaBegin": "CriticalJByteArrayRef{env, ",
+            "FromJavaEnd": "}.uarray()",
+            "ToJavaBegin": "MakeJByteArray(env, ",
+            "ToJavaEnd": ")",
+            "ToJavaArray": "MakeJObjectArray"
+        }
+    },
+    {
+        "TypeName": "BooleanArray",
+        "TypeString": "\"boolean[]\"",
+        "c": {
+            "ValueType": "NT_Bool*",
+            "ParamType": "const NT_Bool*",
+            "IsArray": true
+        },
+        "cpp": {
+            "ValueType": "std::vector<int>",
+            "ParamType": "std::span<const int>",
+            "DefaultValueCopy": "defaultValue.begin(), defaultValue.end()",
+            "TYPE_NAME": "BOOLEAN_ARRAY",
+            "INCLUDES": "#include <utility>",
+            "SmallRetType": "std::span<int>",
+            "SmallElemType": "int"
+        },
+        "java": {
+            "ValueType": "boolean[]",
+            "WrapValueType": "Boolean[]",
+            "EmptyValue": "new boolean[] {}",
+            "FunctionTypeSuffix": "<boolean[]>",
+            "FromStorageBegin": "(boolean[]) "
+        },
+        "jni": {
+            "jtype": "jbooleanArray",
+            "jtypestr": "[Z",
+            "JavaObject": true,
+            "FromJavaBegin": "FromJavaBooleanArray(env, ",
+            "FromJavaEnd": ")",
+            "ToJavaBegin": "MakeJBooleanArray(env, ",
+            "ToJavaEnd": ")",
+            "ToJavaArray": "MakeJObjectArray"
+        }
+    },
+    {
+        "TypeName": "IntegerArray",
+        "TypeString": "\"int[]\"",
+        "c": {
+            "ValueType": "int64_t*",
+            "ParamType": "const int64_t*",
+            "IsArray": true
+        },
+        "cpp": {
+            "ValueType": "std::vector<int64_t>",
+            "ParamType": "std::span<const int64_t>",
+            "DefaultValueCopy": "defaultValue.begin(), defaultValue.end()",
+            "TYPE_NAME": "INTEGER_ARRAY",
+            "INCLUDES": "#include <utility>",
+            "SmallRetType": "std::span<int64_t>",
+            "SmallElemType": "int64_t"
+        },
+        "java": {
+            "ValueType": "long[]",
+            "WrapValueType": "Long[]",
+            "EmptyValue": "new long[] {}",
+            "FunctionTypeSuffix": "<long[]>",
+            "FromStorageBegin": "(long[]) "
+        },
+        "jni": {
+            "jtype": "jlongArray",
+            "jtypestr": "[J",
+            "JavaObject": true,
+            "FromJavaBegin": "CriticalJLongArrayRef{env, ",
+            "FromJavaEnd": "}",
+            "ToJavaBegin": "MakeJLongArray(env, ",
+            "ToJavaEnd": ")",
+            "ToJavaArray": "MakeJObjectArray"
+        }
+    },
+    {
+        "TypeName": "FloatArray",
+        "TypeString": "\"float[]\"",
+        "c": {
+            "ValueType": "float*",
+            "ParamType": "const float*",
+            "IsArray": true
+        },
+        "cpp": {
+            "ValueType": "std::vector<float>",
+            "ParamType": "std::span<const float>",
+            "DefaultValueCopy": "defaultValue.begin(), defaultValue.end()",
+            "TYPE_NAME": "FLOAT_ARRAY",
+            "INCLUDES": "#include <utility>",
+            "SmallRetType": "std::span<float>",
+            "SmallElemType": "float"
+        },
+        "java": {
+            "ValueType": "float[]",
+            "WrapValueType": "Float[]",
+            "EmptyValue": "new float[] {}",
+            "FunctionTypeSuffix": "<float[]>",
+            "FromStorageBegin": "(float[]) "
+        },
+        "jni": {
+            "jtype": "jfloatArray",
+            "jtypestr": "[F",
+            "JavaObject": true,
+            "FromJavaBegin": "CriticalJFloatArrayRef{env, ",
+            "FromJavaEnd": "}",
+            "ToJavaBegin": "MakeJFloatArray(env, ",
+            "ToJavaEnd": ")",
+            "ToJavaArray": "MakeJObjectArray"
+        }
+    },
+    {
+        "TypeName": "DoubleArray",
+        "TypeString": "\"double[]\"",
+        "c": {
+            "ValueType": "double*",
+            "ParamType": "const double*",
+            "IsArray": true
+        },
+        "cpp": {
+            "ValueType": "std::vector<double>",
+            "ParamType": "std::span<const double>",
+            "DefaultValueCopy": "defaultValue.begin(), defaultValue.end()",
+            "TYPE_NAME": "DOUBLE_ARRAY",
+            "INCLUDES": "#include <utility>",
+            "SmallRetType": "std::span<double>",
+            "SmallElemType": "double"
+        },
+        "java": {
+            "ValueType": "double[]",
+            "WrapValueType": "Double[]",
+            "EmptyValue": "new double[] {}",
+            "FunctionTypeSuffix": "<double[]>",
+            "FromStorageBegin": "(double[]) "
+        },
+        "jni": {
+            "jtype": "jdoubleArray",
+            "jtypestr": "[D",
+            "JavaObject": true,
+            "FromJavaBegin": "CriticalJDoubleArrayRef{env, ",
+            "FromJavaEnd": "}",
+            "ToJavaBegin": "MakeJDoubleArray(env, ",
+            "ToJavaEnd": ")",
+            "ToJavaArray": "MakeJObjectArray"
+        }
+    },
+    {
+        "TypeName": "StringArray",
+        "TypeString": "\"string[]\"",
+        "c": {
+            "ValueType": "struct NT_String*",
+            "ParamType": "const struct NT_String*",
+            "IsArray": true
+        },
+        "cpp": {
+            "ValueType": "std::vector<std::string>",
+            "ParamType": "std::span<const std::string>",
+            "DefaultValueCopy": "defaultValue.begin(), defaultValue.end()",
+            "TYPE_NAME": "STRING_ARRAY",
+            "INCLUDES": "#include <utility>"
+        },
+        "java": {
+            "ValueType": "String[]",
+            "EmptyValue": "new String[] {}",
+            "FunctionTypeSuffix": "<String[]>",
+            "FromStorageBegin": "(String[]) "
+        },
+        "jni": {
+            "jtype": "jobjectArray",
+            "jtypestr": "[Ljava/lang/Object;",
+            "JavaObject": true,
+            "FromJavaBegin": "FromJavaStringArray(env, ",
+            "FromJavaEnd": ")",
+            "ToJavaBegin": "MakeJStringArray(env, ",
+            "ToJavaEnd": ")",
+            "ToJavaArray": "MakeJObjectArray"
+        }
+    }
+]
diff --git a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/ConnectionInfo.java b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/ConnectionInfo.java
index 477d53b..147b2ea 100644
--- a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/ConnectionInfo.java
+++ b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/ConnectionInfo.java
@@ -5,34 +5,30 @@
 package edu.wpi.first.networktables;
 
 /** NetworkTables Connection information. */
+@SuppressWarnings("MemberName")
 public final class ConnectionInfo {
   /**
    * The remote identifier (as set on the remote node by {@link
-   * NetworkTableInstance#setNetworkIdentity(String)}).
+   * NetworkTableInstance#startClient4(String)}).
    */
-  @SuppressWarnings("MemberName")
   public final String remote_id;
 
   /** The IP address of the remote node. */
-  @SuppressWarnings("MemberName")
   public final String remote_ip;
 
   /** The port number of the remote node. */
-  @SuppressWarnings("MemberName")
   public final int remote_port;
 
   /**
    * The last time any update was received from the remote node (same scale as returned by {@link
    * NetworkTablesJNI#now()}).
    */
-  @SuppressWarnings("MemberName")
   public final long last_update;
 
   /**
    * The protocol version being used for this connection. This is in protocol layer format, so
    * 0x0200 = 2.0, 0x0300 = 3.0).
    */
-  @SuppressWarnings("MemberName")
   public final int protocol_version;
 
   /**
diff --git a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/ConnectionNotification.java b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/ConnectionNotification.java
deleted file mode 100644
index 544e075..0000000
--- a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/ConnectionNotification.java
+++ /dev/null
@@ -1,42 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.networktables;
-
-/** NetworkTables Connection notification. */
-public final class ConnectionNotification {
-  /** Listener that was triggered. */
-  @SuppressWarnings("MemberName")
-  public final int listener;
-
-  /** True if event is due to connection being established. */
-  @SuppressWarnings("MemberName")
-  public final boolean connected;
-
-  /** Connection information. */
-  @SuppressWarnings("MemberName")
-  public final ConnectionInfo conn;
-
-  /**
-   * Constructor. This should generally only be used internally to NetworkTables.
-   *
-   * @param inst Instance
-   * @param listener Listener that was triggered
-   * @param connected Connected if true
-   * @param conn Connection information
-   */
-  public ConnectionNotification(
-      NetworkTableInstance inst, int listener, boolean connected, ConnectionInfo conn) {
-    this.m_inst = inst;
-    this.listener = listener;
-    this.connected = connected;
-    this.conn = conn;
-  }
-
-  private final NetworkTableInstance m_inst;
-
-  public NetworkTableInstance getInstance() {
-    return m_inst;
-  }
-}
diff --git a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/EntryBase.java b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/EntryBase.java
new file mode 100644
index 0000000..48d4a9c
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/EntryBase.java
@@ -0,0 +1,44 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.networktables;
+
+/** NetworkTables entry base implementation. */
+public abstract class EntryBase implements Subscriber, Publisher {
+  /**
+   * Constructor.
+   *
+   * @param handle handle
+   */
+  public EntryBase(int handle) {
+    m_handle = handle;
+  }
+
+  @Override
+  public boolean isValid() {
+    return m_handle != 0;
+  }
+
+  @Override
+  public int getHandle() {
+    return m_handle;
+  }
+
+  @Override
+  public void close() {
+    NetworkTablesJNI.release(m_handle);
+  }
+
+  @Override
+  public boolean exists() {
+    return NetworkTablesJNI.getTopicExists(m_handle);
+  }
+
+  @Override
+  public long getLastChange() {
+    return NetworkTablesJNI.getEntryLastChange(m_handle);
+  }
+
+  protected int m_handle;
+}
diff --git a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/EntryInfo.java b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/EntryInfo.java
deleted file mode 100644
index 471edc8..0000000
--- a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/EntryInfo.java
+++ /dev/null
@@ -1,66 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.networktables;
-
-/** NetworkTables Entry information. */
-public final class EntryInfo {
-  /** Entry handle. */
-  @SuppressWarnings("MemberName")
-  public final int entry;
-
-  /** Entry name. */
-  @SuppressWarnings("MemberName")
-  public final String name;
-
-  /** Entry type. */
-  @SuppressWarnings("MemberName")
-  public final NetworkTableType type;
-
-  /** Entry flags. */
-  @SuppressWarnings("MemberName")
-  public final int flags;
-
-  /** Timestamp of last change to entry (type or value). */
-  @SuppressWarnings("MemberName")
-  public final long last_change;
-
-  /**
-   * Constructor. This should generally only be used internally to NetworkTables.
-   *
-   * @param inst Instance
-   * @param entry Entry handle
-   * @param name Name
-   * @param type Type (integer version of {@link NetworkTableType})
-   * @param flags Flags
-   * @param lastChange Timestamp of last change
-   */
-  public EntryInfo(
-      NetworkTableInstance inst, int entry, String name, int type, int flags, long lastChange) {
-    this.m_inst = inst;
-    this.entry = entry;
-    this.name = name;
-    this.type = NetworkTableType.getFromInt(type);
-    this.flags = flags;
-    this.last_change = lastChange;
-  }
-
-  /* Network table instance. */
-  private final NetworkTableInstance m_inst;
-
-  /* Cached entry object. */
-  private NetworkTableEntry m_entryObject;
-
-  /**
-   * Get the entry as an object.
-   *
-   * @return NetworkTableEntry for this entry.
-   */
-  NetworkTableEntry getEntry() {
-    if (m_entryObject == null) {
-      m_entryObject = new NetworkTableEntry(m_inst, entry);
-    }
-    return m_entryObject;
-  }
-}
diff --git a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/EntryListenerFlags.java b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/EntryListenerFlags.java
deleted file mode 100644
index 856c962..0000000
--- a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/EntryListenerFlags.java
+++ /dev/null
@@ -1,66 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.networktables;
-
-/**
- * Flag values for use with entry listeners.
- *
- * <p>The flags are a bitmask and must be OR'ed together to indicate the combination of events
- * desired to be received.
- *
- * <p>The constants kNew, kDelete, kUpdate, and kFlags represent different events that can occur to
- * entries.
- *
- * <p>By default, notifications are only generated for remote changes occurring after the listener
- * is created. The constants kImmediate and kLocal are modifiers that cause notifications to be
- * generated at other times.
- */
-public interface EntryListenerFlags {
-  /**
-   * Initial listener addition.
-   *
-   * <p>Set this flag to receive immediate notification of entries matching the flag criteria
-   * (generally only useful when combined with kNew).
-   */
-  int kImmediate = 0x01;
-
-  /**
-   * Changed locally.
-   *
-   * <p>Set this flag to receive notification of both local changes and changes coming from remote
-   * nodes. By default, notifications are only generated for remote changes. Must be combined with
-   * some combination of kNew, kDelete, kUpdate, and kFlags to receive notifications of those
-   * respective events.
-   */
-  int kLocal = 0x02;
-
-  /**
-   * Newly created entry.
-   *
-   * <p>Set this flag to receive a notification when an entry is created.
-   */
-  int kNew = 0x04;
-
-  /**
-   * Entry was deleted.
-   *
-   * <p>Set this flag to receive a notification when an entry is deleted.
-   */
-  int kDelete = 0x08;
-
-  /**
-   * Entry's value changed.
-   *
-   * <p>Set this flag to receive a notification when an entry's value (or type) changes.
-   */
-  int kUpdate = 0x10;
-
-  /**
-   * Entry's flags changed.
-   *
-   * <p>Set this flag to receive a notification when an entry's flags value changes.
-   */
-  int kFlags = 0x20;
-}
diff --git a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/EntryNotification.java b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/EntryNotification.java
deleted file mode 100644
index 0f5cb51..0000000
--- a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/EntryNotification.java
+++ /dev/null
@@ -1,73 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.networktables;
-
-/** NetworkTables Entry notification. */
-public final class EntryNotification {
-  /** Listener that was triggered. */
-  @SuppressWarnings("MemberName")
-  public final int listener;
-
-  /** Entry handle. */
-  @SuppressWarnings("MemberName")
-  public final int entry;
-
-  /** Entry name. */
-  @SuppressWarnings("MemberName")
-  public final String name;
-
-  /** The new value. */
-  @SuppressWarnings("MemberName")
-  public final NetworkTableValue value;
-
-  /**
-   * Update flags. For example, {@link EntryListenerFlags#kNew} if the key did not previously exist.
-   */
-  @SuppressWarnings("MemberName")
-  public final int flags;
-
-  /**
-   * Constructor. This should generally only be used internally to NetworkTables.
-   *
-   * @param inst Instance
-   * @param listener Listener that was triggered
-   * @param entry Entry handle
-   * @param name Entry name
-   * @param value The new value
-   * @param flags Update flags
-   */
-  public EntryNotification(
-      NetworkTableInstance inst,
-      int listener,
-      int entry,
-      String name,
-      NetworkTableValue value,
-      int flags) {
-    this.m_inst = inst;
-    this.listener = listener;
-    this.entry = entry;
-    this.name = name;
-    this.value = value;
-    this.flags = flags;
-  }
-
-  /* Network table instance. */
-  private final NetworkTableInstance m_inst;
-
-  /* Cached entry object. */
-  NetworkTableEntry m_entryObject;
-
-  /**
-   * Get the entry as an object.
-   *
-   * @return NetworkTableEntry for this entry.
-   */
-  public NetworkTableEntry getEntry() {
-    if (m_entryObject == null) {
-      m_entryObject = new NetworkTableEntry(m_inst, entry);
-    }
-    return m_entryObject;
-  }
-}
diff --git a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/GenericEntry.java b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/GenericEntry.java
new file mode 100644
index 0000000..77e7502
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/GenericEntry.java
@@ -0,0 +1,15 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.networktables;
+
+/**
+ * NetworkTables generic entry.
+ *
+ * <p>Unlike NetworkTableEntry, the entry goes away when close() is called.
+ */
+public interface GenericEntry extends GenericSubscriber, GenericPublisher {
+  /** Stops publishing the entry if it's published. */
+  void unpublish();
+}
diff --git a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/LogMessage.java b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/LogMessage.java
index 5d77d8b..fd090af 100644
--- a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/LogMessage.java
+++ b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/LogMessage.java
@@ -5,6 +5,7 @@
 package edu.wpi.first.networktables;
 
 /** NetworkTables log message. */
+@SuppressWarnings("MemberName")
 public final class LogMessage {
   /** Logging levels. */
   public static final int kCritical = 50;
@@ -18,49 +19,30 @@
   public static final int kDebug3 = 7;
   public static final int kDebug4 = 6;
 
-  /** The logger that generated the message. */
-  @SuppressWarnings("MemberName")
-  public final int logger;
-
   /** Log level of the message. */
-  @SuppressWarnings("MemberName")
   public final int level;
 
   /** The filename of the source file that generated the message. */
-  @SuppressWarnings("MemberName")
   public final String filename;
 
   /** The line number in the source file that generated the message. */
-  @SuppressWarnings("MemberName")
   public final int line;
 
   /** The message. */
-  @SuppressWarnings("MemberName")
   public final String message;
 
   /**
    * Constructor. This should generally only be used internally to NetworkTables.
    *
-   * @param inst Instance
-   * @param logger Logger
    * @param level Log level
    * @param filename Filename
    * @param line Line number
    * @param message Message
    */
-  public LogMessage(
-      NetworkTableInstance inst, int logger, int level, String filename, int line, String message) {
-    this.m_inst = inst;
-    this.logger = logger;
+  public LogMessage(int level, String filename, int line, String message) {
     this.level = level;
     this.filename = filename;
     this.line = line;
     this.message = message;
   }
-
-  private final NetworkTableInstance m_inst;
-
-  NetworkTableInstance getInstance() {
-    return m_inst;
-  }
 }
diff --git a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/MultiSubscriber.java b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/MultiSubscriber.java
new file mode 100644
index 0000000..8386c1e
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/MultiSubscriber.java
@@ -0,0 +1,61 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.networktables;
+
+/**
+ * Subscribe to multiple topics based on one or more topic name prefixes. Can be used in combination
+ * with ValueListenerPoller to listen for value changes across all matching topics.
+ */
+public final class MultiSubscriber implements AutoCloseable {
+  /**
+   * Create a multiple subscriber.
+   *
+   * @param inst instance
+   * @param prefixes topic name prefixes
+   * @param options subscriber options
+   */
+  public MultiSubscriber(NetworkTableInstance inst, String[] prefixes, PubSubOption... options) {
+    m_inst = inst;
+    m_handle = NetworkTablesJNI.subscribeMultiple(inst.getHandle(), prefixes, options);
+  }
+
+  @Override
+  public synchronized void close() {
+    if (m_handle != 0) {
+      NetworkTablesJNI.unsubscribeMultiple(m_handle);
+      m_handle = 0;
+    }
+  }
+
+  /**
+   * Gets the instance for the subscriber.
+   *
+   * @return Instance
+   */
+  public NetworkTableInstance getInstance() {
+    return m_inst;
+  }
+
+  /**
+   * Determines if the native handle is valid.
+   *
+   * @return True if the native handle is valid, false otherwise.
+   */
+  public boolean isValid() {
+    return m_handle != 0;
+  }
+
+  /**
+   * Gets the native handle.
+   *
+   * @return Handle
+   */
+  public int getHandle() {
+    return m_handle;
+  }
+
+  private final NetworkTableInstance m_inst;
+  private int m_handle;
+}
diff --git a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/NTSendableBuilder.java b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/NTSendableBuilder.java
index 65bfbca..4d5e6a5 100644
--- a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/NTSendableBuilder.java
+++ b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/NTSendableBuilder.java
@@ -5,8 +5,6 @@
 package edu.wpi.first.networktables;
 
 import edu.wpi.first.util.sendable.SendableBuilder;
-import java.util.function.Consumer;
-import java.util.function.Supplier;
 
 public interface NTSendableBuilder extends SendableBuilder {
   /**
@@ -23,19 +21,9 @@
    * function called by setUpdateTable().
    *
    * @param key property name
-   * @return Network table entry
+   * @return Network table topic
    */
-  NetworkTableEntry getEntry(String key);
-
-  /**
-   * Add a NetworkTableValue property.
-   *
-   * @param key property name
-   * @param getter getter function (returns current value)
-   * @param setter setter function (sets new value)
-   */
-  void addValueProperty(
-      String key, Supplier<NetworkTableValue> getter, Consumer<NetworkTableValue> setter);
+  Topic getTopic(String key);
 
   /**
    * Get the network table.
diff --git a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTable.java b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTable.java
index 7837a21..cc38239 100644
--- a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTable.java
+++ b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTable.java
@@ -5,6 +5,7 @@
 package edu.wpi.first.networktables;
 
 import java.util.ArrayList;
+import java.util.EnumSet;
 import java.util.HashSet;
 import java.util.List;
 import java.util.Objects;
@@ -129,6 +130,126 @@
     return "NetworkTable: " + m_path;
   }
 
+  /**
+   * Get (generic) topic.
+   *
+   * @param name topic name
+   * @return Topic
+   */
+  public Topic getTopic(String name) {
+    return m_inst.getTopic(m_pathWithSep + name);
+  }
+
+  /**
+   * Get boolean topic.
+   *
+   * @param name topic name
+   * @return BooleanTopic
+   */
+  public BooleanTopic getBooleanTopic(String name) {
+    return m_inst.getBooleanTopic(m_pathWithSep + name);
+  }
+
+  /**
+   * Get long topic.
+   *
+   * @param name topic name
+   * @return IntegerTopic
+   */
+  public IntegerTopic getIntegerTopic(String name) {
+    return m_inst.getIntegerTopic(m_pathWithSep + name);
+  }
+
+  /**
+   * Get float topic.
+   *
+   * @param name topic name
+   * @return FloatTopic
+   */
+  public FloatTopic getFloatTopic(String name) {
+    return m_inst.getFloatTopic(m_pathWithSep + name);
+  }
+
+  /**
+   * Get double topic.
+   *
+   * @param name topic name
+   * @return DoubleTopic
+   */
+  public DoubleTopic getDoubleTopic(String name) {
+    return m_inst.getDoubleTopic(m_pathWithSep + name);
+  }
+
+  /**
+   * Get String topic.
+   *
+   * @param name topic name
+   * @return StringTopic
+   */
+  public StringTopic getStringTopic(String name) {
+    return m_inst.getStringTopic(m_pathWithSep + name);
+  }
+
+  /**
+   * Get raw topic.
+   *
+   * @param name topic name
+   * @return RawTopic
+   */
+  public RawTopic getRawTopic(String name) {
+    return m_inst.getRawTopic(m_pathWithSep + name);
+  }
+
+  /**
+   * Get boolean[] topic.
+   *
+   * @param name topic name
+   * @return BooleanArrayTopic
+   */
+  public BooleanArrayTopic getBooleanArrayTopic(String name) {
+    return m_inst.getBooleanArrayTopic(m_pathWithSep + name);
+  }
+
+  /**
+   * Get long[] topic.
+   *
+   * @param name topic name
+   * @return IntegerArrayTopic
+   */
+  public IntegerArrayTopic getIntegerArrayTopic(String name) {
+    return m_inst.getIntegerArrayTopic(m_pathWithSep + name);
+  }
+
+  /**
+   * Get float[] topic.
+   *
+   * @param name topic name
+   * @return FloatArrayTopic
+   */
+  public FloatArrayTopic getFloatArrayTopic(String name) {
+    return m_inst.getFloatArrayTopic(m_pathWithSep + name);
+  }
+
+  /**
+   * Get double[] topic.
+   *
+   * @param name topic name
+   * @return DoubleArrayTopic
+   */
+  public DoubleArrayTopic getDoubleArrayTopic(String name) {
+    return m_inst.getDoubleArrayTopic(m_pathWithSep + name);
+  }
+
+  /**
+   * Get String[] topic.
+   *
+   * @param name topic name
+   * @return StringArrayTopic
+   */
+  public StringArrayTopic getStringArrayTopic(String name) {
+    return m_inst.getStringArrayTopic(m_pathWithSep + name);
+  }
+
   private final ConcurrentMap<String, NetworkTableEntry> m_entries = new ConcurrentHashMap<>();
 
   /**
@@ -141,106 +262,15 @@
     NetworkTableEntry entry = m_entries.get(key);
     if (entry == null) {
       entry = m_inst.getEntry(m_pathWithSep + key);
-      m_entries.putIfAbsent(key, entry);
+      NetworkTableEntry oldEntry = m_entries.putIfAbsent(key, entry);
+      if (oldEntry != null) {
+        entry = oldEntry;
+      }
     }
     return entry;
   }
 
   /**
-   * Listen to keys only within this table.
-   *
-   * @param listener listener to add
-   * @param flags {@link EntryListenerFlags} bitmask
-   * @return Listener handle
-   */
-  public int addEntryListener(TableEntryListener listener, int flags) {
-    final int prefixLen = m_path.length() + 1;
-    return m_inst.addEntryListener(
-        m_pathWithSep,
-        event -> {
-          String relativeKey = event.name.substring(prefixLen);
-          if (relativeKey.indexOf(PATH_SEPARATOR) != -1) {
-            // part of a sub table
-            return;
-          }
-          listener.valueChanged(this, relativeKey, event.getEntry(), event.value, event.flags);
-        },
-        flags);
-  }
-
-  /**
-   * Listen to a single key.
-   *
-   * @param key the key name
-   * @param listener listener to add
-   * @param flags {@link EntryListenerFlags} bitmask
-   * @return Listener handle
-   */
-  public int addEntryListener(String key, TableEntryListener listener, int flags) {
-    final NetworkTableEntry entry = getEntry(key);
-    return m_inst.addEntryListener(
-        entry, event -> listener.valueChanged(this, key, entry, event.value, event.flags), flags);
-  }
-
-  /**
-   * Remove an entry listener.
-   *
-   * @param listener listener handle
-   */
-  public void removeEntryListener(int listener) {
-    m_inst.removeEntryListener(listener);
-  }
-
-  /**
-   * Listen for sub-table creation. This calls the listener once for each newly created sub-table.
-   * It immediately calls the listener for any existing sub-tables.
-   *
-   * @param listener listener to add
-   * @param localNotify notify local changes as well as remote
-   * @return Listener handle
-   */
-  public int addSubTableListener(TableListener listener, boolean localNotify) {
-    int flags = EntryListenerFlags.kNew | EntryListenerFlags.kImmediate;
-    if (localNotify) {
-      flags |= EntryListenerFlags.kLocal;
-    }
-
-    final int prefixLen = m_path.length() + 1;
-    final NetworkTable parent = this;
-
-    return m_inst.addEntryListener(
-        m_pathWithSep,
-        new Consumer<>() {
-          final Set<String> m_notifiedTables = new HashSet<>();
-
-          @Override
-          public void accept(EntryNotification event) {
-            String relativeKey = event.name.substring(prefixLen);
-            int endSubTable = relativeKey.indexOf(PATH_SEPARATOR);
-            if (endSubTable == -1) {
-              return;
-            }
-            String subTableKey = relativeKey.substring(0, endSubTable);
-            if (m_notifiedTables.contains(subTableKey)) {
-              return;
-            }
-            m_notifiedTables.add(subTableKey);
-            listener.tableCreated(parent, subTableKey, parent.getSubTable(subTableKey));
-          }
-        },
-        flags);
-  }
-
-  /**
-   * Remove a sub-table listener.
-   *
-   * @param listener listener handle
-   */
-  public void removeTableListener(int listener) {
-    m_inst.removeEntryListener(listener);
-  }
-
-  /**
    * Returns the table at the specified key. If there is no table at the specified key, it will
    * create a new table
    *
@@ -258,7 +288,7 @@
    * @return true if the table as a value assigned to the given key
    */
   public boolean containsKey(String key) {
-    return !("".equals(key)) && getEntry(key).exists();
+    return !("".equals(key)) && getTopic(key).exists();
   }
 
   /**
@@ -269,9 +299,64 @@
    *     its own
    */
   public boolean containsSubTable(String key) {
-    int[] handles =
-        NetworkTablesJNI.getEntries(m_inst.getHandle(), m_pathWithSep + key + PATH_SEPARATOR, 0);
-    return handles.length != 0;
+    Topic[] topics = m_inst.getTopics(m_pathWithSep + key + PATH_SEPARATOR, 0);
+    return topics.length != 0;
+  }
+
+  /**
+   * Gets topic information for all keys in the table (not including sub-tables).
+   *
+   * @param types bitmask of types (NetworkTableType values); 0 is treated as a "don't care".
+   * @return topic information for keys currently in the table
+   */
+  public List<TopicInfo> getTopicInfo(int types) {
+    List<TopicInfo> infos = new ArrayList<>();
+    int prefixLen = m_path.length() + 1;
+    for (TopicInfo info : m_inst.getTopicInfo(m_pathWithSep, types)) {
+      String relativeKey = info.name.substring(prefixLen);
+      if (relativeKey.indexOf(PATH_SEPARATOR) != -1) {
+        continue;
+      }
+      infos.add(info);
+    }
+    return infos;
+  }
+
+  /**
+   * Gets topic information for all keys in the table (not including sub-tables).
+   *
+   * @return topic information for keys currently in the table
+   */
+  public List<TopicInfo> getTopicInfo() {
+    return getTopicInfo(0);
+  }
+
+  /**
+   * Gets all topics in the table (not including sub-tables).
+   *
+   * @param types bitmask of types (NetworkTableType values); 0 is treated as a "don't care".
+   * @return topic for keys currently in the table
+   */
+  public List<Topic> getTopics(int types) {
+    List<Topic> topics = new ArrayList<>();
+    int prefixLen = m_path.length() + 1;
+    for (TopicInfo info : m_inst.getTopicInfo(m_pathWithSep, types)) {
+      String relativeKey = info.name.substring(prefixLen);
+      if (relativeKey.indexOf(PATH_SEPARATOR) != -1) {
+        continue;
+      }
+      topics.add(info.getTopic());
+    }
+    return topics;
+  }
+
+  /**
+   * Gets all topics in the table (not including sub-tables).
+   *
+   * @return topic for keys currently in the table
+   */
+  public List<Topic> getTopics() {
+    return getTopics(0);
   }
 
   /**
@@ -283,16 +368,12 @@
   public Set<String> getKeys(int types) {
     Set<String> keys = new HashSet<>();
     int prefixLen = m_path.length() + 1;
-    for (EntryInfo info : m_inst.getEntryInfo(m_pathWithSep, types)) {
+    for (TopicInfo info : m_inst.getTopicInfo(m_pathWithSep, types)) {
       String relativeKey = info.name.substring(prefixLen);
       if (relativeKey.indexOf(PATH_SEPARATOR) != -1) {
         continue;
       }
       keys.add(relativeKey);
-      // populate entries as we go
-      if (m_entries.get(relativeKey) == null) {
-        m_entries.putIfAbsent(relativeKey, new NetworkTableEntry(m_inst, info.entry));
-      }
     }
     return keys;
   }
@@ -314,7 +395,7 @@
   public Set<String> getSubTables() {
     Set<String> keys = new HashSet<>();
     int prefixLen = m_path.length() + 1;
-    for (EntryInfo info : m_inst.getEntryInfo(m_pathWithSep, 0)) {
+    for (TopicInfo info : m_inst.getTopicInfo(m_pathWithSep, 0)) {
       String relativeKey = info.name.substring(prefixLen);
       int endSubTable = relativeKey.indexOf(PATH_SEPARATOR);
       if (endSubTable == -1) {
@@ -326,22 +407,13 @@
   }
 
   /**
-   * Deletes the specified key in this table. The key can not be null.
-   *
-   * @param key the key name
-   */
-  public void delete(String key) {
-    getEntry(key).delete();
-  }
-
-  /**
    * Put a value in the table.
    *
    * @param key the key to be assigned to
    * @param value the value that will be assigned
    * @return False if the table key already exists with a different type
    */
-  boolean putValue(String key, NetworkTableValue value) {
+  public boolean putValue(String key, NetworkTableValue value) {
     return getEntry(key).setValue(value);
   }
 
@@ -352,7 +424,7 @@
    * @param defaultValue the default value to set if key doesn't exist.
    * @return False if the table key exists with a different type
    */
-  boolean setDefaultValue(String key, NetworkTableValue defaultValue) {
+  public boolean setDefaultValue(String key, NetworkTableValue defaultValue) {
     return getEntry(key).setDefaultValue(defaultValue);
   }
 
@@ -362,7 +434,7 @@
    * @param key the key of the value to look up
    * @return the value associated with the given key, or nullptr if the key does not exist
    */
-  NetworkTableValue getValue(String key) {
+  public NetworkTableValue getValue(String key) {
     return getEntry(key).getValue();
   }
 
@@ -375,26 +447,121 @@
     return m_path;
   }
 
-  /**
-   * Save table values to a file. The file format used is identical to that used for SavePersistent.
-   *
-   * @param filename filename
-   * @throws PersistentException if error saving file
-   */
-  public void saveEntries(String filename) throws PersistentException {
-    m_inst.saveEntries(filename, m_pathWithSep);
+  /** A listener that listens to events on topics in a {@link NetworkTable}. */
+  @FunctionalInterface
+  public interface TableEventListener {
+    /**
+     * Called when an event occurs on a topic in a {@link NetworkTable}.
+     *
+     * @param table the table the topic exists in
+     * @param key the key associated with the topic that changed
+     * @param event the event
+     */
+    void accept(NetworkTable table, String key, NetworkTableEvent event);
   }
 
   /**
-   * Load table values from a file. The file format used is identical to that used for
-   * SavePersistent / LoadPersistent.
+   * Listen to topics only within this table.
    *
-   * @param filename filename
-   * @return List of warnings (errors result in an exception instead)
-   * @throws PersistentException if error saving file
+   * @param eventKinds set of event kinds to listen to
+   * @param listener listener to add
+   * @return Listener handle
    */
-  public String[] loadEntries(String filename) throws PersistentException {
-    return m_inst.loadEntries(filename, m_pathWithSep);
+  public int addListener(EnumSet<NetworkTableEvent.Kind> eventKinds, TableEventListener listener) {
+    final int prefixLen = m_path.length() + 1;
+    return m_inst.addListener(
+        new String[] {m_pathWithSep},
+        eventKinds,
+        event -> {
+          String topicName = null;
+          if (event.topicInfo != null) {
+            topicName = event.topicInfo.name;
+          } else if (event.valueData != null) {
+            topicName = event.valueData.getTopic().getName();
+          }
+          if (topicName == null) {
+            return;
+          }
+          String relativeKey = topicName.substring(prefixLen);
+          if (relativeKey.indexOf(PATH_SEPARATOR) != -1) {
+            // part of a sub table
+            return;
+          }
+          listener.accept(this, relativeKey, event);
+        });
+  }
+
+  /**
+   * Listen to a single key.
+   *
+   * @param key the key name
+   * @param eventKinds set of event kinds to listen to
+   * @param listener listener to add
+   * @return Listener handle
+   */
+  public int addListener(
+      String key, EnumSet<NetworkTableEvent.Kind> eventKinds, TableEventListener listener) {
+    NetworkTableEntry entry = getEntry(key);
+    return m_inst.addListener(entry, eventKinds, event -> listener.accept(this, key, event));
+  }
+
+  /** A listener that listens to new tables in a {@link NetworkTable}. */
+  @FunctionalInterface
+  public interface SubTableListener {
+    /**
+     * Called when a new table is created within a {@link NetworkTable}.
+     *
+     * @param parent the parent of the table
+     * @param name the name of the new table
+     * @param table the new table
+     */
+    void tableCreated(NetworkTable parent, String name, NetworkTable table);
+  }
+
+  /**
+   * Listen for sub-table creation. This calls the listener once for each newly created sub-table.
+   * It immediately calls the listener for any existing sub-tables.
+   *
+   * @param listener listener to add
+   * @return Listener handle
+   */
+  public int addSubTableListener(SubTableListener listener) {
+    final int prefixLen = m_path.length() + 1;
+    final NetworkTable parent = this;
+
+    return m_inst.addListener(
+        new String[] {m_pathWithSep},
+        EnumSet.of(NetworkTableEvent.Kind.kPublish, NetworkTableEvent.Kind.kImmediate),
+        new Consumer<NetworkTableEvent>() {
+          final Set<String> m_notifiedTables = new HashSet<>();
+
+          @Override
+          public void accept(NetworkTableEvent event) {
+            if (event.topicInfo == null) {
+              return; // should not happen
+            }
+            String relativeKey = event.topicInfo.name.substring(prefixLen);
+            int endSubTable = relativeKey.indexOf(PATH_SEPARATOR);
+            if (endSubTable == -1) {
+              return;
+            }
+            String subTableKey = relativeKey.substring(0, endSubTable);
+            if (m_notifiedTables.contains(subTableKey)) {
+              return;
+            }
+            m_notifiedTables.add(subTableKey);
+            listener.tableCreated(parent, subTableKey, parent.getSubTable(subTableKey));
+          }
+        });
+  }
+
+  /**
+   * Remove a listener.
+   *
+   * @param listener listener handle
+   */
+  public void removeListener(int listener) {
+    m_inst.removeListener(listener);
   }
 
   @Override
diff --git a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableEntry.java b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableEntry.java
deleted file mode 100644
index 872bc89..0000000
--- a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableEntry.java
+++ /dev/null
@@ -1,858 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.networktables;
-
-import java.nio.ByteBuffer;
-import java.util.function.Consumer;
-
-/** NetworkTables Entry. */
-public final class NetworkTableEntry {
-  /** Flag values (as returned by {@link #getFlags()}). */
-  public static final int kPersistent = 0x01;
-
-  /**
-   * Construct from native handle.
-   *
-   * @param inst Instance
-   * @param handle Native handle
-   */
-  public NetworkTableEntry(NetworkTableInstance inst, int handle) {
-    m_inst = inst;
-    m_handle = handle;
-  }
-
-  /**
-   * Determines if the native handle is valid.
-   *
-   * @return True if the native handle is valid, false otherwise.
-   */
-  public boolean isValid() {
-    return m_handle != 0;
-  }
-
-  /**
-   * Gets the native handle for the entry.
-   *
-   * @return Native handle
-   */
-  public int getHandle() {
-    return m_handle;
-  }
-
-  /**
-   * Gets the instance for the entry.
-   *
-   * @return Instance
-   */
-  public NetworkTableInstance getInstance() {
-    return m_inst;
-  }
-
-  /**
-   * Determines if the entry currently exists.
-   *
-   * @return True if the entry exists, false otherwise.
-   */
-  public boolean exists() {
-    return NetworkTablesJNI.getType(m_handle) != 0;
-  }
-
-  /**
-   * Gets the name of the entry (the key).
-   *
-   * @return the entry's name
-   */
-  public String getName() {
-    return NetworkTablesJNI.getEntryName(m_handle);
-  }
-
-  /**
-   * Gets the type of the entry.
-   *
-   * @return the entry's type
-   */
-  public NetworkTableType getType() {
-    return NetworkTableType.getFromInt(NetworkTablesJNI.getType(m_handle));
-  }
-
-  /**
-   * Returns the flags.
-   *
-   * @return the flags (bitmask)
-   */
-  public int getFlags() {
-    return NetworkTablesJNI.getEntryFlags(m_handle);
-  }
-
-  /**
-   * Gets the last time the entry's value was changed.
-   *
-   * @return Entry last change time
-   */
-  public long getLastChange() {
-    return NetworkTablesJNI.getEntryLastChange(m_handle);
-  }
-
-  /**
-   * Gets combined information about the entry.
-   *
-   * @return Entry information
-   */
-  public EntryInfo getInfo() {
-    return NetworkTablesJNI.getEntryInfoHandle(m_inst, m_handle);
-  }
-
-  /**
-   * Gets the entry's value. Returns a value with type NetworkTableType.kUnassigned if the value
-   * does not exist.
-   *
-   * @return the entry's value
-   */
-  public NetworkTableValue getValue() {
-    return NetworkTablesJNI.getValue(m_handle);
-  }
-
-  /**
-   * Gets the entry's value as a boolean. If the entry does not exist or is of different type, it
-   * will return the default value.
-   *
-   * @param defaultValue the value to be returned if no value is found
-   * @return the entry's value or the given default value
-   */
-  public boolean getBoolean(boolean defaultValue) {
-    return NetworkTablesJNI.getBoolean(m_handle, defaultValue);
-  }
-
-  /**
-   * Gets the entry's value as a double. If the entry does not exist or is of different type, it
-   * will return the default value.
-   *
-   * @param defaultValue the value to be returned if no value is found
-   * @return the entry's value or the given default value
-   */
-  public double getDouble(double defaultValue) {
-    return NetworkTablesJNI.getDouble(m_handle, defaultValue);
-  }
-
-  /**
-   * Gets the entry's value as a double. If the entry does not exist or is of different type, it
-   * will return the default value.
-   *
-   * @param defaultValue the value to be returned if no value is found
-   * @return the entry's value or the given default value
-   */
-  public Number getNumber(Number defaultValue) {
-    return NetworkTablesJNI.getDouble(m_handle, defaultValue.doubleValue());
-  }
-
-  /**
-   * Gets the entry's value as a string. If the entry does not exist or is of different type, it
-   * will return the default value.
-   *
-   * @param defaultValue the value to be returned if no value is found
-   * @return the entry's value or the given default value
-   */
-  public String getString(String defaultValue) {
-    return NetworkTablesJNI.getString(m_handle, defaultValue);
-  }
-
-  /**
-   * Gets the entry's value as a raw value (byte array). If the entry does not exist or is of
-   * different type, it will return the default value.
-   *
-   * @param defaultValue the value to be returned if no value is found
-   * @return the entry's value or the given default value
-   */
-  public byte[] getRaw(byte[] defaultValue) {
-    return NetworkTablesJNI.getRaw(m_handle, defaultValue);
-  }
-
-  /**
-   * Gets the entry's value as a boolean array. If the entry does not exist or is of different type,
-   * it will return the default value.
-   *
-   * @param defaultValue the value to be returned if no value is found
-   * @return the entry's value or the given default value
-   */
-  public boolean[] getBooleanArray(boolean[] defaultValue) {
-    return NetworkTablesJNI.getBooleanArray(m_handle, defaultValue);
-  }
-
-  /**
-   * Gets the entry's value as a boolean array. If the entry does not exist or is of different type,
-   * it will return the default value.
-   *
-   * @param defaultValue the value to be returned if no value is found
-   * @return the entry's value or the given default value
-   */
-  public Boolean[] getBooleanArray(Boolean[] defaultValue) {
-    return NetworkTableValue.fromNative(
-        NetworkTablesJNI.getBooleanArray(m_handle, NetworkTableValue.toNative(defaultValue)));
-  }
-
-  /**
-   * Gets the entry's value as a double array. If the entry does not exist or is of different type,
-   * it will return the default value.
-   *
-   * @param defaultValue the value to be returned if no value is found
-   * @return the entry's value or the given default value
-   */
-  public double[] getDoubleArray(double[] defaultValue) {
-    return NetworkTablesJNI.getDoubleArray(m_handle, defaultValue);
-  }
-
-  /**
-   * Gets the entry's value as a double array. If the entry does not exist or is of different type,
-   * it will return the default value.
-   *
-   * @param defaultValue the value to be returned if no value is found
-   * @return the entry's value or the given default value
-   */
-  public Double[] getDoubleArray(Double[] defaultValue) {
-    return NetworkTableValue.fromNative(
-        NetworkTablesJNI.getDoubleArray(m_handle, NetworkTableValue.toNative(defaultValue)));
-  }
-
-  /**
-   * Gets the entry's value as a double array. If the entry does not exist or is of different type,
-   * it will return the default value.
-   *
-   * @param defaultValue the value to be returned if no value is found
-   * @return the entry's value or the given default value
-   */
-  public Number[] getNumberArray(Number[] defaultValue) {
-    return NetworkTableValue.fromNative(
-        NetworkTablesJNI.getDoubleArray(m_handle, NetworkTableValue.toNative(defaultValue)));
-  }
-
-  /**
-   * Gets the entry's value as a string array. If the entry does not exist or is of different type,
-   * it will return the default value.
-   *
-   * @param defaultValue the value to be returned if no value is found
-   * @return the entry's value or the given default value
-   */
-  public String[] getStringArray(String[] defaultValue) {
-    return NetworkTablesJNI.getStringArray(m_handle, defaultValue);
-  }
-
-  /**
-   * Checks if a data value is of a type that can be placed in a NetworkTable entry.
-   *
-   * @param data the data to check
-   * @return true if the data can be placed in an entry, false if it cannot
-   */
-  public static boolean isValidDataType(Object data) {
-    return data instanceof Number
-        || data instanceof Boolean
-        || data instanceof String
-        || data instanceof double[]
-        || data instanceof Double[]
-        || data instanceof Number[]
-        || data instanceof boolean[]
-        || data instanceof Boolean[]
-        || data instanceof String[]
-        || data instanceof byte[]
-        || data instanceof Byte[];
-  }
-
-  /**
-   * Sets the entry's value if it does not exist.
-   *
-   * @param defaultValue the default value to set
-   * @return False if the entry exists with a different type
-   * @throws IllegalArgumentException if the value is not a known type
-   */
-  public boolean setDefaultValue(Object defaultValue) {
-    if (defaultValue instanceof NetworkTableValue) {
-      long time = ((NetworkTableValue) defaultValue).getTime();
-      Object otherValue = ((NetworkTableValue) defaultValue).getValue();
-      switch (((NetworkTableValue) defaultValue).getType()) {
-        case kBoolean:
-          return NetworkTablesJNI.setDefaultBoolean(m_handle, time, (Boolean) otherValue);
-        case kDouble:
-          return NetworkTablesJNI.setDefaultDouble(
-              m_handle, time, ((Number) otherValue).doubleValue());
-        case kString:
-          return NetworkTablesJNI.setDefaultString(m_handle, time, (String) otherValue);
-        case kRaw:
-          return NetworkTablesJNI.setDefaultRaw(m_handle, time, (byte[]) otherValue);
-        case kBooleanArray:
-          return NetworkTablesJNI.setDefaultBooleanArray(m_handle, time, (boolean[]) otherValue);
-        case kDoubleArray:
-          return NetworkTablesJNI.setDefaultDoubleArray(m_handle, time, (double[]) otherValue);
-        case kStringArray:
-          return NetworkTablesJNI.setDefaultStringArray(m_handle, time, (String[]) otherValue);
-        case kRpc:
-          // TODO
-        default:
-          return true;
-      }
-    } else if (defaultValue instanceof Boolean) {
-      return setDefaultBoolean((Boolean) defaultValue);
-    } else if (defaultValue instanceof Number) {
-      return setDefaultNumber((Number) defaultValue);
-    } else if (defaultValue instanceof String) {
-      return setDefaultString((String) defaultValue);
-    } else if (defaultValue instanceof byte[]) {
-      return setDefaultRaw((byte[]) defaultValue);
-    } else if (defaultValue instanceof boolean[]) {
-      return setDefaultBooleanArray((boolean[]) defaultValue);
-    } else if (defaultValue instanceof double[]) {
-      return setDefaultDoubleArray((double[]) defaultValue);
-    } else if (defaultValue instanceof Boolean[]) {
-      return setDefaultBooleanArray((Boolean[]) defaultValue);
-    } else if (defaultValue instanceof Number[]) {
-      return setDefaultNumberArray((Number[]) defaultValue);
-    } else if (defaultValue instanceof String[]) {
-      return setDefaultStringArray((String[]) defaultValue);
-    } else {
-      throw new IllegalArgumentException(
-          "Value of type " + defaultValue.getClass().getName() + " cannot be put into a table");
-    }
-  }
-
-  /**
-   * Sets the entry's value if it does not exist.
-   *
-   * @param defaultValue the default value to set
-   * @return False if the entry exists with a different type
-   */
-  public boolean setDefaultBoolean(boolean defaultValue) {
-    return NetworkTablesJNI.setDefaultBoolean(m_handle, 0, defaultValue);
-  }
-
-  /**
-   * Sets the entry's value if it does not exist.
-   *
-   * @param defaultValue the default value to set
-   * @return False if the entry exists with a different type
-   */
-  public boolean setDefaultDouble(double defaultValue) {
-    return NetworkTablesJNI.setDefaultDouble(m_handle, 0, defaultValue);
-  }
-
-  /**
-   * Sets the entry's value if it does not exist.
-   *
-   * @param defaultValue the default value to set
-   * @return False if the entry exists with a different type
-   */
-  public boolean setDefaultNumber(Number defaultValue) {
-    return NetworkTablesJNI.setDefaultDouble(m_handle, 0, defaultValue.doubleValue());
-  }
-
-  /**
-   * Sets the entry's value if it does not exist.
-   *
-   * @param defaultValue the default value to set
-   * @return False if the entry exists with a different type
-   */
-  public boolean setDefaultString(String defaultValue) {
-    return NetworkTablesJNI.setDefaultString(m_handle, 0, defaultValue);
-  }
-
-  /**
-   * Sets the entry's value if it does not exist.
-   *
-   * @param defaultValue the default value to set
-   * @return False if the entry exists with a different type
-   */
-  public boolean setDefaultRaw(byte[] defaultValue) {
-    return NetworkTablesJNI.setDefaultRaw(m_handle, 0, defaultValue);
-  }
-
-  /**
-   * Sets the entry's value if it does not exist.
-   *
-   * @param defaultValue the default value to set
-   * @return False if the entry exists with a different type
-   */
-  public boolean setDefaultBooleanArray(boolean[] defaultValue) {
-    return NetworkTablesJNI.setDefaultBooleanArray(m_handle, 0, defaultValue);
-  }
-
-  /**
-   * Sets the entry's value if it does not exist.
-   *
-   * @param defaultValue the default value to set
-   * @return False if the entry exists with a different type
-   */
-  public boolean setDefaultBooleanArray(Boolean[] defaultValue) {
-    return NetworkTablesJNI.setDefaultBooleanArray(
-        m_handle, 0, NetworkTableValue.toNative(defaultValue));
-  }
-
-  /**
-   * Sets the entry's value if it does not exist.
-   *
-   * @param defaultValue the default value to set
-   * @return False if the entry exists with a different type
-   */
-  public boolean setDefaultDoubleArray(double[] defaultValue) {
-    return NetworkTablesJNI.setDefaultDoubleArray(m_handle, 0, defaultValue);
-  }
-
-  /**
-   * Sets the entry's value if it does not exist.
-   *
-   * @param defaultValue the default value to set
-   * @return False if the entry exists with a different type
-   */
-  public boolean setDefaultNumberArray(Number[] defaultValue) {
-    return NetworkTablesJNI.setDefaultDoubleArray(
-        m_handle, 0, NetworkTableValue.toNative(defaultValue));
-  }
-
-  /**
-   * Sets the entry's value if it does not exist.
-   *
-   * @param defaultValue the default value to set
-   * @return False if the entry exists with a different type
-   */
-  public boolean setDefaultStringArray(String[] defaultValue) {
-    return NetworkTablesJNI.setDefaultStringArray(m_handle, 0, defaultValue);
-  }
-
-  /**
-   * Sets the entry's value.
-   *
-   * @param value the value that will be assigned
-   * @return False if the table key already exists with a different type
-   * @throws IllegalArgumentException if the value is not a known type
-   */
-  public boolean setValue(Object value) {
-    if (value instanceof NetworkTableValue) {
-      long time = ((NetworkTableValue) value).getTime();
-      Object otherValue = ((NetworkTableValue) value).getValue();
-      switch (((NetworkTableValue) value).getType()) {
-        case kBoolean:
-          return NetworkTablesJNI.setBoolean(m_handle, time, (Boolean) otherValue, false);
-        case kDouble:
-          return NetworkTablesJNI.setDouble(
-              m_handle, time, ((Number) otherValue).doubleValue(), false);
-        case kString:
-          return NetworkTablesJNI.setString(m_handle, time, (String) otherValue, false);
-        case kRaw:
-          return NetworkTablesJNI.setRaw(m_handle, time, (byte[]) otherValue, false);
-        case kBooleanArray:
-          return NetworkTablesJNI.setBooleanArray(m_handle, time, (boolean[]) otherValue, false);
-        case kDoubleArray:
-          return NetworkTablesJNI.setDoubleArray(m_handle, time, (double[]) otherValue, false);
-        case kStringArray:
-          return NetworkTablesJNI.setStringArray(m_handle, time, (String[]) otherValue, false);
-        case kRpc:
-          // TODO
-        default:
-          return true;
-      }
-    } else if (value instanceof Boolean) {
-      return setBoolean((Boolean) value);
-    } else if (value instanceof Number) {
-      return setNumber((Number) value);
-    } else if (value instanceof String) {
-      return setString((String) value);
-    } else if (value instanceof byte[]) {
-      return setRaw((byte[]) value);
-    } else if (value instanceof boolean[]) {
-      return setBooleanArray((boolean[]) value);
-    } else if (value instanceof double[]) {
-      return setDoubleArray((double[]) value);
-    } else if (value instanceof Boolean[]) {
-      return setBooleanArray((Boolean[]) value);
-    } else if (value instanceof Number[]) {
-      return setNumberArray((Number[]) value);
-    } else if (value instanceof String[]) {
-      return setStringArray((String[]) value);
-    } else {
-      throw new IllegalArgumentException(
-          "Value of type " + value.getClass().getName() + " cannot be put into a table");
-    }
-  }
-
-  /**
-   * Sets the entry's value.
-   *
-   * @param value the value to set
-   * @return False if the entry exists with a different type
-   */
-  public boolean setBoolean(boolean value) {
-    return NetworkTablesJNI.setBoolean(m_handle, 0, value, false);
-  }
-
-  /**
-   * Sets the entry's value.
-   *
-   * @param value the value to set
-   * @return False if the entry exists with a different type
-   */
-  public boolean setDouble(double value) {
-    return NetworkTablesJNI.setDouble(m_handle, 0, value, false);
-  }
-
-  /**
-   * Sets the entry's value.
-   *
-   * @param value the value to set
-   * @return False if the entry exists with a different type
-   */
-  public boolean setNumber(Number value) {
-    return NetworkTablesJNI.setDouble(m_handle, 0, value.doubleValue(), false);
-  }
-
-  /**
-   * Sets the entry's value.
-   *
-   * @param value the value to set
-   * @return False if the entry exists with a different type
-   */
-  public boolean setString(String value) {
-    return NetworkTablesJNI.setString(m_handle, 0, value, false);
-  }
-
-  /**
-   * Sets the entry's value.
-   *
-   * @param value the value to set
-   * @return False if the entry exists with a different type
-   */
-  public boolean setRaw(byte[] value) {
-    return NetworkTablesJNI.setRaw(m_handle, 0, value, false);
-  }
-
-  /**
-   * Sets the entry's value.
-   *
-   * @param value the value to set
-   * @param len the length of the value
-   * @return False if the entry exists with a different type
-   */
-  public boolean setRaw(ByteBuffer value, int len) {
-    if (!value.isDirect()) {
-      throw new IllegalArgumentException("must be a direct buffer");
-    }
-    if (value.capacity() < len) {
-      throw new IllegalArgumentException("buffer is too small, must be at least " + len);
-    }
-    return NetworkTablesJNI.setRaw(m_handle, 0, value, len, false);
-  }
-
-  /**
-   * Sets the entry's value.
-   *
-   * @param value the value to set
-   * @return False if the entry exists with a different type
-   */
-  public boolean setBooleanArray(boolean[] value) {
-    return NetworkTablesJNI.setBooleanArray(m_handle, 0, value, false);
-  }
-
-  /**
-   * Sets the entry's value.
-   *
-   * @param value the value to set
-   * @return False if the entry exists with a different type
-   */
-  public boolean setBooleanArray(Boolean[] value) {
-    return NetworkTablesJNI.setBooleanArray(m_handle, 0, NetworkTableValue.toNative(value), false);
-  }
-
-  /**
-   * Sets the entry's value.
-   *
-   * @param value the value to set
-   * @return False if the entry exists with a different type
-   */
-  public boolean setDoubleArray(double[] value) {
-    return NetworkTablesJNI.setDoubleArray(m_handle, 0, value, false);
-  }
-
-  /**
-   * Sets the entry's value.
-   *
-   * @param value the value to set
-   * @return False if the entry exists with a different type
-   */
-  public boolean setNumberArray(Number[] value) {
-    return NetworkTablesJNI.setDoubleArray(m_handle, 0, NetworkTableValue.toNative(value), false);
-  }
-
-  /**
-   * Sets the entry's value.
-   *
-   * @param value the value to set
-   * @return False if the entry exists with a different type
-   */
-  public boolean setStringArray(String[] value) {
-    return NetworkTablesJNI.setStringArray(m_handle, 0, value, false);
-  }
-
-  /**
-   * Sets the entry's value. If the value is of different type, the type is changed to match the new
-   * value.
-   *
-   * @param value the value to set
-   * @throws IllegalArgumentException if the value is not a known type
-   */
-  public void forceSetValue(Object value) {
-    if (value instanceof NetworkTableValue) {
-      long time = ((NetworkTableValue) value).getTime();
-      Object otherValue = ((NetworkTableValue) value).getValue();
-      switch (((NetworkTableValue) value).getType()) {
-        case kBoolean:
-          NetworkTablesJNI.setBoolean(m_handle, time, (Boolean) otherValue, true);
-          return;
-        case kDouble:
-          NetworkTablesJNI.setDouble(m_handle, time, ((Number) otherValue).doubleValue(), true);
-          return;
-        case kString:
-          NetworkTablesJNI.setString(m_handle, time, (String) otherValue, true);
-          return;
-        case kRaw:
-          NetworkTablesJNI.setRaw(m_handle, time, (byte[]) otherValue, true);
-          return;
-        case kBooleanArray:
-          NetworkTablesJNI.setBooleanArray(m_handle, time, (boolean[]) otherValue, true);
-          return;
-        case kDoubleArray:
-          NetworkTablesJNI.setDoubleArray(m_handle, time, (double[]) otherValue, true);
-          return;
-        case kStringArray:
-          NetworkTablesJNI.setStringArray(m_handle, time, (String[]) otherValue, true);
-          return;
-        case kRpc:
-          // TODO
-        default:
-          return;
-      }
-    } else if (value instanceof Boolean) {
-      forceSetBoolean((Boolean) value);
-    } else if (value instanceof Number) {
-      forceSetNumber((Number) value);
-    } else if (value instanceof String) {
-      forceSetString((String) value);
-    } else if (value instanceof byte[]) {
-      forceSetRaw((byte[]) value);
-    } else if (value instanceof boolean[]) {
-      forceSetBooleanArray((boolean[]) value);
-    } else if (value instanceof double[]) {
-      forceSetDoubleArray((double[]) value);
-    } else if (value instanceof Boolean[]) {
-      forceSetBooleanArray((Boolean[]) value);
-    } else if (value instanceof Number[]) {
-      forceSetNumberArray((Number[]) value);
-    } else if (value instanceof String[]) {
-      forceSetStringArray((String[]) value);
-    } else {
-      throw new IllegalArgumentException(
-          "Value of type " + value.getClass().getName() + " cannot be put into a table");
-    }
-  }
-
-  /**
-   * Sets the entry's value. If the value is of different type, the type is changed to match the new
-   * value.
-   *
-   * @param value the value to set
-   */
-  public void forceSetBoolean(boolean value) {
-    NetworkTablesJNI.setBoolean(m_handle, 0, value, true);
-  }
-
-  /**
-   * Sets the entry's value. If the value is of different type, the type is changed to match the new
-   * value.
-   *
-   * @param value the value to set
-   */
-  public void forceSetDouble(double value) {
-    NetworkTablesJNI.setDouble(m_handle, 0, value, true);
-  }
-
-  /**
-   * Sets the entry's value. If the value is of different type, the type is changed to match the new
-   * value.
-   *
-   * @param value the value to set
-   */
-  public void forceSetNumber(Number value) {
-    NetworkTablesJNI.setDouble(m_handle, 0, value.doubleValue(), true);
-  }
-
-  /**
-   * Sets the entry's value. If the value is of different type, the type is changed to match the new
-   * value.
-   *
-   * @param value the value to set
-   */
-  public void forceSetString(String value) {
-    NetworkTablesJNI.setString(m_handle, 0, value, true);
-  }
-
-  /**
-   * Sets the entry's value. If the value is of different type, the type is changed to match the new
-   * value.
-   *
-   * @param value the value to set
-   */
-  public void forceSetRaw(byte[] value) {
-    NetworkTablesJNI.setRaw(m_handle, 0, value, true);
-  }
-
-  /**
-   * Sets the entry's value. If the value is of different type, the type is changed to match the new
-   * value.
-   *
-   * @param value the value to set
-   */
-  public void forceSetBooleanArray(boolean[] value) {
-    NetworkTablesJNI.setBooleanArray(m_handle, 0, value, true);
-  }
-
-  /**
-   * Sets the entry's value. If the value is of different type, the type is changed to match the new
-   * value.
-   *
-   * @param value the value to set
-   */
-  public void forceSetBooleanArray(Boolean[] value) {
-    NetworkTablesJNI.setBooleanArray(m_handle, 0, NetworkTableValue.toNative(value), true);
-  }
-
-  /**
-   * Sets the entry's value. If the value is of different type, the type is changed to match the new
-   * value.
-   *
-   * @param value the value to set
-   */
-  public void forceSetDoubleArray(double[] value) {
-    NetworkTablesJNI.setDoubleArray(m_handle, 0, value, true);
-  }
-
-  /**
-   * Sets the entry's value. If the value is of different type, the type is changed to match the new
-   * value.
-   *
-   * @param value the value to set
-   */
-  public void forceSetNumberArray(Number[] value) {
-    NetworkTablesJNI.setDoubleArray(m_handle, 0, NetworkTableValue.toNative(value), true);
-  }
-
-  /**
-   * Sets the entry's value. If the value is of different type, the type is changed to match the new
-   * value.
-   *
-   * @param value the value to set
-   */
-  public void forceSetStringArray(String[] value) {
-    NetworkTablesJNI.setStringArray(m_handle, 0, value, true);
-  }
-
-  /**
-   * Sets flags.
-   *
-   * @param flags the flags to set (bitmask)
-   */
-  public void setFlags(int flags) {
-    NetworkTablesJNI.setEntryFlags(m_handle, getFlags() | flags);
-  }
-
-  /**
-   * Clears flags.
-   *
-   * @param flags the flags to clear (bitmask)
-   */
-  public void clearFlags(int flags) {
-    NetworkTablesJNI.setEntryFlags(m_handle, getFlags() & ~flags);
-  }
-
-  /** Make value persistent through program restarts. */
-  public void setPersistent() {
-    setFlags(kPersistent);
-  }
-
-  /** Stop making value persistent through program restarts. */
-  public void clearPersistent() {
-    clearFlags(kPersistent);
-  }
-
-  /**
-   * Returns whether the value is persistent through program restarts.
-   *
-   * @return True if the value is persistent.
-   */
-  public boolean isPersistent() {
-    return (getFlags() & kPersistent) != 0;
-  }
-
-  /** Deletes the entry. */
-  public void delete() {
-    NetworkTablesJNI.deleteEntry(m_handle);
-  }
-
-  /**
-   * Create a callback-based RPC entry point. Only valid to use on the server. The callback function
-   * will be called when the RPC is called. This function creates RPC version 0 definitions (raw
-   * data in and out).
-   *
-   * @param callback callback function
-   */
-  public void createRpc(Consumer<RpcAnswer> callback) {
-    m_inst.createRpc(this, callback);
-  }
-
-  /**
-   * Call a RPC function. May be used on either the client or server. This function is non-blocking.
-   * Either {@link RpcCall#getResult()} or {@link RpcCall#cancelResult()} must be called on the
-   * return value to either get or ignore the result of the call.
-   *
-   * @param params parameter
-   * @return RPC call object.
-   */
-  public RpcCall callRpc(byte[] params) {
-    return new RpcCall(this, NetworkTablesJNI.callRpc(m_handle, params));
-  }
-
-  /**
-   * Add a listener for changes to the entry.
-   *
-   * @param listener the listener to add
-   * @param flags bitmask specifying desired notifications
-   * @return listener handle
-   */
-  public int addListener(Consumer<EntryNotification> listener, int flags) {
-    return m_inst.addEntryListener(this, listener, flags);
-  }
-
-  /**
-   * Remove a listener from receiving entry events.
-   *
-   * @param listener the listener to be removed
-   */
-  public void removeListener(int listener) {
-    m_inst.removeEntryListener(listener);
-  }
-
-  @Override
-  public boolean equals(Object other) {
-    if (other == this) {
-      return true;
-    }
-    if (!(other instanceof NetworkTableEntry)) {
-      return false;
-    }
-
-    return m_handle == ((NetworkTableEntry) other).m_handle;
-  }
-
-  @Override
-  public int hashCode() {
-    return m_handle;
-  }
-
-  private final NetworkTableInstance m_inst;
-  private final int m_handle;
-}
diff --git a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableEvent.java b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableEvent.java
new file mode 100644
index 0000000..97883c8
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableEvent.java
@@ -0,0 +1,152 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.networktables;
+
+/**
+ * NetworkTables event.
+ *
+ * <p>There are different kinds of events. When creating a listener, a combination of event kinds
+ * can be listened to by building an EnumSet of NetworkTableEvent.Kind.
+ */
+@SuppressWarnings("MemberName")
+public final class NetworkTableEvent {
+  public enum Kind {
+    /**
+     * Initial listener addition. Set this to receive immediate notification of matches to other
+     * criteria.
+     */
+    kImmediate(0x0001),
+
+    /** Client connected (on server, any client connected). */
+    kConnected(0x0002),
+
+    /** Client disconnected (on server, any client disconnected). */
+    kDisconnected(0x0004),
+
+    /** Any connection event (connect or disconnect). */
+    kConnection(0x0004 | 0x0002),
+
+    /** New topic published. */
+    kPublish(0x0008),
+
+    /** Topic unpublished. */
+    kUnpublish(0x0010),
+
+    /** Topic properties changed. */
+    kProperties(0x0020),
+
+    /** Any topic event (publish, unpublish, or properties changed). */
+    kTopic(0x0020 | 0x0010 | 0x0008),
+
+    /** Topic value updated (via network). */
+    kValueRemote(0x0040),
+
+    /** Topic value updated (local). */
+    kValueLocal(0x0080),
+
+    /** Topic value updated (network or local). */
+    kValueAll(0x0080 | 0x0040),
+
+    /** Log message. */
+    kLogMessage(0x0100),
+
+    /** Time synchronized with server. */
+    kTimeSync(0x0200);
+
+    private final int value;
+
+    Kind(int value) {
+      this.value = value;
+    }
+
+    public int getValue() {
+      return value;
+    }
+  }
+
+  /**
+   * Handle of listener that was triggered. The value returned when adding the listener can be used
+   * to map this to a specific added listener.
+   */
+  public final int listener;
+
+  /**
+   * Determine if event is of a particular kind. For example, kPublish if the topic was not
+   * previously published. Also indicates the data included with the event:
+   *
+   * <ul>
+   *   <li>kConnected or kDisconnected: connInfo
+   *   <li>kPublish, kUnpublish, or kProperties: topicInfo
+   *   <li>kValueRemote, kValueLocal: valueData
+   *   <li>kLogMessage: logMessage
+   * </ul>
+   *
+   * @param kind Kind
+   * @return True if event matches kind
+   */
+  public boolean is(Kind kind) {
+    return (m_flags & kind.getValue()) != 0;
+  }
+
+  private final int m_flags;
+
+  /** Connection information (for connection events). */
+  public final ConnectionInfo connInfo;
+
+  /** Topic information (for topic events). */
+  public final TopicInfo topicInfo;
+
+  /** Value data (for value events). */
+  public final ValueEventData valueData;
+
+  /** Log message (for log message events). */
+  public final LogMessage logMessage;
+
+  /** Log message (for log message events). */
+  public final TimeSyncEventData timeSyncData;
+
+  /**
+   * Constructor. This should generally only be used internally to NetworkTables.
+   *
+   * @param inst Instance
+   * @param listener Listener that was triggered
+   * @param flags Event flags
+   * @param connInfo Connection information
+   * @param topicInfo Topic information
+   * @param valueData Value data
+   * @param logMessage Log message
+   * @param timeSyncData Time sync data
+   */
+  public NetworkTableEvent(
+      NetworkTableInstance inst,
+      int listener,
+      int flags,
+      ConnectionInfo connInfo,
+      TopicInfo topicInfo,
+      ValueEventData valueData,
+      LogMessage logMessage,
+      TimeSyncEventData timeSyncData) {
+    this.m_inst = inst;
+    this.listener = listener;
+    this.m_flags = flags;
+    this.connInfo = connInfo;
+    this.topicInfo = topicInfo;
+    this.valueData = valueData;
+    this.logMessage = logMessage;
+    this.timeSyncData = timeSyncData;
+  }
+
+  /* Network table instance. */
+  private final NetworkTableInstance m_inst;
+
+  /**
+   * Gets the instance associated with this event.
+   *
+   * @return Instance
+   */
+  public NetworkTableInstance getInstance() {
+    return m_inst;
+  }
+}
diff --git a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableInstance.java b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableInstance.java
deleted file mode 100644
index 162327e..0000000
--- a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableInstance.java
+++ /dev/null
@@ -1,1153 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.networktables;
-
-import java.util.HashMap;
-import java.util.Map;
-import java.util.concurrent.ConcurrentHashMap;
-import java.util.concurrent.ConcurrentMap;
-import java.util.concurrent.TimeUnit;
-import java.util.concurrent.locks.Condition;
-import java.util.concurrent.locks.ReentrantLock;
-import java.util.function.Consumer;
-
-/**
- * NetworkTables Instance.
- *
- * <p>Instances are completely independent from each other. Table operations on one instance will
- * not be visible to other instances unless the instances are connected via the network. The main
- * limitation on instances is that you cannot have two servers on the same network port. The main
- * utility of instances is for unit testing, but they can also enable one program to connect to two
- * different NetworkTables networks.
- *
- * <p>The global "default" instance (as returned by {@link #getDefault()}) is always available, and
- * is intended for the common case when there is only a single NetworkTables instance being used in
- * the program.
- *
- * <p>Additional instances can be created with the {@link #create()} function. A reference must be
- * kept to the NetworkTableInstance returned by this function to keep it from being garbage
- * collected.
- */
-public final class NetworkTableInstance implements AutoCloseable {
-  /**
-   * Client/server mode flag values (as returned by {@link #getNetworkMode()}). This is a bitmask.
-   */
-  public static final int kNetModeNone = 0x00;
-
-  public static final int kNetModeServer = 0x01;
-  public static final int kNetModeClient = 0x02;
-  public static final int kNetModeStarting = 0x04;
-  public static final int kNetModeFailure = 0x08;
-  public static final int kNetModeLocal = 0x10;
-
-  /** The default port that network tables operates on. */
-  public static final int kDefaultPort = 1735;
-
-  /**
-   * Construct from native handle.
-   *
-   * @param handle Native handle
-   */
-  private NetworkTableInstance(int handle) {
-    m_owned = false;
-    m_handle = handle;
-  }
-
-  /** Destroys the instance (if created by {@link #create()}). */
-  @Override
-  public synchronized void close() {
-    if (m_owned && m_handle != 0) {
-      NetworkTablesJNI.destroyInstance(m_handle);
-    }
-  }
-
-  /**
-   * Determines if the native handle is valid.
-   *
-   * @return True if the native handle is valid, false otherwise.
-   */
-  public boolean isValid() {
-    return m_handle != 0;
-  }
-
-  /* The default instance. */
-  private static NetworkTableInstance s_defaultInstance;
-
-  /**
-   * Get global default instance.
-   *
-   * @return Global default instance
-   */
-  public static synchronized NetworkTableInstance getDefault() {
-    if (s_defaultInstance == null) {
-      s_defaultInstance = new NetworkTableInstance(NetworkTablesJNI.getDefaultInstance());
-    }
-    return s_defaultInstance;
-  }
-
-  /**
-   * Create an instance. Note: A reference to the returned instance must be retained to ensure the
-   * instance is not garbage collected.
-   *
-   * @return Newly created instance
-   */
-  public static NetworkTableInstance create() {
-    NetworkTableInstance inst = new NetworkTableInstance(NetworkTablesJNI.createInstance());
-    inst.m_owned = true;
-    return inst;
-  }
-
-  /**
-   * Gets the native handle for the entry.
-   *
-   * @return Native handle
-   */
-  public int getHandle() {
-    return m_handle;
-  }
-
-  /**
-   * Gets the entry for a key.
-   *
-   * @param name Key
-   * @return Network table entry.
-   */
-  public NetworkTableEntry getEntry(String name) {
-    return new NetworkTableEntry(this, NetworkTablesJNI.getEntry(m_handle, name));
-  }
-
-  /**
-   * Get entries starting with the given prefix. The results are optionally filtered by string
-   * prefix and entry type to only return a subset of all entries.
-   *
-   * @param prefix entry name required prefix; only entries whose name starts with this string are
-   *     returned
-   * @param types bitmask of types; 0 is treated as a "don't care"
-   * @return Array of entries.
-   */
-  public NetworkTableEntry[] getEntries(String prefix, int types) {
-    int[] handles = NetworkTablesJNI.getEntries(m_handle, prefix, types);
-    NetworkTableEntry[] entries = new NetworkTableEntry[handles.length];
-    for (int i = 0; i < handles.length; i++) {
-      entries[i] = new NetworkTableEntry(this, handles[i]);
-    }
-    return entries;
-  }
-
-  /**
-   * Get information about entries starting with the given prefix. The results are optionally
-   * filtered by string prefix and entry type to only return a subset of all entries.
-   *
-   * @param prefix entry name required prefix; only entries whose name starts with this string are
-   *     returned
-   * @param types bitmask of types; 0 is treated as a "don't care"
-   * @return Array of entry information.
-   */
-  public EntryInfo[] getEntryInfo(String prefix, int types) {
-    return NetworkTablesJNI.getEntryInfo(this, m_handle, prefix, types);
-  }
-
-  /* Cache of created tables. */
-  private final ConcurrentMap<String, NetworkTable> m_tables = new ConcurrentHashMap<>();
-
-  /**
-   * Gets the table with the specified key.
-   *
-   * @param key the key name
-   * @return The network table
-   */
-  public NetworkTable getTable(String key) {
-    // prepend leading / if not present
-    String theKey;
-    if (key.isEmpty() || "/".equals(key)) {
-      theKey = "";
-    } else if (key.charAt(0) == NetworkTable.PATH_SEPARATOR) {
-      theKey = key;
-    } else {
-      theKey = NetworkTable.PATH_SEPARATOR + key;
-    }
-
-    // cache created tables
-    NetworkTable table = m_tables.get(theKey);
-    if (table == null) {
-      table = new NetworkTable(this, theKey);
-      NetworkTable oldTable = m_tables.putIfAbsent(theKey, table);
-      if (oldTable != null) {
-        table = oldTable;
-      }
-    }
-    return table;
-  }
-
-  /** Deletes ALL keys in ALL subtables (except persistent values). Use with caution! */
-  public void deleteAllEntries() {
-    NetworkTablesJNI.deleteAllEntries(m_handle);
-  }
-
-  /*
-   * Callback Creation Functions
-   */
-
-  private static class EntryConsumer<T> {
-    final NetworkTableEntry m_entry;
-    final Consumer<T> m_consumer;
-
-    EntryConsumer(NetworkTableEntry entry, Consumer<T> consumer) {
-      m_entry = entry;
-      m_consumer = consumer;
-    }
-  }
-
-  private final ReentrantLock m_entryListenerLock = new ReentrantLock();
-  private final Map<Integer, EntryConsumer<EntryNotification>> m_entryListeners = new HashMap<>();
-  private int m_entryListenerPoller;
-  private boolean m_entryListenerWaitQueue;
-  private final Condition m_entryListenerWaitQueueCond = m_entryListenerLock.newCondition();
-
-  @SuppressWarnings("PMD.AvoidCatchingThrowable")
-  private void startEntryListenerThread() {
-    var entryListenerThread =
-        new Thread(
-            () -> {
-              boolean wasInterrupted = false;
-              while (!Thread.interrupted()) {
-                EntryNotification[] events;
-                try {
-                  events = NetworkTablesJNI.pollEntryListener(this, m_entryListenerPoller);
-                } catch (InterruptedException ex) {
-                  m_entryListenerLock.lock();
-                  try {
-                    if (m_entryListenerWaitQueue) {
-                      m_entryListenerWaitQueue = false;
-                      m_entryListenerWaitQueueCond.signalAll();
-                      continue;
-                    }
-                  } finally {
-                    m_entryListenerLock.unlock();
-                  }
-                  Thread.currentThread().interrupt();
-                  // don't try to destroy poller, as its handle is likely no longer valid
-                  wasInterrupted = true;
-                  break;
-                }
-                for (EntryNotification event : events) {
-                  EntryConsumer<EntryNotification> listener;
-                  m_entryListenerLock.lock();
-                  try {
-                    listener = m_entryListeners.get(event.listener);
-                  } finally {
-                    m_entryListenerLock.unlock();
-                  }
-                  if (listener != null) {
-                    event.m_entryObject = listener.m_entry;
-                    try {
-                      listener.m_consumer.accept(event);
-                    } catch (Throwable throwable) {
-                      System.err.println(
-                          "Unhandled exception during entry listener callback: "
-                              + throwable.toString());
-                      throwable.printStackTrace();
-                    }
-                  }
-                }
-              }
-              m_entryListenerLock.lock();
-              try {
-                if (!wasInterrupted) {
-                  NetworkTablesJNI.destroyEntryListenerPoller(m_entryListenerPoller);
-                }
-                m_entryListenerPoller = 0;
-              } finally {
-                m_entryListenerLock.unlock();
-              }
-            },
-            "NTEntryListener");
-    entryListenerThread.setDaemon(true);
-    entryListenerThread.start();
-  }
-
-  /**
-   * Add a listener for all entries starting with a certain prefix.
-   *
-   * @param prefix UTF-8 string prefix
-   * @param listener listener to add
-   * @param flags {@link EntryListenerFlags} bitmask
-   * @return Listener handle
-   */
-  public int addEntryListener(String prefix, Consumer<EntryNotification> listener, int flags) {
-    m_entryListenerLock.lock();
-    try {
-      if (m_entryListenerPoller == 0) {
-        m_entryListenerPoller = NetworkTablesJNI.createEntryListenerPoller(m_handle);
-        startEntryListenerThread();
-      }
-      int handle = NetworkTablesJNI.addPolledEntryListener(m_entryListenerPoller, prefix, flags);
-      m_entryListeners.put(handle, new EntryConsumer<>(null, listener));
-      return handle;
-    } finally {
-      m_entryListenerLock.unlock();
-    }
-  }
-
-  /**
-   * Add a listener for a particular entry.
-   *
-   * @param entry the entry
-   * @param listener listener to add
-   * @param flags {@link EntryListenerFlags} bitmask
-   * @return Listener handle
-   */
-  public int addEntryListener(
-      NetworkTableEntry entry, Consumer<EntryNotification> listener, int flags) {
-    if (!equals(entry.getInstance())) {
-      throw new IllegalArgumentException("entry does not belong to this instance");
-    }
-    m_entryListenerLock.lock();
-    try {
-      if (m_entryListenerPoller == 0) {
-        m_entryListenerPoller = NetworkTablesJNI.createEntryListenerPoller(m_handle);
-        startEntryListenerThread();
-      }
-      int handle =
-          NetworkTablesJNI.addPolledEntryListener(m_entryListenerPoller, entry.getHandle(), flags);
-      m_entryListeners.put(handle, new EntryConsumer<>(entry, listener));
-      return handle;
-    } finally {
-      m_entryListenerLock.unlock();
-    }
-  }
-
-  /**
-   * Remove an entry listener.
-   *
-   * @param listener Listener handle to remove
-   */
-  public void removeEntryListener(int listener) {
-    NetworkTablesJNI.removeEntryListener(listener);
-  }
-
-  /**
-   * Wait for the entry listener queue to be empty. This is primarily useful for deterministic
-   * testing. This blocks until either the entry listener queue is empty (e.g. there are no more
-   * events that need to be passed along to callbacks or poll queues) or the timeout expires.
-   *
-   * @param timeout timeout, in seconds. Set to 0 for non-blocking behavior, or a negative value to
-   *     block indefinitely
-   * @return False if timed out, otherwise true.
-   */
-  public boolean waitForEntryListenerQueue(double timeout) {
-    if (!NetworkTablesJNI.waitForEntryListenerQueue(m_handle, timeout)) {
-      return false;
-    }
-    m_entryListenerLock.lock();
-    try {
-      if (m_entryListenerPoller != 0) {
-        m_entryListenerWaitQueue = true;
-        NetworkTablesJNI.cancelPollEntryListener(m_entryListenerPoller);
-        while (m_entryListenerWaitQueue) {
-          try {
-            if (timeout < 0) {
-              m_entryListenerWaitQueueCond.await();
-            } else {
-              return m_entryListenerWaitQueueCond.await(
-                  (long) (timeout * 1e9), TimeUnit.NANOSECONDS);
-            }
-          } catch (InterruptedException ex) {
-            Thread.currentThread().interrupt();
-            return true;
-          }
-        }
-      }
-    } finally {
-      m_entryListenerLock.unlock();
-    }
-    return true;
-  }
-
-  private final ReentrantLock m_connectionListenerLock = new ReentrantLock();
-  private final Map<Integer, Consumer<ConnectionNotification>> m_connectionListeners =
-      new HashMap<>();
-  private int m_connectionListenerPoller;
-  private boolean m_connectionListenerWaitQueue;
-  private final Condition m_connectionListenerWaitQueueCond =
-      m_connectionListenerLock.newCondition();
-
-  @SuppressWarnings("PMD.AvoidCatchingThrowable")
-  private void startConnectionListenerThread() {
-    var connectionListenerThread =
-        new Thread(
-            () -> {
-              boolean wasInterrupted = false;
-              while (!Thread.interrupted()) {
-                ConnectionNotification[] events;
-                try {
-                  events =
-                      NetworkTablesJNI.pollConnectionListener(this, m_connectionListenerPoller);
-                } catch (InterruptedException ex) {
-                  m_connectionListenerLock.lock();
-                  try {
-                    if (m_connectionListenerWaitQueue) {
-                      m_connectionListenerWaitQueue = false;
-                      m_connectionListenerWaitQueueCond.signalAll();
-                      continue;
-                    }
-                  } finally {
-                    m_connectionListenerLock.unlock();
-                  }
-                  Thread.currentThread().interrupt();
-                  // don't try to destroy poller, as its handle is likely no longer valid
-                  wasInterrupted = true;
-                  break;
-                }
-                for (ConnectionNotification event : events) {
-                  Consumer<ConnectionNotification> listener;
-                  m_connectionListenerLock.lock();
-                  try {
-                    listener = m_connectionListeners.get(event.listener);
-                  } finally {
-                    m_connectionListenerLock.unlock();
-                  }
-                  if (listener != null) {
-                    try {
-                      listener.accept(event);
-                    } catch (Throwable throwable) {
-                      System.err.println(
-                          "Unhandled exception during connection listener callback: "
-                              + throwable.toString());
-                      throwable.printStackTrace();
-                    }
-                  }
-                }
-              }
-              m_connectionListenerLock.lock();
-              try {
-                if (!wasInterrupted) {
-                  NetworkTablesJNI.destroyConnectionListenerPoller(m_connectionListenerPoller);
-                }
-                m_connectionListenerPoller = 0;
-              } finally {
-                m_connectionListenerLock.unlock();
-              }
-            },
-            "NTConnectionListener");
-    connectionListenerThread.setDaemon(true);
-    connectionListenerThread.start();
-  }
-
-  /**
-   * Add a connection listener.
-   *
-   * @param listener Listener to add
-   * @param immediateNotify Notify listener of all existing connections
-   * @return Listener handle
-   */
-  public int addConnectionListener(
-      Consumer<ConnectionNotification> listener, boolean immediateNotify) {
-    m_connectionListenerLock.lock();
-    try {
-      if (m_connectionListenerPoller == 0) {
-        m_connectionListenerPoller = NetworkTablesJNI.createConnectionListenerPoller(m_handle);
-        startConnectionListenerThread();
-      }
-      int handle =
-          NetworkTablesJNI.addPolledConnectionListener(m_connectionListenerPoller, immediateNotify);
-      m_connectionListeners.put(handle, listener);
-      return handle;
-    } finally {
-      m_connectionListenerLock.unlock();
-    }
-  }
-
-  /**
-   * Remove a connection listener.
-   *
-   * @param listener Listener handle to remove
-   */
-  public void removeConnectionListener(int listener) {
-    m_connectionListenerLock.lock();
-    try {
-      m_connectionListeners.remove(listener);
-    } finally {
-      m_connectionListenerLock.unlock();
-    }
-    NetworkTablesJNI.removeConnectionListener(listener);
-  }
-
-  /**
-   * Wait for the connection listener queue to be empty. This is primarily useful for deterministic
-   * testing. This blocks until either the connection listener queue is empty (e.g. there are no
-   * more events that need to be passed along to callbacks or poll queues) or the timeout expires.
-   *
-   * @param timeout timeout, in seconds. Set to 0 for non-blocking behavior, or a negative value to
-   *     block indefinitely
-   * @return False if timed out, otherwise true.
-   */
-  public boolean waitForConnectionListenerQueue(double timeout) {
-    if (!NetworkTablesJNI.waitForConnectionListenerQueue(m_handle, timeout)) {
-      return false;
-    }
-    m_connectionListenerLock.lock();
-    try {
-      if (m_connectionListenerPoller != 0) {
-        m_connectionListenerWaitQueue = true;
-        NetworkTablesJNI.cancelPollConnectionListener(m_connectionListenerPoller);
-        while (m_connectionListenerWaitQueue) {
-          try {
-            if (timeout < 0) {
-              m_connectionListenerWaitQueueCond.await();
-            } else {
-              return m_connectionListenerWaitQueueCond.await(
-                  (long) (timeout * 1e9), TimeUnit.NANOSECONDS);
-            }
-          } catch (InterruptedException ex) {
-            Thread.currentThread().interrupt();
-            return true;
-          }
-        }
-      }
-    } finally {
-      m_connectionListenerLock.unlock();
-    }
-    return true;
-  }
-
-  /*
-   * Remote Procedure Call Functions
-   */
-
-  private final ReentrantLock m_rpcCallLock = new ReentrantLock();
-  private final Map<Integer, EntryConsumer<RpcAnswer>> m_rpcCalls = new HashMap<>();
-  private int m_rpcCallPoller;
-  private boolean m_rpcCallWaitQueue;
-  private final Condition m_rpcCallWaitQueueCond = m_rpcCallLock.newCondition();
-
-  @SuppressWarnings("PMD.AvoidCatchingThrowable")
-  private void startRpcCallThread() {
-    var rpcCallThread =
-        new Thread(
-            () -> {
-              boolean wasInterrupted = false;
-              while (!Thread.interrupted()) {
-                RpcAnswer[] events;
-                try {
-                  events = NetworkTablesJNI.pollRpc(this, m_rpcCallPoller);
-                } catch (InterruptedException ex) {
-                  m_rpcCallLock.lock();
-                  try {
-                    if (m_rpcCallWaitQueue) {
-                      m_rpcCallWaitQueue = false;
-                      m_rpcCallWaitQueueCond.signalAll();
-                      continue;
-                    }
-                  } finally {
-                    m_rpcCallLock.unlock();
-                  }
-                  Thread.currentThread().interrupt();
-                  // don't try to destroy poller, as its handle is likely no longer valid
-                  wasInterrupted = true;
-                  break;
-                }
-                for (RpcAnswer event : events) {
-                  EntryConsumer<RpcAnswer> listener;
-                  m_rpcCallLock.lock();
-                  try {
-                    listener = m_rpcCalls.get(event.entry);
-                  } finally {
-                    m_rpcCallLock.unlock();
-                  }
-                  if (listener != null) {
-                    event.m_entryObject = listener.m_entry;
-                    try {
-                      listener.m_consumer.accept(event);
-                    } catch (Throwable throwable) {
-                      System.err.println(
-                          "Unhandled exception during RPC callback: " + throwable.toString());
-                      throwable.printStackTrace();
-                    }
-                    event.finish();
-                  }
-                }
-              }
-              m_rpcCallLock.lock();
-              try {
-                if (!wasInterrupted) {
-                  NetworkTablesJNI.destroyRpcCallPoller(m_rpcCallPoller);
-                }
-                m_rpcCallPoller = 0;
-              } finally {
-                m_rpcCallLock.unlock();
-              }
-            },
-            "NTRpcCall");
-    rpcCallThread.setDaemon(true);
-    rpcCallThread.start();
-  }
-
-  private static final byte[] rev0def = new byte[] {0};
-
-  /**
-   * Create a callback-based RPC entry point. Only valid to use on the server. The callback function
-   * will be called when the RPC is called. This function creates RPC version 0 definitions (raw
-   * data in and out).
-   *
-   * @param entry the entry
-   * @param callback callback function
-   */
-  public void createRpc(NetworkTableEntry entry, Consumer<RpcAnswer> callback) {
-    m_rpcCallLock.lock();
-    try {
-      if (m_rpcCallPoller == 0) {
-        m_rpcCallPoller = NetworkTablesJNI.createRpcCallPoller(m_handle);
-        startRpcCallThread();
-      }
-      NetworkTablesJNI.createPolledRpc(entry.getHandle(), rev0def, m_rpcCallPoller);
-      m_rpcCalls.put(entry.getHandle(), new EntryConsumer<>(entry, callback));
-    } finally {
-      m_rpcCallLock.unlock();
-    }
-  }
-
-  /**
-   * Wait for the incoming RPC call queue to be empty. This is primarily useful for deterministic
-   * testing. This blocks until either the RPC call queue is empty (e.g. there are no more events
-   * that need to be passed along to callbacks or poll queues) or the timeout expires.
-   *
-   * @param timeout timeout, in seconds. Set to 0 for non-blocking behavior, or a negative value to
-   *     block indefinitely
-   * @return False if timed out, otherwise true.
-   */
-  public boolean waitForRpcCallQueue(double timeout) {
-    if (!NetworkTablesJNI.waitForRpcCallQueue(m_handle, timeout)) {
-      return false;
-    }
-    m_rpcCallLock.lock();
-    try {
-      if (m_rpcCallPoller != 0) {
-        m_rpcCallWaitQueue = true;
-        NetworkTablesJNI.cancelPollRpc(m_rpcCallPoller);
-        while (m_rpcCallWaitQueue) {
-          try {
-            if (timeout < 0) {
-              m_rpcCallWaitQueueCond.await();
-            } else {
-              return m_rpcCallWaitQueueCond.await((long) (timeout * 1e9), TimeUnit.NANOSECONDS);
-            }
-          } catch (InterruptedException ex) {
-            Thread.currentThread().interrupt();
-            return true;
-          }
-        }
-      }
-    } finally {
-      m_rpcCallLock.unlock();
-    }
-    return true;
-  }
-
-  /*
-   * Client/Server Functions
-   */
-
-  /**
-   * Set the network identity of this node. This is the name used during the initial connection
-   * handshake, and is visible through ConnectionInfo on the remote node.
-   *
-   * @param name identity to advertise
-   */
-  public void setNetworkIdentity(String name) {
-    NetworkTablesJNI.setNetworkIdentity(m_handle, name);
-  }
-
-  /**
-   * Get the current network mode.
-   *
-   * @return Bitmask of NetworkMode.
-   */
-  public int getNetworkMode() {
-    return NetworkTablesJNI.getNetworkMode(m_handle);
-  }
-
-  /**
-   * Starts local-only operation. Prevents calls to startServer or startClient from taking effect.
-   * Has no effect if startServer or startClient has already been called.
-   */
-  public void startLocal() {
-    NetworkTablesJNI.startLocal(m_handle);
-  }
-
-  /**
-   * Stops local-only operation. startServer or startClient can be called after this call to start a
-   * server or client.
-   */
-  public void stopLocal() {
-    NetworkTablesJNI.stopLocal(m_handle);
-  }
-
-  /**
-   * Starts a server using the networktables.ini as the persistent file, using the default listening
-   * address and port.
-   */
-  public void startServer() {
-    startServer("networktables.ini");
-  }
-
-  /**
-   * Starts a server using the specified persistent filename, using the default listening address
-   * and port.
-   *
-   * @param persistFilename the name of the persist file to use
-   */
-  public void startServer(String persistFilename) {
-    startServer(persistFilename, "");
-  }
-
-  /**
-   * Starts a server using the specified filename and listening address, using the default port.
-   *
-   * @param persistFilename the name of the persist file to use
-   * @param listenAddress the address to listen on, or empty to listen on any address
-   */
-  public void startServer(String persistFilename, String listenAddress) {
-    startServer(persistFilename, listenAddress, kDefaultPort);
-  }
-
-  /**
-   * Starts a server using the specified filename, listening address, and port.
-   *
-   * @param persistFilename the name of the persist file to use
-   * @param listenAddress the address to listen on, or empty to listen on any address
-   * @param port port to communicate over
-   */
-  public void startServer(String persistFilename, String listenAddress, int port) {
-    NetworkTablesJNI.startServer(m_handle, persistFilename, listenAddress, port);
-  }
-
-  /** Stops the server if it is running. */
-  public void stopServer() {
-    NetworkTablesJNI.stopServer(m_handle);
-  }
-
-  /** Starts a client. Use SetServer to set the server name and port. */
-  public void startClient() {
-    NetworkTablesJNI.startClient(m_handle);
-  }
-
-  /**
-   * Starts a client using the specified server and the default port.
-   *
-   * @param serverName server name
-   */
-  public void startClient(String serverName) {
-    startClient(serverName, kDefaultPort);
-  }
-
-  /**
-   * Starts a client using the specified server and port.
-   *
-   * @param serverName server name
-   * @param port port to communicate over
-   */
-  public void startClient(String serverName, int port) {
-    NetworkTablesJNI.startClient(m_handle, serverName, port);
-  }
-
-  /**
-   * Starts a client using the specified servers and default port. The client will attempt to
-   * connect to each server in round robin fashion.
-   *
-   * @param serverNames array of server names
-   */
-  public void startClient(String[] serverNames) {
-    startClient(serverNames, kDefaultPort);
-  }
-
-  /**
-   * Starts a client using the specified servers and port number. The client will attempt to connect
-   * to each server in round robin fashion.
-   *
-   * @param serverNames array of server names
-   * @param port port to communicate over
-   */
-  public void startClient(String[] serverNames, int port) {
-    int[] ports = new int[serverNames.length];
-    for (int i = 0; i < serverNames.length; i++) {
-      ports[i] = port;
-    }
-    startClient(serverNames, ports);
-  }
-
-  /**
-   * Starts a client using the specified (server, port) combinations. The client will attempt to
-   * connect to each server in round robin fashion.
-   *
-   * @param serverNames array of server names
-   * @param ports array of port numbers
-   */
-  public void startClient(String[] serverNames, int[] ports) {
-    NetworkTablesJNI.startClient(m_handle, serverNames, ports);
-  }
-
-  /**
-   * Starts a client using commonly known robot addresses for the specified team using the default
-   * port number.
-   *
-   * @param team team number
-   */
-  public void startClientTeam(int team) {
-    startClientTeam(team, kDefaultPort);
-  }
-
-  /**
-   * Starts a client using commonly known robot addresses for the specified team.
-   *
-   * @param team team number
-   * @param port port to communicate over
-   */
-  public void startClientTeam(int team, int port) {
-    NetworkTablesJNI.startClientTeam(m_handle, team, port);
-  }
-
-  /** Stops the client if it is running. */
-  public void stopClient() {
-    NetworkTablesJNI.stopClient(m_handle);
-  }
-
-  /**
-   * Sets server address and port for client (without restarting client). Changes the port to the
-   * default port.
-   *
-   * @param serverName server name
-   */
-  public void setServer(String serverName) {
-    setServer(serverName, kDefaultPort);
-  }
-
-  /**
-   * Sets server address and port for client (without restarting client).
-   *
-   * @param serverName server name
-   * @param port port to communicate over
-   */
-  public void setServer(String serverName, int port) {
-    NetworkTablesJNI.setServer(m_handle, serverName, port);
-  }
-
-  /**
-   * Sets server addresses and port for client (without restarting client). Changes the port to the
-   * default port. The client will attempt to connect to each server in round robin fashion.
-   *
-   * @param serverNames array of server names
-   */
-  public void setServer(String[] serverNames) {
-    setServer(serverNames, kDefaultPort);
-  }
-
-  /**
-   * Sets server addresses and port for client (without restarting client). The client will attempt
-   * to connect to each server in round robin fashion.
-   *
-   * @param serverNames array of server names
-   * @param port port to communicate over
-   */
-  public void setServer(String[] serverNames, int port) {
-    int[] ports = new int[serverNames.length];
-    for (int i = 0; i < serverNames.length; i++) {
-      ports[i] = port;
-    }
-    setServer(serverNames, ports);
-  }
-
-  /**
-   * Sets server addresses and ports for client (without restarting client). The client will attempt
-   * to connect to each server in round robin fashion.
-   *
-   * @param serverNames array of server names
-   * @param ports array of port numbers
-   */
-  public void setServer(String[] serverNames, int[] ports) {
-    NetworkTablesJNI.setServer(m_handle, serverNames, ports);
-  }
-
-  /**
-   * Sets server addresses and port for client (without restarting client). Changes the port to the
-   * default port. The client will attempt to connect to each server in round robin fashion.
-   *
-   * @param team team number
-   */
-  public void setServerTeam(int team) {
-    setServerTeam(team, kDefaultPort);
-  }
-
-  /**
-   * Sets server addresses and port for client (without restarting client). Connects using commonly
-   * known robot addresses for the specified team.
-   *
-   * @param team team number
-   * @param port port to communicate over
-   */
-  public void setServerTeam(int team, int port) {
-    NetworkTablesJNI.setServerTeam(m_handle, team, port);
-  }
-
-  /**
-   * Starts requesting server address from Driver Station. This connects to the Driver Station
-   * running on localhost to obtain the server IP address, and connects with the default port.
-   */
-  public void startDSClient() {
-    startDSClient(kDefaultPort);
-  }
-
-  /**
-   * Starts requesting server address from Driver Station. This connects to the Driver Station
-   * running on localhost to obtain the server IP address.
-   *
-   * @param port server port to use in combination with IP from DS
-   */
-  public void startDSClient(int port) {
-    NetworkTablesJNI.startDSClient(m_handle, port);
-  }
-
-  /** Stops requesting server address from Driver Station. */
-  public void stopDSClient() {
-    NetworkTablesJNI.stopDSClient(m_handle);
-  }
-
-  /**
-   * Set the periodic update rate. Sets how frequently updates are sent to other nodes over the
-   * network.
-   *
-   * @param interval update interval in seconds (range 0.01 to 1.0)
-   */
-  public void setUpdateRate(double interval) {
-    NetworkTablesJNI.setUpdateRate(m_handle, interval);
-  }
-
-  /**
-   * Flushes all updated values immediately to the network. Note: This is rate-limited to protect
-   * the network from flooding. This is primarily useful for synchronizing network updates with user
-   * code.
-   */
-  public void flush() {
-    NetworkTablesJNI.flush(m_handle);
-  }
-
-  /**
-   * Gets information on the currently established network connections. If operating as a client,
-   * this will return either zero or one values.
-   *
-   * @return array of connection information
-   */
-  public ConnectionInfo[] getConnections() {
-    return NetworkTablesJNI.getConnections(m_handle);
-  }
-
-  /**
-   * Return whether or not the instance is connected to another node.
-   *
-   * @return True if connected.
-   */
-  public boolean isConnected() {
-    return NetworkTablesJNI.isConnected(m_handle);
-  }
-
-  /**
-   * Saves persistent keys to a file. The server does this automatically.
-   *
-   * @param filename file name
-   * @throws PersistentException if error saving file
-   */
-  public void savePersistent(String filename) throws PersistentException {
-    NetworkTablesJNI.savePersistent(m_handle, filename);
-  }
-
-  /**
-   * Loads persistent keys from a file. The server does this automatically.
-   *
-   * @param filename file name
-   * @return List of warnings (errors result in an exception instead)
-   * @throws PersistentException if error reading file
-   */
-  public String[] loadPersistent(String filename) throws PersistentException {
-    return NetworkTablesJNI.loadPersistent(m_handle, filename);
-  }
-
-  /**
-   * Save table values to a file. The file format used is identical to that used for SavePersistent.
-   *
-   * @param filename filename
-   * @param prefix save only keys starting with this prefix
-   * @throws PersistentException if error saving file
-   */
-  public void saveEntries(String filename, String prefix) throws PersistentException {
-    NetworkTablesJNI.saveEntries(m_handle, filename, prefix);
-  }
-
-  /**
-   * Load table values from a file. The file format used is identical to that used for
-   * SavePersistent / LoadPersistent.
-   *
-   * @param filename filename
-   * @param prefix load only keys starting with this prefix
-   * @return List of warnings (errors result in an exception instead)
-   * @throws PersistentException if error saving file
-   */
-  public String[] loadEntries(String filename, String prefix) throws PersistentException {
-    return NetworkTablesJNI.loadEntries(m_handle, filename, prefix);
-  }
-
-  private final ReentrantLock m_loggerLock = new ReentrantLock();
-  private final Map<Integer, Consumer<LogMessage>> m_loggers = new HashMap<>();
-  private int m_loggerPoller;
-  private boolean m_loggerWaitQueue;
-  private final Condition m_loggerWaitQueueCond = m_loggerLock.newCondition();
-
-  @SuppressWarnings("PMD.AvoidCatchingThrowable")
-  private void startLogThread() {
-    var loggerThread =
-        new Thread(
-            () -> {
-              boolean wasInterrupted = false;
-              while (!Thread.interrupted()) {
-                LogMessage[] events;
-                try {
-                  events = NetworkTablesJNI.pollLogger(this, m_loggerPoller);
-                } catch (InterruptedException ex) {
-                  Thread.currentThread().interrupt();
-                  // don't try to destroy poller, as its handle is likely no longer valid
-                  wasInterrupted = true;
-                  break;
-                }
-                for (LogMessage event : events) {
-                  Consumer<LogMessage> logger;
-                  m_loggerLock.lock();
-                  try {
-                    logger = m_loggers.get(event.logger);
-                  } finally {
-                    m_loggerLock.unlock();
-                  }
-                  if (logger != null) {
-                    try {
-                      logger.accept(event);
-                    } catch (Throwable throwable) {
-                      System.err.println(
-                          "Unhandled exception during logger callback: " + throwable.toString());
-                      throwable.printStackTrace();
-                    }
-                  }
-                }
-              }
-              m_loggerLock.lock();
-              try {
-                if (!wasInterrupted) {
-                  NetworkTablesJNI.destroyLoggerPoller(m_loggerPoller);
-                }
-                m_rpcCallPoller = 0;
-              } finally {
-                m_loggerLock.unlock();
-              }
-            },
-            "NTLogger");
-    loggerThread.setDaemon(true);
-    loggerThread.start();
-  }
-
-  /**
-   * Add logger callback function. By default, log messages are sent to stderr; this function sends
-   * log messages with the specified levels to the provided callback function instead. The callback
-   * function will only be called for log messages with level greater than or equal to minLevel and
-   * less than or equal to maxLevel; messages outside this range will be silently ignored.
-   *
-   * @param func log callback function
-   * @param minLevel minimum log level
-   * @param maxLevel maximum log level
-   * @return Logger handle
-   */
-  public int addLogger(Consumer<LogMessage> func, int minLevel, int maxLevel) {
-    m_loggerLock.lock();
-    try {
-      if (m_loggerPoller == 0) {
-        m_loggerPoller = NetworkTablesJNI.createLoggerPoller(m_handle);
-        startLogThread();
-      }
-      int handle = NetworkTablesJNI.addPolledLogger(m_loggerPoller, minLevel, maxLevel);
-      m_loggers.put(handle, func);
-      return handle;
-    } finally {
-      m_loggerLock.unlock();
-    }
-  }
-
-  /**
-   * Remove a logger.
-   *
-   * @param logger Logger handle to remove
-   */
-  public void removeLogger(int logger) {
-    m_loggerLock.lock();
-    try {
-      m_loggers.remove(logger);
-    } finally {
-      m_loggerLock.unlock();
-    }
-    NetworkTablesJNI.removeLogger(logger);
-  }
-
-  /**
-   * Wait for the incoming log event queue to be empty. This is primarily useful for deterministic
-   * testing. This blocks until either the log event queue is empty (e.g. there are no more events
-   * that need to be passed along to callbacks or poll queues) or the timeout expires.
-   *
-   * @param timeout timeout, in seconds. Set to 0 for non-blocking behavior, or a negative value to
-   *     block indefinitely
-   * @return False if timed out, otherwise true.
-   */
-  public boolean waitForLoggerQueue(double timeout) {
-    if (!NetworkTablesJNI.waitForLoggerQueue(m_handle, timeout)) {
-      return false;
-    }
-    m_loggerLock.lock();
-    try {
-      if (m_loggerPoller != 0) {
-        m_loggerWaitQueue = true;
-        NetworkTablesJNI.cancelPollLogger(m_loggerPoller);
-        while (m_loggerWaitQueue) {
-          try {
-            if (timeout < 0) {
-              m_loggerWaitQueueCond.await();
-            } else {
-              return m_loggerWaitQueueCond.await((long) (timeout * 1e9), TimeUnit.NANOSECONDS);
-            }
-          } catch (InterruptedException ex) {
-            Thread.currentThread().interrupt();
-            return true;
-          }
-        }
-      }
-    } finally {
-      m_loggerLock.unlock();
-    }
-    return true;
-  }
-
-  @Override
-  public boolean equals(Object other) {
-    if (other == this) {
-      return true;
-    }
-    if (!(other instanceof NetworkTableInstance)) {
-      return false;
-    }
-
-    return m_handle == ((NetworkTableInstance) other).m_handle;
-  }
-
-  @Override
-  public int hashCode() {
-    return m_handle;
-  }
-
-  private boolean m_owned;
-  private final int m_handle;
-}
diff --git a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableListener.java b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableListener.java
new file mode 100644
index 0000000..2568738
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableListener.java
@@ -0,0 +1,189 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.networktables;
+
+import java.util.EnumSet;
+import java.util.function.Consumer;
+
+/**
+ * Event listener. This calls back to a callback function when an event matching the specified mask
+ * occurs. The callback function is called asynchronously on a separate thread, so it's important to
+ * use synchronization or atomics when accessing any shared state from the callback function.
+ */
+public final class NetworkTableListener implements AutoCloseable {
+  /**
+   * Create a listener for changes to topics with names that start with any of the given prefixes.
+   * This creates a corresponding internal subscriber with the lifetime of the listener.
+   *
+   * @param inst Instance
+   * @param prefixes Topic name string prefixes
+   * @param eventKinds set of event kinds to listen to
+   * @param listener Listener function
+   * @return Listener
+   */
+  public static NetworkTableListener createListener(
+      NetworkTableInstance inst,
+      String[] prefixes,
+      EnumSet<NetworkTableEvent.Kind> eventKinds,
+      Consumer<NetworkTableEvent> listener) {
+    return new NetworkTableListener(inst, inst.addListener(prefixes, eventKinds, listener));
+  }
+
+  /**
+   * Create a listener for changes on a particular topic. This creates a corresponding internal
+   * subscriber with the lifetime of the listener.
+   *
+   * @param topic Topic
+   * @param eventKinds set of event kinds to listen to
+   * @param listener Listener function
+   * @return Listener
+   */
+  public static NetworkTableListener createListener(
+      Topic topic,
+      EnumSet<NetworkTableEvent.Kind> eventKinds,
+      Consumer<NetworkTableEvent> listener) {
+    NetworkTableInstance inst = topic.getInstance();
+    return new NetworkTableListener(inst, inst.addListener(topic, eventKinds, listener));
+  }
+
+  /**
+   * Create a listener for topic changes on a subscriber. This does NOT keep the subscriber active.
+   *
+   * @param subscriber Subscriber
+   * @param eventKinds set of event kinds to listen to
+   * @param listener Listener function
+   * @return Listener
+   */
+  public static NetworkTableListener createListener(
+      Subscriber subscriber,
+      EnumSet<NetworkTableEvent.Kind> eventKinds,
+      Consumer<NetworkTableEvent> listener) {
+    NetworkTableInstance inst = subscriber.getTopic().getInstance();
+    return new NetworkTableListener(inst, inst.addListener(subscriber, eventKinds, listener));
+  }
+
+  /**
+   * Create a listener for topic changes on a subscriber. This does NOT keep the subscriber active.
+   *
+   * @param subscriber Subscriber
+   * @param eventKinds set of event kinds to listen to
+   * @param listener Listener function
+   * @return Listener
+   */
+  public static NetworkTableListener createListener(
+      MultiSubscriber subscriber,
+      EnumSet<NetworkTableEvent.Kind> eventKinds,
+      Consumer<NetworkTableEvent> listener) {
+    NetworkTableInstance inst = subscriber.getInstance();
+    return new NetworkTableListener(inst, inst.addListener(subscriber, eventKinds, listener));
+  }
+
+  /**
+   * Create a listener for topic changes on an entry.
+   *
+   * @param entry Entry
+   * @param eventKinds set of event kinds to listen to
+   * @param listener Listener function
+   * @return Listener
+   */
+  public static NetworkTableListener createListener(
+      NetworkTableEntry entry,
+      EnumSet<NetworkTableEvent.Kind> eventKinds,
+      Consumer<NetworkTableEvent> listener) {
+    NetworkTableInstance inst = entry.getInstance();
+    return new NetworkTableListener(inst, inst.addListener(entry, eventKinds, listener));
+  }
+
+  /**
+   * Create a connection listener.
+   *
+   * @param inst instance
+   * @param immediateNotify notify listener of all existing connections
+   * @param listener listener function
+   * @return Listener
+   */
+  public static NetworkTableListener createConnectionListener(
+      NetworkTableInstance inst, boolean immediateNotify, Consumer<NetworkTableEvent> listener) {
+    return new NetworkTableListener(inst, inst.addConnectionListener(immediateNotify, listener));
+  }
+
+  /**
+   * Create a time synchronization listener.
+   *
+   * @param inst instance
+   * @param immediateNotify notify listener of current time synchonization value
+   * @param listener listener function
+   * @return Listener
+   */
+  public static NetworkTableListener createTimeSyncListener(
+      NetworkTableInstance inst, boolean immediateNotify, Consumer<NetworkTableEvent> listener) {
+    return new NetworkTableListener(inst, inst.addTimeSyncListener(immediateNotify, listener));
+  }
+
+  /**
+   * Create a listener for log messages. By default, log messages are sent to stderr; this function
+   * sends log messages with the specified levels to the provided callback function instead. The
+   * callback function will only be called for log messages with level greater than or equal to
+   * minLevel and less than or equal to maxLevel; messages outside this range will be silently
+   * ignored.
+   *
+   * @param inst instance
+   * @param minLevel minimum log level
+   * @param maxLevel maximum log level
+   * @param listener listener function
+   * @return Listener
+   */
+  public static NetworkTableListener createLogger(
+      NetworkTableInstance inst, int minLevel, int maxLevel, Consumer<NetworkTableEvent> listener) {
+    return new NetworkTableListener(inst, inst.addLogger(minLevel, maxLevel, listener));
+  }
+
+  @Override
+  public synchronized void close() {
+    if (m_handle != 0) {
+      m_inst.removeListener(m_handle);
+      m_handle = 0;
+    }
+  }
+
+  /**
+   * Determines if the native handle is valid.
+   *
+   * @return True if the native handle is valid, false otherwise.
+   */
+  public boolean isValid() {
+    return m_handle != 0;
+  }
+
+  /**
+   * Gets the native handle.
+   *
+   * @return Native handle
+   */
+  public int getHandle() {
+    return m_handle;
+  }
+
+  /**
+   * Wait for the topic listener queue to be empty. This is primarily useful for deterministic
+   * testing. This blocks until either the topic listener queue is empty (e.g. there are no more
+   * events that need to be passed along to callbacks or poll queues) or the timeout expires.
+   *
+   * @param timeout timeout, in seconds. Set to 0 for non-blocking behavior, or a negative value to
+   *     block indefinitely
+   * @return False if timed out, otherwise true.
+   */
+  public boolean waitForQueue(double timeout) {
+    return m_inst.waitForListenerQueue(timeout);
+  }
+
+  private NetworkTableListener(NetworkTableInstance inst, int handle) {
+    m_inst = inst;
+    m_handle = handle;
+  }
+
+  private final NetworkTableInstance m_inst;
+  private int m_handle;
+}
diff --git a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableListenerPoller.java b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableListenerPoller.java
new file mode 100644
index 0000000..3a504f3
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableListenerPoller.java
@@ -0,0 +1,173 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.networktables;
+
+import java.util.EnumSet;
+
+/**
+ * Event listener poller. This queues events matching the specified mask. Code using the listener
+ * must periodically call readQueue() to read the events.
+ */
+public final class NetworkTableListenerPoller implements AutoCloseable {
+  /**
+   * Construct a topic listener poller.
+   *
+   * @param inst Instance
+   */
+  public NetworkTableListenerPoller(NetworkTableInstance inst) {
+    m_inst = inst;
+    m_handle = NetworkTablesJNI.createListenerPoller(inst.getHandle());
+  }
+
+  /**
+   * Start listening to topic changes for topics with names that start with any of the given
+   * prefixes. This creates a corresponding internal subscriber with the lifetime of the listener.
+   *
+   * @param prefixes Topic name string prefixes
+   * @param eventKinds set of event kinds to listen to
+   * @return Listener handle
+   */
+  public int addListener(String[] prefixes, EnumSet<NetworkTableEvent.Kind> eventKinds) {
+    return NetworkTablesJNI.addListener(m_handle, prefixes, eventKinds);
+  }
+
+  /**
+   * Start listening to changes to a particular topic. This creates a corresponding internal
+   * subscriber with the lifetime of the listener.
+   *
+   * @param topic Topic
+   * @param eventKinds set of event kinds to listen to
+   * @return Listener handle
+   */
+  public int addListener(Topic topic, EnumSet<NetworkTableEvent.Kind> eventKinds) {
+    return NetworkTablesJNI.addListener(m_handle, topic.getHandle(), eventKinds);
+  }
+
+  /**
+   * Start listening to topic changes on a subscriber. This does NOT keep the subscriber active.
+   *
+   * @param subscriber Subscriber
+   * @param eventKinds set of event kinds to listen to
+   * @return Listener handle
+   */
+  public int addListener(Subscriber subscriber, EnumSet<NetworkTableEvent.Kind> eventKinds) {
+    return NetworkTablesJNI.addListener(m_handle, subscriber.getHandle(), eventKinds);
+  }
+
+  /**
+   * Start listening to topic changes on a subscriber. This does NOT keep the subscriber active.
+   *
+   * @param subscriber Subscriber
+   * @param eventKinds set of event kinds to listen to
+   * @return Listener handle
+   */
+  public int addListener(MultiSubscriber subscriber, EnumSet<NetworkTableEvent.Kind> eventKinds) {
+    return NetworkTablesJNI.addListener(m_handle, subscriber.getHandle(), eventKinds);
+  }
+
+  /**
+   * Start listening to topic changes on an entry.
+   *
+   * @param entry Entry
+   * @param eventKinds set of event kinds to listen to
+   * @return Listener handle
+   */
+  public int addListener(NetworkTableEntry entry, EnumSet<NetworkTableEvent.Kind> eventKinds) {
+    return NetworkTablesJNI.addListener(m_handle, entry.getHandle(), eventKinds);
+  }
+
+  /**
+   * Add a connection listener. The callback function is called asynchronously on a separate thread,
+   * so it's important to use synchronization or atomics when accessing any shared state from the
+   * callback function.
+   *
+   * @param immediateNotify notify listener of all existing connections
+   * @return Listener handle
+   */
+  public int addConnectionListener(boolean immediateNotify) {
+    EnumSet<NetworkTableEvent.Kind> eventKinds = EnumSet.of(NetworkTableEvent.Kind.kConnection);
+    if (immediateNotify) {
+      eventKinds.add(NetworkTableEvent.Kind.kImmediate);
+    }
+    return NetworkTablesJNI.addListener(m_handle, m_inst.getHandle(), eventKinds);
+  }
+
+  /**
+   * Add a time synchronization listener. The callback function is called asynchronously on a
+   * separate thread, so it's important to use synchronization or atomics when accessing any shared
+   * state from the callback function.
+   *
+   * @param immediateNotify notify listener of current time synchronization value
+   * @return Listener handle
+   */
+  public int addTimeSyncListener(boolean immediateNotify) {
+    EnumSet<NetworkTableEvent.Kind> eventKinds = EnumSet.of(NetworkTableEvent.Kind.kTimeSync);
+    if (immediateNotify) {
+      eventKinds.add(NetworkTableEvent.Kind.kImmediate);
+    }
+    return NetworkTablesJNI.addListener(m_handle, m_inst.getHandle(), eventKinds);
+  }
+
+  /**
+   * Add logger callback function. By default, log messages are sent to stderr; this function sends
+   * log messages with the specified levels to the provided callback function instead. The callback
+   * function will only be called for log messages with level greater than or equal to minLevel and
+   * less than or equal to maxLevel; messages outside this range will be silently ignored.
+   *
+   * @param minLevel minimum log level
+   * @param maxLevel maximum log level
+   * @return Listener handle
+   */
+  public int addLogger(int minLevel, int maxLevel) {
+    return NetworkTablesJNI.addLogger(m_handle, minLevel, maxLevel);
+  }
+
+  /**
+   * Remove a listener.
+   *
+   * @param listener Listener handle
+   */
+  public void removeListener(int listener) {
+    NetworkTablesJNI.removeListener(listener);
+  }
+
+  /**
+   * Read topic notifications.
+   *
+   * @return Topic notifications since the previous call to readQueue()
+   */
+  public NetworkTableEvent[] readQueue() {
+    return NetworkTablesJNI.readListenerQueue(m_inst, m_handle);
+  }
+
+  @Override
+  public synchronized void close() {
+    if (m_handle != 0) {
+      NetworkTablesJNI.destroyListenerPoller(m_handle);
+    }
+    m_handle = 0;
+  }
+
+  /**
+   * Determines if the native handle is valid.
+   *
+   * @return True if the native handle is valid, false otherwise.
+   */
+  public boolean isValid() {
+    return m_handle != 0;
+  }
+
+  /**
+   * Gets the native handle.
+   *
+   * @return Handle
+   */
+  public int getHandle() {
+    return m_handle;
+  }
+
+  private final NetworkTableInstance m_inst;
+  private int m_handle;
+}
diff --git a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableType.java b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableType.java
index a173bb2..2350b49 100644
--- a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableType.java
+++ b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableType.java
@@ -6,24 +6,33 @@
 
 /** Network table data types. */
 public enum NetworkTableType {
-  kUnassigned(0),
-  kBoolean(0x01),
-  kDouble(0x02),
-  kString(0x04),
-  kRaw(0x08),
-  kBooleanArray(0x10),
-  kDoubleArray(0x20),
-  kStringArray(0x40),
-  kRpc(0x80);
+  kUnassigned(0, ""),
+  kBoolean(0x01, "boolean"),
+  kDouble(0x02, "double"),
+  kString(0x04, "string"),
+  kRaw(0x08, "raw"),
+  kBooleanArray(0x10, "boolean[]"),
+  kDoubleArray(0x20, "double[]"),
+  kStringArray(0x40, "string[]"),
+  kInteger(0x100, "int"),
+  kFloat(0x200, "float"),
+  kIntegerArray(0x400, "int[]"),
+  kFloatArray(0x800, "float[]");
 
-  private final int value;
+  private final int m_value;
+  private final String m_valueStr;
 
-  NetworkTableType(int value) {
-    this.value = value;
+  NetworkTableType(int value, String valueStr) {
+    m_value = value;
+    m_valueStr = valueStr;
   }
 
   public int getValue() {
-    return value;
+    return m_value;
+  }
+
+  public String getValueStr() {
+    return m_valueStr;
   }
 
   /**
@@ -48,10 +57,89 @@
         return kDoubleArray;
       case 0x40:
         return kStringArray;
-      case 0x80:
-        return kRpc;
+      case 0x100:
+        return kInteger;
+      case 0x200:
+        return kFloat;
+      case 0x400:
+        return kIntegerArray;
+      case 0x800:
+        return kFloatArray;
       default:
         return kUnassigned;
     }
   }
+
+  /**
+   * Convert from a type string to an enum type.
+   *
+   * @param typeString type string
+   * @return The kind
+   */
+  public static NetworkTableType getFromString(String typeString) {
+    switch (typeString) {
+      case "boolean":
+        return kBoolean;
+      case "double":
+        return kDouble;
+      case "float":
+        return kFloat;
+      case "int":
+        return kInteger;
+      case "string":
+      case "json":
+        return kString;
+      case "boolean[]":
+        return kBooleanArray;
+      case "double[]":
+        return kDoubleArray;
+      case "float[]":
+        return kFloatArray;
+      case "int[]":
+        return kIntegerArray;
+      case "string[]":
+        return kStringArray;
+      case "":
+        return kUnassigned;
+      default:
+        return kRaw;
+    }
+  }
+
+  /**
+   * Gets string from generic data value.
+   *
+   * @param data the data to check
+   * @return type string of the data, or empty string if no match
+   */
+  public static String getStringFromObject(Object data) {
+    if (data instanceof Boolean) {
+      return "boolean";
+    } else if (data instanceof Float) {
+      return "float";
+    } else if (data instanceof Long) {
+      // Checking Long because NT supports 64-bit integers
+      return "int";
+    } else if (data instanceof Double || data instanceof Number) {
+      // If typeof Number class, return "double" as the type. Functions as a "catch-all".
+      return "double";
+    } else if (data instanceof String) {
+      return "string";
+    } else if (data instanceof boolean[] || data instanceof Boolean[]) {
+      return "boolean[]";
+    } else if (data instanceof float[] || data instanceof Float[]) {
+      return "float[]";
+    } else if (data instanceof long[] || data instanceof Long[]) {
+      return "int[]";
+    } else if (data instanceof double[] || data instanceof Double[] || data instanceof Number[]) {
+      // If typeof Number class, return "double[]" as the type. Functions as a "catch-all".
+      return "double[]";
+    } else if (data instanceof String[]) {
+      return "string[]";
+    } else if (data instanceof byte[] || data instanceof Byte[]) {
+      return "raw";
+    } else {
+      return "";
+    }
+  }
 }
diff --git a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableValue.java b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableValue.java
deleted file mode 100644
index f4b9290..0000000
--- a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableValue.java
+++ /dev/null
@@ -1,522 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.networktables;
-
-import java.util.Objects;
-
-/** A network table entry value. */
-public final class NetworkTableValue {
-  NetworkTableValue(NetworkTableType type, Object value, long time) {
-    m_type = type;
-    m_value = value;
-    m_time = time;
-  }
-
-  NetworkTableValue(NetworkTableType type, Object value) {
-    this(type, value, NetworkTablesJNI.now());
-  }
-
-  NetworkTableValue(int type, Object value, long time) {
-    this(NetworkTableType.getFromInt(type), value, time);
-  }
-
-  /**
-   * Get the data type.
-   *
-   * @return The type.
-   */
-  public NetworkTableType getType() {
-    return m_type;
-  }
-
-  /**
-   * Get the data value stored.
-   *
-   * @return The type.
-   */
-  public Object getValue() {
-    return m_value;
-  }
-
-  /**
-   * Get the creation time of the value.
-   *
-   * @return The time, in the units returned by NetworkTablesJNI.now().
-   */
-  public long getTime() {
-    return m_time;
-  }
-
-  /*
-   * Type Checkers
-   */
-
-  /**
-   * Determine if entry value contains a value or is unassigned.
-   *
-   * @return True if the entry value contains a value.
-   */
-  public boolean isValid() {
-    return m_type != NetworkTableType.kUnassigned;
-  }
-
-  /**
-   * Determine if entry value contains a boolean.
-   *
-   * @return True if the entry value is of boolean type.
-   */
-  public boolean isBoolean() {
-    return m_type == NetworkTableType.kBoolean;
-  }
-
-  /**
-   * Determine if entry value contains a double.
-   *
-   * @return True if the entry value is of double type.
-   */
-  public boolean isDouble() {
-    return m_type == NetworkTableType.kDouble;
-  }
-
-  /**
-   * Determine if entry value contains a string.
-   *
-   * @return True if the entry value is of string type.
-   */
-  public boolean isString() {
-    return m_type == NetworkTableType.kString;
-  }
-
-  /**
-   * Determine if entry value contains a raw.
-   *
-   * @return True if the entry value is of raw type.
-   */
-  public boolean isRaw() {
-    return m_type == NetworkTableType.kRaw;
-  }
-
-  /**
-   * Determine if entry value contains a rpc definition.
-   *
-   * @return True if the entry value is of rpc definition type.
-   */
-  public boolean isRpc() {
-    return m_type == NetworkTableType.kRpc;
-  }
-
-  /**
-   * Determine if entry value contains a boolean array.
-   *
-   * @return True if the entry value is of boolean array type.
-   */
-  public boolean isBooleanArray() {
-    return m_type == NetworkTableType.kBooleanArray;
-  }
-
-  /**
-   * Determine if entry value contains a double array.
-   *
-   * @return True if the entry value is of double array type.
-   */
-  public boolean isDoubleArray() {
-    return m_type == NetworkTableType.kDoubleArray;
-  }
-
-  /**
-   * Determine if entry value contains a string array.
-   *
-   * @return True if the entry value is of string array type.
-   */
-  public boolean isStringArray() {
-    return m_type == NetworkTableType.kStringArray;
-  }
-
-  /*
-   * Type-Safe Getters
-   */
-
-  /**
-   * Get the entry's boolean value.
-   *
-   * @return The boolean value.
-   * @throws ClassCastException if the entry value is not of boolean type.
-   */
-  public boolean getBoolean() {
-    if (m_type != NetworkTableType.kBoolean) {
-      throw new ClassCastException("cannot convert " + m_type + " to boolean");
-    }
-    return (Boolean) m_value;
-  }
-
-  /**
-   * Get the entry's double value.
-   *
-   * @return The double value.
-   * @throws ClassCastException if the entry value is not of double type.
-   */
-  public double getDouble() {
-    if (m_type != NetworkTableType.kDouble) {
-      throw new ClassCastException("cannot convert " + m_type + " to double");
-    }
-    return ((Number) m_value).doubleValue();
-  }
-
-  /**
-   * Get the entry's string value.
-   *
-   * @return The string value.
-   * @throws ClassCastException if the entry value is not of string type.
-   */
-  public String getString() {
-    if (m_type != NetworkTableType.kString) {
-      throw new ClassCastException("cannot convert " + m_type + " to string");
-    }
-    return (String) m_value;
-  }
-
-  /**
-   * Get the entry's raw value.
-   *
-   * @return The raw value.
-   * @throws ClassCastException if the entry value is not of raw type.
-   */
-  @SuppressWarnings("PMD.MethodReturnsInternalArray")
-  public byte[] getRaw() {
-    if (m_type != NetworkTableType.kRaw) {
-      throw new ClassCastException("cannot convert " + m_type + " to raw");
-    }
-    return (byte[]) m_value;
-  }
-
-  /**
-   * Get the entry's rpc definition value.
-   *
-   * @return The rpc definition value.
-   * @throws ClassCastException if the entry value is not of rpc definition type.
-   */
-  @SuppressWarnings("PMD.MethodReturnsInternalArray")
-  public byte[] getRpc() {
-    if (m_type != NetworkTableType.kRpc) {
-      throw new ClassCastException("cannot convert " + m_type + " to rpc");
-    }
-    return (byte[]) m_value;
-  }
-
-  /**
-   * Get the entry's boolean array value.
-   *
-   * @return The boolean array value.
-   * @throws ClassCastException if the entry value is not of boolean array type.
-   */
-  @SuppressWarnings("PMD.MethodReturnsInternalArray")
-  public boolean[] getBooleanArray() {
-    if (m_type != NetworkTableType.kBooleanArray) {
-      throw new ClassCastException("cannot convert " + m_type + " to boolean array");
-    }
-    return (boolean[]) m_value;
-  }
-
-  /**
-   * Get the entry's double array value.
-   *
-   * @return The double array value.
-   * @throws ClassCastException if the entry value is not of double array type.
-   */
-  @SuppressWarnings("PMD.MethodReturnsInternalArray")
-  public double[] getDoubleArray() {
-    if (m_type != NetworkTableType.kDoubleArray) {
-      throw new ClassCastException("cannot convert " + m_type + " to double array");
-    }
-    return (double[]) m_value;
-  }
-
-  /**
-   * Get the entry's string array value.
-   *
-   * @return The string array value.
-   * @throws ClassCastException if the entry value is not of string array type.
-   */
-  @SuppressWarnings("PMD.MethodReturnsInternalArray")
-  public String[] getStringArray() {
-    if (m_type != NetworkTableType.kStringArray) {
-      throw new ClassCastException("cannot convert " + m_type + " to string array");
-    }
-    return (String[]) m_value;
-  }
-
-  /*
-   * Factory functions.
-   */
-
-  /**
-   * Creates a boolean entry value.
-   *
-   * @param value the value
-   * @return The entry value
-   */
-  public static NetworkTableValue makeBoolean(boolean value) {
-    return new NetworkTableValue(NetworkTableType.kBoolean, Boolean.valueOf(value));
-  }
-
-  /**
-   * Creates a boolean entry value.
-   *
-   * @param value the value
-   * @param time the creation time to use (instead of the current time)
-   * @return The entry value
-   */
-  public static NetworkTableValue makeBoolean(boolean value, long time) {
-    return new NetworkTableValue(NetworkTableType.kBoolean, Boolean.valueOf(value), time);
-  }
-
-  /**
-   * Creates a double entry value.
-   *
-   * @param value the value
-   * @return The entry value
-   */
-  public static NetworkTableValue makeDouble(double value) {
-    return new NetworkTableValue(NetworkTableType.kDouble, Double.valueOf(value));
-  }
-
-  /**
-   * Creates a double entry value.
-   *
-   * @param value the value
-   * @param time the creation time to use (instead of the current time)
-   * @return The entry value
-   */
-  public static NetworkTableValue makeDouble(double value, long time) {
-    return new NetworkTableValue(NetworkTableType.kDouble, Double.valueOf(value), time);
-  }
-
-  /**
-   * Creates a string entry value.
-   *
-   * @param value the value
-   * @return The entry value
-   */
-  public static NetworkTableValue makeString(String value) {
-    return new NetworkTableValue(NetworkTableType.kString, value);
-  }
-
-  /**
-   * Creates a string entry value.
-   *
-   * @param value the value
-   * @param time the creation time to use (instead of the current time)
-   * @return The entry value
-   */
-  public static NetworkTableValue makeString(String value, long time) {
-    return new NetworkTableValue(NetworkTableType.kString, value, time);
-  }
-
-  /**
-   * Creates a raw entry value.
-   *
-   * @param value the value
-   * @return The entry value
-   */
-  public static NetworkTableValue makeRaw(byte[] value) {
-    return new NetworkTableValue(NetworkTableType.kRaw, value);
-  }
-
-  /**
-   * Creates a raw entry value.
-   *
-   * @param value the value
-   * @param time the creation time to use (instead of the current time)
-   * @return The entry value
-   */
-  public static NetworkTableValue makeRaw(byte[] value, long time) {
-    return new NetworkTableValue(NetworkTableType.kRaw, value, time);
-  }
-
-  /**
-   * Creates a rpc entry value.
-   *
-   * @param value the value
-   * @return The entry value
-   */
-  public static NetworkTableValue makeRpc(byte[] value) {
-    return new NetworkTableValue(NetworkTableType.kRpc, value);
-  }
-
-  /**
-   * Creates a rpc entry value.
-   *
-   * @param value the value
-   * @param time the creation time to use (instead of the current time)
-   * @return The entry value
-   */
-  public static NetworkTableValue makeRpc(byte[] value, long time) {
-    return new NetworkTableValue(NetworkTableType.kRpc, value, time);
-  }
-
-  /**
-   * Creates a boolean array entry value.
-   *
-   * @param value the value
-   * @return The entry value
-   */
-  public static NetworkTableValue makeBooleanArray(boolean[] value) {
-    return new NetworkTableValue(NetworkTableType.kBooleanArray, value);
-  }
-
-  /**
-   * Creates a boolean array entry value.
-   *
-   * @param value the value
-   * @param time the creation time to use (instead of the current time)
-   * @return The entry value
-   */
-  public static NetworkTableValue makeBooleanArray(boolean[] value, long time) {
-    return new NetworkTableValue(NetworkTableType.kBooleanArray, value, time);
-  }
-
-  /**
-   * Creates a boolean array entry value.
-   *
-   * @param value the value
-   * @return The entry value
-   */
-  public static NetworkTableValue makeBooleanArray(Boolean[] value) {
-    return new NetworkTableValue(NetworkTableType.kBooleanArray, toNative(value));
-  }
-
-  /**
-   * Creates a boolean array entry value.
-   *
-   * @param value the value
-   * @param time the creation time to use (instead of the current time)
-   * @return The entry value
-   */
-  public static NetworkTableValue makeBooleanArray(Boolean[] value, long time) {
-    return new NetworkTableValue(NetworkTableType.kBooleanArray, toNative(value), time);
-  }
-
-  /**
-   * Creates a double array entry value.
-   *
-   * @param value the value
-   * @return The entry value
-   */
-  public static NetworkTableValue makeDoubleArray(double[] value) {
-    return new NetworkTableValue(NetworkTableType.kDoubleArray, value);
-  }
-
-  /**
-   * Creates a double array entry value.
-   *
-   * @param value the value
-   * @param time the creation time to use (instead of the current time)
-   * @return The entry value
-   */
-  public static NetworkTableValue makeDoubleArray(double[] value, long time) {
-    return new NetworkTableValue(NetworkTableType.kDoubleArray, value, time);
-  }
-
-  /**
-   * Creates a double array entry value.
-   *
-   * @param value the value
-   * @return The entry value
-   */
-  public static NetworkTableValue makeDoubleArray(Number[] value) {
-    return new NetworkTableValue(NetworkTableType.kDoubleArray, toNative(value));
-  }
-
-  /**
-   * Creates a double array entry value.
-   *
-   * @param value the value
-   * @param time the creation time to use (instead of the current time)
-   * @return The entry value
-   */
-  public static NetworkTableValue makeDoubleArray(Number[] value, long time) {
-    return new NetworkTableValue(NetworkTableType.kDoubleArray, toNative(value), time);
-  }
-
-  /**
-   * Creates a string array entry value.
-   *
-   * @param value the value
-   * @return The entry value
-   */
-  public static NetworkTableValue makeStringArray(String[] value) {
-    return new NetworkTableValue(NetworkTableType.kStringArray, value);
-  }
-
-  /**
-   * Creates a string array entry value.
-   *
-   * @param value the value
-   * @param time the creation time to use (instead of the current time)
-   * @return The entry value
-   */
-  public static NetworkTableValue makeStringArray(String[] value, long time) {
-    return new NetworkTableValue(NetworkTableType.kStringArray, value, time);
-  }
-
-  @Override
-  public boolean equals(Object other) {
-    if (other == this) {
-      return true;
-    }
-    if (!(other instanceof NetworkTableValue)) {
-      return false;
-    }
-    NetworkTableValue ntOther = (NetworkTableValue) other;
-    return m_type == ntOther.m_type && m_value.equals(ntOther.m_value);
-  }
-
-  @Override
-  public int hashCode() {
-    return Objects.hash(m_type, m_value);
-  }
-
-  // arraycopy() doesn't know how to unwrap boxed values; this is a false positive in PMD
-  // (see https://sourceforge.net/p/pmd/bugs/804/)
-  @SuppressWarnings("PMD.AvoidArrayLoops")
-  static boolean[] toNative(Boolean[] arr) {
-    boolean[] out = new boolean[arr.length];
-    for (int i = 0; i < arr.length; i++) {
-      out[i] = arr[i];
-    }
-    return out;
-  }
-
-  @SuppressWarnings("PMD.AvoidArrayLoops")
-  static double[] toNative(Number[] arr) {
-    double[] out = new double[arr.length];
-    for (int i = 0; i < arr.length; i++) {
-      out[i] = arr[i].doubleValue();
-    }
-    return out;
-  }
-
-  @SuppressWarnings("PMD.AvoidArrayLoops")
-  static Boolean[] fromNative(boolean[] arr) {
-    Boolean[] out = new Boolean[arr.length];
-    for (int i = 0; i < arr.length; i++) {
-      out[i] = arr[i];
-    }
-    return out;
-  }
-
-  @SuppressWarnings("PMD.AvoidArrayLoops")
-  static Double[] fromNative(double[] arr) {
-    Double[] out = new Double[arr.length];
-    for (int i = 0; i < arr.length; i++) {
-      out[i] = arr[i];
-    }
-    return out;
-  }
-
-  private NetworkTableType m_type;
-  private Object m_value;
-  private long m_time;
-}
diff --git a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTablesJNI.java b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTablesJNI.java
deleted file mode 100644
index 8c4916f..0000000
--- a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTablesJNI.java
+++ /dev/null
@@ -1,275 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.networktables;
-
-import edu.wpi.first.util.RuntimeLoader;
-import java.io.IOException;
-import java.nio.ByteBuffer;
-import java.util.concurrent.atomic.AtomicBoolean;
-
-public final class NetworkTablesJNI {
-  static boolean libraryLoaded = false;
-  static RuntimeLoader<NetworkTablesJNI> loader = null;
-
-  public static class Helper {
-    private static AtomicBoolean extractOnStaticLoad = new AtomicBoolean(true);
-
-    public static boolean getExtractOnStaticLoad() {
-      return extractOnStaticLoad.get();
-    }
-
-    public static void setExtractOnStaticLoad(boolean load) {
-      extractOnStaticLoad.set(load);
-    }
-  }
-
-  static {
-    if (Helper.getExtractOnStaticLoad()) {
-      try {
-        loader =
-            new RuntimeLoader<>(
-                "ntcorejni", RuntimeLoader.getDefaultExtractionRoot(), NetworkTablesJNI.class);
-        loader.loadLibrary();
-      } catch (IOException ex) {
-        ex.printStackTrace();
-        System.exit(1);
-      }
-      libraryLoaded = true;
-    }
-  }
-
-  /**
-   * Force load the library.
-   *
-   * @throws IOException if the library fails to load
-   */
-  public static synchronized void forceLoad() throws IOException {
-    if (libraryLoaded) {
-      return;
-    }
-    loader =
-        new RuntimeLoader<>(
-            "ntcorejni", RuntimeLoader.getDefaultExtractionRoot(), NetworkTablesJNI.class);
-    loader.loadLibrary();
-    libraryLoaded = true;
-  }
-
-  public static native int getDefaultInstance();
-
-  public static native int createInstance();
-
-  public static native void destroyInstance(int inst);
-
-  public static native int getInstanceFromHandle(int handle);
-
-  public static native int getEntry(int inst, String key);
-
-  public static native int[] getEntries(int inst, String prefix, int types);
-
-  public static native String getEntryName(int entry);
-
-  public static native long getEntryLastChange(int entry);
-
-  public static native int getType(int entry);
-
-  public static native boolean setBoolean(int entry, long time, boolean value, boolean force);
-
-  public static native boolean setDouble(int entry, long time, double value, boolean force);
-
-  public static native boolean setString(int entry, long time, String value, boolean force);
-
-  public static native boolean setRaw(int entry, long time, byte[] value, boolean force);
-
-  public static native boolean setRaw(
-      int entry, long time, ByteBuffer value, int len, boolean force);
-
-  public static native boolean setBooleanArray(
-      int entry, long time, boolean[] value, boolean force);
-
-  public static native boolean setDoubleArray(int entry, long time, double[] value, boolean force);
-
-  public static native boolean setStringArray(int entry, long time, String[] value, boolean force);
-
-  public static native NetworkTableValue getValue(int entry);
-
-  public static native boolean getBoolean(int entry, boolean defaultValue);
-
-  public static native double getDouble(int entry, double defaultValue);
-
-  public static native String getString(int entry, String defaultValue);
-
-  public static native byte[] getRaw(int entry, byte[] defaultValue);
-
-  public static native boolean[] getBooleanArray(int entry, boolean[] defaultValue);
-
-  public static native double[] getDoubleArray(int entry, double[] defaultValue);
-
-  public static native String[] getStringArray(int entry, String[] defaultValue);
-
-  public static native boolean setDefaultBoolean(int entry, long time, boolean defaultValue);
-
-  public static native boolean setDefaultDouble(int entry, long time, double defaultValue);
-
-  public static native boolean setDefaultString(int entry, long time, String defaultValue);
-
-  public static native boolean setDefaultRaw(int entry, long time, byte[] defaultValue);
-
-  public static native boolean setDefaultBooleanArray(int entry, long time, boolean[] defaultValue);
-
-  public static native boolean setDefaultDoubleArray(int entry, long time, double[] defaultValue);
-
-  public static native boolean setDefaultStringArray(int entry, long time, String[] defaultValue);
-
-  public static native void setEntryFlags(int entry, int flags);
-
-  public static native int getEntryFlags(int entry);
-
-  public static native void deleteEntry(int entry);
-
-  public static native void deleteAllEntries(int inst);
-
-  public static native EntryInfo getEntryInfoHandle(NetworkTableInstance inst, int entry);
-
-  public static native EntryInfo[] getEntryInfo(
-      NetworkTableInstance instObject, int inst, String prefix, int types);
-
-  public static native int createEntryListenerPoller(int inst);
-
-  public static native void destroyEntryListenerPoller(int poller);
-
-  public static native int addPolledEntryListener(int poller, String prefix, int flags);
-
-  public static native int addPolledEntryListener(int poller, int entry, int flags);
-
-  public static native EntryNotification[] pollEntryListener(NetworkTableInstance inst, int poller)
-      throws InterruptedException;
-
-  public static native EntryNotification[] pollEntryListenerTimeout(
-      NetworkTableInstance inst, int poller, double timeout) throws InterruptedException;
-
-  public static native void cancelPollEntryListener(int poller);
-
-  public static native void removeEntryListener(int entryListener);
-
-  public static native boolean waitForEntryListenerQueue(int inst, double timeout);
-
-  public static native int createConnectionListenerPoller(int inst);
-
-  public static native void destroyConnectionListenerPoller(int poller);
-
-  public static native int addPolledConnectionListener(int poller, boolean immediateNotify);
-
-  public static native ConnectionNotification[] pollConnectionListener(
-      NetworkTableInstance inst, int poller) throws InterruptedException;
-
-  public static native ConnectionNotification[] pollConnectionListenerTimeout(
-      NetworkTableInstance inst, int poller, double timeout) throws InterruptedException;
-
-  public static native void cancelPollConnectionListener(int poller);
-
-  public static native void removeConnectionListener(int connListener);
-
-  public static native boolean waitForConnectionListenerQueue(int inst, double timeout);
-
-  public static native int createRpcCallPoller(int inst);
-
-  public static native void destroyRpcCallPoller(int poller);
-
-  public static native void createPolledRpc(int entry, byte[] def, int poller);
-
-  public static native RpcAnswer[] pollRpc(NetworkTableInstance inst, int poller)
-      throws InterruptedException;
-
-  public static native RpcAnswer[] pollRpcTimeout(
-      NetworkTableInstance inst, int poller, double timeout) throws InterruptedException;
-
-  public static native void cancelPollRpc(int poller);
-
-  public static native boolean waitForRpcCallQueue(int inst, double timeout);
-
-  public static native boolean postRpcResponse(int entry, int call, byte[] result);
-
-  public static native int callRpc(int entry, byte[] params);
-
-  public static native byte[] getRpcResult(int entry, int call);
-
-  public static native byte[] getRpcResult(int entry, int call, double timeout);
-
-  public static native void cancelRpcResult(int entry, int call);
-
-  public static native byte[] getRpc(int entry, byte[] defaultValue);
-
-  public static native void setNetworkIdentity(int inst, String name);
-
-  public static native int getNetworkMode(int inst);
-
-  public static native void startLocal(int inst);
-
-  public static native void stopLocal(int inst);
-
-  public static native void startServer(
-      int inst, String persistFilename, String listenAddress, int port);
-
-  public static native void stopServer(int inst);
-
-  public static native void startClient(int inst);
-
-  public static native void startClient(int inst, String serverName, int port);
-
-  public static native void startClient(int inst, String[] serverNames, int[] ports);
-
-  public static native void startClientTeam(int inst, int team, int port);
-
-  public static native void stopClient(int inst);
-
-  public static native void setServer(int inst, String serverName, int port);
-
-  public static native void setServer(int inst, String[] serverNames, int[] ports);
-
-  public static native void setServerTeam(int inst, int team, int port);
-
-  public static native void startDSClient(int inst, int port);
-
-  public static native void stopDSClient(int inst);
-
-  public static native void setUpdateRate(int inst, double interval);
-
-  public static native void flush(int inst);
-
-  public static native ConnectionInfo[] getConnections(int inst);
-
-  public static native boolean isConnected(int inst);
-
-  public static native void savePersistent(int inst, String filename) throws PersistentException;
-
-  public static native String[] loadPersistent(int inst, String filename)
-      throws PersistentException; // returns warnings
-
-  public static native void saveEntries(int inst, String filename, String prefix)
-      throws PersistentException;
-
-  public static native String[] loadEntries(int inst, String filename, String prefix)
-      throws PersistentException; // returns warnings
-
-  public static native long now();
-
-  public static native int createLoggerPoller(int inst);
-
-  public static native void destroyLoggerPoller(int poller);
-
-  public static native int addPolledLogger(int poller, int minLevel, int maxLevel);
-
-  public static native LogMessage[] pollLogger(NetworkTableInstance inst, int poller)
-      throws InterruptedException;
-
-  public static native LogMessage[] pollLoggerTimeout(
-      NetworkTableInstance inst, int poller, double timeout) throws InterruptedException;
-
-  public static native void cancelPollLogger(int poller);
-
-  public static native void removeLogger(int logger);
-
-  public static native boolean waitForLoggerQueue(int inst, double timeout);
-}
diff --git a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/PersistentException.java b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/PersistentException.java
deleted file mode 100644
index 1c61595..0000000
--- a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/PersistentException.java
+++ /dev/null
@@ -1,16 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.networktables;
-
-import java.io.IOException;
-
-/** An exception thrown when persistent load/save fails in a {@link NetworkTable}. */
-public final class PersistentException extends IOException {
-  public static final long serialVersionUID = 0;
-
-  public PersistentException(String message) {
-    super(message);
-  }
-}
diff --git a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/PubSub.java b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/PubSub.java
new file mode 100644
index 0000000..7beaf9e
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/PubSub.java
@@ -0,0 +1,32 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.networktables;
+
+/** NetworkTables publisher or subscriber. */
+public interface PubSub extends AutoCloseable {
+  @Override
+  void close();
+
+  /**
+   * Gets the subscribed-to / published-to topic.
+   *
+   * @return Topic
+   */
+  Topic getTopic();
+
+  /**
+   * Determines if the native handle is valid.
+   *
+   * @return True if the native handle is valid, false otherwise.
+   */
+  boolean isValid();
+
+  /**
+   * Gets the native handle.
+   *
+   * @return Handle
+   */
+  int getHandle();
+}
diff --git a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/PubSubOption.java b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/PubSubOption.java
new file mode 100644
index 0000000..dd96eec
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/PubSubOption.java
@@ -0,0 +1,156 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.networktables;
+
+/** NetworkTables publish/subscribe option. */
+public class PubSubOption {
+  enum Kind {
+    periodic,
+    sendAll,
+    topicsOnly,
+    pollStorage,
+    keepDuplicates,
+    disableRemote,
+    disableLocal,
+    excludePublisher,
+    excludeSelf
+  }
+
+  PubSubOption(Kind kind, boolean value) {
+    m_kind = kind;
+    m_bValue = value;
+    m_iValue = 0;
+    m_dValue = 0;
+  }
+
+  PubSubOption(Kind kind, int value) {
+    m_kind = kind;
+    m_bValue = false;
+    m_iValue = value;
+    m_dValue = 0;
+  }
+
+  PubSubOption(Kind kind, double value) {
+    m_kind = kind;
+    m_bValue = false;
+    m_iValue = 0;
+    m_dValue = value;
+  }
+
+  /**
+   * How frequently changes will be sent over the network. NetworkTables may send more frequently
+   * than this (e.g. use a combined minimum period for all values) or apply a restricted range to
+   * this value. The default if unspecified is 100 ms.
+   *
+   * @param period time between updates, in seconds
+   * @return option
+   */
+  public static PubSubOption periodic(double period) {
+    return new PubSubOption(Kind.periodic, period);
+  }
+
+  /**
+   * If enabled, sends all value changes over the network. This option defaults to disabled.
+   *
+   * @param enabled True to enable, false to disable
+   * @return option
+   */
+  public static PubSubOption sendAll(boolean enabled) {
+    return new PubSubOption(Kind.sendAll, enabled);
+  }
+
+  /**
+   * If enabled on a subscription, does not request value changes. This option defaults to disabled.
+   *
+   * @param enabled True to enable, false to disable
+   * @return option
+   */
+  public static PubSubOption topicsOnly(boolean enabled) {
+    return new PubSubOption(Kind.topicsOnly, enabled);
+  }
+
+  /**
+   * If enabled, preserves duplicate value changes (rather than ignoring them). This option defaults
+   * to disabled.
+   *
+   * @param enabled True to enable, false to disable
+   * @return option
+   */
+  public static PubSubOption keepDuplicates(boolean enabled) {
+    return new PubSubOption(Kind.keepDuplicates, enabled);
+  }
+
+  /**
+   * Polling storage for subscription. Specifies the maximum number of updates NetworkTables should
+   * store between calls to the subscriber's readQueue() function. Defaults to 1 if sendAll is
+   * false, 20 if sendAll is true.
+   *
+   * @param depth number of entries to save for polling.
+   * @return option
+   */
+  public static PubSubOption pollStorage(int depth) {
+    return new PubSubOption(Kind.pollStorage, depth);
+  }
+
+  /**
+   * For subscriptions, specify whether remote value updates should not be queued for readQueue().
+   * See also disableLocal(). Defaults to false (remote value updates are queued).
+   *
+   * @param disabled True to disable, false to enable
+   * @return option
+   */
+  public static PubSubOption disableRemote(boolean disabled) {
+    return new PubSubOption(Kind.disableRemote, disabled);
+  }
+
+  /**
+   * For subscriptions, specify whether local value updates should not be queued for readQueue().
+   * See also disableRemote(). Defaults to false (local value updates are queued).
+   *
+   * @param disabled True to disable, false to enable
+   * @return option
+   */
+  public static PubSubOption disableLocal(boolean disabled) {
+    return new PubSubOption(Kind.disableLocal, disabled);
+  }
+
+  /**
+   * Don't queue value updates for the given publisher. Only has an effect on subscriptions. Only
+   * one exclusion may be set.
+   *
+   * @param publisher publisher handle to exclude
+   * @return option
+   */
+  public static PubSubOption excludePublisher(int publisher) {
+    return new PubSubOption(Kind.excludePublisher, publisher);
+  }
+
+  /**
+   * Don't queue value updates for the given publisher. Only has an effect on subscriptions. Only
+   * one exclusion may be set.
+   *
+   * @param publisher publisher to exclude
+   * @return option
+   */
+  public static PubSubOption excludePublisher(Publisher publisher) {
+    return excludePublisher(publisher != null ? publisher.getHandle() : 0);
+  }
+
+  /**
+   * Don't queue value updates for the internal publisher for an entry. Only has an effect on
+   * entries.
+   *
+   * @param enabled True to enable, false to disable
+   * @return option
+   */
+  public static PubSubOption excludeSelf(boolean enabled) {
+    return new PubSubOption(Kind.excludeSelf, enabled);
+  }
+
+  final Kind m_kind;
+  final boolean m_bValue;
+  final int m_iValue;
+  final double m_dValue;
+}
diff --git a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/PubSubOptions.java b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/PubSubOptions.java
new file mode 100644
index 0000000..18557b9
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/PubSubOptions.java
@@ -0,0 +1,126 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.networktables;
+
+/** NetworkTables publish/subscribe options. */
+@SuppressWarnings("MemberName")
+public class PubSubOptions {
+  /**
+   * Construct from a list of options.
+   *
+   * @param options options
+   */
+  public PubSubOptions(PubSubOption... options) {
+    for (PubSubOption option : options) {
+      switch (option.m_kind) {
+        case periodic:
+          periodic = option.m_dValue;
+          break;
+        case sendAll:
+          sendAll = option.m_bValue;
+          break;
+        case topicsOnly:
+          topicsOnly = option.m_bValue;
+          break;
+        case pollStorage:
+          pollStorage = option.m_iValue;
+          break;
+        case keepDuplicates:
+          keepDuplicates = option.m_bValue;
+          break;
+        case disableRemote:
+          disableRemote = option.m_bValue;
+          break;
+        case disableLocal:
+          disableLocal = option.m_bValue;
+          break;
+        case excludePublisher:
+          excludePublisher = option.m_iValue;
+          break;
+        case excludeSelf:
+          excludeSelf = option.m_bValue;
+          break;
+        default:
+          break;
+      }
+    }
+  }
+
+  PubSubOptions(
+      int pollStorage,
+      double periodic,
+      int excludePublisher,
+      boolean sendAll,
+      boolean topicsOnly,
+      boolean keepDuplicates,
+      boolean prefixMatch,
+      boolean disableRemote,
+      boolean disableLocal,
+      boolean excludeSelf) {
+    this.pollStorage = pollStorage;
+    this.periodic = periodic;
+    this.excludePublisher = excludePublisher;
+    this.sendAll = sendAll;
+    this.topicsOnly = topicsOnly;
+    this.keepDuplicates = keepDuplicates;
+    this.prefixMatch = prefixMatch;
+    this.disableRemote = disableRemote;
+    this.disableLocal = disableLocal;
+    this.excludeSelf = excludeSelf;
+  }
+
+  /** Default value of periodic. */
+  public static final double kDefaultPeriodic = 0.1;
+
+  /**
+   * Polling storage size for a subscription. Specifies the maximum number of updates NetworkTables
+   * should store between calls to the subscriber's readQueue() function. If zero, defaults to 1 if
+   * sendAll is false, 20 if sendAll is true.
+   */
+  public int pollStorage;
+
+  /**
+   * How frequently changes will be sent over the network, in seconds. NetworkTables may send more
+   * frequently than this (e.g. use a combined minimum period for all values) or apply a restricted
+   * range to this value. The default is 100 ms.
+   */
+  public double periodic = kDefaultPeriodic;
+
+  /**
+   * For subscriptions, if non-zero, value updates for readQueue() are not queued for this
+   * publisher.
+   */
+  public int excludePublisher;
+
+  /** Send all value changes over the network. */
+  public boolean sendAll;
+
+  /** For subscriptions, don't ask for value changes (only topic announcements). */
+  public boolean topicsOnly;
+
+  /** Preserve duplicate value changes (rather than ignoring them). */
+  public boolean keepDuplicates;
+
+  /**
+   * Perform prefix match on subscriber topic names. Is ignored/overridden by subscribe() functions;
+   * only present in struct for the purposes of getting information about subscriptions.
+   */
+  public boolean prefixMatch;
+
+  /**
+   * For subscriptions, if remote value updates should not be queued for readQueue(). See also
+   * disableLocal.
+   */
+  public boolean disableRemote;
+
+  /**
+   * For subscriptions, if local value updates should not be queued for readQueue(). See also
+   * disableRemote.
+   */
+  public boolean disableLocal;
+
+  /** For entries, don't queue (for readQueue) value updates for the entry's internal publisher. */
+  public boolean excludeSelf;
+}
diff --git a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/Publisher.java b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/Publisher.java
new file mode 100644
index 0000000..616c7ab
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/Publisher.java
@@ -0,0 +1,8 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.networktables;
+
+/** NetworkTables publisher. */
+public interface Publisher extends PubSub {}
diff --git a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/RpcAnswer.java b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/RpcAnswer.java
deleted file mode 100644
index a244bde..0000000
--- a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/RpcAnswer.java
+++ /dev/null
@@ -1,106 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.networktables;
-
-/** NetworkTables Remote Procedure Call (Server Side). */
-public final class RpcAnswer {
-  /** Entry handle. */
-  @SuppressWarnings("MemberName")
-  public final int entry;
-
-  /** Call handle. */
-  @SuppressWarnings("MemberName")
-  public int call;
-
-  /** Entry name. */
-  @SuppressWarnings("MemberName")
-  public final String name;
-
-  /** Call raw parameters. */
-  @SuppressWarnings("MemberName")
-  public final byte[] params;
-
-  /** Connection that called the RPC. */
-  @SuppressWarnings("MemberName")
-  public final ConnectionInfo conn;
-
-  /**
-   * Constructor. This should generally only be used internally to NetworkTables.
-   *
-   * @param inst Instance
-   * @param entry Entry handle
-   * @param call Call handle
-   * @param name Entry name
-   * @param params Call raw parameters
-   * @param conn Connection info
-   */
-  @SuppressWarnings("PMD.ArrayIsStoredDirectly")
-  public RpcAnswer(
-      NetworkTableInstance inst,
-      int entry,
-      int call,
-      String name,
-      byte[] params,
-      ConnectionInfo conn) {
-    this.m_inst = inst;
-    this.entry = entry;
-    this.call = call;
-    this.name = name;
-    this.params = params;
-    this.conn = conn;
-  }
-
-  static final byte[] emptyResponse = new byte[] {};
-
-  /*
-   * Finishes an RPC answer by replying empty if the user did not respond.
-   * Called internally by the callback thread.
-   */
-  void finish() {
-    if (call != 0) {
-      NetworkTablesJNI.postRpcResponse(entry, call, emptyResponse);
-      call = 0;
-    }
-  }
-
-  /**
-   * Determines if the native handle is valid.
-   *
-   * @return True if the native handle is valid, false otherwise.
-   */
-  public boolean isValid() {
-    return call != 0;
-  }
-
-  /**
-   * Post RPC response (return value) for a polled RPC.
-   *
-   * @param result result raw data that will be provided to remote caller
-   * @return true if the response was posted, otherwise false
-   */
-  public boolean postResponse(byte[] result) {
-    boolean ret = NetworkTablesJNI.postRpcResponse(entry, call, result);
-    call = 0;
-    return ret;
-  }
-
-  /* Network table instance. */
-  private final NetworkTableInstance m_inst;
-
-  /* Cached entry object. */
-  NetworkTableEntry m_entryObject;
-
-  /**
-   * Get the entry as an object.
-   *
-   * @return NetworkTableEntry for the RPC.
-   */
-  NetworkTableEntry getEntry() {
-    if (m_entryObject == null) {
-      m_entryObject = new NetworkTableEntry(m_inst, entry);
-    }
-    return m_entryObject;
-  }
-}
diff --git a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/RpcCall.java b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/RpcCall.java
deleted file mode 100644
index 790ff5f..0000000
--- a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/RpcCall.java
+++ /dev/null
@@ -1,90 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.networktables;
-
-/** NetworkTables Remote Procedure Call. */
-public final class RpcCall implements AutoCloseable {
-  /**
-   * Constructor. This should generally only be used internally to NetworkTables.
-   *
-   * @param entry Entry
-   * @param call Call handle
-   */
-  public RpcCall(NetworkTableEntry entry, int call) {
-    m_entry = entry;
-    m_call = call;
-  }
-
-  /** Cancels the result if no other action taken. */
-  @Override
-  public synchronized void close() {
-    if (m_call != 0) {
-      cancelResult();
-    }
-  }
-
-  /**
-   * Determines if the native handle is valid.
-   *
-   * @return True if the native handle is valid, false otherwise.
-   */
-  public boolean isValid() {
-    return m_call != 0;
-  }
-
-  /**
-   * Get the RPC entry.
-   *
-   * @return NetworkTableEntry for the RPC.
-   */
-  public NetworkTableEntry getEntry() {
-    return m_entry;
-  }
-
-  /**
-   * Get the call native handle.
-   *
-   * @return Native handle.
-   */
-  public int getCall() {
-    return m_call;
-  }
-
-  /**
-   * Get the result (return value). This function blocks until the result is received.
-   *
-   * @return Received result (output)
-   */
-  public byte[] getResult() {
-    byte[] result = NetworkTablesJNI.getRpcResult(m_entry.getHandle(), m_call);
-    if (result.length != 0) {
-      m_call = 0;
-    }
-    return result;
-  }
-
-  /**
-   * Get the result (return value). This function blocks until the result is received or it times
-   * out.
-   *
-   * @param timeout timeout, in seconds
-   * @return Received result (output)
-   */
-  public byte[] getResult(double timeout) {
-    byte[] result = NetworkTablesJNI.getRpcResult(m_entry.getHandle(), m_call, timeout);
-    if (result.length != 0) {
-      m_call = 0;
-    }
-    return result;
-  }
-
-  /** Ignore the result. This function is non-blocking. */
-  public void cancelResult() {
-    NetworkTablesJNI.cancelRpcResult(m_entry.getHandle(), m_call);
-  }
-
-  private final NetworkTableEntry m_entry;
-  private int m_call;
-}
diff --git a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/Subscriber.java b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/Subscriber.java
new file mode 100644
index 0000000..08f825d
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/Subscriber.java
@@ -0,0 +1,22 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.networktables;
+
+/** NetworkTables subscriber. */
+public interface Subscriber extends PubSub {
+  /**
+   * Determines if the entry currently exists.
+   *
+   * @return True if the entry exists, false otherwise.
+   */
+  boolean exists();
+
+  /**
+   * Gets the last time the entry's value was changed.
+   *
+   * @return Entry last change time
+   */
+  long getLastChange();
+}
diff --git a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/TableEntryListener.java b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/TableEntryListener.java
deleted file mode 100644
index e0781e1..0000000
--- a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/TableEntryListener.java
+++ /dev/null
@@ -1,22 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.networktables;
-
-/** A listener that listens to changes in values in a {@link NetworkTable}. */
-@FunctionalInterface
-public interface TableEntryListener extends EntryListenerFlags {
-  /**
-   * Called when a key-value pair is changed in a {@link NetworkTable}.
-   *
-   * @param table the table the key-value pair exists in
-   * @param key the key associated with the value that changed
-   * @param entry the entry associated with the value that changed
-   * @param value the new value
-   * @param flags update flags; for example, EntryListenerFlags.kNew if the key did not previously
-   *     exist in the table
-   */
-  void valueChanged(
-      NetworkTable table, String key, NetworkTableEntry entry, NetworkTableValue value, int flags);
-}
diff --git a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/TimeSyncEventData.java b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/TimeSyncEventData.java
new file mode 100644
index 0000000..f8710ad
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/TimeSyncEventData.java
@@ -0,0 +1,37 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.networktables;
+
+/** NetworkTables time sync event data. */
+@SuppressWarnings("MemberName")
+public final class TimeSyncEventData {
+  /**
+   * Offset between local time and server time, in microseconds. Add this value to local time to get
+   * the estimated equivalent server time.
+   */
+  public final long serverTimeOffset;
+
+  /** Measured round trip time divided by 2, in microseconds. */
+  public final long rtt2;
+
+  /**
+   * If serverTimeOffset and RTT are valid. An event with this set to false is sent when the client
+   * disconnects.
+   */
+  public final boolean valid;
+
+  /**
+   * Constructor. This should generally only be used internally to NetworkTables.
+   *
+   * @param serverTimeOffset Server time offset
+   * @param rtt2 Round trip time divided by 2
+   * @param valid If other parameters are valid
+   */
+  public TimeSyncEventData(long serverTimeOffset, long rtt2, boolean valid) {
+    this.serverTimeOffset = serverTimeOffset;
+    this.rtt2 = rtt2;
+    this.valid = valid;
+  }
+}
diff --git a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/Topic.java b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/Topic.java
new file mode 100644
index 0000000..db08a34
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/Topic.java
@@ -0,0 +1,322 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.networktables;
+
+/** NetworkTables Topic. */
+public class Topic {
+  /**
+   * Constructor; use NetworkTableInstance.getTopic() instead.
+   *
+   * @param inst Instance
+   * @param handle Native handle
+   */
+  Topic(NetworkTableInstance inst, int handle) {
+    m_inst = inst;
+    m_handle = handle;
+  }
+
+  /**
+   * Determines if the native handle is valid.
+   *
+   * @return True if the native handle is valid, false otherwise.
+   */
+  public boolean isValid() {
+    return m_handle != 0;
+  }
+
+  /**
+   * Gets the native handle for the topic.
+   *
+   * @return Native handle
+   */
+  public int getHandle() {
+    return m_handle;
+  }
+
+  /**
+   * Gets the instance for the topic.
+   *
+   * @return Instance
+   */
+  public NetworkTableInstance getInstance() {
+    return m_inst;
+  }
+
+  /**
+   * Gets the name of the topic.
+   *
+   * @return the topic's name
+   */
+  public String getName() {
+    return NetworkTablesJNI.getTopicName(m_handle);
+  }
+
+  /**
+   * Gets the type of the topic.
+   *
+   * @return the topic's type
+   */
+  public NetworkTableType getType() {
+    return NetworkTableType.getFromInt(NetworkTablesJNI.getType(m_handle));
+  }
+
+  /**
+   * Gets the type string of the topic. This may have more information than the numeric type
+   * (especially for raw values).
+   *
+   * @return the topic's type
+   */
+  public String getTypeString() {
+    return NetworkTablesJNI.getTopicTypeString(m_handle);
+  }
+
+  /**
+   * Gets combined information about the topic.
+   *
+   * @return Topic information
+   */
+  public TopicInfo getInfo() {
+    return NetworkTablesJNI.getTopicInfo(m_inst, m_handle);
+  }
+
+  /**
+   * Make value persistent through server restarts.
+   *
+   * @param persistent True for persistent, false for not persistent.
+   */
+  public void setPersistent(boolean persistent) {
+    NetworkTablesJNI.setTopicPersistent(m_handle, persistent);
+  }
+
+  /**
+   * Returns whether the value is persistent through server restarts.
+   *
+   * @return True if the value is persistent.
+   */
+  public boolean isPersistent() {
+    return NetworkTablesJNI.getTopicPersistent(m_handle);
+  }
+
+  /**
+   * Make the server retain the topic even when there are no publishers.
+   *
+   * @param retained True for retained, false for not retained.
+   */
+  public void setRetained(boolean retained) {
+    NetworkTablesJNI.setTopicRetained(m_handle, retained);
+  }
+
+  /**
+   * Returns whether the topic is retained by server when there are no publishers.
+   *
+   * @return True if the topic is retained.
+   */
+  public boolean isRetained() {
+    return NetworkTablesJNI.getTopicRetained(m_handle);
+  }
+
+  /**
+   * Determines if the topic is currently being published.
+   *
+   * @return True if the topic exists, false otherwise.
+   */
+  public boolean exists() {
+    return NetworkTablesJNI.getTopicExists(m_handle);
+  }
+
+  /**
+   * Gets the current value of a property (as a JSON string).
+   *
+   * @param name property name
+   * @return JSON string; "null" if the property does not exist.
+   */
+  public String getProperty(String name) {
+    return NetworkTablesJNI.getTopicProperty(m_handle, name);
+  }
+
+  /**
+   * Sets a property value.
+   *
+   * @param name property name
+   * @param value property value (JSON string)
+   * @throws IllegalArgumentException if properties is not parseable as JSON
+   */
+  public void setProperty(String name, String value) {
+    NetworkTablesJNI.setTopicProperty(m_handle, name, value);
+  }
+
+  /**
+   * Deletes a property. Has no effect if the property does not exist.
+   *
+   * @param name property name
+   */
+  public void deleteProperty(String name) {
+    NetworkTablesJNI.deleteTopicProperty(m_handle, name);
+  }
+
+  /**
+   * Gets all topic properties as a JSON object string. Each key in the object is the property name,
+   * and the corresponding value is the property value.
+   *
+   * @return JSON string
+   */
+  public String getProperties() {
+    return NetworkTablesJNI.getTopicProperties(m_handle);
+  }
+
+  /**
+   * Updates multiple topic properties. Each key in the passed-in object is the name of the property
+   * to add/update, and the corresponding value is the property value to set for that property. Null
+   * values result in deletion of the corresponding property.
+   *
+   * @param properties JSON object string with keys to add/update/delete
+   * @throws IllegalArgumentException if properties is not a JSON object
+   */
+  public void setProperties(String properties) {
+    NetworkTablesJNI.setTopicProperties(m_handle, properties);
+  }
+
+  /**
+   * Create a new subscriber to the topic.
+   *
+   * <p>The subscriber is only active as long as the returned object is not closed.
+   *
+   * @param options subscribe options
+   * @return subscriber
+   */
+  public GenericSubscriber genericSubscribe(PubSubOption... options) {
+    return genericSubscribe("", options);
+  }
+
+  /**
+   * Create a new subscriber to the topic.
+   *
+   * <p>The subscriber is only active as long as the returned object is not closed.
+   *
+   * <p>Subscribers that do not match the published data type do not return any values. To determine
+   * if the data type matches, use the appropriate Topic functions.
+   *
+   * @param typeString type string
+   * @param options subscribe options
+   * @return subscriber
+   */
+  public GenericSubscriber genericSubscribe(String typeString, PubSubOption... options) {
+    return new GenericEntryImpl(
+        this,
+        NetworkTablesJNI.subscribe(
+            m_handle, NetworkTableType.getFromString(typeString).getValue(), typeString, options));
+  }
+
+  /**
+   * Create a new publisher to the topic.
+   *
+   * <p>The publisher is only active as long as the returned object is not closed.
+   *
+   * <p>It is not possible to publish two different data types to the same topic. Conflicts between
+   * publishers are typically resolved by the server on a first-come, first-served basis. Any
+   * published values that do not match the topic's data type are dropped (ignored). To determine if
+   * the data type matches, use the appropriate Topic functions.
+   *
+   * @param typeString type string
+   * @param options publish options
+   * @return publisher
+   */
+  public GenericPublisher genericPublish(String typeString, PubSubOption... options) {
+    return new GenericEntryImpl(
+        this,
+        NetworkTablesJNI.publish(
+            m_handle, NetworkTableType.getFromString(typeString).getValue(), typeString, options));
+  }
+
+  /**
+   * Create a new publisher to the topic, with type string and initial properties.
+   *
+   * <p>The publisher is only active as long as the returned object is not closed.
+   *
+   * <p>It is not possible to publish two different data types to the same topic. Conflicts between
+   * publishers are typically resolved by the server on a first-come, first-served basis. Any
+   * published values that do not match the topic's data type are dropped (ignored). To determine if
+   * the data type matches, use the appropriate Topic functions.
+   *
+   * @param typeString type string
+   * @param properties JSON properties
+   * @param options publish options
+   * @return publisher
+   * @throws IllegalArgumentException if properties is not a JSON object
+   */
+  public GenericPublisher genericPublishEx(
+      String typeString, String properties, PubSubOption... options) {
+    return new GenericEntryImpl(
+        this,
+        NetworkTablesJNI.publishEx(
+            m_handle,
+            NetworkTableType.getFromString(typeString).getValue(),
+            typeString,
+            properties,
+            options));
+  }
+
+  /**
+   * Create a new generic entry for the topic.
+   *
+   * <p>Entries act as a combination of a subscriber and a weak publisher. The subscriber is active
+   * as long as the entry is not closed. The publisher is created when the entry is first written
+   * to, and remains active until either unpublish() is called or the entry is closed.
+   *
+   * <p>It is not possible to publish two different data types to the same topic. Conflicts between
+   * publishers are typically resolved by the server on a first-come, first-served basis. Any
+   * published values that do not match the topic's data type are dropped (ignored). To determine if
+   * the data type matches, use the appropriate Topic functions.
+   *
+   * @param options publish and/or subscribe options
+   * @return entry
+   */
+  public GenericEntry getGenericEntry(PubSubOption... options) {
+    return getGenericEntry("", options);
+  }
+
+  /**
+   * Create a new generic entry for the topic.
+   *
+   * <p>Entries act as a combination of a subscriber and a weak publisher. The subscriber is active
+   * as long as the entry is not closed. The publisher is created when the entry is first written
+   * to, and remains active until either unpublish() is called or the entry is closed.
+   *
+   * <p>It is not possible to publish two different data types to the same topic. Conflicts between
+   * publishers are typically resolved by the server on a first-come, first-served basis. Any
+   * published values that do not match the topic's data type are dropped (ignored). To determine if
+   * the data type matches, use the appropriate Topic functions.
+   *
+   * @param typeString type string
+   * @param options publish and/or subscribe options
+   * @return entry
+   */
+  public GenericEntry getGenericEntry(String typeString, PubSubOption... options) {
+    return new GenericEntryImpl(
+        this,
+        NetworkTablesJNI.getEntry(
+            m_handle, NetworkTableType.getFromString(typeString).getValue(), typeString, options));
+  }
+
+  @Override
+  public boolean equals(Object other) {
+    if (other == this) {
+      return true;
+    }
+    if (!(other instanceof Topic)) {
+      return false;
+    }
+
+    return m_handle == ((Topic) other).m_handle;
+  }
+
+  @Override
+  public int hashCode() {
+    return m_handle;
+  }
+
+  protected NetworkTableInstance m_inst;
+  protected int m_handle;
+}
diff --git a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/TopicInfo.java b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/TopicInfo.java
new file mode 100644
index 0000000..abd8c2a
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/TopicInfo.java
@@ -0,0 +1,65 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.networktables;
+
+/** NetworkTables topic information. */
+@SuppressWarnings("MemberName")
+public final class TopicInfo {
+  /** Topic handle. */
+  public final int topic;
+
+  /** Topic name. */
+  public final String name;
+
+  /** Topic type. */
+  public final NetworkTableType type;
+
+  /** Topic type string. */
+  public final String typeStr;
+
+  /**
+   * Constructor. This should generally only be used internally to NetworkTables.
+   *
+   * @param inst Instance
+   * @param handle Topic handle
+   * @param name Name
+   * @param type Type (integer version of {@link NetworkTableType})
+   * @param typeStr Type string
+   */
+  public TopicInfo(NetworkTableInstance inst, int handle, String name, int type, String typeStr) {
+    this.m_inst = inst;
+    this.topic = handle;
+    this.name = name;
+    this.type = NetworkTableType.getFromInt(type);
+    this.typeStr = typeStr;
+  }
+
+  /* Network table instance. */
+  private final NetworkTableInstance m_inst;
+
+  /* Cached topic object. */
+  private Topic m_topicObject;
+
+  /**
+   * Get the instance.
+   *
+   * @return Instance
+   */
+  public NetworkTableInstance getInstance() {
+    return m_inst;
+  }
+
+  /**
+   * Get the topic as an object.
+   *
+   * @return Topic
+   */
+  public Topic getTopic() {
+    if (m_topicObject == null) {
+      m_topicObject = new Topic(m_inst, topic);
+    }
+    return m_topicObject;
+  }
+}
diff --git a/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/ValueEventData.java b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/ValueEventData.java
new file mode 100644
index 0000000..511bb66
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/java/edu/wpi/first/networktables/ValueEventData.java
@@ -0,0 +1,54 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.networktables;
+
+/** NetworkTables value event data. */
+@SuppressWarnings("MemberName")
+public final class ValueEventData {
+  /** Topic handle. Topic.getHandle() can be used to map this to the corresponding Topic object. */
+  public final int topic;
+
+  /**
+   * Subscriber/entry handle. Subscriber.getHandle() or entry.getHandle() can be used to map this to
+   * the corresponding Subscriber or Entry object.
+   */
+  public final int subentry;
+
+  /** The new value. */
+  public final NetworkTableValue value;
+
+  /**
+   * Constructor. This should generally only be used internally to NetworkTables.
+   *
+   * @param inst Instance
+   * @param topic Topic handle
+   * @param subentry Subscriber/entry handle
+   * @param value The new value
+   */
+  public ValueEventData(
+      NetworkTableInstance inst, int topic, int subentry, NetworkTableValue value) {
+    this.m_inst = inst;
+    this.topic = topic;
+    this.subentry = subentry;
+    this.value = value;
+  }
+
+  /* Cached topic object. */
+  private Topic m_topicObject;
+
+  private final NetworkTableInstance m_inst;
+
+  /**
+   * Get the topic as an object.
+   *
+   * @return Topic for this notification.
+   */
+  public Topic getTopic() {
+    if (m_topicObject == null) {
+      m_topicObject = new Topic(m_inst, topic);
+    }
+    return m_topicObject;
+  }
+}
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/ConnectionList.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/ConnectionList.cpp
new file mode 100644
index 0000000..4781f52
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/ConnectionList.cpp
@@ -0,0 +1,126 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "ConnectionList.h"
+
+#include <wpi/SmallVector.h>
+#include <wpi/json_serializer.h>
+#include <wpi/raw_ostream.h>
+
+#include "IListenerStorage.h"
+#include "ntcore_c.h"
+#include "ntcore_cpp.h"
+
+using namespace nt;
+
+static std::string ConnInfoToJson(bool connected, const ConnectionInfo& info) {
+  std::string str;
+  wpi::raw_string_ostream os{str};
+  wpi::json::serializer s{os, ' ', 0};
+  os << "{\"connected\":" << (connected ? "true" : "false");
+  os << ",\"remote_id\":\"";
+  s.dump_escaped(info.remote_id, false);
+  os << "\",\"remote_ip\":\"";
+  s.dump_escaped(info.remote_ip, false);
+  os << "\",\"remote_port\":";
+  s.dump_integer(static_cast<uint64_t>(info.remote_port));
+  os << ",\"protocol_version\":";
+  s.dump_integer(static_cast<uint64_t>(info.protocol_version));
+  os << "}";
+  os.flush();
+  return str;
+}
+
+ConnectionList::ConnectionList(int inst, IListenerStorage& listenerStorage)
+    : m_inst{inst}, m_listenerStorage{listenerStorage} {}
+
+ConnectionList::~ConnectionList() = default;
+
+int ConnectionList::AddConnection(const ConnectionInfo& info) {
+  std::scoped_lock lock{m_mutex};
+  m_connected = true;
+  m_listenerStorage.Notify({}, NT_EVENT_CONNECTED, &info);
+  if (!m_dataloggers.empty()) {
+    auto now = Now();
+    for (auto&& datalogger : m_dataloggers) {
+      datalogger->entry.Append(ConnInfoToJson(true, info), now);
+    }
+  }
+  return m_connections.emplace_back(info);
+}
+
+void ConnectionList::RemoveConnection(int handle) {
+  std::scoped_lock lock{m_mutex};
+  auto val = m_connections.erase(handle);
+  if (m_connections.empty()) {
+    m_connected = false;
+  }
+  if (val) {
+    m_listenerStorage.Notify({}, NT_EVENT_DISCONNECTED, &(*val));
+    if (!m_dataloggers.empty()) {
+      auto now = Now();
+      for (auto&& datalogger : m_dataloggers) {
+        datalogger->entry.Append(ConnInfoToJson(false, *val), now);
+      }
+    }
+  }
+}
+
+void ConnectionList::ClearConnections() {
+  std::scoped_lock lock{m_mutex};
+  m_connected = false;
+  for (auto&& conn : m_connections) {
+    m_listenerStorage.Notify({}, NT_EVENT_DISCONNECTED, &(*conn));
+  }
+  m_connections.clear();
+}
+
+std::vector<ConnectionInfo> ConnectionList::GetConnections() const {
+  std::scoped_lock lock{m_mutex};
+  std::vector<ConnectionInfo> info;
+  info.reserve(m_connections.size());
+  for (auto&& conn : m_connections) {
+    info.emplace_back(*conn);
+  }
+  return info;
+}
+
+bool ConnectionList::IsConnected() const {
+  return m_connected;
+}
+
+void ConnectionList::AddListener(NT_Listener listener, unsigned int eventMask) {
+  std::scoped_lock lock{m_mutex};
+  eventMask &= (NT_EVENT_CONNECTION | NT_EVENT_IMMEDIATE);
+  m_listenerStorage.Activate(listener, eventMask);
+  if ((eventMask & (NT_EVENT_CONNECTED | NT_EVENT_IMMEDIATE)) ==
+          (NT_EVENT_CONNECTED | NT_EVENT_IMMEDIATE) &&
+      !m_connections.empty()) {
+    wpi::SmallVector<const ConnectionInfo*, 16> infos;
+    infos.reserve(m_connections.size());
+    for (auto&& conn : m_connections) {
+      infos.emplace_back(&(*conn));
+    }
+    m_listenerStorage.Notify({&listener, 1},
+                             NT_EVENT_CONNECTED | NT_EVENT_IMMEDIATE, infos);
+  }
+}
+
+NT_ConnectionDataLogger ConnectionList::StartDataLog(wpi::log::DataLog& log,
+                                                     std::string_view name) {
+  std::scoped_lock lock{m_mutex};
+  auto now = Now();
+  auto datalogger = m_dataloggers.Add(m_inst, log, name, now);
+  for (auto&& conn : m_connections) {
+    datalogger->entry.Append(ConnInfoToJson(true, *conn), now);
+  }
+  return datalogger->handle;
+}
+
+void ConnectionList::StopDataLog(NT_ConnectionDataLogger logger) {
+  std::scoped_lock lock{m_mutex};
+  if (auto datalogger = m_dataloggers.Remove(logger)) {
+    datalogger->entry.Finish(Now());
+  }
+}
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/ConnectionList.h b/third_party/allwpilib/ntcore/src/main/native/cpp/ConnectionList.h
new file mode 100644
index 0000000..c46266d
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/ConnectionList.h
@@ -0,0 +1,74 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <stdint.h>
+
+#include <atomic>
+#include <functional>
+#include <memory>
+#include <optional>
+#include <string_view>
+#include <vector>
+
+#include <wpi/DataLog.h>
+#include <wpi/UidVector.h>
+#include <wpi/mutex.h>
+
+#include "Handle.h"
+#include "HandleMap.h"
+#include "IConnectionList.h"
+#include "ntcore_cpp.h"
+
+namespace nt {
+
+class IListenerStorage;
+
+class ConnectionList final : public IConnectionList {
+ public:
+  ConnectionList(int inst, IListenerStorage& listenerStorage);
+  ~ConnectionList() final;
+
+  // IConnectionList interface
+  int AddConnection(const ConnectionInfo& info) final;
+  void RemoveConnection(int handle) final;
+  void ClearConnections() final;
+
+  // user-facing functions
+  std::vector<ConnectionInfo> GetConnections() const final;
+  bool IsConnected() const final;
+
+  void AddListener(NT_Listener listener, unsigned int eventMask);
+
+  NT_ConnectionDataLogger StartDataLog(wpi::log::DataLog& log,
+                                       std::string_view name);
+  void StopDataLog(NT_ConnectionDataLogger logger);
+
+ private:
+  int m_inst;
+  IListenerStorage& m_listenerStorage;
+  mutable wpi::mutex m_mutex;
+
+  // shared with user (must be atomic or mutex-protected)
+  std::atomic_bool m_connected{false};
+  wpi::UidVector<std::optional<ConnectionInfo>, 8> m_connections;
+
+  struct DataLoggerData {
+    static constexpr auto kType = Handle::kConnectionDataLogger;
+
+    DataLoggerData(NT_ConnectionDataLogger handle, wpi::log::DataLog& log,
+                   std::string_view name, int64_t time)
+        : handle{handle},
+          entry{log, name,
+                "{\"schema\":\"NTConnectionInfo\",\"source\":\"NT\"}", "json",
+                time} {}
+
+    NT_ConnectionDataLogger handle;
+    wpi::log::StringLogEntry entry;
+  };
+  HandleMap<DataLoggerData, 8> m_dataloggers;
+};
+
+}  // namespace nt
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/ConnectionNotifier.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/ConnectionNotifier.cpp
deleted file mode 100644
index 60e7303..0000000
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/ConnectionNotifier.cpp
+++ /dev/null
@@ -1,28 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "ConnectionNotifier.h"
-
-using namespace nt;
-
-ConnectionNotifier::ConnectionNotifier(int inst) : m_inst(inst) {}
-
-void ConnectionNotifier::Start() {
-  DoStart(m_inst);
-}
-
-unsigned int ConnectionNotifier::Add(
-    std::function<void(const ConnectionNotification& event)> callback) {
-  return DoAdd(callback);
-}
-
-unsigned int ConnectionNotifier::AddPolled(unsigned int poller_uid) {
-  return DoAdd(poller_uid);
-}
-
-void ConnectionNotifier::NotifyConnection(bool connected,
-                                          const ConnectionInfo& conn_info,
-                                          unsigned int only_listener) {
-  Send(only_listener, 0, connected, conn_info);
-}
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/ConnectionNotifier.h b/third_party/allwpilib/ntcore/src/main/native/cpp/ConnectionNotifier.h
deleted file mode 100644
index fab4733..0000000
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/ConnectionNotifier.h
+++ /dev/null
@@ -1,75 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef NTCORE_CONNECTIONNOTIFIER_H_
-#define NTCORE_CONNECTIONNOTIFIER_H_
-
-#include <utility>
-
-#include <wpi/CallbackManager.h>
-
-#include "Handle.h"
-#include "IConnectionNotifier.h"
-#include "ntcore_cpp.h"
-
-namespace nt {
-
-namespace impl {
-
-class ConnectionNotifierThread
-    : public wpi::CallbackThread<ConnectionNotifierThread,
-                                 ConnectionNotification> {
- public:
-  ConnectionNotifierThread(std::function<void()> on_start,
-                           std::function<void()> on_exit, int inst)
-      : CallbackThread(std::move(on_start), std::move(on_exit)), m_inst(inst) {}
-
-  bool Matches(const ListenerData& /*listener*/,
-               const ConnectionNotification& /*data*/) {
-    return true;
-  }
-
-  void SetListener(ConnectionNotification* data, unsigned int listener_uid) {
-    data->listener =
-        Handle(m_inst, listener_uid, Handle::kConnectionListener).handle();
-  }
-
-  void DoCallback(
-      std::function<void(const ConnectionNotification& event)> callback,
-      const ConnectionNotification& data) {
-    callback(data);
-  }
-
-  int m_inst;
-};
-
-}  // namespace impl
-
-class ConnectionNotifier
-    : public IConnectionNotifier,
-      public wpi::CallbackManager<ConnectionNotifier,
-                                  impl::ConnectionNotifierThread> {
-  friend class ConnectionNotifierTest;
-  friend class wpi::CallbackManager<ConnectionNotifier,
-                                    impl::ConnectionNotifierThread>;
-
- public:
-  explicit ConnectionNotifier(int inst);
-
-  void Start();
-
-  unsigned int Add(std::function<void(const ConnectionNotification& event)>
-                       callback) override;
-  unsigned int AddPolled(unsigned int poller_uid) override;
-
-  void NotifyConnection(bool connected, const ConnectionInfo& conn_info,
-                        unsigned int only_listener = UINT_MAX) override;
-
- private:
-  int m_inst;
-};
-
-}  // namespace nt
-
-#endif  // NTCORE_CONNECTIONNOTIFIER_H_
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/Dispatcher.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/Dispatcher.cpp
deleted file mode 100644
index 84d9698..0000000
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/Dispatcher.cpp
+++ /dev/null
@@ -1,711 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "Dispatcher.h"
-
-#include <algorithm>
-#include <iterator>
-
-#include <wpi/SmallVector.h>
-#include <wpi/StringExtras.h>
-#include <wpi/TCPAcceptor.h>
-#include <wpi/TCPConnector.h>
-#include <wpi/timestamp.h>
-
-#include "IConnectionNotifier.h"
-#include "IStorage.h"
-#include "Log.h"
-#include "NetworkConnection.h"
-
-using namespace nt;
-
-void Dispatcher::StartServer(std::string_view persist_filename,
-                             const char* listen_address, unsigned int port) {
-  std::string listen_address_copy(wpi::trim(listen_address));
-  DispatcherBase::StartServer(
-      persist_filename,
-      std::unique_ptr<wpi::NetworkAcceptor>(new wpi::TCPAcceptor(
-          static_cast<int>(port), listen_address_copy.c_str(), m_logger)));
-}
-
-void Dispatcher::SetServer(const char* server_name, unsigned int port) {
-  std::string server_name_copy(wpi::trim(server_name));
-  SetConnector([=]() -> std::unique_ptr<wpi::NetworkStream> {
-    return wpi::TCPConnector::connect(server_name_copy.c_str(),
-                                      static_cast<int>(port), m_logger, 1);
-  });
-}
-
-void Dispatcher::SetServer(
-    wpi::span<const std::pair<std::string_view, unsigned int>> servers) {
-  wpi::SmallVector<std::pair<std::string, int>, 16> servers_copy;
-  for (const auto& server : servers) {
-    servers_copy.emplace_back(std::string{wpi::trim(server.first)},
-                              static_cast<int>(server.second));
-  }
-
-  SetConnector([=]() -> std::unique_ptr<wpi::NetworkStream> {
-    wpi::SmallVector<std::pair<const char*, int>, 16> servers_copy2;
-    for (const auto& server : servers_copy) {
-      servers_copy2.emplace_back(server.first.c_str(), server.second);
-    }
-    return wpi::TCPConnector::connect_parallel(servers_copy2, m_logger, 1);
-  });
-}
-
-void Dispatcher::SetServerTeam(unsigned int team, unsigned int port) {
-  std::pair<std::string_view, unsigned int> servers[5];
-
-  // 10.te.am.2
-  auto fixed = fmt::format("10.{}.{}.2", static_cast<int>(team / 100),
-                           static_cast<int>(team % 100));
-  servers[0] = {fixed, port};
-
-  // 172.22.11.2
-  servers[1] = {"172.22.11.2", port};
-
-  // roboRIO-<team>-FRC.local
-  auto mdns = fmt::format("roboRIO-{}-FRC.local", team);
-  servers[2] = {mdns, port};
-
-  // roboRIO-<team>-FRC.lan
-  auto mdns_lan = fmt::format("roboRIO-{}-FRC.lan", team);
-  servers[3] = {mdns_lan, port};
-
-  // roboRIO-<team>-FRC.frc-field.local
-  auto field_local = fmt::format("roboRIO-{}-FRC.frc-field.local", team);
-  servers[4] = {field_local, port};
-
-  SetServer(servers);
-}
-
-void Dispatcher::SetServerOverride(const char* server_name, unsigned int port) {
-  std::string server_name_copy(wpi::trim(server_name));
-  SetConnectorOverride([=]() -> std::unique_ptr<wpi::NetworkStream> {
-    return wpi::TCPConnector::connect(server_name_copy.c_str(),
-                                      static_cast<int>(port), m_logger, 1);
-  });
-}
-
-void Dispatcher::ClearServerOverride() {
-  ClearConnectorOverride();
-}
-
-DispatcherBase::DispatcherBase(IStorage& storage, IConnectionNotifier& notifier,
-                               wpi::Logger& logger)
-    : m_storage(storage), m_notifier(notifier), m_logger(logger) {
-  m_active = false;
-  m_update_rate = 100;
-}
-
-DispatcherBase::~DispatcherBase() {
-  Stop();
-}
-
-unsigned int DispatcherBase::GetNetworkMode() const {
-  return m_networkMode;
-}
-
-void DispatcherBase::StartLocal() {
-  {
-    std::scoped_lock lock(m_user_mutex);
-    if (m_active) {
-      return;
-    }
-    m_active = true;
-  }
-  m_networkMode = NT_NET_MODE_LOCAL;
-  m_storage.SetDispatcher(this, false);
-}
-
-void DispatcherBase::StartServer(
-    std::string_view persist_filename,
-    std::unique_ptr<wpi::NetworkAcceptor> acceptor) {
-  {
-    std::scoped_lock lock(m_user_mutex);
-    if (m_active) {
-      return;
-    }
-    m_active = true;
-  }
-  m_networkMode = NT_NET_MODE_SERVER | NT_NET_MODE_STARTING;
-  m_persist_filename = persist_filename;
-  m_server_acceptor = std::move(acceptor);
-
-  // Load persistent file.  Ignore errors, but pass along warnings.
-  if (!persist_filename.empty()) {
-    bool first = true;
-    m_storage.LoadPersistent(
-        persist_filename, [&](size_t line, const char* msg) {
-          if (first) {
-            first = false;
-            WARNING("When reading initial persistent values from '{}':",
-                    persist_filename);
-          }
-          WARNING("{}:{}: {}", persist_filename, line, msg);
-        });
-  }
-
-  m_storage.SetDispatcher(this, true);
-
-  m_dispatch_thread = std::thread(&Dispatcher::DispatchThreadMain, this);
-  m_clientserver_thread = std::thread(&Dispatcher::ServerThreadMain, this);
-}
-
-void DispatcherBase::StartClient() {
-  {
-    std::scoped_lock lock(m_user_mutex);
-    if (m_active) {
-      return;
-    }
-    m_active = true;
-  }
-  m_networkMode = NT_NET_MODE_CLIENT | NT_NET_MODE_STARTING;
-  m_storage.SetDispatcher(this, false);
-
-  m_dispatch_thread = std::thread(&Dispatcher::DispatchThreadMain, this);
-  m_clientserver_thread = std::thread(&Dispatcher::ClientThreadMain, this);
-}
-
-void DispatcherBase::Stop() {
-  m_active = false;
-
-  // wake up dispatch thread with a flush
-  m_flush_cv.notify_one();
-
-  // wake up client thread with a reconnect
-  {
-    std::scoped_lock lock(m_user_mutex);
-    m_client_connector = nullptr;
-  }
-  ClientReconnect();
-
-  // wake up server thread by shutting down the socket
-  if (m_server_acceptor) {
-    m_server_acceptor->shutdown();
-  }
-
-  // join threads, with timeout
-  if (m_dispatch_thread.joinable()) {
-    m_dispatch_thread.join();
-  }
-  if (m_clientserver_thread.joinable()) {
-    m_clientserver_thread.join();
-  }
-
-  std::vector<std::shared_ptr<INetworkConnection>> conns;
-  {
-    std::scoped_lock lock(m_user_mutex);
-    conns.swap(m_connections);
-  }
-
-  // close all connections
-  conns.resize(0);
-}
-
-void DispatcherBase::SetUpdateRate(double interval) {
-  // don't allow update rates faster than 5 ms or slower than 1 second
-  if (interval < 0.005) {
-    interval = 0.005;
-  } else if (interval > 1.0) {
-    interval = 1.0;
-  }
-  m_update_rate = static_cast<unsigned int>(interval * 1000);
-}
-
-void DispatcherBase::SetIdentity(std::string_view name) {
-  std::scoped_lock lock(m_user_mutex);
-  m_identity = name;
-}
-
-void DispatcherBase::Flush() {
-  auto now = wpi::Now();
-  {
-    std::scoped_lock lock(m_flush_mutex);
-    // don't allow flushes more often than every 5 ms
-    if ((now - m_last_flush) < 5000) {
-      return;
-    }
-    m_last_flush = now;
-    m_do_flush = true;
-  }
-  m_flush_cv.notify_one();
-}
-
-std::vector<ConnectionInfo> DispatcherBase::GetConnections() const {
-  std::vector<ConnectionInfo> conns;
-  if (!m_active) {
-    return conns;
-  }
-
-  std::scoped_lock lock(m_user_mutex);
-  for (auto& conn : m_connections) {
-    if (conn->state() != NetworkConnection::kActive) {
-      continue;
-    }
-    conns.emplace_back(conn->info());
-  }
-
-  return conns;
-}
-
-bool DispatcherBase::IsConnected() const {
-  if (!m_active) {
-    return false;
-  }
-
-  if (m_networkMode == NT_NET_MODE_LOCAL) {
-    return true;
-  }
-
-  std::scoped_lock lock(m_user_mutex);
-  for (auto& conn : m_connections) {
-    if (conn->state() == NetworkConnection::kActive) {
-      return true;
-    }
-  }
-
-  return false;
-}
-
-unsigned int DispatcherBase::AddListener(
-    std::function<void(const ConnectionNotification& event)> callback,
-    bool immediate_notify) const {
-  std::scoped_lock lock(m_user_mutex);
-  unsigned int uid = m_notifier.Add(callback);
-  // perform immediate notifications
-  if (immediate_notify) {
-    for (auto& conn : m_connections) {
-      if (conn->state() != NetworkConnection::kActive) {
-        continue;
-      }
-      m_notifier.NotifyConnection(true, conn->info(), uid);
-    }
-  }
-  return uid;
-}
-
-unsigned int DispatcherBase::AddPolledListener(unsigned int poller_uid,
-                                               bool immediate_notify) const {
-  std::scoped_lock lock(m_user_mutex);
-  unsigned int uid = m_notifier.AddPolled(poller_uid);
-  // perform immediate notifications
-  if (immediate_notify) {
-    for (auto& conn : m_connections) {
-      if (conn->state() != NetworkConnection::kActive) {
-        continue;
-      }
-      m_notifier.NotifyConnection(true, conn->info(), uid);
-    }
-  }
-  return uid;
-}
-
-void DispatcherBase::SetConnector(Connector connector) {
-  std::scoped_lock lock(m_user_mutex);
-  m_client_connector = std::move(connector);
-}
-
-void DispatcherBase::SetConnectorOverride(Connector connector) {
-  std::scoped_lock lock(m_user_mutex);
-  m_client_connector_override = std::move(connector);
-}
-
-void DispatcherBase::ClearConnectorOverride() {
-  std::scoped_lock lock(m_user_mutex);
-  m_client_connector_override = nullptr;
-}
-
-void DispatcherBase::DispatchThreadMain() {
-  auto timeout_time = std::chrono::steady_clock::now();
-
-  static const auto save_delta_time = std::chrono::seconds(1);
-  auto next_save_time = timeout_time + save_delta_time;
-
-  int count = 0;
-
-  while (m_active) {
-    // handle loop taking too long
-    auto start = std::chrono::steady_clock::now();
-    if (start > timeout_time) {
-      timeout_time = start;
-    }
-
-    // wait for periodic or when flushed
-    timeout_time += std::chrono::milliseconds(m_update_rate);
-    std::unique_lock<wpi::mutex> flush_lock(m_flush_mutex);
-    m_flush_cv.wait_until(flush_lock, timeout_time,
-                          [&] { return !m_active || m_do_flush; });
-    m_do_flush = false;
-    flush_lock.unlock();
-    if (!m_active) {
-      break;  // in case we were woken up to terminate
-    }
-
-    // perform periodic persistent save
-    if ((m_networkMode & NT_NET_MODE_SERVER) != 0 &&
-        !m_persist_filename.empty() && start > next_save_time) {
-      next_save_time += save_delta_time;
-      // handle loop taking too long
-      if (start > next_save_time) {
-        next_save_time = start + save_delta_time;
-      }
-      const char* err = m_storage.SavePersistent(m_persist_filename, true);
-      if (err) {
-        WARNING("periodic persistent save: {}", err);
-      }
-    }
-
-    {
-      std::scoped_lock user_lock(m_user_mutex);
-      bool reconnect = false;
-
-      if (++count > 10) {
-        DEBUG0("dispatch running {} connections", m_connections.size());
-        count = 0;
-      }
-
-      for (auto& conn : m_connections) {
-        // post outgoing messages if connection is active
-        // only send keep-alives on client
-        if (conn->state() == NetworkConnection::kActive) {
-          conn->PostOutgoing((m_networkMode & NT_NET_MODE_CLIENT) != 0);
-        }
-
-        // if client, reconnect if connection died
-        if ((m_networkMode & NT_NET_MODE_CLIENT) != 0 &&
-            conn->state() == NetworkConnection::kDead) {
-          reconnect = true;
-        }
-      }
-      // reconnect if we disconnected (and a reconnect is not in progress)
-      if (reconnect && !m_do_reconnect) {
-        m_do_reconnect = true;
-        m_reconnect_cv.notify_one();
-      }
-    }
-  }
-}
-
-void DispatcherBase::QueueOutgoing(std::shared_ptr<Message> msg,
-                                   INetworkConnection* only,
-                                   INetworkConnection* except) {
-  std::scoped_lock user_lock(m_user_mutex);
-  for (auto& conn : m_connections) {
-    if (conn.get() == except) {
-      continue;
-    }
-    if (only && conn.get() != only) {
-      continue;
-    }
-    auto state = conn->state();
-    if (state != NetworkConnection::kSynchronized &&
-        state != NetworkConnection::kActive) {
-      continue;
-    }
-    conn->QueueOutgoing(msg);
-  }
-}
-
-void DispatcherBase::ServerThreadMain() {
-  if (m_server_acceptor->start() != 0) {
-    m_active = false;
-    m_networkMode = NT_NET_MODE_SERVER | NT_NET_MODE_FAILURE;
-    return;
-  }
-  m_networkMode = NT_NET_MODE_SERVER;
-  while (m_active) {
-    auto stream = m_server_acceptor->accept();
-    if (!stream) {
-      m_active = false;
-      return;
-    }
-    if (!m_active) {
-      m_networkMode = NT_NET_MODE_NONE;
-      return;
-    }
-    DEBUG0("server: client connection from {} port {}", stream->getPeerIP(),
-           stream->getPeerPort());
-
-    // add to connections list
-    using namespace std::placeholders;
-    auto conn = std::make_shared<NetworkConnection>(
-        ++m_connections_uid, std::move(stream), m_notifier, m_logger,
-        std::bind(&Dispatcher::ServerHandshake, this, _1, _2, _3),   // NOLINT
-        std::bind(&IStorage::GetMessageEntryType, &m_storage, _1));  // NOLINT
-    conn->set_process_incoming(
-        std::bind(&IStorage::ProcessIncoming, &m_storage, _1, _2,  // NOLINT
-                  std::weak_ptr<NetworkConnection>(conn)));
-    {
-      std::scoped_lock lock(m_user_mutex);
-      // reuse dead connection slots
-      bool placed = false;
-      for (auto& c : m_connections) {
-        if (c->state() == NetworkConnection::kDead) {
-          c = conn;
-          placed = true;
-          break;
-        }
-      }
-      if (!placed) {
-        m_connections.emplace_back(conn);
-      }
-      conn->Start();
-    }
-  }
-  m_networkMode = NT_NET_MODE_NONE;
-}
-
-void DispatcherBase::ClientThreadMain() {
-  while (m_active) {
-    // sleep between retries
-    std::this_thread::sleep_for(std::chrono::milliseconds(250));
-    Connector connect;
-
-    // get next server to connect to
-    {
-      std::scoped_lock lock(m_user_mutex);
-      if (m_client_connector_override) {
-        connect = m_client_connector_override;
-      } else {
-        if (!m_client_connector) {
-          m_networkMode = NT_NET_MODE_CLIENT | NT_NET_MODE_FAILURE;
-          continue;
-        }
-        connect = m_client_connector;
-      }
-    }
-
-    // try to connect (with timeout)
-    DEBUG0("{}", "client trying to connect");
-    auto stream = connect();
-    if (!stream) {
-      m_networkMode = NT_NET_MODE_CLIENT | NT_NET_MODE_FAILURE;
-      continue;  // keep retrying
-    }
-    DEBUG0("{}", "client connected");
-    m_networkMode = NT_NET_MODE_CLIENT;
-
-    std::unique_lock lock(m_user_mutex);
-    using namespace std::placeholders;
-    auto conn = std::make_shared<NetworkConnection>(
-        ++m_connections_uid, std::move(stream), m_notifier, m_logger,
-        std::bind(&Dispatcher::ClientHandshake, this, _1, _2, _3),   // NOLINT
-        std::bind(&IStorage::GetMessageEntryType, &m_storage, _1));  // NOLINT
-    conn->set_process_incoming(
-        std::bind(&IStorage::ProcessIncoming, &m_storage, _1, _2,  // NOLINT
-                  std::weak_ptr<NetworkConnection>(conn)));
-    m_connections.resize(0);  // disconnect any current
-    m_connections.emplace_back(conn);
-    conn->set_proto_rev(m_reconnect_proto_rev);
-    conn->Start();
-
-    // reconnect the next time starting with latest protocol revision
-    m_reconnect_proto_rev = 0x0300;
-
-    // block until told to reconnect
-    m_do_reconnect = false;
-    m_reconnect_cv.wait(lock, [&] { return !m_active || m_do_reconnect; });
-  }
-  m_networkMode = NT_NET_MODE_NONE;
-}
-
-bool DispatcherBase::ClientHandshake(
-    NetworkConnection& conn, std::function<std::shared_ptr<Message>()> get_msg,
-    std::function<void(wpi::span<std::shared_ptr<Message>>)> send_msgs) {
-  // get identity
-  std::string self_id;
-  {
-    std::scoped_lock lock(m_user_mutex);
-    self_id = m_identity;
-  }
-
-  // send client hello
-  DEBUG0("{}", "client: sending hello");
-  auto msg = Message::ClientHello(self_id);
-  send_msgs(wpi::span(&msg, 1));
-
-  // wait for response
-  msg = get_msg();
-  if (!msg) {
-    // disconnected, retry
-    DEBUG0("{}", "client: server disconnected before first response");
-    return false;
-  }
-
-  if (msg->Is(Message::kProtoUnsup)) {
-    if (msg->id() == 0x0200) {
-      ClientReconnect(0x0200);
-    }
-    return false;
-  }
-
-  bool new_server = true;
-  if (conn.proto_rev() >= 0x0300) {
-    // should be server hello; if not, disconnect.
-    if (!msg->Is(Message::kServerHello)) {
-      return false;
-    }
-    conn.set_remote_id(msg->str());
-    if ((msg->flags() & 1) != 0) {
-      new_server = false;
-    }
-    // get the next message
-    msg = get_msg();
-  }
-
-  // receive initial assignments
-  std::vector<std::shared_ptr<Message>> incoming;
-  for (;;) {
-    if (!msg) {
-      // disconnected, retry
-      DEBUG0("{}", "client: server disconnected during initial entries");
-      return false;
-    }
-    DEBUG4("received init str={} id={} seq_num={}", msg->str(), msg->id(),
-           msg->seq_num_uid());
-    if (msg->Is(Message::kServerHelloDone)) {
-      break;
-    }
-    // shouldn't receive a keep alive, but handle gracefully
-    if (msg->Is(Message::kKeepAlive)) {
-      msg = get_msg();
-      continue;
-    }
-    if (!msg->Is(Message::kEntryAssign)) {
-      // unexpected message
-      DEBUG0(
-          "client: received message ({}) other than entry assignment during "
-          "initial handshake",
-          msg->type());
-      return false;
-    }
-    incoming.emplace_back(std::move(msg));
-    // get the next message
-    msg = get_msg();
-  }
-
-  // generate outgoing assignments
-  NetworkConnection::Outgoing outgoing;
-
-  m_storage.ApplyInitialAssignments(conn, incoming, new_server, &outgoing);
-
-  if (conn.proto_rev() >= 0x0300) {
-    outgoing.emplace_back(Message::ClientHelloDone());
-  }
-
-  if (!outgoing.empty()) {
-    send_msgs(outgoing);
-  }
-
-  INFO("client: CONNECTED to server {} port {}", conn.stream().getPeerIP(),
-       conn.stream().getPeerPort());
-  return true;
-}
-
-bool DispatcherBase::ServerHandshake(
-    NetworkConnection& conn, std::function<std::shared_ptr<Message>()> get_msg,
-    std::function<void(wpi::span<std::shared_ptr<Message>>)> send_msgs) {
-  // Wait for the client to send us a hello.
-  auto msg = get_msg();
-  if (!msg) {
-    DEBUG0("{}", "server: client disconnected before sending hello");
-    return false;
-  }
-  if (!msg->Is(Message::kClientHello)) {
-    DEBUG0("{}", "server: client initial message was not client hello");
-    return false;
-  }
-
-  // Check that the client requested version is not too high.
-  unsigned int proto_rev = msg->id();
-  if (proto_rev > 0x0300) {
-    DEBUG0("{}", "server: client requested proto > 0x0300");
-    auto toSend = Message::ProtoUnsup();
-    send_msgs(wpi::span(&toSend, 1));
-    return false;
-  }
-
-  if (proto_rev >= 0x0300) {
-    conn.set_remote_id(msg->str());
-  }
-
-  // Set the proto version to the client requested version
-  DEBUG0("server: client protocol {}", proto_rev);
-  conn.set_proto_rev(proto_rev);
-
-  // Send initial set of assignments
-  NetworkConnection::Outgoing outgoing;
-
-  // Start with server hello.  TODO: initial connection flag
-  if (proto_rev >= 0x0300) {
-    std::scoped_lock lock(m_user_mutex);
-    outgoing.emplace_back(Message::ServerHello(0u, m_identity));
-  }
-
-  // Get snapshot of initial assignments
-  m_storage.GetInitialAssignments(conn, &outgoing);
-
-  // Finish with server hello done
-  outgoing.emplace_back(Message::ServerHelloDone());
-
-  // Batch transmit
-  DEBUG0("{}", "server: sending initial assignments");
-  send_msgs(outgoing);
-
-  // In proto rev 3.0 and later, the handshake concludes with a client hello
-  // done message, so we can batch the assigns before marking the connection
-  // active.  In pre-3.0, we need to just immediately mark it active and hand
-  // off control to the dispatcher to assign them as they arrive.
-  if (proto_rev >= 0x0300) {
-    // receive client initial assignments
-    std::vector<std::shared_ptr<Message>> incoming;
-    msg = get_msg();
-    for (;;) {
-      if (!msg) {
-        // disconnected, retry
-        DEBUG0("{}", "server: disconnected waiting for initial entries");
-        return false;
-      }
-      if (msg->Is(Message::kClientHelloDone)) {
-        break;
-      }
-      // shouldn't receive a keep alive, but handle gracefully
-      if (msg->Is(Message::kKeepAlive)) {
-        msg = get_msg();
-        continue;
-      }
-      if (!msg->Is(Message::kEntryAssign)) {
-        // unexpected message
-        DEBUG0(
-            "server: received message ({}) other than entry assignment during "
-            "initial handshake",
-            msg->type());
-        return false;
-      }
-      incoming.push_back(msg);
-      // get the next message (blocks)
-      msg = get_msg();
-    }
-    for (auto& msg : incoming) {
-      m_storage.ProcessIncoming(msg, &conn, std::weak_ptr<NetworkConnection>());
-    }
-  }
-
-  INFO("server: client CONNECTED: {} port {}", conn.stream().getPeerIP(),
-       conn.stream().getPeerPort());
-  return true;
-}
-
-void DispatcherBase::ClientReconnect(unsigned int proto_rev) {
-  if ((m_networkMode & NT_NET_MODE_SERVER) != 0) {
-    return;
-  }
-  {
-    std::scoped_lock lock(m_user_mutex);
-    m_reconnect_proto_rev = proto_rev;
-    m_do_reconnect = true;
-  }
-  m_reconnect_cv.notify_one();
-}
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/Dispatcher.h b/third_party/allwpilib/ntcore/src/main/native/cpp/Dispatcher.h
deleted file mode 100644
index 51b8ec7..0000000
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/Dispatcher.h
+++ /dev/null
@@ -1,149 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef NTCORE_DISPATCHER_H_
-#define NTCORE_DISPATCHER_H_
-
-#include <atomic>
-#include <functional>
-#include <memory>
-#include <string>
-#include <string_view>
-#include <thread>
-#include <utility>
-#include <vector>
-
-#include <wpi/condition_variable.h>
-#include <wpi/mutex.h>
-#include <wpi/span.h>
-
-#include "IDispatcher.h"
-#include "INetworkConnection.h"
-
-namespace wpi {
-class Logger;
-class NetworkAcceptor;
-class NetworkStream;
-}  // namespace wpi
-
-namespace nt {
-
-class IConnectionNotifier;
-class IStorage;
-class NetworkConnection;
-
-class DispatcherBase : public IDispatcher {
-  friend class DispatcherTest;
-
- public:
-  using Connector = std::function<std::unique_ptr<wpi::NetworkStream>()>;
-
-  DispatcherBase(IStorage& storage, IConnectionNotifier& notifier,
-                 wpi::Logger& logger);
-  ~DispatcherBase() override;
-
-  unsigned int GetNetworkMode() const;
-  void StartLocal();
-  void StartServer(std::string_view persist_filename,
-                   std::unique_ptr<wpi::NetworkAcceptor> acceptor);
-  void StartClient();
-  void Stop();
-  void SetUpdateRate(double interval);
-  void SetIdentity(std::string_view name);
-  void Flush();
-  std::vector<ConnectionInfo> GetConnections() const;
-  bool IsConnected() const;
-
-  unsigned int AddListener(
-      std::function<void(const ConnectionNotification& event)> callback,
-      bool immediate_notify) const;
-  unsigned int AddPolledListener(unsigned int poller_uid,
-                                 bool immediate_notify) const;
-
-  void SetConnector(Connector connector);
-  void SetConnectorOverride(Connector connector);
-  void ClearConnectorOverride();
-
-  bool active() const { return m_active; }
-
-  DispatcherBase(const DispatcherBase&) = delete;
-  DispatcherBase& operator=(const DispatcherBase&) = delete;
-
- private:
-  void DispatchThreadMain();
-  void ServerThreadMain();
-  void ClientThreadMain();
-
-  bool ClientHandshake(
-      NetworkConnection& conn,
-      std::function<std::shared_ptr<Message>()> get_msg,
-      std::function<void(wpi::span<std::shared_ptr<Message>>)> send_msgs);
-  bool ServerHandshake(
-      NetworkConnection& conn,
-      std::function<std::shared_ptr<Message>()> get_msg,
-      std::function<void(wpi::span<std::shared_ptr<Message>>)> send_msgs);
-
-  void ClientReconnect(unsigned int proto_rev = 0x0300);
-
-  void QueueOutgoing(std::shared_ptr<Message> msg, INetworkConnection* only,
-                     INetworkConnection* except) override;
-
-  IStorage& m_storage;
-  IConnectionNotifier& m_notifier;
-  unsigned int m_networkMode = NT_NET_MODE_NONE;
-  std::string m_persist_filename;
-  std::thread m_dispatch_thread;
-  std::thread m_clientserver_thread;
-
-  std::unique_ptr<wpi::NetworkAcceptor> m_server_acceptor;
-  Connector m_client_connector_override;
-  Connector m_client_connector;
-  uint8_t m_connections_uid = 0;
-
-  // Mutex for user-accessible items
-  mutable wpi::mutex m_user_mutex;
-  std::vector<std::shared_ptr<INetworkConnection>> m_connections;
-  std::string m_identity;
-
-  std::atomic_bool m_active;       // set to false to terminate threads
-  std::atomic_uint m_update_rate;  // periodic dispatch update rate, in ms
-
-  // Condition variable for forced dispatch wakeup (flush)
-  wpi::mutex m_flush_mutex;
-  wpi::condition_variable m_flush_cv;
-  uint64_t m_last_flush = 0;
-  bool m_do_flush = false;
-
-  // Condition variable for client reconnect (uses user mutex)
-  wpi::condition_variable m_reconnect_cv;
-  unsigned int m_reconnect_proto_rev = 0x0300;
-  bool m_do_reconnect = true;
-
- protected:
-  wpi::Logger& m_logger;
-};
-
-class Dispatcher : public DispatcherBase {
-  friend class DispatcherTest;
-
- public:
-  Dispatcher(IStorage& storage, IConnectionNotifier& notifier,
-             wpi::Logger& logger)
-      : DispatcherBase(storage, notifier, logger) {}
-
-  void StartServer(std::string_view persist_filename,
-                   const char* listen_address, unsigned int port);
-
-  void SetServer(const char* server_name, unsigned int port);
-  void SetServer(
-      wpi::span<const std::pair<std::string_view, unsigned int>> servers);
-  void SetServerTeam(unsigned int team, unsigned int port);
-
-  void SetServerOverride(const char* server_name, unsigned int port);
-  void ClearServerOverride();
-};
-
-}  // namespace nt
-
-#endif  // NTCORE_DISPATCHER_H_
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/DsClient.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/DsClient.cpp
deleted file mode 100644
index 9ed1850..0000000
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/DsClient.cpp
+++ /dev/null
@@ -1,177 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "DsClient.h"
-
-#include <wpi/SmallString.h>
-#include <wpi/StringExtras.h>
-#include <wpi/TCPConnector.h>
-#include <wpi/raw_ostream.h>
-#include <wpi/raw_socket_istream.h>
-
-#include "Dispatcher.h"
-#include "Log.h"
-
-using namespace nt;
-
-class DsClient::Thread : public wpi::SafeThread {
- public:
-  Thread(Dispatcher& dispatcher, wpi::Logger& logger, unsigned int port)
-      : m_dispatcher(dispatcher), m_logger(logger), m_port(port) {}
-
-  void Main() override;
-
-  Dispatcher& m_dispatcher;
-  wpi::Logger& m_logger;
-  unsigned int m_port;
-  std::unique_ptr<wpi::NetworkStream> m_stream;
-};
-
-DsClient::DsClient(Dispatcher& dispatcher, wpi::Logger& logger)
-    : m_dispatcher(dispatcher), m_logger(logger) {}
-
-void DsClient::Start(unsigned int port) {
-  auto thr = m_owner.GetThread();
-  if (!thr) {
-    m_owner.Start(m_dispatcher, m_logger, port);
-  } else {
-    thr->m_port = port;
-  }
-}
-
-void DsClient::Stop() {
-  {
-    // Close the stream so the read (if any) terminates.
-    auto thr = m_owner.GetThread();
-    if (thr) {
-      thr->m_active = false;
-      if (thr->m_stream) {
-        thr->m_stream->close();
-      }
-    }
-  }
-  m_owner.Stop();
-}
-
-void DsClient::Thread::Main() {
-  unsigned int oldip = 0;
-  wpi::Logger nolog;  // to silence log messages from TCPConnector
-
-  while (m_active) {
-    // wait for periodic reconnect or termination
-    auto timeout_time =
-        std::chrono::steady_clock::now() + std::chrono::milliseconds(500);
-    unsigned int port;
-    {
-      std::unique_lock lock(m_mutex);
-      m_cond.wait_until(lock, timeout_time, [&] { return !m_active; });
-      port = m_port;
-    }
-    if (!m_active) {
-      goto done;
-    }
-
-    // Try to connect to DS on the local machine
-    m_stream = wpi::TCPConnector::connect("127.0.0.1", 1742, nolog, 1);
-    if (!m_active) {
-      goto done;
-    }
-    if (!m_stream) {
-      continue;
-    }
-
-    DEBUG3("{}", "connected to DS");
-    wpi::raw_socket_istream is(*m_stream);
-
-    while (m_active && !is.has_error()) {
-      // Read JSON "{...}".  This is very limited, does not handle quoted "}" or
-      // nested {}, but is sufficient for this purpose.
-      wpi::SmallString<128> json;
-      char ch;
-
-      // Throw away characters until {
-      do {
-        is.read(ch);
-        if (is.has_error()) {
-          break;
-        }
-        if (!m_active) {
-          goto done;
-        }
-      } while (ch != '{');
-      json += '{';
-
-      if (is.has_error()) {
-        m_stream = nullptr;
-        break;
-      }
-
-      // Read characters until }
-      do {
-        is.read(ch);
-        if (is.has_error()) {
-          break;
-        }
-        if (!m_active) {
-          goto done;
-        }
-        json += ch;
-      } while (ch != '}');
-
-      if (is.has_error()) {
-        m_stream = nullptr;
-        break;
-      }
-      DEBUG3("json={}", json);
-
-      // Look for "robotIP":12345, and get 12345 portion
-      size_t pos = json.find("\"robotIP\"");
-      if (pos == std::string_view::npos) {
-        continue;  // could not find?
-      }
-      pos += 9;
-      pos = json.find(':', pos);
-      if (pos == std::string_view::npos) {
-        continue;  // could not find?
-      }
-      size_t endpos = json.find_first_not_of("0123456789", pos + 1);
-      DEBUG3("found robotIP={}", wpi::slice(json, pos + 1, endpos));
-
-      // Parse into number
-      unsigned int ip = 0;
-      if (auto v = wpi::parse_integer<unsigned int>(
-              wpi::slice(json, pos + 1, endpos), 10)) {
-        ip = v.value();
-      } else {
-        continue;  // error
-      }
-
-      // If zero, clear the server override
-      if (ip == 0) {
-        m_dispatcher.ClearServerOverride();
-        oldip = 0;
-        continue;
-      }
-
-      // If unchanged, don't reconnect
-      if (ip == oldip) {
-        continue;
-      }
-      oldip = ip;
-
-      // Convert number into dotted quad
-      auto newip = fmt::format("{}.{}.{}.{}", (ip >> 24) & 0xff,
-                               (ip >> 16) & 0xff, (ip >> 8) & 0xff, ip & 0xff);
-      INFO("client: DS overriding server IP to {}", newip);
-      m_dispatcher.SetServerOverride(newip.c_str(), port);
-    }
-
-    // We disconnected from the DS, clear the server override
-    m_dispatcher.ClearServerOverride();
-    oldip = 0;
-  }
-
-done:
-  m_dispatcher.ClearServerOverride();
-}
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/DsClient.h b/third_party/allwpilib/ntcore/src/main/native/cpp/DsClient.h
deleted file mode 100644
index 73fc3d3..0000000
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/DsClient.h
+++ /dev/null
@@ -1,33 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef NTCORE_DSCLIENT_H_
-#define NTCORE_DSCLIENT_H_
-
-#include <wpi/SafeThread.h>
-
-#include "Log.h"
-
-namespace nt {
-
-class Dispatcher;
-
-class DsClient {
- public:
-  DsClient(Dispatcher& dispatcher, wpi::Logger& logger);
-  ~DsClient() = default;
-
-  void Start(unsigned int port);
-  void Stop();
-
- private:
-  class Thread;
-  wpi::SafeThreadOwner<Thread> m_owner;
-  Dispatcher& m_dispatcher;
-  wpi::Logger& m_logger;
-};
-
-}  // namespace nt
-
-#endif  // NTCORE_DSCLIENT_H_
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/EntryNotifier.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/EntryNotifier.cpp
deleted file mode 100644
index 6f251a3..0000000
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/EntryNotifier.cpp
+++ /dev/null
@@ -1,109 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "EntryNotifier.h"
-
-#include <wpi/StringExtras.h>
-
-#include "Log.h"
-
-using namespace nt;
-
-EntryNotifier::EntryNotifier(int inst, wpi::Logger& logger)
-    : m_inst(inst), m_logger(logger) {
-  m_local_notifiers = false;
-}
-
-void EntryNotifier::Start() {
-  DoStart(m_inst);
-}
-
-bool EntryNotifier::local_notifiers() const {
-  return m_local_notifiers;
-}
-
-bool impl::EntryNotifierThread::Matches(const EntryListenerData& listener,
-                                        const EntryNotification& data) {
-  if (!data.value) {
-    return false;
-  }
-
-  // Flags must be within requested flag set for this listener.
-  // Because assign messages can result in both a value and flags update,
-  // we handle that case specially.
-  unsigned int listen_flags =
-      listener.flags & ~(NT_NOTIFY_IMMEDIATE | NT_NOTIFY_LOCAL);
-  unsigned int flags = data.flags & ~(NT_NOTIFY_IMMEDIATE | NT_NOTIFY_LOCAL);
-  unsigned int assign_both = NT_NOTIFY_UPDATE | NT_NOTIFY_FLAGS;
-  if ((flags & assign_both) == assign_both) {
-    if ((listen_flags & assign_both) == 0) {
-      return false;
-    }
-    listen_flags &= ~assign_both;
-    flags &= ~assign_both;
-  }
-  if ((flags & ~listen_flags) != 0) {
-    return false;
-  }
-
-  // must match local id or prefix
-  if (listener.entry != 0 && data.entry != listener.entry) {
-    return false;
-  }
-  if (listener.entry == 0 && !wpi::starts_with(data.name, listener.prefix)) {
-    return false;
-  }
-
-  return true;
-}
-
-unsigned int EntryNotifier::Add(
-    std::function<void(const EntryNotification& event)> callback,
-    std::string_view prefix, unsigned int flags) {
-  if ((flags & NT_NOTIFY_LOCAL) != 0) {
-    m_local_notifiers = true;
-  }
-  return DoAdd(callback, prefix, flags);
-}
-
-unsigned int EntryNotifier::Add(
-    std::function<void(const EntryNotification& event)> callback,
-    unsigned int local_id, unsigned int flags) {
-  if ((flags & NT_NOTIFY_LOCAL) != 0) {
-    m_local_notifiers = true;
-  }
-  return DoAdd(callback, Handle(m_inst, local_id, Handle::kEntry), flags);
-}
-
-unsigned int EntryNotifier::AddPolled(unsigned int poller_uid,
-                                      std::string_view prefix,
-                                      unsigned int flags) {
-  if ((flags & NT_NOTIFY_LOCAL) != 0) {
-    m_local_notifiers = true;
-  }
-  return DoAdd(poller_uid, prefix, flags);
-}
-
-unsigned int EntryNotifier::AddPolled(unsigned int poller_uid,
-                                      unsigned int local_id,
-                                      unsigned int flags) {
-  if ((flags & NT_NOTIFY_LOCAL) != 0) {
-    m_local_notifiers = true;
-  }
-  return DoAdd(poller_uid, Handle(m_inst, local_id, Handle::kEntry), flags);
-}
-
-void EntryNotifier::NotifyEntry(unsigned int local_id, std::string_view name,
-                                std::shared_ptr<Value> value,
-                                unsigned int flags,
-                                unsigned int only_listener) {
-  // optimization: don't generate needless local queue entries if we have
-  // no local listeners (as this is a common case on the server side)
-  if ((flags & NT_NOTIFY_LOCAL) != 0 && !m_local_notifiers) {
-    return;
-  }
-  DEBUG0("notifying '{}' (local={}), flags={}", name, local_id, flags);
-  Send(only_listener, 0, Handle(m_inst, local_id, Handle::kEntry).handle(),
-       name, value, flags);
-}
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/EntryNotifier.h b/third_party/allwpilib/ntcore/src/main/native/cpp/EntryNotifier.h
deleted file mode 100644
index bbe2172..0000000
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/EntryNotifier.h
+++ /dev/null
@@ -1,112 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef NTCORE_ENTRYNOTIFIER_H_
-#define NTCORE_ENTRYNOTIFIER_H_
-
-#include <atomic>
-#include <memory>
-#include <string>
-#include <string_view>
-#include <utility>
-
-#include <wpi/CallbackManager.h>
-
-#include "Handle.h"
-#include "IEntryNotifier.h"
-#include "ntcore_cpp.h"
-
-namespace wpi {
-class Logger;
-}  // namespace wpi
-
-namespace nt {
-
-namespace impl {
-
-struct EntryListenerData
-    : public wpi::CallbackListenerData<
-          std::function<void(const EntryNotification& event)>> {
-  EntryListenerData() = default;
-  EntryListenerData(
-      std::function<void(const EntryNotification& event)> callback_,
-      std::string_view prefix_, unsigned int flags_)
-      : CallbackListenerData(callback_), prefix(prefix_), flags(flags_) {}
-  EntryListenerData(
-      std::function<void(const EntryNotification& event)> callback_,
-      NT_Entry entry_, unsigned int flags_)
-      : CallbackListenerData(callback_), entry(entry_), flags(flags_) {}
-  EntryListenerData(unsigned int poller_uid_, std::string_view prefix_,
-                    unsigned int flags_)
-      : CallbackListenerData(poller_uid_), prefix(prefix_), flags(flags_) {}
-  EntryListenerData(unsigned int poller_uid_, NT_Entry entry_,
-                    unsigned int flags_)
-      : CallbackListenerData(poller_uid_), entry(entry_), flags(flags_) {}
-
-  std::string prefix;
-  NT_Entry entry = 0;
-  unsigned int flags;
-};
-
-class EntryNotifierThread
-    : public wpi::CallbackThread<EntryNotifierThread, EntryNotification,
-                                 EntryListenerData> {
- public:
-  EntryNotifierThread(std::function<void()> on_start,
-                      std::function<void()> on_exit, int inst)
-      : CallbackThread(std::move(on_start), std::move(on_exit)), m_inst(inst) {}
-
-  bool Matches(const EntryListenerData& listener,
-               const EntryNotification& data);
-
-  void SetListener(EntryNotification* data, unsigned int listener_uid) {
-    data->listener =
-        Handle(m_inst, listener_uid, Handle::kEntryListener).handle();
-  }
-
-  void DoCallback(std::function<void(const EntryNotification& event)> callback,
-                  const EntryNotification& data) {
-    callback(data);
-  }
-
-  int m_inst;
-};
-
-}  // namespace impl
-
-class EntryNotifier
-    : public IEntryNotifier,
-      public wpi::CallbackManager<EntryNotifier, impl::EntryNotifierThread> {
-  friend class EntryNotifierTest;
-  friend class wpi::CallbackManager<EntryNotifier, impl::EntryNotifierThread>;
-
- public:
-  explicit EntryNotifier(int inst, wpi::Logger& logger);
-
-  void Start();
-
-  bool local_notifiers() const override;
-
-  unsigned int Add(std::function<void(const EntryNotification& event)> callback,
-                   std::string_view prefix, unsigned int flags) override;
-  unsigned int Add(std::function<void(const EntryNotification& event)> callback,
-                   unsigned int local_id, unsigned int flags) override;
-  unsigned int AddPolled(unsigned int poller_uid, std::string_view prefix,
-                         unsigned int flags) override;
-  unsigned int AddPolled(unsigned int poller_uid, unsigned int local_id,
-                         unsigned int flags) override;
-
-  void NotifyEntry(unsigned int local_id, std::string_view name,
-                   std::shared_ptr<Value> value, unsigned int flags,
-                   unsigned int only_listener = UINT_MAX) override;
-
- private:
-  int m_inst;
-  wpi::Logger& m_logger;
-  std::atomic_bool m_local_notifiers;
-};
-
-}  // namespace nt
-
-#endif  // NTCORE_ENTRYNOTIFIER_H_
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/Handle.h b/third_party/allwpilib/ntcore/src/main/native/cpp/Handle.h
index df12381..0eb9041 100644
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/Handle.h
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/Handle.h
@@ -2,8 +2,7 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
-#ifndef NTCORE_HANDLE_H_
-#define NTCORE_HANDLE_H_
+#pragma once
 
 #include <wpi/Synchronization.h>
 
@@ -19,17 +18,19 @@
 class Handle {
  public:
   enum Type {
-    kConnectionListener = wpi::kHandleTypeNTBase,
-    kConnectionListenerPoller,
+    kListener = wpi::kHandleTypeNTBase,
+    kListenerPoller,
     kEntry,
-    kEntryListener,
-    kEntryListenerPoller,
     kInstance,
-    kLogger,
-    kLoggerPoller,
-    kRpcCall,
-    kRpcCallPoller
+    kDataLogger,
+    kConnectionDataLogger,
+    kMultiSubscriber,
+    kTopic,
+    kSubscriber,
+    kPublisher,
+    kTypeMax
   };
+  static_assert(kTypeMax <= wpi::kHandleTypeHALBase);
   enum { kIndexMax = 0xfffff };
 
   explicit Handle(NT_Handle handle) : m_handle(handle) {}
@@ -46,7 +47,9 @@
                (index & 0xfffff);
   }
 
-  int GetIndex() const { return static_cast<int>(m_handle) & 0xfffff; }
+  unsigned int GetIndex() const {
+    return static_cast<unsigned int>(m_handle) & 0xfffff;
+  }
   Type GetType() const {
     return static_cast<Type>((static_cast<int>(m_handle) >> 24) & 0x7f);
   }
@@ -60,5 +63,3 @@
 };
 
 }  // namespace nt
-
-#endif  // NTCORE_HANDLE_H_
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/HandleMap.h b/third_party/allwpilib/ntcore/src/main/native/cpp/HandleMap.h
new file mode 100644
index 0000000..03e73f9
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/HandleMap.h
@@ -0,0 +1,54 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <memory>
+#include <utility>
+
+#include <wpi/UidVector.h>
+
+#include "Handle.h"
+
+namespace nt {
+
+// Utility wrapper class for our UidVectors
+template <typename T, size_t Size>
+class HandleMap : public wpi::UidVector<std::unique_ptr<T>, Size> {
+ public:
+  template <typename... Args>
+  T* Add(int inst, Args&&... args) {
+    auto i = this->emplace_back();
+    auto& it = (*this)[i];
+    it = std::make_unique<T>(Handle(inst, i, T::kType),
+                             std::forward<Args>(args)...);
+    return it.get();
+  }
+
+  std::unique_ptr<T> Remove(NT_Handle handle) {
+    Handle h{handle};
+    if (!h.IsType(T::kType)) {
+      return {};
+    }
+    unsigned int i = h.GetIndex();
+    if (i >= this->size()) {
+      return {};
+    }
+    return this->erase(i);
+  }
+
+  T* Get(NT_Handle handle) {
+    Handle h{handle};
+    if (!h.IsType(T::kType)) {
+      return {};
+    }
+    unsigned int i = h.GetIndex();
+    if (i >= this->size()) {
+      return {};
+    }
+    return (*this)[i].get();
+  }
+};
+
+}  // namespace nt
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/IConnectionList.h b/third_party/allwpilib/ntcore/src/main/native/cpp/IConnectionList.h
new file mode 100644
index 0000000..a4a59e3
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/IConnectionList.h
@@ -0,0 +1,24 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <vector>
+
+#include "ntcore_cpp.h"
+
+namespace nt {
+
+class IConnectionList {
+ public:
+  virtual ~IConnectionList() = default;
+
+  virtual int AddConnection(const ConnectionInfo& info) = 0;
+  virtual void RemoveConnection(int handle) = 0;
+  virtual void ClearConnections() = 0;
+  virtual std::vector<ConnectionInfo> GetConnections() const = 0;
+  virtual bool IsConnected() const = 0;
+};
+
+}  // namespace nt
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/IConnectionNotifier.h b/third_party/allwpilib/ntcore/src/main/native/cpp/IConnectionNotifier.h
deleted file mode 100644
index 5983866..0000000
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/IConnectionNotifier.h
+++ /dev/null
@@ -1,29 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef NTCORE_ICONNECTIONNOTIFIER_H_
-#define NTCORE_ICONNECTIONNOTIFIER_H_
-
-#include <climits>
-
-#include "ntcore_cpp.h"
-
-namespace nt {
-
-class IConnectionNotifier {
- public:
-  IConnectionNotifier() = default;
-  IConnectionNotifier(const IConnectionNotifier&) = delete;
-  IConnectionNotifier& operator=(const IConnectionNotifier&) = delete;
-  virtual ~IConnectionNotifier() = default;
-  virtual unsigned int Add(
-      std::function<void(const ConnectionNotification& event)> callback) = 0;
-  virtual unsigned int AddPolled(unsigned int poller_uid) = 0;
-  virtual void NotifyConnection(bool connected, const ConnectionInfo& conn_info,
-                                unsigned int only_listener = UINT_MAX) = 0;
-};
-
-}  // namespace nt
-
-#endif  // NTCORE_ICONNECTIONNOTIFIER_H_
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/IDispatcher.h b/third_party/allwpilib/ntcore/src/main/native/cpp/IDispatcher.h
deleted file mode 100644
index 4cf8a5f..0000000
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/IDispatcher.h
+++ /dev/null
@@ -1,31 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef NTCORE_IDISPATCHER_H_
-#define NTCORE_IDISPATCHER_H_
-
-#include <memory>
-
-#include "Message.h"
-
-namespace nt {
-
-class INetworkConnection;
-
-// Interface for generation of outgoing messages to break a dependency loop
-// between Storage and Dispatcher.
-class IDispatcher {
- public:
-  IDispatcher() = default;
-  IDispatcher(const IDispatcher&) = delete;
-  IDispatcher& operator=(const IDispatcher&) = delete;
-  virtual ~IDispatcher() = default;
-  virtual void QueueOutgoing(std::shared_ptr<Message> msg,
-                             INetworkConnection* only,
-                             INetworkConnection* except) = 0;
-};
-
-}  // namespace nt
-
-#endif  // NTCORE_IDISPATCHER_H_
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/IEntryNotifier.h b/third_party/allwpilib/ntcore/src/main/native/cpp/IEntryNotifier.h
deleted file mode 100644
index b3f91b2..0000000
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/IEntryNotifier.h
+++ /dev/null
@@ -1,43 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef NTCORE_IENTRYNOTIFIER_H_
-#define NTCORE_IENTRYNOTIFIER_H_
-
-#include <climits>
-#include <memory>
-#include <string_view>
-
-#include "ntcore_cpp.h"
-
-namespace nt {
-
-class IEntryNotifier {
- public:
-  IEntryNotifier() = default;
-  IEntryNotifier(const IEntryNotifier&) = delete;
-  IEntryNotifier& operator=(const IEntryNotifier&) = delete;
-  virtual ~IEntryNotifier() = default;
-  virtual bool local_notifiers() const = 0;
-
-  virtual unsigned int Add(
-      std::function<void(const EntryNotification& event)> callback,
-      std::string_view prefix, unsigned int flags) = 0;
-  virtual unsigned int Add(
-      std::function<void(const EntryNotification& event)> callback,
-      unsigned int local_id, unsigned int flags) = 0;
-  virtual unsigned int AddPolled(unsigned int poller_uid,
-                                 std::string_view prefix,
-                                 unsigned int flags) = 0;
-  virtual unsigned int AddPolled(unsigned int poller_uid, unsigned int local_id,
-                                 unsigned int flags) = 0;
-
-  virtual void NotifyEntry(unsigned int local_id, std::string_view name,
-                           std::shared_ptr<Value> value, unsigned int flags,
-                           unsigned int only_listener = UINT_MAX) = 0;
-};
-
-}  // namespace nt
-
-#endif  // NTCORE_IENTRYNOTIFIER_H_
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/IListenerStorage.h b/third_party/allwpilib/ntcore/src/main/native/cpp/IListenerStorage.h
new file mode 100644
index 0000000..82d7432
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/IListenerStorage.h
@@ -0,0 +1,52 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <functional>
+#include <memory>
+#include <span>
+#include <string_view>
+
+#include "ntcore_cpp.h"
+
+namespace nt {
+
+class IListenerStorage {
+ public:
+  // Return false if event should not be issued (final check).
+  // This is called only during Notify() processing.
+  using FinishEventFunc = std::function<bool(unsigned int mask, Event* event)>;
+
+  virtual ~IListenerStorage() = default;
+
+  virtual void Activate(NT_Listener listener, unsigned int mask,
+                        FinishEventFunc finishEvent = {}) = 0;
+
+  // If handles is not empty, notifies ONLY those listeners
+  virtual void Notify(std::span<const NT_Listener> handles, unsigned int flags,
+                      std::span<ConnectionInfo const* const> infos) = 0;
+  virtual void Notify(std::span<const NT_Listener> handles, unsigned int flags,
+                      std::span<const TopicInfo> infos) = 0;
+  virtual void Notify(std::span<const NT_Listener> handles, unsigned int flags,
+                      NT_Topic topic, NT_Handle subentry,
+                      const Value& value) = 0;
+  virtual void Notify(unsigned int flags, unsigned int level,
+                      std::string_view filename, unsigned int line,
+                      std::string_view message) = 0;
+  virtual void NotifyTimeSync(std::span<const NT_Listener> handles,
+                              unsigned int flags, int64_t serverTimeOffset,
+                              int64_t rtt2, bool valid) = 0;
+
+  void Notify(std::span<const NT_Listener> handles, unsigned int flags,
+              const ConnectionInfo* info) {
+    Notify(handles, flags, {&info, 1});
+  }
+  void Notify(std::span<const NT_Listener> handles, unsigned int flags,
+              const TopicInfo& info) {
+    Notify(handles, flags, {&info, 1});
+  }
+};
+
+}  // namespace nt
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/INetworkClient.h b/third_party/allwpilib/ntcore/src/main/native/cpp/INetworkClient.h
new file mode 100644
index 0000000..986f43a
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/INetworkClient.h
@@ -0,0 +1,29 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <span>
+#include <string>
+#include <utility>
+
+#include "ntcore_cpp.h"
+
+namespace nt {
+
+class INetworkClient {
+ public:
+  virtual ~INetworkClient() = default;
+
+  virtual void SetServers(
+      std::span<const std::pair<std::string, unsigned int>> servers) = 0;
+
+  virtual void StartDSClient(unsigned int port) = 0;
+  virtual void StopDSClient() = 0;
+
+  virtual void FlushLocal() = 0;
+  virtual void Flush() = 0;
+};
+
+}  // namespace nt
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/INetworkConnection.h b/third_party/allwpilib/ntcore/src/main/native/cpp/INetworkConnection.h
deleted file mode 100644
index 94e9bb1..0000000
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/INetworkConnection.h
+++ /dev/null
@@ -1,38 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef NTCORE_INETWORKCONNECTION_H_
-#define NTCORE_INETWORKCONNECTION_H_
-
-#include <memory>
-
-#include "Message.h"
-#include "ntcore_cpp.h"
-
-namespace nt {
-
-class INetworkConnection {
- public:
-  enum State { kCreated, kInit, kHandshake, kSynchronized, kActive, kDead };
-
-  INetworkConnection() = default;
-  INetworkConnection(const INetworkConnection&) = delete;
-  INetworkConnection& operator=(const INetworkConnection&) = delete;
-  virtual ~INetworkConnection() = default;
-
-  virtual ConnectionInfo info() const = 0;
-
-  virtual void QueueOutgoing(std::shared_ptr<Message> msg) = 0;
-  virtual void PostOutgoing(bool keep_alive) = 0;
-
-  virtual unsigned int proto_rev() const = 0;
-  virtual void set_proto_rev(unsigned int proto_rev) = 0;
-
-  virtual State state() const = 0;
-  virtual void set_state(State state) = 0;
-};
-
-}  // namespace nt
-
-#endif  // NTCORE_INETWORKCONNECTION_H_
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/IRpcServer.h b/third_party/allwpilib/ntcore/src/main/native/cpp/IRpcServer.h
deleted file mode 100644
index aa16084..0000000
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/IRpcServer.h
+++ /dev/null
@@ -1,36 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef NTCORE_IRPCSERVER_H_
-#define NTCORE_IRPCSERVER_H_
-
-#include <memory>
-#include <string_view>
-
-#include "Message.h"
-#include "ntcore_cpp.h"
-
-namespace nt {
-
-class IRpcServer {
- public:
-  using SendResponseFunc = std::function<void(std::string_view result)>;
-
-  IRpcServer() = default;
-  IRpcServer(const IRpcServer&) = delete;
-  IRpcServer& operator=(const IRpcServer&) = delete;
-  virtual ~IRpcServer() = default;
-
-  virtual void RemoveRpc(unsigned int rpc_uid) = 0;
-
-  virtual void ProcessRpc(unsigned int local_id, unsigned int call_uid,
-                          std::string_view name, std::string_view params,
-                          const ConnectionInfo& conn,
-                          SendResponseFunc send_response,
-                          unsigned int rpc_uid) = 0;
-};
-
-}  // namespace nt
-
-#endif  // NTCORE_IRPCSERVER_H_
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/IStorage.h b/third_party/allwpilib/ntcore/src/main/native/cpp/IStorage.h
deleted file mode 100644
index 795d032..0000000
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/IStorage.h
+++ /dev/null
@@ -1,62 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef NTCORE_ISTORAGE_H_
-#define NTCORE_ISTORAGE_H_
-
-#include <functional>
-#include <memory>
-#include <string_view>
-#include <vector>
-
-#include <wpi/span.h>
-
-#include "Message.h"
-#include "ntcore_cpp.h"
-
-namespace nt {
-
-class IDispatcher;
-class INetworkConnection;
-
-class IStorage {
- public:
-  IStorage() = default;
-  IStorage(const IStorage&) = delete;
-  IStorage& operator=(const IStorage&) = delete;
-  virtual ~IStorage() = default;
-
-  // Accessors required by Dispatcher.  An interface is used for
-  // generation of outgoing messages to break a dependency loop between
-  // Storage and Dispatcher.
-  virtual void SetDispatcher(IDispatcher* dispatcher, bool server) = 0;
-  virtual void ClearDispatcher() = 0;
-
-  // Required for wire protocol 2.0 to get the entry type of an entry when
-  // receiving entry updates (because the length/type is not provided in the
-  // message itself).  Not used in wire protocol 3.0.
-  virtual NT_Type GetMessageEntryType(unsigned int id) const = 0;
-
-  virtual void ProcessIncoming(std::shared_ptr<Message> msg,
-                               INetworkConnection* conn,
-                               std::weak_ptr<INetworkConnection> conn_weak) = 0;
-  virtual void GetInitialAssignments(
-      INetworkConnection& conn,
-      std::vector<std::shared_ptr<Message>>* msgs) = 0;
-  virtual void ApplyInitialAssignments(
-      INetworkConnection& conn, wpi::span<std::shared_ptr<Message>> msgs,
-      bool new_server, std::vector<std::shared_ptr<Message>>* out_msgs) = 0;
-
-  // Filename-based save/load functions.  Used both by periodic saves and
-  // accessible directly via the user API.
-  virtual const char* SavePersistent(std::string_view filename,
-                                     bool periodic) const = 0;
-  virtual const char* LoadPersistent(
-      std::string_view filename,
-      std::function<void(size_t line, const char* msg)> warn) = 0;
-};
-
-}  // namespace nt
-
-#endif  // NTCORE_ISTORAGE_H_
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/InstanceImpl.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/InstanceImpl.cpp
index 8d59a0b..b34db73 100644
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/InstanceImpl.cpp
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/InstanceImpl.cpp
@@ -13,22 +13,16 @@
 using namespace std::placeholders;
 
 InstanceImpl::InstanceImpl(int inst)
-    : logger_impl(inst),
-      logger(
-          std::bind(&LoggerImpl::Log, &logger_impl, _1, _2, _3, _4)),  // NOLINT
-      connection_notifier(inst),
-      entry_notifier(inst, logger),
-      rpc_server(inst, logger),
-      storage(entry_notifier, rpc_server, logger),
-      dispatcher(storage, connection_notifier, logger),
-      ds_client(dispatcher, logger) {
+    : listenerStorage{inst},
+      logger_impl{listenerStorage},
+      logger{
+          std::bind(&LoggerImpl::Log, &logger_impl, _1, _2, _3, _4)},  // NOLINT
+      connectionList{inst, listenerStorage},
+      localStorage{inst, listenerStorage, logger},
+      m_inst{inst} {
   logger.set_min_level(logger_impl.GetMinLevel());
 }
 
-InstanceImpl::~InstanceImpl() {
-  logger.SetLogger(nullptr);
-}
-
 InstanceImpl* InstanceImpl::GetDefault() {
   return Get(GetDefaultIndex());
 }
@@ -83,7 +77,164 @@
     return;
   }
 
-  InstanceImpl* ptr = nullptr;
-  s_instances[inst].exchange(ptr);
-  delete ptr;
+  delete s_instances[inst].exchange(nullptr);
+}
+
+void InstanceImpl::StartLocal() {
+  std::scoped_lock lock{m_mutex};
+  if (networkMode != NT_NET_MODE_NONE) {
+    return;
+  }
+  networkMode = NT_NET_MODE_LOCAL;
+}
+
+void InstanceImpl::StopLocal() {
+  std::scoped_lock lock{m_mutex};
+  if ((networkMode & NT_NET_MODE_LOCAL) == 0) {
+    return;
+  }
+  networkMode = NT_NET_MODE_NONE;
+}
+
+void InstanceImpl::StartServer(std::string_view persistFilename,
+                               std::string_view listenAddress,
+                               unsigned int port3, unsigned int port4) {
+  std::scoped_lock lock{m_mutex};
+  if (networkMode != NT_NET_MODE_NONE) {
+    return;
+  }
+  m_networkServer = std::make_shared<NetworkServer>(
+      persistFilename, listenAddress, port3, port4, localStorage,
+      connectionList, logger, [this] {
+        std::scoped_lock lock{m_mutex};
+        networkMode &= ~NT_NET_MODE_STARTING;
+      });
+  networkMode = NT_NET_MODE_SERVER | NT_NET_MODE_STARTING;
+  listenerStorage.NotifyTimeSync({}, NT_EVENT_TIMESYNC, 0, 0, true);
+  m_serverTimeOffset = 0;
+  m_rtt2 = 0;
+}
+
+void InstanceImpl::StopServer() {
+  std::shared_ptr<NetworkServer> server;
+  {
+    std::scoped_lock lock{m_mutex};
+    if ((networkMode & NT_NET_MODE_SERVER) == 0) {
+      return;
+    }
+    server = std::move(m_networkServer);
+    networkMode = NT_NET_MODE_NONE;
+    listenerStorage.NotifyTimeSync({}, NT_EVENT_TIMESYNC, 0, 0, false);
+    m_serverTimeOffset.reset();
+    m_rtt2 = 0;
+  }
+}
+
+void InstanceImpl::StartClient3(std::string_view identity) {
+  std::scoped_lock lock{m_mutex};
+  if (networkMode != NT_NET_MODE_NONE) {
+    return;
+  }
+  m_networkClient = std::make_shared<NetworkClient3>(
+      m_inst, identity, localStorage, connectionList, logger);
+  if (!m_servers.empty()) {
+    m_networkClient->SetServers(m_servers);
+  }
+  networkMode = NT_NET_MODE_CLIENT3;
+}
+
+void InstanceImpl::StartClient4(std::string_view identity) {
+  std::scoped_lock lock{m_mutex};
+  if (networkMode != NT_NET_MODE_NONE) {
+    return;
+  }
+  m_networkClient = std::make_shared<NetworkClient>(
+      m_inst, identity, localStorage, connectionList, logger,
+      [this](int64_t serverTimeOffset, int64_t rtt2, bool valid) {
+        std::scoped_lock lock{m_mutex};
+        listenerStorage.NotifyTimeSync({}, NT_EVENT_TIMESYNC, serverTimeOffset,
+                                       rtt2, valid);
+        if (valid) {
+          m_serverTimeOffset = serverTimeOffset;
+          m_rtt2 = rtt2;
+        } else {
+          m_serverTimeOffset.reset();
+          m_rtt2 = 0;
+        }
+      });
+  if (!m_servers.empty()) {
+    m_networkClient->SetServers(m_servers);
+  }
+  networkMode = NT_NET_MODE_CLIENT4;
+}
+
+void InstanceImpl::StopClient() {
+  std::shared_ptr<INetworkClient> client;
+  {
+    std::scoped_lock lock{m_mutex};
+    if ((networkMode & (NT_NET_MODE_CLIENT3 | NT_NET_MODE_CLIENT4)) == 0) {
+      return;
+    }
+    client = std::move(m_networkClient);
+    networkMode = NT_NET_MODE_NONE;
+  }
+  client.reset();
+  {
+    std::scoped_lock lock{m_mutex};
+    listenerStorage.NotifyTimeSync({}, NT_EVENT_TIMESYNC, 0, 0, false);
+    m_serverTimeOffset.reset();
+    m_rtt2 = 0;
+  }
+}
+
+void InstanceImpl::SetServers(
+    std::span<const std::pair<std::string, unsigned int>> servers) {
+  std::scoped_lock lock{m_mutex};
+  m_servers = {servers.begin(), servers.end()};
+  if (m_networkClient) {
+    m_networkClient->SetServers(servers);
+  }
+}
+
+std::shared_ptr<NetworkServer> InstanceImpl::GetServer() {
+  std::scoped_lock lock{m_mutex};
+  return m_networkServer;
+}
+
+std::shared_ptr<INetworkClient> InstanceImpl::GetClient() {
+  std::scoped_lock lock{m_mutex};
+  return m_networkClient;
+}
+
+std::optional<int64_t> InstanceImpl::GetServerTimeOffset() {
+  std::scoped_lock lock{m_mutex};
+  return m_serverTimeOffset;
+}
+
+void InstanceImpl::AddTimeSyncListener(NT_Listener listener,
+                                       unsigned int eventMask) {
+  std::scoped_lock lock{m_mutex};
+  eventMask &= (NT_EVENT_TIMESYNC | NT_EVENT_IMMEDIATE);
+  listenerStorage.Activate(listener, eventMask);
+  if ((eventMask & (NT_EVENT_TIMESYNC | NT_EVENT_IMMEDIATE)) ==
+          (NT_EVENT_TIMESYNC | NT_EVENT_IMMEDIATE) &&
+      m_serverTimeOffset) {
+    listenerStorage.NotifyTimeSync({&listener, 1},
+                                   NT_EVENT_TIMESYNC | NT_EVENT_IMMEDIATE,
+                                   *m_serverTimeOffset, m_rtt2, true);
+  }
+}
+
+void InstanceImpl::Reset() {
+  std::scoped_lock lock{m_mutex};
+  m_networkServer.reset();
+  m_networkClient.reset();
+  m_servers.clear();
+  networkMode = NT_NET_MODE_NONE;
+  m_serverTimeOffset.reset();
+  m_rtt2 = 0;
+
+  listenerStorage.Reset();
+  // connectionList should have been cleared by destroying networkClient/server
+  localStorage.Reset();
 }
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/InstanceImpl.h b/third_party/allwpilib/ntcore/src/main/native/cpp/InstanceImpl.h
index 22d94f5..a7b4742 100644
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/InstanceImpl.h
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/InstanceImpl.h
@@ -2,45 +2,72 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
-#ifndef NTCORE_INSTANCEIMPL_H_
-#define NTCORE_INSTANCEIMPL_H_
+#pragma once
 
 #include <atomic>
 #include <memory>
+#include <optional>
+#include <string>
+#include <string_view>
+#include <utility>
+#include <vector>
 
 #include <wpi/mutex.h>
 
-#include "ConnectionNotifier.h"
-#include "Dispatcher.h"
-#include "DsClient.h"
-#include "EntryNotifier.h"
+#include "ConnectionList.h"
+#include "Handle.h"
+#include "ListenerStorage.h"
+#include "LocalStorage.h"
 #include "Log.h"
 #include "LoggerImpl.h"
-#include "RpcServer.h"
-#include "Storage.h"
+#include "NetworkClient.h"
+#include "NetworkServer.h"
 
 namespace nt {
 
 class InstanceImpl {
  public:
   explicit InstanceImpl(int inst);
-  ~InstanceImpl();
 
   // Instance repository
   static InstanceImpl* GetDefault();
   static InstanceImpl* Get(int inst);
+  static InstanceImpl* GetHandle(NT_Handle handle) {
+    return Get(Handle{handle}.GetInst());
+  }
+  static InstanceImpl* GetTyped(NT_Handle handle, Handle::Type type) {
+    return Get(Handle{handle}.GetTypedInst(type));
+  }
   static int GetDefaultIndex();
   static int Alloc();
   static void Destroy(int inst);
 
+  void StartLocal();
+  void StopLocal();
+  void StartServer(std::string_view persistFilename,
+                   std::string_view listenAddress, unsigned int port3,
+                   unsigned int port4);
+  void StopServer();
+  void StartClient3(std::string_view identity);
+  void StartClient4(std::string_view identity);
+  void StopClient();
+  void SetServers(
+      std::span<const std::pair<std::string, unsigned int>> servers);
+
+  std::shared_ptr<NetworkServer> GetServer();
+  std::shared_ptr<INetworkClient> GetClient();
+
+  std::optional<int64_t> GetServerTimeOffset();
+  void AddTimeSyncListener(NT_Listener listener, unsigned int eventMask);
+
+  void Reset();
+
+  ListenerStorage listenerStorage;
   LoggerImpl logger_impl;
   wpi::Logger logger;
-  ConnectionNotifier connection_notifier;
-  EntryNotifier entry_notifier;
-  RpcServer rpc_server;
-  Storage storage;
-  Dispatcher dispatcher;
-  DsClient ds_client;
+  ConnectionList connectionList;
+  LocalStorage localStorage;
+  std::atomic<int> networkMode{NT_NET_MODE_NONE};
 
  private:
   static int AllocImpl();
@@ -49,8 +76,14 @@
   static constexpr int kNumInstances = 16;
   static std::atomic<InstanceImpl*> s_instances[kNumInstances];
   static wpi::mutex s_mutex;
+
+  wpi::mutex m_mutex;
+  std::shared_ptr<NetworkServer> m_networkServer;
+  std::shared_ptr<INetworkClient> m_networkClient;
+  std::vector<std::pair<std::string, unsigned int>> m_servers;
+  std::optional<int64_t> m_serverTimeOffset;
+  int64_t m_rtt2 = 0;
+  int m_inst;
 };
 
 }  // namespace nt
-
-#endif  // NTCORE_INSTANCEIMPL_H_
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/ListenerStorage.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/ListenerStorage.cpp
new file mode 100644
index 0000000..fdbf03b
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/ListenerStorage.cpp
@@ -0,0 +1,405 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "ListenerStorage.h"
+
+#include <algorithm>
+
+#include <wpi/DenseMap.h>
+#include <wpi/SmallVector.h>
+
+#include "ntcore_c.h"
+
+using namespace nt;
+
+class ListenerStorage::Thread final : public wpi::SafeThreadEvent {
+ public:
+  explicit Thread(NT_ListenerPoller poller) : m_poller{poller} {}
+
+  void Main() final;
+
+  NT_ListenerPoller m_poller;
+  wpi::DenseMap<NT_Listener, ListenerCallback> m_callbacks;
+  wpi::Event m_waitQueueWakeup;
+  wpi::Event m_waitQueueWaiter;
+};
+
+void ListenerStorage::Thread::Main() {
+  while (m_active) {
+    WPI_Handle signaledBuf[3];
+    auto signaled = wpi::WaitForObjects(
+        {m_poller, m_stopEvent.GetHandle(), m_waitQueueWakeup.GetHandle()},
+        signaledBuf);
+    if (signaled.empty() || !m_active) {
+      return;
+    }
+    // call all the way back out to the C++ API to ensure valid handle
+    auto events = nt::ReadListenerQueue(m_poller);
+    if (!events.empty()) {
+      std::unique_lock lock{m_mutex};
+      for (auto&& event : events) {
+        auto callbackIt = m_callbacks.find(event.listener);
+        if (callbackIt != m_callbacks.end()) {
+          auto callback = callbackIt->second;
+          lock.unlock();
+          callback(event);
+          lock.lock();
+        }
+      }
+    }
+    if (std::find(signaled.begin(), signaled.end(),
+                  m_waitQueueWakeup.GetHandle()) != signaled.end()) {
+      m_waitQueueWaiter.Set();
+    }
+  }
+}
+
+ListenerStorage::ListenerStorage(int inst) : m_inst{inst} {}
+
+ListenerStorage::~ListenerStorage() = default;
+
+void ListenerStorage::Activate(NT_Listener listenerHandle, unsigned int mask,
+                               FinishEventFunc finishEvent) {
+  std::scoped_lock lock{m_mutex};
+  if (auto listener = m_listeners.Get(listenerHandle)) {
+    listener->sources.emplace_back(std::move(finishEvent), mask);
+    unsigned int deltaMask = mask & (~listener->eventMask);
+    listener->eventMask |= mask;
+
+    if ((deltaMask & NT_EVENT_CONNECTION) != 0) {
+      m_connListeners.Add(listener);
+    }
+    if ((deltaMask & NT_EVENT_TOPIC) != 0) {
+      m_topicListeners.Add(listener);
+    }
+    if ((deltaMask & NT_EVENT_VALUE_ALL) != 0) {
+      m_valueListeners.Add(listener);
+    }
+    // detect the higher log bits too; see LoggerImpl
+    if ((deltaMask & NT_EVENT_LOGMESSAGE) != 0 ||
+        (deltaMask & 0x1ff0000) != 0) {
+      m_logListeners.Add(listener);
+    }
+    if ((deltaMask & NT_EVENT_TIMESYNC) != 0) {
+      m_timeSyncListeners.Add(listener);
+    }
+  }
+}
+
+void ListenerStorage::Notify(std::span<const NT_Listener> handles,
+                             unsigned int flags,
+                             std::span<ConnectionInfo const* const> infos) {
+  if (flags == 0) {
+    return;
+  }
+  std::scoped_lock lock{m_mutex};
+
+  auto doSignal = [&](ListenerData& listener) {
+    if ((flags & listener.eventMask) != 0) {
+      for (auto&& [finishEvent, mask] : listener.sources) {
+        if ((flags & mask) != 0) {
+          for (auto&& info : infos) {
+            listener.poller->queue.emplace_back(listener.handle, flags, *info);
+            // finishEvent is never set (see ConnectionList)
+          }
+        }
+      }
+      listener.handle.Set();
+      listener.poller->handle.Set();
+    }
+  };
+
+  if (!handles.empty()) {
+    for (auto handle : handles) {
+      if (auto listener = m_listeners.Get(handle)) {
+        doSignal(*listener);
+      }
+    }
+  } else {
+    for (auto&& listener : m_connListeners) {
+      doSignal(*listener);
+    }
+  }
+}
+
+void ListenerStorage::Notify(std::span<const NT_Listener> handles,
+                             unsigned int flags,
+                             std::span<const TopicInfo> infos) {
+  if (flags == 0) {
+    return;
+  }
+  std::scoped_lock lock{m_mutex};
+
+  auto doSignal = [&](ListenerData& listener) {
+    if ((flags & listener.eventMask) != 0) {
+      int count = 0;
+      for (auto&& [finishEvent, mask] : listener.sources) {
+        if ((flags & mask) != 0) {
+          for (auto&& info : infos) {
+            listener.poller->queue.emplace_back(listener.handle, flags, info);
+            if (finishEvent &&
+                !finishEvent(mask, &listener.poller->queue.back())) {
+              listener.poller->queue.pop_back();
+            } else {
+              ++count;
+            }
+          }
+        }
+      }
+      if (count > 0) {
+        listener.handle.Set();
+        listener.poller->handle.Set();
+      }
+    }
+  };
+
+  if (!handles.empty()) {
+    for (auto handle : handles) {
+      if (auto listener = m_listeners.Get(handle)) {
+        doSignal(*listener);
+      }
+    }
+  } else {
+    for (auto&& listener : m_topicListeners) {
+      doSignal(*listener);
+    }
+  }
+}
+
+void ListenerStorage::Notify(std::span<const NT_Listener> handles,
+                             unsigned int flags, NT_Topic topic,
+                             NT_Handle subentry, const Value& value) {
+  if (flags == 0) {
+    return;
+  }
+  std::scoped_lock lock{m_mutex};
+
+  auto doSignal = [&](ListenerData& listener) {
+    if ((flags & listener.eventMask) != 0) {
+      int count = 0;
+      for (auto&& [finishEvent, mask] : listener.sources) {
+        if ((flags & mask) != 0) {
+          listener.poller->queue.emplace_back(listener.handle, flags, topic,
+                                              subentry, value);
+          if (finishEvent &&
+              !finishEvent(mask, &listener.poller->queue.back())) {
+            listener.poller->queue.pop_back();
+          } else {
+            ++count;
+          }
+        }
+      }
+      if (count > 0) {
+        listener.handle.Set();
+        listener.poller->handle.Set();
+      }
+    }
+  };
+
+  if (!handles.empty()) {
+    for (auto handle : handles) {
+      if (auto listener = m_listeners.Get(handle)) {
+        doSignal(*listener);
+      }
+    }
+  } else {
+    for (auto&& listener : m_valueListeners) {
+      doSignal(*listener);
+    }
+  }
+}
+
+void ListenerStorage::Notify(unsigned int flags, unsigned int level,
+                             std::string_view filename, unsigned int line,
+                             std::string_view message) {
+  if (flags == 0) {
+    return;
+  }
+  std::scoped_lock lock{m_mutex};
+  for (auto&& listener : m_logListeners) {
+    if ((flags & listener->eventMask) != 0) {
+      int count = 0;
+      for (auto&& [finishEvent, mask] : listener->sources) {
+        if ((flags & mask) != 0) {
+          listener->poller->queue.emplace_back(listener->handle, flags, level,
+                                               filename, line, message);
+          if (finishEvent &&
+              !finishEvent(mask, &listener->poller->queue.back())) {
+            listener->poller->queue.pop_back();
+          } else {
+            ++count;
+          }
+        }
+      }
+      if (count > 0) {
+        listener->handle.Set();
+        listener->poller->handle.Set();
+      }
+    }
+  }
+}
+
+void ListenerStorage::NotifyTimeSync(std::span<const NT_Listener> handles,
+                                     unsigned int flags,
+                                     int64_t serverTimeOffset, int64_t rtt2,
+                                     bool valid) {
+  if (flags == 0) {
+    return;
+  }
+  std::scoped_lock lock{m_mutex};
+
+  auto doSignal = [&](ListenerData& listener) {
+    if ((flags & listener.eventMask) != 0) {
+      for (auto&& [finishEvent, mask] : listener.sources) {
+        if ((flags & mask) != 0) {
+          listener.poller->queue.emplace_back(listener.handle, flags,
+                                              serverTimeOffset, rtt2, valid);
+          // finishEvent is never set (see InstanceImpl)
+        }
+      }
+      listener.handle.Set();
+      listener.poller->handle.Set();
+    }
+  };
+
+  if (!handles.empty()) {
+    for (auto handle : handles) {
+      if (auto listener = m_listeners.Get(handle)) {
+        doSignal(*listener);
+      }
+    }
+  } else {
+    for (auto&& listener : m_timeSyncListeners) {
+      doSignal(*listener);
+    }
+  }
+}
+
+NT_Listener ListenerStorage::AddListener(ListenerCallback callback) {
+  std::scoped_lock lock{m_mutex};
+  if (!m_thread) {
+    m_thread.Start(m_pollers.Add(m_inst)->handle);
+  }
+  if (auto thr = m_thread.GetThread()) {
+    auto listener = DoAddListener(thr->m_poller);
+    if (listener) {
+      thr->m_callbacks.try_emplace(listener, std::move(callback));
+    }
+    return listener;
+  } else {
+    return {};
+  }
+}
+
+NT_Listener ListenerStorage::AddListener(NT_ListenerPoller pollerHandle) {
+  std::scoped_lock lock{m_mutex};
+  return DoAddListener(pollerHandle);
+}
+
+NT_Listener ListenerStorage::DoAddListener(NT_ListenerPoller pollerHandle) {
+  if (auto poller = m_pollers.Get(pollerHandle)) {
+    return m_listeners.Add(m_inst, poller)->handle;
+  } else {
+    return {};
+  }
+}
+
+NT_ListenerPoller ListenerStorage::CreateListenerPoller() {
+  std::scoped_lock lock{m_mutex};
+  return m_pollers.Add(m_inst)->handle;
+}
+
+std::vector<std::pair<NT_Listener, unsigned int>>
+ListenerStorage::DestroyListenerPoller(NT_ListenerPoller pollerHandle) {
+  std::scoped_lock lock{m_mutex};
+  if (auto poller = m_pollers.Remove(pollerHandle)) {
+    // ensure all listeners that use this poller are removed
+    wpi::SmallVector<NT_Listener, 16> toRemove;
+    for (auto&& listener : m_listeners) {
+      if (listener->poller == poller.get()) {
+        toRemove.emplace_back(listener->handle);
+      }
+    }
+    return DoRemoveListeners(toRemove);
+  } else {
+    return {};
+  }
+}
+
+std::vector<Event> ListenerStorage::ReadListenerQueue(
+    NT_ListenerPoller pollerHandle) {
+  std::scoped_lock lock{m_mutex};
+  if (auto poller = m_pollers.Get(pollerHandle)) {
+    std::vector<Event> rv;
+    rv.swap(poller->queue);
+    return rv;
+  } else {
+    return {};
+  }
+}
+
+std::vector<std::pair<NT_Listener, unsigned int>>
+ListenerStorage::RemoveListener(NT_Listener listenerHandle) {
+  std::scoped_lock lock{m_mutex};
+  return DoRemoveListeners({&listenerHandle, 1});
+}
+
+bool ListenerStorage::WaitForListenerQueue(double timeout) {
+  WPI_EventHandle h;
+  {
+    std::scoped_lock lock{m_mutex};
+    if (auto thr = m_thread.GetThread()) {
+      h = thr->m_waitQueueWaiter.GetHandle();
+      thr->m_waitQueueWakeup.Set();
+    } else {
+      return false;
+    }
+  }
+  bool timedOut;
+  wpi::WaitForObject(h, timeout, &timedOut);
+  return !timedOut;
+}
+
+void ListenerStorage::Reset() {
+  std::scoped_lock lock{m_mutex};
+  m_pollers.clear();
+  m_listeners.clear();
+  m_connListeners.clear();
+  m_topicListeners.clear();
+  m_valueListeners.clear();
+  m_logListeners.clear();
+  if (m_thread) {
+    m_thread.Stop();
+  }
+}
+
+std::vector<std::pair<NT_Listener, unsigned int>>
+ListenerStorage::DoRemoveListeners(std::span<const NT_Listener> handles) {
+  std::vector<std::pair<NT_Listener, unsigned int>> rv;
+  auto thr = m_thread.GetThread();
+  for (auto handle : handles) {
+    if (auto listener = m_listeners.Remove(handle)) {
+      rv.emplace_back(handle, listener->eventMask);
+      if (thr) {
+        if (thr->m_poller == listener->poller->handle) {
+          thr->m_callbacks.erase(handle);
+        }
+      }
+      if ((listener->eventMask & NT_EVENT_CONNECTION) != 0) {
+        m_connListeners.Remove(listener.get());
+      }
+      if ((listener->eventMask & NT_EVENT_TOPIC) != 0) {
+        m_topicListeners.Remove(listener.get());
+      }
+      if ((listener->eventMask & NT_EVENT_VALUE_ALL) != 0) {
+        m_valueListeners.Remove(listener.get());
+      }
+      if ((listener->eventMask & NT_EVENT_LOGMESSAGE) != 0 ||
+          (listener->eventMask & 0x1ff0000) != 0) {
+        m_logListeners.Remove(listener.get());
+      }
+    }
+  }
+  return rv;
+}
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/ListenerStorage.h b/third_party/allwpilib/ntcore/src/main/native/cpp/ListenerStorage.h
new file mode 100644
index 0000000..b291a12
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/ListenerStorage.h
@@ -0,0 +1,116 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <functional>
+#include <memory>
+#include <span>
+#include <string_view>
+#include <utility>
+#include <vector>
+
+#include <wpi/SafeThread.h>
+#include <wpi/SmallVector.h>
+#include <wpi/Synchronization.h>
+#include <wpi/mutex.h>
+
+#include "Handle.h"
+#include "HandleMap.h"
+#include "IListenerStorage.h"
+#include "ntcore_cpp.h"
+
+namespace nt {
+
+class ListenerStorage final : public IListenerStorage {
+ public:
+  explicit ListenerStorage(int inst);
+  ListenerStorage(const ListenerStorage&) = delete;
+  ListenerStorage& operator=(const ListenerStorage&) = delete;
+  ~ListenerStorage() final;
+
+  // IListenerStorage interface
+  void Activate(NT_Listener listenerHandle, unsigned int mask,
+                FinishEventFunc finishEvent = {}) final;
+  void Notify(std::span<const NT_Listener> handles, unsigned int flags,
+              std::span<ConnectionInfo const* const> infos) final;
+  void Notify(std::span<const NT_Listener> handles, unsigned int flags,
+              std::span<const TopicInfo> infos) final;
+  void Notify(std::span<const NT_Listener> handles, unsigned int flags,
+              NT_Topic topic, NT_Handle subentry, const Value& value) final;
+  void Notify(unsigned int flags, unsigned int level, std::string_view filename,
+              unsigned int line, std::string_view message) final;
+  void NotifyTimeSync(std::span<const NT_Listener> handles, unsigned int flags,
+                      int64_t serverTimeOffset, int64_t rtt2, bool valid) final;
+
+  // user-facing functions
+  NT_Listener AddListener(ListenerCallback callback);
+  NT_Listener AddListener(NT_ListenerPoller pollerHandle);
+  NT_ListenerPoller CreateListenerPoller();
+
+  // returns listener handle and mask for each listener that was destroyed
+  [[nodiscard]] std::vector<std::pair<NT_Listener, unsigned int>>
+  DestroyListenerPoller(NT_ListenerPoller pollerHandle);
+
+  std::vector<Event> ReadListenerQueue(NT_ListenerPoller pollerHandle);
+
+  // returns listener handle and mask for each listener that was destroyed
+  [[nodiscard]] std::vector<std::pair<NT_Listener, unsigned int>>
+  RemoveListener(NT_Listener listenerHandle);
+
+  bool WaitForListenerQueue(double timeout);
+
+  void Reset();
+
+ private:
+  // these assume the mutex is already held
+  NT_Listener DoAddListener(NT_ListenerPoller pollerHandle);
+  std::vector<std::pair<NT_Listener, unsigned int>> DoRemoveListeners(
+      std::span<const NT_Listener> handles);
+
+  int m_inst;
+  mutable wpi::mutex m_mutex;
+
+  struct PollerData {
+    static constexpr auto kType = Handle::kListenerPoller;
+
+    explicit PollerData(NT_ListenerPoller handle) : handle{handle} {}
+
+    wpi::SignalObject<NT_ListenerPoller> handle;
+    std::vector<Event> queue;
+  };
+  HandleMap<PollerData, 8> m_pollers;
+
+  struct ListenerData {
+    static constexpr auto kType = Handle::kListener;
+
+    ListenerData(NT_Listener handle, PollerData* poller)
+        : handle{handle}, poller{poller} {}
+
+    wpi::SignalObject<NT_Listener> handle;
+    PollerData* poller;
+    wpi::SmallVector<std::pair<FinishEventFunc, unsigned int>, 2> sources;
+    unsigned int eventMask{0};
+  };
+  HandleMap<ListenerData, 8> m_listeners;
+
+  // Utility wrapper for making a set-like vector
+  template <typename T>
+  class VectorSet : public std::vector<T> {
+   public:
+    void Add(T value) { this->push_back(value); }
+    void Remove(T value) { std::erase(*this, value); }
+  };
+
+  VectorSet<ListenerData*> m_connListeners;
+  VectorSet<ListenerData*> m_topicListeners;
+  VectorSet<ListenerData*> m_valueListeners;
+  VectorSet<ListenerData*> m_logListeners;
+  VectorSet<ListenerData*> m_timeSyncListeners;
+
+  class Thread;
+  wpi::SafeThreadOwner<Thread> m_thread;
+};
+
+}  // namespace nt
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/LocalStorage.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/LocalStorage.cpp
new file mode 100644
index 0000000..db8e065
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/LocalStorage.cpp
@@ -0,0 +1,2264 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "LocalStorage.h"
+
+#include <algorithm>
+
+#include <wpi/DataLog.h>
+#include <wpi/StringExtras.h>
+#include <wpi/StringMap.h>
+#include <wpi/Synchronization.h>
+#include <wpi/UidVector.h>
+#include <wpi/circular_buffer.h>
+#include <wpi/json.h>
+
+#include "Handle.h"
+#include "HandleMap.h"
+#include "IListenerStorage.h"
+#include "Log.h"
+#include "PubSubOptions.h"
+#include "Types_internal.h"
+#include "Value_internal.h"
+#include "networktables/NetworkTableValue.h"
+#include "ntcore_c.h"
+
+using namespace nt;
+
+// maximum number of local publishers / subscribers to any given topic
+static constexpr size_t kMaxPublishers = 512;
+static constexpr size_t kMaxSubscribers = 512;
+static constexpr size_t kMaxMultiSubscribers = 512;
+static constexpr size_t kMaxListeners = 512;
+
+namespace {
+
+static constexpr bool IsSpecial(std::string_view name) {
+  return name.empty() ? false : name.front() == '$';
+}
+
+static constexpr bool PrefixMatch(std::string_view name,
+                                  std::string_view prefix, bool special) {
+  return (!special || !prefix.empty()) && wpi::starts_with(name, prefix);
+}
+
+// Utility wrapper for making a set-like vector
+template <typename T>
+class VectorSet : public std::vector<T> {
+ public:
+  void Add(T value) { this->push_back(value); }
+  void Remove(T value) { std::erase(*this, value); }
+};
+
+struct EntryData;
+struct PublisherData;
+struct SubscriberData;
+struct MultiSubscriberData;
+
+struct DataLoggerEntry {
+  DataLoggerEntry(wpi::log::DataLog& log, int entry, NT_DataLogger logger)
+      : log{&log}, entry{entry}, logger{logger} {}
+
+  static std::string MakeMetadata(std::string_view properties) {
+    return fmt::format("{{\"properties\":{},\"source\":\"NT\"}}", properties);
+  }
+
+  void Append(const Value& v);
+
+  wpi::log::DataLog* log;
+  int entry;
+  NT_DataLogger logger;
+};
+
+struct TopicData {
+  static constexpr auto kType = Handle::kTopic;
+
+  TopicData(NT_Topic handle, std::string_view name)
+      : handle{handle}, name{name}, special{IsSpecial(name)} {}
+
+  bool Exists() const { return onNetwork || !localPublishers.empty(); }
+
+  TopicInfo GetTopicInfo() const;
+
+  // invariants
+  wpi::SignalObject<NT_Topic> handle;
+  std::string name;
+  bool special;
+
+  Value lastValue;  // also stores timestamp
+  Value lastValueNetwork;
+  NT_Type type{NT_UNASSIGNED};
+  std::string typeStr;
+  unsigned int flags{0};            // for NT3 APIs
+  std::string propertiesStr{"{}"};  // cached string for GetTopicInfo() et al
+  wpi::json properties = wpi::json::object();
+  NT_Entry entry{0};  // cached entry for GetEntry()
+
+  bool onNetwork{false};  // true if there are any remote publishers
+
+  wpi::SmallVector<DataLoggerEntry, 1> datalogs;
+  NT_Type datalogType{NT_UNASSIGNED};
+
+  VectorSet<PublisherData*> localPublishers;
+  VectorSet<SubscriberData*> localSubscribers;
+  VectorSet<MultiSubscriberData*> multiSubscribers;
+  VectorSet<EntryData*> entries;
+  VectorSet<NT_Listener> listeners;
+};
+
+struct PubSubConfig : public PubSubOptionsImpl {
+  PubSubConfig() = default;
+  PubSubConfig(NT_Type type, std::string_view typeStr,
+               const PubSubOptions& options)
+      : PubSubOptionsImpl{options}, type{type}, typeStr{typeStr} {
+    prefixMatch = false;
+  }
+
+  NT_Type type{NT_UNASSIGNED};
+  std::string typeStr;
+};
+
+struct PublisherData {
+  static constexpr auto kType = Handle::kPublisher;
+
+  PublisherData(NT_Publisher handle, TopicData* topic, PubSubConfig config)
+      : handle{handle}, topic{topic}, config{std::move(config)} {}
+
+  void UpdateActive();
+
+  // invariants
+  wpi::SignalObject<NT_Publisher> handle;
+  TopicData* topic;
+  PubSubConfig config;
+
+  // whether or not the publisher should actually publish values
+  bool active{false};
+};
+
+struct SubscriberData {
+  static constexpr auto kType = Handle::kSubscriber;
+
+  SubscriberData(NT_Subscriber handle, TopicData* topic, PubSubConfig config)
+      : handle{handle},
+        topic{topic},
+        config{std::move(config)},
+        pollStorage{config.pollStorage} {}
+
+  void UpdateActive();
+
+  // invariants
+  wpi::SignalObject<NT_Subscriber> handle;
+  TopicData* topic;
+  PubSubConfig config;
+
+  // whether or not the subscriber should actually receive values
+  bool active{false};
+
+  // polling storage
+  wpi::circular_buffer<Value> pollStorage;
+
+  // value listeners
+  VectorSet<NT_Listener> valueListeners;
+};
+
+struct EntryData {
+  static constexpr auto kType = Handle::kEntry;
+
+  EntryData(NT_Entry handle, SubscriberData* subscriber)
+      : handle{handle}, topic{subscriber->topic}, subscriber{subscriber} {}
+
+  // invariants
+  wpi::SignalObject<NT_Entry> handle;
+  TopicData* topic;
+  SubscriberData* subscriber;
+
+  // the publisher (created on demand)
+  PublisherData* publisher{nullptr};
+};
+
+struct MultiSubscriberData {
+  static constexpr auto kType = Handle::kMultiSubscriber;
+
+  MultiSubscriberData(NT_MultiSubscriber handle,
+                      std::span<const std::string_view> prefixes,
+                      const PubSubOptionsImpl& options)
+      : handle{handle}, options{options} {
+    this->options.prefixMatch = true;
+    this->prefixes.reserve(prefixes.size());
+    for (auto&& prefix : prefixes) {
+      this->prefixes.emplace_back(prefix);
+    }
+  }
+
+  bool Matches(std::string_view name, bool special);
+
+  // invariants
+  wpi::SignalObject<NT_MultiSubscriber> handle;
+  std::vector<std::string> prefixes;
+  PubSubOptionsImpl options;
+
+  // value listeners
+  VectorSet<NT_Listener> valueListeners;
+};
+
+bool MultiSubscriberData::Matches(std::string_view name, bool special) {
+  for (auto&& prefix : prefixes) {
+    if (PrefixMatch(name, prefix, special)) {
+      return true;
+    }
+  }
+  return false;
+}
+
+struct ListenerData {
+  ListenerData(NT_Listener handle, SubscriberData* subscriber,
+               unsigned int eventMask, bool subscriberOwned)
+      : handle{handle},
+        eventMask{eventMask},
+        subscriber{subscriber},
+        subscriberOwned{subscriberOwned} {}
+  ListenerData(NT_Listener handle, MultiSubscriberData* subscriber,
+               unsigned int eventMask, bool subscriberOwned)
+      : handle{handle},
+        eventMask{eventMask},
+        multiSubscriber{subscriber},
+        subscriberOwned{subscriberOwned} {}
+
+  NT_Listener handle;
+  unsigned int eventMask;
+  SubscriberData* subscriber{nullptr};
+  MultiSubscriberData* multiSubscriber{nullptr};
+  bool subscriberOwned;
+};
+
+struct DataLoggerData {
+  static constexpr auto kType = Handle::kDataLogger;
+
+  DataLoggerData(NT_DataLogger handle, wpi::log::DataLog& log,
+                 std::string_view prefix, std::string_view logPrefix)
+      : handle{handle}, log{log}, prefix{prefix}, logPrefix{logPrefix} {}
+
+  int Start(TopicData* topic, int64_t time) {
+    return log.Start(fmt::format("{}{}", logPrefix,
+                                 wpi::drop_front(topic->name, prefix.size())),
+                     topic->typeStr,
+                     DataLoggerEntry::MakeMetadata(topic->propertiesStr), time);
+  }
+
+  NT_DataLogger handle;
+  wpi::log::DataLog& log;
+  std::string prefix;
+  std::string logPrefix;
+};
+
+struct LSImpl {
+  LSImpl(int inst, IListenerStorage& listenerStorage, wpi::Logger& logger)
+      : m_inst{inst}, m_listenerStorage{listenerStorage}, m_logger{logger} {}
+
+  int m_inst;
+  IListenerStorage& m_listenerStorage;
+  wpi::Logger& m_logger;
+  net::NetworkInterface* m_network{nullptr};
+
+  // handle mappings
+  HandleMap<TopicData, 16> m_topics;
+  HandleMap<PublisherData, 16> m_publishers;
+  HandleMap<SubscriberData, 16> m_subscribers;
+  HandleMap<EntryData, 16> m_entries;
+  HandleMap<MultiSubscriberData, 16> m_multiSubscribers;
+  HandleMap<DataLoggerData, 16> m_dataloggers;
+
+  // name mappings
+  wpi::StringMap<TopicData*> m_nameTopics;
+
+  // listeners
+  wpi::DenseMap<NT_Listener, std::unique_ptr<ListenerData>> m_listeners;
+
+  // string-based listeners
+  VectorSet<ListenerData*> m_topicPrefixListeners;
+
+  // topic functions
+  void NotifyTopic(TopicData* topic, unsigned int eventFlags);
+
+  void CheckReset(TopicData* topic);
+
+  bool SetValue(TopicData* topic, const Value& value, unsigned int eventFlags,
+                bool isDuplicate, const PublisherData* publisher);
+  void NotifyValue(TopicData* topic, unsigned int eventFlags, bool isDuplicate,
+                   const PublisherData* publisher);
+
+  void SetFlags(TopicData* topic, unsigned int flags);
+  void SetPersistent(TopicData* topic, bool value);
+  void SetRetained(TopicData* topic, bool value);
+  void SetProperties(TopicData* topic, const wpi::json& update,
+                     bool sendNetwork);
+  void PropertiesUpdated(TopicData* topic, const wpi::json& update,
+                         unsigned int eventFlags, bool sendNetwork,
+                         bool updateFlags = true);
+
+  void RefreshPubSubActive(TopicData* topic, bool warnOnSubMismatch);
+
+  void NetworkAnnounce(TopicData* topic, std::string_view typeStr,
+                       const wpi::json& properties, NT_Publisher pubHandle);
+  void RemoveNetworkPublisher(TopicData* topic);
+  void NetworkPropertiesUpdate(TopicData* topic, const wpi::json& update,
+                               bool ack);
+
+  PublisherData* AddLocalPublisher(TopicData* topic,
+                                   const wpi::json& properties,
+                                   const PubSubConfig& options);
+  std::unique_ptr<PublisherData> RemoveLocalPublisher(NT_Publisher pubHandle);
+
+  SubscriberData* AddLocalSubscriber(TopicData* topic,
+                                     const PubSubConfig& options);
+  std::unique_ptr<SubscriberData> RemoveLocalSubscriber(
+      NT_Subscriber subHandle);
+
+  EntryData* AddEntry(SubscriberData* subscriber);
+  std::unique_ptr<EntryData> RemoveEntry(NT_Entry entryHandle);
+
+  MultiSubscriberData* AddMultiSubscriber(
+      std::span<const std::string_view> prefixes, const PubSubOptions& options);
+  std::unique_ptr<MultiSubscriberData> RemoveMultiSubscriber(
+      NT_MultiSubscriber subHandle);
+
+  void AddListenerImpl(NT_Listener listenerHandle, TopicData* topic,
+                       unsigned int eventMask);
+  void AddListenerImpl(NT_Listener listenerHandle, SubscriberData* subscriber,
+                       unsigned int eventMask, NT_Handle subentryHandle,
+                       bool subscriberOwned);
+  void AddListenerImpl(NT_Listener listenerHandle,
+                       MultiSubscriberData* subscriber, unsigned int eventMask,
+                       bool subscriberOwned);
+  void AddListenerImpl(NT_Listener listenerHandle,
+                       std::span<const std::string_view> prefixes,
+                       unsigned int eventMask);
+
+  void AddListener(NT_Listener listenerHandle,
+                   std::span<const std::string_view> prefixes,
+                   unsigned int mask);
+  void AddListener(NT_Listener listenerHandle, NT_Handle handle,
+                   unsigned int mask);
+  void RemoveListener(NT_Listener listenerHandle, unsigned int mask);
+
+  TopicData* GetOrCreateTopic(std::string_view name);
+  TopicData* GetTopic(NT_Handle handle);
+  SubscriberData* GetSubEntry(NT_Handle subentryHandle);
+  PublisherData* PublishEntry(EntryData* entry, NT_Type type);
+  Value* GetSubEntryValue(NT_Handle subentryHandle);
+
+  bool PublishLocalValue(PublisherData* publisher, const Value& value,
+                         bool force = false);
+
+  bool SetEntryValue(NT_Handle pubentryHandle, const Value& value);
+  bool SetDefaultEntryValue(NT_Handle pubsubentryHandle, const Value& value);
+
+  void RemoveSubEntry(NT_Handle subentryHandle);
+};
+
+}  // namespace
+
+void DataLoggerEntry::Append(const Value& v) {
+  auto time = v.time();
+  switch (v.type()) {
+    case NT_BOOLEAN:
+      log->AppendBoolean(entry, v.GetBoolean(), time);
+      break;
+    case NT_INTEGER:
+      log->AppendInteger(entry, v.GetInteger(), time);
+      break;
+    case NT_FLOAT:
+      log->AppendFloat(entry, v.GetFloat(), time);
+      break;
+    case NT_DOUBLE:
+      log->AppendDouble(entry, v.GetDouble(), time);
+      break;
+    case NT_STRING:
+      log->AppendString(entry, v.GetString(), time);
+      break;
+    case NT_RAW: {
+      auto val = v.GetRaw();
+      log->AppendRaw(entry,
+                     {reinterpret_cast<const uint8_t*>(val.data()), val.size()},
+                     time);
+      break;
+    }
+    case NT_BOOLEAN_ARRAY:
+      log->AppendBooleanArray(entry, v.GetBooleanArray(), time);
+      break;
+    case NT_INTEGER_ARRAY:
+      log->AppendIntegerArray(entry, v.GetIntegerArray(), time);
+      break;
+    case NT_FLOAT_ARRAY:
+      log->AppendFloatArray(entry, v.GetFloatArray(), time);
+      break;
+    case NT_DOUBLE_ARRAY:
+      log->AppendDoubleArray(entry, v.GetDoubleArray(), time);
+      break;
+    case NT_STRING_ARRAY:
+      log->AppendStringArray(entry, v.GetStringArray(), time);
+      break;
+    default:
+      break;
+  }
+}
+
+TopicInfo TopicData::GetTopicInfo() const {
+  TopicInfo info;
+  info.topic = handle;
+  info.name = name;
+  info.type = type;
+  info.type_str = typeStr;
+  info.properties = propertiesStr;
+  return info;
+}
+
+void PublisherData::UpdateActive() {
+  active = config.type == topic->type && config.typeStr == topic->typeStr;
+}
+
+void SubscriberData::UpdateActive() {
+  // for subscribers, unassigned is a wildcard
+  // also allow numerically compatible subscribers
+  active = config.type == NT_UNASSIGNED ||
+           (config.type == topic->type && config.typeStr == topic->typeStr) ||
+           IsNumericCompatible(config.type, topic->type);
+}
+
+void LSImpl::NotifyTopic(TopicData* topic, unsigned int eventFlags) {
+  DEBUG4("NotifyTopic({}, {})", topic->name, eventFlags);
+  auto topicInfo = topic->GetTopicInfo();
+  if (!topic->listeners.empty()) {
+    m_listenerStorage.Notify(topic->listeners, eventFlags, topicInfo);
+  }
+
+  wpi::SmallVector<NT_Listener, 32> listeners;
+  for (auto listener : m_topicPrefixListeners) {
+    if (listener->multiSubscriber &&
+        listener->multiSubscriber->Matches(topic->name, topic->special)) {
+      listeners.emplace_back(listener->handle);
+    }
+  }
+  if (!listeners.empty()) {
+    m_listenerStorage.Notify(listeners, eventFlags, topicInfo);
+  }
+
+  if ((eventFlags & (NT_EVENT_PUBLISH | NT_EVENT_UNPUBLISH)) != 0) {
+    if (!m_dataloggers.empty()) {
+      auto now = Now();
+      for (auto&& datalogger : m_dataloggers) {
+        if (wpi::starts_with(topic->name, datalogger->prefix)) {
+          auto it = std::find_if(topic->datalogs.begin(), topic->datalogs.end(),
+                                 [&](const auto& elem) {
+                                   return elem.logger == datalogger->handle;
+                                 });
+          if ((eventFlags & NT_EVENT_PUBLISH) != 0 &&
+              it == topic->datalogs.end()) {
+            topic->datalogs.emplace_back(datalogger->log,
+                                         datalogger->Start(topic, now),
+                                         datalogger->handle);
+            topic->datalogType = topic->type;
+          } else if ((eventFlags & NT_EVENT_UNPUBLISH) != 0 &&
+                     it != topic->datalogs.end()) {
+            it->log->Finish(it->entry, now);
+            topic->datalogType = NT_UNASSIGNED;
+            topic->datalogs.erase(it);
+          }
+        }
+      }
+    }
+  } else if ((eventFlags & NT_EVENT_PROPERTIES) != 0) {
+    if (!topic->datalogs.empty()) {
+      auto metadata = DataLoggerEntry::MakeMetadata(topic->propertiesStr);
+      for (auto&& datalog : topic->datalogs) {
+        datalog.log->SetMetadata(datalog.entry, metadata);
+      }
+    }
+  }
+}
+
+void LSImpl::CheckReset(TopicData* topic) {
+  if (topic->Exists()) {
+    return;
+  }
+  topic->lastValue = {};
+  topic->lastValueNetwork = {};
+  topic->type = NT_UNASSIGNED;
+  topic->typeStr.clear();
+  topic->flags = 0;
+  topic->properties = wpi::json::object();
+  topic->propertiesStr = "{}";
+}
+
+bool LSImpl::SetValue(TopicData* topic, const Value& value,
+                      unsigned int eventFlags, bool isDuplicate,
+                      const PublisherData* publisher) {
+  DEBUG4("SetValue({}, {}, {}, {})", topic->name, value.time(), eventFlags,
+         isDuplicate);
+  if (topic->type != NT_UNASSIGNED && topic->type != value.type()) {
+    return false;
+  }
+  if (!topic->lastValue || value.time() >= topic->lastValue.time()) {
+    // TODO: notify option even if older value
+    topic->type = value.type();
+    topic->lastValue = value;
+    NotifyValue(topic, eventFlags, isDuplicate, publisher);
+  }
+  if (!isDuplicate && topic->datalogType == value.type()) {
+    for (auto&& datalog : topic->datalogs) {
+      datalog.Append(value);
+    }
+  }
+  return true;
+}
+
+void LSImpl::NotifyValue(TopicData* topic, unsigned int eventFlags,
+                         bool isDuplicate, const PublisherData* publisher) {
+  bool isNetwork = (eventFlags & NT_EVENT_VALUE_REMOTE) != 0;
+  for (auto&& subscriber : topic->localSubscribers) {
+    if (subscriber->active &&
+        (subscriber->config.keepDuplicates || !isDuplicate) &&
+        ((isNetwork && !subscriber->config.disableRemote) ||
+         (!isNetwork && !subscriber->config.disableLocal)) &&
+        (!publisher || (publisher && (subscriber->config.excludePublisher !=
+                                      publisher->handle)))) {
+      subscriber->pollStorage.emplace_back(topic->lastValue);
+      subscriber->handle.Set();
+      if (!subscriber->valueListeners.empty()) {
+        m_listenerStorage.Notify(subscriber->valueListeners, eventFlags,
+                                 topic->handle, 0, topic->lastValue);
+      }
+    }
+  }
+
+  for (auto&& subscriber : topic->multiSubscribers) {
+    if (subscriber->options.keepDuplicates || !isDuplicate) {
+      subscriber->handle.Set();
+      if (!subscriber->valueListeners.empty()) {
+        m_listenerStorage.Notify(subscriber->valueListeners, eventFlags,
+                                 topic->handle, 0, topic->lastValue);
+      }
+    }
+  }
+}
+
+void LSImpl::SetFlags(TopicData* topic, unsigned int flags) {
+  wpi::json update = wpi::json::object();
+  if ((flags & NT_PERSISTENT) != 0) {
+    topic->properties["persistent"] = true;
+    update["persistent"] = true;
+  } else {
+    topic->properties.erase("persistent");
+    update["persistent"] = wpi::json();
+  }
+  if ((flags & NT_RETAINED) != 0) {
+    topic->properties["retained"] = true;
+    update["retained"] = true;
+  } else {
+    topic->properties.erase("retained");
+    update["retained"] = wpi::json();
+  }
+  topic->flags = flags;
+  if (!update.empty()) {
+    PropertiesUpdated(topic, update, NT_EVENT_NONE, true, false);
+  }
+}
+
+void LSImpl::SetPersistent(TopicData* topic, bool value) {
+  wpi::json update = wpi::json::object();
+  if (value) {
+    topic->flags |= NT_PERSISTENT;
+    topic->properties["persistent"] = true;
+    update["persistent"] = true;
+  } else {
+    topic->flags &= ~NT_PERSISTENT;
+    topic->properties.erase("persistent");
+    update["persistent"] = wpi::json();
+  }
+  PropertiesUpdated(topic, update, NT_EVENT_NONE, true, false);
+}
+
+void LSImpl::SetRetained(TopicData* topic, bool value) {
+  wpi::json update = wpi::json::object();
+  if (value) {
+    topic->flags |= NT_RETAINED;
+    topic->properties["retained"] = true;
+    update["retained"] = true;
+  } else {
+    topic->flags &= ~NT_RETAINED;
+    topic->properties.erase("retained");
+    update["retained"] = wpi::json();
+  }
+  PropertiesUpdated(topic, update, NT_EVENT_NONE, true, false);
+}
+
+void LSImpl::SetProperties(TopicData* topic, const wpi::json& update,
+                           bool sendNetwork) {
+  if (!update.is_object()) {
+    return;
+  }
+  DEBUG4("SetProperties({},{})", topic->name, sendNetwork);
+  for (auto&& change : update.items()) {
+    if (change.value().is_null()) {
+      topic->properties.erase(change.key());
+    } else {
+      topic->properties[change.key()] = change.value();
+    }
+  }
+  PropertiesUpdated(topic, update, NT_EVENT_NONE, sendNetwork);
+}
+
+void LSImpl::PropertiesUpdated(TopicData* topic, const wpi::json& update,
+                               unsigned int eventFlags, bool sendNetwork,
+                               bool updateFlags) {
+  DEBUG4("PropertiesUpdated({}, {}, {}, {}, {})", topic->name, update.dump(),
+         eventFlags, sendNetwork, updateFlags);
+  if (updateFlags) {
+    // set flags from properties
+    auto it = topic->properties.find("persistent");
+    if (it != topic->properties.end()) {
+      if (auto val = it->get_ptr<bool*>()) {
+        if (*val) {
+          topic->flags |= NT_PERSISTENT;
+        } else {
+          topic->flags &= ~NT_PERSISTENT;
+        }
+      }
+    }
+    it = topic->properties.find("retained");
+    if (it != topic->properties.end()) {
+      if (auto val = it->get_ptr<bool*>()) {
+        if (*val) {
+          topic->flags |= NT_RETAINED;
+        } else {
+          topic->flags &= ~NT_RETAINED;
+        }
+      }
+    }
+  }
+
+  topic->propertiesStr = topic->properties.dump();
+  NotifyTopic(topic, eventFlags | NT_EVENT_PROPERTIES);
+  // check local flag so we don't echo back received properties changes
+  if (m_network && sendNetwork) {
+    m_network->SetProperties(topic->handle, topic->name, update);
+  }
+}
+
+void LSImpl::RefreshPubSubActive(TopicData* topic, bool warnOnSubMismatch) {
+  for (auto&& publisher : topic->localPublishers) {
+    publisher->UpdateActive();
+  }
+  for (auto&& subscriber : topic->localSubscribers) {
+    subscriber->UpdateActive();
+    if (warnOnSubMismatch && topic->Exists() && !subscriber->active) {
+      // warn on type mismatch
+      INFO(
+          "local subscribe to '{}' disabled due to type mismatch (wanted '{}', "
+          "published as '{}')",
+          topic->name, subscriber->config.typeStr, topic->typeStr);
+    }
+  }
+}
+
+void LSImpl::NetworkAnnounce(TopicData* topic, std::string_view typeStr,
+                             const wpi::json& properties,
+                             NT_Publisher pubHandle) {
+  DEBUG4("LS NetworkAnnounce({}, {}, {}, {})", topic->name, typeStr,
+         properties.dump(), pubHandle);
+  if (pubHandle != 0) {
+    return;  // ack of our publish; ignore
+  }
+
+  unsigned int event = NT_EVENT_NONE;
+  // fresh non-local publish; the network publish always sets the type even
+  // if it was locally published, but output a diagnostic for this case
+  bool didExist = topic->Exists();
+  topic->onNetwork = true;
+  NT_Type type = StringToType(typeStr);
+  if (topic->type != type || topic->typeStr != typeStr) {
+    if (didExist) {
+      INFO(
+          "network announce of '{}' overriding local publish (was '{}', now "
+          "'{}')",
+          topic->name, topic->typeStr, typeStr);
+    }
+    topic->type = type;
+    topic->typeStr = typeStr;
+    RefreshPubSubActive(topic, true);
+  }
+  if (!didExist) {
+    event |= NT_EVENT_PUBLISH;
+  }
+
+  // may be properties update, but need to compare to see if it actually
+  // changed to determine whether to update string / send event
+  wpi::json update = wpi::json::object();
+  // added/changed
+  for (auto&& prop : properties.items()) {
+    auto it = topic->properties.find(prop.key());
+    if (it == topic->properties.end() || *it != prop.value()) {
+      update[prop.key()] = prop.value();
+    }
+  }
+  // removed
+  for (auto&& prop : topic->properties.items()) {
+    if (properties.find(prop.key()) == properties.end()) {
+      update[prop.key()] = wpi::json();
+    }
+  }
+  if (!update.empty()) {
+    topic->properties = properties;
+    PropertiesUpdated(topic, update, event, false);
+  } else if (event != NT_EVENT_NONE) {
+    NotifyTopic(topic, event);
+  }
+}
+
+void LSImpl::RemoveNetworkPublisher(TopicData* topic) {
+  DEBUG4("LS RemoveNetworkPublisher({}, {})", topic->handle, topic->name);
+  // this acts as an unpublish
+  bool didExist = topic->Exists();
+  topic->onNetwork = false;
+  if (didExist && !topic->Exists()) {
+    DEBUG4("Unpublished {}", topic->name);
+    CheckReset(topic);
+    NotifyTopic(topic, NT_EVENT_UNPUBLISH);
+  }
+
+  if (!topic->localPublishers.empty()) {
+    // some other publisher still exists; if it has a different type, refresh
+    // and publish it over the network
+    auto& nextPub = topic->localPublishers.front();
+    if (nextPub->config.type != topic->type ||
+        nextPub->config.typeStr != topic->typeStr) {
+      topic->type = nextPub->config.type;
+      topic->typeStr = nextPub->config.typeStr;
+      RefreshPubSubActive(topic, false);
+      // this may result in a duplicate publish warning on the server side,
+      // but send one anyway in this case just to be sure
+      if (nextPub->active && m_network) {
+        m_network->Publish(nextPub->handle, topic->handle, topic->name,
+                           topic->typeStr, topic->properties, nextPub->config);
+      }
+    }
+  }
+}
+
+void LSImpl::NetworkPropertiesUpdate(TopicData* topic, const wpi::json& update,
+                                     bool ack) {
+  DEBUG4("NetworkPropertiesUpdate({},{})", topic->name, ack);
+  if (ack) {
+    return;  // ignore acks
+  }
+  SetProperties(topic, update, false);
+}
+
+PublisherData* LSImpl::AddLocalPublisher(TopicData* topic,
+                                         const wpi::json& properties,
+                                         const PubSubConfig& config) {
+  bool didExist = topic->Exists();
+  auto publisher = m_publishers.Add(m_inst, topic, config);
+  topic->localPublishers.Add(publisher);
+
+  if (!didExist) {
+    DEBUG4("AddLocalPublisher: setting {} type {} typestr {}", topic->name,
+           static_cast<int>(config.type), config.typeStr);
+    // set the type to the published type
+    topic->type = config.type;
+    topic->typeStr = config.typeStr;
+    RefreshPubSubActive(topic, true);
+
+    if (properties.is_null()) {
+      topic->properties = wpi::json::object();
+    } else if (properties.is_object()) {
+      topic->properties = properties;
+    } else {
+      WARNING("ignoring non-object properties when publishing '{}'",
+              topic->name);
+      topic->properties = wpi::json::object();
+    }
+
+    if (topic->properties.empty()) {
+      NotifyTopic(topic, NT_EVENT_PUBLISH);
+    } else {
+      PropertiesUpdated(topic, topic->properties, NT_EVENT_PUBLISH, false);
+    }
+  } else {
+    // only need to update just this publisher
+    publisher->UpdateActive();
+    if (!publisher->active) {
+      // warn on type mismatch
+      INFO(
+          "local publish to '{}' disabled due to type mismatch (wanted '{}', "
+          "currently '{}')",
+          topic->name, config.typeStr, topic->typeStr);
+    }
+  }
+
+  if (publisher->active && m_network) {
+    m_network->Publish(publisher->handle, topic->handle, topic->name,
+                       topic->typeStr, topic->properties, config);
+  }
+  return publisher;
+}
+
+std::unique_ptr<PublisherData> LSImpl::RemoveLocalPublisher(
+    NT_Publisher pubHandle) {
+  auto publisher = m_publishers.Remove(pubHandle);
+  if (publisher) {
+    auto topic = publisher->topic;
+    bool didExist = topic->Exists();
+    topic->localPublishers.Remove(publisher.get());
+    if (didExist && !topic->Exists()) {
+      CheckReset(topic);
+      NotifyTopic(topic, NT_EVENT_UNPUBLISH);
+    }
+
+    if (publisher->active && m_network) {
+      m_network->Unpublish(publisher->handle, topic->handle);
+    }
+
+    if (publisher->active && !topic->localPublishers.empty()) {
+      // some other publisher still exists; if it has a different type, refresh
+      // and publish it over the network
+      auto& nextPub = topic->localPublishers.front();
+      if (nextPub->config.type != topic->type ||
+          nextPub->config.typeStr != topic->typeStr) {
+        topic->type = nextPub->config.type;
+        topic->typeStr = nextPub->config.typeStr;
+        RefreshPubSubActive(topic, false);
+        if (nextPub->active && m_network) {
+          m_network->Publish(nextPub->handle, topic->handle, topic->name,
+                             topic->typeStr, topic->properties,
+                             nextPub->config);
+        }
+      }
+    }
+  }
+  return publisher;
+}
+
+SubscriberData* LSImpl::AddLocalSubscriber(TopicData* topic,
+                                           const PubSubConfig& config) {
+  DEBUG4("AddLocalSubscriber({})", topic->name);
+  auto subscriber = m_subscribers.Add(m_inst, topic, config);
+  topic->localSubscribers.Add(subscriber);
+  // set subscriber to active if the type matches
+  subscriber->UpdateActive();
+  if (topic->Exists() && !subscriber->active) {
+    // warn on type mismatch
+    INFO(
+        "local subscribe to '{}' disabled due to type mismatch (wanted '{}', "
+        "published as '{}')",
+        topic->name, config.typeStr, topic->typeStr);
+  }
+  if (m_network) {
+    DEBUG4("-> NetworkSubscribe({})", topic->name);
+    m_network->Subscribe(subscriber->handle, {{topic->name}}, config);
+  }
+  return subscriber;
+}
+
+std::unique_ptr<SubscriberData> LSImpl::RemoveLocalSubscriber(
+    NT_Subscriber subHandle) {
+  auto subscriber = m_subscribers.Remove(subHandle);
+  if (subscriber) {
+    auto topic = subscriber->topic;
+    topic->localSubscribers.Remove(subscriber.get());
+    for (auto&& listener : m_listeners) {
+      if (listener.getSecond()->subscriber == subscriber.get()) {
+        listener.getSecond()->subscriber = nullptr;
+      }
+    }
+    if (m_network) {
+      m_network->Unsubscribe(subscriber->handle);
+    }
+  }
+  return subscriber;
+}
+
+EntryData* LSImpl::AddEntry(SubscriberData* subscriber) {
+  auto entry = m_entries.Add(m_inst, subscriber);
+  subscriber->topic->entries.Add(entry);
+  return entry;
+}
+
+std::unique_ptr<EntryData> LSImpl::RemoveEntry(NT_Entry entryHandle) {
+  auto entry = m_entries.Remove(entryHandle);
+  if (entry) {
+    entry->topic->entries.Remove(entry.get());
+  }
+  return entry;
+}
+
+MultiSubscriberData* LSImpl::AddMultiSubscriber(
+    std::span<const std::string_view> prefixes, const PubSubOptions& options) {
+  auto subscriber = m_multiSubscribers.Add(m_inst, prefixes, options);
+  // subscribe to any already existing topics
+  for (auto&& topic : m_topics) {
+    for (auto&& prefix : prefixes) {
+      if (PrefixMatch(topic->name, prefix, topic->special)) {
+        topic->multiSubscribers.Add(subscriber);
+        break;
+      }
+    }
+  }
+  if (m_network) {
+    m_network->Subscribe(subscriber->handle, subscriber->prefixes,
+                         subscriber->options);
+  }
+  return subscriber;
+}
+
+std::unique_ptr<MultiSubscriberData> LSImpl::RemoveMultiSubscriber(
+    NT_MultiSubscriber subHandle) {
+  auto subscriber = m_multiSubscribers.Remove(subHandle);
+  if (subscriber) {
+    for (auto&& topic : m_topics) {
+      topic->multiSubscribers.Remove(subscriber.get());
+    }
+    for (auto&& listener : m_listeners) {
+      if (listener.getSecond()->multiSubscriber == subscriber.get()) {
+        listener.getSecond()->multiSubscriber = nullptr;
+      }
+    }
+    if (m_network) {
+      m_network->Unsubscribe(subscriber->handle);
+    }
+  }
+  return subscriber;
+}
+
+void LSImpl::AddListenerImpl(NT_Listener listenerHandle, TopicData* topic,
+                             unsigned int eventMask) {
+  if (topic->localSubscribers.size() >= kMaxSubscribers) {
+    ERROR(
+        "reached maximum number of subscribers to '{}', ignoring listener add",
+        topic->name);
+    return;
+  }
+  // subscribe to make sure topic updates are received
+  PubSubConfig config;
+  config.topicsOnly = (eventMask & NT_EVENT_VALUE_ALL) == 0;
+  auto sub = AddLocalSubscriber(topic, config);
+  AddListenerImpl(listenerHandle, sub, eventMask, sub->handle, true);
+}
+
+void LSImpl::AddListenerImpl(NT_Listener listenerHandle,
+                             SubscriberData* subscriber, unsigned int eventMask,
+                             NT_Handle subentryHandle, bool subscriberOwned) {
+  m_listeners.try_emplace(listenerHandle, std::make_unique<ListenerData>(
+                                              listenerHandle, subscriber,
+                                              eventMask, subscriberOwned));
+
+  auto topic = subscriber->topic;
+
+  if ((eventMask & NT_EVENT_TOPIC) != 0) {
+    if (topic->listeners.size() >= kMaxListeners) {
+      ERROR("reached maximum number of listeners to '{}', not adding listener",
+            topic->name);
+      return;
+    }
+
+    m_listenerStorage.Activate(
+        listenerHandle, eventMask & (NT_EVENT_TOPIC | NT_EVENT_IMMEDIATE));
+
+    topic->listeners.Add(listenerHandle);
+
+    // handle immediate publish
+    if ((eventMask & (NT_EVENT_PUBLISH | NT_EVENT_IMMEDIATE)) ==
+            (NT_EVENT_PUBLISH | NT_EVENT_IMMEDIATE) &&
+        topic->Exists()) {
+      m_listenerStorage.Notify({&listenerHandle, 1},
+                               NT_EVENT_PUBLISH | NT_EVENT_IMMEDIATE,
+                               topic->GetTopicInfo());
+    }
+  }
+
+  if ((eventMask & NT_EVENT_VALUE_ALL) != 0) {
+    if (subscriber->valueListeners.size() >= kMaxListeners) {
+      ERROR("reached maximum number of listeners to '{}', not adding listener",
+            topic->name);
+      return;
+    }
+    m_listenerStorage.Activate(
+        listenerHandle, eventMask & (NT_EVENT_VALUE_ALL | NT_EVENT_IMMEDIATE),
+        [subentryHandle](unsigned int mask, Event* event) {
+          if (auto valueData = event->GetValueEventData()) {
+            valueData->subentry = subentryHandle;
+          }
+          return true;
+        });
+
+    subscriber->valueListeners.Add(listenerHandle);
+
+    // handle immediate value
+    if ((eventMask & NT_EVENT_VALUE_ALL) != 0 &&
+        (eventMask & NT_EVENT_IMMEDIATE) != 0 && topic->lastValue) {
+      m_listenerStorage.Notify({&listenerHandle, 1},
+                               NT_EVENT_IMMEDIATE | NT_EVENT_VALUE_ALL,
+                               topic->handle, subentryHandle, topic->lastValue);
+    }
+  }
+}
+
+void LSImpl::AddListenerImpl(NT_Listener listenerHandle,
+                             MultiSubscriberData* subscriber,
+                             unsigned int eventMask, bool subscriberOwned) {
+  auto listener =
+      m_listeners
+          .try_emplace(listenerHandle, std::make_unique<ListenerData>(
+                                           listenerHandle, subscriber,
+                                           eventMask, subscriberOwned))
+          .first->getSecond()
+          .get();
+
+  // if we're doing anything immediate, get the list of matching topics
+  wpi::SmallVector<TopicData*, 32> topics;
+  if ((eventMask & NT_EVENT_IMMEDIATE) != 0 &&
+      (eventMask & (NT_EVENT_PUBLISH | NT_EVENT_VALUE_ALL)) != 0) {
+    for (auto&& topic : m_topics) {
+      if (topic->Exists() && subscriber->Matches(topic->name, topic->special)) {
+        topics.emplace_back(topic.get());
+      }
+    }
+  }
+
+  if ((eventMask & NT_EVENT_TOPIC) != 0) {
+    if (m_topicPrefixListeners.size() >= kMaxListeners) {
+      ERROR("reached maximum number of listeners, not adding listener");
+      return;
+    }
+
+    m_listenerStorage.Activate(
+        listenerHandle, eventMask & (NT_EVENT_TOPIC | NT_EVENT_IMMEDIATE));
+
+    m_topicPrefixListeners.Add(listener);
+
+    // handle immediate publish
+    if ((eventMask & (NT_EVENT_PUBLISH | NT_EVENT_IMMEDIATE)) ==
+        (NT_EVENT_PUBLISH | NT_EVENT_IMMEDIATE)) {
+      std::vector<TopicInfo> topicInfos;
+      for (auto&& topic : topics) {
+        topicInfos.emplace_back(topic->GetTopicInfo());
+      }
+      if (!topicInfos.empty()) {
+        m_listenerStorage.Notify({&listenerHandle, 1},
+                                 NT_EVENT_PUBLISH | NT_EVENT_IMMEDIATE,
+                                 topicInfos);
+      }
+    }
+  }
+
+  if ((eventMask & NT_EVENT_VALUE_ALL) != 0) {
+    if (subscriber->valueListeners.size() >= kMaxListeners) {
+      ERROR("reached maximum number of listeners, not adding listener");
+      return;
+    }
+
+    m_listenerStorage.Activate(
+        listenerHandle, eventMask & (NT_EVENT_VALUE_ALL | NT_EVENT_IMMEDIATE),
+        [subentryHandle = subscriber->handle.GetHandle()](unsigned int mask,
+                                                          Event* event) {
+          if (auto valueData = event->GetValueEventData()) {
+            valueData->subentry = subentryHandle;
+          }
+          return true;
+        });
+
+    subscriber->valueListeners.Add(listenerHandle);
+
+    // handle immediate value
+    if ((eventMask & NT_EVENT_VALUE_ALL) != 0 &&
+        (eventMask & NT_EVENT_IMMEDIATE) != 0) {
+      for (auto&& topic : topics) {
+        if (topic->lastValue) {
+          m_listenerStorage.Notify(
+              {&listenerHandle, 1}, NT_EVENT_VALUE_ALL | NT_EVENT_IMMEDIATE,
+              topic->handle, subscriber->handle, topic->lastValue);
+        }
+      }
+    }
+  }
+}
+
+void LSImpl::AddListener(NT_Listener listenerHandle,
+                         std::span<const std::string_view> prefixes,
+                         unsigned int eventMask) {
+  if (m_multiSubscribers.size() >= kMaxMultiSubscribers) {
+    ERROR("reached maximum number of multi-subscribers, not adding listener");
+    return;
+  }
+  // subscribe to make sure topic updates are received
+  auto sub = AddMultiSubscriber(
+      prefixes, {.topicsOnly = (eventMask & NT_EVENT_VALUE_ALL) == 0});
+  AddListenerImpl(listenerHandle, sub, eventMask, true);
+}
+
+void LSImpl::AddListener(NT_Listener listenerHandle, NT_Handle handle,
+                         unsigned int mask) {
+  if (auto topic = m_topics.Get(handle)) {
+    AddListenerImpl(listenerHandle, topic, mask);
+  } else if (auto sub = m_multiSubscribers.Get(handle)) {
+    AddListenerImpl(listenerHandle, sub, mask, false);
+  } else if (auto sub = m_subscribers.Get(handle)) {
+    AddListenerImpl(listenerHandle, sub, mask, sub->handle, false);
+  } else if (auto entry = m_entries.Get(handle)) {
+    AddListenerImpl(listenerHandle, entry->subscriber, mask, entry->handle,
+                    false);
+  }
+}
+
+void LSImpl::RemoveListener(NT_Listener listenerHandle, unsigned int mask) {
+  auto listenerIt = m_listeners.find(listenerHandle);
+  if (listenerIt == m_listeners.end()) {
+    return;
+  }
+  auto listener = std::move(listenerIt->getSecond());
+  m_listeners.erase(listenerIt);
+  if (!listener) {
+    return;
+  }
+
+  m_topicPrefixListeners.Remove(listener.get());
+  if (listener->subscriber) {
+    listener->subscriber->valueListeners.Remove(listenerHandle);
+    listener->subscriber->topic->listeners.Remove(listenerHandle);
+    if (listener->subscriberOwned) {
+      RemoveLocalSubscriber(listener->subscriber->handle);
+    }
+  }
+  if (listener->multiSubscriber) {
+    listener->multiSubscriber->valueListeners.Remove(listenerHandle);
+    if (listener->subscriberOwned) {
+      RemoveMultiSubscriber(listener->multiSubscriber->handle);
+    }
+  }
+}
+
+TopicData* LSImpl::GetOrCreateTopic(std::string_view name) {
+  auto& topic = m_nameTopics[name];
+  // create if it does not already exist
+  if (!topic) {
+    topic = m_topics.Add(m_inst, name);
+    // attach multi-subscribers
+    for (auto&& sub : m_multiSubscribers) {
+      if (sub->Matches(name, topic->special)) {
+        topic->multiSubscribers.Add(sub.get());
+      }
+    }
+  }
+  return topic;
+}
+
+TopicData* LSImpl::GetTopic(NT_Handle handle) {
+  switch (Handle{handle}.GetType()) {
+    case Handle::kEntry: {
+      if (auto entry = m_entries.Get(handle)) {
+        return entry->topic;
+      }
+      break;
+    }
+    case Handle::kSubscriber: {
+      if (auto subscriber = m_subscribers.Get(handle)) {
+        return subscriber->topic;
+      }
+      break;
+    }
+    case Handle::kPublisher: {
+      if (auto publisher = m_publishers.Get(handle)) {
+        return publisher->topic;
+      }
+      break;
+    }
+    case Handle::kTopic:
+      return m_topics.Get(handle);
+    default:
+      break;
+  }
+  return {};
+}
+
+SubscriberData* LSImpl::GetSubEntry(NT_Handle subentryHandle) {
+  Handle h{subentryHandle};
+  if (h.IsType(Handle::kSubscriber)) {
+    return m_subscribers.Get(subentryHandle);
+  } else if (h.IsType(Handle::kEntry)) {
+    auto entry = m_entries.Get(subentryHandle);
+    return entry ? entry->subscriber : nullptr;
+  } else {
+    return nullptr;
+  }
+}
+
+PublisherData* LSImpl::PublishEntry(EntryData* entry, NT_Type type) {
+  if (entry->publisher) {
+    return entry->publisher;
+  }
+  auto typeStr = TypeToString(type);
+  if (entry->subscriber->config.type == NT_UNASSIGNED) {
+    entry->subscriber->config.type = type;
+    entry->subscriber->config.typeStr = typeStr;
+  } else if (entry->subscriber->config.type != type ||
+             entry->subscriber->config.typeStr != typeStr) {
+    if (!IsNumericCompatible(type, entry->subscriber->config.type)) {
+      // don't allow dynamically changing the type of an entry
+      ERROR("cannot publish entry {} as type {}, previously subscribed as {}",
+            entry->topic->name, typeStr, entry->subscriber->config.typeStr);
+      return nullptr;
+    }
+  }
+  // create publisher
+  entry->publisher = AddLocalPublisher(entry->topic, wpi::json::object(),
+                                       entry->subscriber->config);
+  return entry->publisher;
+}
+
+Value* LSImpl::GetSubEntryValue(NT_Handle subentryHandle) {
+  if (auto subscriber = GetSubEntry(subentryHandle)) {
+    return &subscriber->topic->lastValue;
+  } else {
+    return nullptr;
+  }
+}
+
+bool LSImpl::PublishLocalValue(PublisherData* publisher, const Value& value,
+                               bool force) {
+  if (!value) {
+    return false;
+  }
+  if (publisher->topic->type != NT_UNASSIGNED &&
+      publisher->topic->type != value.type()) {
+    if (IsNumericCompatible(publisher->topic->type, value.type())) {
+      return PublishLocalValue(
+          publisher, ConvertNumericValue(value, publisher->topic->type));
+    }
+    return false;
+  }
+  if (publisher->active) {
+    bool isDuplicate, isNetworkDuplicate;
+    if (force || publisher->config.keepDuplicates) {
+      isDuplicate = false;
+      isNetworkDuplicate = false;
+    } else {
+      isDuplicate = (publisher->topic->lastValue == value);
+      isNetworkDuplicate = (publisher->topic->lastValueNetwork == value);
+    }
+    if (!isNetworkDuplicate && m_network) {
+      publisher->topic->lastValueNetwork = value;
+      m_network->SetValue(publisher->handle, value);
+    }
+    return SetValue(publisher->topic, value, NT_EVENT_VALUE_LOCAL, isDuplicate,
+                    publisher);
+  } else {
+    return false;
+  }
+}
+
+bool LSImpl::SetEntryValue(NT_Handle pubentryHandle, const Value& value) {
+  if (!value) {
+    return false;
+  }
+  auto publisher = m_publishers.Get(pubentryHandle);
+  if (!publisher) {
+    if (auto entry = m_entries.Get(pubentryHandle)) {
+      publisher = PublishEntry(entry, value.type());
+      if (entry->subscriber->config.excludeSelf) {
+        entry->subscriber->config.excludePublisher = publisher->handle;
+      }
+    }
+    if (!publisher) {
+      return false;
+    }
+  }
+  return PublishLocalValue(publisher, value);
+}
+
+bool LSImpl::SetDefaultEntryValue(NT_Handle pubsubentryHandle,
+                                  const Value& value) {
+  DEBUG4("SetDefaultEntryValue({}, {})", pubsubentryHandle,
+         static_cast<int>(value.type()));
+  if (!value) {
+    return false;
+  }
+  if (auto topic = GetTopic(pubsubentryHandle)) {
+    if (!topic->lastValue &&
+        (topic->type == NT_UNASSIGNED || topic->type == value.type() ||
+         IsNumericCompatible(topic->type, value.type()))) {
+      // publish if we haven't yet
+      auto publisher = m_publishers.Get(pubsubentryHandle);
+      if (!publisher) {
+        if (auto entry = m_entries.Get(pubsubentryHandle)) {
+          publisher = PublishEntry(entry, value.type());
+        }
+      }
+
+      // force value timestamps to 0
+      if (topic->type == NT_UNASSIGNED) {
+        topic->type = value.type();
+      }
+      if (topic->type == value.type()) {
+        topic->lastValue = value;
+      } else if (IsNumericCompatible(topic->type, value.type())) {
+        topic->lastValue = ConvertNumericValue(value, topic->type);
+      } else {
+        return true;
+      }
+      topic->lastValue.SetTime(0);
+      topic->lastValue.SetServerTime(0);
+      if (publisher) {
+        PublishLocalValue(publisher, topic->lastValue, true);
+      }
+      return true;
+    }
+  }
+  return false;
+}
+
+void LSImpl::RemoveSubEntry(NT_Handle subentryHandle) {
+  Handle h{subentryHandle};
+  if (h.IsType(Handle::kSubscriber)) {
+    RemoveLocalSubscriber(subentryHandle);
+  } else if (h.IsType(Handle::kMultiSubscriber)) {
+    RemoveMultiSubscriber(subentryHandle);
+  } else if (h.IsType(Handle::kEntry)) {
+    if (auto entry = RemoveEntry(subentryHandle)) {
+      RemoveLocalSubscriber(entry->subscriber->handle);
+      if (entry->publisher) {
+        RemoveLocalPublisher(entry->publisher->handle);
+      }
+    }
+  }
+}
+
+class LocalStorage::Impl : public LSImpl {
+ public:
+  Impl(int inst, IListenerStorage& listenerStorage, wpi::Logger& logger)
+      : LSImpl{inst, listenerStorage, logger} {}
+};
+
+LocalStorage::LocalStorage(int inst, IListenerStorage& listenerStorage,
+                           wpi::Logger& logger)
+    : m_impl{std::make_unique<Impl>(inst, listenerStorage, logger)} {}
+
+LocalStorage::~LocalStorage() = default;
+
+NT_Topic LocalStorage::NetworkAnnounce(std::string_view name,
+                                       std::string_view typeStr,
+                                       const wpi::json& properties,
+                                       NT_Publisher pubHandle) {
+  std::scoped_lock lock{m_mutex};
+  auto topic = m_impl->GetOrCreateTopic(name);
+  m_impl->NetworkAnnounce(topic, typeStr, properties, pubHandle);
+  return topic->handle;
+}
+
+void LocalStorage::NetworkUnannounce(std::string_view name) {
+  std::scoped_lock lock{m_mutex};
+  auto topic = m_impl->GetOrCreateTopic(name);
+  m_impl->RemoveNetworkPublisher(topic);
+}
+
+void LocalStorage::NetworkPropertiesUpdate(std::string_view name,
+                                           const wpi::json& update, bool ack) {
+  std::scoped_lock lock{m_mutex};
+  auto it = m_impl->m_nameTopics.find(name);
+  if (it != m_impl->m_nameTopics.end()) {
+    m_impl->NetworkPropertiesUpdate(it->second, update, ack);
+  }
+}
+
+void LocalStorage::NetworkSetValue(NT_Topic topicHandle, const Value& value) {
+  std::scoped_lock lock{m_mutex};
+  if (auto topic = m_impl->m_topics.Get(topicHandle)) {
+    if (m_impl->SetValue(topic, value, NT_EVENT_VALUE_REMOTE,
+                         value == topic->lastValue, nullptr)) {
+      topic->lastValueNetwork = value;
+    }
+  }
+}
+
+void LocalStorage::StartNetwork(net::NetworkInterface* network) {
+  WPI_DEBUG4(m_impl->m_logger, "StartNetwork()");
+  std::scoped_lock lock{m_mutex};
+  m_impl->m_network = network;
+  // publish all active publishers to the network and send last values
+  // only send value once per topic
+  for (auto&& topic : m_impl->m_topics) {
+    PublisherData* anyPublisher = nullptr;
+    for (auto&& publisher : topic->localPublishers) {
+      if (publisher->active) {
+        network->Publish(publisher->handle, topic->handle, topic->name,
+                         topic->typeStr, topic->properties, publisher->config);
+        anyPublisher = publisher;
+      }
+    }
+    if (anyPublisher && topic->lastValue) {
+      network->SetValue(anyPublisher->handle, topic->lastValue);
+    }
+  }
+  for (auto&& subscriber : m_impl->m_subscribers) {
+    network->Subscribe(subscriber->handle, {{subscriber->topic->name}},
+                       subscriber->config);
+  }
+  for (auto&& subscriber : m_impl->m_multiSubscribers) {
+    network->Subscribe(subscriber->handle, subscriber->prefixes,
+                       subscriber->options);
+  }
+}
+
+void LocalStorage::ClearNetwork() {
+  WPI_DEBUG4(m_impl->m_logger, "ClearNetwork()");
+  std::scoped_lock lock{m_mutex};
+  m_impl->m_network = nullptr;
+  // treat as an unannounce all from the network side
+  for (auto&& topic : m_impl->m_topics) {
+    m_impl->RemoveNetworkPublisher(topic.get());
+  }
+}
+
+template <typename T, typename F>
+static void ForEachTopic(T& topics, std::string_view prefix, unsigned int types,
+                         F func) {
+  for (auto&& topic : topics) {
+    if (!topic->Exists()) {
+      continue;
+    }
+    if (!wpi::starts_with(topic->name, prefix)) {
+      continue;
+    }
+    if (types != 0 && (types & topic->type) == 0) {
+      continue;
+    }
+    func(*topic);
+  }
+}
+
+template <typename T, typename F>
+static void ForEachTopic(T& topics, std::string_view prefix,
+                         std::span<const std::string_view> types, F func) {
+  for (auto&& topic : topics) {
+    if (!topic->Exists()) {
+      continue;
+    }
+    if (!wpi::starts_with(topic->name, prefix)) {
+      continue;
+    }
+    if (!types.empty()) {
+      bool match = false;
+      for (auto&& type : types) {
+        if (topic->typeStr == type) {
+          match = true;
+          break;
+        }
+      }
+      if (!match) {
+        continue;
+      }
+    }
+    func(*topic);
+  }
+}
+
+std::vector<NT_Topic> LocalStorage::GetTopics(std::string_view prefix,
+                                              unsigned int types) {
+  std::scoped_lock lock(m_mutex);
+  std::vector<NT_Topic> rv;
+  ForEachTopic(m_impl->m_topics, prefix, types,
+               [&](TopicData& topic) { rv.push_back(topic.handle); });
+  return rv;
+}
+
+std::vector<NT_Topic> LocalStorage::GetTopics(
+    std::string_view prefix, std::span<const std::string_view> types) {
+  std::scoped_lock lock(m_mutex);
+  std::vector<NT_Topic> rv;
+  ForEachTopic(m_impl->m_topics, prefix, types,
+               [&](TopicData& topic) { rv.push_back(topic.handle); });
+  return rv;
+}
+
+std::vector<TopicInfo> LocalStorage::GetTopicInfo(std::string_view prefix,
+                                                  unsigned int types) {
+  std::scoped_lock lock(m_mutex);
+  std::vector<TopicInfo> rv;
+  ForEachTopic(m_impl->m_topics, prefix, types, [&](TopicData& topic) {
+    rv.emplace_back(topic.GetTopicInfo());
+  });
+  return rv;
+}
+
+std::vector<TopicInfo> LocalStorage::GetTopicInfo(
+    std::string_view prefix, std::span<const std::string_view> types) {
+  std::scoped_lock lock(m_mutex);
+  std::vector<TopicInfo> rv;
+  ForEachTopic(m_impl->m_topics, prefix, types, [&](TopicData& topic) {
+    rv.emplace_back(topic.GetTopicInfo());
+  });
+  return rv;
+}
+
+NT_Topic LocalStorage::GetTopic(std::string_view name) {
+  if (name.empty()) {
+    return {};
+  }
+  std::scoped_lock lock{m_mutex};
+  return m_impl->GetOrCreateTopic(name)->handle;
+}
+
+std::string LocalStorage::GetTopicName(NT_Topic topicHandle) {
+  std::scoped_lock lock{m_mutex};
+  if (auto topic = m_impl->m_topics.Get(topicHandle)) {
+    return topic->name;
+  } else {
+    return {};
+  }
+}
+
+NT_Type LocalStorage::GetTopicType(NT_Topic topicHandle) {
+  std::scoped_lock lock{m_mutex};
+  if (auto topic = m_impl->m_topics.Get(topicHandle)) {
+    return topic->type;
+  } else {
+    return {};
+  }
+}
+
+std::string LocalStorage::GetTopicTypeString(NT_Topic topicHandle) {
+  std::scoped_lock lock{m_mutex};
+  if (auto topic = m_impl->m_topics.Get(topicHandle)) {
+    return topic->typeStr;
+  } else {
+    return {};
+  }
+}
+
+void LocalStorage::SetTopicPersistent(NT_Topic topicHandle, bool value) {
+  std::scoped_lock lock{m_mutex};
+  if (auto topic = m_impl->m_topics.Get(topicHandle)) {
+    m_impl->SetPersistent(topic, value);
+  }
+}
+
+bool LocalStorage::GetTopicPersistent(NT_Topic topicHandle) {
+  std::scoped_lock lock{m_mutex};
+  if (auto topic = m_impl->m_topics.Get(topicHandle)) {
+    return (topic->flags & NT_PERSISTENT) != 0;
+  } else {
+    return false;
+  }
+}
+
+void LocalStorage::SetTopicRetained(NT_Topic topicHandle, bool value) {
+  std::scoped_lock lock{m_mutex};
+  if (auto topic = m_impl->m_topics.Get(topicHandle)) {
+    m_impl->SetRetained(topic, value);
+  }
+}
+
+bool LocalStorage::GetTopicRetained(NT_Topic topicHandle) {
+  std::scoped_lock lock{m_mutex};
+  if (auto topic = m_impl->m_topics.Get(topicHandle)) {
+    return (topic->flags & NT_RETAINED) != 0;
+  } else {
+    return false;
+  }
+}
+
+bool LocalStorage::GetTopicExists(NT_Handle handle) {
+  std::scoped_lock lock{m_mutex};
+  TopicData* topic = m_impl->GetTopic(handle);
+  return topic && topic->Exists();
+}
+
+wpi::json LocalStorage::GetTopicProperty(NT_Topic topicHandle,
+                                         std::string_view name) {
+  std::scoped_lock lock{m_mutex};
+  if (auto topic = m_impl->m_topics.Get(topicHandle)) {
+    return topic->properties.value(name, wpi::json{});
+  } else {
+    return {};
+  }
+}
+
+void LocalStorage::SetTopicProperty(NT_Topic topicHandle, std::string_view name,
+                                    const wpi::json& value) {
+  std::scoped_lock lock{m_mutex};
+  if (auto topic = m_impl->m_topics.Get(topicHandle)) {
+    if (value.is_null()) {
+      topic->properties.erase(name);
+    } else {
+      topic->properties[name] = value;
+    }
+    wpi::json update = wpi::json::object();
+    update[name] = value;
+    m_impl->PropertiesUpdated(topic, update, NT_EVENT_NONE, true);
+  }
+}
+
+void LocalStorage::DeleteTopicProperty(NT_Topic topicHandle,
+                                       std::string_view name) {
+  std::scoped_lock lock{m_mutex};
+  if (auto topic = m_impl->m_topics.Get(topicHandle)) {
+    topic->properties.erase(name);
+    wpi::json update = wpi::json::object();
+    update[name] = wpi::json();
+    m_impl->PropertiesUpdated(topic, update, NT_EVENT_NONE, true);
+  }
+}
+
+wpi::json LocalStorage::GetTopicProperties(NT_Topic topicHandle) {
+  std::scoped_lock lock{m_mutex};
+  if (auto topic = m_impl->m_topics.Get(topicHandle)) {
+    return topic->properties;
+  } else {
+    return wpi::json::object();
+  }
+}
+
+bool LocalStorage::SetTopicProperties(NT_Topic topicHandle,
+                                      const wpi::json& update) {
+  if (!update.is_object()) {
+    return false;
+  }
+  std::scoped_lock lock{m_mutex};
+  if (auto topic = m_impl->m_topics.Get(topicHandle)) {
+    m_impl->SetProperties(topic, update, true);
+    return true;
+  } else {
+    return {};
+  }
+}
+
+TopicInfo LocalStorage::GetTopicInfo(NT_Topic topicHandle) {
+  std::scoped_lock lock{m_mutex};
+  if (auto topic = m_impl->m_topics.Get(topicHandle)) {
+    return topic->GetTopicInfo();
+  } else {
+    return {};
+  }
+}
+
+NT_Subscriber LocalStorage::Subscribe(NT_Topic topicHandle, NT_Type type,
+                                      std::string_view typeStr,
+                                      const PubSubOptions& options) {
+  std::scoped_lock lock{m_mutex};
+
+  // Get the topic
+  auto* topic = m_impl->m_topics.Get(topicHandle);
+  if (!topic) {
+    return 0;
+  }
+
+  if (topic->localSubscribers.size() >= kMaxSubscribers) {
+    WPI_ERROR(m_impl->m_logger,
+              "reached maximum number of subscribers to '{}', not subscribing",
+              topic->name);
+    return 0;
+  }
+
+  // Create subscriber
+  return m_impl->AddLocalSubscriber(topic, PubSubConfig{type, typeStr, options})
+      ->handle;
+}
+
+void LocalStorage::Unsubscribe(NT_Subscriber subHandle) {
+  std::scoped_lock lock{m_mutex};
+  m_impl->RemoveSubEntry(subHandle);
+}
+
+NT_MultiSubscriber LocalStorage::SubscribeMultiple(
+    std::span<const std::string_view> prefixes, const PubSubOptions& options) {
+  std::scoped_lock lock{m_mutex};
+
+  if (m_impl->m_multiSubscribers.size() >= kMaxMultiSubscribers) {
+    WPI_ERROR(m_impl->m_logger,
+              "reached maximum number of multi-subscribers, not subscribing");
+    return 0;
+  }
+
+  return m_impl->AddMultiSubscriber(prefixes, options)->handle;
+}
+
+void LocalStorage::UnsubscribeMultiple(NT_MultiSubscriber subHandle) {
+  std::scoped_lock lock{m_mutex};
+  m_impl->RemoveMultiSubscriber(subHandle);
+}
+
+NT_Publisher LocalStorage::Publish(NT_Topic topicHandle, NT_Type type,
+                                   std::string_view typeStr,
+                                   const wpi::json& properties,
+                                   const PubSubOptions& options) {
+  std::scoped_lock lock{m_mutex};
+
+  // Get the topic
+  auto* topic = m_impl->m_topics.Get(topicHandle);
+  if (!topic) {
+    WPI_ERROR(m_impl->m_logger, "trying to publish invalid topic handle ({})",
+              topicHandle);
+    return 0;
+  }
+
+  if (type == NT_UNASSIGNED || typeStr.empty()) {
+    WPI_ERROR(
+        m_impl->m_logger,
+        "cannot publish '{}' with an unassigned type or empty type string",
+        topic->name);
+    return 0;
+  }
+
+  if (topic->localPublishers.size() >= kMaxPublishers) {
+    WPI_ERROR(m_impl->m_logger,
+              "reached maximum number of publishers to '{}', not publishing",
+              topic->name);
+    return 0;
+  }
+
+  return m_impl
+      ->AddLocalPublisher(topic, properties,
+                          PubSubConfig{type, typeStr, options})
+      ->handle;
+}
+
+void LocalStorage::Unpublish(NT_Handle pubentryHandle) {
+  std::scoped_lock lock{m_mutex};
+
+  if (Handle{pubentryHandle}.IsType(Handle::kPublisher)) {
+    m_impl->RemoveLocalPublisher(pubentryHandle);
+  } else if (auto entry = m_impl->m_entries.Get(pubentryHandle)) {
+    if (entry->publisher) {
+      m_impl->RemoveLocalPublisher(entry->publisher->handle);
+      entry->publisher = nullptr;
+    }
+  } else {
+    // TODO: report warning
+    return;
+  }
+}
+
+NT_Entry LocalStorage::GetEntry(NT_Topic topicHandle, NT_Type type,
+                                std::string_view typeStr,
+                                const PubSubOptions& options) {
+  std::scoped_lock lock{m_mutex};
+
+  // Get the topic
+  auto* topic = m_impl->m_topics.Get(topicHandle);
+  if (!topic) {
+    return 0;
+  }
+
+  if (topic->localSubscribers.size() >= kMaxSubscribers) {
+    WPI_ERROR(
+        m_impl->m_logger,
+        "reached maximum number of subscribers to '{}', not creating entry",
+        topic->name);
+    return 0;
+  }
+
+  // Create subscriber
+  auto subscriber =
+      m_impl->AddLocalSubscriber(topic, PubSubConfig{type, typeStr, options});
+
+  // Create entry
+  return m_impl->AddEntry(subscriber)->handle;
+}
+
+void LocalStorage::ReleaseEntry(NT_Entry entryHandle) {
+  std::scoped_lock lock{m_mutex};
+  m_impl->RemoveSubEntry(entryHandle);
+}
+
+void LocalStorage::Release(NT_Handle pubsubentryHandle) {
+  switch (Handle{pubsubentryHandle}.GetType()) {
+    case Handle::kEntry:
+      ReleaseEntry(pubsubentryHandle);
+      break;
+    case Handle::kPublisher:
+      Unpublish(pubsubentryHandle);
+      break;
+    case Handle::kSubscriber:
+      Unsubscribe(pubsubentryHandle);
+      break;
+    case Handle::kMultiSubscriber:
+      UnsubscribeMultiple(pubsubentryHandle);
+      break;
+    default:
+      break;
+  }
+}
+
+NT_Topic LocalStorage::GetTopicFromHandle(NT_Handle pubsubentryHandle) {
+  std::scoped_lock lock{m_mutex};
+  if (auto topic = m_impl->GetTopic(pubsubentryHandle)) {
+    return topic->handle;
+  } else {
+    return {};
+  }
+}
+
+bool LocalStorage::SetEntryValue(NT_Handle pubentryHandle, const Value& value) {
+  std::scoped_lock lock{m_mutex};
+  return m_impl->SetEntryValue(pubentryHandle, value);
+}
+
+bool LocalStorage::SetDefaultEntryValue(NT_Handle pubsubentryHandle,
+                                        const Value& value) {
+  std::scoped_lock lock{m_mutex};
+  return m_impl->SetDefaultEntryValue(pubsubentryHandle, value);
+}
+
+TimestampedBoolean LocalStorage::GetAtomicBoolean(NT_Handle subentryHandle,
+                                                  bool defaultValue) {
+  std::scoped_lock lock{m_mutex};
+  Value* value = m_impl->GetSubEntryValue(subentryHandle);
+  if (value && value->type() == NT_BOOLEAN) {
+    return {value->time(), value->server_time(), value->GetBoolean()};
+  } else {
+    return {0, 0, defaultValue};
+  }
+}
+
+TimestampedString LocalStorage::GetAtomicString(NT_Handle subentryHandle,
+                                                std::string_view defaultValue) {
+  std::scoped_lock lock{m_mutex};
+  Value* value = m_impl->GetSubEntryValue(subentryHandle);
+  if (value && value->type() == NT_STRING) {
+    return {value->time(), value->server_time(),
+            std::string{value->GetString()}};
+  } else {
+    return {0, 0, std::string{defaultValue}};
+  }
+}
+
+TimestampedStringView LocalStorage::GetAtomicString(
+    NT_Handle subentryHandle, wpi::SmallVectorImpl<char>& buf,
+    std::string_view defaultValue) {
+  std::scoped_lock lock{m_mutex};
+  Value* value = m_impl->GetSubEntryValue(subentryHandle);
+  if (value && value->type() == NT_STRING) {
+    auto str = value->GetString();
+    buf.assign(str.begin(), str.end());
+    return {value->time(), value->server_time(), {buf.data(), buf.size()}};
+  } else {
+    return {0, 0, defaultValue};
+  }
+}
+
+template <typename T, typename U>
+static T GetAtomicNumber(Value* value, U defaultValue) {
+  if (value && value->type() == NT_INTEGER) {
+    return {value->time(), value->server_time(),
+            static_cast<U>(value->GetInteger())};
+  } else if (value && value->type() == NT_FLOAT) {
+    return {value->time(), value->server_time(),
+            static_cast<U>(value->GetFloat())};
+  } else if (value && value->type() == NT_DOUBLE) {
+    return {value->time(), value->server_time(),
+            static_cast<U>(value->GetDouble())};
+  } else {
+    return {0, 0, defaultValue};
+  }
+}
+
+template <typename T, typename U>
+static T GetAtomicNumberArray(Value* value, std::span<const U> defaultValue) {
+  if (value && value->type() == NT_INTEGER_ARRAY) {
+    auto arr = value->GetIntegerArray();
+    return {value->time(), value->server_time(), {arr.begin(), arr.end()}};
+  } else if (value && value->type() == NT_FLOAT_ARRAY) {
+    auto arr = value->GetFloatArray();
+    return {value->time(), value->server_time(), {arr.begin(), arr.end()}};
+  } else if (value && value->type() == NT_DOUBLE_ARRAY) {
+    auto arr = value->GetDoubleArray();
+    return {value->time(), value->server_time(), {arr.begin(), arr.end()}};
+  } else {
+    return {0, 0, {defaultValue.begin(), defaultValue.end()}};
+  }
+}
+
+template <typename T, typename U>
+static T GetAtomicNumberArray(Value* value, wpi::SmallVectorImpl<U>& buf,
+                              std::span<const U> defaultValue) {
+  if (value && value->type() == NT_INTEGER_ARRAY) {
+    auto str = value->GetIntegerArray();
+    buf.assign(str.begin(), str.end());
+    return {value->time(), value->server_time(), {buf.data(), buf.size()}};
+  } else if (value && value->type() == NT_FLOAT_ARRAY) {
+    auto str = value->GetFloatArray();
+    buf.assign(str.begin(), str.end());
+    return {value->time(), value->server_time(), {buf.data(), buf.size()}};
+  } else if (value && value->type() == NT_DOUBLE_ARRAY) {
+    auto str = value->GetDoubleArray();
+    buf.assign(str.begin(), str.end());
+    return {value->time(), value->server_time(), {buf.data(), buf.size()}};
+  } else {
+    buf.assign(defaultValue.begin(), defaultValue.end());
+    return {0, 0, {buf.data(), buf.size()}};
+  }
+}
+
+#define GET_ATOMIC_NUMBER(Name, dtype)                                  \
+  Timestamped##Name LocalStorage::GetAtomic##Name(NT_Handle subentry,   \
+                                                  dtype defaultValue) { \
+    std::scoped_lock lock{m_mutex};                                     \
+    return GetAtomicNumber<Timestamped##Name>(                          \
+        m_impl->GetSubEntryValue(subentry), defaultValue);              \
+  }                                                                     \
+                                                                        \
+  Timestamped##Name##Array LocalStorage::GetAtomic##Name##Array(        \
+      NT_Handle subentry, std::span<const dtype> defaultValue) {        \
+    std::scoped_lock lock{m_mutex};                                     \
+    return GetAtomicNumberArray<Timestamped##Name##Array>(              \
+        m_impl->GetSubEntryValue(subentry), defaultValue);              \
+  }                                                                     \
+                                                                        \
+  Timestamped##Name##ArrayView LocalStorage::GetAtomic##Name##Array(    \
+      NT_Handle subentry, wpi::SmallVectorImpl<dtype>& buf,             \
+      std::span<const dtype> defaultValue) {                            \
+    std::scoped_lock lock{m_mutex};                                     \
+    return GetAtomicNumberArray<Timestamped##Name##ArrayView>(          \
+        m_impl->GetSubEntryValue(subentry), buf, defaultValue);         \
+  }
+
+GET_ATOMIC_NUMBER(Integer, int64_t)
+GET_ATOMIC_NUMBER(Float, float)
+GET_ATOMIC_NUMBER(Double, double)
+
+#define GET_ATOMIC_ARRAY(Name, dtype)                                         \
+  Timestamped##Name LocalStorage::GetAtomic##Name(                            \
+      NT_Handle subentry, std::span<const dtype> defaultValue) {              \
+    std::scoped_lock lock{m_mutex};                                           \
+    Value* value = m_impl->GetSubEntryValue(subentry);                        \
+    if (value && value->Is##Name()) {                                         \
+      auto arr = value->Get##Name();                                          \
+      return {value->time(), value->server_time(), {arr.begin(), arr.end()}}; \
+    } else {                                                                  \
+      return {0, 0, {defaultValue.begin(), defaultValue.end()}};              \
+    }                                                                         \
+  }
+
+GET_ATOMIC_ARRAY(Raw, uint8_t)
+GET_ATOMIC_ARRAY(BooleanArray, int)
+GET_ATOMIC_ARRAY(StringArray, std::string)
+
+#define GET_ATOMIC_SMALL_ARRAY(Name, dtype)                                   \
+  Timestamped##Name##View LocalStorage::GetAtomic##Name(                      \
+      NT_Handle subentry, wpi::SmallVectorImpl<dtype>& buf,                   \
+      std::span<const dtype> defaultValue) {                                  \
+    std::scoped_lock lock{m_mutex};                                           \
+    Value* value = m_impl->GetSubEntryValue(subentry);                        \
+    if (value && value->Is##Name()) {                                         \
+      auto str = value->Get##Name();                                          \
+      buf.assign(str.begin(), str.end());                                     \
+      return {value->time(), value->server_time(), {buf.data(), buf.size()}}; \
+    } else {                                                                  \
+      buf.assign(defaultValue.begin(), defaultValue.end());                   \
+      return {0, 0, {buf.data(), buf.size()}};                                \
+    }                                                                         \
+  }
+
+GET_ATOMIC_SMALL_ARRAY(Raw, uint8_t)
+GET_ATOMIC_SMALL_ARRAY(BooleanArray, int)
+
+std::vector<Value> LocalStorage::ReadQueueValue(NT_Handle subentry) {
+  std::scoped_lock lock{m_mutex};
+  auto subscriber = m_impl->GetSubEntry(subentry);
+  if (!subscriber) {
+    return {};
+  }
+  std::vector<Value> rv;
+  rv.reserve(subscriber->pollStorage.size());
+  for (auto&& val : subscriber->pollStorage) {
+    rv.emplace_back(std::move(val));
+  }
+  subscriber->pollStorage.reset();
+  return rv;
+}
+
+std::vector<TimestampedBoolean> LocalStorage::ReadQueueBoolean(
+    NT_Handle subentry) {
+  std::scoped_lock lock{m_mutex};
+  auto subscriber = m_impl->GetSubEntry(subentry);
+  if (!subscriber) {
+    return {};
+  }
+  std::vector<TimestampedBoolean> rv;
+  rv.reserve(subscriber->pollStorage.size());
+  for (auto&& val : subscriber->pollStorage) {
+    if (val.IsBoolean()) {
+      rv.emplace_back(val.time(), val.server_time(), val.GetBoolean());
+    }
+  }
+  subscriber->pollStorage.reset();
+  return rv;
+}
+
+std::vector<TimestampedString> LocalStorage::ReadQueueString(
+    NT_Handle subentry) {
+  std::scoped_lock lock{m_mutex};
+  auto subscriber = m_impl->GetSubEntry(subentry);
+  if (!subscriber) {
+    return {};
+  }
+  std::vector<TimestampedString> rv;
+  rv.reserve(subscriber->pollStorage.size());
+  for (auto&& val : subscriber->pollStorage) {
+    if (val.IsString()) {
+      rv.emplace_back(val.time(), val.server_time(),
+                      std::string{val.GetString()});
+    }
+  }
+  subscriber->pollStorage.reset();
+  return rv;
+}
+
+#define READ_QUEUE_ARRAY(Name)                                         \
+  std::vector<Timestamped##Name> LocalStorage::ReadQueue##Name(        \
+      NT_Handle subentry) {                                            \
+    std::scoped_lock lock{m_mutex};                                    \
+    auto subscriber = m_impl->GetSubEntry(subentry);                   \
+    if (!subscriber) {                                                 \
+      return {};                                                       \
+    }                                                                  \
+    std::vector<Timestamped##Name> rv;                                 \
+    rv.reserve(subscriber->pollStorage.size());                        \
+    for (auto&& val : subscriber->pollStorage) {                       \
+      if (val.Is##Name()) {                                            \
+        auto arr = val.Get##Name();                                    \
+        rv.emplace_back(Timestamped##Name{                             \
+            val.time(), val.server_time(), {arr.begin(), arr.end()}}); \
+      }                                                                \
+    }                                                                  \
+    subscriber->pollStorage.reset();                                   \
+    return rv;                                                         \
+  }
+
+READ_QUEUE_ARRAY(Raw)
+READ_QUEUE_ARRAY(BooleanArray)
+READ_QUEUE_ARRAY(StringArray)
+
+template <typename T>
+static std::vector<T> ReadQueueNumber(SubscriberData* subscriber) {
+  if (!subscriber) {
+    return {};
+  }
+  std::vector<T> rv;
+  rv.reserve(subscriber->pollStorage.size());
+  for (auto&& val : subscriber->pollStorage) {
+    auto ts = val.time();
+    auto sts = val.server_time();
+    if (val.IsInteger()) {
+      rv.emplace_back(T(ts, sts, val.GetInteger()));
+    } else if (val.IsFloat()) {
+      rv.emplace_back(T(ts, sts, val.GetFloat()));
+    } else if (val.IsDouble()) {
+      rv.emplace_back(T(ts, sts, val.GetDouble()));
+    }
+  }
+  subscriber->pollStorage.reset();
+  return rv;
+}
+
+template <typename T>
+static std::vector<T> ReadQueueNumberArray(SubscriberData* subscriber) {
+  if (!subscriber) {
+    return {};
+  }
+  std::vector<T> rv;
+  rv.reserve(subscriber->pollStorage.size());
+  for (auto&& val : subscriber->pollStorage) {
+    auto ts = val.time();
+    auto sts = val.server_time();
+    if (val.IsIntegerArray()) {
+      auto arr = val.GetIntegerArray();
+      rv.emplace_back(T{ts, sts, {arr.begin(), arr.end()}});
+    } else if (val.IsFloatArray()) {
+      auto arr = val.GetFloatArray();
+      rv.emplace_back(T{ts, sts, {arr.begin(), arr.end()}});
+    } else if (val.IsDoubleArray()) {
+      auto arr = val.GetDoubleArray();
+      rv.emplace_back(T{ts, sts, {arr.begin(), arr.end()}});
+    }
+  }
+  subscriber->pollStorage.reset();
+  return rv;
+}
+
+#define READ_QUEUE_NUMBER(Name)                                               \
+  std::vector<Timestamped##Name> LocalStorage::ReadQueue##Name(               \
+      NT_Handle subentry) {                                                   \
+    std::scoped_lock lock{m_mutex};                                           \
+    return ReadQueueNumber<Timestamped##Name>(m_impl->GetSubEntry(subentry)); \
+  }                                                                           \
+                                                                              \
+  std::vector<Timestamped##Name##Array> LocalStorage::ReadQueue##Name##Array( \
+      NT_Handle subentry) {                                                   \
+    std::scoped_lock lock{m_mutex};                                           \
+    return ReadQueueNumberArray<Timestamped##Name##Array>(                    \
+        m_impl->GetSubEntry(subentry));                                       \
+  }
+
+READ_QUEUE_NUMBER(Integer)
+READ_QUEUE_NUMBER(Float)
+READ_QUEUE_NUMBER(Double)
+
+Value LocalStorage::GetEntryValue(NT_Handle subentryHandle) {
+  std::scoped_lock lock{m_mutex};
+  if (auto subscriber = m_impl->GetSubEntry(subentryHandle)) {
+    if (subscriber->config.type == NT_UNASSIGNED ||
+        !subscriber->topic->lastValue ||
+        subscriber->config.type == subscriber->topic->lastValue.type()) {
+      return subscriber->topic->lastValue;
+    } else if (IsNumericCompatible(subscriber->config.type,
+                                   subscriber->topic->lastValue.type())) {
+      return ConvertNumericValue(subscriber->topic->lastValue,
+                                 subscriber->config.type);
+    }
+  }
+  return {};
+}
+
+void LocalStorage::SetEntryFlags(NT_Entry entryHandle, unsigned int flags) {
+  std::scoped_lock lock{m_mutex};
+  if (auto entry = m_impl->m_entries.Get(entryHandle)) {
+    m_impl->SetFlags(entry->subscriber->topic, flags);
+  }
+}
+
+unsigned int LocalStorage::GetEntryFlags(NT_Entry entryHandle) {
+  std::scoped_lock lock{m_mutex};
+  if (auto entry = m_impl->m_entries.Get(entryHandle)) {
+    return entry->subscriber->topic->flags;
+  } else {
+    return 0;
+  }
+}
+
+NT_Entry LocalStorage::GetEntry(std::string_view name) {
+  if (name.empty()) {
+    return {};
+  }
+
+  std::scoped_lock lock{m_mutex};
+
+  // Get the topic data
+  auto* topic = m_impl->GetOrCreateTopic(name);
+
+  if (topic->entry == 0) {
+    if (topic->localSubscribers.size() >= kMaxSubscribers) {
+      WPI_ERROR(
+          m_impl->m_logger,
+          "reached maximum number of subscribers to '{}', not creating entry",
+          topic->name);
+      return 0;
+    }
+
+    // Create subscriber
+    auto* subscriber = m_impl->AddLocalSubscriber(topic, {});
+
+    // Create entry
+    topic->entry = m_impl->AddEntry(subscriber)->handle;
+  }
+
+  return topic->entry;
+}
+
+std::string LocalStorage::GetEntryName(NT_Handle subentryHandle) {
+  std::scoped_lock lock{m_mutex};
+  if (auto subscriber = m_impl->GetSubEntry(subentryHandle)) {
+    return subscriber->topic->name;
+  } else {
+    return {};
+  }
+}
+
+NT_Type LocalStorage::GetEntryType(NT_Handle subentryHandle) {
+  std::scoped_lock lock{m_mutex};
+  if (auto subscriber = m_impl->GetSubEntry(subentryHandle)) {
+    return subscriber->topic->type;
+  } else {
+    return {};
+  }
+}
+
+int64_t LocalStorage::GetEntryLastChange(NT_Handle subentryHandle) {
+  std::scoped_lock lock{m_mutex};
+  if (auto subscriber = m_impl->GetSubEntry(subentryHandle)) {
+    return subscriber->topic->lastValue.time();
+  } else {
+    return 0;
+  }
+}
+
+void LocalStorage::AddListener(NT_Listener listener,
+                               std::span<const std::string_view> prefixes,
+                               unsigned int mask) {
+  mask &= (NT_EVENT_TOPIC | NT_EVENT_VALUE_ALL | NT_EVENT_IMMEDIATE);
+  std::scoped_lock lock{m_mutex};
+  m_impl->AddListener(listener, prefixes, mask);
+}
+
+void LocalStorage::AddListener(NT_Listener listener, NT_Handle handle,
+                               unsigned int mask) {
+  mask &= (NT_EVENT_TOPIC | NT_EVENT_VALUE_ALL | NT_EVENT_IMMEDIATE);
+  std::scoped_lock lock{m_mutex};
+  m_impl->AddListener(listener, handle, mask);
+}
+
+void LocalStorage::RemoveListener(NT_Listener listener, unsigned int mask) {
+  std::scoped_lock lock{m_mutex};
+  m_impl->RemoveListener(listener, mask);
+}
+
+NT_DataLogger LocalStorage::StartDataLog(wpi::log::DataLog& log,
+                                         std::string_view prefix,
+                                         std::string_view logPrefix) {
+  std::scoped_lock lock{m_mutex};
+  auto datalogger =
+      m_impl->m_dataloggers.Add(m_impl->m_inst, log, prefix, logPrefix);
+
+  // start logging any matching topics
+  auto now = nt::Now();
+  for (auto&& topic : m_impl->m_topics) {
+    if (!wpi::starts_with(topic->name, prefix) ||
+        topic->type == NT_UNASSIGNED || topic->typeStr.empty()) {
+      continue;
+    }
+    topic->datalogs.emplace_back(log, datalogger->Start(topic.get(), now),
+                                 datalogger->handle);
+
+    // log current value, if any
+    if (!topic->lastValue) {
+      continue;
+    }
+    topic->datalogType = topic->type;
+    topic->datalogs.back().Append(topic->lastValue);
+  }
+
+  return datalogger->handle;
+}
+
+void LocalStorage::StopDataLog(NT_DataLogger logger) {
+  std::scoped_lock lock{m_mutex};
+  if (auto datalogger = m_impl->m_dataloggers.Remove(logger)) {
+    // finish any active entries
+    auto now = Now();
+    for (auto&& topic : m_impl->m_topics) {
+      auto it =
+          std::find_if(topic->datalogs.begin(), topic->datalogs.end(),
+                       [&](const auto& elem) { return elem.logger == logger; });
+      if (it != topic->datalogs.end()) {
+        it->log->Finish(it->entry, now);
+        topic->datalogs.erase(it);
+      }
+    }
+  }
+}
+
+void LocalStorage::Reset() {
+  std::scoped_lock lock{m_mutex};
+  m_impl = std::make_unique<Impl>(m_impl->m_inst, m_impl->m_listenerStorage,
+                                  m_impl->m_logger);
+}
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/LocalStorage.h b/third_party/allwpilib/ntcore/src/main/native/cpp/LocalStorage.h
new file mode 100644
index 0000000..a93adb0
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/LocalStorage.h
@@ -0,0 +1,219 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <stdint.h>
+
+#include <functional>
+#include <memory>
+#include <span>
+#include <string>
+#include <string_view>
+#include <utility>
+#include <vector>
+
+#include <wpi/mutex.h>
+
+#include "net/NetworkInterface.h"
+#include "ntcore_cpp.h"
+
+namespace wpi {
+class Logger;
+}  // namespace wpi
+
+namespace nt {
+
+class IListenerStorage;
+
+class LocalStorage final : public net::ILocalStorage {
+ public:
+  LocalStorage(int inst, IListenerStorage& listenerStorage,
+               wpi::Logger& logger);
+  LocalStorage(const LocalStorage&) = delete;
+  LocalStorage& operator=(const LocalStorage&) = delete;
+  ~LocalStorage() final;
+
+  // network interface functions
+  NT_Topic NetworkAnnounce(std::string_view name, std::string_view typeStr,
+                           const wpi::json& properties,
+                           NT_Publisher pubHandle) final;
+  void NetworkUnannounce(std::string_view name) final;
+  void NetworkPropertiesUpdate(std::string_view name, const wpi::json& update,
+                               bool ack) final;
+  void NetworkSetValue(NT_Topic topicHandle, const Value& value) final;
+
+  void StartNetwork(net::NetworkInterface* network) final;
+  void ClearNetwork() final;
+
+  // User functions.  These are the actual implementations of the corresponding
+  // user API functions in ntcore_cpp.
+
+  std::vector<NT_Topic> GetTopics(std::string_view prefix, unsigned int types);
+  std::vector<NT_Topic> GetTopics(std::string_view prefix,
+                                  std::span<const std::string_view> types);
+
+  std::vector<TopicInfo> GetTopicInfo(std::string_view prefix,
+                                      unsigned int types);
+  std::vector<TopicInfo> GetTopicInfo(std::string_view prefix,
+                                      std::span<const std::string_view> types);
+
+  NT_Topic GetTopic(std::string_view name);
+
+  std::string GetTopicName(NT_Topic topic);
+
+  NT_Type GetTopicType(NT_Topic topic);
+
+  std::string GetTopicTypeString(NT_Topic topic);
+
+  void SetTopicPersistent(NT_Topic topic, bool value);
+
+  bool GetTopicPersistent(NT_Topic topic);
+
+  void SetTopicRetained(NT_Topic topic, bool value);
+
+  bool GetTopicRetained(NT_Topic topic);
+
+  bool GetTopicExists(NT_Handle handle);
+
+  wpi::json GetTopicProperty(NT_Topic topic, std::string_view name);
+
+  void SetTopicProperty(NT_Topic topic, std::string_view name,
+                        const wpi::json& value);
+
+  void DeleteTopicProperty(NT_Topic topic, std::string_view name);
+
+  wpi::json GetTopicProperties(NT_Topic topic);
+
+  bool SetTopicProperties(NT_Topic topic, const wpi::json& update);
+
+  TopicInfo GetTopicInfo(NT_Topic topic);
+
+  NT_Subscriber Subscribe(NT_Topic topic, NT_Type type,
+                          std::string_view typeStr,
+                          const PubSubOptions& options);
+
+  void Unsubscribe(NT_Subscriber sub);
+
+  NT_MultiSubscriber SubscribeMultiple(
+      std::span<const std::string_view> prefixes, const PubSubOptions& options);
+
+  void UnsubscribeMultiple(NT_MultiSubscriber subHandle);
+
+  NT_Publisher Publish(NT_Topic topic, NT_Type type, std::string_view typeStr,
+                       const wpi::json& properties,
+                       const PubSubOptions& options);
+
+  void Unpublish(NT_Handle pubentry);
+
+  NT_Entry GetEntry(NT_Topic topic, NT_Type type, std::string_view typeStr,
+                    const PubSubOptions& options);
+
+  void ReleaseEntry(NT_Entry entry);
+
+  void Release(NT_Handle pubsubentry);
+
+  NT_Topic GetTopicFromHandle(NT_Handle pubsubentry);
+
+  bool SetEntryValue(NT_Handle pubentry, const Value& value);
+
+  bool SetDefaultEntryValue(NT_Handle pubsubentry, const Value& value);
+
+  TimestampedBoolean GetAtomicBoolean(NT_Handle subentry, bool defaultValue);
+  TimestampedInteger GetAtomicInteger(NT_Handle subentry, int64_t defaultValue);
+  TimestampedFloat GetAtomicFloat(NT_Handle subentry, float defaultValue);
+  TimestampedDouble GetAtomicDouble(NT_Handle subentry, double defaultValue);
+  TimestampedString GetAtomicString(NT_Handle subentry,
+                                    std::string_view defaultValue);
+  TimestampedRaw GetAtomicRaw(NT_Handle subentry,
+                              std::span<const uint8_t> defaultValue);
+  TimestampedBooleanArray GetAtomicBooleanArray(
+      NT_Handle subentry, std::span<const int> defaultValue);
+  TimestampedIntegerArray GetAtomicIntegerArray(
+      NT_Handle subentry, std::span<const int64_t> defaultValue);
+  TimestampedFloatArray GetAtomicFloatArray(
+      NT_Handle subentry, std::span<const float> defaultValue);
+  TimestampedDoubleArray GetAtomicDoubleArray(
+      NT_Handle subentry, std::span<const double> defaultValue);
+  TimestampedStringArray GetAtomicStringArray(
+      NT_Handle subentry, std::span<const std::string> defaultValue);
+
+  TimestampedStringView GetAtomicString(NT_Handle subentry,
+                                        wpi::SmallVectorImpl<char>& buf,
+                                        std::string_view defaultValue);
+  TimestampedRawView GetAtomicRaw(NT_Handle subentry,
+                                  wpi::SmallVectorImpl<uint8_t>& buf,
+                                  std::span<const uint8_t> defaultValue);
+  TimestampedBooleanArrayView GetAtomicBooleanArray(
+      NT_Handle subentry, wpi::SmallVectorImpl<int>& buf,
+      std::span<const int> defaultValue);
+  TimestampedIntegerArrayView GetAtomicIntegerArray(
+      NT_Handle subentry, wpi::SmallVectorImpl<int64_t>& buf,
+      std::span<const int64_t> defaultValue);
+  TimestampedFloatArrayView GetAtomicFloatArray(
+      NT_Handle subentry, wpi::SmallVectorImpl<float>& buf,
+      std::span<const float> defaultValue);
+  TimestampedDoubleArrayView GetAtomicDoubleArray(
+      NT_Handle subentry, wpi::SmallVectorImpl<double>& buf,
+      std::span<const double> defaultValue);
+
+  std::vector<Value> ReadQueueValue(NT_Handle subentry);
+
+  std::vector<TimestampedBoolean> ReadQueueBoolean(NT_Handle subentry);
+  std::vector<TimestampedInteger> ReadQueueInteger(NT_Handle subentry);
+  std::vector<TimestampedFloat> ReadQueueFloat(NT_Handle subentry);
+  std::vector<TimestampedDouble> ReadQueueDouble(NT_Handle subentry);
+  std::vector<TimestampedString> ReadQueueString(NT_Handle subentry);
+  std::vector<TimestampedRaw> ReadQueueRaw(NT_Handle subentry);
+  std::vector<TimestampedBooleanArray> ReadQueueBooleanArray(
+      NT_Handle subentry);
+  std::vector<TimestampedIntegerArray> ReadQueueIntegerArray(
+      NT_Handle subentry);
+  std::vector<TimestampedFloatArray> ReadQueueFloatArray(NT_Handle subentry);
+  std::vector<TimestampedDoubleArray> ReadQueueDoubleArray(NT_Handle subentry);
+  std::vector<TimestampedStringArray> ReadQueueStringArray(NT_Handle subentry);
+
+  //
+  // Backwards compatible user functions
+  //
+
+  Value GetEntryValue(NT_Handle subentry);
+  void SetEntryFlags(NT_Entry entry, unsigned int flags);
+  unsigned int GetEntryFlags(NT_Entry entry);
+
+  // Index-only
+  NT_Entry GetEntry(std::string_view name);
+
+  std::string GetEntryName(NT_Entry entry);
+  NT_Type GetEntryType(NT_Entry entry);
+  int64_t GetEntryLastChange(NT_Entry entry);
+
+  //
+  // Listener functions
+  //
+
+  void AddListener(NT_Listener listener,
+                   std::span<const std::string_view> prefixes,
+                   unsigned int mask);
+  void AddListener(NT_Listener listener, NT_Handle handle, unsigned int mask);
+
+  void RemoveListener(NT_Listener listener, unsigned int mask);
+
+  //
+  // Data log functions
+  //
+  NT_DataLogger StartDataLog(wpi::log::DataLog& log, std::string_view prefix,
+                             std::string_view logPrefix);
+  void StopDataLog(NT_DataLogger logger);
+
+  void Reset();
+
+ private:
+  class Impl;
+  std::unique_ptr<Impl> m_impl;
+
+  wpi::mutex m_mutex;
+};
+
+}  // namespace nt
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/Log.h b/third_party/allwpilib/ntcore/src/main/native/cpp/Log.h
index d3066d7..7e052f9 100644
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/Log.h
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/Log.h
@@ -2,22 +2,27 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
-#ifndef NTCORE_LOG_H_
-#define NTCORE_LOG_H_
+#pragma once
 
 #include <wpi/Logger.h>
 
-#define LOG(level, format, ...) WPI_LOG(m_logger, level, format, __VA_ARGS__)
+#define LOG(level, format, ...) \
+  WPI_LOG(m_logger, level, format __VA_OPT__(, ) __VA_ARGS__)
 
 #undef ERROR
-#define ERROR(format, ...) WPI_ERROR(m_logger, format, __VA_ARGS__)
-#define WARNING(format, ...) WPI_WARNING(m_logger, format, __VA_ARGS__)
-#define INFO(format, ...) WPI_INFO(m_logger, format, __VA_ARGS__)
+#define ERROR(format, ...) \
+  WPI_ERROR(m_logger, format __VA_OPT__(, ) __VA_ARGS__)
+#define WARNING(format, ...) \
+  WPI_WARNING(m_logger, format __VA_OPT__(, ) __VA_ARGS__)
+#define INFO(format, ...) WPI_INFO(m_logger, format __VA_OPT__(, ) __VA_ARGS__)
 
-#define DEBUG0(format, ...) WPI_DEBUG(m_logger, format, __VA_ARGS__)
-#define DEBUG1(format, ...) WPI_DEBUG1(m_logger, format, __VA_ARGS__)
-#define DEBUG2(format, ...) WPI_DEBUG2(m_logger, format, __VA_ARGS__)
-#define DEBUG3(format, ...) WPI_DEBUG3(m_logger, format, __VA_ARGS__)
-#define DEBUG4(format, ...) WPI_DEBUG4(m_logger, format, __VA_ARGS__)
-
-#endif  // NTCORE_LOG_H_
+#define DEBUG0(format, ...) \
+  WPI_DEBUG(m_logger, format __VA_OPT__(, ) __VA_ARGS__)
+#define DEBUG1(format, ...) \
+  WPI_DEBUG1(m_logger, format __VA_OPT__(, ) __VA_ARGS__)
+#define DEBUG2(format, ...) \
+  WPI_DEBUG2(m_logger, format __VA_OPT__(, ) __VA_ARGS__)
+#define DEBUG3(format, ...) \
+  WPI_DEBUG3(m_logger, format __VA_OPT__(, ) __VA_ARGS__)
+#define DEBUG4(format, ...) \
+  WPI_DEBUG4(m_logger, format __VA_OPT__(, ) __VA_ARGS__)
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/LoggerImpl.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/LoggerImpl.cpp
index fcb59d6..f5742d5 100644
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/LoggerImpl.cpp
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/LoggerImpl.cpp
@@ -5,23 +5,27 @@
 #include "LoggerImpl.h"
 
 #include <fmt/format.h>
+#include <wpi/Logger.h>
+#include <wpi/SmallVector.h>
 #include <wpi/fs.h>
 
+#include "IListenerStorage.h"
+
 using namespace nt;
 
 static void DefaultLogger(unsigned int level, const char* file,
                           unsigned int line, const char* msg) {
-  if (level == 20) {
+  if (level == wpi::WPI_LOG_INFO) {
     fmt::print(stderr, "NT: {}\n", msg);
     return;
   }
 
   std::string_view levelmsg;
-  if (level >= 50) {
+  if (level >= wpi::WPI_LOG_CRITICAL) {
     levelmsg = "CRITICAL";
-  } else if (level >= 40) {
+  } else if (level >= wpi::WPI_LOG_ERROR) {
     levelmsg = "ERROR";
-  } else if (level >= 30) {
+  } else if (level >= wpi::WPI_LOG_WARNING) {
     levelmsg = "WARNING";
   } else {
     return;
@@ -29,34 +33,107 @@
   fmt::print(stderr, "NT: {}: {} ({}:{})\n", levelmsg, msg, file, line);
 }
 
-LoggerImpl::LoggerImpl(int inst) : m_inst(inst) {}
+static constexpr unsigned int kFlagCritical = 1u << 16;
+static constexpr unsigned int kFlagError = 1u << 17;
+static constexpr unsigned int kFlagWarning = 1u << 18;
+static constexpr unsigned int kFlagInfo = 1u << 19;
+static constexpr unsigned int kFlagDebug = 1u << 20;
+static constexpr unsigned int kFlagDebug1 = 1u << 21;
+static constexpr unsigned int kFlagDebug2 = 1u << 22;
+static constexpr unsigned int kFlagDebug3 = 1u << 23;
+static constexpr unsigned int kFlagDebug4 = 1u << 24;
 
-void LoggerImpl::Start() {
-  DoStart(m_inst);
+static unsigned int LevelToFlag(unsigned int level) {
+  if (level >= wpi::WPI_LOG_CRITICAL) {
+    return EventFlags::kLogMessage | kFlagCritical;
+  } else if (level >= wpi::WPI_LOG_ERROR) {
+    return EventFlags::kLogMessage | kFlagError;
+  } else if (level >= wpi::WPI_LOG_WARNING) {
+    return EventFlags::kLogMessage | kFlagWarning;
+  } else if (level >= wpi::WPI_LOG_INFO) {
+    return EventFlags::kLogMessage | kFlagInfo;
+  } else if (level >= wpi::WPI_LOG_DEBUG) {
+    return EventFlags::kLogMessage | kFlagDebug;
+  } else if (level >= wpi::WPI_LOG_DEBUG1) {
+    return EventFlags::kLogMessage | kFlagDebug1;
+  } else if (level >= wpi::WPI_LOG_DEBUG2) {
+    return EventFlags::kLogMessage | kFlagDebug2;
+  } else if (level >= wpi::WPI_LOG_DEBUG3) {
+    return EventFlags::kLogMessage | kFlagDebug3;
+  } else if (level >= wpi::WPI_LOG_DEBUG4) {
+    return EventFlags::kLogMessage | kFlagDebug4;
+  } else {
+    return EventFlags::kLogMessage;
+  }
 }
 
-unsigned int LoggerImpl::Add(
-    std::function<void(const LogMessage& msg)> callback, unsigned int min_level,
-    unsigned int max_level) {
-  return DoAdd(callback, min_level, max_level);
+static unsigned int LevelsToEventMask(unsigned int minLevel,
+                                      unsigned int maxLevel) {
+  unsigned int mask = 0;
+  if (minLevel <= wpi::WPI_LOG_CRITICAL && maxLevel >= wpi::WPI_LOG_CRITICAL) {
+    mask |= kFlagCritical;
+  }
+  if (minLevel <= wpi::WPI_LOG_ERROR && maxLevel >= wpi::WPI_LOG_ERROR) {
+    mask |= kFlagError;
+  }
+  if (minLevel <= wpi::WPI_LOG_WARNING && maxLevel >= wpi::WPI_LOG_WARNING) {
+    mask |= kFlagWarning;
+  }
+  if (minLevel <= wpi::WPI_LOG_INFO && maxLevel >= wpi::WPI_LOG_INFO) {
+    mask |= kFlagInfo;
+  }
+  if (minLevel <= wpi::WPI_LOG_DEBUG && maxLevel >= wpi::WPI_LOG_DEBUG) {
+    mask |= kFlagDebug;
+  }
+  if (minLevel <= wpi::WPI_LOG_DEBUG1 && maxLevel >= wpi::WPI_LOG_DEBUG1) {
+    mask |= kFlagDebug1;
+  }
+  if (minLevel <= wpi::WPI_LOG_DEBUG2 && maxLevel >= wpi::WPI_LOG_DEBUG2) {
+    mask |= kFlagDebug2;
+  }
+  if (minLevel <= wpi::WPI_LOG_DEBUG3 && maxLevel >= wpi::WPI_LOG_DEBUG3) {
+    mask |= kFlagDebug3;
+  }
+  if (minLevel <= wpi::WPI_LOG_DEBUG4 && maxLevel >= wpi::WPI_LOG_DEBUG4) {
+    mask |= kFlagDebug4;
+  }
+  if (mask == 0) {
+    mask = EventFlags::kLogMessage;
+  }
+  return mask;
 }
 
-unsigned int LoggerImpl::AddPolled(unsigned int poller_uid,
-                                   unsigned int min_level,
-                                   unsigned int max_level) {
-  return DoAdd(poller_uid, min_level, max_level);
+LoggerImpl::LoggerImpl(IListenerStorage& listenerStorage)
+    : m_listenerStorage{listenerStorage} {}
+
+LoggerImpl::~LoggerImpl() = default;
+
+void LoggerImpl::AddListener(NT_Listener listener, unsigned int minLevel,
+                             unsigned int maxLevel) {
+  ++m_listenerCount;
+  std::scoped_lock lock{m_mutex};
+  m_listenerLevels.emplace_back(listener, minLevel, maxLevel);
+  m_listenerStorage.Activate(listener, LevelsToEventMask(minLevel, maxLevel),
+                             [](unsigned int mask, Event* event) {
+                               event->flags = NT_EVENT_LOGMESSAGE;
+                               return true;
+                             });
+}
+
+void LoggerImpl::RemoveListener(NT_Listener listener) {
+  --m_listenerCount;
+  std::scoped_lock lock{m_mutex};
+  std::erase_if(m_listenerLevels,
+                [&](auto& v) { return v.listener == listener; });
 }
 
 unsigned int LoggerImpl::GetMinLevel() {
-  auto thr = GetThread();
-  if (!thr) {
-    return NT_LOG_INFO;
-  }
+  // return 0;
+  std::scoped_lock lock{m_mutex};
   unsigned int level = NT_LOG_INFO;
-  for (size_t i = 0; i < thr->m_listeners.size(); ++i) {
-    const auto& listener = thr->m_listeners[i];
-    if (listener && listener.min_level < level) {
-      level = listener.min_level;
+  for (auto&& listenerLevel : m_listenerLevels) {
+    if (listenerLevel.minLevel < level) {
+      level = listenerLevel.minLevel;
     }
   }
   return level;
@@ -65,11 +142,10 @@
 void LoggerImpl::Log(unsigned int level, const char* file, unsigned int line,
                      const char* msg) {
   auto filename = fs::path{file}.filename();
-  {
-    auto thr = GetThread();
-    if (!thr || thr->m_listeners.empty()) {
-      DefaultLogger(level, filename.string().c_str(), line, msg);
-    }
+  if (m_listenerCount == 0) {
+    DefaultLogger(level, filename.string().c_str(), line, msg);
+  } else {
+    m_listenerStorage.Notify(LevelToFlag(level), level, filename.string(), line,
+                             msg);
   }
-  Send(UINT_MAX, 0, level, filename.string(), line, msg);
 }
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/LoggerImpl.h b/third_party/allwpilib/ntcore/src/main/native/cpp/LoggerImpl.h
index 2b577c1..13a1b80 100644
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/LoggerImpl.h
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/LoggerImpl.h
@@ -2,76 +2,31 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
-#ifndef NTCORE_LOGGERIMPL_H_
-#define NTCORE_LOGGERIMPL_H_
+#pragma once
 
-#include <utility>
+#include <atomic>
+#include <vector>
 
-#include <wpi/CallbackManager.h>
+#include <wpi/mutex.h>
 
-#include "Handle.h"
+#include "IListenerStorage.h"
+#include "ntcore_c.h"
 #include "ntcore_cpp.h"
 
 namespace nt {
 
-namespace impl {
+class IListenerStorage;
 
-struct LoggerListenerData : public wpi::CallbackListenerData<
-                                std::function<void(const LogMessage& msg)>> {
-  LoggerListenerData() = default;
-  LoggerListenerData(std::function<void(const LogMessage& msg)> callback_,
-                     unsigned int min_level_, unsigned int max_level_)
-      : CallbackListenerData(callback_),
-        min_level(min_level_),
-        max_level(max_level_) {}
-  LoggerListenerData(unsigned int poller_uid_, unsigned int min_level_,
-                     unsigned int max_level_)
-      : CallbackListenerData(poller_uid_),
-        min_level(min_level_),
-        max_level(max_level_) {}
-
-  unsigned int min_level;
-  unsigned int max_level;
-};
-
-class LoggerThread
-    : public wpi::CallbackThread<LoggerThread, LogMessage, LoggerListenerData> {
+class LoggerImpl {
  public:
-  LoggerThread(std::function<void()> on_start, std::function<void()> on_exit,
-               int inst)
-      : CallbackThread(std::move(on_start), std::move(on_exit)), m_inst(inst) {}
+  explicit LoggerImpl(IListenerStorage& listenerStorage);
+  LoggerImpl(const LoggerImpl&) = delete;
+  LoggerImpl& operator=(const LoggerImpl&) = delete;
+  ~LoggerImpl();
 
-  bool Matches(const LoggerListenerData& listener, const LogMessage& data) {
-    return data.level >= listener.min_level && data.level <= listener.max_level;
-  }
-
-  void SetListener(LogMessage* data, unsigned int listener_uid) {
-    data->logger = Handle(m_inst, listener_uid, Handle::kLogger).handle();
-  }
-
-  void DoCallback(std::function<void(const LogMessage& msg)> callback,
-                  const LogMessage& data) {
-    callback(data);
-  }
-
-  int m_inst;
-};
-
-}  // namespace impl
-
-class LoggerImpl : public wpi::CallbackManager<LoggerImpl, impl::LoggerThread> {
-  friend class LoggerTest;
-  friend class wpi::CallbackManager<LoggerImpl, impl::LoggerThread>;
-
- public:
-  explicit LoggerImpl(int inst);
-
-  void Start();
-
-  unsigned int Add(std::function<void(const LogMessage& msg)> callback,
-                   unsigned int min_level, unsigned int max_level);
-  unsigned int AddPolled(unsigned int poller_uid, unsigned int min_level,
-                         unsigned int max_level);
+  void AddListener(NT_Listener listener, unsigned int minLevel,
+                   unsigned int maxLevel);
+  void RemoveListener(NT_Listener listener);
 
   unsigned int GetMinLevel();
 
@@ -79,9 +34,20 @@
            const char* msg);
 
  private:
-  int m_inst;
+  IListenerStorage& m_listenerStorage;
+  std::atomic_int m_listenerCount{0};
+  wpi::mutex m_mutex;
+
+  struct ListenerLevels {
+    ListenerLevels(NT_Listener listener, unsigned int minLevel,
+                   unsigned int maxLevel)
+        : listener{listener}, minLevel{minLevel}, maxLevel{maxLevel} {}
+
+    NT_Listener listener;
+    unsigned int minLevel;
+    unsigned int maxLevel;
+  };
+  std::vector<ListenerLevels> m_listenerLevels;
 };
 
 }  // namespace nt
-
-#endif  // NTCORE_LOGGERIMPL_H_
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/Message.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/Message.cpp
deleted file mode 100644
index 61efed1..0000000
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/Message.cpp
+++ /dev/null
@@ -1,374 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "Message.h"
-
-#include <stdint.h>
-
-#include "Log.h"
-#include "WireDecoder.h"
-#include "WireEncoder.h"
-
-#define kClearAllMagic 0xD06CB27Aul
-
-using namespace nt;
-
-std::shared_ptr<Message> Message::Read(WireDecoder& decoder,
-                                       GetEntryTypeFunc get_entry_type) {
-  unsigned int msg_type = 0;
-  if (!decoder.Read8(&msg_type)) {
-    return nullptr;
-  }
-  auto msg =
-      std::make_shared<Message>(static_cast<MsgType>(msg_type), private_init());
-  switch (msg_type) {
-    case kKeepAlive:
-      break;
-    case kClientHello: {
-      unsigned int proto_rev;
-      if (!decoder.Read16(&proto_rev)) {
-        return nullptr;
-      }
-      msg->m_id = proto_rev;
-      // This intentionally uses the provided proto_rev instead of
-      // decoder.proto_rev().
-      if (proto_rev >= 0x0300u) {
-        if (!decoder.ReadString(&msg->m_str)) {
-          return nullptr;
-        }
-      }
-      break;
-    }
-    case kProtoUnsup: {
-      if (!decoder.Read16(&msg->m_id)) {
-        return nullptr;  // proto rev
-      }
-      break;
-    }
-    case kServerHelloDone:
-      break;
-    case kServerHello:
-      if (decoder.proto_rev() < 0x0300u) {
-        decoder.set_error("received SERVER_HELLO in protocol < 3.0");
-        return nullptr;
-      }
-      if (!decoder.Read8(&msg->m_flags)) {
-        return nullptr;
-      }
-      if (!decoder.ReadString(&msg->m_str)) {
-        return nullptr;
-      }
-      break;
-    case kClientHelloDone:
-      if (decoder.proto_rev() < 0x0300u) {
-        decoder.set_error("received CLIENT_HELLO_DONE in protocol < 3.0");
-        return nullptr;
-      }
-      break;
-    case kEntryAssign: {
-      if (!decoder.ReadString(&msg->m_str)) {
-        return nullptr;  // name
-      }
-      NT_Type type;
-      if (!decoder.ReadType(&type)) {
-        return nullptr;  // entry type
-      }
-      if (!decoder.Read16(&msg->m_id)) {
-        return nullptr;  // id
-      }
-      if (!decoder.Read16(&msg->m_seq_num_uid)) {
-        return nullptr;  // seq num
-      }
-      if (decoder.proto_rev() >= 0x0300u) {
-        if (!decoder.Read8(&msg->m_flags)) {
-          return nullptr;  // flags
-        }
-      }
-      msg->m_value = decoder.ReadValue(type);
-      if (!msg->m_value) {
-        return nullptr;
-      }
-      break;
-    }
-    case kEntryUpdate: {
-      if (!decoder.Read16(&msg->m_id)) {
-        return nullptr;  // id
-      }
-      if (!decoder.Read16(&msg->m_seq_num_uid)) {
-        return nullptr;  // seq num
-      }
-      NT_Type type;
-      if (decoder.proto_rev() >= 0x0300u) {
-        if (!decoder.ReadType(&type)) {
-          return nullptr;
-        }
-      } else {
-        type = get_entry_type(msg->m_id);
-      }
-      WPI_DEBUG4(decoder.logger(), "update message data type: {}", type);
-      msg->m_value = decoder.ReadValue(type);
-      if (!msg->m_value) {
-        return nullptr;
-      }
-      break;
-    }
-    case kFlagsUpdate: {
-      if (decoder.proto_rev() < 0x0300u) {
-        decoder.set_error("received FLAGS_UPDATE in protocol < 3.0");
-        return nullptr;
-      }
-      if (!decoder.Read16(&msg->m_id)) {
-        return nullptr;
-      }
-      if (!decoder.Read8(&msg->m_flags)) {
-        return nullptr;
-      }
-      break;
-    }
-    case kEntryDelete: {
-      if (decoder.proto_rev() < 0x0300u) {
-        decoder.set_error("received ENTRY_DELETE in protocol < 3.0");
-        return nullptr;
-      }
-      if (!decoder.Read16(&msg->m_id)) {
-        return nullptr;
-      }
-      break;
-    }
-    case kClearEntries: {
-      if (decoder.proto_rev() < 0x0300u) {
-        decoder.set_error("received CLEAR_ENTRIES in protocol < 3.0");
-        return nullptr;
-      }
-      uint32_t magic;
-      if (!decoder.Read32(&magic)) {
-        return nullptr;
-      }
-      if (magic != kClearAllMagic) {
-        decoder.set_error(
-            "received incorrect CLEAR_ENTRIES magic value, ignoring");
-        return nullptr;
-      }
-      break;
-    }
-    case kExecuteRpc: {
-      if (decoder.proto_rev() < 0x0300u) {
-        decoder.set_error("received EXECUTE_RPC in protocol < 3.0");
-        return nullptr;
-      }
-      if (!decoder.Read16(&msg->m_id)) {
-        return nullptr;
-      }
-      if (!decoder.Read16(&msg->m_seq_num_uid)) {
-        return nullptr;  // uid
-      }
-      uint64_t size;
-      if (!decoder.ReadUleb128(&size)) {
-        return nullptr;
-      }
-      const char* params;
-      if (!decoder.Read(&params, size)) {
-        return nullptr;
-      }
-      msg->m_str.assign(params, size);
-      break;
-    }
-    case kRpcResponse: {
-      if (decoder.proto_rev() < 0x0300u) {
-        decoder.set_error("received RPC_RESPONSE in protocol < 3.0");
-        return nullptr;
-      }
-      if (!decoder.Read16(&msg->m_id)) {
-        return nullptr;
-      }
-      if (!decoder.Read16(&msg->m_seq_num_uid)) {
-        return nullptr;  // uid
-      }
-      uint64_t size;
-      if (!decoder.ReadUleb128(&size)) {
-        return nullptr;
-      }
-      const char* results;
-      if (!decoder.Read(&results, size)) {
-        return nullptr;
-      }
-      msg->m_str.assign(results, size);
-      break;
-    }
-    default:
-      decoder.set_error("unrecognized message type");
-      WPI_INFO(decoder.logger(), "unrecognized message type: {}", msg_type);
-      return nullptr;
-  }
-  return msg;
-}
-
-std::shared_ptr<Message> Message::ClientHello(std::string_view self_id) {
-  auto msg = std::make_shared<Message>(kClientHello, private_init());
-  msg->m_str = self_id;
-  return msg;
-}
-
-std::shared_ptr<Message> Message::ServerHello(unsigned int flags,
-                                              std::string_view self_id) {
-  auto msg = std::make_shared<Message>(kServerHello, private_init());
-  msg->m_str = self_id;
-  msg->m_flags = flags;
-  return msg;
-}
-
-std::shared_ptr<Message> Message::EntryAssign(std::string_view name,
-                                              unsigned int id,
-                                              unsigned int seq_num,
-                                              std::shared_ptr<Value> value,
-                                              unsigned int flags) {
-  auto msg = std::make_shared<Message>(kEntryAssign, private_init());
-  msg->m_str = name;
-  msg->m_value = value;
-  msg->m_id = id;
-  msg->m_flags = flags;
-  msg->m_seq_num_uid = seq_num;
-  return msg;
-}
-
-std::shared_ptr<Message> Message::EntryUpdate(unsigned int id,
-                                              unsigned int seq_num,
-                                              std::shared_ptr<Value> value) {
-  auto msg = std::make_shared<Message>(kEntryUpdate, private_init());
-  msg->m_value = value;
-  msg->m_id = id;
-  msg->m_seq_num_uid = seq_num;
-  return msg;
-}
-
-std::shared_ptr<Message> Message::FlagsUpdate(unsigned int id,
-                                              unsigned int flags) {
-  auto msg = std::make_shared<Message>(kFlagsUpdate, private_init());
-  msg->m_id = id;
-  msg->m_flags = flags;
-  return msg;
-}
-
-std::shared_ptr<Message> Message::EntryDelete(unsigned int id) {
-  auto msg = std::make_shared<Message>(kEntryDelete, private_init());
-  msg->m_id = id;
-  return msg;
-}
-
-std::shared_ptr<Message> Message::ExecuteRpc(unsigned int id, unsigned int uid,
-                                             std::string_view params) {
-  auto msg = std::make_shared<Message>(kExecuteRpc, private_init());
-  msg->m_str = params;
-  msg->m_id = id;
-  msg->m_seq_num_uid = uid;
-  return msg;
-}
-
-std::shared_ptr<Message> Message::RpcResponse(unsigned int id, unsigned int uid,
-                                              std::string_view result) {
-  auto msg = std::make_shared<Message>(kRpcResponse, private_init());
-  msg->m_str = result;
-  msg->m_id = id;
-  msg->m_seq_num_uid = uid;
-  return msg;
-}
-
-void Message::Write(WireEncoder& encoder) const {
-  switch (m_type) {
-    case kKeepAlive:
-      encoder.Write8(kKeepAlive);
-      break;
-    case kClientHello:
-      encoder.Write8(kClientHello);
-      encoder.Write16(encoder.proto_rev());
-      if (encoder.proto_rev() < 0x0300u) {
-        return;
-      }
-      encoder.WriteString(m_str);
-      break;
-    case kProtoUnsup:
-      encoder.Write8(kProtoUnsup);
-      encoder.Write16(encoder.proto_rev());
-      break;
-    case kServerHelloDone:
-      encoder.Write8(kServerHelloDone);
-      break;
-    case kServerHello:
-      if (encoder.proto_rev() < 0x0300u) {
-        return;  // new message in version 3.0
-      }
-      encoder.Write8(kServerHello);
-      encoder.Write8(m_flags);
-      encoder.WriteString(m_str);
-      break;
-    case kClientHelloDone:
-      if (encoder.proto_rev() < 0x0300u) {
-        return;  // new message in version 3.0
-      }
-      encoder.Write8(kClientHelloDone);
-      break;
-    case kEntryAssign:
-      encoder.Write8(kEntryAssign);
-      encoder.WriteString(m_str);
-      encoder.WriteType(m_value->type());
-      encoder.Write16(m_id);
-      encoder.Write16(m_seq_num_uid);
-      if (encoder.proto_rev() >= 0x0300u) {
-        encoder.Write8(m_flags);
-      }
-      encoder.WriteValue(*m_value);
-      break;
-    case kEntryUpdate:
-      encoder.Write8(kEntryUpdate);
-      encoder.Write16(m_id);
-      encoder.Write16(m_seq_num_uid);
-      if (encoder.proto_rev() >= 0x0300u) {
-        encoder.WriteType(m_value->type());
-      }
-      encoder.WriteValue(*m_value);
-      break;
-    case kFlagsUpdate:
-      if (encoder.proto_rev() < 0x0300u) {
-        return;  // new message in version 3.0
-      }
-      encoder.Write8(kFlagsUpdate);
-      encoder.Write16(m_id);
-      encoder.Write8(m_flags);
-      break;
-    case kEntryDelete:
-      if (encoder.proto_rev() < 0x0300u) {
-        return;  // new message in version 3.0
-      }
-      encoder.Write8(kEntryDelete);
-      encoder.Write16(m_id);
-      break;
-    case kClearEntries:
-      if (encoder.proto_rev() < 0x0300u) {
-        return;  // new message in version 3.0
-      }
-      encoder.Write8(kClearEntries);
-      encoder.Write32(kClearAllMagic);
-      break;
-    case kExecuteRpc:
-      if (encoder.proto_rev() < 0x0300u) {
-        return;  // new message in version 3.0
-      }
-      encoder.Write8(kExecuteRpc);
-      encoder.Write16(m_id);
-      encoder.Write16(m_seq_num_uid);
-      encoder.WriteString(m_str);
-      break;
-    case kRpcResponse:
-      if (encoder.proto_rev() < 0x0300u) {
-        return;  // new message in version 3.0
-      }
-      encoder.Write8(kRpcResponse);
-      encoder.Write16(m_id);
-      encoder.Write16(m_seq_num_uid);
-      encoder.WriteString(m_str);
-      break;
-    default:
-      break;
-  }
-}
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/Message.h b/third_party/allwpilib/ntcore/src/main/native/cpp/Message.h
deleted file mode 100644
index ec34a75..0000000
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/Message.h
+++ /dev/null
@@ -1,114 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef NTCORE_MESSAGE_H_
-#define NTCORE_MESSAGE_H_
-
-#include <functional>
-#include <memory>
-#include <string>
-#include <string_view>
-
-#include "networktables/NetworkTableValue.h"
-
-namespace nt {
-
-class WireDecoder;
-class WireEncoder;
-
-class Message {
-  struct private_init {};
-
- public:
-  enum MsgType {
-    kUnknown = -1,
-    kKeepAlive = 0x00,
-    kClientHello = 0x01,
-    kProtoUnsup = 0x02,
-    kServerHelloDone = 0x03,
-    kServerHello = 0x04,
-    kClientHelloDone = 0x05,
-    kEntryAssign = 0x10,
-    kEntryUpdate = 0x11,
-    kFlagsUpdate = 0x12,
-    kEntryDelete = 0x13,
-    kClearEntries = 0x14,
-    kExecuteRpc = 0x20,
-    kRpcResponse = 0x21
-  };
-  using GetEntryTypeFunc = std::function<NT_Type(unsigned int id)>;
-
-  Message() = default;
-  Message(MsgType type, const private_init&) : m_type(type) {}
-
-  MsgType type() const { return m_type; }
-  bool Is(MsgType type) const { return type == m_type; }
-
-  // Message data accessors.  Callers are responsible for knowing what data is
-  // actually provided for a particular message.
-  std::string_view str() const { return m_str; }
-  std::shared_ptr<Value> value() const { return m_value; }
-  unsigned int id() const { return m_id; }
-  unsigned int flags() const { return m_flags; }
-  unsigned int seq_num_uid() const { return m_seq_num_uid; }
-
-  // Read and write from wire representation
-  void Write(WireEncoder& encoder) const;
-  static std::shared_ptr<Message> Read(WireDecoder& decoder,
-                                       GetEntryTypeFunc get_entry_type);
-
-  // Create messages without data
-  static std::shared_ptr<Message> KeepAlive() {
-    return std::make_shared<Message>(kKeepAlive, private_init());
-  }
-  static std::shared_ptr<Message> ProtoUnsup() {
-    return std::make_shared<Message>(kProtoUnsup, private_init());
-  }
-  static std::shared_ptr<Message> ServerHelloDone() {
-    return std::make_shared<Message>(kServerHelloDone, private_init());
-  }
-  static std::shared_ptr<Message> ClientHelloDone() {
-    return std::make_shared<Message>(kClientHelloDone, private_init());
-  }
-  static std::shared_ptr<Message> ClearEntries() {
-    return std::make_shared<Message>(kClearEntries, private_init());
-  }
-
-  // Create messages with data
-  static std::shared_ptr<Message> ClientHello(std::string_view self_id);
-  static std::shared_ptr<Message> ServerHello(unsigned int flags,
-                                              std::string_view self_id);
-  static std::shared_ptr<Message> EntryAssign(std::string_view name,
-                                              unsigned int id,
-                                              unsigned int seq_num,
-                                              std::shared_ptr<Value> value,
-                                              unsigned int flags);
-  static std::shared_ptr<Message> EntryUpdate(unsigned int id,
-                                              unsigned int seq_num,
-                                              std::shared_ptr<Value> value);
-  static std::shared_ptr<Message> FlagsUpdate(unsigned int id,
-                                              unsigned int flags);
-  static std::shared_ptr<Message> EntryDelete(unsigned int id);
-  static std::shared_ptr<Message> ExecuteRpc(unsigned int id, unsigned int uid,
-                                             std::string_view params);
-  static std::shared_ptr<Message> RpcResponse(unsigned int id, unsigned int uid,
-                                              std::string_view result);
-
-  Message(const Message&) = delete;
-  Message& operator=(const Message&) = delete;
-
- private:
-  MsgType m_type{kUnknown};
-
-  // Message data.  Use varies by message type.
-  std::string m_str;
-  std::shared_ptr<Value> m_value;
-  unsigned int m_id{0};  // also used for proto_rev
-  unsigned int m_flags{0};
-  unsigned int m_seq_num_uid{0};
-};
-
-}  // namespace nt
-
-#endif  // NTCORE_MESSAGE_H_
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/NetworkClient.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/NetworkClient.cpp
new file mode 100644
index 0000000..a329fb9
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/NetworkClient.cpp
@@ -0,0 +1,557 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "NetworkClient.h"
+
+#include <stdint.h>
+
+#include <atomic>
+#include <memory>
+#include <vector>
+
+#include <fmt/format.h>
+#include <wpi/SmallString.h>
+#include <wpi/StringExtras.h>
+#include <wpinet/DsClient.h>
+#include <wpinet/EventLoopRunner.h>
+#include <wpinet/HttpUtil.h>
+#include <wpinet/ParallelTcpConnector.h>
+#include <wpinet/WebSocket.h>
+#include <wpinet/uv/Async.h>
+#include <wpinet/uv/Loop.h>
+#include <wpinet/uv/Tcp.h>
+#include <wpinet/uv/Timer.h>
+#include <wpinet/uv/util.h>
+
+#include "IConnectionList.h"
+#include "Log.h"
+#include "net/ClientImpl.h"
+#include "net/Message.h"
+#include "net/NetworkLoopQueue.h"
+#include "net/WebSocketConnection.h"
+#include "net3/ClientImpl3.h"
+#include "net3/UvStreamConnection3.h"
+
+using namespace nt;
+namespace uv = wpi::uv;
+
+static constexpr uv::Timer::Time kReconnectRate{1000};
+static constexpr uv::Timer::Time kWebsocketHandshakeTimeout{500};
+// use a larger max message size for websockets
+static constexpr size_t kMaxMessageSize = 2 * 1024 * 1024;
+
+namespace {
+
+class NCImpl {
+ public:
+  NCImpl(int inst, std::string_view id, net::ILocalStorage& localStorage,
+         IConnectionList& connList, wpi::Logger& logger);
+  virtual ~NCImpl() = default;
+
+  // user-facing functions
+  void SetServers(std::span<const std::pair<std::string, unsigned int>> servers,
+                  unsigned int defaultPort);
+  void StartDSClient(unsigned int port);
+  void StopDSClient();
+
+  virtual void TcpConnected(uv::Tcp& tcp) = 0;
+  virtual void Disconnect(std::string_view reason);
+
+  // invariants
+  int m_inst;
+  net::ILocalStorage& m_localStorage;
+  IConnectionList& m_connList;
+  wpi::Logger& m_logger;
+  std::string m_id;
+
+  // used only from loop
+  std::shared_ptr<wpi::ParallelTcpConnector> m_parallelConnect;
+  std::shared_ptr<uv::Timer> m_readLocalTimer;
+  std::shared_ptr<uv::Timer> m_sendValuesTimer;
+  std::shared_ptr<uv::Async<>> m_flushLocal;
+  std::shared_ptr<uv::Async<>> m_flush;
+
+  std::vector<net::ClientMessage> m_localMsgs;
+
+  std::vector<std::pair<std::string, unsigned int>> m_servers;
+
+  std::pair<std::string, unsigned int> m_dsClientServer{"", 0};
+  std::shared_ptr<wpi::DsClient> m_dsClient;
+
+  // shared with user
+  std::atomic<uv::Async<>*> m_flushLocalAtomic{nullptr};
+  std::atomic<uv::Async<>*> m_flushAtomic{nullptr};
+
+  net::NetworkLoopQueue m_localQueue;
+
+  int m_connHandle = 0;
+
+  wpi::EventLoopRunner m_loopRunner;
+  uv::Loop& m_loop;
+};
+
+class NCImpl3 : public NCImpl {
+ public:
+  NCImpl3(int inst, std::string_view id, net::ILocalStorage& localStorage,
+          IConnectionList& connList, wpi::Logger& logger);
+  ~NCImpl3() override;
+
+  void HandleLocal();
+  void TcpConnected(uv::Tcp& tcp) final;
+  void Disconnect(std::string_view reason) override;
+
+  std::shared_ptr<net3::UvStreamConnection3> m_wire;
+  std::shared_ptr<net3::ClientImpl3> m_clientImpl;
+};
+
+class NCImpl4 : public NCImpl {
+ public:
+  NCImpl4(
+      int inst, std::string_view id, net::ILocalStorage& localStorage,
+      IConnectionList& connList, wpi::Logger& logger,
+      std::function<void(int64_t serverTimeOffset, int64_t rtt2, bool valid)>
+          timeSyncUpdated);
+  ~NCImpl4() override;
+
+  void HandleLocal();
+  void TcpConnected(uv::Tcp& tcp) final;
+  void WsConnected(wpi::WebSocket& ws, uv::Tcp& tcp);
+  void Disconnect(std::string_view reason) override;
+
+  std::function<void(int64_t serverTimeOffset, int64_t rtt2, bool valid)>
+      m_timeSyncUpdated;
+  std::shared_ptr<net::WebSocketConnection> m_wire;
+  std::unique_ptr<net::ClientImpl> m_clientImpl;
+};
+
+}  // namespace
+
+NCImpl::NCImpl(int inst, std::string_view id, net::ILocalStorage& localStorage,
+               IConnectionList& connList, wpi::Logger& logger)
+    : m_inst{inst},
+      m_localStorage{localStorage},
+      m_connList{connList},
+      m_logger{logger},
+      m_id{id},
+      m_localQueue{logger},
+      m_loop{*m_loopRunner.GetLoop()} {
+  m_localMsgs.reserve(net::NetworkLoopQueue::kInitialQueueSize);
+
+  INFO("starting network client");
+}
+
+void NCImpl::SetServers(
+    std::span<const std::pair<std::string, unsigned int>> servers,
+    unsigned int defaultPort) {
+  std::vector<std::pair<std::string, unsigned int>> serversCopy;
+  serversCopy.reserve(servers.size());
+  for (auto&& server : servers) {
+    serversCopy.emplace_back(wpi::trim(server.first),
+                             server.second == 0 ? defaultPort : server.second);
+  }
+
+  m_loopRunner.ExecAsync(
+      [this, servers = std::move(serversCopy)](uv::Loop&) mutable {
+        m_servers = std::move(servers);
+        if (m_dsClientServer.first.empty()) {
+          m_parallelConnect->SetServers(m_servers);
+        }
+      });
+}
+
+void NCImpl::StartDSClient(unsigned int port) {
+  m_loopRunner.ExecAsync([=, this](uv::Loop& loop) {
+    if (m_dsClient) {
+      return;
+    }
+    m_dsClientServer.second = port == 0 ? NT_DEFAULT_PORT4 : port;
+    m_dsClient = wpi::DsClient::Create(m_loop, m_logger);
+    m_dsClient->setIp.connect([this](std::string_view ip) {
+      m_dsClientServer.first = ip;
+      m_parallelConnect->SetServers({{m_dsClientServer}});
+    });
+    m_dsClient->clearIp.connect([this] {
+      m_dsClientServer.first.clear();
+      m_parallelConnect->SetServers(m_servers);
+    });
+  });
+}
+
+void NCImpl::StopDSClient() {
+  m_loopRunner.ExecAsync([this](uv::Loop& loop) {
+    if (m_dsClient) {
+      m_dsClient->Close();
+      m_dsClient.reset();
+    }
+  });
+}
+
+void NCImpl::Disconnect(std::string_view reason) {
+  if (m_readLocalTimer) {
+    m_readLocalTimer->Stop();
+  }
+  m_sendValuesTimer->Stop();
+  m_localStorage.ClearNetwork();
+  m_localQueue.ClearQueue();
+  m_connList.RemoveConnection(m_connHandle);
+  m_connHandle = 0;
+
+  // start trying to connect again
+  uv::Timer::SingleShot(m_loop, kReconnectRate,
+                        [this] { m_parallelConnect->Disconnected(); });
+}
+
+NCImpl3::NCImpl3(int inst, std::string_view id,
+                 net::ILocalStorage& localStorage, IConnectionList& connList,
+                 wpi::Logger& logger)
+    : NCImpl{inst, id, localStorage, connList, logger} {
+  m_loopRunner.ExecAsync([this](uv::Loop& loop) {
+    m_parallelConnect = wpi::ParallelTcpConnector::Create(
+        loop, kReconnectRate, m_logger,
+        [this](uv::Tcp& tcp) { TcpConnected(tcp); });
+
+    m_sendValuesTimer = uv::Timer::Create(loop);
+    m_sendValuesTimer->timeout.connect([this] {
+      if (m_clientImpl) {
+        HandleLocal();
+        m_clientImpl->SendPeriodic(m_loop.Now().count());
+      }
+    });
+
+    // set up flush async
+    m_flush = uv::Async<>::Create(m_loop);
+    m_flush->wakeup.connect([this] {
+      if (m_clientImpl) {
+        HandleLocal();
+        m_clientImpl->SendPeriodic(m_loop.Now().count());
+      }
+    });
+    m_flushAtomic = m_flush.get();
+
+    m_flushLocal = uv::Async<>::Create(m_loop);
+    m_flushLocal->wakeup.connect([this] { HandleLocal(); });
+    m_flushLocalAtomic = m_flushLocal.get();
+  });
+}
+
+NCImpl3::~NCImpl3() {
+  // must explicitly destroy these on loop
+  m_loopRunner.ExecSync([&](auto&) {
+    m_clientImpl.reset();
+    m_wire.reset();
+  });
+  // shut down loop here to avoid race
+  m_loopRunner.Stop();
+}
+
+void NCImpl3::HandleLocal() {
+  m_localQueue.ReadQueue(&m_localMsgs);
+  if (m_clientImpl) {
+    m_clientImpl->HandleLocal(m_localMsgs);
+  }
+}
+
+void NCImpl3::TcpConnected(uv::Tcp& tcp) {
+  tcp.SetNoDelay(true);
+
+  // create as shared_ptr and capture in lambda because there may be multiple
+  // simultaneous attempts
+  auto wire = std::make_shared<net3::UvStreamConnection3>(tcp);
+  auto clientImpl = std::make_shared<net3::ClientImpl3>(
+      m_loop.Now().count(), m_inst, *wire, m_logger, [this](uint32_t repeatMs) {
+        DEBUG4("Setting periodic timer to {}", repeatMs);
+        m_sendValuesTimer->Start(uv::Timer::Time{repeatMs},
+                                 uv::Timer::Time{repeatMs});
+      });
+  clientImpl->Start(
+      m_id, [this, wire,
+             clientWeak = std::weak_ptr<net3::ClientImpl3>{clientImpl}, &tcp] {
+        auto clientImpl = clientWeak.lock();
+        if (!clientImpl) {
+          return;
+        }
+        if (m_connList.IsConnected()) {
+          tcp.Close();  // no longer needed
+          return;
+        }
+
+        m_parallelConnect->Succeeded(tcp);
+
+        m_wire = std::move(wire);
+        m_clientImpl = std::move(clientImpl);
+
+        ConnectionInfo connInfo;
+        uv::AddrToName(tcp.GetPeer(), &connInfo.remote_ip,
+                       &connInfo.remote_port);
+        connInfo.protocol_version = 0x0300;
+
+        INFO("CONNECTED NT3 to {} port {}", connInfo.remote_ip,
+             connInfo.remote_port);
+        m_connHandle = m_connList.AddConnection(connInfo);
+
+        tcp.error.connect([this, &tcp](uv::Error err) {
+          DEBUG3("NT3 TCP error {}", err.str());
+          if (!tcp.IsLoopClosing()) {
+            Disconnect(err.str());
+          }
+        });
+        tcp.end.connect([this, &tcp] {
+          DEBUG3("NT3 TCP read ended");
+          if (!tcp.IsLoopClosing()) {
+            Disconnect("remote end closed connection");
+          }
+        });
+        tcp.closed.connect([this, &tcp] {
+          DEBUG3("NT3 TCP connection closed");
+          if (!tcp.IsLoopClosing()) {
+            Disconnect(m_wire->GetDisconnectReason());
+          }
+        });
+
+        m_clientImpl->SetLocal(&m_localStorage);
+        m_localStorage.StartNetwork(&m_localQueue);
+        HandleLocal();
+      });
+
+  tcp.SetData(clientImpl);
+  tcp.data.connect(
+      [clientImpl = clientImpl.get()](uv::Buffer& buf, size_t len) {
+        clientImpl->ProcessIncoming(
+            {reinterpret_cast<const uint8_t*>(buf.base), len});
+      });
+  tcp.StartRead();
+}
+
+void NCImpl3::Disconnect(std::string_view reason) {
+  INFO("DISCONNECTED NT3 connection: {}", reason);
+  m_clientImpl.reset();
+  m_wire.reset();
+  NCImpl::Disconnect(reason);
+}
+
+NCImpl4::NCImpl4(
+    int inst, std::string_view id, net::ILocalStorage& localStorage,
+    IConnectionList& connList, wpi::Logger& logger,
+    std::function<void(int64_t serverTimeOffset, int64_t rtt2, bool valid)>
+        timeSyncUpdated)
+    : NCImpl{inst, id, localStorage, connList, logger},
+      m_timeSyncUpdated{std::move(timeSyncUpdated)} {
+  m_loopRunner.ExecAsync([this](uv::Loop& loop) {
+    m_parallelConnect = wpi::ParallelTcpConnector::Create(
+        loop, kReconnectRate, m_logger,
+        [this](uv::Tcp& tcp) { TcpConnected(tcp); });
+
+    m_readLocalTimer = uv::Timer::Create(loop);
+    m_readLocalTimer->timeout.connect([this] {
+      if (m_clientImpl) {
+        HandleLocal();
+        m_clientImpl->SendControl(m_loop.Now().count());
+      }
+    });
+    m_readLocalTimer->Start(uv::Timer::Time{100}, uv::Timer::Time{100});
+
+    m_sendValuesTimer = uv::Timer::Create(loop);
+    m_sendValuesTimer->timeout.connect([this] {
+      if (m_clientImpl) {
+        HandleLocal();
+        m_clientImpl->SendValues(m_loop.Now().count());
+      }
+    });
+
+    // set up flush async
+    m_flush = uv::Async<>::Create(m_loop);
+    m_flush->wakeup.connect([this] {
+      if (m_clientImpl) {
+        HandleLocal();
+        m_clientImpl->SendValues(m_loop.Now().count());
+      }
+    });
+    m_flushAtomic = m_flush.get();
+
+    m_flushLocal = uv::Async<>::Create(m_loop);
+    m_flushLocal->wakeup.connect([this] { HandleLocal(); });
+    m_flushLocalAtomic = m_flushLocal.get();
+  });
+}
+
+NCImpl4::~NCImpl4() {
+  // must explicitly destroy these on loop
+  m_loopRunner.ExecSync([&](auto&) {
+    m_clientImpl.reset();
+    m_wire.reset();
+  });
+  // shut down loop here to avoid race
+  m_loopRunner.Stop();
+}
+
+void NCImpl4::HandleLocal() {
+  m_localQueue.ReadQueue(&m_localMsgs);
+  if (m_clientImpl) {
+    m_clientImpl->HandleLocal(std::move(m_localMsgs));
+  }
+}
+
+void NCImpl4::TcpConnected(uv::Tcp& tcp) {
+  tcp.SetNoDelay(true);
+  // Start the WS client
+  if (m_logger.min_level() >= wpi::WPI_LOG_DEBUG4) {
+    std::string ip;
+    unsigned int port = 0;
+    uv::AddrToName(tcp.GetPeer(), &ip, &port);
+    DEBUG4("Starting WebSocket client on {} port {}", ip, port);
+  }
+  wpi::WebSocket::ClientOptions options;
+  options.handshakeTimeout = kWebsocketHandshakeTimeout;
+  wpi::SmallString<128> idBuf;
+  auto ws = wpi::WebSocket::CreateClient(
+      tcp, fmt::format("/nt/{}", wpi::EscapeURI(m_id, idBuf)), "",
+      {{"networktables.first.wpi.edu"}}, options);
+  ws->SetMaxMessageSize(kMaxMessageSize);
+  ws->open.connect([this, &tcp, ws = ws.get()](std::string_view) {
+    if (m_connList.IsConnected()) {
+      ws->Terminate(1006, "no longer needed");
+      return;
+    }
+    WsConnected(*ws, tcp);
+  });
+}
+
+void NCImpl4::WsConnected(wpi::WebSocket& ws, uv::Tcp& tcp) {
+  m_parallelConnect->Succeeded(tcp);
+
+  ConnectionInfo connInfo;
+  uv::AddrToName(tcp.GetPeer(), &connInfo.remote_ip, &connInfo.remote_port);
+  connInfo.protocol_version = 0x0400;
+
+  INFO("CONNECTED NT4 to {} port {}", connInfo.remote_ip, connInfo.remote_port);
+  m_connHandle = m_connList.AddConnection(connInfo);
+
+  m_wire = std::make_shared<net::WebSocketConnection>(ws);
+  m_clientImpl = std::make_unique<net::ClientImpl>(
+      m_loop.Now().count(), m_inst, *m_wire, m_logger, m_timeSyncUpdated,
+      [this](uint32_t repeatMs) {
+        DEBUG4("Setting periodic timer to {}", repeatMs);
+        m_sendValuesTimer->Start(uv::Timer::Time{repeatMs},
+                                 uv::Timer::Time{repeatMs});
+      });
+  m_clientImpl->SetLocal(&m_localStorage);
+  m_localStorage.StartNetwork(&m_localQueue);
+  HandleLocal();
+  m_clientImpl->SendInitial();
+  ws.closed.connect([this, &ws](uint16_t, std::string_view reason) {
+    if (!ws.GetStream().IsLoopClosing()) {
+      Disconnect(reason);
+    }
+  });
+  ws.text.connect([this](std::string_view data, bool) {
+    if (m_clientImpl) {
+      m_clientImpl->ProcessIncomingText(data);
+    }
+  });
+  ws.binary.connect([this](std::span<const uint8_t> data, bool) {
+    if (m_clientImpl) {
+      m_clientImpl->ProcessIncomingBinary(data);
+    }
+  });
+}
+
+void NCImpl4::Disconnect(std::string_view reason) {
+  INFO("DISCONNECTED NT4 connection: {}", reason);
+  m_clientImpl.reset();
+  m_wire.reset();
+  NCImpl::Disconnect(reason);
+  m_timeSyncUpdated(0, 0, false);
+}
+
+class NetworkClient::Impl final : public NCImpl4 {
+ public:
+  Impl(int inst, std::string_view id, net::ILocalStorage& localStorage,
+       IConnectionList& connList, wpi::Logger& logger,
+       std::function<void(int64_t serverTimeOffset, int64_t rtt2, bool valid)>
+           timeSyncUpdated)
+      : NCImpl4{inst,     id,     localStorage,
+                connList, logger, std::move(timeSyncUpdated)} {}
+};
+
+NetworkClient::NetworkClient(
+    int inst, std::string_view id, net::ILocalStorage& localStorage,
+    IConnectionList& connList, wpi::Logger& logger,
+    std::function<void(int64_t serverTimeOffset, int64_t rtt2, bool valid)>
+        timeSyncUpdated)
+    : m_impl{std::make_unique<Impl>(inst, id, localStorage, connList, logger,
+                                    std::move(timeSyncUpdated))} {}
+
+NetworkClient::~NetworkClient() {
+  m_impl->m_localStorage.ClearNetwork();
+  m_impl->m_connList.ClearConnections();
+}
+
+void NetworkClient::SetServers(
+    std::span<const std::pair<std::string, unsigned int>> servers) {
+  m_impl->SetServers(servers, NT_DEFAULT_PORT4);
+}
+
+void NetworkClient::StartDSClient(unsigned int port) {
+  m_impl->StartDSClient(port);
+}
+
+void NetworkClient::StopDSClient() {
+  m_impl->StopDSClient();
+}
+
+void NetworkClient::FlushLocal() {
+  m_impl->m_loopRunner.ExecAsync([this](uv::Loop&) { m_impl->HandleLocal(); });
+}
+
+void NetworkClient::Flush() {
+  m_impl->m_loopRunner.ExecAsync([this](uv::Loop&) {
+    m_impl->HandleLocal();
+    if (m_impl->m_clientImpl) {
+      m_impl->m_clientImpl->SendValues(m_impl->m_loop.Now().count());
+    }
+  });
+}
+
+class NetworkClient3::Impl final : public NCImpl3 {
+ public:
+  Impl(int inst, std::string_view id, net::ILocalStorage& localStorage,
+       IConnectionList& connList, wpi::Logger& logger)
+      : NCImpl3{inst, id, localStorage, connList, logger} {}
+};
+
+NetworkClient3::NetworkClient3(int inst, std::string_view id,
+                               net::ILocalStorage& localStorage,
+                               IConnectionList& connList, wpi::Logger& logger)
+    : m_impl{std::make_unique<Impl>(inst, id, localStorage, connList, logger)} {
+}
+
+NetworkClient3::~NetworkClient3() {
+  m_impl->m_localStorage.ClearNetwork();
+  m_impl->m_connList.ClearConnections();
+}
+
+void NetworkClient3::SetServers(
+    std::span<const std::pair<std::string, unsigned int>> servers) {
+  m_impl->SetServers(servers, NT_DEFAULT_PORT3);
+}
+
+void NetworkClient3::StartDSClient(unsigned int port) {
+  m_impl->StartDSClient(port);
+}
+
+void NetworkClient3::StopDSClient() {
+  m_impl->StopDSClient();
+}
+
+void NetworkClient3::FlushLocal() {
+  if (auto async = m_impl->m_flushLocalAtomic.load(std::memory_order_relaxed)) {
+    async->UnsafeSend();
+  }
+}
+
+void NetworkClient3::Flush() {
+  if (auto async = m_impl->m_flushAtomic.load(std::memory_order_relaxed)) {
+    async->UnsafeSend();
+  }
+}
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/NetworkClient.h b/third_party/allwpilib/ntcore/src/main/native/cpp/NetworkClient.h
new file mode 100644
index 0000000..34bf379
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/NetworkClient.h
@@ -0,0 +1,74 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <functional>
+#include <memory>
+#include <optional>
+#include <span>
+#include <string>
+#include <string_view>
+#include <utility>
+
+#include "INetworkClient.h"
+#include "ntcore_cpp.h"
+
+namespace wpi {
+class Logger;
+}  // namespace wpi
+
+namespace nt::net {
+class ILocalStorage;
+}  // namespace nt::net
+
+namespace nt {
+
+class IConnectionList;
+
+class NetworkClient final : public INetworkClient {
+ public:
+  NetworkClient(
+      int inst, std::string_view id, net::ILocalStorage& localStorage,
+      IConnectionList& connList, wpi::Logger& logger,
+      std::function<void(int64_t serverTimeOffset, int64_t rtt2, bool valid)>
+          timeSyncUpdated);
+  ~NetworkClient() final;
+
+  void SetServers(
+      std::span<const std::pair<std::string, unsigned int>> servers) final;
+
+  void StartDSClient(unsigned int port) final;
+  void StopDSClient() final;
+
+  void FlushLocal() final;
+  void Flush() final;
+
+ private:
+  class Impl;
+  std::unique_ptr<Impl> m_impl;
+};
+
+class NetworkClient3 final : public INetworkClient {
+ public:
+  NetworkClient3(int inst, std::string_view id,
+                 net::ILocalStorage& localStorage, IConnectionList& connList,
+                 wpi::Logger& logger);
+  ~NetworkClient3() final;
+
+  void SetServers(
+      std::span<const std::pair<std::string, unsigned int>> servers) final;
+
+  void StartDSClient(unsigned int port) final;
+  void StopDSClient() final;
+
+  void FlushLocal() final;
+  void Flush() final;
+
+ private:
+  class Impl;
+  std::unique_ptr<Impl> m_impl;
+};
+
+}  // namespace nt
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/NetworkConnection.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/NetworkConnection.cpp
deleted file mode 100644
index 838eecb..0000000
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/NetworkConnection.cpp
+++ /dev/null
@@ -1,378 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "NetworkConnection.h"
-
-#include <utility>
-
-#include <wpi/NetworkStream.h>
-#include <wpi/raw_socket_istream.h>
-#include <wpi/timestamp.h>
-
-#include "IConnectionNotifier.h"
-#include "Log.h"
-#include "WireDecoder.h"
-#include "WireEncoder.h"
-
-using namespace nt;
-
-NetworkConnection::NetworkConnection(unsigned int uid,
-                                     std::unique_ptr<wpi::NetworkStream> stream,
-                                     IConnectionNotifier& notifier,
-                                     wpi::Logger& logger,
-                                     HandshakeFunc handshake,
-                                     Message::GetEntryTypeFunc get_entry_type)
-    : m_uid(uid),
-      m_stream(std::move(stream)),
-      m_notifier(notifier),
-      m_logger(logger),
-      m_handshake(std::move(handshake)),
-      m_get_entry_type(std::move(get_entry_type)),
-      m_state(kCreated) {
-  m_active = false;
-  m_proto_rev = 0x0300;
-  m_last_update = 0;
-
-  // turn off Nagle algorithm; we bundle packets for transmission
-  m_stream->setNoDelay();
-}
-
-NetworkConnection::~NetworkConnection() {
-  Stop();
-}
-
-void NetworkConnection::Start() {
-  if (m_active) {
-    return;
-  }
-  m_active = true;
-  set_state(kInit);
-  // clear queue
-  while (!m_outgoing.empty()) {
-    m_outgoing.pop();
-  }
-  // reset shutdown flags
-  {
-    std::scoped_lock lock(m_shutdown_mutex);
-    m_read_shutdown = false;
-    m_write_shutdown = false;
-  }
-  // start threads
-  m_write_thread = std::thread(&NetworkConnection::WriteThreadMain, this);
-  m_read_thread = std::thread(&NetworkConnection::ReadThreadMain, this);
-}
-
-void NetworkConnection::Stop() {
-  DEBUG2("NetworkConnection stopping ({})", fmt::ptr(this));
-  set_state(kDead);
-  m_active = false;
-  // closing the stream so the read thread terminates
-  if (m_stream) {
-    m_stream->close();
-  }
-  // send an empty outgoing message set so the write thread terminates
-  m_outgoing.push(Outgoing());
-  // wait for threads to terminate, with timeout
-  if (m_write_thread.joinable()) {
-    std::unique_lock lock(m_shutdown_mutex);
-    auto timeout_time =
-        std::chrono::steady_clock::now() + std::chrono::milliseconds(200);
-    if (m_write_shutdown_cv.wait_until(lock, timeout_time,
-                                       [&] { return m_write_shutdown; })) {
-      m_write_thread.join();
-    } else {
-      m_write_thread.detach();  // timed out, detach it
-    }
-  }
-  if (m_read_thread.joinable()) {
-    std::unique_lock lock(m_shutdown_mutex);
-    auto timeout_time =
-        std::chrono::steady_clock::now() + std::chrono::milliseconds(200);
-    if (m_read_shutdown_cv.wait_until(lock, timeout_time,
-                                      [&] { return m_read_shutdown; })) {
-      m_read_thread.join();
-    } else {
-      m_read_thread.detach();  // timed out, detach it
-    }
-  }
-  // clear queue
-  while (!m_outgoing.empty()) {
-    m_outgoing.pop();
-  }
-}
-
-ConnectionInfo NetworkConnection::info() const {
-  return ConnectionInfo{remote_id(), std::string{m_stream->getPeerIP()},
-                        static_cast<unsigned int>(m_stream->getPeerPort()),
-                        m_last_update, m_proto_rev};
-}
-
-unsigned int NetworkConnection::proto_rev() const {
-  return m_proto_rev;
-}
-
-void NetworkConnection::set_proto_rev(unsigned int proto_rev) {
-  m_proto_rev = proto_rev;
-}
-
-NetworkConnection::State NetworkConnection::state() const {
-  std::scoped_lock lock(m_state_mutex);
-  return m_state;
-}
-
-void NetworkConnection::set_state(State state) {
-  std::scoped_lock lock(m_state_mutex);
-  // Don't update state any more once we've died
-  if (m_state == kDead) {
-    return;
-  }
-  // One-shot notify state changes
-  if (m_state != kActive && state == kActive) {
-    m_notifier.NotifyConnection(true, info());
-  }
-  if (m_state != kDead && state == kDead) {
-    m_notifier.NotifyConnection(false, info());
-  }
-  m_state = state;
-}
-
-std::string NetworkConnection::remote_id() const {
-  std::scoped_lock lock(m_remote_id_mutex);
-  return m_remote_id;
-}
-
-void NetworkConnection::set_remote_id(std::string_view remote_id) {
-  std::scoped_lock lock(m_remote_id_mutex);
-  m_remote_id = remote_id;
-}
-
-void NetworkConnection::ReadThreadMain() {
-  wpi::raw_socket_istream is(*m_stream);
-  WireDecoder decoder(is, m_proto_rev, m_logger);
-
-  set_state(kHandshake);
-  if (!m_handshake(
-          *this,
-          [&] {
-            decoder.set_proto_rev(m_proto_rev);
-            auto msg = Message::Read(decoder, m_get_entry_type);
-            if (!msg && decoder.error()) {
-              DEBUG0("error reading in handshake: {}", decoder.error());
-            }
-            return msg;
-          },
-          [&](auto msgs) {
-            m_outgoing.emplace(std::vector<std::shared_ptr<Message>>(
-                msgs.begin(), msgs.end()));
-          })) {
-    set_state(kDead);
-    m_active = false;
-    goto done;
-  }
-
-  set_state(kActive);
-  while (m_active) {
-    if (!m_stream) {
-      break;
-    }
-    decoder.set_proto_rev(m_proto_rev);
-    decoder.Reset();
-    auto msg = Message::Read(decoder, m_get_entry_type);
-    if (!msg) {
-      if (decoder.error()) {
-        INFO("read error: {}", decoder.error());
-      }
-      // terminate connection on bad message
-      if (m_stream) {
-        m_stream->close();
-      }
-      break;
-    }
-    DEBUG3("received type={} with str={} id={} seq_num={}", msg->type(),
-           msg->str(), msg->id(), msg->seq_num_uid());
-    m_last_update = Now();
-    m_process_incoming(std::move(msg), this);
-  }
-  DEBUG2("read thread died ({})", fmt::ptr(this));
-  set_state(kDead);
-  m_active = false;
-  m_outgoing.push(Outgoing());  // also kill write thread
-
-done:
-  // use condition variable to signal thread shutdown
-  {
-    std::scoped_lock lock(m_shutdown_mutex);
-    m_read_shutdown = true;
-    m_read_shutdown_cv.notify_one();
-  }
-}
-
-void NetworkConnection::WriteThreadMain() {
-  WireEncoder encoder(m_proto_rev);
-
-  while (m_active) {
-    auto msgs = m_outgoing.pop();
-    DEBUG4("{}", "write thread woke up");
-    if (msgs.empty()) {
-      continue;
-    }
-    encoder.set_proto_rev(m_proto_rev);
-    encoder.Reset();
-    DEBUG3("sending {} messages", msgs.size());
-    for (auto& msg : msgs) {
-      if (msg) {
-        DEBUG3("sending type={} with str={} id={} seq_num={}", msg->type(),
-               msg->str(), msg->id(), msg->seq_num_uid());
-        msg->Write(encoder);
-      }
-    }
-    wpi::NetworkStream::Error err;
-    if (!m_stream) {
-      break;
-    }
-    if (encoder.size() == 0) {
-      continue;
-    }
-    if (m_stream->send(encoder.data(), encoder.size(), &err) == 0) {
-      break;
-    }
-    DEBUG4("sent {} bytes", encoder.size());
-  }
-  DEBUG2("write thread died ({})", fmt::ptr(this));
-  set_state(kDead);
-  m_active = false;
-  if (m_stream) {
-    m_stream->close();  // also kill read thread
-  }
-
-  // use condition variable to signal thread shutdown
-  {
-    std::scoped_lock lock(m_shutdown_mutex);
-    m_write_shutdown = true;
-    m_write_shutdown_cv.notify_one();
-  }
-}
-
-void NetworkConnection::QueueOutgoing(std::shared_ptr<Message> msg) {
-  std::scoped_lock lock(m_pending_mutex);
-
-  // Merge with previous.  One case we don't combine: delete/assign loop.
-  switch (msg->type()) {
-    case Message::kEntryAssign:
-    case Message::kEntryUpdate: {
-      // don't do this for unassigned id's
-      unsigned int id = msg->id();
-      if (id == 0xffff) {
-        m_pending_outgoing.push_back(msg);
-        break;
-      }
-      if (id < m_pending_update.size() && m_pending_update[id].first != 0) {
-        // overwrite the previous one for this id
-        auto& oldmsg = m_pending_outgoing[m_pending_update[id].first - 1];
-        if (oldmsg && oldmsg->Is(Message::kEntryAssign) &&
-            msg->Is(Message::kEntryUpdate)) {
-          // need to update assignment with new seq_num and value
-          oldmsg = Message::EntryAssign(oldmsg->str(), id, msg->seq_num_uid(),
-                                        msg->value(), oldmsg->flags());
-        } else {
-          oldmsg = msg;  // easy update
-        }
-      } else {
-        // new, but remember it
-        size_t pos = m_pending_outgoing.size();
-        m_pending_outgoing.push_back(msg);
-        if (id >= m_pending_update.size()) {
-          m_pending_update.resize(id + 1);
-        }
-        m_pending_update[id].first = pos + 1;
-      }
-      break;
-    }
-    case Message::kEntryDelete: {
-      // don't do this for unassigned id's
-      unsigned int id = msg->id();
-      if (id == 0xffff) {
-        m_pending_outgoing.push_back(msg);
-        break;
-      }
-
-      // clear previous updates
-      if (id < m_pending_update.size()) {
-        if (m_pending_update[id].first != 0) {
-          m_pending_outgoing[m_pending_update[id].first - 1].reset();
-          m_pending_update[id].first = 0;
-        }
-        if (m_pending_update[id].second != 0) {
-          m_pending_outgoing[m_pending_update[id].second - 1].reset();
-          m_pending_update[id].second = 0;
-        }
-      }
-
-      // add deletion
-      m_pending_outgoing.push_back(msg);
-      break;
-    }
-    case Message::kFlagsUpdate: {
-      // don't do this for unassigned id's
-      unsigned int id = msg->id();
-      if (id == 0xffff) {
-        m_pending_outgoing.push_back(msg);
-        break;
-      }
-      if (id < m_pending_update.size() && m_pending_update[id].second != 0) {
-        // overwrite the previous one for this id
-        m_pending_outgoing[m_pending_update[id].second - 1] = msg;
-      } else {
-        // new, but remember it
-        size_t pos = m_pending_outgoing.size();
-        m_pending_outgoing.push_back(msg);
-        if (id >= m_pending_update.size()) {
-          m_pending_update.resize(id + 1);
-        }
-        m_pending_update[id].second = pos + 1;
-      }
-      break;
-    }
-    case Message::kClearEntries: {
-      // knock out all previous assigns/updates!
-      for (auto& i : m_pending_outgoing) {
-        if (!i) {
-          continue;
-        }
-        auto t = i->type();
-        if (t == Message::kEntryAssign || t == Message::kEntryUpdate ||
-            t == Message::kFlagsUpdate || t == Message::kEntryDelete ||
-            t == Message::kClearEntries) {
-          i.reset();
-        }
-      }
-      m_pending_update.resize(0);
-      m_pending_outgoing.push_back(msg);
-      break;
-    }
-    default:
-      m_pending_outgoing.push_back(msg);
-      break;
-  }
-}
-
-void NetworkConnection::PostOutgoing(bool keep_alive) {
-  std::scoped_lock lock(m_pending_mutex);
-  auto now = std::chrono::steady_clock::now();
-  if (m_pending_outgoing.empty()) {
-    if (!keep_alive) {
-      return;
-    }
-    // send keep-alives once a second (if no other messages have been sent)
-    if ((now - m_last_post) < std::chrono::seconds(1)) {
-      return;
-    }
-    m_outgoing.emplace(Outgoing{Message::KeepAlive()});
-  } else {
-    m_outgoing.emplace(std::move(m_pending_outgoing));
-    m_pending_outgoing.resize(0);
-    m_pending_update.resize(0);
-  }
-  m_last_post = now;
-}  // NOLINT
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/NetworkConnection.h b/third_party/allwpilib/ntcore/src/main/native/cpp/NetworkConnection.h
deleted file mode 100644
index 59f18ff..0000000
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/NetworkConnection.h
+++ /dev/null
@@ -1,124 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef NTCORE_NETWORKCONNECTION_H_
-#define NTCORE_NETWORKCONNECTION_H_
-
-#include <stdint.h>
-
-#include <atomic>
-#include <chrono>
-#include <memory>
-#include <string>
-#include <string_view>
-#include <thread>
-#include <utility>
-#include <vector>
-
-#include <wpi/ConcurrentQueue.h>
-#include <wpi/condition_variable.h>
-#include <wpi/mutex.h>
-#include <wpi/span.h>
-
-#include "INetworkConnection.h"
-#include "Message.h"
-#include "ntcore_cpp.h"
-
-namespace wpi {
-class Logger;
-class NetworkStream;
-}  // namespace wpi
-
-namespace nt {
-
-class IConnectionNotifier;
-
-class NetworkConnection : public INetworkConnection {
- public:
-  using HandshakeFunc = std::function<bool(
-      NetworkConnection& conn,
-      std::function<std::shared_ptr<Message>()> get_msg,
-      std::function<void(wpi::span<std::shared_ptr<Message>>)> send_msgs)>;
-  using ProcessIncomingFunc =
-      std::function<void(std::shared_ptr<Message>, NetworkConnection*)>;
-  using Outgoing = std::vector<std::shared_ptr<Message>>;
-  using OutgoingQueue = wpi::ConcurrentQueue<Outgoing>;
-
-  NetworkConnection(unsigned int uid,
-                    std::unique_ptr<wpi::NetworkStream> stream,
-                    IConnectionNotifier& notifier, wpi::Logger& logger,
-                    HandshakeFunc handshake,
-                    Message::GetEntryTypeFunc get_entry_type);
-  ~NetworkConnection() override;
-
-  // Set the input processor function.  This must be called before Start().
-  void set_process_incoming(ProcessIncomingFunc func) {
-    m_process_incoming = func;
-  }
-
-  void Start();
-  void Stop();
-
-  ConnectionInfo info() const final;
-
-  bool active() const { return m_active; }
-  wpi::NetworkStream& stream() { return *m_stream; }
-
-  void QueueOutgoing(std::shared_ptr<Message> msg) final;
-  void PostOutgoing(bool keep_alive) override;
-
-  unsigned int uid() const { return m_uid; }
-
-  unsigned int proto_rev() const final;
-  void set_proto_rev(unsigned int proto_rev) final;
-
-  State state() const final;
-  void set_state(State state) final;
-
-  std::string remote_id() const;
-  void set_remote_id(std::string_view remote_id);
-
-  uint64_t last_update() const { return m_last_update; }
-
-  NetworkConnection(const NetworkConnection&) = delete;
-  NetworkConnection& operator=(const NetworkConnection&) = delete;
-
- private:
-  void ReadThreadMain();
-  void WriteThreadMain();
-
-  unsigned int m_uid;
-  std::unique_ptr<wpi::NetworkStream> m_stream;
-  IConnectionNotifier& m_notifier;
-  wpi::Logger& m_logger;
-  OutgoingQueue m_outgoing;
-  HandshakeFunc m_handshake;
-  Message::GetEntryTypeFunc m_get_entry_type;
-  ProcessIncomingFunc m_process_incoming;
-  std::thread m_read_thread;
-  std::thread m_write_thread;
-  std::atomic_bool m_active;
-  std::atomic_uint m_proto_rev;
-  mutable wpi::mutex m_state_mutex;
-  State m_state;
-  mutable wpi::mutex m_remote_id_mutex;
-  std::string m_remote_id;
-  std::atomic_ullong m_last_update;
-  std::chrono::steady_clock::time_point m_last_post;
-
-  wpi::mutex m_pending_mutex;
-  Outgoing m_pending_outgoing;
-  std::vector<std::pair<size_t, size_t>> m_pending_update;
-
-  // Condition variables for shutdown
-  wpi::mutex m_shutdown_mutex;
-  wpi::condition_variable m_read_shutdown_cv;
-  wpi::condition_variable m_write_shutdown_cv;
-  bool m_read_shutdown = false;
-  bool m_write_shutdown = false;
-};
-
-}  // namespace nt
-
-#endif  // NTCORE_NETWORKCONNECTION_H_
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/NetworkServer.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/NetworkServer.cpp
new file mode 100644
index 0000000..0086d24
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/NetworkServer.cpp
@@ -0,0 +1,571 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "NetworkServer.h"
+
+#include <stdint.h>
+
+#include <atomic>
+#include <span>
+#include <system_error>
+#include <vector>
+
+#include <wpi/SmallString.h>
+#include <wpi/StringExtras.h>
+#include <wpi/fs.h>
+#include <wpi/mutex.h>
+#include <wpi/raw_istream.h>
+#include <wpi/raw_ostream.h>
+#include <wpinet/EventLoopRunner.h>
+#include <wpinet/HttpUtil.h>
+#include <wpinet/HttpWebSocketServerConnection.h>
+#include <wpinet/UrlParser.h>
+#include <wpinet/uv/Async.h>
+#include <wpinet/uv/Tcp.h>
+#include <wpinet/uv/Work.h>
+#include <wpinet/uv/util.h>
+
+#include "IConnectionList.h"
+#include "InstanceImpl.h"
+#include "Log.h"
+#include "net/Message.h"
+#include "net/NetworkLoopQueue.h"
+#include "net/ServerImpl.h"
+#include "net/WebSocketConnection.h"
+#include "net3/UvStreamConnection3.h"
+
+using namespace nt;
+namespace uv = wpi::uv;
+
+// use a larger max message size for websockets
+static constexpr size_t kMaxMessageSize = 2 * 1024 * 1024;
+
+namespace {
+
+class NSImpl;
+
+class ServerConnection {
+ public:
+  ServerConnection(NSImpl& server, std::string_view addr, unsigned int port,
+                   wpi::Logger& logger)
+      : m_server{server},
+        m_connInfo{fmt::format("{}:{}", addr, port)},
+        m_logger{logger} {
+    m_info.remote_ip = addr;
+    m_info.remote_port = port;
+  }
+
+  int GetClientId() const { return m_clientId; }
+
+ protected:
+  void SetupPeriodicTimer();
+  void UpdatePeriodicTimer(uint32_t repeatMs);
+  void ConnectionClosed();
+
+  NSImpl& m_server;
+  ConnectionInfo m_info;
+  std::string m_connInfo;
+  wpi::Logger& m_logger;
+  int m_clientId;
+
+ private:
+  std::shared_ptr<uv::Timer> m_sendValuesTimer;
+};
+
+class ServerConnection4 final
+    : public ServerConnection,
+      public wpi::HttpWebSocketServerConnection<ServerConnection4> {
+ public:
+  ServerConnection4(std::shared_ptr<uv::Stream> stream, NSImpl& server,
+                    std::string_view addr, unsigned int port,
+                    wpi::Logger& logger)
+      : ServerConnection{server, addr, port, logger},
+        HttpWebSocketServerConnection(stream, {"networktables.first.wpi.edu"}) {
+    m_info.protocol_version = 0x0400;
+  }
+
+ private:
+  void ProcessRequest() final;
+  void ProcessWsUpgrade() final;
+
+  std::shared_ptr<net::WebSocketConnection> m_wire;
+};
+
+class ServerConnection3 : public ServerConnection {
+ public:
+  ServerConnection3(std::shared_ptr<uv::Stream> stream, NSImpl& server,
+                    std::string_view addr, unsigned int port,
+                    wpi::Logger& logger);
+
+ private:
+  std::shared_ptr<net3::UvStreamConnection3> m_wire;
+};
+
+class NSImpl {
+ public:
+  NSImpl(std::string_view persistFilename, std::string_view listenAddress,
+         unsigned int port3, unsigned int port4,
+         net::ILocalStorage& localStorage, IConnectionList& connList,
+         wpi::Logger& logger, std::function<void()> initDone);
+  ~NSImpl();
+
+  void HandleLocal();
+  void LoadPersistent();
+  void SavePersistent(std::string_view filename, std::string_view data);
+  void Init();
+  void AddConnection(ServerConnection* conn, const ConnectionInfo& info);
+  void RemoveConnection(ServerConnection* conn);
+
+  net::ILocalStorage& m_localStorage;
+  IConnectionList& m_connList;
+  wpi::Logger& m_logger;
+  std::function<void()> m_initDone;
+  std::string m_persistentData;
+  std::string m_persistentFilename;
+  std::string m_listenAddress;
+  unsigned int m_port3;
+  unsigned int m_port4;
+
+  // used only from loop
+  std::shared_ptr<uv::Timer> m_readLocalTimer;
+  std::shared_ptr<uv::Timer> m_savePersistentTimer;
+  std::shared_ptr<uv::Async<>> m_flushLocal;
+  std::shared_ptr<uv::Async<>> m_flush;
+  bool m_shutdown = false;
+
+  std::vector<net::ClientMessage> m_localMsgs;
+
+  net::ServerImpl m_serverImpl;
+
+  // shared with user (must be atomic or mutex-protected)
+  std::atomic<uv::Async<>*> m_flushLocalAtomic{nullptr};
+  std::atomic<uv::Async<>*> m_flushAtomic{nullptr};
+  mutable wpi::mutex m_mutex;
+  struct Connection {
+    ServerConnection* conn;
+    int connHandle;
+  };
+  std::vector<Connection> m_connections;
+
+  net::NetworkLoopQueue m_localQueue;
+
+  wpi::EventLoopRunner m_loopRunner;
+  wpi::uv::Loop& m_loop;
+};
+
+}  // namespace
+
+void ServerConnection::SetupPeriodicTimer() {
+  m_sendValuesTimer = uv::Timer::Create(m_server.m_loop);
+  m_sendValuesTimer->timeout.connect([this] {
+    m_server.HandleLocal();
+    m_server.m_serverImpl.SendValues(m_clientId, m_server.m_loop.Now().count());
+  });
+}
+
+void ServerConnection::UpdatePeriodicTimer(uint32_t repeatMs) {
+  if (repeatMs == UINT32_MAX) {
+    m_sendValuesTimer->Stop();
+  } else {
+    m_sendValuesTimer->Start(uv::Timer::Time{repeatMs},
+                             uv::Timer::Time{repeatMs});
+  }
+}
+
+void ServerConnection::ConnectionClosed() {
+  // don't call back into m_server if it's being destroyed
+  if (!m_sendValuesTimer->IsLoopClosing()) {
+    m_server.m_serverImpl.RemoveClient(m_clientId);
+    m_server.RemoveConnection(this);
+  }
+  m_sendValuesTimer->Close();
+}
+
+void ServerConnection4::ProcessRequest() {
+  DEBUG1("HTTP request: '{}'", m_request.GetUrl());
+  wpi::UrlParser url{m_request.GetUrl(),
+                     m_request.GetMethod() == wpi::HTTP_CONNECT};
+  if (!url.IsValid()) {
+    // failed to parse URL
+    SendError(400);
+    return;
+  }
+
+  std::string_view path;
+  if (url.HasPath()) {
+    path = url.GetPath();
+  }
+  DEBUG4("path: \"{}\"", path);
+
+  std::string_view query;
+  if (url.HasQuery()) {
+    query = url.GetQuery();
+  }
+  DEBUG4("query: \"{}\"\n", query);
+
+  const bool isGET = m_request.GetMethod() == wpi::HTTP_GET;
+  if (isGET && path == "/") {
+    // build HTML root page
+    SendResponse(200, "OK", "text/html",
+                 "<html><head><title>NetworkTables</title></head>"
+                 "<body><p>WebSockets must be used to access NetworkTables."
+                 "</body></html>");
+  } else if (isGET && path == "/nt/persistent.json") {
+    SendResponse(200, "OK", "application/json",
+                 m_server.m_serverImpl.DumpPersistent());
+  } else {
+    SendError(404, "Resource not found");
+  }
+}
+
+void ServerConnection4::ProcessWsUpgrade() {
+  // get name from URL
+  wpi::UrlParser url{m_request.GetUrl(), false};
+  std::string_view path;
+  if (url.HasPath()) {
+    path = url.GetPath();
+  }
+  DEBUG4("path: '{}'", path);
+
+  wpi::SmallString<128> nameBuf;
+  std::string_view name;
+  bool err = false;
+  if (wpi::starts_with(path, "/nt/")) {
+    name = wpi::UnescapeURI(wpi::drop_front(path, 4), nameBuf, &err);
+  }
+  if (err || name.empty()) {
+    INFO("invalid path '{}' (from {}), must match /nt/[clientId], closing",
+         path, m_connInfo);
+    m_websocket->Fail(
+        404, fmt::format("invalid path '{}', must match /nt/[clientId]", path));
+    return;
+  }
+
+  m_websocket->SetMaxMessageSize(kMaxMessageSize);
+
+  m_websocket->open.connect([this, name = std::string{name}](std::string_view) {
+    m_wire = std::make_shared<net::WebSocketConnection>(*m_websocket);
+    // TODO: set local flag appropriately
+    std::string dedupName;
+    std::tie(dedupName, m_clientId) = m_server.m_serverImpl.AddClient(
+        name, m_connInfo, false, *m_wire,
+        [this](uint32_t repeatMs) { UpdatePeriodicTimer(repeatMs); });
+    INFO("CONNECTED NT4 client '{}' (from {})", dedupName, m_connInfo);
+    m_info.remote_id = dedupName;
+    m_server.AddConnection(this, m_info);
+    m_websocket->closed.connect([this](uint16_t, std::string_view reason) {
+      INFO("DISCONNECTED NT4 client '{}' (from {}): {}", m_info.remote_id,
+           m_connInfo, reason);
+      ConnectionClosed();
+    });
+    m_websocket->text.connect([this](std::string_view data, bool) {
+      m_server.m_serverImpl.ProcessIncomingText(m_clientId, data);
+    });
+    m_websocket->binary.connect([this](std::span<const uint8_t> data, bool) {
+      m_server.m_serverImpl.ProcessIncomingBinary(m_clientId, data);
+    });
+
+    SetupPeriodicTimer();
+  });
+}
+
+ServerConnection3::ServerConnection3(std::shared_ptr<uv::Stream> stream,
+                                     NSImpl& server, std::string_view addr,
+                                     unsigned int port, wpi::Logger& logger)
+    : ServerConnection{server, addr, port, logger},
+      m_wire{std::make_shared<net3::UvStreamConnection3>(*stream)} {
+  m_info.remote_ip = addr;
+  m_info.remote_port = port;
+
+  // TODO: set local flag appropriately
+  m_clientId = m_server.m_serverImpl.AddClient3(
+      m_connInfo, false, *m_wire,
+      [this](std::string_view name, uint16_t proto) {
+        m_info.remote_id = name;
+        m_info.protocol_version = proto;
+        m_server.AddConnection(this, m_info);
+        INFO("CONNECTED NT3 client '{}' (from {})", name, m_connInfo);
+      },
+      [this](uint32_t repeatMs) { UpdatePeriodicTimer(repeatMs); });
+
+  stream->error.connect([this](uv::Error err) {
+    if (!m_wire->GetDisconnectReason().empty()) {
+      return;
+    }
+    m_wire->Disconnect(fmt::format("stream error: {}", err.name()));
+    m_wire->GetStream().Shutdown([this] { m_wire->GetStream().Close(); });
+  });
+  stream->end.connect([this] {
+    if (!m_wire->GetDisconnectReason().empty()) {
+      return;
+    }
+    m_wire->Disconnect("remote end closed connection");
+    m_wire->GetStream().Shutdown([this] { m_wire->GetStream().Close(); });
+  });
+  stream->closed.connect([this] {
+    INFO("DISCONNECTED NT3 client '{}' (from {}): {}", m_info.remote_id,
+         m_connInfo, m_wire->GetDisconnectReason());
+    ConnectionClosed();
+  });
+  stream->data.connect([this](uv::Buffer& buf, size_t size) {
+    m_server.m_serverImpl.ProcessIncomingBinary(
+        m_clientId, {reinterpret_cast<const uint8_t*>(buf.base), size});
+  });
+  stream->StartRead();
+
+  SetupPeriodicTimer();
+}
+
+NSImpl::NSImpl(std::string_view persistentFilename,
+               std::string_view listenAddress, unsigned int port3,
+               unsigned int port4, net::ILocalStorage& localStorage,
+               IConnectionList& connList, wpi::Logger& logger,
+               std::function<void()> initDone)
+    : m_localStorage{localStorage},
+      m_connList{connList},
+      m_logger{logger},
+      m_initDone{std::move(initDone)},
+      m_persistentFilename{persistentFilename},
+      m_listenAddress{wpi::trim(listenAddress)},
+      m_port3{port3},
+      m_port4{port4},
+      m_serverImpl{logger},
+      m_localQueue{logger},
+      m_loop(*m_loopRunner.GetLoop()) {
+  m_localMsgs.reserve(net::NetworkLoopQueue::kInitialQueueSize);
+  m_loopRunner.ExecAsync([=, this](uv::Loop& loop) {
+    // connect local storage to server
+    m_serverImpl.SetLocal(&m_localStorage);
+    m_localStorage.StartNetwork(&m_localQueue);
+    HandleLocal();
+
+    // load persistent file first, then initialize
+    uv::QueueWork(
+        m_loop, [this] { LoadPersistent(); }, [this] { Init(); });
+  });
+}
+
+NSImpl::~NSImpl() {
+  m_loopRunner.ExecAsync([this](uv::Loop&) { m_shutdown = true; });
+}
+
+void NSImpl::HandleLocal() {
+  m_localQueue.ReadQueue(&m_localMsgs);
+  m_serverImpl.HandleLocal(m_localMsgs);
+}
+
+void NSImpl::LoadPersistent() {
+  std::error_code ec;
+  auto size = fs::file_size(m_persistentFilename, ec);
+  wpi::raw_fd_istream is{m_persistentFilename, ec};
+  if (ec.value() != 0) {
+    INFO("could not open persistent file '{}': {}", m_persistentFilename,
+         ec.message());
+    return;
+  }
+  is.readinto(m_persistentData, size);
+  DEBUG4("read data: {}", m_persistentData);
+  if (is.has_error()) {
+    WARNING("error reading persistent file");
+    return;
+  }
+}
+
+void NSImpl::SavePersistent(std::string_view filename, std::string_view data) {
+  // write to temporary file
+  auto tmp = fmt::format("{}.tmp", filename);
+  std::error_code ec;
+  wpi::raw_fd_ostream os{tmp, ec, fs::F_Text};
+  if (ec.value() != 0) {
+    INFO("could not open persistent file '{}' for write: {}", tmp,
+         ec.message());
+    return;
+  }
+  os << data;
+  os.close();
+  if (os.has_error()) {
+    fs::remove(tmp);
+    return;
+  }
+
+  // move to real file
+  auto bak = fmt::format("{}.bck", filename);
+  fs::remove(bak, ec);
+  fs::rename(filename, bak, ec);
+  fs::rename(tmp, filename, ec);
+  if (ec.value() != 0) {
+    // attempt to restore backup
+    fs::rename(bak, filename, ec);
+  }
+}
+
+void NSImpl::Init() {
+  if (m_shutdown) {
+    return;
+  }
+  auto errs = m_serverImpl.LoadPersistent(m_persistentData);
+  if (!errs.empty()) {
+    WARNING("error reading persistent file: {}", errs);
+  }
+
+  // set up timers
+  m_readLocalTimer = uv::Timer::Create(m_loop);
+  m_readLocalTimer->timeout.connect([this] {
+    HandleLocal();
+    m_serverImpl.SendControl(m_loop.Now().count());
+  });
+  m_readLocalTimer->Start(uv::Timer::Time{100}, uv::Timer::Time{100});
+
+  m_savePersistentTimer = uv::Timer::Create(m_loop);
+  m_savePersistentTimer->timeout.connect([this] {
+    if (m_serverImpl.PersistentChanged()) {
+      uv::QueueWork(
+          m_loop,
+          [this, fn = m_persistentFilename,
+           data = m_serverImpl.DumpPersistent()] { SavePersistent(fn, data); },
+          nullptr);
+    }
+  });
+  m_savePersistentTimer->Start(uv::Timer::Time{1000}, uv::Timer::Time{1000});
+
+  // set up flush async
+  m_flush = uv::Async<>::Create(m_loop);
+  m_flush->wakeup.connect([this] {
+    HandleLocal();
+    for (auto&& conn : m_connections) {
+      m_serverImpl.SendValues(conn.conn->GetClientId(), m_loop.Now().count());
+    }
+  });
+  m_flushAtomic = m_flush.get();
+
+  m_flushLocal = uv::Async<>::Create(m_loop);
+  m_flushLocal->wakeup.connect([this] { HandleLocal(); });
+  m_flushLocalAtomic = m_flushLocal.get();
+
+  INFO("Listening on NT3 port {}, NT4 port {}", m_port3, m_port4);
+
+  if (m_port3 != 0) {
+    auto tcp3 = uv::Tcp::Create(m_loop);
+    tcp3->error.connect([logger = &m_logger](uv::Error err) {
+      WPI_INFO(*logger, "NT3 server socket error: {}", err.str());
+    });
+    tcp3->Bind(m_listenAddress, m_port3);
+
+    // when we get a NT3 connection, accept it and start reading
+    tcp3->connection.connect([this, srv = tcp3.get()] {
+      auto tcp = srv->Accept();
+      if (!tcp) {
+        return;
+      }
+      tcp->error.connect([logger = &m_logger](uv::Error err) {
+        WPI_INFO(*logger, "NT3 socket error: {}", err.str());
+      });
+      tcp->SetNoDelay(true);
+      std::string peerAddr;
+      unsigned int peerPort = 0;
+      if (uv::AddrToName(tcp->GetPeer(), &peerAddr, &peerPort) == 0) {
+        INFO("Got a NT3 connection from {} port {}", peerAddr, peerPort);
+      } else {
+        INFO("Got a NT3 connection from unknown");
+      }
+      auto conn = std::make_shared<ServerConnection3>(tcp, *this, peerAddr,
+                                                      peerPort, m_logger);
+      tcp->SetData(conn);
+    });
+
+    tcp3->Listen();
+  }
+
+  if (m_port4 != 0) {
+    auto tcp4 = uv::Tcp::Create(m_loop);
+    tcp4->error.connect([logger = &m_logger](uv::Error err) {
+      WPI_INFO(*logger, "NT4 server socket error: {}", err.str());
+    });
+    tcp4->Bind(m_listenAddress, m_port4);
+
+    // when we get a NT4 connection, accept it and start reading
+    tcp4->connection.connect([this, srv = tcp4.get()] {
+      auto tcp = srv->Accept();
+      if (!tcp) {
+        return;
+      }
+      tcp->error.connect([logger = &m_logger](uv::Error err) {
+        WPI_INFO(*logger, "NT4 socket error: {}", err.str());
+      });
+      tcp->SetNoDelay(true);
+      std::string peerAddr;
+      unsigned int peerPort = 0;
+      if (uv::AddrToName(tcp->GetPeer(), &peerAddr, &peerPort) == 0) {
+        INFO("Got a NT4 connection from {} port {}", peerAddr, peerPort);
+      } else {
+        INFO("Got a NT4 connection from unknown");
+      }
+      auto conn = std::make_shared<ServerConnection4>(tcp, *this, peerAddr,
+                                                      peerPort, m_logger);
+      tcp->SetData(conn);
+    });
+
+    tcp4->Listen();
+  }
+
+  if (m_initDone) {
+    DEBUG4("NetworkServer initDone()");
+    m_initDone();
+    m_initDone = nullptr;
+  }
+}
+
+void NSImpl::AddConnection(ServerConnection* conn, const ConnectionInfo& info) {
+  std::scoped_lock lock{m_mutex};
+  m_connections.emplace_back(Connection{conn, m_connList.AddConnection(info)});
+  m_serverImpl.ConnectionsChanged(m_connList.GetConnections());
+}
+
+void NSImpl::RemoveConnection(ServerConnection* conn) {
+  std::scoped_lock lock{m_mutex};
+  auto it = std::find_if(m_connections.begin(), m_connections.end(),
+                         [=](auto&& c) { return c.conn == conn; });
+  if (it != m_connections.end()) {
+    m_connList.RemoveConnection(it->connHandle);
+    m_connections.erase(it);
+    m_serverImpl.ConnectionsChanged(m_connList.GetConnections());
+  }
+}
+
+class NetworkServer::Impl final : public NSImpl {
+ public:
+  Impl(std::string_view persistFilename, std::string_view listenAddress,
+       unsigned int port3, unsigned int port4, net::ILocalStorage& localStorage,
+       IConnectionList& connList, wpi::Logger& logger,
+       std::function<void()> initDone)
+      : NSImpl{persistFilename, listenAddress, port3,  port4,
+               localStorage,    connList,      logger, std::move(initDone)} {}
+};
+
+NetworkServer::NetworkServer(std::string_view persistFilename,
+                             std::string_view listenAddress, unsigned int port3,
+                             unsigned int port4,
+                             net::ILocalStorage& localStorage,
+                             IConnectionList& connList, wpi::Logger& logger,
+                             std::function<void()> initDone)
+    : m_impl{std::make_unique<Impl>(persistFilename, listenAddress, port3,
+                                    port4, localStorage, connList, logger,
+                                    std::move(initDone))} {}
+
+NetworkServer::~NetworkServer() {
+  m_impl->m_localStorage.ClearNetwork();
+  m_impl->m_connList.ClearConnections();
+}
+
+void NetworkServer::FlushLocal() {
+  if (auto async = m_impl->m_flushLocalAtomic.load(std::memory_order_relaxed)) {
+    async->UnsafeSend();
+  }
+}
+
+void NetworkServer::Flush() {
+  if (auto async = m_impl->m_flushAtomic.load(std::memory_order_relaxed)) {
+    async->UnsafeSend();
+  }
+}
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/NetworkServer.h b/third_party/allwpilib/ntcore/src/main/native/cpp/NetworkServer.h
new file mode 100644
index 0000000..b70c968
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/NetworkServer.h
@@ -0,0 +1,42 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <functional>
+#include <memory>
+#include <string_view>
+
+#include "ntcore_cpp.h"
+
+namespace wpi {
+class Logger;
+}  // namespace wpi
+
+namespace nt::net {
+class ILocalStorage;
+}  // namespace nt::net
+
+namespace nt {
+
+class IConnectionList;
+
+class NetworkServer {
+ public:
+  NetworkServer(std::string_view persistentFilename,
+                std::string_view listenAddress, unsigned int port3,
+                unsigned int port4, net::ILocalStorage& localStorage,
+                IConnectionList& connList, wpi::Logger& logger,
+                std::function<void()> initDone);
+  ~NetworkServer();
+
+  void FlushLocal();
+  void Flush();
+
+ private:
+  class Impl;
+  std::unique_ptr<Impl> m_impl;
+};
+
+}  // namespace nt
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/PubSubOptions.h b/third_party/allwpilib/ntcore/src/main/native/cpp/PubSubOptions.h
new file mode 100644
index 0000000..72ba2c3
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/PubSubOptions.h
@@ -0,0 +1,36 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include "ntcore_cpp.h"
+
+namespace nt {
+
+// internal helper class for PubSubOptions
+class PubSubOptionsImpl : public PubSubOptions {
+ public:
+  constexpr PubSubOptionsImpl() : PubSubOptionsImpl{kDefaultPubSubOptions} {}
+
+  /*implicit*/ constexpr PubSubOptionsImpl(  // NOLINT
+      const PubSubOptions& options)
+      : PubSubOptions{options} {
+    if (periodic == 0) {
+      periodic = kDefaultPeriodic;
+    }
+    periodicMs = static_cast<unsigned int>(periodic * 1000);
+    if (pollStorage == 0) {
+      if (sendAll) {
+        pollStorage = 20;
+      } else {
+        pollStorage = 1;
+      }
+    }
+  }
+
+  static constexpr unsigned int kDefaultPeriodicMs = 100;
+  unsigned int periodicMs = kDefaultPeriodicMs;
+};
+
+}  // namespace nt
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/RpcServer.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/RpcServer.cpp
deleted file mode 100644
index b4bf96a..0000000
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/RpcServer.cpp
+++ /dev/null
@@ -1,51 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "RpcServer.h"
-
-using namespace nt;
-
-RpcServer::RpcServer(int inst, wpi::Logger& logger)
-    : m_inst(inst), m_logger(logger) {}
-
-void RpcServer::Start() {
-  DoStart(m_inst, m_logger);
-}
-
-unsigned int RpcServer::Add(
-    std::function<void(const RpcAnswer& answer)> callback) {
-  return DoAdd(callback);
-}
-
-unsigned int RpcServer::AddPolled(unsigned int poller_uid) {
-  return DoAdd(poller_uid);
-}
-
-void RpcServer::RemoveRpc(unsigned int rpc_uid) {
-  Remove(rpc_uid);
-}
-
-void RpcServer::ProcessRpc(unsigned int local_id, unsigned int call_uid,
-                           std::string_view name, std::string_view params,
-                           const ConnectionInfo& conn,
-                           SendResponseFunc send_response,
-                           unsigned int rpc_uid) {
-  Send(rpc_uid, Handle(m_inst, local_id, Handle::kEntry).handle(),
-       Handle(m_inst, call_uid, Handle::kRpcCall).handle(), name, params, conn,
-       send_response);
-}
-
-bool RpcServer::PostRpcResponse(unsigned int local_id, unsigned int call_uid,
-                                std::string_view result) {
-  auto thr = GetThread();
-  auto i = thr->m_response_map.find(impl::RpcIdPair{local_id, call_uid});
-  if (i == thr->m_response_map.end()) {
-    WARNING("{}",
-            "posting RPC response to nonexistent call (or duplicate response)");
-    return false;
-  }
-  (i->getSecond())(result);
-  thr->m_response_map.erase(i);
-  return true;
-}
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/RpcServer.h b/third_party/allwpilib/ntcore/src/main/native/cpp/RpcServer.h
deleted file mode 100644
index b8ae6b7..0000000
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/RpcServer.h
+++ /dev/null
@@ -1,114 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef NTCORE_RPCSERVER_H_
-#define NTCORE_RPCSERVER_H_
-
-#include <utility>
-
-#include <wpi/CallbackManager.h>
-#include <wpi/DenseMap.h>
-#include <wpi/mutex.h>
-
-#include "Handle.h"
-#include "IRpcServer.h"
-#include "Log.h"
-
-namespace nt {
-
-namespace impl {
-
-using RpcIdPair = std::pair<unsigned int, unsigned int>;
-
-struct RpcNotifierData : public RpcAnswer {
-  RpcNotifierData(NT_Entry entry_, NT_RpcCall call_, std::string_view name_,
-                  std::string_view params_, const ConnectionInfo& conn_,
-                  IRpcServer::SendResponseFunc send_response_)
-      : RpcAnswer{entry_, call_, name_, params_, conn_},
-        send_response{std::move(send_response_)} {}
-
-  IRpcServer::SendResponseFunc send_response;
-};
-
-using RpcListenerData =
-    wpi::CallbackListenerData<std::function<void(const RpcAnswer& answer)>>;
-
-class RpcServerThread
-    : public wpi::CallbackThread<RpcServerThread, RpcAnswer, RpcListenerData,
-                                 RpcNotifierData> {
- public:
-  RpcServerThread(std::function<void()> on_start, std::function<void()> on_exit,
-                  int inst, wpi::Logger& logger)
-      : CallbackThread(std::move(on_start), std::move(on_exit)),
-        m_inst(inst),
-        m_logger(logger) {}
-
-  bool Matches(const RpcListenerData& /*listener*/,
-               const RpcNotifierData& data) {
-    return !data.name.empty() && data.send_response;
-  }
-
-  void SetListener(RpcNotifierData* data, unsigned int /*listener_uid*/) {
-    unsigned int local_id = Handle{data->entry}.GetIndex();
-    unsigned int call_uid = Handle{data->call}.GetIndex();
-    RpcIdPair lookup_uid{local_id, call_uid};
-    m_response_map.insert(std::make_pair(lookup_uid, data->send_response));
-  }
-
-  void DoCallback(std::function<void(const RpcAnswer& call)> callback,
-                  const RpcNotifierData& data) {
-    DEBUG4("rpc calling {}", data.name);
-    unsigned int local_id = Handle{data.entry}.GetIndex();
-    unsigned int call_uid = Handle{data.call}.GetIndex();
-    RpcIdPair lookup_uid{local_id, call_uid};
-    callback(data);
-    {
-      std::scoped_lock lock(m_mutex);
-      auto i = m_response_map.find(lookup_uid);
-      if (i != m_response_map.end()) {
-        // post an empty response and erase it
-        (i->getSecond())("");
-        m_response_map.erase(i);
-      }
-    }
-  }
-
-  int m_inst;
-  wpi::Logger& m_logger;
-  wpi::DenseMap<RpcIdPair, IRpcServer::SendResponseFunc> m_response_map;
-};
-
-}  // namespace impl
-
-class RpcServer
-    : public IRpcServer,
-      public wpi::CallbackManager<RpcServer, impl::RpcServerThread> {
-  friend class RpcServerTest;
-  friend class wpi::CallbackManager<RpcServer, impl::RpcServerThread>;
-
- public:
-  RpcServer(int inst, wpi::Logger& logger);
-
-  void Start();
-
-  unsigned int Add(std::function<void(const RpcAnswer& answer)> callback);
-  unsigned int AddPolled(unsigned int poller_uid);
-  void RemoveRpc(unsigned int rpc_uid) override;
-
-  void ProcessRpc(unsigned int local_id, unsigned int call_uid,
-                  std::string_view name, std::string_view params,
-                  const ConnectionInfo& conn, SendResponseFunc send_response,
-                  unsigned int rpc_uid) override;
-
-  bool PostRpcResponse(unsigned int local_id, unsigned int call_uid,
-                       std::string_view result);
-
- private:
-  int m_inst;
-  wpi::Logger& m_logger;
-};
-
-}  // namespace nt
-
-#endif  // NTCORE_RPCSERVER_H_
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/SequenceNumber.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/SequenceNumber.cpp
deleted file mode 100644
index e25e636..0000000
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/SequenceNumber.cpp
+++ /dev/null
@@ -1,29 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "SequenceNumber.h"
-
-namespace nt {
-
-bool operator<(const SequenceNumber& lhs, const SequenceNumber& rhs) {
-  if (lhs.m_value < rhs.m_value) {
-    return (rhs.m_value - lhs.m_value) < (1u << 15);
-  } else if (lhs.m_value > rhs.m_value) {
-    return (lhs.m_value - rhs.m_value) > (1u << 15);
-  } else {
-    return false;
-  }
-}
-
-bool operator>(const SequenceNumber& lhs, const SequenceNumber& rhs) {
-  if (lhs.m_value < rhs.m_value) {
-    return (rhs.m_value - lhs.m_value) > (1u << 15);
-  } else if (lhs.m_value > rhs.m_value) {
-    return (lhs.m_value - rhs.m_value) < (1u << 15);
-  } else {
-    return false;
-  }
-}
-
-}  // namespace nt
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/SequenceNumber.h b/third_party/allwpilib/ntcore/src/main/native/cpp/SequenceNumber.h
deleted file mode 100644
index 719d85c..0000000
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/SequenceNumber.h
+++ /dev/null
@@ -1,62 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef NTCORE_SEQUENCENUMBER_H_
-#define NTCORE_SEQUENCENUMBER_H_
-
-namespace nt {
-
-/* A sequence number per RFC 1982 */
-class SequenceNumber {
- public:
-  SequenceNumber() = default;
-  explicit SequenceNumber(unsigned int value) : m_value(value) {}
-  unsigned int value() const { return m_value; }
-
-  SequenceNumber& operator++() {
-    ++m_value;
-    if (m_value > 0xffff) {
-      m_value = 0;
-    }
-    return *this;
-  }
-  SequenceNumber operator++(int) {
-    SequenceNumber tmp(*this);
-    operator++();
-    return tmp;
-  }
-
-  friend bool operator<(const SequenceNumber& lhs, const SequenceNumber& rhs);
-  friend bool operator>(const SequenceNumber& lhs, const SequenceNumber& rhs);
-  friend bool operator<=(const SequenceNumber& lhs, const SequenceNumber& rhs);
-  friend bool operator>=(const SequenceNumber& lhs, const SequenceNumber& rhs);
-  friend bool operator==(const SequenceNumber& lhs, const SequenceNumber& rhs);
-  friend bool operator!=(const SequenceNumber& lhs, const SequenceNumber& rhs);
-
- private:
-  unsigned int m_value{0};
-};
-
-bool operator<(const SequenceNumber& lhs, const SequenceNumber& rhs);
-bool operator>(const SequenceNumber& lhs, const SequenceNumber& rhs);
-
-inline bool operator<=(const SequenceNumber& lhs, const SequenceNumber& rhs) {
-  return lhs == rhs || lhs < rhs;
-}
-
-inline bool operator>=(const SequenceNumber& lhs, const SequenceNumber& rhs) {
-  return lhs == rhs || lhs > rhs;
-}
-
-inline bool operator==(const SequenceNumber& lhs, const SequenceNumber& rhs) {
-  return lhs.m_value == rhs.m_value;
-}
-
-inline bool operator!=(const SequenceNumber& lhs, const SequenceNumber& rhs) {
-  return lhs.m_value != rhs.m_value;
-}
-
-}  // namespace nt
-
-#endif  // NTCORE_SEQUENCENUMBER_H_
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/Storage.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/Storage.cpp
deleted file mode 100644
index dadc3f6..0000000
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/Storage.cpp
+++ /dev/null
@@ -1,1286 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "Storage.h"
-
-#include <wpi/StringExtras.h>
-#include <wpi/timestamp.h>
-
-#include "Handle.h"
-#include "IDispatcher.h"
-#include "IEntryNotifier.h"
-#include "INetworkConnection.h"
-#include "IRpcServer.h"
-#include "Log.h"
-
-using namespace nt;
-
-Storage::Storage(IEntryNotifier& notifier, IRpcServer& rpc_server,
-                 wpi::Logger& logger)
-    : m_notifier(notifier), m_rpc_server(rpc_server), m_logger(logger) {
-  m_terminating = false;
-}
-
-Storage::~Storage() {
-  m_terminating = true;
-  m_rpc_results_cond.notify_all();
-}
-
-void Storage::SetDispatcher(IDispatcher* dispatcher, bool server) {
-  std::scoped_lock lock(m_mutex);
-  m_dispatcher = dispatcher;
-  m_server = server;
-}
-
-void Storage::ClearDispatcher() {
-  m_dispatcher = nullptr;
-}
-
-NT_Type Storage::GetMessageEntryType(unsigned int id) const {
-  std::scoped_lock lock(m_mutex);
-  if (id >= m_idmap.size()) {
-    return NT_UNASSIGNED;
-  }
-  Entry* entry = m_idmap[id];
-  if (!entry || !entry->value) {
-    return NT_UNASSIGNED;
-  }
-  return entry->value->type();
-}
-
-void Storage::ProcessIncoming(std::shared_ptr<Message> msg,
-                              INetworkConnection* conn,
-                              std::weak_ptr<INetworkConnection> conn_weak) {
-  switch (msg->type()) {
-    case Message::kKeepAlive:
-      break;  // ignore
-    case Message::kClientHello:
-    case Message::kProtoUnsup:
-    case Message::kServerHelloDone:
-    case Message::kServerHello:
-    case Message::kClientHelloDone:
-      // shouldn't get these, but ignore if we do
-      break;
-    case Message::kEntryAssign:
-      ProcessIncomingEntryAssign(std::move(msg), conn);
-      break;
-    case Message::kEntryUpdate:
-      ProcessIncomingEntryUpdate(std::move(msg), conn);
-      break;
-    case Message::kFlagsUpdate:
-      ProcessIncomingFlagsUpdate(std::move(msg), conn);
-      break;
-    case Message::kEntryDelete:
-      ProcessIncomingEntryDelete(std::move(msg), conn);
-      break;
-    case Message::kClearEntries:
-      ProcessIncomingClearEntries(std::move(msg), conn);
-      break;
-    case Message::kExecuteRpc:
-      ProcessIncomingExecuteRpc(std::move(msg), conn, std::move(conn_weak));
-      break;
-    case Message::kRpcResponse:
-      ProcessIncomingRpcResponse(std::move(msg), conn);
-      break;
-    default:
-      break;
-  }
-}
-
-void Storage::ProcessIncomingEntryAssign(std::shared_ptr<Message> msg,
-                                         INetworkConnection* conn) {
-  std::unique_lock lock(m_mutex);
-  unsigned int id = msg->id();
-  std::string_view name = msg->str();
-  Entry* entry;
-  bool may_need_update = false;
-  SequenceNumber seq_num(msg->seq_num_uid());
-  if (m_server) {
-    // if we're a server, id=0xffff requests are requests for an id
-    // to be assigned, and we need to send the new assignment back to
-    // the sender as well as all other connections.
-    if (id == 0xffff) {
-      entry = GetOrNew(name);
-      // see if it was already assigned; ignore if so.
-      if (entry->id != 0xffff) {
-        return;
-      }
-
-      entry->flags = msg->flags();
-      entry->seq_num = seq_num;
-      SetEntryValueImpl(entry, msg->value(), lock, false);
-      return;
-    }
-    if (id >= m_idmap.size() || !m_idmap[id]) {
-      // ignore arbitrary entry assignments
-      // this can happen due to e.g. assignment to deleted entry
-      lock.unlock();
-      DEBUG0("{}", "server: received assignment to unknown entry");
-      return;
-    }
-    entry = m_idmap[id];
-  } else {
-    // clients simply accept new assignments
-    if (id == 0xffff) {
-      lock.unlock();
-      DEBUG0("{}", "client: received entry assignment request?");
-      return;
-    }
-    if (id >= m_idmap.size()) {
-      m_idmap.resize(id + 1);
-    }
-    entry = m_idmap[id];
-    if (!entry) {
-      // create local
-      entry = GetOrNew(name);
-      entry->id = id;
-      m_idmap[id] = entry;
-      if (!entry->value) {
-        // didn't exist at all (rather than just being a response to a
-        // id assignment request)
-        entry->value = msg->value();
-        entry->flags = msg->flags();
-        entry->seq_num = seq_num;
-
-        // notify
-        m_notifier.NotifyEntry(entry->local_id, name, entry->value,
-                               NT_NOTIFY_NEW);
-        return;
-      }
-      may_need_update = true;  // we may need to send an update message
-
-      // if the received flags don't match what we sent, we most likely
-      // updated flags locally in the interim; send flags update message.
-      if (msg->flags() != entry->flags) {
-        auto dispatcher = m_dispatcher;
-        auto outmsg = Message::FlagsUpdate(id, entry->flags);
-        lock.unlock();
-        dispatcher->QueueOutgoing(outmsg, nullptr, nullptr);
-        lock.lock();
-      }
-    }
-  }
-
-  // common client and server handling
-
-  // already exists; ignore if sequence number not higher than local
-  if (seq_num < entry->seq_num) {
-    if (may_need_update) {
-      auto dispatcher = m_dispatcher;
-      auto outmsg =
-          Message::EntryUpdate(entry->id, entry->seq_num.value(), entry->value);
-      lock.unlock();
-      dispatcher->QueueOutgoing(outmsg, nullptr, nullptr);
-    }
-    return;
-  }
-
-  // sanity check: name should match id
-  if (msg->str() != entry->name) {
-    lock.unlock();
-    DEBUG0("{}", "entry assignment for same id with different name?");
-    return;
-  }
-
-  unsigned int notify_flags = NT_NOTIFY_UPDATE;
-
-  // don't update flags from a <3.0 remote (not part of message)
-  // don't update flags if this is a server response to a client id request
-  if (!may_need_update && conn->proto_rev() >= 0x0300) {
-    // update persistent dirty flag if persistent flag changed
-    if ((entry->flags & NT_PERSISTENT) != (msg->flags() & NT_PERSISTENT)) {
-      m_persistent_dirty = true;
-    }
-    if (entry->flags != msg->flags()) {
-      notify_flags |= NT_NOTIFY_FLAGS;
-    }
-    entry->flags = msg->flags();
-  }
-
-  // update persistent dirty flag if the value changed and it's persistent
-  if (entry->IsPersistent() && *entry->value != *msg->value()) {
-    m_persistent_dirty = true;
-  }
-
-  // update local
-  entry->value = msg->value();
-  entry->seq_num = seq_num;
-
-  // notify
-  m_notifier.NotifyEntry(entry->local_id, name, entry->value, notify_flags);
-
-  // broadcast to all other connections (note for client there won't
-  // be any other connections, so don't bother)
-  if (m_server && m_dispatcher) {
-    auto dispatcher = m_dispatcher;
-    auto outmsg = Message::EntryAssign(entry->name, id, msg->seq_num_uid(),
-                                       msg->value(), entry->flags);
-    lock.unlock();
-    dispatcher->QueueOutgoing(outmsg, nullptr, conn);
-  }
-}
-
-void Storage::ProcessIncomingEntryUpdate(std::shared_ptr<Message> msg,
-                                         INetworkConnection* conn) {
-  std::unique_lock lock(m_mutex);
-  unsigned int id = msg->id();
-  if (id >= m_idmap.size() || !m_idmap[id]) {
-    // ignore arbitrary entry updates;
-    // this can happen due to deleted entries
-    lock.unlock();
-    DEBUG0("{}", "received update to unknown entry");
-    return;
-  }
-  Entry* entry = m_idmap[id];
-
-  // ignore if sequence number not higher than local
-  SequenceNumber seq_num(msg->seq_num_uid());
-  if (seq_num <= entry->seq_num) {
-    return;
-  }
-
-  // update local
-  entry->value = msg->value();
-  entry->seq_num = seq_num;
-
-  // update persistent dirty flag if it's a persistent value
-  if (entry->IsPersistent()) {
-    m_persistent_dirty = true;
-  }
-
-  // notify
-  m_notifier.NotifyEntry(entry->local_id, entry->name, entry->value,
-                         NT_NOTIFY_UPDATE);
-
-  // broadcast to all other connections (note for client there won't
-  // be any other connections, so don't bother)
-  if (m_server && m_dispatcher) {
-    auto dispatcher = m_dispatcher;
-    lock.unlock();
-    dispatcher->QueueOutgoing(msg, nullptr, conn);
-  }
-}
-
-void Storage::ProcessIncomingFlagsUpdate(std::shared_ptr<Message> msg,
-                                         INetworkConnection* conn) {
-  std::unique_lock lock(m_mutex);
-  unsigned int id = msg->id();
-  if (id >= m_idmap.size() || !m_idmap[id]) {
-    // ignore arbitrary entry updates;
-    // this can happen due to deleted entries
-    lock.unlock();
-    DEBUG0("{}", "received flags update to unknown entry");
-    return;
-  }
-
-  // update local
-  SetEntryFlagsImpl(m_idmap[id], msg->flags(), lock, false);
-
-  // broadcast to all other connections (note for client there won't
-  // be any other connections, so don't bother)
-  if (m_server && m_dispatcher) {
-    auto dispatcher = m_dispatcher;
-    lock.unlock();
-    dispatcher->QueueOutgoing(msg, nullptr, conn);
-  }
-}
-
-void Storage::ProcessIncomingEntryDelete(std::shared_ptr<Message> msg,
-                                         INetworkConnection* conn) {
-  std::unique_lock lock(m_mutex);
-  unsigned int id = msg->id();
-  if (id >= m_idmap.size() || !m_idmap[id]) {
-    // ignore arbitrary entry updates;
-    // this can happen due to deleted entries
-    lock.unlock();
-    DEBUG0("{}", "received delete to unknown entry");
-    return;
-  }
-
-  // update local
-  DeleteEntryImpl(m_idmap[id], lock, false);
-
-  // broadcast to all other connections (note for client there won't
-  // be any other connections, so don't bother)
-  if (m_server && m_dispatcher) {
-    auto dispatcher = m_dispatcher;
-    lock.unlock();
-    dispatcher->QueueOutgoing(msg, nullptr, conn);
-  }
-}
-
-void Storage::ProcessIncomingClearEntries(std::shared_ptr<Message> msg,
-                                          INetworkConnection* conn) {
-  std::unique_lock lock(m_mutex);
-  // update local
-  DeleteAllEntriesImpl(false);
-
-  // broadcast to all other connections (note for client there won't
-  // be any other connections, so don't bother)
-  if (m_server && m_dispatcher) {
-    auto dispatcher = m_dispatcher;
-    lock.unlock();
-    dispatcher->QueueOutgoing(msg, nullptr, conn);
-  }
-}
-
-void Storage::ProcessIncomingExecuteRpc(
-    std::shared_ptr<Message> msg, INetworkConnection* /*conn*/,
-    std::weak_ptr<INetworkConnection> conn_weak) {
-  std::unique_lock lock(m_mutex);
-  if (!m_server) {
-    return;  // only process on server
-  }
-  unsigned int id = msg->id();
-  if (id >= m_idmap.size() || !m_idmap[id]) {
-    // ignore call to non-existent RPC
-    // this can happen due to deleted entries
-    lock.unlock();
-    DEBUG0("{}", "received RPC call to unknown entry");
-    return;
-  }
-  Entry* entry = m_idmap[id];
-  if (!entry->value || !entry->value->IsRpc()) {
-    lock.unlock();
-    DEBUG0("{}", "received RPC call to non-RPC entry");
-    return;
-  }
-  ConnectionInfo conn_info;
-  auto c = conn_weak.lock();
-  if (c) {
-    conn_info = c->info();
-  } else {
-    conn_info.remote_id = "";
-    conn_info.remote_ip = "";
-    conn_info.remote_port = 0;
-    conn_info.last_update = 0;
-    conn_info.protocol_version = 0;
-  }
-  unsigned int call_uid = msg->seq_num_uid();
-  m_rpc_server.ProcessRpc(
-      entry->local_id, call_uid, entry->name, msg->str(), conn_info,
-      [=](std::string_view result) {
-        auto c = conn_weak.lock();
-        if (c) {
-          c->QueueOutgoing(Message::RpcResponse(id, call_uid, result));
-        }
-      },
-      entry->rpc_uid);
-}
-
-void Storage::ProcessIncomingRpcResponse(std::shared_ptr<Message> msg,
-                                         INetworkConnection* /*conn*/) {
-  std::unique_lock lock(m_mutex);
-  if (m_server) {
-    return;  // only process on client
-  }
-  unsigned int id = msg->id();
-  if (id >= m_idmap.size() || !m_idmap[id]) {
-    // ignore response to non-existent RPC
-    // this can happen due to deleted entries
-    lock.unlock();
-    DEBUG0("{}", "received rpc response to unknown entry");
-    return;
-  }
-  Entry* entry = m_idmap[id];
-  if (!entry->value || !entry->value->IsRpc()) {
-    lock.unlock();
-    DEBUG0("{}", "received RPC response to non-RPC entry");
-    return;
-  }
-  m_rpc_results.insert({RpcIdPair{entry->local_id, msg->seq_num_uid()},
-                        std::string{msg->str()}});
-  m_rpc_results_cond.notify_all();
-}
-
-void Storage::GetInitialAssignments(
-    INetworkConnection& conn, std::vector<std::shared_ptr<Message>>* msgs) {
-  std::scoped_lock lock(m_mutex);
-  conn.set_state(INetworkConnection::kSynchronized);
-  for (auto& i : m_entries) {
-    Entry* entry = i.getValue();
-    if (!entry->value) {
-      continue;
-    }
-    msgs->emplace_back(Message::EntryAssign(i.getKey(), entry->id,
-                                            entry->seq_num.value(),
-                                            entry->value, entry->flags));
-  }
-}
-
-void Storage::ApplyInitialAssignments(
-    INetworkConnection& conn, wpi::span<std::shared_ptr<Message>> msgs,
-    bool /*new_server*/, std::vector<std::shared_ptr<Message>>* out_msgs) {
-  std::unique_lock lock(m_mutex);
-  if (m_server) {
-    return;  // should not do this on server
-  }
-
-  conn.set_state(INetworkConnection::kSynchronized);
-
-  std::vector<std::shared_ptr<Message>> update_msgs;
-
-  // clear existing id's
-  for (auto& i : m_entries) {
-    i.getValue()->id = 0xffff;
-  }
-
-  // clear existing idmap
-  m_idmap.resize(0);
-
-  // apply assignments
-  for (auto& msg : msgs) {
-    if (!msg->Is(Message::kEntryAssign)) {
-      DEBUG0("{}", "client: received non-entry assignment request?");
-      continue;
-    }
-
-    unsigned int id = msg->id();
-    if (id == 0xffff) {
-      DEBUG0("{}", "client: received entry assignment request?");
-      continue;
-    }
-
-    SequenceNumber seq_num(msg->seq_num_uid());
-    std::string_view name = msg->str();
-
-    Entry* entry = GetOrNew(name);
-    entry->seq_num = seq_num;
-    entry->id = id;
-    if (!entry->value) {
-      // doesn't currently exist
-      entry->value = msg->value();
-      entry->flags = msg->flags();
-      // notify
-      m_notifier.NotifyEntry(entry->local_id, name, entry->value,
-                             NT_NOTIFY_NEW);
-    } else {
-      // if we have written the value locally and the value is not persistent,
-      // then we don't update the local value and instead send it back to the
-      // server as an update message
-      if (entry->local_write && !entry->IsPersistent()) {
-        ++entry->seq_num;
-        update_msgs.emplace_back(Message::EntryUpdate(
-            entry->id, entry->seq_num.value(), entry->value));
-      } else {
-        entry->value = msg->value();
-        unsigned int notify_flags = NT_NOTIFY_UPDATE;
-        // don't update flags from a <3.0 remote (not part of message)
-        if (conn.proto_rev() >= 0x0300) {
-          if (entry->flags != msg->flags()) {
-            notify_flags |= NT_NOTIFY_FLAGS;
-          }
-          entry->flags = msg->flags();
-        }
-        // notify
-        m_notifier.NotifyEntry(entry->local_id, name, entry->value,
-                               notify_flags);
-      }
-    }
-
-    // save to idmap
-    if (id >= m_idmap.size()) {
-      m_idmap.resize(id + 1);
-    }
-    m_idmap[id] = entry;
-  }
-
-  // delete or generate assign messages for unassigned local entries
-  DeleteAllEntriesImpl(false, [&](Entry* entry) -> bool {
-    // was assigned by the server, don't delete
-    if (entry->id != 0xffff) {
-      return false;
-    }
-    // if we have written the value locally, we send an assign message to the
-    // server instead of deleting
-    if (entry->local_write) {
-      out_msgs->emplace_back(Message::EntryAssign(entry->name, entry->id,
-                                                  entry->seq_num.value(),
-                                                  entry->value, entry->flags));
-      return false;
-    }
-    // otherwise delete
-    return true;
-  });
-  auto dispatcher = m_dispatcher;
-  lock.unlock();
-  for (auto& msg : update_msgs) {
-    dispatcher->QueueOutgoing(msg, nullptr, nullptr);
-  }
-}
-
-std::shared_ptr<Value> Storage::GetEntryValue(std::string_view name) const {
-  std::scoped_lock lock(m_mutex);
-  auto i = m_entries.find(name);
-  if (i == m_entries.end()) {
-    return nullptr;
-  }
-  return i->getValue()->value;
-}
-
-std::shared_ptr<Value> Storage::GetEntryValue(unsigned int local_id) const {
-  std::scoped_lock lock(m_mutex);
-  if (local_id >= m_localmap.size()) {
-    return nullptr;
-  }
-  return m_localmap[local_id]->value;
-}
-
-bool Storage::SetDefaultEntryValue(std::string_view name,
-                                   std::shared_ptr<Value> value) {
-  if (name.empty()) {
-    return false;
-  }
-  if (!value) {
-    return false;
-  }
-  std::unique_lock lock(m_mutex);
-  Entry* entry = GetOrNew(name);
-
-  // we return early if value already exists; if types match return true
-  if (entry->value) {
-    return entry->value->type() == value->type();
-  }
-
-  SetEntryValueImpl(entry, value, lock, true);
-  return true;
-}
-
-bool Storage::SetDefaultEntryValue(unsigned int local_id,
-                                   std::shared_ptr<Value> value) {
-  if (!value) {
-    return false;
-  }
-  std::unique_lock lock(m_mutex);
-  if (local_id >= m_localmap.size()) {
-    return false;
-  }
-  Entry* entry = m_localmap[local_id].get();
-
-  // we return early if value already exists; if types match return true
-  if (entry->value) {
-    return entry->value->type() == value->type();
-  }
-
-  SetEntryValueImpl(entry, value, lock, true);
-  return true;
-}
-
-bool Storage::SetEntryValue(std::string_view name,
-                            std::shared_ptr<Value> value) {
-  if (name.empty()) {
-    return true;
-  }
-  if (!value) {
-    return true;
-  }
-  std::unique_lock lock(m_mutex);
-  Entry* entry = GetOrNew(name);
-
-  if (entry->value && entry->value->type() != value->type()) {
-    return false;  // error on type mismatch
-  }
-
-  SetEntryValueImpl(entry, value, lock, true);
-  return true;
-}
-
-bool Storage::SetEntryValue(unsigned int local_id,
-                            std::shared_ptr<Value> value) {
-  if (!value) {
-    return true;
-  }
-  std::unique_lock lock(m_mutex);
-  if (local_id >= m_localmap.size()) {
-    return true;
-  }
-  Entry* entry = m_localmap[local_id].get();
-
-  if (entry->value && entry->value->type() != value->type()) {
-    return false;  // error on type mismatch
-  }
-
-  SetEntryValueImpl(entry, value, lock, true);
-  return true;
-}
-
-void Storage::SetEntryValueImpl(Entry* entry, std::shared_ptr<Value> value,
-                                std::unique_lock<wpi::mutex>& lock,
-                                bool local) {
-  if (!value) {
-    return;
-  }
-  auto old_value = entry->value;
-  entry->value = value;
-
-  // if we're the server, assign an id if it doesn't have one
-  if (m_server && entry->id == 0xffff) {
-    unsigned int id = m_idmap.size();
-    entry->id = id;
-    m_idmap.push_back(entry);
-  }
-
-  // update persistent dirty flag if value changed and it's persistent
-  if (entry->IsPersistent() && (!old_value || *old_value != *value)) {
-    m_persistent_dirty = true;
-  }
-
-  // notify
-  if (!old_value) {
-    m_notifier.NotifyEntry(entry->local_id, entry->name, value,
-                           NT_NOTIFY_NEW | (local ? NT_NOTIFY_LOCAL : 0));
-  } else if (*old_value != *value) {
-    m_notifier.NotifyEntry(entry->local_id, entry->name, value,
-                           NT_NOTIFY_UPDATE | (local ? NT_NOTIFY_LOCAL : 0));
-  }
-
-  // remember local changes
-  if (local) {
-    entry->local_write = true;
-  }
-
-  // generate message
-  if (!m_dispatcher || (!local && !m_server)) {
-    return;
-  }
-  auto dispatcher = m_dispatcher;
-  if (!old_value || old_value->type() != value->type()) {
-    if (local) {
-      ++entry->seq_num;
-    }
-    auto msg = Message::EntryAssign(
-        entry->name, entry->id, entry->seq_num.value(), value, entry->flags);
-    lock.unlock();
-    dispatcher->QueueOutgoing(msg, nullptr, nullptr);
-  } else if (*old_value != *value) {
-    if (local) {
-      ++entry->seq_num;
-    }
-    // don't send an update if we don't have an assigned id yet
-    if (entry->id != 0xffff) {
-      auto msg = Message::EntryUpdate(entry->id, entry->seq_num.value(), value);
-      lock.unlock();
-      dispatcher->QueueOutgoing(msg, nullptr, nullptr);
-    }
-  }
-}
-
-void Storage::SetEntryTypeValue(std::string_view name,
-                                std::shared_ptr<Value> value) {
-  if (name.empty()) {
-    return;
-  }
-  if (!value) {
-    return;
-  }
-  std::unique_lock lock(m_mutex);
-  Entry* entry = GetOrNew(name);
-
-  SetEntryValueImpl(entry, value, lock, true);
-}
-
-void Storage::SetEntryTypeValue(unsigned int local_id,
-                                std::shared_ptr<Value> value) {
-  if (!value) {
-    return;
-  }
-  std::unique_lock lock(m_mutex);
-  if (local_id >= m_localmap.size()) {
-    return;
-  }
-  Entry* entry = m_localmap[local_id].get();
-  if (!entry) {
-    return;
-  }
-
-  SetEntryValueImpl(entry, value, lock, true);
-}
-
-void Storage::SetEntryFlags(std::string_view name, unsigned int flags) {
-  if (name.empty()) {
-    return;
-  }
-  std::unique_lock lock(m_mutex);
-  auto i = m_entries.find(name);
-  if (i == m_entries.end()) {
-    return;
-  }
-  SetEntryFlagsImpl(i->getValue(), flags, lock, true);
-}
-
-void Storage::SetEntryFlags(unsigned int id_local, unsigned int flags) {
-  std::unique_lock lock(m_mutex);
-  if (id_local >= m_localmap.size()) {
-    return;
-  }
-  SetEntryFlagsImpl(m_localmap[id_local].get(), flags, lock, true);
-}
-
-void Storage::SetEntryFlagsImpl(Entry* entry, unsigned int flags,
-                                std::unique_lock<wpi::mutex>& lock,
-                                bool local) {
-  if (!entry->value || entry->flags == flags) {
-    return;
-  }
-
-  // update persistent dirty flag if persistent flag changed
-  if ((entry->flags & NT_PERSISTENT) != (flags & NT_PERSISTENT)) {
-    m_persistent_dirty = true;
-  }
-
-  entry->flags = flags;
-
-  // notify
-  m_notifier.NotifyEntry(entry->local_id, entry->name, entry->value,
-                         NT_NOTIFY_FLAGS | (local ? NT_NOTIFY_LOCAL : 0));
-
-  // generate message
-  if (!local || !m_dispatcher) {
-    return;
-  }
-  auto dispatcher = m_dispatcher;
-  unsigned int id = entry->id;
-  // don't send an update if we don't have an assigned id yet
-  if (id != 0xffff) {
-    lock.unlock();
-    dispatcher->QueueOutgoing(Message::FlagsUpdate(id, flags), nullptr,
-                              nullptr);
-  }
-}
-
-unsigned int Storage::GetEntryFlags(std::string_view name) const {
-  std::scoped_lock lock(m_mutex);
-  auto i = m_entries.find(name);
-  if (i == m_entries.end()) {
-    return 0;
-  }
-  return i->getValue()->flags;
-}
-
-unsigned int Storage::GetEntryFlags(unsigned int local_id) const {
-  std::scoped_lock lock(m_mutex);
-  if (local_id >= m_localmap.size()) {
-    return 0;
-  }
-  return m_localmap[local_id]->flags;
-}
-
-void Storage::DeleteEntry(std::string_view name) {
-  std::unique_lock lock(m_mutex);
-  auto i = m_entries.find(name);
-  if (i == m_entries.end()) {
-    return;
-  }
-  DeleteEntryImpl(i->getValue(), lock, true);
-}
-
-void Storage::DeleteEntry(unsigned int local_id) {
-  std::unique_lock lock(m_mutex);
-  if (local_id >= m_localmap.size()) {
-    return;
-  }
-  DeleteEntryImpl(m_localmap[local_id].get(), lock, true);
-}
-
-void Storage::DeleteEntryImpl(Entry* entry, std::unique_lock<wpi::mutex>& lock,
-                              bool local) {
-  unsigned int id = entry->id;
-
-  // Erase entry from id mapping.
-  if (id < m_idmap.size()) {
-    m_idmap[id] = nullptr;
-  }
-
-  // empty the value and reset id and local_write flag
-  std::shared_ptr<Value> old_value;
-  old_value.swap(entry->value);
-  entry->id = 0xffff;
-  entry->local_write = false;
-
-  // remove RPC if there was one
-  if (entry->rpc_uid != UINT_MAX) {
-    m_rpc_server.RemoveRpc(entry->rpc_uid);
-    entry->rpc_uid = UINT_MAX;
-  }
-
-  // update persistent dirty flag if it's a persistent value
-  if (entry->IsPersistent()) {
-    m_persistent_dirty = true;
-  }
-
-  // reset flags
-  entry->flags = 0;
-
-  if (!old_value) {
-    return;  // was not previously assigned
-  }
-
-  // notify
-  m_notifier.NotifyEntry(entry->local_id, entry->name, old_value,
-                         NT_NOTIFY_DELETE | (local ? NT_NOTIFY_LOCAL : 0));
-
-  // if it had a value, generate message
-  // don't send an update if we don't have an assigned id yet
-  if (local && id != 0xffff) {
-    if (!m_dispatcher) {
-      return;
-    }
-    auto dispatcher = m_dispatcher;
-    lock.unlock();
-    dispatcher->QueueOutgoing(Message::EntryDelete(id), nullptr, nullptr);
-  }
-}
-
-template <typename F>
-void Storage::DeleteAllEntriesImpl(bool local, F should_delete) {
-  for (auto& i : m_entries) {
-    Entry* entry = i.getValue();
-    if (entry->value && should_delete(entry)) {
-      // notify it's being deleted
-      m_notifier.NotifyEntry(entry->local_id, i.getKey(), entry->value,
-                             NT_NOTIFY_DELETE | (local ? NT_NOTIFY_LOCAL : 0));
-      // remove it from idmap
-      if (entry->id < m_idmap.size()) {
-        m_idmap[entry->id] = nullptr;
-      }
-      entry->id = 0xffff;
-      entry->local_write = false;
-      entry->value.reset();
-      continue;
-    }
-  }
-}
-
-void Storage::DeleteAllEntriesImpl(bool local) {
-  // only delete non-persistent values
-  DeleteAllEntriesImpl(local,
-                       [](Entry* entry) { return !entry->IsPersistent(); });
-}
-
-void Storage::DeleteAllEntries() {
-  std::unique_lock lock(m_mutex);
-  if (m_entries.empty()) {
-    return;
-  }
-
-  DeleteAllEntriesImpl(true);
-
-  // generate message
-  if (!m_dispatcher) {
-    return;
-  }
-  auto dispatcher = m_dispatcher;
-  lock.unlock();
-  dispatcher->QueueOutgoing(Message::ClearEntries(), nullptr, nullptr);
-}
-
-Storage::Entry* Storage::GetOrNew(std::string_view name) {
-  auto& entry = m_entries[name];
-  if (!entry) {
-    m_localmap.emplace_back(new Entry(name));
-    entry = m_localmap.back().get();
-    entry->local_id = m_localmap.size() - 1;
-  }
-  return entry;
-}
-
-unsigned int Storage::GetEntry(std::string_view name) {
-  if (name.empty()) {
-    return UINT_MAX;
-  }
-  std::unique_lock lock(m_mutex);
-  return GetOrNew(name)->local_id;
-}
-
-std::vector<unsigned int> Storage::GetEntries(std::string_view prefix,
-                                              unsigned int types) {
-  std::scoped_lock lock(m_mutex);
-  std::vector<unsigned int> ids;
-  for (auto& i : m_entries) {
-    Entry* entry = i.getValue();
-    auto value = entry->value.get();
-    if (!value || !wpi::starts_with(i.getKey(), prefix)) {
-      continue;
-    }
-    if (types != 0 && (types & value->type()) == 0) {
-      continue;
-    }
-    ids.push_back(entry->local_id);
-  }
-  return ids;
-}
-
-EntryInfo Storage::GetEntryInfo(int inst, unsigned int local_id) const {
-  EntryInfo info;
-  info.entry = 0;
-  info.type = NT_UNASSIGNED;
-  info.flags = 0;
-  info.last_change = 0;
-
-  std::unique_lock lock(m_mutex);
-  if (local_id >= m_localmap.size()) {
-    return info;
-  }
-  Entry* entry = m_localmap[local_id].get();
-  if (!entry->value) {
-    return info;
-  }
-
-  info.entry = Handle(inst, local_id, Handle::kEntry);
-  info.name = entry->name;
-  info.type = entry->value->type();
-  info.flags = entry->flags;
-  info.last_change = entry->value->last_change();
-  return info;
-}
-
-std::string Storage::GetEntryName(unsigned int local_id) const {
-  std::unique_lock lock(m_mutex);
-  if (local_id >= m_localmap.size()) {
-    return {};
-  }
-  return m_localmap[local_id]->name;
-}
-
-NT_Type Storage::GetEntryType(unsigned int local_id) const {
-  std::unique_lock lock(m_mutex);
-  if (local_id >= m_localmap.size()) {
-    return NT_UNASSIGNED;
-  }
-  Entry* entry = m_localmap[local_id].get();
-  if (!entry->value) {
-    return NT_UNASSIGNED;
-  }
-  return entry->value->type();
-}
-
-uint64_t Storage::GetEntryLastChange(unsigned int local_id) const {
-  std::unique_lock lock(m_mutex);
-  if (local_id >= m_localmap.size()) {
-    return 0;
-  }
-  Entry* entry = m_localmap[local_id].get();
-  if (!entry->value) {
-    return 0;
-  }
-  return entry->value->last_change();
-}
-
-std::vector<EntryInfo> Storage::GetEntryInfo(int inst, std::string_view prefix,
-                                             unsigned int types) {
-  std::scoped_lock lock(m_mutex);
-  std::vector<EntryInfo> infos;
-  for (auto& i : m_entries) {
-    Entry* entry = i.getValue();
-    auto value = entry->value.get();
-    if (!value || !wpi::starts_with(i.getKey(), prefix)) {
-      continue;
-    }
-    if (types != 0 && (types & value->type()) == 0) {
-      continue;
-    }
-    EntryInfo info;
-    info.entry = Handle(inst, entry->local_id, Handle::kEntry);
-    info.name = i.getKey();
-    info.type = value->type();
-    info.flags = entry->flags;
-    info.last_change = value->last_change();
-    infos.push_back(std::move(info));
-  }
-  return infos;
-}
-
-unsigned int Storage::AddListener(
-    std::string_view prefix,
-    std::function<void(const EntryNotification& event)> callback,
-    unsigned int flags) const {
-  std::scoped_lock lock(m_mutex);
-  unsigned int uid = m_notifier.Add(callback, prefix, flags);
-  // perform immediate notifications
-  if ((flags & NT_NOTIFY_IMMEDIATE) != 0 && (flags & NT_NOTIFY_NEW) != 0) {
-    for (auto& i : m_entries) {
-      Entry* entry = i.getValue();
-      if (!entry->value || !wpi::starts_with(i.getKey(), prefix)) {
-        continue;
-      }
-      m_notifier.NotifyEntry(entry->local_id, i.getKey(), entry->value,
-                             NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW, uid);
-    }
-  }
-  return uid;
-}
-
-unsigned int Storage::AddListener(
-    unsigned int local_id,
-    std::function<void(const EntryNotification& event)> callback,
-    unsigned int flags) const {
-  std::scoped_lock lock(m_mutex);
-  unsigned int uid = m_notifier.Add(callback, local_id, flags);
-  // perform immediate notifications
-  if ((flags & NT_NOTIFY_IMMEDIATE) != 0 && (flags & NT_NOTIFY_NEW) != 0 &&
-      local_id < m_localmap.size()) {
-    Entry* entry = m_localmap[local_id].get();
-    if (entry->value) {
-      m_notifier.NotifyEntry(local_id, entry->name, entry->value,
-                             NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW, uid);
-    }
-  }
-  return uid;
-}
-
-unsigned int Storage::AddPolledListener(unsigned int poller,
-                                        std::string_view prefix,
-                                        unsigned int flags) const {
-  std::scoped_lock lock(m_mutex);
-  unsigned int uid = m_notifier.AddPolled(poller, prefix, flags);
-  // perform immediate notifications
-  if ((flags & NT_NOTIFY_IMMEDIATE) != 0 && (flags & NT_NOTIFY_NEW) != 0) {
-    for (auto& i : m_entries) {
-      if (!wpi::starts_with(i.getKey(), prefix)) {
-        continue;
-      }
-      Entry* entry = i.getValue();
-      if (!entry->value) {
-        continue;
-      }
-      m_notifier.NotifyEntry(entry->local_id, i.getKey(), entry->value,
-                             NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW, uid);
-    }
-  }
-  return uid;
-}
-
-unsigned int Storage::AddPolledListener(unsigned int poller,
-                                        unsigned int local_id,
-                                        unsigned int flags) const {
-  std::scoped_lock lock(m_mutex);
-  unsigned int uid = m_notifier.AddPolled(poller, local_id, flags);
-  // perform immediate notifications
-  if ((flags & NT_NOTIFY_IMMEDIATE) != 0 && (flags & NT_NOTIFY_NEW) != 0 &&
-      local_id < m_localmap.size()) {
-    Entry* entry = m_localmap[local_id].get();
-    // if no value, don't notify
-    if (entry->value) {
-      m_notifier.NotifyEntry(local_id, entry->name, entry->value,
-                             NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW, uid);
-    }
-  }
-  return uid;
-}
-
-bool Storage::GetPersistentEntries(
-    bool periodic,
-    std::vector<std::pair<std::string, std::shared_ptr<Value>>>* entries)
-    const {
-  // copy values out of storage as quickly as possible so lock isn't held
-  {
-    std::scoped_lock lock(m_mutex);
-    // for periodic, don't re-save unless something has changed
-    if (periodic && !m_persistent_dirty) {
-      return false;
-    }
-    m_persistent_dirty = false;
-    entries->reserve(m_entries.size());
-    for (auto& i : m_entries) {
-      Entry* entry = i.getValue();
-      // only write persistent-flagged values
-      if (!entry->value || !entry->IsPersistent()) {
-        continue;
-      }
-      entries->emplace_back(i.getKey(), entry->value);
-    }
-  }
-
-  // sort in name order
-  std::sort(entries->begin(), entries->end(),
-            [](const std::pair<std::string, std::shared_ptr<Value>>& a,
-               const std::pair<std::string, std::shared_ptr<Value>>& b) {
-              return a.first < b.first;
-            });
-  return true;
-}
-
-bool Storage::GetEntries(
-    std::string_view prefix,
-    std::vector<std::pair<std::string, std::shared_ptr<Value>>>* entries)
-    const {
-  // copy values out of storage as quickly as possible so lock isn't held
-  {
-    std::scoped_lock lock(m_mutex);
-    entries->reserve(m_entries.size());
-    for (auto& i : m_entries) {
-      Entry* entry = i.getValue();
-      // only write values with given prefix
-      if (!entry->value || !wpi::starts_with(i.getKey(), prefix)) {
-        continue;
-      }
-      entries->emplace_back(i.getKey(), entry->value);
-    }
-  }
-
-  // sort in name order
-  std::sort(entries->begin(), entries->end(),
-            [](const std::pair<std::string, std::shared_ptr<Value>>& a,
-               const std::pair<std::string, std::shared_ptr<Value>>& b) {
-              return a.first < b.first;
-            });
-  return true;
-}
-
-void Storage::CreateRpc(unsigned int local_id, std::string_view def,
-                        unsigned int rpc_uid) {
-  std::unique_lock lock(m_mutex);
-  if (local_id >= m_localmap.size()) {
-    return;
-  }
-  Entry* entry = m_localmap[local_id].get();
-
-  auto old_value = entry->value;
-  auto value = Value::MakeRpc(def);
-  entry->value = value;
-
-  // set up the RPC info
-  entry->rpc_uid = rpc_uid;
-
-  if (old_value && *old_value == *value) {
-    return;
-  }
-
-  // assign an id if it doesn't have one
-  if (entry->id == 0xffff) {
-    unsigned int id = m_idmap.size();
-    entry->id = id;
-    m_idmap.push_back(entry);
-  }
-
-  // generate message
-  if (!m_dispatcher) {
-    return;
-  }
-  auto dispatcher = m_dispatcher;
-  if (!old_value || old_value->type() != value->type()) {
-    ++entry->seq_num;
-    auto msg = Message::EntryAssign(
-        entry->name, entry->id, entry->seq_num.value(), value, entry->flags);
-    lock.unlock();
-    dispatcher->QueueOutgoing(msg, nullptr, nullptr);
-  } else {
-    ++entry->seq_num;
-    auto msg = Message::EntryUpdate(entry->id, entry->seq_num.value(), value);
-    lock.unlock();
-    dispatcher->QueueOutgoing(msg, nullptr, nullptr);
-  }
-}
-
-unsigned int Storage::CallRpc(unsigned int local_id, std::string_view params) {
-  std::unique_lock lock(m_mutex);
-  if (local_id >= m_localmap.size()) {
-    return 0;
-  }
-  Entry* entry = m_localmap[local_id].get();
-
-  if (!entry->value || !entry->value->IsRpc()) {
-    return 0;
-  }
-
-  ++entry->rpc_call_uid;
-  if (entry->rpc_call_uid > 0xffff) {
-    entry->rpc_call_uid = 0;
-  }
-  unsigned int call_uid = entry->rpc_call_uid;
-
-  auto msg = Message::ExecuteRpc(entry->id, call_uid, params);
-  std::string_view name{entry->name};
-
-  if (m_server) {
-    // RPCs are unlikely to be used locally on the server, but handle it
-    // gracefully anyway.
-    auto rpc_uid = entry->rpc_uid;
-    lock.unlock();
-    ConnectionInfo conn_info;
-    conn_info.remote_id = "Server";
-    conn_info.remote_ip = "localhost";
-    conn_info.remote_port = 0;
-    conn_info.last_update = wpi::Now();
-    conn_info.protocol_version = 0x0300;
-    unsigned int call_uid = msg->seq_num_uid();
-    m_rpc_server.ProcessRpc(
-        local_id, call_uid, name, msg->str(), conn_info,
-        [=](std::string_view result) {
-          std::scoped_lock lock(m_mutex);
-          m_rpc_results.insert(std::make_pair(RpcIdPair{local_id, call_uid},
-                                              std::string{result}));
-          m_rpc_results_cond.notify_all();
-        },
-        rpc_uid);
-  } else {
-    auto dispatcher = m_dispatcher;
-    lock.unlock();
-    dispatcher->QueueOutgoing(msg, nullptr, nullptr);
-  }
-  return call_uid;
-}
-
-bool Storage::GetRpcResult(unsigned int local_id, unsigned int call_uid,
-                           std::string* result) {
-  bool timed_out = false;
-  return GetRpcResult(local_id, call_uid, result, -1, &timed_out);
-}
-
-bool Storage::GetRpcResult(unsigned int local_id, unsigned int call_uid,
-                           std::string* result, double timeout,
-                           bool* timed_out) {
-  std::unique_lock lock(m_mutex);
-
-  RpcIdPair call_pair{local_id, call_uid};
-
-  // only allow one blocking call per rpc call uid
-  if (!m_rpc_blocking_calls.insert(call_pair).second) {
-    return false;
-  }
-
-  auto timeout_time =
-      std::chrono::steady_clock::now() + std::chrono::duration<double>(timeout);
-  *timed_out = false;
-  for (;;) {
-    auto i = m_rpc_results.find(call_pair);
-    if (i == m_rpc_results.end()) {
-      if (timeout == 0 || m_terminating) {
-        m_rpc_blocking_calls.erase(call_pair);
-        return false;
-      }
-      if (timeout < 0) {
-        m_rpc_results_cond.wait(lock);
-      } else {
-        auto cond_timed_out = m_rpc_results_cond.wait_until(lock, timeout_time);
-        if (cond_timed_out == std::cv_status::timeout) {
-          m_rpc_blocking_calls.erase(call_pair);
-          *timed_out = true;
-          return false;
-        }
-      }
-      // if element does not exist, we have been canceled
-      if (m_rpc_blocking_calls.count(call_pair) == 0) {
-        return false;
-      }
-      if (m_terminating) {
-        m_rpc_blocking_calls.erase(call_pair);
-        return false;
-      }
-      continue;
-    }
-    result->swap(i->getSecond());
-    // safe to erase even if id does not exist
-    m_rpc_blocking_calls.erase(call_pair);
-    m_rpc_results.erase(i);
-    return true;
-  }
-}
-
-void Storage::CancelRpcResult(unsigned int local_id, unsigned int call_uid) {
-  std::unique_lock lock(m_mutex);
-  // safe to erase even if id does not exist
-  m_rpc_blocking_calls.erase(RpcIdPair{local_id, call_uid});
-  m_rpc_results_cond.notify_all();
-}
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/Storage.h b/third_party/allwpilib/ntcore/src/main/native/cpp/Storage.h
deleted file mode 100644
index f49c071..0000000
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/Storage.h
+++ /dev/null
@@ -1,267 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef NTCORE_STORAGE_H_
-#define NTCORE_STORAGE_H_
-
-#include <stdint.h>
-
-#include <atomic>
-#include <cstddef>
-#include <functional>
-#include <memory>
-#include <string>
-#include <string_view>
-#include <utility>
-#include <vector>
-
-#include <wpi/DenseMap.h>
-#include <wpi/SmallSet.h>
-#include <wpi/StringMap.h>
-#include <wpi/condition_variable.h>
-#include <wpi/mutex.h>
-#include <wpi/span.h>
-
-#include "IStorage.h"
-#include "Message.h"
-#include "SequenceNumber.h"
-#include "ntcore_cpp.h"
-
-namespace wpi {
-class Logger;
-class raw_istream;
-class raw_ostream;
-}  // namespace wpi
-
-namespace nt {
-
-class IEntryNotifier;
-class INetworkConnection;
-class IRpcServer;
-class IStorageTest;
-
-class Storage : public IStorage {
-  friend class StorageTest;
-
- public:
-  Storage(IEntryNotifier& notifier, IRpcServer& rpcserver, wpi::Logger& logger);
-  Storage(const Storage&) = delete;
-  Storage& operator=(const Storage&) = delete;
-
-  ~Storage() override;
-
-  // Accessors required by Dispatcher.  An interface is used for
-  // generation of outgoing messages to break a dependency loop between
-  // Storage and Dispatcher.
-  void SetDispatcher(IDispatcher* dispatcher, bool server) override;
-  void ClearDispatcher() override;
-
-  // Required for wire protocol 2.0 to get the entry type of an entry when
-  // receiving entry updates (because the length/type is not provided in the
-  // message itself).  Not used in wire protocol 3.0.
-  NT_Type GetMessageEntryType(unsigned int id) const override;
-
-  void ProcessIncoming(std::shared_ptr<Message> msg, INetworkConnection* conn,
-                       std::weak_ptr<INetworkConnection> conn_weak) override;
-  void GetInitialAssignments(
-      INetworkConnection& conn,
-      std::vector<std::shared_ptr<Message>>* msgs) override;
-  void ApplyInitialAssignments(
-      INetworkConnection& conn, wpi::span<std::shared_ptr<Message>> msgs,
-      bool new_server,
-      std::vector<std::shared_ptr<Message>>* out_msgs) override;
-
-  // User functions.  These are the actual implementations of the corresponding
-  // user API functions in ntcore_cpp.
-  std::shared_ptr<Value> GetEntryValue(std::string_view name) const;
-  std::shared_ptr<Value> GetEntryValue(unsigned int local_id) const;
-
-  bool SetDefaultEntryValue(std::string_view name,
-                            std::shared_ptr<Value> value);
-  bool SetDefaultEntryValue(unsigned int local_id,
-                            std::shared_ptr<Value> value);
-
-  bool SetEntryValue(std::string_view name, std::shared_ptr<Value> value);
-  bool SetEntryValue(unsigned int local_id, std::shared_ptr<Value> value);
-
-  void SetEntryTypeValue(std::string_view name, std::shared_ptr<Value> value);
-  void SetEntryTypeValue(unsigned int local_id, std::shared_ptr<Value> value);
-
-  void SetEntryFlags(std::string_view name, unsigned int flags);
-  void SetEntryFlags(unsigned int local_id, unsigned int flags);
-
-  unsigned int GetEntryFlags(std::string_view name) const;
-  unsigned int GetEntryFlags(unsigned int local_id) const;
-
-  void DeleteEntry(std::string_view name);
-  void DeleteEntry(unsigned int local_id);
-
-  void DeleteAllEntries();
-
-  std::vector<EntryInfo> GetEntryInfo(int inst, std::string_view prefix,
-                                      unsigned int types);
-
-  unsigned int AddListener(
-      std::string_view prefix,
-      std::function<void(const EntryNotification& event)> callback,
-      unsigned int flags) const;
-  unsigned int AddListener(
-      unsigned int local_id,
-      std::function<void(const EntryNotification& event)> callback,
-      unsigned int flags) const;
-
-  unsigned int AddPolledListener(unsigned int poller_uid,
-                                 std::string_view prefix,
-                                 unsigned int flags) const;
-  unsigned int AddPolledListener(unsigned int poller_uid, unsigned int local_id,
-                                 unsigned int flags) const;
-
-  // Index-only
-  unsigned int GetEntry(std::string_view name);
-  std::vector<unsigned int> GetEntries(std::string_view prefix,
-                                       unsigned int types);
-  EntryInfo GetEntryInfo(int inst, unsigned int local_id) const;
-  std::string GetEntryName(unsigned int local_id) const;
-  NT_Type GetEntryType(unsigned int local_id) const;
-  uint64_t GetEntryLastChange(unsigned int local_id) const;
-
-  // Filename-based save/load functions.  Used both by periodic saves and
-  // accessible directly via the user API.
-  const char* SavePersistent(std::string_view filename,
-                             bool periodic) const override;
-  const char* LoadPersistent(
-      std::string_view filename,
-      std::function<void(size_t line, const char* msg)> warn) override;
-
-  const char* SaveEntries(std::string_view filename,
-                          std::string_view prefix) const;
-  const char* LoadEntries(
-      std::string_view filename, std::string_view prefix,
-      std::function<void(size_t line, const char* msg)> warn);
-
-  // Stream-based save/load functions (exposed for testing purposes).  These
-  // implement the guts of the filename-based functions.
-  void SavePersistent(wpi::raw_ostream& os, bool periodic) const;
-  bool LoadEntries(wpi::raw_istream& is, std::string_view prefix,
-                   bool persistent,
-                   std::function<void(size_t line, const char* msg)> warn);
-
-  void SaveEntries(wpi::raw_ostream& os, std::string_view prefix) const;
-
-  // RPC configuration needs to come through here as RPC definitions are
-  // actually special Storage value types.
-  void CreateRpc(unsigned int local_id, std::string_view def,
-                 unsigned int rpc_uid);
-  unsigned int CallRpc(unsigned int local_id, std::string_view params);
-  bool GetRpcResult(unsigned int local_id, unsigned int call_uid,
-                    std::string* result);
-  bool GetRpcResult(unsigned int local_id, unsigned int call_uid,
-                    std::string* result, double timeout, bool* timed_out);
-  void CancelRpcResult(unsigned int local_id, unsigned int call_uid);
-
- private:
-  // Data for each table entry.
-  struct Entry {
-    explicit Entry(std::string_view name_) : name(name_) {}
-    bool IsPersistent() const { return (flags & NT_PERSISTENT) != 0; }
-
-    // We redundantly store the name so that it's available when accessing the
-    // raw Entry* via the ID map.
-    std::string name;
-
-    // The current value and flags.
-    std::shared_ptr<Value> value;
-    unsigned int flags{0};
-
-    // Unique ID for this entry as used in network messages.  The value is
-    // assigned by the server, so on the client this is 0xffff until an
-    // entry assignment is received back from the server.
-    unsigned int id{0xffff};
-
-    // Local ID.
-    unsigned int local_id{UINT_MAX};
-
-    // Sequence number for update resolution.
-    SequenceNumber seq_num;
-
-    // If value has been written locally.  Used during initial handshake
-    // on client to determine whether or not to accept remote changes.
-    bool local_write{false};
-
-    // RPC handle.
-    unsigned int rpc_uid{UINT_MAX};
-
-    // Last UID used when calling this RPC (primarily for client use).  This
-    // is incremented for each call.
-    unsigned int rpc_call_uid{0};
-  };
-
-  using EntriesMap = wpi::StringMap<Entry*>;
-  using IdMap = std::vector<Entry*>;
-  using LocalMap = std::vector<std::unique_ptr<Entry>>;
-  using RpcIdPair = std::pair<unsigned int, unsigned int>;
-  using RpcResultMap = wpi::DenseMap<RpcIdPair, std::string>;
-  using RpcBlockingCallSet = wpi::SmallSet<RpcIdPair, 12>;
-
-  mutable wpi::mutex m_mutex;
-  EntriesMap m_entries;
-  IdMap m_idmap;
-  LocalMap m_localmap;
-  RpcResultMap m_rpc_results;
-  RpcBlockingCallSet m_rpc_blocking_calls;
-  // If any persistent values have changed
-  mutable bool m_persistent_dirty = false;
-
-  // condition variable and termination flag for blocking on a RPC result
-  std::atomic_bool m_terminating;
-  wpi::condition_variable m_rpc_results_cond;
-
-  // configured by dispatcher at startup
-  IDispatcher* m_dispatcher = nullptr;
-  bool m_server = true;
-
-  IEntryNotifier& m_notifier;
-  IRpcServer& m_rpc_server;
-  wpi::Logger& m_logger;
-
-  void ProcessIncomingEntryAssign(std::shared_ptr<Message> msg,
-                                  INetworkConnection* conn);
-  void ProcessIncomingEntryUpdate(std::shared_ptr<Message> msg,
-                                  INetworkConnection* conn);
-  void ProcessIncomingFlagsUpdate(std::shared_ptr<Message> msg,
-                                  INetworkConnection* conn);
-  void ProcessIncomingEntryDelete(std::shared_ptr<Message> msg,
-                                  INetworkConnection* conn);
-  void ProcessIncomingClearEntries(std::shared_ptr<Message> msg,
-                                   INetworkConnection* conn);
-  void ProcessIncomingExecuteRpc(std::shared_ptr<Message> msg,
-                                 INetworkConnection* conn,
-                                 std::weak_ptr<INetworkConnection> conn_weak);
-  void ProcessIncomingRpcResponse(std::shared_ptr<Message> msg,
-                                  INetworkConnection* conn);
-
-  bool GetPersistentEntries(
-      bool periodic,
-      std::vector<std::pair<std::string, std::shared_ptr<Value>>>* entries)
-      const;
-  bool GetEntries(std::string_view prefix,
-                  std::vector<std::pair<std::string, std::shared_ptr<Value>>>*
-                      entries) const;
-  void SetEntryValueImpl(Entry* entry, std::shared_ptr<Value> value,
-                         std::unique_lock<wpi::mutex>& lock, bool local);
-  void SetEntryFlagsImpl(Entry* entry, unsigned int flags,
-                         std::unique_lock<wpi::mutex>& lock, bool local);
-  void DeleteEntryImpl(Entry* entry, std::unique_lock<wpi::mutex>& lock,
-                       bool local);
-
-  // Must be called with m_mutex held
-  template <typename F>
-  void DeleteAllEntriesImpl(bool local, F should_delete);
-  void DeleteAllEntriesImpl(bool local);
-  Entry* GetOrNew(std::string_view name);
-};
-
-}  // namespace nt
-
-#endif  // NTCORE_STORAGE_H_
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/Storage_load.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/Storage_load.cpp
deleted file mode 100644
index 98046e7..0000000
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/Storage_load.cpp
+++ /dev/null
@@ -1,484 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include <cctype>
-#include <string>
-#include <utility>
-
-#include <wpi/Base64.h>
-#include <wpi/SmallString.h>
-#include <wpi/StringExtras.h>
-#include <wpi/raw_istream.h>
-
-#include "IDispatcher.h"
-#include "IEntryNotifier.h"
-#include "Storage.h"
-
-using namespace nt;
-
-namespace {
-
-class LoadPersistentImpl {
- public:
-  using Entry = std::pair<std::string, std::shared_ptr<Value>>;
-  using WarnFunc = std::function<void(size_t, const char*)>;
-
-  LoadPersistentImpl(wpi::raw_istream& is, WarnFunc warn)
-      : m_is(is), m_warn(std::move(warn)) {}
-
-  bool Load(std::string_view prefix, std::vector<Entry>* entries);
-
- private:
-  bool ReadLine();
-  bool ReadHeader();
-  NT_Type ReadType();
-  std::string_view ReadName(wpi::SmallVectorImpl<char>& buf);
-  std::shared_ptr<Value> ReadValue(NT_Type type);
-  std::shared_ptr<Value> ReadBooleanValue();
-  std::shared_ptr<Value> ReadDoubleValue();
-  std::shared_ptr<Value> ReadStringValue();
-  std::shared_ptr<Value> ReadRawValue();
-  std::shared_ptr<Value> ReadBooleanArrayValue();
-  std::shared_ptr<Value> ReadDoubleArrayValue();
-  std::shared_ptr<Value> ReadStringArrayValue();
-
-  void Warn(const char* msg) {
-    if (m_warn) {
-      m_warn(m_line_num, msg);
-    }
-  }
-
-  wpi::raw_istream& m_is;
-  WarnFunc m_warn;
-
-  std::string_view m_line;
-  wpi::SmallString<128> m_line_buf;
-  size_t m_line_num = 0;
-
-  std::vector<int> m_buf_boolean_array;
-  std::vector<double> m_buf_double_array;
-  std::vector<std::string> m_buf_string_array;
-};
-
-}  // namespace
-
-/* Extracts an escaped string token.  Does not unescape the string.
- * If a string cannot be matched, an empty string is returned.
- * If the string is unterminated, an empty tail string is returned.
- * The returned token includes the starting and trailing quotes (unless the
- * string is unterminated).
- * Returns a pair containing the extracted token (if any) and the remaining
- * tail string.
- */
-static std::pair<std::string_view, std::string_view> ReadStringToken(
-    std::string_view source) {
-  // Match opening quote
-  if (source.empty() || source.front() != '"') {
-    return {{}, source};
-  }
-
-  // Scan for ending double quote, checking for escaped as we go.
-  size_t size = source.size();
-  size_t pos;
-  for (pos = 1; pos < size; ++pos) {
-    if (source[pos] == '"' && source[pos - 1] != '\\') {
-      ++pos;  // we want to include the trailing quote in the result
-      break;
-    }
-  }
-  return {wpi::slice(source, 0, pos), wpi::substr(source, pos)};
-}
-
-static int fromxdigit(char ch) {
-  if (ch >= 'a' && ch <= 'f') {
-    return (ch - 'a' + 10);
-  } else if (ch >= 'A' && ch <= 'F') {
-    return (ch - 'A' + 10);
-  } else {
-    return ch - '0';
-  }
-}
-
-static std::string_view UnescapeString(std::string_view source,
-                                       wpi::SmallVectorImpl<char>& buf) {
-  assert(source.size() >= 2 && source.front() == '"' && source.back() == '"');
-  buf.clear();
-  buf.reserve(source.size() - 2);
-  for (auto s = source.begin() + 1, end = source.end() - 1; s != end; ++s) {
-    if (*s != '\\') {
-      buf.push_back(*s);
-      continue;
-    }
-    switch (*++s) {
-      case 't':
-        buf.push_back('\t');
-        break;
-      case 'n':
-        buf.push_back('\n');
-        break;
-      case 'x': {
-        if (!isxdigit(*(s + 1))) {
-          buf.push_back('x');  // treat it like a unknown escape
-          break;
-        }
-        int ch = fromxdigit(*++s);
-        if (std::isxdigit(*(s + 1))) {
-          ch <<= 4;
-          ch |= fromxdigit(*++s);
-        }
-        buf.push_back(static_cast<char>(ch));
-        break;
-      }
-      default:
-        buf.push_back(*s);
-        break;
-    }
-  }
-  return {buf.data(), buf.size()};
-}
-
-bool LoadPersistentImpl::Load(std::string_view prefix,
-                              std::vector<Entry>* entries) {
-  if (!ReadHeader()) {
-    return false;  // header
-  }
-
-  while (ReadLine()) {
-    // type
-    NT_Type type = ReadType();
-    if (type == NT_UNASSIGNED) {
-      Warn("unrecognized type");
-      continue;
-    }
-
-    // name
-    wpi::SmallString<128> buf;
-    std::string_view name = ReadName(buf);
-    if (name.empty() || !wpi::starts_with(name, prefix)) {
-      continue;
-    }
-
-    // =
-    m_line = wpi::ltrim(m_line, " \t");
-    if (m_line.empty() || m_line.front() != '=') {
-      Warn("expected = after name");
-      continue;
-    }
-    m_line.remove_prefix(1);
-    m_line = wpi::ltrim(m_line, " \t");
-
-    // value
-    auto value = ReadValue(type);
-
-    // move to entries
-    if (value) {
-      entries->emplace_back(name, std::move(value));
-    }
-  }
-  return true;
-}
-
-bool LoadPersistentImpl::ReadLine() {
-  // ignore blank lines and lines that start with ; or # (comments)
-  while (!m_is.has_error()) {
-    ++m_line_num;
-    m_line = wpi::trim(m_is.getline(m_line_buf, INT_MAX));
-    if (!m_line.empty() && m_line.front() != ';' && m_line.front() != '#') {
-      return true;
-    }
-  }
-  return false;
-}
-
-bool LoadPersistentImpl::ReadHeader() {
-  // header
-  if (!ReadLine() || m_line != "[NetworkTables Storage 3.0]") {
-    Warn("header line mismatch, ignoring rest of file");
-    return false;
-  }
-  return true;
-}
-
-NT_Type LoadPersistentImpl::ReadType() {
-  std::string_view tok;
-  std::tie(tok, m_line) = wpi::split(m_line, ' ');
-  if (tok == "boolean") {
-    return NT_BOOLEAN;
-  } else if (tok == "double") {
-    return NT_DOUBLE;
-  } else if (tok == "string") {
-    return NT_STRING;
-  } else if (tok == "raw") {
-    return NT_RAW;
-  } else if (tok == "array") {
-    std::string_view array_tok;
-    std::tie(array_tok, m_line) = wpi::split(m_line, ' ');
-    if (array_tok == "boolean") {
-      return NT_BOOLEAN_ARRAY;
-    } else if (array_tok == "double") {
-      return NT_DOUBLE_ARRAY;
-    } else if (array_tok == "string") {
-      return NT_STRING_ARRAY;
-    }
-  }
-  return NT_UNASSIGNED;
-}
-
-std::string_view LoadPersistentImpl::ReadName(wpi::SmallVectorImpl<char>& buf) {
-  std::string_view tok;
-  std::tie(tok, m_line) = ReadStringToken(m_line);
-  if (tok.empty()) {
-    Warn("missing name");
-    return {};
-  }
-  if (tok.back() != '"') {
-    Warn("unterminated name string");
-    return {};
-  }
-  return UnescapeString(tok, buf);
-}
-
-std::shared_ptr<Value> LoadPersistentImpl::ReadValue(NT_Type type) {
-  switch (type) {
-    case NT_BOOLEAN:
-      return ReadBooleanValue();
-    case NT_DOUBLE:
-      return ReadDoubleValue();
-    case NT_STRING:
-      return ReadStringValue();
-    case NT_RAW:
-      return ReadRawValue();
-    case NT_BOOLEAN_ARRAY:
-      return ReadBooleanArrayValue();
-    case NT_DOUBLE_ARRAY:
-      return ReadDoubleArrayValue();
-    case NT_STRING_ARRAY:
-      return ReadStringArrayValue();
-    default:
-      return nullptr;
-  }
-}
-
-std::shared_ptr<Value> LoadPersistentImpl::ReadBooleanValue() {
-  // only true or false is accepted
-  if (m_line == "true") {
-    return Value::MakeBoolean(true);
-  }
-  if (m_line == "false") {
-    return Value::MakeBoolean(false);
-  }
-  Warn("unrecognized boolean value, not 'true' or 'false'");
-  return nullptr;
-}
-
-std::shared_ptr<Value> LoadPersistentImpl::ReadDoubleValue() {
-  // need to convert to null-terminated string for std::strtod()
-  wpi::SmallString<64> buf{m_line};
-  char* end;
-  double v = std::strtod(buf.c_str(), &end);
-  if (*end != '\0') {
-    Warn("invalid double value");
-    return nullptr;
-  }
-  return Value::MakeDouble(v);
-}
-
-std::shared_ptr<Value> LoadPersistentImpl::ReadStringValue() {
-  std::string_view tok;
-  std::tie(tok, m_line) = ReadStringToken(m_line);
-  if (tok.empty()) {
-    Warn("missing string value");
-    return nullptr;
-  }
-  if (tok.back() != '"') {
-    Warn("unterminated string value");
-    return nullptr;
-  }
-  wpi::SmallString<128> buf;
-  return Value::MakeString(UnescapeString(tok, buf));
-}
-
-std::shared_ptr<Value> LoadPersistentImpl::ReadRawValue() {
-  wpi::SmallString<128> buf;
-  size_t nr;
-  return Value::MakeRaw(wpi::Base64Decode(m_line, &nr, buf));
-}
-
-std::shared_ptr<Value> LoadPersistentImpl::ReadBooleanArrayValue() {
-  m_buf_boolean_array.clear();
-  while (!m_line.empty()) {
-    std::string_view tok;
-    std::tie(tok, m_line) = wpi::split(m_line, ',');
-    tok = wpi::trim(tok, " \t");
-    if (tok == "true") {
-      m_buf_boolean_array.push_back(1);
-    } else if (tok == "false") {
-      m_buf_boolean_array.push_back(0);
-    } else {
-      Warn("unrecognized boolean value, not 'true' or 'false'");
-      return nullptr;
-    }
-  }
-  return Value::MakeBooleanArray(std::move(m_buf_boolean_array));
-}
-
-std::shared_ptr<Value> LoadPersistentImpl::ReadDoubleArrayValue() {
-  m_buf_double_array.clear();
-  while (!m_line.empty()) {
-    std::string_view tok;
-    std::tie(tok, m_line) = wpi::split(m_line, ',');
-    tok = wpi::trim(tok, " \t");
-    // need to convert to null-terminated string for std::strtod()
-    wpi::SmallString<64> buf{tok};
-    char* end;
-    double v = std::strtod(buf.c_str(), &end);
-    if (*end != '\0') {
-      Warn("invalid double value");
-      return nullptr;
-    }
-    m_buf_double_array.push_back(v);
-  }
-
-  return Value::MakeDoubleArray(std::move(m_buf_double_array));
-}
-
-std::shared_ptr<Value> LoadPersistentImpl::ReadStringArrayValue() {
-  m_buf_string_array.clear();
-  while (!m_line.empty()) {
-    std::string_view tok;
-    std::tie(tok, m_line) = ReadStringToken(m_line);
-    if (tok.empty()) {
-      Warn("missing string value");
-      return nullptr;
-    }
-    if (tok.back() != '"') {
-      Warn("unterminated string value");
-      return nullptr;
-    }
-
-    wpi::SmallString<128> buf;
-    m_buf_string_array.emplace_back(UnescapeString(tok, buf));
-
-    m_line = wpi::ltrim(m_line, " \t");
-    if (m_line.empty()) {
-      break;
-    }
-    if (m_line.front() != ',') {
-      Warn("expected comma between strings");
-      return nullptr;
-    }
-    m_line.remove_prefix(1);
-    m_line = wpi::ltrim(m_line, " \t");
-  }
-
-  return Value::MakeStringArray(std::move(m_buf_string_array));
-}
-
-bool Storage::LoadEntries(
-    wpi::raw_istream& is, std::string_view prefix, bool persistent,
-    std::function<void(size_t line, const char* msg)> warn) {
-  // entries to add
-  std::vector<LoadPersistentImpl::Entry> entries;
-
-  // load file
-  if (!LoadPersistentImpl(is, warn).Load(prefix, &entries)) {
-    return false;
-  }
-
-  // copy values into storage as quickly as possible so lock isn't held
-  std::vector<std::shared_ptr<Message>> msgs;
-  std::unique_lock lock(m_mutex);
-  for (auto& i : entries) {
-    Entry* entry = GetOrNew(i.first);
-    auto old_value = entry->value;
-    entry->value = i.second;
-    bool was_persist = entry->IsPersistent();
-    if (!was_persist && persistent) {
-      entry->flags |= NT_PERSISTENT;
-    }
-
-    // if we're the server, assign an id if it doesn't have one
-    if (m_server && entry->id == 0xffff) {
-      unsigned int id = m_idmap.size();
-      entry->id = id;
-      m_idmap.push_back(entry);
-    }
-
-    // notify (for local listeners)
-    if (m_notifier.local_notifiers()) {
-      if (!old_value) {
-        m_notifier.NotifyEntry(entry->local_id, i.first, i.second,
-                               NT_NOTIFY_NEW | NT_NOTIFY_LOCAL);
-      } else if (*old_value != *i.second) {
-        unsigned int notify_flags = NT_NOTIFY_UPDATE | NT_NOTIFY_LOCAL;
-        if (!was_persist && persistent) {
-          notify_flags |= NT_NOTIFY_FLAGS;
-        }
-        m_notifier.NotifyEntry(entry->local_id, i.first, i.second,
-                               notify_flags);
-      } else if (!was_persist && persistent) {
-        m_notifier.NotifyEntry(entry->local_id, i.first, i.second,
-                               NT_NOTIFY_FLAGS | NT_NOTIFY_LOCAL);
-      }
-    }
-
-    if (!m_dispatcher) {
-      continue;  // shortcut
-    }
-    ++entry->seq_num;
-
-    // put on update queue
-    if (!old_value || old_value->type() != i.second->type()) {
-      msgs.emplace_back(Message::EntryAssign(
-          i.first, entry->id, entry->seq_num.value(), i.second, entry->flags));
-    } else if (entry->id != 0xffff) {
-      // don't send an update if we don't have an assigned id yet
-      if (*old_value != *i.second) {
-        msgs.emplace_back(
-            Message::EntryUpdate(entry->id, entry->seq_num.value(), i.second));
-      }
-      if (!was_persist) {
-        msgs.emplace_back(Message::FlagsUpdate(entry->id, entry->flags));
-      }
-    }
-  }
-
-  if (m_dispatcher) {
-    auto dispatcher = m_dispatcher;
-    lock.unlock();
-    for (auto& msg : msgs) {
-      dispatcher->QueueOutgoing(std::move(msg), nullptr, nullptr);
-    }
-  }
-
-  return true;
-}
-
-const char* Storage::LoadPersistent(
-    std::string_view filename,
-    std::function<void(size_t line, const char* msg)> warn) {
-  std::error_code ec;
-  wpi::raw_fd_istream is(filename, ec);
-  if (ec.value() != 0) {
-    return "could not open file";
-  }
-  if (!LoadEntries(is, "", true, warn)) {
-    return "error reading file";
-  }
-  return nullptr;
-}
-
-const char* Storage::LoadEntries(
-    std::string_view filename, std::string_view prefix,
-    std::function<void(size_t line, const char* msg)> warn) {
-  std::error_code ec;
-  wpi::raw_fd_istream is(filename, ec);
-  if (ec.value() != 0) {
-    return "could not open file";
-  }
-  if (!LoadEntries(is, prefix, false, warn)) {
-    return "error reading file";
-  }
-  return nullptr;
-}
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/Storage_save.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/Storage_save.cpp
deleted file mode 100644
index 6d5db9f..0000000
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/Storage_save.cpp
+++ /dev/null
@@ -1,283 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include <cctype>
-#include <string>
-
-#include <fmt/format.h>
-#include <wpi/Base64.h>
-#include <wpi/SmallString.h>
-#include <wpi/StringExtras.h>
-#include <wpi/fs.h>
-#include <wpi/raw_ostream.h>
-
-#include "Log.h"
-#include "Storage.h"
-
-using namespace nt;
-
-namespace {
-
-class SavePersistentImpl {
- public:
-  using Entry = std::pair<std::string, std::shared_ptr<Value>>;
-
-  explicit SavePersistentImpl(wpi::raw_ostream& os) : m_os(os) {}
-
-  void Save(wpi::span<const Entry> entries);
-
- private:
-  void WriteString(std::string_view str);
-  void WriteHeader();
-  void WriteEntries(wpi::span<const Entry> entries);
-  void WriteEntry(std::string_view name, const Value& value);
-  bool WriteType(NT_Type type);
-  void WriteValue(const Value& value);
-
-  wpi::raw_ostream& m_os;
-};
-
-}  // namespace
-
-/* Escapes and writes a string, including start and end double quotes */
-void SavePersistentImpl::WriteString(std::string_view str) {
-  m_os << '"';
-  for (auto c : str) {
-    switch (c) {
-      case '\\':
-        m_os << "\\\\";
-        break;
-      case '\t':
-        m_os << "\\t";
-        break;
-      case '\n':
-        m_os << "\\n";
-        break;
-      case '"':
-        m_os << "\\\"";
-        break;
-      default:
-        if (std::isprint(c) && c != '=') {
-          m_os << c;
-          break;
-        }
-
-        // Write out the escaped representation.
-        m_os << "\\x";
-        m_os << wpi::hexdigit((c >> 4) & 0xF);
-        m_os << wpi::hexdigit((c >> 0) & 0xF);
-    }
-  }
-  m_os << '"';
-}
-
-void SavePersistentImpl::Save(wpi::span<const Entry> entries) {
-  WriteHeader();
-  WriteEntries(entries);
-}
-
-void SavePersistentImpl::WriteHeader() {
-  m_os << "[NetworkTables Storage 3.0]\n";
-}
-
-void SavePersistentImpl::WriteEntries(wpi::span<const Entry> entries) {
-  for (auto& i : entries) {
-    if (!i.second) {
-      continue;
-    }
-    WriteEntry(i.first, *i.second);
-  }
-}
-
-void SavePersistentImpl::WriteEntry(std::string_view name, const Value& value) {
-  if (!WriteType(value.type())) {
-    return;  // type
-  }
-  WriteString(name);  // name
-  m_os << '=';        // '='
-  WriteValue(value);  // value
-  m_os << '\n';       // eol
-}
-
-bool SavePersistentImpl::WriteType(NT_Type type) {
-  switch (type) {
-    case NT_BOOLEAN:
-      m_os << "boolean ";
-      break;
-    case NT_DOUBLE:
-      m_os << "double ";
-      break;
-    case NT_STRING:
-      m_os << "string ";
-      break;
-    case NT_RAW:
-      m_os << "raw ";
-      break;
-    case NT_BOOLEAN_ARRAY:
-      m_os << "array boolean ";
-      break;
-    case NT_DOUBLE_ARRAY:
-      m_os << "array double ";
-      break;
-    case NT_STRING_ARRAY:
-      m_os << "array string ";
-      break;
-    default:
-      return false;
-  }
-  return true;
-}
-
-void SavePersistentImpl::WriteValue(const Value& value) {
-  switch (value.type()) {
-    case NT_BOOLEAN:
-      m_os << (value.GetBoolean() ? "true" : "false");
-      break;
-    case NT_DOUBLE:
-      m_os << fmt::format("{:g}", value.GetDouble());
-      break;
-    case NT_STRING:
-      WriteString(value.GetString());
-      break;
-    case NT_RAW: {
-      wpi::Base64Encode(m_os, value.GetRaw());
-      break;
-    }
-    case NT_BOOLEAN_ARRAY: {
-      bool first = true;
-      for (auto elem : value.GetBooleanArray()) {
-        if (!first) {
-          m_os << ',';
-        }
-        first = false;
-        m_os << (elem ? "true" : "false");
-      }
-      break;
-    }
-    case NT_DOUBLE_ARRAY: {
-      bool first = true;
-      for (auto elem : value.GetDoubleArray()) {
-        if (!first) {
-          m_os << ',';
-        }
-        first = false;
-        m_os << fmt::format("{:g}", elem);
-      }
-      break;
-    }
-    case NT_STRING_ARRAY: {
-      bool first = true;
-      for (auto& elem : value.GetStringArray()) {
-        if (!first) {
-          m_os << ',';
-        }
-        first = false;
-        WriteString(elem);
-      }
-      break;
-    }
-    default:
-      break;
-  }
-}
-
-void Storage::SavePersistent(wpi::raw_ostream& os, bool periodic) const {
-  std::vector<SavePersistentImpl::Entry> entries;
-  if (!GetPersistentEntries(periodic, &entries)) {
-    return;
-  }
-  SavePersistentImpl(os).Save(entries);
-}
-
-const char* Storage::SavePersistent(std::string_view filename,
-                                    bool periodic) const {
-  std::string fn{filename};
-  auto tmp = fmt::format("{}.tmp", filename);
-  auto bak = fmt::format("{}.bak", filename);
-
-  // Get entries before creating file
-  std::vector<SavePersistentImpl::Entry> entries;
-  if (!GetPersistentEntries(periodic, &entries)) {
-    return nullptr;
-  }
-
-  const char* err = nullptr;
-
-  // start by writing to temporary file
-  std::error_code ec;
-  wpi::raw_fd_ostream os(tmp, ec, fs::F_Text);
-  if (ec.value() != 0) {
-    err = "could not open file";
-    goto done;
-  }
-  DEBUG0("saving persistent file '{}'", filename);
-  SavePersistentImpl(os).Save(entries);
-  os.close();
-  if (os.has_error()) {
-    std::remove(tmp.c_str());
-    err = "error saving file";
-    goto done;
-  }
-
-  // Safely move to real file.  We ignore any failures related to the backup.
-  std::remove(bak.c_str());
-  std::rename(fn.c_str(), bak.c_str());
-  if (std::rename(tmp.c_str(), fn.c_str()) != 0) {
-    std::rename(bak.c_str(), fn.c_str());  // attempt to restore backup
-    err = "could not rename temp file to real file";
-    goto done;
-  }
-
-done:
-  // try again if there was an error
-  if (err && periodic) {
-    m_persistent_dirty = true;
-  }
-  return err;
-}
-
-void Storage::SaveEntries(wpi::raw_ostream& os, std::string_view prefix) const {
-  std::vector<SavePersistentImpl::Entry> entries;
-  if (!GetEntries(prefix, &entries)) {
-    return;
-  }
-  SavePersistentImpl(os).Save(entries);
-}
-
-const char* Storage::SaveEntries(std::string_view filename,
-                                 std::string_view prefix) const {
-  std::string fn{filename};
-  auto tmp = fmt::format("{}.tmp", filename);
-  auto bak = fmt::format("{}.bak", filename);
-
-  // Get entries before creating file
-  std::vector<SavePersistentImpl::Entry> entries;
-  if (!GetEntries(prefix, &entries)) {
-    return nullptr;
-  }
-
-  // start by writing to temporary file
-  std::error_code ec;
-  wpi::raw_fd_ostream os(tmp, ec, fs::F_Text);
-  if (ec.value() != 0) {
-    return "could not open file";
-  }
-  DEBUG0("saving file '{}'", filename);
-  SavePersistentImpl(os).Save(entries);
-  os.close();
-  if (os.has_error()) {
-    std::remove(tmp.c_str());
-    return "error saving file";
-  }
-
-  // Safely move to real file.  We ignore any failures related to the backup.
-  std::remove(bak.c_str());
-  std::rename(fn.c_str(), bak.c_str());
-  if (std::rename(tmp.c_str(), fn.c_str()) != 0) {
-    std::rename(bak.c_str(), fn.c_str());  // attempt to restore backup
-    return "could not rename temp file to real file";
-  }
-
-  return nullptr;
-}
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/Types_internal.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/Types_internal.cpp
new file mode 100644
index 0000000..d6de540
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/Types_internal.cpp
@@ -0,0 +1,83 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "Types_internal.h"
+
+std::string_view nt::TypeToString(NT_Type type) {
+  switch (type) {
+    case NT_BOOLEAN:
+      return "boolean";
+    case NT_DOUBLE:
+      return "double";
+    case NT_STRING:
+      return "string";
+    case NT_BOOLEAN_ARRAY:
+      return "boolean[]";
+    case NT_DOUBLE_ARRAY:
+      return "double[]";
+    case NT_STRING_ARRAY:
+      return "string[]";
+    case NT_RPC:
+      return "rpc";
+    case NT_INTEGER:
+      return "int";
+    case NT_FLOAT:
+      return "float";
+    case NT_INTEGER_ARRAY:
+      return "int[]";
+    case NT_FLOAT_ARRAY:
+      return "float";
+    default:
+      return "raw";
+  }
+}
+
+NT_Type nt::StringToType(std::string_view typeStr) {
+  if (typeStr == "boolean") {
+    return NT_BOOLEAN;
+  } else if (typeStr == "double") {
+    return NT_DOUBLE;
+  } else if (typeStr == "string" || typeStr == "json") {
+    return NT_STRING;
+  } else if (typeStr == "boolean[]") {
+    return NT_BOOLEAN_ARRAY;
+  } else if (typeStr == "double[]") {
+    return NT_DOUBLE_ARRAY;
+  } else if (typeStr == "string[]") {
+    return NT_STRING_ARRAY;
+  } else if (typeStr == "rpc") {
+    return NT_RPC;
+  } else if (typeStr == "int") {
+    return NT_INTEGER;
+  } else if (typeStr == "float") {
+    return NT_FLOAT;
+  } else if (typeStr == "int[]") {
+    return NT_INTEGER_ARRAY;
+  } else if (typeStr == "float[]") {
+    return NT_FLOAT_ARRAY;
+  } else {
+    return NT_RAW;
+  }
+}
+
+NT_Type nt::StringToType3(std::string_view typeStr) {
+  if (typeStr == "boolean") {
+    return NT_BOOLEAN;
+  } else if (typeStr == "double" || typeStr == "int" || typeStr == "float") {
+    return NT_DOUBLE;
+  } else if (typeStr == "string" || typeStr == "json") {
+    return NT_STRING;
+  } else if (typeStr == "boolean[]") {
+    return NT_BOOLEAN_ARRAY;
+  } else if (typeStr == "double[]" || typeStr == "int[]" ||
+             typeStr == "float[]") {
+    return NT_DOUBLE_ARRAY;
+  } else if (typeStr == "string[]") {
+    return NT_STRING_ARRAY;
+  } else if (typeStr == "rpc") {
+    return NT_RPC;
+  } else {
+    return NT_RAW;
+  }
+}
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/Types_internal.h b/third_party/allwpilib/ntcore/src/main/native/cpp/Types_internal.h
new file mode 100644
index 0000000..0919641
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/Types_internal.h
@@ -0,0 +1,30 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <string_view>
+
+#include "ntcore_c.h"
+
+namespace nt {
+
+std::string_view TypeToString(NT_Type type);
+NT_Type StringToType(std::string_view typeStr);
+NT_Type StringToType3(std::string_view typeStr);
+
+constexpr bool IsNumeric(NT_Type type) {
+  return (type & (NT_INTEGER | NT_FLOAT | NT_DOUBLE)) != 0;
+}
+
+constexpr bool IsNumericArray(NT_Type type) {
+  return (type & (NT_INTEGER_ARRAY | NT_FLOAT_ARRAY | NT_DOUBLE_ARRAY)) != 0;
+}
+
+constexpr bool IsNumericCompatible(NT_Type a, NT_Type b) {
+  return (IsNumeric(a) && IsNumeric(b)) ||
+         (IsNumericArray(a) && IsNumericArray(b));
+}
+
+}  // namespace nt
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/Value.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/Value.cpp
index e0d65c9..240447f 100644
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/Value.cpp
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/Value.cpp
@@ -5,29 +5,63 @@
 #include <stdint.h>
 
 #include <cstring>
+#include <span>
 
 #include <wpi/MemAlloc.h>
 #include <wpi/timestamp.h>
 
 #include "Value_internal.h"
 #include "networktables/NetworkTableValue.h"
+#include "ntcore_cpp.h"
 
 using namespace nt;
 
-Value::Value() {
-  m_val.type = NT_UNASSIGNED;
-  m_val.last_change = wpi::Now();
+namespace {
+struct StringArrayStorage {
+  explicit StringArrayStorage(std::span<const std::string> value)
+      : strings{value.begin(), value.end()} {
+    InitNtStrings();
+  }
+  explicit StringArrayStorage(std::vector<std::string>&& value)
+      : strings{std::move(value)} {
+    InitNtStrings();
+  }
+  void InitNtStrings();
+
+  std::vector<std::string> strings;
+  std::vector<NT_String> ntStrings;
+};
+}  // namespace
+
+void StringArrayStorage::InitNtStrings() {
+  // point NT_String's to the contents in the vector.
+  ntStrings.reserve(strings.size());
+  for (const auto& str : strings) {
+    ntStrings.emplace_back(
+        NT_String{const_cast<char*>(str.c_str()), str.size()});
+  }
 }
 
-Value::Value(NT_Type type, uint64_t time, const private_init&) {
+Value::Value() {
+  m_val.type = NT_UNASSIGNED;
+  m_val.last_change = 0;
+  m_val.server_time = 0;
+}
+
+Value::Value(NT_Type type, int64_t time, const private_init&)
+    : Value{type, time == 0 ? nt::Now() : time, 1, private_init{}} {}
+
+Value::Value(NT_Type type, int64_t time, int64_t serverTime,
+             const private_init&) {
   m_val.type = type;
-  if (time == 0) {
-    m_val.last_change = wpi::Now();
-  } else {
-    m_val.last_change = time;
-  }
+  m_val.last_change = time;
+  m_val.server_time = serverTime;
   if (m_val.type == NT_BOOLEAN_ARRAY) {
     m_val.data.arr_boolean.arr = nullptr;
+  } else if (m_val.type == NT_INTEGER_ARRAY) {
+    m_val.data.arr_int.arr = nullptr;
+  } else if (m_val.type == NT_FLOAT_ARRAY) {
+    m_val.data.arr_float.arr = nullptr;
   } else if (m_val.type == NT_DOUBLE_ARRAY) {
     m_val.data.arr_double.arr = nullptr;
   } else if (m_val.type == NT_STRING_ARRAY) {
@@ -35,93 +69,121 @@
   }
 }
 
-Value::~Value() {
-  if (m_val.type == NT_BOOLEAN_ARRAY) {
-    delete[] m_val.data.arr_boolean.arr;
-  } else if (m_val.type == NT_DOUBLE_ARRAY) {
-    delete[] m_val.data.arr_double.arr;
-  } else if (m_val.type == NT_STRING_ARRAY) {
-    delete[] m_val.data.arr_string.arr;
-  }
-}
-
-std::shared_ptr<Value> Value::MakeBooleanArray(wpi::span<const bool> value,
-                                               uint64_t time) {
-  auto val = std::make_shared<Value>(NT_BOOLEAN_ARRAY, time, private_init());
-  val->m_val.data.arr_boolean.arr = new int[value.size()];
-  val->m_val.data.arr_boolean.size = value.size();
-  std::copy(value.begin(), value.end(), val->m_val.data.arr_boolean.arr);
+Value Value::MakeBooleanArray(std::span<const bool> value, int64_t time) {
+  Value val{NT_BOOLEAN_ARRAY, time, private_init{}};
+  auto data = std::make_shared<std::vector<int>>(value.begin(), value.end());
+  // data->reserve(value.size());
+  // std::copy(value.begin(), value.end(), *data);
+  val.m_val.data.arr_boolean.arr = data->data();
+  val.m_val.data.arr_boolean.size = data->size();
+  val.m_storage = std::move(data);
   return val;
 }
 
-std::shared_ptr<Value> Value::MakeBooleanArray(wpi::span<const int> value,
-                                               uint64_t time) {
-  auto val = std::make_shared<Value>(NT_BOOLEAN_ARRAY, time, private_init());
-  val->m_val.data.arr_boolean.arr = new int[value.size()];
-  val->m_val.data.arr_boolean.size = value.size();
-  std::copy(value.begin(), value.end(), val->m_val.data.arr_boolean.arr);
+Value Value::MakeBooleanArray(std::span<const int> value, int64_t time) {
+  Value val{NT_BOOLEAN_ARRAY, time, private_init{}};
+  auto data = std::make_shared<std::vector<int>>(value.begin(), value.end());
+  val.m_val.data.arr_boolean.arr = data->data();
+  val.m_val.data.arr_boolean.size = data->size();
+  val.m_storage = std::move(data);
   return val;
 }
 
-std::shared_ptr<Value> Value::MakeDoubleArray(wpi::span<const double> value,
-                                              uint64_t time) {
-  auto val = std::make_shared<Value>(NT_DOUBLE_ARRAY, time, private_init());
-  val->m_val.data.arr_double.arr = new double[value.size()];
-  val->m_val.data.arr_double.size = value.size();
-  std::copy(value.begin(), value.end(), val->m_val.data.arr_double.arr);
+Value Value::MakeBooleanArray(std::vector<int>&& value, int64_t time) {
+  Value val{NT_BOOLEAN_ARRAY, time, private_init{}};
+  auto data = std::make_shared<std::vector<int>>(std::move(value));
+  val.m_val.data.arr_boolean.arr = data->data();
+  val.m_val.data.arr_boolean.size = data->size();
+  val.m_storage = std::move(data);
   return val;
 }
 
-std::shared_ptr<Value> Value::MakeStringArray(
-    wpi::span<const std::string> value, uint64_t time) {
-  auto val = std::make_shared<Value>(NT_STRING_ARRAY, time, private_init());
-  val->m_string_array.assign(value.begin(), value.end());
-  // point NT_Value to the contents in the vector.
-  val->m_val.data.arr_string.arr = new NT_String[value.size()];
-  val->m_val.data.arr_string.size = val->m_string_array.size();
-  for (size_t i = 0; i < value.size(); ++i) {
-    val->m_val.data.arr_string.arr[i].str = const_cast<char*>(value[i].c_str());
-    val->m_val.data.arr_string.arr[i].len = value[i].size();
-  }
+Value Value::MakeIntegerArray(std::span<const int64_t> value, int64_t time) {
+  Value val{NT_INTEGER_ARRAY, time, private_init{}};
+  auto data =
+      std::make_shared<std::vector<int64_t>>(value.begin(), value.end());
+  val.m_val.data.arr_int.arr = data->data();
+  val.m_val.data.arr_int.size = data->size();
+  val.m_storage = std::move(data);
   return val;
 }
 
-std::shared_ptr<Value> Value::MakeStringArray(std::vector<std::string>&& value,
-                                              uint64_t time) {
-  auto val = std::make_shared<Value>(NT_STRING_ARRAY, time, private_init());
-  val->m_string_array = std::move(value);
-  value.clear();
-  // point NT_Value to the contents in the vector.
-  val->m_val.data.arr_string.arr = new NT_String[val->m_string_array.size()];
-  val->m_val.data.arr_string.size = val->m_string_array.size();
-  for (size_t i = 0; i < val->m_string_array.size(); ++i) {
-    val->m_val.data.arr_string.arr[i].str =
-        const_cast<char*>(val->m_string_array[i].c_str());
-    val->m_val.data.arr_string.arr[i].len = val->m_string_array[i].size();
-  }
+Value Value::MakeIntegerArray(std::vector<int64_t>&& value, int64_t time) {
+  Value val{NT_INTEGER_ARRAY, time, private_init{}};
+  auto data = std::make_shared<std::vector<int64_t>>(std::move(value));
+  val.m_val.data.arr_int.arr = data->data();
+  val.m_val.data.arr_int.size = data->size();
+  val.m_storage = std::move(data);
+  return val;
+}
+
+Value Value::MakeFloatArray(std::span<const float> value, int64_t time) {
+  Value val{NT_FLOAT_ARRAY, time, private_init{}};
+  auto data = std::make_shared<std::vector<float>>(value.begin(), value.end());
+  val.m_val.data.arr_float.arr = data->data();
+  val.m_val.data.arr_float.size = data->size();
+  val.m_storage = std::move(data);
+  return val;
+}
+
+Value Value::MakeFloatArray(std::vector<float>&& value, int64_t time) {
+  Value val{NT_FLOAT_ARRAY, time, private_init{}};
+  auto data = std::make_shared<std::vector<float>>(std::move(value));
+  val.m_val.data.arr_float.arr = data->data();
+  val.m_val.data.arr_float.size = data->size();
+  val.m_storage = std::move(data);
+  return val;
+}
+
+Value Value::MakeDoubleArray(std::span<const double> value, int64_t time) {
+  Value val{NT_DOUBLE_ARRAY, time, private_init{}};
+  auto data = std::make_shared<std::vector<double>>(value.begin(), value.end());
+  val.m_val.data.arr_double.arr = data->data();
+  val.m_val.data.arr_double.size = data->size();
+  val.m_storage = std::move(data);
+  return val;
+}
+
+Value Value::MakeDoubleArray(std::vector<double>&& value, int64_t time) {
+  Value val{NT_DOUBLE_ARRAY, time, private_init{}};
+  auto data = std::make_shared<std::vector<double>>(std::move(value));
+  val.m_val.data.arr_double.arr = data->data();
+  val.m_val.data.arr_double.size = data->size();
+  val.m_storage = std::move(data);
+  return val;
+}
+
+Value Value::MakeStringArray(std::span<const std::string> value, int64_t time) {
+  Value val{NT_STRING_ARRAY, time, private_init{}};
+  auto data = std::make_shared<StringArrayStorage>(value);
+  val.m_val.data.arr_string.arr = data->ntStrings.data();
+  val.m_val.data.arr_string.size = data->ntStrings.size();
+  val.m_storage = std::move(data);
+  return val;
+}
+
+Value Value::MakeStringArray(std::vector<std::string>&& value, int64_t time) {
+  Value val{NT_STRING_ARRAY, time, private_init{}};
+  auto data = std::make_shared<StringArrayStorage>(std::move(value));
+  val.m_val.data.arr_string.arr = data->ntStrings.data();
+  val.m_val.data.arr_string.size = data->ntStrings.size();
+  val.m_storage = std::move(data);
   return val;
 }
 
 void nt::ConvertToC(const Value& in, NT_Value* out) {
-  out->type = NT_UNASSIGNED;
+  *out = in.value();
   switch (in.type()) {
-    case NT_UNASSIGNED:
-      return;
-    case NT_BOOLEAN:
-      out->data.v_boolean = in.GetBoolean() ? 1 : 0;
-      break;
-    case NT_DOUBLE:
-      out->data.v_double = in.GetDouble();
-      break;
     case NT_STRING:
       ConvertToC(in.GetString(), &out->data.v_string);
       break;
-    case NT_RAW:
-      ConvertToC(in.GetRaw(), &out->data.v_raw);
+    case NT_RAW: {
+      auto v = in.GetRaw();
+      out->data.v_raw.data = static_cast<uint8_t*>(wpi::safe_malloc(v.size()));
+      out->data.v_raw.size = v.size();
+      std::memcpy(out->data.v_raw.data, v.data(), v.size());
       break;
-    case NT_RPC:
-      ConvertToC(in.GetRpc(), &out->data.v_raw);
-      break;
+    }
     case NT_BOOLEAN_ARRAY: {
       auto v = in.GetBooleanArray();
       out->data.arr_boolean.arr =
@@ -130,6 +192,22 @@
       std::copy(v.begin(), v.end(), out->data.arr_boolean.arr);
       break;
     }
+    case NT_INTEGER_ARRAY: {
+      auto v = in.GetIntegerArray();
+      out->data.arr_int.arr =
+          static_cast<int64_t*>(wpi::safe_malloc(v.size() * sizeof(int64_t)));
+      out->data.arr_int.size = v.size();
+      std::copy(v.begin(), v.end(), out->data.arr_int.arr);
+      break;
+    }
+    case NT_FLOAT_ARRAY: {
+      auto v = in.GetFloatArray();
+      out->data.arr_float.arr =
+          static_cast<float*>(wpi::safe_malloc(v.size() * sizeof(float)));
+      out->data.arr_float.size = v.size();
+      std::copy(v.begin(), v.end(), out->data.arr_float.arr);
+      break;
+    }
     case NT_DOUBLE_ARRAY: {
       auto v = in.GetDoubleArray();
       out->data.arr_double.arr =
@@ -143,16 +221,21 @@
       out->data.arr_string.arr = static_cast<NT_String*>(
           wpi::safe_malloc(v.size() * sizeof(NT_String)));
       for (size_t i = 0; i < v.size(); ++i) {
-        ConvertToC(v[i], &out->data.arr_string.arr[i]);
+        ConvertToC(std::string_view{v[i]}, &out->data.arr_string.arr[i]);
       }
       out->data.arr_string.size = v.size();
       break;
     }
     default:
-      // assert(false && "unknown value type");
-      return;
+      break;
   }
-  out->type = in.type();
+}
+
+size_t nt::ConvertToC(std::string_view in, char** out) {
+  *out = static_cast<char*>(wpi::safe_malloc(in.size() + 1));
+  std::memmove(*out, in.data(), in.size());  // NOLINT
+  (*out)[in.size()] = '\0';
+  return in.size();
 }
 
 void nt::ConvertToC(std::string_view in, NT_String* out) {
@@ -162,37 +245,48 @@
   out->str[in.size()] = '\0';
 }
 
-std::shared_ptr<Value> nt::ConvertFromC(const NT_Value& value) {
+Value nt::ConvertFromC(const NT_Value& value) {
   switch (value.type) {
-    case NT_UNASSIGNED:
-      return nullptr;
     case NT_BOOLEAN:
-      return Value::MakeBoolean(value.data.v_boolean != 0);
+      return Value::MakeBoolean(value.data.v_boolean != 0, value.last_change);
+    case NT_INTEGER:
+      return Value::MakeInteger(value.data.v_int, value.last_change);
+    case NT_FLOAT:
+      return Value::MakeFloat(value.data.v_float, value.last_change);
     case NT_DOUBLE:
-      return Value::MakeDouble(value.data.v_double);
+      return Value::MakeDouble(value.data.v_double, value.last_change);
     case NT_STRING:
-      return Value::MakeString(ConvertFromC(value.data.v_string));
+      return Value::MakeString(ConvertFromC(value.data.v_string),
+                               value.last_change);
     case NT_RAW:
-      return Value::MakeRaw(ConvertFromC(value.data.v_raw));
-    case NT_RPC:
-      return Value::MakeRpc(ConvertFromC(value.data.v_raw));
+      return Value::MakeRaw({value.data.v_raw.data, value.data.v_raw.size},
+                            value.last_change);
     case NT_BOOLEAN_ARRAY:
       return Value::MakeBooleanArray(
-          wpi::span(value.data.arr_boolean.arr, value.data.arr_boolean.size));
+          std::span(value.data.arr_boolean.arr, value.data.arr_boolean.size),
+          value.last_change);
+    case NT_INTEGER_ARRAY:
+      return Value::MakeIntegerArray(
+          std::span(value.data.arr_int.arr, value.data.arr_int.size),
+          value.last_change);
+    case NT_FLOAT_ARRAY:
+      return Value::MakeFloatArray(
+          std::span(value.data.arr_float.arr, value.data.arr_float.size),
+          value.last_change);
     case NT_DOUBLE_ARRAY:
       return Value::MakeDoubleArray(
-          wpi::span(value.data.arr_double.arr, value.data.arr_double.size));
+          std::span(value.data.arr_double.arr, value.data.arr_double.size),
+          value.last_change);
     case NT_STRING_ARRAY: {
       std::vector<std::string> v;
       v.reserve(value.data.arr_string.size);
       for (size_t i = 0; i < value.data.arr_string.size; ++i) {
         v.emplace_back(ConvertFromC(value.data.arr_string.arr[i]));
       }
-      return Value::MakeStringArray(std::move(v));
+      return Value::MakeStringArray(std::move(v), value.last_change);
     }
     default:
-      // assert(false && "unknown value type");
-      return nullptr;
+      return {};
   }
 }
 
@@ -205,12 +299,20 @@
       return true;  // XXX: is this better being false instead?
     case NT_BOOLEAN:
       return lhs.m_val.data.v_boolean == rhs.m_val.data.v_boolean;
+    case NT_INTEGER:
+      return lhs.m_val.data.v_int == rhs.m_val.data.v_int;
+    case NT_FLOAT:
+      return lhs.m_val.data.v_float == rhs.m_val.data.v_float;
     case NT_DOUBLE:
       return lhs.m_val.data.v_double == rhs.m_val.data.v_double;
     case NT_STRING:
+      return lhs.GetString() == rhs.GetString();
     case NT_RAW:
-    case NT_RPC:
-      return lhs.m_string == rhs.m_string;
+      if (lhs.m_val.data.v_raw.size != rhs.m_val.data.v_raw.size) {
+        return false;
+      }
+      return std::memcmp(lhs.m_val.data.v_raw.data, rhs.m_val.data.v_raw.data,
+                         lhs.m_val.data.v_raw.size) == 0;
     case NT_BOOLEAN_ARRAY:
       if (lhs.m_val.data.arr_boolean.size != rhs.m_val.data.arr_boolean.size) {
         return false;
@@ -219,6 +321,21 @@
                          rhs.m_val.data.arr_boolean.arr,
                          lhs.m_val.data.arr_boolean.size *
                              sizeof(lhs.m_val.data.arr_boolean.arr[0])) == 0;
+    case NT_INTEGER_ARRAY:
+      if (lhs.m_val.data.arr_int.size != rhs.m_val.data.arr_int.size) {
+        return false;
+      }
+      return std::memcmp(lhs.m_val.data.arr_int.arr, rhs.m_val.data.arr_int.arr,
+                         lhs.m_val.data.arr_int.size *
+                             sizeof(lhs.m_val.data.arr_int.arr[0])) == 0;
+    case NT_FLOAT_ARRAY:
+      if (lhs.m_val.data.arr_float.size != rhs.m_val.data.arr_float.size) {
+        return false;
+      }
+      return std::memcmp(lhs.m_val.data.arr_float.arr,
+                         rhs.m_val.data.arr_float.arr,
+                         lhs.m_val.data.arr_float.size *
+                             sizeof(lhs.m_val.data.arr_float.arr[0])) == 0;
     case NT_DOUBLE_ARRAY:
       if (lhs.m_val.data.arr_double.size != rhs.m_val.data.arr_double.size) {
         return false;
@@ -228,7 +345,8 @@
                          lhs.m_val.data.arr_double.size *
                              sizeof(lhs.m_val.data.arr_double.arr[0])) == 0;
     case NT_STRING_ARRAY:
-      return lhs.m_string_array == rhs.m_string_array;
+      return static_cast<StringArrayStorage*>(lhs.m_storage.get())->strings ==
+             static_cast<StringArrayStorage*>(rhs.m_storage.get())->strings;
     default:
       // assert(false && "unknown value type");
       return false;
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/Value_internal.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/Value_internal.cpp
new file mode 100644
index 0000000..2003d31
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/Value_internal.cpp
@@ -0,0 +1,49 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "Value_internal.h"
+
+using namespace nt;
+
+Value nt::ConvertNumericValue(const Value& value, NT_Type type) {
+  switch (type) {
+    case NT_INTEGER: {
+      Value newval =
+          Value::MakeInteger(GetNumericAs<int64_t>(value), value.time());
+      newval.SetServerTime(value.server_time());
+      return newval;
+    }
+    case NT_FLOAT: {
+      Value newval = Value::MakeFloat(GetNumericAs<float>(value), value.time());
+      newval.SetServerTime(value.server_time());
+      return newval;
+    }
+    case NT_DOUBLE: {
+      Value newval =
+          Value::MakeDouble(GetNumericAs<double>(value), value.time());
+      newval.SetServerTime(value.server_time());
+      return newval;
+    }
+    case NT_INTEGER_ARRAY: {
+      Value newval = Value::MakeIntegerArray(GetNumericArrayAs<int64_t>(value),
+                                             value.time());
+      newval.SetServerTime(value.server_time());
+      return newval;
+    }
+    case NT_FLOAT_ARRAY: {
+      Value newval =
+          Value::MakeFloatArray(GetNumericArrayAs<float>(value), value.time());
+      newval.SetServerTime(value.server_time());
+      return newval;
+    }
+    case NT_DOUBLE_ARRAY: {
+      Value newval = Value::MakeDoubleArray(GetNumericArrayAs<double>(value),
+                                            value.time());
+      newval.SetServerTime(value.server_time());
+      return newval;
+    }
+    default:
+      return {};
+  }
+}
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/Value_internal.h b/third_party/allwpilib/ntcore/src/main/native/cpp/Value_internal.h
index 54850ab..03532ac 100644
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/Value_internal.h
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/Value_internal.h
@@ -2,26 +2,90 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
-#ifndef NTCORE_VALUE_INTERNAL_H_
-#define NTCORE_VALUE_INTERNAL_H_
+#pragma once
 
+#include <cstring>
 #include <memory>
 #include <string>
 #include <string_view>
+#include <vector>
 
+#include <wpi/MemAlloc.h>
+
+#include "networktables/NetworkTableValue.h"
 #include "ntcore_c.h"
 
 namespace nt {
 
 class Value;
 
+template <typename T>
+inline void ConvertToC(const T& in, T* out) {
+  *out = in;
+}
+
 void ConvertToC(const Value& in, NT_Value* out);
-std::shared_ptr<Value> ConvertFromC(const NT_Value& value);
+Value ConvertFromC(const NT_Value& value);
+size_t ConvertToC(std::string_view in, char** out);
 void ConvertToC(std::string_view in, NT_String* out);
 inline std::string_view ConvertFromC(const NT_String& str) {
   return {str.str, str.len};
 }
 
-}  // namespace nt
+template <typename O, typename I>
+O* ConvertToC(const std::vector<I>& in, size_t* out_len) {
+  if (!out_len) {
+    return nullptr;
+  }
+  *out_len = in.size();
+  if (in.empty()) {
+    return nullptr;
+  }
+  O* out = static_cast<O*>(wpi::safe_malloc(sizeof(O) * in.size()));
+  for (size_t i = 0; i < in.size(); ++i) {
+    ConvertToC(in[i], &out[i]);
+  }
+  return out;
+}
 
-#endif  // NTCORE_VALUE_INTERNAL_H_
+template <typename O, typename I>
+O* ConvertToC(const std::basic_string<I>& in, size_t* out_len) {
+  char* out = static_cast<char*>(wpi::safe_malloc(in.size() + 1));
+  std::memmove(out, in.data(), in.size());  // NOLINT
+  out[in.size()] = '\0';
+  *out_len = in.size();
+  return out;
+}
+
+template <typename T>
+T GetNumericAs(const Value& value) {
+  if (value.IsInteger()) {
+    return static_cast<T>(value.GetInteger());
+  } else if (value.IsFloat()) {
+    return static_cast<T>(value.GetFloat());
+  } else if (value.IsDouble()) {
+    return static_cast<T>(value.GetDouble());
+  } else {
+    return {};
+  }
+}
+
+template <typename T>
+std::vector<T> GetNumericArrayAs(const Value& value) {
+  if (value.IsIntegerArray()) {
+    auto arr = value.GetIntegerArray();
+    return {arr.begin(), arr.end()};
+  } else if (value.IsFloatArray()) {
+    auto arr = value.GetFloatArray();
+    return {arr.begin(), arr.end()};
+  } else if (value.IsDoubleArray()) {
+    auto arr = value.GetDoubleArray();
+    return {arr.begin(), arr.end()};
+  } else {
+    return {};
+  }
+}
+
+Value ConvertNumericValue(const Value& value, NT_Type type);
+
+}  // namespace nt
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/WireDecoder.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/WireDecoder.cpp
deleted file mode 100644
index c0647dc..0000000
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/WireDecoder.cpp
+++ /dev/null
@@ -1,247 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "WireDecoder.h"
-
-#include <stdint.h>
-
-#include <cassert>
-#include <cstdlib>
-#include <cstring>
-
-#include <wpi/MathExtras.h>
-#include <wpi/MemAlloc.h>
-#include <wpi/leb128.h>
-
-using namespace nt;
-
-static double ReadDouble(const char*& buf) {
-  // Fast but non-portable!
-  uint64_t val = (*reinterpret_cast<const unsigned char*>(buf)) & 0xff;
-  ++buf;
-  val <<= 8;
-  val |= (*reinterpret_cast<const unsigned char*>(buf)) & 0xff;
-  ++buf;
-  val <<= 8;
-  val |= (*reinterpret_cast<const unsigned char*>(buf)) & 0xff;
-  ++buf;
-  val <<= 8;
-  val |= (*reinterpret_cast<const unsigned char*>(buf)) & 0xff;
-  ++buf;
-  val <<= 8;
-  val |= (*reinterpret_cast<const unsigned char*>(buf)) & 0xff;
-  ++buf;
-  val <<= 8;
-  val |= (*reinterpret_cast<const unsigned char*>(buf)) & 0xff;
-  ++buf;
-  val <<= 8;
-  val |= (*reinterpret_cast<const unsigned char*>(buf)) & 0xff;
-  ++buf;
-  val <<= 8;
-  val |= (*reinterpret_cast<const unsigned char*>(buf)) & 0xff;
-  ++buf;
-  return wpi::BitsToDouble(val);
-}
-
-WireDecoder::WireDecoder(wpi::raw_istream& is, unsigned int proto_rev,
-                         wpi::Logger& logger)
-    : m_is(is), m_logger(logger) {
-  // Start with a 1K temporary buffer.  Use malloc instead of new so we can
-  // realloc.
-  m_allocated = 1024;
-  m_buf = static_cast<char*>(wpi::safe_malloc(m_allocated));
-  m_proto_rev = proto_rev;
-  m_error = nullptr;
-}
-
-WireDecoder::~WireDecoder() {
-  std::free(m_buf);
-}
-
-bool WireDecoder::ReadDouble(double* val) {
-  const char* buf;
-  if (!Read(&buf, 8)) {
-    return false;
-  }
-  *val = ::ReadDouble(buf);
-  return true;
-}
-
-void WireDecoder::Realloc(size_t len) {
-  // Double current buffer size until we have enough space.
-  if (m_allocated >= len) {
-    return;
-  }
-  size_t newlen = m_allocated * 2;
-  while (newlen < len) {
-    newlen *= 2;
-  }
-  m_buf = static_cast<char*>(wpi::safe_realloc(m_buf, newlen));
-  m_allocated = newlen;
-}
-
-bool WireDecoder::ReadType(NT_Type* type) {
-  unsigned int itype;
-  if (!Read8(&itype)) {
-    return false;
-  }
-  // Convert from byte value to enum
-  switch (itype) {
-    case 0x00:
-      *type = NT_BOOLEAN;
-      break;
-    case 0x01:
-      *type = NT_DOUBLE;
-      break;
-    case 0x02:
-      *type = NT_STRING;
-      break;
-    case 0x03:
-      *type = NT_RAW;
-      break;
-    case 0x10:
-      *type = NT_BOOLEAN_ARRAY;
-      break;
-    case 0x11:
-      *type = NT_DOUBLE_ARRAY;
-      break;
-    case 0x12:
-      *type = NT_STRING_ARRAY;
-      break;
-    case 0x20:
-      *type = NT_RPC;
-      break;
-    default:
-      *type = NT_UNASSIGNED;
-      m_error = "unrecognized value type";
-      return false;
-  }
-  return true;
-}
-
-std::shared_ptr<Value> WireDecoder::ReadValue(NT_Type type) {
-  switch (type) {
-    case NT_BOOLEAN: {
-      unsigned int v;
-      if (!Read8(&v)) {
-        return nullptr;
-      }
-      return Value::MakeBoolean(v != 0);
-    }
-    case NT_DOUBLE: {
-      double v;
-      if (!ReadDouble(&v)) {
-        return nullptr;
-      }
-      return Value::MakeDouble(v);
-    }
-    case NT_STRING: {
-      std::string v;
-      if (!ReadString(&v)) {
-        return nullptr;
-      }
-      return Value::MakeString(std::move(v));
-    }
-    case NT_RAW: {
-      if (m_proto_rev < 0x0300u) {
-        m_error = "received raw value in protocol < 3.0";
-        return nullptr;
-      }
-      std::string v;
-      if (!ReadString(&v)) {
-        return nullptr;
-      }
-      return Value::MakeRaw(std::move(v));
-    }
-    case NT_RPC: {
-      if (m_proto_rev < 0x0300u) {
-        m_error = "received RPC value in protocol < 3.0";
-        return nullptr;
-      }
-      std::string v;
-      if (!ReadString(&v)) {
-        return nullptr;
-      }
-      return Value::MakeRpc(std::move(v));
-    }
-    case NT_BOOLEAN_ARRAY: {
-      // size
-      unsigned int size;
-      if (!Read8(&size)) {
-        return nullptr;
-      }
-
-      // array values
-      const char* buf;
-      if (!Read(&buf, size)) {
-        return nullptr;
-      }
-      std::vector<int> v(size);
-      for (unsigned int i = 0; i < size; ++i) {
-        v[i] = buf[i] ? 1 : 0;
-      }
-      return Value::MakeBooleanArray(std::move(v));
-    }
-    case NT_DOUBLE_ARRAY: {
-      // size
-      unsigned int size;
-      if (!Read8(&size)) {
-        return nullptr;
-      }
-
-      // array values
-      const char* buf;
-      if (!Read(&buf, size * 8)) {
-        return nullptr;
-      }
-      std::vector<double> v(size);
-      for (unsigned int i = 0; i < size; ++i) {
-        v[i] = ::ReadDouble(buf);
-      }
-      return Value::MakeDoubleArray(std::move(v));
-    }
-    case NT_STRING_ARRAY: {
-      // size
-      unsigned int size;
-      if (!Read8(&size)) {
-        return nullptr;
-      }
-
-      // array values
-      std::vector<std::string> v(size);
-      for (unsigned int i = 0; i < size; ++i) {
-        if (!ReadString(&v[i])) {
-          return nullptr;
-        }
-      }
-      return Value::MakeStringArray(std::move(v));
-    }
-    default:
-      m_error = "invalid type when trying to read value";
-      return nullptr;
-  }
-}
-
-bool WireDecoder::ReadString(std::string* str) {
-  size_t len;
-  if (m_proto_rev < 0x0300u) {
-    unsigned int v;
-    if (!Read16(&v)) {
-      return false;
-    }
-    len = v;
-  } else {
-    uint64_t v;
-    if (!ReadUleb128(&v)) {
-      return false;
-    }
-    len = v;
-  }
-  const char* buf;
-  if (!Read(&buf, len)) {
-    return false;
-  }
-  str->assign(buf, len);
-  return true;
-}
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/WireDecoder.h b/third_party/allwpilib/ntcore/src/main/native/cpp/WireDecoder.h
deleted file mode 100644
index 972be57..0000000
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/WireDecoder.h
+++ /dev/null
@@ -1,163 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef NTCORE_WIREDECODER_H_
-#define NTCORE_WIREDECODER_H_
-
-#include <stdint.h>
-
-#include <cstddef>
-#include <memory>
-#include <string>
-
-#include <wpi/leb128.h>
-#include <wpi/raw_istream.h>
-
-#include "Log.h"
-#include "networktables/NetworkTableValue.h"
-
-namespace nt {
-
-/* Decodes network data into native representation.
- * This class is designed to read from a raw_istream, which provides a blocking
- * read interface.  There are no provisions in this class for resuming a read
- * that was interrupted partway.  Read functions return false if
- * raw_istream.read() returned false (indicating the end of the input data
- * stream).
- */
-class WireDecoder {
- public:
-  WireDecoder(wpi::raw_istream& is, unsigned int proto_rev,
-              wpi::Logger& logger);
-  ~WireDecoder();
-
-  void set_proto_rev(unsigned int proto_rev) { m_proto_rev = proto_rev; }
-
-  /* Get the active protocol revision. */
-  unsigned int proto_rev() const { return m_proto_rev; }
-
-  /* Get the logger. */
-  wpi::Logger& logger() const { return m_logger; }
-
-  /* Clears error indicator. */
-  void Reset() { m_error = nullptr; }
-
-  /* Returns error indicator (a string describing the error).  Returns nullptr
-   * if no error has occurred.
-   */
-  const char* error() const { return m_error; }
-
-  void set_error(const char* error) { m_error = error; }
-
-  /* Reads the specified number of bytes.
-   * @param buf pointer to read data (output parameter)
-   * @param len number of bytes to read
-   * Caution: the buffer is only temporarily valid.
-   */
-  bool Read(const char** buf, size_t len) {
-    if (len > m_allocated) {
-      Realloc(len);
-    }
-    *buf = m_buf;
-    m_is.read(m_buf, len);
-#if 0
-    if (m_logger.min_level() <= NT_LOG_DEBUG4 && m_logger.HasLogger()) {
-      std::ostringstream oss;
-      oss << "read " << len << " bytes:" << std::hex;
-      if (!rv) {
-        oss << "error";
-      } else {
-        for (size_t i = 0; i < len; ++i)
-          oss << ' ' << static_cast<unsigned int>((*buf)[i]);
-      }
-      m_logger.Log(NT_LOG_DEBUG4, __FILE__, __LINE__, oss.str().c_str());
-    }
-#endif
-    return !m_is.has_error();
-  }
-
-  /* Reads a single byte. */
-  bool Read8(unsigned int* val) {
-    const char* buf;
-    if (!Read(&buf, 1)) {
-      return false;
-    }
-    *val = (*reinterpret_cast<const unsigned char*>(buf)) & 0xff;
-    return true;
-  }
-
-  /* Reads a 16-bit word. */
-  bool Read16(unsigned int* val) {
-    const char* buf;
-    if (!Read(&buf, 2)) {
-      return false;
-    }
-    unsigned int v = (*reinterpret_cast<const unsigned char*>(buf)) & 0xff;
-    ++buf;
-    v <<= 8;
-    v |= (*reinterpret_cast<const unsigned char*>(buf)) & 0xff;
-    *val = v;
-    return true;
-  }
-
-  /* Reads a 32-bit word. */
-  bool Read32(uint32_t* val) {
-    const char* buf;
-    if (!Read(&buf, 4)) {
-      return false;
-    }
-    unsigned int v = (*reinterpret_cast<const unsigned char*>(buf)) & 0xff;
-    ++buf;
-    v <<= 8;
-    v |= (*reinterpret_cast<const unsigned char*>(buf)) & 0xff;
-    ++buf;
-    v <<= 8;
-    v |= (*reinterpret_cast<const unsigned char*>(buf)) & 0xff;
-    ++buf;
-    v <<= 8;
-    v |= (*reinterpret_cast<const unsigned char*>(buf)) & 0xff;
-    *val = v;
-    return true;
-  }
-
-  /* Reads a double. */
-  bool ReadDouble(double* val);
-
-  /* Reads an ULEB128-encoded unsigned integer. */
-  bool ReadUleb128(uint64_t* val) { return wpi::ReadUleb128(m_is, val); }
-
-  bool ReadType(NT_Type* type);
-  bool ReadString(std::string* str);
-  std::shared_ptr<Value> ReadValue(NT_Type type);
-
-  WireDecoder(const WireDecoder&) = delete;
-  WireDecoder& operator=(const WireDecoder&) = delete;
-
- protected:
-  /* The protocol revision.  E.g. 0x0200 for version 2.0. */
-  unsigned int m_proto_rev;
-
-  /* Error indicator. */
-  const char* m_error;
-
- private:
-  /* Reallocate temporary buffer to specified length. */
-  void Realloc(size_t len);
-
-  /* input stream */
-  wpi::raw_istream& m_is;
-
-  /* logger */
-  wpi::Logger& m_logger;
-
-  /* temporary buffer */
-  char* m_buf;
-
-  /* allocated size of temporary buffer */
-  size_t m_allocated;
-};
-
-}  // namespace nt
-
-#endif  // NTCORE_WIREDECODER_H_
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/WireEncoder.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/WireEncoder.cpp
deleted file mode 100644
index b35b780..0000000
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/WireEncoder.cpp
+++ /dev/null
@@ -1,226 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "WireEncoder.h"
-
-#include <stdint.h>
-
-#include <cassert>
-#include <cstdlib>
-#include <cstring>
-
-#include <wpi/MathExtras.h>
-#include <wpi/leb128.h>
-
-using namespace nt;
-
-WireEncoder::WireEncoder(unsigned int proto_rev) {
-  m_proto_rev = proto_rev;
-  m_error = nullptr;
-}
-
-void WireEncoder::WriteDouble(double val) {
-  // The highest performance way to do this, albeit non-portable.
-  uint64_t v = wpi::DoubleToBits(val);
-  m_data.append(
-      {static_cast<char>((v >> 56) & 0xff), static_cast<char>((v >> 48) & 0xff),
-       static_cast<char>((v >> 40) & 0xff), static_cast<char>((v >> 32) & 0xff),
-       static_cast<char>((v >> 24) & 0xff), static_cast<char>((v >> 16) & 0xff),
-       static_cast<char>((v >> 8) & 0xff), static_cast<char>(v & 0xff)});
-}
-
-void WireEncoder::WriteUleb128(uint32_t val) {
-  wpi::WriteUleb128(m_data, val);
-}
-
-void WireEncoder::WriteType(NT_Type type) {
-  char ch;
-  // Convert from enum to actual byte value.
-  switch (type) {
-    case NT_BOOLEAN:
-      ch = 0x00;
-      break;
-    case NT_DOUBLE:
-      ch = 0x01;
-      break;
-    case NT_STRING:
-      ch = 0x02;
-      break;
-    case NT_RAW:
-      if (m_proto_rev < 0x0300u) {
-        m_error = "raw type not supported in protocol < 3.0";
-        return;
-      }
-      ch = 0x03;
-      break;
-    case NT_BOOLEAN_ARRAY:
-      ch = 0x10;
-      break;
-    case NT_DOUBLE_ARRAY:
-      ch = 0x11;
-      break;
-    case NT_STRING_ARRAY:
-      ch = 0x12;
-      break;
-    case NT_RPC:
-      if (m_proto_rev < 0x0300u) {
-        m_error = "RPC type not supported in protocol < 3.0";
-        return;
-      }
-      ch = 0x20;
-      break;
-    default:
-      m_error = "unrecognized type";
-      return;
-  }
-  m_data.push_back(ch);
-}
-
-size_t WireEncoder::GetValueSize(const Value& value) const {
-  switch (value.type()) {
-    case NT_BOOLEAN:
-      return 1;
-    case NT_DOUBLE:
-      return 8;
-    case NT_STRING:
-      return GetStringSize(value.GetString());
-    case NT_RAW:
-      if (m_proto_rev < 0x0300u) {
-        return 0;
-      }
-      return GetStringSize(value.GetRaw());
-    case NT_RPC:
-      if (m_proto_rev < 0x0300u) {
-        return 0;
-      }
-      return GetStringSize(value.GetRpc());
-    case NT_BOOLEAN_ARRAY: {
-      // 1-byte size, 1 byte per element
-      size_t size = value.GetBooleanArray().size();
-      if (size > 0xff) {
-        size = 0xff;  // size is only 1 byte, truncate
-      }
-      return 1 + size;
-    }
-    case NT_DOUBLE_ARRAY: {
-      // 1-byte size, 8 bytes per element
-      size_t size = value.GetDoubleArray().size();
-      if (size > 0xff) {
-        size = 0xff;  // size is only 1 byte, truncate
-      }
-      return 1 + size * 8;
-    }
-    case NT_STRING_ARRAY: {
-      auto v = value.GetStringArray();
-      size_t size = v.size();
-      if (size > 0xff) {
-        size = 0xff;  // size is only 1 byte, truncate
-      }
-      size_t len = 1;  // 1-byte size
-      for (size_t i = 0; i < size; ++i) {
-        len += GetStringSize(v[i]);
-      }
-      return len;
-    }
-    default:
-      return 0;
-  }
-}
-
-void WireEncoder::WriteValue(const Value& value) {
-  switch (value.type()) {
-    case NT_BOOLEAN:
-      Write8(value.GetBoolean() ? 1 : 0);
-      break;
-    case NT_DOUBLE:
-      WriteDouble(value.GetDouble());
-      break;
-    case NT_STRING:
-      WriteString(value.GetString());
-      break;
-    case NT_RAW:
-      if (m_proto_rev < 0x0300u) {
-        m_error = "raw values not supported in protocol < 3.0";
-        return;
-      }
-      WriteString(value.GetRaw());
-      break;
-    case NT_RPC:
-      if (m_proto_rev < 0x0300u) {
-        m_error = "RPC values not supported in protocol < 3.0";
-        return;
-      }
-      WriteString(value.GetRpc());
-      break;
-    case NT_BOOLEAN_ARRAY: {
-      auto v = value.GetBooleanArray();
-      size_t size = v.size();
-      if (size > 0xff) {
-        size = 0xff;  // size is only 1 byte, truncate
-      }
-      Write8(size);
-
-      for (size_t i = 0; i < size; ++i) {
-        Write8(v[i] ? 1 : 0);
-      }
-      break;
-    }
-    case NT_DOUBLE_ARRAY: {
-      auto v = value.GetDoubleArray();
-      size_t size = v.size();
-      if (size > 0xff) {
-        size = 0xff;  // size is only 1 byte, truncate
-      }
-      Write8(size);
-
-      for (size_t i = 0; i < size; ++i) {
-        WriteDouble(v[i]);
-      }
-      break;
-    }
-    case NT_STRING_ARRAY: {
-      auto v = value.GetStringArray();
-      size_t size = v.size();
-      if (size > 0xff) {
-        size = 0xff;  // size is only 1 byte, truncate
-      }
-      Write8(size);
-
-      for (size_t i = 0; i < size; ++i) {
-        WriteString(v[i]);
-      }
-      break;
-    }
-    default:
-      m_error = "unrecognized type when writing value";
-      return;
-  }
-}
-
-size_t WireEncoder::GetStringSize(std::string_view str) const {
-  if (m_proto_rev < 0x0300u) {
-    size_t len = str.size();
-    if (len > 0xffff) {
-      len = 0xffff;  // Limited to 64K length; truncate
-    }
-    return 2 + len;
-  }
-  return wpi::SizeUleb128(str.size()) + str.size();
-}
-
-void WireEncoder::WriteString(std::string_view str) {
-  // length
-  size_t len = str.size();
-  if (m_proto_rev < 0x0300u) {
-    if (len > 0xffff) {
-      len = 0xffff;  // Limited to 64K length; truncate
-    }
-    Write16(len);
-  } else {
-    WriteUleb128(len);
-  }
-
-  // contents
-  m_data.append(str.data(), str.data() + len);
-}
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/WireEncoder.h b/third_party/allwpilib/ntcore/src/main/native/cpp/WireEncoder.h
deleted file mode 100644
index 84edc39..0000000
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/WireEncoder.h
+++ /dev/null
@@ -1,108 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef NTCORE_WIREENCODER_H_
-#define NTCORE_WIREENCODER_H_
-
-#include <stdint.h>
-
-#include <cassert>
-#include <cstddef>
-#include <string_view>
-
-#include <wpi/SmallVector.h>
-
-#include "networktables/NetworkTableValue.h"
-
-namespace nt {
-
-/* Encodes native data for network transmission.
- * This class maintains an internal memory buffer for written data so that
- * it can be efficiently bursted to the network after a number of writes
- * have been performed.  For this reason, all operations are non-blocking.
- */
-class WireEncoder {
- public:
-  explicit WireEncoder(unsigned int proto_rev);
-
-  /* Change the protocol revision (mostly affects value encoding). */
-  void set_proto_rev(unsigned int proto_rev) { m_proto_rev = proto_rev; }
-
-  /* Get the active protocol revision. */
-  unsigned int proto_rev() const { return m_proto_rev; }
-
-  /* Clears buffer and error indicator. */
-  void Reset() {
-    m_data.clear();
-    m_error = nullptr;
-  }
-
-  /* Returns error indicator (a string describing the error).  Returns nullptr
-   * if no error has occurred.
-   */
-  const char* error() const { return m_error; }
-
-  /* Returns pointer to start of memory buffer with written data. */
-  const char* data() const { return m_data.data(); }
-
-  /* Returns number of bytes written to memory buffer. */
-  size_t size() const { return m_data.size(); }
-
-  std::string_view ToStringView() const {
-    return {m_data.data(), m_data.size()};
-  }
-
-  /* Writes a single byte. */
-  void Write8(unsigned int val) {
-    m_data.push_back(static_cast<char>(val & 0xff));
-  }
-
-  /* Writes a 16-bit word. */
-  void Write16(unsigned int val) {
-    m_data.append(
-        {static_cast<char>((val >> 8) & 0xff), static_cast<char>(val & 0xff)});
-  }
-
-  /* Writes a 32-bit word. */
-  void Write32(uint32_t val) {
-    m_data.append({static_cast<char>((val >> 24) & 0xff),
-                   static_cast<char>((val >> 16) & 0xff),
-                   static_cast<char>((val >> 8) & 0xff),
-                   static_cast<char>(val & 0xff)});
-  }
-
-  /* Writes a double. */
-  void WriteDouble(double val);
-
-  /* Writes an ULEB128-encoded unsigned integer. */
-  void WriteUleb128(uint32_t val);
-
-  void WriteType(NT_Type type);
-  void WriteValue(const Value& value);
-  void WriteString(std::string_view str);
-
-  /* Utility function to get the written size of a value (without actually
-   * writing it).
-   */
-  size_t GetValueSize(const Value& value) const;
-
-  /* Utility function to get the written size of a string (without actually
-   * writing it).
-   */
-  size_t GetStringSize(std::string_view str) const;
-
- protected:
-  /* The protocol revision.  E.g. 0x0200 for version 2.0. */
-  unsigned int m_proto_rev;
-
-  /* Error indicator. */
-  const char* m_error;
-
- private:
-  wpi::SmallVector<char, 256> m_data;
-};
-
-}  // namespace nt
-
-#endif  // NTCORE_WIREENCODER_H_
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/jni/NetworkTablesJNI.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/jni/NetworkTablesJNI.cpp
index 6c7ed82..b868604 100644
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/jni/NetworkTablesJNI.cpp
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/jni/NetworkTablesJNI.cpp
@@ -9,9 +9,11 @@
 #include <fmt/format.h>
 #include <wpi/ConvertUTF.h>
 #include <wpi/jni_util.h>
+#include <wpi/json.h>
 
 #include "edu_wpi_first_networktables_NetworkTablesJNI.h"
 #include "ntcore.h"
+#include "ntcore_cpp.h"
 
 using namespace wpi::java;
 
@@ -19,6 +21,11 @@
 #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
 #endif
 
+namespace nt {
+bool JNI_LoadTypes(JNIEnv* env);
+void JNI_UnloadTypes(JNIEnv* env);
+}  // namespace nt
+
 //
 // Globals and load/unload
 //
@@ -27,35 +34,40 @@
 static JavaVM* jvm = nullptr;
 static JClass booleanCls;
 static JClass connectionInfoCls;
-static JClass connectionNotificationCls;
 static JClass doubleCls;
-static JClass entryInfoCls;
-static JClass entryNotificationCls;
+static JClass eventCls;
+static JClass floatCls;
 static JClass logMessageCls;
-static JClass rpcAnswerCls;
+static JClass longCls;
+static JClass optionalLongCls;
+static JClass pubSubOptionsCls;
+static JClass timeSyncEventDataCls;
+static JClass topicInfoCls;
 static JClass valueCls;
+static JClass valueEventDataCls;
 static JException illegalArgEx;
 static JException interruptedEx;
 static JException nullPointerEx;
-static JException persistentEx;
 
 static const JClassInit classes[] = {
     {"java/lang/Boolean", &booleanCls},
     {"edu/wpi/first/networktables/ConnectionInfo", &connectionInfoCls},
-    {"edu/wpi/first/networktables/ConnectionNotification",
-     &connectionNotificationCls},
     {"java/lang/Double", &doubleCls},
-    {"edu/wpi/first/networktables/EntryInfo", &entryInfoCls},
-    {"edu/wpi/first/networktables/EntryNotification", &entryNotificationCls},
+    {"edu/wpi/first/networktables/NetworkTableEvent", &eventCls},
+    {"java/lang/Float", &floatCls},
     {"edu/wpi/first/networktables/LogMessage", &logMessageCls},
-    {"edu/wpi/first/networktables/RpcAnswer", &rpcAnswerCls},
-    {"edu/wpi/first/networktables/NetworkTableValue", &valueCls}};
+    {"java/lang/Long", &longCls},
+    {"java/util/OptionalLong", &optionalLongCls},
+    {"edu/wpi/first/networktables/PubSubOptions", &pubSubOptionsCls},
+    {"edu/wpi/first/networktables/TimeSyncEventData", &timeSyncEventDataCls},
+    {"edu/wpi/first/networktables/TopicInfo", &topicInfoCls},
+    {"edu/wpi/first/networktables/NetworkTableValue", &valueCls},
+    {"edu/wpi/first/networktables/ValueEventData", &valueEventDataCls}};
 
 static const JExceptionInit exceptions[] = {
     {"java/lang/IllegalArgumentException", &illegalArgEx},
     {"java/lang/InterruptedException", &interruptedEx},
-    {"java/lang/NullPointerException", &nullPointerEx},
-    {"edu/wpi/first/networktables/PersistentException", &persistentEx}};
+    {"java/lang/NullPointerException", &nullPointerEx}};
 
 extern "C" {
 
@@ -82,6 +94,10 @@
     }
   }
 
+  if (!nt::JNI_LoadTypes(env)) {
+    return JNI_ERR;
+  }
+
   return JNI_VERSION_1_6;
 }
 
@@ -97,6 +113,7 @@
   for (auto& c : exceptions) {
     c.cls->free(env);
   }
+  nt::JNI_UnloadTypes(env);
   jvm = nullptr;
 }
 
@@ -106,92 +123,98 @@
 // Conversions from Java objects to C++
 //
 
-inline std::shared_ptr<nt::Value> FromJavaRaw(JNIEnv* env, jbyteArray jarr,
-                                              jlong time) {
-  CriticalJByteArrayRef ref{env, jarr};
-  if (!ref) {
-    return nullptr;
+static nt::PubSubOptions FromJavaPubSubOptions(JNIEnv* env, jobject joptions) {
+  if (!joptions) {
+    return {};
   }
-  return nt::Value::MakeRaw(ref.str(), time);
-}
+#define FIELD(name, sig)                                         \
+  static jfieldID name##Field = nullptr;                         \
+  if (!name##Field) {                                            \
+    name##Field = env->GetFieldID(pubSubOptionsCls, #name, sig); \
+  }
 
-inline std::shared_ptr<nt::Value> FromJavaRawBB(JNIEnv* env, jobject jbb,
-                                                int len, jlong time) {
-  JByteArrayRef ref{env, jbb, len};
-  if (!ref) {
-    return nullptr;
-  }
-  return nt::Value::MakeRaw(ref.str(), time);
-}
+  FIELD(pollStorage, "I");
+  FIELD(periodic, "D");
+  FIELD(excludePublisher, "I");
+  FIELD(sendAll, "Z");
+  FIELD(topicsOnly, "Z");
+  FIELD(keepDuplicates, "Z");
+  FIELD(prefixMatch, "Z");
+  FIELD(disableRemote, "Z");
+  FIELD(disableLocal, "Z");
+  FIELD(excludeSelf, "Z");
 
-inline std::shared_ptr<nt::Value> FromJavaRpc(JNIEnv* env, jbyteArray jarr,
-                                              jlong time) {
-  CriticalJByteArrayRef ref{env, jarr};
-  if (!ref) {
-    return nullptr;
-  }
-  return nt::Value::MakeRpc(ref.str(), time);
-}
+#undef FIELD
 
-std::shared_ptr<nt::Value> FromJavaBooleanArray(JNIEnv* env, jbooleanArray jarr,
-                                                jlong time) {
-  CriticalJBooleanArrayRef ref{env, jarr};
-  if (!ref) {
-    return nullptr;
-  }
-  wpi::span<const jboolean> elements{ref};
-  size_t len = elements.size();
-  std::vector<int> arr;
-  arr.reserve(len);
-  for (size_t i = 0; i < len; ++i) {
-    arr.push_back(elements[i]);
-  }
-  return nt::Value::MakeBooleanArray(arr, time);
-}
+#define FIELD(ctype, jtype, name) \
+  .name = static_cast<ctype>(env->Get##jtype##Field(joptions, name##Field))
 
-std::shared_ptr<nt::Value> FromJavaDoubleArray(JNIEnv* env, jdoubleArray jarr,
-                                               jlong time) {
-  CriticalJDoubleArrayRef ref{env, jarr};
-  if (!ref) {
-    return nullptr;
-  }
-  return nt::Value::MakeDoubleArray(ref, time);
-}
+  return {FIELD(unsigned int, Int, pollStorage),
+          FIELD(double, Double, periodic),
+          FIELD(NT_Publisher, Int, excludePublisher),
+          FIELD(bool, Boolean, sendAll),
+          FIELD(bool, Boolean, topicsOnly),
+          FIELD(bool, Boolean, keepDuplicates),
+          FIELD(bool, Boolean, prefixMatch),
+          FIELD(bool, Boolean, disableRemote),
+          FIELD(bool, Boolean, disableLocal),
+          FIELD(bool, Boolean, excludeSelf)};
 
-std::shared_ptr<nt::Value> FromJavaStringArray(JNIEnv* env, jobjectArray jarr,
-                                               jlong time) {
-  size_t len = env->GetArrayLength(jarr);
-  std::vector<std::string> arr;
-  arr.reserve(len);
-  for (size_t i = 0; i < len; ++i) {
-    JLocal<jstring> elem{
-        env, static_cast<jstring>(env->GetObjectArrayElement(jarr, i))};
-    if (!elem) {
-      return nullptr;
-    }
-    arr.emplace_back(JStringRef{env, elem}.str());
-  }
-  return nt::Value::MakeStringArray(std::move(arr), time);
+#undef GET
+#undef FIELD
 }
 
 //
 // Conversions from C++ to Java objects
 //
 
+static jobject MakeJObject(JNIEnv* env, std::optional<int64_t> value) {
+  static jmethodID emptyMethod = nullptr;
+  static jmethodID ofMethod = nullptr;
+  if (!emptyMethod) {
+    emptyMethod = env->GetStaticMethodID(optionalLongCls, "empty",
+                                         "()Ljava/util/OptionalLong;");
+  }
+  if (!ofMethod) {
+    ofMethod = env->GetStaticMethodID(optionalLongCls, "of",
+                                      "(J)Ljava/util/OptionalLong;");
+  }
+  if (value) {
+    return env->CallStaticObjectMethod(optionalLongCls, ofMethod,
+                                       static_cast<jlong>(*value));
+  } else {
+    return env->CallStaticObjectMethod(optionalLongCls, emptyMethod);
+  }
+}
+
 static jobject MakeJObject(JNIEnv* env, const nt::Value& value) {
   static jmethodID booleanConstructor = nullptr;
   static jmethodID doubleConstructor = nullptr;
+  static jmethodID floatConstructor = nullptr;
+  static jmethodID longConstructor = nullptr;
   if (!booleanConstructor) {
     booleanConstructor = env->GetMethodID(booleanCls, "<init>", "(Z)V");
   }
   if (!doubleConstructor) {
     doubleConstructor = env->GetMethodID(doubleCls, "<init>", "(D)V");
   }
+  if (!floatConstructor) {
+    floatConstructor = env->GetMethodID(floatCls, "<init>", "(F)V");
+  }
+  if (!longConstructor) {
+    longConstructor = env->GetMethodID(longCls, "<init>", "(J)V");
+  }
 
   switch (value.type()) {
     case NT_BOOLEAN:
       return env->NewObject(booleanCls, booleanConstructor,
                             static_cast<jboolean>(value.GetBoolean() ? 1 : 0));
+    case NT_INTEGER:
+      return env->NewObject(longCls, longConstructor,
+                            static_cast<jlong>(value.GetInteger()));
+    case NT_FLOAT:
+      return env->NewObject(floatCls, floatConstructor,
+                            static_cast<jfloat>(value.GetFloat()));
     case NT_DOUBLE:
       return env->NewObject(doubleCls, doubleConstructor,
                             static_cast<jdouble>(value.GetDouble()));
@@ -201,28 +224,31 @@
       return MakeJByteArray(env, value.GetRaw());
     case NT_BOOLEAN_ARRAY:
       return MakeJBooleanArray(env, value.GetBooleanArray());
+    case NT_INTEGER_ARRAY:
+      return MakeJLongArray(env, value.GetIntegerArray());
+    case NT_FLOAT_ARRAY:
+      return MakeJFloatArray(env, value.GetFloatArray());
     case NT_DOUBLE_ARRAY:
       return MakeJDoubleArray(env, value.GetDoubleArray());
     case NT_STRING_ARRAY:
       return MakeJStringArray(env, value.GetStringArray());
-    case NT_RPC:
-      return MakeJByteArray(env, value.GetRpc());
     default:
       return nullptr;
   }
 }
 
-static jobject MakeJValue(JNIEnv* env, const nt::Value* value) {
+static jobject MakeJValue(JNIEnv* env, const nt::Value& value) {
   static jmethodID constructor =
-      env->GetMethodID(valueCls, "<init>", "(ILjava/lang/Object;J)V");
+      env->GetMethodID(valueCls, "<init>", "(ILjava/lang/Object;JJ)V");
   if (!value) {
     return env->NewObject(valueCls, constructor,
                           static_cast<jint>(NT_UNASSIGNED), nullptr,
-                          static_cast<jlong>(0));
+                          static_cast<jlong>(0), static_cast<jlong>(0));
   }
-  return env->NewObject(valueCls, constructor, static_cast<jint>(value->type()),
-                        MakeJObject(env, *value),
-                        static_cast<jlong>(value->time()));
+  return env->NewObject(valueCls, constructor, static_cast<jint>(value.type()),
+                        MakeJObject(env, value),
+                        static_cast<jlong>(value.time()),
+                        static_cast<jlong>(value.server_time()));
 }
 
 static jobject MakeJObject(JNIEnv* env, const nt::ConnectionInfo& info) {
@@ -237,120 +263,96 @@
                         static_cast<jint>(info.protocol_version));
 }
 
-static jobject MakeJObject(JNIEnv* env, jobject inst,
-                           const nt::ConnectionNotification& notification) {
+static jobject MakeJObject(JNIEnv* env, const nt::LogMessage& msg) {
   static jmethodID constructor = env->GetMethodID(
-      connectionNotificationCls, "<init>",
-      "(Ledu/wpi/first/networktables/NetworkTableInstance;IZLedu/wpi/first/"
-      "networktables/ConnectionInfo;)V");
-  JLocal<jobject> conn{env, MakeJObject(env, notification.conn)};
-  return env->NewObject(connectionNotificationCls, constructor, inst,
-                        static_cast<jint>(notification.listener),
-                        static_cast<jboolean>(notification.connected),
-                        conn.obj());
-}
-
-static jobject MakeJObject(JNIEnv* env, jobject inst,
-                           const nt::EntryInfo& info) {
-  static jmethodID constructor =
-      env->GetMethodID(entryInfoCls, "<init>",
-                       "(Ledu/wpi/first/networktables/"
-                       "NetworkTableInstance;ILjava/lang/String;IIJ)V");
-  JLocal<jstring> name{env, MakeJString(env, info.name)};
-  return env->NewObject(
-      entryInfoCls, constructor, inst, static_cast<jint>(info.entry),
-      name.obj(), static_cast<jint>(info.type), static_cast<jint>(info.flags),
-      static_cast<jlong>(info.last_change));
-}
-
-static jobject MakeJObject(JNIEnv* env, jobject inst,
-                           const nt::EntryNotification& notification) {
-  static jmethodID constructor = env->GetMethodID(
-      entryNotificationCls, "<init>",
-      "(Ledu/wpi/first/networktables/NetworkTableInstance;IILjava/lang/"
-      "String;Ledu/wpi/first/networktables/NetworkTableValue;I)V");
-  JLocal<jstring> name{env, MakeJString(env, notification.name)};
-  JLocal<jobject> value{env, MakeJValue(env, notification.value.get())};
-  return env->NewObject(entryNotificationCls, constructor, inst,
-                        static_cast<jint>(notification.listener),
-                        static_cast<jint>(notification.entry), name.obj(),
-                        value.obj(), static_cast<jint>(notification.flags));
-}
-
-static jobject MakeJObject(JNIEnv* env, jobject inst,
-                           const nt::LogMessage& msg) {
-  static jmethodID constructor = env->GetMethodID(
-      logMessageCls, "<init>",
-      "(Ledu/wpi/first/networktables/NetworkTableInstance;IILjava/lang/"
-      "String;ILjava/lang/String;)V");
+      logMessageCls, "<init>", "(ILjava/lang/String;ILjava/lang/String;)V");
   JLocal<jstring> filename{env, MakeJString(env, msg.filename)};
   JLocal<jstring> message{env, MakeJString(env, msg.message)};
-  return env->NewObject(logMessageCls, constructor, inst,
-                        static_cast<jint>(msg.logger),
+  return env->NewObject(logMessageCls, constructor,
                         static_cast<jint>(msg.level), filename.obj(),
                         static_cast<jint>(msg.line), message.obj());
 }
 
 static jobject MakeJObject(JNIEnv* env, jobject inst,
-                           const nt::RpcAnswer& answer) {
+                           const nt::TopicInfo& info) {
+  static jmethodID constructor = env->GetMethodID(
+      topicInfoCls, "<init>",
+      "(Ledu/wpi/first/networktables/"
+      "NetworkTableInstance;ILjava/lang/String;ILjava/lang/String;)V");
+  JLocal<jstring> name{env, MakeJString(env, info.name)};
+  JLocal<jstring> typeStr{env, MakeJString(env, info.type_str)};
+  return env->NewObject(topicInfoCls, constructor, inst,
+                        static_cast<jint>(info.topic), name.obj(),
+                        static_cast<jint>(info.type), typeStr.obj());
+}
+
+static jobject MakeJObject(JNIEnv* env, jobject inst,
+                           const nt::ValueEventData& data) {
   static jmethodID constructor =
-      env->GetMethodID(rpcAnswerCls, "<init>",
-                       "(Ledu/wpi/first/networktables/"
-                       "NetworkTableInstance;IILjava/lang/String;[B"
-                       "Ledu/wpi/first/networktables/ConnectionInfo;)V");
-  JLocal<jstring> name{env, MakeJString(env, answer.name)};
-  JLocal<jbyteArray> params{env, MakeJByteArray(env, answer.params)};
-  JLocal<jobject> conn{env, MakeJObject(env, answer.conn)};
+      env->GetMethodID(valueEventDataCls, "<init>",
+                       "(Ledu/wpi/first/networktables/NetworkTableInstance;II"
+                       "Ledu/wpi/first/networktables/NetworkTableValue;)V");
+  JLocal<jobject> value{env, MakeJValue(env, data.value)};
+  return env->NewObject(valueEventDataCls, constructor, inst,
+                        static_cast<jint>(data.topic),
+                        static_cast<jint>(data.subentry), value.obj());
+}
+
+static jobject MakeJObject(JNIEnv* env, const nt::TimeSyncEventData& data) {
+  static jmethodID constructor =
+      env->GetMethodID(timeSyncEventDataCls, "<init>", "(JJZ)V");
+  return env->NewObject(timeSyncEventDataCls, constructor,
+                        static_cast<jlong>(data.serverTimeOffset),
+                        static_cast<jlong>(data.rtt2),
+                        static_cast<jboolean>(data.valid));
+}
+
+static jobject MakeJObject(JNIEnv* env, jobject inst, const nt::Event& event) {
+  static jmethodID constructor =
+      env->GetMethodID(eventCls, "<init>",
+                       "(Ledu/wpi/first/networktables/NetworkTableInstance;II"
+                       "Ledu/wpi/first/networktables/ConnectionInfo;"
+                       "Ledu/wpi/first/networktables/TopicInfo;"
+                       "Ledu/wpi/first/networktables/ValueEventData;"
+                       "Ledu/wpi/first/networktables/LogMessage;"
+                       "Ledu/wpi/first/networktables/TimeSyncEventData;)V");
+  JLocal<jobject> connInfo{env, nullptr};
+  JLocal<jobject> topicInfo{env, nullptr};
+  JLocal<jobject> valueData{env, nullptr};
+  JLocal<jobject> logMessage{env, nullptr};
+  JLocal<jobject> timeSyncData{env, nullptr};
+  if (auto v = event.GetConnectionInfo()) {
+    connInfo = JLocal<jobject>{env, MakeJObject(env, *v)};
+  } else if (auto v = event.GetTopicInfo()) {
+    topicInfo = JLocal<jobject>{env, MakeJObject(env, inst, *v)};
+  } else if (auto v = event.GetValueEventData()) {
+    valueData = JLocal<jobject>{env, MakeJObject(env, inst, *v)};
+  } else if (auto v = event.GetLogMessage()) {
+    logMessage = JLocal<jobject>{env, MakeJObject(env, *v)};
+  } else if (auto v = event.GetTimeSyncEventData()) {
+    timeSyncData = JLocal<jobject>{env, MakeJObject(env, *v)};
+  }
   return env->NewObject(
-      rpcAnswerCls, constructor, inst, static_cast<jint>(answer.entry),
-      static_cast<jint>(answer.call), name.obj(), params.obj(), conn.obj());
+      eventCls, constructor, inst, static_cast<jint>(event.listener),
+      static_cast<jint>(event.flags), connInfo.obj(), topicInfo.obj(),
+      valueData.obj(), logMessage.obj(), timeSyncData.obj());
 }
 
-static jobjectArray MakeJObject(
-    JNIEnv* env, jobject inst,
-    wpi::span<const nt::ConnectionNotification> arr) {
-  jobjectArray jarr =
-      env->NewObjectArray(arr.size(), connectionNotificationCls, nullptr);
+static jobjectArray MakeJObject(JNIEnv* env, std::span<const nt::Value> arr) {
+  jobjectArray jarr = env->NewObjectArray(arr.size(), valueCls, nullptr);
   if (!jarr) {
     return nullptr;
   }
   for (size_t i = 0; i < arr.size(); ++i) {
-    JLocal<jobject> elem{env, MakeJObject(env, inst, arr[i])};
+    JLocal<jobject> elem{env, MakeJValue(env, arr[i])};
     env->SetObjectArrayElement(jarr, i, elem.obj());
   }
   return jarr;
 }
 
 static jobjectArray MakeJObject(JNIEnv* env, jobject inst,
-                                wpi::span<const nt::EntryNotification> arr) {
-  jobjectArray jarr =
-      env->NewObjectArray(arr.size(), entryNotificationCls, nullptr);
-  if (!jarr) {
-    return nullptr;
-  }
-  for (size_t i = 0; i < arr.size(); ++i) {
-    JLocal<jobject> elem{env, MakeJObject(env, inst, arr[i])};
-    env->SetObjectArrayElement(jarr, i, elem.obj());
-  }
-  return jarr;
-}
-
-static jobjectArray MakeJObject(JNIEnv* env, jobject inst,
-                                wpi::span<const nt::LogMessage> arr) {
-  jobjectArray jarr = env->NewObjectArray(arr.size(), logMessageCls, nullptr);
-  if (!jarr) {
-    return nullptr;
-  }
-  for (size_t i = 0; i < arr.size(); ++i) {
-    JLocal<jobject> elem{env, MakeJObject(env, inst, arr[i])};
-    env->SetObjectArrayElement(jarr, i, elem.obj());
-  }
-  return jarr;
-}
-
-static jobjectArray MakeJObject(JNIEnv* env, jobject inst,
-                                wpi::span<const nt::RpcAnswer> arr) {
-  jobjectArray jarr = env->NewObjectArray(arr.size(), rpcAnswerCls, nullptr);
+                                std::span<const nt::Event> arr) {
+  jobjectArray jarr = env->NewObjectArray(arr.size(), eventCls, nullptr);
   if (!jarr) {
     return nullptr;
   }
@@ -424,24 +426,7 @@
     nullPointerEx.Throw(env, "key cannot be null");
     return false;
   }
-  return nt::GetEntry(inst, JStringRef{env, key}.str());
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    getEntries
- * Signature: (ILjava/lang/String;I)[I
- */
-JNIEXPORT jintArray JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_getEntries
-  (JNIEnv* env, jclass, jint inst, jstring prefix, jint types)
-{
-  if (!prefix) {
-    nullPointerEx.Throw(env, "prefix cannot be null");
-    return nullptr;
-  }
-  return MakeJIntArray(
-      env, nt::GetEntries(inst, JStringRef{env, prefix}.str(), types));
+  return nt::GetEntry(inst, JStringRef{env, key});
 }
 
 /*
@@ -482,183 +467,504 @@
 
 /*
  * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    setBoolean
- * Signature: (IJZZ)Z
+ * Method:    getTopics
+ * Signature: (ILjava/lang/String;I)[I
  */
-JNIEXPORT jboolean JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_setBoolean
-  (JNIEnv*, jclass, jint entry, jlong time, jboolean value, jboolean force)
+JNIEXPORT jintArray JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getTopics
+  (JNIEnv* env, jclass, jint inst, jstring prefix, jint types)
 {
-  if (force) {
-    nt::SetEntryTypeValue(entry,
-                          nt::Value::MakeBoolean(value != JNI_FALSE, time));
-    return JNI_TRUE;
+  if (!prefix) {
+    nullPointerEx.Throw(env, "prefix cannot be null");
+    return nullptr;
   }
-  return nt::SetEntryValue(entry,
-                           nt::Value::MakeBoolean(value != JNI_FALSE, time));
+  auto arr = nt::GetTopics(inst, JStringRef{env, prefix}.str(), types);
+  return MakeJIntArray(env, arr);
 }
 
 /*
  * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    setDouble
- * Signature: (IJDZ)Z
+ * Method:    getTopicsStr
+ * Signature: (ILjava/lang/String;[Ljava/lang/Object;)[I
  */
-JNIEXPORT jboolean JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_setDouble
-  (JNIEnv*, jclass, jint entry, jlong time, jdouble value, jboolean force)
+JNIEXPORT jintArray JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getTopicsStr
+  (JNIEnv* env, jclass, jint inst, jstring prefix, jobjectArray types)
 {
-  if (force) {
-    nt::SetEntryTypeValue(entry, nt::Value::MakeDouble(value, time));
-    return JNI_TRUE;
+  if (!prefix) {
+    nullPointerEx.Throw(env, "prefix cannot be null");
+    return nullptr;
   }
-  return nt::SetEntryValue(entry, nt::Value::MakeDouble(value, time));
+  if (!types) {
+    nullPointerEx.Throw(env, "types cannot be null");
+    return nullptr;
+  }
+
+  int len = env->GetArrayLength(types);
+  std::vector<std::string> typeStrData;
+  std::vector<std::string_view> typeStrs;
+  typeStrs.reserve(len);
+  for (int i = 0; i < len; ++i) {
+    JLocal<jstring> elem{
+        env, static_cast<jstring>(env->GetObjectArrayElement(types, i))};
+    if (!elem) {
+      nullPointerEx.Throw(env, "null string in types");
+      return nullptr;
+    }
+    typeStrData.emplace_back(JStringRef{env, elem}.str());
+    typeStrs.emplace_back(typeStrData.back());
+  }
+
+  auto arr = nt::GetTopics(inst, JStringRef{env, prefix}.str(), typeStrs);
+  return MakeJIntArray(env, arr);
 }
 
 /*
  * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    setString
- * Signature: (IJLjava/lang/String;Z)Z
+ * Method:    getTopicInfos
+ * Signature: (Ljava/lang/Object;ILjava/lang/String;I)[Ljava/lang/Object;
  */
-JNIEXPORT jboolean JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_setString
-  (JNIEnv* env, jclass, jint entry, jlong time, jstring value, jboolean force)
+JNIEXPORT jobjectArray JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getTopicInfos
+  (JNIEnv* env, jclass, jobject instObject, jint inst, jstring prefix,
+   jint types)
 {
-  if (!value) {
-    nullPointerEx.Throw(env, "value cannot be null");
-    return false;
+  if (!prefix) {
+    nullPointerEx.Throw(env, "prefix cannot be null");
+    return nullptr;
   }
-  if (force) {
-    nt::SetEntryTypeValue(
-        entry, nt::Value::MakeString(JStringRef{env, value}.str(), time));
-    return JNI_TRUE;
+  auto arr = nt::GetTopicInfo(inst, JStringRef{env, prefix}.str(), types);
+  jobjectArray jarr = env->NewObjectArray(arr.size(), topicInfoCls, nullptr);
+  if (!jarr) {
+    return nullptr;
   }
-  return nt::SetEntryValue(
-      entry, nt::Value::MakeString(JStringRef{env, value}.str(), time));
+  for (size_t i = 0; i < arr.size(); ++i) {
+    JLocal<jobject> jelem{env, MakeJObject(env, instObject, arr[i])};
+    env->SetObjectArrayElement(jarr, i, jelem);
+  }
+  return jarr;
 }
 
 /*
  * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    setRaw
- * Signature: (IJ[BZ)Z
+ * Method:    getTopicInfosStr
+ * Signature: (Ljava/lang/Object;ILjava/lang/String;[Ljava/lang/Object;)[Ljava/lang/Object;
  */
-JNIEXPORT jboolean JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_setRaw__IJ_3BZ
-  (JNIEnv* env, jclass, jint entry, jlong time, jbyteArray value,
-   jboolean force)
+JNIEXPORT jobjectArray JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getTopicInfosStr
+  (JNIEnv* env, jclass, jobject instObject, jint inst, jstring prefix,
+   jobjectArray types)
 {
-  if (!value) {
-    nullPointerEx.Throw(env, "value cannot be null");
-    return false;
+  if (!prefix) {
+    nullPointerEx.Throw(env, "prefix cannot be null");
+    return nullptr;
   }
-  auto v = FromJavaRaw(env, value, time);
-  if (!v) {
-    return false;
+  if (!types) {
+    nullPointerEx.Throw(env, "types cannot be null");
+    return nullptr;
   }
-  if (force) {
-    nt::SetEntryTypeValue(entry, v);
-    return JNI_TRUE;
+
+  int len = env->GetArrayLength(types);
+  std::vector<std::string> typeStrData;
+  std::vector<std::string_view> typeStrs;
+  typeStrs.reserve(len);
+  for (int i = 0; i < len; ++i) {
+    JLocal<jstring> elem{
+        env, static_cast<jstring>(env->GetObjectArrayElement(types, i))};
+    if (!elem) {
+      nullPointerEx.Throw(env, "null string in types");
+      return nullptr;
+    }
+    typeStrData.emplace_back(JStringRef{env, elem}.str());
+    typeStrs.emplace_back(typeStrData.back());
   }
-  return nt::SetEntryValue(entry, v);
+
+  auto arr = nt::GetTopicInfo(inst, JStringRef{env, prefix}.str(), typeStrs);
+  jobjectArray jarr = env->NewObjectArray(arr.size(), topicInfoCls, nullptr);
+  if (!jarr) {
+    return nullptr;
+  }
+  for (size_t i = 0; i < arr.size(); ++i) {
+    JLocal<jobject> jelem{env, MakeJObject(env, instObject, arr[i])};
+    env->SetObjectArrayElement(jarr, i, jelem);
+  }
+  return jarr;
 }
 
 /*
  * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    setRaw
- * Signature: (IJLjava/lang/Object;IZ)Z
+ * Method:    getTopic
+ * Signature: (ILjava/lang/String;)I
  */
-JNIEXPORT jboolean JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_setRaw__IJLjava_nio_ByteBuffer_2IZ
-  (JNIEnv* env, jclass, jint entry, jlong time, jobject value, jint len,
-   jboolean force)
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getTopic
+  (JNIEnv* env, jclass, jint inst, jstring name)
 {
-  if (!value) {
-    nullPointerEx.Throw(env, "value cannot be null");
-    return false;
-  }
-  auto v = FromJavaRawBB(env, value, len, time);
-  if (!v) {
-    return false;
-  }
-  if (force) {
-    nt::SetEntryTypeValue(entry, v);
-    return JNI_TRUE;
-  }
-  return nt::SetEntryValue(entry, v);
+  return nt::GetTopic(inst, JStringRef{env, name});
 }
 
 /*
  * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    setBooleanArray
- * Signature: (IJ[ZZ)Z
+ * Method:    getTopicName
+ * Signature: (I)Ljava/lang/String;
  */
-JNIEXPORT jboolean JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_setBooleanArray
-  (JNIEnv* env, jclass, jint entry, jlong time, jbooleanArray value,
-   jboolean force)
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getTopicName
+  (JNIEnv* env, jclass, jint topic)
 {
-  if (!value) {
-    nullPointerEx.Throw(env, "value cannot be null");
-    return false;
-  }
-  auto v = FromJavaBooleanArray(env, value, time);
-  if (!v) {
-    return false;
-  }
-  if (force) {
-    nt::SetEntryTypeValue(entry, v);
-    return JNI_TRUE;
-  }
-  return nt::SetEntryValue(entry, v);
+  return MakeJString(env, nt::GetTopicName(topic));
 }
 
 /*
  * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    setDoubleArray
- * Signature: (IJ[DZ)Z
+ * Method:    getTopicType
+ * Signature: (I)I
  */
-JNIEXPORT jboolean JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_setDoubleArray
-  (JNIEnv* env, jclass, jint entry, jlong time, jdoubleArray value,
-   jboolean force)
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getTopicType
+  (JNIEnv*, jclass, jint topic)
 {
-  if (!value) {
-    nullPointerEx.Throw(env, "value cannot be null");
-    return false;
-  }
-  auto v = FromJavaDoubleArray(env, value, time);
-  if (!v) {
-    return false;
-  }
-  if (force) {
-    nt::SetEntryTypeValue(entry, v);
-    return JNI_TRUE;
-  }
-  return nt::SetEntryValue(entry, v);
+  return nt::GetTopicType(topic);
 }
 
 /*
  * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    setStringArray
- * Signature: (IJ[Ljava/lang/Object;Z)Z
+ * Method:    setTopicPersistent
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_setTopicPersistent
+  (JNIEnv*, jclass, jint topic, jboolean value)
+{
+  nt::SetTopicPersistent(topic, value);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    getTopicPersistent
+ * Signature: (I)Z
  */
 JNIEXPORT jboolean JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_setStringArray
-  (JNIEnv* env, jclass, jint entry, jlong time, jobjectArray value,
-   jboolean force)
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getTopicPersistent
+  (JNIEnv*, jclass, jint topic)
 {
-  if (!value) {
-    nullPointerEx.Throw(env, "value cannot be null");
-    return false;
+  return nt::GetTopicPersistent(topic);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    setTopicRetained
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_setTopicRetained
+  (JNIEnv*, jclass, jint topic, jboolean value)
+{
+  nt::SetTopicRetained(topic, value);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    getTopicRetained
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getTopicRetained
+  (JNIEnv*, jclass, jint topic)
+{
+  return nt::GetTopicRetained(topic);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    getTopicTypeString
+ * Signature: (I)Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getTopicTypeString
+  (JNIEnv* env, jclass, jint topic)
+{
+  return MakeJString(env, nt::GetTopicTypeString(topic));
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    getTopicExists
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getTopicExists
+  (JNIEnv*, jclass, jint topic)
+{
+  return nt::GetTopicExists(topic);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    getTopicProperty
+ * Signature: (ILjava/lang/String;)Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getTopicProperty
+  (JNIEnv* env, jclass, jint topic, jstring name)
+{
+  return MakeJString(env,
+                     nt::GetTopicProperty(topic, JStringRef{env, name}).dump());
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    setTopicProperty
+ * Signature: (ILjava/lang/String;Ljava/lang/String;)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_setTopicProperty
+  (JNIEnv* env, jclass, jint topic, jstring name, jstring value)
+{
+  wpi::json j;
+  try {
+    j = wpi::json::parse(JStringRef{env, value});
+  } catch (wpi::json::parse_error& err) {
+    illegalArgEx.Throw(
+        env, fmt::format("could not parse value JSON: {}", err.what()));
+    return;
   }
-  auto v = FromJavaStringArray(env, value, time);
-  if (!v) {
-    return false;
+  nt::SetTopicProperty(topic, JStringRef{env, name}, j);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    deleteTopicProperty
+ * Signature: (ILjava/lang/String;)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_deleteTopicProperty
+  (JNIEnv* env, jclass, jint topic, jstring name)
+{
+  nt::DeleteTopicProperty(topic, JStringRef{env, name});
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    getTopicProperties
+ * Signature: (I)Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getTopicProperties
+  (JNIEnv* env, jclass, jint topic)
+{
+  return MakeJString(env, nt::GetTopicProperties(topic).dump());
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    setTopicProperties
+ * Signature: (ILjava/lang/String;)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_setTopicProperties
+  (JNIEnv* env, jclass, jint topic, jstring properties)
+{
+  wpi::json j;
+  try {
+    j = wpi::json::parse(JStringRef{env, properties});
+  } catch (wpi::json::parse_error& err) {
+    illegalArgEx.Throw(
+        env, fmt::format("could not parse properties JSON: {}", err.what()));
+    return;
   }
-  if (force) {
-    nt::SetEntryTypeValue(entry, v);
-    return JNI_TRUE;
+  if (!j.is_object()) {
+    illegalArgEx.Throw(env, "properties is not a JSON object");
+    return;
   }
-  return nt::SetEntryValue(entry, v);
+  nt::SetTopicProperties(topic, j);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    subscribe
+ * Signature: (IILjava/lang/String;Ljava/lang/Object;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_subscribe
+  (JNIEnv* env, jclass, jint topic, jint type, jstring typeStr, jobject options)
+{
+  return nt::Subscribe(topic, static_cast<NT_Type>(type),
+                       JStringRef{env, typeStr},
+                       FromJavaPubSubOptions(env, options));
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    unsubscribe
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_unsubscribe
+  (JNIEnv*, jclass, jint sub)
+{
+  nt::Unsubscribe(sub);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    publish
+ * Signature: (IILjava/lang/String;Ljava/lang/Object;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_publish
+  (JNIEnv* env, jclass, jint topic, jint type, jstring typeStr, jobject options)
+{
+  return nt::Publish(topic, static_cast<NT_Type>(type),
+                     JStringRef{env, typeStr},
+                     FromJavaPubSubOptions(env, options));
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    publishEx
+ * Signature: (IILjava/lang/String;Ljava/lang/String;Ljava/lang/Object;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_publishEx
+  (JNIEnv* env, jclass, jint topic, jint type, jstring typeStr,
+   jstring properties, jobject options)
+{
+  wpi::json j;
+  try {
+    j = wpi::json::parse(JStringRef{env, properties});
+  } catch (wpi::json::parse_error& err) {
+    illegalArgEx.Throw(
+        env, fmt::format("could not parse properties JSON: {}", err.what()));
+    return 0;
+  }
+  if (!j.is_object()) {
+    illegalArgEx.Throw(env, "properties is not a JSON object");
+    return 0;
+  }
+  return nt::PublishEx(topic, static_cast<NT_Type>(type),
+                       JStringRef{env, typeStr}, j,
+                       FromJavaPubSubOptions(env, options));
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    unpublish
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_unpublish
+  (JNIEnv*, jclass, jint pubentry)
+{
+  nt::Unpublish(pubentry);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    getEntryImpl
+ * Signature: (IILjava/lang/String;Ljava/lang/Object;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getEntryImpl
+  (JNIEnv* env, jclass, jint topic, jint type, jstring typeStr, jobject options)
+{
+  return nt::GetEntry(topic, static_cast<NT_Type>(type),
+                      JStringRef{env, typeStr},
+                      FromJavaPubSubOptions(env, options));
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    releaseEntry
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_releaseEntry
+  (JNIEnv*, jclass, jint entry)
+{
+  nt::ReleaseEntry(entry);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    release
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_release
+  (JNIEnv*, jclass, jint pubsubentry)
+{
+  nt::Release(pubsubentry);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    getTopicFromHandle
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getTopicFromHandle
+  (JNIEnv*, jclass, jint pubsubentry)
+{
+  return nt::GetTopicFromHandle(pubsubentry);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    subscribeMultiple
+ * Signature: (I[Ljava/lang/Object;Ljava/lang/Object;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_subscribeMultiple
+  (JNIEnv* env, jclass, jint inst, jobjectArray prefixes, jobject options)
+{
+  if (!prefixes) {
+    nullPointerEx.Throw(env, "prefixes cannot be null");
+    return {};
+  }
+  int len = env->GetArrayLength(prefixes);
+
+  std::vector<std::string> prefixStrings;
+  std::vector<std::string_view> prefixStringViews;
+  prefixStrings.reserve(len);
+  prefixStringViews.reserve(len);
+  for (int i = 0; i < len; ++i) {
+    JLocal<jstring> elem{
+        env, static_cast<jstring>(env->GetObjectArrayElement(prefixes, i))};
+    if (!elem) {
+      nullPointerEx.Throw(env, "null string in prefixes");
+      return {};
+    }
+    prefixStrings.emplace_back(JStringRef{env, elem}.str());
+    prefixStringViews.emplace_back(prefixStrings.back());
+  }
+
+  return nt::SubscribeMultiple(inst, prefixStringViews,
+                               FromJavaPubSubOptions(env, options));
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    unsubscribeMultiple
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_unsubscribeMultiple
+  (JNIEnv*, jclass, jint sub)
+{
+  nt::UnsubscribeMultiple(sub);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    readQueueValue
+ * Signature: (I)[Ljava/lang/Object;
+ */
+JNIEXPORT jobjectArray JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_readQueueValue
+  (JNIEnv* env, jclass, jint subentry)
+{
+  return MakeJObject(env, nt::ReadQueueValue(subentry));
 }
 
 /*
@@ -670,231 +976,7 @@
 Java_edu_wpi_first_networktables_NetworkTablesJNI_getValue
   (JNIEnv* env, jclass, jint entry)
 {
-  auto val = nt::GetEntryValue(entry);
-  return MakeJValue(env, val.get());
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    getBoolean
- * Signature: (IZ)Z
- */
-JNIEXPORT jboolean JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_getBoolean
-  (JNIEnv*, jclass, jint entry, jboolean defaultValue)
-{
-  auto val = nt::GetEntryValue(entry);
-  if (!val || !val->IsBoolean()) {
-    return defaultValue;
-  }
-  return val->GetBoolean();
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    getDouble
- * Signature: (ID)D
- */
-JNIEXPORT jdouble JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_getDouble
-  (JNIEnv*, jclass, jint entry, jdouble defaultValue)
-{
-  auto val = nt::GetEntryValue(entry);
-  if (!val || !val->IsDouble()) {
-    return defaultValue;
-  }
-  return val->GetDouble();
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    getString
- * Signature: (ILjava/lang/String;)Ljava/lang/String;
- */
-JNIEXPORT jstring JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_getString
-  (JNIEnv* env, jclass, jint entry, jstring defaultValue)
-{
-  auto val = nt::GetEntryValue(entry);
-  if (!val || !val->IsString()) {
-    return defaultValue;
-  }
-  return MakeJString(env, val->GetString());
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    getRaw
- * Signature: (I[B)[B
- */
-JNIEXPORT jbyteArray JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_getRaw
-  (JNIEnv* env, jclass, jint entry, jbyteArray defaultValue)
-{
-  auto val = nt::GetEntryValue(entry);
-  if (!val || !val->IsRaw()) {
-    return defaultValue;
-  }
-  return MakeJByteArray(env, val->GetRaw());
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    getBooleanArray
- * Signature: (I[Z)[Z
- */
-JNIEXPORT jbooleanArray JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_getBooleanArray
-  (JNIEnv* env, jclass, jint entry, jbooleanArray defaultValue)
-{
-  auto val = nt::GetEntryValue(entry);
-  if (!val || !val->IsBooleanArray()) {
-    return defaultValue;
-  }
-  return MakeJBooleanArray(env, val->GetBooleanArray());
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    getDoubleArray
- * Signature: (I[D)[D
- */
-JNIEXPORT jdoubleArray JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_getDoubleArray
-  (JNIEnv* env, jclass, jint entry, jdoubleArray defaultValue)
-{
-  auto val = nt::GetEntryValue(entry);
-  if (!val || !val->IsDoubleArray()) {
-    return defaultValue;
-  }
-  return MakeJDoubleArray(env, val->GetDoubleArray());
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    getStringArray
- * Signature: (I[Ljava/lang/Object;)[Ljava/lang/Object;
- */
-JNIEXPORT jobjectArray JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_getStringArray
-  (JNIEnv* env, jclass, jint entry, jobjectArray defaultValue)
-{
-  auto val = nt::GetEntryValue(entry);
-  if (!val || !val->IsStringArray()) {
-    return defaultValue;
-  }
-  return MakeJStringArray(env, val->GetStringArray());
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    setDefaultBoolean
- * Signature: (IJZ)Z
- */
-JNIEXPORT jboolean JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_setDefaultBoolean
-  (JNIEnv*, jclass, jint entry, jlong time, jboolean defaultValue)
-{
-  return nt::SetDefaultEntryValue(
-      entry, nt::Value::MakeBoolean(defaultValue != JNI_FALSE, time));
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    setDefaultDouble
- * Signature: (IJD)Z
- */
-JNIEXPORT jboolean JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_setDefaultDouble
-  (JNIEnv*, jclass, jint entry, jlong time, jdouble defaultValue)
-{
-  return nt::SetDefaultEntryValue(entry,
-                                  nt::Value::MakeDouble(defaultValue, time));
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    setDefaultString
- * Signature: (IJLjava/lang/String;)Z
- */
-JNIEXPORT jboolean JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_setDefaultString
-  (JNIEnv* env, jclass, jint entry, jlong time, jstring defaultValue)
-{
-  if (!defaultValue) {
-    nullPointerEx.Throw(env, "defaultValue cannot be null");
-    return false;
-  }
-  return nt::SetDefaultEntryValue(
-      entry, nt::Value::MakeString(JStringRef{env, defaultValue}.str(), time));
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    setDefaultRaw
- * Signature: (IJ[B)Z
- */
-JNIEXPORT jboolean JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_setDefaultRaw
-  (JNIEnv* env, jclass, jint entry, jlong time, jbyteArray defaultValue)
-{
-  if (!defaultValue) {
-    nullPointerEx.Throw(env, "defaultValue cannot be null");
-    return false;
-  }
-  auto v = FromJavaRaw(env, defaultValue, time);
-  return nt::SetDefaultEntryValue(entry, v);
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    setDefaultBooleanArray
- * Signature: (IJ[Z)Z
- */
-JNIEXPORT jboolean JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_setDefaultBooleanArray
-  (JNIEnv* env, jclass, jint entry, jlong time, jbooleanArray defaultValue)
-{
-  if (!defaultValue) {
-    nullPointerEx.Throw(env, "defaultValue cannot be null");
-    return false;
-  }
-  auto v = FromJavaBooleanArray(env, defaultValue, time);
-  return nt::SetDefaultEntryValue(entry, v);
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    setDefaultDoubleArray
- * Signature: (IJ[D)Z
- */
-JNIEXPORT jboolean JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_setDefaultDoubleArray
-  (JNIEnv* env, jclass, jint entry, jlong time, jdoubleArray defaultValue)
-{
-  if (!defaultValue) {
-    nullPointerEx.Throw(env, "defaultValue cannot be null");
-    return false;
-  }
-  auto v = FromJavaDoubleArray(env, defaultValue, time);
-  return nt::SetDefaultEntryValue(entry, v);
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    setDefaultStringArray
- * Signature: (IJ[Ljava/lang/Object;)Z
- */
-JNIEXPORT jboolean JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_setDefaultStringArray
-  (JNIEnv* env, jclass, jint entry, jlong time, jobjectArray defaultValue)
-{
-  if (!defaultValue) {
-    nullPointerEx.Throw(env, "defaultValue cannot be null");
-    return false;
-  }
-  auto v = FromJavaStringArray(env, defaultValue, time);
-  return nt::SetDefaultEntryValue(entry, v);
+  return MakeJValue(env, nt::GetEntryValue(entry));
 }
 
 /*
@@ -923,503 +1005,108 @@
 
 /*
  * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    deleteEntry
- * Signature: (I)V
- */
-JNIEXPORT void JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_deleteEntry
-  (JNIEnv*, jclass, jint entry)
-{
-  nt::DeleteEntry(entry);
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    deleteAllEntries
- * Signature: (I)V
- */
-JNIEXPORT void JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_deleteAllEntries
-  (JNIEnv*, jclass, jint inst)
-{
-  nt::DeleteAllEntries(inst);
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    getEntryInfoHandle
+ * Method:    getTopicInfo
  * Signature: (Ljava/lang/Object;I)Ljava/lang/Object;
  */
 JNIEXPORT jobject JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_getEntryInfoHandle
-  (JNIEnv* env, jclass, jobject inst, jint entry)
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getTopicInfo
+  (JNIEnv* env, jclass, jobject inst, jint topic)
 {
-  return MakeJObject(env, inst, nt::GetEntryInfo(entry));
+  return MakeJObject(env, inst, nt::GetTopicInfo(topic));
 }
 
 /*
  * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    getEntryInfo
- * Signature: (Ljava/lang/Object;ILjava/lang/String;I)[Ljava/lang/Object;
- */
-JNIEXPORT jobjectArray JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_getEntryInfo
-  (JNIEnv* env, jclass, jobject instObject, jint inst, jstring prefix,
-   jint types)
-{
-  if (!prefix) {
-    nullPointerEx.Throw(env, "prefix cannot be null");
-    return nullptr;
-  }
-  auto arr = nt::GetEntryInfo(inst, JStringRef{env, prefix}.str(), types);
-  jobjectArray jarr = env->NewObjectArray(arr.size(), entryInfoCls, nullptr);
-  if (!jarr) {
-    return nullptr;
-  }
-  for (size_t i = 0; i < arr.size(); ++i) {
-    JLocal<jobject> jelem{env, MakeJObject(env, instObject, arr[i])};
-    env->SetObjectArrayElement(jarr, i, jelem);
-  }
-  return jarr;
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    createEntryListenerPoller
+ * Method:    createListenerPoller
  * Signature: (I)I
  */
 JNIEXPORT jint JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_createEntryListenerPoller
+Java_edu_wpi_first_networktables_NetworkTablesJNI_createListenerPoller
   (JNIEnv*, jclass, jint inst)
 {
-  return nt::CreateEntryListenerPoller(inst);
+  return nt::CreateListenerPoller(inst);
 }
 
 /*
  * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    destroyEntryListenerPoller
+ * Method:    destroyListenerPoller
  * Signature: (I)V
  */
 JNIEXPORT void JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_destroyEntryListenerPoller
+Java_edu_wpi_first_networktables_NetworkTablesJNI_destroyListenerPoller
   (JNIEnv*, jclass, jint poller)
 {
-  nt::DestroyEntryListenerPoller(poller);
+  nt::DestroyListenerPoller(poller);
 }
 
 /*
  * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    addPolledEntryListener
- * Signature: (ILjava/lang/String;I)I
+ * Method:    addListener
+ * Signature: (I[Ljava/lang/Object;I)I
  */
 JNIEXPORT jint JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_addPolledEntryListener__ILjava_lang_String_2I
-  (JNIEnv* env, jclass, jint poller, jstring prefix, jint flags)
+Java_edu_wpi_first_networktables_NetworkTablesJNI_addListener__I_3Ljava_lang_String_2I
+  (JNIEnv* env, jclass, jint poller, jobjectArray prefixes, jint flags)
 {
-  if (!prefix) {
-    nullPointerEx.Throw(env, "prefix cannot be null");
+  if (!prefixes) {
+    nullPointerEx.Throw(env, "prefixes cannot be null");
     return 0;
   }
-  return nt::AddPolledEntryListener(poller, JStringRef{env, prefix}.str(),
-                                    flags);
+
+  size_t len = env->GetArrayLength(prefixes);
+  std::vector<std::string> arr;
+  std::vector<std::string_view> arrview;
+  arr.reserve(len);
+  arrview.reserve(len);
+  for (size_t i = 0; i < len; ++i) {
+    JLocal<jstring> elem{
+        env, static_cast<jstring>(env->GetObjectArrayElement(prefixes, i))};
+    if (!elem) {
+      nullPointerEx.Throw(env, "prefixes cannot contain null");
+      return 0;
+    }
+    arr.emplace_back(JStringRef{env, elem}.str());
+    // this is safe because of the reserve (so arr elements won't move)
+    arrview.emplace_back(arr.back());
+  }
+
+  return nt::AddPolledListener(poller, arrview, flags);
 }
 
 /*
  * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    addPolledEntryListener
+ * Method:    addListener
  * Signature: (III)I
  */
 JNIEXPORT jint JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_addPolledEntryListener__III
-  (JNIEnv* env, jclass, jint poller, jint entry, jint flags)
+Java_edu_wpi_first_networktables_NetworkTablesJNI_addListener__III
+  (JNIEnv* env, jclass, jint poller, jint handle, jint flags)
 {
-  return nt::AddPolledEntryListener(poller, entry, flags);
+  return nt::AddPolledListener(poller, handle, flags);
 }
 
 /*
  * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    pollEntryListener
+ * Method:    readListenerQueue
  * Signature: (Ljava/lang/Object;I)[Ljava/lang/Object;
  */
 JNIEXPORT jobjectArray JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_pollEntryListener
+Java_edu_wpi_first_networktables_NetworkTablesJNI_readListenerQueue
   (JNIEnv* env, jclass, jobject inst, jint poller)
 {
-  auto events = nt::PollEntryListener(poller);
-  if (events.empty()) {
-    interruptedEx.Throw(env, "PollEntryListener interrupted");
-    return nullptr;
-  }
-  return MakeJObject(env, inst, events);
+  return MakeJObject(env, inst, nt::ReadListenerQueue(poller));
 }
 
 /*
  * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    pollEntryListenerTimeout
- * Signature: (Ljava/lang/Object;ID)[Ljava/lang/Object;
- */
-JNIEXPORT jobjectArray JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_pollEntryListenerTimeout
-  (JNIEnv* env, jclass, jobject inst, jint poller, jdouble timeout)
-{
-  bool timed_out = false;
-  auto events = nt::PollEntryListener(poller, timeout, &timed_out);
-  if (events.empty() && !timed_out) {
-    interruptedEx.Throw(env, "PollEntryListener interrupted");
-    return nullptr;
-  }
-  return MakeJObject(env, inst, events);
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    cancelPollEntryListener
+ * Method:    removeListener
  * Signature: (I)V
  */
 JNIEXPORT void JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_cancelPollEntryListener
-  (JNIEnv*, jclass, jint poller)
+Java_edu_wpi_first_networktables_NetworkTablesJNI_removeListener
+  (JNIEnv*, jclass, jint topicListener)
 {
-  nt::CancelPollEntryListener(poller);
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    removeEntryListener
- * Signature: (I)V
- */
-JNIEXPORT void JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_removeEntryListener
-  (JNIEnv*, jclass, jint entryListenerUid)
-{
-  nt::RemoveEntryListener(entryListenerUid);
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    waitForEntryListenerQueue
- * Signature: (ID)Z
- */
-JNIEXPORT jboolean JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_waitForEntryListenerQueue
-  (JNIEnv*, jclass, jint inst, jdouble timeout)
-{
-  return nt::WaitForEntryListenerQueue(inst, timeout);
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    createConnectionListenerPoller
- * Signature: (I)I
- */
-JNIEXPORT jint JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_createConnectionListenerPoller
-  (JNIEnv*, jclass, jint inst)
-{
-  return nt::CreateConnectionListenerPoller(inst);
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    destroyConnectionListenerPoller
- * Signature: (I)V
- */
-JNIEXPORT void JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_destroyConnectionListenerPoller
-  (JNIEnv*, jclass, jint poller)
-{
-  nt::DestroyConnectionListenerPoller(poller);
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    addPolledConnectionListener
- * Signature: (IZ)I
- */
-JNIEXPORT jint JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_addPolledConnectionListener
-  (JNIEnv* env, jclass, jint poller, jboolean immediateNotify)
-{
-  return nt::AddPolledConnectionListener(poller, immediateNotify);
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    pollConnectionListener
- * Signature: (Ljava/lang/Object;I)[Ljava/lang/Object;
- */
-JNIEXPORT jobjectArray JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_pollConnectionListener
-  (JNIEnv* env, jclass, jobject inst, jint poller)
-{
-  auto events = nt::PollConnectionListener(poller);
-  if (events.empty()) {
-    interruptedEx.Throw(env, "PollConnectionListener interrupted");
-    return nullptr;
-  }
-  return MakeJObject(env, inst, events);
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    pollConnectionListenerTimeout
- * Signature: (Ljava/lang/Object;ID)[Ljava/lang/Object;
- */
-JNIEXPORT jobjectArray JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_pollConnectionListenerTimeout
-  (JNIEnv* env, jclass, jobject inst, jint poller, jdouble timeout)
-{
-  bool timed_out = false;
-  auto events = nt::PollConnectionListener(poller, timeout, &timed_out);
-  if (events.empty() && !timed_out) {
-    interruptedEx.Throw(env, "PollConnectionListener interrupted");
-    return nullptr;
-  }
-  return MakeJObject(env, inst, events);
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    cancelPollConnectionListener
- * Signature: (I)V
- */
-JNIEXPORT void JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_cancelPollConnectionListener
-  (JNIEnv*, jclass, jint poller)
-{
-  nt::CancelPollConnectionListener(poller);
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    removeConnectionListener
- * Signature: (I)V
- */
-JNIEXPORT void JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_removeConnectionListener
-  (JNIEnv*, jclass, jint connListenerUid)
-{
-  nt::RemoveConnectionListener(connListenerUid);
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    waitForConnectionListenerQueue
- * Signature: (ID)Z
- */
-JNIEXPORT jboolean JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_waitForConnectionListenerQueue
-  (JNIEnv*, jclass, jint inst, jdouble timeout)
-{
-  return nt::WaitForConnectionListenerQueue(inst, timeout);
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    createRpcCallPoller
- * Signature: (I)I
- */
-JNIEXPORT jint JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_createRpcCallPoller
-  (JNIEnv*, jclass, jint inst)
-{
-  return nt::CreateRpcCallPoller(inst);
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    destroyRpcCallPoller
- * Signature: (I)V
- */
-JNIEXPORT void JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_destroyRpcCallPoller
-  (JNIEnv*, jclass, jint poller)
-{
-  nt::DestroyRpcCallPoller(poller);
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    createPolledRpc
- * Signature: (I[BI)V
- */
-JNIEXPORT void JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_createPolledRpc
-  (JNIEnv* env, jclass, jint entry, jbyteArray def, jint poller)
-{
-  if (!def) {
-    nullPointerEx.Throw(env, "def cannot be null");
-    return;
-  }
-  nt::CreatePolledRpc(entry, JByteArrayRef{env, def}.str(), poller);
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    pollRpc
- * Signature: (Ljava/lang/Object;I)[Ljava/lang/Object;
- */
-JNIEXPORT jobjectArray JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_pollRpc
-  (JNIEnv* env, jclass, jobject inst, jint poller)
-{
-  auto infos = nt::PollRpc(poller);
-  if (infos.empty()) {
-    interruptedEx.Throw(env, "PollRpc interrupted");
-    return nullptr;
-  }
-  return MakeJObject(env, inst, infos);
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    pollRpcTimeout
- * Signature: (Ljava/lang/Object;ID)[Ljava/lang/Object;
- */
-JNIEXPORT jobjectArray JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_pollRpcTimeout
-  (JNIEnv* env, jclass, jobject inst, jint poller, jdouble timeout)
-{
-  bool timed_out = false;
-  auto infos = nt::PollRpc(poller, timeout, &timed_out);
-  if (infos.empty() && !timed_out) {
-    interruptedEx.Throw(env, "PollRpc interrupted");
-    return nullptr;
-  }
-  return MakeJObject(env, inst, infos);
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    cancelPollRpc
- * Signature: (I)V
- */
-JNIEXPORT void JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_cancelPollRpc
-  (JNIEnv*, jclass, jint poller)
-{
-  nt::CancelPollRpc(poller);
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    waitForRpcCallQueue
- * Signature: (ID)Z
- */
-JNIEXPORT jboolean JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_waitForRpcCallQueue
-  (JNIEnv*, jclass, jint inst, jdouble timeout)
-{
-  return nt::WaitForRpcCallQueue(inst, timeout);
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    postRpcResponse
- * Signature: (II[B)Z
- */
-JNIEXPORT jboolean JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_postRpcResponse
-  (JNIEnv* env, jclass, jint entry, jint call, jbyteArray result)
-{
-  if (!result) {
-    nullPointerEx.Throw(env, "result cannot be null");
-    return false;
-  }
-  return nt::PostRpcResponse(entry, call, JByteArrayRef{env, result}.str());
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    callRpc
- * Signature: (I[B)I
- */
-JNIEXPORT jint JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_callRpc
-  (JNIEnv* env, jclass, jint entry, jbyteArray params)
-{
-  if (!params) {
-    nullPointerEx.Throw(env, "params cannot be null");
-    return 0;
-  }
-  return nt::CallRpc(entry, JByteArrayRef{env, params}.str());
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    getRpcResult
- * Signature: (II)[B
- */
-JNIEXPORT jbyteArray JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_getRpcResult__II
-  (JNIEnv* env, jclass, jint entry, jint call)
-{
-  std::string result;
-  if (!nt::GetRpcResult(entry, call, &result)) {
-    return nullptr;
-  }
-  return MakeJByteArray(env, result);
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    getRpcResult
- * Signature: (IID)[B
- */
-JNIEXPORT jbyteArray JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_getRpcResult__IID
-  (JNIEnv* env, jclass, jint entry, jint call, jdouble timeout)
-{
-  std::string result;
-  bool timed_out = false;
-  if (!nt::GetRpcResult(entry, call, &result, timeout, &timed_out)) {
-    return nullptr;
-  }
-  return MakeJByteArray(env, result);
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    cancelRpcResult
- * Signature: (II)V
- */
-JNIEXPORT void JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_cancelRpcResult
-  (JNIEnv*, jclass, jint entry, jint call)
-{
-  nt::CancelRpcResult(entry, call);
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    getRpc
- * Signature: (I[B)[B
- */
-JNIEXPORT jbyteArray JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_getRpc
-  (JNIEnv* env, jclass, jint entry, jbyteArray defaultValue)
-{
-  auto val = nt::GetEntryValue(entry);
-  if (!val || !val->IsRpc()) {
-    return defaultValue;
-  }
-  return MakeJByteArray(env, val->GetRpc());
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    setNetworkIdentity
- * Signature: (ILjava/lang/String;)V
- */
-JNIEXPORT void JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_setNetworkIdentity
-  (JNIEnv* env, jclass, jint inst, jstring name)
-{
-  if (!name) {
-    nullPointerEx.Throw(env, "name cannot be null");
-    return;
-  }
-  nt::SetNetworkIdentity(inst, JStringRef{env, name}.str());
+  nt::RemoveListener(topicListener);
 }
 
 /*
@@ -1461,12 +1148,12 @@
 /*
  * Class:     edu_wpi_first_networktables_NetworkTablesJNI
  * Method:    startServer
- * Signature: (ILjava/lang/String;Ljava/lang/String;I)V
+ * Signature: (ILjava/lang/String;Ljava/lang/String;II)V
  */
 JNIEXPORT void JNICALL
 Java_edu_wpi_first_networktables_NetworkTablesJNI_startServer
   (JNIEnv* env, jclass, jint inst, jstring persistFilename,
-   jstring listenAddress, jint port)
+   jstring listenAddress, jint port3, jint port4)
 {
   if (!persistFilename) {
     nullPointerEx.Throw(env, "persistFilename cannot be null");
@@ -1477,7 +1164,7 @@
     return;
   }
   nt::StartServer(inst, JStringRef{env, persistFilename}.str(),
-                  JStringRef{env, listenAddress}.c_str(), port);
+                  JStringRef{env, listenAddress}.c_str(), port3, port4);
 }
 
 /*
@@ -1494,89 +1181,34 @@
 
 /*
  * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    startClient
- * Signature: (I)V
+ * Method:    startClient3
+ * Signature: (ILjava/lang/String;)V
  */
 JNIEXPORT void JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_startClient__I
-  (JNIEnv*, jclass, jint inst)
+Java_edu_wpi_first_networktables_NetworkTablesJNI_startClient3
+  (JNIEnv* env, jclass, jint inst, jstring identity)
 {
-  nt::StartClient(inst);
+  if (!identity) {
+    nullPointerEx.Throw(env, "identity cannot be null");
+    return;
+  }
+  nt::StartClient3(inst, JStringRef{env, identity}.str());
 }
 
 /*
  * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    startClient
- * Signature: (ILjava/lang/String;I)V
+ * Method:    startClient4
+ * Signature: (ILjava/lang/String;)V
  */
 JNIEXPORT void JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_startClient__ILjava_lang_String_2I
-  (JNIEnv* env, jclass, jint inst, jstring serverName, jint port)
+Java_edu_wpi_first_networktables_NetworkTablesJNI_startClient4
+  (JNIEnv* env, jclass, jint inst, jstring identity)
 {
-  if (!serverName) {
-    nullPointerEx.Throw(env, "serverName cannot be null");
+  if (!identity) {
+    nullPointerEx.Throw(env, "identity cannot be null");
     return;
   }
-  nt::StartClient(inst, JStringRef{env, serverName}.c_str(), port);
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    startClient
- * Signature: (I[Ljava/lang/Object;[I)V
- */
-JNIEXPORT void JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_startClient__I_3Ljava_lang_String_2_3I
-  (JNIEnv* env, jclass, jint inst, jobjectArray serverNames, jintArray ports)
-{
-  if (!serverNames) {
-    nullPointerEx.Throw(env, "serverNames cannot be null");
-    return;
-  }
-  if (!ports) {
-    nullPointerEx.Throw(env, "ports cannot be null");
-    return;
-  }
-  int len = env->GetArrayLength(serverNames);
-  if (len != env->GetArrayLength(ports)) {
-    illegalArgEx.Throw(env,
-                       "serverNames and ports arrays must be the same size");
-    return;
-  }
-  jint* portInts = env->GetIntArrayElements(ports, nullptr);
-  if (!portInts) {
-    return;
-  }
-
-  std::vector<std::string> names;
-  std::vector<std::pair<std::string_view, unsigned int>> servers;
-  names.reserve(len);
-  servers.reserve(len);
-  for (int i = 0; i < len; ++i) {
-    JLocal<jstring> elem{
-        env, static_cast<jstring>(env->GetObjectArrayElement(serverNames, i))};
-    if (!elem) {
-      nullPointerEx.Throw(env, "null string in serverNames");
-      return;
-    }
-    names.emplace_back(JStringRef{env, elem}.str());
-    servers.emplace_back(
-        std::make_pair(std::string_view{names.back()}, portInts[i]));
-  }
-  env->ReleaseIntArrayElements(ports, portInts, JNI_ABORT);
-  nt::StartClient(inst, servers);
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    startClientTeam
- * Signature: (III)V
- */
-JNIEXPORT void JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_startClientTeam
-  (JNIEnv* env, jclass cls, jint inst, jint team, jint port)
-{
-  nt::StartClientTeam(inst, team, port);
+  nt::StartClient4(inst, JStringRef{env, identity}.str());
 }
 
 /*
@@ -1692,14 +1324,14 @@
 
 /*
  * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    setUpdateRate
- * Signature: (ID)V
+ * Method:    flushLocal
+ * Signature: (I)V
  */
 JNIEXPORT void JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_setUpdateRate
-  (JNIEnv*, jclass, jint inst, jdouble interval)
+Java_edu_wpi_first_networktables_NetworkTablesJNI_flushLocal
+  (JNIEnv*, jclass, jint inst)
 {
-  nt::SetUpdateRate(inst, interval);
+  nt::FlushLocal(inst);
 }
 
 /*
@@ -1750,100 +1382,14 @@
 
 /*
  * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    savePersistent
- * Signature: (ILjava/lang/String;)V
+ * Method:    getServerTimeOffset
+ * Signature: (I)Ljava/lang/Object;
  */
-JNIEXPORT void JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_savePersistent
-  (JNIEnv* env, jclass, jint inst, jstring filename)
+JNIEXPORT jobject JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getServerTimeOffset
+  (JNIEnv* env, jclass, jint inst)
 {
-  if (!filename) {
-    nullPointerEx.Throw(env, "filename cannot be null");
-    return;
-  }
-  const char* err = nt::SavePersistent(inst, JStringRef{env, filename}.str());
-  if (err) {
-    persistentEx.Throw(env, err);
-  }
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    loadPersistent
- * Signature: (ILjava/lang/String;)[Ljava/lang/Object;
- */
-JNIEXPORT jobjectArray JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_loadPersistent
-  (JNIEnv* env, jclass, jint inst, jstring filename)
-{
-  if (!filename) {
-    nullPointerEx.Throw(env, "filename cannot be null");
-    return nullptr;
-  }
-  std::vector<std::string> warns;
-  const char* err = nt::LoadPersistent(
-      inst, JStringRef{env, filename}.str(), [&](size_t line, const char* msg) {
-        warns.emplace_back(fmt::format("{}: {}", line, msg));
-      });
-  if (err) {
-    persistentEx.Throw(env, err);
-    return nullptr;
-  }
-  return MakeJStringArray(env, warns);
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    saveEntries
- * Signature: (ILjava/lang/String;Ljava/lang/String;)V
- */
-JNIEXPORT void JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_saveEntries
-  (JNIEnv* env, jclass, jint inst, jstring filename, jstring prefix)
-{
-  if (!filename) {
-    nullPointerEx.Throw(env, "filename cannot be null");
-    return;
-  }
-  if (!prefix) {
-    nullPointerEx.Throw(env, "prefix cannot be null");
-    return;
-  }
-  const char* err = nt::SaveEntries(inst, JStringRef{env, filename}.str(),
-                                    JStringRef{env, prefix}.str());
-  if (err) {
-    persistentEx.Throw(env, err);
-  }
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    loadEntries
- * Signature: (ILjava/lang/String;Ljava/lang/String;)[Ljava/lang/Object;
- */
-JNIEXPORT jobjectArray JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_loadEntries
-  (JNIEnv* env, jclass, jint inst, jstring filename, jstring prefix)
-{
-  if (!filename) {
-    nullPointerEx.Throw(env, "filename cannot be null");
-    return nullptr;
-  }
-  if (!prefix) {
-    nullPointerEx.Throw(env, "prefix cannot be null");
-    return nullptr;
-  }
-  std::vector<std::string> warns;
-  const char* err = nt::LoadEntries(
-      inst, JStringRef{env, filename}.str(), JStringRef{env, prefix}.str(),
-      [&](size_t line, const char* msg) {
-        warns.emplace_back(fmt::format("{}: {}", line, msg));
-      });
-  if (err) {
-    persistentEx.Throw(env, err);
-    return nullptr;
-  }
-  return MakeJStringArray(env, warns);
+  return MakeJObject(env, nt::GetServerTimeOffset(inst));
 }
 
 /*
@@ -1860,109 +1406,65 @@
 
 /*
  * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    createLoggerPoller
- * Signature: (I)I
+ * Method:    startEntryDataLog
+ * Signature: (IJLjava/lang/String;Ljava/lang/String;)I
  */
 JNIEXPORT jint JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_createLoggerPoller
-  (JNIEnv*, jclass, jint inst)
+Java_edu_wpi_first_networktables_NetworkTablesJNI_startEntryDataLog
+  (JNIEnv* env, jclass, jint inst, jlong log, jstring prefix, jstring logPrefix)
 {
-  return nt::CreateLoggerPoller(inst);
+  return nt::StartEntryDataLog(inst, *reinterpret_cast<wpi::log::DataLog*>(log),
+                               JStringRef{env, prefix},
+                               JStringRef{env, logPrefix});
 }
 
 /*
  * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    destroyLoggerPoller
+ * Method:    stopEntryDataLog
  * Signature: (I)V
  */
 JNIEXPORT void JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_destroyLoggerPoller
-  (JNIEnv*, jclass, jint poller)
+Java_edu_wpi_first_networktables_NetworkTablesJNI_stopEntryDataLog
+  (JNIEnv*, jclass, jint logger)
 {
-  nt::DestroyLoggerPoller(poller);
+  nt::StopEntryDataLog(logger);
 }
 
 /*
  * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    addPolledLogger
+ * Method:    startConnectionDataLog
+ * Signature: (IJLjava/lang/String;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_startConnectionDataLog
+  (JNIEnv* env, jclass, jint inst, jlong log, jstring name)
+{
+  return nt::StartConnectionDataLog(
+      inst, *reinterpret_cast<wpi::log::DataLog*>(log), JStringRef{env, name});
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    stopConnectionDataLog
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_stopConnectionDataLog
+  (JNIEnv*, jclass, jint logger)
+{
+  nt::StopConnectionDataLog(logger);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    addLogger
  * Signature: (III)I
  */
 JNIEXPORT jint JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_addPolledLogger
+Java_edu_wpi_first_networktables_NetworkTablesJNI_addLogger
   (JNIEnv*, jclass, jint poller, jint minLevel, jint maxLevel)
 {
   return nt::AddPolledLogger(poller, minLevel, maxLevel);
 }
 
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    pollLogger
- * Signature: (Ljava/lang/Object;I)[Ljava/lang/Object;
- */
-JNIEXPORT jobjectArray JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_pollLogger
-  (JNIEnv* env, jclass, jobject inst, jint poller)
-{
-  auto events = nt::PollLogger(poller);
-  if (events.empty()) {
-    interruptedEx.Throw(env, "PollLogger interrupted");
-    return nullptr;
-  }
-  return MakeJObject(env, inst, events);
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    pollLoggerTimeout
- * Signature: (Ljava/lang/Object;ID)[Ljava/lang/Object;
- */
-JNIEXPORT jobjectArray JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_pollLoggerTimeout
-  (JNIEnv* env, jclass, jobject inst, jint poller, jdouble timeout)
-{
-  bool timed_out = false;
-  auto events = nt::PollLogger(poller, timeout, &timed_out);
-  if (events.empty() && !timed_out) {
-    interruptedEx.Throw(env, "PollLogger interrupted");
-    return nullptr;
-  }
-  return MakeJObject(env, inst, events);
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    cancelPollLogger
- * Signature: (I)V
- */
-JNIEXPORT void JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_cancelPollLogger
-  (JNIEnv*, jclass, jint poller)
-{
-  nt::CancelPollLogger(poller);
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    removeLogger
- * Signature: (I)V
- */
-JNIEXPORT void JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_removeLogger
-  (JNIEnv*, jclass, jint logger)
-{
-  nt::RemoveLogger(logger);
-}
-
-/*
- * Class:     edu_wpi_first_networktables_NetworkTablesJNI
- * Method:    waitForLoggerQueue
- * Signature: (ID)Z
- */
-JNIEXPORT jboolean JNICALL
-Java_edu_wpi_first_networktables_NetworkTablesJNI_waitForLoggerQueue
-  (JNIEnv*, jclass, jint inst, jdouble timeout)
-{
-  return nt::WaitForLoggerQueue(inst, timeout);
-}
-
 }  // extern "C"
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/net/ClientImpl.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/net/ClientImpl.cpp
new file mode 100644
index 0000000..2efbb29
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/net/ClientImpl.cpp
@@ -0,0 +1,489 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "ClientImpl.h"
+
+#include <numeric>
+#include <optional>
+#include <string>
+#include <variant>
+
+#include <fmt/format.h>
+#include <wpi/DenseMap.h>
+#include <wpi/Logger.h>
+#include <wpi/raw_ostream.h>
+#include <wpi/timestamp.h>
+
+#include "Handle.h"
+#include "Log.h"
+#include "Message.h"
+#include "NetworkInterface.h"
+#include "PubSubOptions.h"
+#include "WireConnection.h"
+#include "WireDecoder.h"
+#include "WireEncoder.h"
+#include "networktables/NetworkTableValue.h"
+
+using namespace nt;
+using namespace nt::net;
+
+static constexpr uint32_t kMinPeriodMs = 5;
+
+// maximum number of times the wire can be not ready to send another
+// transmission before we close the connection
+static constexpr int kWireMaxNotReady = 10;
+
+namespace {
+
+struct PublisherData {
+  NT_Publisher handle;
+  PubSubOptionsImpl options;
+  // in options as double, but copy here as integer; rounded to the nearest
+  // 10 ms
+  uint32_t periodMs;
+  uint64_t nextSendMs{0};
+  std::vector<Value> outValues;  // outgoing values
+};
+
+class CImpl : public ServerMessageHandler {
+ public:
+  CImpl(uint64_t curTimeMs, int inst, WireConnection& wire, wpi::Logger& logger,
+        std::function<void(int64_t serverTimeOffset, int64_t rtt2, bool valid)>
+            timeSyncUpdated,
+        std::function<void(uint32_t repeatMs)> setPeriodic);
+
+  void ProcessIncomingBinary(std::span<const uint8_t> data);
+  void HandleLocal(std::vector<ClientMessage>&& msgs);
+  bool SendControl(uint64_t curTimeMs);
+  void SendValues(uint64_t curTimeMs);
+  void SendInitialValues();
+  bool CheckNetworkReady();
+
+  // ServerMessageHandler interface
+  void ServerAnnounce(std::string_view name, int64_t id,
+                      std::string_view typeStr, const wpi::json& properties,
+                      std::optional<int64_t> pubuid) final;
+  void ServerUnannounce(std::string_view name, int64_t id) final;
+  void ServerPropertiesUpdate(std::string_view name, const wpi::json& update,
+                              bool ack) final;
+
+  void Publish(NT_Publisher pubHandle, NT_Topic topicHandle,
+               std::string_view name, std::string_view typeStr,
+               const wpi::json& properties, const PubSubOptionsImpl& options);
+  bool Unpublish(NT_Publisher pubHandle, NT_Topic topicHandle);
+  void SetValue(NT_Publisher pubHandle, const Value& value);
+
+  int m_inst;
+  WireConnection& m_wire;
+  wpi::Logger& m_logger;
+  LocalInterface* m_local{nullptr};
+  std::function<void(int64_t serverTimeOffset, int64_t rtt2, bool valid)>
+      m_timeSyncUpdated;
+  std::function<void(uint32_t repeatMs)> m_setPeriodic;
+
+  // indexed by publisher index
+  std::vector<std::unique_ptr<PublisherData>> m_publishers;
+
+  // indexed by server-provided topic id
+  wpi::DenseMap<int64_t, NT_Topic> m_topicMap;
+
+  // timestamp handling
+  static constexpr uint32_t kPingIntervalMs = 3000;
+  uint64_t m_nextPingTimeMs{0};
+  uint32_t m_rtt2Us{UINT32_MAX};
+  bool m_haveTimeOffset{false};
+  int64_t m_serverTimeOffsetUs{0};
+
+  // periodic sweep handling
+  uint32_t m_periodMs{kPingIntervalMs + 10};
+  uint64_t m_lastSendMs{0};
+  int m_notReadyCount{0};
+
+  // outgoing queue
+  std::vector<ClientMessage> m_outgoing;
+};
+
+}  // namespace
+
+CImpl::CImpl(
+    uint64_t curTimeMs, int inst, WireConnection& wire, wpi::Logger& logger,
+    std::function<void(int64_t serverTimeOffset, int64_t rtt2, bool valid)>
+        timeSyncUpdated,
+    std::function<void(uint32_t repeatMs)> setPeriodic)
+    : m_inst{inst},
+      m_wire{wire},
+      m_logger{logger},
+      m_timeSyncUpdated{std::move(timeSyncUpdated)},
+      m_setPeriodic{std::move(setPeriodic)},
+      m_nextPingTimeMs{curTimeMs + kPingIntervalMs} {
+  // immediately send RTT ping
+  auto out = m_wire.SendBinary();
+  auto now = wpi::Now();
+  DEBUG4("Sending initial RTT ping {}", now);
+  WireEncodeBinary(out.Add(), -1, 0, Value::MakeInteger(now));
+  m_wire.Flush();
+  m_setPeriodic(m_periodMs);
+}
+
+void CImpl::ProcessIncomingBinary(std::span<const uint8_t> data) {
+  for (;;) {
+    if (data.empty()) {
+      break;
+    }
+
+    // decode message
+    int64_t id;
+    Value value;
+    std::string error;
+    if (!WireDecodeBinary(&data, &id, &value, &error, -m_serverTimeOffsetUs)) {
+      ERROR("binary decode error: {}", error);
+      break;  // FIXME
+    }
+    DEBUG4("BinaryMessage({})", id);
+
+    // handle RTT ping response
+    if (id == -1) {
+      if (!value.IsInteger()) {
+        WARNING("RTT ping response with non-integer type {}",
+                static_cast<int>(value.type()));
+        continue;
+      }
+      DEBUG4("RTT ping response time {} value {}", value.time(),
+             value.GetInteger());
+      int64_t now = wpi::Now();
+      int64_t rtt2 = (now - value.GetInteger()) / 2;
+      if (rtt2 < m_rtt2Us) {
+        m_rtt2Us = rtt2;
+        m_serverTimeOffsetUs = value.server_time() + rtt2 - now;
+        DEBUG3("Time offset: {}", m_serverTimeOffsetUs);
+        m_haveTimeOffset = true;
+        m_timeSyncUpdated(m_serverTimeOffsetUs, m_rtt2Us, true);
+      }
+      continue;
+    }
+
+    // otherwise it's a value message, get the local topic handle for it
+    auto topicIt = m_topicMap.find(id);
+    if (topicIt == m_topicMap.end()) {
+      WARNING("received unknown id {}", id);
+      continue;
+    }
+
+    // pass along to local handler
+    if (m_local) {
+      m_local->NetworkSetValue(topicIt->second, value);
+    }
+  }
+}
+
+void CImpl::HandleLocal(std::vector<ClientMessage>&& msgs) {
+  DEBUG4("HandleLocal()");
+  for (auto&& elem : msgs) {
+    // common case is value
+    if (auto msg = std::get_if<ClientValueMsg>(&elem.contents)) {
+      SetValue(msg->pubHandle, msg->value);
+      // setvalue puts on individual publish outgoing queues
+    } else if (auto msg = std::get_if<PublishMsg>(&elem.contents)) {
+      Publish(msg->pubHandle, msg->topicHandle, msg->name, msg->typeStr,
+              msg->properties, msg->options);
+      m_outgoing.emplace_back(std::move(elem));
+    } else if (auto msg = std::get_if<UnpublishMsg>(&elem.contents)) {
+      if (Unpublish(msg->pubHandle, msg->topicHandle)) {
+        m_outgoing.emplace_back(std::move(elem));
+      }
+    } else {
+      m_outgoing.emplace_back(std::move(elem));
+    }
+  }
+}
+
+bool CImpl::SendControl(uint64_t curTimeMs) {
+  DEBUG4("SendControl({})", curTimeMs);
+
+  // rate limit sends
+  if (curTimeMs < (m_lastSendMs + kMinPeriodMs)) {
+    return false;
+  }
+
+  // start a timestamp RTT ping if it's time to do one
+  if (curTimeMs >= m_nextPingTimeMs) {
+    if (!CheckNetworkReady()) {
+      return false;
+    }
+    auto now = wpi::Now();
+    DEBUG4("Sending RTT ping {}", now);
+    WireEncodeBinary(m_wire.SendBinary().Add(), -1, 0, Value::MakeInteger(now));
+    // drift isn't critical here, so just go from current time
+    m_nextPingTimeMs = curTimeMs + kPingIntervalMs;
+  }
+
+  if (!m_outgoing.empty()) {
+    if (!CheckNetworkReady()) {
+      return false;
+    }
+    auto writer = m_wire.SendText();
+    for (auto&& msg : m_outgoing) {
+      auto& stream = writer.Add();
+      if (!WireEncodeText(stream, msg)) {
+        // shouldn't happen, but just in case...
+        stream << "{}";
+      }
+    }
+    m_outgoing.resize(0);
+  }
+
+  m_lastSendMs = curTimeMs;
+  return true;
+}
+
+void CImpl::SendValues(uint64_t curTimeMs) {
+  DEBUG4("SendValues({})", curTimeMs);
+
+  // can't send value updates until we have a RTT
+  if (!m_haveTimeOffset) {
+    return;
+  }
+
+  // ensure all control messages are sent ahead of value updates
+  if (!SendControl(curTimeMs)) {
+    return;
+  }
+
+  // send any pending updates due to be sent
+  bool checkedNetwork = false;
+  auto writer = m_wire.SendBinary();
+  for (auto&& pub : m_publishers) {
+    if (pub && !pub->outValues.empty() && curTimeMs >= pub->nextSendMs) {
+      for (auto&& val : pub->outValues) {
+        if (!checkedNetwork) {
+          if (!CheckNetworkReady()) {
+            return;
+          }
+          checkedNetwork = true;
+        }
+        DEBUG4("Sending {} value time={} server_time={} st_off={}", pub->handle,
+               val.time(), val.server_time(), m_serverTimeOffsetUs);
+        int64_t time = val.time();
+        if (time != 0) {
+          time += m_serverTimeOffsetUs;
+        }
+        WireEncodeBinary(writer.Add(), Handle{pub->handle}.GetIndex(), time,
+                         val);
+      }
+      pub->outValues.resize(0);
+      pub->nextSendMs = curTimeMs + pub->periodMs;
+    }
+  }
+}
+
+void CImpl::SendInitialValues() {
+  DEBUG4("SendInitialValues()");
+
+  // ensure all control messages are sent ahead of value updates
+  if (!SendControl(0)) {
+    return;
+  }
+
+  // only send time=0 values (as we don't have a RTT yet)
+  auto writer = m_wire.SendBinary();
+  for (auto&& pub : m_publishers) {
+    if (pub && !pub->outValues.empty()) {
+      bool sent = false;
+      for (auto&& val : pub->outValues) {
+        if (val.server_time() == 0) {
+          DEBUG4("Sending {} value time={} server_time={}", pub->handle,
+                 val.time(), val.server_time());
+          WireEncodeBinary(writer.Add(), Handle{pub->handle}.GetIndex(), 0,
+                           val);
+          sent = true;
+        }
+      }
+      if (sent) {
+        std::erase_if(pub->outValues,
+                      [](const auto& v) { return v.server_time() == 0; });
+      }
+    }
+  }
+}
+
+bool CImpl::CheckNetworkReady() {
+  if (!m_wire.Ready()) {
+    ++m_notReadyCount;
+    if (m_notReadyCount > kWireMaxNotReady) {
+      m_wire.Disconnect("transmit stalled");
+    }
+    return false;
+  }
+  m_notReadyCount = 0;
+  return true;
+}
+
+void CImpl::Publish(NT_Publisher pubHandle, NT_Topic topicHandle,
+                    std::string_view name, std::string_view typeStr,
+                    const wpi::json& properties,
+                    const PubSubOptionsImpl& options) {
+  unsigned int index = Handle{pubHandle}.GetIndex();
+  if (index >= m_publishers.size()) {
+    m_publishers.resize(index + 1);
+  }
+  auto& publisher = m_publishers[index];
+  if (!publisher) {
+    publisher = std::make_unique<PublisherData>();
+  }
+  publisher->handle = pubHandle;
+  publisher->options = options;
+  publisher->periodMs = std::lround(options.periodicMs / 10.0) * 10;
+  if (publisher->periodMs < kMinPeriodMs) {
+    publisher->periodMs = kMinPeriodMs;
+  }
+
+  // update period
+  m_periodMs = std::gcd(m_periodMs, publisher->periodMs);
+  if (m_periodMs < kMinPeriodMs) {
+    m_periodMs = kMinPeriodMs;
+  }
+  m_setPeriodic(m_periodMs);
+}
+
+bool CImpl::Unpublish(NT_Publisher pubHandle, NT_Topic topicHandle) {
+  unsigned int index = Handle{pubHandle}.GetIndex();
+  if (index >= m_publishers.size()) {
+    return false;
+  }
+  bool doSend = true;
+  if (m_publishers[index]) {
+    // Look through outgoing queue to see if the publish hasn't been sent yet;
+    // if it hasn't, delete it and don't send the server a message.
+    // The outgoing queue doesn't contain values; those are deleted with the
+    // publisher object.
+    auto it = std::find_if(
+        m_outgoing.begin(), m_outgoing.end(), [&](const auto& elem) {
+          if (auto msg = std::get_if<PublishMsg>(&elem.contents)) {
+            return msg->pubHandle == pubHandle;
+          }
+          return false;
+        });
+    if (it != m_outgoing.end()) {
+      m_outgoing.erase(it);
+      doSend = false;
+    }
+  }
+  m_publishers[index].reset();
+
+  // loop over all publishers to update period
+  m_periodMs = kPingIntervalMs + 10;
+  for (auto&& pub : m_publishers) {
+    if (pub) {
+      m_periodMs = std::gcd(m_periodMs, pub->periodMs);
+    }
+  }
+  if (m_periodMs < kMinPeriodMs) {
+    m_periodMs = kMinPeriodMs;
+  }
+  m_setPeriodic(m_periodMs);
+
+  return doSend;
+}
+
+void CImpl::SetValue(NT_Publisher pubHandle, const Value& value) {
+  DEBUG4("SetValue({}, time={}, server_time={}, st_off={})", pubHandle,
+         value.time(), value.server_time(), m_serverTimeOffsetUs);
+  unsigned int index = Handle{pubHandle}.GetIndex();
+  if (index >= m_publishers.size() || !m_publishers[index]) {
+    return;
+  }
+  auto& publisher = *m_publishers[index];
+  if (publisher.outValues.empty() || publisher.options.sendAll) {
+    publisher.outValues.emplace_back(value);
+  } else {
+    publisher.outValues.back() = value;
+  }
+}
+
+void CImpl::ServerAnnounce(std::string_view name, int64_t id,
+                           std::string_view typeStr,
+                           const wpi::json& properties,
+                           std::optional<int64_t> pubuid) {
+  DEBUG4("ServerAnnounce({}, {}, {})", name, id, typeStr);
+  assert(m_local);
+  NT_Publisher pubHandle{0};
+  if (pubuid) {
+    pubHandle = Handle(m_inst, pubuid.value(), Handle::kPublisher);
+  }
+  m_topicMap[id] =
+      m_local->NetworkAnnounce(name, typeStr, properties, pubHandle);
+}
+
+void CImpl::ServerUnannounce(std::string_view name, int64_t id) {
+  DEBUG4("ServerUnannounce({}, {})", name, id);
+  assert(m_local);
+  m_local->NetworkUnannounce(name);
+  m_topicMap.erase(id);
+}
+
+void CImpl::ServerPropertiesUpdate(std::string_view name,
+                                   const wpi::json& update, bool ack) {
+  DEBUG4("ServerProperties({}, {}, {})", name, update.dump(), ack);
+  assert(m_local);
+  m_local->NetworkPropertiesUpdate(name, update, ack);
+}
+
+class ClientImpl::Impl final : public CImpl {
+ public:
+  Impl(uint64_t curTimeMs, int inst, WireConnection& wire, wpi::Logger& logger,
+       std::function<void(int64_t serverTimeOffset, int64_t rtt2, bool valid)>
+           timeSyncUpdated,
+       std::function<void(uint32_t repeatMs)> setPeriodic)
+      : CImpl{curTimeMs,
+              inst,
+              wire,
+              logger,
+              std::move(timeSyncUpdated),
+              std::move(setPeriodic)} {}
+};
+
+ClientImpl::ClientImpl(
+    uint64_t curTimeMs, int inst, WireConnection& wire, wpi::Logger& logger,
+    std::function<void(int64_t serverTimeOffset, int64_t rtt2, bool valid)>
+        timeSyncUpdated,
+    std::function<void(uint32_t repeatMs)> setPeriodic)
+    : m_impl{std::make_unique<Impl>(curTimeMs, inst, wire, logger,
+                                    std::move(timeSyncUpdated),
+                                    std::move(setPeriodic))} {}
+
+ClientImpl::~ClientImpl() = default;
+
+void ClientImpl::ProcessIncomingText(std::string_view data) {
+  if (!m_impl->m_local) {
+    return;
+  }
+  WireDecodeText(data, *m_impl, m_impl->m_logger);
+}
+
+void ClientImpl::ProcessIncomingBinary(std::span<const uint8_t> data) {
+  m_impl->ProcessIncomingBinary(data);
+}
+
+void ClientImpl::HandleLocal(std::vector<ClientMessage>&& msgs) {
+  m_impl->HandleLocal(std::move(msgs));
+}
+
+void ClientImpl::SendControl(uint64_t curTimeMs) {
+  m_impl->SendControl(curTimeMs);
+  m_impl->m_wire.Flush();
+}
+
+void ClientImpl::SendValues(uint64_t curTimeMs) {
+  m_impl->SendValues(curTimeMs);
+  m_impl->m_wire.Flush();
+}
+
+void ClientImpl::SetLocal(LocalInterface* local) {
+  m_impl->m_local = local;
+}
+
+void ClientImpl::SendInitial() {
+  m_impl->SendInitialValues();
+  m_impl->m_wire.Flush();
+}
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/net/ClientImpl.h b/third_party/allwpilib/ntcore/src/main/native/cpp/net/ClientImpl.h
new file mode 100644
index 0000000..0e7fd4a
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/net/ClientImpl.h
@@ -0,0 +1,57 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <stdint.h>
+
+#include <functional>
+#include <memory>
+#include <span>
+#include <string>
+#include <string_view>
+#include <vector>
+
+#include "NetworkInterface.h"
+#include "WireConnection.h"
+
+namespace wpi {
+class Logger;
+}  // namespace wpi
+
+namespace nt {
+class PubSubOptionsImpl;
+class Value;
+}  // namespace nt
+
+namespace nt::net {
+
+struct ClientMessage;
+class WireConnection;
+
+class ClientImpl {
+ public:
+  ClientImpl(
+      uint64_t curTimeMs, int inst, WireConnection& wire, wpi::Logger& logger,
+      std::function<void(int64_t serverTimeOffset, int64_t rtt2, bool valid)>
+          timeSyncUpdated,
+      std::function<void(uint32_t repeatMs)> setPeriodic);
+  ~ClientImpl();
+
+  void ProcessIncomingText(std::string_view data);
+  void ProcessIncomingBinary(std::span<const uint8_t> data);
+  void HandleLocal(std::vector<ClientMessage>&& msgs);
+
+  void SendControl(uint64_t curTimeMs);
+  void SendValues(uint64_t curTimeMs);
+
+  void SetLocal(LocalInterface* local);
+  void SendInitial();
+
+ private:
+  class Impl;
+  std::unique_ptr<Impl> m_impl;
+};
+
+}  // namespace nt::net
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/net/Message.h b/third_party/allwpilib/ntcore/src/main/native/cpp/net/Message.h
new file mode 100644
index 0000000..a95c5e8
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/net/Message.h
@@ -0,0 +1,100 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <optional>
+#include <string>
+#include <variant>
+#include <vector>
+
+#include <wpi/json.h>
+
+#include "PubSubOptions.h"
+#include "networktables/NetworkTableValue.h"
+#include "ntcore_c.h"
+
+namespace nt::net {
+
+struct PublishMsg {
+  static constexpr std::string_view kMethodStr = "publish";
+  NT_Publisher pubHandle{0};
+  NT_Topic topicHandle{0};  // will be 0 when coming from network
+  std::string name;
+  std::string typeStr;
+  wpi::json properties;
+  PubSubOptionsImpl options;  // will be empty when coming from network
+};
+
+struct UnpublishMsg {
+  static constexpr std::string_view kMethodStr = "unpublish";
+  NT_Publisher pubHandle{0};
+  NT_Topic topicHandle{0};  // will be 0 when coming from network
+};
+
+struct SetPropertiesMsg {
+  static constexpr std::string_view kMethodStr = "setproperties";
+  NT_Topic topicHandle{0};  // will be 0 when coming from network
+  std::string name;
+  wpi::json update;
+};
+
+struct SubscribeMsg {
+  static constexpr std::string_view kMethodStr = "subscribe";
+  NT_Subscriber subHandle{0};
+  std::vector<std::string> topicNames;
+  PubSubOptionsImpl options;
+};
+
+struct UnsubscribeMsg {
+  static constexpr std::string_view kMethodStr = "unsubscribe";
+  NT_Subscriber subHandle{0};
+};
+
+struct ClientValueMsg {
+  NT_Publisher pubHandle{0};
+  Value value;
+};
+
+struct ClientMessage {
+  using Contents =
+      std::variant<std::monostate, PublishMsg, UnpublishMsg, SetPropertiesMsg,
+                   SubscribeMsg, UnsubscribeMsg, ClientValueMsg>;
+  Contents contents;
+};
+
+struct AnnounceMsg {
+  static constexpr std::string_view kMethodStr = "announce";
+  std::string name;
+  int64_t id{0};
+  std::string typeStr;
+  std::optional<int64_t> pubuid;
+  wpi::json properties;
+};
+
+struct UnannounceMsg {
+  static constexpr std::string_view kMethodStr = "unannounce";
+  std::string name;
+  int64_t id{0};
+};
+
+struct PropertiesUpdateMsg {
+  static constexpr std::string_view kMethodStr = "properties";
+  std::string name;
+  wpi::json update;
+  bool ack;
+};
+
+struct ServerValueMsg {
+  NT_Topic topic{0};
+  Value value;
+};
+
+struct ServerMessage {
+  using Contents = std::variant<std::monostate, AnnounceMsg, UnannounceMsg,
+                                PropertiesUpdateMsg, ServerValueMsg>;
+  Contents contents;
+};
+
+}  // namespace nt::net
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/net/NetworkInterface.h b/third_party/allwpilib/ntcore/src/main/native/cpp/net/NetworkInterface.h
new file mode 100644
index 0000000..3b2e7dd
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/net/NetworkInterface.h
@@ -0,0 +1,62 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <span>
+#include <string>
+#include <string_view>
+
+#include "ntcore_cpp.h"
+
+namespace wpi {
+class json;
+}  // namespace wpi
+
+namespace nt {
+class PubSubOptionsImpl;
+class Value;
+}  // namespace nt
+
+namespace nt::net {
+
+class LocalInterface {
+ public:
+  virtual ~LocalInterface() = default;
+
+  virtual NT_Topic NetworkAnnounce(std::string_view name,
+                                   std::string_view typeStr,
+                                   const wpi::json& properties,
+                                   NT_Publisher pubHandle) = 0;
+  virtual void NetworkUnannounce(std::string_view name) = 0;
+  virtual void NetworkPropertiesUpdate(std::string_view name,
+                                       const wpi::json& update, bool ack) = 0;
+  virtual void NetworkSetValue(NT_Topic topicHandle, const Value& value) = 0;
+};
+
+class NetworkInterface {
+ public:
+  virtual ~NetworkInterface() = default;
+
+  virtual void Publish(NT_Publisher pubHandle, NT_Topic topicHandle,
+                       std::string_view name, std::string_view typeStr,
+                       const wpi::json& properties,
+                       const PubSubOptionsImpl& options) = 0;
+  virtual void Unpublish(NT_Publisher pubHandle, NT_Topic topicHandle) = 0;
+  virtual void SetProperties(NT_Topic topicHandle, std::string_view name,
+                             const wpi::json& update) = 0;
+  virtual void Subscribe(NT_Subscriber subHandle,
+                         std::span<const std::string> topicNames,
+                         const PubSubOptionsImpl& options) = 0;
+  virtual void Unsubscribe(NT_Subscriber subHandle) = 0;
+  virtual void SetValue(NT_Publisher pubHandle, const Value& value) = 0;
+};
+
+class ILocalStorage : public LocalInterface {
+ public:
+  virtual void StartNetwork(NetworkInterface* network) = 0;
+  virtual void ClearNetwork() = 0;
+};
+
+}  // namespace nt::net
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/net/NetworkLoopQueue.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/net/NetworkLoopQueue.cpp
new file mode 100644
index 0000000..7c58c65
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/net/NetworkLoopQueue.cpp
@@ -0,0 +1,54 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "NetworkLoopQueue.h"
+
+#include <wpi/Logger.h>
+
+using namespace nt::net;
+
+static constexpr size_t kMaxSize = 2 * 1024 * 1024;
+
+void NetworkLoopQueue::SetValue(NT_Publisher pubHandle, const Value& value) {
+  std::scoped_lock lock{m_mutex};
+  switch (value.type()) {
+    case NT_STRING:
+      m_size += value.GetString().size();  // imperfect but good enough
+      break;
+    case NT_RAW:
+      m_size += value.GetRaw().size_bytes();
+      break;
+    case NT_BOOLEAN_ARRAY:
+      m_size += value.GetBooleanArray().size_bytes();
+      break;
+    case NT_INTEGER_ARRAY:
+      m_size += value.GetIntegerArray().size_bytes();
+      break;
+    case NT_FLOAT_ARRAY:
+      m_size += value.GetFloatArray().size_bytes();
+      break;
+    case NT_DOUBLE_ARRAY:
+      m_size += value.GetDoubleArray().size_bytes();
+      break;
+    case NT_STRING_ARRAY: {
+      auto arr = value.GetStringArray();
+      m_size += arr.size_bytes();
+      for (auto&& s : arr) {
+        m_size += s.capacity();
+      }
+      break;
+    }
+    default:
+      break;
+  }
+  m_size += sizeof(ClientMessage);
+  if (m_size > kMaxSize) {
+    if (!m_sizeErrored) {
+      WPI_ERROR(m_logger, "NT: dropping value set due to memory limits");
+      m_sizeErrored = true;
+    }
+    return;  // avoid potential out of memory
+  }
+  m_queue.emplace_back(ClientMessage{ClientValueMsg{pubHandle, value}});
+}
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/net/NetworkLoopQueue.h b/third_party/allwpilib/ntcore/src/main/native/cpp/net/NetworkLoopQueue.h
new file mode 100644
index 0000000..6ab68b6
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/net/NetworkLoopQueue.h
@@ -0,0 +1,57 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <span>
+#include <string>
+#include <vector>
+
+#include <wpi/mutex.h>
+
+#include "Message.h"
+#include "NetworkInterface.h"
+
+namespace wpi {
+class Logger;
+}  // namespace wpi
+
+namespace nt::net {
+
+class NetworkLoopQueue : public NetworkInterface {
+ public:
+  static constexpr size_t kInitialQueueSize = 2000;
+
+  explicit NetworkLoopQueue(wpi::Logger& logger) : m_logger{logger} {
+    m_queue.reserve(kInitialQueueSize);
+  }
+
+  void ReadQueue(std::vector<ClientMessage>* out);
+  void ClearQueue();
+
+  // NetworkInterface - calls to these append to the queue
+  void Publish(NT_Publisher pubHandle, NT_Topic topicHandle,
+               std::string_view name, std::string_view typeStr,
+               const wpi::json& properties,
+               const PubSubOptionsImpl& options) final;
+  void Unpublish(NT_Publisher pubHandle, NT_Topic topicHandle) final;
+  void SetProperties(NT_Topic topicHandle, std::string_view name,
+                     const wpi::json& update) final;
+  void Subscribe(NT_Subscriber subHandle,
+                 std::span<const std::string> topicNames,
+                 const PubSubOptionsImpl& options) final;
+  void Unsubscribe(NT_Subscriber subHandle) final;
+  void SetValue(NT_Publisher pubHandle, const Value& value) final;
+
+ private:
+  wpi::mutex m_mutex;
+  std::vector<ClientMessage> m_queue;
+  wpi::Logger& m_logger;
+  size_t m_size{0};
+  bool m_sizeErrored{false};
+};
+
+}  // namespace nt::net
+
+#include "NetworkLoopQueue.inc"
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/net/NetworkLoopQueue.inc b/third_party/allwpilib/ntcore/src/main/native/cpp/net/NetworkLoopQueue.inc
new file mode 100644
index 0000000..a441780
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/net/NetworkLoopQueue.inc
@@ -0,0 +1,71 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <span>
+#include <string>
+#include <vector>
+
+#include "NetworkLoopQueue.h"
+#include "ntcore_c.h"
+
+namespace nt::net {
+
+inline void NetworkLoopQueue::ReadQueue(std::vector<ClientMessage>* out) {
+  std::scoped_lock lock{m_mutex};
+  out->swap(m_queue);
+  m_queue.resize(0);
+  m_queue.reserve(out->capacity());  // keep the same running capacity
+  m_size = 0;
+  m_sizeErrored = false;
+}
+
+inline void NetworkLoopQueue::ClearQueue() {
+  std::scoped_lock lock{m_mutex};
+  m_queue.resize(0);
+  m_size = 0;
+  m_sizeErrored = false;
+}
+
+inline void NetworkLoopQueue::Publish(NT_Publisher pubHandle,
+                                      NT_Topic topicHandle,
+                                      std::string_view name,
+                                      std::string_view typeStr,
+                                      const wpi::json& properties,
+                                      const PubSubOptionsImpl& options) {
+  std::scoped_lock lock{m_mutex};
+  m_queue.emplace_back(
+      ClientMessage{PublishMsg{pubHandle, topicHandle, std::string{name},
+                               std::string{typeStr}, properties, options}});
+}
+
+inline void NetworkLoopQueue::Unpublish(NT_Publisher pubHandle,
+                                        NT_Topic topicHandle) {
+  std::scoped_lock lock{m_mutex};
+  m_queue.emplace_back(ClientMessage{UnpublishMsg{pubHandle, topicHandle}});
+}
+
+inline void NetworkLoopQueue::SetProperties(NT_Topic topicHandle,
+                                            std::string_view name,
+                                            const wpi::json& update) {
+  std::scoped_lock lock{m_mutex};
+  m_queue.emplace_back(
+      ClientMessage{SetPropertiesMsg{topicHandle, std::string{name}, update}});
+}
+
+inline void NetworkLoopQueue::Subscribe(NT_Subscriber subHandle,
+                                        std::span<const std::string> topicNames,
+                                        const PubSubOptionsImpl& options) {
+  std::scoped_lock lock{m_mutex};
+  m_queue.emplace_back(ClientMessage{SubscribeMsg{
+      subHandle, {topicNames.begin(), topicNames.end()}, options}});
+}
+
+inline void NetworkLoopQueue::Unsubscribe(NT_Subscriber subHandle) {
+  std::scoped_lock lock{m_mutex};
+  m_queue.emplace_back(ClientMessage{UnsubscribeMsg{subHandle}});
+}
+
+}  // namespace nt::net
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/net/ServerImpl.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/net/ServerImpl.cpp
new file mode 100644
index 0000000..d9b1c0c
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/net/ServerImpl.cpp
@@ -0,0 +1,2363 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "ServerImpl.h"
+
+#include <stdint.h>
+
+#include <algorithm>
+#include <cmath>
+#include <numeric>
+#include <optional>
+#include <string>
+#include <vector>
+
+#include <wpi/Base64.h>
+#include <wpi/DenseMap.h>
+#include <wpi/MessagePack.h>
+#include <wpi/SmallVector.h>
+#include <wpi/StringExtras.h>
+#include <wpi/StringMap.h>
+#include <wpi/UidVector.h>
+#include <wpi/json.h>
+#include <wpi/json_serializer.h>
+#include <wpi/raw_ostream.h>
+#include <wpi/timestamp.h>
+
+#include "IConnectionList.h"
+#include "Log.h"
+#include "Message.h"
+#include "NetworkInterface.h"
+#include "PubSubOptions.h"
+#include "Types_internal.h"
+#include "WireConnection.h"
+#include "WireDecoder.h"
+#include "WireEncoder.h"
+#include "net3/Message3.h"
+#include "net3/SequenceNumber.h"
+#include "net3/WireConnection3.h"
+#include "net3/WireDecoder3.h"
+#include "net3/WireEncoder3.h"
+#include "networktables/NetworkTableValue.h"
+#include "ntcore_c.h"
+
+using namespace nt;
+using namespace nt::net;
+using namespace mpack;
+
+static constexpr uint32_t kMinPeriodMs = 5;
+
+// maximum number of times the wire can be not ready to send another
+// transmission before we close the connection
+static constexpr int kWireMaxNotReady = 10;
+
+namespace {
+
+// Utility wrapper for making a set-like vector
+template <typename T>
+class VectorSet : public std::vector<T> {
+ public:
+  using iterator = typename std::vector<T>::iterator;
+  void Add(T value) { this->push_back(value); }
+  // returns true if element was present
+  bool Remove(T value) {
+    auto removeIt = std::remove(this->begin(), this->end(), value);
+    if (removeIt == this->end()) {
+      return false;
+    }
+    this->erase(removeIt, this->end());
+    return true;
+  }
+};
+
+struct PublisherData;
+struct SubscriberData;
+struct TopicData;
+class SImpl;
+
+class ClientData {
+ public:
+  ClientData(std::string_view originalName, std::string_view name,
+             std::string_view connInfo, bool local,
+             ServerImpl::SetPeriodicFunc setPeriodic, SImpl& server, int id,
+             wpi::Logger& logger)
+      : m_originalName{originalName},
+        m_name{name},
+        m_connInfo{connInfo},
+        m_local{local},
+        m_setPeriodic{std::move(setPeriodic)},
+        m_server{server},
+        m_id{id},
+        m_logger{logger} {}
+  virtual ~ClientData() = default;
+
+  virtual void ProcessIncomingText(std::string_view data) = 0;
+  virtual void ProcessIncomingBinary(std::span<const uint8_t> data) = 0;
+
+  enum SendMode { kSendDisabled = 0, kSendAll, kSendNormal, kSendImmNoFlush };
+
+  virtual void SendValue(TopicData* topic, const Value& value,
+                         SendMode mode) = 0;
+  virtual void SendAnnounce(TopicData* topic,
+                            std::optional<int64_t> pubuid) = 0;
+  virtual void SendUnannounce(TopicData* topic) = 0;
+  virtual void SendPropertiesUpdate(TopicData* topic, const wpi::json& update,
+                                    bool ack) = 0;
+  virtual void SendOutgoing(uint64_t curTimeMs) = 0;
+  virtual void Flush() = 0;
+
+  void UpdateMetaClientPub();
+  void UpdateMetaClientSub();
+
+  std::span<SubscriberData*> GetSubscribers(
+      std::string_view name, bool special,
+      wpi::SmallVectorImpl<SubscriberData*>& buf);
+
+  std::string_view GetOriginalName() const { return m_originalName; }
+  std::string_view GetName() const { return m_name; }
+  int GetId() const { return m_id; }
+
+ protected:
+  std::string m_originalName;
+  std::string m_name;
+  std::string m_connInfo;
+  bool m_local;  // local to machine
+  ServerImpl::SetPeriodicFunc m_setPeriodic;
+  // TODO: make this per-topic?
+  uint32_t m_periodMs{UINT32_MAX};
+  uint64_t m_lastSendMs{0};
+  SImpl& m_server;
+  int m_id;
+
+  wpi::Logger& m_logger;
+
+  wpi::DenseMap<int64_t, std::unique_ptr<PublisherData>> m_publishers;
+  wpi::DenseMap<int64_t, std::unique_ptr<SubscriberData>> m_subscribers;
+
+ public:
+  // meta topics
+  TopicData* m_metaPub = nullptr;
+  TopicData* m_metaSub = nullptr;
+};
+
+class ClientData4Base : public ClientData, protected ClientMessageHandler {
+ public:
+  ClientData4Base(std::string_view originalName, std::string_view name,
+                  std::string_view connInfo, bool local,
+                  ServerImpl::SetPeriodicFunc setPeriodic, SImpl& server,
+                  int id, wpi::Logger& logger)
+      : ClientData{originalName, name,   connInfo, local,
+                   setPeriodic,  server, id,       logger} {}
+
+ protected:
+  // ClientMessageHandler interface
+  void ClientPublish(int64_t pubuid, std::string_view name,
+                     std::string_view typeStr,
+                     const wpi::json& properties) final;
+  void ClientUnpublish(int64_t pubuid) final;
+  void ClientSetProperties(std::string_view name,
+                           const wpi::json& update) final;
+  void ClientSubscribe(int64_t subuid, std::span<const std::string> topicNames,
+                       const PubSubOptionsImpl& options) final;
+  void ClientUnsubscribe(int64_t subuid) final;
+
+  void ClientSetValue(int64_t pubuid, const Value& value);
+
+  wpi::DenseMap<TopicData*, bool> m_announceSent;
+};
+
+class ClientDataLocal final : public ClientData4Base {
+ public:
+  ClientDataLocal(SImpl& server, int id, wpi::Logger& logger)
+      : ClientData4Base{"", "", "", true, [](uint32_t) {}, server, id, logger} {
+  }
+
+  void ProcessIncomingText(std::string_view data) final {}
+  void ProcessIncomingBinary(std::span<const uint8_t> data) final {}
+
+  void SendValue(TopicData* topic, const Value& value, SendMode mode) final;
+  void SendAnnounce(TopicData* topic, std::optional<int64_t> pubuid) final;
+  void SendUnannounce(TopicData* topic) final;
+  void SendPropertiesUpdate(TopicData* topic, const wpi::json& update,
+                            bool ack) final;
+  void SendOutgoing(uint64_t curTimeMs) final {}
+  void Flush() final {}
+
+  void HandleLocal(std::span<const ClientMessage> msgs);
+};
+
+class ClientData4 final : public ClientData4Base {
+ public:
+  ClientData4(std::string_view originalName, std::string_view name,
+              std::string_view connInfo, bool local, WireConnection& wire,
+              ServerImpl::SetPeriodicFunc setPeriodic, SImpl& server, int id,
+              wpi::Logger& logger)
+      : ClientData4Base{originalName, name,   connInfo, local,
+                        setPeriodic,  server, id,       logger},
+        m_wire{wire} {}
+
+  void ProcessIncomingText(std::string_view data) final;
+  void ProcessIncomingBinary(std::span<const uint8_t> data) final;
+
+  void SendValue(TopicData* topic, const Value& value, SendMode mode) final;
+  void SendAnnounce(TopicData* topic, std::optional<int64_t> pubuid) final;
+  void SendUnannounce(TopicData* topic) final;
+  void SendPropertiesUpdate(TopicData* topic, const wpi::json& update,
+                            bool ack) final;
+  void SendOutgoing(uint64_t curTimeMs) final;
+
+  void Flush() final;
+
+ public:
+  WireConnection& m_wire;
+
+ private:
+  std::vector<ServerMessage> m_outgoing;
+  int m_notReadyCount{0};
+
+  bool WriteBinary(int64_t id, int64_t time, const Value& value) {
+    return WireEncodeBinary(SendBinary().Add(), id, time, value);
+  }
+
+  TextWriter& SendText() {
+    m_outBinary.reset();  // ensure proper interleaving of text and binary
+    if (!m_outText) {
+      m_outText = m_wire.SendText();
+    }
+    return *m_outText;
+  }
+
+  BinaryWriter& SendBinary() {
+    m_outText.reset();  // ensure proper interleaving of text and binary
+    if (!m_outBinary) {
+      m_outBinary = m_wire.SendBinary();
+    }
+    return *m_outBinary;
+  }
+
+  // valid when we are actively writing to this client
+  std::optional<TextWriter> m_outText;
+  std::optional<BinaryWriter> m_outBinary;
+};
+
+class ClientData3 final : public ClientData, private net3::MessageHandler3 {
+ public:
+  ClientData3(std::string_view connInfo, bool local,
+              net3::WireConnection3& wire, ServerImpl::Connected3Func connected,
+              ServerImpl::SetPeriodicFunc setPeriodic, SImpl& server, int id,
+              wpi::Logger& logger)
+      : ClientData{"", "", connInfo, local, setPeriodic, server, id, logger},
+        m_connected{std::move(connected)},
+        m_wire{wire},
+        m_decoder{*this} {}
+
+  void ProcessIncomingText(std::string_view data) final {}
+  void ProcessIncomingBinary(std::span<const uint8_t> data) final;
+
+  void SendValue(TopicData* topic, const Value& value, SendMode mode) final;
+  void SendAnnounce(TopicData* topic, std::optional<int64_t> pubuid) final;
+  void SendUnannounce(TopicData* topic) final;
+  void SendPropertiesUpdate(TopicData* topic, const wpi::json& update,
+                            bool ack) final;
+  void SendOutgoing(uint64_t curTimeMs) final;
+
+  void Flush() final { m_wire.Flush(); }
+
+ private:
+  // MessageHandler3 interface
+  void KeepAlive() final;
+  void ServerHelloDone() final;
+  void ClientHelloDone() final;
+  void ClearEntries() final;
+  void ProtoUnsup(unsigned int proto_rev) final;
+  void ClientHello(std::string_view self_id, unsigned int proto_rev) final;
+  void ServerHello(unsigned int flags, std::string_view self_id) final;
+  void EntryAssign(std::string_view name, unsigned int id, unsigned int seq_num,
+                   const Value& value, unsigned int flags) final;
+  void EntryUpdate(unsigned int id, unsigned int seq_num,
+                   const Value& value) final;
+  void FlagsUpdate(unsigned int id, unsigned int flags) final;
+  void EntryDelete(unsigned int id) final;
+  void ExecuteRpc(unsigned int id, unsigned int uid,
+                  std::span<const uint8_t> params) final {}
+  void RpcResponse(unsigned int id, unsigned int uid,
+                   std::span<const uint8_t> result) final {}
+
+  ServerImpl::Connected3Func m_connected;
+  net3::WireConnection3& m_wire;
+
+  enum State { kStateInitial, kStateServerHelloComplete, kStateRunning };
+  State m_state{kStateInitial};
+  net3::WireDecoder3 m_decoder;
+
+  std::vector<net3::Message3> m_outgoing;
+  int64_t m_nextPubUid{1};
+  int m_notReadyCount{0};
+
+  struct TopicData3 {
+    explicit TopicData3(TopicData* topic) { UpdateFlags(topic); }
+
+    unsigned int flags{0};
+    net3::SequenceNumber seqNum;
+    bool sentAssign{false};
+    bool published{false};
+    int64_t pubuid{0};
+
+    bool UpdateFlags(TopicData* topic);
+  };
+  wpi::DenseMap<TopicData*, TopicData3> m_topics3;
+  TopicData3* GetTopic3(TopicData* topic) {
+    return &m_topics3.try_emplace(topic, topic).first->second;
+  }
+};
+
+struct TopicData {
+  TopicData(std::string_view name, std::string_view typeStr)
+      : name{name}, typeStr{typeStr} {}
+  TopicData(std::string_view name, std::string_view typeStr,
+            wpi::json properties)
+      : name{name}, typeStr{typeStr}, properties(std::move(properties)) {
+    RefreshProperties();
+  }
+
+  bool IsPublished() const {
+    return persistent || retained || !publishers.empty();
+  }
+
+  // returns true if properties changed
+  bool SetProperties(const wpi::json& update);
+  void RefreshProperties();
+  bool SetFlags(unsigned int flags_);
+
+  std::string name;
+  unsigned int id;
+  Value lastValue;
+  ClientData* lastValueClient = nullptr;
+  std::string typeStr;
+  wpi::json properties = wpi::json::object();
+  bool persistent{false};
+  bool retained{false};
+  bool special{false};
+  NT_Topic localHandle{0};
+
+  VectorSet<PublisherData*> publishers;
+  VectorSet<SubscriberData*> subscribers;
+
+  // meta topics
+  TopicData* metaPub = nullptr;
+  TopicData* metaSub = nullptr;
+};
+
+struct PublisherData {
+  PublisherData(ClientData* client, TopicData* topic, int64_t pubuid)
+      : client{client}, topic{topic}, pubuid{pubuid} {}
+
+  ClientData* client;
+  TopicData* topic;
+  int64_t pubuid;
+};
+
+struct SubscriberData {
+  SubscriberData(ClientData* client, std::span<const std::string> topicNames,
+                 int64_t subuid, const PubSubOptionsImpl& options)
+      : client{client},
+        topicNames{topicNames.begin(), topicNames.end()},
+        subuid{subuid},
+        options{options},
+        periodMs(std::lround(options.periodicMs / 10.0) * 10) {
+    if (periodMs < kMinPeriodMs) {
+      periodMs = kMinPeriodMs;
+    }
+  }
+
+  void Update(std::span<const std::string> topicNames_,
+              const PubSubOptionsImpl& options_) {
+    topicNames = {topicNames_.begin(), topicNames_.end()};
+    options = options_;
+    periodMs = std::lround(options_.periodicMs / 10.0) * 10;
+    if (periodMs < kMinPeriodMs) {
+      periodMs = kMinPeriodMs;
+    }
+  }
+
+  bool Matches(std::string_view name, bool special);
+
+  ClientData* client;
+  std::vector<std::string> topicNames;
+  int64_t subuid;
+  PubSubOptionsImpl options;
+  // in options as double, but copy here as integer; rounded to the nearest
+  // 10 ms
+  uint32_t periodMs;
+};
+
+class SImpl {
+ public:
+  explicit SImpl(wpi::Logger& logger);
+
+  wpi::Logger& m_logger;
+  LocalInterface* m_local{nullptr};
+  bool m_controlReady{false};
+
+  ClientDataLocal* m_localClient;
+  std::vector<std::unique_ptr<ClientData>> m_clients;
+  wpi::UidVector<std::unique_ptr<TopicData>, 16> m_topics;
+  wpi::StringMap<TopicData*> m_nameTopics;
+  bool m_persistentChanged{false};
+
+  // global meta topics (other meta topics are linked to from the specific
+  // client or topic)
+  TopicData* m_metaClients;
+
+  // ServerImpl interface
+  std::pair<std::string, int> AddClient(
+      std::string_view name, std::string_view connInfo, bool local,
+      WireConnection& wire, ServerImpl::SetPeriodicFunc setPeriodic);
+  int AddClient3(std::string_view connInfo, bool local,
+                 net3::WireConnection3& wire,
+                 ServerImpl::Connected3Func connected,
+                 ServerImpl::SetPeriodicFunc setPeriodic);
+  void RemoveClient(int clientId);
+
+  bool PersistentChanged();
+  void DumpPersistent(wpi::raw_ostream& os);
+  std::string LoadPersistent(std::string_view in);
+
+  // helper functions
+  TopicData* CreateTopic(ClientData* client, std::string_view name,
+                         std::string_view typeStr, const wpi::json& properties,
+                         bool special = false);
+  TopicData* CreateMetaTopic(std::string_view name);
+  void DeleteTopic(TopicData* topic);
+  void SetProperties(ClientData* client, TopicData* topic,
+                     const wpi::json& update);
+  void SetFlags(ClientData* client, TopicData* topic, unsigned int flags);
+  void SetValue(ClientData* client, TopicData* topic, const Value& value);
+
+  // update meta topic values from data structures
+  void UpdateMetaClients(const std::vector<ConnectionInfo>& conns);
+  void UpdateMetaTopicPub(TopicData* topic);
+  void UpdateMetaTopicSub(TopicData* topic);
+
+ private:
+  void PropertiesChanged(ClientData* client, TopicData* topic,
+                         const wpi::json& update);
+};
+
+struct Writer : public mpack_writer_t {
+  Writer() {
+    mpack_writer_init(this, buf, sizeof(buf));
+    mpack_writer_set_context(this, &os);
+    mpack_writer_set_flush(
+        this, [](mpack_writer_t* w, const char* buffer, size_t count) {
+          static_cast<wpi::raw_ostream*>(w->context)->write(buffer, count);
+        });
+  }
+
+  std::vector<uint8_t> bytes;
+  wpi::raw_uvector_ostream os{bytes};
+  char buf[128];
+};
+}  // namespace
+
+static void WriteOptions(mpack_writer_t& w, const PubSubOptionsImpl& options) {
+  int size =
+      (options.sendAll ? 1 : 0) + (options.topicsOnly ? 1 : 0) +
+      (options.periodicMs != PubSubOptionsImpl::kDefaultPeriodicMs ? 1 : 0) +
+      (options.prefixMatch ? 1 : 0);
+  mpack_start_map(&w, size);
+  if (options.sendAll) {
+    mpack_write_str(&w, "all");
+    mpack_write_bool(&w, true);
+  }
+  if (options.topicsOnly) {
+    mpack_write_str(&w, "topicsonly");
+    mpack_write_bool(&w, true);
+  }
+  if (options.periodicMs != PubSubOptionsImpl::kDefaultPeriodicMs) {
+    mpack_write_str(&w, "periodic");
+    mpack_write_float(&w, options.periodicMs / 1000.0);
+  }
+  if (options.prefixMatch) {
+    mpack_write_str(&w, "prefix");
+    mpack_write_bool(&w, true);
+  }
+  mpack_finish_map(&w);
+}
+
+void ClientData::UpdateMetaClientPub() {
+  if (!m_metaPub) {
+    return;
+  }
+  Writer w;
+  mpack_start_array(&w, m_publishers.size());
+  for (auto&& pub : m_publishers) {
+    mpack_start_map(&w, 2);
+    mpack_write_str(&w, "uid");
+    mpack_write_int(&w, pub.first);
+    mpack_write_str(&w, "topic");
+    mpack_write_str(&w, pub.second->topic->name);
+    mpack_finish_map(&w);
+  }
+  mpack_finish_array(&w);
+  if (mpack_writer_destroy(&w) == mpack_ok) {
+    m_server.SetValue(nullptr, m_metaPub, Value::MakeRaw(std::move(w.bytes)));
+  }
+}
+
+void ClientData::UpdateMetaClientSub() {
+  if (!m_metaSub) {
+    return;
+  }
+  Writer w;
+  mpack_start_array(&w, m_subscribers.size());
+  for (auto&& sub : m_subscribers) {
+    mpack_start_map(&w, 3);
+    mpack_write_str(&w, "uid");
+    mpack_write_int(&w, sub.first);
+    mpack_write_str(&w, "topics");
+    mpack_start_array(&w, sub.second->topicNames.size());
+    for (auto&& name : sub.second->topicNames) {
+      mpack_write_str(&w, name);
+    }
+    mpack_finish_array(&w);
+    mpack_write_str(&w, "options");
+    WriteOptions(w, sub.second->options);
+    mpack_finish_map(&w);
+  }
+  mpack_finish_array(&w);
+  if (mpack_writer_destroy(&w) == mpack_ok) {
+    m_server.SetValue(nullptr, m_metaSub, Value::MakeRaw(std::move(w.bytes)));
+  }
+}
+
+std::span<SubscriberData*> ClientData::GetSubscribers(
+    std::string_view name, bool special,
+    wpi::SmallVectorImpl<SubscriberData*>& buf) {
+  buf.resize(0);
+  for (auto&& subPair : m_subscribers) {
+    SubscriberData* subscriber = subPair.getSecond().get();
+    if (subscriber->Matches(name, special)) {
+      buf.emplace_back(subscriber);
+    }
+  }
+  return {buf.data(), buf.size()};
+}
+
+void ClientData4Base::ClientPublish(int64_t pubuid, std::string_view name,
+                                    std::string_view typeStr,
+                                    const wpi::json& properties) {
+  DEBUG3("ClientPublish({}, {}, {}, {})", m_id, name, pubuid, typeStr);
+  auto topic = m_server.CreateTopic(this, name, typeStr, properties);
+
+  // create publisher
+  auto [publisherIt, isNew] = m_publishers.try_emplace(
+      pubuid, std::make_unique<PublisherData>(this, topic, pubuid));
+  if (!isNew) {
+    WARNING("client {} duplicate publish of pubuid {}", m_id, pubuid);
+  }
+
+  // add publisher to topic
+  topic->publishers.Add(publisherIt->getSecond().get());
+
+  // update meta data
+  m_server.UpdateMetaTopicPub(topic);
+  UpdateMetaClientPub();
+
+  // respond with announce with pubuid to client
+  DEBUG4("client {}: announce {} pubuid {}", m_id, topic->name, pubuid);
+  SendAnnounce(topic, pubuid);
+}
+
+void ClientData4Base::ClientUnpublish(int64_t pubuid) {
+  DEBUG3("ClientUnpublish({}, {})", m_id, pubuid);
+  auto publisherIt = m_publishers.find(pubuid);
+  if (publisherIt == m_publishers.end()) {
+    return;  // nothing to do
+  }
+  auto publisher = publisherIt->getSecond().get();
+  auto topic = publisher->topic;
+
+  // remove publisher from topic
+  topic->publishers.Remove(publisher);
+
+  // remove publisher from client
+  m_publishers.erase(publisherIt);
+
+  // update meta data
+  m_server.UpdateMetaTopicPub(topic);
+  UpdateMetaClientPub();
+
+  // delete topic if no longer published
+  if (!topic->IsPublished()) {
+    m_server.DeleteTopic(topic);
+  }
+}
+
+void ClientData4Base::ClientSetProperties(std::string_view name,
+                                          const wpi::json& update) {
+  DEBUG4("ClientSetProperties({}, {}, {})", m_id, name, update.dump());
+  auto topicIt = m_server.m_nameTopics.find(name);
+  if (topicIt == m_server.m_nameTopics.end() ||
+      !topicIt->second->IsPublished()) {
+    DEBUG3("ignored SetProperties from {} on non-existent topic '{}'", m_id,
+           name);
+    return;  // nothing to do
+  }
+  auto topic = topicIt->second;
+  if (topic->special) {
+    DEBUG3("ignored SetProperties from {} on meta topic '{}'", m_id, name);
+    return;  // nothing to do
+  }
+  m_server.SetProperties(nullptr, topic, update);
+}
+
+void ClientData4Base::ClientSubscribe(int64_t subuid,
+                                      std::span<const std::string> topicNames,
+                                      const PubSubOptionsImpl& options) {
+  DEBUG4("ClientSubscribe({}, ({}), {})", m_id, fmt::join(topicNames, ","),
+         subuid);
+  auto& sub = m_subscribers[subuid];
+  bool replace = false;
+  if (sub) {
+    // replace subscription
+    sub->Update(topicNames, options);
+    replace = true;
+  } else {
+    // create
+    sub = std::make_unique<SubscriberData>(this, topicNames, subuid, options);
+  }
+
+  // limit subscriber min period
+  if (sub->periodMs < kMinPeriodMs) {
+    sub->periodMs = kMinPeriodMs;
+  }
+
+  // update periodic sender (if not local)
+  if (!m_local) {
+    if (m_periodMs == UINT32_MAX) {
+      m_periodMs = sub->periodMs;
+    } else {
+      m_periodMs = std::gcd(m_periodMs, sub->periodMs);
+    }
+    if (m_periodMs < kMinPeriodMs) {
+      m_periodMs = kMinPeriodMs;
+    }
+    m_setPeriodic(m_periodMs);
+  }
+
+  // see if this immediately subscribes to any topics
+  for (auto&& topic : m_server.m_topics) {
+    bool removed = false;
+    if (replace) {
+      removed = topic->subscribers.Remove(sub.get());
+    }
+
+    // is client already subscribed?
+    bool wasSubscribed = false;
+    for (auto subscriber : topic->subscribers) {
+      if (subscriber->client == this) {
+        wasSubscribed = true;
+        break;
+      }
+    }
+
+    bool added = false;
+    if (sub->Matches(topic->name, topic->special)) {
+      topic->subscribers.Add(sub.get());
+      added = true;
+    }
+
+    if (added ^ removed) {
+      m_server.UpdateMetaTopicSub(topic.get());
+    }
+
+    if (!wasSubscribed && added && !removed) {
+      // announce topic to client
+      DEBUG4("client {}: announce {}", m_id, topic->name);
+      SendAnnounce(topic.get(), std::nullopt);
+
+      // send last value
+      if (!sub->options.topicsOnly && topic->lastValue) {
+        DEBUG4("send last value for {} to client {}", topic->name, m_id);
+        SendValue(topic.get(), topic->lastValue, kSendAll);
+      }
+    }
+  }
+
+  // update meta data
+  UpdateMetaClientSub();
+
+  Flush();
+}
+
+void ClientData4Base::ClientUnsubscribe(int64_t subuid) {
+  DEBUG3("ClientUnsubscribe({}, {})", m_id, subuid);
+  auto subIt = m_subscribers.find(subuid);
+  if (subIt == m_subscribers.end() || !subIt->getSecond()) {
+    return;  // nothing to do
+  }
+  auto sub = subIt->getSecond().get();
+
+  // remove from topics
+  for (auto&& topic : m_server.m_topics) {
+    if (topic->subscribers.Remove(sub)) {
+      m_server.UpdateMetaTopicSub(topic.get());
+    }
+  }
+
+  // delete it from client (future value sets will be ignored)
+  m_subscribers.erase(subIt);
+  UpdateMetaClientSub();
+
+  // loop over all publishers to update period
+  m_periodMs = UINT32_MAX;
+  for (auto&& sub : m_subscribers) {
+    if (m_periodMs == UINT32_MAX) {
+      m_periodMs = sub.getSecond()->periodMs;
+    } else {
+      m_periodMs = std::gcd(m_periodMs, sub.getSecond()->periodMs);
+    }
+  }
+  if (m_periodMs < kMinPeriodMs) {
+    m_periodMs = kMinPeriodMs;
+  }
+  m_setPeriodic(m_periodMs);
+}
+
+void ClientData4Base::ClientSetValue(int64_t pubuid, const Value& value) {
+  DEBUG4("ClientSetValue({}, {})", m_id, pubuid);
+  auto publisherIt = m_publishers.find(pubuid);
+  if (publisherIt == m_publishers.end()) {
+    WARNING("unrecognized client {} pubuid {}, ignoring set", m_id, pubuid);
+    return;  // ignore unrecognized pubuids
+  }
+  auto topic = publisherIt->getSecond().get()->topic;
+  m_server.SetValue(this, topic, value);
+}
+
+void ClientDataLocal::SendValue(TopicData* topic, const Value& value,
+                                SendMode mode) {
+  if (m_server.m_local) {
+    m_server.m_local->NetworkSetValue(topic->localHandle, value);
+  }
+}
+
+void ClientDataLocal::SendAnnounce(TopicData* topic,
+                                   std::optional<int64_t> pubuid) {
+  if (m_server.m_local) {
+    auto& sent = m_announceSent[topic];
+    if (sent) {
+      return;
+    }
+    sent = true;
+
+    topic->localHandle = m_server.m_local->NetworkAnnounce(
+        topic->name, topic->typeStr, topic->properties, pubuid.value_or(0));
+  }
+}
+
+void ClientDataLocal::SendUnannounce(TopicData* topic) {
+  if (m_server.m_local) {
+    auto& sent = m_announceSent[topic];
+    if (!sent) {
+      return;
+    }
+    sent = false;
+    m_server.m_local->NetworkUnannounce(topic->name);
+  }
+}
+
+void ClientDataLocal::SendPropertiesUpdate(TopicData* topic,
+                                           const wpi::json& update, bool ack) {
+  if (m_server.m_local) {
+    if (!m_announceSent.lookup(topic)) {
+      return;
+    }
+    m_server.m_local->NetworkPropertiesUpdate(topic->name, update, ack);
+  }
+}
+
+void ClientDataLocal::HandleLocal(std::span<const ClientMessage> msgs) {
+  DEBUG4("HandleLocal()");
+  // just map as a normal client into client=0 calls
+  for (const auto& elem : msgs) {  // NOLINT
+    // common case is value, so check that first
+    if (auto msg = std::get_if<ClientValueMsg>(&elem.contents)) {
+      ClientSetValue(msg->pubHandle, msg->value);
+    } else if (auto msg = std::get_if<PublishMsg>(&elem.contents)) {
+      ClientPublish(msg->pubHandle, msg->name, msg->typeStr, msg->properties);
+    } else if (auto msg = std::get_if<UnpublishMsg>(&elem.contents)) {
+      ClientUnpublish(msg->pubHandle);
+    } else if (auto msg = std::get_if<SetPropertiesMsg>(&elem.contents)) {
+      ClientSetProperties(msg->name, msg->update);
+    } else if (auto msg = std::get_if<SubscribeMsg>(&elem.contents)) {
+      ClientSubscribe(msg->subHandle, msg->topicNames, msg->options);
+    } else if (auto msg = std::get_if<UnsubscribeMsg>(&elem.contents)) {
+      ClientUnsubscribe(msg->subHandle);
+    }
+  }
+}
+
+void ClientData4::ProcessIncomingText(std::string_view data) {
+  WireDecodeText(data, *this, m_logger);
+}
+
+void ClientData4::ProcessIncomingBinary(std::span<const uint8_t> data) {
+  for (;;) {
+    if (data.empty()) {
+      break;
+    }
+
+    // decode message
+    int64_t pubuid;
+    Value value;
+    std::string error;
+    if (!WireDecodeBinary(&data, &pubuid, &value, &error, 0)) {
+      m_wire.Disconnect(fmt::format("binary decode error: {}", error));
+      break;
+    }
+
+    // respond to RTT ping
+    if (pubuid == -1) {
+      auto now = wpi::Now();
+      DEBUG4("RTT ping from {}, responding with time={}", m_id, now);
+      {
+        auto out = m_wire.SendBinary();
+        WireEncodeBinary(out.Add(), -1, now, value);
+      }
+      m_wire.Flush();
+      continue;
+    }
+
+    // handle value set
+    ClientSetValue(pubuid, value);
+  }
+}
+
+void ClientData4::SendValue(TopicData* topic, const Value& value,
+                            SendMode mode) {
+  if (m_local) {
+    mode = ClientData::kSendImmNoFlush;  // always send local immediately
+  }
+  switch (mode) {
+    case ClientData::kSendDisabled:  // do nothing
+      break;
+    case ClientData::kSendImmNoFlush:  // send immediately
+      WriteBinary(topic->id, value.time(), value);
+      if (m_local) {
+        Flush();
+      }
+      break;
+    case ClientData::kSendAll:  // append to outgoing
+      m_outgoing.emplace_back(ServerMessage{ServerValueMsg{topic->id, value}});
+      break;
+    case ClientData::kSendNormal: {
+      // scan outgoing and replace, or append if not present
+      bool found = false;
+      for (auto&& msg : m_outgoing) {
+        if (auto m = std::get_if<ServerValueMsg>(&msg.contents)) {
+          if (m->topic == topic->id) {
+            m->value = value;
+            found = true;
+            break;
+          }
+        }
+      }
+      if (!found) {
+        m_outgoing.emplace_back(
+            ServerMessage{ServerValueMsg{topic->id, value}});
+      }
+      break;
+    }
+  }
+}
+
+void ClientData4::SendAnnounce(TopicData* topic,
+                               std::optional<int64_t> pubuid) {
+  auto& sent = m_announceSent[topic];
+  if (sent) {
+    return;
+  }
+  sent = true;
+
+  if (m_local) {
+    WireEncodeAnnounce(SendText().Add(), topic->name, topic->id, topic->typeStr,
+                       topic->properties, pubuid);
+    Flush();
+  } else {
+    m_outgoing.emplace_back(ServerMessage{AnnounceMsg{
+        topic->name, topic->id, topic->typeStr, pubuid, topic->properties}});
+    m_server.m_controlReady = true;
+  }
+}
+
+void ClientData4::SendUnannounce(TopicData* topic) {
+  auto& sent = m_announceSent[topic];
+  if (!sent) {
+    return;
+  }
+  sent = false;
+
+  if (m_local) {
+    WireEncodeUnannounce(SendText().Add(), topic->name, topic->id);
+    Flush();
+  } else {
+    m_outgoing.emplace_back(
+        ServerMessage{UnannounceMsg{topic->name, topic->id}});
+    m_server.m_controlReady = true;
+  }
+}
+
+void ClientData4::SendPropertiesUpdate(TopicData* topic,
+                                       const wpi::json& update, bool ack) {
+  if (!m_announceSent.lookup(topic)) {
+    return;
+  }
+
+  if (m_local) {
+    WireEncodePropertiesUpdate(SendText().Add(), topic->name, update, ack);
+    Flush();
+  } else {
+    m_outgoing.emplace_back(
+        ServerMessage{PropertiesUpdateMsg{topic->name, update, ack}});
+    m_server.m_controlReady = true;
+  }
+}
+
+void ClientData4::SendOutgoing(uint64_t curTimeMs) {
+  if (m_outgoing.empty()) {
+    return;  // nothing to do
+  }
+
+  // rate limit frequency of transmissions
+  if (curTimeMs < (m_lastSendMs + kMinPeriodMs)) {
+    return;
+  }
+
+  if (!m_wire.Ready()) {
+    ++m_notReadyCount;
+    if (m_notReadyCount > kWireMaxNotReady) {
+      m_wire.Disconnect("transmit stalled");
+    }
+    return;
+  }
+  m_notReadyCount = 0;
+
+  for (auto&& msg : m_outgoing) {
+    if (auto m = std::get_if<ServerValueMsg>(&msg.contents)) {
+      WriteBinary(m->topic, m->value.time(), m->value);
+    } else {
+      WireEncodeText(SendText().Add(), msg);
+    }
+  }
+  m_outgoing.resize(0);
+  m_lastSendMs = curTimeMs;
+}
+
+void ClientData4::Flush() {
+  m_outText.reset();
+  m_outBinary.reset();
+  m_wire.Flush();
+}
+
+bool ClientData3::TopicData3::UpdateFlags(TopicData* topic) {
+  unsigned int newFlags = topic->persistent ? NT_PERSISTENT : 0;
+  bool updated = flags != newFlags;
+  flags = newFlags;
+  return updated;
+}
+
+void ClientData3::ProcessIncomingBinary(std::span<const uint8_t> data) {
+  if (!m_decoder.Execute(&data)) {
+    m_wire.Disconnect(m_decoder.GetError());
+  }
+}
+
+void ClientData3::SendValue(TopicData* topic, const Value& value,
+                            SendMode mode) {
+  if (m_state != kStateRunning) {
+    if (mode == kSendImmNoFlush) {
+      mode = kSendAll;
+    }
+  } else if (m_local) {
+    mode = ClientData::kSendImmNoFlush;  // always send local immediately
+  }
+  TopicData3* topic3 = GetTopic3(topic);
+
+  switch (mode) {
+    case ClientData::kSendDisabled:  // do nothing
+      break;
+    case ClientData::kSendImmNoFlush:  // send immediately and flush
+      ++topic3->seqNum;
+      if (topic3->sentAssign) {
+        net3::WireEncodeEntryUpdate(m_wire.Send().stream(), topic->id,
+                                    topic3->seqNum.value(), value);
+      } else {
+        net3::WireEncodeEntryAssign(m_wire.Send().stream(), topic->name,
+                                    topic->id, topic3->seqNum.value(), value,
+                                    topic3->flags);
+        topic3->sentAssign = true;
+      }
+      if (m_local) {
+        Flush();
+      }
+      break;
+    case ClientData::kSendNormal: {
+      // scan outgoing and replace, or append if not present
+      bool found = false;
+      for (auto&& msg : m_outgoing) {
+        if (msg.Is(net3::Message3::kEntryUpdate) ||
+            msg.Is(net3::Message3::kEntryAssign)) {
+          if (msg.id() == topic->id) {
+            msg.SetValue(value);
+            found = true;
+            break;
+          }
+        }
+      }
+      if (found) {
+        break;
+      }
+    }
+      // fallthrough
+    case ClientData::kSendAll:  // append to outgoing
+      ++topic3->seqNum;
+      if (topic3->sentAssign) {
+        m_outgoing.emplace_back(net3::Message3::EntryUpdate(
+            topic->id, topic3->seqNum.value(), value));
+      } else {
+        m_outgoing.emplace_back(net3::Message3::EntryAssign(
+            topic->name, topic->id, topic3->seqNum.value(), value,
+            topic3->flags));
+        topic3->sentAssign = true;
+      }
+      break;
+  }
+}
+
+void ClientData3::SendAnnounce(TopicData* topic,
+                               std::optional<int64_t> pubuid) {
+  // ignore if we've not yet built the subscriber
+  if (m_subscribers.empty()) {
+    return;
+  }
+
+  // subscribe to all non-special topics
+  if (!topic->special) {
+    topic->subscribers.Add(m_subscribers[0].get());
+    m_server.UpdateMetaTopicSub(topic);
+  }
+
+  // NT3 requires a value to send the assign message, so the assign message
+  // will get sent when the first value is sent (by SendValue).
+}
+
+void ClientData3::SendUnannounce(TopicData* topic) {
+  auto it = m_topics3.find(topic);
+  if (it == m_topics3.end()) {
+    return;  // never sent to client
+  }
+  bool sentAssign = it->second.sentAssign;
+  m_topics3.erase(it);
+  if (!sentAssign) {
+    return;  // never sent to client
+  }
+
+  // map to NT3 delete message
+  if (m_local && m_state == kStateRunning) {
+    net3::WireEncodeEntryDelete(m_wire.Send().stream(), topic->id);
+    Flush();
+  } else {
+    m_outgoing.emplace_back(net3::Message3::EntryDelete(topic->id));
+  }
+}
+
+void ClientData3::SendPropertiesUpdate(TopicData* topic,
+                                       const wpi::json& update, bool ack) {
+  if (ack) {
+    return;  // we don't ack in NT3
+  }
+  auto it = m_topics3.find(topic);
+  if (it == m_topics3.end()) {
+    return;  // never sent to client
+  }
+  TopicData3* topic3 = &it->second;
+  // Don't send flags update unless we've already sent an assign message.
+  // The assign message will contain the updated flags when we eventually
+  // send it.
+  if (topic3->UpdateFlags(topic) && topic3->sentAssign) {
+    if (m_local && m_state == kStateRunning) {
+      net3::WireEncodeFlagsUpdate(m_wire.Send().stream(), topic->id,
+                                  topic3->flags);
+      Flush();
+    } else {
+      m_outgoing.emplace_back(
+          net3::Message3::FlagsUpdate(topic->id, topic3->flags));
+    }
+  }
+}
+
+void ClientData3::SendOutgoing(uint64_t curTimeMs) {
+  if (m_outgoing.empty() || m_state != kStateRunning) {
+    return;  // nothing to do
+  }
+
+  // rate limit frequency of transmissions
+  if (curTimeMs < (m_lastSendMs + kMinPeriodMs)) {
+    return;
+  }
+
+  if (!m_wire.Ready()) {
+    ++m_notReadyCount;
+    if (m_notReadyCount > kWireMaxNotReady) {
+      m_wire.Disconnect("transmit stalled");
+    }
+    return;
+  }
+  m_notReadyCount = 0;
+
+  auto out = m_wire.Send();
+  for (auto&& msg : m_outgoing) {
+    net3::WireEncode(out.stream(), msg);
+  }
+  m_outgoing.resize(0);
+  m_lastSendMs = curTimeMs;
+}
+
+void ClientData3::KeepAlive() {
+  DEBUG4("KeepAlive({})", m_id);
+  if (m_state != kStateRunning) {
+    m_decoder.SetError("received unexpected KeepAlive message");
+    return;
+  }
+  // ignore
+}
+
+void ClientData3::ServerHelloDone() {
+  DEBUG4("ServerHelloDone({})", m_id);
+  m_decoder.SetError("received unexpected ServerHelloDone message");
+}
+
+void ClientData3::ClientHelloDone() {
+  DEBUG4("ClientHelloDone({})", m_id);
+  if (m_state != kStateServerHelloComplete) {
+    m_decoder.SetError("received unexpected ClientHelloDone message");
+    return;
+  }
+  m_state = kStateRunning;
+}
+
+void ClientData3::ClearEntries() {
+  DEBUG4("ClearEntries({})", m_id);
+  if (m_state != kStateRunning) {
+    m_decoder.SetError("received unexpected ClearEntries message");
+    return;
+  }
+
+  for (auto topic3it : m_topics3) {
+    TopicData* topic = topic3it.first;
+
+    // make sure we send assign the next time
+    topic3it.second.sentAssign = false;
+
+    // unpublish from this client (if it was previously published)
+    if (topic3it.second.published) {
+      topic3it.second.published = false;
+      auto publisherIt = m_publishers.find(topic3it.second.pubuid);
+      if (publisherIt != m_publishers.end()) {
+        // remove publisher from topic
+        topic->publishers.Remove(publisherIt->second.get());
+
+        // remove publisher from client
+        m_publishers.erase(publisherIt);
+
+        // update meta data
+        m_server.UpdateMetaTopicPub(topic);
+        UpdateMetaClientPub();
+      }
+    }
+
+    // set retained=false
+    m_server.SetProperties(this, topic, {{"retained", false}});
+  }
+}
+
+void ClientData3::ProtoUnsup(unsigned int proto_rev) {
+  DEBUG4("ProtoUnsup({})", m_id);
+  m_decoder.SetError("received unexpected ProtoUnsup message");
+}
+
+void ClientData3::ClientHello(std::string_view self_id,
+                              unsigned int proto_rev) {
+  DEBUG4("ClientHello({}, '{}', {:04x})", m_id, self_id, proto_rev);
+  if (m_state != kStateInitial) {
+    m_decoder.SetError("received unexpected ClientHello message");
+    return;
+  }
+  if (proto_rev != 0x0300) {
+    net3::WireEncodeProtoUnsup(m_wire.Send().stream(), 0x0300);
+    Flush();
+    m_decoder.SetError(
+        fmt::format("unsupported protocol version {:04x}", proto_rev));
+    return;
+  }
+  // create a unique name (just ignore provided client id)
+  m_name = fmt::format("NT3@{}", m_connInfo);
+  m_connected(m_name, 0x0300);
+  m_connected = nullptr;  // no longer required
+
+  // create client meta topics
+  m_metaPub = m_server.CreateMetaTopic(fmt::format("$clientpub${}", m_name));
+  m_metaSub = m_server.CreateMetaTopic(fmt::format("$clientsub${}", m_name));
+
+  // subscribe and send initial assignments
+  auto& sub = m_subscribers[0];
+  std::string prefix;
+  PubSubOptions options;
+  options.prefixMatch = true;
+  sub = std::make_unique<SubscriberData>(
+      this, std::span<const std::string>{{prefix}}, 0, options);
+  m_periodMs = std::gcd(m_periodMs, sub->periodMs);
+  if (m_periodMs < kMinPeriodMs) {
+    m_periodMs = kMinPeriodMs;
+  }
+  m_setPeriodic(m_periodMs);
+
+  {
+    auto out = m_wire.Send();
+    net3::WireEncodeServerHello(out.stream(), 0, "server");
+    for (auto&& topic : m_server.m_topics) {
+      if (topic && !topic->special && topic->IsPublished() &&
+          topic->lastValue) {
+        DEBUG4("client {}: initial announce of '{}' (id {})", m_id, topic->name,
+               topic->id);
+        topic->subscribers.Add(sub.get());
+        m_server.UpdateMetaTopicSub(topic.get());
+
+        TopicData3* topic3 = GetTopic3(topic.get());
+        ++topic3->seqNum;
+        net3::WireEncodeEntryAssign(out.stream(), topic->name, topic->id,
+                                    topic3->seqNum.value(), topic->lastValue,
+                                    topic3->flags);
+        topic3->sentAssign = true;
+      }
+    }
+    net3::WireEncodeServerHelloDone(out.stream());
+  }
+  Flush();
+  m_state = kStateServerHelloComplete;
+
+  // update meta topics
+  UpdateMetaClientPub();
+  UpdateMetaClientSub();
+}
+
+void ClientData3::ServerHello(unsigned int flags, std::string_view self_id) {
+  DEBUG4("ServerHello({}, {}, {})", m_id, flags, self_id);
+  m_decoder.SetError("received unexpected ServerHello message");
+}
+
+void ClientData3::EntryAssign(std::string_view name, unsigned int id,
+                              unsigned int seq_num, const Value& value,
+                              unsigned int flags) {
+  DEBUG4("EntryAssign({}, {}, {}, {}, {})", m_id, id, seq_num,
+         static_cast<int>(value.type()), flags);
+  if (id != 0xffff) {
+    DEBUG3("ignored EntryAssign from {} with non-0xffff id {}", m_id, id);
+    return;
+  }
+
+  // convert from NT3 info
+  auto typeStr = TypeToString(value.type());
+  wpi::json properties = wpi::json::object();
+  properties["retained"] = true;  // treat all NT3 published topics as retained
+  if ((flags & NT_PERSISTENT) != 0) {
+    properties["persistent"] = true;
+  }
+
+  // create topic
+  auto topic = m_server.CreateTopic(this, name, typeStr, properties);
+  TopicData3* topic3 = GetTopic3(topic);
+  if (topic3->published || topic3->sentAssign) {
+    WARNING("ignorning client {} duplicate publish of '{}'", m_id, name);
+    return;
+  }
+  ++topic3->seqNum;
+  topic3->published = true;
+  topic3->pubuid = m_nextPubUid++;
+  topic3->sentAssign = true;
+
+  // create publisher
+  auto [publisherIt, isNew] = m_publishers.try_emplace(
+      topic3->pubuid,
+      std::make_unique<PublisherData>(this, topic, topic3->pubuid));
+  if (!isNew) {
+    return;  // shouldn't happen, but just in case...
+  }
+
+  // add publisher to topic
+  topic->publishers.Add(publisherIt->getSecond().get());
+
+  // update meta data
+  m_server.UpdateMetaTopicPub(topic);
+  UpdateMetaClientPub();
+
+  // acts as an announce + data update
+  SendAnnounce(topic, topic3->pubuid);
+  m_server.SetValue(this, topic, value);
+
+  // respond with assign message with assigned topic ID
+  if (m_local && m_state == kStateRunning) {
+    net3::WireEncodeEntryAssign(m_wire.Send().stream(), topic->name, topic->id,
+                                topic3->seqNum.value(), value, topic3->flags);
+  } else {
+    m_outgoing.emplace_back(net3::Message3::EntryAssign(
+        topic->name, topic->id, topic3->seqNum.value(), value, topic3->flags));
+  }
+}
+
+void ClientData3::EntryUpdate(unsigned int id, unsigned int seq_num,
+                              const Value& value) {
+  DEBUG4("EntryUpdate({}, {}, {}, {})", m_id, id, seq_num,
+         static_cast<int>(value.type()));
+  if (m_state != kStateRunning) {
+    m_decoder.SetError("received unexpected EntryUpdate message");
+    return;
+  }
+
+  if (id >= m_server.m_topics.size()) {
+    DEBUG3("ignored EntryUpdate from {} on non-existent topic {}", m_id, id);
+    return;
+  }
+  TopicData* topic = m_server.m_topics[id].get();
+  if (!topic || !topic->IsPublished()) {
+    DEBUG3("ignored EntryUpdate from {} on non-existent topic {}", m_id, id);
+    return;
+  }
+
+  TopicData3* topic3 = GetTopic3(topic);
+  if (!topic3->published) {
+    topic3->published = true;
+    topic3->pubuid = m_nextPubUid++;
+
+    // create publisher
+    auto [publisherIt, isNew] = m_publishers.try_emplace(
+        topic3->pubuid,
+        std::make_unique<PublisherData>(this, topic, topic3->pubuid));
+    if (isNew) {
+      // add publisher to topic
+      topic->publishers.Add(publisherIt->getSecond().get());
+
+      // update meta data
+      m_server.UpdateMetaTopicPub(topic);
+      UpdateMetaClientPub();
+    }
+  }
+  topic3->seqNum = net3::SequenceNumber{seq_num};
+
+  m_server.SetValue(this, topic, value);
+}
+
+void ClientData3::FlagsUpdate(unsigned int id, unsigned int flags) {
+  DEBUG4("FlagsUpdate({}, {}, {})", m_id, id, flags);
+  if (m_state != kStateRunning) {
+    m_decoder.SetError("received unexpected FlagsUpdate message");
+    return;
+  }
+  if (id >= m_server.m_topics.size()) {
+    DEBUG3("ignored FlagsUpdate from {} on non-existent topic {}", m_id, id);
+    return;
+  }
+  TopicData* topic = m_server.m_topics[id].get();
+  if (!topic || !topic->IsPublished()) {
+    DEBUG3("ignored FlagsUpdate from {} on non-existent topic {}", m_id, id);
+    return;
+  }
+  if (topic->special) {
+    DEBUG3("ignored FlagsUpdate from {} on special topic {}", m_id, id);
+    return;
+  }
+  m_server.SetFlags(this, topic, flags);
+}
+
+void ClientData3::EntryDelete(unsigned int id) {
+  DEBUG4("EntryDelete({}, {})", m_id, id);
+  if (m_state != kStateRunning) {
+    m_decoder.SetError("received unexpected EntryDelete message");
+    return;
+  }
+  if (id >= m_server.m_topics.size()) {
+    DEBUG3("ignored EntryDelete from {} on non-existent topic {}", m_id, id);
+    return;
+  }
+  TopicData* topic = m_server.m_topics[id].get();
+  if (!topic || !topic->IsPublished()) {
+    DEBUG3("ignored EntryDelete from {} on non-existent topic {}", m_id, id);
+    return;
+  }
+  if (topic->special) {
+    DEBUG3("ignored EntryDelete from {} on special topic {}", m_id, id);
+    return;
+  }
+
+  auto topic3it = m_topics3.find(topic);
+  if (topic3it != m_topics3.end()) {
+    // make sure we send assign the next time
+    topic3it->second.sentAssign = false;
+
+    // unpublish from this client (if it was previously published)
+    if (topic3it->second.published) {
+      topic3it->second.published = false;
+      auto publisherIt = m_publishers.find(topic3it->second.pubuid);
+      if (publisherIt != m_publishers.end()) {
+        // remove publisher from topic
+        topic->publishers.Remove(publisherIt->second.get());
+
+        // remove publisher from client
+        m_publishers.erase(publisherIt);
+
+        // update meta data
+        m_server.UpdateMetaTopicPub(topic);
+        UpdateMetaClientPub();
+      }
+    }
+  }
+
+  // set retained=false
+  m_server.SetProperties(this, topic, {{"retained", false}});
+}
+
+bool TopicData::SetProperties(const wpi::json& update) {
+  if (!update.is_object()) {
+    return false;
+  }
+  bool updated = false;
+  for (auto&& elem : update.items()) {
+    if (elem.value().is_null()) {
+      properties.erase(elem.key());
+    } else {
+      properties[elem.key()] = elem.value();
+    }
+    updated = true;
+  }
+  if (updated) {
+    RefreshProperties();
+  }
+  return updated;
+}
+
+void TopicData::RefreshProperties() {
+  persistent = false;
+  retained = false;
+
+  auto persistentIt = properties.find("persistent");
+  if (persistentIt != properties.end()) {
+    if (auto val = persistentIt->get_ptr<bool*>()) {
+      persistent = *val;
+    }
+  }
+
+  auto retainedIt = properties.find("retained");
+  if (retainedIt != properties.end()) {
+    if (auto val = retainedIt->get_ptr<bool*>()) {
+      retained = *val;
+    }
+  }
+}
+
+bool TopicData::SetFlags(unsigned int flags_) {
+  bool updated;
+  if ((flags_ & NT_PERSISTENT) != 0) {
+    updated = !persistent;
+    persistent = true;
+    properties["persistent"] = true;
+  } else {
+    updated = persistent;
+    persistent = false;
+    properties.erase("persistent");
+  }
+  return updated;
+}
+
+bool SubscriberData::Matches(std::string_view name, bool special) {
+  for (auto&& topicName : topicNames) {
+    if ((!options.prefixMatch && name == topicName) ||
+        (options.prefixMatch && (!special || !topicName.empty()) &&
+         wpi::starts_with(name, topicName))) {
+      return true;
+    }
+  }
+  return false;
+}
+
+SImpl::SImpl(wpi::Logger& logger) : m_logger{logger} {
+  // local is client 0
+  m_clients.emplace_back(std::make_unique<ClientDataLocal>(*this, 0, logger));
+  m_localClient = static_cast<ClientDataLocal*>(m_clients.back().get());
+}
+
+std::pair<std::string, int> SImpl::AddClient(
+    std::string_view name, std::string_view connInfo, bool local,
+    WireConnection& wire, ServerImpl::SetPeriodicFunc setPeriodic) {
+  // strip anything after @ in the name
+  name = wpi::split(name, '@').first;
+  if (name.empty()) {
+    name = "NT4";
+  }
+  size_t index = m_clients.size();
+  // find an empty slot and check for duplicates
+  // just do a linear search as number of clients is typically small (<10)
+  int duplicateName = 0;
+  for (size_t i = 0, end = index; i < end; ++i) {
+    auto& clientData = m_clients[i];
+    if (clientData && clientData->GetOriginalName() == name) {
+      ++duplicateName;
+    } else if (!clientData && index == end) {
+      index = i;
+    }
+  }
+  if (index == m_clients.size()) {
+    m_clients.emplace_back();
+  }
+
+  // if duplicate name, de-duplicate
+  std::string dedupName;
+  if (duplicateName > 0) {
+    dedupName = fmt::format("{}@{}", name, duplicateName);
+  } else {
+    dedupName = name;
+  }
+
+  auto& clientData = m_clients[index];
+  clientData = std::make_unique<ClientData4>(name, dedupName, connInfo, local,
+                                             wire, std::move(setPeriodic),
+                                             *this, index, m_logger);
+
+  // create client meta topics
+  clientData->m_metaPub =
+      CreateMetaTopic(fmt::format("$clientpub${}", dedupName));
+  clientData->m_metaSub =
+      CreateMetaTopic(fmt::format("$clientsub${}", dedupName));
+
+  // update meta topics
+  clientData->UpdateMetaClientPub();
+  clientData->UpdateMetaClientSub();
+
+  wire.Flush();
+
+  DEBUG3("AddClient('{}', '{}') -> {}", name, connInfo, index);
+  return {std::move(dedupName), index};
+}
+
+int SImpl::AddClient3(std::string_view connInfo, bool local,
+                      net3::WireConnection3& wire,
+                      ServerImpl::Connected3Func connected,
+                      ServerImpl::SetPeriodicFunc setPeriodic) {
+  size_t index = m_clients.size();
+  // find an empty slot; we can't check for duplicates until we get a hello.
+  // just do a linear search as number of clients is typically small (<10)
+  for (size_t i = 0, end = index; i < end; ++i) {
+    if (!m_clients[i]) {
+      index = i;
+      break;
+    }
+  }
+  if (index == m_clients.size()) {
+    m_clients.emplace_back();
+  }
+
+  m_clients[index] = std::make_unique<ClientData3>(
+      connInfo, local, wire, std::move(connected), std::move(setPeriodic),
+      *this, index, m_logger);
+
+  DEBUG3("AddClient3('{}') -> {}", connInfo, index);
+  return index;
+}
+
+void SImpl::RemoveClient(int clientId) {
+  DEBUG3("RemoveClient({})", clientId);
+  auto& client = m_clients[clientId];
+
+  // remove all publishers and subscribers for this client
+  wpi::SmallVector<TopicData*, 16> toDelete;
+  for (auto&& topic : m_topics) {
+    auto pubRemove =
+        std::remove_if(topic->publishers.begin(), topic->publishers.end(),
+                       [&](auto&& e) { return e->client == client.get(); });
+    bool pubChanged = pubRemove != topic->publishers.end();
+    topic->publishers.erase(pubRemove, topic->publishers.end());
+
+    auto subRemove =
+        std::remove_if(topic->subscribers.begin(), topic->subscribers.end(),
+                       [&](auto&& e) { return e->client == client.get(); });
+    bool subChanged = subRemove != topic->subscribers.end();
+    topic->subscribers.erase(subRemove, topic->subscribers.end());
+
+    if (!topic->IsPublished()) {
+      toDelete.push_back(topic.get());
+    } else {
+      if (pubChanged) {
+        UpdateMetaTopicPub(topic.get());
+      }
+      if (subChanged) {
+        UpdateMetaTopicSub(topic.get());
+      }
+    }
+  }
+
+  // delete unpublished topics
+  for (auto topic : toDelete) {
+    DeleteTopic(topic);
+  }
+  DeleteTopic(client->m_metaPub);
+  DeleteTopic(client->m_metaSub);
+
+  // delete the client
+  client.reset();
+}
+
+bool SImpl::PersistentChanged() {
+  bool rv = m_persistentChanged;
+  m_persistentChanged = false;
+  return rv;
+}
+
+static void DumpValue(wpi::raw_ostream& os, const Value& value,
+                      wpi::json::serializer& s) {
+  switch (value.type()) {
+    case NT_BOOLEAN:
+      if (value.GetBoolean()) {
+        os << "true";
+      } else {
+        os << "false";
+      }
+      break;
+    case NT_DOUBLE:
+      s.dump_float(value.GetDouble());
+      break;
+    case NT_FLOAT:
+      s.dump_float(value.GetFloat());
+      break;
+    case NT_INTEGER:
+      s.dump_integer(value.GetInteger());
+      break;
+    case NT_STRING:
+      os << '"';
+      s.dump_escaped(value.GetString(), false);
+      os << '"';
+      break;
+    case NT_RAW:
+    case NT_RPC:
+      os << '"';
+      wpi::Base64Encode(os, value.GetRaw());
+      os << '"';
+      break;
+    case NT_BOOLEAN_ARRAY: {
+      os << '[';
+      bool first = true;
+      for (auto v : value.GetBooleanArray()) {
+        if (first) {
+          first = false;
+        } else {
+          os << ", ";
+        }
+        if (v) {
+          os << "true";
+        } else {
+          os << "false";
+        }
+      }
+      os << ']';
+      break;
+    }
+    case NT_DOUBLE_ARRAY: {
+      os << '[';
+      bool first = true;
+      for (auto v : value.GetDoubleArray()) {
+        if (first) {
+          first = false;
+        } else {
+          os << ", ";
+        }
+        s.dump_float(v);
+      }
+      os << ']';
+      break;
+    }
+    case NT_FLOAT_ARRAY: {
+      os << '[';
+      bool first = true;
+      for (auto v : value.GetFloatArray()) {
+        if (first) {
+          first = false;
+        } else {
+          os << ", ";
+        }
+        s.dump_float(v);
+      }
+      os << ']';
+      break;
+    }
+    case NT_INTEGER_ARRAY: {
+      os << '[';
+      bool first = true;
+      for (auto v : value.GetIntegerArray()) {
+        if (first) {
+          first = false;
+        } else {
+          os << ", ";
+        }
+        s.dump_integer(v);
+      }
+      os << ']';
+      break;
+    }
+    case NT_STRING_ARRAY: {
+      os << '[';
+      bool first = true;
+      for (auto&& v : value.GetStringArray()) {
+        if (first) {
+          first = false;
+        } else {
+          os << ", ";
+        }
+        os << '"';
+        s.dump_escaped(v, false);
+        os << '"';
+      }
+      os << ']';
+      break;
+    }
+    default:
+      os << "null";
+      break;
+  }
+}
+
+void SImpl::DumpPersistent(wpi::raw_ostream& os) {
+  wpi::json::serializer s{os, ' ', 16};
+  os << "[\n";
+  bool first = true;
+  for (const auto& topic : m_topics) {
+    if (!topic->persistent || !topic->lastValue) {
+      continue;
+    }
+    if (first) {
+      first = false;
+    } else {
+      os << ",\n";
+    }
+    os << "  {\n    \"name\": \"";
+    s.dump_escaped(topic->name, false);
+    os << "\",\n    \"type\": \"";
+    s.dump_escaped(topic->typeStr, false);
+    os << "\",\n    \"value\": ";
+    DumpValue(os, topic->lastValue, s);
+    os << ",\n    \"properties\": ";
+    s.dump(topic->properties, true, false, 2, 4);
+    os << "\n  }";
+  }
+  os << "\n]\n";
+}
+
+static std::string* ObjGetString(wpi::json::object_t& obj, std::string_view key,
+                                 std::string* error) {
+  auto it = obj.find(key);
+  if (it == obj.end()) {
+    *error = fmt::format("no {} key", key);
+    return nullptr;
+  }
+  auto val = it->second.get_ptr<std::string*>();
+  if (!val) {
+    *error = fmt::format("{} must be a string", key);
+  }
+  return val;
+}
+
+std::string SImpl::LoadPersistent(std::string_view in) {
+  if (in.empty()) {
+    return {};
+  }
+
+  wpi::json j;
+  try {
+    j = wpi::json::parse(in);
+  } catch (wpi::json::parse_error& err) {
+    return fmt::format("could not decode JSON: {}", err.what());
+  }
+
+  if (!j.is_array()) {
+    return "expected JSON array at top level";
+  }
+
+  bool persistentChanged = m_persistentChanged;
+
+  std::string allerrors;
+  int i = -1;
+  auto time = nt::Now();
+  for (auto&& jitem : j) {
+    ++i;
+    std::string error;
+    {
+      auto obj = jitem.get_ptr<wpi::json::object_t*>();
+      if (!obj) {
+        error = "expected item to be an object";
+        goto err;
+      }
+
+      // name
+      auto name = ObjGetString(*obj, "name", &error);
+      if (!name) {
+        goto err;
+      }
+
+      // type
+      auto typeStr = ObjGetString(*obj, "type", &error);
+      if (!typeStr) {
+        goto err;
+      }
+
+      // properties
+      auto propsIt = obj->find("properties");
+      if (propsIt == obj->end()) {
+        error = "no properties key";
+        goto err;
+      }
+      auto& props = propsIt->second;
+      if (!props.is_object()) {
+        error = "properties must be an object";
+        goto err;
+      }
+
+      // check to make sure persistent property is set
+      auto persistentIt = props.find("persistent");
+      if (persistentIt == props.end()) {
+        error = "no persistent property";
+        goto err;
+      }
+      if (auto v = persistentIt->get_ptr<bool*>()) {
+        if (!*v) {
+          error = "persistent property is false";
+          goto err;
+        }
+      } else {
+        error = "persistent property is not boolean";
+        goto err;
+      }
+
+      // value
+      auto valueIt = obj->find("value");
+      if (valueIt == obj->end()) {
+        error = "no value key";
+        goto err;
+      }
+      Value value;
+      if (*typeStr == "boolean") {
+        if (auto v = valueIt->second.get_ptr<bool*>()) {
+          value = Value::MakeBoolean(*v, time);
+        } else {
+          error = "value type mismatch, expected boolean";
+          goto err;
+        }
+      } else if (*typeStr == "int") {
+        if (auto v = valueIt->second.get_ptr<int64_t*>()) {
+          value = Value::MakeInteger(*v, time);
+        } else if (auto v = valueIt->second.get_ptr<uint64_t*>()) {
+          value = Value::MakeInteger(*v, time);
+        } else {
+          error = "value type mismatch, expected int";
+          goto err;
+        }
+      } else if (*typeStr == "float") {
+        if (auto v = valueIt->second.get_ptr<double*>()) {
+          value = Value::MakeFloat(*v, time);
+        } else {
+          error = "value type mismatch, expected float";
+          goto err;
+        }
+      } else if (*typeStr == "double") {
+        if (auto v = valueIt->second.get_ptr<double*>()) {
+          value = Value::MakeDouble(*v, time);
+        } else {
+          error = "value type mismatch, expected double";
+          goto err;
+        }
+      } else if (*typeStr == "string" || *typeStr == "json") {
+        if (auto v = valueIt->second.get_ptr<std::string*>()) {
+          value = Value::MakeString(*v, time);
+        } else {
+          error = "value type mismatch, expected string";
+          goto err;
+        }
+      } else if (*typeStr == "boolean[]") {
+        auto arr = valueIt->second.get_ptr<wpi::json::array_t*>();
+        if (!arr) {
+          error = "value type mismatch, expected array";
+          goto err;
+        }
+        std::vector<int> elems;
+        for (auto&& jelem : valueIt->second) {
+          if (auto v = jelem.get_ptr<bool*>()) {
+            elems.push_back(*v);
+          } else {
+            error = "value type mismatch, expected boolean";
+          }
+        }
+        value = Value::MakeBooleanArray(elems, time);
+      } else if (*typeStr == "int[]") {
+        auto arr = valueIt->second.get_ptr<wpi::json::array_t*>();
+        if (!arr) {
+          error = "value type mismatch, expected array";
+          goto err;
+        }
+        std::vector<int64_t> elems;
+        for (auto&& jelem : valueIt->second) {
+          if (auto v = jelem.get_ptr<int64_t*>()) {
+            elems.push_back(*v);
+          } else if (auto v = jelem.get_ptr<uint64_t*>()) {
+            elems.push_back(*v);
+          } else {
+            error = "value type mismatch, expected int";
+          }
+        }
+        value = Value::MakeIntegerArray(elems, time);
+      } else if (*typeStr == "double[]") {
+        auto arr = valueIt->second.get_ptr<wpi::json::array_t*>();
+        if (!arr) {
+          error = "value type mismatch, expected array";
+          goto err;
+        }
+        std::vector<double> elems;
+        for (auto&& jelem : valueIt->second) {
+          if (auto v = jelem.get_ptr<double*>()) {
+            elems.push_back(*v);
+          } else {
+            error = "value type mismatch, expected double";
+          }
+        }
+        value = Value::MakeDoubleArray(elems, time);
+      } else if (*typeStr == "float[]") {
+        auto arr = valueIt->second.get_ptr<wpi::json::array_t*>();
+        if (!arr) {
+          error = "value type mismatch, expected array";
+          goto err;
+        }
+        std::vector<float> elems;
+        for (auto&& jelem : valueIt->second) {
+          if (auto v = jelem.get_ptr<double*>()) {
+            elems.push_back(*v);
+          } else {
+            error = "value type mismatch, expected float";
+          }
+        }
+        value = Value::MakeFloatArray(elems, time);
+      } else if (*typeStr == "string[]") {
+        auto arr = valueIt->second.get_ptr<wpi::json::array_t*>();
+        if (!arr) {
+          error = "value type mismatch, expected array";
+          goto err;
+        }
+        std::vector<std::string> elems;
+        for (auto&& jelem : valueIt->second) {
+          if (auto v = jelem.get_ptr<std::string*>()) {
+            elems.emplace_back(*v);
+          } else {
+            error = "value type mismatch, expected string";
+          }
+        }
+        value = Value::MakeStringArray(std::move(elems), time);
+      } else {
+        // raw
+        if (auto v = valueIt->second.get_ptr<std::string*>()) {
+          std::vector<uint8_t> data;
+          wpi::Base64Decode(*v, &data);
+          value = Value::MakeRaw(std::move(data), time);
+        } else {
+          error = "value type mismatch, expected string";
+          goto err;
+        }
+      }
+
+      // create persistent topic
+      auto topic = CreateTopic(nullptr, *name, *typeStr, props);
+
+      // set value
+      SetValue(nullptr, topic, value);
+
+      continue;
+    }
+  err:
+    allerrors += fmt::format("{}: {}\n", i, error);
+  }
+
+  m_persistentChanged = persistentChanged;  // restore flag
+
+  return allerrors;
+}
+
+TopicData* SImpl::CreateTopic(ClientData* client, std::string_view name,
+                              std::string_view typeStr,
+                              const wpi::json& properties, bool special) {
+  auto& topic = m_nameTopics[name];
+  if (topic) {
+    if (typeStr != topic->typeStr) {
+      if (client) {
+        WARNING("client {} publish '{}' conflicting type '{}' (currently '{}')",
+                client->GetName(), name, typeStr, topic->typeStr);
+      }
+    }
+  } else {
+    // new topic
+    unsigned int id = m_topics.emplace_back(
+        std::make_unique<TopicData>(name, typeStr, properties));
+    topic = m_topics[id].get();
+    topic->id = id;
+    topic->special = special;
+
+    for (auto&& aClient : m_clients) {
+      if (!aClient) {
+        continue;
+      }
+
+      // look for subscriber matching prefixes
+      wpi::SmallVector<SubscriberData*, 16> subscribersBuf;
+      auto subscribers =
+          aClient->GetSubscribers(name, topic->special, subscribersBuf);
+      for (auto subscriber : subscribers) {
+        topic->subscribers.Add(subscriber);
+      }
+
+      // don't announce to this client if no subscribers
+      if (subscribers.empty()) {
+        continue;
+      }
+
+      if (aClient.get() == client) {
+        continue;  // don't announce to requesting client again
+      }
+
+      DEBUG4("client {}: announce {}", aClient->GetId(), topic->name);
+      aClient->SendAnnounce(topic, std::nullopt);
+    }
+
+    // create meta topics; don't create if topic is itself a meta topic
+    if (!special) {
+      topic->metaPub = CreateMetaTopic(fmt::format("$pub${}", name));
+      topic->metaSub = CreateMetaTopic(fmt::format("$sub${}", name));
+      UpdateMetaTopicPub(topic);
+      UpdateMetaTopicSub(topic);
+    }
+  }
+
+  return topic;
+}
+
+TopicData* SImpl::CreateMetaTopic(std::string_view name) {
+  return CreateTopic(nullptr, name, "msgpack", {{"retained", true}}, true);
+}
+
+void SImpl::DeleteTopic(TopicData* topic) {
+  if (!topic) {
+    return;
+  }
+
+  // delete meta topics
+  if (topic->metaPub) {
+    DeleteTopic(topic->metaPub);
+  }
+  if (topic->metaSub) {
+    DeleteTopic(topic->metaSub);
+  }
+
+  // unannounce to all subscribers
+  wpi::SmallVector<bool, 16> clients;
+  clients.resize(m_clients.size());
+  for (auto&& sub : topic->subscribers) {
+    clients[sub->client->GetId()] = true;
+  }
+  for (size_t i = 0, iend = clients.size(); i < iend; ++i) {
+    if (!clients[i]) {
+      continue;
+    }
+    if (auto aClient = m_clients[i].get()) {
+      aClient->SendUnannounce(topic);
+    }
+  }
+
+  // erase the topic
+  m_nameTopics.erase(topic->name);
+  m_topics.erase(topic->id);
+}
+
+void SImpl::SetProperties(ClientData* client, TopicData* topic,
+                          const wpi::json& update) {
+  DEBUG4("SetProperties({}, {}, {})", client ? client->GetId() : -1,
+         topic->name, update.dump());
+  bool wasPersistent = topic->persistent;
+  if (topic->SetProperties(update)) {
+    // update persistentChanged flag
+    if (topic->persistent != wasPersistent) {
+      m_persistentChanged = true;
+    }
+    PropertiesChanged(client, topic, update);
+  }
+}
+
+void SImpl::SetFlags(ClientData* client, TopicData* topic, unsigned int flags) {
+  bool wasPersistent = topic->persistent;
+  if (topic->SetFlags(flags)) {
+    // update persistentChanged flag
+    if (topic->persistent != wasPersistent) {
+      m_persistentChanged = true;
+      wpi::json update;
+      if (topic->persistent) {
+        update = {{"persistent", true}};
+      } else {
+        update = {{"persistent", wpi::json::object()}};
+      }
+      PropertiesChanged(client, topic, update);
+    }
+  }
+}
+
+void SImpl::SetValue(ClientData* client, TopicData* topic, const Value& value) {
+  // update retained value if from same client or timestamp newer
+  if (!topic->lastValue || topic->lastValueClient == client ||
+      value.time() >= topic->lastValue.time()) {
+    DEBUG4("updating '{}' last value (time was {} is {})", topic->name,
+           topic->lastValue.time(), value.time());
+    topic->lastValue = value;
+    topic->lastValueClient = client;
+
+    // if persistent, update flag
+    if (topic->persistent) {
+      m_persistentChanged = true;
+    }
+  }
+
+  // propagate to subscribers; as each client may have multiple subscribers,
+  // but we only want to send the value once, first map to clients and then
+  // take action based on union of subscriptions
+
+  // indexed by clientId
+  wpi::SmallVector<ClientData::SendMode, 16> toSend;
+  toSend.resize(m_clients.size());
+
+  for (auto&& subscriber : topic->subscribers) {
+    int id = subscriber->client->GetId();
+    if (subscriber->options.topicsOnly) {
+      continue;
+    } else if (subscriber->options.sendAll) {
+      toSend[id] = ClientData::kSendAll;
+    } else if (toSend[id] != ClientData::kSendAll) {
+      toSend[id] = ClientData::kSendNormal;
+    }
+  }
+
+  for (size_t i = 0, iend = toSend.size(); i < iend; ++i) {
+    auto aClient = m_clients[i].get();
+    if (!aClient || client == aClient) {
+      continue;  // don't echo back
+    }
+    if (toSend[i] != ClientData::kSendDisabled) {
+      aClient->SendValue(topic, value, toSend[i]);
+    }
+  }
+}
+
+void SImpl::UpdateMetaClients(const std::vector<ConnectionInfo>& conns) {
+  Writer w;
+  mpack_start_array(&w, conns.size());
+  for (auto&& conn : conns) {
+    mpack_start_map(&w, 3);
+    mpack_write_str(&w, "id");
+    mpack_write_str(&w, conn.remote_id);
+    mpack_write_str(&w, "conn");
+    mpack_write_str(&w, fmt::format("{}:{}", conn.remote_ip, conn.remote_port));
+    mpack_write_str(&w, "ver");
+    mpack_write_u16(&w, conn.protocol_version);
+    mpack_finish_map(&w);
+  }
+  mpack_finish_array(&w);
+  if (mpack_writer_destroy(&w) == mpack_ok) {
+    SetValue(nullptr, m_metaClients, Value::MakeRaw(std::move(w.bytes)));
+  } else {
+    DEBUG4("failed to encode $clients");
+  }
+}
+
+void SImpl::UpdateMetaTopicPub(TopicData* topic) {
+  if (!topic->metaPub) {
+    return;
+  }
+  Writer w;
+  mpack_start_array(&w, topic->publishers.size());
+  for (auto&& pub : topic->publishers) {
+    mpack_start_map(&w, 2);
+    mpack_write_str(&w, "client");
+    if (pub->client) {
+      mpack_write_str(&w, pub->client->GetName());
+    } else {
+      mpack_write_str(&w, "");
+    }
+    mpack_write_str(&w, "pubuid");
+    mpack_write_int(&w, pub->pubuid);
+    mpack_finish_map(&w);
+  }
+  mpack_finish_array(&w);
+  if (mpack_writer_destroy(&w) == mpack_ok) {
+    SetValue(nullptr, topic->metaPub, Value::MakeRaw(std::move(w.bytes)));
+  }
+}
+
+void SImpl::UpdateMetaTopicSub(TopicData* topic) {
+  if (!topic->metaSub) {
+    return;
+  }
+  Writer w;
+  mpack_start_array(&w, topic->subscribers.size());
+  for (auto&& sub : topic->subscribers) {
+    mpack_start_map(&w, 3);
+    mpack_write_str(&w, "client");
+    if (sub->client) {
+      mpack_write_str(&w, sub->client->GetName());
+    } else {
+      mpack_write_str(&w, "");
+    }
+    mpack_write_str(&w, "subuid");
+    mpack_write_int(&w, sub->subuid);
+    mpack_write_str(&w, "options");
+    WriteOptions(w, sub->options);
+    mpack_finish_map(&w);
+  }
+  mpack_finish_array(&w);
+  if (mpack_writer_destroy(&w) == mpack_ok) {
+    SetValue(nullptr, topic->metaSub, Value::MakeRaw(std::move(w.bytes)));
+  }
+}
+
+void SImpl::PropertiesChanged(ClientData* client, TopicData* topic,
+                              const wpi::json& update) {
+  // removing some properties can result in the topic being unpublished
+  if (!topic->IsPublished()) {
+    DeleteTopic(topic);
+  } else {
+    // send updated announcement to all subscribers
+    wpi::SmallVector<bool, 16> clients;
+    clients.resize(m_clients.size());
+    for (auto&& sub : topic->subscribers) {
+      clients[sub->client->GetId()] = true;
+    }
+    for (size_t i = 0, iend = clients.size(); i < iend; ++i) {
+      if (!clients[i]) {
+        continue;
+      }
+      if (auto aClient = m_clients[i].get()) {
+        aClient->SendPropertiesUpdate(topic, update, aClient == client);
+      }
+    }
+  }
+}
+
+class ServerImpl::Impl final : public SImpl {
+ public:
+  explicit Impl(wpi::Logger& logger) : SImpl{logger} {}
+};
+
+ServerImpl::ServerImpl(wpi::Logger& logger)
+    : m_impl{std::make_unique<Impl>(logger)} {}
+
+ServerImpl::~ServerImpl() = default;
+
+void ServerImpl::SendControl(uint64_t curTimeMs) {
+  if (!m_impl->m_controlReady) {
+    return;
+  }
+  m_impl->m_controlReady = false;
+
+  for (auto&& client : m_impl->m_clients) {
+    if (client) {
+      // to ensure ordering, just send everything
+      client->SendOutgoing(curTimeMs);
+      client->Flush();
+    }
+  }
+}
+
+void ServerImpl::SendValues(int clientId, uint64_t curTimeMs) {
+  auto client = m_impl->m_clients[clientId].get();
+  client->SendOutgoing(curTimeMs);
+  client->Flush();
+}
+
+void ServerImpl::HandleLocal(std::span<const ClientMessage> msgs) {
+  // just map as a normal client into client=0 calls
+  m_impl->m_localClient->HandleLocal(msgs);
+}
+
+void ServerImpl::SetLocal(LocalInterface* local) {
+  WPI_DEBUG4(m_impl->m_logger, "SetLocal()");
+  m_impl->m_local = local;
+
+  // create server meta topics
+  m_impl->m_metaClients = m_impl->CreateMetaTopic("$clients");
+
+  // create local client meta topics
+  m_impl->m_localClient->m_metaPub = m_impl->CreateMetaTopic("$serverpub");
+  m_impl->m_localClient->m_metaSub = m_impl->CreateMetaTopic("$serversub");
+
+  // update meta topics
+  m_impl->m_localClient->UpdateMetaClientPub();
+  m_impl->m_localClient->UpdateMetaClientSub();
+}
+
+void ServerImpl::ProcessIncomingText(int clientId, std::string_view data) {
+  m_impl->m_clients[clientId]->ProcessIncomingText(data);
+}
+
+void ServerImpl::ProcessIncomingBinary(int clientId,
+                                       std::span<const uint8_t> data) {
+  m_impl->m_clients[clientId]->ProcessIncomingBinary(data);
+}
+
+std::pair<std::string, int> ServerImpl::AddClient(std::string_view name,
+                                                  std::string_view connInfo,
+                                                  bool local,
+                                                  WireConnection& wire,
+                                                  SetPeriodicFunc setPeriodic) {
+  return m_impl->AddClient(name, connInfo, local, wire, std::move(setPeriodic));
+}
+
+int ServerImpl::AddClient3(std::string_view connInfo, bool local,
+                           net3::WireConnection3& wire,
+                           Connected3Func connected,
+                           SetPeriodicFunc setPeriodic) {
+  return m_impl->AddClient3(connInfo, local, wire, std::move(connected),
+                            std::move(setPeriodic));
+}
+
+void ServerImpl::RemoveClient(int clientId) {
+  m_impl->RemoveClient(clientId);
+}
+
+void ServerImpl::ConnectionsChanged(const std::vector<ConnectionInfo>& conns) {
+  m_impl->UpdateMetaClients(conns);
+}
+
+bool ServerImpl::PersistentChanged() {
+  return m_impl->PersistentChanged();
+}
+
+std::string ServerImpl::DumpPersistent() {
+  std::string rv;
+  wpi::raw_string_ostream os{rv};
+  m_impl->DumpPersistent(os);
+  os.flush();
+  return rv;
+}
+
+std::string ServerImpl::LoadPersistent(std::string_view in) {
+  return m_impl->LoadPersistent(in);
+}
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/net/ServerImpl.h b/third_party/allwpilib/ntcore/src/main/native/cpp/net/ServerImpl.h
new file mode 100644
index 0000000..86607e9
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/net/ServerImpl.h
@@ -0,0 +1,76 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <stdint.h>
+
+#include <functional>
+#include <memory>
+#include <span>
+#include <string>
+#include <string_view>
+#include <utility>
+#include <vector>
+
+#include "NetworkInterface.h"
+#include "net3/WireConnection3.h"
+
+namespace wpi {
+class Logger;
+}  // namespace wpi
+
+namespace nt::net3 {
+class WireConnection3;
+}  // namespace nt::net3
+
+namespace nt::net {
+
+struct ClientMessage;
+class LocalInterface;
+class WireConnection;
+
+class ServerImpl final {
+ public:
+  using SetPeriodicFunc = std::function<void(uint32_t repeatMs)>;
+  using Connected3Func =
+      std::function<void(std::string_view name, uint16_t proto)>;
+
+  explicit ServerImpl(wpi::Logger& logger);
+  ~ServerImpl();
+
+  void SendControl(uint64_t curTimeMs);
+  void SendValues(int clientId, uint64_t curTimeMs);
+
+  void HandleLocal(std::span<const ClientMessage> msgs);
+  void SetLocal(LocalInterface* local);
+
+  void ProcessIncomingText(int clientId, std::string_view data);
+  void ProcessIncomingBinary(int clientId, std::span<const uint8_t> data);
+
+  // Returns -1 if cannot add client (e.g. due to duplicate name).
+  // Caller must ensure WireConnection lifetime lasts until RemoveClient() call.
+  std::pair<std::string, int> AddClient(std::string_view name,
+                                        std::string_view connInfo, bool local,
+                                        WireConnection& wire,
+                                        SetPeriodicFunc setPeriodic);
+  int AddClient3(std::string_view connInfo, bool local,
+                 net3::WireConnection3& wire, Connected3Func connected,
+                 SetPeriodicFunc setPeriodic);
+  void RemoveClient(int clientId);
+
+  void ConnectionsChanged(const std::vector<ConnectionInfo>& conns);
+
+  // if any persistent values changed since the last call to this function
+  bool PersistentChanged();
+  std::string DumpPersistent();
+  // returns newline-separated errors
+  std::string LoadPersistent(std::string_view in);
+
+ private:
+  class Impl;
+  std::unique_ptr<Impl> m_impl;
+};
+
+}  // namespace nt::net
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/net/WebSocketConnection.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/net/WebSocketConnection.cpp
new file mode 100644
index 0000000..d3d192f
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/net/WebSocketConnection.cpp
@@ -0,0 +1,126 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "WebSocketConnection.h"
+
+#include <span>
+
+#include <wpi/SpanExtras.h>
+#include <wpinet/WebSocket.h>
+
+using namespace nt;
+using namespace nt::net;
+
+static constexpr size_t kAllocSize = 4096;
+static constexpr size_t kTextFrameRolloverSize = 4096;
+static constexpr size_t kBinaryFrameRolloverSize = 8192;
+
+WebSocketConnection::WebSocketConnection(wpi::WebSocket& ws)
+    : m_ws{ws},
+      m_text_os{m_text_buffers, [this] { return AllocBuf(); }},
+      m_binary_os{m_binary_buffers, [this] { return AllocBuf(); }} {}
+
+WebSocketConnection::~WebSocketConnection() {
+  for (auto&& buf : m_buf_pool) {
+    buf.Deallocate();
+  }
+}
+
+void WebSocketConnection::Flush() {
+  FinishSendText();
+  FinishSendBinary();
+  if (m_frames.empty()) {
+    return;
+  }
+
+  // convert internal frames into WS frames
+  m_ws_frames.clear();
+  m_ws_frames.reserve(m_frames.size());
+  for (auto&& frame : m_frames) {
+    m_ws_frames.emplace_back(frame.opcode,
+                             std::span{frame.bufs->begin() + frame.start,
+                                       frame.bufs->begin() + frame.end});
+  }
+
+  ++m_sendsActive;
+  m_ws.SendFrames(m_ws_frames, [selfweak = weak_from_this()](auto bufs, auto) {
+    if (auto self = selfweak.lock()) {
+      self->m_buf_pool.insert(self->m_buf_pool.end(), bufs.begin(), bufs.end());
+      if (self->m_sendsActive > 0) {
+        --self->m_sendsActive;
+      }
+    }
+  });
+  m_frames.clear();
+  m_text_buffers.clear();
+  m_binary_buffers.clear();
+  m_text_pos = 0;
+  m_binary_pos = 0;
+}
+
+void WebSocketConnection::Disconnect(std::string_view reason) {
+  m_ws.Close(1005, reason);
+}
+
+void WebSocketConnection::StartSendText() {
+  // limit amount per single frame
+  size_t total = 0;
+  for (size_t i = m_text_pos; i < m_text_buffers.size(); ++i) {
+    total += m_text_buffers[i].len;
+  }
+  if (total >= kTextFrameRolloverSize) {
+    FinishSendText();
+  }
+
+  if (m_in_text) {
+    m_text_os << ',';
+  } else {
+    m_text_os << '[';
+    m_in_text = true;
+  }
+}
+
+void WebSocketConnection::FinishSendText() {
+  if (m_in_text) {
+    m_text_os << ']';
+    m_in_text = false;
+  }
+  if (m_text_pos >= m_text_buffers.size()) {
+    return;
+  }
+  m_frames.emplace_back(wpi::WebSocket::Frame::kText, &m_text_buffers,
+                        m_text_pos, m_text_buffers.size());
+  m_text_pos = m_text_buffers.size();
+  m_text_os.reset();
+}
+
+void WebSocketConnection::StartSendBinary() {
+  // limit amount per single frame
+  size_t total = 0;
+  for (size_t i = m_binary_pos; i < m_binary_buffers.size(); ++i) {
+    total += m_binary_buffers[i].len;
+  }
+  if (total >= kBinaryFrameRolloverSize) {
+    FinishSendBinary();
+  }
+}
+
+void WebSocketConnection::FinishSendBinary() {
+  if (m_binary_pos >= m_binary_buffers.size()) {
+    return;
+  }
+  m_frames.emplace_back(wpi::WebSocket::Frame::kBinary, &m_binary_buffers,
+                        m_binary_pos, m_binary_buffers.size());
+  m_binary_pos = m_binary_buffers.size();
+  m_binary_os.reset();
+}
+
+wpi::uv::Buffer WebSocketConnection::AllocBuf() {
+  if (!m_buf_pool.empty()) {
+    auto buf = m_buf_pool.back();
+    m_buf_pool.pop_back();
+    return buf;
+  }
+  return wpi::uv::Buffer::Allocate(kAllocSize);
+}
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/net/WebSocketConnection.h b/third_party/allwpilib/ntcore/src/main/native/cpp/net/WebSocketConnection.h
new file mode 100644
index 0000000..ba15215
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/net/WebSocketConnection.h
@@ -0,0 +1,69 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <memory>
+#include <vector>
+
+#include <wpi/SmallVector.h>
+#include <wpinet/WebSocket.h>
+#include <wpinet/raw_uv_ostream.h>
+#include <wpinet/uv/Buffer.h>
+
+#include "WireConnection.h"
+
+namespace nt::net {
+
+class WebSocketConnection final
+    : public WireConnection,
+      public std::enable_shared_from_this<WebSocketConnection> {
+ public:
+  explicit WebSocketConnection(wpi::WebSocket& ws);
+  ~WebSocketConnection() override;
+  WebSocketConnection(const WebSocketConnection&) = delete;
+  WebSocketConnection& operator=(const WebSocketConnection&) = delete;
+
+  bool Ready() const final { return m_sendsActive == 0; }
+
+  TextWriter SendText() final { return {m_text_os, *this}; }
+  BinaryWriter SendBinary() final { return {m_binary_os, *this}; }
+
+  void Flush() final;
+
+  void Disconnect(std::string_view reason) final;
+
+ private:
+  void StartSendText() final;
+  void FinishSendText() final;
+  void StartSendBinary() final;
+  void FinishSendBinary() final;
+
+  wpi::uv::Buffer AllocBuf();
+
+  wpi::WebSocket& m_ws;
+  // Can't use WS frames directly as span could have dangling pointers
+  struct Frame {
+    Frame(uint8_t opcode, wpi::SmallVectorImpl<wpi::uv::Buffer>* bufs,
+          size_t start, size_t end)
+        : opcode{opcode}, bufs{bufs}, start{start}, end{end} {}
+    uint8_t opcode;
+    wpi::SmallVectorImpl<wpi::uv::Buffer>* bufs;
+    size_t start;
+    size_t end;
+  };
+  std::vector<Frame> m_frames;
+  std::vector<wpi::WebSocket::Frame> m_ws_frames;  // to reduce allocs
+  wpi::SmallVector<wpi::uv::Buffer, 4> m_text_buffers;
+  wpi::SmallVector<wpi::uv::Buffer, 4> m_binary_buffers;
+  std::vector<wpi::uv::Buffer> m_buf_pool;
+  wpi::raw_uv_ostream m_text_os;
+  wpi::raw_uv_ostream m_binary_os;
+  size_t m_text_pos = 0;
+  size_t m_binary_pos = 0;
+  bool m_in_text = false;
+  int m_sendsActive = 0;
+};
+
+}  // namespace nt::net
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/net/WireConnection.h b/third_party/allwpilib/ntcore/src/main/native/cpp/net/WireConnection.h
new file mode 100644
index 0000000..2a79a12
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/net/WireConnection.h
@@ -0,0 +1,110 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <stdint.h>
+
+#include <string_view>
+
+#include <wpi/raw_ostream.h>
+
+namespace nt::net {
+
+class BinaryWriter;
+class TextWriter;
+
+class WireConnection {
+  friend class TextWriter;
+  friend class BinaryWriter;
+
+ public:
+  virtual ~WireConnection() = default;
+
+  virtual bool Ready() const = 0;
+
+  virtual TextWriter SendText() = 0;
+
+  virtual BinaryWriter SendBinary() = 0;
+
+  virtual void Flush() = 0;
+
+  virtual void Disconnect(std::string_view reason) = 0;
+
+ protected:
+  virtual void StartSendText() = 0;
+  virtual void FinishSendText() = 0;
+  virtual void StartSendBinary() = 0;
+  virtual void FinishSendBinary() = 0;
+};
+
+class TextWriter {
+ public:
+  TextWriter(wpi::raw_ostream& os, WireConnection& wire)
+      : m_os{&os}, m_wire{&wire} {}
+  TextWriter(const TextWriter&) = delete;
+  TextWriter(TextWriter&& rhs) : m_os{rhs.m_os}, m_wire{rhs.m_wire} {
+    rhs.m_os = nullptr;
+    rhs.m_wire = nullptr;
+  }
+  TextWriter& operator=(const TextWriter&) = delete;
+  TextWriter& operator=(TextWriter&& rhs) {
+    m_os = rhs.m_os;
+    m_wire = rhs.m_wire;
+    rhs.m_os = nullptr;
+    rhs.m_wire = nullptr;
+    return *this;
+  }
+  ~TextWriter() {
+    if (m_os) {
+      m_wire->FinishSendText();
+    }
+  }
+
+  wpi::raw_ostream& Add() {
+    m_wire->StartSendText();
+    return *m_os;
+  }
+  WireConnection& wire() { return *m_wire; }
+
+ private:
+  wpi::raw_ostream* m_os;
+  WireConnection* m_wire;
+};
+
+class BinaryWriter {
+ public:
+  BinaryWriter(wpi::raw_ostream& os, WireConnection& wire)
+      : m_os{&os}, m_wire{&wire} {}
+  BinaryWriter(const BinaryWriter&) = delete;
+  BinaryWriter(BinaryWriter&& rhs) : m_os{rhs.m_os}, m_wire{rhs.m_wire} {
+    rhs.m_os = nullptr;
+    rhs.m_wire = nullptr;
+  }
+  BinaryWriter& operator=(const BinaryWriter&) = delete;
+  BinaryWriter& operator=(BinaryWriter&& rhs) {
+    m_os = rhs.m_os;
+    m_wire = rhs.m_wire;
+    rhs.m_os = nullptr;
+    rhs.m_wire = nullptr;
+    return *this;
+  }
+  ~BinaryWriter() {
+    if (m_wire) {
+      m_wire->FinishSendBinary();
+    }
+  }
+
+  wpi::raw_ostream& Add() {
+    m_wire->StartSendBinary();
+    return *m_os;
+  }
+  WireConnection& wire() { return *m_wire; }
+
+ private:
+  wpi::raw_ostream* m_os;
+  WireConnection* m_wire;
+};
+
+}  // namespace nt::net
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/net/WireDecoder.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/net/WireDecoder.cpp
new file mode 100644
index 0000000..e6474b2
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/net/WireDecoder.cpp
@@ -0,0 +1,567 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "WireDecoder.h"
+
+#include <algorithm>
+
+#include <fmt/format.h>
+#include <wpi/Logger.h>
+#include <wpi/SpanExtras.h>
+#include <wpi/json.h>
+#include <wpi/mpack.h>
+
+#include "Message.h"
+
+using namespace nt;
+using namespace nt::net;
+using namespace mpack;
+
+static bool GetNumber(wpi::json& val, double* num) {
+  if (auto v = val.get_ptr<const int64_t*>()) {
+    *num = *v;
+  } else if (auto v = val.get_ptr<const uint64_t*>()) {
+    *num = *v;
+  } else if (auto v = val.get_ptr<const double*>()) {
+    *num = *v;
+  } else {
+    return false;
+  }
+  return true;
+}
+
+static bool GetNumber(wpi::json& val, int64_t* num) {
+  if (auto v = val.get_ptr<const int64_t*>()) {
+    *num = *v;
+  } else if (auto v = val.get_ptr<const uint64_t*>()) {
+    *num = *v;
+  } else {
+    return false;
+  }
+  return true;
+}
+
+static std::string* ObjGetString(wpi::json::object_t& obj, std::string_view key,
+                                 std::string* error) {
+  auto it = obj.find(key);
+  if (it == obj.end()) {
+    *error = fmt::format("no {} key", key);
+    return nullptr;
+  }
+  auto val = it->second.get_ptr<std::string*>();
+  if (!val) {
+    *error = fmt::format("{} must be a string", key);
+  }
+  return val;
+}
+
+static bool ObjGetNumber(wpi::json::object_t& obj, std::string_view key,
+                         std::string* error, int64_t* num) {
+  auto it = obj.find(key);
+  if (it == obj.end()) {
+    *error = fmt::format("no {} key", key);
+    return false;
+  }
+  if (!GetNumber(it->second, num)) {
+    *error = fmt::format("{} must be a number", key);
+    return false;
+  }
+  return true;
+}
+
+static bool ObjGetStringArray(wpi::json::object_t& obj, std::string_view key,
+                              std::string* error,
+                              std::vector<std::string>* out) {
+  // prefixes
+  auto it = obj.find(key);
+  if (it == obj.end()) {
+    *error = fmt::format("no {} key", key);
+    return false;
+  }
+  auto jarr = it->second.get_ptr<wpi::json::array_t*>();
+  if (!jarr) {
+    *error = fmt::format("{} must be an array", key);
+    return false;
+  }
+  out->resize(0);
+  out->reserve(jarr->size());
+  for (auto&& jval : *jarr) {
+    auto str = jval.get_ptr<std::string*>();
+    if (!str) {
+      *error = fmt::format("{}/{} must be a string", key, out->size());
+      return false;
+    }
+    out->emplace_back(std::move(*str));
+  }
+  return true;
+}
+
+// avoid a fmtlib "unused type alias 'char_type'" warning false positive
+#ifdef __clang__
+#pragma clang diagnostic push
+#pragma clang diagnostic ignored "-Wunused-local-typedef"
+#endif
+
+template <typename T>
+static void WireDecodeTextImpl(std::string_view in, T& out,
+                               wpi::Logger& logger) {
+  static_assert(std::is_same_v<T, ClientMessageHandler> ||
+                    std::is_same_v<T, ServerMessageHandler>,
+                "T must be ClientMessageHandler or ServerMessageHandler");
+
+  wpi::json j;
+  try {
+    j = wpi::json::parse(in);
+  } catch (wpi::json::parse_error& err) {
+    WPI_WARNING(logger, "could not decode JSON message: {}", err.what());
+    return;
+  }
+
+  if (!j.is_array()) {
+    WPI_WARNING(logger, "expected JSON array at top level");
+    return;
+  }
+
+  int i = -1;
+  for (auto&& jmsg : j) {
+    ++i;
+    std::string error;
+    {
+      auto obj = jmsg.get_ptr<wpi::json::object_t*>();
+      if (!obj) {
+        error = "expected message to be an object";
+        goto err;
+      }
+
+      auto method = ObjGetString(*obj, "method", &error);
+      if (!method) {
+        goto err;
+      }
+
+      auto paramsIt = obj->find("params");
+      if (paramsIt == obj->end()) {
+        error = "no params key";
+        goto err;
+      }
+      auto params = paramsIt->second.get_ptr<wpi::json::object_t*>();
+      if (!params) {
+        error = "params must be an object";
+        goto err;
+      }
+
+      if constexpr (std::is_same_v<T, ClientMessageHandler>) {
+        if (*method == PublishMsg::kMethodStr) {
+          // name
+          auto name = ObjGetString(*params, "name", &error);
+          if (!name) {
+            goto err;
+          }
+
+          // type
+          auto typeStr = ObjGetString(*params, "type", &error);
+          if (!typeStr) {
+            goto err;
+          }
+
+          // pubuid
+          int64_t pubuid;
+          if (!ObjGetNumber(*params, "pubuid", &error, &pubuid)) {
+            goto err;
+          }
+
+          // properties; allow missing (treated as empty)
+          wpi::json* properties = nullptr;
+          auto propertiesIt = params->find("properties");
+          if (propertiesIt != params->end()) {
+            properties = &propertiesIt->second;
+            if (!properties->is_object()) {
+              error = "properties must be an object";
+              goto err;
+            }
+          }
+          wpi::json propertiesEmpty;
+          if (!properties) {
+            propertiesEmpty = wpi::json::object();
+            properties = &propertiesEmpty;
+          }
+
+          // complete
+          out.ClientPublish(pubuid, *name, *typeStr, *properties);
+        } else if (*method == UnpublishMsg::kMethodStr) {
+          // pubuid
+          int64_t pubuid;
+          if (!ObjGetNumber(*params, "pubuid", &error, &pubuid)) {
+            goto err;
+          }
+
+          // complete
+          out.ClientUnpublish(pubuid);
+        } else if (*method == SetPropertiesMsg::kMethodStr) {
+          // name
+          auto name = ObjGetString(*params, "name", &error);
+          if (!name) {
+            goto err;
+          }
+
+          // update
+          auto updateIt = params->find("update");
+          if (updateIt == params->end()) {
+            error = "no update key";
+            goto err;
+          }
+          auto update = &updateIt->second;
+          if (!update->is_object()) {
+            error = "update must be an object";
+            goto err;
+          }
+
+          // complete
+          out.ClientSetProperties(*name, *update);
+        } else if (*method == SubscribeMsg::kMethodStr) {
+          // subuid
+          int64_t subuid;
+          if (!ObjGetNumber(*params, "subuid", &error, &subuid)) {
+            goto err;
+          }
+
+          // options
+          PubSubOptionsImpl options;
+          auto optionsIt = params->find("options");
+          if (optionsIt != params->end()) {
+            auto joptions = optionsIt->second.get_ptr<wpi::json::object_t*>();
+            if (!joptions) {
+              error = "options must be an object";
+              goto err;
+            }
+
+            // periodic
+            auto periodicIt = joptions->find("periodic");
+            if (periodicIt != joptions->end()) {
+              double val;
+              if (!GetNumber(periodicIt->second, &val)) {
+                error = "periodic value must be a number";
+                goto err;
+              }
+              options.periodic = val;
+              options.periodicMs = val * 1000;
+            }
+
+            // send all changes
+            auto sendAllIt = joptions->find("all");
+            if (sendAllIt != joptions->end()) {
+              auto sendAll = sendAllIt->second.get_ptr<bool*>();
+              if (!sendAll) {
+                error = "all value must be a boolean";
+                goto err;
+              }
+              options.sendAll = *sendAll;
+            }
+
+            // topics only
+            auto topicsOnlyIt = joptions->find("topicsonly");
+            if (topicsOnlyIt != joptions->end()) {
+              auto topicsOnly = topicsOnlyIt->second.get_ptr<bool*>();
+              if (!topicsOnly) {
+                error = "topicsonly value must be a boolean";
+                goto err;
+              }
+              options.topicsOnly = *topicsOnly;
+            }
+
+            // prefix match
+            auto prefixMatchIt = joptions->find("prefix");
+            if (prefixMatchIt != joptions->end()) {
+              auto prefixMatch = prefixMatchIt->second.get_ptr<bool*>();
+              if (!prefixMatch) {
+                error = "prefix value must be a boolean";
+                goto err;
+              }
+              options.prefixMatch = *prefixMatch;
+            }
+          }
+
+          // topic names
+          std::vector<std::string> topicNames;
+          if (!ObjGetStringArray(*params, "topics", &error, &topicNames)) {
+            goto err;
+          }
+
+          // complete
+          out.ClientSubscribe(subuid, topicNames, options);
+        } else if (*method == UnsubscribeMsg::kMethodStr) {
+          // subuid
+          int64_t subuid;
+          if (!ObjGetNumber(*params, "subuid", &error, &subuid)) {
+            goto err;
+          }
+
+          // complete
+          out.ClientUnsubscribe(subuid);
+        } else {
+          error = fmt::format("unrecognized method '{}'", *method);
+          goto err;
+        }
+      } else if constexpr (std::is_same_v<T, ServerMessageHandler>) {
+        if (*method == AnnounceMsg::kMethodStr) {
+          // name
+          auto name = ObjGetString(*params, "name", &error);
+          if (!name) {
+            goto err;
+          }
+
+          // id
+          int64_t id;
+          if (!ObjGetNumber(*params, "id", &error, &id)) {
+            goto err;
+          }
+
+          // type
+          auto typeStr = ObjGetString(*params, "type", &error);
+          if (!typeStr) {
+            goto err;
+          }
+
+          // pubuid
+          std::optional<int64_t> pubuid;
+          auto pubuidIt = params->find("pubuid");
+          if (pubuidIt != params->end()) {
+            int64_t val;
+            if (!GetNumber(pubuidIt->second, &val)) {
+              error = "pubuid value must be a number";
+              goto err;
+            }
+            pubuid = val;
+          }
+
+          // properties
+          auto propertiesIt = params->find("properties");
+          if (propertiesIt == params->end()) {
+            error = "no properties key";
+            goto err;
+          }
+          auto properties = &propertiesIt->second;
+          if (!properties->is_object()) {
+            WPI_WARNING(logger, "{}: properties is not an object", *name);
+            *properties = wpi::json::object();
+          }
+
+          // complete
+          out.ServerAnnounce(*name, id, *typeStr, *properties, pubuid);
+        } else if (*method == UnannounceMsg::kMethodStr) {
+          // name
+          auto name = ObjGetString(*params, "name", &error);
+          if (!name) {
+            goto err;
+          }
+
+          // id
+          int64_t id;
+          if (!ObjGetNumber(*params, "id", &error, &id)) {
+            goto err;
+          }
+
+          // complete
+          out.ServerUnannounce(*name, id);
+        } else if (*method == PropertiesUpdateMsg::kMethodStr) {
+          // name
+          auto name = ObjGetString(*params, "name", &error);
+          if (!name) {
+            goto err;
+          }
+
+          // update
+          auto updateIt = params->find("update");
+          if (updateIt == params->end()) {
+            error = "no update key";
+            goto err;
+          }
+          auto update = &updateIt->second;
+          if (!update->is_object()) {
+            error = "update must be an object";
+            goto err;
+          }
+
+          bool ack = false;
+          auto ackIt = params->find("ack");
+          if (ackIt != params->end()) {
+            auto val = ackIt->second.get_ptr<bool*>();
+            if (!val) {
+              error = "ack must be a boolean";
+              goto err;
+            }
+            ack = *val;
+          }
+
+          // complete
+          out.ServerPropertiesUpdate(*name, *update, ack);
+        } else {
+          error = fmt::format("unrecognized method '{}'", *method);
+          goto err;
+        }
+      }
+      continue;
+    }
+  err:
+    WPI_WARNING(logger, "{}: {}", i, error);
+  }
+}
+
+#ifdef __clang__
+#pragma clang diagnostic pop
+#endif
+
+void nt::net::WireDecodeText(std::string_view in, ClientMessageHandler& out,
+                             wpi::Logger& logger) {
+  ::WireDecodeTextImpl(in, out, logger);
+}
+
+void nt::net::WireDecodeText(std::string_view in, ServerMessageHandler& out,
+                             wpi::Logger& logger) {
+  ::WireDecodeTextImpl(in, out, logger);
+}
+
+bool nt::net::WireDecodeBinary(std::span<const uint8_t>* in, int64_t* outId,
+                               Value* outValue, std::string* error,
+                               int64_t localTimeOffset) {
+  mpack_reader_t reader;
+  mpack_reader_init_data(&reader, reinterpret_cast<const char*>(in->data()),
+                         in->size());
+  mpack_expect_array_match(&reader, 4);
+  *outId = mpack_expect_i64(&reader);
+  auto time = mpack_expect_i64(&reader);
+  int type = mpack_expect_int(&reader);
+  switch (type) {
+    case 0:  // boolean
+      *outValue = Value::MakeBoolean(mpack_expect_bool(&reader), 1);
+      break;
+    case 2:  // integer
+      *outValue = Value::MakeInteger(mpack_expect_i64(&reader), 1);
+      break;
+    case 3:  // float
+      *outValue = Value::MakeFloat(mpack_expect_float(&reader), 1);
+      break;
+    case 1:  // double
+      *outValue = Value::MakeDouble(mpack_expect_double(&reader), 1);
+      break;
+    case 4: {  // string
+      auto length = mpack_expect_str(&reader);
+      auto data = mpack_read_bytes_inplace(&reader, length);
+      if (mpack_reader_error(&reader) == mpack_ok) {
+        *outValue = Value::MakeString({data, length}, 1);
+      }
+      mpack_done_str(&reader);
+      break;
+    }
+    case 5: {  // raw
+      auto length = mpack_expect_bin(&reader);
+      auto data = mpack_read_bytes_inplace(&reader, length);
+      if (mpack_reader_error(&reader) == mpack_ok) {
+        *outValue =
+            Value::MakeRaw({reinterpret_cast<const uint8_t*>(data), length}, 1);
+      }
+      mpack_done_bin(&reader);
+      break;
+    }
+    case 16: {  // boolean array
+      auto length = mpack_expect_array(&reader);
+      std::vector<int> arr;
+      arr.reserve((std::min)(length, 1000u));
+      for (uint32_t i = 0; i < length; ++i) {
+        arr.emplace_back(mpack_expect_bool(&reader));
+        if (mpack_reader_error(&reader) != mpack_ok) {
+          break;
+        }
+      }
+      if (mpack_reader_error(&reader) == mpack_ok) {
+        *outValue = Value::MakeBooleanArray(std::move(arr), 1);
+      }
+      mpack_done_array(&reader);
+      break;
+    }
+    case 18: {  // integer array
+      auto length = mpack_expect_array(&reader);
+      std::vector<int64_t> arr;
+      arr.reserve((std::min)(length, 1000u));
+      for (uint32_t i = 0; i < length; ++i) {
+        arr.emplace_back(mpack_expect_i64(&reader));
+        if (mpack_reader_error(&reader) != mpack_ok) {
+          break;
+        }
+      }
+      if (mpack_reader_error(&reader) == mpack_ok) {
+        *outValue = Value::MakeIntegerArray(std::move(arr), 1);
+      }
+      mpack_done_array(&reader);
+      break;
+    }
+    case 19: {  // float array
+      auto length = mpack_expect_array(&reader);
+      std::vector<float> arr;
+      arr.reserve((std::min)(length, 1000u));
+      for (uint32_t i = 0; i < length; ++i) {
+        arr.emplace_back(mpack_expect_float(&reader));
+        if (mpack_reader_error(&reader) != mpack_ok) {
+          break;
+        }
+      }
+      if (mpack_reader_error(&reader) == mpack_ok) {
+        *outValue = Value::MakeFloatArray(std::move(arr), 1);
+      }
+      mpack_done_array(&reader);
+      break;
+    }
+    case 17: {  // double array
+      auto length = mpack_expect_array(&reader);
+      std::vector<double> arr;
+      arr.reserve((std::min)(length, 1000u));
+      for (uint32_t i = 0; i < length; ++i) {
+        arr.emplace_back(mpack_expect_double(&reader));
+        if (mpack_reader_error(&reader) != mpack_ok) {
+          break;
+        }
+      }
+      if (mpack_reader_error(&reader) == mpack_ok) {
+        *outValue = Value::MakeDoubleArray(std::move(arr), 1);
+      }
+      mpack_done_array(&reader);
+      break;
+    }
+    case 20: {  // string array
+      auto length = mpack_expect_array(&reader);
+      std::vector<std::string> arr;
+      arr.reserve((std::min)(length, 1000u));
+      for (uint32_t i = 0; i < length; ++i) {
+        auto length = mpack_expect_str(&reader);
+        auto data = mpack_read_bytes_inplace(&reader, length);
+        if (mpack_reader_error(&reader) == mpack_ok) {
+          arr.emplace_back(std::string{data, length});
+        } else {
+          break;
+        }
+        mpack_done_str(&reader);
+      }
+      if (mpack_reader_error(&reader) == mpack_ok) {
+        *outValue = Value::MakeStringArray(std::move(arr), 1);
+      }
+      mpack_done_array(&reader);
+      break;
+    }
+    default:
+      *error = fmt::format("unrecognized type {}", type);
+      return false;
+  }
+  mpack_done_array(&reader);
+  auto err = mpack_reader_destroy(&reader);
+  if (err != mpack_ok) {
+    *error = mpack_error_to_string(err);
+    return false;
+  }
+  // set time
+  outValue->SetServerTime(time);
+  outValue->SetTime(time == 0 ? 0 : time + localTimeOffset);
+  // update input range
+  *in = wpi::drop_front(*in,
+                        in->size() - mpack_reader_remaining(&reader, nullptr));
+  return true;
+}
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/net/WireDecoder.h b/third_party/allwpilib/ntcore/src/main/native/cpp/net/WireDecoder.h
new file mode 100644
index 0000000..128dff2
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/net/WireDecoder.h
@@ -0,0 +1,64 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <stdint.h>
+
+#include <optional>
+#include <span>
+#include <string>
+#include <string_view>
+
+namespace wpi {
+class Logger;
+class json;
+}  // namespace wpi
+
+namespace nt {
+class PubSubOptionsImpl;
+class Value;
+}  // namespace nt
+
+namespace nt::net {
+
+class ClientMessageHandler {
+ public:
+  virtual ~ClientMessageHandler() = default;
+
+  virtual void ClientPublish(int64_t pubuid, std::string_view name,
+                             std::string_view typeStr,
+                             const wpi::json& properties) = 0;
+  virtual void ClientUnpublish(int64_t pubuid) = 0;
+  virtual void ClientSetProperties(std::string_view name,
+                                   const wpi::json& update) = 0;
+  virtual void ClientSubscribe(int64_t subuid,
+                               std::span<const std::string> topicNames,
+                               const PubSubOptionsImpl& options) = 0;
+  virtual void ClientUnsubscribe(int64_t subuid) = 0;
+};
+
+class ServerMessageHandler {
+ public:
+  virtual ~ServerMessageHandler() = default;
+  virtual void ServerAnnounce(std::string_view name, int64_t id,
+                              std::string_view typeStr,
+                              const wpi::json& properties,
+                              std::optional<int64_t> pubuid) = 0;
+  virtual void ServerUnannounce(std::string_view name, int64_t id) = 0;
+  virtual void ServerPropertiesUpdate(std::string_view name,
+                                      const wpi::json& update, bool ack) = 0;
+};
+
+void WireDecodeText(std::string_view in, ClientMessageHandler& out,
+                    wpi::Logger& logger);
+void WireDecodeText(std::string_view in, ServerMessageHandler& out,
+                    wpi::Logger& logger);
+
+// returns true if successfully decoded a message
+bool WireDecodeBinary(std::span<const uint8_t>* in, int64_t* outId,
+                      Value* outValue, std::string* error,
+                      int64_t localTimeOffset);
+
+}  // namespace nt::net
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/net/WireEncoder.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/net/WireEncoder.cpp
new file mode 100644
index 0000000..143fe0d
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/net/WireEncoder.cpp
@@ -0,0 +1,316 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "WireEncoder.h"
+
+#include <optional>
+
+#include <wpi/json_serializer.h>
+#include <wpi/mpack.h>
+#include <wpi/raw_ostream.h>
+
+#include "Handle.h"
+#include "Message.h"
+#include "PubSubOptions.h"
+#include "networktables/NetworkTableValue.h"
+
+using namespace nt;
+using namespace nt::net;
+using namespace mpack;
+
+void nt::net::WireEncodePublish(wpi::raw_ostream& os, int64_t pubuid,
+                                std::string_view name, std::string_view typeStr,
+                                const wpi::json& properties) {
+  wpi::json::serializer s{os, ' ', 0};
+  os << "{\"method\":\"" << PublishMsg::kMethodStr << "\",\"params\":{";
+  os << "\"name\":\"";
+  s.dump_escaped(name, false);
+  os << "\",\"properties\":";
+  s.dump(properties, false, false, 0, 0);
+  os << ",\"pubuid\":";
+  s.dump_integer(pubuid);
+  os << ",\"type\":\"";
+  s.dump_escaped(typeStr, false);
+  os << "\"}}";
+}
+
+void nt::net::WireEncodeUnpublish(wpi::raw_ostream& os, int64_t pubuid) {
+  wpi::json::serializer s{os, ' ', 0};
+  os << "{\"method\":\"" << UnpublishMsg::kMethodStr << "\",\"params\":{";
+  os << "\"pubuid\":";
+  s.dump_integer(pubuid);
+  os << "}}";
+}
+
+void nt::net::WireEncodeSetProperties(wpi::raw_ostream& os,
+                                      std::string_view name,
+                                      const wpi::json& update) {
+  wpi::json::serializer s{os, ' ', 0};
+  os << "{\"method\":\"" << SetPropertiesMsg::kMethodStr << "\",\"params\":{";
+  os << "\"name\":\"";
+  s.dump_escaped(name, false);
+  os << "\",\"update\":";
+  s.dump(update, false, false, 0, 0);
+  os << "}}";
+}
+
+template <typename T>
+static void EncodePrefixes(wpi::raw_ostream& os, std::span<const T> topicNames,
+                           wpi::json::serializer& s) {
+  os << '[';
+  bool first = true;
+  for (auto&& name : topicNames) {
+    if (first) {
+      first = false;
+    } else {
+      os << ',';
+    }
+    os << '"';
+    s.dump_escaped(name, false);
+    os << '"';
+  }
+  os << ']';
+}
+
+template <typename T>
+static void WireEncodeSubscribeImpl(wpi::raw_ostream& os, int64_t subuid,
+                                    std::span<const T> topicNames,
+                                    const PubSubOptionsImpl& options) {
+  wpi::json::serializer s{os, ' ', 0};
+  os << "{\"method\":\"" << SubscribeMsg::kMethodStr << "\",\"params\":{";
+  os << "\"options\":{";
+  bool first = true;
+  if (options.sendAll) {
+    os << "\"all\":true";
+    first = false;
+  }
+  if (options.topicsOnly) {
+    if (!first) {
+      os << ',';
+    }
+    os << "\"topicsonly\":true";
+    first = false;
+  }
+  if (options.prefixMatch) {
+    if (!first) {
+      os << ',';
+    }
+    os << "\"prefix\":true";
+    first = false;
+  }
+  if (options.periodicMs != PubSubOptionsImpl::kDefaultPeriodicMs) {
+    if (!first) {
+      os << ',';
+    }
+    os << "\"periodic\":";
+    s.dump_float(options.periodicMs / 1000.0);
+  }
+  os << "},\"topics\":";
+  EncodePrefixes(os, topicNames, s);
+  os << ",\"subuid\":";
+  s.dump_integer(subuid);
+  os << "}}";
+}
+
+void nt::net::WireEncodeSubscribe(wpi::raw_ostream& os, int64_t subuid,
+                                  std::span<const std::string_view> topicNames,
+                                  const PubSubOptionsImpl& options) {
+  WireEncodeSubscribeImpl(os, subuid, topicNames, options);
+}
+
+void nt::net::WireEncodeSubscribe(wpi::raw_ostream& os, int64_t subuid,
+                                  std::span<const std::string> topicNames,
+                                  const PubSubOptionsImpl& options) {
+  WireEncodeSubscribeImpl(os, subuid, topicNames, options);
+}
+
+void nt::net::WireEncodeUnsubscribe(wpi::raw_ostream& os, int64_t subHandle) {
+  wpi::json::serializer s{os, ' ', 0};
+  os << "{\"method\":\"" << UnsubscribeMsg::kMethodStr << "\",\"params\":{";
+  os << "\"subuid\":";
+  s.dump_integer(subHandle);
+  os << "}}";
+}
+
+bool nt::net::WireEncodeText(wpi::raw_ostream& os, const ClientMessage& msg) {
+  if (auto m = std::get_if<PublishMsg>(&msg.contents)) {
+    WireEncodePublish(os, Handle{m->pubHandle}.GetIndex(), m->name, m->typeStr,
+                      m->properties);
+  } else if (auto m = std::get_if<UnpublishMsg>(&msg.contents)) {
+    WireEncodeUnpublish(os, Handle{m->pubHandle}.GetIndex());
+  } else if (auto m = std::get_if<SetPropertiesMsg>(&msg.contents)) {
+    WireEncodeSetProperties(os, m->name, m->update);
+  } else if (auto m = std::get_if<SubscribeMsg>(&msg.contents)) {
+    WireEncodeSubscribe(os, Handle{m->subHandle}.GetIndex(), m->topicNames,
+                        m->options);
+  } else if (auto m = std::get_if<UnsubscribeMsg>(&msg.contents)) {
+    WireEncodeUnsubscribe(os, Handle{m->subHandle}.GetIndex());
+  } else {
+    return false;
+  }
+  return true;
+}
+
+void nt::net::WireEncodeAnnounce(wpi::raw_ostream& os, std::string_view name,
+                                 int64_t id, std::string_view typeStr,
+                                 const wpi::json& properties,
+                                 std::optional<int64_t> pubHandle) {
+  wpi::json::serializer s{os, ' ', 0};
+  os << "{\"method\":\"" << AnnounceMsg::kMethodStr << "\",\"params\":{";
+  os << "\"id\":";
+  s.dump_integer(id);
+  os << ",\"name\":\"";
+  s.dump_escaped(name, false);
+  os << "\",\"properties\":";
+  s.dump(properties, false, false, 0, 0);
+  if (pubHandle) {
+    os << ",\"pubuid\":";
+    s.dump_integer(*pubHandle);
+  }
+  os << ",\"type\":\"";
+  s.dump_escaped(typeStr, false);
+  os << "\"}}";
+}
+
+void nt::net::WireEncodeUnannounce(wpi::raw_ostream& os, std::string_view name,
+                                   int64_t id) {
+  wpi::json::serializer s{os, ' ', 0};
+  os << "{\"method\":\"" << UnannounceMsg::kMethodStr << "\",\"params\":{";
+  os << "\"id\":";
+  s.dump_integer(id);
+  os << ",\"name\":\"";
+  s.dump_escaped(name, false);
+  os << "\"}}";
+}
+
+void nt::net::WireEncodePropertiesUpdate(wpi::raw_ostream& os,
+                                         std::string_view name,
+                                         const wpi::json& update, bool ack) {
+  wpi::json::serializer s{os, ' ', 0};
+  os << "{\"method\":\"" << PropertiesUpdateMsg::kMethodStr
+     << "\",\"params\":{";
+  os << "\"name\":\"";
+  s.dump_escaped(name, false);
+  os << "\",\"update\":";
+  s.dump(update, false, false, 0, 0);
+  if (ack) {
+    os << ",\"ack\":true";
+  }
+  os << "}}";
+}
+
+bool nt::net::WireEncodeText(wpi::raw_ostream& os, const ServerMessage& msg) {
+  if (auto m = std::get_if<AnnounceMsg>(&msg.contents)) {
+    WireEncodeAnnounce(os, m->name, m->id, m->typeStr, m->properties,
+                       m->pubuid);
+  } else if (auto m = std::get_if<UnannounceMsg>(&msg.contents)) {
+    WireEncodeUnannounce(os, m->name, m->id);
+  } else if (auto m = std::get_if<PropertiesUpdateMsg>(&msg.contents)) {
+    WireEncodePropertiesUpdate(os, m->name, m->update, m->ack);
+  } else {
+    return false;
+  }
+  return true;
+}
+
+bool nt::net::WireEncodeBinary(wpi::raw_ostream& os, int64_t id, int64_t time,
+                               const Value& value) {
+  char buf[128];
+  mpack_writer_t writer;
+  mpack_writer_init(&writer, buf, sizeof(buf));
+  mpack_writer_set_context(&writer, &os);
+  mpack_writer_set_flush(
+      &writer, [](mpack_writer_t* writer, const char* buffer, size_t count) {
+        static_cast<wpi::raw_ostream*>(writer->context)->write(buffer, count);
+      });
+  mpack_start_array(&writer, 4);
+  mpack_write_int(&writer, id);
+  mpack_write_int(&writer, time);
+  switch (value.type()) {
+    case NT_BOOLEAN:
+      mpack_write_u8(&writer, 0);
+      mpack_write_bool(&writer, value.GetBoolean());
+      break;
+    case NT_INTEGER:
+      mpack_write_u8(&writer, 2);
+      mpack_write_int(&writer, value.GetInteger());
+      break;
+    case NT_FLOAT:
+      mpack_write_u8(&writer, 3);
+      mpack_write_float(&writer, value.GetFloat());
+      break;
+    case NT_DOUBLE:
+      mpack_write_u8(&writer, 1);
+      mpack_write_double(&writer, value.GetDouble());
+      break;
+    case NT_STRING: {
+      auto v = value.GetString();
+      mpack_write_u8(&writer, 4);
+      mpack_write_str(&writer, v.data(), v.size());
+      break;
+    }
+    case NT_RPC:
+    case NT_RAW: {
+      auto v = value.GetRaw();
+      mpack_write_u8(&writer, 5);
+      mpack_write_bin(&writer, reinterpret_cast<const char*>(v.data()),
+                      v.size());
+      break;
+    }
+    case NT_BOOLEAN_ARRAY: {
+      auto v = value.GetBooleanArray();
+      mpack_write_u8(&writer, 16);
+      mpack_start_array(&writer, v.size());
+      for (auto val : v) {
+        mpack_write_bool(&writer, val);
+      }
+      mpack_finish_array(&writer);
+      break;
+    }
+    case NT_INTEGER_ARRAY: {
+      auto v = value.GetIntegerArray();
+      mpack_write_u8(&writer, 18);
+      mpack_start_array(&writer, v.size());
+      for (auto val : v) {
+        mpack_write_int(&writer, val);
+      }
+      mpack_finish_array(&writer);
+      break;
+    }
+    case NT_FLOAT_ARRAY: {
+      auto v = value.GetFloatArray();
+      mpack_write_u8(&writer, 19);
+      mpack_start_array(&writer, v.size());
+      for (auto val : v) {
+        mpack_write_float(&writer, val);
+      }
+      mpack_finish_array(&writer);
+      break;
+    }
+    case NT_DOUBLE_ARRAY: {
+      auto v = value.GetDoubleArray();
+      mpack_write_u8(&writer, 17);
+      mpack_start_array(&writer, v.size());
+      for (auto val : v) {
+        mpack_write_double(&writer, val);
+      }
+      mpack_finish_array(&writer);
+      break;
+    }
+    case NT_STRING_ARRAY: {
+      auto v = value.GetStringArray();
+      mpack_write_u8(&writer, 20);
+      mpack_start_array(&writer, v.size());
+      for (auto&& val : v) {
+        mpack_write_str(&writer, val.data(), val.size());
+      }
+      mpack_finish_array(&writer);
+      break;
+    }
+    default:
+      return false;
+  }
+  mpack_finish_array(&writer);
+  return mpack_writer_destroy(&writer) == mpack_ok;
+}
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/net/WireEncoder.h b/third_party/allwpilib/ntcore/src/main/native/cpp/net/WireEncoder.h
new file mode 100644
index 0000000..d0a04cb
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/net/WireEncoder.h
@@ -0,0 +1,61 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <optional>
+#include <span>
+#include <string>
+#include <string_view>
+
+namespace wpi {
+class json;
+class raw_ostream;
+}  // namespace wpi
+
+namespace nt {
+class PubSubOptionsImpl;
+class Value;
+}  // namespace nt
+
+namespace nt::net {
+
+struct ClientMessage;
+struct ServerMessage;
+
+// encoders for client text messages (avoids need to construct a Message struct)
+void WireEncodePublish(wpi::raw_ostream& os, int64_t pubuid,
+                       std::string_view name, std::string_view typeStr,
+                       const wpi::json& properties);
+void WireEncodeUnpublish(wpi::raw_ostream& os, int64_t pubuid);
+void WireEncodeSetProperties(wpi::raw_ostream& os, std::string_view name,
+                             const wpi::json& update);
+void WireEncodeSubscribe(wpi::raw_ostream& os, int64_t subuid,
+                         std::span<const std::string_view> topicNames,
+                         const PubSubOptionsImpl& options);
+void WireEncodeSubscribe(wpi::raw_ostream& os, int64_t subuid,
+                         std::span<const std::string> topicNames,
+                         const PubSubOptionsImpl& options);
+void WireEncodeUnsubscribe(wpi::raw_ostream& os, int64_t subuid);
+
+// encoders for server text messages (avoids need to construct a Message struct)
+void WireEncodeAnnounce(wpi::raw_ostream& os, std::string_view name, int64_t id,
+                        std::string_view typeStr, const wpi::json& properties,
+                        std::optional<int64_t> pubuid);
+void WireEncodeUnannounce(wpi::raw_ostream& os, std::string_view name,
+                          int64_t id);
+void WireEncodePropertiesUpdate(wpi::raw_ostream& os, std::string_view name,
+                                const wpi::json& update, bool ack);
+
+// Encode a single message; note text messages must be put into a
+// JSON array "[msg1, msg2]" for transmission.
+// Returns true if message was written
+bool WireEncodeText(wpi::raw_ostream& os, const ClientMessage& msg);
+bool WireEncodeText(wpi::raw_ostream& os, const ServerMessage& msg);
+
+// encoder for binary messages
+bool WireEncodeBinary(wpi::raw_ostream& os, int64_t id, int64_t time,
+                      const Value& value);
+
+}  // namespace nt::net
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/net3/ClientImpl3.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/net3/ClientImpl3.cpp
new file mode 100644
index 0000000..0783865
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/net3/ClientImpl3.cpp
@@ -0,0 +1,642 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "ClientImpl3.h"
+
+#include <algorithm>
+#include <numeric>
+#include <string>
+#include <vector>
+
+#include <fmt/format.h>
+#include <wpi/DenseMap.h>
+#include <wpi/StringMap.h>
+#include <wpi/json.h>
+
+#include "Handle.h"
+#include "Log.h"
+#include "Types_internal.h"
+#include "net/Message.h"
+#include "net/NetworkInterface.h"
+#include "net3/Message3.h"
+#include "net3/SequenceNumber.h"
+#include "net3/WireConnection3.h"
+#include "net3/WireDecoder3.h"
+#include "net3/WireEncoder3.h"
+#include "networktables/NetworkTableValue.h"
+
+using namespace nt;
+using namespace nt::net3;
+
+static constexpr uint32_t kMinPeriodMs = 5;
+
+// maximum number of times the wire can be not ready to send another
+// transmission before we close the connection
+static constexpr int kWireMaxNotReady = 10;
+
+namespace {
+
+struct Entry;
+
+struct PublisherData {
+  explicit PublisherData(Entry* entry) : entry{entry} {}
+
+  Entry* entry;
+  NT_Publisher handle;
+  PubSubOptionsImpl options;
+  // in options as double, but copy here as integer; rounded to the nearest
+  // 10 ms
+  uint32_t periodMs;
+  uint64_t nextSendMs{0};
+  std::vector<Value> outValues;  // outgoing values
+};
+
+// data for each entry
+struct Entry {
+  explicit Entry(std::string_view name_) : name(name_) {}
+  bool IsPersistent() const { return (flags & NT_PERSISTENT) != 0; }
+  wpi::json SetFlags(unsigned int flags_);
+
+  std::string name;
+
+  std::string typeStr;
+  NT_Type type{NT_UNASSIGNED};
+
+  wpi::json properties = wpi::json::object();
+
+  // The current value and flags
+  Value value;
+  unsigned int flags{0};
+
+  // Unique ID used in network messages; this is 0xffff until assigned
+  // by the server.
+  unsigned int id{0xffff};
+
+  // Sequence number for update resolution
+  SequenceNumber seqNum;
+
+  // Local topic handle
+  NT_Topic topic{0};
+
+  // Local publishers
+  std::vector<PublisherData*> publishers;
+};
+
+class CImpl : public MessageHandler3 {
+ public:
+  CImpl(uint64_t curTimeMs, int inst, WireConnection3& wire,
+        wpi::Logger& logger,
+        std::function<void(uint32_t repeatMs)> setPeriodic);
+
+  void ProcessIncoming(std::span<const uint8_t> data);
+  void HandleLocal(std::span<const net::ClientMessage> msgs);
+  void SendPeriodic(uint64_t curTimeMs, bool initial);
+  void SendValue(Writer& out, Entry* entry, const Value& value);
+  bool CheckNetworkReady();
+
+  // Outgoing handlers
+  void Publish(NT_Publisher pubHandle, NT_Topic topicHandle,
+               std::string_view name, std::string_view typeStr,
+               const wpi::json& properties, const PubSubOptionsImpl& options);
+  void Unpublish(NT_Publisher pubHandle, NT_Topic topicHandle);
+  void SetProperties(NT_Topic topicHandle, std::string_view name,
+                     const wpi::json& update);
+  void SetValue(NT_Publisher pubHandle, const Value& value);
+
+  // MessageHandler interface
+  void KeepAlive() final;
+  void ServerHelloDone() final;
+  void ClientHelloDone() final;
+  void ClearEntries() final;
+  void ProtoUnsup(unsigned int proto_rev) final;
+  void ClientHello(std::string_view self_id, unsigned int proto_rev) final;
+  void ServerHello(unsigned int flags, std::string_view self_id) final;
+  void EntryAssign(std::string_view name, unsigned int id, unsigned int seq_num,
+                   const Value& value, unsigned int flags) final;
+  void EntryUpdate(unsigned int id, unsigned int seq_num,
+                   const Value& value) final;
+  void FlagsUpdate(unsigned int id, unsigned int flags) final;
+  void EntryDelete(unsigned int id) final;
+  void ExecuteRpc(unsigned int id, unsigned int uid,
+                  std::span<const uint8_t> params) final {}
+  void RpcResponse(unsigned int id, unsigned int uid,
+                   std::span<const uint8_t> result) final {}
+
+  enum State {
+    kStateInitial,
+    kStateHelloSent,
+    kStateInitialAssignments,
+    kStateRunning
+  };
+
+  int m_inst;
+  WireConnection3& m_wire;
+  wpi::Logger& m_logger;
+  net::LocalInterface* m_local{nullptr};
+  std::function<void(uint32_t repeatMs)> m_setPeriodic;
+  uint64_t m_initTimeMs;
+
+  // periodic sweep handling
+  static constexpr uint32_t kKeepAliveIntervalMs = 1000;
+  uint32_t m_periodMs{kKeepAliveIntervalMs + 10};
+  uint64_t m_lastSendMs{0};
+  uint64_t m_nextKeepAliveTimeMs;
+  int m_notReadyCount{0};
+
+  // indexed by publisher index
+  std::vector<std::unique_ptr<PublisherData>> m_publishers;
+
+  State m_state{kStateInitial};
+  WireDecoder3 m_decoder;
+  std::string m_remoteId;
+  std::function<void()> m_handshakeSucceeded;
+
+  std::vector<std::pair<unsigned int, unsigned int>> m_outgoingFlags;
+
+  using NameMap = wpi::StringMap<std::unique_ptr<Entry>>;
+  using IdMap = std::vector<Entry*>;
+
+  NameMap m_nameMap;
+  IdMap m_idMap;
+
+  Entry* GetOrNewEntry(std::string_view name) {
+    auto& entry = m_nameMap[name];
+    if (!entry) {
+      entry = std::make_unique<Entry>(name);
+    }
+    return entry.get();
+  }
+  Entry* LookupId(unsigned int id) {
+    return id < m_idMap.size() ? m_idMap[id] : nullptr;
+  }
+};
+
+}  // namespace
+
+wpi::json Entry::SetFlags(unsigned int flags_) {
+  bool wasPersistent = IsPersistent();
+  flags = flags_;
+  bool isPersistent = IsPersistent();
+  if (isPersistent && !wasPersistent) {
+    properties["persistent"] = true;
+    return {{"persistent", true}};
+  } else if (!isPersistent && wasPersistent) {
+    properties.erase("persistent");
+    return {{"persistent", wpi::json()}};
+  } else {
+    return wpi::json::object();
+  }
+}
+
+CImpl::CImpl(uint64_t curTimeMs, int inst, WireConnection3& wire,
+             wpi::Logger& logger,
+             std::function<void(uint32_t repeatMs)> setPeriodic)
+    : m_inst{inst},
+      m_wire{wire},
+      m_logger{logger},
+      m_setPeriodic{std::move(setPeriodic)},
+      m_initTimeMs{curTimeMs},
+      m_nextKeepAliveTimeMs{curTimeMs + kKeepAliveIntervalMs},
+      m_decoder{*this} {}
+
+void CImpl::ProcessIncoming(std::span<const uint8_t> data) {
+  DEBUG4("received {} bytes", data.size());
+  if (!m_decoder.Execute(&data)) {
+    m_wire.Disconnect(m_decoder.GetError());
+  }
+}
+
+void CImpl::HandleLocal(std::span<const net::ClientMessage> msgs) {
+  for (const auto& elem : msgs) {  // NOLINT
+    // common case is value
+    if (auto msg = std::get_if<net::ClientValueMsg>(&elem.contents)) {
+      SetValue(msg->pubHandle, msg->value);
+    } else if (auto msg = std::get_if<net::PublishMsg>(&elem.contents)) {
+      Publish(msg->pubHandle, msg->topicHandle, msg->name, msg->typeStr,
+              msg->properties, msg->options);
+    } else if (auto msg = std::get_if<net::UnpublishMsg>(&elem.contents)) {
+      Unpublish(msg->pubHandle, msg->topicHandle);
+    } else if (auto msg = std::get_if<net::SetPropertiesMsg>(&elem.contents)) {
+      SetProperties(msg->topicHandle, msg->name, msg->update);
+    }
+  }
+}
+
+void CImpl::SendPeriodic(uint64_t curTimeMs, bool initial) {
+  DEBUG4("SendPeriodic({})", curTimeMs);
+
+  // rate limit sends
+  if (curTimeMs < (m_lastSendMs + kMinPeriodMs)) {
+    return;
+  }
+
+  auto out = m_wire.Send();
+
+  // send keep-alives
+  if (curTimeMs >= m_nextKeepAliveTimeMs) {
+    if (!CheckNetworkReady()) {
+      return;
+    }
+    DEBUG4("Sending keep alive");
+    WireEncodeKeepAlive(out.stream());
+    // drift isn't critical here, so just go from current time
+    m_nextKeepAliveTimeMs = curTimeMs + kKeepAliveIntervalMs;
+  }
+
+  // send any stored-up flags updates
+  if (!m_outgoingFlags.empty()) {
+    if (!CheckNetworkReady()) {
+      return;
+    }
+    for (auto&& p : m_outgoingFlags) {
+      WireEncodeFlagsUpdate(out.stream(), p.first, p.second);
+    }
+    m_outgoingFlags.resize(0);
+  }
+
+  // send any pending updates due to be sent
+  bool checkedNetwork = false;
+  for (auto&& pub : m_publishers) {
+    if (pub && !pub->outValues.empty() && curTimeMs >= pub->nextSendMs) {
+      if (!checkedNetwork) {
+        if (!CheckNetworkReady()) {
+          return;
+        }
+        checkedNetwork = true;
+      }
+      for (auto&& val : pub->outValues) {
+        SendValue(out, pub->entry, val);
+      }
+      pub->outValues.resize(0);
+      pub->nextSendMs = curTimeMs + pub->periodMs;
+    }
+  }
+
+  if (initial) {
+    DEBUG4("Sending ClientHelloDone");
+    WireEncodeClientHelloDone(out.stream());
+  }
+
+  m_wire.Flush();
+  m_lastSendMs = curTimeMs;
+}
+
+void CImpl::SendValue(Writer& out, Entry* entry, const Value& value) {
+  DEBUG4("sending value for '{}', seqnum {}", entry->name,
+         entry->seqNum.value());
+
+  // bump sequence number
+  ++entry->seqNum;
+
+  // only send assigns during initial handshake
+  if (entry->id == 0xffff || m_state == kStateInitialAssignments) {
+    // send assign
+    WireEncodeEntryAssign(out.stream(), entry->name, entry->id,
+                          entry->seqNum.value(), value, entry->flags);
+  } else {
+    // send update
+    WireEncodeEntryUpdate(out.stream(), entry->id, entry->seqNum.value(),
+                          value);
+  }
+}
+
+bool CImpl::CheckNetworkReady() {
+  if (!m_wire.Ready()) {
+    ++m_notReadyCount;
+    if (m_notReadyCount > kWireMaxNotReady) {
+      m_wire.Disconnect("transmit stalled");
+    }
+    return false;
+  }
+  m_notReadyCount = 0;
+  return true;
+}
+
+void CImpl::Publish(NT_Publisher pubHandle, NT_Topic topicHandle,
+                    std::string_view name, std::string_view typeStr,
+                    const wpi::json& properties,
+                    const PubSubOptionsImpl& options) {
+  DEBUG4("Publish('{}', '{}')", name, typeStr);
+  unsigned int index = Handle{pubHandle}.GetIndex();
+  if (index >= m_publishers.size()) {
+    m_publishers.resize(index + 1);
+  }
+  auto& publisher = m_publishers[index];
+  if (!publisher) {
+    publisher = std::make_unique<PublisherData>(GetOrNewEntry(name));
+    publisher->entry->typeStr = typeStr;
+    publisher->entry->type = StringToType3(typeStr);
+    publisher->entry->publishers.emplace_back(publisher.get());
+  }
+  publisher->handle = pubHandle;
+  publisher->options = options;
+  publisher->periodMs = std::lround(options.periodicMs / 10.0) * 10;
+  if (publisher->periodMs < 10) {
+    publisher->periodMs = 10;
+  }
+
+  // update period
+  m_periodMs = std::gcd(m_periodMs, publisher->periodMs);
+  m_setPeriodic(m_periodMs);
+}
+
+void CImpl::Unpublish(NT_Publisher pubHandle, NT_Topic topicHandle) {
+  DEBUG4("Unpublish({}, {})", pubHandle, topicHandle);
+  unsigned int index = Handle{pubHandle}.GetIndex();
+  if (index >= m_publishers.size()) {
+    return;
+  }
+  auto& publisher = m_publishers[index];
+  publisher->entry->publishers.erase(
+      std::remove(publisher->entry->publishers.begin(),
+                  publisher->entry->publishers.end(), publisher.get()),
+      publisher->entry->publishers.end());
+  publisher.reset();
+
+  // loop over all publishers to update period
+  m_periodMs = kKeepAliveIntervalMs + 10;
+  for (auto&& pub : m_publishers) {
+    if (pub) {
+      m_periodMs = std::gcd(m_periodMs, pub->periodMs);
+    }
+  }
+  m_setPeriodic(m_periodMs);
+}
+
+void CImpl::SetProperties(NT_Topic topicHandle, std::string_view name,
+                          const wpi::json& update) {
+  DEBUG4("SetProperties({}, {}, {})", topicHandle, name, update.dump());
+  auto entry = GetOrNewEntry(name);
+  bool updated = false;
+  for (auto&& elem : update.items()) {
+    entry->properties[elem.key()] = elem.value();
+    if (elem.key() == "persistent") {
+      if (auto val = elem.value().get_ptr<const bool*>()) {
+        if (*val) {
+          entry->flags |= NT_PERSISTENT;
+        } else {
+          entry->flags &= ~NT_PERSISTENT;
+        }
+        updated = true;
+      }
+    }
+  }
+  if (updated && entry->id == 0xffff) {
+    m_outgoingFlags.emplace_back(entry->id, entry->flags);
+  }
+}
+
+void CImpl::SetValue(NT_Publisher pubHandle, const Value& value) {
+  DEBUG4("SetValue({})", pubHandle);
+  unsigned int index = Handle{pubHandle}.GetIndex();
+  assert(index < m_publishers.size() && m_publishers[index]);
+  auto& publisher = *m_publishers[index];
+  if (value == publisher.entry->value) {
+    return;
+  }
+  publisher.entry->value = value;
+  if (publisher.outValues.empty() || publisher.options.sendAll) {
+    publisher.outValues.emplace_back(value);
+  } else {
+    publisher.outValues.back() = value;
+  }
+}
+
+void CImpl::KeepAlive() {
+  DEBUG4("KeepAlive()");
+  if (m_state != kStateRunning && m_state != kStateInitialAssignments) {
+    m_decoder.SetError("received unexpected KeepAlive message");
+    return;
+  }
+  // ignore
+}
+
+void CImpl::ServerHelloDone() {
+  DEBUG4("ServerHelloDone()");
+  if (m_state != kStateInitialAssignments) {
+    m_decoder.SetError("received unexpected ServerHelloDone message");
+    return;
+  }
+
+  // send initial assignments
+  SendPeriodic(m_initTimeMs, true);
+
+  m_state = kStateRunning;
+  m_setPeriodic(m_periodMs);
+}
+
+void CImpl::ClientHelloDone() {
+  DEBUG4("ClientHelloDone()");
+  m_decoder.SetError("received unexpected ClientHelloDone message");
+}
+
+void CImpl::ProtoUnsup(unsigned int proto_rev) {
+  DEBUG4("ProtoUnsup({})", proto_rev);
+  m_decoder.SetError(fmt::format("received ProtoUnsup(version={})", proto_rev));
+}
+
+void CImpl::ClientHello(std::string_view self_id, unsigned int proto_rev) {
+  DEBUG4("ClientHello({}, {})", self_id, proto_rev);
+  m_decoder.SetError("received unexpected ClientHello message");
+}
+
+void CImpl::ServerHello(unsigned int flags, std::string_view self_id) {
+  DEBUG4("ServerHello({}, {})", flags, self_id);
+  if (m_state != kStateHelloSent) {
+    m_decoder.SetError("received unexpected ServerHello message");
+    return;
+  }
+  m_state = kStateInitialAssignments;
+  m_remoteId = self_id;
+  m_handshakeSucceeded();
+  m_handshakeSucceeded = nullptr;  // no longer required
+}
+
+void CImpl::EntryAssign(std::string_view name, unsigned int id,
+                        unsigned int seq_num, const Value& value,
+                        unsigned int flags) {
+  DEBUG4("EntryAssign({}, {}, {}, value, {})", name, id, seq_num, flags);
+  if (m_state != kStateInitialAssignments && m_state != kStateRunning) {
+    m_decoder.SetError("received unexpected EntryAssign message");
+    return;
+  }
+  auto entry = GetOrNewEntry(name);
+  bool flagsChanged = entry->flags != flags;
+  bool typeChanged;
+  bool valueChanged;
+
+  // don't update value if we locally published a "strong" value
+  if (m_state == kStateInitialAssignments && entry->value &&
+      entry->value.server_time() != 0) {
+    typeChanged = false;
+    valueChanged = false;
+  } else {
+    typeChanged = entry->type != value.type();
+    valueChanged = entry->value != value;
+    if (m_state == kStateInitialAssignments) {
+      // remove outgoing during initial assignments so we don't get out of sync
+      for (auto publisher : entry->publishers) {
+        publisher->outValues.clear();
+      }
+    }
+  }
+
+  entry->id = id;
+  entry->seqNum = SequenceNumber{seq_num};
+  entry->SetFlags(flags);
+  if (typeChanged) {
+    entry->type = value.type();
+    entry->typeStr = TypeToString(value.type());
+  }
+  if (valueChanged) {
+    entry->value = value;
+  }
+
+  // add to id map
+  if (id >= m_idMap.size()) {
+    m_idMap.resize(id + 1);
+  }
+  m_idMap[id] = entry;
+
+  if (m_local) {
+    // XXX: need to handle type change specially? (e.g. with unannounce)
+    if (entry->topic == 0 || flagsChanged || typeChanged) {
+      DEBUG4("NetworkAnnounce({}, {})", name, entry->typeStr);
+      entry->topic =
+          m_local->NetworkAnnounce(name, entry->typeStr, entry->properties, 0);
+    }
+    if (valueChanged) {
+      m_local->NetworkSetValue(entry->topic, entry->value);
+    }
+  }
+}
+
+void CImpl::EntryUpdate(unsigned int id, unsigned int seq_num,
+                        const Value& value) {
+  DEBUG4("EntryUpdate({}, {}, value)", id, seq_num);
+  if (m_state != kStateRunning) {
+    m_decoder.SetError("received EntryUpdate message before ServerHelloDone");
+    return;
+  }
+  if (auto entry = LookupId(id)) {
+    entry->value = value;
+    if (m_local && entry->topic != 0) {
+      m_local->NetworkSetValue(entry->topic, entry->value);
+    }
+  }
+}
+
+void CImpl::FlagsUpdate(unsigned int id, unsigned int flags) {
+  DEBUG4("FlagsUpdate({}, {})", id, flags);
+  if (m_state != kStateRunning) {
+    m_decoder.SetError("received FlagsUpdate message before ServerHelloDone");
+    return;
+  }
+  if (auto entry = LookupId(id)) {
+    wpi::json update = entry->SetFlags(flags);
+    if (!update.empty() && m_local) {
+      m_local->NetworkPropertiesUpdate(entry->name, update, false);
+    }
+  }
+
+  // erase any outgoing flags updates
+  m_outgoingFlags.erase(
+      std::remove_if(m_outgoingFlags.begin(), m_outgoingFlags.end(),
+                     [&](const auto& p) { return p.first == id; }),
+      m_outgoingFlags.end());
+}
+
+void CImpl::EntryDelete(unsigned int id) {
+  DEBUG4("EntryDelete({})", id);
+  if (m_state != kStateRunning) {
+    m_decoder.SetError("received EntryDelete message before ServerHelloDone");
+    return;
+  }
+  if (auto entry = LookupId(id)) {
+    m_idMap[id] = nullptr;
+    // set id to 0xffff so any future local setvalue will result in assign
+    entry->id = 0xffff;
+    entry->value = Value{};
+
+    // if we have no local publishers, unannounce
+    if (entry->publishers.empty() && m_local) {
+      m_local->NetworkUnannounce(entry->name);
+    }
+  }
+
+  // erase any outgoing flags updates
+  m_outgoingFlags.erase(
+      std::remove_if(m_outgoingFlags.begin(), m_outgoingFlags.end(),
+                     [&](const auto& p) { return p.first == id; }),
+      m_outgoingFlags.end());
+}
+
+void CImpl::ClearEntries() {
+  DEBUG4("ClearEntries()");
+  if (m_state != kStateRunning) {
+    m_decoder.SetError("received ClearEntries message before ServerHelloDone");
+    return;
+  }
+  for (auto& entry : m_idMap) {
+    if (entry && entry->id != 0xffff && !entry->IsPersistent()) {
+      entry->id = 0xffff;
+      entry->value = Value{};
+
+      // if we have no local publishers, unannounce
+      if (entry->publishers.empty() && m_local) {
+        m_local->NetworkUnannounce(entry->name);
+      }
+
+      entry = nullptr;  // clear id mapping
+    }
+  }
+
+  // erase all outgoing flags updates
+  m_outgoingFlags.resize(0);
+}
+
+class ClientImpl3::Impl final : public CImpl {
+ public:
+  Impl(uint64_t curTimeMs, int inst, WireConnection3& wire, wpi::Logger& logger,
+       std::function<void(uint32_t repeatMs)> setPeriodic)
+      : CImpl{curTimeMs, inst, wire, logger, std::move(setPeriodic)} {}
+};
+
+ClientImpl3::ClientImpl3(uint64_t curTimeMs, int inst, WireConnection3& wire,
+                         wpi::Logger& logger,
+                         std::function<void(uint32_t repeatMs)> setPeriodic)
+    : m_impl{std::make_unique<Impl>(curTimeMs, inst, wire, logger,
+                                    std::move(setPeriodic))} {}
+
+ClientImpl3::~ClientImpl3() {
+  WPI_DEBUG4(m_impl->m_logger, "NT3 ClientImpl destroyed");
+}
+
+void ClientImpl3::Start(std::string_view selfId,
+                        std::function<void()> succeeded) {
+  if (m_impl->m_state != CImpl::kStateInitial) {
+    return;
+  }
+  m_impl->m_handshakeSucceeded = std::move(succeeded);
+  auto writer = m_impl->m_wire.Send();
+  WireEncodeClientHello(writer.stream(), selfId, 0x0300);
+  m_impl->m_wire.Flush();
+  m_impl->m_state = CImpl::kStateHelloSent;
+}
+
+void ClientImpl3::ProcessIncoming(std::span<const uint8_t> data) {
+  m_impl->ProcessIncoming(data);
+}
+
+void ClientImpl3::HandleLocal(std::span<const net::ClientMessage> msgs) {
+  m_impl->HandleLocal(msgs);
+}
+
+void ClientImpl3::SendPeriodic(uint64_t curTimeMs) {
+  m_impl->SendPeriodic(curTimeMs, false);
+}
+
+void ClientImpl3::SetLocal(net::LocalInterface* local) {
+  m_impl->m_local = local;
+}
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/net3/ClientImpl3.h b/third_party/allwpilib/ntcore/src/main/native/cpp/net3/ClientImpl3.h
new file mode 100644
index 0000000..484ea3d
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/net3/ClientImpl3.h
@@ -0,0 +1,50 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <stdint.h>
+
+#include <functional>
+#include <memory>
+#include <span>
+#include <string>
+#include <string_view>
+
+#include "net/NetworkInterface.h"
+
+namespace wpi {
+class Logger;
+}  // namespace wpi
+
+namespace nt::net {
+struct ClientMessage;
+class LocalInterface;
+}  // namespace nt::net
+
+namespace nt::net3 {
+
+class WireConnection3;
+
+class ClientImpl3 {
+ public:
+  explicit ClientImpl3(uint64_t curTimeMs, int inst, WireConnection3& wire,
+                       wpi::Logger& logger,
+                       std::function<void(uint32_t repeatMs)> setPeriodic);
+  ~ClientImpl3();
+
+  void Start(std::string_view selfId, std::function<void()> succeeded);
+  void ProcessIncoming(std::span<const uint8_t> data);
+  void HandleLocal(std::span<const net::ClientMessage> msgs);
+
+  void SendPeriodic(uint64_t curTimeMs);
+
+  void SetLocal(net::LocalInterface* local);
+
+ private:
+  class Impl;
+  std::unique_ptr<Impl> m_impl;
+};
+
+}  // namespace nt::net3
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/net3/Message3.h b/third_party/allwpilib/ntcore/src/main/native/cpp/net3/Message3.h
new file mode 100644
index 0000000..ebac75f
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/net3/Message3.h
@@ -0,0 +1,156 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <stdint.h>
+
+#include <span>
+#include <string>
+
+#include "networktables/NetworkTableValue.h"
+#include "ntcore_c.h"
+
+namespace nt::net3 {
+
+class WireDecoder3;
+
+class Message3 {
+  struct private_init {};
+  friend class WireDecoder3;
+
+ public:
+  enum MsgType {
+    kUnknown = -1,
+    kKeepAlive = 0x00,
+    kClientHello = 0x01,
+    kProtoUnsup = 0x02,
+    kServerHelloDone = 0x03,
+    kServerHello = 0x04,
+    kClientHelloDone = 0x05,
+    kEntryAssign = 0x10,
+    kEntryUpdate = 0x11,
+    kFlagsUpdate = 0x12,
+    kEntryDelete = 0x13,
+    kClearEntries = 0x14,
+    kExecuteRpc = 0x20,
+    kRpcResponse = 0x21
+  };
+  enum DataType {
+    kBoolean = 0x00,
+    kDouble = 0x01,
+    kString = 0x02,
+    kRaw = 0x03,
+    kBooleanArray = 0x10,
+    kDoubleArray = 0x11,
+    kStringArray = 0x12,
+    kRpcDef = 0x20
+  };
+  static constexpr uint32_t kClearAllMagic = 0xD06CB27Aul;
+
+  Message3() = default;
+  Message3(MsgType type, const private_init&) : m_type(type) {}
+
+  MsgType type() const { return m_type; }
+  bool Is(MsgType type) const { return type == m_type; }
+
+  // Message data accessors.  Callers are responsible for knowing what data is
+  // actually provided for a particular message.
+  std::string_view str() const { return m_str; }
+  std::span<const uint8_t> bytes() const {
+    return {reinterpret_cast<const uint8_t*>(m_str.data()), m_str.size()};
+  }
+  const Value& value() const { return m_value; }
+  unsigned int id() const { return m_id; }
+  unsigned int flags() const { return m_flags; }
+  unsigned int seq_num_uid() const { return m_seq_num_uid; }
+
+  void SetValue(const Value& value) { m_value = value; }
+
+  // Create messages without data
+  static Message3 KeepAlive() { return {kKeepAlive, {}}; }
+  static Message3 ServerHelloDone() { return {kServerHelloDone, {}}; }
+  static Message3 ClientHelloDone() { return {kClientHelloDone, {}}; }
+  static Message3 ClearEntries() { return {kClearEntries, {}}; }
+
+  // Create messages with data
+  static Message3 ProtoUnsup(unsigned int proto_rev = 0x0300u) {
+    Message3 msg{kProtoUnsup, {}};
+    msg.m_id = proto_rev;
+    return msg;
+  }
+  static Message3 ClientHello(std::string_view self_id,
+                              unsigned int proto_rev = 0x0300u) {
+    Message3 msg{kClientHello, {}};
+    msg.m_str = self_id;
+    msg.m_id = proto_rev;
+    return msg;
+  }
+  static Message3 ServerHello(unsigned int flags, std::string_view self_id) {
+    Message3 msg{kServerHello, {}};
+    msg.m_str = self_id;
+    msg.m_flags = flags;
+    return msg;
+  }
+  static Message3 EntryAssign(std::string_view name, unsigned int id,
+                              unsigned int seq_num, const Value& value,
+                              unsigned int flags) {
+    Message3 msg{kEntryAssign, {}};
+    msg.m_str = name;
+    msg.m_value = value;
+    msg.m_id = id;
+    msg.m_flags = flags;
+    msg.m_seq_num_uid = seq_num;
+    return msg;
+  }
+  static Message3 EntryUpdate(unsigned int id, unsigned int seq_num,
+                              const Value& value) {
+    Message3 msg{kEntryUpdate, {}};
+    msg.m_value = value;
+    msg.m_id = id;
+    msg.m_seq_num_uid = seq_num;
+    return msg;
+  }
+  static Message3 FlagsUpdate(unsigned int id, unsigned int flags) {
+    Message3 msg{kFlagsUpdate, {}};
+    msg.m_id = id;
+    msg.m_flags = flags;
+    return msg;
+  }
+  static Message3 EntryDelete(unsigned int id) {
+    Message3 msg{kEntryDelete, {}};
+    msg.m_id = id;
+    return msg;
+  }
+  static Message3 ExecuteRpc(unsigned int id, unsigned int uid,
+                             std::span<const uint8_t> params) {
+    Message3 msg{kExecuteRpc, {}};
+    msg.m_str.assign(reinterpret_cast<const char*>(params.data()),
+                     params.size());
+    msg.m_id = id;
+    msg.m_seq_num_uid = uid;
+    return msg;
+  }
+  static Message3 RpcResponse(unsigned int id, unsigned int uid,
+                              std::span<const uint8_t> result) {
+    Message3 msg{kRpcResponse, {}};
+    msg.m_str.assign(reinterpret_cast<const char*>(result.data()),
+                     result.size());
+    msg.m_id = id;
+    msg.m_seq_num_uid = uid;
+    return msg;
+  }
+
+ private:
+  MsgType m_type{kUnknown};
+
+  // Message data.  Use varies by message type.
+  std::string m_str;
+  Value m_value;
+  unsigned int m_id{0};  // also used for proto_rev
+  unsigned int m_flags{0};
+  unsigned int m_seq_num_uid{0};
+};
+
+}  // namespace nt::net3
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/net3/SequenceNumber.h b/third_party/allwpilib/ntcore/src/main/native/cpp/net3/SequenceNumber.h
new file mode 100644
index 0000000..d8bf995
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/net3/SequenceNumber.h
@@ -0,0 +1,38 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <compare>
+
+namespace nt::net3 {
+
+/* A sequence number per RFC 1982 */
+class SequenceNumber {
+ public:
+  SequenceNumber() = default;
+  explicit SequenceNumber(unsigned int value) : m_value(value) {}
+  unsigned int value() const { return m_value; }
+
+  SequenceNumber& operator++() {
+    ++m_value;
+    if (m_value > 0xffff) {
+      m_value = 0;
+    }
+    return *this;
+  }
+  SequenceNumber operator++(int) {
+    SequenceNumber tmp(*this);
+    operator++();
+    return tmp;
+  }
+
+  friend auto operator<=>(const SequenceNumber& lhs,
+                          const SequenceNumber& rhs) = default;
+
+ private:
+  unsigned int m_value{0};
+};
+
+}  // namespace nt::net3
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/net3/UvStreamConnection3.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/net3/UvStreamConnection3.cpp
new file mode 100644
index 0000000..93af700
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/net3/UvStreamConnection3.cpp
@@ -0,0 +1,52 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "UvStreamConnection3.h"
+
+#include <wpinet/uv/Stream.h>
+
+using namespace nt;
+using namespace nt::net3;
+
+UvStreamConnection3::UvStreamConnection3(wpi::uv::Stream& stream)
+    : m_stream{stream}, m_os{m_buffers, [this] { return AllocBuf(); }} {}
+
+UvStreamConnection3::~UvStreamConnection3() {
+  for (auto&& buf : m_buf_pool) {
+    buf.Deallocate();
+  }
+}
+
+void UvStreamConnection3::Flush() {
+  if (m_buffers.empty()) {
+    return;
+  }
+  ++m_sendsActive;
+  m_stream.Write(m_buffers, [selfweak = weak_from_this()](auto bufs, auto) {
+    if (auto self = selfweak.lock()) {
+      self->m_buf_pool.insert(self->m_buf_pool.end(), bufs.begin(), bufs.end());
+      if (self->m_sendsActive > 0) {
+        --self->m_sendsActive;
+      }
+    }
+  });
+  m_buffers.clear();
+  m_os.reset();
+}
+
+void UvStreamConnection3::Disconnect(std::string_view reason) {
+  m_reason = reason;
+  m_stream.Close();
+}
+
+void UvStreamConnection3::FinishSend() {}
+
+wpi::uv::Buffer UvStreamConnection3::AllocBuf() {
+  if (!m_buf_pool.empty()) {
+    auto buf = m_buf_pool.back();
+    m_buf_pool.pop_back();
+    return buf;
+  }
+  return wpi::uv::Buffer::Allocate(kAllocSize);
+}
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/net3/UvStreamConnection3.h b/third_party/allwpilib/ntcore/src/main/native/cpp/net3/UvStreamConnection3.h
new file mode 100644
index 0000000..f94c4a3
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/net3/UvStreamConnection3.h
@@ -0,0 +1,60 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <memory>
+#include <string>
+#include <string_view>
+#include <vector>
+
+#include <wpi/SmallVector.h>
+#include <wpinet/raw_uv_ostream.h>
+#include <wpinet/uv/Buffer.h>
+
+#include "net3/WireConnection3.h"
+
+namespace wpi::uv {
+class Stream;
+}  // namespace wpi::uv
+
+namespace nt::net3 {
+
+class UvStreamConnection3 final
+    : public WireConnection3,
+      public std::enable_shared_from_this<UvStreamConnection3> {
+  static constexpr size_t kAllocSize = 4096;
+
+ public:
+  explicit UvStreamConnection3(wpi::uv::Stream& stream);
+  ~UvStreamConnection3() override;
+  UvStreamConnection3(const UvStreamConnection3&) = delete;
+  UvStreamConnection3& operator=(const UvStreamConnection3&) = delete;
+
+  bool Ready() const final { return m_sendsActive == 0; }
+
+  Writer Send() final { return {m_os, *this}; }
+
+  void Flush() final;
+
+  void Disconnect(std::string_view reason) final;
+
+  std::string_view GetDisconnectReason() const { return m_reason; }
+
+  wpi::uv::Stream& GetStream() { return m_stream; }
+
+ private:
+  void FinishSend() final;
+
+  wpi::uv::Buffer AllocBuf();
+
+  wpi::uv::Stream& m_stream;
+  wpi::SmallVector<wpi::uv::Buffer, 4> m_buffers;
+  std::vector<wpi::uv::Buffer> m_buf_pool;
+  wpi::raw_uv_ostream m_os;
+  std::string m_reason;
+  int m_sendsActive = 0;
+};
+
+}  // namespace nt::net3
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/net3/WireConnection3.h b/third_party/allwpilib/ntcore/src/main/native/cpp/net3/WireConnection3.h
new file mode 100644
index 0000000..85453d7
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/net3/WireConnection3.h
@@ -0,0 +1,65 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <string_view>
+
+namespace wpi {
+class raw_ostream;
+}  // namespace wpi
+
+namespace nt::net3 {
+
+class Writer;
+
+class WireConnection3 {
+  friend class Writer;
+
+ public:
+  virtual ~WireConnection3() = default;
+
+  virtual bool Ready() const = 0;
+
+  virtual Writer Send() = 0;
+
+  virtual void Flush() = 0;
+
+  virtual void Disconnect(std::string_view reason) = 0;
+
+ protected:
+  virtual void FinishSend() = 0;
+};
+
+class Writer {
+ public:
+  Writer(wpi::raw_ostream& os, WireConnection3& wire)
+      : m_os{&os}, m_wire{&wire} {}
+  Writer(const Writer&) = delete;
+  Writer(Writer&& rhs) : m_os{rhs.m_os}, m_wire{rhs.m_wire} {
+    rhs.m_os = nullptr;
+    rhs.m_wire = nullptr;
+  }
+  ~Writer() {
+    if (m_wire) {
+      m_wire->FinishSend();
+    }
+  }
+  Writer& operator=(const Writer&) = delete;
+  Writer& operator=(Writer&& rhs) {
+    m_os = rhs.m_os;
+    m_wire = rhs.m_wire;
+    rhs.m_os = nullptr;
+    rhs.m_wire = nullptr;
+    return *this;
+  }
+
+  wpi::raw_ostream& stream() { return *m_os; }
+
+ private:
+  wpi::raw_ostream* m_os;
+  WireConnection3* m_wire;
+};
+
+}  // namespace nt::net3
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/net3/WireDecoder3.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/net3/WireDecoder3.cpp
new file mode 100644
index 0000000..ea08358
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/net3/WireDecoder3.cpp
@@ -0,0 +1,600 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "WireDecoder3.h"
+
+#include <algorithm>
+#include <optional>
+#include <string>
+#include <vector>
+
+#include <fmt/format.h>
+#include <wpi/MathExtras.h>
+#include <wpi/SpanExtras.h>
+#include <wpi/leb128.h>
+
+#include "Message3.h"
+
+using namespace nt;
+using namespace nt::net3;
+
+namespace {
+
+class SimpleValueReader {
+ public:
+  std::optional<uint16_t> Read16(std::span<const uint8_t>* in);
+  std::optional<uint32_t> Read32(std::span<const uint8_t>* in);
+  std::optional<uint64_t> Read64(std::span<const uint8_t>* in);
+  std::optional<double> ReadDouble(std::span<const uint8_t>* in);
+
+ private:
+  uint64_t m_value = 0;
+  int m_count = 0;
+};
+
+struct StringReader {
+  void SetLen(uint64_t len_) {
+    len = len_;
+    buf.clear();
+  }
+
+  std::optional<uint64_t> len;
+  std::string buf;
+};
+
+struct RawReader {
+  void SetLen(uint64_t len_) {
+    len = len_;
+    buf.clear();
+  }
+
+  std::optional<uint64_t> len;
+  std::vector<uint8_t> buf;
+};
+
+struct ValueReader {
+  ValueReader() = default;
+  explicit ValueReader(NT_Type type_) : type{type_} {}
+
+  void SetSize(uint32_t size_) {
+    haveSize = true;
+    size = size_;
+    ints.clear();
+    doubles.clear();
+    strings.clear();
+  }
+
+  NT_Type type = NT_UNASSIGNED;
+  bool haveSize = false;
+  uint32_t size = 0;
+  std::vector<int> ints;
+  std::vector<double> doubles;
+  std::vector<std::string> strings;
+};
+
+struct WDImpl {
+  explicit WDImpl(MessageHandler3& out) : m_out{out} {}
+
+  MessageHandler3& m_out;
+
+  // primary (message) decode state
+  enum {
+    kStart,
+    kClientHello_1ProtoRev,
+    kClientHello_2Id,
+    kProtoUnsup_1ProtoRev,
+    kServerHello_1Flags,
+    kServerHello_2Id,
+    kEntryAssign_1Name,
+    kEntryAssign_2Type,
+    kEntryAssign_3Id,
+    kEntryAssign_4SeqNum,
+    kEntryAssign_5Flags,
+    kEntryAssign_6Value,
+    kEntryUpdate_1Id,
+    kEntryUpdate_2SeqNum,
+    kEntryUpdate_3Type,
+    kEntryUpdate_4Value,
+    kFlagsUpdate_1Id,
+    kFlagsUpdate_2Flags,
+    kEntryDelete_1Id,
+    kClearEntries_1Magic,
+    kExecuteRpc_1Id,
+    kExecuteRpc_2Uid,
+    kExecuteRpc_3Params,
+    kRpcResponse_1Id,
+    kRpcResponse_2Uid,
+    kRpcResponse_3Result,
+    kError
+  } m_state = kStart;
+
+  // detail decoders
+  wpi::Uleb128Reader m_ulebReader;
+  SimpleValueReader m_simpleReader;
+  StringReader m_stringReader;
+  RawReader m_rawReader;
+  ValueReader m_valueReader;
+
+  std::string m_error;
+
+  std::string m_str;
+  unsigned int m_id{0};  // also used for proto_rev
+  unsigned int m_flags{0};
+  unsigned int m_seq_num_uid{0};
+
+  void Execute(std::span<const uint8_t>* in);
+
+  std::nullopt_t EmitError(std::string_view msg) {
+    m_state = kError;
+    m_error = msg;
+    return std::nullopt;
+  }
+
+  std::optional<std::string> ReadString(std::span<const uint8_t>* in);
+  std::optional<std::vector<uint8_t>> ReadRaw(std::span<const uint8_t>* in);
+  std::optional<NT_Type> ReadType(std::span<const uint8_t>* in);
+  std::optional<Value> ReadValue(std::span<const uint8_t>* in);
+};
+
+}  // namespace
+
+static uint8_t Read8(std::span<const uint8_t>* in) {
+  uint8_t val = in->front();
+  *in = wpi::drop_front(*in);
+  return val;
+}
+
+std::optional<uint16_t> SimpleValueReader::Read16(
+    std::span<const uint8_t>* in) {
+  while (!in->empty()) {
+    m_value <<= 8;
+    m_value |= in->front() & 0xff;
+    *in = wpi::drop_front(*in);
+    if (++m_count >= 2) {
+      uint16_t val = static_cast<uint16_t>(m_value);
+      m_count = 0;
+      m_value = 0;
+      return val;
+    }
+  }
+  return std::nullopt;
+}
+
+std::optional<uint32_t> SimpleValueReader::Read32(
+    std::span<const uint8_t>* in) {
+  while (!in->empty()) {
+    m_value <<= 8;
+    m_value |= in->front() & 0xff;
+    *in = wpi::drop_front(*in);
+    if (++m_count >= 4) {
+      uint32_t val = static_cast<uint32_t>(m_value);
+      m_count = 0;
+      m_value = 0;
+      return val;
+    }
+  }
+  return std::nullopt;
+}
+
+std::optional<uint64_t> SimpleValueReader::Read64(
+    std::span<const uint8_t>* in) {
+  while (!in->empty()) {
+    m_value <<= 8;
+    m_value |= in->front() & 0xff;
+    *in = wpi::drop_front(*in);
+    if (++m_count >= 8) {
+      uint64_t val = m_value;
+      m_count = 0;
+      m_value = 0;
+      return val;
+    }
+  }
+  return std::nullopt;
+}
+
+std::optional<double> SimpleValueReader::ReadDouble(
+    std::span<const uint8_t>* in) {
+  if (auto val = Read64(in)) {
+    return wpi::BitsToDouble(val.value());
+  } else {
+    return std::nullopt;
+  }
+}
+
+void WDImpl::Execute(std::span<const uint8_t>* in) {
+  while (!in->empty()) {
+    switch (m_state) {
+      case kStart: {
+        uint8_t msgType = Read8(in);
+        switch (msgType) {
+          case Message3::kKeepAlive:
+            m_out.KeepAlive();
+            break;
+          case Message3::kClientHello:
+            m_state = kClientHello_1ProtoRev;
+            break;
+          case Message3::kProtoUnsup:
+            m_state = kProtoUnsup_1ProtoRev;
+            break;
+          case Message3::kServerHello:
+            m_state = kServerHello_1Flags;
+            break;
+          case Message3::kServerHelloDone:
+            m_out.ServerHelloDone();
+            break;
+          case Message3::kClientHelloDone:
+            m_out.ClientHelloDone();
+            break;
+          case Message3::kEntryAssign:
+            m_state = kEntryAssign_1Name;
+            break;
+          case Message3::kEntryUpdate:
+            m_state = kEntryUpdate_1Id;
+            break;
+          case Message3::kFlagsUpdate:
+            m_state = kFlagsUpdate_1Id;
+            break;
+          case Message3::kEntryDelete:
+            m_state = kEntryDelete_1Id;
+            break;
+          case Message3::kClearEntries:
+            m_state = kClearEntries_1Magic;
+            break;
+          case Message3::kExecuteRpc:
+            m_state = kExecuteRpc_1Id;
+            break;
+          case Message3::kRpcResponse:
+            m_state = kRpcResponse_1Id;
+            break;
+          default:
+            EmitError(fmt::format("unrecognized message type: {}",
+                                  static_cast<uint32_t>(msgType)));
+            return;
+        }
+        break;
+      }
+      case kClientHello_1ProtoRev:
+        if (auto val = m_simpleReader.Read16(in)) {
+          if (val < 0x0300u) {
+            m_state = kStart;
+            m_out.ClientHello("", val.value());
+          } else {
+            m_state = kClientHello_2Id;
+            m_id = val.value();
+          }
+        }
+        break;
+      case kClientHello_2Id:
+        if (auto val = ReadString(in)) {
+          m_state = kStart;
+          m_out.ClientHello(val.value(), m_id);
+        }
+        break;
+      case kProtoUnsup_1ProtoRev:
+        if (auto val = m_simpleReader.Read16(in)) {
+          m_state = kStart;
+          m_out.ProtoUnsup(val.value());
+        }
+        break;
+      case kServerHello_1Flags: {
+        m_state = kServerHello_2Id;
+        m_flags = Read8(in);
+        break;
+      }
+      case kServerHello_2Id:
+        if (auto val = ReadString(in)) {
+          m_state = kStart;
+          m_out.ServerHello(m_flags, val.value());
+        }
+        break;
+      case kEntryAssign_1Name:
+        if (auto val = ReadString(in)) {
+          m_state = kEntryAssign_2Type;
+          m_str = std::move(val.value());
+        }
+        break;
+      case kEntryAssign_2Type:
+        if (auto val = ReadType(in)) {
+          m_state = kEntryAssign_3Id;
+          m_valueReader = ValueReader{val.value()};
+        }
+        break;
+      case kEntryAssign_3Id:
+        if (auto val = m_simpleReader.Read16(in)) {
+          m_state = kEntryAssign_4SeqNum;
+          m_id = val.value();
+        }
+        break;
+      case kEntryAssign_4SeqNum:
+        if (auto val = m_simpleReader.Read16(in)) {
+          m_state = kEntryAssign_5Flags;
+          m_seq_num_uid = val.value();
+        }
+        break;
+      case kEntryAssign_5Flags: {
+        m_state = kEntryAssign_6Value;
+        m_flags = Read8(in);
+        break;
+      }
+      case kEntryAssign_6Value:
+        if (auto val = ReadValue(in)) {
+          m_state = kStart;
+          m_out.EntryAssign(m_str, m_id, m_seq_num_uid, val.value(), m_flags);
+        }
+        break;
+      case kEntryUpdate_1Id:
+        if (auto val = m_simpleReader.Read16(in)) {
+          m_state = kEntryUpdate_2SeqNum;
+          m_id = val.value();
+        }
+        break;
+      case kEntryUpdate_2SeqNum:
+        if (auto val = m_simpleReader.Read16(in)) {
+          m_state = kEntryUpdate_3Type;
+          m_seq_num_uid = val.value();
+        }
+        break;
+      case kEntryUpdate_3Type:
+        if (auto val = ReadType(in)) {
+          m_state = kEntryUpdate_4Value;
+          m_valueReader = ValueReader{val.value()};
+        }
+        break;
+      case kEntryUpdate_4Value:
+        if (auto val = ReadValue(in)) {
+          m_state = kStart;
+          m_out.EntryUpdate(m_id, m_seq_num_uid, val.value());
+        }
+        break;
+      case kFlagsUpdate_1Id:
+        if (auto val = m_simpleReader.Read16(in)) {
+          m_state = kFlagsUpdate_2Flags;
+          m_id = val.value();
+        }
+        break;
+      case kFlagsUpdate_2Flags: {
+        m_state = kStart;
+        m_out.FlagsUpdate(m_id, Read8(in));
+        break;
+      }
+      case kEntryDelete_1Id:
+        if (auto val = m_simpleReader.Read16(in)) {
+          m_state = kStart;
+          m_out.EntryDelete(val.value());
+        }
+        break;
+      case kClearEntries_1Magic:
+        if (auto val = m_simpleReader.Read32(in)) {
+          m_state = kStart;
+          if (val.value() == Message3::kClearAllMagic) {
+            m_out.ClearEntries();
+          } else {
+            EmitError("received incorrect CLEAR_ENTRIES magic value");
+          }
+          break;
+        }
+        break;
+      case kExecuteRpc_1Id:
+        if (auto val = m_simpleReader.Read16(in)) {
+          m_state = kExecuteRpc_2Uid;
+          m_id = val.value();
+        }
+        break;
+      case kExecuteRpc_2Uid:
+        if (auto val = m_simpleReader.Read16(in)) {
+          m_state = kExecuteRpc_3Params;
+          m_seq_num_uid = val.value();
+        }
+        break;
+      case kExecuteRpc_3Params:
+        if (auto val = ReadRaw(in)) {
+          m_state = kStart;
+          m_out.ExecuteRpc(m_id, m_seq_num_uid, val.value());
+        }
+        break;
+      case kRpcResponse_1Id:
+        if (auto val = m_simpleReader.Read16(in)) {
+          m_state = kRpcResponse_2Uid;
+          m_id = val.value();
+        }
+        break;
+      case kRpcResponse_2Uid:
+        if (auto val = m_simpleReader.Read16(in)) {
+          m_state = kRpcResponse_3Result;
+          m_seq_num_uid = val.value();
+        }
+        break;
+      case kRpcResponse_3Result:
+        if (auto val = ReadRaw(in)) {
+          m_state = kStart;
+          m_out.RpcResponse(m_id, m_seq_num_uid, val.value());
+        }
+        break;
+      case kError:
+        return;
+    }
+  }
+}
+
+std::optional<std::string> WDImpl::ReadString(std::span<const uint8_t>* in) {
+  // string length
+  if (!m_stringReader.len) {
+    if (auto val = m_ulebReader.ReadOne(in)) {
+      m_stringReader.SetLen(val.value());
+      m_stringReader.buf.clear();
+    } else {
+      return std::nullopt;
+    }
+  }
+
+  // string data; nolint to avoid clang-tidy false positive
+  size_t toCopy =
+      (std::min)(in->size(),
+                 static_cast<size_t>(m_stringReader.len.value() -
+                                     m_stringReader.buf.size()));  // NOLINT
+  m_stringReader.buf.append(reinterpret_cast<const char*>(in->data()), toCopy);
+  *in = wpi::drop_front(*in, toCopy);
+  if (m_stringReader.buf.size() >= m_stringReader.len) {
+    m_stringReader.len.reset();
+    return std::move(m_stringReader.buf);
+  }
+  return std::nullopt;
+}
+
+std::optional<std::vector<uint8_t>> WDImpl::ReadRaw(
+    std::span<const uint8_t>* in) {
+  // string length
+  if (!m_rawReader.len) {
+    if (auto val = m_ulebReader.ReadOne(in)) {
+      m_rawReader.SetLen(val.value());
+      m_rawReader.buf.clear();
+    } else {
+      return std::nullopt;
+    }
+  }
+
+  // string data
+  size_t toCopy = (std::min)(
+      static_cast<size_t>(in->size()),
+      static_cast<size_t>(m_rawReader.len.value() - m_rawReader.buf.size()));
+  m_rawReader.buf.insert(m_rawReader.buf.end(), in->begin(),
+                         in->begin() + toCopy);
+  *in = wpi::drop_front(*in, toCopy);
+  if (m_rawReader.buf.size() >= m_rawReader.len) {
+    m_rawReader.len.reset();
+    return std::move(m_rawReader.buf);
+  }
+  return std::nullopt;
+}
+
+std::optional<NT_Type> WDImpl::ReadType(std::span<const uint8_t>* in) {
+  // Convert from byte value to enum
+  switch (Read8(in)) {
+    case Message3::kBoolean:
+      return NT_BOOLEAN;
+    case Message3::kDouble:
+      return NT_DOUBLE;
+    case Message3::kString:
+      return NT_STRING;
+    case Message3::kRaw:
+      return NT_RAW;
+    case Message3::kBooleanArray:
+      return NT_BOOLEAN_ARRAY;
+    case Message3::kDoubleArray:
+      return NT_DOUBLE_ARRAY;
+    case Message3::kStringArray:
+      return NT_STRING_ARRAY;
+    case Message3::kRpcDef:
+      return NT_RPC;
+    default:
+      return EmitError("unrecognized value type");
+  }
+}
+
+std::optional<Value> WDImpl::ReadValue(std::span<const uint8_t>* in) {
+  while (!in->empty()) {
+    switch (m_valueReader.type) {
+      case NT_BOOLEAN:
+        return Value::MakeBoolean(Read8(in) != 0);
+      case NT_DOUBLE:
+        if (auto val = m_simpleReader.ReadDouble(in)) {
+          return Value::MakeDouble(val.value());
+        }
+        break;
+      case NT_STRING:
+        if (auto val = ReadString(in)) {
+          return Value::MakeString(std::move(val.value()));
+        }
+        break;
+      case NT_RAW:
+      case NT_RPC:
+        if (auto val = ReadRaw(in)) {
+          return Value::MakeRaw(std::move(val.value()));
+        }
+        break;
+#if 0
+      case NT_RPC:
+        if (auto val = ReadRaw(in)) {
+          return Value::MakeRpc(std::move(val.value()));
+        }
+        break;
+#endif
+      case NT_BOOLEAN_ARRAY:
+        // size
+        if (!m_valueReader.haveSize) {
+          m_valueReader.SetSize(Read8(in));
+          break;
+        }
+
+        // array values
+        while (!in->empty() && m_valueReader.ints.size() < m_valueReader.size) {
+          m_valueReader.ints.emplace_back(Read8(in) ? 1 : 0);
+        }
+        if (m_valueReader.ints.size() == m_valueReader.size) {
+          return Value::MakeBooleanArray(std::move(m_valueReader.ints));
+        }
+        break;
+      case NT_DOUBLE_ARRAY:
+        // size
+        if (!m_valueReader.haveSize) {
+          m_valueReader.SetSize(Read8(in));
+          break;
+        }
+
+        // array values
+        while (!in->empty() &&
+               m_valueReader.doubles.size() < m_valueReader.size) {
+          if (auto val = m_simpleReader.ReadDouble(in)) {
+            m_valueReader.doubles.emplace_back(std::move(val.value()));
+          }
+        }
+        if (m_valueReader.doubles.size() == m_valueReader.size) {
+          return Value::MakeDoubleArray(std::move(m_valueReader.doubles));
+        }
+        break;
+      case NT_STRING_ARRAY:
+        // size
+        if (!m_valueReader.haveSize) {
+          m_valueReader.SetSize(Read8(in));
+          break;
+        }
+
+        // array values
+        while (!in->empty() &&
+               m_valueReader.strings.size() < m_valueReader.size) {
+          if (auto val = ReadString(in)) {
+            m_valueReader.strings.emplace_back(std::move(val.value()));
+          }
+        }
+        if (m_valueReader.strings.size() == m_valueReader.size) {
+          return Value::MakeStringArray(std::move(m_valueReader.strings));
+        }
+        break;
+      default:
+        return EmitError("invalid type when trying to read value");
+    }
+  }
+  return std::nullopt;
+}
+
+struct WireDecoder3::Impl : public WDImpl {
+  explicit Impl(MessageHandler3& out) : WDImpl{out} {}
+};
+
+WireDecoder3::WireDecoder3(MessageHandler3& out) : m_impl{new Impl{out}} {}
+
+WireDecoder3::~WireDecoder3() = default;
+
+bool WireDecoder3::Execute(std::span<const uint8_t>* in) {
+  m_impl->Execute(in);
+  return m_impl->m_state != Impl::kError;
+}
+
+void WireDecoder3::SetError(std::string_view message) {
+  m_impl->EmitError(message);
+}
+
+std::string WireDecoder3::GetError() const {
+  return m_impl->m_error;
+}
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/net3/WireDecoder3.h b/third_party/allwpilib/ntcore/src/main/native/cpp/net3/WireDecoder3.h
new file mode 100644
index 0000000..e877833
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/net3/WireDecoder3.h
@@ -0,0 +1,64 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <stdint.h>
+
+#include <memory>
+#include <span>
+#include <string>
+
+namespace nt {
+class Value;
+}  // namespace nt
+
+namespace nt::net3 {
+
+class MessageHandler3 {
+ public:
+  virtual void KeepAlive() = 0;
+  virtual void ServerHelloDone() = 0;
+  virtual void ClientHelloDone() = 0;
+  virtual void ClearEntries() = 0;
+  virtual void ProtoUnsup(unsigned int proto_rev) = 0;
+  virtual void ClientHello(std::string_view self_id,
+                           unsigned int proto_rev) = 0;
+  virtual void ServerHello(unsigned int flags, std::string_view self_id) = 0;
+  virtual void EntryAssign(std::string_view name, unsigned int id,
+                           unsigned int seq_num, const Value& value,
+                           unsigned int flags) = 0;
+  virtual void EntryUpdate(unsigned int id, unsigned int seq_num,
+                           const Value& value) = 0;
+  virtual void FlagsUpdate(unsigned int id, unsigned int flags) = 0;
+  virtual void EntryDelete(unsigned int id) = 0;
+  virtual void ExecuteRpc(unsigned int id, unsigned int uid,
+                          std::span<const uint8_t> params) = 0;
+  virtual void RpcResponse(unsigned int id, unsigned int uid,
+                           std::span<const uint8_t> result) = 0;
+};
+
+/* Decodes NT3 protocol into native representation. */
+class WireDecoder3 {
+ public:
+  explicit WireDecoder3(MessageHandler3& out);
+  ~WireDecoder3();
+
+  /**
+   * Executes the decoder.  All input data will be consumed unless an error
+   * occurs.
+   * @param in input data (updated during parse)
+   * @return false if error occurred
+   */
+  bool Execute(std::span<const uint8_t>* in);
+
+  void SetError(std::string_view message);
+  std::string GetError() const;
+
+ private:
+  struct Impl;
+  std::unique_ptr<Impl> m_impl;
+};
+
+}  // namespace nt::net3
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/net3/WireEncoder3.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/net3/WireEncoder3.cpp
new file mode 100644
index 0000000..6bf3435
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/net3/WireEncoder3.cpp
@@ -0,0 +1,326 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "WireEncoder3.h"
+
+#include <wpi/MathExtras.h>
+#include <wpi/SmallVector.h>
+#include <wpi/leb128.h>
+#include <wpi/raw_ostream.h>
+
+#include "Message3.h"
+
+using namespace nt;
+using namespace nt::net3;
+
+static void Write8(wpi::raw_ostream& os, uint8_t val) {
+  os << val;
+}
+
+static void Write16(wpi::raw_ostream& os, uint16_t val) {
+  os << std::span<const uint8_t>{{static_cast<uint8_t>((val >> 8) & 0xff),
+                                  static_cast<uint8_t>(val & 0xff)}};
+}
+
+static void Write32(wpi::raw_ostream& os, uint32_t val) {
+  os << std::span<const uint8_t>{{static_cast<uint8_t>((val >> 24) & 0xff),
+                                  static_cast<uint8_t>((val >> 16) & 0xff),
+                                  static_cast<uint8_t>((val >> 8) & 0xff),
+                                  static_cast<uint8_t>(val & 0xff)}};
+}
+
+static void WriteDouble(wpi::raw_ostream& os, double val) {
+  // The highest performance way to do this, albeit non-portable.
+  uint64_t v = wpi::DoubleToBits(val);
+  os << std::span<const uint8_t>{{static_cast<uint8_t>((v >> 56) & 0xff),
+                                  static_cast<uint8_t>((v >> 48) & 0xff),
+                                  static_cast<uint8_t>((v >> 40) & 0xff),
+                                  static_cast<uint8_t>((v >> 32) & 0xff),
+                                  static_cast<uint8_t>((v >> 24) & 0xff),
+                                  static_cast<uint8_t>((v >> 16) & 0xff),
+                                  static_cast<uint8_t>((v >> 8) & 0xff),
+                                  static_cast<uint8_t>(v & 0xff)}};
+}
+
+static void WriteString(wpi::raw_ostream& os, std::string_view str) {
+  wpi::WriteUleb128(os, str.size());
+  os << str;
+}
+
+static void WriteRaw(wpi::raw_ostream& os, std::span<const uint8_t> str) {
+  wpi::WriteUleb128(os, str.size());
+  os << str;
+}
+
+static bool WriteType(wpi::raw_ostream& os, NT_Type type) {
+  char ch;
+  // Convert from enum to actual byte value.
+  switch (type) {
+    case NT_BOOLEAN:
+      ch = Message3::kBoolean;
+      break;
+    case NT_INTEGER:
+    case NT_FLOAT:
+    case NT_DOUBLE:
+      ch = Message3::kDouble;
+      break;
+    case NT_STRING:
+      ch = Message3::kString;
+      break;
+    case NT_RAW:
+      ch = Message3::kRaw;
+      break;
+    case NT_BOOLEAN_ARRAY:
+      ch = Message3::kBooleanArray;
+      break;
+    case NT_INTEGER_ARRAY:
+    case NT_FLOAT_ARRAY:
+    case NT_DOUBLE_ARRAY:
+      ch = Message3::kDoubleArray;
+      break;
+    case NT_STRING_ARRAY:
+      ch = Message3::kStringArray;
+      break;
+    case NT_RPC:
+      ch = Message3::kRpcDef;
+      break;
+    default:
+      return false;
+  }
+  os << ch;
+  return true;
+}
+
+static bool WriteValue(wpi::raw_ostream& os, const Value& value) {
+  switch (value.type()) {
+    case NT_BOOLEAN:
+      Write8(os, value.GetBoolean() ? 1 : 0);
+      break;
+    case NT_INTEGER:
+      WriteDouble(os, value.GetInteger());
+      break;
+    case NT_FLOAT:
+      WriteDouble(os, value.GetFloat());
+      break;
+    case NT_DOUBLE:
+      WriteDouble(os, value.GetDouble());
+      break;
+    case NT_STRING:
+      WriteString(os, value.GetString());
+      break;
+    case NT_RAW:
+      WriteRaw(os, value.GetRaw());
+      break;
+    case NT_RPC:
+      WriteRaw(os, value.GetRaw());
+      break;
+    case NT_BOOLEAN_ARRAY: {
+      auto v = value.GetBooleanArray();
+      size_t size = v.size();
+      if (size > 0xff) {
+        size = 0xff;  // size is only 1 byte, truncate
+      }
+      Write8(os, size);
+
+      for (size_t i = 0; i < size; ++i) {
+        Write8(os, v[i] ? 1 : 0);
+      }
+      break;
+    }
+    case NT_INTEGER_ARRAY: {
+      auto v = value.GetIntegerArray();
+      size_t size = v.size();
+      if (size > 0xff) {
+        size = 0xff;  // size is only 1 byte, truncate
+      }
+      Write8(os, size);
+
+      for (size_t i = 0; i < size; ++i) {
+        WriteDouble(os, v[i]);
+      }
+      break;
+    }
+    case NT_FLOAT_ARRAY: {
+      auto v = value.GetFloatArray();
+      size_t size = v.size();
+      if (size > 0xff) {
+        size = 0xff;  // size is only 1 byte, truncate
+      }
+      Write8(os, size);
+
+      for (size_t i = 0; i < size; ++i) {
+        WriteDouble(os, v[i]);
+      }
+      break;
+    }
+    case NT_DOUBLE_ARRAY: {
+      auto v = value.GetDoubleArray();
+      size_t size = v.size();
+      if (size > 0xff) {
+        size = 0xff;  // size is only 1 byte, truncate
+      }
+      Write8(os, size);
+
+      for (size_t i = 0; i < size; ++i) {
+        WriteDouble(os, v[i]);
+      }
+      break;
+    }
+    case NT_STRING_ARRAY: {
+      auto v = value.GetStringArray();
+      size_t size = v.size();
+      if (size > 0xff) {
+        size = 0xff;  // size is only 1 byte, truncate
+      }
+      Write8(os, size);
+
+      for (size_t i = 0; i < size; ++i) {
+        WriteString(os, v[i]);
+      }
+      break;
+    }
+    default:
+      return false;
+  }
+  return true;
+}
+
+void nt::net3::WireEncodeKeepAlive(wpi::raw_ostream& os) {
+  Write8(os, Message3::kKeepAlive);
+}
+
+void nt::net3::WireEncodeServerHelloDone(wpi::raw_ostream& os) {
+  Write8(os, Message3::kServerHelloDone);
+}
+
+void nt::net3::WireEncodeClientHelloDone(wpi::raw_ostream& os) {
+  Write8(os, Message3::kClientHelloDone);
+}
+
+void nt::net3::WireEncodeClearEntries(wpi::raw_ostream& os) {
+  Write8(os, Message3::kClearEntries);
+  Write32(os, Message3::kClearAllMagic);
+}
+
+void nt::net3::WireEncodeProtoUnsup(wpi::raw_ostream& os,
+                                    unsigned int proto_rev) {
+  Write8(os, Message3::kProtoUnsup);
+  Write16(os, proto_rev);
+}
+
+void nt::net3::WireEncodeClientHello(wpi::raw_ostream& os,
+                                     std::string_view self_id,
+                                     unsigned int proto_rev) {
+  Write8(os, Message3::kClientHello);
+  Write16(os, proto_rev);
+  WriteString(os, self_id);
+}
+
+void nt::net3::WireEncodeServerHello(wpi::raw_ostream& os, unsigned int flags,
+                                     std::string_view self_id) {
+  Write8(os, Message3::kServerHello);
+  Write8(os, flags);
+  WriteString(os, self_id);
+}
+
+bool nt::net3::WireEncodeEntryAssign(wpi::raw_ostream& os,
+                                     std::string_view name, unsigned int id,
+                                     unsigned int seq_num, const Value& value,
+                                     unsigned int flags) {
+  Write8(os, Message3::kEntryAssign);
+  WriteString(os, name);
+  WriteType(os, value.type());
+  Write16(os, id);
+  Write16(os, seq_num);
+  Write8(os, flags);
+  return WriteValue(os, value);
+}
+
+bool nt::net3::WireEncodeEntryUpdate(wpi::raw_ostream& os, unsigned int id,
+                                     unsigned int seq_num, const Value& value) {
+  Write8(os, Message3::kEntryUpdate);
+  Write16(os, id);
+  Write16(os, seq_num);
+  WriteType(os, value.type());
+  return WriteValue(os, value);
+}
+
+void nt::net3::WireEncodeFlagsUpdate(wpi::raw_ostream& os, unsigned int id,
+                                     unsigned int flags) {
+  Write8(os, Message3::kFlagsUpdate);
+  Write16(os, id);
+  Write8(os, flags);
+}
+
+void nt::net3::WireEncodeEntryDelete(wpi::raw_ostream& os, unsigned int id) {
+  Write8(os, Message3::kEntryDelete);
+  Write16(os, id);
+}
+
+void nt::net3::WireEncodeExecuteRpc(wpi::raw_ostream& os, unsigned int id,
+                                    unsigned int uid,
+                                    std::span<const uint8_t> params) {
+  Write8(os, Message3::kExecuteRpc);
+  Write16(os, id);
+  Write16(os, uid);
+  WriteRaw(os, params);
+}
+
+void nt::net3::WireEncodeRpcResponse(wpi::raw_ostream& os, unsigned int id,
+                                     unsigned int uid,
+                                     std::span<const uint8_t> result) {
+  Write8(os, Message3::kRpcResponse);
+  Write16(os, id);
+  Write16(os, uid);
+  WriteRaw(os, result);
+}
+
+bool nt::net3::WireEncode(wpi::raw_ostream& os, const Message3& msg) {
+  switch (msg.type()) {
+    case Message3::kKeepAlive:
+      WireEncodeKeepAlive(os);
+      break;
+    case Message3::kServerHelloDone:
+      WireEncodeServerHelloDone(os);
+      break;
+    case Message3::kClientHelloDone:
+      WireEncodeClientHelloDone(os);
+      break;
+    case Message3::kClientHello:
+      WireEncodeClientHello(os, msg.str(), msg.id());
+      break;
+    case Message3::kProtoUnsup:
+      WireEncodeProtoUnsup(os, msg.id());
+      break;
+    case Message3::kServerHello:
+      WireEncodeServerHello(os, msg.flags(), msg.str());
+      break;
+    case Message3::kEntryAssign:
+      return WireEncodeEntryAssign(os, msg.str(), msg.id(), msg.seq_num_uid(),
+                                   msg.value(), msg.flags());
+    case Message3::kEntryUpdate:
+      return WireEncodeEntryUpdate(os, msg.id(), msg.seq_num_uid(),
+                                   msg.value());
+    case Message3::kFlagsUpdate:
+      WireEncodeFlagsUpdate(os, msg.id(), msg.flags());
+      break;
+    case Message3::kEntryDelete:
+      WireEncodeEntryDelete(os, msg.id());
+      break;
+    case Message3::kClearEntries:
+      WireEncodeClearEntries(os);
+      break;
+    case Message3::kExecuteRpc:
+      WireEncodeExecuteRpc(os, msg.id(), msg.seq_num_uid(), msg.bytes());
+      break;
+    case Message3::kRpcResponse:
+      WireEncodeRpcResponse(os, msg.id(), msg.seq_num_uid(), msg.bytes());
+      break;
+    case Message3::kUnknown:
+      return true;  // ignore
+    default:
+      return false;
+  }
+  return true;
+}
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/net3/WireEncoder3.h b/third_party/allwpilib/ntcore/src/main/native/cpp/net3/WireEncoder3.h
new file mode 100644
index 0000000..66be9ae
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/net3/WireEncoder3.h
@@ -0,0 +1,49 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <stdint.h>
+
+#include <span>
+#include <string_view>
+
+namespace wpi {
+class raw_ostream;
+}  // namespace wpi
+
+namespace nt {
+class Value;
+}  // namespace nt
+
+namespace nt::net3 {
+
+class Message3;
+
+// encoders for messages (avoids need to construct a Message struct)
+void WireEncodeKeepAlive(wpi::raw_ostream& os);
+void WireEncodeServerHelloDone(wpi::raw_ostream& os);
+void WireEncodeClientHelloDone(wpi::raw_ostream& os);
+void WireEncodeClearEntries(wpi::raw_ostream& os);
+void WireEncodeProtoUnsup(wpi::raw_ostream& os, unsigned int proto_rev);
+void WireEncodeClientHello(wpi::raw_ostream& os, std::string_view self_id,
+                           unsigned int proto_rev);
+void WireEncodeServerHello(wpi::raw_ostream& os, unsigned int flags,
+                           std::string_view self_id);
+bool WireEncodeEntryAssign(wpi::raw_ostream& os, std::string_view name,
+                           unsigned int id, unsigned int seq_num,
+                           const Value& value, unsigned int flags);
+bool WireEncodeEntryUpdate(wpi::raw_ostream& os, unsigned int id,
+                           unsigned int seq_num, const Value& value);
+void WireEncodeFlagsUpdate(wpi::raw_ostream& os, unsigned int id,
+                           unsigned int flags);
+void WireEncodeEntryDelete(wpi::raw_ostream& os, unsigned int id);
+void WireEncodeExecuteRpc(wpi::raw_ostream& os, unsigned int id,
+                          unsigned int uid, std::span<const uint8_t> params);
+void WireEncodeRpcResponse(wpi::raw_ostream& os, unsigned int id,
+                           unsigned int uid, std::span<const uint8_t> result);
+
+bool WireEncode(wpi::raw_ostream& os, const Message3& msg);
+
+}  // namespace nt::net3
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/networktables/NetworkTable.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/networktables/NetworkTable.cpp
index 0c28dd4..1f6a760 100644
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/networktables/NetworkTable.cpp
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/networktables/NetworkTable.cpp
@@ -12,8 +12,20 @@
 #include <wpi/StringExtras.h>
 #include <wpi/StringMap.h>
 
+#include "networktables/BooleanArrayTopic.h"
+#include "networktables/BooleanTopic.h"
+#include "networktables/DoubleArrayTopic.h"
+#include "networktables/DoubleTopic.h"
+#include "networktables/FloatArrayTopic.h"
+#include "networktables/FloatTopic.h"
+#include "networktables/IntegerArrayTopic.h"
+#include "networktables/IntegerTopic.h"
 #include "networktables/NetworkTableInstance.h"
+#include "networktables/RawTopic.h"
+#include "networktables/StringArrayTopic.h"
+#include "networktables/StringTopic.h"
 #include "ntcore.h"
+#include "ntcore_cpp.h"
 
 using namespace nt;
 
@@ -78,11 +90,7 @@
                            const private_init&)
     : m_inst(inst), m_path(path) {}
 
-NetworkTable::~NetworkTable() {
-  for (auto i : m_listeners) {
-    RemoveEntryListener(i);
-  }
-}
+NetworkTable::~NetworkTable() = default;
 
 NetworkTableInstance NetworkTable::GetInstance() const {
   return NetworkTableInstance{m_inst};
@@ -99,78 +107,58 @@
   return NetworkTableEntry{entry};
 }
 
-NT_EntryListener NetworkTable::AddEntryListener(TableEntryListener listener,
-                                                unsigned int flags) const {
-  size_t prefix_len = m_path.size() + 1;
-  return nt::AddEntryListener(
-      m_inst, fmt::format("{}/", m_path),
-      [=](const EntryNotification& event) {
-        auto relative_key = wpi::substr(event.name, prefix_len);
-        if (relative_key.find(PATH_SEPARATOR_CHAR) != std::string_view::npos) {
-          return;
-        }
-        listener(const_cast<NetworkTable*>(this), relative_key,
-                 NetworkTableEntry{event.entry}, event.value, event.flags);
-      },
-      flags);
+Topic NetworkTable::GetTopic(std::string_view name) const {
+  fmt::memory_buffer buf;
+  fmt::format_to(fmt::appender{buf}, "{}/{}", m_path, name);
+  return Topic{::nt::GetTopic(m_inst, {buf.data(), buf.size()})};
 }
 
-NT_EntryListener NetworkTable::AddEntryListener(std::string_view key,
-                                                TableEntryListener listener,
-                                                unsigned int flags) const {
-  size_t prefix_len = m_path.size() + 1;
-  auto entry = GetEntry(key);
-  return nt::AddEntryListener(
-      entry.GetHandle(),
-      [=](const EntryNotification& event) {
-        listener(const_cast<NetworkTable*>(this),
-                 wpi::substr(event.name, prefix_len), entry, event.value,
-                 event.flags);
-      },
-      flags);
+BooleanTopic NetworkTable::GetBooleanTopic(std::string_view name) const {
+  return BooleanTopic{GetTopic(name)};
 }
 
-void NetworkTable::RemoveEntryListener(NT_EntryListener listener) const {
-  nt::RemoveEntryListener(listener);
+IntegerTopic NetworkTable::GetIntegerTopic(std::string_view name) const {
+  return IntegerTopic{GetTopic(name)};
 }
 
-NT_EntryListener NetworkTable::AddSubTableListener(TableListener listener,
-                                                   bool localNotify) {
-  size_t prefix_len = m_path.size() + 1;
-
-  // The lambda needs to be copyable, but StringMap is not, so use
-  // a shared_ptr to it.
-  auto notified_tables = std::make_shared<wpi::StringMap<char>>();
-
-  unsigned int flags = NT_NOTIFY_NEW | NT_NOTIFY_IMMEDIATE;
-  if (localNotify) {
-    flags |= NT_NOTIFY_LOCAL;
-  }
-  NT_EntryListener id = nt::AddEntryListener(
-      m_inst, fmt::format("{}/", m_path),
-      [=](const EntryNotification& event) {
-        auto relative_key = wpi::substr(event.name, prefix_len);
-        auto end_sub_table = relative_key.find(PATH_SEPARATOR_CHAR);
-        if (end_sub_table == std::string_view::npos) {
-          return;
-        }
-        auto sub_table_key = wpi::substr(relative_key, 0, end_sub_table);
-        if (notified_tables->find(sub_table_key) == notified_tables->end()) {
-          return;
-        }
-        notified_tables->insert(std::make_pair(sub_table_key, '\0'));
-        listener(this, sub_table_key, this->GetSubTable(sub_table_key));
-      },
-      flags);
-  m_listeners.emplace_back(id);
-  return id;
+FloatTopic NetworkTable::GetFloatTopic(std::string_view name) const {
+  return FloatTopic{GetTopic(name)};
 }
 
-void NetworkTable::RemoveTableListener(NT_EntryListener listener) {
-  nt::RemoveEntryListener(listener);
-  auto matches_begin =
-      std::remove(m_listeners.begin(), m_listeners.end(), listener);
-  m_listeners.erase(matches_begin, m_listeners.end());
+DoubleTopic NetworkTable::GetDoubleTopic(std::string_view name) const {
+  return DoubleTopic{GetTopic(name)};
+}
+
+StringTopic NetworkTable::GetStringTopic(std::string_view name) const {
+  return StringTopic{GetTopic(name)};
+}
+
+RawTopic NetworkTable::GetRawTopic(std::string_view name) const {
+  return RawTopic{GetTopic(name)};
+}
+
+BooleanArrayTopic NetworkTable::GetBooleanArrayTopic(
+    std::string_view name) const {
+  return BooleanArrayTopic{GetTopic(name)};
+}
+
+IntegerArrayTopic NetworkTable::GetIntegerArrayTopic(
+    std::string_view name) const {
+  return IntegerArrayTopic{GetTopic(name)};
+}
+
+FloatArrayTopic NetworkTable::GetFloatArrayTopic(std::string_view name) const {
+  return FloatArrayTopic{GetTopic(name)};
+}
+
+DoubleArrayTopic NetworkTable::GetDoubleArrayTopic(
+    std::string_view name) const {
+  return DoubleArrayTopic{GetTopic(name)};
+}
+
+StringArrayTopic NetworkTable::GetStringArrayTopic(
+    std::string_view name) const {
+  return StringArrayTopic{GetTopic(name)};
 }
 
 std::shared_ptr<NetworkTable> NetworkTable::GetSubTable(
@@ -183,25 +171,52 @@
   if (key.empty()) {
     return false;
   }
-  return GetEntry(key).Exists();
+  return GetTopic(key).Exists();
 }
 
 bool NetworkTable::ContainsSubTable(std::string_view key) const {
-  return !GetEntryInfo(m_inst, fmt::format("{}/{}/", m_path, key), 0).empty();
+  return !::nt::GetTopics(m_inst, fmt::format("{}/{}/", m_path, key), 0)
+              .empty();
+}
+
+std::vector<TopicInfo> NetworkTable::GetTopicInfo(int types) const {
+  std::vector<TopicInfo> infos;
+  size_t prefix_len = m_path.size() + 1;
+  for (auto&& info :
+       ::nt::GetTopicInfo(m_inst, fmt::format("{}/", m_path), types)) {
+    auto relative_key = wpi::substr(info.name, prefix_len);
+    if (relative_key.find(PATH_SEPARATOR_CHAR) != std::string_view::npos) {
+      continue;
+    }
+    infos.emplace_back(std::move(info));
+  }
+  return infos;
+}
+
+std::vector<Topic> NetworkTable::GetTopics(int types) const {
+  std::vector<Topic> topics;
+  size_t prefix_len = m_path.size() + 1;
+  for (auto&& info :
+       ::nt::GetTopicInfo(m_inst, fmt::format("{}/", m_path), types)) {
+    auto relative_key = wpi::substr(info.name, prefix_len);
+    if (relative_key.find(PATH_SEPARATOR_CHAR) != std::string_view::npos) {
+      continue;
+    }
+    topics.emplace_back(info.topic);
+  }
+  return topics;
 }
 
 std::vector<std::string> NetworkTable::GetKeys(int types) const {
   std::vector<std::string> keys;
   size_t prefix_len = m_path.size() + 1;
-  auto infos = GetEntryInfo(m_inst, fmt::format("{}/", m_path), types);
-  std::scoped_lock lock(m_mutex);
-  for (auto& info : infos) {
+  for (auto&& info :
+       ::nt::GetTopicInfo(m_inst, fmt::format("{}/", m_path), types)) {
     auto relative_key = wpi::substr(info.name, prefix_len);
     if (relative_key.find(PATH_SEPARATOR_CHAR) != std::string_view::npos) {
       continue;
     }
     keys.emplace_back(relative_key);
-    m_entries[relative_key] = info.entry;
   }
   return keys;
 }
@@ -209,8 +224,9 @@
 std::vector<std::string> NetworkTable::GetSubTables() const {
   std::vector<std::string> keys;
   size_t prefix_len = m_path.size() + 1;
-  for (auto& entry : GetEntryInfo(m_inst, fmt::format("{}/", m_path), 0)) {
-    auto relative_key = wpi::substr(entry.name, prefix_len);
+  for (auto&& topic :
+       ::nt::GetTopicInfo(m_inst, fmt::format("{}/", m_path), 0)) {
+    auto relative_key = wpi::substr(topic.name, prefix_len);
     size_t end_subtable = relative_key.find(PATH_SEPARATOR_CHAR);
     if (end_subtable == std::string_view::npos) {
       continue;
@@ -232,22 +248,6 @@
   return GetEntry(key).IsPersistent();
 }
 
-void NetworkTable::SetFlags(std::string_view key, unsigned int flags) {
-  GetEntry(key).SetFlags(flags);
-}
-
-void NetworkTable::ClearFlags(std::string_view key, unsigned int flags) {
-  GetEntry(key).ClearFlags(flags);
-}
-
-unsigned int NetworkTable::GetFlags(std::string_view key) const {
-  return GetEntry(key).GetFlags();
-}
-
-void NetworkTable::Delete(std::string_view key) {
-  GetEntry(key).Delete();
-}
-
 bool NetworkTable::PutNumber(std::string_view key, double value) {
   return GetEntry(key).SetDouble(value);
 }
@@ -288,75 +288,75 @@
 }
 
 bool NetworkTable::PutBooleanArray(std::string_view key,
-                                   wpi::span<const int> value) {
+                                   std::span<const int> value) {
   return GetEntry(key).SetBooleanArray(value);
 }
 
 bool NetworkTable::SetDefaultBooleanArray(std::string_view key,
-                                          wpi::span<const int> defaultValue) {
+                                          std::span<const int> defaultValue) {
   return GetEntry(key).SetDefaultBooleanArray(defaultValue);
 }
 
 std::vector<int> NetworkTable::GetBooleanArray(
-    std::string_view key, wpi::span<const int> defaultValue) const {
+    std::string_view key, std::span<const int> defaultValue) const {
   return GetEntry(key).GetBooleanArray(defaultValue);
 }
 
 bool NetworkTable::PutNumberArray(std::string_view key,
-                                  wpi::span<const double> value) {
+                                  std::span<const double> value) {
   return GetEntry(key).SetDoubleArray(value);
 }
 
 bool NetworkTable::SetDefaultNumberArray(std::string_view key,
-                                         wpi::span<const double> defaultValue) {
+                                         std::span<const double> defaultValue) {
   return GetEntry(key).SetDefaultDoubleArray(defaultValue);
 }
 
 std::vector<double> NetworkTable::GetNumberArray(
-    std::string_view key, wpi::span<const double> defaultValue) const {
+    std::string_view key, std::span<const double> defaultValue) const {
   return GetEntry(key).GetDoubleArray(defaultValue);
 }
 
 bool NetworkTable::PutStringArray(std::string_view key,
-                                  wpi::span<const std::string> value) {
+                                  std::span<const std::string> value) {
   return GetEntry(key).SetStringArray(value);
 }
 
 bool NetworkTable::SetDefaultStringArray(
-    std::string_view key, wpi::span<const std::string> defaultValue) {
+    std::string_view key, std::span<const std::string> defaultValue) {
   return GetEntry(key).SetDefaultStringArray(defaultValue);
 }
 
 std::vector<std::string> NetworkTable::GetStringArray(
-    std::string_view key, wpi::span<const std::string> defaultValue) const {
+    std::string_view key, std::span<const std::string> defaultValue) const {
   return GetEntry(key).GetStringArray(defaultValue);
 }
 
-bool NetworkTable::PutRaw(std::string_view key, std::string_view value) {
+bool NetworkTable::PutRaw(std::string_view key,
+                          std::span<const uint8_t> value) {
   return GetEntry(key).SetRaw(value);
 }
 
 bool NetworkTable::SetDefaultRaw(std::string_view key,
-                                 std::string_view defaultValue) {
+                                 std::span<const uint8_t> defaultValue) {
   return GetEntry(key).SetDefaultRaw(defaultValue);
 }
 
-std::string NetworkTable::GetRaw(std::string_view key,
-                                 std::string_view defaultValue) const {
+std::vector<uint8_t> NetworkTable::GetRaw(
+    std::string_view key, std::span<const uint8_t> defaultValue) const {
   return GetEntry(key).GetRaw(defaultValue);
 }
 
-bool NetworkTable::PutValue(std::string_view key,
-                            std::shared_ptr<Value> value) {
+bool NetworkTable::PutValue(std::string_view key, const Value& value) {
   return GetEntry(key).SetValue(value);
 }
 
 bool NetworkTable::SetDefaultValue(std::string_view key,
-                                   std::shared_ptr<Value> defaultValue) {
+                                   const Value& defaultValue) {
   return GetEntry(key).SetDefaultValue(defaultValue);
 }
 
-std::shared_ptr<Value> NetworkTable::GetValue(std::string_view key) const {
+Value NetworkTable::GetValue(std::string_view key) const {
   return GetEntry(key).GetValue();
 }
 
@@ -364,12 +364,63 @@
   return m_path;
 }
 
-const char* NetworkTable::SaveEntries(std::string_view filename) const {
-  return nt::SaveEntries(m_inst, filename, fmt::format("{}/", m_path));
+NT_Listener NetworkTable::AddListener(int eventMask,
+                                      TableEventListener listener) {
+  return NetworkTableInstance{m_inst}.AddListener(
+      {{fmt::format("{}/", m_path)}}, eventMask,
+      [this, cb = std::move(listener)](const Event& event) {
+        std::string topicNameStr;
+        std::string_view topicName;
+        if (auto topicInfo = event.GetTopicInfo()) {
+          topicName = topicInfo->name;
+        } else if (auto valueData = event.GetValueEventData()) {
+          topicNameStr = Topic{valueData->topic}.GetName();
+          topicName = topicNameStr;
+        } else {
+          return;
+        }
+        auto relative_key = wpi::substr(topicName, m_path.size() + 1);
+        if (relative_key.find(PATH_SEPARATOR_CHAR) != std::string_view::npos) {
+          return;
+        }
+        cb(this, relative_key, event);
+      });
 }
 
-const char* NetworkTable::LoadEntries(
-    std::string_view filename,
-    std::function<void(size_t line, const char* msg)> warn) {
-  return nt::LoadEntries(m_inst, filename, fmt::format("{}/", m_path), warn);
+NT_Listener NetworkTable::AddListener(std::string_view key, int eventMask,
+                                      TableEventListener listener) {
+  return NetworkTableInstance{m_inst}.AddListener(
+      GetEntry(key), eventMask,
+      [this, cb = std::move(listener),
+       key = std::string{key}](const Event& event) { cb(this, key, event); });
+}
+
+NT_Listener NetworkTable::AddSubTableListener(SubTableListener listener) {
+  // The lambda needs to be copyable, but StringMap is not, so use
+  // a shared_ptr to it.
+  auto notified_tables = std::make_shared<wpi::StringMap<char>>();
+
+  return NetworkTableInstance{m_inst}.AddListener(
+      {{fmt::format("{}/", m_path)}}, NT_EVENT_PUBLISH | NT_EVENT_IMMEDIATE,
+      [this, cb = std::move(listener), notified_tables](const Event& event) {
+        auto topicInfo = event.GetTopicInfo();
+        if (!topicInfo) {
+          return;
+        }
+        auto relative_key = wpi::substr(topicInfo->name, m_path.size() + 1);
+        auto end_sub_table = relative_key.find(PATH_SEPARATOR_CHAR);
+        if (end_sub_table == std::string_view::npos) {
+          return;
+        }
+        auto sub_table_key = relative_key.substr(0, end_sub_table);
+        if (notified_tables->find(sub_table_key) != notified_tables->end()) {
+          return;
+        }
+        notified_tables->insert(std::make_pair(sub_table_key, '\0'));
+        cb(this, sub_table_key, this->GetSubTable(sub_table_key));
+      });
+}
+
+void NetworkTable::RemoveListener(NT_Listener listener) {
+  NetworkTableInstance{m_inst}.RemoveListener(listener);
 }
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/networktables/NetworkTableEntry.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/networktables/NetworkTableEntry.cpp
index abe64e5..12bb5d8 100644
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/networktables/NetworkTableEntry.cpp
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/networktables/NetworkTableEntry.cpp
@@ -5,9 +5,14 @@
 #include "networktables/NetworkTableEntry.h"
 
 #include "networktables/NetworkTableInstance.h"
+#include "networktables/Topic.h"
 
 using namespace nt;
 
 NetworkTableInstance NetworkTableEntry::GetInstance() const {
   return NetworkTableInstance{GetInstanceFromHandle(m_handle)};
 }
+
+Topic NetworkTableEntry::GetTopic() const {
+  return Topic{::nt::GetTopicFromHandle(m_handle)};
+}
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/networktables/NetworkTableInstance.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/networktables/NetworkTableInstance.cpp
index 4566b30..251e211 100644
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/networktables/NetworkTableInstance.cpp
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/networktables/NetworkTableInstance.cpp
@@ -7,8 +7,76 @@
 #include <fmt/format.h>
 #include <wpi/SmallVector.h>
 
+#include "networktables/BooleanArrayTopic.h"
+#include "networktables/BooleanTopic.h"
+#include "networktables/DoubleArrayTopic.h"
+#include "networktables/DoubleTopic.h"
+#include "networktables/FloatArrayTopic.h"
+#include "networktables/FloatTopic.h"
+#include "networktables/IntegerArrayTopic.h"
+#include "networktables/IntegerTopic.h"
+#include "networktables/MultiSubscriber.h"
+#include "networktables/RawTopic.h"
+#include "networktables/StringArrayTopic.h"
+#include "networktables/StringTopic.h"
+
 using namespace nt;
 
+Topic NetworkTableInstance::GetTopic(std::string_view name) const {
+  return Topic{::nt::GetTopic(m_handle, name)};
+}
+
+BooleanTopic NetworkTableInstance::GetBooleanTopic(
+    std::string_view name) const {
+  return BooleanTopic{GetTopic(name)};
+}
+
+IntegerTopic NetworkTableInstance::GetIntegerTopic(
+    std::string_view name) const {
+  return IntegerTopic{GetTopic(name)};
+}
+
+FloatTopic NetworkTableInstance::GetFloatTopic(std::string_view name) const {
+  return FloatTopic{GetTopic(name)};
+}
+
+DoubleTopic NetworkTableInstance::GetDoubleTopic(std::string_view name) const {
+  return DoubleTopic{GetTopic(name)};
+}
+
+StringTopic NetworkTableInstance::GetStringTopic(std::string_view name) const {
+  return StringTopic{GetTopic(name)};
+}
+
+RawTopic NetworkTableInstance::GetRawTopic(std::string_view name) const {
+  return RawTopic{GetTopic(name)};
+}
+
+BooleanArrayTopic NetworkTableInstance::GetBooleanArrayTopic(
+    std::string_view name) const {
+  return BooleanArrayTopic{GetTopic(name)};
+}
+
+IntegerArrayTopic NetworkTableInstance::GetIntegerArrayTopic(
+    std::string_view name) const {
+  return IntegerArrayTopic{GetTopic(name)};
+}
+
+FloatArrayTopic NetworkTableInstance::GetFloatArrayTopic(
+    std::string_view name) const {
+  return FloatArrayTopic{GetTopic(name)};
+}
+
+DoubleArrayTopic NetworkTableInstance::GetDoubleArrayTopic(
+    std::string_view name) const {
+  return DoubleArrayTopic{GetTopic(name)};
+}
+
+StringArrayTopic NetworkTableInstance::GetStringArrayTopic(
+    std::string_view name) const {
+  return StringArrayTopic{GetTopic(name)};
+}
+
 std::shared_ptr<NetworkTable> NetworkTableInstance::GetTable(
     std::string_view key) const {
   if (key.empty() || key == "/") {
@@ -23,33 +91,54 @@
   }
 }
 
-void NetworkTableInstance::StartClient(
-    wpi::span<const std::string_view> servers, unsigned int port) {
-  wpi::SmallVector<std::pair<std::string_view, unsigned int>, 8> server_ports;
-  for (const auto& server : servers) {
-    server_ports.emplace_back(std::make_pair(server, port));
-  }
-  StartClient(server_ports);
-}
-
-void NetworkTableInstance::SetServer(wpi::span<const std::string_view> servers,
+void NetworkTableInstance::SetServer(std::span<const std::string_view> servers,
                                      unsigned int port) {
-  wpi::SmallVector<std::pair<std::string_view, unsigned int>, 8> server_ports;
+  std::vector<std::pair<std::string_view, unsigned int>> serversArr;
+  serversArr.reserve(servers.size());
   for (const auto& server : servers) {
-    server_ports.emplace_back(std::make_pair(server, port));
+    serversArr.emplace_back(std::string{server}, port);
   }
-  SetServer(server_ports);
+  SetServer(serversArr);
 }
 
-NT_EntryListener NetworkTableInstance::AddEntryListener(
-    std::string_view prefix,
-    std::function<void(const EntryNotification& event)> callback,
-    unsigned int flags) const {
-  return ::nt::AddEntryListener(m_handle, prefix, callback, flags);
+NT_Listener NetworkTableInstance::AddListener(Topic topic,
+                                              unsigned int eventMask,
+                                              ListenerCallback listener) {
+  if (::nt::GetInstanceFromHandle(topic.GetHandle()) != m_handle) {
+    fmt::print(stderr, "AddListener: topic is not from this instance\n");
+    return 0;
+  }
+  return ::nt::AddListener(topic.GetHandle(), eventMask, std::move(listener));
 }
 
-NT_ConnectionListener NetworkTableInstance::AddConnectionListener(
-    std::function<void(const ConnectionNotification& event)> callback,
-    bool immediate_notify) const {
-  return ::nt::AddConnectionListener(m_handle, callback, immediate_notify);
+NT_Listener NetworkTableInstance::AddListener(Subscriber& subscriber,
+                                              unsigned int eventMask,
+                                              ListenerCallback listener) {
+  if (::nt::GetInstanceFromHandle(subscriber.GetHandle()) != m_handle) {
+    fmt::print(stderr, "AddListener: subscriber is not from this instance\n");
+    return 0;
+  }
+  return ::nt::AddListener(subscriber.GetHandle(), eventMask,
+                           std::move(listener));
+}
+
+NT_Listener NetworkTableInstance::AddListener(const NetworkTableEntry& entry,
+                                              int eventMask,
+                                              ListenerCallback listener) {
+  if (::nt::GetInstanceFromHandle(entry.GetHandle()) != m_handle) {
+    fmt::print(stderr, "AddListener: entry is not from this instance\n");
+    return 0;
+  }
+  return ::nt::AddListener(entry.GetHandle(), eventMask, std::move(listener));
+}
+
+NT_Listener NetworkTableInstance::AddListener(MultiSubscriber& subscriber,
+                                              int eventMask,
+                                              ListenerCallback listener) {
+  if (::nt::GetInstanceFromHandle(subscriber.GetHandle()) != m_handle) {
+    fmt::print(stderr, "AddListener: subscriber is not from this instance\n");
+    return 0;
+  }
+  return ::nt::AddListener(subscriber.GetHandle(), eventMask,
+                           std::move(listener));
 }
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/networktables/RpcCall.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/networktables/RpcCall.cpp
deleted file mode 100644
index 2192a82..0000000
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/networktables/RpcCall.cpp
+++ /dev/null
@@ -1,13 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "networktables/RpcCall.h"
-
-#include "networktables/NetworkTableEntry.h"
-
-using namespace nt;
-
-NetworkTableEntry RpcCall::GetEntry() const {
-  return NetworkTableEntry{m_entry};
-}
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/networktables/Topic.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/networktables/Topic.cpp
new file mode 100644
index 0000000..e3f6ac0
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/networktables/Topic.cpp
@@ -0,0 +1,57 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "networktables/Topic.h"
+
+#include <wpi/json.h>
+
+#include "networktables/GenericEntry.h"
+
+using namespace nt;
+
+wpi::json Topic::GetProperty(std::string_view name) const {
+  return ::nt::GetTopicProperty(m_handle, name);
+}
+
+void Topic::SetProperty(std::string_view name, const wpi::json& value) {
+  ::nt::SetTopicProperty(m_handle, name, value);
+}
+
+wpi::json Topic::GetProperties() const {
+  return ::nt::GetTopicProperties(m_handle);
+}
+
+GenericSubscriber Topic::GenericSubscribe(const PubSubOptions& options) {
+  return GenericSubscribe("", options);
+}
+
+GenericSubscriber Topic::GenericSubscribe(std::string_view typeString,
+                                          const PubSubOptions& options) {
+  return GenericSubscriber{::nt::Subscribe(
+      m_handle, ::nt::GetTypeFromString(typeString), typeString, options)};
+}
+
+GenericPublisher Topic::GenericPublish(std::string_view typeString,
+                                       const PubSubOptions& options) {
+  return GenericPublisher{::nt::Publish(
+      m_handle, ::nt::GetTypeFromString(typeString), typeString, options)};
+}
+
+GenericPublisher Topic::GenericPublishEx(std::string_view typeString,
+                                         const wpi::json& properties,
+                                         const PubSubOptions& options) {
+  return GenericPublisher{::nt::PublishEx(m_handle,
+                                          ::nt::GetTypeFromString(typeString),
+                                          typeString, properties, options)};
+}
+
+GenericEntry Topic::GetGenericEntry(const PubSubOptions& options) {
+  return GetGenericEntry("", options);
+}
+
+GenericEntry Topic::GetGenericEntry(std::string_view typeString,
+                                    const PubSubOptions& options) {
+  return GenericEntry{::nt::GetEntry(
+      m_handle, ::nt::GetTypeFromString(typeString), typeString, options)};
+}
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/ntcore_c.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/ntcore_c.cpp
index d910892..151e0f1 100644
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/ntcore_c.cpp
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/ntcore_c.cpp
@@ -2,6 +2,8 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
+#include "ntcore_c.h"
+
 #include <stdint.h>
 
 #include <cassert>
@@ -10,27 +12,24 @@
 #include <string_view>
 
 #include <wpi/MemAlloc.h>
+#include <wpi/SmallVector.h>
+#include <wpi/json.h>
 #include <wpi/timestamp.h>
 
 #include "Value_internal.h"
 #include "ntcore.h"
+#include "ntcore_cpp.h"
 
 using namespace nt;
 
 // Conversion helpers
 
-static void ConvertToC(std::string_view in, char** out) {
-  *out = static_cast<char*>(wpi::safe_malloc(in.size() + 1));
-  std::memmove(*out, in.data(), in.size());  // NOLINT
-  (*out)[in.size()] = '\0';
-}
-
-static void ConvertToC(const EntryInfo& in, NT_EntryInfo* out) {
-  out->entry = in.entry;
+static void ConvertToC(const TopicInfo& in, NT_TopicInfo* out) {
+  out->topic = in.topic;
   ConvertToC(in.name, &out->name);
   out->type = in.type;
-  out->flags = in.flags;
-  out->last_change = in.last_change;
+  ConvertToC(in.type_str, &out->type_str);
+  ConvertToC(in.properties, &out->properties);
 }
 
 static void ConvertToC(const ConnectionInfo& in, NT_ConnectionInfo* out) {
@@ -41,80 +40,50 @@
   out->protocol_version = in.protocol_version;
 }
 
-static void ConvertToC(const RpcParamDef& in, NT_RpcParamDef* out) {
-  ConvertToC(in.name, &out->name);
-  ConvertToC(*in.def_value, &out->def_value);
-}
-
-static void ConvertToC(const RpcResultDef& in, NT_RpcResultDef* out) {
-  ConvertToC(in.name, &out->name);
-  out->type = in.type;
-}
-
-static void ConvertToC(const RpcDefinition& in, NT_RpcDefinition* out) {
-  out->version = in.version;
-  ConvertToC(in.name, &out->name);
-
-  out->num_params = in.params.size();
-  out->params = static_cast<NT_RpcParamDef*>(
-      wpi::safe_malloc(in.params.size() * sizeof(NT_RpcParamDef)));
-  for (size_t i = 0; i < in.params.size(); ++i) {
-    ConvertToC(in.params[i], &out->params[i]);
-  }
-
-  out->num_results = in.results.size();
-  out->results = static_cast<NT_RpcResultDef*>(
-      wpi::safe_malloc(in.results.size() * sizeof(NT_RpcResultDef)));
-  for (size_t i = 0; i < in.results.size(); ++i) {
-    ConvertToC(in.results[i], &out->results[i]);
-  }
-}
-
-static void ConvertToC(const RpcAnswer& in, NT_RpcAnswer* out) {
-  out->entry = in.entry;
-  out->call = in.call;
-  ConvertToC(in.name, &out->name);
-  ConvertToC(in.params, &out->params);
-  ConvertToC(in.conn, &out->conn);
-}
-
-static void ConvertToC(const EntryNotification& in, NT_EntryNotification* out) {
-  out->listener = in.listener;
-  out->entry = in.entry;
-  ConvertToC(in.name, &out->name);
-  ConvertToC(*in.value, &out->value);
-  out->flags = in.flags;
-}
-
-static void ConvertToC(const ConnectionNotification& in,
-                       NT_ConnectionNotification* out) {
-  out->listener = in.listener;
-  out->connected = in.connected;
-  ConvertToC(in.conn, &out->conn);
+static void ConvertToC(const ValueEventData& in, NT_ValueEventData* out) {
+  out->topic = in.topic;
+  out->subentry = in.subentry;
+  ConvertToC(in.value, &out->value);
 }
 
 static void ConvertToC(const LogMessage& in, NT_LogMessage* out) {
-  out->logger = in.logger;
   out->level = in.level;
   ConvertToC(in.filename, &out->filename);
   out->line = in.line;
   ConvertToC(in.message, &out->message);
 }
 
-template <typename O, typename I>
-static O* ConvertToC(const std::vector<I>& in, size_t* out_len) {
-  if (!out_len) {
-    return nullptr;
+static void ConvertToC(const TimeSyncEventData& in, NT_TimeSyncEventData* out) {
+  out->serverTimeOffset = in.serverTimeOffset;
+  out->rtt2 = in.rtt2;
+  out->valid = in.valid;
+}
+
+static void ConvertToC(const Event& in, NT_Event* out) {
+  out->listener = in.listener;
+  out->flags = in.flags;
+  if ((in.flags & NT_EVENT_VALUE_ALL) != 0) {
+    if (auto v = in.GetValueEventData()) {
+      return ConvertToC(*v, &out->data.valueData);
+    }
+  } else if ((in.flags & NT_EVENT_TOPIC) != 0) {
+    if (auto v = in.GetTopicInfo()) {
+      return ConvertToC(*v, &out->data.topicInfo);
+    }
+  } else if ((in.flags & NT_EVENT_CONNECTION) != 0) {
+    if (auto v = in.GetConnectionInfo()) {
+      return ConvertToC(*v, &out->data.connInfo);
+    }
+  } else if ((in.flags & NT_EVENT_LOGMESSAGE) != 0) {
+    if (auto v = in.GetLogMessage()) {
+      return ConvertToC(*v, &out->data.logMessage);
+    }
+  } else if ((in.flags & NT_EVENT_TIMESYNC) != 0) {
+    if (auto v = in.GetTimeSyncEventData()) {
+      return ConvertToC(*v, &out->data.timeSyncData);
+    }
   }
-  *out_len = in.size();
-  if (in.empty()) {
-    return nullptr;
-  }
-  O* out = static_cast<O*>(wpi::safe_malloc(sizeof(O) * in.size()));
-  for (size_t i = 0; i < in.size(); ++i) {
-    ConvertToC(in[i], &out[i]);
-  }
-  return out;
+  out->flags = NT_EVENT_NONE;  // sanity to make sure we don't dispose
 }
 
 static void DisposeConnectionInfo(NT_ConnectionInfo* info) {
@@ -122,48 +91,41 @@
   std::free(info->remote_ip.str);
 }
 
-static void DisposeEntryInfo(NT_EntryInfo* info) {
+static void DisposeTopicInfo(NT_TopicInfo* info) {
   std::free(info->name.str);
+  std::free(info->type_str.str);
+  std::free(info->properties.str);
 }
 
-static void DisposeEntryNotification(NT_EntryNotification* info) {
-  std::free(info->name.str);
-  NT_DisposeValue(&info->value);
+static void DisposeLogMessage(NT_LogMessage* msg) {
+  std::free(msg->filename);
+  std::free(msg->message);
 }
 
-static void DisposeConnectionNotification(NT_ConnectionNotification* info) {
-  DisposeConnectionInfo(&info->conn);
-}
-
-static RpcParamDef ConvertFromC(const NT_RpcParamDef& in) {
-  RpcParamDef out;
-  out.name = ConvertFromC(in.name);
-  out.def_value = ConvertFromC(in.def_value);
-  return out;
-}
-
-static RpcResultDef ConvertFromC(const NT_RpcResultDef& in) {
-  RpcResultDef out;
-  out.name = ConvertFromC(in.name);
-  out.type = in.type;
-  return out;
-}
-
-static RpcDefinition ConvertFromC(const NT_RpcDefinition& in) {
-  RpcDefinition out;
-  out.version = in.version;
-  out.name = ConvertFromC(in.name);
-
-  out.params.reserve(in.num_params);
-  for (size_t i = 0; i < in.num_params; ++i) {
-    out.params.push_back(ConvertFromC(in.params[i]));
+static void DisposeEvent(NT_Event* event) {
+  if ((event->flags & NT_EVENT_VALUE_ALL) != 0) {
+    NT_DisposeValue(&event->data.valueData.value);
+  } else if ((event->flags & NT_EVENT_TOPIC) != 0) {
+    DisposeTopicInfo(&event->data.topicInfo);
+  } else if ((event->flags & NT_EVENT_CONNECTION) != 0) {
+    DisposeConnectionInfo(&event->data.connInfo);
+  } else if ((event->flags & NT_EVENT_LOGMESSAGE) != 0) {
+    DisposeLogMessage(&event->data.logMessage);
   }
+}
 
-  out.results.reserve(in.num_results);
-  for (size_t i = 0; i < in.num_results; ++i) {
-    out.results.push_back(ConvertFromC(in.results[i]));
-  }
-
+static PubSubOptions ConvertToCpp(const NT_PubSubOptions* in) {
+  PubSubOptions out;
+  out.pollStorage = in->pollStorage;
+  out.periodic = in->periodic;
+  out.excludePublisher = in->excludePublisher;
+  out.sendAll = in->sendAll;
+  out.topicsOnly = in->topicsOnly;
+  out.prefixMatch = in->prefixMatch;
+  out.keepDuplicates = in->keepDuplicates;
+  out.disableRemote = in->disableRemote;
+  out.disableLocal = in->disableLocal;
+  out.excludeSelf = in->excludeSelf;
   return out;
 }
 
@@ -197,21 +159,6 @@
   return nt::GetEntry(inst, {name, name_len});
 }
 
-NT_Entry* NT_GetEntries(NT_Inst inst, const char* prefix, size_t prefix_len,
-                        unsigned int types, size_t* count) {
-  auto info_v = nt::GetEntries(inst, {prefix, prefix_len}, types);
-  *count = info_v.size();
-  if (info_v.size() == 0) {
-    return nullptr;
-  }
-
-  // create array and copy into it
-  NT_Entry* info = static_cast<NT_Entry*>(
-      wpi::safe_malloc(info_v.size() * sizeof(NT_Entry)));
-  std::memcpy(info, info_v.data(), info_v.size() * sizeof(NT_Entry));
-  return info;
-}
-
 char* NT_GetEntryName(NT_Entry entry, size_t* name_len) {
   struct NT_String v_name;
   nt::ConvertToC(nt::GetEntryName(entry), &v_name);
@@ -233,7 +180,7 @@
   if (!v) {
     return;
   }
-  ConvertToC(*v, value);
+  ConvertToC(v, value);
 }
 
 int NT_SetDefaultEntryValue(NT_Entry entry,
@@ -245,10 +192,6 @@
   return nt::SetEntryValue(entry, ConvertFromC(*value));
 }
 
-void NT_SetEntryTypeValue(NT_Entry entry, const struct NT_Value* value) {
-  nt::SetEntryTypeValue(entry, ConvertFromC(*value));
-}
-
 void NT_SetEntryFlags(NT_Entry entry, unsigned int flags) {
   nt::SetEntryFlags(entry, flags);
 }
@@ -257,23 +200,50 @@
   return nt::GetEntryFlags(entry);
 }
 
-void NT_DeleteEntry(NT_Entry entry) {
-  nt::DeleteEntry(entry);
+struct NT_Value* NT_ReadQueueValue(NT_Handle subentry, size_t* count) {
+  return ConvertToC<NT_Value>(nt::ReadQueueValue(subentry), count);
 }
 
-void NT_DeleteAllEntries(NT_Inst inst) {
-  nt::DeleteAllEntries(inst);
+NT_Topic* NT_GetTopics(NT_Inst inst, const char* prefix, size_t prefix_len,
+                       unsigned int types, size_t* count) {
+  auto info_v = nt::GetTopics(inst, {prefix, prefix_len}, types);
+  return ConvertToC<NT_Topic>(info_v, count);
 }
 
-struct NT_EntryInfo* NT_GetEntryInfo(NT_Inst inst, const char* prefix,
-                                     size_t prefix_len, unsigned int types,
-                                     size_t* count) {
-  auto info_v = nt::GetEntryInfo(inst, {prefix, prefix_len}, types);
-  return ConvertToC<NT_EntryInfo>(info_v, count);
+NT_Topic* NT_GetTopicsStr(NT_Inst inst, const char* prefix, size_t prefix_len,
+                          const char* const* types, size_t types_len,
+                          size_t* count) {
+  wpi::SmallVector<std::string_view, 4> typesCpp;
+  typesCpp.reserve(types_len);
+  for (size_t i = 0; i < types_len; ++i) {
+    typesCpp.emplace_back(types[i]);
+  }
+  auto info_v = nt::GetTopics(inst, {prefix, prefix_len}, typesCpp);
+  return ConvertToC<NT_Topic>(info_v, count);
 }
 
-NT_Bool NT_GetEntryInfoHandle(NT_Entry entry, struct NT_EntryInfo* info) {
-  auto info_v = nt::GetEntryInfo(entry);
+struct NT_TopicInfo* NT_GetTopicInfos(NT_Inst inst, const char* prefix,
+                                      size_t prefix_len, unsigned int types,
+                                      size_t* count) {
+  auto info_v = nt::GetTopicInfo(inst, {prefix, prefix_len}, types);
+  return ConvertToC<NT_TopicInfo>(info_v, count);
+}
+
+struct NT_TopicInfo* NT_GetTopicInfosStr(NT_Inst inst, const char* prefix,
+                                         size_t prefix_len,
+                                         const char* const* types,
+                                         size_t types_len, size_t* count) {
+  wpi::SmallVector<std::string_view, 4> typesCpp;
+  typesCpp.reserve(types_len);
+  for (size_t i = 0; i < types_len; ++i) {
+    typesCpp.emplace_back(types[i]);
+  }
+  auto info_v = nt::GetTopicInfo(inst, {prefix, prefix_len}, typesCpp);
+  return ConvertToC<NT_TopicInfo>(info_v, count);
+}
+
+NT_Bool NT_GetTopicInfo(NT_Topic topic, struct NT_TopicInfo* info) {
+  auto info_v = nt::GetTopicInfo(topic);
   if (info_v.name.empty()) {
     return false;
   }
@@ -281,299 +251,240 @@
   return true;
 }
 
+NT_Topic NT_GetTopic(NT_Inst inst, const char* name, size_t name_len) {
+  return nt::GetTopic(inst, std::string_view{name, name_len});
+}
+
+char* NT_GetTopicName(NT_Topic topic, size_t* name_len) {
+  auto name = nt::GetTopicName(topic);
+  if (name.empty()) {
+    *name_len = 0;
+    return nullptr;
+  }
+  struct NT_String v_name;
+  nt::ConvertToC(name, &v_name);
+  *name_len = v_name.len;
+  return v_name.str;
+}
+
+NT_Type NT_GetTopicType(NT_Topic topic) {
+  return nt::GetTopicType(topic);
+}
+
+char* NT_GetTopicTypeString(NT_Topic topic, size_t* type_len) {
+  auto type = nt::GetTopicTypeString(topic);
+  struct NT_String v_type;
+  nt::ConvertToC(type, &v_type);
+  *type_len = v_type.len;
+  return v_type.str;
+}
+
+void NT_SetTopicPersistent(NT_Topic topic, NT_Bool value) {
+  nt::SetTopicPersistent(topic, value);
+}
+
+NT_Bool NT_GetTopicPersistent(NT_Topic topic) {
+  return nt::GetTopicPersistent(topic);
+}
+
+void NT_SetTopicRetained(NT_Topic topic, NT_Bool value) {
+  nt::SetTopicRetained(topic, value);
+}
+
+NT_Bool NT_GetTopicRetained(NT_Topic topic) {
+  return nt::GetTopicRetained(topic);
+}
+
+NT_Bool NT_GetTopicExists(NT_Handle handle) {
+  return nt::GetTopicExists(handle);
+}
+
+char* NT_GetTopicProperty(NT_Topic topic, const char* name, size_t* len) {
+  wpi::json j = nt::GetTopicProperty(topic, name);
+  struct NT_String v;
+  nt::ConvertToC(j.dump(), &v);
+  *len = v.len;
+  return v.str;
+}
+
+NT_Bool NT_SetTopicProperty(NT_Topic topic, const char* name,
+                            const char* value) {
+  wpi::json j;
+  try {
+    j = wpi::json::parse(value);
+  } catch (wpi::json::parse_error&) {
+    return false;
+  }
+  nt::SetTopicProperty(topic, name, j);
+  return true;
+}
+
+void NT_DeleteTopicProperty(NT_Topic topic, const char* name) {
+  nt::DeleteTopicProperty(topic, name);
+}
+
+char* NT_GetTopicProperties(NT_Topic topic, size_t* len) {
+  wpi::json j = nt::GetTopicProperties(topic);
+  struct NT_String v;
+  nt::ConvertToC(j.dump(), &v);
+  *len = v.len;
+  return v.str;
+}
+
+NT_Bool NT_SetTopicProperties(NT_Topic topic, const char* properties) {
+  wpi::json j;
+  try {
+    j = wpi::json::parse(properties);
+  } catch (wpi::json::parse_error&) {
+    return false;
+  }
+  return nt::SetTopicProperties(topic, j);
+}
+
+NT_Subscriber NT_Subscribe(NT_Topic topic, NT_Type type, const char* typeStr,
+                           const struct NT_PubSubOptions* options) {
+  return nt::Subscribe(topic, type, typeStr, ConvertToCpp(options));
+}
+
+void NT_Unsubscribe(NT_Subscriber sub) {
+  return nt::Unsubscribe(sub);
+}
+
+NT_Publisher NT_Publish(NT_Topic topic, NT_Type type, const char* typeStr,
+                        const struct NT_PubSubOptions* options) {
+  return nt::Publish(topic, type, typeStr, ConvertToCpp(options));
+}
+
+NT_Publisher NT_PublishEx(NT_Topic topic, NT_Type type, const char* typeStr,
+                          const char* properties,
+                          const struct NT_PubSubOptions* options) {
+  wpi::json j;
+  if (properties[0] == '\0') {
+    // gracefully handle empty string
+    j = wpi::json::object();
+  } else {
+    try {
+      j = wpi::json::parse(properties);
+    } catch (wpi::json::parse_error&) {
+      return {};
+    }
+  }
+
+  return nt::PublishEx(topic, type, typeStr, j, ConvertToCpp(options));
+}
+
+void NT_Unpublish(NT_Handle pubentry) {
+  return nt::Unpublish(pubentry);
+}
+
+NT_Entry NT_GetEntryEx(NT_Topic topic, NT_Type type, const char* typeStr,
+                       const struct NT_PubSubOptions* options) {
+  return nt::GetEntry(topic, type, typeStr, ConvertToCpp(options));
+}
+
+void NT_ReleaseEntry(NT_Entry entry) {
+  nt::ReleaseEntry(entry);
+}
+
+void NT_Release(NT_Handle pubsubentry) {
+  nt::Release(pubsubentry);
+}
+
+NT_Topic NT_GetTopicFromHandle(NT_Handle pubsubentry) {
+  return nt::GetTopicFromHandle(pubsubentry);
+}
+
 /*
  * Callback Creation Functions
  */
 
-NT_EntryListener NT_AddEntryListener(NT_Inst inst, const char* prefix,
-                                     size_t prefix_len, void* data,
-                                     NT_EntryListenerCallback callback,
-                                     unsigned int flags) {
-  return nt::AddEntryListener(
-      inst, {prefix, prefix_len},
-      [=](const EntryNotification& event) {
-        NT_EntryNotification c_event;
-        ConvertToC(event, &c_event);
-        callback(data, &c_event);
-        DisposeEntryNotification(&c_event);
-      },
-      flags);
+NT_ListenerPoller NT_CreateListenerPoller(NT_Inst inst) {
+  return nt::CreateListenerPoller(inst);
 }
 
-NT_EntryListener NT_AddEntryListenerSingle(NT_Entry entry, void* data,
-                                           NT_EntryListenerCallback callback,
-                                           unsigned int flags) {
-  return nt::AddEntryListener(
-      entry,
-      [=](const EntryNotification& event) {
-        NT_EntryNotification c_event;
-        ConvertToC(event, &c_event);
-        callback(data, &c_event);
-        DisposeEntryNotification(&c_event);
-      },
-      flags);
+void NT_DestroyListenerPoller(NT_ListenerPoller poller) {
+  nt::DestroyListenerPoller(poller);
 }
 
-NT_EntryListenerPoller NT_CreateEntryListenerPoller(NT_Inst inst) {
-  return nt::CreateEntryListenerPoller(inst);
+struct NT_Event* NT_ReadListenerQueue(NT_ListenerPoller poller, size_t* len) {
+  auto arr_cpp = nt::ReadListenerQueue(poller);
+  return ConvertToC<NT_Event>(arr_cpp, len);
 }
 
-void NT_DestroyEntryListenerPoller(NT_EntryListenerPoller poller) {
-  nt::DestroyEntryListenerPoller(poller);
+void NT_RemoveListener(NT_Listener listener) {
+  nt::RemoveListener(listener);
 }
 
-NT_EntryListener NT_AddPolledEntryListener(NT_EntryListenerPoller poller,
-                                           const char* prefix,
-                                           size_t prefix_len,
-                                           unsigned int flags) {
-  return nt::AddPolledEntryListener(poller, {prefix, prefix_len}, flags);
+NT_Bool NT_WaitForListenerQueue(NT_Handle handle, double timeout) {
+  return nt::WaitForListenerQueue(handle, timeout);
 }
 
-NT_EntryListener NT_AddPolledEntryListenerSingle(NT_EntryListenerPoller poller,
-                                                 NT_Entry entry,
-                                                 unsigned int flags) {
-  return nt::AddPolledEntryListener(poller, entry, flags);
-}
-
-struct NT_EntryNotification* NT_PollEntryListener(NT_EntryListenerPoller poller,
-                                                  size_t* len) {
-  auto arr_cpp = nt::PollEntryListener(poller);
-  return ConvertToC<NT_EntryNotification>(arr_cpp, len);
-}
-
-struct NT_EntryNotification* NT_PollEntryListenerTimeout(
-    NT_EntryListenerPoller poller, size_t* len, double timeout,
-    NT_Bool* timed_out) {
-  bool cpp_timed_out = false;
-  auto arr_cpp = nt::PollEntryListener(poller, timeout, &cpp_timed_out);
-  *timed_out = cpp_timed_out;
-  return ConvertToC<NT_EntryNotification>(arr_cpp, len);
-}
-
-void NT_CancelPollEntryListener(NT_EntryListenerPoller poller) {
-  nt::CancelPollEntryListener(poller);
-}
-
-void NT_RemoveEntryListener(NT_EntryListener entry_listener) {
-  nt::RemoveEntryListener(entry_listener);
-}
-
-NT_Bool NT_WaitForEntryListenerQueue(NT_Inst inst, double timeout) {
-  return nt::WaitForEntryListenerQueue(inst, timeout);
-}
-
-NT_ConnectionListener NT_AddConnectionListener(
-    NT_Inst inst, void* data, NT_ConnectionListenerCallback callback,
-    NT_Bool immediate_notify) {
-  return nt::AddConnectionListener(
-      inst,
-      [=](const ConnectionNotification& event) {
-        NT_ConnectionNotification event_c;
-        ConvertToC(event, &event_c);
-        callback(data, &event_c);
-        DisposeConnectionNotification(&event_c);
-      },
-      immediate_notify != 0);
-}
-
-NT_ConnectionListenerPoller NT_CreateConnectionListenerPoller(NT_Inst inst) {
-  return nt::CreateConnectionListenerPoller(inst);
-}
-
-void NT_DestroyConnectionListenerPoller(NT_ConnectionListenerPoller poller) {
-  nt::DestroyConnectionListenerPoller(poller);
-}
-
-NT_ConnectionListener NT_AddPolledConnectionListener(
-    NT_ConnectionListenerPoller poller, NT_Bool immediate_notify) {
-  return nt::AddPolledConnectionListener(poller, immediate_notify);
-}
-
-struct NT_ConnectionNotification* NT_PollConnectionListener(
-    NT_ConnectionListenerPoller poller, size_t* len) {
-  auto arr_cpp = nt::PollConnectionListener(poller);
-  return ConvertToC<NT_ConnectionNotification>(arr_cpp, len);
-}
-
-struct NT_ConnectionNotification* NT_PollConnectionListenerTimeout(
-    NT_ConnectionListenerPoller poller, size_t* len, double timeout,
-    NT_Bool* timed_out) {
-  bool cpp_timed_out = false;
-  auto arr_cpp = nt::PollConnectionListener(poller, timeout, &cpp_timed_out);
-  *timed_out = cpp_timed_out;
-  return ConvertToC<NT_ConnectionNotification>(arr_cpp, len);
-}
-
-void NT_CancelPollConnectionListener(NT_ConnectionListenerPoller poller) {
-  nt::CancelPollConnectionListener(poller);
-}
-
-void NT_RemoveConnectionListener(NT_ConnectionListener conn_listener) {
-  nt::RemoveConnectionListener(conn_listener);
-}
-
-NT_Bool NT_WaitForConnectionListenerQueue(NT_Inst inst, double timeout) {
-  return nt::WaitForConnectionListenerQueue(inst, timeout);
-}
-
-/*
- * Remote Procedure Call Functions
- */
-
-void NT_CreateRpc(NT_Entry entry, const char* def, size_t def_len, void* data,
-                  NT_RpcCallback callback) {
-  nt::CreateRpc(entry, {def, def_len}, [=](const RpcAnswer& answer) {
-    NT_RpcAnswer answer_c;
-    ConvertToC(answer, &answer_c);
-    callback(data, &answer_c);
-    NT_DisposeRpcAnswer(&answer_c);
+NT_Listener NT_AddListenerSingle(NT_Inst inst, const char* prefix,
+                                 size_t prefix_len, unsigned int mask,
+                                 void* data, NT_ListenerCallback callback) {
+  std::string_view p{prefix, prefix_len};
+  return nt::AddListener(inst, {{p}}, mask, [=](auto& event) {
+    NT_Event event_c;
+    ConvertToC(event, &event_c);
+    callback(data, &event_c);
+    DisposeEvent(&event_c);
   });
 }
 
-NT_RpcCallPoller NT_CreateRpcCallPoller(NT_Inst inst) {
-  return nt::CreateRpcCallPoller(inst);
-}
-
-void NT_DestroyRpcCallPoller(NT_RpcCallPoller poller) {
-  nt::DestroyRpcCallPoller(poller);
-}
-
-void NT_CreatePolledRpc(NT_Entry entry, const char* def, size_t def_len,
-                        NT_RpcCallPoller poller) {
-  nt::CreatePolledRpc(entry, {def, def_len}, poller);
-}
-
-NT_RpcAnswer* NT_PollRpc(NT_RpcCallPoller poller, size_t* len) {
-  auto arr_cpp = nt::PollRpc(poller);
-  return ConvertToC<NT_RpcAnswer>(arr_cpp, len);
-}
-
-NT_RpcAnswer* NT_PollRpcTimeout(NT_RpcCallPoller poller, size_t* len,
-                                double timeout, NT_Bool* timed_out) {
-  bool cpp_timed_out = false;
-  auto arr_cpp = nt::PollRpc(poller, timeout, &cpp_timed_out);
-  *timed_out = cpp_timed_out;
-  return ConvertToC<NT_RpcAnswer>(arr_cpp, len);
-}
-
-void NT_CancelPollRpc(NT_RpcCallPoller poller) {
-  nt::CancelPollRpc(poller);
-}
-
-NT_Bool NT_WaitForRpcCallQueue(NT_Inst inst, double timeout) {
-  return nt::WaitForRpcCallQueue(inst, timeout);
-}
-
-NT_Bool NT_PostRpcResponse(NT_Entry entry, NT_RpcCall call, const char* result,
-                           size_t result_len) {
-  return nt::PostRpcResponse(entry, call, {result, result_len});
-}
-
-NT_RpcCall NT_CallRpc(NT_Entry entry, const char* params, size_t params_len) {
-  return nt::CallRpc(entry, {params, params_len});
-}
-
-char* NT_GetRpcResult(NT_Entry entry, NT_RpcCall call, size_t* result_len) {
-  std::string result;
-  if (!nt::GetRpcResult(entry, call, &result)) {
-    return nullptr;
+NT_Listener NT_AddListenerMultiple(NT_Inst inst, const NT_String* prefixes,
+                                   size_t prefixes_len, unsigned int mask,
+                                   void* data, NT_ListenerCallback callback) {
+  wpi::SmallVector<std::string_view, 8> p;
+  p.reserve(prefixes_len);
+  for (size_t i = 0; i < prefixes_len; ++i) {
+    p.emplace_back(prefixes[i].str, prefixes[i].len);
   }
-
-  // convert result
-  *result_len = result.size();
-  char* result_cstr;
-  ConvertToC(result, &result_cstr);
-  return result_cstr;
+  return nt::AddListener(inst, p, mask, [=](auto& event) {
+    NT_Event event_c;
+    ConvertToC(event, &event_c);
+    callback(data, &event_c);
+    DisposeEvent(&event_c);
+  });
 }
 
-char* NT_GetRpcResultTimeout(NT_Entry entry, NT_RpcCall call,
-                             size_t* result_len, double timeout,
-                             NT_Bool* timed_out) {
-  std::string result;
-  bool cpp_timed_out = false;
-  if (!nt::GetRpcResult(entry, call, &result, timeout, &cpp_timed_out)) {
-    *timed_out = cpp_timed_out;
-    return nullptr;
+NT_Listener NT_AddListener(NT_Topic topic, unsigned int mask, void* data,
+                           NT_ListenerCallback callback) {
+  return nt::AddListener(topic, mask, [=](auto& event) {
+    NT_Event event_c;
+    ConvertToC(event, &event_c);
+    callback(data, &event_c);
+    DisposeEvent(&event_c);
+  });
+}
+
+NT_Listener NT_AddPolledListenerSingle(NT_ListenerPoller poller,
+                                       const char* prefix, size_t prefix_len,
+                                       unsigned int mask) {
+  std::string_view p{prefix, prefix_len};
+  return nt::AddPolledListener(poller, {{p}}, mask);
+}
+
+NT_Listener NT_AddPolledListenerMultiple(NT_ListenerPoller poller,
+                                         const NT_String* prefixes,
+                                         size_t prefixes_len,
+                                         unsigned int mask) {
+  wpi::SmallVector<std::string_view, 8> p;
+  p.reserve(prefixes_len);
+  for (size_t i = 0; i < prefixes_len; ++i) {
+    p.emplace_back(prefixes[i].str, prefixes[i].len);
   }
-
-  *timed_out = cpp_timed_out;
-  // convert result
-  *result_len = result.size();
-  char* result_cstr;
-  ConvertToC(result, &result_cstr);
-  return result_cstr;
+  return nt::AddPolledListener(poller, p, mask);
 }
 
-void NT_CancelRpcResult(NT_Entry entry, NT_RpcCall call) {
-  nt::CancelRpcResult(entry, call);
-}
-
-char* NT_PackRpcDefinition(const NT_RpcDefinition* def, size_t* packed_len) {
-  auto packed = nt::PackRpcDefinition(ConvertFromC(*def));
-
-  // convert result
-  *packed_len = packed.size();
-  char* packed_cstr;
-  ConvertToC(packed, &packed_cstr);
-  return packed_cstr;
-}
-
-NT_Bool NT_UnpackRpcDefinition(const char* packed, size_t packed_len,
-                               NT_RpcDefinition* def) {
-  nt::RpcDefinition def_v;
-  if (!nt::UnpackRpcDefinition({packed, packed_len}, &def_v)) {
-    return 0;
-  }
-
-  // convert result
-  ConvertToC(def_v, def);
-  return 1;
-}
-
-char* NT_PackRpcValues(const NT_Value** values, size_t values_len,
-                       size_t* packed_len) {
-  // create input vector
-  std::vector<std::shared_ptr<Value>> values_v;
-  values_v.reserve(values_len);
-  for (size_t i = 0; i < values_len; ++i) {
-    values_v.push_back(ConvertFromC(*values[i]));
-  }
-
-  // make the call
-  auto packed = nt::PackRpcValues(values_v);
-
-  // convert result
-  *packed_len = packed.size();
-  char* packed_cstr;
-  ConvertToC(packed, &packed_cstr);
-  return packed_cstr;
-}
-
-NT_Value** NT_UnpackRpcValues(const char* packed, size_t packed_len,
-                              const NT_Type* types, size_t types_len) {
-  auto values_v = nt::UnpackRpcValues({packed, packed_len}, {types, types_len});
-  if (values_v.size() == 0) {
-    return nullptr;
-  }
-
-  // create array and copy into it
-  NT_Value** values = static_cast<NT_Value**>(
-      wpi::safe_malloc(values_v.size() * sizeof(NT_Value*)));  // NOLINT
-  for (size_t i = 0; i < values_v.size(); ++i) {
-    values[i] = static_cast<NT_Value*>(wpi::safe_malloc(sizeof(NT_Value)));
-    ConvertToC(*values_v[i], values[i]);
-  }
-  return values;
+NT_Listener NT_AddPolledListener(NT_ListenerPoller poller, NT_Topic topic,
+                                 unsigned int mask) {
+  return nt::AddPolledListener(poller, topic, mask);
 }
 
 /*
  * Client/Server Functions
  */
 
-void NT_SetNetworkIdentity(NT_Inst inst, const char* name, size_t name_len) {
-  nt::SetNetworkIdentity(inst, {name, name_len});
-}
-
 unsigned int NT_GetNetworkMode(NT_Inst inst) {
   return nt::GetNetworkMode(inst);
 }
@@ -587,34 +498,21 @@
 }
 
 void NT_StartServer(NT_Inst inst, const char* persist_filename,
-                    const char* listen_address, unsigned int port) {
-  nt::StartServer(inst, persist_filename, listen_address, port);
+                    const char* listen_address, unsigned int port3,
+                    unsigned int port4) {
+  nt::StartServer(inst, persist_filename, listen_address, port3, port4);
 }
 
 void NT_StopServer(NT_Inst inst) {
   nt::StopServer(inst);
 }
 
-void NT_StartClientNone(NT_Inst inst) {
-  nt::StartClient(inst);
+void NT_StartClient3(NT_Inst inst, const char* identity) {
+  nt::StartClient3(inst, identity);
 }
 
-void NT_StartClient(NT_Inst inst, const char* server_name, unsigned int port) {
-  nt::StartClient(inst, server_name, port);
-}
-
-void NT_StartClientMulti(NT_Inst inst, size_t count, const char** server_names,
-                         const unsigned int* ports) {
-  std::vector<std::pair<std::string_view, unsigned int>> servers;
-  servers.reserve(count);
-  for (size_t i = 0; i < count; ++i) {
-    servers.emplace_back(std::make_pair(server_names[i], ports[i]));
-  }
-  nt::StartClient(inst, servers);
-}
-
-void NT_StartClientTeam(NT_Inst inst, unsigned int team, unsigned int port) {
-  nt::StartClientTeam(inst, team, port);
+void NT_StartClient4(NT_Inst inst, const char* identity) {
+  nt::StartClient4(inst, identity);
 }
 
 void NT_StopClient(NT_Inst inst) {
@@ -647,8 +545,8 @@
   nt::StopDSClient(inst);
 }
 
-void NT_SetUpdateRate(NT_Inst inst, double interval) {
-  nt::SetUpdateRate(inst, interval);
+void NT_FlushLocal(NT_Inst inst) {
+  nt::FlushLocal(inst);
 }
 
 void NT_Flush(NT_Inst inst) {
@@ -664,103 +562,67 @@
   return ConvertToC<NT_ConnectionInfo>(conn_v, count);
 }
 
-/*
- * File Save/Load Functions
- */
-
-const char* NT_SavePersistent(NT_Inst inst, const char* filename) {
-  return nt::SavePersistent(inst, filename);
-}
-
-const char* NT_LoadPersistent(NT_Inst inst, const char* filename,
-                              void (*warn)(size_t line, const char* msg)) {
-  return nt::LoadPersistent(inst, filename, warn);
-}
-
-const char* NT_SaveEntries(NT_Inst inst, const char* filename,
-                           const char* prefix, size_t prefix_len) {
-  return nt::SaveEntries(inst, filename, {prefix, prefix_len});
-}
-
-const char* NT_LoadEntries(NT_Inst inst, const char* filename,
-                           const char* prefix, size_t prefix_len,
-                           void (*warn)(size_t line, const char* msg)) {
-  return nt::LoadEntries(inst, filename, {prefix, prefix_len}, warn);
+int64_t NT_GetServerTimeOffset(NT_Inst inst, NT_Bool* valid) {
+  if (auto v = nt::GetServerTimeOffset(inst)) {
+    *valid = true;
+    return *v;
+  } else {
+    *valid = false;
+    return 0;
+  }
 }
 
 /*
  * Utility Functions
  */
 
-uint64_t NT_Now(void) {
-  return wpi::Now();
+int64_t NT_Now(void) {
+  return nt::Now();
 }
 
-NT_Logger NT_AddLogger(NT_Inst inst, void* data, NT_LogFunc func,
-                       unsigned int min_level, unsigned int max_level) {
-  return nt::AddLogger(
-      inst,
-      [=](const LogMessage& msg) {
-        NT_LogMessage msg_c;
-        ConvertToC(msg, &msg_c);
-        func(data, &msg_c);
-        NT_DisposeLogMessage(&msg_c);
-      },
-      min_level, max_level);
+void NT_SetNow(int64_t timestamp) {
+  nt::SetNow(timestamp);
 }
 
-NT_LoggerPoller NT_CreateLoggerPoller(NT_Inst inst) {
-  return nt::CreateLoggerPoller(inst);
+NT_Listener NT_AddLogger(NT_Inst inst, unsigned int min_level,
+                         unsigned int max_level, void* data,
+                         NT_ListenerCallback func) {
+  return nt::AddLogger(inst, min_level, max_level, [=](auto& event) {
+    NT_Event event_c;
+    ConvertToC(event, &event_c);
+    func(data, &event_c);
+    NT_DisposeEvent(&event_c);
+  });
 }
 
-void NT_DestroyLoggerPoller(NT_LoggerPoller poller) {
-  nt::DestroyLoggerPoller(poller);
-}
-
-NT_Logger NT_AddPolledLogger(NT_LoggerPoller poller, unsigned int min_level,
-                             unsigned int max_level) {
+NT_Listener NT_AddPolledLogger(NT_ListenerPoller poller, unsigned int min_level,
+                               unsigned int max_level) {
   return nt::AddPolledLogger(poller, min_level, max_level);
 }
 
-struct NT_LogMessage* NT_PollLogger(NT_LoggerPoller poller, size_t* len) {
-  auto arr_cpp = nt::PollLogger(poller);
-  return ConvertToC<NT_LogMessage>(arr_cpp, len);
-}
-
-struct NT_LogMessage* NT_PollLoggerTimeout(NT_LoggerPoller poller, size_t* len,
-                                           double timeout, NT_Bool* timed_out) {
-  bool cpp_timed_out = false;
-  auto arr_cpp = nt::PollLogger(poller, timeout, &cpp_timed_out);
-  *timed_out = cpp_timed_out;
-  return ConvertToC<NT_LogMessage>(arr_cpp, len);
-}
-
-void NT_CancelPollLogger(NT_LoggerPoller poller) {
-  nt::CancelPollLogger(poller);
-}
-
-void NT_RemoveLogger(NT_Logger logger) {
-  nt::RemoveLogger(logger);
-}
-
-NT_Bool NT_WaitForLoggerQueue(NT_Inst inst, double timeout) {
-  return nt::WaitForLoggerQueue(inst, timeout);
-}
-
 void NT_DisposeValue(NT_Value* value) {
   switch (value->type) {
     case NT_UNASSIGNED:
     case NT_BOOLEAN:
+    case NT_INTEGER:
+    case NT_FLOAT:
     case NT_DOUBLE:
       break;
     case NT_STRING:
-    case NT_RAW:
-    case NT_RPC:
       std::free(value->data.v_string.str);
       break;
+    case NT_RAW:
+      std::free(value->data.v_raw.data);
+      break;
     case NT_BOOLEAN_ARRAY:
       std::free(value->data.arr_boolean.arr);
       break;
+    case NT_INTEGER_ARRAY:
+      std::free(value->data.arr_int.arr);
+      break;
+    case NT_FLOAT_ARRAY:
+      std::free(value->data.arr_float.arr);
+      break;
     case NT_DOUBLE_ARRAY:
       std::free(value->data.arr_double.arr);
       break;
@@ -776,11 +638,13 @@
   }
   value->type = NT_UNASSIGNED;
   value->last_change = 0;
+  value->server_time = 0;
 }
 
 void NT_InitValue(NT_Value* value) {
   value->type = NT_UNASSIGNED;
   value->last_change = 0;
+  value->server_time = 0;
 }
 
 void NT_DisposeString(NT_String* str) {
@@ -794,7 +658,10 @@
   str->len = 0;
 }
 
-void NT_DisposeEntryArray(NT_Entry* arr, size_t /*count*/) {
+void NT_DisposeValueArray(struct NT_Value* arr, size_t count) {
+  for (size_t i = 0; i < count; ++i) {
+    NT_DisposeValue(&arr[i]);
+  }
   std::free(arr);
 }
 
@@ -805,108 +672,59 @@
   std::free(arr);
 }
 
-void NT_DisposeEntryInfoArray(NT_EntryInfo* arr, size_t count) {
+void NT_DisposeTopicInfoArray(NT_TopicInfo* arr, size_t count) {
   for (size_t i = 0; i < count; i++) {
-    DisposeEntryInfo(&arr[i]);
+    DisposeTopicInfo(&arr[i]);
   }
   std::free(arr);
 }
 
-void NT_DisposeEntryInfo(NT_EntryInfo* info) {
-  DisposeEntryInfo(info);
+void NT_DisposeTopicInfo(NT_TopicInfo* info) {
+  DisposeTopicInfo(info);
 }
 
-void NT_DisposeEntryNotificationArray(NT_EntryNotification* arr, size_t count) {
+void NT_DisposeEventArray(NT_Event* arr, size_t count) {
   for (size_t i = 0; i < count; i++) {
-    DisposeEntryNotification(&arr[i]);
+    DisposeEvent(&arr[i]);
   }
   std::free(arr);
 }
 
-void NT_DisposeEntryNotification(NT_EntryNotification* info) {
-  DisposeEntryNotification(info);
-}
-
-void NT_DisposeConnectionNotificationArray(NT_ConnectionNotification* arr,
-                                           size_t count) {
-  for (size_t i = 0; i < count; i++) {
-    DisposeConnectionNotification(&arr[i]);
-  }
-  std::free(arr);
-}
-
-void NT_DisposeConnectionNotification(NT_ConnectionNotification* info) {
-  DisposeConnectionNotification(info);
-}
-
-void NT_DisposeLogMessageArray(NT_LogMessage* arr, size_t count) {
-  for (size_t i = 0; i < count; i++) {
-    NT_DisposeLogMessage(&arr[i]);
-  }
-  std::free(arr);
-}
-
-void NT_DisposeLogMessage(NT_LogMessage* info) {
-  std::free(info->filename);
-  std::free(info->message);
-}
-
-void NT_DisposeRpcDefinition(NT_RpcDefinition* def) {
-  NT_DisposeString(&def->name);
-
-  for (size_t i = 0; i < def->num_params; ++i) {
-    NT_DisposeString(&def->params[i].name);
-    NT_DisposeValue(&def->params[i].def_value);
-  }
-  std::free(def->params);
-  def->params = nullptr;
-  def->num_params = 0;
-
-  for (size_t i = 0; i < def->num_results; ++i) {
-    NT_DisposeString(&def->results[i].name);
-  }
-  std::free(def->results);
-  def->results = nullptr;
-  def->num_results = 0;
-}
-
-void NT_DisposeRpcAnswerArray(NT_RpcAnswer* arr, size_t count) {
-  for (size_t i = 0; i < count; i++) {
-    NT_DisposeRpcAnswer(&arr[i]);
-  }
-  std::free(arr);
-}
-
-void NT_DisposeRpcAnswer(NT_RpcAnswer* call_info) {
-  NT_DisposeString(&call_info->name);
-  NT_DisposeString(&call_info->params);
-  DisposeConnectionInfo(&call_info->conn);
+void NT_DisposeEvent(NT_Event* event) {
+  DisposeEvent(event);
 }
 
 /* Interop Utility Functions */
 
 /* Array and Struct Allocations */
 
-/* Allocates a char array of the specified size.*/
 char* NT_AllocateCharArray(size_t size) {
   char* retVal = static_cast<char*>(wpi::safe_malloc(size * sizeof(char)));
   return retVal;
 }
 
-/* Allocates an integer or boolean array of the specified size. */
 int* NT_AllocateBooleanArray(size_t size) {
   int* retVal = static_cast<int*>(wpi::safe_malloc(size * sizeof(int)));
   return retVal;
 }
 
-/* Allocates a double array of the specified size. */
+int64_t* NT_AllocateIntegerArray(size_t size) {
+  int64_t* retVal =
+      static_cast<int64_t*>(wpi::safe_malloc(size * sizeof(int64_t)));
+  return retVal;
+}
+
+float* NT_AllocateFloatArray(size_t size) {
+  float* retVal = static_cast<float*>(wpi::safe_malloc(size * sizeof(float)));
+  return retVal;
+}
+
 double* NT_AllocateDoubleArray(size_t size) {
   double* retVal =
       static_cast<double*>(wpi::safe_malloc(size * sizeof(double)));
   return retVal;
 }
 
-/* Allocates an NT_String array of the specified size. */
 struct NT_String* NT_AllocateStringArray(size_t size) {
   NT_String* retVal =
       static_cast<NT_String*>(wpi::safe_malloc(size * sizeof(NT_String)));
@@ -916,99 +734,25 @@
 void NT_FreeCharArray(char* v_char) {
   std::free(v_char);
 }
-void NT_FreeDoubleArray(double* v_double) {
-  std::free(v_double);
-}
 void NT_FreeBooleanArray(int* v_boolean) {
   std::free(v_boolean);
 }
+void NT_FreeIntegerArray(int64_t* v_int) {
+  std::free(v_int);
+}
+void NT_FreeFloatArray(float* v_float) {
+  std::free(v_float);
+}
+void NT_FreeDoubleArray(double* v_double) {
+  std::free(v_double);
+}
 void NT_FreeStringArray(struct NT_String* v_string, size_t arr_size) {
-  for (size_t i = 0; i < arr_size; i++) {
+  for (size_t i = 0; i < arr_size; ++i) {
     std::free(v_string[i].str);
   }
   std::free(v_string);
 }
 
-NT_Bool NT_SetEntryDouble(NT_Entry entry, uint64_t time, double v_double,
-                          NT_Bool force) {
-  if (force != 0) {
-    nt::SetEntryTypeValue(entry, Value::MakeDouble(v_double, time));
-    return 1;
-  } else {
-    return nt::SetEntryValue(entry, Value::MakeDouble(v_double, time));
-  }
-}
-
-NT_Bool NT_SetEntryBoolean(NT_Entry entry, uint64_t time, NT_Bool v_boolean,
-                           NT_Bool force) {
-  if (force != 0) {
-    nt::SetEntryTypeValue(entry, Value::MakeBoolean(v_boolean != 0, time));
-    return 1;
-  } else {
-    return nt::SetEntryValue(entry, Value::MakeBoolean(v_boolean != 0, time));
-  }
-}
-
-NT_Bool NT_SetEntryString(NT_Entry entry, uint64_t time, const char* str,
-                          size_t str_len, NT_Bool force) {
-  if (force != 0) {
-    nt::SetEntryTypeValue(entry, Value::MakeString({str, str_len}, time));
-    return 1;
-  } else {
-    return nt::SetEntryValue(entry, Value::MakeString({str, str_len}, time));
-  }
-}
-
-NT_Bool NT_SetEntryRaw(NT_Entry entry, uint64_t time, const char* raw,
-                       size_t raw_len, NT_Bool force) {
-  if (force != 0) {
-    nt::SetEntryTypeValue(entry, Value::MakeRaw({raw, raw_len}, time));
-    return 1;
-  } else {
-    return nt::SetEntryValue(entry, Value::MakeRaw({raw, raw_len}, time));
-  }
-}
-
-NT_Bool NT_SetEntryBooleanArray(NT_Entry entry, uint64_t time,
-                                const NT_Bool* arr, size_t size,
-                                NT_Bool force) {
-  if (force != 0) {
-    nt::SetEntryTypeValue(entry,
-                          Value::MakeBooleanArray(wpi::span(arr, size), time));
-    return 1;
-  } else {
-    return nt::SetEntryValue(
-        entry, Value::MakeBooleanArray(wpi::span(arr, size), time));
-  }
-}
-
-NT_Bool NT_SetEntryDoubleArray(NT_Entry entry, uint64_t time, const double* arr,
-                               size_t size, NT_Bool force) {
-  if (force != 0) {
-    nt::SetEntryTypeValue(entry, Value::MakeDoubleArray({arr, size}, time));
-    return 1;
-  } else {
-    return nt::SetEntryValue(entry, Value::MakeDoubleArray({arr, size}, time));
-  }
-}
-
-NT_Bool NT_SetEntryStringArray(NT_Entry entry, uint64_t time,
-                               const struct NT_String* arr, size_t size,
-                               NT_Bool force) {
-  std::vector<std::string> v;
-  v.reserve(size);
-  for (size_t i = 0; i < size; ++i) {
-    v.emplace_back(ConvertFromC(arr[i]));
-  }
-
-  if (force != 0) {
-    nt::SetEntryTypeValue(entry, Value::MakeStringArray(std::move(v), time));
-    return 1;
-  } else {
-    return nt::SetEntryValue(entry, Value::MakeStringArray(std::move(v), time));
-  }
-}
-
 enum NT_Type NT_GetValueType(const struct NT_Value* value) {
   if (!value) {
     return NT_Type::NT_UNASSIGNED;
@@ -1026,6 +770,26 @@
   return 1;
 }
 
+NT_Bool NT_GetValueInteger(const struct NT_Value* value, uint64_t* last_change,
+                           int64_t* v_int) {
+  if (!value || value->type != NT_Type::NT_INTEGER) {
+    return 0;
+  }
+  *last_change = value->last_change;
+  *v_int = value->data.v_int;
+  return 1;
+}
+
+NT_Bool NT_GetValueFloat(const struct NT_Value* value, uint64_t* last_change,
+                         float* v_float) {
+  if (!value || value->type != NT_Type::NT_FLOAT) {
+    return 0;
+  }
+  *last_change = value->last_change;
+  *v_float = value->data.v_float;
+  return 1;
+}
+
 NT_Bool NT_GetValueDouble(const struct NT_Value* value, uint64_t* last_change,
                           double* v_double) {
   if (!value || value->type != NT_Type::NT_DOUBLE) {
@@ -1049,16 +813,16 @@
   return str;
 }
 
-char* NT_GetValueRaw(const struct NT_Value* value, uint64_t* last_change,
-                     size_t* raw_len) {
+uint8_t* NT_GetValueRaw(const struct NT_Value* value, uint64_t* last_change,
+                        size_t* raw_len) {
   if (!value || value->type != NT_Type::NT_RAW) {
     return nullptr;
   }
   *last_change = value->last_change;
-  *raw_len = value->data.v_string.len;
-  char* raw =
-      static_cast<char*>(wpi::safe_malloc(value->data.v_string.len + 1));
-  std::memcpy(raw, value->data.v_string.str, value->data.v_string.len + 1);
+  *raw_len = value->data.v_raw.size;
+  uint8_t* raw =
+      static_cast<uint8_t*>(wpi::safe_malloc(value->data.v_raw.size));
+  std::memcpy(raw, value->data.v_raw.data, value->data.v_raw.size);
   return raw;
 }
 
@@ -1076,6 +840,34 @@
   return arr;
 }
 
+int64_t* NT_GetValueIntegerArray(const struct NT_Value* value,
+                                 uint64_t* last_change, size_t* arr_size) {
+  if (!value || value->type != NT_Type::NT_INTEGER_ARRAY) {
+    return nullptr;
+  }
+  *last_change = value->last_change;
+  *arr_size = value->data.arr_int.size;
+  int64_t* arr = static_cast<int64_t*>(
+      wpi::safe_malloc(value->data.arr_int.size * sizeof(int64_t)));
+  std::memcpy(arr, value->data.arr_int.arr,
+              value->data.arr_int.size * sizeof(int64_t));
+  return arr;
+}
+
+float* NT_GetValueFloatArray(const struct NT_Value* value,
+                             uint64_t* last_change, size_t* arr_size) {
+  if (!value || value->type != NT_Type::NT_FLOAT_ARRAY) {
+    return nullptr;
+  }
+  *last_change = value->last_change;
+  *arr_size = value->data.arr_float.size;
+  float* arr = static_cast<float*>(
+      wpi::safe_malloc(value->data.arr_float.size * sizeof(float)));
+  std::memcpy(arr, value->data.arr_float.arr,
+              value->data.arr_float.size * sizeof(float));
+  return arr;
+}
+
 double* NT_GetValueDoubleArray(const struct NT_Value* value,
                                uint64_t* last_change, size_t* arr_size) {
   if (!value || value->type != NT_Type::NT_DOUBLE_ARRAY) {
@@ -1108,151 +900,4 @@
   return arr;
 }
 
-NT_Bool NT_SetDefaultEntryBoolean(NT_Entry entry, uint64_t time,
-                                  NT_Bool default_boolean) {
-  return nt::SetDefaultEntryValue(
-      entry, Value::MakeBoolean(default_boolean != 0, time));
-}
-
-NT_Bool NT_SetDefaultEntryDouble(NT_Entry entry, uint64_t time,
-                                 double default_double) {
-  return nt::SetDefaultEntryValue(entry,
-                                  Value::MakeDouble(default_double, time));
-}
-
-NT_Bool NT_SetDefaultEntryString(NT_Entry entry, uint64_t time,
-                                 const char* default_value,
-                                 size_t default_len) {
-  return nt::SetDefaultEntryValue(
-      entry, Value::MakeString({default_value, default_len}, time));
-}
-
-NT_Bool NT_SetDefaultEntryRaw(NT_Entry entry, uint64_t time,
-                              const char* default_value, size_t default_len) {
-  return nt::SetDefaultEntryValue(
-      entry, Value::MakeRaw({default_value, default_len}, time));
-}
-
-NT_Bool NT_SetDefaultEntryBooleanArray(NT_Entry entry, uint64_t time,
-                                       const NT_Bool* default_value,
-                                       size_t default_size) {
-  return nt::SetDefaultEntryValue(
-      entry,
-      Value::MakeBooleanArray(wpi::span(default_value, default_size), time));
-}
-
-NT_Bool NT_SetDefaultEntryDoubleArray(NT_Entry entry, uint64_t time,
-                                      const double* default_value,
-                                      size_t default_size) {
-  return nt::SetDefaultEntryValue(
-      entry, Value::MakeDoubleArray({default_value, default_size}, time));
-}
-
-NT_Bool NT_SetDefaultEntryStringArray(NT_Entry entry, uint64_t time,
-                                      const struct NT_String* default_value,
-                                      size_t default_size) {
-  std::vector<std::string> vec;
-  vec.reserve(default_size);
-  for (size_t i = 0; i < default_size; ++i) {
-    vec.emplace_back(ConvertFromC(default_value[i]));
-  }
-
-  return nt::SetDefaultEntryValue(entry,
-                                  Value::MakeStringArray(std::move(vec), time));
-}
-
-NT_Bool NT_GetEntryBoolean(NT_Entry entry, uint64_t* last_change,
-                           NT_Bool* v_boolean) {
-  auto v = nt::GetEntryValue(entry);
-  if (!v || !v->IsBoolean()) {
-    return 0;
-  }
-  *v_boolean = v->GetBoolean();
-  *last_change = v->last_change();
-  return 1;
-}
-
-NT_Bool NT_GetEntryDouble(NT_Entry entry, uint64_t* last_change,
-                          double* v_double) {
-  auto v = nt::GetEntryValue(entry);
-  if (!v || !v->IsDouble()) {
-    return 0;
-  }
-  *last_change = v->last_change();
-  *v_double = v->GetDouble();
-  return 1;
-}
-
-char* NT_GetEntryString(NT_Entry entry, uint64_t* last_change,
-                        size_t* str_len) {
-  auto v = nt::GetEntryValue(entry);
-  if (!v || !v->IsString()) {
-    return nullptr;
-  }
-  *last_change = v->last_change();
-  struct NT_String v_string;
-  nt::ConvertToC(v->GetString(), &v_string);
-  *str_len = v_string.len;
-  return v_string.str;
-}
-
-char* NT_GetEntryRaw(NT_Entry entry, uint64_t* last_change, size_t* raw_len) {
-  auto v = nt::GetEntryValue(entry);
-  if (!v || !v->IsRaw()) {
-    return nullptr;
-  }
-  *last_change = v->last_change();
-  struct NT_String v_raw;
-  nt::ConvertToC(v->GetRaw(), &v_raw);
-  *raw_len = v_raw.len;
-  return v_raw.str;
-}
-
-NT_Bool* NT_GetEntryBooleanArray(NT_Entry entry, uint64_t* last_change,
-                                 size_t* arr_size) {
-  auto v = nt::GetEntryValue(entry);
-  if (!v || !v->IsBooleanArray()) {
-    return nullptr;
-  }
-  *last_change = v->last_change();
-  auto vArr = v->GetBooleanArray();
-  NT_Bool* arr =
-      static_cast<int*>(wpi::safe_malloc(vArr.size() * sizeof(NT_Bool)));
-  *arr_size = vArr.size();
-  std::copy(vArr.begin(), vArr.end(), arr);
-  return arr;
-}
-
-double* NT_GetEntryDoubleArray(NT_Entry entry, uint64_t* last_change,
-                               size_t* arr_size) {
-  auto v = nt::GetEntryValue(entry);
-  if (!v || !v->IsDoubleArray()) {
-    return nullptr;
-  }
-  *last_change = v->last_change();
-  auto vArr = v->GetDoubleArray();
-  double* arr =
-      static_cast<double*>(wpi::safe_malloc(vArr.size() * sizeof(double)));
-  *arr_size = vArr.size();
-  std::copy(vArr.begin(), vArr.end(), arr);
-  return arr;
-}
-
-NT_String* NT_GetEntryStringArray(NT_Entry entry, uint64_t* last_change,
-                                  size_t* arr_size) {
-  auto v = nt::GetEntryValue(entry);
-  if (!v || !v->IsStringArray()) {
-    return nullptr;
-  }
-  *last_change = v->last_change();
-  auto vArr = v->GetStringArray();
-  NT_String* arr = static_cast<NT_String*>(
-      wpi::safe_malloc(vArr.size() * sizeof(NT_String)));
-  for (size_t i = 0; i < vArr.size(); ++i) {
-    ConvertToC(vArr[i], &arr[i]);
-  }
-  *arr_size = vArr.size();
-  return arr;
-}
-
 }  // extern "C"
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/ntcore_cpp.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/ntcore_cpp.cpp
index 8616aaf..cfb5af2 100644
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/ntcore_cpp.cpp
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/ntcore_cpp.cpp
@@ -4,21 +4,35 @@
 
 #include <stdint.h>
 
+#include <atomic>
 #include <cassert>
 #include <cstdio>
 #include <cstdlib>
 
+#include <fmt/format.h>
+#include <wpi/json.h>
 #include <wpi/timestamp.h>
 
 #include "Handle.h"
 #include "InstanceImpl.h"
 #include "Log.h"
-#include "WireDecoder.h"
-#include "WireEncoder.h"
+#include "Types_internal.h"
 #include "ntcore.h"
+#include "ntcore_c.h"
+
+static std::atomic_bool gNowSet{false};
+static std::atomic<int64_t> gNowTime;
 
 namespace nt {
 
+wpi::json TopicInfo::GetProperties() const {
+  try {
+    return wpi::json::parse(properties);
+  } catch (wpi::json::parse_error&) {
+    return wpi::json::object();
+  }
+}
+
 /*
  * Instance Functions
  */
@@ -31,6 +45,12 @@
   return Handle{InstanceImpl::Alloc(), 0, Handle::kInstance};
 }
 
+void ResetInstance(NT_Inst inst) {
+  if (auto ii = InstanceImpl::GetTyped(inst, Handle::kInstance)) {
+    ii->Reset();
+  }
+}
+
 void DestroyInstance(NT_Inst inst) {
   int i = Handle{inst}.GetTypedInst(Handle::kInstance);
   if (i < 0) {
@@ -42,7 +62,7 @@
 NT_Inst GetInstanceFromHandle(NT_Handle handle) {
   Handle h{handle};
   auto type = h.GetType();
-  if (type >= Handle::kConnectionListener && type <= Handle::kRpcCallPoller) {
+  if (type >= Handle::kListener && type < Handle::kTypeMax) {
     return Handle(h.GetInst(), 0, Handle::kInstance);
   }
 
@@ -54,1120 +74,704 @@
  */
 
 NT_Entry GetEntry(NT_Inst inst, std::string_view name) {
-  int i = Handle{inst}.GetTypedInst(Handle::kInstance);
-  auto ii = InstanceImpl::Get(i);
-  if (!ii) {
-    return 0;
-  }
-
-  unsigned int id = ii->storage.GetEntry(name);
-  if (id == UINT_MAX) {
-    return 0;
-  }
-  return Handle(i, id, Handle::kEntry);
-}
-
-std::vector<NT_Entry> GetEntries(NT_Inst inst, std::string_view prefix,
-                                 unsigned int types) {
-  int i = Handle{inst}.GetTypedInst(Handle::kInstance);
-  auto ii = InstanceImpl::Get(i);
-  if (!ii) {
+  if (auto ii = InstanceImpl::GetTyped(inst, Handle::kInstance)) {
+    return ii->localStorage.GetEntry(name);
+  } else {
     return {};
   }
-
-  auto arr = ii->storage.GetEntries(prefix, types);
-  // convert indices to handles
-  for (auto& val : arr) {
-    val = Handle(i, val, Handle::kEntry);
-  }
-  return arr;
 }
 
 std::string GetEntryName(NT_Entry entry) {
-  Handle handle{entry};
-  int id = handle.GetTypedIndex(Handle::kEntry);
-  auto ii = InstanceImpl::Get(handle.GetInst());
-  if (id < 0 || !ii) {
+  if (auto ii = InstanceImpl::GetHandle(entry)) {
+    return ii->localStorage.GetEntryName(entry);
+  } else {
     return {};
   }
-
-  return ii->storage.GetEntryName(id);
 }
 
 NT_Type GetEntryType(NT_Entry entry) {
-  Handle handle{entry};
-  int id = handle.GetTypedIndex(Handle::kEntry);
-  auto ii = InstanceImpl::Get(handle.GetInst());
-  if (id < 0 || !ii) {
-    return NT_UNASSIGNED;
+  if (auto ii = InstanceImpl::GetHandle(entry)) {
+    return ii->localStorage.GetEntryType(entry);
+  } else {
+    return {};
   }
-
-  return ii->storage.GetEntryType(id);
 }
 
-uint64_t GetEntryLastChange(NT_Entry entry) {
-  Handle handle{entry};
-  int id = handle.GetTypedIndex(Handle::kEntry);
-  auto ii = InstanceImpl::Get(handle.GetInst());
-  if (id < 0 || !ii) {
-    return 0;
+int64_t GetEntryLastChange(NT_Handle subentry) {
+  if (auto ii = InstanceImpl::GetHandle(subentry)) {
+    return ii->localStorage.GetEntryLastChange(subentry);
+  } else {
+    return {};
   }
-
-  return ii->storage.GetEntryLastChange(id);
 }
 
-std::shared_ptr<Value> GetEntryValue(NT_Entry entry) {
-  Handle handle{entry};
-  int id = handle.GetTypedIndex(Handle::kEntry);
-  auto ii = InstanceImpl::Get(handle.GetInst());
-  if (id < 0 || !ii) {
-    return nullptr;
+Value GetEntryValue(NT_Handle subentry) {
+  if (auto ii = InstanceImpl::GetHandle(subentry)) {
+    return ii->localStorage.GetEntryValue(subentry);
+  } else {
+    return {};
   }
-
-  return ii->storage.GetEntryValue(id);
 }
 
-bool SetDefaultEntryValue(NT_Entry entry, std::shared_ptr<Value> value) {
-  Handle handle{entry};
-  int id = handle.GetTypedIndex(Handle::kEntry);
-  auto ii = InstanceImpl::Get(handle.GetInst());
-  if (id < 0 || !ii) {
-    return false;
+bool SetDefaultEntryValue(NT_Entry entry, const Value& value) {
+  if (auto ii = InstanceImpl::GetHandle(entry)) {
+    return ii->localStorage.SetDefaultEntryValue(entry, value);
+  } else {
+    return {};
   }
-
-  return ii->storage.SetDefaultEntryValue(id, value);
 }
 
-bool SetEntryValue(NT_Entry entry, std::shared_ptr<Value> value) {
-  Handle handle{entry};
-  int id = handle.GetTypedIndex(Handle::kEntry);
-  auto ii = InstanceImpl::Get(handle.GetInst());
-  if (id < 0 || !ii) {
-    return false;
+bool SetEntryValue(NT_Entry entry, const Value& value) {
+  if (auto ii = InstanceImpl::GetHandle(entry)) {
+    return ii->localStorage.SetEntryValue(entry, value);
+  } else {
+    return {};
   }
-
-  return ii->storage.SetEntryValue(id, value);
-}
-
-void SetEntryTypeValue(NT_Entry entry, std::shared_ptr<Value> value) {
-  Handle handle{entry};
-  int id = handle.GetTypedIndex(Handle::kEntry);
-  auto ii = InstanceImpl::Get(handle.GetInst());
-  if (id < 0 || !ii) {
-    return;
-  }
-
-  ii->storage.SetEntryTypeValue(id, value);
 }
 
 void SetEntryFlags(NT_Entry entry, unsigned int flags) {
-  Handle handle{entry};
-  int id = handle.GetTypedIndex(Handle::kEntry);
-  auto ii = InstanceImpl::Get(handle.GetInst());
-  if (id < 0 || !ii) {
-    return;
+  if (auto ii = InstanceImpl::GetHandle(entry)) {
+    ii->localStorage.SetEntryFlags(entry, flags);
   }
-
-  ii->storage.SetEntryFlags(id, flags);
 }
 
 unsigned int GetEntryFlags(NT_Entry entry) {
-  Handle handle{entry};
-  int id = handle.GetTypedIndex(Handle::kEntry);
-  auto ii = InstanceImpl::Get(handle.GetInst());
-  if (id < 0 || !ii) {
-    return 0;
-  }
-
-  return ii->storage.GetEntryFlags(id);
-}
-
-void DeleteEntry(NT_Entry entry) {
-  Handle handle{entry};
-  int id = handle.GetTypedIndex(Handle::kEntry);
-  auto ii = InstanceImpl::Get(handle.GetInst());
-  if (id < 0 || !ii) {
-    return;
-  }
-
-  ii->storage.DeleteEntry(id);
-}
-
-void DeleteAllEntries(NT_Inst inst) {
-  int i = Handle{inst}.GetTypedInst(Handle::kInstance);
-  auto ii = InstanceImpl::Get(i);
-  if (i < 0 || !ii) {
-    return;
-  }
-
-  ii->storage.DeleteAllEntries();
-}
-
-std::vector<EntryInfo> GetEntryInfo(NT_Inst inst, std::string_view prefix,
-                                    unsigned int types) {
-  int i = Handle{inst}.GetTypedInst(Handle::kInstance);
-  auto ii = InstanceImpl::Get(i);
-  if (!ii) {
+  if (auto ii = InstanceImpl::GetHandle(entry)) {
+    return ii->localStorage.GetEntryFlags(entry);
+  } else {
     return {};
   }
-
-  return ii->storage.GetEntryInfo(i, prefix, types);
 }
 
-EntryInfo GetEntryInfo(NT_Entry entry) {
-  Handle handle{entry};
-  int id = handle.GetTypedIndex(Handle::kEntry);
-  int i = handle.GetInst();
-  auto ii = InstanceImpl::Get(i);
-  if (id < 0 || !ii) {
-    EntryInfo info;
-    info.entry = 0;
-    info.type = NT_UNASSIGNED;
-    info.flags = 0;
-    info.last_change = 0;
-    return info;
+std::vector<Value> ReadQueueValue(NT_Handle subentry) {
+  if (auto ii = InstanceImpl::GetHandle(subentry)) {
+    return ii->localStorage.ReadQueueValue(subentry);
+  } else {
+    return {};
   }
+}
 
-  return ii->storage.GetEntryInfo(i, id);
+/*
+ * Topic Functions
+ */
+
+std::vector<NT_Topic> GetTopics(NT_Inst inst, std::string_view prefix,
+                                unsigned int types) {
+  if (auto ii = InstanceImpl::GetTyped(inst, Handle::kInstance)) {
+    return ii->localStorage.GetTopics(prefix, types);
+  } else {
+    return {};
+  }
+}
+
+std::vector<NT_Topic> GetTopics(NT_Inst inst, std::string_view prefix,
+                                std::span<const std::string_view> types) {
+  if (auto ii = InstanceImpl::GetTyped(inst, Handle::kInstance)) {
+    return ii->localStorage.GetTopics(prefix, types);
+  } else {
+    return {};
+  }
+}
+
+std::vector<TopicInfo> GetTopicInfo(NT_Inst inst, std::string_view prefix,
+                                    unsigned int types) {
+  if (auto ii = InstanceImpl::GetTyped(inst, Handle::kInstance)) {
+    return ii->localStorage.GetTopicInfo(prefix, types);
+  } else {
+    return {};
+  }
+}
+
+std::vector<TopicInfo> GetTopicInfo(NT_Inst inst, std::string_view prefix,
+                                    std::span<const std::string_view> types) {
+  if (auto ii = InstanceImpl::GetTyped(inst, Handle::kInstance)) {
+    return ii->localStorage.GetTopicInfo(prefix, types);
+  } else {
+    return {};
+  }
+}
+
+TopicInfo GetTopicInfo(NT_Topic topic) {
+  if (auto ii = InstanceImpl::GetTyped(topic, Handle::kTopic)) {
+    return ii->localStorage.GetTopicInfo(topic);
+  } else {
+    return {};
+  }
+}
+
+NT_Topic GetTopic(NT_Inst inst, std::string_view name) {
+  if (auto ii = InstanceImpl::GetTyped(inst, Handle::kInstance)) {
+    return ii->localStorage.GetTopic(name);
+  } else {
+    return {};
+  }
+}
+
+std::string GetTopicName(NT_Topic topic) {
+  if (auto ii = InstanceImpl::GetTyped(topic, Handle::kTopic)) {
+    return ii->localStorage.GetTopicName(topic);
+  } else {
+    return {};
+  }
+}
+
+NT_Type GetTopicType(NT_Topic topic) {
+  if (auto ii = InstanceImpl::GetTyped(topic, Handle::kTopic)) {
+    return ii->localStorage.GetTopicType(topic);
+  } else {
+    return {};
+  }
+}
+
+std::string GetTopicTypeString(NT_Topic topic) {
+  if (auto ii = InstanceImpl::GetTyped(topic, Handle::kTopic)) {
+    return ii->localStorage.GetTopicTypeString(topic);
+  } else {
+    return {};
+  }
+}
+
+void SetTopicPersistent(NT_Topic topic, bool value) {
+  if (auto ii = InstanceImpl::GetTyped(topic, Handle::kTopic)) {
+    ii->localStorage.SetTopicPersistent(topic, value);
+  } else {
+    return;
+  }
+}
+
+bool GetTopicPersistent(NT_Topic topic) {
+  if (auto ii = InstanceImpl::GetTyped(topic, Handle::kTopic)) {
+    return ii->localStorage.GetTopicPersistent(topic);
+  } else {
+    return {};
+  }
+}
+
+void SetTopicRetained(NT_Topic topic, bool value) {
+  if (auto ii = InstanceImpl::GetTyped(topic, Handle::kTopic)) {
+    ii->localStorage.SetTopicRetained(topic, value);
+  } else {
+    return;
+  }
+}
+
+bool GetTopicRetained(NT_Topic topic) {
+  if (auto ii = InstanceImpl::GetTyped(topic, Handle::kTopic)) {
+    return ii->localStorage.GetTopicRetained(topic);
+  } else {
+    return {};
+  }
+}
+
+bool GetTopicExists(NT_Handle handle) {
+  if (auto ii = InstanceImpl::GetHandle(handle)) {
+    return ii->localStorage.GetTopicExists(handle);
+  }
+  return false;
+}
+
+wpi::json GetTopicProperty(NT_Topic topic, std::string_view name) {
+  if (auto ii = InstanceImpl::GetTyped(topic, Handle::kTopic)) {
+    return ii->localStorage.GetTopicProperty(topic, name);
+  } else {
+    return {};
+  }
+}
+
+void SetTopicProperty(NT_Topic topic, std::string_view name,
+                      const wpi::json& value) {
+  if (auto ii = InstanceImpl::GetTyped(topic, Handle::kTopic)) {
+    ii->localStorage.SetTopicProperty(topic, name, value);
+  } else {
+    return;
+  }
+}
+
+void DeleteTopicProperty(NT_Topic topic, std::string_view name) {
+  if (auto ii = InstanceImpl::GetTyped(topic, Handle::kTopic)) {
+    ii->localStorage.DeleteTopicProperty(topic, name);
+  }
+}
+
+wpi::json GetTopicProperties(NT_Topic topic) {
+  if (auto ii = InstanceImpl::GetTyped(topic, Handle::kTopic)) {
+    return ii->localStorage.GetTopicProperties(topic);
+  } else {
+    return {};
+  }
+}
+
+bool SetTopicProperties(NT_Topic topic, const wpi::json& properties) {
+  if (auto ii = InstanceImpl::GetTyped(topic, Handle::kTopic)) {
+    return ii->localStorage.SetTopicProperties(topic, properties);
+  } else {
+    return {};
+  }
+}
+
+NT_Subscriber Subscribe(NT_Topic topic, NT_Type type, std::string_view typeStr,
+                        const PubSubOptions& options) {
+  if (auto ii = InstanceImpl::GetTyped(topic, Handle::kTopic)) {
+    return ii->localStorage.Subscribe(topic, type, typeStr, options);
+  } else {
+    return {};
+  }
+}
+
+void Unsubscribe(NT_Subscriber sub) {
+  if (auto ii = InstanceImpl::GetTyped(sub, Handle::kSubscriber)) {
+    ii->localStorage.Unsubscribe(sub);
+  }
+}
+
+NT_Publisher Publish(NT_Topic topic, NT_Type type, std::string_view typeStr,
+                     const PubSubOptions& options) {
+  return PublishEx(topic, type, typeStr, wpi::json::object(), options);
+}
+
+NT_Publisher PublishEx(NT_Topic topic, NT_Type type, std::string_view typeStr,
+                       const wpi::json& properties,
+                       const PubSubOptions& options) {
+  if (auto ii = InstanceImpl::GetTyped(topic, Handle::kTopic)) {
+    return ii->localStorage.Publish(topic, type, typeStr, properties, options);
+  } else {
+    return {};
+  }
+}
+
+void Unpublish(NT_Handle pubentry) {
+  if (auto ii = InstanceImpl::GetHandle(pubentry)) {
+    ii->localStorage.Unpublish(pubentry);
+  }
+}
+
+NT_Entry GetEntry(NT_Topic topic, NT_Type type, std::string_view typeStr,
+                  const PubSubOptions& options) {
+  if (auto ii = InstanceImpl::GetTyped(topic, Handle::kTopic)) {
+    return ii->localStorage.GetEntry(topic, type, typeStr, options);
+  } else {
+    return {};
+  }
+}
+
+void ReleaseEntry(NT_Entry entry) {
+  if (auto ii = InstanceImpl::GetTyped(entry, Handle::kEntry)) {
+    ii->localStorage.ReleaseEntry(entry);
+  }
+}
+
+void Release(NT_Handle pubsubentry) {
+  if (auto ii = InstanceImpl::GetHandle(pubsubentry)) {
+    ii->localStorage.Release(pubsubentry);
+  }
+}
+
+NT_Topic GetTopicFromHandle(NT_Handle pubsubentry) {
+  if (auto ii = InstanceImpl::GetHandle(pubsubentry)) {
+    return ii->localStorage.GetTopicFromHandle(pubsubentry);
+  } else {
+    return {};
+  }
+}
+
+NT_MultiSubscriber SubscribeMultiple(NT_Inst inst,
+                                     std::span<const std::string_view> prefixes,
+                                     const PubSubOptions& options) {
+  if (auto ii = InstanceImpl::GetTyped(inst, Handle::kInstance)) {
+    return ii->localStorage.SubscribeMultiple(prefixes, options);
+  } else {
+    return {};
+  }
+}
+
+void UnsubscribeMultiple(NT_MultiSubscriber sub) {
+  if (auto ii = InstanceImpl::GetTyped(sub, Handle::kMultiSubscriber)) {
+    ii->localStorage.UnsubscribeMultiple(sub);
+  }
 }
 
 /*
  * Callback Creation Functions
  */
 
-NT_EntryListener AddEntryListener(
-    NT_Inst inst, std::string_view prefix,
-    std::function<void(const EntryNotification& event)> callback,
-    unsigned int flags) {
-  int i = Handle{inst}.GetTypedInst(Handle::kInstance);
-  auto ii = InstanceImpl::Get(i);
-  if (i < 0 || !ii) {
-    return 0;
+static void CleanupListeners(
+    InstanceImpl& ii,
+    std::span<const std::pair<NT_Listener, unsigned int>> listeners) {
+  bool updateMinLevel = false;
+  for (auto&& [listener, mask] : listeners) {
+    // connection doesn't need removal notification
+    if ((mask & (NT_EVENT_TOPIC | NT_EVENT_VALUE_ALL)) != 0) {
+      ii.localStorage.RemoveListener(listener, mask);
+    }
+    if ((mask & NT_EVENT_LOGMESSAGE) != 0) {
+      ii.logger_impl.RemoveListener(listener);
+      updateMinLevel = true;
+    }
   }
-
-  unsigned int uid = ii->storage.AddListener(prefix, callback, flags);
-  return Handle(i, uid, Handle::kEntryListener);
+  if (updateMinLevel) {
+    ii.logger.set_min_level(ii.logger_impl.GetMinLevel());
+  }
 }
 
-NT_EntryListener AddEntryListener(
-    NT_Entry entry,
-    std::function<void(const EntryNotification& event)> callback,
-    unsigned int flags) {
-  Handle handle{entry};
-  int id = handle.GetTypedIndex(Handle::kEntry);
-  int i = handle.GetInst();
-  auto ii = InstanceImpl::Get(i);
-  if (id < 0 || !ii) {
-    return 0;
+static void DoAddListener(InstanceImpl& ii, NT_Listener listener,
+                          NT_Handle handle, unsigned int mask) {
+  if (Handle{handle}.IsType(Handle::kInstance)) {
+    if ((mask & NT_EVENT_CONNECTION) != 0) {
+      ii.connectionList.AddListener(listener, mask);
+    }
+    if ((mask & NT_EVENT_LOGMESSAGE) != 0) {
+      ii.logger_impl.AddListener(listener, NT_LOG_INFO, UINT_MAX);
+    }
+    if ((mask & NT_EVENT_TIMESYNC) != 0) {
+      ii.AddTimeSyncListener(listener, mask);
+    }
+  } else if ((mask & (NT_EVENT_TOPIC | NT_EVENT_VALUE_ALL)) != 0) {
+    ii.localStorage.AddListener(listener, handle, mask);
   }
-
-  unsigned int uid = ii->storage.AddListener(id, callback, flags);
-  return Handle(i, uid, Handle::kEntryListener);
 }
 
-NT_EntryListenerPoller CreateEntryListenerPoller(NT_Inst inst) {
-  int i = Handle{inst}.GetTypedInst(Handle::kInstance);
-  auto ii = InstanceImpl::Get(i);
-  if (!ii) {
-    return 0;
-  }
-
-  return Handle(i, ii->entry_notifier.CreatePoller(),
-                Handle::kEntryListenerPoller);
-}
-
-void DestroyEntryListenerPoller(NT_EntryListenerPoller poller) {
-  Handle handle{poller};
-  int id = handle.GetTypedIndex(Handle::kEntryListenerPoller);
-  auto ii = InstanceImpl::Get(handle.GetInst());
-  if (id < 0 || !ii) {
-    return;
-  }
-
-  ii->entry_notifier.RemovePoller(id);
-}
-
-NT_EntryListener AddPolledEntryListener(NT_EntryListenerPoller poller,
-                                        std::string_view prefix,
-                                        unsigned int flags) {
-  Handle handle{poller};
-  int id = handle.GetTypedIndex(Handle::kEntryListenerPoller);
-  int i = handle.GetInst();
-  auto ii = InstanceImpl::Get(i);
-  if (id < 0 || !ii) {
-    return 0;
-  }
-
-  unsigned int uid = ii->storage.AddPolledListener(id, prefix, flags);
-  return Handle(i, uid, Handle::kEntryListener);
-}
-
-NT_EntryListener AddPolledEntryListener(NT_EntryListenerPoller poller,
-                                        NT_Entry entry, unsigned int flags) {
-  Handle handle{entry};
-  int id = handle.GetTypedIndex(Handle::kEntry);
-  int i = handle.GetInst();
-  auto ii = InstanceImpl::Get(i);
-  if (id < 0 || !ii) {
-    return 0;
-  }
-
-  Handle phandle{poller};
-  int p_id = phandle.GetTypedIndex(Handle::kEntryListenerPoller);
-  if (p_id < 0) {
-    return 0;
-  }
-  if (handle.GetInst() != phandle.GetInst()) {
-    return 0;
-  }
-
-  unsigned int uid = ii->storage.AddPolledListener(p_id, id, flags);
-  return Handle(i, uid, Handle::kEntryListener);
-}
-
-std::vector<EntryNotification> PollEntryListener(
-    NT_EntryListenerPoller poller) {
-  Handle handle{poller};
-  int id = handle.GetTypedIndex(Handle::kEntryListenerPoller);
-  auto ii = InstanceImpl::Get(handle.GetInst());
-  if (id < 0 || !ii) {
+NT_ListenerPoller CreateListenerPoller(NT_Inst inst) {
+  if (auto ii = InstanceImpl::GetTyped(inst, Handle::kInstance)) {
+    return ii->listenerStorage.CreateListenerPoller();
+  } else {
     return {};
   }
-
-  return ii->entry_notifier.Poll(static_cast<unsigned int>(id));
 }
 
-std::vector<EntryNotification> PollEntryListener(NT_EntryListenerPoller poller,
-                                                 double timeout,
-                                                 bool* timed_out) {
-  *timed_out = false;
-  Handle handle{poller};
-  int id = handle.GetTypedIndex(Handle::kEntryListenerPoller);
-  auto ii = InstanceImpl::Get(handle.GetInst());
-  if (id < 0 || !ii) {
+void DestroyListenerPoller(NT_ListenerPoller poller) {
+  if (auto ii = InstanceImpl::GetTyped(poller, Handle::kListenerPoller)) {
+    CleanupListeners(*ii, ii->listenerStorage.DestroyListenerPoller(poller));
+  }
+}
+
+std::vector<Event> ReadListenerQueue(NT_ListenerPoller poller) {
+  if (auto ii = InstanceImpl::GetTyped(poller, Handle::kListenerPoller)) {
+    return ii->listenerStorage.ReadListenerQueue(poller);
+  } else {
     return {};
   }
-
-  return ii->entry_notifier.Poll(static_cast<unsigned int>(id), timeout,
-                                 timed_out);
 }
 
-void CancelPollEntryListener(NT_EntryListenerPoller poller) {
-  Handle handle{poller};
-  int id = handle.GetTypedIndex(Handle::kEntryListenerPoller);
-  auto ii = InstanceImpl::Get(handle.GetInst());
-  if (id < 0 || !ii) {
-    return;
+void RemoveListener(NT_Listener listener) {
+  if (auto ii = InstanceImpl::GetTyped(listener, Handle::kListener)) {
+    CleanupListeners(*ii, ii->listenerStorage.RemoveListener(listener));
   }
-
-  ii->entry_notifier.CancelPoll(id);
 }
 
-void RemoveEntryListener(NT_EntryListener entry_listener) {
-  Handle handle{entry_listener};
-  int uid = handle.GetTypedIndex(Handle::kEntryListener);
-  auto ii = InstanceImpl::Get(handle.GetInst());
-  if (uid < 0 || !ii) {
-    return;
-  }
-
-  ii->entry_notifier.Remove(uid);
-}
-
-bool WaitForEntryListenerQueue(NT_Inst inst, double timeout) {
-  int i = Handle{inst}.GetTypedInst(Handle::kInstance);
-  auto ii = InstanceImpl::Get(i);
-  if (!ii) {
-    return true;
-  }
-  return ii->entry_notifier.WaitForQueue(timeout);
-}
-
-NT_ConnectionListener AddConnectionListener(
-    NT_Inst inst,
-    std::function<void(const ConnectionNotification& event)> callback,
-    bool immediate_notify) {
-  int i = Handle{inst}.GetTypedInst(Handle::kInstance);
-  auto ii = InstanceImpl::Get(i);
-  if (!ii) {
-    return 0;
-  }
-
-  unsigned int uid = ii->dispatcher.AddListener(callback, immediate_notify);
-  return Handle(i, uid, Handle::kConnectionListener);
-}
-
-NT_ConnectionListenerPoller CreateConnectionListenerPoller(NT_Inst inst) {
-  int i = Handle{inst}.GetTypedInst(Handle::kInstance);
-  auto ii = InstanceImpl::Get(i);
-  if (!ii) {
-    return 0;
-  }
-
-  return Handle(i, ii->connection_notifier.CreatePoller(),
-                Handle::kConnectionListenerPoller);
-}
-
-void DestroyConnectionListenerPoller(NT_ConnectionListenerPoller poller) {
-  Handle handle{poller};
-  int id = handle.GetTypedIndex(Handle::kConnectionListenerPoller);
-  auto ii = InstanceImpl::Get(handle.GetInst());
-  if (id < 0 || !ii) {
-    return;
-  }
-
-  ii->connection_notifier.RemovePoller(id);
-}
-
-NT_ConnectionListener AddPolledConnectionListener(
-    NT_ConnectionListenerPoller poller, bool immediate_notify) {
-  Handle handle{poller};
-  int id = handle.GetTypedIndex(Handle::kConnectionListenerPoller);
-  int i = handle.GetInst();
-  auto ii = InstanceImpl::Get(i);
-  if (id < 0 || !ii) {
-    return 0;
-  }
-
-  unsigned int uid = ii->dispatcher.AddPolledListener(id, immediate_notify);
-  return Handle(i, uid, Handle::kConnectionListener);
-}
-
-std::vector<ConnectionNotification> PollConnectionListener(
-    NT_ConnectionListenerPoller poller) {
-  Handle handle{poller};
-  int id = handle.GetTypedIndex(Handle::kConnectionListenerPoller);
-  auto ii = InstanceImpl::Get(handle.GetInst());
-  if (id < 0 || !ii) {
+bool WaitForListenerQueue(NT_Handle handle, double timeout) {
+  if (auto ii = InstanceImpl::GetHandle(handle)) {
+    return ii->listenerStorage.WaitForListenerQueue(timeout);
+  } else {
     return {};
   }
-
-  return ii->connection_notifier.Poll(static_cast<unsigned int>(id));
 }
 
-std::vector<ConnectionNotification> PollConnectionListener(
-    NT_ConnectionListenerPoller poller, double timeout, bool* timed_out) {
-  *timed_out = false;
-  Handle handle{poller};
-  int id = handle.GetTypedIndex(Handle::kConnectionListenerPoller);
-  auto ii = InstanceImpl::Get(handle.GetInst());
-  if (id < 0 || !ii) {
+NT_Listener AddListener(NT_Inst inst,
+                        std::span<const std::string_view> prefixes,
+                        unsigned int mask, ListenerCallback callback) {
+  if (auto ii = InstanceImpl::GetTyped(inst, Handle::kInstance)) {
+    if ((mask & (NT_EVENT_TOPIC | NT_EVENT_VALUE_ALL)) != 0) {
+      auto listener = ii->listenerStorage.AddListener(std::move(callback));
+      ii->localStorage.AddListener(listener, prefixes, mask);
+      return listener;
+    }
+  }
+  return {};
+}
+
+NT_Listener AddListener(NT_Handle handle, unsigned int mask,
+                        ListenerCallback callback) {
+  if (auto ii = InstanceImpl::GetHandle(handle)) {
+    auto listener = ii->listenerStorage.AddListener(std::move(callback));
+    DoAddListener(*ii, listener, handle, mask);
+    return listener;
+  } else {
     return {};
   }
-
-  return ii->connection_notifier.Poll(static_cast<unsigned int>(id), timeout,
-                                      timed_out);
 }
 
-void CancelPollConnectionListener(NT_ConnectionListenerPoller poller) {
-  Handle handle{poller};
-  int id = handle.GetTypedIndex(Handle::kConnectionListenerPoller);
-  auto ii = InstanceImpl::Get(handle.GetInst());
-  if (id < 0 || !ii) {
-    return;
+NT_Listener AddPolledListener(NT_ListenerPoller poller,
+                              std::span<const std::string_view> prefixes,
+                              unsigned int mask) {
+  if (auto ii = InstanceImpl::GetTyped(poller, Handle::kListenerPoller)) {
+    if ((mask & (NT_EVENT_TOPIC | NT_EVENT_VALUE_ALL)) != 0) {
+      auto listener = ii->listenerStorage.AddListener(poller);
+      ii->localStorage.AddListener(listener, prefixes, mask);
+      return listener;
+    }
   }
-
-  ii->connection_notifier.CancelPoll(id);
+  return {};
 }
 
-void RemoveConnectionListener(NT_ConnectionListener conn_listener) {
-  Handle handle{conn_listener};
-  int uid = handle.GetTypedIndex(Handle::kConnectionListener);
-  auto ii = InstanceImpl::Get(handle.GetInst());
-  if (uid < 0 || !ii) {
-    return;
+NT_Listener AddPolledListener(NT_ListenerPoller poller, NT_Handle handle,
+                              unsigned int mask) {
+  if (auto ii = InstanceImpl::GetTyped(poller, Handle::kListenerPoller)) {
+    if (Handle{handle}.GetInst() != Handle{poller}.GetInst()) {
+      WPI_ERROR(
+          ii->logger,
+          "AddPolledListener(): trying to listen to handle {} (instance {}) "
+          "with poller {} (instance {}), ignored due to different instance",
+          handle, Handle{handle}.GetInst(), poller, Handle{poller}.GetInst());
+      return {};
+    }
+    auto listener = ii->listenerStorage.AddListener(poller);
+    DoAddListener(*ii, listener, handle, mask);
+    return listener;
+  } else {
+    return {};
   }
-
-  ii->connection_notifier.Remove(uid);
 }
 
-bool WaitForConnectionListenerQueue(NT_Inst inst, double timeout) {
-  int i = Handle{inst}.GetTypedInst(Handle::kInstance);
-  auto ii = InstanceImpl::Get(i);
-  if (!ii) {
-    return true;
+int64_t Now() {
+  if (gNowSet) {
+    return gNowTime;
   }
-  return ii->connection_notifier.WaitForQueue(timeout);
+  return wpi::Now();
+}
+
+void SetNow(int64_t timestamp) {
+  gNowTime = timestamp;
+  gNowSet = true;
+}
+
+NT_Type GetTypeFromString(std::string_view typeString) {
+  if (typeString.empty()) {
+    return NT_UNASSIGNED;
+  } else {
+    return StringToType(typeString);
+  }
+}
+
+std::string_view GetStringFromType(NT_Type type) {
+  if (type == NT_UNASSIGNED) {
+    return "";
+  } else {
+    return TypeToString(type);
+  }
 }
 
 /*
- * Remote Procedure Call Functions
+ * Data Logger Functions
  */
-
-void CreateRpc(NT_Entry entry, std::string_view def,
-               std::function<void(const RpcAnswer& answer)> callback) {
-  Handle handle{entry};
-  int id = handle.GetTypedIndex(Handle::kEntry);
-  auto ii = InstanceImpl::Get(handle.GetInst());
-  if (id < 0 || !ii) {
-    return;
-  }
-
-  // only server can create RPCs
-  if ((ii->dispatcher.GetNetworkMode() & NT_NET_MODE_SERVER) == 0) {
-    return;
-  }
-  if (def.empty() || !callback) {
-    return;
-  }
-
-  ii->storage.CreateRpc(id, def, ii->rpc_server.Add(callback));
-}
-
-NT_RpcCallPoller CreateRpcCallPoller(NT_Inst inst) {
-  int i = Handle{inst}.GetTypedInst(Handle::kInstance);
-  auto ii = InstanceImpl::Get(i);
-  if (!ii) {
+NT_DataLogger StartEntryDataLog(NT_Inst inst, wpi::log::DataLog& log,
+                                std::string_view prefix,
+                                std::string_view logPrefix) {
+  if (auto ii = InstanceImpl::GetTyped(inst, Handle::kInstance)) {
+    return ii->localStorage.StartDataLog(log, prefix, logPrefix);
+  } else {
     return 0;
   }
-
-  return Handle(i, ii->rpc_server.CreatePoller(), Handle::kRpcCallPoller);
 }
 
-void DestroyRpcCallPoller(NT_RpcCallPoller poller) {
-  Handle handle{poller};
-  int id = handle.GetTypedIndex(Handle::kRpcCallPoller);
-  auto ii = InstanceImpl::Get(handle.GetInst());
-  if (id < 0 || !ii) {
-    return;
+void StopEntryDataLog(NT_DataLogger logger) {
+  if (auto ii = InstanceImpl::GetTyped(logger, Handle::kDataLogger)) {
+    ii->localStorage.StopDataLog(logger);
   }
-
-  ii->rpc_server.RemovePoller(id);
 }
 
-void CreatePolledRpc(NT_Entry entry, std::string_view def,
-                     NT_RpcCallPoller poller) {
-  Handle handle{entry};
-  int id = handle.GetTypedIndex(Handle::kEntry);
-  auto ii = InstanceImpl::Get(handle.GetInst());
-  if (id < 0 || !ii) {
-    return;
-  }
-
-  Handle phandle{poller};
-  int p_id = phandle.GetTypedIndex(Handle::kRpcCallPoller);
-  if (p_id < 0) {
-    return;
-  }
-  if (handle.GetInst() != phandle.GetInst()) {
-    return;
-  }
-
-  // only server can create RPCs
-  if ((ii->dispatcher.GetNetworkMode() & NT_NET_MODE_SERVER) == 0) {
-    return;
-  }
-  if (def.empty()) {
-    return;
-  }
-
-  ii->storage.CreateRpc(id, def, ii->rpc_server.AddPolled(p_id));
-}
-
-std::vector<RpcAnswer> PollRpc(NT_RpcCallPoller poller) {
-  Handle handle{poller};
-  int id = handle.GetTypedIndex(Handle::kRpcCallPoller);
-  auto ii = InstanceImpl::Get(handle.GetInst());
-  if (id < 0 || !ii) {
-    return {};
-  }
-
-  return ii->rpc_server.Poll(static_cast<unsigned int>(id));
-}
-
-std::vector<RpcAnswer> PollRpc(NT_RpcCallPoller poller, double timeout,
-                               bool* timed_out) {
-  *timed_out = false;
-  Handle handle{poller};
-  int id = handle.GetTypedIndex(Handle::kRpcCallPoller);
-  auto ii = InstanceImpl::Get(handle.GetInst());
-  if (id < 0 || !ii) {
-    return {};
-  }
-
-  return ii->rpc_server.Poll(static_cast<unsigned int>(id), timeout, timed_out);
-}
-
-void CancelPollRpc(NT_RpcCallPoller poller) {
-  Handle handle{poller};
-  int id = handle.GetTypedIndex(Handle::kRpcCallPoller);
-  auto ii = InstanceImpl::Get(handle.GetInst());
-  if (id < 0 || !ii) {
-    return;
-  }
-
-  ii->rpc_server.CancelPoll(id);
-}
-
-bool WaitForRpcCallQueue(NT_Inst inst, double timeout) {
-  int i = Handle{inst}.GetTypedInst(Handle::kInstance);
-  auto ii = InstanceImpl::Get(i);
-  if (!ii) {
-    return true;
-  }
-  return ii->rpc_server.WaitForQueue(timeout);
-}
-
-bool PostRpcResponse(NT_Entry entry, NT_RpcCall call, std::string_view result) {
-  Handle handle{entry};
-  int id = handle.GetTypedIndex(Handle::kEntry);
-  auto ii = InstanceImpl::Get(handle.GetInst());
-  if (id < 0 || !ii) {
-    return false;
-  }
-
-  Handle chandle{call};
-  int call_uid = chandle.GetTypedIndex(Handle::kRpcCall);
-  if (call_uid < 0) {
-    return false;
-  }
-  if (handle.GetInst() != chandle.GetInst()) {
-    return false;
-  }
-
-  return ii->rpc_server.PostRpcResponse(id, call_uid, result);
-}
-
-NT_RpcCall CallRpc(NT_Entry entry, std::string_view params) {
-  Handle handle{entry};
-  int id = handle.GetTypedIndex(Handle::kEntry);
-  int i = handle.GetInst();
-  auto ii = InstanceImpl::Get(i);
-  if (id < 0 || !ii) {
+NT_ConnectionDataLogger StartConnectionDataLog(NT_Inst inst,
+                                               wpi::log::DataLog& log,
+                                               std::string_view name) {
+  if (auto ii = InstanceImpl::GetTyped(inst, Handle::kInstance)) {
+    return ii->connectionList.StartDataLog(log, name);
+  } else {
     return 0;
   }
-
-  unsigned int call_uid = ii->storage.CallRpc(id, params);
-  if (call_uid == 0) {
-    return 0;
-  }
-  return Handle(i, call_uid, Handle::kRpcCall);
 }
 
-bool GetRpcResult(NT_Entry entry, NT_RpcCall call, std::string* result) {
-  Handle handle{entry};
-  int id = handle.GetTypedIndex(Handle::kEntry);
-  auto ii = InstanceImpl::Get(handle.GetInst());
-  if (id < 0 || !ii) {
-    return false;
+void StopConnectionDataLog(NT_ConnectionDataLogger logger) {
+  if (auto ii = InstanceImpl::GetTyped(logger, Handle::kConnectionDataLogger)) {
+    ii->connectionList.StopDataLog(logger);
   }
-
-  Handle chandle{call};
-  int call_uid = chandle.GetTypedIndex(Handle::kRpcCall);
-  if (call_uid < 0) {
-    return false;
-  }
-  if (handle.GetInst() != chandle.GetInst()) {
-    return false;
-  }
-
-  return ii->storage.GetRpcResult(id, call_uid, result);
-}
-
-bool GetRpcResult(NT_Entry entry, NT_RpcCall call, std::string* result,
-                  double timeout, bool* timed_out) {
-  *timed_out = false;
-  Handle handle{entry};
-  int id = handle.GetTypedIndex(Handle::kEntry);
-  auto ii = InstanceImpl::Get(handle.GetInst());
-  if (id < 0 || !ii) {
-    return false;
-  }
-
-  Handle chandle{call};
-  int call_uid = chandle.GetTypedIndex(Handle::kRpcCall);
-  if (call_uid < 0) {
-    return false;
-  }
-  if (handle.GetInst() != chandle.GetInst()) {
-    return false;
-  }
-
-  return ii->storage.GetRpcResult(id, call_uid, result, timeout, timed_out);
-}
-
-void CancelRpcResult(NT_Entry entry, NT_RpcCall call) {
-  Handle handle{entry};
-  int id = handle.GetTypedIndex(Handle::kEntry);
-  auto ii = InstanceImpl::Get(handle.GetInst());
-  if (id < 0 || !ii) {
-    return;
-  }
-
-  Handle chandle{call};
-  int call_uid = chandle.GetTypedIndex(Handle::kRpcCall);
-  if (call_uid < 0) {
-    return;
-  }
-  if (handle.GetInst() != chandle.GetInst()) {
-    return;
-  }
-
-  ii->storage.CancelRpcResult(id, call_uid);
-}
-
-std::string PackRpcDefinition(const RpcDefinition& def) {
-  WireEncoder enc(0x0300);
-  enc.Write8(def.version);
-  enc.WriteString(def.name);
-
-  // parameters
-  unsigned int params_size = def.params.size();
-  if (params_size > 0xff) {
-    params_size = 0xff;
-  }
-  enc.Write8(params_size);
-  for (size_t i = 0; i < params_size; ++i) {
-    enc.WriteType(def.params[i].def_value->type());
-    enc.WriteString(def.params[i].name);
-    enc.WriteValue(*def.params[i].def_value);
-  }
-
-  // results
-  unsigned int results_size = def.results.size();
-  if (results_size > 0xff) {
-    results_size = 0xff;
-  }
-  enc.Write8(results_size);
-  for (size_t i = 0; i < results_size; ++i) {
-    enc.WriteType(def.results[i].type);
-    enc.WriteString(def.results[i].name);
-  }
-
-  return std::string{enc.ToStringView()};
-}
-
-bool UnpackRpcDefinition(std::string_view packed, RpcDefinition* def) {
-  wpi::raw_mem_istream is(packed.data(), packed.size());
-  wpi::Logger logger;
-  WireDecoder dec(is, 0x0300, logger);
-  if (!dec.Read8(&def->version)) {
-    return false;
-  }
-  if (!dec.ReadString(&def->name)) {
-    return false;
-  }
-
-  // parameters
-  unsigned int params_size;
-  if (!dec.Read8(&params_size)) {
-    return false;
-  }
-  def->params.resize(0);
-  def->params.reserve(params_size);
-  for (size_t i = 0; i < params_size; ++i) {
-    RpcParamDef pdef;
-    NT_Type type;
-    if (!dec.ReadType(&type)) {
-      return false;
-    }
-    if (!dec.ReadString(&pdef.name)) {
-      return false;
-    }
-    pdef.def_value = dec.ReadValue(type);
-    if (!pdef.def_value) {
-      return false;
-    }
-    def->params.emplace_back(std::move(pdef));
-  }
-
-  // results
-  unsigned int results_size;
-  if (!dec.Read8(&results_size)) {
-    return false;
-  }
-  def->results.resize(0);
-  def->results.reserve(results_size);
-  for (size_t i = 0; i < results_size; ++i) {
-    RpcResultDef rdef;
-    if (!dec.ReadType(&rdef.type)) {
-      return false;
-    }
-    if (!dec.ReadString(&rdef.name)) {
-      return false;
-    }
-    def->results.emplace_back(std::move(rdef));
-  }
-
-  return true;
-}
-
-std::string PackRpcValues(wpi::span<const std::shared_ptr<Value>> values) {
-  WireEncoder enc(0x0300);
-  for (auto& value : values) {
-    enc.WriteValue(*value);
-  }
-  return std::string{enc.ToStringView()};
-}
-
-std::vector<std::shared_ptr<Value>> UnpackRpcValues(
-    std::string_view packed, wpi::span<const NT_Type> types) {
-  wpi::raw_mem_istream is(packed.data(), packed.size());
-  wpi::Logger logger;
-  WireDecoder dec(is, 0x0300, logger);
-  std::vector<std::shared_ptr<Value>> vec;
-  for (auto type : types) {
-    auto item = dec.ReadValue(type);
-    if (!item) {
-      return std::vector<std::shared_ptr<Value>>();
-    }
-    vec.emplace_back(std::move(item));
-  }
-  return vec;
-}
-
-uint64_t Now() {
-  return wpi::Now();
 }
 
 /*
  * Client/Server Functions
  */
 
-void SetNetworkIdentity(NT_Inst inst, std::string_view name) {
-  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
-  if (!ii) {
-    return;
-  }
-
-  ii->dispatcher.SetIdentity(name);
-}
-
 unsigned int GetNetworkMode(NT_Inst inst) {
-  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
-  if (!ii) {
-    return 0;
+  if (auto ii = InstanceImpl::GetTyped(inst, Handle::kInstance)) {
+    return ii->networkMode;
+  } else {
+    return {};
   }
-
-  return ii->dispatcher.GetNetworkMode();
 }
 
 void StartLocal(NT_Inst inst) {
-  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
-  if (!ii) {
-    return;
+  if (auto ii = InstanceImpl::GetTyped(inst, Handle::kInstance)) {
+    ii->StartLocal();
   }
-
-  ii->dispatcher.StartLocal();
 }
 
 void StopLocal(NT_Inst inst) {
-  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
-  if (!ii) {
-    return;
+  if (auto ii = InstanceImpl::GetTyped(inst, Handle::kInstance)) {
+    ii->StopLocal();
   }
-
-  ii->dispatcher.Stop();
 }
 
 void StartServer(NT_Inst inst, std::string_view persist_filename,
-                 const char* listen_address, unsigned int port) {
-  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
-  if (!ii) {
-    return;
+                 const char* listen_address, unsigned int port3,
+                 unsigned int port4) {
+  if (auto ii = InstanceImpl::GetTyped(inst, Handle::kInstance)) {
+    ii->StartServer(persist_filename, listen_address, port3, port4);
   }
-
-  ii->dispatcher.StartServer(persist_filename, listen_address, port);
 }
 
 void StopServer(NT_Inst inst) {
-  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
-  if (!ii) {
-    return;
+  if (auto ii = InstanceImpl::GetTyped(inst, Handle::kInstance)) {
+    ii->StopServer();
   }
-
-  ii->dispatcher.Stop();
 }
 
-void StartClient(NT_Inst inst) {
-  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
-  if (!ii) {
-    return;
+void StartClient3(NT_Inst inst, std::string_view identity) {
+  if (auto ii = InstanceImpl::GetTyped(inst, Handle::kInstance)) {
+    ii->StartClient3(identity);
   }
-
-  ii->dispatcher.StartClient();
 }
 
-void StartClient(NT_Inst inst, const char* server_name, unsigned int port) {
-  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
-  if (!ii) {
-    return;
+void StartClient4(NT_Inst inst, std::string_view identity) {
+  if (auto ii = InstanceImpl::GetTyped(inst, Handle::kInstance)) {
+    ii->StartClient4(identity);
   }
-
-  ii->dispatcher.SetServer(server_name, port);
-  ii->dispatcher.StartClient();
-}
-
-void StartClient(
-    NT_Inst inst,
-    wpi::span<const std::pair<std::string_view, unsigned int>> servers) {
-  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
-  if (!ii) {
-    return;
-  }
-
-  ii->dispatcher.SetServer(servers);
-  ii->dispatcher.StartClient();
-}
-
-void StartClientTeam(NT_Inst inst, unsigned int team, unsigned int port) {
-  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
-  if (!ii) {
-    return;
-  }
-
-  ii->dispatcher.SetServerTeam(team, port);
-  ii->dispatcher.StartClient();
 }
 
 void StopClient(NT_Inst inst) {
-  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
-  if (!ii) {
-    return;
+  if (auto ii = InstanceImpl::GetTyped(inst, Handle::kInstance)) {
+    ii->StopClient();
   }
-
-  ii->dispatcher.Stop();
 }
 
 void SetServer(NT_Inst inst, const char* server_name, unsigned int port) {
-  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
-  if (!ii) {
-    return;
-  }
-
-  ii->dispatcher.SetServer(server_name, port);
+  SetServer(inst, {{{server_name, port}}});
 }
 
 void SetServer(
     NT_Inst inst,
-    wpi::span<const std::pair<std::string_view, unsigned int>> servers) {
-  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
-  if (!ii) {
-    return;
+    std::span<const std::pair<std::string_view, unsigned int>> servers) {
+  if (auto ii = InstanceImpl::GetTyped(inst, Handle::kInstance)) {
+    std::vector<std::pair<std::string, unsigned int>> serversCopy;
+    serversCopy.reserve(servers.size());
+    for (auto&& server : servers) {
+      serversCopy.emplace_back(std::string{server.first}, server.second);
+    }
+    ii->SetServers(serversCopy);
   }
-
-  ii->dispatcher.SetServer(servers);
 }
 
 void SetServerTeam(NT_Inst inst, unsigned int team, unsigned int port) {
-  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
-  if (!ii) {
-    return;
-  }
+  if (auto ii = InstanceImpl::GetTyped(inst, Handle::kInstance)) {
+    std::vector<std::pair<std::string, unsigned int>> servers;
+    servers.reserve(5);
 
-  ii->dispatcher.SetServerTeam(team, port);
+    // 10.te.am.2
+    servers.emplace_back(fmt::format("10.{}.{}.2", static_cast<int>(team / 100),
+                                     static_cast<int>(team % 100)),
+                         port);
+
+    // 172.22.11.2
+    servers.emplace_back("172.22.11.2", port);
+
+    // roboRIO-<team>-FRC.local
+    servers.emplace_back(fmt::format("roboRIO-{}-FRC.local", team), port);
+
+    // roboRIO-<team>-FRC.lan
+    servers.emplace_back(fmt::format("roboRIO-{}-FRC.lan", team), port);
+
+    // roboRIO-<team>-FRC.frc-field.local
+    servers.emplace_back(fmt::format("roboRIO-{}-FRC.frc-field.local", team),
+                         port);
+
+    ii->SetServers(servers);
+  }
 }
 
 void StartDSClient(NT_Inst inst, unsigned int port) {
-  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
-  if (!ii) {
-    return;
+  if (auto ii = InstanceImpl::GetTyped(inst, Handle::kInstance)) {
+    if (auto client = ii->GetClient()) {
+      client->StartDSClient(port);
+    }
   }
-
-  ii->ds_client.Start(port);
 }
 
 void StopDSClient(NT_Inst inst) {
-  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
-  if (!ii) {
-    return;
+  if (auto ii = InstanceImpl::GetTyped(inst, Handle::kInstance)) {
+    if (auto client = ii->GetClient()) {
+      client->StopDSClient();
+    }
   }
-
-  ii->ds_client.Stop();
 }
 
-void SetUpdateRate(NT_Inst inst, double interval) {
-  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
-  if (!ii) {
-    return;
+void FlushLocal(NT_Inst inst) {
+  if (auto ii = InstanceImpl::GetTyped(inst, Handle::kInstance)) {
+    if (auto client = ii->GetClient()) {
+      client->FlushLocal();
+    } else if (auto server = ii->GetServer()) {
+      server->FlushLocal();
+    }
   }
-
-  ii->dispatcher.SetUpdateRate(interval);
 }
 
 void Flush(NT_Inst inst) {
-  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
-  if (!ii) {
-    return;
+  if (auto ii = InstanceImpl::GetTyped(inst, Handle::kInstance)) {
+    if (auto client = ii->GetClient()) {
+      client->Flush();
+    } else if (auto server = ii->GetServer()) {
+      server->Flush();
+    }
   }
-
-  ii->dispatcher.Flush();
 }
 
 std::vector<ConnectionInfo> GetConnections(NT_Inst inst) {
-  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
-  if (!ii) {
+  if (auto ii = InstanceImpl::GetTyped(inst, Handle::kInstance)) {
+    return ii->connectionList.GetConnections();
+  } else {
     return {};
   }
-
-  return ii->dispatcher.GetConnections();
 }
 
 bool IsConnected(NT_Inst inst) {
-  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
-  if (!ii) {
+  if (auto ii = InstanceImpl::GetTyped(inst, Handle::kInstance)) {
+    return ii->networkMode == NT_NET_MODE_LOCAL ||
+           ii->connectionList.IsConnected();
+  } else {
     return false;
   }
-
-  return ii->dispatcher.IsConnected();
 }
 
-/*
- * Persistent Functions
- */
-
-const char* SavePersistent(NT_Inst inst, std::string_view filename) {
-  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
-  if (!ii) {
-    return "invalid instance handle";
-  }
-
-  return ii->storage.SavePersistent(filename, false);
-}
-
-const char* LoadPersistent(
-    NT_Inst inst, std::string_view filename,
-    std::function<void(size_t line, const char* msg)> warn) {
-  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
-  if (!ii) {
-    return "invalid instance handle";
-  }
-
-  return ii->storage.LoadPersistent(filename, warn);
-}
-
-const char* SaveEntries(NT_Inst inst, std::string_view filename,
-                        std::string_view prefix) {
-  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
-  if (!ii) {
-    return "invalid instance handle";
-  }
-
-  return ii->storage.SaveEntries(filename, prefix);
-}
-
-const char* LoadEntries(
-    NT_Inst inst, std::string_view filename, std::string_view prefix,
-    std::function<void(size_t line, const char* msg)> warn) {
-  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
-  if (!ii) {
-    return "invalid instance handle";
-  }
-
-  return ii->storage.LoadEntries(filename, prefix, warn);
-}
-
-NT_Logger AddLogger(NT_Inst inst,
-                    std::function<void(const LogMessage& msg)> func,
-                    unsigned int minLevel, unsigned int maxLevel) {
-  int i = Handle{inst}.GetTypedInst(Handle::kInstance);
-  auto ii = InstanceImpl::Get(i);
-  if (!ii) {
-    return 0;
-  }
-
-  if (minLevel < ii->logger.min_level()) {
-    ii->logger.set_min_level(minLevel);
-  }
-
-  return Handle(i, ii->logger_impl.Add(func, minLevel, maxLevel),
-                Handle::kLogger);
-}
-
-NT_LoggerPoller CreateLoggerPoller(NT_Inst inst) {
-  int i = Handle{inst}.GetTypedInst(Handle::kInstance);
-  auto ii = InstanceImpl::Get(i);
-  if (!ii) {
-    return 0;
-  }
-
-  return Handle(i, ii->logger_impl.CreatePoller(), Handle::kLoggerPoller);
-}
-
-void DestroyLoggerPoller(NT_LoggerPoller poller) {
-  Handle handle{poller};
-  int id = handle.GetTypedIndex(Handle::kLoggerPoller);
-  auto ii = InstanceImpl::Get(handle.GetInst());
-  if (id < 0 || !ii) {
-    return;
-  }
-
-  ii->logger_impl.RemovePoller(id);
-}
-
-NT_Logger AddPolledLogger(NT_LoggerPoller poller, unsigned int min_level,
-                          unsigned int max_level) {
-  Handle handle{poller};
-  int id = handle.GetTypedIndex(Handle::kLoggerPoller);
-  int i = handle.GetInst();
-  auto ii = InstanceImpl::Get(i);
-  if (id < 0 || !ii) {
-    return 0;
-  }
-
-  if (min_level < ii->logger.min_level()) {
-    ii->logger.set_min_level(min_level);
-  }
-
-  return Handle(i, ii->logger_impl.AddPolled(id, min_level, max_level),
-                Handle::kLogger);
-}
-
-std::vector<LogMessage> PollLogger(NT_LoggerPoller poller) {
-  Handle handle{poller};
-  int id = handle.GetTypedIndex(Handle::kLoggerPoller);
-  auto ii = InstanceImpl::Get(handle.GetInst());
-  if (id < 0 || !ii) {
+std::optional<int64_t> GetServerTimeOffset(NT_Inst inst) {
+  if (auto ii = InstanceImpl::GetTyped(inst, Handle::kInstance)) {
+    return ii->GetServerTimeOffset();
+  } else {
     return {};
   }
-
-  return ii->logger_impl.Poll(static_cast<unsigned int>(id));
 }
 
-std::vector<LogMessage> PollLogger(NT_LoggerPoller poller, double timeout,
-                                   bool* timed_out) {
-  *timed_out = false;
-  Handle handle{poller};
-  int id = handle.GetTypedIndex(Handle::kLoggerPoller);
-  auto ii = InstanceImpl::Get(handle.GetInst());
-  if (id < 0 || !ii) {
+NT_Listener AddLogger(NT_Inst inst, unsigned int minLevel,
+                      unsigned int maxLevel, ListenerCallback func) {
+  if (auto ii = InstanceImpl::GetTyped(inst, Handle::kInstance)) {
+    if (minLevel < ii->logger.min_level()) {
+      ii->logger.set_min_level(minLevel);
+    }
+    auto listener = ii->listenerStorage.AddListener(std::move(func));
+    ii->logger_impl.AddListener(listener, minLevel, maxLevel);
+    return listener;
+  } else {
     return {};
   }
-
-  return ii->logger_impl.Poll(static_cast<unsigned int>(id), timeout,
-                              timed_out);
 }
 
-void CancelPollLogger(NT_LoggerPoller poller) {
-  Handle handle{poller};
-  int id = handle.GetTypedIndex(Handle::kLoggerPoller);
-  auto ii = InstanceImpl::Get(handle.GetInst());
-  if (id < 0 || !ii) {
-    return;
+NT_Listener AddPolledLogger(NT_ListenerPoller poller, unsigned int minLevel,
+                            unsigned int maxLevel) {
+  if (auto ii = InstanceImpl::GetTyped(poller, Handle::kListenerPoller)) {
+    if (minLevel < ii->logger.min_level()) {
+      ii->logger.set_min_level(minLevel);
+    }
+    auto listener = ii->listenerStorage.AddListener(poller);
+    ii->logger_impl.AddListener(listener, minLevel, maxLevel);
+    return listener;
+  } else {
+    return {};
   }
-
-  ii->logger_impl.CancelPoll(id);
-}
-
-void RemoveLogger(NT_Logger logger) {
-  Handle handle{logger};
-  int uid = handle.GetTypedIndex(Handle::kLogger);
-  auto ii = InstanceImpl::Get(handle.GetInst());
-  if (uid < 0 || !ii) {
-    return;
-  }
-
-  ii->logger_impl.Remove(uid);
-  ii->logger.set_min_level(ii->logger_impl.GetMinLevel());
-}
-
-bool WaitForLoggerQueue(NT_Inst inst, double timeout) {
-  int i = Handle{inst}.GetTypedInst(Handle::kInstance);
-  auto ii = InstanceImpl::Get(i);
-  if (!ii) {
-    return true;
-  }
-  return ii->logger_impl.WaitForQueue(timeout);
 }
 
 }  // namespace nt
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/ntcore_meta.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/ntcore_meta.cpp
new file mode 100644
index 0000000..05cb4b7
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/ntcore_meta.cpp
@@ -0,0 +1,210 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <fmt/format.h>
+#include <wpi/MessagePack.h>
+#include <wpi/mpack.h>
+
+#include "ntcore_cpp.h"
+
+using namespace mpack;
+
+using namespace nt::meta;
+
+static SubscriberOptions DecodeSubscriberOptions(mpack_reader_t& r) {
+  SubscriberOptions options;
+  uint32_t numMapElem = mpack_expect_map(&r);
+  for (uint32_t j = 0; j < numMapElem; ++j) {
+    std::string key;
+    mpack_expect_str(&r, &key);
+    if (key == "topicsonly") {
+      options.topicsOnly = mpack_expect_bool(&r);
+    } else if (key == "all") {
+      options.sendAll = mpack_expect_bool(&r);
+    } else if (key == "periodic") {
+      options.periodic = mpack_expect_float(&r);
+    } else if (key == "prefix") {
+      options.prefixMatch = mpack_expect_bool(&r);
+    } else {
+      // TODO: Save other options
+      mpack_discard(&r);
+    }
+  }
+  mpack_done_map(&r);
+  return options;
+}
+
+std::optional<std::vector<ClientPublisher>> nt::meta::DecodeClientPublishers(
+    std::span<const uint8_t> data) {
+  mpack_reader_t r;
+  mpack_reader_init_data(&r, data);
+  uint32_t numPub = mpack_expect_array_max(&r, 1000);
+  std::vector<ClientPublisher> publishers;
+  publishers.reserve(numPub);
+  for (uint32_t i = 0; i < numPub; ++i) {
+    ClientPublisher pub;
+    uint32_t numMapElem = mpack_expect_map(&r);
+    for (uint32_t j = 0; j < numMapElem; ++j) {
+      std::string key;
+      mpack_expect_str(&r, &key);
+      if (key == "uid") {
+        pub.uid = mpack_expect_i64(&r);
+      } else if (key == "topic") {
+        mpack_expect_str(&r, &pub.topic);
+      } else {
+        mpack_discard(&r);
+      }
+    }
+    mpack_done_map(&r);
+    publishers.emplace_back(std::move(pub));
+  }
+  mpack_done_array(&r);
+  if (mpack_reader_destroy(&r) == mpack_ok) {
+    return {std::move(publishers)};
+  } else {
+    return {};
+  }
+}
+
+std::optional<std::vector<ClientSubscriber>> nt::meta::DecodeClientSubscribers(
+    std::span<const uint8_t> data) {
+  mpack_reader_t r;
+  mpack_reader_init_data(&r, data);
+  uint32_t numSub = mpack_expect_array_max(&r, 1000);
+  std::vector<ClientSubscriber> subscribers;
+  subscribers.reserve(numSub);
+  for (uint32_t i = 0; i < numSub; ++i) {
+    ClientSubscriber sub;
+    uint32_t numMapElem = mpack_expect_map(&r);
+    for (uint32_t j = 0; j < numMapElem; ++j) {
+      std::string key;
+      mpack_expect_str(&r, &key);
+      if (key == "uid") {
+        sub.uid = mpack_expect_i64(&r);
+      } else if (key == "topics") {
+        uint32_t numPrefix = mpack_expect_array_max(&r, 100);
+        sub.topics.reserve(numPrefix);
+        for (uint32_t k = 0; k < numPrefix; ++k) {
+          std::string val;
+          if (mpack_expect_str(&r, &val) == mpack_ok) {
+            sub.topics.emplace_back(std::move(val));
+          }
+        }
+        mpack_done_array(&r);
+      } else if (key == "options") {
+        sub.options = DecodeSubscriberOptions(r);
+      } else {
+        mpack_discard(&r);
+      }
+    }
+    mpack_done_map(&r);
+    subscribers.emplace_back(std::move(sub));
+  }
+  mpack_done_array(&r);
+  if (mpack_reader_destroy(&r) == mpack_ok) {
+    return {std::move(subscribers)};
+  } else {
+    return {};
+  }
+}
+
+std::optional<std::vector<TopicPublisher>> nt::meta::DecodeTopicPublishers(
+    std::span<const uint8_t> data) {
+  mpack_reader_t r;
+  mpack_reader_init_data(&r, data);
+  uint32_t numPub = mpack_expect_array_max(&r, 1000);
+  std::vector<TopicPublisher> publishers;
+  publishers.reserve(numPub);
+  for (uint32_t i = 0; i < numPub; ++i) {
+    TopicPublisher pub;
+    uint32_t numMapElem = mpack_expect_map(&r);
+    for (uint32_t j = 0; j < numMapElem; ++j) {
+      std::string key;
+      mpack_expect_str(&r, &key);
+      if (key == "pubuid") {
+        pub.pubuid = mpack_expect_i64(&r);
+      } else if (key == "client") {
+        mpack_expect_str(&r, &pub.client);
+      } else {
+        mpack_discard(&r);
+      }
+    }
+    mpack_done_map(&r);
+    publishers.emplace_back(std::move(pub));
+  }
+  mpack_done_array(&r);
+  if (mpack_reader_destroy(&r) == mpack_ok) {
+    return {std::move(publishers)};
+  } else {
+    return {};
+  }
+}
+
+std::optional<std::vector<TopicSubscriber>> nt::meta::DecodeTopicSubscribers(
+    std::span<const uint8_t> data) {
+  mpack_reader_t r;
+  mpack_reader_init_data(&r, data);
+  uint32_t numSub = mpack_expect_array_max(&r, 1000);
+  std::vector<TopicSubscriber> subscribers;
+  subscribers.reserve(numSub);
+  for (uint32_t i = 0; i < numSub; ++i) {
+    TopicSubscriber sub;
+    uint32_t numMapElem = mpack_expect_map(&r);
+    for (uint32_t j = 0; j < numMapElem; ++j) {
+      std::string key;
+      mpack_expect_str(&r, &key);
+      if (key == "subuid") {
+        sub.subuid = mpack_expect_i64(&r);
+      } else if (key == "client") {
+        mpack_expect_str(&r, &sub.client);
+      } else if (key == "options") {
+        sub.options = DecodeSubscriberOptions(r);
+      } else {
+        mpack_discard(&r);
+      }
+    }
+    mpack_done_map(&r);
+    subscribers.emplace_back(std::move(sub));
+  }
+  mpack_done_array(&r);
+  if (mpack_reader_destroy(&r) == mpack_ok) {
+    return {std::move(subscribers)};
+  } else {
+    return {};
+  }
+}
+
+std::optional<std::vector<Client>> nt::meta::DecodeClients(
+    std::span<const uint8_t> data) {
+  mpack_reader_t r;
+  mpack_reader_init_data(&r, data);
+  uint32_t numClients = mpack_expect_array_max(&r, 100);
+  std::vector<Client> clients;
+  clients.reserve(numClients);
+  for (uint32_t i = 0; i < numClients; ++i) {
+    Client client;
+    uint32_t numMapElem = mpack_expect_map(&r);
+    for (uint32_t j = 0; j < numMapElem; ++j) {
+      std::string key;
+      mpack_expect_str(&r, &key);
+      if (key == "id") {
+        mpack_expect_str(&r, &client.id);
+      } else if (key == "conn") {
+        mpack_expect_str(&r, &client.conn);
+      } else if (key == "ver") {
+        client.version = mpack_expect_u16(&r);
+      } else {
+        mpack_discard(&r);
+      }
+    }
+    mpack_done_map(&r);
+    clients.emplace_back(std::move(client));
+  }
+  mpack_done_array(&r);
+  if (mpack_reader_destroy(&r) == mpack_ok) {
+    return {std::move(clients)};
+  } else {
+    return {};
+  }
+}
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/ntcore_meta_c.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/ntcore_meta_c.cpp
new file mode 100644
index 0000000..889254e
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/ntcore_meta_c.cpp
@@ -0,0 +1,138 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <optional>
+#include <vector>
+
+#include "Value_internal.h"
+#include "ntcore_cpp.h"
+
+using namespace nt;
+using namespace nt::meta;
+
+static void ConvertToC(const SubscriberOptions& in,
+                       NT_Meta_SubscriberOptions* out) {
+  out->periodic = in.periodic;
+  out->topicsOnly = in.topicsOnly;
+  out->sendAll = in.sendAll;
+  out->prefixMatch = in.prefixMatch;
+}
+
+static void ConvertToC(const TopicPublisher& in, NT_Meta_TopicPublisher* out) {
+  ConvertToC(in.client, &out->client);
+  out->pubuid = in.pubuid;
+}
+
+static void ConvertToC(const TopicSubscriber& in,
+                       NT_Meta_TopicSubscriber* out) {
+  ConvertToC(in.client, &out->client);
+  out->subuid = in.subuid;
+  ConvertToC(in.options, &out->options);
+}
+
+static void ConvertToC(const ClientPublisher& in,
+                       NT_Meta_ClientPublisher* out) {
+  out->uid = in.uid;
+  ConvertToC(in.topic, &out->topic);
+}
+
+static void ConvertToC(const ClientSubscriber& in,
+                       NT_Meta_ClientSubscriber* out) {
+  out->uid = in.uid;
+  out->topics = ConvertToC<NT_String>(in.topics, &out->topicsCount);
+  ConvertToC(in.options, &out->options);
+}
+
+static void ConvertToC(const Client& in, NT_Meta_Client* out) {
+  ConvertToC(in.id, &out->id);
+  ConvertToC(in.conn, &out->conn);
+  out->version = in.version;
+}
+
+template <typename O, typename I>
+static O* ConvertToC(const std::optional<std::vector<I>>& in, size_t* out_len) {
+  if (in) {
+    if (O* rv = ConvertToC<O>(*in, out_len)) {
+      return rv;
+    } else {
+      return static_cast<O*>(wpi::safe_malloc(0));  // return non-NULL
+    }
+  } else {
+    *out_len = 0;
+    return nullptr;
+  }
+}
+
+extern "C" {
+
+struct NT_Meta_TopicPublisher* NT_Meta_DecodeTopicPublishers(
+    const uint8_t* data, size_t size, size_t* count) {
+  return ConvertToC<NT_Meta_TopicPublisher>(DecodeTopicPublishers({data, size}),
+                                            count);
+}
+
+struct NT_Meta_TopicSubscriber* NT_Meta_DecodeTopicSubscribers(
+    const uint8_t* data, size_t size, size_t* count) {
+  return ConvertToC<NT_Meta_TopicSubscriber>(
+      DecodeTopicSubscribers({data, size}), count);
+}
+
+struct NT_Meta_ClientPublisher* NT_Meta_DecodeClientPublishers(
+    const uint8_t* data, size_t size, size_t* count) {
+  return ConvertToC<NT_Meta_ClientPublisher>(
+      DecodeClientPublishers({data, size}), count);
+}
+
+struct NT_Meta_ClientSubscriber* NT_Meta_DecodeClientSubscribers(
+    const uint8_t* data, size_t size, size_t* count) {
+  return ConvertToC<NT_Meta_ClientSubscriber>(
+      DecodeClientSubscribers({data, size}), count);
+}
+
+struct NT_Meta_Client* NT_Meta_DecodeClients(const uint8_t* data, size_t size,
+                                             size_t* count) {
+  return ConvertToC<NT_Meta_Client>(DecodeClients({data, size}), count);
+}
+
+void NT_Meta_FreeTopicPublishers(struct NT_Meta_TopicPublisher* arr,
+                                 size_t count) {
+  for (size_t i = 0; i < count; ++i) {
+    std::free(arr[i].client.str);
+  }
+  std::free(arr);
+}
+
+void NT_Meta_FreeTopicSubscribers(struct NT_Meta_TopicSubscriber* arr,
+                                  size_t count) {
+  for (size_t i = 0; i < count; ++i) {
+    std::free(arr[i].client.str);
+  }
+  std::free(arr);
+}
+
+void NT_Meta_FreeClientPublishers(struct NT_Meta_ClientPublisher* arr,
+                                  size_t count) {
+  for (size_t i = 0; i < count; ++i) {
+    std::free(arr[i].topic.str);
+  }
+  std::free(arr);
+}
+
+void NT_Meta_FreeClientSubscribers(struct NT_Meta_ClientSubscriber* arr,
+                                   size_t count) {
+  for (size_t i = 0; i < count; ++i) {
+    NT_FreeStringArray(arr[i].topics, arr[i].topicsCount);
+  }
+  std::free(arr);
+}
+
+void NT_Meta_FreeClients(struct NT_Meta_Client* arr, size_t count) {
+  for (size_t i = 0; i < count; ++i) {
+    std::free(arr[i].id.str);
+    std::free(arr[i].conn.str);
+  }
+  std::free(arr);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib/ntcore/src/main/native/cpp/ntcore_test.cpp b/third_party/allwpilib/ntcore/src/main/native/cpp/ntcore_test.cpp
index 64bde68..2a07867 100644
--- a/third_party/allwpilib/ntcore/src/main/native/cpp/ntcore_test.cpp
+++ b/third_party/allwpilib/ntcore/src/main/native/cpp/ntcore_test.cpp
@@ -11,31 +11,30 @@
 #include "Value_internal.h"
 
 extern "C" {
-struct NT_String* NT_GetStringForTesting(const char* string, int* struct_size) {
-  struct NT_String* str =
+struct NT_String* NT_GetStringForTesting(const char* str, int* struct_size) {
+  struct NT_String* strout =
       static_cast<NT_String*>(wpi::safe_calloc(1, sizeof(NT_String)));
-  nt::ConvertToC(string, str);
+  nt::ConvertToC(str, strout);
   *struct_size = sizeof(NT_String);
-  return str;
+  return strout;
 }
 
-struct NT_EntryInfo* NT_GetEntryInfoForTesting(const char* name,
+struct NT_TopicInfo* NT_GetTopicInfoForTesting(const char* name,
                                                enum NT_Type type,
-                                               unsigned int flags,
-                                               uint64_t last_change,
+                                               const char* type_str,
                                                int* struct_size) {
-  struct NT_EntryInfo* entry_info =
-      static_cast<NT_EntryInfo*>(wpi::safe_calloc(1, sizeof(NT_EntryInfo)));
-  nt::ConvertToC(name, &entry_info->name);
-  entry_info->type = type;
-  entry_info->flags = flags;
-  entry_info->last_change = last_change;
-  *struct_size = sizeof(NT_EntryInfo);
-  return entry_info;
+  struct NT_TopicInfo* topic_info =
+      static_cast<NT_TopicInfo*>(wpi::safe_calloc(1, sizeof(NT_TopicInfo)));
+  nt::ConvertToC(name, &topic_info->name);
+  topic_info->type = type;
+  nt::ConvertToC(type_str, &topic_info->type_str);
+  *struct_size = sizeof(NT_TopicInfo);
+  return topic_info;
 }
 
-void NT_FreeEntryInfoForTesting(struct NT_EntryInfo* info) {
+void NT_FreeTopicInfoForTesting(struct NT_TopicInfo* info) {
   std::free(info->name.str);
+  std::free(info->type_str.str);
   std::free(info);
 }
 
@@ -158,88 +157,4 @@
 }
 // No need for free as one already exists in the main library
 
-static void CopyNtValue(const struct NT_Value* copy_from,
-                        struct NT_Value* copy_to) {
-  auto cpp_value = nt::ConvertFromC(*copy_from);
-  nt::ConvertToC(*cpp_value, copy_to);
-}
-
-static void CopyNtString(const struct NT_String* copy_from,
-                         struct NT_String* copy_to) {
-  nt::ConvertToC({copy_from->str, copy_from->len}, copy_to);
-}
-
-struct NT_RpcParamDef* NT_GetRpcParamDefForTesting(const char* name,
-                                                   const struct NT_Value* val,
-                                                   int* struct_size) {
-  struct NT_RpcParamDef* def =
-      static_cast<NT_RpcParamDef*>(wpi::safe_calloc(1, sizeof(NT_RpcParamDef)));
-  nt::ConvertToC(name, &def->name);
-  CopyNtValue(val, &def->def_value);
-  *struct_size = sizeof(NT_RpcParamDef);
-  return def;
-}
-
-void NT_FreeRpcParamDefForTesting(struct NT_RpcParamDef* def) {
-  NT_DisposeValue(&def->def_value);
-  NT_DisposeString(&def->name);
-  std::free(def);
-}
-
-struct NT_RpcResultDef* NT_GetRpcResultsDefForTesting(const char* name,
-                                                      enum NT_Type type,
-                                                      int* struct_size) {
-  struct NT_RpcResultDef* def = static_cast<NT_RpcResultDef*>(
-      wpi::safe_calloc(1, sizeof(NT_RpcResultDef)));
-  nt::ConvertToC(name, &def->name);
-  def->type = type;
-  *struct_size = sizeof(NT_RpcResultDef);
-  return def;
-}
-
-void NT_FreeRpcResultsDefForTesting(struct NT_RpcResultDef* def) {
-  NT_DisposeString(&def->name);
-  std::free(def);
-}
-
-struct NT_RpcDefinition* NT_GetRpcDefinitionForTesting(
-    unsigned int version, const char* name, size_t num_params,
-    const struct NT_RpcParamDef* params, size_t num_results,
-    const struct NT_RpcResultDef* results, int* struct_size) {
-  struct NT_RpcDefinition* def = static_cast<NT_RpcDefinition*>(
-      wpi::safe_calloc(1, sizeof(NT_RpcDefinition)));
-  def->version = version;
-  nt::ConvertToC(name, &def->name);
-  def->num_params = num_params;
-  def->params = static_cast<NT_RpcParamDef*>(
-      wpi::safe_malloc(num_params * sizeof(NT_RpcParamDef)));
-  for (size_t i = 0; i < num_params; ++i) {
-    CopyNtString(&params[i].name, &def->params[i].name);
-    CopyNtValue(&params[i].def_value, &def->params[i].def_value);
-  }
-  def->num_results = num_results;
-  def->results = static_cast<NT_RpcResultDef*>(
-      wpi::safe_malloc(num_results * sizeof(NT_RpcResultDef)));
-  for (size_t i = 0; i < num_results; ++i) {
-    CopyNtString(&results[i].name, &def->results[i].name);
-    def->results[i].type = results[i].type;
-  }
-  *struct_size = sizeof(NT_RpcDefinition);
-  return def;
-}
-// No need for free as one already exists in the main library
-
-struct NT_RpcAnswer* NT_GetRpcAnswerForTesting(
-    unsigned int rpc_id, unsigned int call_uid, const char* name,
-    const char* params, size_t params_len, int* struct_size) {
-  struct NT_RpcAnswer* info =
-      static_cast<NT_RpcAnswer*>(wpi::safe_calloc(1, sizeof(NT_RpcAnswer)));
-  info->entry = rpc_id;
-  info->call = call_uid;
-  nt::ConvertToC(name, &info->name);
-  nt::ConvertToC({params, params_len}, &info->params);
-  *struct_size = sizeof(NT_RpcAnswer);
-  return info;
-}
-// No need for free as one already exists in the main library
 }  // extern "C"
diff --git a/third_party/allwpilib/ntcore/src/main/native/include/networktables/EntryListenerFlags.h b/third_party/allwpilib/ntcore/src/main/native/include/networktables/EntryListenerFlags.h
deleted file mode 100644
index bbf5e42..0000000
--- a/third_party/allwpilib/ntcore/src/main/native/include/networktables/EntryListenerFlags.h
+++ /dev/null
@@ -1,75 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef NTCORE_NETWORKTABLES_ENTRYLISTENERFLAGS_H_
-#define NTCORE_NETWORKTABLES_ENTRYLISTENERFLAGS_H_
-
-#include "ntcore_c.h"
-
-/** Entry listener flags */
-namespace nt::EntryListenerFlags {
-
-/**
- * Flag values for use with entry listeners.
- *
- * The flags are a bitmask and must be OR'ed together to indicate the
- * combination of events desired to be received.
- *
- * The constants kNew, kDelete, kUpdate, and kFlags represent different events
- * that can occur to entries.
- *
- * By default, notifications are only generated for remote changes occurring
- * after the listener is created.  The constants kImmediate and kLocal are
- * modifiers that cause notifications to be generated at other times.
- *
- * @ingroup ntcore_cpp_api
- */
-enum {
-  /**
-   * Initial listener addition.
-   * Set this flag to receive immediate notification of entries matching the
-   * flag criteria (generally only useful when combined with kNew).
-   */
-  kImmediate = NT_NOTIFY_IMMEDIATE,
-
-  /**
-   * Changed locally.
-   * Set this flag to receive notification of both local changes and changes
-   * coming from remote nodes.  By default, notifications are only generated
-   * for remote changes.  Must be combined with some combination of kNew,
-   * kDelete, kUpdate, and kFlags to receive notifications of those respective
-   * events.
-   */
-  kLocal = NT_NOTIFY_LOCAL,
-
-  /**
-   * Newly created entry.
-   * Set this flag to receive a notification when an entry is created.
-   */
-  kNew = NT_NOTIFY_NEW,
-
-  /**
-   * Entry was deleted.
-   * Set this flag to receive a notification when an entry is deleted.
-   */
-  kDelete = NT_NOTIFY_DELETE,
-
-  /**
-   * Entry's value changed.
-   * Set this flag to receive a notification when an entry's value (or type)
-   * changes.
-   */
-  kUpdate = NT_NOTIFY_UPDATE,
-
-  /**
-   * Entry's flags changed.
-   * Set this flag to receive a notification when an entry's flags value
-   * changes.
-   */
-  kFlags = NT_NOTIFY_FLAGS
-};
-
-}  // namespace nt::EntryListenerFlags
-
-#endif  // NTCORE_NETWORKTABLES_ENTRYLISTENERFLAGS_H_
diff --git a/third_party/allwpilib/ntcore/src/main/native/include/networktables/GenericEntry.h b/third_party/allwpilib/ntcore/src/main/native/include/networktables/GenericEntry.h
new file mode 100644
index 0000000..6c7fee4
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/include/networktables/GenericEntry.h
@@ -0,0 +1,483 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <stdint.h>
+
+#include <span>
+#include <string>
+#include <string_view>
+#include <utility>
+#include <vector>
+
+#include "networktables/Topic.h"
+
+namespace nt {
+
+class Value;
+
+/**
+ * NetworkTables generic subscriber.
+ */
+class GenericSubscriber : public Subscriber {
+ public:
+  using TopicType = Topic;
+  using ValueType = Value;
+  using ParamType = const Value&;
+  using TimestampedValueType = Value;
+
+  GenericSubscriber() = default;
+
+  /**
+   * Construct from a subscriber handle; recommended to use
+   * Topic::GenericSubscribe() instead.
+   *
+   * @param handle Native handle
+   */
+  explicit GenericSubscriber(NT_Subscriber handle);
+
+  /**
+   * Get the last published value.
+   * If no value has been published, returns a value with unassigned type.
+   *
+   * @return value
+   */
+  ValueType Get() const;
+
+  /**
+   * Gets the entry's value as a boolean. If the entry does not exist or is of
+   * different type, it will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   */
+  bool GetBoolean(bool defaultValue) const;
+
+  /**
+   * Gets the entry's value as a integer. If the entry does not exist or is of
+   * different type, it will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   */
+  int64_t GetInteger(int64_t defaultValue) const;
+
+  /**
+   * Gets the entry's value as a float. If the entry does not exist or is of
+   * different type, it will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   */
+  float GetFloat(float defaultValue) const;
+
+  /**
+   * Gets the entry's value as a double. If the entry does not exist or is of
+   * different type, it will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   */
+  double GetDouble(double defaultValue) const;
+
+  /**
+   * Gets the entry's value as a string. If the entry does not exist or is of
+   * different type, it will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   */
+  std::string GetString(std::string_view defaultValue) const;
+
+  /**
+   * Gets the entry's value as a raw. If the entry does not exist or is of
+   * different type, it will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   */
+  std::vector<uint8_t> GetRaw(std::span<const uint8_t> defaultValue) const;
+
+  /**
+   * Gets the entry's value as a boolean array. If the entry does not exist
+   * or is of different type, it will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   *
+   * @note This makes a copy of the array.  If the overhead of this is a
+   *       concern, use GetValue() instead.
+   *
+   * @note The returned array is std::vector<int> instead of std::vector<bool>
+   *       because std::vector<bool> is special-cased in C++.  0 is false, any
+   *       non-zero value is true.
+   */
+  std::vector<int> GetBooleanArray(std::span<const int> defaultValue) const;
+
+  /**
+   * Gets the entry's value as a integer array. If the entry does not exist
+   * or is of different type, it will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   *
+   * @note This makes a copy of the array.  If the overhead of this is a
+   *       concern, use GetValue() instead.
+   */
+  std::vector<int64_t> GetIntegerArray(
+      std::span<const int64_t> defaultValue) const;
+
+  /**
+   * Gets the entry's value as a float array. If the entry does not exist
+   * or is of different type, it will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   *
+   * @note This makes a copy of the array.  If the overhead of this is a
+   *       concern, use GetValue() instead.
+   */
+  std::vector<float> GetFloatArray(std::span<const float> defaultValue) const;
+
+  /**
+   * Gets the entry's value as a double array. If the entry does not exist
+   * or is of different type, it will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   *
+   * @note This makes a copy of the array.  If the overhead of this is a
+   *       concern, use GetValue() instead.
+   */
+  std::vector<double> GetDoubleArray(
+      std::span<const double> defaultValue) const;
+
+  /**
+   * Gets the entry's value as a string array. If the entry does not exist
+   * or is of different type, it will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   *
+   * @note This makes a copy of the array.  If the overhead of this is a
+   *       concern, use GetValue() instead.
+   */
+  std::vector<std::string> GetStringArray(
+      std::span<const std::string> defaultValue) const;
+
+  /**
+   * Get an array of all value changes since the last call to ReadQueue.
+   * Also provides a timestamp for each value.
+   *
+   * @note The "poll storage" subscribe option can be used to set the queue
+   *     depth.
+   *
+   * @return Array of timestamped values; empty array if no new changes have
+   *     been published since the previous call.
+   */
+  std::vector<TimestampedValueType> ReadQueue();
+
+  /**
+   * Get the corresponding topic.
+   *
+   * @return Topic
+   */
+  TopicType GetTopic() const;
+};
+
+/**
+ * NetworkTables generic publisher.
+ */
+class GenericPublisher : public Publisher {
+ public:
+  using TopicType = Topic;
+  using ValueType = Value;
+  using ParamType = const Value&;
+  using TimestampedValueType = Value;
+
+  GenericPublisher() = default;
+
+  /**
+   * Construct from a publisher handle; recommended to use
+   * Topic::GenericPublish() instead.
+   *
+   * @param handle Native handle
+   */
+  explicit GenericPublisher(NT_Publisher handle);
+
+  /**
+   * Publish a new value.
+   *
+   * @param value value to publish
+   */
+  void Set(ParamType value);
+
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @param time the timestamp to set (0 = nt::Now())
+   * @return False if the entry exists with a different type
+   */
+  bool SetBoolean(bool value, int64_t time = 0);
+
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @param time the timestamp to set (0 = nt::Now())
+   * @return False if the entry exists with a different type
+   */
+  bool SetInteger(int64_t value, int64_t time = 0);
+
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @param time the timestamp to set (0 = nt::Now())
+   * @return False if the entry exists with a different type
+   */
+  bool SetFloat(float value, int64_t time = 0);
+
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @param time the timestamp to set (0 = nt::Now())
+   * @return False if the entry exists with a different type
+   */
+  bool SetDouble(double value, int64_t time = 0);
+
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @param time the timestamp to set (0 = nt::Now())
+   * @return False if the entry exists with a different type
+   */
+  bool SetString(std::string_view value, int64_t time = 0);
+
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @param time the timestamp to set (0 = nt::Now())
+   * @return False if the entry exists with a different type
+   */
+  bool SetRaw(std::span<const uint8_t> value, int64_t time = 0);
+
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @param time the timestamp to set (0 = nt::Now())
+   * @return False if the entry exists with a different type
+   */
+  bool SetBooleanArray(std::span<const bool> value, int64_t time = 0);
+
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @param time the timestamp to set (0 = nt::Now())
+   * @return False if the entry exists with a different type
+   */
+  bool SetBooleanArray(std::span<const int> value, int64_t time = 0);
+
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @param time the timestamp to set (0 = nt::Now())
+   * @return False if the entry exists with a different type
+   */
+  bool SetIntegerArray(std::span<const int64_t> value, int64_t time = 0);
+
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @param time the timestamp to set (0 = nt::Now())
+   * @return False if the entry exists with a different type
+   */
+  bool SetFloatArray(std::span<const float> value, int64_t time = 0);
+
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @param time the timestamp to set (0 = nt::Now())
+   * @return False if the entry exists with a different type
+   */
+  bool SetDoubleArray(std::span<const double> value, int64_t time = 0);
+
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @param time the timestamp to set (0 = nt::Now())
+   * @return False if the entry exists with a different type
+   */
+  bool SetStringArray(std::span<const std::string> value, int64_t time = 0);
+
+  /**
+   * Publish a default value.
+   * On reconnect, a default value will never be used in preference to a
+   * published value.
+   *
+   * @param value value
+   */
+  void SetDefault(ParamType value);
+
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  bool SetDefaultBoolean(bool defaultValue);
+
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  bool SetDefaultInteger(int64_t defaultValue);
+
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  bool SetDefaultFloat(float defaultValue);
+
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  bool SetDefaultDouble(double defaultValue);
+
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  bool SetDefaultString(std::string_view defaultValue);
+
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  bool SetDefaultRaw(std::span<const uint8_t> defaultValue);
+
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  bool SetDefaultBooleanArray(std::span<const int> defaultValue);
+
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  bool SetDefaultIntegerArray(std::span<const int64_t> defaultValue);
+
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  bool SetDefaultFloatArray(std::span<const float> defaultValue);
+
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  bool SetDefaultDoubleArray(std::span<const double> defaultValue);
+
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  bool SetDefaultStringArray(std::span<const std::string> defaultValue);
+
+  /**
+   * Get the corresponding topic.
+   *
+   * @return Topic
+   */
+  TopicType GetTopic() const;
+};
+
+/**
+ * NetworkTables generic entry.
+ *
+ * @note Unlike NetworkTableEntry, the entry goes away when this is destroyed.
+ */
+class GenericEntry final : public GenericSubscriber, public GenericPublisher {
+ public:
+  using SubscriberType = GenericSubscriber;
+  using PublisherType = GenericPublisher;
+  using TopicType = Topic;
+  using ValueType = Value;
+  using ParamType = const Value&;
+  using TimestampedValueType = Value;
+
+  GenericEntry() = default;
+
+  /**
+   * Construct from an entry handle; recommended to use
+   * RawTopic::GetEntry() instead.
+   *
+   * @param handle Native handle
+   */
+  explicit GenericEntry(NT_Entry handle);
+
+  /**
+   * Determines if the native handle is valid.
+   *
+   * @return True if the native handle is valid, false otherwise.
+   */
+  explicit operator bool() const { return m_subHandle != 0; }
+
+  /**
+   * Gets the native handle for the entry.
+   *
+   * @return Native handle
+   */
+  NT_Entry GetHandle() const { return m_subHandle; }
+
+  /**
+   * Get the corresponding topic.
+   *
+   * @return Topic
+   */
+  TopicType GetTopic() const;
+
+  /**
+   * Stops publishing the entry if it's published.
+   */
+  void Unpublish();
+};
+
+}  // namespace nt
+
+#include "networktables/GenericEntry.inc"
diff --git a/third_party/allwpilib/ntcore/src/main/native/include/networktables/GenericEntry.inc b/third_party/allwpilib/ntcore/src/main/native/include/networktables/GenericEntry.inc
new file mode 100644
index 0000000..f3d9967
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/include/networktables/GenericEntry.inc
@@ -0,0 +1,214 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <span>
+#include <string>
+#include <string_view>
+#include <vector>
+
+#include "networktables/GenericEntry.h"
+#include "networktables/NetworkTableType.h"
+#include "ntcore_cpp.h"
+
+namespace nt {
+
+inline GenericSubscriber::GenericSubscriber(NT_Subscriber handle)
+    : Subscriber{handle} {}
+
+inline Value GenericSubscriber::Get() const {
+  return ::nt::GetEntryValue(m_subHandle);
+}
+
+inline bool GenericSubscriber::GetBoolean(bool defaultValue) const {
+  return ::nt::GetBoolean(m_subHandle, defaultValue);
+}
+
+inline int64_t GenericSubscriber::GetInteger(int64_t defaultValue) const {
+  return ::nt::GetInteger(m_subHandle, defaultValue);
+}
+
+inline float GenericSubscriber::GetFloat(float defaultValue) const {
+  return ::nt::GetFloat(m_subHandle, defaultValue);
+}
+
+inline double GenericSubscriber::GetDouble(double defaultValue) const {
+  return ::nt::GetDouble(m_subHandle, defaultValue);
+}
+
+inline std::string GenericSubscriber::GetString(
+    std::string_view defaultValue) const {
+  return ::nt::GetString(m_subHandle, defaultValue);
+}
+
+inline std::vector<uint8_t> GenericSubscriber::GetRaw(
+    std::span<const uint8_t> defaultValue) const {
+  return ::nt::GetRaw(m_subHandle, defaultValue);
+}
+
+inline std::vector<int> GenericSubscriber::GetBooleanArray(
+    std::span<const int> defaultValue) const {
+  return ::nt::GetBooleanArray(m_subHandle, defaultValue);
+}
+
+inline std::vector<int64_t> GenericSubscriber::GetIntegerArray(
+    std::span<const int64_t> defaultValue) const {
+  return ::nt::GetIntegerArray(m_subHandle, defaultValue);
+}
+
+inline std::vector<float> GenericSubscriber::GetFloatArray(
+    std::span<const float> defaultValue) const {
+  return ::nt::GetFloatArray(m_subHandle, defaultValue);
+}
+
+inline std::vector<double> GenericSubscriber::GetDoubleArray(
+    std::span<const double> defaultValue) const {
+  return ::nt::GetDoubleArray(m_subHandle, defaultValue);
+}
+
+inline std::vector<std::string> GenericSubscriber::GetStringArray(
+    std::span<const std::string> defaultValue) const {
+  return ::nt::GetStringArray(m_subHandle, defaultValue);
+}
+
+inline std::vector<Value> GenericSubscriber::ReadQueue() {
+  return ::nt::ReadQueueValue(m_subHandle);
+}
+
+inline Topic GenericSubscriber::GetTopic() const {
+  return Topic{::nt::GetTopicFromHandle(m_subHandle)};
+}
+
+inline GenericPublisher::GenericPublisher(NT_Publisher handle)
+    : Publisher{handle} {}
+
+inline void GenericPublisher::Set(const Value& value) {
+  ::nt::SetEntryValue(m_pubHandle, value);
+}
+
+inline bool GenericPublisher::SetBoolean(bool value, int64_t time) {
+  return nt::SetBoolean(m_pubHandle, value, time);
+}
+
+inline bool GenericPublisher::SetInteger(int64_t value, int64_t time) {
+  return nt::SetInteger(m_pubHandle, value, time);
+}
+
+inline bool GenericPublisher::SetFloat(float value, int64_t time) {
+  return nt::SetFloat(m_pubHandle, value, time);
+}
+
+inline bool GenericPublisher::SetDouble(double value, int64_t time) {
+  return nt::SetDouble(m_pubHandle, value, time);
+}
+
+inline bool GenericPublisher::SetString(std::string_view value, int64_t time) {
+  return nt::SetString(m_pubHandle, value, time);
+}
+
+inline bool GenericPublisher::SetRaw(std::span<const uint8_t> value,
+                                     int64_t time) {
+  return nt::SetRaw(m_pubHandle, value, time);
+}
+
+inline bool GenericPublisher::SetBooleanArray(std::span<const bool> value,
+                                              int64_t time) {
+  return SetEntryValue(m_pubHandle, Value::MakeBooleanArray(value, time));
+}
+
+inline bool GenericPublisher::SetBooleanArray(std::span<const int> value,
+                                              int64_t time) {
+  return nt::SetBooleanArray(m_pubHandle, value, time);
+}
+
+inline bool GenericPublisher::SetIntegerArray(std::span<const int64_t> value,
+                                              int64_t time) {
+  return nt::SetIntegerArray(m_pubHandle, value, time);
+}
+
+inline bool GenericPublisher::SetFloatArray(std::span<const float> value,
+                                            int64_t time) {
+  return nt::SetFloatArray(m_pubHandle, value, time);
+}
+
+inline bool GenericPublisher::SetDoubleArray(std::span<const double> value,
+                                             int64_t time) {
+  return nt::SetDoubleArray(m_pubHandle, value, time);
+}
+
+inline bool GenericPublisher::SetStringArray(std::span<const std::string> value,
+                                             int64_t time) {
+  return nt::SetStringArray(m_pubHandle, value, time);
+}
+
+inline void GenericPublisher::SetDefault(const Value& value) {
+  ::nt::SetDefaultEntryValue(m_pubHandle, value);
+}
+
+inline bool GenericPublisher::SetDefaultBoolean(bool defaultValue) {
+  return nt::SetDefaultBoolean(m_pubHandle, defaultValue);
+}
+
+inline bool GenericPublisher::SetDefaultInteger(int64_t defaultValue) {
+  return nt::SetDefaultInteger(m_pubHandle, defaultValue);
+}
+
+inline bool GenericPublisher::SetDefaultFloat(float defaultValue) {
+  return nt::SetDefaultFloat(m_pubHandle, defaultValue);
+}
+
+inline bool GenericPublisher::SetDefaultDouble(double defaultValue) {
+  return nt::SetDefaultDouble(m_pubHandle, defaultValue);
+}
+
+inline bool GenericPublisher::SetDefaultString(std::string_view defaultValue) {
+  return nt::SetDefaultString(m_pubHandle, defaultValue);
+}
+
+inline bool GenericPublisher::SetDefaultRaw(
+    std::span<const uint8_t> defaultValue) {
+  return nt::SetDefaultRaw(m_pubHandle, defaultValue);
+}
+
+inline bool GenericPublisher::SetDefaultBooleanArray(
+    std::span<const int> defaultValue) {
+  return nt::SetDefaultBooleanArray(m_pubHandle, defaultValue);
+}
+
+inline bool GenericPublisher::SetDefaultIntegerArray(
+    std::span<const int64_t> defaultValue) {
+  return nt::SetDefaultIntegerArray(m_pubHandle, defaultValue);
+}
+
+inline bool GenericPublisher::SetDefaultFloatArray(
+    std::span<const float> defaultValue) {
+  return nt::SetDefaultFloatArray(m_pubHandle, defaultValue);
+}
+
+inline bool GenericPublisher::SetDefaultDoubleArray(
+    std::span<const double> defaultValue) {
+  return nt::SetDefaultDoubleArray(m_pubHandle, defaultValue);
+}
+
+inline bool GenericPublisher::SetDefaultStringArray(
+    std::span<const std::string> defaultValue) {
+  return nt::SetDefaultStringArray(m_pubHandle, defaultValue);
+}
+
+inline Topic GenericPublisher::GetTopic() const {
+  return Topic{::nt::GetTopicFromHandle(m_pubHandle)};
+}
+
+inline GenericEntry::GenericEntry(NT_Entry handle)
+    : GenericSubscriber{handle}, GenericPublisher{handle} {}
+
+inline Topic GenericEntry::GetTopic() const {
+  return Topic{::nt::GetTopicFromHandle(m_subHandle)};
+}
+
+inline void GenericEntry::Unpublish() {
+  ::nt::Unpublish(m_pubHandle);
+}
+}  // namespace nt
diff --git a/third_party/allwpilib/ntcore/src/main/native/include/networktables/MultiSubscriber.h b/third_party/allwpilib/ntcore/src/main/native/include/networktables/MultiSubscriber.h
new file mode 100644
index 0000000..f146351
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/include/networktables/MultiSubscriber.h
@@ -0,0 +1,61 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <span>
+#include <string_view>
+
+#include "networktables/NetworkTableInstance.h"
+#include "ntcore_cpp.h"
+
+namespace nt {
+
+/**
+ * Subscribe to multiple topics based on one or more topic name prefixes. Can be
+ * used in combination with ValueListenerPoller to listen for value changes
+ * across all matching topics.
+ */
+class MultiSubscriber final {
+ public:
+  MultiSubscriber() = default;
+
+  /**
+   * Create a multiple subscriber.
+   *
+   * @param inst instance
+   * @param prefixes topic name prefixes
+   * @param options subscriber options
+   */
+  MultiSubscriber(NetworkTableInstance inst,
+                  std::span<const std::string_view> prefixes,
+                  const PubSubOptions& options = kDefaultPubSubOptions);
+
+  MultiSubscriber(const MultiSubscriber&) = delete;
+  MultiSubscriber& operator=(const MultiSubscriber&) = delete;
+  MultiSubscriber(MultiSubscriber&& rhs);
+  MultiSubscriber& operator=(MultiSubscriber&& rhs);
+  ~MultiSubscriber();
+
+  /**
+   * Determines if the native handle is valid.
+   *
+   * @return True if the native handle is valid, false otherwise.
+   */
+  explicit operator bool() const { return m_handle != 0; }
+
+  /**
+   * Gets the native handle.
+   *
+   * @return Handle
+   */
+  NT_MultiSubscriber GetHandle() const { return m_handle; }
+
+ private:
+  NT_MultiSubscriber m_handle{0};
+};
+
+}  // namespace nt
+
+#include "MultiSubscriber.inc"
diff --git a/third_party/allwpilib/ntcore/src/main/native/include/networktables/MultiSubscriber.inc b/third_party/allwpilib/ntcore/src/main/native/include/networktables/MultiSubscriber.inc
new file mode 100644
index 0000000..c32c06a
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/include/networktables/MultiSubscriber.inc
@@ -0,0 +1,36 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include "networktables/MultiSubscriber.h"
+
+namespace nt {
+
+inline MultiSubscriber::MultiSubscriber(
+    NetworkTableInstance inst, std::span<const std::string_view> prefixes,
+    const PubSubOptions& options)
+    : m_handle{::nt::SubscribeMultiple(inst.GetHandle(), prefixes, options)} {}
+
+inline MultiSubscriber::MultiSubscriber(MultiSubscriber&& rhs)
+    : m_handle{rhs.m_handle} {
+  rhs.m_handle = 0;
+}
+
+inline MultiSubscriber& MultiSubscriber::operator=(MultiSubscriber&& rhs) {
+  if (m_handle != 0) {
+    ::nt::UnsubscribeMultiple(m_handle);
+  }
+  m_handle = rhs.m_handle;
+  rhs.m_handle = 0;
+  return *this;
+}
+
+inline MultiSubscriber::~MultiSubscriber() {
+  if (m_handle != 0) {
+    ::nt::UnsubscribeMultiple(m_handle);
+  }
+}
+
+}  // namespace nt
diff --git a/third_party/allwpilib/ntcore/src/main/native/include/networktables/NTSendableBuilder.h b/third_party/allwpilib/ntcore/src/main/native/include/networktables/NTSendableBuilder.h
index 8ff265b..01ce6cc 100644
--- a/third_party/allwpilib/ntcore/src/main/native/include/networktables/NTSendableBuilder.h
+++ b/third_party/allwpilib/ntcore/src/main/native/include/networktables/NTSendableBuilder.h
@@ -4,15 +4,14 @@
 
 #pragma once
 
-#include <functional>
 #include <memory>
 #include <string_view>
 
+#include <wpi/FunctionExtras.h>
 #include <wpi/sendable/SendableBuilder.h>
 
 #include "networktables/NetworkTable.h"
-#include "networktables/NetworkTableEntry.h"
-#include "networktables/NetworkTableValue.h"
+#include "networktables/Topic.h"
 
 namespace nt {
 
@@ -26,27 +25,16 @@
    *
    * @param func    function
    */
-  virtual void SetUpdateTable(std::function<void()> func) = 0;
+  virtual void SetUpdateTable(wpi::unique_function<void()> func) = 0;
 
   /**
    * Add a property without getters or setters.  This can be used to get
    * entry handles for the function called by SetUpdateTable().
    *
    * @param key   property name
-   * @return Network table entry
+   * @return Network table topic
    */
-  virtual NetworkTableEntry GetEntry(std::string_view key) = 0;
-
-  /**
-   * Add a NetworkTableValue property.
-   *
-   * @param key     property name
-   * @param getter  getter function (returns current value)
-   * @param setter  setter function (sets new value)
-   */
-  virtual void AddValueProperty(
-      std::string_view key, std::function<std::shared_ptr<Value>()> getter,
-      std::function<void(std::shared_ptr<Value>)> setter) = 0;
+  virtual Topic GetTopic(std::string_view key) = 0;
 
   /**
    * Get the network table.
diff --git a/third_party/allwpilib/ntcore/src/main/native/include/networktables/NetworkTable.h b/third_party/allwpilib/ntcore/src/main/native/include/networktables/NetworkTable.h
index 3a04e45..d34f54b 100644
--- a/third_party/allwpilib/ntcore/src/main/native/include/networktables/NetworkTable.h
+++ b/third_party/allwpilib/ntcore/src/main/native/include/networktables/NetworkTable.h
@@ -2,11 +2,11 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
-#ifndef NTCORE_NETWORKTABLES_NETWORKTABLE_H_
-#define NTCORE_NETWORKTABLES_NETWORKTABLE_H_
+#pragma once
 
 #include <functional>
 #include <memory>
+#include <span>
 #include <string>
 #include <string_view>
 #include <utility>
@@ -14,16 +14,25 @@
 
 #include <wpi/StringMap.h>
 #include <wpi/mutex.h>
-#include <wpi/span.h>
 
 #include "networktables/NetworkTableEntry.h"
-#include "networktables/TableEntryListener.h"
-#include "networktables/TableListener.h"
 #include "ntcore_c.h"
 
 namespace nt {
 
+class BooleanArrayTopic;
+class BooleanTopic;
+class DoubleArrayTopic;
+class DoubleTopic;
+class FloatArrayTopic;
+class FloatTopic;
+class IntegerArrayTopic;
+class IntegerTopic;
 class NetworkTableInstance;
+class RawTopic;
+class StringArrayTopic;
+class StringTopic;
+class Topic;
 
 /**
  * @defgroup ntcore_cpp_api ntcore C++ object-oriented API
@@ -41,7 +50,6 @@
   std::string m_path;
   mutable wpi::mutex m_mutex;
   mutable wpi::StringMap<NT_Entry> m_entries;
-  std::vector<NT_EntryListener> m_listeners;
 
   struct private_init {};
   friend class NetworkTableInstance;
@@ -94,7 +102,7 @@
    * instead.
    */
   NetworkTable(NT_Inst inst, std::string_view path, const private_init&);
-  virtual ~NetworkTable();
+  ~NetworkTable();
 
   /**
    * Gets the instance for the table.
@@ -117,52 +125,100 @@
   NetworkTableEntry GetEntry(std::string_view key) const;
 
   /**
-   * Listen to keys only within this table.
+   * Get (generic) topic.
    *
-   * @param listener    listener to add
-   * @param flags       EntryListenerFlags bitmask
-   * @return Listener handle
+   * @param name topic name
+   * @return Topic
    */
-  NT_EntryListener AddEntryListener(TableEntryListener listener,
-                                    unsigned int flags) const;
+  Topic GetTopic(std::string_view name) const;
 
   /**
-   * Listen to a single key.
+   * Get boolean topic.
    *
-   * @param key         the key name
-   * @param listener    listener to add
-   * @param flags       EntryListenerFlags bitmask
-   * @return Listener handle
+   * @param name topic name
+   * @return BooleanTopic
    */
-  NT_EntryListener AddEntryListener(std::string_view key,
-                                    TableEntryListener listener,
-                                    unsigned int flags) const;
+  BooleanTopic GetBooleanTopic(std::string_view name) const;
 
   /**
-   * Remove an entry listener.
+   * Get integer topic.
    *
-   * @param listener    listener handle
+   * @param name topic name
+   * @return IntegerTopic
    */
-  void RemoveEntryListener(NT_EntryListener listener) const;
+  IntegerTopic GetIntegerTopic(std::string_view name) const;
 
   /**
-   * Listen for sub-table creation.
-   * This calls the listener once for each newly created sub-table.
-   * It immediately calls the listener for any existing sub-tables.
+   * Get float topic.
    *
-   * @param listener        listener to add
-   * @param localNotify     notify local changes as well as remote
-   * @return Listener handle
+   * @param name topic name
+   * @return FloatTopic
    */
-  NT_EntryListener AddSubTableListener(TableListener listener,
-                                       bool localNotify = false);
+  FloatTopic GetFloatTopic(std::string_view name) const;
 
   /**
-   * Remove a sub-table listener.
+   * Get double topic.
    *
-   * @param listener    listener handle
+   * @param name topic name
+   * @return DoubleTopic
    */
-  void RemoveTableListener(NT_EntryListener listener);
+  DoubleTopic GetDoubleTopic(std::string_view name) const;
+
+  /**
+   * Get String topic.
+   *
+   * @param name topic name
+   * @return StringTopic
+   */
+  StringTopic GetStringTopic(std::string_view name) const;
+
+  /**
+   * Get raw topic.
+   *
+   * @param name topic name
+   * @return BooleanArrayTopic
+   */
+  RawTopic GetRawTopic(std::string_view name) const;
+
+  /**
+   * Get boolean[] topic.
+   *
+   * @param name topic name
+   * @return BooleanArrayTopic
+   */
+  BooleanArrayTopic GetBooleanArrayTopic(std::string_view name) const;
+
+  /**
+   * Get integer[] topic.
+   *
+   * @param name topic name
+   * @return IntegerArrayTopic
+   */
+  IntegerArrayTopic GetIntegerArrayTopic(std::string_view name) const;
+
+  /**
+   * Get float[] topic.
+   *
+   * @param name topic name
+   * @return FloatArrayTopic
+   */
+  FloatArrayTopic GetFloatArrayTopic(std::string_view name) const;
+
+  /**
+   * Get double[] topic.
+   *
+   * @param name topic name
+   * @return DoubleArrayTopic
+   */
+  DoubleArrayTopic GetDoubleArrayTopic(std::string_view name) const;
+
+  /**
+   * Get String[] topic.
+   *
+   * @param name topic name
+   * @return StringArrayTopic
+   */
+  StringArrayTopic GetStringArrayTopic(std::string_view name) const;
 
   /**
    * Returns the table at the specified key. If there is no table at the
@@ -192,6 +248,23 @@
   bool ContainsSubTable(std::string_view key) const;
 
   /**
+   * Gets topic information for all keys in the table (not including
+   * sub-tables).
+   *
+   * @param types bitmask of types; 0 is treated as a "don't care".
+   * @return topic information for keys currently in the table
+   */
+  std::vector<TopicInfo> GetTopicInfo(int types = 0) const;
+
+  /**
+   * Gets all topics in the table (not including sub-tables).
+   *
+   * @param types bitmask of types; 0 is treated as a "don't care".
+   * @return topic for keys currently in the table
+   */
+  std::vector<Topic> GetTopics(int types = 0) const;
+
+  /**
    * Gets all keys in the table (not including sub-tables).
    *
    * @param types bitmask of types; 0 is treated as a "don't care".
@@ -230,39 +303,6 @@
   bool IsPersistent(std::string_view key) const;
 
   /**
-   * Sets flags on the specified key in this table. The key can
-   * not be null.
-   *
-   * @param key the key name
-   * @param flags the flags to set (bitmask)
-   */
-  void SetFlags(std::string_view key, unsigned int flags);
-
-  /**
-   * Clears flags on the specified key in this table. The key can
-   * not be null.
-   *
-   * @param key the key name
-   * @param flags the flags to clear (bitmask)
-   */
-  void ClearFlags(std::string_view key, unsigned int flags);
-
-  /**
-   * Returns the flags for the specified key.
-   *
-   * @param key the key name
-   * @return the flags, or 0 if the key is not defined
-   */
-  unsigned int GetFlags(std::string_view key) const;
-
-  /**
-   * Deletes the specified key in this table.
-   *
-   * @param key the key name
-   */
-  void Delete(std::string_view key);
-
-  /**
    * Put a number in the table
    *
    * @param key the key to be assigned to
@@ -360,7 +400,7 @@
    *       std::vector<bool> is special-cased in C++.  0 is false, any
    *       non-zero value is true.
    */
-  bool PutBooleanArray(std::string_view key, wpi::span<const int> value);
+  bool PutBooleanArray(std::string_view key, std::span<const int> value);
 
   /**
    * Gets the current value in the table, setting it if it does not exist.
@@ -370,7 +410,7 @@
    * @return False if the table key exists with a different type
    */
   bool SetDefaultBooleanArray(std::string_view key,
-                              wpi::span<const int> defaultValue);
+                              std::span<const int> defaultValue);
 
   /**
    * Returns the boolean array the key maps to. If the key does not exist or is
@@ -389,7 +429,7 @@
    *       non-zero value is true.
    */
   std::vector<int> GetBooleanArray(std::string_view key,
-                                   wpi::span<const int> defaultValue) const;
+                                   std::span<const int> defaultValue) const;
 
   /**
    * Put a number array in the table
@@ -398,7 +438,7 @@
    * @param value the value that will be assigned
    * @return False if the table key already exists with a different type
    */
-  bool PutNumberArray(std::string_view key, wpi::span<const double> value);
+  bool PutNumberArray(std::string_view key, std::span<const double> value);
 
   /**
    * Gets the current value in the table, setting it if it does not exist.
@@ -408,7 +448,7 @@
    * @returns False if the table key exists with a different type
    */
   bool SetDefaultNumberArray(std::string_view key,
-                             wpi::span<const double> defaultValue);
+                             std::span<const double> defaultValue);
 
   /**
    * Returns the number array the key maps to. If the key does not exist or is
@@ -423,7 +463,7 @@
    *       concern, use GetValue() instead.
    */
   std::vector<double> GetNumberArray(
-      std::string_view key, wpi::span<const double> defaultValue) const;
+      std::string_view key, std::span<const double> defaultValue) const;
 
   /**
    * Put a string array in the table
@@ -432,7 +472,7 @@
    * @param value the value that will be assigned
    * @return False if the table key already exists with a different type
    */
-  bool PutStringArray(std::string_view key, wpi::span<const std::string> value);
+  bool PutStringArray(std::string_view key, std::span<const std::string> value);
 
   /**
    * Gets the current value in the table, setting it if it does not exist.
@@ -442,7 +482,7 @@
    * @returns False if the table key exists with a different type
    */
   bool SetDefaultStringArray(std::string_view key,
-                             wpi::span<const std::string> defaultValue);
+                             std::span<const std::string> defaultValue);
 
   /**
    * Returns the string array the key maps to. If the key does not exist or is
@@ -457,7 +497,7 @@
    *       concern, use GetValue() instead.
    */
   std::vector<std::string> GetStringArray(
-      std::string_view key, wpi::span<const std::string> defaultValue) const;
+      std::string_view key, std::span<const std::string> defaultValue) const;
 
   /**
    * Put a raw value (byte array) in the table
@@ -466,7 +506,7 @@
    * @param value the value that will be assigned
    * @return False if the table key already exists with a different type
    */
-  bool PutRaw(std::string_view key, std::string_view value);
+  bool PutRaw(std::string_view key, std::span<const uint8_t> value);
 
   /**
    * Gets the current value in the table, setting it if it does not exist.
@@ -475,7 +515,8 @@
    * @param defaultValue the default value to set if key doesn't exist.
    * @return False if the table key exists with a different type
    */
-  bool SetDefaultRaw(std::string_view key, std::string_view defaultValue);
+  bool SetDefaultRaw(std::string_view key,
+                     std::span<const uint8_t> defaultValue);
 
   /**
    * Returns the raw value (byte array) the key maps to. If the key does not
@@ -489,7 +530,8 @@
    * @note This makes a copy of the raw contents.  If the overhead of this is a
    *       concern, use GetValue() instead.
    */
-  std::string GetRaw(std::string_view key, std::string_view defaultValue) const;
+  std::vector<uint8_t> GetRaw(std::string_view key,
+                              std::span<const uint8_t> defaultValue) const;
 
   /**
    * Put a value in the table
@@ -498,7 +540,7 @@
    * @param value the value that will be assigned
    * @return False if the table key already exists with a different type
    */
-  bool PutValue(std::string_view key, std::shared_ptr<Value> value);
+  bool PutValue(std::string_view key, const Value& value);
 
   /**
    * Gets the current value in the table, setting it if it does not exist.
@@ -507,8 +549,7 @@
    * @param defaultValue the default value to set if key doesn't exist.
    * @return False if the table key exists with a different type
    */
-  bool SetDefaultValue(std::string_view key,
-                       std::shared_ptr<Value> defaultValue);
+  bool SetDefaultValue(std::string_view key, const Value& defaultValue);
 
   /**
    * Gets the value associated with a key as an object
@@ -517,7 +558,7 @@
    * @return the value associated with the given key, or nullptr if the key
    * does not exist
    */
-  std::shared_ptr<Value> GetValue(std::string_view key) const;
+  Value GetValue(std::string_view key) const;
 
   /**
    * Gets the full path of this table.  Does not include the trailing "/".
@@ -527,27 +568,62 @@
   std::string_view GetPath() const;
 
   /**
-   * Save table values to a file.  The file format used is identical to
-   * that used for SavePersistent.
+   * Called when an event occurs on a topic in a {@link NetworkTable}.
    *
-   * @param filename  filename
-   * @return error string, or nullptr if successful
+   * @param table the table the topic exists in
+   * @param key the key associated with the topic that changed
+   * @param event the event
    */
-  const char* SaveEntries(std::string_view filename) const;
+  using TableEventListener = std::function<void(
+      NetworkTable* table, std::string_view key, const Event& event)>;
 
   /**
-   * Load table values from a file.  The file format used is identical to
-   * that used for SavePersistent / LoadPersistent.
+   * Listen to topics only within this table.
    *
-   * @param filename  filename
-   * @param warn      callback function for warnings
-   * @return error string, or nullptr if successful
+   * @param eventMask Bitmask of EventFlags values
+   * @param listener listener to add
+   * @return Listener handle
    */
-  const char* LoadEntries(
-      std::string_view filename,
-      std::function<void(size_t line, const char* msg)> warn);
+  NT_Listener AddListener(int eventMask, TableEventListener listener);
+
+  /**
+   * Listen to a single key.
+   *
+   * @param key the key name
+   * @param eventMask Bitmask of EventFlags values
+   * @param listener listener to add
+   * @return Listener handle
+   */
+  NT_Listener AddListener(std::string_view key, int eventMask,
+                          TableEventListener listener);
+
+  /**
+   * Called when a new table is created within a NetworkTable.
+   *
+   * @param parent the parent of the table
+   * @param name the name of the new table
+   * @param table the new table
+   */
+  using SubTableListener =
+      std::function<void(NetworkTable* parent, std::string_view name,
+                         std::shared_ptr<NetworkTable> table)>;
+
+  /**
+   * Listen for sub-table creation. This calls the listener once for each newly
+   * created sub-table. It immediately calls the listener for any existing
+   * sub-tables.
+   *
+   * @param listener listener to add
+   * @return Listener handle
+   */
+  NT_Listener AddSubTableListener(SubTableListener listener);
+
+  /**
+   * Remove a listener.
+   *
+   * @param listener listener handle
+   */
+  void RemoveListener(NT_Listener listener);
 };
 
 }  // namespace nt
-
-#endif  // NTCORE_NETWORKTABLES_NETWORKTABLE_H_
diff --git a/third_party/allwpilib/ntcore/src/main/native/include/networktables/NetworkTableEntry.h b/third_party/allwpilib/ntcore/src/main/native/include/networktables/NetworkTableEntry.h
index c6c9c86..b9d509a 100644
--- a/third_party/allwpilib/ntcore/src/main/native/include/networktables/NetworkTableEntry.h
+++ b/third_party/allwpilib/ntcore/src/main/native/include/networktables/NetworkTableEntry.h
@@ -2,37 +2,42 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
-#ifndef NTCORE_NETWORKTABLES_NETWORKTABLEENTRY_H_
-#define NTCORE_NETWORKTABLES_NETWORKTABLEENTRY_H_
+#pragma once
 
 #include <stdint.h>
 
 #include <initializer_list>
 #include <memory>
+#include <span>
 #include <string>
 #include <string_view>
 #include <vector>
 
-#include <wpi/span.h>
+#include <wpi/deprecated.h>
 
 #include "networktables/NetworkTableType.h"
 #include "networktables/NetworkTableValue.h"
-#include "networktables/RpcCall.h"
 #include "ntcore_c.h"
 #include "ntcore_cpp.h"
 
 namespace nt {
 
 class NetworkTableInstance;
+class Topic;
 
 /**
  * NetworkTables Entry
+ *
+ * @note For backwards compatibility, the NetworkTableEntry destructor does not
+ *       release the entry.
+ *
  * @ingroup ntcore_cpp_api
  */
 class NetworkTableEntry final {
  public:
   /**
    * Flag values (as returned by GetFlags()).
+   * @deprecated Use IsPersistent() instead.
    */
   enum Flags { kPersistent = NT_PERSISTENT };
 
@@ -94,7 +99,9 @@
    * Returns the flags.
    *
    * @return the flags (bitmask)
+   * @deprecated Use IsPersistent() or topic properties instead
    */
+  WPI_DEPRECATED("Use IsPersistent() or topic properties instead")
   unsigned int GetFlags() const;
 
   /**
@@ -102,21 +109,15 @@
    *
    * @return Entry last change time
    */
-  uint64_t GetLastChange() const;
+  int64_t GetLastChange() const;
 
   /**
-   * Gets combined information about the entry.
+   * Gets the entry's value. If the entry does not exist, returns an empty
+   * value.
    *
-   * @return Entry information
+   * @return the entry's value or an empty value if it does not exist.
    */
-  EntryInfo GetInfo() const;
-
-  /**
-   * Gets the entry's value. If the entry does not exist, returns nullptr.
-   *
-   * @return the entry's value or nullptr if it does not exist.
-   */
-  std::shared_ptr<Value> GetValue() const;
+  Value GetValue() const;
 
   /**
    * Gets the entry's value as a boolean. If the entry does not exist or is of
@@ -128,6 +129,24 @@
   bool GetBoolean(bool defaultValue) const;
 
   /**
+   * Gets the entry's value as a integer. If the entry does not exist or is of
+   * different type, it will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   */
+  int64_t GetInteger(int64_t defaultValue) const;
+
+  /**
+   * Gets the entry's value as a float. If the entry does not exist or is of
+   * different type, it will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   */
+  float GetFloat(float defaultValue) const;
+
+  /**
    * Gets the entry's value as a double. If the entry does not exist or is of
    * different type, it will return the default value.
    *
@@ -152,7 +171,7 @@
    * @param defaultValue the value to be returned if no value is found
    * @return the entry's value or the given default value
    */
-  std::string GetRaw(std::string_view defaultValue) const;
+  std::vector<uint8_t> GetRaw(std::span<const uint8_t> defaultValue) const;
 
   /**
    * Gets the entry's value as a boolean array. If the entry does not exist
@@ -168,10 +187,10 @@
    *       because std::vector<bool> is special-cased in C++.  0 is false, any
    *       non-zero value is true.
    */
-  std::vector<int> GetBooleanArray(wpi::span<const int> defaultValue) const;
+  std::vector<int> GetBooleanArray(std::span<const int> defaultValue) const;
 
   /**
-   * Gets the entry's value as a boolean array. If the entry does not exist
+   * Gets the entry's value as a integer array. If the entry does not exist
    * or is of different type, it will return the default value.
    *
    * @param defaultValue the value to be returned if no value is found
@@ -179,13 +198,21 @@
    *
    * @note This makes a copy of the array.  If the overhead of this is a
    *       concern, use GetValue() instead.
-   *
-   * @note The returned array is std::vector<int> instead of std::vector<bool>
-   *       because std::vector<bool> is special-cased in C++.  0 is false, any
-   *       non-zero value is true.
    */
-  std::vector<int> GetBooleanArray(
-      std::initializer_list<int> defaultValue) const;
+  std::vector<int64_t> GetIntegerArray(
+      std::span<const int64_t> defaultValue) const;
+
+  /**
+   * Gets the entry's value as a float array. If the entry does not exist
+   * or is of different type, it will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   *
+   * @note This makes a copy of the array.  If the overhead of this is a
+   *       concern, use GetValue() instead.
+   */
+  std::vector<float> GetFloatArray(std::span<const float> defaultValue) const;
 
   /**
    * Gets the entry's value as a double array. If the entry does not exist
@@ -198,20 +225,7 @@
    *       concern, use GetValue() instead.
    */
   std::vector<double> GetDoubleArray(
-      wpi::span<const double> defaultValue) const;
-
-  /**
-   * Gets the entry's value as a double array. If the entry does not exist
-   * or is of different type, it will return the default value.
-   *
-   * @param defaultValue the value to be returned if no value is found
-   * @return the entry's value or the given default value
-   *
-   * @note This makes a copy of the array.  If the overhead of this is a
-   *       concern, use GetValue() instead.
-   */
-  std::vector<double> GetDoubleArray(
-      std::initializer_list<double> defaultValue) const;
+      std::span<const double> defaultValue) const;
 
   /**
    * Gets the entry's value as a string array. If the entry does not exist
@@ -224,28 +238,25 @@
    *       concern, use GetValue() instead.
    */
   std::vector<std::string> GetStringArray(
-      wpi::span<const std::string> defaultValue) const;
+      std::span<const std::string> defaultValue) const;
 
   /**
-   * Gets the entry's value as a string array. If the entry does not exist
-   * or is of different type, it will return the default value.
+   * Get an array of all value changes since the last call to ReadQueue.
    *
-   * @param defaultValue the value to be returned if no value is found
-   * @return the entry's value or the given default value
+   * The "poll storage" subscribe option can be used to set the queue depth.
    *
-   * @note This makes a copy of the array.  If the overhead of this is a
-   *       concern, use GetValue() instead.
+   * @return Array of values; empty array if no new changes have been
+   *     published since the previous call.
    */
-  std::vector<std::string> GetStringArray(
-      std::initializer_list<std::string> defaultValue) const;
+  std::vector<NetworkTableValue> ReadQueue();
 
   /**
    * Sets the entry's value if it does not exist.
    *
-   * @param value the default value to set
+   * @param defaultValue the default value to set
    * @return False if the entry exists with a different type
    */
-  bool SetDefaultValue(std::shared_ptr<Value> value);
+  bool SetDefaultValue(const Value& defaultValue);
 
   /**
    * Sets the entry's value if it does not exist.
@@ -261,6 +272,22 @@
    * @param defaultValue the default value to set
    * @return False if the entry exists with a different type
    */
+  bool SetDefaultInteger(int64_t defaultValue);
+
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  bool SetDefaultFloat(float defaultValue);
+
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
   bool SetDefaultDouble(double defaultValue);
 
   /**
@@ -277,7 +304,7 @@
    * @param defaultValue the default value to set
    * @return False if the entry exists with a different type
    */
-  bool SetDefaultRaw(std::string_view defaultValue);
+  bool SetDefaultRaw(std::span<const uint8_t> defaultValue);
 
   /**
    * Sets the entry's value if it does not exist.
@@ -285,7 +312,7 @@
    * @param defaultValue the default value to set
    * @return False if the entry exists with a different type
    */
-  bool SetDefaultBooleanArray(wpi::span<const int> defaultValue);
+  bool SetDefaultBooleanArray(std::span<const int> defaultValue);
 
   /**
    * Sets the entry's value if it does not exist.
@@ -293,7 +320,7 @@
    * @param defaultValue the default value to set
    * @return False if the entry exists with a different type
    */
-  bool SetDefaultBooleanArray(std::initializer_list<int> defaultValue);
+  bool SetDefaultIntegerArray(std::span<const int64_t> defaultValue);
 
   /**
    * Sets the entry's value if it does not exist.
@@ -301,7 +328,7 @@
    * @param defaultValue the default value to set
    * @return False if the entry exists with a different type
    */
-  bool SetDefaultDoubleArray(wpi::span<const double> defaultValue);
+  bool SetDefaultFloatArray(std::span<const float> defaultValue);
 
   /**
    * Sets the entry's value if it does not exist.
@@ -309,7 +336,7 @@
    * @param defaultValue the default value to set
    * @return False if the entry exists with a different type
    */
-  bool SetDefaultDoubleArray(std::initializer_list<double> defaultValue);
+  bool SetDefaultDoubleArray(std::span<const double> defaultValue);
 
   /**
    * Sets the entry's value if it does not exist.
@@ -317,15 +344,7 @@
    * @param defaultValue the default value to set
    * @return False if the entry exists with a different type
    */
-  bool SetDefaultStringArray(wpi::span<const std::string> defaultValue);
-
-  /**
-   * Sets the entry's value if it does not exist.
-   *
-   * @param defaultValue the default value to set
-   * @return False if the entry exists with a different type
-   */
-  bool SetDefaultStringArray(std::initializer_list<std::string> defaultValue);
+  bool SetDefaultStringArray(std::span<const std::string> defaultValue);
 
   /**
    * Sets the entry's value.
@@ -333,220 +352,132 @@
    * @param value the value to set
    * @return False if the entry exists with a different type
    */
-  bool SetValue(std::shared_ptr<Value> value);
+  bool SetValue(const Value& value);
 
   /**
    * Sets the entry's value.
    *
    * @param value the value to set
+   * @param time the timestamp to set (0 = nt::Now())
    * @return False if the entry exists with a different type
    */
-  bool SetBoolean(bool value);
+  bool SetBoolean(bool value, int64_t time = 0);
 
   /**
    * Sets the entry's value.
    *
    * @param value the value to set
+   * @param time the timestamp to set (0 = nt::Now())
    * @return False if the entry exists with a different type
    */
-  bool SetDouble(double value);
+  bool SetInteger(int64_t value, int64_t time = 0);
 
   /**
    * Sets the entry's value.
    *
    * @param value the value to set
+   * @param time the timestamp to set (0 = nt::Now())
    * @return False if the entry exists with a different type
    */
-  bool SetString(std::string_view value);
+  bool SetFloat(float value, int64_t time = 0);
 
   /**
    * Sets the entry's value.
    *
    * @param value the value to set
+   * @param time the timestamp to set (0 = nt::Now())
    * @return False if the entry exists with a different type
    */
-  bool SetRaw(std::string_view value);
+  bool SetDouble(double value, int64_t time = 0);
 
   /**
    * Sets the entry's value.
    *
    * @param value the value to set
+   * @param time the timestamp to set (0 = nt::Now())
    * @return False if the entry exists with a different type
    */
-  bool SetBooleanArray(wpi::span<const bool> value);
+  bool SetString(std::string_view value, int64_t time = 0);
 
   /**
    * Sets the entry's value.
    *
    * @param value the value to set
+   * @param time the timestamp to set (0 = nt::Now())
    * @return False if the entry exists with a different type
    */
-  bool SetBooleanArray(std::initializer_list<bool> value);
+  bool SetRaw(std::span<const uint8_t> value, int64_t time = 0);
 
   /**
    * Sets the entry's value.
    *
    * @param value the value to set
+   * @param time the timestamp to set (0 = nt::Now())
    * @return False if the entry exists with a different type
    */
-  bool SetBooleanArray(wpi::span<const int> value);
+  bool SetBooleanArray(std::span<const bool> value, int64_t time = 0);
 
   /**
    * Sets the entry's value.
    *
    * @param value the value to set
+   * @param time the timestamp to set (0 = nt::Now())
    * @return False if the entry exists with a different type
    */
-  bool SetBooleanArray(std::initializer_list<int> value);
+  bool SetBooleanArray(std::span<const int> value, int64_t time = 0);
 
   /**
    * Sets the entry's value.
    *
    * @param value the value to set
+   * @param time the timestamp to set (0 = nt::Now())
    * @return False if the entry exists with a different type
    */
-  bool SetDoubleArray(wpi::span<const double> value);
+  bool SetIntegerArray(std::span<const int64_t> value, int64_t time = 0);
 
   /**
    * Sets the entry's value.
    *
    * @param value the value to set
+   * @param time the timestamp to set (0 = nt::Now())
    * @return False if the entry exists with a different type
    */
-  bool SetDoubleArray(std::initializer_list<double> value);
+  bool SetFloatArray(std::span<const float> value, int64_t time = 0);
 
   /**
    * Sets the entry's value.
    *
    * @param value the value to set
+   * @param time the timestamp to set (0 = nt::Now())
    * @return False if the entry exists with a different type
    */
-  bool SetStringArray(wpi::span<const std::string> value);
+  bool SetDoubleArray(std::span<const double> value, int64_t time = 0);
 
   /**
    * Sets the entry's value.
    *
    * @param value the value to set
+   * @param time the timestamp to set (0 = nt::Now())
    * @return False if the entry exists with a different type
    */
-  bool SetStringArray(std::initializer_list<std::string> value);
-
-  /**
-   * Sets the entry's value.  If the value is of different type, the type is
-   * changed to match the new value.
-   *
-   * @param value the value to set
-   */
-  void ForceSetValue(std::shared_ptr<Value> value);
-
-  /**
-   * Sets the entry's value.  If the value is of different type, the type is
-   * changed to match the new value.
-   *
-   * @param value the value to set
-   */
-  void ForceSetBoolean(bool value);
-
-  /**
-   * Sets the entry's value.  If the value is of different type, the type is
-   * changed to match the new value.
-   *
-   * @param value the value to set
-   */
-  void ForceSetDouble(double value);
-
-  /**
-   * Sets the entry's value.  If the value is of different type, the type is
-   * changed to match the new value.
-   *
-   * @param value the value to set
-   */
-  void ForceSetString(std::string_view value);
-
-  /**
-   * Sets the entry's value.  If the value is of different type, the type is
-   * changed to match the new value.
-   *
-   * @param value the value to set
-   */
-  void ForceSetRaw(std::string_view value);
-
-  /**
-   * Sets the entry's value.  If the value is of different type, the type is
-   * changed to match the new value.
-   *
-   * @param value the value to set
-   */
-  void ForceSetBooleanArray(wpi::span<const bool> value);
-
-  /**
-   * Sets the entry's value.  If the value is of different type, the type is
-   * changed to match the new value.
-   *
-   * @param value the value to set
-   */
-  void ForceSetBooleanArray(std::initializer_list<bool> value);
-
-  /**
-   * Sets the entry's value.  If the value is of different type, the type is
-   * changed to match the new value.
-   *
-   * @param value the value to set
-   */
-  void ForceSetBooleanArray(wpi::span<const int> value);
-
-  /**
-   * Sets the entry's value.  If the value is of different type, the type is
-   * changed to match the new value.
-   *
-   * @param value the value to set
-   */
-  void ForceSetBooleanArray(std::initializer_list<int> value);
-
-  /**
-   * Sets the entry's value.  If the value is of different type, the type is
-   * changed to match the new value.
-   *
-   * @param value the value to set
-   */
-  void ForceSetDoubleArray(wpi::span<const double> value);
-
-  /**
-   * Sets the entry's value.  If the value is of different type, the type is
-   * changed to match the new value.
-   *
-   * @param value the value to set
-   */
-  void ForceSetDoubleArray(std::initializer_list<double> value);
-
-  /**
-   * Sets the entry's value.  If the value is of different type, the type is
-   * changed to match the new value.
-   *
-   * @param value the value to set
-   */
-  void ForceSetStringArray(wpi::span<const std::string> value);
-
-  /**
-   * Sets the entry's value.  If the value is of different type, the type is
-   * changed to match the new value.
-   *
-   * @param value the value to set
-   */
-  void ForceSetStringArray(std::initializer_list<std::string> value);
+  bool SetStringArray(std::span<const std::string> value, int64_t time = 0);
 
   /**
    * Sets flags.
    *
    * @param flags the flags to set (bitmask)
+   * @deprecated Use SetPersistent() or topic properties instead
    */
+  WPI_DEPRECATED("Use SetPersistent() or topic properties instead")
   void SetFlags(unsigned int flags);
 
   /**
    * Clears flags.
    *
    * @param flags the flags to clear (bitmask)
+   * @deprecated Use SetPersistent() or topic properties instead
    */
+  WPI_DEPRECATED("Use SetPersistent() or topic properties instead")
   void ClearFlags(unsigned int flags);
 
   /**
@@ -567,68 +498,29 @@
   bool IsPersistent() const;
 
   /**
-   * Deletes the entry.
+   * Stops publishing the entry if it's been published.
    */
+  void Unpublish();
+
+  /**
+   * Deletes the entry.
+   * @deprecated Use Unpublish() instead.
+   */
+  WPI_DEPRECATED("Use Unpublish() instead")
   void Delete();
 
   /**
-   * Create a callback-based RPC entry point.  Only valid to use on the server.
-   * The callback function will be called when the RPC is called.
-   * This function creates RPC version 0 definitions (raw data in and out).
+   * Gets the entry's topic.
    *
-   * @param callback  callback function
+   * @return Topic
    */
-  void CreateRpc(std::function<void(const RpcAnswer& answer)> callback);
-
-  /**
-   * Create a polled RPC entry point.  Only valid to use on the server.
-   * The caller is responsible for calling NetworkTableInstance::PollRpc()
-   * to poll for servicing incoming RPC calls.
-   * This function creates RPC version 0 definitions (raw data in and out).
-   */
-  void CreatePolledRpc();
-
-  /**
-   * Call a RPC function.  May be used on either the client or server.
-   * This function is non-blocking.  Either RpcCall::GetResult() or
-   * RpcCall::CancelResult() must be called on the return value to either
-   * get or ignore the result of the call.
-   *
-   * @param params      parameter
-   * @return RPC call object.
-   */
-  RpcCall CallRpc(std::string_view params);
-
-  /**
-   * Add a listener for changes to this entry.
-   *
-   * @param callback          listener to add
-   * @param flags             NotifyKind bitmask
-   * @return Listener handle
-   */
-  NT_EntryListener AddListener(
-      std::function<void(const EntryNotification& event)> callback,
-      unsigned int flags) const;
-
-  /**
-   * Remove an entry listener.
-   *
-   * @param entry_listener Listener handle to remove
-   */
-  void RemoveListener(NT_EntryListener entry_listener);
+  Topic GetTopic() const;
 
   /**
    * Equality operator.  Returns true if both instances refer to the same
    * native handle.
    */
-  bool operator==(const NetworkTableEntry& oth) const {
-    return m_handle == oth.m_handle;
-  }
-
-  /** Inequality operator. */
-  bool operator!=(const NetworkTableEntry& oth) const {
-    return !(*this == oth);
-  }
+  bool operator==(const NetworkTableEntry&) const = default;
 
  protected:
   /* Native handle */
@@ -638,5 +530,3 @@
 }  // namespace nt
 
 #include "networktables/NetworkTableEntry.inc"
-
-#endif  // NTCORE_NETWORKTABLES_NETWORKTABLEENTRY_H_
diff --git a/third_party/allwpilib/ntcore/src/main/native/include/networktables/NetworkTableEntry.inc b/third_party/allwpilib/ntcore/src/main/native/include/networktables/NetworkTableEntry.inc
index e7deb51..0b4f628 100644
--- a/third_party/allwpilib/ntcore/src/main/native/include/networktables/NetworkTableEntry.inc
+++ b/third_party/allwpilib/ntcore/src/main/native/include/networktables/NetworkTableEntry.inc
@@ -2,8 +2,7 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
-#ifndef NTCORE_NETWORKTABLES_NETWORKTABLEENTRY_INC_
-#define NTCORE_NETWORKTABLES_NETWORKTABLEENTRY_INC_
+#pragma once
 
 #include <memory>
 #include <string>
@@ -11,6 +10,8 @@
 #include <vector>
 
 #include "networktables/NetworkTableEntry.h"
+#include "ntcore_cpp.h"
+#include "ntcore_cpp_types.h"
 
 namespace nt {
 
@@ -39,307 +40,208 @@
   return GetEntryFlags(m_handle);
 }
 
-inline uint64_t NetworkTableEntry::GetLastChange() const {
+inline int64_t NetworkTableEntry::GetLastChange() const {
   return GetEntryLastChange(m_handle);
 }
 
-inline EntryInfo NetworkTableEntry::GetInfo() const {
-  return GetEntryInfo(m_handle);
-}
-
-inline std::shared_ptr<Value> NetworkTableEntry::GetValue() const {
+inline Value NetworkTableEntry::GetValue() const {
   return GetEntryValue(m_handle);
 }
 
 inline bool NetworkTableEntry::GetBoolean(bool defaultValue) const {
-  auto value = GetEntryValue(m_handle);
-  if (!value || value->type() != NT_BOOLEAN) {
-    return defaultValue;
-  }
-  return value->GetBoolean();
+  return nt::GetBoolean(m_handle, defaultValue);
+}
+
+inline int64_t NetworkTableEntry::GetInteger(int64_t defaultValue) const {
+  return nt::GetInteger(m_handle, defaultValue);
+}
+
+inline float NetworkTableEntry::GetFloat(float defaultValue) const {
+  return nt::GetFloat(m_handle, defaultValue);
 }
 
 inline double NetworkTableEntry::GetDouble(double defaultValue) const {
-  auto value = GetEntryValue(m_handle);
-  if (!value || value->type() != NT_DOUBLE) {
-    return defaultValue;
-  }
-  return value->GetDouble();
+  return nt::GetDouble(m_handle, defaultValue);
 }
 
 inline std::string NetworkTableEntry::GetString(
     std::string_view defaultValue) const {
-  auto value = GetEntryValue(m_handle);
-  if (!value || value->type() != NT_STRING) {
-    return std::string{defaultValue};
-  }
-  return std::string{value->GetString()};
+  return nt::GetString(m_handle, defaultValue);
 }
 
-inline std::string NetworkTableEntry::GetRaw(
-    std::string_view defaultValue) const {
-  auto value = GetEntryValue(m_handle);
-  if (!value || value->type() != NT_RAW) {
-    return std::string{defaultValue};
-  }
-  return std::string{value->GetRaw()};
+inline std::vector<uint8_t> NetworkTableEntry::GetRaw(
+    std::span<const uint8_t> defaultValue) const {
+  return nt::GetRaw(m_handle, defaultValue);
 }
 
 inline std::vector<int> NetworkTableEntry::GetBooleanArray(
-    wpi::span<const int> defaultValue) const {
-  auto value = GetEntryValue(m_handle);
-  if (!value || value->type() != NT_BOOLEAN_ARRAY) {
-    return {defaultValue.begin(), defaultValue.end()};
-  }
-  auto arr = value->GetBooleanArray();
-  return {arr.begin(), arr.end()};
+    std::span<const int> defaultValue) const {
+  return nt::GetBooleanArray(m_handle, defaultValue);
 }
 
-inline std::vector<int> NetworkTableEntry::GetBooleanArray(
-    std::initializer_list<int> defaultValue) const {
-  return GetBooleanArray({defaultValue.begin(), defaultValue.end()});
+inline std::vector<int64_t> NetworkTableEntry::GetIntegerArray(
+    std::span<const int64_t> defaultValue) const {
+  return nt::GetIntegerArray(m_handle, defaultValue);
+}
+
+inline std::vector<float> NetworkTableEntry::GetFloatArray(
+    std::span<const float> defaultValue) const {
+  return nt::GetFloatArray(m_handle, defaultValue);
 }
 
 inline std::vector<double> NetworkTableEntry::GetDoubleArray(
-    wpi::span<const double> defaultValue) const {
-  auto value = GetEntryValue(m_handle);
-  if (!value || value->type() != NT_DOUBLE_ARRAY) {
-    return {defaultValue.begin(), defaultValue.end()};
-  }
-  auto arr = value->GetDoubleArray();
-  return {arr.begin(), arr.end()};
-}
-
-inline std::vector<double> NetworkTableEntry::GetDoubleArray(
-    std::initializer_list<double> defaultValue) const {
-  return GetDoubleArray({defaultValue.begin(), defaultValue.end()});
+    std::span<const double> defaultValue) const {
+  return nt::GetDoubleArray(m_handle, defaultValue);
 }
 
 inline std::vector<std::string> NetworkTableEntry::GetStringArray(
-    wpi::span<const std::string> defaultValue) const {
-  auto value = GetEntryValue(m_handle);
-  if (!value || value->type() != NT_STRING_ARRAY) {
-    return {defaultValue.begin(), defaultValue.end()};
-  }
-  auto arr = value->GetStringArray();
-  return {arr.begin(), arr.end()};
+    std::span<const std::string> defaultValue) const {
+  return nt::GetStringArray(m_handle, defaultValue);
 }
 
-inline std::vector<std::string> NetworkTableEntry::GetStringArray(
-    std::initializer_list<std::string> defaultValue) const {
-  return GetStringArray({defaultValue.begin(), defaultValue.end()});
+inline std::vector<NetworkTableValue> NetworkTableEntry::ReadQueue() {
+  return nt::ReadQueueValue(m_handle);
 }
 
-inline bool NetworkTableEntry::SetDefaultValue(std::shared_ptr<Value> value) {
-  return SetDefaultEntryValue(m_handle, value);
+inline bool NetworkTableEntry::SetDefaultValue(const Value& defaultValue) {
+  return SetDefaultEntryValue(m_handle, defaultValue);
 }
 
 inline bool NetworkTableEntry::SetDefaultBoolean(bool defaultValue) {
-  return SetDefaultEntryValue(m_handle, Value::MakeBoolean(defaultValue));
+  return nt::SetDefaultBoolean(m_handle, defaultValue);
+}
+
+inline bool NetworkTableEntry::SetDefaultInteger(int64_t defaultValue) {
+  return nt::SetDefaultInteger(m_handle, defaultValue);
+}
+
+inline bool NetworkTableEntry::SetDefaultFloat(float defaultValue) {
+  return nt::SetDefaultFloat(m_handle, defaultValue);
 }
 
 inline bool NetworkTableEntry::SetDefaultDouble(double defaultValue) {
-  return SetDefaultEntryValue(m_handle, Value::MakeDouble(defaultValue));
+  return nt::SetDefaultDouble(m_handle, defaultValue);
 }
 
 inline bool NetworkTableEntry::SetDefaultString(std::string_view defaultValue) {
-  return SetDefaultEntryValue(m_handle, Value::MakeString(defaultValue));
+  return nt::SetDefaultString(m_handle, defaultValue);
 }
 
-inline bool NetworkTableEntry::SetDefaultRaw(std::string_view defaultValue) {
-  return SetDefaultEntryValue(m_handle, Value::MakeRaw(defaultValue));
+inline bool NetworkTableEntry::SetDefaultRaw(
+    std::span<const uint8_t> defaultValue) {
+  return nt::SetDefaultRaw(m_handle, defaultValue);
 }
 
 inline bool NetworkTableEntry::SetDefaultBooleanArray(
-    wpi::span<const int> defaultValue) {
-  return SetDefaultEntryValue(m_handle, Value::MakeBooleanArray(defaultValue));
+    std::span<const int> defaultValue) {
+  return nt::SetDefaultBooleanArray(m_handle, defaultValue);
 }
 
-inline bool NetworkTableEntry::SetDefaultBooleanArray(
-    std::initializer_list<int> defaultValue) {
-  return SetDefaultEntryValue(m_handle, Value::MakeBooleanArray(defaultValue));
+inline bool NetworkTableEntry::SetDefaultIntegerArray(
+    std::span<const int64_t> defaultValue) {
+  return nt::SetDefaultIntegerArray(m_handle, defaultValue);
+}
+
+inline bool NetworkTableEntry::SetDefaultFloatArray(
+    std::span<const float> defaultValue) {
+  return nt::SetDefaultFloatArray(m_handle, defaultValue);
 }
 
 inline bool NetworkTableEntry::SetDefaultDoubleArray(
-    wpi::span<const double> defaultValue) {
-  return SetDefaultEntryValue(m_handle, Value::MakeDoubleArray(defaultValue));
-}
-
-inline bool NetworkTableEntry::SetDefaultDoubleArray(
-    std::initializer_list<double> value) {
-  return SetDefaultEntryValue(m_handle, Value::MakeDoubleArray(value));
+    std::span<const double> defaultValue) {
+  return nt::SetDefaultDoubleArray(m_handle, defaultValue);
 }
 
 inline bool NetworkTableEntry::SetDefaultStringArray(
-    wpi::span<const std::string> defaultValue) {
-  return SetDefaultEntryValue(m_handle, Value::MakeStringArray(defaultValue));
+    std::span<const std::string> defaultValue) {
+  return nt::SetDefaultStringArray(m_handle, defaultValue);
 }
 
-inline bool NetworkTableEntry::SetDefaultStringArray(
-    std::initializer_list<std::string> defaultValue) {
-  return SetDefaultEntryValue(m_handle, Value::MakeStringArray(defaultValue));
-}
-
-inline bool NetworkTableEntry::SetValue(std::shared_ptr<Value> value) {
+inline bool NetworkTableEntry::SetValue(const Value& value) {
   return SetEntryValue(m_handle, value);
 }
 
-inline bool NetworkTableEntry::SetBoolean(bool value) {
-  return SetEntryValue(m_handle, Value::MakeBoolean(value));
+inline bool NetworkTableEntry::SetBoolean(bool value, int64_t time) {
+  return nt::SetBoolean(m_handle, value, time);
 }
 
-inline bool NetworkTableEntry::SetDouble(double value) {
-  return SetEntryValue(m_handle, Value::MakeDouble(value));
+inline bool NetworkTableEntry::SetInteger(int64_t value, int64_t time) {
+  return nt::SetInteger(m_handle, value, time);
 }
 
-inline bool NetworkTableEntry::SetString(std::string_view value) {
-  return SetEntryValue(m_handle, Value::MakeString(value));
+inline bool NetworkTableEntry::SetFloat(float value, int64_t time) {
+  return nt::SetFloat(m_handle, value, time);
 }
 
-inline bool NetworkTableEntry::SetRaw(std::string_view value) {
-  return SetEntryValue(m_handle, Value::MakeRaw(value));
+inline bool NetworkTableEntry::SetDouble(double value, int64_t time) {
+  return nt::SetDouble(m_handle, value, time);
 }
 
-inline bool NetworkTableEntry::SetBooleanArray(wpi::span<const bool> value) {
-  return SetEntryValue(m_handle, Value::MakeBooleanArray(value));
+inline bool NetworkTableEntry::SetString(std::string_view value, int64_t time) {
+  return nt::SetString(m_handle, value, time);
 }
 
-inline bool NetworkTableEntry::SetBooleanArray(
-    std::initializer_list<bool> value) {
-  return SetEntryValue(m_handle, Value::MakeBooleanArray(value));
+inline bool NetworkTableEntry::SetRaw(std::span<const uint8_t> value,
+                                      int64_t time) {
+  return nt::SetRaw(m_handle, value, time);
 }
 
-inline bool NetworkTableEntry::SetBooleanArray(wpi::span<const int> value) {
-  return SetEntryValue(m_handle, Value::MakeBooleanArray(value));
+inline bool NetworkTableEntry::SetBooleanArray(std::span<const bool> value,
+                                               int64_t time) {
+  return SetEntryValue(m_handle, Value::MakeBooleanArray(value, time));
 }
 
-inline bool NetworkTableEntry::SetBooleanArray(
-    std::initializer_list<int> value) {
-  return SetEntryValue(m_handle, Value::MakeBooleanArray(value));
+inline bool NetworkTableEntry::SetBooleanArray(std::span<const int> value,
+                                               int64_t time) {
+  return nt::SetBooleanArray(m_handle, value, time);
 }
 
-inline bool NetworkTableEntry::SetDoubleArray(wpi::span<const double> value) {
-  return SetEntryValue(m_handle, Value::MakeDoubleArray(value));
+inline bool NetworkTableEntry::SetIntegerArray(std::span<const int64_t> value,
+                                               int64_t time) {
+  return nt::SetIntegerArray(m_handle, value, time);
 }
 
-inline bool NetworkTableEntry::SetDoubleArray(
-    std::initializer_list<double> value) {
-  return SetEntryValue(m_handle, Value::MakeDoubleArray(value));
+inline bool NetworkTableEntry::SetFloatArray(std::span<const float> value,
+                                             int64_t time) {
+  return nt::SetFloatArray(m_handle, value, time);
+}
+
+inline bool NetworkTableEntry::SetDoubleArray(std::span<const double> value,
+                                              int64_t time) {
+  return nt::SetDoubleArray(m_handle, value, time);
 }
 
 inline bool NetworkTableEntry::SetStringArray(
-    wpi::span<const std::string> value) {
-  return SetEntryValue(m_handle, Value::MakeStringArray(value));
-}
-
-inline bool NetworkTableEntry::SetStringArray(
-    std::initializer_list<std::string> value) {
-  return SetEntryValue(m_handle, Value::MakeStringArray(value));
-}
-
-inline void NetworkTableEntry::ForceSetValue(std::shared_ptr<Value> value) {
-  SetEntryTypeValue(m_handle, value);
-}
-
-inline void NetworkTableEntry::ForceSetBoolean(bool value) {
-  SetEntryTypeValue(m_handle, Value::MakeBoolean(value));
-}
-
-inline void NetworkTableEntry::ForceSetDouble(double value) {
-  SetEntryTypeValue(m_handle, Value::MakeDouble(value));
-}
-
-inline void NetworkTableEntry::ForceSetString(std::string_view value) {
-  SetEntryTypeValue(m_handle, Value::MakeString(value));
-}
-
-inline void NetworkTableEntry::ForceSetRaw(std::string_view value) {
-  SetEntryTypeValue(m_handle, Value::MakeRaw(value));
-}
-
-inline void NetworkTableEntry::ForceSetBooleanArray(
-    wpi::span<const bool> value) {
-  SetEntryTypeValue(m_handle, Value::MakeBooleanArray(value));
-}
-
-inline void NetworkTableEntry::ForceSetBooleanArray(
-    std::initializer_list<bool> value) {
-  SetEntryTypeValue(m_handle, Value::MakeBooleanArray(value));
-}
-
-inline void NetworkTableEntry::ForceSetBooleanArray(
-    wpi::span<const int> value) {
-  SetEntryTypeValue(m_handle, Value::MakeBooleanArray(value));
-}
-
-inline void NetworkTableEntry::ForceSetBooleanArray(
-    std::initializer_list<int> value) {
-  SetEntryTypeValue(m_handle, Value::MakeBooleanArray(value));
-}
-
-inline void NetworkTableEntry::ForceSetDoubleArray(
-    wpi::span<const double> value) {
-  SetEntryTypeValue(m_handle, Value::MakeDoubleArray(value));
-}
-
-inline void NetworkTableEntry::ForceSetDoubleArray(
-    std::initializer_list<double> value) {
-  SetEntryTypeValue(m_handle, Value::MakeDoubleArray(value));
-}
-
-inline void NetworkTableEntry::ForceSetStringArray(
-    wpi::span<const std::string> value) {
-  SetEntryTypeValue(m_handle, Value::MakeStringArray(value));
-}
-
-inline void NetworkTableEntry::ForceSetStringArray(
-    std::initializer_list<std::string> value) {
-  SetEntryTypeValue(m_handle, Value::MakeStringArray(value));
+    std::span<const std::string> value, int64_t time) {
+  return nt::SetStringArray(m_handle, value, time);
 }
 
 inline void NetworkTableEntry::SetFlags(unsigned int flags) {
-  SetEntryFlags(m_handle, GetFlags() | flags);
+  SetEntryFlags(m_handle, GetEntryFlags(m_handle) | flags);
 }
 
 inline void NetworkTableEntry::ClearFlags(unsigned int flags) {
-  SetEntryFlags(m_handle, GetFlags() & ~flags);
+  SetEntryFlags(m_handle, GetEntryFlags(m_handle) & ~flags);
 }
 
 inline void NetworkTableEntry::SetPersistent() {
-  SetFlags(kPersistent);
+  nt::SetTopicPersistent(nt::GetTopicFromHandle(m_handle), true);
 }
 
 inline void NetworkTableEntry::ClearPersistent() {
-  ClearFlags(kPersistent);
+  nt::SetTopicPersistent(nt::GetTopicFromHandle(m_handle), false);
 }
 
 inline bool NetworkTableEntry::IsPersistent() const {
-  return (GetFlags() & kPersistent) != 0;
+  return nt::GetTopicPersistent(nt::GetTopicFromHandle(m_handle));
+}
+
+inline void NetworkTableEntry::Unpublish() {
+  return nt::Unpublish(m_handle);
 }
 
 inline void NetworkTableEntry::Delete() {
-  DeleteEntry(m_handle);
-}
-
-inline void NetworkTableEntry::CreateRpc(
-    std::function<void(const RpcAnswer& answer)> callback) {
-  ::nt::CreateRpc(m_handle, std::string_view("\0", 1), callback);
-}
-
-inline RpcCall NetworkTableEntry::CallRpc(std::string_view params) {
-  return RpcCall{m_handle, ::nt::CallRpc(m_handle, params)};
-}
-
-inline NT_EntryListener NetworkTableEntry::AddListener(
-    std::function<void(const EntryNotification& event)> callback,
-    unsigned int flags) const {
-  return AddEntryListener(m_handle, callback, flags);
-}
-
-inline void NetworkTableEntry::RemoveListener(NT_EntryListener entry_listener) {
-  RemoveEntryListener(entry_listener);
+  Unpublish();
 }
 
 }  // namespace nt
-
-#endif  // NTCORE_NETWORKTABLES_NETWORKTABLEENTRY_INC_
diff --git a/third_party/allwpilib/ntcore/src/main/native/include/networktables/NetworkTableInstance.h b/third_party/allwpilib/ntcore/src/main/native/include/networktables/NetworkTableInstance.h
index 54b5324..fabc634 100644
--- a/third_party/allwpilib/ntcore/src/main/native/include/networktables/NetworkTableInstance.h
+++ b/third_party/allwpilib/ntcore/src/main/native/include/networktables/NetworkTableInstance.h
@@ -2,18 +2,17 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
-#ifndef NTCORE_NETWORKTABLES_NETWORKTABLEINSTANCE_H_
-#define NTCORE_NETWORKTABLES_NETWORKTABLEINSTANCE_H_
+#pragma once
 
 #include <functional>
 #include <memory>
+#include <optional>
+#include <span>
 #include <string>
 #include <string_view>
 #include <utility>
 #include <vector>
 
-#include <wpi/span.h>
-
 #include "networktables/NetworkTable.h"
 #include "networktables/NetworkTableEntry.h"
 #include "ntcore_c.h"
@@ -21,6 +20,21 @@
 
 namespace nt {
 
+class BooleanArrayTopic;
+class BooleanTopic;
+class DoubleArrayTopic;
+class DoubleTopic;
+class FloatArrayTopic;
+class FloatTopic;
+class IntegerArrayTopic;
+class IntegerTopic;
+class MultiSubscriber;
+class RawTopic;
+class StringArrayTopic;
+class StringTopic;
+class Subscriber;
+class Topic;
+
 /**
  * NetworkTables Instance.
  *
@@ -51,9 +65,8 @@
   enum NetworkMode {
     kNetModeNone = NT_NET_MODE_NONE,
     kNetModeServer = NT_NET_MODE_SERVER,
-    kNetModeClient = NT_NET_MODE_CLIENT,
-    kNetModeStarting = NT_NET_MODE_STARTING,
-    kNetModeFailure = NT_NET_MODE_FAILURE,
+    kNetModeClient3 = NT_NET_MODE_CLIENT3,
+    kNetModeClient4 = NT_NET_MODE_CLIENT4,
     kNetModeLocal = NT_NET_MODE_LOCAL
   };
 
@@ -73,9 +86,14 @@
   };
 
   /**
-   * The default port that network tables operates on.
+   * The default port that network tables operates on for NT3.
    */
-  enum { kDefaultPort = NT_DEFAULT_PORT };
+  static constexpr unsigned int kDefaultPort3 = NT_DEFAULT_PORT3;
+
+  /**
+   * The default port that network tables operates on for NT4.
+   */
+  static constexpr unsigned int kDefaultPort4 = NT_DEFAULT_PORT4;
 
   /**
    * Construct invalid instance.
@@ -115,7 +133,7 @@
    *
    * @param inst Instance
    */
-  static void Destroy(NetworkTableInstance inst);
+  static void Destroy(NetworkTableInstance& inst);
 
   /**
    * Gets the native handle for the entry.
@@ -125,6 +143,204 @@
   NT_Inst GetHandle() const;
 
   /**
+   * Gets a "generic" (untyped) topic.
+   *
+   * @param name topic name
+   * @return Topic
+   */
+  Topic GetTopic(std::string_view name) const;
+
+  /**
+   * Gets a boolean topic.
+   *
+   * @param name topic name
+   * @return Topic
+   */
+  BooleanTopic GetBooleanTopic(std::string_view name) const;
+
+  /**
+   * Gets an integer topic.
+   *
+   * @param name topic name
+   * @return Topic
+   */
+  IntegerTopic GetIntegerTopic(std::string_view name) const;
+
+  /**
+   * Gets a float topic.
+   *
+   * @param name topic name
+   * @return Topic
+   */
+  FloatTopic GetFloatTopic(std::string_view name) const;
+
+  /**
+   * Gets a double topic.
+   *
+   * @param name topic name
+   * @return Topic
+   */
+  DoubleTopic GetDoubleTopic(std::string_view name) const;
+
+  /**
+   * Gets a string topic.
+   *
+   * @param name topic name
+   * @return Topic
+   */
+  StringTopic GetStringTopic(std::string_view name) const;
+
+  /**
+   * Gets a raw topic.
+   *
+   * @param name topic name
+   * @return Topic
+   */
+  RawTopic GetRawTopic(std::string_view name) const;
+
+  /**
+   * Gets a boolean array topic.
+   *
+   * @param name topic name
+   * @return Topic
+   */
+  BooleanArrayTopic GetBooleanArrayTopic(std::string_view name) const;
+
+  /**
+   * Gets an integer array topic.
+   *
+   * @param name topic name
+   * @return Topic
+   */
+  IntegerArrayTopic GetIntegerArrayTopic(std::string_view name) const;
+
+  /**
+   * Gets a float array topic.
+   *
+   * @param name topic name
+   * @return Topic
+   */
+  FloatArrayTopic GetFloatArrayTopic(std::string_view name) const;
+
+  /**
+   * Gets a double array topic.
+   *
+   * @param name topic name
+   * @return Topic
+   */
+  DoubleArrayTopic GetDoubleArrayTopic(std::string_view name) const;
+
+  /**
+   * Gets a string array topic.
+   *
+   * @param name topic name
+   * @return Topic
+   */
+  StringArrayTopic GetStringArrayTopic(std::string_view name) const;
+
+  /**
+   * Get Published Topics.
+   *
+   * Returns an array of topics.
+   *
+   * @return Array of topics.
+   */
+  std::vector<Topic> GetTopics();
+
+  /**
+   * Get Published Topics.
+   *
+   * Returns an array of topics.  The results are filtered by
+   * string prefix to only return a subset of all topics.
+   *
+   * @param prefix  name required prefix; only topics whose name
+   *                starts with this string are returned
+   * @return Array of topics.
+   */
+  std::vector<Topic> GetTopics(std::string_view prefix);
+
+  /**
+   * Get Published Topics.
+   *
+   * Returns an array of topics.  The results are filtered by
+   * string prefix and type to only return a subset of all topics.
+   *
+   * @param prefix  name required prefix; only topics whose name
+   *                starts with this string are returned
+   * @param types   bitmask of NT_Type values; 0 is treated specially
+   *                as a "don't care"
+   * @return Array of topics.
+   */
+  std::vector<Topic> GetTopics(std::string_view prefix, unsigned int types);
+
+  /**
+   * Get Published Topics.
+   *
+   * Returns an array of topics.  The results are filtered by
+   * string prefix and type to only return a subset of all topics.
+   *
+   * @param prefix  name required prefix; only topics whose name
+   *                starts with this string are returned
+   * @param types   array of type strings
+   * @return Array of topic handles.
+   */
+  std::vector<Topic> GetTopics(std::string_view prefix,
+                               std::span<std::string_view> types);
+
+  /**
+   * Get Topic Information about multiple topics.
+   *
+   * Returns an array of topic information (handle, name, type, and properties).
+   *
+   * @return Array of topic information.
+   */
+  std::vector<TopicInfo> GetTopicInfo();
+
+  /**
+   * Get Topic Information about multiple topics.
+   *
+   * Returns an array of topic information (handle, name, type, and properties).
+   * The results are filtered by string prefix to only
+   * return a subset of all topics.
+   *
+   * @param prefix  name required prefix; only topics whose name
+   *                starts with this string are returned
+   * @return Array of topic information.
+   */
+  std::vector<TopicInfo> GetTopicInfo(std::string_view prefix);
+
+  /**
+   * Get Topic Information about multiple topics.
+   *
+   * Returns an array of topic information (handle, name, type, and properties).
+   * The results are filtered by string prefix and type to only
+   * return a subset of all topics.
+   *
+   * @param prefix  name required prefix; only topics whose name
+   *                starts with this string are returned
+   * @param types   bitmask of NT_Type values; 0 is treated specially
+   *                as a "don't care"
+   * @return Array of topic information.
+   */
+  std::vector<TopicInfo> GetTopicInfo(std::string_view prefix,
+                                      unsigned int types);
+
+  /**
+   * Get Topic Information about multiple topics.
+   *
+   * Returns an array of topic information (handle, name, type, and properties).
+   * The results are filtered by string prefix and type to only
+   * return a subset of all topics.
+   *
+   * @param prefix  name required prefix; only topics whose name
+   *                starts with this string are returned
+   * @param types   array of type strings
+   * @return Array of topic information.
+   */
+  std::vector<TopicInfo> GetTopicInfo(std::string_view prefix,
+                                      std::span<std::string_view> types);
+
+  /**
    * Gets the entry for a key.
    *
    * @param name Key
@@ -133,34 +349,6 @@
   NetworkTableEntry GetEntry(std::string_view name);
 
   /**
-   * Get entries starting with the given prefix.
-   *
-   * The results are optionally filtered by string prefix and entry type to
-   * only return a subset of all entries.
-   *
-   * @param prefix entry name required prefix; only entries whose name
-   * starts with this string are returned
-   * @param types bitmask of types; 0 is treated as a "don't care"
-   * @return Array of entries.
-   */
-  std::vector<NetworkTableEntry> GetEntries(std::string_view prefix,
-                                            unsigned int types);
-
-  /**
-   * Get information about entries starting with the given prefix.
-   *
-   * The results are optionally filtered by string prefix and entry type to
-   * only return a subset of all entries.
-   *
-   * @param prefix entry name required prefix; only entries whose name
-   * starts with this string are returned
-   * @param types bitmask of types; 0 is treated as a "don't care"
-   * @return Array of entry information.
-   */
-  std::vector<EntryInfo> GetEntryInfo(std::string_view prefix,
-                                      unsigned int types) const;
-
-  /**
    * Gets the table with the specified key.
    *
    * @param key the key name
@@ -169,103 +357,130 @@
   std::shared_ptr<NetworkTable> GetTable(std::string_view key) const;
 
   /**
-   * Deletes ALL keys in ALL subtables (except persistent values).
-   * Use with caution!
-   */
-  void DeleteAllEntries();
-
-  /**
    * @{
-   * @name Entry Listener Functions
+   * @name Listener Functions
    */
 
   /**
-   * Add a listener for all entries starting with a certain prefix.
+   * Remove a listener.
    *
-   * @param prefix            UTF-8 string prefix
-   * @param callback          listener to add
-   * @param flags             EntryListenerFlags bitmask
-   * @return Listener handle
+   * @param listener Listener handle to remove
    */
-  NT_EntryListener AddEntryListener(
-      std::string_view prefix,
-      std::function<void(const EntryNotification& event)> callback,
-      unsigned int flags) const;
+  static void RemoveListener(NT_Listener listener);
 
   /**
-   * Remove an entry listener.
-   *
-   * @param entry_listener Listener handle to remove
-   */
-  static void RemoveEntryListener(NT_EntryListener entry_listener);
-
-  /**
-   * Wait for the entry listener queue to be empty.  This is primarily useful
-   * for deterministic testing.  This blocks until either the entry listener
-   * queue is empty (e.g. there are no more events that need to be passed along
-   * to callbacks or poll queues) or the timeout expires.
-   *
-   * @param timeout   timeout, in seconds.  Set to 0 for non-blocking behavior,
-   *                  or a negative value to block indefinitely
-   * @return False if timed out, otherwise true.
-   */
-  bool WaitForEntryListenerQueue(double timeout);
-
-  /** @} */
-
-  /**
-   * @{
-   * @name Connection Listener Functions
-   */
-
-  /**
-   * Add a connection listener.
-   *
-   * @param callback          listener to add
-   * @param immediate_notify  notify listener of all existing connections
-   * @return Listener handle
-   */
-  NT_ConnectionListener AddConnectionListener(
-      std::function<void(const ConnectionNotification& event)> callback,
-      bool immediate_notify) const;
-
-  /**
-   * Remove a connection listener.
-   *
-   * @param conn_listener Listener handle to remove
-   */
-  static void RemoveConnectionListener(NT_ConnectionListener conn_listener);
-
-  /**
-   * Wait for the connection listener queue to be empty.  This is primarily
-   * useful for deterministic testing.  This blocks until either the connection
+   * Wait for the listener queue to be empty. This is primarily
+   * useful for deterministic testing. This blocks until either the
    * listener queue is empty (e.g. there are no more events that need to be
    * passed along to callbacks or poll queues) or the timeout expires.
    *
-   * @param timeout   timeout, in seconds.  Set to 0 for non-blocking behavior,
-   *                  or a negative value to block indefinitely
+   * @param timeout timeout, in seconds. Set to 0 for non-blocking behavior, or
+   *                a negative value to block indefinitely
    * @return False if timed out, otherwise true.
    */
-  bool WaitForConnectionListenerQueue(double timeout);
-
-  /** @} */
+  bool WaitForListenerQueue(double timeout);
 
   /**
-   * @{
-   * @name Remote Procedure Call Functions
-   */
-
-  /**
-   * Wait for the incoming RPC call queue to be empty.  This is primarily useful
-   * for deterministic testing.  This blocks until either the RPC call
-   * queue is empty (e.g. there are no more events that need to be passed along
-   * to callbacks or poll queues) or the timeout expires.
+   * Add a connection listener. The callback function is called asynchronously
+   * on a separate thread, so it's important to use synchronization or atomics
+   * when accessing any shared state from the callback function.
    *
-   * @param timeout   timeout, in seconds.  Set to 0 for non-blocking behavior,
-   *                  or a negative value to block indefinitely
-   * @return False if timed out, otherwise true.
+   * @param immediate_notify  notify listener of all existing connections
+   * @param callback          listener to add
+   * @return Listener handle
    */
-  bool WaitForRpcCallQueue(double timeout);
+  NT_Listener AddConnectionListener(bool immediate_notify,
+                                    ListenerCallback callback) const;
+
+  /**
+   * Add a time synchronization listener. The callback function is called
+   * asynchronously on a separate thread, so it's important to use
+   * synchronization or atomics when accessing any shared state from the
+   * callback function.
+   *
+   * @param immediate_notify  notify listener of current time synchronization
+   *                          value
+   * @param callback          listener to add
+   * @return Listener handle
+   */
+  NT_Listener AddTimeSyncListener(bool immediate_notify,
+                                  ListenerCallback callback) const;
+
+  /**
+   * Add a listener for changes on a particular topic. The callback
+   * function is called asynchronously on a separate thread, so it's important
+   * to use synchronization or atomics when accessing any shared state from the
+   * callback function.
+   *
+   * This creates a corresponding internal subscriber with the lifetime of the
+   * listener.
+   *
+   * @param topic Topic
+   * @param eventMask Bitmask of EventFlags values
+   * @param listener Listener function
+   * @return Listener handle
+   */
+  NT_Listener AddListener(Topic topic, unsigned int eventMask,
+                          ListenerCallback listener);
+
+  /**
+   * Add a listener for changes on a subscriber. The callback
+   * function is called asynchronously on a separate thread, so it's important
+   * to use synchronization or atomics when accessing any shared state from the
+   * callback function. This does NOT keep the subscriber active.
+   *
+   * @param subscriber Subscriber
+   * @param eventMask Bitmask of EventFlags values
+   * @param listener Listener function
+   * @return Listener handle
+   */
+  NT_Listener AddListener(Subscriber& subscriber, unsigned int eventMask,
+                          ListenerCallback listener);
+
+  /**
+   * Add a listener for changes on a subscriber. The callback
+   * function is called asynchronously on a separate thread, so it's important
+   * to use synchronization or atomics when accessing any shared state from the
+   * callback function. This does NOT keep the subscriber active.
+   *
+   * @param subscriber Subscriber
+   * @param eventMask Bitmask of EventFlags values
+   * @param listener Listener function
+   * @return Listener handle
+   */
+  NT_Listener AddListener(MultiSubscriber& subscriber, int eventMask,
+                          ListenerCallback listener);
+
+  /**
+   * Add a listener for changes on an entry. The callback function
+   * is called asynchronously on a separate thread, so it's important to use
+   * synchronization or atomics when accessing any shared state from the
+   * callback function.
+   *
+   * @param entry Entry
+   * @param eventMask Bitmask of EventFlags values
+   * @param listener Listener function
+   * @return Listener handle
+   */
+  NT_Listener AddListener(const NetworkTableEntry& entry, int eventMask,
+                          ListenerCallback listener);
+
+  /**
+   * Add a listener for changes to topics with names that start with any
+   * of the given prefixes. The callback function is called asynchronously on a
+   * separate thread, so it's important to use synchronization or atomics when
+   * accessing any shared state from the callback function.
+   *
+   * This creates a corresponding internal subscriber with the lifetime of the
+   * listener.
+   *
+   * @param prefixes Topic name string prefixes
+   * @param eventMask Bitmask of EventFlags values
+   * @param listener Listener function
+   * @return Listener handle
+   */
+  NT_Listener AddListener(std::span<const std::string_view> prefixes,
+                          int eventMask, ListenerCallback listener);
 
   /** @} */
 
@@ -275,16 +490,6 @@
    */
 
   /**
-   * Set the network identity of this node.
-   *
-   * This is the name used during the initial connection handshake, and is
-   * visible through ConnectionInfo on the remote node.
-   *
-   * @param name      identity to advertise
-   */
-  void SetNetworkIdentity(std::string_view name);
-
-  /**
    * Get the current network mode.
    *
    * @return Bitmask of NetworkMode.
@@ -311,11 +516,13 @@
    *                          null terminated)
    * @param listen_address    the address to listen on, or null to listen on any
    *                          address (UTF-8 string, null terminated)
-   * @param port              port to communicate over
+   * @param port3             port to communicate over (NT3)
+   * @param port4             port to communicate over (NT4)
    */
-  void StartServer(std::string_view persist_filename = "networktables.ini",
+  void StartServer(std::string_view persist_filename = "networktables.json",
                    const char* listen_address = "",
-                   unsigned int port = kDefaultPort);
+                   unsigned int port3 = kDefaultPort3,
+                   unsigned int port4 = kDefaultPort4);
 
   /**
    * Stops the server if it is running.
@@ -323,45 +530,20 @@
   void StopServer();
 
   /**
-   * Starts a client.  Use SetServer to set the server name and port.
+   * Starts a NT3 client.  Use SetServer or SetServerTeam to set the server name
+   * and port.
+   *
+   * @param identity  network identity to advertise (cannot be empty string)
    */
-  void StartClient();
+  void StartClient3(std::string_view identity);
 
   /**
-   * Starts a client using the specified server and port
+   * Starts a NT4 client.  Use SetServer or SetServerTeam to set the server name
+   * and port.
    *
-   * @param server_name server name (UTF-8 string, null terminated)
-   * @param port        port to communicate over
+   * @param identity  network identity to advertise (cannot be empty string)
    */
-  void StartClient(const char* server_name, unsigned int port = kDefaultPort);
-
-  /**
-   * Starts a client using the specified (server, port) combinations.  The
-   * client will attempt to connect to each server in round robin fashion.
-   *
-   * @param servers   array of server name and port pairs
-   */
-  void StartClient(
-      wpi::span<const std::pair<std::string_view, unsigned int>> servers);
-
-  /**
-   * Starts a client using the specified servers and port.  The
-   * client will attempt to connect to each server in round robin fashion.
-   *
-   * @param servers   array of server names
-   * @param port      port to communicate over
-   */
-  void StartClient(wpi::span<const std::string_view> servers,
-                   unsigned int port = kDefaultPort);
-
-  /**
-   * Starts a client using commonly known robot addresses for the specified
-   * team.
-   *
-   * @param team        team number
-   * @param port        port to communicate over
-   */
-  void StartClientTeam(unsigned int team, unsigned int port = kDefaultPort);
+  void StartClient4(std::string_view identity);
 
   /**
    * Stops the client if it is running.
@@ -372,46 +554,46 @@
    * Sets server address and port for client (without restarting client).
    *
    * @param server_name server name (UTF-8 string, null terminated)
-   * @param port        port to communicate over
+   * @param port        port to communicate over (0 = default)
    */
-  void SetServer(const char* server_name, unsigned int port = kDefaultPort);
+  void SetServer(const char* server_name, unsigned int port = 0);
 
   /**
    * Sets server addresses and ports for client (without restarting client).
    * The client will attempt to connect to each server in round robin fashion.
    *
-   * @param servers   array of server name and port pairs
+   * @param servers   array of server address and port pairs
    */
   void SetServer(
-      wpi::span<const std::pair<std::string_view, unsigned int>> servers);
+      std::span<const std::pair<std::string_view, unsigned int>> servers);
 
   /**
    * Sets server addresses and port for client (without restarting client).
    * The client will attempt to connect to each server in round robin fashion.
    *
    * @param servers   array of server names
-   * @param port      port to communicate over
+   * @param port      port to communicate over (0 = default)
    */
-  void SetServer(wpi::span<const std::string_view> servers,
-                 unsigned int port = kDefaultPort);
+  void SetServer(std::span<const std::string_view> servers,
+                 unsigned int port = 0);
 
   /**
    * Sets server addresses and port for client (without restarting client).
    * Connects using commonly known robot addresses for the specified team.
    *
    * @param team        team number
-   * @param port        port to communicate over
+   * @param port        port to communicate over (0 = default)
    */
-  void SetServerTeam(unsigned int team, unsigned int port = kDefaultPort);
+  void SetServerTeam(unsigned int team, unsigned int port = 0);
 
   /**
    * Starts requesting server address from Driver Station.
    * This connects to the Driver Station running on localhost to obtain the
    * server IP address.
    *
-   * @param port server port to use in combination with IP from DS
+   * @param port server port to use in combination with IP from DS (0 = default)
    */
-  void StartDSClient(unsigned int port = kDefaultPort);
+  void StartDSClient(unsigned int port = 0);
 
   /**
    * Stops requesting server address from Driver Station.
@@ -419,12 +601,10 @@
   void StopDSClient();
 
   /**
-   * Set the periodic update rate.
-   * Sets how frequently updates are sent to other nodes over the network.
-   *
-   * @param interval update interval in seconds (range 0.01 to 1.0)
+   * Flushes all updated values immediately to the local client/server. This
+   * does not flush to the network.
    */
-  void SetUpdateRate(double interval);
+  void FlushLocal() const;
 
   /**
    * Flushes all updated values immediately to the network.
@@ -449,59 +629,64 @@
    */
   bool IsConnected() const;
 
+  /**
+   * Get the time offset between server time and local time. Add this value to
+   * local time to get the estimated equivalent server time. In server mode,
+   * this always returns 0. In client mode, this returns the time offset only if
+   * the client and server are connected and have exchanged synchronization
+   * messages. Note the time offset may change over time as it is periodically
+   * updated; to receive updates as events, add a listener to the "time sync"
+   * event.
+   *
+   * @return Time offset in microseconds (optional)
+   */
+  std::optional<int64_t> GetServerTimeOffset() const;
+
   /** @} */
 
   /**
    * @{
-   * @name File Save/Load Functions
+   * @name Data Logger Functions
    */
 
   /**
-   * Save persistent values to a file.  The server automatically does this,
-   * but this function provides a way to save persistent values in the same
-   * format to a file on either a client or a server.
+   * Starts logging entry changes to a DataLog.
    *
-   * @param filename  filename
-   * @return error string, or nullptr if successful
+   * @param log data log object; lifetime must extend until StopEntryDataLog is
+   *            called or the instance is destroyed
+   * @param prefix only store entries with names that start with this prefix;
+   *               the prefix is not included in the data log entry name
+   * @param logPrefix prefix to add to data log entry names
+   * @return Data logger handle
    */
-  const char* SavePersistent(std::string_view filename) const;
+  NT_DataLogger StartEntryDataLog(wpi::log::DataLog& log,
+                                  std::string_view prefix,
+                                  std::string_view logPrefix);
 
   /**
-   * Load persistent values from a file.  The server automatically does this
-   * at startup, but this function provides a way to restore persistent values
-   * in the same format from a file at any time on either a client or a server.
+   * Stops logging entry changes to a DataLog.
    *
-   * @param filename  filename
-   * @param warn      callback function for warnings
-   * @return error string, or nullptr if successful
+   * @param logger data logger handle
    */
-  const char* LoadPersistent(
-      std::string_view filename,
-      std::function<void(size_t line, const char* msg)> warn);
+  static void StopEntryDataLog(NT_DataLogger logger);
 
   /**
-   * Save table values to a file.  The file format used is identical to
-   * that used for SavePersistent.
+   * Starts logging connection changes to a DataLog.
    *
-   * @param filename  filename
-   * @param prefix    save only keys starting with this prefix
-   * @return error string, or nullptr if successful
+   * @param log data log object; lifetime must extend until
+   *            StopConnectionDataLog is called or the instance is destroyed
+   * @param name data log entry name
+   * @return Data logger handle
    */
-  const char* SaveEntries(std::string_view filename,
-                          std::string_view prefix) const;
+  NT_ConnectionDataLogger StartConnectionDataLog(wpi::log::DataLog& log,
+                                                 std::string_view name);
 
   /**
-   * Load table values from a file.  The file format used is identical to
-   * that used for SavePersistent / LoadPersistent.
+   * Stops logging connection changes to a DataLog.
    *
-   * @param filename  filename
-   * @param prefix    load only keys starting with this prefix
-   * @param warn      callback function for warnings
-   * @return error string, or nullptr if successful
+   * @param logger data logger handle
    */
-  const char* LoadEntries(
-      std::string_view filename, std::string_view prefix,
-      std::function<void(size_t line, const char* msg)> warn);
+  static void StopConnectionDataLog(NT_ConnectionDataLogger logger);
 
   /** @} */
 
@@ -517,32 +702,13 @@
    * log messages with level greater than or equal to minLevel and less than or
    * equal to maxLevel; messages outside this range will be silently ignored.
    *
-   * @param func        log callback function
    * @param minLevel    minimum log level
    * @param maxLevel    maximum log level
-   * @return Logger handle
+   * @param func        callback function
+   * @return Listener handle
    */
-  NT_Logger AddLogger(std::function<void(const LogMessage& msg)> func,
-                      unsigned int minLevel, unsigned int maxLevel);
-
-  /**
-   * Remove a logger.
-   *
-   * @param logger Logger handle to remove
-   */
-  static void RemoveLogger(NT_Logger logger);
-
-  /**
-   * Wait for the incoming log event queue to be empty.  This is primarily
-   * useful for deterministic testing.  This blocks until either the log event
-   * queue is empty (e.g. there are no more events that need to be passed along
-   * to callbacks or poll queues) or the timeout expires.
-   *
-   * @param timeout   timeout, in seconds.  Set to 0 for non-blocking behavior,
-   *                  or a negative value to block indefinitely
-   * @return False if timed out, otherwise true.
-   */
-  bool WaitForLoggerQueue(double timeout);
+  NT_Listener AddLogger(unsigned int minLevel, unsigned int maxLevel,
+                        ListenerCallback func);
 
   /** @} */
 
@@ -550,14 +716,7 @@
    * Equality operator.  Returns true if both instances refer to the same
    * native handle.
    */
-  bool operator==(const NetworkTableInstance& other) const {
-    return m_handle == other.m_handle;
-  }
-
-  /** Inequality operator. */
-  bool operator!=(const NetworkTableInstance& other) const {
-    return !(*this == other);
-  }
+  bool operator==(const NetworkTableInstance&) const = default;
 
  private:
   /* Native handle */
@@ -567,5 +726,3 @@
 }  // namespace nt
 
 #include "networktables/NetworkTableInstance.inc"
-
-#endif  // NTCORE_NETWORKTABLES_NETWORKTABLEINSTANCE_H_
diff --git a/third_party/allwpilib/ntcore/src/main/native/include/networktables/NetworkTableInstance.inc b/third_party/allwpilib/ntcore/src/main/native/include/networktables/NetworkTableInstance.inc
index 5cb7be0..9b712eb 100644
--- a/third_party/allwpilib/ntcore/src/main/native/include/networktables/NetworkTableInstance.inc
+++ b/third_party/allwpilib/ntcore/src/main/native/include/networktables/NetworkTableInstance.inc
@@ -2,14 +2,15 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
-#ifndef NTCORE_NETWORKTABLES_NETWORKTABLEINSTANCE_INC_
-#define NTCORE_NETWORKTABLES_NETWORKTABLEINSTANCE_INC_
+#pragma once
 
 #include <string_view>
 #include <utility>
 #include <vector>
 
 #include "networktables/NetworkTableInstance.h"
+#include "networktables/Topic.h"
+#include "ntcore_c.h"
 
 namespace nt {
 
@@ -26,9 +27,10 @@
   return NetworkTableInstance{CreateInstance()};
 }
 
-inline void NetworkTableInstance::Destroy(NetworkTableInstance inst) {
+inline void NetworkTableInstance::Destroy(NetworkTableInstance& inst) {
   if (inst.m_handle != 0) {
     DestroyInstance(inst.m_handle);
+    inst.m_handle = 0;
   }
 }
 
@@ -36,53 +38,79 @@
   return m_handle;
 }
 
+inline std::vector<Topic> NetworkTableInstance::GetTopics() {
+  auto handles = ::nt::GetTopics(m_handle, "", 0);
+  return {handles.begin(), handles.end()};
+}
+
+inline std::vector<Topic> NetworkTableInstance::GetTopics(
+    std::string_view prefix) {
+  auto handles = ::nt::GetTopics(m_handle, prefix, 0);
+  return {handles.begin(), handles.end()};
+}
+
+inline std::vector<Topic> NetworkTableInstance::GetTopics(
+    std::string_view prefix, unsigned int types) {
+  auto handles = ::nt::GetTopics(m_handle, prefix, types);
+  return {handles.begin(), handles.end()};
+}
+
+inline std::vector<Topic> NetworkTableInstance::GetTopics(
+    std::string_view prefix, std::span<std::string_view> types) {
+  auto handles = ::nt::GetTopics(m_handle, prefix, types);
+  return {handles.begin(), handles.end()};
+}
+
+inline std::vector<TopicInfo> NetworkTableInstance::GetTopicInfo() {
+  return ::nt::GetTopicInfo(m_handle, "", 0);
+}
+
+inline std::vector<TopicInfo> NetworkTableInstance::GetTopicInfo(
+    std::string_view prefix) {
+  return ::nt::GetTopicInfo(m_handle, prefix, 0);
+}
+
+inline std::vector<TopicInfo> NetworkTableInstance::GetTopicInfo(
+    std::string_view prefix, unsigned int types) {
+  return ::nt::GetTopicInfo(m_handle, prefix, types);
+}
+
+inline std::vector<TopicInfo> NetworkTableInstance::GetTopicInfo(
+    std::string_view prefix, std::span<std::string_view> types) {
+  return ::nt::GetTopicInfo(m_handle, prefix, types);
+}
+
 inline NetworkTableEntry NetworkTableInstance::GetEntry(std::string_view name) {
   return NetworkTableEntry{::nt::GetEntry(m_handle, name)};
 }
 
-inline std::vector<NetworkTableEntry> NetworkTableInstance::GetEntries(
-    std::string_view prefix, unsigned int types) {
-  std::vector<NetworkTableEntry> entries;
-  for (auto entry : ::nt::GetEntries(m_handle, prefix, types)) {
-    entries.emplace_back(entry);
-  }
-  return entries;
+inline bool NetworkTableInstance::WaitForListenerQueue(double timeout) {
+  return ::nt::WaitForListenerQueue(m_handle, timeout);
 }
 
-inline std::vector<EntryInfo> NetworkTableInstance::GetEntryInfo(
-    std::string_view prefix, unsigned int types) const {
-  return ::nt::GetEntryInfo(m_handle, prefix, types);
+inline void NetworkTableInstance::RemoveListener(NT_Listener listener) {
+  ::nt::RemoveListener(listener);
 }
 
-inline void NetworkTableInstance::DeleteAllEntries() {
-  ::nt::DeleteAllEntries(m_handle);
+inline NT_Listener NetworkTableInstance::AddConnectionListener(
+    bool immediate_notify, ListenerCallback callback) const {
+  return ::nt::AddListener(
+      m_handle,
+      NT_EVENT_CONNECTION | (immediate_notify ? NT_EVENT_IMMEDIATE : 0),
+      std::move(callback));
 }
 
-inline void NetworkTableInstance::RemoveEntryListener(
-    NT_EntryListener entry_listener) {
-  ::nt::RemoveEntryListener(entry_listener);
+inline NT_Listener NetworkTableInstance::AddTimeSyncListener(
+    bool immediate_notify, ListenerCallback callback) const {
+  return ::nt::AddListener(
+      m_handle, NT_EVENT_TIMESYNC | (immediate_notify ? NT_EVENT_IMMEDIATE : 0),
+      std::move(callback));
 }
 
-inline bool NetworkTableInstance::WaitForEntryListenerQueue(double timeout) {
-  return ::nt::WaitForEntryListenerQueue(m_handle, timeout);
-}
-
-inline void NetworkTableInstance::RemoveConnectionListener(
-    NT_ConnectionListener conn_listener) {
-  ::nt::RemoveConnectionListener(conn_listener);
-}
-
-inline bool NetworkTableInstance::WaitForConnectionListenerQueue(
-    double timeout) {
-  return ::nt::WaitForConnectionListenerQueue(m_handle, timeout);
-}
-
-inline bool NetworkTableInstance::WaitForRpcCallQueue(double timeout) {
-  return ::nt::WaitForRpcCallQueue(m_handle, timeout);
-}
-
-inline void NetworkTableInstance::SetNetworkIdentity(std::string_view name) {
-  ::nt::SetNetworkIdentity(m_handle, name);
+inline NT_Listener NetworkTableInstance::AddListener(
+    std::span<const std::string_view> prefixes, int eventMask,
+    ListenerCallback listener) {
+  return ::nt::AddListener(m_handle, prefixes, eventMask, std::move(listener));
 }
 
 inline unsigned int NetworkTableInstance::GetNetworkMode() const {
@@ -99,31 +127,21 @@
 
 inline void NetworkTableInstance::StartServer(std::string_view persist_filename,
                                               const char* listen_address,
-                                              unsigned int port) {
-  ::nt::StartServer(m_handle, persist_filename, listen_address, port);
+                                              unsigned int port3,
+                                              unsigned int port4) {
+  ::nt::StartServer(m_handle, persist_filename, listen_address, port3, port4);
 }
 
 inline void NetworkTableInstance::StopServer() {
   ::nt::StopServer(m_handle);
 }
 
-inline void NetworkTableInstance::StartClient() {
-  ::nt::StartClient(m_handle);
+inline void NetworkTableInstance::StartClient3(std::string_view identity) {
+  ::nt::StartClient3(m_handle, identity);
 }
 
-inline void NetworkTableInstance::StartClient(const char* server_name,
-                                              unsigned int port) {
-  ::nt::StartClient(m_handle, server_name, port);
-}
-
-inline void NetworkTableInstance::StartClient(
-    wpi::span<const std::pair<std::string_view, unsigned int>> servers) {
-  ::nt::StartClient(m_handle, servers);
-}
-
-inline void NetworkTableInstance::StartClientTeam(unsigned int team,
-                                                  unsigned int port) {
-  ::nt::StartClientTeam(m_handle, team, port);
+inline void NetworkTableInstance::StartClient4(std::string_view identity) {
+  ::nt::StartClient4(m_handle, identity);
 }
 
 inline void NetworkTableInstance::StopClient() {
@@ -136,7 +154,7 @@
 }
 
 inline void NetworkTableInstance::SetServer(
-    wpi::span<const std::pair<std::string_view, unsigned int>> servers) {
+    std::span<const std::pair<std::string_view, unsigned int>> servers) {
   ::nt::SetServer(m_handle, servers);
 }
 
@@ -153,8 +171,8 @@
   ::nt::StopDSClient(m_handle);
 }
 
-inline void NetworkTableInstance::SetUpdateRate(double interval) {
-  ::nt::SetUpdateRate(m_handle, interval);
+inline void NetworkTableInstance::FlushLocal() const {
+  ::nt::FlushLocal(m_handle);
 }
 
 inline void NetworkTableInstance::Flush() const {
@@ -170,42 +188,35 @@
   return ::nt::IsConnected(m_handle);
 }
 
-inline const char* NetworkTableInstance::SavePersistent(
-    std::string_view filename) const {
-  return ::nt::SavePersistent(m_handle, filename);
+inline std::optional<int64_t> NetworkTableInstance::GetServerTimeOffset()
+    const {
+  return ::nt::GetServerTimeOffset(m_handle);
 }
 
-inline const char* NetworkTableInstance::LoadPersistent(
-    std::string_view filename,
-    std::function<void(size_t line, const char* msg)> warn) {
-  return ::nt::LoadPersistent(m_handle, filename, warn);
+inline NT_DataLogger NetworkTableInstance::StartEntryDataLog(
+    wpi::log::DataLog& log, std::string_view prefix,
+    std::string_view logPrefix) {
+  return ::nt::StartEntryDataLog(m_handle, log, prefix, logPrefix);
 }
 
-inline const char* NetworkTableInstance::SaveEntries(
-    std::string_view filename, std::string_view prefix) const {
-  return ::nt::SaveEntries(m_handle, filename, prefix);
+inline void NetworkTableInstance::StopEntryDataLog(NT_DataLogger logger) {
+  ::nt::StopEntryDataLog(logger);
 }
 
-inline const char* NetworkTableInstance::LoadEntries(
-    std::string_view filename, std::string_view prefix,
-    std::function<void(size_t line, const char* msg)> warn) {
-  return ::nt::LoadEntries(m_handle, filename, prefix, warn);
+inline NT_ConnectionDataLogger NetworkTableInstance::StartConnectionDataLog(
+    wpi::log::DataLog& log, std::string_view name) {
+  return ::nt::StartConnectionDataLog(m_handle, log, name);
 }
 
-inline NT_Logger NetworkTableInstance::AddLogger(
-    std::function<void(const LogMessage& msg)> func, unsigned int min_level,
-    unsigned int max_level) {
-  return ::nt::AddLogger(m_handle, func, min_level, max_level);
+inline void NetworkTableInstance::StopConnectionDataLog(
+    NT_ConnectionDataLogger logger) {
+  ::nt::StopConnectionDataLog(logger);
 }
 
-inline void NetworkTableInstance::RemoveLogger(NT_Logger logger) {
-  ::nt::RemoveLogger(logger);
-}
-
-inline bool NetworkTableInstance::WaitForLoggerQueue(double timeout) {
-  return ::nt::WaitForLoggerQueue(m_handle, timeout);
+inline NT_Listener NetworkTableInstance::AddLogger(unsigned int min_level,
+                                                   unsigned int max_level,
+                                                   ListenerCallback func) {
+  return ::nt::AddLogger(m_handle, min_level, max_level, std::move(func));
 }
 
 }  // namespace nt
-
-#endif  // NTCORE_NETWORKTABLES_NETWORKTABLEINSTANCE_INC_
diff --git a/third_party/allwpilib/ntcore/src/main/native/include/networktables/NetworkTableListener.h b/third_party/allwpilib/ntcore/src/main/native/include/networktables/NetworkTableListener.h
new file mode 100644
index 0000000..1a8cf1f
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/include/networktables/NetworkTableListener.h
@@ -0,0 +1,312 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <functional>
+#include <span>
+#include <string_view>
+#include <vector>
+
+#include "ntcore_cpp.h"
+
+namespace nt {
+
+class MultiSubscriber;
+class NetworkTableEntry;
+class NetworkTableInstance;
+class Subscriber;
+class Topic;
+
+/**
+ * Event listener. This calls back to a callback function when an event
+ * matching the specified mask occurs. The callback function is called
+ * asynchronously on a separate thread, so it's important to use synchronization
+ * or atomics when accessing any shared state from the callback function.
+ */
+class NetworkTableListener final {
+ public:
+  NetworkTableListener() = default;
+
+  /**
+   * Create a listener for changes to topics with names that start with any of
+   * the given prefixes. This creates a corresponding internal subscriber with
+   * the lifetime of the listener.
+   *
+   * @param inst Instance
+   * @param prefixes Topic name string prefixes
+   * @param mask Bitmask of EventFlags values
+   * @param listener Listener function
+   * @return Listener
+   */
+  static NetworkTableListener CreateListener(
+      NetworkTableInstance inst, std::span<const std::string_view> prefixes,
+      unsigned int mask, ListenerCallback listener);
+
+  /**
+   * Create a listener for changes on a particular topic. This creates a
+   * corresponding internal subscriber with the lifetime of the listener.
+   *
+   * @param topic Topic
+   * @param mask Bitmask of EventFlags values
+   * @param listener Listener function
+   * @return Listener
+   */
+  static NetworkTableListener CreateListener(Topic topic, unsigned int mask,
+                                             ListenerCallback listener);
+
+  /**
+   * Create a listener for topic changes on a subscriber. This does NOT keep the
+   * subscriber active.
+   *
+   * @param subscriber Subscriber
+   * @param mask Bitmask of EventFlags values
+   * @param listener Listener function
+   * @return Listener
+   */
+  static NetworkTableListener CreateListener(Subscriber& subscriber,
+                                             unsigned int mask,
+                                             ListenerCallback listener);
+
+  /**
+   * Create a listener for topic changes on a subscriber. This does NOT keep the
+   * subscriber active.
+   *
+   * @param subscriber Subscriber
+   * @param mask Bitmask of EventFlags values
+   * @param listener Listener function
+   * @return Listener
+   */
+  static NetworkTableListener CreateListener(MultiSubscriber& subscriber,
+                                             unsigned int mask,
+                                             ListenerCallback listener);
+
+  /**
+   * Create a listener for topic changes on an entry.
+   *
+   * @param entry Entry
+   * @param mask Bitmask of EventFlags values
+   * @param listener Listener function
+   * @return Listener
+   */
+  static NetworkTableListener CreateListener(NetworkTableEntry& entry,
+                                             unsigned int mask,
+                                             ListenerCallback listener);
+
+  /**
+   * Create a connection listener.
+   *
+   * @param inst              instance
+   * @param immediate_notify  notify listener of all existing connections
+   * @param listener          listener function
+   * @return Listener
+   */
+  static NetworkTableListener CreateConnectionListener(
+      NetworkTableInstance inst, bool immediate_notify,
+      ListenerCallback listener);
+
+  /**
+   * Create a time synchronization listener.
+   *
+   * @param inst              instance
+   * @param immediate_notify  notify listener of current time synchronization
+   *                          value
+   * @param listener          listener function
+   * @return Listener
+   */
+  static NetworkTableListener CreateTimeSyncListener(NetworkTableInstance inst,
+                                                     bool immediate_notify,
+                                                     ListenerCallback listener);
+
+  /**
+   * Create a listener for log messages.  By default, log messages are sent to
+   * stderr; this function sends log messages with the specified levels to the
+   * provided callback function instead.  The callback function will only be
+   * called for log messages with level greater than or equal to minLevel and
+   * less than or equal to maxLevel; messages outside this range will be
+   * silently ignored.
+   *
+   * @param inst        instance
+   * @param minLevel    minimum log level
+   * @param maxLevel    maximum log level
+   * @param listener    listener function
+   * @return Listener
+   */
+  static NetworkTableListener CreateLogger(NetworkTableInstance inst,
+                                           unsigned int minLevel,
+                                           unsigned int maxLevel,
+                                           ListenerCallback listener);
+
+  NetworkTableListener(const NetworkTableListener&) = delete;
+  NetworkTableListener& operator=(const NetworkTableListener&) = delete;
+  NetworkTableListener(NetworkTableListener&& rhs);
+  NetworkTableListener& operator=(NetworkTableListener&& rhs);
+  ~NetworkTableListener();
+
+  explicit operator bool() const { return m_handle != 0; }
+
+  /**
+   * Gets the native handle.
+   *
+   * @return Handle
+   */
+  NT_Listener GetHandle() const { return m_handle; }
+
+  /**
+   * Wait for the listener queue to be empty. This is primarily useful for
+   * deterministic testing. This blocks until either the listener queue is
+   * empty (e.g. there are no more events that need to be passed along to
+   * callbacks or poll queues) or the timeout expires.
+   *
+   * @param timeout timeout, in seconds. Set to 0 for non-blocking behavior, or
+   *                a negative value to block indefinitely
+   * @return False if timed out, otherwise true.
+   */
+  bool WaitForQueue(double timeout);
+
+ private:
+  explicit NetworkTableListener(NT_Listener handle) : m_handle{handle} {}
+
+  NT_Listener m_handle{0};
+};
+
+/**
+ * Event polled listener. This queues events matching the specified mask. Code
+ * using the listener must periodically call ReadQueue() to read the
+ * events.
+ */
+class NetworkTableListenerPoller final {
+ public:
+  NetworkTableListenerPoller() = default;
+
+  /**
+   * Construct a listener poller.
+   *
+   * @param inst Instance
+   */
+  explicit NetworkTableListenerPoller(NetworkTableInstance inst);
+
+  NetworkTableListenerPoller(const NetworkTableListenerPoller&) = delete;
+  NetworkTableListenerPoller& operator=(const NetworkTableListenerPoller&) =
+      delete;
+  NetworkTableListenerPoller(NetworkTableListenerPoller&& rhs);
+  NetworkTableListenerPoller& operator=(NetworkTableListenerPoller&& rhs);
+  ~NetworkTableListenerPoller();
+
+  explicit operator bool() const { return m_handle != 0; }
+
+  /**
+   * Gets the native handle.
+   *
+   * @return Handle
+   */
+  NT_ListenerPoller GetHandle() const { return m_handle; }
+
+  /**
+   * Start listening to topic changes for topics with names that start with any
+   * of the given prefixes. This creates a corresponding internal subscriber
+   * with the lifetime of the listener.
+   *
+   * @param prefixes Topic name string prefixes
+   * @param mask Bitmask of EventFlags values
+   * @return Listener handle
+   */
+  NT_Listener AddListener(std::span<const std::string_view> prefixes,
+                          unsigned int mask);
+
+  /**
+   * Start listening to changes to a particular topic. This creates a
+   * corresponding internal subscriber with the lifetime of the listener.
+   *
+   * @param topic Topic
+   * @param mask Bitmask of EventFlags values
+   * @return Listener handle
+   */
+  NT_Listener AddListener(Topic topic, unsigned int mask);
+
+  /**
+   * Start listening to topic changes on a subscriber. This does NOT keep the
+   * subscriber active.
+   *
+   * @param subscriber Subscriber
+   * @param mask Bitmask of EventFlags values
+   * @return Listener handle
+   */
+  NT_Listener AddListener(Subscriber& subscriber, unsigned int mask);
+
+  /**
+   * Start listening to topic changes on a subscriber. This does NOT keep the
+   * subscriber active.
+   *
+   * @param subscriber Subscriber
+   * @param mask Bitmask of EventFlags values
+   * @return Listener handle
+   */
+  NT_Listener AddListener(MultiSubscriber& subscriber, unsigned int mask);
+
+  /**
+   * Start listening to topic changes on an entry.
+   *
+   * @param entry Entry
+   * @param mask Bitmask of EventFlags values
+   * @return Listener handle
+   */
+  NT_Listener AddListener(NetworkTableEntry& entry, unsigned int mask);
+
+  /**
+   * Add a connection listener. The callback function is called asynchronously
+   * on a separate thread, so it's important to use synchronization or atomics
+   * when accessing any shared state from the callback function.
+   *
+   * @param immediate_notify  notify listener of all existing connections
+   * @return Listener handle
+   */
+  NT_Listener AddConnectionListener(bool immediate_notify);
+
+  /**
+   * Add a time synchronization listener. The callback function is called
+   * asynchronously on a separate thread, so it's important to use
+   * synchronization or atomics when accessing any shared state from the
+   * callback function.
+   *
+   * @param immediate_notify  notify listener of current time synchronization
+   *                          value
+   * @return Listener handle
+   */
+  NT_Listener AddTimeSyncListener(bool immediate_notify);
+
+  /**
+   * Add logger callback function.  By default, log messages are sent to stderr;
+   * this function sends log messages with the specified levels to the provided
+   * callback function instead.  The callback function will only be called for
+   * log messages with level greater than or equal to minLevel and less than or
+   * equal to maxLevel; messages outside this range will be silently ignored.
+   *
+   * @param minLevel    minimum log level
+   * @param maxLevel    maximum log level
+   * @return Listener handle
+   */
+  NT_Listener AddLogger(unsigned int minLevel, unsigned int maxLevel);
+
+  /**
+   * Remove a listener.
+   *
+   * @param listener Listener handle
+   */
+  void RemoveListener(NT_Listener listener);
+
+  /**
+   * Read events.
+   *
+   * @return Events since the previous call to ReadQueue()
+   */
+  std::vector<Event> ReadQueue();
+
+ private:
+  NT_ListenerPoller m_handle{0};
+};
+
+}  // namespace nt
+
+#include "NetworkTableListener.inc"
diff --git a/third_party/allwpilib/ntcore/src/main/native/include/networktables/NetworkTableListener.inc b/third_party/allwpilib/ntcore/src/main/native/include/networktables/NetworkTableListener.inc
new file mode 100644
index 0000000..5453d87
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/include/networktables/NetworkTableListener.inc
@@ -0,0 +1,184 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <span>
+#include <string_view>
+#include <utility>
+#include <vector>
+
+#include "networktables/MultiSubscriber.h"
+#include "networktables/NetworkTableEntry.h"
+#include "networktables/NetworkTableInstance.h"
+#include "networktables/NetworkTableListener.h"
+#include "networktables/Topic.h"
+#include "ntcore_cpp.h"
+
+namespace nt {
+
+inline NetworkTableListener NetworkTableListener::CreateListener(
+    NetworkTableInstance inst, std::span<const std::string_view> prefixes,
+    unsigned int mask, ListenerCallback listener) {
+  return NetworkTableListener{
+      ::nt::AddListener(inst.GetHandle(), prefixes, mask, std::move(listener))};
+}
+
+inline NetworkTableListener NetworkTableListener::CreateListener(
+    Topic topic, unsigned int mask, ListenerCallback listener) {
+  return NetworkTableListener{
+      nt::AddListener(topic.GetHandle(), mask, std::move(listener))};
+}
+
+inline NetworkTableListener NetworkTableListener::CreateListener(
+    Subscriber& subscriber, unsigned int mask, ListenerCallback listener) {
+  return NetworkTableListener{
+      ::nt::AddListener(subscriber.GetHandle(), mask, std::move(listener))};
+}
+
+inline NetworkTableListener NetworkTableListener::CreateListener(
+    MultiSubscriber& subscriber, unsigned int mask, ListenerCallback listener) {
+  return NetworkTableListener{
+      ::nt::AddListener(subscriber.GetHandle(), mask, std::move(listener))};
+}
+
+inline NetworkTableListener NetworkTableListener::CreateListener(
+    NetworkTableEntry& entry, unsigned int mask, ListenerCallback listener) {
+  return NetworkTableListener{
+      ::nt::AddListener(entry.GetHandle(), mask, std::move(listener))};
+}
+
+inline NetworkTableListener NetworkTableListener::CreateConnectionListener(
+    NetworkTableInstance inst, bool immediate_notify,
+    ListenerCallback listener) {
+  return NetworkTableListener{::nt::AddListener(
+      inst.GetHandle(),
+      NT_EVENT_CONNECTION | (immediate_notify ? NT_EVENT_IMMEDIATE : 0),
+      std::move(listener))};
+}
+
+inline NetworkTableListener NetworkTableListener::CreateTimeSyncListener(
+    NetworkTableInstance inst, bool immediate_notify,
+    ListenerCallback listener) {
+  return NetworkTableListener{::nt::AddListener(
+      inst.GetHandle(),
+      NT_EVENT_TIMESYNC | (immediate_notify ? NT_EVENT_IMMEDIATE : 0),
+      std::move(listener))};
+}
+
+inline NetworkTableListener NetworkTableListener::CreateLogger(
+    NetworkTableInstance inst, unsigned int minLevel, unsigned int maxLevel,
+    ListenerCallback listener) {
+  return NetworkTableListener{::nt::AddLogger(inst.GetHandle(), minLevel,
+                                              maxLevel, std::move(listener))};
+}
+
+inline NetworkTableListener::NetworkTableListener(NetworkTableListener&& rhs)
+    : m_handle(rhs.m_handle) {
+  rhs.m_handle = 0;
+}
+
+inline NetworkTableListener& NetworkTableListener::operator=(
+    NetworkTableListener&& rhs) {
+  if (m_handle != 0) {
+    nt::RemoveListener(m_handle);
+  }
+  m_handle = rhs.m_handle;
+  rhs.m_handle = 0;
+  return *this;
+}
+
+inline NetworkTableListener::~NetworkTableListener() {
+  if (m_handle != 0) {
+    nt::RemoveListener(m_handle);
+  }
+}
+
+inline bool NetworkTableListener::WaitForQueue(double timeout) {
+  if (m_handle != 0) {
+    return nt::WaitForListenerQueue(m_handle, timeout);
+  } else {
+    return false;
+  }
+}
+
+inline NetworkTableListenerPoller::NetworkTableListenerPoller(
+    NetworkTableInstance inst)
+    : m_handle(nt::CreateListenerPoller(inst.GetHandle())) {}
+
+inline NetworkTableListenerPoller::NetworkTableListenerPoller(
+    NetworkTableListenerPoller&& rhs)
+    : m_handle(rhs.m_handle) {
+  rhs.m_handle = 0;
+}
+
+inline NetworkTableListenerPoller& NetworkTableListenerPoller::operator=(
+    NetworkTableListenerPoller&& rhs) {
+  if (m_handle != 0) {
+    nt::DestroyListenerPoller(m_handle);
+  }
+  m_handle = rhs.m_handle;
+  rhs.m_handle = 0;
+  return *this;
+}
+
+inline NetworkTableListenerPoller::~NetworkTableListenerPoller() {
+  if (m_handle != 0) {
+    nt::DestroyListenerPoller(m_handle);
+  }
+}
+
+inline NT_Listener NetworkTableListenerPoller::AddListener(
+    std::span<const std::string_view> prefixes, unsigned int mask) {
+  return nt::AddPolledListener(m_handle, prefixes, mask);
+}
+
+inline NT_Listener NetworkTableListenerPoller::AddListener(Topic topic,
+                                                           unsigned int mask) {
+  return ::nt::AddPolledListener(m_handle, topic.GetHandle(), mask);
+}
+
+inline NT_Listener NetworkTableListenerPoller::AddListener(
+    Subscriber& subscriber, unsigned int mask) {
+  return ::nt::AddPolledListener(m_handle, subscriber.GetHandle(), mask);
+}
+
+inline NT_Listener NetworkTableListenerPoller::AddListener(
+    MultiSubscriber& subscriber, unsigned int mask) {
+  return ::nt::AddPolledListener(m_handle, subscriber.GetHandle(), mask);
+}
+
+inline NT_Listener NetworkTableListenerPoller::AddListener(
+    NetworkTableEntry& entry, unsigned int mask) {
+  return ::nt::AddPolledListener(m_handle, entry.GetHandle(), mask);
+}
+
+inline NT_Listener NetworkTableListenerPoller::AddConnectionListener(
+    bool immediate_notify) {
+  return ::nt::AddPolledListener(
+      m_handle, ::nt::GetInstanceFromHandle(m_handle),
+      NT_EVENT_CONNECTION | (immediate_notify ? NT_EVENT_IMMEDIATE : 0));
+}
+
+inline NT_Listener NetworkTableListenerPoller::AddTimeSyncListener(
+    bool immediate_notify) {
+  return ::nt::AddPolledListener(
+      m_handle, ::nt::GetInstanceFromHandle(m_handle),
+      NT_EVENT_TIMESYNC | (immediate_notify ? NT_EVENT_IMMEDIATE : 0));
+}
+
+inline NT_Listener NetworkTableListenerPoller::AddLogger(
+    unsigned int minLevel, unsigned int maxLevel) {
+  return ::nt::AddPolledLogger(m_handle, minLevel, maxLevel);
+}
+
+inline void NetworkTableListenerPoller::RemoveListener(NT_Listener listener) {
+  ::nt::RemoveListener(listener);
+}
+
+inline std::vector<Event> NetworkTableListenerPoller::ReadQueue() {
+  return ::nt::ReadListenerQueue(m_handle);
+}
+
+}  // namespace nt
diff --git a/third_party/allwpilib/ntcore/src/main/native/include/networktables/NetworkTableType.h b/third_party/allwpilib/ntcore/src/main/native/include/networktables/NetworkTableType.h
index d7681f2..4b60454 100644
--- a/third_party/allwpilib/ntcore/src/main/native/include/networktables/NetworkTableType.h
+++ b/third_party/allwpilib/ntcore/src/main/native/include/networktables/NetworkTableType.h
@@ -2,8 +2,7 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
-#ifndef NTCORE_NETWORKTABLES_NETWORKTABLETYPE_H_
-#define NTCORE_NETWORKTABLES_NETWORKTABLETYPE_H_
+#pragma once
 
 #include "ntcore_c.h"
 
@@ -22,9 +21,10 @@
   kBooleanArray = NT_BOOLEAN_ARRAY,
   kDoubleArray = NT_DOUBLE_ARRAY,
   kStringArray = NT_STRING_ARRAY,
-  kRpc = NT_RPC
+  kInteger = NT_INTEGER,
+  kFloat = NT_FLOAT,
+  kIntegerArray = NT_INTEGER_ARRAY,
+  kFloatArray = NT_FLOAT_ARRAY
 };
 
 }  // namespace nt
-
-#endif  // NTCORE_NETWORKTABLES_NETWORKTABLETYPE_H_
diff --git a/third_party/allwpilib/ntcore/src/main/native/include/networktables/NetworkTableValue.h b/third_party/allwpilib/ntcore/src/main/native/include/networktables/NetworkTableValue.h
index fcb9cb5..673a833 100644
--- a/third_party/allwpilib/ntcore/src/main/native/include/networktables/NetworkTableValue.h
+++ b/third_party/allwpilib/ntcore/src/main/native/include/networktables/NetworkTableValue.h
@@ -2,22 +2,20 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
-#ifndef NTCORE_NETWORKTABLES_NETWORKTABLEVALUE_H_
-#define NTCORE_NETWORKTABLES_NETWORKTABLEVALUE_H_
+#pragma once
 
 #include <stdint.h>
 
 #include <cassert>
 #include <initializer_list>
 #include <memory>
+#include <span>
 #include <string>
 #include <string_view>
 #include <type_traits>
 #include <utility>
 #include <vector>
 
-#include <wpi/span.h>
-
 #include "ntcore_c.h"
 
 namespace nt {
@@ -31,8 +29,10 @@
 
  public:
   Value();
-  Value(NT_Type type, uint64_t time, const private_init&);
-  ~Value();
+  Value(NT_Type type, int64_t time, const private_init&);
+  Value(NT_Type type, int64_t time, int64_t serverTime, const private_init&);
+
+  explicit operator bool() const { return m_val.type != NT_UNASSIGNED; }
 
   /**
    * Get the data type.
@@ -49,18 +49,39 @@
   const NT_Value& value() const { return m_val; }
 
   /**
-   * Get the creation time of the value.
+   * Get the creation time of the value, in local time.
    *
    * @return The time, in the units returned by nt::Now().
    */
-  uint64_t last_change() const { return m_val.last_change; }
+  int64_t last_change() const { return m_val.last_change; }
 
   /**
-   * Get the creation time of the value.
+   * Get the creation time of the value, in local time.
    *
    * @return The time, in the units returned by nt::Now().
    */
-  uint64_t time() const { return m_val.last_change; }
+  int64_t time() const { return m_val.last_change; }
+
+  /**
+   * Set the local creation time of the value.
+   *
+   * @param time The time.
+   */
+  void SetTime(int64_t time) { m_val.last_change = time; }
+
+  /**
+   * Get the creation time of the value, in server time.
+   *
+   * @return The server time.
+   */
+  int64_t server_time() const { return m_val.server_time; }
+
+  /**
+   * Set the creation time of the value, in server time.
+   *
+   * @param time The server time.
+   */
+  void SetServerTime(int64_t time) { m_val.server_time = time; }
 
   /**
    * @{
@@ -82,6 +103,20 @@
   bool IsBoolean() const { return m_val.type == NT_BOOLEAN; }
 
   /**
+   * Determine if entry value contains an integer.
+   *
+   * @return True if the entry value is of integer type.
+   */
+  bool IsInteger() const { return m_val.type == NT_INTEGER; }
+
+  /**
+   * Determine if entry value contains a float.
+   *
+   * @return True if the entry value is of float type.
+   */
+  bool IsFloat() const { return m_val.type == NT_FLOAT; }
+
+  /**
    * Determine if entry value contains a double.
    *
    * @return True if the entry value is of double type.
@@ -103,13 +138,6 @@
   bool IsRaw() const { return m_val.type == NT_RAW; }
 
   /**
-   * Determine if entry value contains a rpc definition.
-   *
-   * @return True if the entry value is of rpc definition type.
-   */
-  bool IsRpc() const { return m_val.type == NT_RPC; }
-
-  /**
    * Determine if entry value contains a boolean array.
    *
    * @return True if the entry value is of boolean array type.
@@ -117,6 +145,20 @@
   bool IsBooleanArray() const { return m_val.type == NT_BOOLEAN_ARRAY; }
 
   /**
+   * Determine if entry value contains an integer array.
+   *
+   * @return True if the entry value is of integer array type.
+   */
+  bool IsIntegerArray() const { return m_val.type == NT_INTEGER_ARRAY; }
+
+  /**
+   * Determine if entry value contains a float array.
+   *
+   * @return True if the entry value is of float array type.
+   */
+  bool IsFloatArray() const { return m_val.type == NT_FLOAT_ARRAY; }
+
+  /**
    * Determine if entry value contains a double array.
    *
    * @return True if the entry value is of double array type.
@@ -148,6 +190,26 @@
   }
 
   /**
+   * Get the entry's integer value.
+   *
+   * @return The integer value.
+   */
+  int64_t GetInteger() const {
+    assert(m_val.type == NT_INTEGER);
+    return m_val.data.v_int;
+  }
+
+  /**
+   * Get the entry's float value.
+   *
+   * @return The float value.
+   */
+  float GetFloat() const {
+    assert(m_val.type == NT_FLOAT);
+    return m_val.data.v_float;
+  }
+
+  /**
    * Get the entry's double value.
    *
    * @return The double value.
@@ -164,7 +226,7 @@
    */
   std::string_view GetString() const {
     assert(m_val.type == NT_STRING);
-    return m_string;
+    return {m_val.data.v_string.str, m_val.data.v_string.len};
   }
 
   /**
@@ -172,19 +234,9 @@
    *
    * @return The raw value.
    */
-  std::string_view GetRaw() const {
+  std::span<const uint8_t> GetRaw() const {
     assert(m_val.type == NT_RAW);
-    return m_string;
-  }
-
-  /**
-   * Get the entry's rpc definition value.
-   *
-   * @return The rpc definition value.
-   */
-  std::string_view GetRpc() const {
-    assert(m_val.type == NT_RPC);
-    return m_string;
+    return {m_val.data.v_raw.data, m_val.data.v_raw.size};
   }
 
   /**
@@ -192,17 +244,37 @@
    *
    * @return The boolean array value.
    */
-  wpi::span<const int> GetBooleanArray() const {
+  std::span<const int> GetBooleanArray() const {
     assert(m_val.type == NT_BOOLEAN_ARRAY);
     return {m_val.data.arr_boolean.arr, m_val.data.arr_boolean.size};
   }
 
   /**
+   * Get the entry's integer array value.
+   *
+   * @return The integer array value.
+   */
+  std::span<const int64_t> GetIntegerArray() const {
+    assert(m_val.type == NT_INTEGER_ARRAY);
+    return {m_val.data.arr_int.arr, m_val.data.arr_int.size};
+  }
+
+  /**
+   * Get the entry's float array value.
+   *
+   * @return The float array value.
+   */
+  std::span<const float> GetFloatArray() const {
+    assert(m_val.type == NT_FLOAT_ARRAY);
+    return {m_val.data.arr_float.arr, m_val.data.arr_float.size};
+  }
+
+  /**
    * Get the entry's double array value.
    *
    * @return The double array value.
    */
-  wpi::span<const double> GetDoubleArray() const {
+  std::span<const double> GetDoubleArray() const {
     assert(m_val.type == NT_DOUBLE_ARRAY);
     return {m_val.data.arr_double.arr, m_val.data.arr_double.size};
   }
@@ -212,9 +284,9 @@
    *
    * @return The string array value.
    */
-  wpi::span<const std::string> GetStringArray() const {
+  std::span<const std::string> GetStringArray() const {
     assert(m_val.type == NT_STRING_ARRAY);
-    return m_string_array;
+    return *static_cast<std::vector<std::string>*>(m_storage.get());
   }
 
   /** @} */
@@ -232,9 +304,37 @@
    *             time)
    * @return The entry value
    */
-  static std::shared_ptr<Value> MakeBoolean(bool value, uint64_t time = 0) {
-    auto val = std::make_shared<Value>(NT_BOOLEAN, time, private_init());
-    val->m_val.data.v_boolean = value;
+  static Value MakeBoolean(bool value, int64_t time = 0) {
+    Value val{NT_BOOLEAN, time, private_init{}};
+    val.m_val.data.v_boolean = value;
+    return val;
+  }
+
+  /**
+   * Creates an integer entry value.
+   *
+   * @param value the value
+   * @param time if nonzero, the creation time to use (instead of the current
+   *             time)
+   * @return The entry value
+   */
+  static Value MakeInteger(int64_t value, int64_t time = 0) {
+    Value val{NT_INTEGER, time, private_init{}};
+    val.m_val.data.v_int = value;
+    return val;
+  }
+
+  /**
+   * Creates a float entry value.
+   *
+   * @param value the value
+   * @param time if nonzero, the creation time to use (instead of the current
+   *             time)
+   * @return The entry value
+   */
+  static Value MakeFloat(float value, int64_t time = 0) {
+    Value val{NT_FLOAT, time, private_init{}};
+    val.m_val.data.v_float = value;
     return val;
   }
 
@@ -246,9 +346,9 @@
    *             time)
    * @return The entry value
    */
-  static std::shared_ptr<Value> MakeDouble(double value, uint64_t time = 0) {
-    auto val = std::make_shared<Value>(NT_DOUBLE, time, private_init());
-    val->m_val.data.v_double = value;
+  static Value MakeDouble(double value, int64_t time = 0) {
+    Value val{NT_DOUBLE, time, private_init{}};
+    val.m_val.data.v_double = value;
     return val;
   }
 
@@ -260,12 +360,12 @@
    *             time)
    * @return The entry value
    */
-  static std::shared_ptr<Value> MakeString(std::string_view value,
-                                           uint64_t time = 0) {
-    auto val = std::make_shared<Value>(NT_STRING, time, private_init());
-    val->m_string = value;
-    val->m_val.data.v_string.str = const_cast<char*>(val->m_string.c_str());
-    val->m_val.data.v_string.len = val->m_string.size();
+  static Value MakeString(std::string_view value, int64_t time = 0) {
+    Value val{NT_STRING, time, private_init{}};
+    auto data = std::make_shared<std::string>(value);
+    val.m_val.data.v_string.str = const_cast<char*>(data->c_str());
+    val.m_val.data.v_string.len = data->size();
+    val.m_storage = std::move(data);
     return val;
   }
 
@@ -279,11 +379,12 @@
    */
   template <typename T,
             typename std::enable_if<std::is_same<T, std::string>::value>::type>
-  static std::shared_ptr<Value> MakeString(T&& value, uint64_t time = 0) {
-    auto val = std::make_shared<Value>(NT_STRING, time, private_init());
-    val->m_string = std::forward<T>(value);
-    val->m_val.data.v_string.str = const_cast<char*>(val->m_string.c_str());
-    val->m_val.data.v_string.len = val->m_string.size();
+  static Value MakeString(T&& value, int64_t time = 0) {
+    Value val{NT_STRING, time, private_init{}};
+    auto data = std::make_shared<std::string>(std::forward(value));
+    val.m_val.data.v_string.str = const_cast<char*>(data->c_str());
+    val.m_val.data.v_string.len = data->size();
+    val.m_storage = std::move(data);
     return val;
   }
 
@@ -295,12 +396,13 @@
    *             time)
    * @return The entry value
    */
-  static std::shared_ptr<Value> MakeRaw(std::string_view value,
-                                        uint64_t time = 0) {
-    auto val = std::make_shared<Value>(NT_RAW, time, private_init());
-    val->m_string = value;
-    val->m_val.data.v_raw.str = const_cast<char*>(val->m_string.c_str());
-    val->m_val.data.v_raw.len = val->m_string.size();
+  static Value MakeRaw(std::span<const uint8_t> value, int64_t time = 0) {
+    Value val{NT_RAW, time, private_init{}};
+    auto data =
+        std::make_shared<std::vector<uint8_t>>(value.begin(), value.end());
+    val.m_val.data.v_raw.data = const_cast<uint8_t*>(data->data());
+    val.m_val.data.v_raw.size = data->size();
+    val.m_storage = std::move(data);
     return val;
   }
 
@@ -312,47 +414,14 @@
    *             time)
    * @return The entry value
    */
-  template <typename T,
-            typename std::enable_if<std::is_same<T, std::string>::value>::type>
-  static std::shared_ptr<Value> MakeRaw(T&& value, uint64_t time = 0) {
-    auto val = std::make_shared<Value>(NT_RAW, time, private_init());
-    val->m_string = std::forward<T>(value);
-    val->m_val.data.v_raw.str = const_cast<char*>(val->m_string.c_str());
-    val->m_val.data.v_raw.len = val->m_string.size();
-    return val;
-  }
-
-  /**
-   * Creates a rpc entry value.
-   *
-   * @param value the value
-   * @param time if nonzero, the creation time to use (instead of the current
-   *             time)
-   * @return The entry value
-   */
-  static std::shared_ptr<Value> MakeRpc(std::string_view value,
-                                        uint64_t time = 0) {
-    auto val = std::make_shared<Value>(NT_RPC, time, private_init());
-    val->m_string = value;
-    val->m_val.data.v_raw.str = const_cast<char*>(val->m_string.c_str());
-    val->m_val.data.v_raw.len = val->m_string.size();
-    return val;
-  }
-
-  /**
-   * Creates a rpc entry value.
-   *
-   * @param value the value
-   * @param time if nonzero, the creation time to use (instead of the current
-   *             time)
-   * @return The entry value
-   */
-  template <typename T>
-  static std::shared_ptr<Value> MakeRpc(T&& value, uint64_t time = 0) {
-    auto val = std::make_shared<Value>(NT_RPC, time, private_init());
-    val->m_string = std::forward<T>(value);
-    val->m_val.data.v_raw.str = const_cast<char*>(val->m_string.c_str());
-    val->m_val.data.v_raw.len = val->m_string.size();
+  template <typename T, typename std::enable_if<
+                            std::is_same<T, std::vector<uint8_t>>::value>::type>
+  static Value MakeRaw(T&& value, int64_t time = 0) {
+    Value val{NT_RAW, time, private_init{}};
+    auto data = std::make_shared<std::vector<uint8_t>>(std::forward(value));
+    val.m_val.data.v_raw.data = const_cast<uint8_t*>(data->data());
+    val.m_val.data.v_raw.size = data->size();
+    val.m_storage = std::move(data);
     return val;
   }
 
@@ -364,8 +433,7 @@
    *             time)
    * @return The entry value
    */
-  static std::shared_ptr<Value> MakeBooleanArray(wpi::span<const bool> value,
-                                                 uint64_t time = 0);
+  static Value MakeBooleanArray(std::span<const bool> value, int64_t time = 0);
 
   /**
    * Creates a boolean array entry value.
@@ -375,9 +443,9 @@
    *             time)
    * @return The entry value
    */
-  static std::shared_ptr<Value> MakeBooleanArray(
-      std::initializer_list<bool> value, uint64_t time = 0) {
-    return MakeBooleanArray(wpi::span(value.begin(), value.end()), time);
+  static Value MakeBooleanArray(std::initializer_list<bool> value,
+                                int64_t time = 0) {
+    return MakeBooleanArray(std::span(value.begin(), value.end()), time);
   }
 
   /**
@@ -388,8 +456,7 @@
    *             time)
    * @return The entry value
    */
-  static std::shared_ptr<Value> MakeBooleanArray(wpi::span<const int> value,
-                                                 uint64_t time = 0);
+  static Value MakeBooleanArray(std::span<const int> value, int64_t time = 0);
 
   /**
    * Creates a boolean array entry value.
@@ -399,12 +466,95 @@
    *             time)
    * @return The entry value
    */
-  static std::shared_ptr<Value> MakeBooleanArray(
-      std::initializer_list<int> value, uint64_t time = 0) {
-    return MakeBooleanArray(wpi::span(value.begin(), value.end()), time);
+  static Value MakeBooleanArray(std::initializer_list<int> value,
+                                int64_t time = 0) {
+    return MakeBooleanArray(std::span(value.begin(), value.end()), time);
   }
 
   /**
+   * Creates a boolean array entry value.
+   *
+   * @param value the value
+   * @param time if nonzero, the creation time to use (instead of the current
+   *             time)
+   * @return The entry value
+   *
+   * @note This function moves the values out of the vector.
+   */
+  static Value MakeBooleanArray(std::vector<int>&& value, int64_t time = 0);
+
+  /**
+   * Creates an integer array entry value.
+   *
+   * @param value the value
+   * @param time if nonzero, the creation time to use (instead of the current
+   *             time)
+   * @return The entry value
+   */
+  static Value MakeIntegerArray(std::span<const int64_t> value,
+                                int64_t time = 0);
+
+  /**
+   * Creates an integer array entry value.
+   *
+   * @param value the value
+   * @param time if nonzero, the creation time to use (instead of the current
+   *             time)
+   * @return The entry value
+   */
+  static Value MakeIntegerArray(std::initializer_list<int64_t> value,
+                                int64_t time = 0) {
+    return MakeIntegerArray(std::span(value.begin(), value.end()), time);
+  }
+
+  /**
+   * Creates an integer array entry value.
+   *
+   * @param value the value
+   * @param time if nonzero, the creation time to use (instead of the current
+   *             time)
+   * @return The entry value
+   *
+   * @note This function moves the values out of the vector.
+   */
+  static Value MakeIntegerArray(std::vector<int64_t>&& value, int64_t time = 0);
+
+  /**
+   * Creates a float array entry value.
+   *
+   * @param value the value
+   * @param time if nonzero, the creation time to use (instead of the current
+   *             time)
+   * @return The entry value
+   */
+  static Value MakeFloatArray(std::span<const float> value, int64_t time = 0);
+
+  /**
+   * Creates a float array entry value.
+   *
+   * @param value the value
+   * @param time if nonzero, the creation time to use (instead of the current
+   *             time)
+   * @return The entry value
+   */
+  static Value MakeFloatArray(std::initializer_list<float> value,
+                              int64_t time = 0) {
+    return MakeFloatArray(std::span(value.begin(), value.end()), time);
+  }
+
+  /**
+   * Creates a float array entry value.
+   *
+   * @param value the value
+   * @param time if nonzero, the creation time to use (instead of the current
+   *             time)
+   * @return The entry value
+   *
+   * @note This function moves the values out of the vector.
+   */
+  static Value MakeFloatArray(std::vector<float>&& value, int64_t time = 0);
+
+  /**
    * Creates a double array entry value.
    *
    * @param value the value
@@ -412,8 +562,7 @@
    *             time)
    * @return The entry value
    */
-  static std::shared_ptr<Value> MakeDoubleArray(wpi::span<const double> value,
-                                                uint64_t time = 0);
+  static Value MakeDoubleArray(std::span<const double> value, int64_t time = 0);
 
   /**
    * Creates a double array entry value.
@@ -423,21 +572,22 @@
    *             time)
    * @return The entry value
    */
-  static std::shared_ptr<Value> MakeDoubleArray(
-      std::initializer_list<double> value, uint64_t time = 0) {
-    return MakeDoubleArray(wpi::span(value.begin(), value.end()), time);
+  static Value MakeDoubleArray(std::initializer_list<double> value,
+                               int64_t time = 0) {
+    return MakeDoubleArray(std::span(value.begin(), value.end()), time);
   }
 
   /**
-   * Creates a string array entry value.
+   * Creates a double array entry value.
    *
    * @param value the value
    * @param time if nonzero, the creation time to use (instead of the current
    *             time)
    * @return The entry value
+   *
+   * @note This function moves the values out of the vector.
    */
-  static std::shared_ptr<Value> MakeStringArray(
-      wpi::span<const std::string> value, uint64_t time = 0);
+  static Value MakeDoubleArray(std::vector<double>&& value, int64_t time = 0);
 
   /**
    * Creates a string array entry value.
@@ -447,9 +597,20 @@
    *             time)
    * @return The entry value
    */
-  static std::shared_ptr<Value> MakeStringArray(
-      std::initializer_list<std::string> value, uint64_t time = 0) {
-    return MakeStringArray(wpi::span(value.begin(), value.end()), time);
+  static Value MakeStringArray(std::span<const std::string> value,
+                               int64_t time = 0);
+
+  /**
+   * Creates a string array entry value.
+   *
+   * @param value the value
+   * @param time if nonzero, the creation time to use (instead of the current
+   *             time)
+   * @return The entry value
+   */
+  static Value MakeStringArray(std::initializer_list<std::string> value,
+                               int64_t time = 0) {
+    return MakeStringArray(std::span(value.begin(), value.end()), time);
   }
 
   /**
@@ -462,25 +623,19 @@
    *
    * @note This function moves the values out of the vector.
    */
-  static std::shared_ptr<Value> MakeStringArray(
-      std::vector<std::string>&& value, uint64_t time = 0);
+  static Value MakeStringArray(std::vector<std::string>&& value,
+                               int64_t time = 0);
 
   /** @} */
 
-  Value(const Value&) = delete;
-  Value& operator=(const Value&) = delete;
   friend bool operator==(const Value& lhs, const Value& rhs);
 
  private:
   NT_Value m_val;
-  std::string m_string;
-  std::vector<std::string> m_string_array;
+  std::shared_ptr<void> m_storage;
 };
 
 bool operator==(const Value& lhs, const Value& rhs);
-inline bool operator!=(const Value& lhs, const Value& rhs) {
-  return !(lhs == rhs);
-}
 
 /**
  * NetworkTable Value alias for similarity with Java.
@@ -489,5 +644,3 @@
 using NetworkTableValue = Value;
 
 }  // namespace nt
-
-#endif  // NTCORE_NETWORKTABLES_NETWORKTABLEVALUE_H_
diff --git a/third_party/allwpilib/ntcore/src/main/native/include/networktables/RpcCall.h b/third_party/allwpilib/ntcore/src/main/native/include/networktables/RpcCall.h
deleted file mode 100644
index 9c6e9f9..0000000
--- a/third_party/allwpilib/ntcore/src/main/native/include/networktables/RpcCall.h
+++ /dev/null
@@ -1,106 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef NTCORE_NETWORKTABLES_RPCCALL_H_
-#define NTCORE_NETWORKTABLES_RPCCALL_H_
-
-#include <string>
-#include <utility>
-
-#include "ntcore_c.h"
-
-namespace nt {
-
-class NetworkTableEntry;
-
-/**
- * NetworkTables Remote Procedure Call
- * @ingroup ntcore_cpp_api
- */
-class RpcCall final {
- public:
-  /**
-   * Construct invalid instance.
-   */
-  RpcCall() = default;
-
-  /**
-   * Construct from native handles.
-   *
-   * @param entry Entry handle
-   * @param call  Call handle
-   */
-  RpcCall(NT_Entry entry, NT_RpcCall call) : m_entry(entry), m_call(call) {}
-
-  RpcCall(RpcCall&& other) noexcept;
-  RpcCall(const RpcCall&) = delete;
-  RpcCall& operator=(const RpcCall&) = delete;
-
-  /**
-   * Destructor.  Cancels the result if no other action taken.
-   */
-  ~RpcCall();
-
-  /**
-   * Determines if the native handle is valid.
-   *
-   * @return True if the native handle is valid, false otherwise.
-   */
-  explicit operator bool() const { return m_call != 0; }
-
-  /**
-   * Get the RPC entry.
-   *
-   * @return NetworkTableEntry for the RPC.
-   */
-  NetworkTableEntry GetEntry() const;
-
-  /**
-   * Get the call native handle.
-   *
-   * @return Native handle.
-   */
-  NT_RpcCall GetCall() const { return m_call; }
-
-  /**
-   * Get the result (return value).  This function blocks until
-   * the result is received.
-   *
-   * @param result      received result (output)
-   * @return False on error, true otherwise.
-   */
-  bool GetResult(std::string* result);
-
-  /**
-   * Get the result (return value).  This function blocks until
-   * the result is received or it times out.
-   *
-   * @param result      received result (output)
-   * @param timeout     timeout, in seconds
-   * @param timed_out   true if the timeout period elapsed (output)
-   * @return False on error or timeout, true otherwise.
-   */
-  bool GetResult(std::string* result, double timeout, bool* timed_out);
-
-  /**
-   * Ignore the result.  This function is non-blocking.
-   */
-  void CancelResult();
-
-  friend void swap(RpcCall& first, RpcCall& second) {
-    using std::swap;
-    swap(first.m_entry, second.m_entry);
-    swap(first.m_call, second.m_call);
-  }
-
- private:
-  NT_Entry m_entry{0};
-  NT_RpcCall m_call{0};
-};
-
-}  // namespace nt
-
-#include "networktables/RpcCall.inc"
-
-#endif  // NTCORE_NETWORKTABLES_RPCCALL_H_
diff --git a/third_party/allwpilib/ntcore/src/main/native/include/networktables/RpcCall.inc b/third_party/allwpilib/ntcore/src/main/native/include/networktables/RpcCall.inc
deleted file mode 100644
index 5e25b04..0000000
--- a/third_party/allwpilib/ntcore/src/main/native/include/networktables/RpcCall.inc
+++ /dev/null
@@ -1,51 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef NTCORE_NETWORKTABLES_RPCCALL_INC_
-#define NTCORE_NETWORKTABLES_RPCCALL_INC_
-
-#include <string>
-#include <utility>
-
-#include "networktables/RpcCall.h"
-#include "ntcore_cpp.h"
-
-namespace nt {
-
-inline RpcCall::RpcCall(RpcCall&& other) noexcept : RpcCall() {
-  swap(*this, other);
-}
-
-inline RpcCall::~RpcCall() {
-  // automatically cancel result if user didn't request it
-  if (m_call != 0) {
-    CancelResult();
-  }
-}
-
-inline bool RpcCall::GetResult(std::string* result) {
-  if (GetRpcResult(m_entry, m_call, result)) {
-    m_call = 0;
-    return true;
-  }
-  return false;
-}
-
-inline bool RpcCall::GetResult(std::string* result, double timeout,
-                               bool* timed_out) {
-  if (GetRpcResult(m_entry, m_call, result, timeout, timed_out)) {
-    m_call = 0;
-    return true;
-  }
-  return false;
-}
-
-inline void RpcCall::CancelResult() {
-  CancelRpcResult(m_entry, m_call);
-  m_call = 0;
-}
-
-}  // namespace nt
-
-#endif  // NTCORE_NETWORKTABLES_RPCCALL_INC_
diff --git a/third_party/allwpilib/ntcore/src/main/native/include/networktables/TableEntryListener.h b/third_party/allwpilib/ntcore/src/main/native/include/networktables/TableEntryListener.h
deleted file mode 100644
index 180234f..0000000
--- a/third_party/allwpilib/ntcore/src/main/native/include/networktables/TableEntryListener.h
+++ /dev/null
@@ -1,38 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef NTCORE_NETWORKTABLES_TABLEENTRYLISTENER_H_
-#define NTCORE_NETWORKTABLES_TABLEENTRYLISTENER_H_
-
-#include <functional>
-#include <memory>
-#include <string_view>
-
-namespace nt {
-
-class NetworkTable;
-class NetworkTableEntry;
-class Value;
-
-/**
- * A listener that listens to changes in values in a NetworkTable.
- *
- * Called when a key-value pair is changed in a NetworkTable.
- *
- * @param table the table the key-value pair exists in
- * @param key the key associated with the value that changed
- * @param entry the entry associated with the value that changed
- * @param value the new value
- * @param flags update flags; for example, EntryListenerFlags.kNew if the key
- * did not previously exist
- *
- * @ingroup ntcore_cpp_api
- */
-using TableEntryListener = std::function<void(
-    NetworkTable* table, std::string_view name, NetworkTableEntry entry,
-    std::shared_ptr<Value> value, int flags)>;
-
-}  // namespace nt
-
-#endif  // NTCORE_NETWORKTABLES_TABLEENTRYLISTENER_H_
diff --git a/third_party/allwpilib/ntcore/src/main/native/include/networktables/TableListener.h b/third_party/allwpilib/ntcore/src/main/native/include/networktables/TableListener.h
deleted file mode 100644
index cc1113e..0000000
--- a/third_party/allwpilib/ntcore/src/main/native/include/networktables/TableListener.h
+++ /dev/null
@@ -1,33 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef NTCORE_NETWORKTABLES_TABLELISTENER_H_
-#define NTCORE_NETWORKTABLES_TABLELISTENER_H_
-
-#include <functional>
-#include <memory>
-#include <string_view>
-
-namespace nt {
-
-class NetworkTable;
-
-/**
- * A listener that listens to new sub-tables in a NetworkTable.
- *
- * Called when a new table is created.
- *
- * @param parent the parent of the table
- * @param name the name of the new table
- * @param table the new table
- *
- * @ingroup ntcore_cpp_api
- */
-using TableListener =
-    std::function<void(NetworkTable* parent, std::string_view name,
-                       std::shared_ptr<NetworkTable> table)>;
-
-}  // namespace nt
-
-#endif  // NTCORE_NETWORKTABLES_TABLELISTENER_H_
diff --git a/third_party/allwpilib/ntcore/src/main/native/include/networktables/Topic.h b/third_party/allwpilib/ntcore/src/main/native/include/networktables/Topic.h
new file mode 100644
index 0000000..e2a8a5a
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/include/networktables/Topic.h
@@ -0,0 +1,385 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <stdint.h>
+
+#include <string>
+#include <string_view>
+#include <utility>
+#include <vector>
+
+#include "networktables/NetworkTableType.h"
+#include "ntcore_c.h"
+#include "ntcore_cpp.h"
+
+namespace wpi {
+class json;
+}  // namespace wpi
+
+namespace nt {
+
+class GenericEntry;
+class GenericPublisher;
+class GenericSubscriber;
+class NetworkTableInstance;
+
+/** NetworkTables Topic. */
+class Topic {
+ public:
+  Topic() = default;
+  explicit Topic(NT_Topic handle) : m_handle{handle} {}
+
+  /**
+   * Determines if the native handle is valid.
+   *
+   * @return True if the native handle is valid, false otherwise.
+   */
+  explicit operator bool() const { return m_handle != 0; }
+
+  /**
+   * Gets the native handle for the topic.
+   *
+   * @return Native handle
+   */
+  NT_Topic GetHandle() const { return m_handle; }
+
+  /**
+   * Gets the instance for the topic.
+   *
+   * @return Instance
+   */
+  NetworkTableInstance GetInstance() const;
+
+  /**
+   * Gets the name of the topic.
+   *
+   * @return the topic's name
+   */
+  std::string GetName() const;
+
+  /**
+   * Gets the type of the topic.
+   *
+   * @return the topic's type
+   */
+  NetworkTableType GetType() const;
+
+  /**
+   * Gets the type string of the topic. This may have more information
+   * than the numeric type (especially for raw values).
+   *
+   * @return the topic's type
+   */
+  std::string GetTypeString() const;
+
+  /**
+   * Make value persistent through server restarts.
+   *
+   * @param persistent True for persistent, false for not persistent.
+   */
+  void SetPersistent(bool persistent);
+
+  /**
+   * Returns whether the value is persistent through server restarts.
+   *
+   * @return True if the value is persistent.
+   */
+  bool IsPersistent() const;
+
+  /**
+   * Make the server retain the topic even when there are no publishers.
+   *
+   * @param retained True for retained, false for not retained.
+   */
+  void SetRetained(bool retained);
+
+  /**
+   * Returns whether the topic is retained by server when there are no
+   * publishers.
+   *
+   * @return True if the topic is retained.
+   */
+  bool IsRetained() const;
+
+  /**
+   * Determines if the topic is currently being published.
+   *
+   * @return True if the topic exists, false otherwise.
+   */
+  bool Exists() const;
+
+  /**
+   * Gets the current value of a property (as a JSON object).
+   *
+   * @param name property name
+   * @return JSON object; null object if the property does not exist.
+   */
+  wpi::json GetProperty(std::string_view name) const;
+
+  /**
+   * Sets a property value.
+   *
+   * @param name property name
+   * @param value property value
+   */
+  void SetProperty(std::string_view name, const wpi::json& value);
+
+  /**
+   * Deletes a property.  Has no effect if the property does not exist.
+   *
+   * @param name property name
+   */
+  void DeleteProperty(std::string_view name);
+
+  /**
+   * Gets all topic properties as a JSON object.  Each key in the object
+   * is the property name, and the corresponding value is the property value.
+   *
+   * @return JSON object
+   */
+  wpi::json GetProperties() const;
+
+  /**
+   * Updates multiple topic properties.  Each key in the passed-in object is
+   * the name of the property to add/update, and the corresponding value is the
+   * property value to set for that property.  Null values result in deletion
+   * of the corresponding property.
+   *
+   * @param properties JSON object with keys to add/update/delete
+   * @return False if properties is not an object
+   */
+  bool SetProperties(const wpi::json& properties);
+
+  /**
+   * Gets combined information about the topic.
+   *
+   * @return Topic information
+   */
+  TopicInfo GetInfo() const;
+
+  /**
+   * Create a new subscriber to the topic.
+   *
+   * <p>The subscriber is only active as long as the returned object
+   * is not destroyed.
+   *
+   * @param options subscribe options
+   * @return subscriber
+   */
+  [[nodiscard]] GenericSubscriber GenericSubscribe(
+      const PubSubOptions& options = kDefaultPubSubOptions);
+
+  /**
+   * Create a new subscriber to the topic.
+   *
+   * <p>The subscriber is only active as long as the returned object
+   * is not destroyed.
+   *
+   * @note Subscribers that do not match the published data type do not return
+   *     any values. To determine if the data type matches, use the appropriate
+   *     Topic functions.
+   *
+   * @param typeString type string
+   * @param options subscribe options
+   * @return subscriber
+   */
+  [[nodiscard]] GenericSubscriber GenericSubscribe(
+      std::string_view typeString,
+      const PubSubOptions& options = kDefaultPubSubOptions);
+
+  /**
+   * Create a new publisher to the topic.
+   *
+   * The publisher is only active as long as the returned object
+   * is not destroyed.
+   *
+   * @note It is not possible to publish two different data types to the same
+   *     topic. Conflicts between publishers are typically resolved by the
+   *     server on a first-come, first-served basis. Any published values that
+   *     do not match the topic's data type are dropped (ignored). To determine
+   *     if the data type matches, use the appropriate Topic functions.
+   *
+   * @param typeString type string
+   * @param options publish options
+   * @return publisher
+   */
+  [[nodiscard]] GenericPublisher GenericPublish(
+      std::string_view typeString,
+      const PubSubOptions& options = kDefaultPubSubOptions);
+
+  /**
+   * Create a new publisher to the topic, with type string and initial
+   * properties.
+   *
+   * The publisher is only active as long as the returned object
+   * is not destroyed.
+   *
+   * @note It is not possible to publish two different data types to the same
+   *     topic. Conflicts between publishers are typically resolved by the
+   *     server on a first-come, first-served basis. Any published values that
+   *     do not match the topic's data type are dropped (ignored). To determine
+   *     if the data type matches, use the appropriate Topic functions.
+   *
+   * @param typeString type string
+   * @param properties JSON properties
+   * @param options publish options
+   * @return publisher
+   */
+  [[nodiscard]] GenericPublisher GenericPublishEx(
+      std::string_view typeString, const wpi::json& properties,
+      const PubSubOptions& options = kDefaultPubSubOptions);
+
+  /**
+   * Create a new generic entry for the topic.
+   *
+   * Entries act as a combination of a subscriber and a weak publisher. The
+   * subscriber is active as long as the entry is not destroyed. The publisher
+   * is created when the entry is first written to, and remains active until
+   * either Unpublish() is called or the entry is destroyed.
+   *
+   * @note It is not possible to use two different data types with the same
+   *     topic. Conflicts between publishers are typically resolved by the
+   *     server on a first-come, first-served basis. Any published values that
+   *     do not match the topic's data type are dropped (ignored), and the entry
+   *     will show no new values if the data type does not match. To determine
+   *     if the data type matches, use the appropriate Topic functions.
+   *
+   * @param options publish and/or subscribe options
+   * @return entry
+   */
+  [[nodiscard]] GenericEntry GetGenericEntry(
+      const PubSubOptions& options = kDefaultPubSubOptions);
+
+  /**
+   * Create a new generic entry for the topic.
+   *
+   * Entries act as a combination of a subscriber and a weak publisher. The
+   * subscriber is active as long as the entry is not destroyed. The publisher
+   * is created when the entry is first written to, and remains active until
+   * either Unpublish() is called or the entry is destroyed.
+   *
+   * @note It is not possible to use two different data types with the same
+   *     topic. Conflicts between publishers are typically resolved by the
+   *     server on a first-come, first-served basis. Any published values that
+   *     do not match the topic's data type are dropped (ignored), and the entry
+   *     will show no new values if the data type does not match. To determine
+   *     if the data type matches, use the appropriate Topic functions.
+   *
+   * @param typeString type string
+   * @param options publish and/or subscribe options
+   * @return entry
+   */
+  [[nodiscard]] GenericEntry GetGenericEntry(
+      std::string_view typeString,
+      const PubSubOptions& options = kDefaultPubSubOptions);
+
+  /**
+   * Equality operator.  Returns true if both instances refer to the same
+   * native handle.
+   */
+  bool operator==(const Topic&) const = default;
+
+ protected:
+  NT_Topic m_handle{0};
+};
+
+/** NetworkTables subscriber. */
+class Subscriber {
+ public:
+  virtual ~Subscriber();
+
+  Subscriber(const Subscriber&) = delete;
+  Subscriber& operator=(const Subscriber&) = delete;
+
+  Subscriber(Subscriber&&);
+  Subscriber& operator=(Subscriber&&);
+
+  /**
+   * Determines if the native handle is valid.
+   *
+   * @return True if the native handle is valid, false otherwise.
+   */
+  explicit operator bool() const { return m_subHandle != 0; }
+
+  /**
+   * Gets the native handle for the subscriber.
+   *
+   * @return Native handle
+   */
+  NT_Subscriber GetHandle() const { return m_subHandle; }
+
+  /**
+   * Determines if the topic is currently being published.
+   *
+   * @return True if the topic exists, false otherwise.
+   */
+  bool Exists() const;
+
+  /**
+   * Gets the last time the value was changed.
+   * Note: this is not atomic with Get(); use GetAtomic() to get
+   * both the value and last change as an atomic operation.
+   *
+   * @return Topic last change time
+   */
+  int64_t GetLastChange() const;
+
+  /**
+   * Gets the subscribed-to topic.
+   *
+   * @return Topic
+   */
+  Topic GetTopic() const;
+
+ protected:
+  Subscriber() = default;
+  explicit Subscriber(NT_Subscriber handle) : m_subHandle{handle} {}
+
+  NT_Subscriber m_subHandle{0};
+};
+
+/** NetworkTables publisher. */
+class Publisher {
+ public:
+  virtual ~Publisher();
+
+  Publisher(const Publisher&) = delete;
+  Publisher& operator=(const Publisher&) = delete;
+
+  Publisher(Publisher&&);
+  Publisher& operator=(Publisher&&);
+
+  /**
+   * Determines if the native handle is valid.
+   *
+   * @return True if the native handle is valid, false otherwise.
+   */
+  explicit operator bool() const { return m_pubHandle != 0; }
+
+  /**
+   * Gets the native handle for the publisher.
+   *
+   * @return Native handle
+   */
+  NT_Publisher GetHandle() const { return m_pubHandle; }
+
+  /**
+   * Gets the published-to topic.
+   *
+   * @return Topic
+   */
+  Topic GetTopic() const;
+
+ protected:
+  Publisher() = default;
+  explicit Publisher(NT_Publisher handle) : m_pubHandle{handle} {}
+
+  NT_Publisher m_pubHandle{0};
+};
+
+}  // namespace nt
+
+#include "networktables/Topic.inc"
diff --git a/third_party/allwpilib/ntcore/src/main/native/include/networktables/Topic.inc b/third_party/allwpilib/ntcore/src/main/native/include/networktables/Topic.inc
new file mode 100644
index 0000000..642e49e
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/include/networktables/Topic.inc
@@ -0,0 +1,115 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <string>
+
+#include "networktables/NetworkTableInstance.h"
+#include "networktables/NetworkTableType.h"
+#include "networktables/Topic.h"
+#include "ntcore_c.h"
+#include "ntcore_cpp.h"
+
+namespace nt {
+
+inline NetworkTableInstance Topic::GetInstance() const {
+  return NetworkTableInstance{GetInstanceFromHandle(m_handle)};
+}
+
+inline std::string Topic::GetName() const {
+  return ::nt::GetTopicName(m_handle);
+}
+
+inline NetworkTableType Topic::GetType() const {
+  return static_cast<NetworkTableType>(::nt::GetTopicType(m_handle));
+}
+
+inline std::string Topic::GetTypeString() const {
+  return ::nt::GetTopicTypeString(m_handle);
+}
+
+inline void Topic::SetPersistent(bool persistent) {
+  ::nt::SetTopicPersistent(m_handle, persistent);
+}
+
+inline bool Topic::IsPersistent() const {
+  return ::nt::GetTopicPersistent(m_handle);
+}
+
+inline void Topic::SetRetained(bool retained) {
+  ::nt::SetTopicRetained(m_handle, retained);
+}
+
+inline bool Topic::IsRetained() const {
+  return ::nt::GetTopicRetained(m_handle);
+}
+
+inline bool Topic::Exists() const {
+  return nt::GetTopicExists(m_handle);
+}
+
+inline void Topic::DeleteProperty(std::string_view name) {
+  ::nt::DeleteTopicProperty(m_handle, name);
+}
+
+inline bool Topic::SetProperties(const wpi::json& properties) {
+  return ::nt::SetTopicProperties(m_handle, properties);
+}
+
+inline TopicInfo Topic::GetInfo() const {
+  return ::nt::GetTopicInfo(m_handle);
+}
+
+inline Subscriber::~Subscriber() {
+  ::nt::Release(m_subHandle);
+}
+
+inline Subscriber::Subscriber(Subscriber&& rhs) : m_subHandle{rhs.m_subHandle} {
+  rhs.m_subHandle = 0;
+}
+
+inline Subscriber& Subscriber::operator=(Subscriber&& rhs) {
+  if (m_subHandle != 0) {
+    ::nt::Release(m_subHandle);
+  }
+  m_subHandle = rhs.m_subHandle;
+  rhs.m_subHandle = 0;
+  return *this;
+}
+
+inline bool Subscriber::Exists() const {
+  return nt::GetTopicExists(m_subHandle);
+}
+
+inline int64_t Subscriber::GetLastChange() const {
+  return ::nt::GetEntryLastChange(m_subHandle);
+}
+
+inline Topic Subscriber::GetTopic() const {
+  return Topic{::nt::GetTopicFromHandle(m_subHandle)};
+}
+
+inline Publisher::~Publisher() {
+  ::nt::Release(m_pubHandle);
+}
+
+inline Publisher::Publisher(Publisher&& rhs) : m_pubHandle{rhs.m_pubHandle} {
+  rhs.m_pubHandle = 0;
+}
+
+inline Publisher& Publisher::operator=(Publisher&& rhs) {
+  if (m_pubHandle != 0) {
+    ::nt::Release(m_pubHandle);
+  }
+  m_pubHandle = rhs.m_pubHandle;
+  rhs.m_pubHandle = 0;
+  return *this;
+}
+
+inline Topic Publisher::GetTopic() const {
+  return Topic{::nt::GetTopicFromHandle(m_pubHandle)};
+}
+
+}  // namespace nt
diff --git a/third_party/allwpilib/ntcore/src/main/native/include/networktables/UnitTopic.h b/third_party/allwpilib/ntcore/src/main/native/include/networktables/UnitTopic.h
new file mode 100644
index 0000000..cac9501
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/include/networktables/UnitTopic.h
@@ -0,0 +1,414 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <stdint.h>
+
+#include <span>
+#include <string_view>
+#include <vector>
+
+#include "networktables/Topic.h"
+#include "ntcore_cpp.h"
+
+namespace wpi {
+class json;
+}  // namespace wpi
+
+namespace nt {
+
+template <typename T>
+class UnitTopic;
+
+/**
+ * Timestamped unit.
+ *
+ * @tparam T unit type, e.g. units::meter_t
+ */
+template <typename T>
+struct TimestampedUnit {
+  TimestampedUnit() = default;
+  TimestampedUnit(int64_t time, int64_t serverTime, T value)
+      : time{time}, serverTime{serverTime}, value{value} {}
+
+  /**
+   * Time in local time base.
+   */
+  int64_t time = 0;
+
+  /**
+   * Time in server time base.  May be 0 or 1 for locally set values.
+   */
+  int64_t serverTime = 0;
+
+  /**
+   * Value.
+   */
+  T value = {};
+};
+
+/**
+ * NetworkTables unit-typed subscriber.
+ *
+ * @tparam T unit type, e.g. units::meter_t
+ */
+template <typename T>
+class UnitSubscriber : public Subscriber {
+ public:
+  using TopicType = UnitTopic<T>;
+  using ValueType = T;
+  using ParamType = T;
+  using TimestampedValueType = TimestampedUnit<T>;
+
+  UnitSubscriber() = default;
+
+  /**
+   * Construct from a subscriber handle; recommended to use
+   * UnitTopic::Subscribe() instead.
+   *
+   * @param handle Native handle
+   * @param defaultValue Default value
+   */
+  UnitSubscriber(NT_Subscriber handle, ParamType defaultValue);
+
+  /**
+   * Get the last published value.
+   * If no value has been published, returns the stored default value.
+   *
+   * @return value
+   */
+  ValueType Get() const;
+
+  /**
+   * Get the last published value.
+   * If no value has been published, returns the passed defaultValue.
+   *
+   * @param defaultValue default value to return if no value has been published
+   * @return value
+   */
+  ValueType Get(ParamType defaultValue) const;
+
+  /**
+   * Get the last published value along with its timestamp
+   * If no value has been published, returns the stored default value and a
+   * timestamp of 0.
+   *
+   * @return timestamped value
+   */
+  TimestampedValueType GetAtomic() const;
+
+  /**
+   * Get the last published value along with its timestamp.
+   * If no value has been published, returns the passed defaultValue and a
+   * timestamp of 0.
+   *
+   * @param defaultValue default value to return if no value has been published
+   * @return timestamped value
+   */
+  TimestampedValueType GetAtomic(ParamType defaultValue) const;
+
+  /**
+   * Get an array of all value changes since the last call to ReadQueue.
+   * Also provides a timestamp for each value.
+   *
+   * @note The "poll storage" subscribe option can be used to set the queue
+   *     depth.
+   *
+   * @return Array of timestamped values; empty array if no new changes have
+   *     been published since the previous call.
+   */
+  std::vector<TimestampedValueType> ReadQueue();
+
+  /**
+   * Get the corresponding topic.
+   *
+   * @return Topic
+   */
+  TopicType GetTopic() const;
+
+ private:
+  ValueType m_defaultValue;
+};
+
+/**
+ * NetworkTables unit-typed publisher.
+ *
+ * @tparam T unit type, e.g. units::meter_t
+ */
+template <typename T>
+class UnitPublisher : public Publisher {
+ public:
+  using TopicType = UnitTopic<T>;
+  using ValueType = T;
+  using ParamType = T;
+
+  using TimestampedValueType = TimestampedUnit<T>;
+
+  UnitPublisher() = default;
+
+  /**
+   * Construct from a publisher handle; recommended to use
+   * UnitTopic::Publish() instead.
+   *
+   * @param handle Native handle
+   */
+  explicit UnitPublisher(NT_Publisher handle);
+
+  /**
+   * Publish a new value.
+   *
+   * @param value value to publish
+   * @param time timestamp; 0 indicates current NT time should be used
+   */
+  void Set(ParamType value, int64_t time = 0);
+
+  /**
+   * Publish a default value.
+   * On reconnect, a default value will never be used in preference to a
+   * published value.
+   *
+   * @param value value
+   */
+  void SetDefault(ParamType value);
+
+  /**
+   * Get the corresponding topic.
+   *
+   * @return Topic
+   */
+  TopicType GetTopic() const;
+};
+
+/**
+ * NetworkTables unit-typed entry.
+ *
+ * @note Unlike NetworkTableEntry, the entry goes away when this is destroyed.
+ *
+ * @tparam T unit type, e.g. units::meter_t
+ */
+template <typename T>
+class UnitEntry final : public UnitSubscriber<T>, public UnitPublisher<T> {
+ public:
+  using SubscriberType = UnitSubscriber<T>;
+  using PublisherType = UnitPublisher<T>;
+  using TopicType = UnitTopic<T>;
+  using ValueType = T;
+  using ParamType = T;
+
+  using TimestampedValueType = TimestampedUnit<T>;
+
+  UnitEntry() = default;
+
+  /**
+   * Construct from an entry handle; recommended to use
+   * UnitTopic::GetEntry() instead.
+   *
+   * @param handle Native handle
+   * @param defaultValue Default value
+   */
+  UnitEntry(NT_Entry handle, ParamType defaultValue);
+
+  /**
+   * Determines if the native handle is valid.
+   *
+   * @return True if the native handle is valid, false otherwise.
+   */
+  explicit operator bool() const { return this->m_subHandle != 0; }
+
+  /**
+   * Gets the native handle for the entry.
+   *
+   * @return Native handle
+   */
+  NT_Entry GetHandle() const { return this->m_subHandle; }
+
+  /**
+   * Get the corresponding topic.
+   *
+   * @return Topic
+   */
+  TopicType GetTopic() const;
+
+  /**
+   * Stops publishing the entry if it's published.
+   */
+  void Unpublish();
+};
+
+/**
+ * NetworkTables unit-typed topic. Publishers publish the type name (e.g.
+ * "meter") as the "unit" property. Type conversions are not performed--for
+ * correct behavior the publisher and subscriber must use the same unit type,
+ * but this can be checked at runtime using IsMatchingUnit().
+ *
+ * @tparam T unit type, e.g. units::meter_t
+ */
+template <typename T>
+class UnitTopic final : public Topic {
+ public:
+  using SubscriberType = UnitSubscriber<T>;
+  using PublisherType = UnitPublisher<T>;
+  using EntryType = UnitEntry<T>;
+  using ValueType = T;
+  using ParamType = T;
+  using TimestampedValueType = TimestampedUnit<T>;
+  /** The default type string for this topic type. */
+  static constexpr std::string_view kTypeString = "double";
+
+  UnitTopic() = default;
+
+  /**
+   * Construct from a topic handle.
+   *
+   * @param handle Native handle
+   */
+  explicit UnitTopic(NT_Topic handle) : Topic{handle} {}
+
+  /**
+   * Construct from a generic topic.
+   *
+   * @param topic Topic
+   */
+  explicit UnitTopic(Topic topic) : Topic{topic} {}
+
+  /**
+   * Verify the topic has a matching unit type (if the topic is published).
+   *
+   * @return True if unit matches, false if not matching or topic not published.
+   */
+  bool IsMatchingUnit() const;
+
+  /**
+   * Create a new subscriber to the topic.
+   *
+   * <p>The subscriber is only active as long as the returned object
+   * is not destroyed.
+   *
+   * @note Subscribers that do not match the published data type do not return
+   *     any values. To determine if the data type matches, use the appropriate
+   *     Topic functions.
+   *
+   * @param defaultValue default value used when a default is not provided to a
+   *        getter function
+   * @param options subscribe options
+   * @return subscriber
+   */
+  [[nodiscard]] SubscriberType Subscribe(
+      ParamType defaultValue,
+      const PubSubOptions& options = kDefaultPubSubOptions);
+
+  /**
+   * Create a new subscriber to the topic, with specific type string.
+   *
+   * <p>The subscriber is only active as long as the returned object
+   * is not destroyed.
+   *
+   * @note Subscribers that do not match the published data type do not return
+   *     any values. To determine if the data type matches, use the appropriate
+   *     Topic functions.
+   *
+   * @param typeString type string
+   * @param defaultValue default value used when a default is not provided to a
+   *        getter function
+   * @param options subscribe options
+   * @return subscriber
+   */
+  [[nodiscard]] SubscriberType SubscribeEx(
+      std::string_view typeString, ParamType defaultValue,
+      const PubSubOptions& options = kDefaultPubSubOptions);
+
+  /**
+   * Create a new publisher to the topic.
+   *
+   * The publisher is only active as long as the returned object
+   * is not destroyed.
+   *
+   * @note It is not possible to publish two different data types to the same
+   *     topic. Conflicts between publishers are typically resolved by the
+   *     server on a first-come, first-served basis. Any published values that
+   *     do not match the topic's data type are dropped (ignored). To determine
+   *     if the data type matches, use the appropriate Topic functions.
+   *
+   * @param options publish options
+   * @return publisher
+   */
+  [[nodiscard]] PublisherType Publish(
+      const PubSubOptions& options = kDefaultPubSubOptions);
+
+  /**
+   * Create a new publisher to the topic, with type string and initial
+   * properties.
+   *
+   * The publisher is only active as long as the returned object
+   * is not destroyed.
+   *
+   * @note It is not possible to publish two different data types to the same
+   *     topic. Conflicts between publishers are typically resolved by the
+   *     server on a first-come, first-served basis. Any published values that
+   *     do not match the topic's data type are dropped (ignored). To determine
+   *     if the data type matches, use the appropriate Topic functions.
+   *
+   * @param typeString type string
+   * @param properties JSON properties
+   * @param options publish options
+   * @return publisher
+   */
+  [[nodiscard]] PublisherType PublishEx(
+      std::string_view typeString, const wpi::json& properties,
+      const PubSubOptions& options = kDefaultPubSubOptions);
+
+  /**
+   * Create a new entry for the topic.
+   *
+   * Entries act as a combination of a subscriber and a weak publisher. The
+   * subscriber is active as long as the entry is not destroyed. The publisher
+   * is created when the entry is first written to, and remains active until
+   * either Unpublish() is called or the entry is destroyed.
+   *
+   * @note It is not possible to use two different data types with the same
+   *     topic. Conflicts between publishers are typically resolved by the
+   *     server on a first-come, first-served basis. Any published values that
+   *     do not match the topic's data type are dropped (ignored), and the entry
+   *     will show no new values if the data type does not match. To determine
+   *     if the data type matches, use the appropriate Topic functions.
+   *
+   * @param defaultValue default value used when a default is not provided to a
+   *        getter function
+   * @param options publish and/or subscribe options
+   * @return entry
+   */
+  [[nodiscard]] EntryType GetEntry(
+      ParamType defaultValue,
+      const PubSubOptions& options = kDefaultPubSubOptions);
+
+  /**
+   * Create a new entry for the topic, with specific type string.
+   *
+   * Entries act as a combination of a subscriber and a weak publisher. The
+   * subscriber is active as long as the entry is not destroyed. The publisher
+   * is created when the entry is first written to, and remains active until
+   * either Unpublish() is called or the entry is destroyed.
+   *
+   * @note It is not possible to use two different data types with the same
+   *     topic. Conflicts between publishers are typically resolved by the
+   *     server on a first-come, first-served basis. Any published values that
+   *     do not match the topic's data type are dropped (ignored), and the entry
+   *     will show no new values if the data type does not match. To determine
+   *     if the data type matches, use the appropriate Topic functions.
+   *
+   * @param typeString type string
+   * @param defaultValue default value used when a default is not provided to a
+   *        getter function
+   * @param options publish and/or subscribe options
+   * @return entry
+   */
+  [[nodiscard]] EntryType GetEntryEx(
+      std::string_view typeString, ParamType defaultValue,
+      const PubSubOptions& options = kDefaultPubSubOptions);
+};
+
+}  // namespace nt
+
+#include "networktables/UnitTopic.inc"
diff --git a/third_party/allwpilib/ntcore/src/main/native/include/networktables/UnitTopic.inc b/third_party/allwpilib/ntcore/src/main/native/include/networktables/UnitTopic.inc
new file mode 100644
index 0000000..c107526
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/main/native/include/networktables/UnitTopic.inc
@@ -0,0 +1,140 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <vector>
+
+#include <wpi/json.h>
+
+#include "networktables/NetworkTableType.h"
+#include "networktables/UnitTopic.h"
+#include "ntcore_cpp.h"
+
+namespace nt {
+
+template <typename T>
+inline UnitSubscriber<T>::UnitSubscriber(NT_Subscriber handle, T defaultValue)
+    : Subscriber{handle}, m_defaultValue{defaultValue} {}
+
+template <typename T>
+inline T UnitSubscriber<T>::Get() const {
+  return Get(m_defaultValue);
+}
+
+template <typename T>
+inline T UnitSubscriber<T>::Get(T defaultValue) const {
+  return T{::nt::GetDouble(m_subHandle, defaultValue.value())};
+}
+
+template <typename T>
+inline TimestampedUnit<T> UnitSubscriber<T>::GetAtomic() const {
+  return GetAtomic(m_defaultValue);
+}
+
+template <typename T>
+inline TimestampedUnit<T> UnitSubscriber<T>::GetAtomic(T defaultValue) const {
+  auto doubleVal = ::nt::GetAtomicDouble(m_subHandle, defaultValue.value());
+  return {doubleVal.time, doubleVal.serverTime, doubleVal.value};
+}
+
+template <typename T>
+inline std::vector<TimestampedUnit<T>> UnitSubscriber<T>::ReadQueue() {
+  std::vector<TimestampedUnit<T>> vals;
+  auto doubleVals = ::nt::ReadQueueDouble(m_subHandle);
+  vals.reserve(doubleVals.size());
+  for (auto&& val : doubleVals) {
+    vals.emplace_back(val.time, val.serverTime, val.value);
+  }
+}
+
+template <typename T>
+inline UnitTopic<T> UnitSubscriber<T>::GetTopic() const {
+  return UnitTopic<T>{::nt::GetTopicFromHandle(m_subHandle)};
+}
+
+template <typename T>
+inline UnitPublisher<T>::UnitPublisher(NT_Publisher handle)
+    : Publisher{handle} {}
+
+template <typename T>
+inline void UnitPublisher<T>::Set(T value, int64_t time) {
+  ::nt::SetDouble(m_pubHandle, value.value(), time);
+}
+
+template <typename T>
+inline void UnitPublisher<T>::SetDefault(T value) {
+  ::nt::SetDefaultDouble(m_pubHandle, value.value());
+}
+
+template <typename T>
+inline UnitTopic<T> UnitPublisher<T>::GetTopic() const {
+  return UnitTopic<T>{::nt::GetTopicFromHandle(m_pubHandle)};
+}
+
+template <typename T>
+inline UnitEntry<T>::UnitEntry(NT_Entry handle, T defaultValue)
+    : UnitSubscriber<T>{handle, defaultValue}, UnitPublisher<T>{handle} {}
+
+template <typename T>
+inline UnitTopic<T> UnitEntry<T>::GetTopic() const {
+  return UnitTopic<T>{::nt::GetTopicFromHandle(this->m_subHandle)};
+}
+
+template <typename T>
+inline void UnitEntry<T>::Unpublish() {
+  ::nt::Unpublish(this->m_pubHandle);
+}
+
+template <typename T>
+inline bool UnitTopic<T>::IsMatchingUnit() const {
+  return GetProperty("unit") == T{}.name();
+}
+
+template <typename T>
+inline UnitSubscriber<T> UnitTopic<T>::Subscribe(T defaultValue,
+                                                 const PubSubOptions& options) {
+  return UnitSubscriber<T>{
+      ::nt::Subscribe(m_handle, NT_DOUBLE, "double", options), defaultValue};
+}
+
+template <typename T>
+inline UnitSubscriber<T> UnitTopic<T>::SubscribeEx(
+    std::string_view typeString, T defaultValue, const PubSubOptions& options) {
+  return UnitSubscriber<T>{
+      ::nt::Subscribe(m_handle, NT_DOUBLE, typeString, options), defaultValue};
+}
+
+template <typename T>
+inline UnitPublisher<T> UnitTopic<T>::Publish(const PubSubOptions& options) {
+  return UnitPublisher<T>{::nt::PublishEx(m_handle, NT_DOUBLE, "double",
+                                          {{"unit", T{}.name()}}, options)};
+}
+
+template <typename T>
+inline UnitPublisher<T> UnitTopic<T>::PublishEx(std::string_view typeString,
+                                                const wpi::json& properties,
+                                                const PubSubOptions& options) {
+  wpi::json props = properties;
+  props["unit"] = T{}.name();
+  return UnitPublisher<T>{
+      ::nt::PublishEx(m_handle, NT_DOUBLE, typeString, props, options)};
+}
+
+template <typename T>
+inline UnitEntry<T> UnitTopic<T>::GetEntry(T defaultValue,
+                                           const PubSubOptions& options) {
+  return UnitEntry<T>{::nt::GetEntry(m_handle, NT_DOUBLE, "double", options),
+                      defaultValue};
+}
+
+template <typename T>
+inline UnitEntry<T> UnitTopic<T>::GetEntryEx(std::string_view typeString,
+                                             T defaultValue,
+                                             const PubSubOptions& options) {
+  return UnitEntry<T>{::nt::GetEntry(m_handle, NT_DOUBLE, typeString, options),
+                      defaultValue};
+}
+
+}  // namespace nt
diff --git a/third_party/allwpilib/ntcore/src/main/native/include/ntcore.h b/third_party/allwpilib/ntcore/src/main/native/include/ntcore.h
index 5cdd473..e4ae7f9 100644
--- a/third_party/allwpilib/ntcore/src/main/native/include/ntcore.h
+++ b/third_party/allwpilib/ntcore/src/main/native/include/ntcore.h
@@ -2,8 +2,7 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
-#ifndef NTCORE_NTCORE_H_
-#define NTCORE_NTCORE_H_
+#pragma once
 
 /* C API */
 #include "ntcore_c.h"
@@ -12,5 +11,3 @@
 /* C++ API */
 #include "ntcore_cpp.h"
 #endif /* __cplusplus */
-
-#endif  // NTCORE_NTCORE_H_
diff --git a/third_party/allwpilib/ntcore/src/main/native/include/ntcore_c.h b/third_party/allwpilib/ntcore/src/main/native/include/ntcore_c.h
index 3ee6d51..e9e9f81 100644
--- a/third_party/allwpilib/ntcore/src/main/native/include/ntcore_c.h
+++ b/third_party/allwpilib/ntcore/src/main/native/include/ntcore_c.h
@@ -2,8 +2,7 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
-#ifndef NTCORE_NTCORE_C_H_
-#define NTCORE_NTCORE_C_H_
+#pragma once
 
 #include <stdint.h>
 
@@ -29,19 +28,22 @@
 typedef int NT_Bool;
 
 typedef unsigned int NT_Handle;
-typedef NT_Handle NT_ConnectionListener;
-typedef NT_Handle NT_ConnectionListenerPoller;
+typedef NT_Handle NT_ConnectionDataLogger;
+typedef NT_Handle NT_DataLogger;
 typedef NT_Handle NT_Entry;
-typedef NT_Handle NT_EntryListener;
-typedef NT_Handle NT_EntryListenerPoller;
 typedef NT_Handle NT_Inst;
-typedef NT_Handle NT_Logger;
-typedef NT_Handle NT_LoggerPoller;
-typedef NT_Handle NT_RpcCall;
-typedef NT_Handle NT_RpcCallPoller;
+typedef NT_Handle NT_Listener;
+typedef NT_Handle NT_ListenerPoller;
+typedef NT_Handle NT_MultiSubscriber;
+typedef NT_Handle NT_Topic;
+typedef NT_Handle NT_Subscriber;
+typedef NT_Handle NT_Publisher;
 
-/** Default network tables port number */
-#define NT_DEFAULT_PORT 1735
+/** Default network tables port number (NT3) */
+#define NT_DEFAULT_PORT3 1735
+
+/** Default network tables port number (NT4) */
+#define NT_DEFAULT_PORT4 5810
 
 /** NetworkTables data types. */
 enum NT_Type {
@@ -53,11 +55,15 @@
   NT_BOOLEAN_ARRAY = 0x10,
   NT_DOUBLE_ARRAY = 0x20,
   NT_STRING_ARRAY = 0x40,
-  NT_RPC = 0x80
+  NT_RPC = 0x80,
+  NT_INTEGER = 0x100,
+  NT_FLOAT = 0x200,
+  NT_INTEGER_ARRAY = 0x400,
+  NT_FLOAT_ARRAY = 0x800
 };
 
 /** NetworkTables entry flags. */
-enum NT_EntryFlags { NT_PERSISTENT = 0x01 };
+enum NT_EntryFlags { NT_PERSISTENT = 0x01, NT_RETAINED = 0x02 };
 
 /** NetworkTables logging levels. */
 enum NT_LogLevel {
@@ -72,27 +78,47 @@
   NT_LOG_DEBUG4 = 6
 };
 
-/** NetworkTables notifier kinds. */
-enum NT_NotifyKind {
-  NT_NOTIFY_NONE = 0,
-  NT_NOTIFY_IMMEDIATE = 0x01, /* initial listener addition */
-  NT_NOTIFY_LOCAL = 0x02,     /* changed locally */
-  NT_NOTIFY_NEW = 0x04,       /* newly created entry */
-  NT_NOTIFY_DELETE = 0x08,    /* deleted */
-  NT_NOTIFY_UPDATE = 0x10,    /* value changed */
-  NT_NOTIFY_FLAGS = 0x20      /* flags changed */
-};
-
 /** Client/server modes */
 enum NT_NetworkMode {
   NT_NET_MODE_NONE = 0x00,     /* not running */
   NT_NET_MODE_SERVER = 0x01,   /* running in server mode */
-  NT_NET_MODE_CLIENT = 0x02,   /* running in client mode */
-  NT_NET_MODE_STARTING = 0x04, /* flag for starting (either client or server) */
-  NT_NET_MODE_FAILURE = 0x08,  /* flag for failure (either client or server) */
+  NT_NET_MODE_CLIENT3 = 0x02,  /* running in NT3 client mode */
+  NT_NET_MODE_CLIENT4 = 0x04,  /* running in NT4 client mode */
+  NT_NET_MODE_STARTING = 0x08, /* flag for starting (either client or server) */
   NT_NET_MODE_LOCAL = 0x10,    /* running in local-only mode */
 };
 
+/** Event notification flags. */
+enum NT_EventFlags {
+  NT_EVENT_NONE = 0,
+  /** Initial listener addition. */
+  NT_EVENT_IMMEDIATE = 0x01,
+  /** Client connected (on server, any client connected). */
+  NT_EVENT_CONNECTED = 0x02,
+  /** Client disconnected (on server, any client disconnected). */
+  NT_EVENT_DISCONNECTED = 0x04,
+  /** Any connection event (connect or disconnect). */
+  NT_EVENT_CONNECTION = NT_EVENT_CONNECTED | NT_EVENT_DISCONNECTED,
+  /** New topic published. */
+  NT_EVENT_PUBLISH = 0x08,
+  /** Topic unpublished. */
+  NT_EVENT_UNPUBLISH = 0x10,
+  /** Topic properties changed. */
+  NT_EVENT_PROPERTIES = 0x20,
+  /** Any topic event (publish, unpublish, or properties changed). */
+  NT_EVENT_TOPIC = NT_EVENT_PUBLISH | NT_EVENT_UNPUBLISH | NT_EVENT_PROPERTIES,
+  /** Topic value updated (via network). */
+  NT_EVENT_VALUE_REMOTE = 0x40,
+  /** Topic value updated (local). */
+  NT_EVENT_VALUE_LOCAL = 0x80,
+  /** Topic value updated (network or local). */
+  NT_EVENT_VALUE_ALL = NT_EVENT_VALUE_REMOTE | NT_EVENT_VALUE_LOCAL,
+  /** Log message. */
+  NT_EVENT_LOGMESSAGE = 0x100,
+  /** Time synchronized with server. */
+  NT_EVENT_TIMESYNC = 0x200,
+};
+
 /*
  * Structures
  */
@@ -117,12 +143,18 @@
 /** NetworkTables Entry Value.  Note this is a typed union. */
 struct NT_Value {
   enum NT_Type type;
-  uint64_t last_change;
+  int64_t last_change;
+  int64_t server_time;
   union {
     NT_Bool v_boolean;
+    int64_t v_int;
+    float v_float;
     double v_double;
     struct NT_String v_string;
-    struct NT_String v_raw;
+    struct {
+      uint8_t* data;
+      size_t size;
+    } v_raw;
     struct {
       NT_Bool* arr;
       size_t size;
@@ -132,35 +164,42 @@
       size_t size;
     } arr_double;
     struct {
+      float* arr;
+      size_t size;
+    } arr_float;
+    struct {
+      int64_t* arr;
+      size_t size;
+    } arr_int;
+    struct {
       struct NT_String* arr;
       size_t size;
     } arr_string;
   } data;
 };
 
-/** NetworkTables Entry Information */
-struct NT_EntryInfo {
-  /** Entry handle */
-  NT_Entry entry;
+/** NetworkTables Topic Information */
+struct NT_TopicInfo {
+  /** Topic handle */
+  NT_Topic topic;
 
-  /** Entry name */
+  /** Topic name */
   struct NT_String name;
 
-  /** Entry type */
+  /** Topic type */
   enum NT_Type type;
 
-  /** Entry flags */
-  unsigned int flags;
+  /** Topic type string */
+  struct NT_String type_str;
 
-  /** Timestamp of last change to entry (type or value). */
-  uint64_t last_change;
+  /** Topic properties JSON string */
+  struct NT_String properties;
 };
 
 /** NetworkTables Connection Information */
 struct NT_ConnectionInfo {
   /**
-   * The remote identifier (as set on the remote node by
-   * NetworkTableInstance::SetNetworkIdentity() or nt::SetNetworkIdentity()).
+   * The remote identifier (as set on the remote node by NT_StartClient4().
    */
   struct NT_String remote_id;
 
@@ -183,75 +222,20 @@
   unsigned int protocol_version;
 };
 
-/** NetworkTables RPC Version 1 Definition Parameter */
-struct NT_RpcParamDef {
-  struct NT_String name;
-  struct NT_Value def_value;
-};
+/** NetworkTables value event data. */
+struct NT_ValueEventData {
+  /** Topic handle. */
+  NT_Topic topic;
 
-/** NetworkTables RPC Version 1 Definition Result */
-struct NT_RpcResultDef {
-  struct NT_String name;
-  enum NT_Type type;
-};
-
-/** NetworkTables RPC Version 1 Definition */
-struct NT_RpcDefinition {
-  unsigned int version;
-  struct NT_String name;
-  size_t num_params;
-  struct NT_RpcParamDef* params;
-  size_t num_results;
-  struct NT_RpcResultDef* results;
-};
-
-/** NetworkTables RPC Call Data */
-struct NT_RpcAnswer {
-  NT_Entry entry;
-  NT_RpcCall call;
-  struct NT_String name;
-  struct NT_String params;
-  struct NT_ConnectionInfo conn;
-};
-
-/** NetworkTables Entry Notification */
-struct NT_EntryNotification {
-  /** Listener that was triggered. */
-  NT_EntryListener listener;
-
-  /** Entry handle. */
-  NT_Entry entry;
-
-  /** Entry name. */
-  struct NT_String name;
+  /** Subscriber/entry handle. */
+  NT_Handle subentry;
 
   /** The new value. */
   struct NT_Value value;
-
-  /**
-   * Update flags.  For example, NT_NOTIFY_NEW if the key did not previously
-   * exist.
-   */
-  unsigned int flags;
-};
-
-/** NetworkTables Connection Notification */
-struct NT_ConnectionNotification {
-  /** Listener that was triggered. */
-  NT_ConnectionListener listener;
-
-  /** True if event is due to connection being established. */
-  NT_Bool connected;
-
-  /** Connection info. */
-  struct NT_ConnectionInfo conn;
 };
 
 /** NetworkTables log message. */
 struct NT_LogMessage {
-  /** The logger that generated the message. */
-  NT_Logger logger;
-
   /** Log level of the message.  See NT_LogLevel. */
   unsigned int level;
 
@@ -265,6 +249,120 @@
   char* message;
 };
 
+/** NetworkTables time sync event data. */
+struct NT_TimeSyncEventData {
+  /**
+   * Offset between local time and server time, in microseconds. Add this value
+   * to local time to get the estimated equivalent server time.
+   */
+  int64_t serverTimeOffset;
+
+  /** Measured round trip time divided by 2, in microseconds. */
+  int64_t rtt2;
+
+  /**
+   * If serverTimeOffset and RTT are valid. An event with this set to false is
+   * sent when the client disconnects.
+   */
+  NT_Bool valid;
+};
+
+/** NetworkTables event */
+struct NT_Event {
+  /** Listener that triggered this event. */
+  NT_Handle listener;
+
+  /**
+   * Event flags (NT_EventFlags). Also indicates the data included with the
+   * event:
+   * - NT_EVENT_CONNECTED or NT_EVENT_DISCONNECTED: connInfo
+   * - NT_EVENT_PUBLISH, NT_EVENT_UNPUBLISH, or NT_EVENT_PROPERTIES: topicInfo
+   * - NT_EVENT_VALUE_REMOTE, NT_NOTIFY_VALUE_LOCAL: valueData
+   * - NT_EVENT_LOGMESSAGE: logMessage
+   * - NT_EVENT_TIMESYNC: timeSyncData
+   */
+  unsigned int flags;
+
+  /** Event data; content depends on flags. */
+  union {
+    struct NT_ConnectionInfo connInfo;
+    struct NT_TopicInfo topicInfo;
+    struct NT_ValueEventData valueData;
+    struct NT_LogMessage logMessage;
+    struct NT_TimeSyncEventData timeSyncData;
+  } data;
+};
+
+/** NetworkTables publish/subscribe options. */
+struct NT_PubSubOptions {
+  /**
+   * Structure size. Must be set to sizeof(NT_PubSubOptions).
+   */
+  unsigned int structSize;
+
+  /**
+   * Polling storage size for a subscription. Specifies the maximum number of
+   * updates NetworkTables should store between calls to the subscriber's
+   * ReadQueue() function. If zero, defaults to 1 if sendAll is false, 20 if
+   * sendAll is true.
+   */
+  unsigned int pollStorage;
+
+  /**
+   * How frequently changes will be sent over the network, in seconds.
+   * NetworkTables may send more frequently than this (e.g. use a combined
+   * minimum period for all values) or apply a restricted range to this value.
+   * The default is 100 ms.
+   */
+  double periodic;
+
+  /**
+   * For subscriptions, if non-zero, value updates for ReadQueue() are not
+   * queued for this publisher.
+   */
+  NT_Publisher excludePublisher;
+
+  /**
+   * Send all value changes over the network.
+   */
+  NT_Bool sendAll;
+
+  /**
+   * For subscriptions, don't ask for value changes (only topic announcements).
+   */
+  NT_Bool topicsOnly;
+
+  /**
+   * Perform prefix match on subscriber topic names. Is ignored/overridden by
+   * Subscribe() functions; only present in struct for the purposes of getting
+   * information about subscriptions.
+   */
+  NT_Bool prefixMatch;
+
+  /**
+   * Preserve duplicate value changes (rather than ignoring them).
+   */
+  NT_Bool keepDuplicates;
+
+  /**
+   * For subscriptions, if remote value updates should not be queued for
+   * ReadQueue(). See also disableLocal.
+   */
+  NT_Bool disableRemote;
+
+  /**
+   * For subscriptions, if local value updates should not be queued for
+   * ReadQueue(). See also disableRemote.
+   */
+  NT_Bool disableLocal;
+
+  /**
+   * For entries, don't queue (for ReadQueue) value updates for the entry's
+   * internal publisher.
+   */
+  NT_Bool excludeSelf;
+};
+
 /**
  * @defgroup ntcore_instance_cfunc Instance Functions
  * @{
@@ -319,25 +417,6 @@
 NT_Entry NT_GetEntry(NT_Inst inst, const char* name, size_t name_len);
 
 /**
- * Get Entry Handles.
- *
- * Returns an array of entry handles.  The results are optionally
- * filtered by string prefix and entry type to only return a subset of all
- * entries.
- *
- * @param inst       NetworkTable instance
- * @param prefix     entry name required prefix; only entries whose name starts
- *                   with this string are returned
- * @param prefix_len length of prefix in bytes
- * @param types      bitmask of NT_Type values; 0 is treated specially as a
- *                   "don't care"
- * @param count      stores number of entry handles returned
- * @return Array of entry handles.
- */
-NT_Entry* NT_GetEntries(NT_Inst inst, const char* prefix, size_t prefix_len,
-                        unsigned int types, size_t* count);
-
-/**
  * Gets the name of the specified entry.
  * Returns an empty string if the handle is invalid.
  *
@@ -406,21 +485,6 @@
 NT_Bool NT_SetEntryValue(NT_Entry entry, const struct NT_Value* value);
 
 /**
- * Set Entry Type and Value.
- *
- * Sets new entry value.  If type of new value differs from the type of the
- * currently stored entry, the currently stored entry type is overridden
- * (generally this will generate an Entry Assignment message).
- *
- * This is NOT the preferred method to update a value; generally
- * NT_SetEntryValue() should be used instead, with appropriate error handling.
- *
- * @param entry     entry handle
- * @param value     new entry value
- */
-void NT_SetEntryTypeValue(NT_Entry entry, const struct NT_Value* value);
-
-/**
  * Set Entry Flags.
  *
  * @param entry     entry handle
@@ -437,578 +501,544 @@
 unsigned int NT_GetEntryFlags(NT_Entry entry);
 
 /**
- * Delete Entry.
+ * Read Entry Queue.
  *
- * Deletes an entry.  This is a new feature in version 3.0 of the protocol,
- * so this may not have an effect if any other node in the network is not
- * version 3.0 or newer.
+ * Returns new entry values since last call. The returned array must be freed
+ * using NT_DisposeValueArray().
  *
- * Note: NT_GetConnections() can be used to determine the protocol version
- * of direct remote connection(s), but this is not sufficient to determine
- * if all nodes in the network are version 3.0 or newer.
- *
- * @param entry     entry handle
+ * @param subentry     subscriber or entry handle
+ * @param count        count of items in returned array (output)
+ * @return entry value array; returns NULL and count=0 if no new values
  */
-void NT_DeleteEntry(NT_Entry entry);
+struct NT_Value* NT_ReadQueueValue(NT_Handle subentry, size_t* count);
+
+/** @} */
 
 /**
- * Delete All Entries.
- *
- * Deletes ALL table entries.  This is a new feature in version 3.0 of the
- * so this may not have an effect if any other node in the network is not
- * version 3.0 or newer.
- *
- * Note: NT_GetConnections() can be used to determine the protocol version
- * of direct remote connection(s), but this is not sufficient to determine
- * if all nodes in the network are version 3.0 or newer.
- *
- * @param inst      instance handle
+ * @defgroup ntcore_topic_cfunc Topic Functions
+ * @{
  */
-void NT_DeleteAllEntries(NT_Inst inst);
 
 /**
- * Get Entry Information.
+ * Get Published Topic Handles.
  *
- * Returns an array of entry information (entry handle, name, entry type,
- * and timestamp of last change to type/value).  The results are optionally
- * filtered by string prefix and entry type to only return a subset of all
- * entries.
+ * Returns an array of topic handles.  The results are optionally
+ * filtered by string prefix and type to only return a subset of all
+ * topics.
  *
  * @param inst          instance handle
- * @param prefix        entry name required prefix; only entries whose name
+ * @param prefix        name required prefix; only topics whose name
  *                      starts with this string are returned
  * @param prefix_len    length of prefix in bytes
  * @param types         bitmask of NT_Type values; 0 is treated specially
  *                      as a "don't care"
  * @param count         output parameter; set to length of returned array
- * @return Array of entry information.
+ * @return Array of topic handles.
  */
-struct NT_EntryInfo* NT_GetEntryInfo(NT_Inst inst, const char* prefix,
-                                     size_t prefix_len, unsigned int types,
-                                     size_t* count);
+NT_Topic* NT_GetTopics(NT_Inst inst, const char* prefix, size_t prefix_len,
+                       unsigned int types, size_t* count);
 
 /**
- * Get Entry Information.
+ * Get Published Topic Handles.
  *
- * Returns information about an entry (name, entry type,
- * and timestamp of last change to type/value).
+ * Returns an array of topic handles.  The results are optionally
+ * filtered by string prefix and type to only return a subset of all
+ * topics.
  *
- * @param entry         entry handle
- * @param info          entry information (output)
+ * @param inst          instance handle
+ * @param prefix        name required prefix; only topics whose name
+ *                      starts with this string are returned
+ * @param prefix_len    length of prefix in bytes
+ * @param types         array of type strings
+ * @param types_len     number of elements in types array
+ * @param count         output parameter; set to length of returned array
+ * @return Array of topic handles.
+ */
+NT_Topic* NT_GetTopicsStr(NT_Inst inst, const char* prefix, size_t prefix_len,
+                          const char* const* types, size_t types_len,
+                          size_t* count);
+
+/**
+ * Get Topics.
+ *
+ * Returns an array of topic information (handle, name, type).  The results are
+ * optionally filtered by string prefix and type to only return a subset
+ * of all topics.
+ *
+ * @param inst          instance handle
+ * @param prefix        name required prefix; only topics whose name
+ *                      starts with this string are returned
+ * @param prefix_len    length of prefix in bytes
+ * @param types         bitmask of NT_Type values; 0 is treated specially
+ *                      as a "don't care"
+ * @param count         output parameter; set to length of returned array
+ * @return Array of topic information.
+ */
+struct NT_TopicInfo* NT_GetTopicInfos(NT_Inst inst, const char* prefix,
+                                      size_t prefix_len, unsigned int types,
+                                      size_t* count);
+
+/**
+ * Get Topics.
+ *
+ * Returns an array of topic information (handle, name, type).  The results are
+ * optionally filtered by string prefix and type to only return a subset
+ * of all topics.
+ *
+ * @param inst          instance handle
+ * @param prefix        name required prefix; only topics whose name
+ *                      starts with this string are returned
+ * @param prefix_len    length of prefix in bytes
+ * @param types         array of type strings
+ * @param types_len     number of elements in types array
+ * @param count         output parameter; set to length of returned array
+ * @return Array of topic information.
+ */
+struct NT_TopicInfo* NT_GetTopicInfosStr(NT_Inst inst, const char* prefix,
+                                         size_t prefix_len,
+                                         const char* const* types,
+                                         size_t types_len, size_t* count);
+
+/**
+ * Gets Topic Information.
+ *
+ * Returns information about a topic (name and type).
+ *
+ * @param topic         handle
+ * @param info          information (output)
  * @return True if successful, false on error.
  */
-NT_Bool NT_GetEntryInfoHandle(NT_Entry entry, struct NT_EntryInfo* info);
+NT_Bool NT_GetTopicInfo(NT_Topic topic, struct NT_TopicInfo* info);
+
+/**
+ * Gets Topic Handle.
+ *
+ * Returns topic handle.
+ *
+ * @param inst      instance handle
+ * @param name      topic name
+ * @param name_len  length of topic name in bytes
+ * @return Topic handle.
+ */
+NT_Topic NT_GetTopic(NT_Inst inst, const char* name, size_t name_len);
+
+/**
+ * Gets the name of the specified topic.
+ *
+ * @param topic     topic handle
+ * @param name_len  length of topic name (output)
+ * @return Topic name; returns NULL and name_len=0 if the handle is invalid.
+ */
+char* NT_GetTopicName(NT_Topic topic, size_t* name_len);
+
+/**
+ * Gets the type for the specified topic, or unassigned if non existent.
+ *
+ * @param topic   topic handle
+ * @return Topic type
+ */
+enum NT_Type NT_GetTopicType(NT_Topic topic);
+
+/**
+ * Gets the type string for the specified topic.  This may have more information
+ * than the numeric type (especially for raw values).
+ *
+ * @param topic     topic handle
+ * @param type_len  length of type string (output)
+ * @return Topic type string; returns NULL if non-existent
+ */
+char* NT_GetTopicTypeString(NT_Topic topic, size_t* type_len);
+
+/**
+ * Sets the persistent property of a topic.  If true, the stored value is
+ * persistent through server restarts.
+ *
+ * @param topic topic handle
+ * @param value True for persistent, false for not persistent.
+ */
+void NT_SetTopicPersistent(NT_Topic topic, NT_Bool value);
+
+/**
+ * Gets the persistent property of a topic.
+ *
+ * @param topic topic handle
+ * @return persistent property value
+ */
+NT_Bool NT_GetTopicPersistent(NT_Topic topic);
+
+/**
+ * Sets the retained property of a topic.  If true, the server retains the
+ * topic even when there are no publishers.
+ *
+ * @param topic topic handle
+ * @param value new retained property value
+ */
+void NT_SetTopicRetained(NT_Topic topic, NT_Bool value);
+
+/**
+ * Gets the retained property of a topic.
+ *
+ * @param topic topic handle
+ * @return retained property value
+ */
+NT_Bool NT_GetTopicRetained(NT_Topic topic);
+
+/**
+ * Determine if topic exists (e.g. has at least one publisher).
+ *
+ * @param handle Topic, entry, or subscriber handle.
+ * @return True if topic exists.
+ */
+NT_Bool NT_GetTopicExists(NT_Handle handle);
+
+/**
+ * Gets the current value of a property (as a JSON string).
+ *
+ * @param topic topic handle
+ * @param name property name
+ * @param len length of returned string (output)
+ * @return JSON string; empty string if the property does not exist.
+ */
+char* NT_GetTopicProperty(NT_Topic topic, const char* name, size_t* len);
+
+/**
+ * Sets a property value.
+ *
+ * @param topic topic handle
+ * @param name property name
+ * @param value property value (JSON string)
+ */
+NT_Bool NT_SetTopicProperty(NT_Topic topic, const char* name,
+                            const char* value);
+
+/**
+ * Deletes a property.  Has no effect if the property does not exist.
+ *
+ * @param topic topic handle
+ * @param name property name
+ */
+void NT_DeleteTopicProperty(NT_Topic topic, const char* name);
+
+/**
+ * Gets all topic properties as a JSON string.  Each key in the object
+ * is the property name, and the corresponding value is the property value.
+ *
+ * @param topic topic handle
+ * @param len length of returned string (output)
+ * @return JSON string
+ */
+char* NT_GetTopicProperties(NT_Topic topic, size_t* len);
+
+/**
+ * Updates multiple topic properties.  Each key in the passed-in JSON object is
+ * the name of the property to add/update, and the corresponding value is the
+ * property value to set for that property.  Null values result in deletion
+ * of the corresponding property.
+ *
+ * @param topic topic handle
+ * @param properties JSON object string with keys to add/update/delete
+ * @return False if properties are not a valid JSON object
+ */
+NT_Bool NT_SetTopicProperties(NT_Topic topic, const char* properties);
+
+/**
+ * Creates a new subscriber to value changes on a topic.
+ *
+ * @param topic topic handle
+ * @param type expected type
+ * @param typeStr expected type string
+ * @param options subscription options
+ * @return Subscriber handle
+ */
+NT_Subscriber NT_Subscribe(NT_Topic topic, enum NT_Type type,
+                           const char* typeStr,
+                           const struct NT_PubSubOptions* options);
+
+/**
+ * Stops subscriber.
+ *
+ * @param sub subscriber handle
+ */
+void NT_Unsubscribe(NT_Subscriber sub);
+
+/**
+ * Creates a new publisher to a topic.
+ *
+ * @param topic topic handle
+ * @param type type
+ * @param typeStr type string
+ * @param options publish options
+ * @return Publisher handle
+ */
+NT_Publisher NT_Publish(NT_Topic topic, enum NT_Type type, const char* typeStr,
+                        const struct NT_PubSubOptions* options);
+
+/**
+ * Creates a new publisher to a topic.
+ *
+ * @param topic topic handle
+ * @param type type
+ * @param typeStr type string
+ * @param properties initial properties (JSON object)
+ * @param options publish options
+ * @return Publisher handle
+ */
+NT_Publisher NT_PublishEx(NT_Topic topic, enum NT_Type type,
+                          const char* typeStr, const char* properties,
+                          const struct NT_PubSubOptions* options);
+
+/**
+ * Stops publisher.
+ *
+ * @param pubentry publisher/entry handle
+ */
+void NT_Unpublish(NT_Handle pubentry);
+
+/**
+ * @brief Creates a new entry (subscriber and weak publisher) to a topic.
+ *
+ * @param topic topic handle
+ * @param type type
+ * @param typeStr type string
+ * @param options publish options
+ * @return Entry handle
+ */
+NT_Entry NT_GetEntryEx(NT_Topic topic, enum NT_Type type, const char* typeStr,
+                       const struct NT_PubSubOptions* options);
+
+/**
+ * Stops entry subscriber/publisher.
+ *
+ * @param entry entry handle
+ */
+void NT_ReleaseEntry(NT_Entry entry);
+
+/**
+ * Stops entry/subscriber/publisher.
+ *
+ * @param pubsubentry entry/subscriber/publisher handle
+ */
+void NT_Release(NT_Handle pubsubentry);
+
+/**
+ * Gets the topic handle from an entry/subscriber/publisher handle.
+ *
+ * @param pubsubentry entry/subscriber/publisher handle
+ * @return Topic handle
+ */
+NT_Topic NT_GetTopicFromHandle(NT_Handle pubsubentry);
 
 /** @} */
 
 /**
- * @defgroup ntcore_entrylistener_cfunc Entry Listener Functions
+ * @defgroup ntcore_advancedsub_cfunc Advanced Subscriber Functions
  * @{
  */
 
 /**
- * Entry listener callback function.
- * Called when a key-value pair is changed.
+ * Subscribes to multiple topics based on one or more topic name prefixes. Can
+ * be used in combination with a Value Listener or ReadQueueValue() to get value
+ * changes across all matching topics.
  *
- * @param data            data pointer provided to callback creation function
- * @param event           event information
+ * @param inst instance handle
+ * @param prefixes topic name prefixes
+ * @param prefixes_len number of elements in prefixes array
+ * @param options subscriber options
+ * @return subscriber handle
  */
-typedef void (*NT_EntryListenerCallback)(
-    void* data, const struct NT_EntryNotification* event);
+NT_MultiSubscriber NT_SubscribeMultiple(NT_Inst inst,
+                                        const struct NT_String* prefixes,
+                                        size_t prefixes_len,
+                                        const struct NT_PubSubOptions* options);
 
 /**
- * Add a listener for all entries starting with a certain prefix.
+ * Unsubscribes a multi-subscriber.
  *
- * @param inst              instance handle
- * @param prefix            UTF-8 string prefix
- * @param prefix_len        length of prefix in bytes
- * @param data              data pointer to pass to callback
- * @param callback          listener to add
- * @param flags             NT_NotifyKind bitmask
- * @return Listener handle
+ * @param sub multi-subscriber handle
  */
-NT_EntryListener NT_AddEntryListener(NT_Inst inst, const char* prefix,
-                                     size_t prefix_len, void* data,
-                                     NT_EntryListenerCallback callback,
-                                     unsigned int flags);
-
-/**
- * Add a listener for a single entry.
- *
- * @param entry             entry handle
- * @param data              data pointer to pass to callback
- * @param callback          listener to add
- * @param flags             NT_NotifyKind bitmask
- * @return Listener handle
- */
-NT_EntryListener NT_AddEntryListenerSingle(NT_Entry entry, void* data,
-                                           NT_EntryListenerCallback callback,
-                                           unsigned int flags);
-
-/**
- * Create a entry listener poller.
- *
- * A poller provides a single queue of poll events.  Events linked to this
- * poller (using NT_AddPolledEntryListener()) will be stored in the queue and
- * must be collected by calling NT_PollEntryListener().
- * The returned handle must be destroyed with NT_DestroyEntryListenerPoller().
- *
- * @param inst      instance handle
- * @return poller handle
- */
-NT_EntryListenerPoller NT_CreateEntryListenerPoller(NT_Inst inst);
-
-/**
- * Destroy a entry listener poller.  This will abort any blocked polling
- * call and prevent additional events from being generated for this poller.
- *
- * @param poller    poller handle
- */
-void NT_DestroyEntryListenerPoller(NT_EntryListenerPoller poller);
-
-/**
- * Create a polled entry listener.
- * The caller is responsible for calling NT_PollEntryListener() to poll.
- *
- * @param poller            poller handle
- * @param prefix            UTF-8 string prefix
- * @param prefix_len        Length of UTF-8 string prefix
- * @param flags             NT_NotifyKind bitmask
- * @return Listener handle
- */
-NT_EntryListener NT_AddPolledEntryListener(NT_EntryListenerPoller poller,
-                                           const char* prefix,
-                                           size_t prefix_len,
-                                           unsigned int flags);
-
-/**
- * Create a polled entry listener.
- * The caller is responsible for calling NT_PollEntryListener() to poll.
- *
- * @param poller            poller handle
- * @param entry             entry handle
- * @param flags             NT_NotifyKind bitmask
- * @return Listener handle
- */
-NT_EntryListener NT_AddPolledEntryListenerSingle(NT_EntryListenerPoller poller,
-                                                 NT_Entry entry,
-                                                 unsigned int flags);
-
-/**
- * Get the next entry listener event.  This blocks until the next event occurs.
- *
- * This is intended to be used with NT_AddPolledEntryListener(void); entry
- * listeners created using NT_AddEntryListener() will not be serviced through
- * this function.
- *
- * @param poller    poller handle
- * @param len       length of returned array (output)
- * @return Array of information on the entry listener events.  Returns NULL if
- *         an erroroccurred (e.g. the instance was invalid or is shutting down).
- */
-struct NT_EntryNotification* NT_PollEntryListener(NT_EntryListenerPoller poller,
-                                                  size_t* len);
-
-/**
- * Get the next entry listener event.  This blocks until the next event occurs
- * or it times out.  This is intended to be used with
- * NT_AddPolledEntryListener(); entry listeners created using
- * NT_AddEntryListener() will not be serviced through this function.
- *
- * @param poller      poller handle
- * @param len         length of returned array (output)
- * @param timeout     timeout, in seconds
- * @param timed_out   true if the timeout period elapsed (output)
- * @return Array of information on the entry listener events.  If NULL is
- *         returned and timed_out is also false, an error occurred (e.g. the
- *         instance was invalid or is shutting down).
- */
-struct NT_EntryNotification* NT_PollEntryListenerTimeout(
-    NT_EntryListenerPoller poller, size_t* len, double timeout,
-    NT_Bool* timed_out);
-
-/**
- * Cancel a PollEntryListener call.  This wakes up a call to
- * PollEntryListener for this poller and causes it to immediately return
- * an empty array.
- *
- * @param poller  poller handle
- */
-void NT_CancelPollEntryListener(NT_EntryListenerPoller poller);
-
-/**
- * Remove an entry listener.
- *
- * @param entry_listener Listener handle to remove
- */
-void NT_RemoveEntryListener(NT_EntryListener entry_listener);
-
-/**
- * Wait for the entry listener queue to be empty.  This is primarily useful
- * for deterministic testing.  This blocks until either the entry listener
- * queue is empty (e.g. there are no more events that need to be passed along
- * to callbacks or poll queues) or the timeout expires.
- *
- * @param inst      instance handle
- * @param timeout   timeout, in seconds.  Set to 0 for non-blocking behavior,
- *                  or a negative value to block indefinitely
- * @return False if timed out, otherwise true.
- */
-NT_Bool NT_WaitForEntryListenerQueue(NT_Inst inst, double timeout);
+void NT_UnsubscribeMultiple(NT_MultiSubscriber sub);
 
 /** @} */
 
 /**
- * @defgroup ntcore_connectionlistener_cfunc Connection Listener Functions
+ * @defgroup ntcore_listener_cfunc Listener Functions
  * @{
  */
 
 /**
- * Connection listener callback function.
- * Called when a network connection is made or lost.
+ * Event listener callback function.
  *
  * @param data            data pointer provided to callback creation function
  * @param event           event info
  */
-typedef void (*NT_ConnectionListenerCallback)(
-    void* data, const struct NT_ConnectionNotification* event);
+typedef void (*NT_ListenerCallback)(void* data, const struct NT_Event* event);
 
 /**
- * Add a connection listener.
+ * Creates a listener poller.
  *
- * @param inst              instance handle
- * @param data              data pointer to pass to callback
- * @param callback          listener to add
- * @param immediate_notify  notify listener of all existing connections
- * @return Listener handle
- */
-NT_ConnectionListener NT_AddConnectionListener(
-    NT_Inst inst, void* data, NT_ConnectionListenerCallback callback,
-    NT_Bool immediate_notify);
-
-/**
- * Create a connection listener poller.
  * A poller provides a single queue of poll events.  Events linked to this
- * poller (using NT_AddPolledConnectionListener()) will be stored in the queue
- * and must be collected by calling NT_PollConnectionListener().
- * The returned handle must be destroyed with
- * NT_DestroyConnectionListenerPoller().
+ * poller (using NT_AddPolledXListener()) will be stored in the queue and
+ * must be collected by calling NT_ReadListenerQueue().
+ * The returned handle must be destroyed with NT_DestroyListenerPoller().
  *
  * @param inst      instance handle
  * @return poller handle
  */
-NT_ConnectionListenerPoller NT_CreateConnectionListenerPoller(NT_Inst inst);
+NT_ListenerPoller NT_CreateListenerPoller(NT_Inst inst);
 
 /**
- * Destroy a connection listener poller.  This will abort any blocked polling
+ * Destroys a listener poller.  This will abort any blocked polling
  * call and prevent additional events from being generated for this poller.
  *
  * @param poller    poller handle
  */
-void NT_DestroyConnectionListenerPoller(NT_ConnectionListenerPoller poller);
+void NT_DestroyListenerPoller(NT_ListenerPoller poller);
 
 /**
- * Create a polled connection listener.
- * The caller is responsible for calling NT_PollConnectionListener() to poll.
- *
- * @param poller            poller handle
- * @param immediate_notify  notify listener of all existing connections
- */
-NT_ConnectionListener NT_AddPolledConnectionListener(
-    NT_ConnectionListenerPoller poller, NT_Bool immediate_notify);
-
-/**
- * Get the next connection event.  This blocks until the next connect or
- * disconnect occurs.  This is intended to be used with
- * NT_AddPolledConnectionListener(); connection listeners created using
- * NT_AddConnectionListener() will not be serviced through this function.
+ * Read notifications.
  *
  * @param poller    poller handle
  * @param len       length of returned array (output)
- * @return Array of information on the connection events.  Only returns NULL
- *         if an error occurred (e.g. the instance was invalid or is shutting
- *         down).
+ * @return Array of events.  Returns NULL and len=0 if no events since last
+ *         call.
  */
-struct NT_ConnectionNotification* NT_PollConnectionListener(
-    NT_ConnectionListenerPoller poller, size_t* len);
+struct NT_Event* NT_ReadListenerQueue(NT_ListenerPoller poller, size_t* len);
 
 /**
- * Get the next connection event.  This blocks until the next connect or
- * disconnect occurs or it times out.  This is intended to be used with
- * NT_AddPolledConnectionListener(); connection listeners created using
- * NT_AddConnectionListener() will not be serviced through this function.
+ * Removes a listener.
  *
- * @param poller      poller handle
- * @param len         length of returned array (output)
- * @param timeout     timeout, in seconds
- * @param timed_out   true if the timeout period elapsed (output)
- * @return Array of information on the connection events.  If NULL is returned
- *         and timed_out is also false, an error occurred (e.g. the instance
- *         was invalid or is shutting down).
+ * @param listener Listener handle to remove
  */
-struct NT_ConnectionNotification* NT_PollConnectionListenerTimeout(
-    NT_ConnectionListenerPoller poller, size_t* len, double timeout,
-    NT_Bool* timed_out);
+void NT_RemoveListener(NT_Listener listener);
 
 /**
- * Cancel a PollConnectionListener call.  This wakes up a call to
- * PollConnectionListener for this poller and causes it to immediately return
- * an empty array.
+ * Wait for the listener queue to be empty. This is primarily useful
+ * for deterministic testing. This blocks until either the listener
+ * queue is empty (e.g. there are no more events that need to be passed along to
+ * callbacks or poll queues) or the timeout expires.
  *
- * @param poller  poller handle
- */
-void NT_CancelPollConnectionListener(NT_ConnectionListenerPoller poller);
-
-/**
- * Remove a connection listener.
- *
- * @param conn_listener Listener handle to remove
- */
-void NT_RemoveConnectionListener(NT_ConnectionListener conn_listener);
-
-/**
- * Wait for the connection listener queue to be empty.  This is primarily useful
- * for deterministic testing.  This blocks until either the connection listener
- * queue is empty (e.g. there are no more events that need to be passed along
- * to callbacks or poll queues) or the timeout expires.
- *
- * @param inst      instance handle
- * @param timeout   timeout, in seconds.  Set to 0 for non-blocking behavior,
- *                  or a negative value to block indefinitely
+ * @param handle  handle
+ * @param timeout timeout, in seconds. Set to 0 for non-blocking behavior, or a
+ *                negative value to block indefinitely
  * @return False if timed out, otherwise true.
  */
-NT_Bool NT_WaitForConnectionListenerQueue(NT_Inst inst, double timeout);
-
-/** @} */
+NT_Bool NT_WaitForListenerQueue(NT_Handle handle, double timeout);
 
 /**
- * @defgroup ntcore_rpc_cfunc Remote Procedure Call Functions
- * @{
+ * Create a listener for changes to topics with names that start with
+ * the given prefix. This creates a corresponding internal subscriber with the
+ * lifetime of the listener.
+ *
+ * @param inst Instance handle
+ * @param prefix Topic name string prefix
+ * @param prefix_len Length of topic name string prefix
+ * @param mask Bitmask of NT_EventFlags values (only topic and value events will
+ *             be generated)
+ * @param data Data passed to callback function
+ * @param callback Listener function
+ * @return Listener handle
  */
+NT_Listener NT_AddListenerSingle(NT_Inst inst, const char* prefix,
+                                 size_t prefix_len, unsigned int mask,
+                                 void* data, NT_ListenerCallback callback);
 
 /**
- * Remote Procedure Call (RPC) callback function.
+ * Create a listener for changes to topics with names that start with any of
+ * the given prefixes. This creates a corresponding internal subscriber with the
+ * lifetime of the listener.
  *
- * @param data        data pointer provided to NT_CreateRpc()
- * @param call        call information
- *
- * Note: NT_PostRpcResponse() must be called by the callback to provide a
- * response to the call.
+ * @param inst Instance handle
+ * @param prefixes Topic name string prefixes
+ * @param prefixes_len Number of elements in prefixes array
+ * @param mask Bitmask of NT_EventFlags values (only topic and value events will
+ *             be generated)
+ * @param data Data passed to callback function
+ * @param callback Listener function
+ * @return Listener handle
  */
-typedef void (*NT_RpcCallback)(void* data, const struct NT_RpcAnswer* call);
+NT_Listener NT_AddListenerMultiple(NT_Inst inst,
+                                   const struct NT_String* prefixes,
+                                   size_t prefixes_len, unsigned int mask,
+                                   void* data, NT_ListenerCallback callback);
 
 /**
- * Create a callback-based RPC entry point.  Only valid to use on the server.
- * The callback function will be called when the RPC is called.
+ * Create a listener.
  *
- * @param entry     entry handle of RPC entry
- * @param def       RPC definition
- * @param def_len   length of def in bytes
- * @param data      data pointer to pass to callback function
- * @param callback  callback function
+ * Some combinations of handle and mask have no effect:
+ * - connection and log message events are only generated on instances
+ * - topic and value events are only generated on non-instances
+ *
+ * Adding value and topic events on a topic will create a corresponding internal
+ * subscriber with the lifetime of the listener.
+ *
+ * Adding a log message listener through this function will only result in
+ * events at NT_LOG_INFO or higher; for more customized settings, use
+ * NT_AddLogger().
+ *
+ * @param handle Handle
+ * @param mask Bitmask of NT_EventFlags values
+ * @param data Data passed to callback function
+ * @param callback Listener function
+ * @return Listener handle
  */
-void NT_CreateRpc(NT_Entry entry, const char* def, size_t def_len, void* data,
-                  NT_RpcCallback callback);
+NT_Listener NT_AddListener(NT_Handle handle, unsigned int mask, void* data,
+                           NT_ListenerCallback callback);
 
 /**
- * Create a RPC call poller.  Only valid to use on the server.
+ * Creates a polled topic listener. This creates a corresponding internal
+ * subscriber with the lifetime of the listener.
+ * The caller is responsible for calling NT_ReadListenerQueue() to poll.
  *
- * A poller provides a single queue of poll events.  Events linked to this
- * poller (using NT_CreatePolledRpc()) will be stored in the queue and must be
- * collected by calling NT_PollRpc() or NT_PollRpcTimeout().
- * The returned handle must be destroyed with NT_DestroyRpcCallPoller().
- *
- * @param inst      instance handle
- * @return poller handle
+ * @param poller            poller handle
+ * @param prefix            UTF-8 string prefix
+ * @param prefix_len        Length of UTF-8 string prefix
+ * @param mask              NT_EventFlags bitmask (only topic and value events
+ * will be generated)
+ * @return Listener handle
  */
-NT_RpcCallPoller NT_CreateRpcCallPoller(NT_Inst inst);
+NT_Listener NT_AddPolledListenerSingle(NT_ListenerPoller poller,
+                                       const char* prefix, size_t prefix_len,
+                                       unsigned int mask);
 
 /**
- * Destroy a RPC call poller.  This will abort any blocked polling call and
- * prevent additional events from being generated for this poller.
+ * Creates a polled topic listener. This creates a corresponding internal
+ * subscriber with the lifetime of the listener.
+ * The caller is responsible for calling NT_ReadListenerQueue() to poll.
  *
- * @param poller    poller handle
+ * @param poller            poller handle
+ * @param prefixes          array of UTF-8 string prefixes
+ * @param prefixes_len      Length of prefixes array
+ * @param mask              NT_EventFlags bitmask (only topic and value events
+ * will be generated)
+ * @return Listener handle
  */
-void NT_DestroyRpcCallPoller(NT_RpcCallPoller poller);
+NT_Listener NT_AddPolledListenerMultiple(NT_ListenerPoller poller,
+                                         const struct NT_String* prefixes,
+                                         size_t prefixes_len,
+                                         unsigned int mask);
 
 /**
- * Create a polled RPC entry point.  Only valid to use on the server.
+ * Creates a polled listener.
+ * The caller is responsible for calling NT_ReadListenerQueue() to poll.
  *
- * The caller is responsible for calling NT_PollRpc() or NT_PollRpcTimeout()
- * to poll for servicing incoming RPC calls.
+ * Some combinations of handle and mask have no effect:
+ * - connection and log message events are only generated on instances
+ * - topic and value events are only generated on non-instances
  *
- * @param entry     entry handle of RPC entry
- * @param def       RPC definition
- * @param def_len   length of def in bytes
- * @param poller    poller handle
+ * Adding value and topic events on a topic will create a corresponding internal
+ * subscriber with the lifetime of the listener.
+ *
+ * Adding a log message listener through this function will only result in
+ * events at NT_LOG_INFO or higher; for more customized settings, use
+ * NT_AddPolledLogger().
+ *
+ * @param poller            poller handle
+ * @param handle            handle
+ * @param mask              NT_NotifyKind bitmask
+ * @return Listener handle
  */
-void NT_CreatePolledRpc(NT_Entry entry, const char* def, size_t def_len,
-                        NT_RpcCallPoller poller);
-
-/**
- * Get the next incoming RPC call.  This blocks until the next incoming RPC
- * call is received.  This is intended to be used with NT_CreatePolledRpc(void);
- * RPC calls created using NT_CreateRpc() will not be serviced through this
- * function.  Upon successful return, NT_PostRpcResponse() must be called to
- * send the return value to the caller.  The returned array must be freed
- * using NT_DisposeRpcAnswerArray().
- *
- * @param poller      poller handle
- * @param len         length of returned array (output)
- * @return Array of RPC call information.  Only returns NULL if an error
- *         occurred (e.g. the instance was invalid or is shutting down).
- */
-struct NT_RpcAnswer* NT_PollRpc(NT_RpcCallPoller poller, size_t* len);
-
-/**
- * Get the next incoming RPC call.  This blocks until the next incoming RPC
- * call is received or it times out.  This is intended to be used with
- * NT_CreatePolledRpc(); RPC calls created using NT_CreateRpc() will not be
- * serviced through this function.  Upon successful return,
- * NT_PostRpcResponse() must be called to send the return value to the caller.
- * The returned array must be freed using NT_DisposeRpcAnswerArray().
- *
- * @param poller      poller handle
- * @param len         length of returned array (output)
- * @param timeout     timeout, in seconds
- * @param timed_out   true if the timeout period elapsed (output)
- * @return Array of RPC call information.  If NULL is returned and timed_out
- *         is also false, an error occurred (e.g. the instance was invalid or
- *         is shutting down).
- */
-struct NT_RpcAnswer* NT_PollRpcTimeout(NT_RpcCallPoller poller, size_t* len,
-                                       double timeout, NT_Bool* timed_out);
-
-/**
- * Cancel a PollRpc call.  This wakes up a call to PollRpc for this poller
- * and causes it to immediately return an empty array.
- *
- * @param poller  poller handle
- */
-void NT_CancelPollRpc(NT_RpcCallPoller poller);
-
-/**
- * Wait for the incoming RPC call queue to be empty.  This is primarily useful
- * for deterministic testing.  This blocks until either the RPC call
- * queue is empty (e.g. there are no more events that need to be passed along
- * to callbacks or poll queues) or the timeout expires.
- *
- * @param inst      instance handle
- * @param timeout   timeout, in seconds.  Set to 0 for non-blocking behavior,
- *                  or a negative value to block indefinitely
- * @return False if timed out, otherwise true.
- */
-NT_Bool NT_WaitForRpcCallQueue(NT_Inst inst, double timeout);
-
-/**
- * Post RPC response (return value) for a polled RPC.
- *
- * The rpc and call parameters should come from the NT_RpcAnswer returned
- * by NT_PollRpc().
- *
- * @param entry       entry handle of RPC entry (from NT_RpcAnswer)
- * @param call        RPC call handle (from NT_RpcAnswer)
- * @param result      result raw data that will be provided to remote caller
- * @param result_len  length of result in bytes
- * @return            true if the response was posted, otherwise false
- */
-NT_Bool NT_PostRpcResponse(NT_Entry entry, NT_RpcCall call, const char* result,
-                           size_t result_len);
-
-/**
- * Call a RPC function.  May be used on either the client or server.
- *
- * This function is non-blocking.  Either NT_GetRpcResult() or
- * NT_CancelRpcResult() must be called to either get or ignore the result of
- * the call.
- *
- * @param entry       entry handle of RPC entry
- * @param params      parameter
- * @param params_len  length of param in bytes
- * @return RPC call handle (for use with NT_GetRpcResult() or
- *         NT_CancelRpcResult()).
- */
-NT_RpcCall NT_CallRpc(NT_Entry entry, const char* params, size_t params_len);
-
-/**
- * Get the result (return value) of a RPC call.  This function blocks until
- * the result is received.
- *
- * @param entry       entry handle of RPC entry
- * @param call        RPC call handle returned by NT_CallRpc()
- * @param result_len  length of returned result in bytes
- * @return NULL on error, or result.
- */
-char* NT_GetRpcResult(NT_Entry entry, NT_RpcCall call, size_t* result_len);
-
-/**
- * Get the result (return value) of a RPC call.  This function blocks until
- * the result is received or it times out.
- *
- * @param entry       entry handle of RPC entry
- * @param call        RPC call handle returned by NT_CallRpc()
- * @param result_len  length of returned result in bytes
- * @param timeout     timeout, in seconds
- * @param timed_out   true if the timeout period elapsed (output)
- * @return NULL on error or timeout, or result.
- */
-char* NT_GetRpcResultTimeout(NT_Entry entry, NT_RpcCall call,
-                             size_t* result_len, double timeout,
-                             NT_Bool* timed_out);
-
-/**
- * Ignore the result of a RPC call.  This function is non-blocking.
- *
- * @param entry       entry handle of RPC entry
- * @param call        RPC call handle returned by NT_CallRpc()
- */
-void NT_CancelRpcResult(NT_Entry entry, NT_RpcCall call);
-
-/**
- * Pack a RPC version 1 definition.
- *
- * @param def         RPC version 1 definition
- * @param packed_len  length of return value in bytes
- * @return Raw packed bytes.  Use C standard library std::free() to release.
- */
-char* NT_PackRpcDefinition(const struct NT_RpcDefinition* def,
-                           size_t* packed_len);
-
-/**
- * Unpack a RPC version 1 definition.  This can be used for introspection or
- * validation.
- *
- * @param packed      raw packed bytes
- * @param packed_len  length of packed in bytes
- * @param def         RPC version 1 definition (output)
- * @return True if successfully unpacked, false otherwise.
- */
-NT_Bool NT_UnpackRpcDefinition(const char* packed, size_t packed_len,
-                               struct NT_RpcDefinition* def);
-
-/**
- * Pack RPC values as required for RPC version 1 definition messages.
- *
- * @param values      array of values to pack
- * @param values_len  length of values
- * @param packed_len  length of return value in bytes
- * @return Raw packed bytes.  Use C standard library std::free() to release.
- */
-char* NT_PackRpcValues(const struct NT_Value** values, size_t values_len,
-                       size_t* packed_len);
-
-/**
- * Unpack RPC values as required for RPC version 1 definition messages.
- *
- * @param packed      raw packed bytes
- * @param packed_len  length of packed in bytes
- * @param types       array of data types (as provided in the RPC definition)
- * @param types_len   length of types
- * @return Array of NT_Value's.
- */
-struct NT_Value** NT_UnpackRpcValues(const char* packed, size_t packed_len,
-                                     const enum NT_Type* types,
-                                     size_t types_len);
+NT_Listener NT_AddPolledListener(NT_ListenerPoller poller, NT_Handle handle,
+                                 unsigned int mask);
 
 /** @} */
 
@@ -1018,17 +1048,6 @@
  */
 
 /**
- * Set the network identity of this node.
- * This is the name used during the initial connection handshake, and is
- * visible through NT_ConnectionInfo on the remote node.
- *
- * @param inst      instance handle
- * @param name      identity to advertise
- * @param name_len  length of name in bytes
- */
-void NT_SetNetworkIdentity(NT_Inst inst, const char* name, size_t name_len);
-
-/**
  * Get the current network mode.
  *
  * @param inst  instance handle
@@ -1057,10 +1076,12 @@
  *                          null terminated)
  * @param listen_address    the address to listen on, or null to listen on any
  *                          address. (UTF-8 string, null terminated)
- * @param port              port to communicate over.
+ * @param port3             port to communicate over (NT3)
+ * @param port4             port to communicate over (NT4)
  */
 void NT_StartServer(NT_Inst inst, const char* persist_filename,
-                    const char* listen_address, unsigned int port);
+                    const char* listen_address, unsigned int port3,
+                    unsigned int port4);
 
 /**
  * Stops the server if it is running.
@@ -1070,42 +1091,22 @@
 void NT_StopServer(NT_Inst inst);
 
 /**
- * Starts a client.  Use NT_SetServer to set the server name and port.
+ * Starts a NT3 client.  Use NT_SetServer or NT_SetServerTeam to set the server
+ * name and port.
  *
- * @param inst  instance handle
+ * @param inst      instance handle
+ * @param identity  network identity to advertise (cannot be empty string)
  */
-void NT_StartClientNone(NT_Inst inst);
+void NT_StartClient3(NT_Inst inst, const char* identity);
 
 /**
- * Starts a client using the specified server and port
+ * Starts a NT4 client.  Use NT_SetServer or NT_SetServerTeam to set the server
+ * name and port.
  *
- * @param inst        instance handle
- * @param server_name server name (UTF-8 string, null terminated)
- * @param port        port to communicate over
+ * @param inst      instance handle
+ * @param identity  network identity to advertise (cannot be empty string)
  */
-void NT_StartClient(NT_Inst inst, const char* server_name, unsigned int port);
-
-/**
- * Starts a client using the specified (server, port) combinations.  The
- * client will attempt to connect to each server in round robin fashion.
- *
- * @param inst         instance handle
- * @param count        length of the server_names and ports arrays
- * @param server_names array of server names (each a UTF-8 string, null
- *                     terminated)
- * @param ports        array of ports to communicate over (one for each server)
- */
-void NT_StartClientMulti(NT_Inst inst, size_t count, const char** server_names,
-                         const unsigned int* ports);
-
-/**
- * Starts a client using commonly known robot addresses for the specified team.
- *
- * @param inst        instance handle
- * @param team        team number
- * @param port        port to communicate over
- */
-void NT_StartClientTeam(NT_Inst inst, unsigned int team, unsigned int port);
+void NT_StartClient4(NT_Inst inst, const char* identity);
 
 /**
  * Stops the client if it is running.
@@ -1152,7 +1153,7 @@
  * server IP address.
  *
  * @param inst  instance handle
- * @param port server port to use in combination with IP from DS
+ * @param port  server port to use in combination with IP from DS
  */
 void NT_StartDSClient(NT_Inst inst, unsigned int port);
 
@@ -1164,20 +1165,23 @@
 void NT_StopDSClient(NT_Inst inst);
 
 /**
- * Set the periodic update rate.
- * Sets how frequently updates are sent to other nodes over the network.
+ * Flush local updates.
+ *
+ * Forces an immediate flush of all local changes to the client/server.
+ * This does not flush to the network.
+ *
+ * Normally this is done on a regularly scheduled interval.
  *
  * @param inst      instance handle
- * @param interval  update interval in seconds (range 0.01 to 1.0)
  */
-void NT_SetUpdateRate(NT_Inst inst, double interval);
+void NT_FlushLocal(NT_Inst inst);
 
 /**
- * Flush Entries.
+ * Flush to network.
  *
  * Forces an immediate flush of all local entry changes to network.
- * Normally this is done on a regularly scheduled interval (see
- * NT_SetUpdateRate()).
+ * Normally this is done on a regularly scheduled interval (set
+ * by update rates on individual publishers).
  *
  * Note: flushes are rate limited to avoid excessive network traffic.  If
  * the time between calls is too short, the flush will occur after the minimum
@@ -1208,64 +1212,21 @@
  */
 NT_Bool NT_IsConnected(NT_Inst inst);
 
-/** @} */
-
 /**
- * @defgroup ntcore_file_cfunc File Save/Load Functions
- * @{
- */
-
-/**
- * Save persistent values to a file.  The server automatically does this,
- * but this function provides a way to save persistent values in the same
- * format to a file on either a client or a server.
+ * Get the time offset between server time and local time. Add this value to
+ * local time to get the estimated equivalent server time. In server mode, this
+ * always returns a valid value of 0. In client mode, this returns the time
+ * offset only if the client and server are connected and have exchanged
+ * synchronization messages. Note the time offset may change over time as it is
+ * periodically updated; to receive updates as events, add a listener to the
+ * "time sync" event.
  *
- * @param inst      instance handle
- * @param filename  filename
- * @return error string, or NULL if successful
+ * @param inst instance handle
+ * @param valid set to true if the return value is valid, false otherwise
+ *              (output)
+ * @return Time offset in microseconds (if valid is set to true)
  */
-const char* NT_SavePersistent(NT_Inst inst, const char* filename);
-
-/**
- * Load persistent values from a file.  The server automatically does this
- * at startup, but this function provides a way to restore persistent values
- * in the same format from a file at any time on either a client or a server.
- *
- * @param inst      instance handle
- * @param filename  filename
- * @param warn      callback function for warnings
- * @return error string, or NULL if successful
- */
-const char* NT_LoadPersistent(NT_Inst inst, const char* filename,
-                              void (*warn)(size_t line, const char* msg));
-
-/**
- * Save table values to a file.  The file format used is identical to
- * that used for SavePersistent.
- *
- * @param inst        instance handle
- * @param filename    filename
- * @param prefix      save only keys starting with this prefix
- * @param prefix_len  length of prefix in bytes
- * @return error string, or nullptr if successful
- */
-const char* NT_SaveEntries(NT_Inst inst, const char* filename,
-                           const char* prefix, size_t prefix_len);
-
-/**
- * Load table values from a file.  The file format used is identical to
- * that used for SavePersistent / LoadPersistent.
- *
- * @param inst        instance handle
- * @param filename    filename
- * @param prefix      load only keys starting with this prefix
- * @param prefix_len  length of prefix in bytes
- * @param warn        callback function for warnings
- * @return error string, or nullptr if successful
- */
-const char* NT_LoadEntries(NT_Inst inst, const char* filename,
-                           const char* prefix, size_t prefix_len,
-                           void (*warn)(size_t line, const char* msg));
+int64_t NT_GetServerTimeOffset(NT_Inst inst, NT_Bool* valid);
 
 /** @} */
 
@@ -1305,12 +1266,16 @@
 void NT_InitString(struct NT_String* str);
 
 /**
- * Disposes an entry handle array.
+ * Frees an array of NT_Values.
  *
- * @param arr   pointer to the array to dispose
+ * @param arr   pointer to the value array to free
  * @param count number of elements in the array
+ *
+ * Note that the individual NT_Values in the array should NOT be
+ * freed before calling this. This function will free all the values
+ * individually.
  */
-void NT_DisposeEntryArray(NT_Entry* arr, size_t count);
+void NT_DisposeValueArray(struct NT_Value* arr, size_t count);
 
 /**
  * Disposes a connection info array.
@@ -1321,97 +1286,56 @@
 void NT_DisposeConnectionInfoArray(struct NT_ConnectionInfo* arr, size_t count);
 
 /**
- * Disposes an entry info array.
+ * Disposes a topic info array.
  *
  * @param arr   pointer to the array to dispose
  * @param count number of elements in the array
  */
-void NT_DisposeEntryInfoArray(struct NT_EntryInfo* arr, size_t count);
+void NT_DisposeTopicInfoArray(struct NT_TopicInfo* arr, size_t count);
 
 /**
- * Disposes a single entry info (as returned by NT_GetEntryInfoHandle).
+ * Disposes a single topic info (as returned by NT_GetTopicInfo).
  *
  * @param info  pointer to the info to dispose
  */
-void NT_DisposeEntryInfo(struct NT_EntryInfo* info);
+void NT_DisposeTopicInfo(struct NT_TopicInfo* info);
 
 /**
- * Disposes a Rpc Definition structure.
- *
- * @param def  pointer to the struct to dispose
- */
-void NT_DisposeRpcDefinition(struct NT_RpcDefinition* def);
-
-/**
- * Disposes a Rpc Answer array.
+ * Disposes an event array.
  *
  * @param arr   pointer to the array to dispose
  * @param count number of elements in the array
  */
-void NT_DisposeRpcAnswerArray(struct NT_RpcAnswer* arr, size_t count);
+void NT_DisposeEventArray(struct NT_Event* arr, size_t count);
 
 /**
- * Disposes a Rpc Answer structure.
+ * Disposes a single event.
  *
- * @param answer     pointer to the struct to dispose
+ * @param event  pointer to the event to dispose
  */
-void NT_DisposeRpcAnswer(struct NT_RpcAnswer* answer);
-
-/**
- * Disposes an entry notification array.
- *
- * @param arr   pointer to the array to dispose
- * @param count number of elements in the array
- */
-void NT_DisposeEntryNotificationArray(struct NT_EntryNotification* arr,
-                                      size_t count);
-
-/**
- * Disposes a single entry notification.
- *
- * @param info  pointer to the info to dispose
- */
-void NT_DisposeEntryNotification(struct NT_EntryNotification* info);
-
-/**
- * Disposes a connection notification array.
- *
- * @param arr   pointer to the array to dispose
- * @param count number of elements in the array
- */
-void NT_DisposeConnectionNotificationArray(
-    struct NT_ConnectionNotification* arr, size_t count);
-
-/**
- * Disposes a single connection notification.
- *
- * @param info  pointer to the info to dispose
- */
-void NT_DisposeConnectionNotification(struct NT_ConnectionNotification* info);
-
-/**
- * Disposes a log message array.
- *
- * @param arr   pointer to the array to dispose
- * @param count number of elements in the array
- */
-void NT_DisposeLogMessageArray(struct NT_LogMessage* arr, size_t count);
-
-/**
- * Disposes a single log message.
- *
- * @param info  pointer to the info to dispose
- */
-void NT_DisposeLogMessage(struct NT_LogMessage* info);
+void NT_DisposeEvent(struct NT_Event* event);
 
 /**
  * Returns monotonic current time in 1 us increments.
  * This is the same time base used for entry and connection timestamps.
- * This function is a compatibility wrapper around WPI_Now().
+ * This function by default simply wraps WPI_Now(), but if NT_SetNow() is
+ * called, this function instead returns the value passed to NT_SetNow();
+ * this can be used to reduce overhead.
  *
  * @return Timestamp
  */
-uint64_t NT_Now(void);
+int64_t NT_Now(void);
+
+/**
+ * Sets the current timestamp used for timestamping values that do not
+ * provide a timestamp (e.g. a value of 0 is passed).  For consistency,
+ * it also results in NT_Now() returning the set value.  This should generally
+ * be used only if the overhead of calling WPI_Now() is a concern.
+ * If used, it should be called periodically with the value of WPI_Now().
+ *
+ * @param timestamp timestamp (1 us increments)
+ */
+void NT_SetNow(int64_t timestamp);
 
 /** @} */
 
@@ -1421,14 +1345,6 @@
  */
 
 /**
- * Log function.
- *
- * @param data    data pointer passed to NT_AddLogger()
- * @param msg     message information
- */
-typedef void (*NT_LogFunc)(void* data, const struct NT_LogMessage* msg);
-
-/**
  * Add logger callback function.  By default, log messages are sent to stderr;
  * this function sends log messages to the provided callback function instead.
  * The callback function will only be called for log messages with level
@@ -1436,97 +1352,28 @@
  * messages outside this range will be silently ignored.
  *
  * @param inst        instance handle
- * @param data        data pointer to pass to func
- * @param func        log callback function
  * @param min_level   minimum log level
  * @param max_level   maximum log level
- * @return Logger handle
+ * @param data        data pointer to pass to func
+ * @param func        listener callback function
+ * @return Listener handle
  */
-NT_Logger NT_AddLogger(NT_Inst inst, void* data, NT_LogFunc func,
-                       unsigned int min_level, unsigned int max_level);
+NT_Listener NT_AddLogger(NT_Inst inst, unsigned int min_level,
+                         unsigned int max_level, void* data,
+                         NT_ListenerCallback func);
 
 /**
- * Create a log poller.  A poller provides a single queue of poll events.
- * The returned handle must be destroyed with NT_DestroyLoggerPoller().
- *
- * @param inst      instance handle
- * @return poller handle
- */
-NT_LoggerPoller NT_CreateLoggerPoller(NT_Inst inst);
-
-/**
- * Destroy a log poller.  This will abort any blocked polling call and prevent
- * additional events from being generated for this poller.
- *
- * @param poller    poller handle
- */
-void NT_DestroyLoggerPoller(NT_LoggerPoller poller);
-
-/**
- * Set the log level for a log poller.  Events will only be generated for
+ * Set the log level for a listener poller.  Events will only be generated for
  * log messages with level greater than or equal to min_level and less than or
  * equal to max_level; messages outside this range will be silently ignored.
  *
  * @param poller        poller handle
  * @param min_level     minimum log level
  * @param max_level     maximum log level
- * @return Logger handle
+ * @return Listener handle
  */
-NT_Logger NT_AddPolledLogger(NT_LoggerPoller poller, unsigned int min_level,
-                             unsigned int max_level);
-
-/**
- * Get the next log event.  This blocks until the next log occurs.
- *
- * @param poller    poller handle
- * @param len       length of returned array (output)
- * @return Array of information on the log events.  Only returns NULL if an
- *         error occurred (e.g. the instance was invalid or is shutting down).
- */
-struct NT_LogMessage* NT_PollLogger(NT_LoggerPoller poller, size_t* len);
-
-/**
- * Get the next log event.  This blocks until the next log occurs or it times
- * out.
- *
- * @param poller      poller handle
- * @param len         length of returned array (output)
- * @param timeout     timeout, in seconds
- * @param timed_out   true if the timeout period elapsed (output)
- * @return Array of information on the log events.  If NULL is returned and
- *         timed_out is also false, an error occurred (e.g. the instance was
- *         invalid or is shutting down).
- */
-struct NT_LogMessage* NT_PollLoggerTimeout(NT_LoggerPoller poller, size_t* len,
-                                           double timeout, NT_Bool* timed_out);
-
-/**
- * Cancel a PollLogger call.  This wakes up a call to PollLogger for this
- * poller and causes it to immediately return an empty array.
- *
- * @param poller  poller handle
- */
-void NT_CancelPollLogger(NT_LoggerPoller poller);
-
-/**
- * Remove a logger.
- *
- * @param logger Logger handle to remove
- */
-void NT_RemoveLogger(NT_Logger logger);
-
-/**
- * Wait for the incoming log event queue to be empty.  This is primarily useful
- * for deterministic testing.  This blocks until either the log event
- * queue is empty (e.g. there are no more events that need to be passed along
- * to callbacks or poll queues) or the timeout expires.
- *
- * @param inst      instance handle
- * @param timeout   timeout, in seconds.  Set to 0 for non-blocking behavior,
- *                  or a negative value to block indefinitely
- * @return False if timed out, otherwise true.
- */
-NT_Bool NT_WaitForLoggerQueue(NT_Inst inst, double timeout);
+NT_Listener NT_AddPolledLogger(NT_ListenerPoller poller, unsigned int min_level,
+                               unsigned int max_level);
 
 /** @} */
 
@@ -1567,6 +1414,32 @@
 NT_Bool* NT_AllocateBooleanArray(size_t size);
 
 /**
+ * Allocates an array of ints.
+ * Note that the size is the number of elements, and not the
+ * specific number of bytes to allocate. That is calculated internally.
+ *
+ * @param size  the number of elements the array will contain
+ * @return      the allocated double array
+ *
+ * After use, the array should be freed using the NT_FreeIntArray()
+ * function.
+ */
+int64_t* NT_AllocateIntegerArray(size_t size);
+
+/**
+ * Allocates an array of floats.
+ * Note that the size is the number of elements, and not the
+ * specific number of bytes to allocate. That is calculated internally.
+ *
+ * @param size  the number of elements the array will contain
+ * @return      the allocated double array
+ *
+ * After use, the array should be freed using the NT_FreeFloatArray()
+ * function.
+ */
+float* NT_AllocateFloatArray(size_t size);
+
+/**
  * Allocates an array of doubles.
  * Note that the size is the number of elements, and not the
  * specific number of bytes to allocate. That is calculated internally.
@@ -1600,13 +1473,6 @@
 void NT_FreeCharArray(char* v_char);
 
 /**
- * Frees an array of doubles.
- *
- * @param v_double pointer to the double array to free
- */
-void NT_FreeDoubleArray(double* v_double);
-
-/**
  * Frees an array of booleans.
  *
  * @param v_boolean pointer to the boolean array to free
@@ -1614,6 +1480,27 @@
 void NT_FreeBooleanArray(NT_Bool* v_boolean);
 
 /**
+ * Frees an array of ints.
+ *
+ * @param v_int pointer to the int array to free
+ */
+void NT_FreeIntegerArray(int64_t* v_int);
+
+/**
+ * Frees an array of floats.
+ *
+ * @param v_float pointer to the float array to free
+ */
+void NT_FreeFloatArray(float* v_float);
+
+/**
+ * Frees an array of doubles.
+ *
+ * @param v_double pointer to the double array to free
+ */
+void NT_FreeDoubleArray(double* v_double);
+
+/**
  * Frees an array of NT_Strings.
  *
  * @param v_string  pointer to the string array to free
@@ -1654,12 +1541,36 @@
                            NT_Bool* v_boolean);
 
 /**
+ * Returns the int from the NT_Value.
+ * If the NT_Value is null, or is assigned to a different type, returns 0.
+ *
+ * @param value       NT_Value struct to get the int from
+ * @param last_change returns time in ms since the last change in the value
+ * @param v_int       returns the int assigned to the name
+ * @return            1 if successful, or 0 if value is null or not an int
+ */
+NT_Bool NT_GetValueInteger(const struct NT_Value* value, uint64_t* last_change,
+                           int64_t* v_int);
+
+/**
+ * Returns the float from the NT_Value.
+ * If the NT_Value is null, or is assigned to a different type, returns 0.
+ *
+ * @param value       NT_Value struct to get the float from
+ * @param last_change returns time in ms since the last change in the value
+ * @param v_float     returns the float assigned to the name
+ * @return            1 if successful, or 0 if value is null or not a float
+ */
+NT_Bool NT_GetValueFloat(const struct NT_Value* value, uint64_t* last_change,
+                         float* v_float);
+
+/**
  * Returns the double from the NT_Value.
  * If the NT_Value is null, or is assigned to a different type, returns 0.
  *
  * @param value       NT_Value struct to get the double from
  * @param last_change returns time in ms since the last change in the value
- * @param v_double    returns the boolean assigned to the name
+ * @param v_double    returns the double assigned to the name
  * @return            1 if successful, or 0 if value is null or not a double
  */
 NT_Bool NT_GetValueDouble(const struct NT_Value* value, uint64_t* last_change,
@@ -1696,8 +1607,8 @@
  * returned string is a copy of the string in the value, and must be freed
  * separately.
  */
-char* NT_GetValueRaw(const struct NT_Value* value, uint64_t* last_change,
-                     size_t* raw_len);
+uint8_t* NT_GetValueRaw(const struct NT_Value* value, uint64_t* last_change,
+                        size_t* raw_len);
 
 /**
  * Returns a copy of the boolean array from the NT_Value.
@@ -1717,6 +1628,40 @@
                                  uint64_t* last_change, size_t* arr_size);
 
 /**
+ * Returns a copy of the int array from the NT_Value.
+ * If the NT_Value is null, or is assigned to a different type, returns null.
+ *
+ * @param value       NT_Value struct to get the int array from
+ * @param last_change returns time in ms since the last change in the value
+ * @param arr_size    returns the number of elements in the array
+ * @return            pointer to the int array, or null if error
+ *
+ * It is the caller's responsibility to free the array once its no longer
+ * needed. The NT_FreeIntArray() function is useful for this purpose.
+ * The returned array is a copy of the array in the value, and must be
+ * freed separately.
+ */
+int64_t* NT_GetValueIntegerArray(const struct NT_Value* value,
+                                 uint64_t* last_change, size_t* arr_size);
+
+/**
+ * Returns a copy of the float array from the NT_Value.
+ * If the NT_Value is null, or is assigned to a different type, returns null.
+ *
+ * @param value       NT_Value struct to get the float array from
+ * @param last_change returns time in ms since the last change in the value
+ * @param arr_size    returns the number of elements in the array
+ * @return            pointer to the float array, or null if error
+ *
+ * It is the caller's responsibility to free the array once its no longer
+ * needed. The NT_FreeFloatArray() function is useful for this purpose.
+ * The returned array is a copy of the array in the value, and must be
+ * freed separately.
+ */
+float* NT_GetValueFloatArray(const struct NT_Value* value,
+                             uint64_t* last_change, size_t* arr_size);
+
+/**
  * Returns a copy of the double array from the NT_Value.
  * If the NT_Value is null, or is assigned to a different type, returns null.
  *
@@ -1753,331 +1698,176 @@
                                          uint64_t* last_change,
                                          size_t* arr_size);
 
-/**
- * Returns the boolean currently assigned to the entry name.
- * If the entry name is not currently assigned, or is assigned to a
- * different type, returns 0.
- *
- * @param entry       entry handle
- * @param last_change returns time in ms since the last change in the value
- * @param v_boolean   returns the boolean assigned to the name
- * @return            1 if successful, or 0 if value is unassigned or not a
- *                    boolean
- */
-NT_Bool NT_GetEntryBoolean(NT_Entry entry, uint64_t* last_change,
-                           NT_Bool* v_boolean);
-
-/**
- * Returns the double currently assigned to the entry name.
- * If the entry name is not currently assigned, or is assigned to a
- * different type, returns 0.
- *
- * @param entry       entry handle
- * @param last_change returns time in ms since the last change in the value
- * @param v_double    returns the double assigned to the name
- * @return            1 if successful, or 0 if value is unassigned or not a
- *                    double
- */
-NT_Bool NT_GetEntryDouble(NT_Entry entry, uint64_t* last_change,
-                          double* v_double);
-
-/**
- * Returns a copy of the string assigned to the entry name.
- * If the entry name is not currently assigned, or is assigned to a
- * different type, returns null.
- *
- * @param entry       entry handle
- * @param last_change returns time in ms since the last change in the value
- * @param str_len     returns the length of the string
- * @return            pointer to the string (UTF-8), or null if error
- *
- * It is the caller's responsibility to free the string once its no longer
- * needed. The NT_FreeCharArray() function is useful for this purpose.
- */
-char* NT_GetEntryString(NT_Entry entry, uint64_t* last_change, size_t* str_len);
-
-/**
- * Returns a copy of the raw value assigned to the entry name.
- * If the entry name is not currently assigned, or is assigned to a
- * different type, returns null.
- *
- * @param entry       entry handle
- * @param last_change returns time in ms since the last change in the value
- * @param raw_len     returns the length of the string
- * @return            pointer to the raw value (UTF-8), or null if error
- *
- * It is the caller's responsibility to free the raw value once its no longer
- * needed. The NT_FreeCharArray() function is useful for this purpose.
- */
-char* NT_GetEntryRaw(NT_Entry entry, uint64_t* last_change, size_t* raw_len);
-
-/**
- * Returns a copy of the boolean array assigned to the entry name.
- * If the entry name is not currently assigned, or is assigned to a
- * different type, returns null.
- *
- * @param entry       entry handle
- * @param last_change returns time in ms since the last change in the value
- * @param arr_size    returns the number of elements in the array
- * @return            pointer to the boolean array, or null if error
- *
- * It is the caller's responsibility to free the array once its no longer
- * needed. The NT_FreeBooleanArray() function is useful for this purpose.
- */
-NT_Bool* NT_GetEntryBooleanArray(NT_Entry entry, uint64_t* last_change,
-                                 size_t* arr_size);
-
-/**
- * Returns a copy of the double array assigned to the entry name.
- * If the entry name is not currently assigned, or is assigned to a
- * different type, returns null.
- *
- * @param entry       entry handle
- * @param last_change returns time in ms since the last change in the value
- * @param arr_size    returns the number of elements in the array
- * @return            pointer to the double array, or null if error
- *
- * It is the caller's responsibility to free the array once its no longer
- * needed. The NT_FreeDoubleArray() function is useful for this purpose.
- */
-double* NT_GetEntryDoubleArray(NT_Entry entry, uint64_t* last_change,
-                               size_t* arr_size);
-
-/**
- * Returns a copy of the NT_String array assigned to the entry name.
- * If the entry name is not currently assigned, or is assigned to a
- * different type, returns null.
- *
- * @param entry       entry handle
- * @param last_change returns time in ms since the last change in the value
- * @param arr_size    returns the number of elements in the array
- * @return            pointer to the NT_String array, or null if error
- *
- * It is the caller's responsibility to free the array once its no longer
- * needed. The NT_FreeStringArray() function is useful for this purpose. Note
- * that the individual NT_Strings should not be freed, but the entire array
- * should be freed at once. The NT_FreeStringArray() function will free all the
- * NT_Strings.
- */
-struct NT_String* NT_GetEntryStringArray(NT_Entry entry, uint64_t* last_change,
-                                         size_t* arr_size);
-
+/** @} */
+/** @} */
 /** @} */
 
 /**
- * @defgroup ntcore_setdefault_cfunc Set Default Values
+ * @defgroup ntcore_c_meta_api ntcore C meta-topic API
+ *
+ * Meta-topic decoders for C.
+ *
  * @{
  */
 
-/** Set Default Entry Boolean.
- * Sets the default for the specified key to be a boolean.
- * If key exists with same type, does not set value. Otherwise
- * sets value to the default.
- *
- * @param entry     entry handle
- * @param time      timestamp
- * @param default_boolean     value to be set if name does not exist
- * @return 0 on error (value not set), 1 on success
+/**
+ * Subscriber options. Different from PubSubOptions in this reflects only
+ * options that are sent over the network.
  */
-NT_Bool NT_SetDefaultEntryBoolean(NT_Entry entry, uint64_t time,
-                                  NT_Bool default_boolean);
-
-/** Set Default Entry Double.
- * Sets the default for the specified key.
- * If key exists with same type, does not set value. Otherwise
- * sets value to the default.
- *
- * @param entry     entry handle
- * @param time      timestamp
- * @param default_double     value to be set if name does not exist
- * @return 0 on error (value not set), 1 on success
- */
-NT_Bool NT_SetDefaultEntryDouble(NT_Entry entry, uint64_t time,
-                                 double default_double);
-
-/** Set Default Entry String.
- * Sets the default for the specified key.
- * If key exists with same type, does not set value. Otherwise
- * sets value to the default.
- *
- * @param entry     entry handle
- * @param time      timestamp
- * @param default_value     value to be set if name does not exist
- * @param default_len       length of value
- * @return 0 on error (value not set), 1 on success
- */
-NT_Bool NT_SetDefaultEntryString(NT_Entry entry, uint64_t time,
-                                 const char* default_value, size_t default_len);
-
-/** Set Default Entry Raw.
- * Sets the default for the specified key.
- * If key exists with same type, does not set value. Otherwise
- * sets value to the default.
- *
- * @param entry     entry handle
- * @param time      timestamp
- * @param default_value     value to be set if name does not exist
- * @param default_len       length of value array
- * @return 0 on error (value not set), 1 on success
- */
-NT_Bool NT_SetDefaultEntryRaw(NT_Entry entry, uint64_t time,
-                              const char* default_value, size_t default_len);
-
-/** Set Default Entry Boolean Array.
- * Sets the default for the specified key.
- * If key exists with same type, does not set value. Otherwise
- * sets value to the default.
- *
- * @param entry     entry handle
- * @param time      timestamp
- * @param default_value     value to be set if name does not exist
- * @param default_size      size of value array
- * @return 0 on error (value not set), 1 on success
- */
-NT_Bool NT_SetDefaultEntryBooleanArray(NT_Entry entry, uint64_t time,
-                                       const int* default_value,
-                                       size_t default_size);
-
-/** Set Default Entry Double Array.
- * Sets the default for the specified key.
- * If key exists with same type, does not set value. Otherwise
- * sets value to the default.
- *
- * @param entry     entry handle
- * @param time      timestamp
- * @param default_value     value to be set if name does not exist
- * @param default_size      size of value array
- * @return 0 on error (value not set), 1 on success
- */
-NT_Bool NT_SetDefaultEntryDoubleArray(NT_Entry entry, uint64_t time,
-                                      const double* default_value,
-                                      size_t default_size);
-
-/** Set Default Entry String Array.
- * Sets the default for the specified key.
- * If key exists with same type, does not set value. Otherwise
- * sets value to the default.
- *
- * @param entry     entry handle
- * @param time      timestamp
- * @param default_value     value to be set if name does not exist
- * @param default_size      size of value array
- * @return 0 on error (value not set), 1 on success
- */
-NT_Bool NT_SetDefaultEntryStringArray(NT_Entry entry, uint64_t time,
-                                      const struct NT_String* default_value,
-                                      size_t default_size);
-
-/** @} */
+struct NT_Meta_SubscriberOptions {
+  double periodic;
+  NT_Bool topicsOnly;
+  NT_Bool sendAll;
+  NT_Bool prefixMatch;
+};
 
 /**
- * @defgroup ntcore_valuesetters_cfunc Entry Value Setters
- * @{
+ * Topic publisher (as published via `$pub$<topic>`).
  */
+struct NT_Meta_TopicPublisher {
+  struct NT_String client;
+  uint64_t pubuid;
+};
 
-/** Set Entry Boolean
- * Sets an entry boolean. If the entry name is not currently assigned to a
- * boolean, returns error unless the force parameter is set.
+/**
+ * Topic subscriber (as published via `$sub$<topic>`).
+ */
+struct NT_Meta_TopicSubscriber {
+  struct NT_String client;
+  uint64_t subuid;
+  struct NT_Meta_SubscriberOptions options;
+};
+
+/**
+ * Client publisher (as published via `$clientpub$<client>` or `$serverpub`).
+ */
+struct NT_Meta_ClientPublisher {
+  int64_t uid;
+  struct NT_String topic;
+};
+
+/**
+ * Client subscriber (as published via `$clientsub$<client>` or `$serversub`).
+ */
+struct NT_Meta_ClientSubscriber {
+  int64_t uid;
+  size_t topicsCount;
+  struct NT_String* topics;
+  struct NT_Meta_SubscriberOptions options;
+};
+
+/**
+ * Client (as published via `$clients`).
+ */
+struct NT_Meta_Client {
+  struct NT_String id;
+  struct NT_String conn;
+  uint16_t version;
+};
+
+/**
+ * Decodes `$pub$<topic>` meta-topic data.
  *
- * @param entry     entry handle
- * @param time      timestamp
- * @param v_boolean boolean value to set
- * @param force     1 to force the entry to get overwritten, otherwise 0
- * @return          0 on error (type mismatch), 1 on success
+ * @param data data contents
+ * @param size size of data contents
+ * @param count number of elements in returned array (output)
+ * @return Array of TopicPublishers, or NULL on decoding error.
  */
-NT_Bool NT_SetEntryBoolean(NT_Entry entry, uint64_t time, NT_Bool v_boolean,
-                           NT_Bool force);
+struct NT_Meta_TopicPublisher* NT_Meta_DecodeTopicPublishers(
+    const uint8_t* data, size_t size, size_t* count);
 
-/** Set Entry Double
- * Sets an entry double. If the entry name is not currently assigned to a
- * double, returns error unless the force parameter is set.
+/**
+ * Decodes `$sub$<topic>` meta-topic data.
  *
- * @param entry     entry handle
- * @param time      timestamp
- * @param v_double  double value to set
- * @param force     1 to force the entry to get overwritten, otherwise 0
- * @return          0 on error (type mismatch), 1 on success
+ * @param data data contents
+ * @param size size of data contents
+ * @param count number of elements in returned array (output)
+ * @return Array of TopicSubscribers, or NULL on decoding error.
  */
-NT_Bool NT_SetEntryDouble(NT_Entry entry, uint64_t time, double v_double,
-                          NT_Bool force);
+struct NT_Meta_TopicSubscriber* NT_Meta_DecodeTopicSubscribers(
+    const uint8_t* data, size_t size, size_t* count);
 
-/** Set Entry String
- * Sets an entry string. If the entry name is not currently assigned to a
- * string, returns error unless the force parameter is set.
+/**
+ * Decodes `$clientpub$<topic>` meta-topic data.
  *
- * @param entry     entry handle
- * @param time      timestamp
- * @param str       string to set (UTF-8 string)
- * @param str_len   length of string to write in bytes
- * @param force     1 to force the entry to get overwritten, otherwise 0
- * @return          0 on error (type mismatch), 1 on success
+ * @param data data contents
+ * @param size size of data contents
+ * @param count number of elements in returned array (output)
+ * @return Array of ClientPublishers, or NULL on decoding error.
  */
-NT_Bool NT_SetEntryString(NT_Entry entry, uint64_t time, const char* str,
-                          size_t str_len, NT_Bool force);
+struct NT_Meta_ClientPublisher* NT_Meta_DecodeClientPublishers(
+    const uint8_t* data, size_t size, size_t* count);
 
-/** Set Entry Raw
- * Sets the raw value of an entry. If the entry name is not currently assigned
- * to a raw value, returns error unless the force parameter is set.
+/**
+ * Decodes `$clientsub$<topic>` meta-topic data.
  *
- * @param entry     entry handle
- * @param time      timestamp
- * @param raw       raw string to set (UTF-8 string)
- * @param raw_len   length of raw string to write in bytes
- * @param force     1 to force the entry to get overwritten, otherwise 0
- * @return          0 on error (type mismatch), 1 on success
+ * @param data data contents
+ * @param size size of data contents
+ * @param count number of elements in returned array (output)
+ * @return Array of ClientSubscribers, or NULL on decoding error.
  */
-NT_Bool NT_SetEntryRaw(NT_Entry entry, uint64_t time, const char* raw,
-                       size_t raw_len, NT_Bool force);
+struct NT_Meta_ClientSubscriber* NT_Meta_DecodeClientSubscribers(
+    const uint8_t* data, size_t size, size_t* count);
 
-/** Set Entry Boolean Array
- * Sets an entry boolean array. If the entry name is not currently assigned to
- * a boolean array, returns error unless the force parameter is set.
+/**
+ * Decodes `$clients` meta-topic data.
  *
- * @param entry     entry handle
- * @param time      timestamp
- * @param arr       boolean array to write
- * @param size      number of elements in the array
- * @param force     1 to force the entry to get overwritten, otherwise 0
- * @return          0 on error (type mismatch), 1 on success
+ * @param data data contents
+ * @param size size of data contents
+ * @param count number of elements in returned array (output)
+ * @return Array of Clients, or NULL on decoding error.
  */
-NT_Bool NT_SetEntryBooleanArray(NT_Entry entry, uint64_t time, const int* arr,
-                                size_t size, NT_Bool force);
+struct NT_Meta_Client* NT_Meta_DecodeClients(const uint8_t* data, size_t size,
+                                             size_t* count);
 
-/** Set Entry Double Array
- * Sets an entry double array. If the entry name is not currently assigned to
- * a double array, returns error unless the force parameter is set.
+/**
+ * Frees an array of NT_Meta_TopicPublisher.
  *
- * @param entry     entry handle
- * @param time      timestamp
- * @param arr       double array to write
- * @param size      number of elements in the array
- * @param force     1 to force the entry to get overwritten, otherwise 0
- * @return          0 on error (type mismatch), 1 on success
+ * @param arr   pointer to the array to free
+ * @param count size of the array to free
  */
-NT_Bool NT_SetEntryDoubleArray(NT_Entry entry, uint64_t time, const double* arr,
-                               size_t size, NT_Bool force);
+void NT_Meta_FreeTopicPublishers(struct NT_Meta_TopicPublisher* arr,
+                                 size_t count);
 
-/** Set Entry String Array
- * Sets an entry string array. If the entry name is not currently assigned to
- * a string array, returns error unless the force parameter is set.
+/**
+ * Frees an array of NT_Meta_TopicSubscriber.
  *
- * @param entry     entry handle
- * @param time      timestamp
- * @param arr       NT_String array to write
- * @param size      number of elements in the array
- * @param force     1 to force the entry to get overwritten, otherwise 0
- * @return          0 on error (type mismatch), 1 on success
+ * @param arr   pointer to the array to free
+ * @param count size of the array to free
  */
-NT_Bool NT_SetEntryStringArray(NT_Entry entry, uint64_t time,
-                               const struct NT_String* arr, size_t size,
-                               NT_Bool force);
+void NT_Meta_FreeTopicSubscribers(struct NT_Meta_TopicSubscriber* arr,
+                                  size_t count);
 
-/** @} */
-/** @} */
+/**
+ * Frees an array of NT_Meta_ClientPublisher.
+ *
+ * @param arr   pointer to the array to free
+ * @param count size of the array to free
+ */
+void NT_Meta_FreeClientPublishers(struct NT_Meta_ClientPublisher* arr,
+                                  size_t count);
+
+/**
+ * Frees an array of NT_Meta_ClientSubscriber.
+ *
+ * @param arr   pointer to the array to free
+ * @param count size of the array to free
+ */
+void NT_Meta_FreeClientSubscribers(struct NT_Meta_ClientSubscriber* arr,
+                                   size_t count);
+
+/**
+ * Frees an array of NT_Meta_Client.
+ *
+ * @param arr   pointer to the array to free
+ * @param count size of the array to free
+ */
+void NT_Meta_FreeClients(struct NT_Meta_Client* arr, size_t count);
+
 /** @} */
 
 #ifdef __cplusplus
 }  // extern "C"
 #endif
 
-#endif  // NTCORE_NTCORE_C_H_
+#include "ntcore_c_types.h"
diff --git a/third_party/allwpilib/ntcore/src/main/native/include/ntcore_cpp.h b/third_party/allwpilib/ntcore/src/main/native/include/ntcore_cpp.h
index 2d91fe5..cbb541b 100644
--- a/third_party/allwpilib/ntcore/src/main/native/include/ntcore_cpp.h
+++ b/third_party/allwpilib/ntcore/src/main/native/include/ntcore_cpp.h
@@ -2,23 +2,34 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
-#ifndef NTCORE_NTCORE_CPP_H_
-#define NTCORE_NTCORE_CPP_H_
+#pragma once
 
 #include <stdint.h>
 
 #include <cassert>
 #include <functional>
 #include <memory>
+#include <optional>
+#include <span>
 #include <string>
 #include <string_view>
-#include <thread>
 #include <utility>
+#include <variant>
 #include <vector>
 
-#include <wpi/span.h>
-
 #include "networktables/NetworkTableValue.h"
+#include "ntcore_c.h"
+#include "ntcore_cpp_types.h"
+
+namespace wpi {
+template <typename T>
+class SmallVectorImpl;
+class json;
+}  // namespace wpi
+
+namespace wpi::log {
+class DataLog;
+}  // namespace wpi::log
 
 /** NetworkTables (ntcore) namespace */
 namespace nt {
@@ -31,30 +42,76 @@
  * @{
  */
 
-/** NetworkTables Entry Information */
-struct EntryInfo {
-  /** Entry handle */
-  NT_Entry entry;
+/**
+ * Event notification flags.
+ *
+ * The flags are a bitmask and must be OR'ed together to indicate the
+ * combination of events desired to be received.
+ *
+ */
+struct EventFlags {
+  EventFlags() = delete;
 
-  /** Entry name */
+  static constexpr unsigned int kNone = NT_EVENT_NONE;
+  /**
+   * Initial listener addition.
+   * Set this flag to receive immediate notification of matches to the
+   * flag criteria.
+   */
+  static constexpr unsigned int kImmediate = NT_EVENT_IMMEDIATE;
+  /** Client connected (on server, any client connected). */
+  static constexpr unsigned int kConnected = NT_EVENT_CONNECTED;
+  /** Client disconnected (on server, any client disconnected). */
+  static constexpr unsigned int kDisconnected = NT_EVENT_DISCONNECTED;
+  /** Any connection event (connect or disconnect). */
+  static constexpr unsigned int kConnection = kConnected | kDisconnected;
+  /** New topic published. */
+  static constexpr unsigned int kPublish = NT_EVENT_PUBLISH;
+  /** Topic unpublished. */
+  static constexpr unsigned int kUnpublish = NT_EVENT_UNPUBLISH;
+  /** Topic properties changed. */
+  static constexpr unsigned int kProperties = NT_EVENT_PROPERTIES;
+  /** Any topic event (publish, unpublish, or properties changed). */
+  static constexpr unsigned int kTopic = kPublish | kUnpublish | kProperties;
+  /** Topic value updated (via network). */
+  static constexpr unsigned int kValueRemote = NT_EVENT_VALUE_REMOTE;
+  /** Topic value updated (local). */
+  static constexpr unsigned int kValueLocal = NT_EVENT_VALUE_LOCAL;
+  /** Topic value updated (network or local). */
+  static constexpr unsigned int kValueAll = kValueRemote | kValueLocal;
+  /** Log message. */
+  static constexpr unsigned int kLogMessage = NT_EVENT_LOGMESSAGE;
+  /** Time synchronized with server. */
+  static constexpr unsigned int kTimeSync = NT_EVENT_TIMESYNC;
+};
+
+/** NetworkTables Topic Information */
+struct TopicInfo {
+  /** Topic handle */
+  NT_Topic topic{0};
+
+  /** Topic name */
   std::string name;
 
-  /** Entry type */
-  NT_Type type;
+  /** Topic type */
+  NT_Type type{NT_UNASSIGNED};
 
-  /** Entry flags */
-  unsigned int flags;
+  /** Topic type string */
+  std::string type_str;
 
-  /** Timestamp of last change to entry (type or value). */
-  uint64_t last_change;
+  /** Topic properties JSON string */
+  std::string properties;
 
-  friend void swap(EntryInfo& first, EntryInfo& second) {
+  /** Get topic properties as a JSON object. */
+  wpi::json GetProperties() const;
+
+  friend void swap(TopicInfo& first, TopicInfo& second) {
     using std::swap;
-    swap(first.entry, second.entry);
+    swap(first.topic, second.topic);
     swap(first.name, second.name);
     swap(first.type, second.type);
-    swap(first.flags, second.flags);
-    swap(first.last_change, second.last_change);
+    swap(first.type_str, second.type_str);
+    swap(first.properties, second.properties);
   }
 };
 
@@ -62,7 +119,7 @@
 struct ConnectionInfo {
   /**
    * The remote identifier (as set on the remote node by
-   * NetworkTableInstance::SetNetworkIdentity() or nt::SetNetworkIdentity()).
+   * NetworkTableInstance::StartClient4() or nt::StartClient4()).
    */
   std::string remote_id;
 
@@ -76,7 +133,7 @@
    * The last time any update was received from the remote node (same scale as
    * returned by nt::Now()).
    */
-  uint64_t last_update{0};
+  int64_t last_update{0};
 
   /**
    * The protocol version being used for this connection.  This in protocol
@@ -94,165 +151,30 @@
   }
 };
 
-/** NetworkTables RPC Version 1 Definition Parameter */
-struct RpcParamDef {
-  RpcParamDef() = default;
-  RpcParamDef(std::string_view name_, std::shared_ptr<Value> def_value_)
-      : name(name_), def_value(std::move(def_value_)) {}
-
-  std::string name;
-  std::shared_ptr<Value> def_value;
-};
-
-/** NetworkTables RPC Version 1 Definition Result */
-struct RpcResultDef {
-  RpcResultDef() = default;
-  RpcResultDef(std::string_view name_, NT_Type type_)
-      : name(name_), type(type_) {}
-
-  std::string name;
-  NT_Type type;
-};
-
-/** NetworkTables RPC Version 1 Definition */
-struct RpcDefinition {
-  unsigned int version;
-  std::string name;
-  std::vector<RpcParamDef> params;
-  std::vector<RpcResultDef> results;
-};
-
-/** NetworkTables Remote Procedure Call (Server Side) */
-class RpcAnswer {
+/** NetworkTables Value Event Data */
+class ValueEventData {
  public:
-  RpcAnswer() = default;
-  RpcAnswer(NT_Entry entry_, NT_RpcCall call_, std::string_view name_,
-            std::string_view params_, ConnectionInfo conn_)
-      : entry(entry_),
-        call(call_),
-        name(name_),
-        params(params_),
-        conn(std::move(conn_)) {}
+  ValueEventData() = default;
+  ValueEventData(NT_Topic topic, NT_Handle subentry, Value value)
+      : topic{topic}, subentry{subentry}, value{std::move(value)} {}
 
-  /** Entry handle. */
-  NT_Entry entry{0};
+  /** Topic handle. */
+  NT_Topic topic{0};
 
-  /** Call handle. */
-  mutable NT_RpcCall call{0};
-
-  /** Entry name. */
-  std::string name;
-
-  /** Call raw parameters. */
-  std::string params;
-
-  /** Connection that called the RPC. */
-  ConnectionInfo conn;
-
-  /**
-   * Determines if the native handle is valid.
-   * @return True if the native handle is valid, false otherwise.
-   */
-  explicit operator bool() const { return call != 0; }
-
-  /**
-   * Post RPC response (return value) for a polled RPC.
-   * @param result  result raw data that will be provided to remote caller
-   * @return True if posting the response is valid, otherwise false
-   */
-  bool PostResponse(std::string_view result) const;
-
-  friend void swap(RpcAnswer& first, RpcAnswer& second) {
-    using std::swap;
-    swap(first.entry, second.entry);
-    swap(first.call, second.call);
-    swap(first.name, second.name);
-    swap(first.params, second.params);
-    swap(first.conn, second.conn);
-  }
-};
-
-/** NetworkTables Entry Notification */
-class EntryNotification {
- public:
-  EntryNotification() = default;
-  EntryNotification(NT_EntryListener listener_, NT_Entry entry_,
-                    std::string_view name_, std::shared_ptr<Value> value_,
-                    unsigned int flags_)
-      : listener(listener_),
-        entry(entry_),
-        name(name_),
-        value(std::move(value_)),
-        flags(flags_) {}
-
-  /** Listener that was triggered. */
-  NT_EntryListener listener{0};
-
-  /** Entry handle. */
-  NT_Entry entry{0};
-
-  /** Entry name. */
-  std::string name;
+  /** Subscriber/entry handle. */
+  NT_Handle subentry{0};
 
   /** The new value. */
-  std::shared_ptr<Value> value;
-
-  /**
-   * Update flags.  For example, NT_NOTIFY_NEW if the key did not previously
-   * exist.
-   */
-  unsigned int flags{0};
-
-  friend void swap(EntryNotification& first, EntryNotification& second) {
-    using std::swap;
-    swap(first.listener, second.listener);
-    swap(first.entry, second.entry);
-    swap(first.name, second.name);
-    swap(first.value, second.value);
-    swap(first.flags, second.flags);
-  }
-};
-
-/** NetworkTables Connection Notification */
-class ConnectionNotification {
- public:
-  ConnectionNotification() = default;
-  ConnectionNotification(NT_ConnectionListener listener_, bool connected_,
-                         ConnectionInfo conn_)
-      : listener(listener_), connected(connected_), conn(std::move(conn_)) {}
-
-  /** Listener that was triggered. */
-  NT_ConnectionListener listener{0};
-
-  /** True if event is due to connection being established. */
-  bool connected = false;
-
-  /** Connection info. */
-  ConnectionInfo conn;
-
-  friend void swap(ConnectionNotification& first,
-                   ConnectionNotification& second) {
-    using std::swap;
-    swap(first.listener, second.listener);
-    swap(first.connected, second.connected);
-    swap(first.conn, second.conn);
-  }
+  Value value;
 };
 
 /** NetworkTables log message. */
 class LogMessage {
  public:
   LogMessage() = default;
-  LogMessage(NT_Logger logger_, unsigned int level_, std::string_view filename_,
-             unsigned int line_, std::string_view message_)
-      : logger(logger_),
-        level(level_),
-        filename(filename_),
-        line(line_),
-        message(message_) {}
-
-  /** The logger that generated the message. */
-  NT_Logger logger{0};
+  LogMessage(unsigned int level, std::string_view filename, unsigned int line,
+             std::string_view message)
+      : level{level}, filename{filename}, line{line}, message{message} {}
 
   /** Log level of the message.  See NT_LogLevel. */
   unsigned int level{0};
@@ -265,17 +187,199 @@
 
   /** The message. */
   std::string message;
+};
 
-  friend void swap(LogMessage& first, LogMessage& second) {
-    using std::swap;
-    swap(first.logger, second.logger);
-    swap(first.level, second.level);
-    swap(first.filename, second.filename);
-    swap(first.line, second.line);
-    swap(first.message, second.message);
+/** NetworkTables time sync event data. */
+class TimeSyncEventData {
+ public:
+  TimeSyncEventData() = default;
+  TimeSyncEventData(int64_t serverTimeOffset, int64_t rtt2, bool valid)
+      : serverTimeOffset{serverTimeOffset}, rtt2{rtt2}, valid{valid} {}
+
+  /**
+   * Offset between local time and server time, in microseconds. Add this value
+   * to local time to get the estimated equivalent server time.
+   */
+  int64_t serverTimeOffset;
+
+  /** Measured round trip time divided by 2, in microseconds. */
+  int64_t rtt2;
+
+  /**
+   * If serverTimeOffset and RTT are valid. An event with this set to false is
+   * sent when the client disconnects.
+   */
+  bool valid;
+};
+
+/** NetworkTables event */
+class Event {
+ public:
+  Event() = default;
+  Event(NT_Listener listener, unsigned int flags, ConnectionInfo info)
+      : listener{listener}, flags{flags}, data{std::move(info)} {}
+  Event(NT_Listener listener, unsigned int flags, TopicInfo info)
+      : listener{listener}, flags{flags}, data{std::move(info)} {}
+  Event(NT_Listener listener, unsigned int flags, ValueEventData data)
+      : listener{listener}, flags{flags}, data{std::move(data)} {}
+  Event(NT_Listener listener, unsigned int flags, LogMessage msg)
+      : listener{listener}, flags{flags}, data{std::move(msg)} {}
+  Event(NT_Listener listener, unsigned int flags, NT_Topic topic,
+        NT_Handle subentry, Value value)
+      : listener{listener},
+        flags{flags},
+        data{ValueEventData{topic, subentry, std::move(value)}} {}
+  Event(NT_Listener listener, unsigned int flags, unsigned int level,
+        std::string_view filename, unsigned int line, std::string_view message)
+      : listener{listener},
+        flags{flags},
+        data{LogMessage{level, filename, line, message}} {}
+  Event(NT_Listener listener, unsigned int flags, int64_t serverTimeOffset,
+        int64_t rtt2, bool valid)
+      : listener{listener},
+        flags{flags},
+        data{TimeSyncEventData{serverTimeOffset, rtt2, valid}} {}
+
+  /** Listener that triggered this event. */
+  NT_Listener listener{0};
+
+  /**
+   * Event flags (NT_EventFlags). Also indicates the data included with the
+   * event:
+   * - NT_EVENT_CONNECTED or NT_EVENT_DISCONNECTED: GetConnectionInfo()
+   * - NT_EVENT_PUBLISH, NT_EVENT_UNPUBLISH, or NT_EVENT_PROPERTIES:
+   *   GetTopicInfo()
+   * - NT_EVENT_VALUE, NT_EVENT_VALUE_LOCAL: GetValueData()
+   * - NT_EVENT_LOGMESSAGE: GetLogMessage()
+   * - NT_EVENT_TIMESYNC: GetTimeSyncEventData()
+   */
+  unsigned int flags{0};
+
+  /**
+   * Test event flags.
+   *
+   * @param kind event flag(s) to test
+   * @return True if flags matches kind
+   */
+  bool Is(unsigned int kind) const { return (flags & kind) != 0; }
+
+  /** Event data; content depends on flags. */
+  std::variant<ConnectionInfo, TopicInfo, ValueEventData, LogMessage,
+               TimeSyncEventData>
+      data;
+
+  const ConnectionInfo* GetConnectionInfo() const {
+    return std::get_if<ConnectionInfo>(&data);
+  }
+  ConnectionInfo* GetConnectionInfo() {
+    return std::get_if<ConnectionInfo>(&data);
+  }
+
+  const TopicInfo* GetTopicInfo() const {
+    return std::get_if<TopicInfo>(&data);
+  }
+  TopicInfo* GetTopicInfo() { return std::get_if<TopicInfo>(&data); }
+
+  const ValueEventData* GetValueEventData() const {
+    return std::get_if<ValueEventData>(&data);
+  }
+  ValueEventData* GetValueEventData() {
+    return std::get_if<ValueEventData>(&data);
+  }
+
+  const LogMessage* GetLogMessage() const {
+    return std::get_if<LogMessage>(&data);
+  }
+  LogMessage* GetLogMessage() { return std::get_if<LogMessage>(&data); }
+
+  const TimeSyncEventData* GetTimeSyncEventData() const {
+    return std::get_if<TimeSyncEventData>(&data);
+  }
+  TimeSyncEventData* GetTimeSyncEventData() {
+    return std::get_if<TimeSyncEventData>(&data);
   }
 };
 
+/** NetworkTables publish/subscribe options. */
+struct PubSubOptions {
+  /**
+   * Default value of periodic.
+   */
+  static constexpr double kDefaultPeriodic = 0.1;
+
+  /**
+   * Structure size. Must be set to sizeof(PubSubOptions).
+   */
+  unsigned int structSize = sizeof(PubSubOptions);
+
+  /**
+   * Polling storage size for a subscription. Specifies the maximum number of
+   * updates NetworkTables should store between calls to the subscriber's
+   * ReadQueue() function. If zero, defaults to 1 if sendAll is false, 20 if
+   * sendAll is true.
+   */
+  unsigned int pollStorage = 0;
+
+  /**
+   * How frequently changes will be sent over the network, in seconds.
+   * NetworkTables may send more frequently than this (e.g. use a combined
+   * minimum period for all values) or apply a restricted range to this value.
+   * The default is 100 ms.
+   */
+  double periodic = kDefaultPeriodic;
+
+  /**
+   * For subscriptions, if non-zero, value updates for ReadQueue() are not
+   * queued for this publisher.
+   */
+  NT_Publisher excludePublisher = 0;
+
+  /**
+   * Send all value changes over the network.
+   */
+  bool sendAll = false;
+
+  /**
+   * For subscriptions, don't ask for value changes (only topic announcements).
+   */
+  bool topicsOnly = false;
+
+  /**
+   * Preserve duplicate value changes (rather than ignoring them).
+   */
+  bool keepDuplicates = false;
+
+  /**
+   * Perform prefix match on subscriber topic names. Is ignored/overridden by
+   * Subscribe() functions; only present in struct for the purposes of getting
+   * information about subscriptions.
+   */
+  bool prefixMatch = false;
+
+  /**
+   * For subscriptions, if remote value updates should not be queued for
+   * ReadQueue(). See also disableLocal.
+   */
+  bool disableRemote = false;
+
+  /**
+   * For subscriptions, if local value updates should not be queued for
+   * ReadQueue(). See also disableRemote.
+   */
+  bool disableLocal = false;
+
+  /**
+   * For entries, don't queue (for ReadQueue) value updates for the entry's
+   * internal publisher.
+   */
+  bool excludeSelf = false;
+};
+
+/**
+ * Default publish/subscribe options.
+ */
+constexpr PubSubOptions kDefaultPubSubOptions;
+
 /**
  * @defgroup ntcore_instance_func Instance Functions
  * @{
@@ -297,6 +401,13 @@
 NT_Inst CreateInstance();
 
 /**
+ * Reset the internals of an instance. Every handle previously associated
+ * with this instance will no longer be valid, except for the instance
+ * handle.
+ */
+void ResetInstance(NT_Inst inst);
+
+/**
  * Destroy an instance.
  * The default instance cannot be destroyed.
  *
@@ -329,23 +440,6 @@
 NT_Entry GetEntry(NT_Inst inst, std::string_view name);
 
 /**
- * Get Entry Handles.
- *
- * Returns an array of entry handles.  The results are optionally
- * filtered by string prefix and entry type to only return a subset of all
- * entries.
- *
- * @param inst          instance handle
- * @param prefix        entry name required prefix; only entries whose name
- *                      starts with this string are returned
- * @param types         bitmask of NT_Type values; 0 is treated specially
- *                      as a "don't care"
- * @return Array of entry handles.
- */
-std::vector<NT_Entry> GetEntries(NT_Inst inst, std::string_view prefix,
-                                 unsigned int types);
-
-/**
  * Gets the name of the specified entry.
  * Returns an empty string if the handle is invalid.
  *
@@ -366,10 +460,10 @@
  * Gets the last time the entry was changed.
  * Returns 0 if the handle is invalid.
  *
- * @param entry   entry handle
+ * @param subentry   subscriber or entry handle
  * @return Entry last change time
  */
-uint64_t GetEntryLastChange(NT_Entry entry);
+int64_t GetEntryLastChange(NT_Handle subentry);
 
 /**
  * Get Entry Value.
@@ -377,10 +471,10 @@
  * Returns copy of current entry value.
  * Note that one of the type options is "unassigned".
  *
- * @param entry     entry handle
+ * @param subentry     subscriber or entry handle
  * @return entry value
  */
-std::shared_ptr<Value> GetEntryValue(NT_Entry entry);
+Value GetEntryValue(NT_Handle subentry);
 
 /**
  * Set Default Entry Value
@@ -393,7 +487,7 @@
  * @param value     value to be set if name does not exist
  * @return False on error (value not set), True on success
  */
-bool SetDefaultEntryValue(NT_Entry entry, std::shared_ptr<Value> value);
+bool SetDefaultEntryValue(NT_Entry entry, const Value& value);
 
 /**
  * Set Entry Value.
@@ -405,22 +499,7 @@
  * @param value     new entry value
  * @return False on error (type mismatch), True on success
  */
-bool SetEntryValue(NT_Entry entry, std::shared_ptr<Value> value);
-
-/**
- * Set Entry Type and Value.
- *
- * Sets new entry value.  If type of new value differs from the type of the
- * currently stored entry, the currently stored entry type is overridden
- * (generally this will generate an Entry Assignment message).
- *
- * This is NOT the preferred method to update a value; generally
- * SetEntryValue() should be used instead, with appropriate error handling.
- *
- * @param entry     entry handle
- * @param value     new entry value
- */
-void SetEntryTypeValue(NT_Entry entry, std::shared_ptr<Value> value);
+bool SetEntryValue(NT_Entry entry, const Value& value);
 
 /**
  * Set Entry Flags.
@@ -439,533 +518,469 @@
 unsigned int GetEntryFlags(NT_Entry entry);
 
 /**
- * Delete Entry.
+ * Read Entry Queue.
  *
- * Deletes an entry.  This is a new feature in version 3.0 of the protocol,
- * so this may not have an effect if any other node in the network is not
- * version 3.0 or newer.
+ * Returns new entry values since last call.
  *
- * Note: GetConnections() can be used to determine the protocol version
- * of direct remote connection(s), but this is not sufficient to determine
- * if all nodes in the network are version 3.0 or newer.
- *
- * @param entry     entry handle
+ * @param subentry     subscriber or entry handle
+ * @return entry value array
  */
-void DeleteEntry(NT_Entry entry);
+std::vector<Value> ReadQueueValue(NT_Handle subentry);
+
+/** @} */
 
 /**
- * Delete All Entries.
- *
- * Deletes ALL table entries.  This is a new feature in version 3.0 of the
- * so this may not have an effect if any other node in the network is not
- * version 3.0 or newer.
- *
- * Note: GetConnections() can be used to determine the protocol version
- * of direct remote connection(s), but this is not sufficient to determine
- * if all nodes in the network are version 3.0 or newer.
- *
- * @param inst      instance handle
+ * @defgroup ntcore_topic_func Topic Functions
+ * @{
  */
-void DeleteAllEntries(NT_Inst inst);
 
 /**
- * Get Entry Information.
+ * Get Published Topics.
  *
- * Returns an array of entry information (name, entry type,
- * and timestamp of last change to type/value).  The results are optionally
- * filtered by string prefix and entry type to only return a subset of all
- * entries.
+ * Returns an array of topic handles.  The results are optionally filtered by
+ * string prefix and type to only return a subset of all topics.
  *
  * @param inst    instance handle
- * @param prefix        entry name required prefix; only entries whose name
- *                      starts with this string are returned
- * @param types         bitmask of NT_Type values; 0 is treated specially
- *                      as a "don't care"
- * @return Array of entry information.
+ * @param prefix  name required prefix; only topics whose name
+ *                starts with this string are returned
+ * @param types   bitmask of NT_Type values; 0 is treated specially
+ *                as a "don't care"
+ * @return Array of topic handles.
  */
-std::vector<EntryInfo> GetEntryInfo(NT_Inst inst, std::string_view prefix,
+std::vector<NT_Topic> GetTopics(NT_Inst inst, std::string_view prefix,
+                                unsigned int types);
+
+/**
+ * Get Published Topics.
+ *
+ * Returns an array of topic handles.  The results are optionally filtered by
+ * string prefix and type to only return a subset of all topics.
+ *
+ * @param inst    instance handle
+ * @param prefix  name required prefix; only topics whose name
+ *                starts with this string are returned
+ * @param types   array of type strings
+ * @return Array of topic handles.
+ */
+std::vector<NT_Topic> GetTopics(NT_Inst inst, std::string_view prefix,
+                                std::span<const std::string_view> types);
+
+/**
+ * Get Topic Information about multiple topics.
+ *
+ * Returns an array of topic information (handle, name, type, and properties).
+ * The results are optionally filtered by string prefix and type to only
+ * return a subset of all topics.
+ *
+ * @param inst    instance handle
+ * @param prefix  name required prefix; only topics whose name
+ *                starts with this string are returned
+ * @param types   bitmask of NT_Type values; 0 is treated specially
+ *                as a "don't care"
+ * @return Array of topic information.
+ */
+std::vector<TopicInfo> GetTopicInfo(NT_Inst inst, std::string_view prefix,
                                     unsigned int types);
 
 /**
- * Get Entry Information.
+ * Get Topic Information about multiple topics.
  *
- * Returns information about an entry (name, entry type,
- * and timestamp of last change to type/value).
+ * Returns an array of topic information (handle, name, type, and properties).
+ * The results are optionally filtered by string prefix and type to only
+ * return a subset of all topics.
  *
- * @param entry         entry handle
- * @return Entry information.
+ * @param inst    instance handle
+ * @param prefix  name required prefix; only topics whose name
+ *                starts with this string are returned
+ * @param types   array of type strings
+ * @return Array of topic information.
  */
-EntryInfo GetEntryInfo(NT_Entry entry);
+std::vector<TopicInfo> GetTopicInfo(NT_Inst inst, std::string_view prefix,
+                                    std::span<const std::string_view> types);
+
+/**
+ * Gets Topic Information.
+ *
+ * Returns information about a topic (name, type, and properties).
+ *
+ * @param topic   handle
+ * @return Topic information.
+ */
+TopicInfo GetTopicInfo(NT_Topic topic);
+
+/**
+ * Gets Topic Handle.
+ *
+ * Returns topic handle.
+ *
+ * @param inst   instance handle
+ * @param name   topic name
+ * @return Topic handle.
+ */
+NT_Topic GetTopic(NT_Inst inst, std::string_view name);
+
+/**
+ * Gets the name of the specified topic.
+ * Returns an empty string if the handle is invalid.
+ *
+ * @param topic   topic handle
+ * @return Topic name
+ */
+std::string GetTopicName(NT_Topic topic);
+
+/**
+ * Gets the type for the specified topic, or unassigned if non existent.
+ *
+ * @param topic   topic handle
+ * @return Topic type
+ */
+NT_Type GetTopicType(NT_Topic topic);
+
+/**
+ * Gets the type string for the specified topic, or empty string if non
+ * existent.  This may have more information than the numeric type (especially
+ * for raw values).
+ *
+ * @param topic   topic handle
+ * @return Topic type string
+ */
+std::string GetTopicTypeString(NT_Topic topic);
+
+/**
+ * Sets the persistent property of a topic.  If true, the stored value is
+ * persistent through server restarts.
+ *
+ * @param topic topic handle
+ * @param value True for persistent, false for not persistent.
+ */
+void SetTopicPersistent(NT_Topic topic, bool value);
+
+/**
+ * Gets the persistent property of a topic.  If true, the server retains the
+ * topic even when there are no publishers.
+ *
+ * @param topic topic handle
+ * @return persistent property value
+ */
+bool GetTopicPersistent(NT_Topic topic);
+
+/**
+ * Sets the retained property of a topic.
+ *
+ * @param topic topic handle
+ * @param value new retained property value
+ */
+void SetTopicRetained(NT_Topic topic, bool value);
+
+/**
+ * Gets the retained property of a topic.
+ *
+ * @param topic topic handle
+ * @return retained property value
+ */
+bool GetTopicRetained(NT_Topic topic);
+
+/**
+ * Determine if topic exists (e.g. has at least one publisher).
+ *
+ * @param handle Topic, entry, or subscriber handle.
+ * @return True if topic exists.
+ */
+bool GetTopicExists(NT_Handle handle);
+
+/**
+ * Gets the current value of a property (as a JSON object).
+ *
+ * @param topic topic handle
+ * @param name property name
+ * @return JSON object; null object if the property does not exist.
+ */
+wpi::json GetTopicProperty(NT_Topic topic, std::string_view name);
+
+/**
+ * Sets a property value.
+ *
+ * @param topic topic handle
+ * @param name property name
+ * @param value property value
+ */
+void SetTopicProperty(NT_Topic topic, std::string_view name,
+                      const wpi::json& value);
+
+/**
+ * Deletes a property.  Has no effect if the property does not exist.
+ *
+ * @param topic topic handle
+ * @param name property name
+ */
+void DeleteTopicProperty(NT_Topic topic, std::string_view name);
+
+/**
+ * Gets all topic properties as a JSON object.  Each key in the object
+ * is the property name, and the corresponding value is the property value.
+ *
+ * @param topic topic handle
+ * @return JSON object
+ */
+wpi::json GetTopicProperties(NT_Topic topic);
+
+/**
+ * Updates multiple topic properties.  Each key in the passed-in object is
+ * the name of the property to add/update, and the corresponding value is the
+ * property value to set for that property.  Null values result in deletion
+ * of the corresponding property.
+ *
+ * @param topic topic handle
+ * @param update JSON object with keys to add/update/delete
+ * @return False if update is not a JSON object
+ */
+bool SetTopicProperties(NT_Topic topic, const wpi::json& update);
+
+/**
+ * Creates a new subscriber to value changes on a topic.
+ *
+ * @param topic topic handle
+ * @param type expected type
+ * @param typeStr expected type string
+ * @param options subscription options
+ * @return Subscriber handle
+ */
+NT_Subscriber Subscribe(NT_Topic topic, NT_Type type, std::string_view typeStr,
+                        const PubSubOptions& options = kDefaultPubSubOptions);
+
+/**
+ * Stops subscriber.
+ *
+ * @param sub subscriber handle
+ */
+void Unsubscribe(NT_Subscriber sub);
+
+/**
+ * Creates a new publisher to a topic.
+ *
+ * @param topic topic handle
+ * @param type type
+ * @param typeStr type string
+ * @param options publish options
+ * @return Publisher handle
+ */
+NT_Publisher Publish(NT_Topic topic, NT_Type type, std::string_view typeStr,
+                     const PubSubOptions& options = kDefaultPubSubOptions);
+
+/**
+ * Creates a new publisher to a topic.
+ *
+ * @param topic topic handle
+ * @param type type
+ * @param typeStr type string
+ * @param properties initial properties
+ * @param options publish options
+ * @return Publisher handle
+ */
+NT_Publisher PublishEx(NT_Topic topic, NT_Type type, std::string_view typeStr,
+                       const wpi::json& properties,
+                       const PubSubOptions& options = kDefaultPubSubOptions);
+
+/**
+ * Stops publisher.
+ *
+ * @param pubentry publisher/entry handle
+ */
+void Unpublish(NT_Handle pubentry);
+
+/**
+ * @brief Creates a new entry (subscriber and weak publisher) to a topic.
+ *
+ * @param topic topic handle
+ * @param type type
+ * @param typeStr type string
+ * @param options publish options
+ * @return Entry handle
+ */
+NT_Entry GetEntry(NT_Topic topic, NT_Type type, std::string_view typeStr,
+                  const PubSubOptions& options = kDefaultPubSubOptions);
+
+/**
+ * Stops entry subscriber/publisher.
+ *
+ * @param entry entry handle
+ */
+void ReleaseEntry(NT_Entry entry);
+
+/**
+ * Stops entry/subscriber/publisher.
+ *
+ * @param pubsubentry entry/subscriber/publisher handle
+ */
+void Release(NT_Handle pubsubentry);
+
+/**
+ * Gets the topic handle from an entry/subscriber/publisher handle.
+ *
+ * @param pubsubentry entry/subscriber/publisher handle
+ * @return Topic handle
+ */
+NT_Topic GetTopicFromHandle(NT_Handle pubsubentry);
 
 /** @} */
 
 /**
- * @defgroup ntcore_entrylistener_func Entry Listener Functions
+ * @defgroup ntcore_advancedsub_func Advanced Subscriber Functions
  * @{
  */
 
 /**
- * Entry listener callback function.
- * Called when a key-value pair is changed.
+ * Subscribes to multiple topics based on one or more topic name prefixes. Can
+ * be used in combination with a Value Listener or ReadQueueValue() to get value
+ * changes across all matching topics.
  *
- * @param entry_listener  entry listener handle returned by callback creation
- *                        function
- * @param name            entry name
- * @param value           the new value
- * @param flags           update flags; for example, NT_NOTIFY_NEW if the key
- *                        did not previously exist
+ * @param inst instance handle
+ * @param prefixes topic name prefixes
+ * @param options subscriber options
+ * @return subscriber handle
  */
-using EntryListenerCallback =
-    std::function<void(NT_EntryListener entry_listener, std::string_view name,
-                       std::shared_ptr<Value> value, unsigned int flags)>;
+NT_MultiSubscriber SubscribeMultiple(
+    NT_Inst inst, std::span<const std::string_view> prefixes,
+    const PubSubOptions& options = kDefaultPubSubOptions);
 
 /**
- * Add a listener for all entries starting with a certain prefix.
+ * Unsubscribes a multi-subscriber.
  *
- * @param inst              instance handle
- * @param prefix            UTF-8 string prefix
- * @param callback          listener to add
- * @param flags             NotifyKind bitmask
- * @return Listener handle
+ * @param sub multi-subscriber handle
  */
-NT_EntryListener AddEntryListener(
-    NT_Inst inst, std::string_view prefix,
-    std::function<void(const EntryNotification& event)> callback,
-    unsigned int flags);
+void UnsubscribeMultiple(NT_MultiSubscriber sub);
+
+/** @} */
 
 /**
- * Add a listener for a single entry.
- *
- * @param entry             entry handle
- * @param callback          listener to add
- * @param flags             NotifyKind bitmask
- * @return Listener handle
+ * @defgroup ntcore_listener_func Listener Functions
+ * @{
  */
-NT_EntryListener AddEntryListener(
-    NT_Entry entry,
-    std::function<void(const EntryNotification& event)> callback,
-    unsigned int flags);
+
+using ListenerCallback = std::function<void(const Event&)>;
 
 /**
- * Create a entry listener poller.
+ * Creates a listener poller.
  *
  * A poller provides a single queue of poll events.  Events linked to this
- * poller (using AddPolledEntryListener()) will be stored in the queue and
- * must be collected by calling PollEntryListener().
- * The returned handle must be destroyed with DestroyEntryListenerPoller().
+ * poller (using AddPolledListener()) will be stored in the queue and
+ * must be collected by calling ReadListenerQueue().
+ * The returned handle must be destroyed with DestroyListenerPoller().
  *
  * @param inst      instance handle
  * @return poller handle
  */
-NT_EntryListenerPoller CreateEntryListenerPoller(NT_Inst inst);
+NT_ListenerPoller CreateListenerPoller(NT_Inst inst);
 
 /**
- * Destroy a entry listener poller.  This will abort any blocked polling
+ * Destroys a listener poller.  This will abort any blocked polling
  * call and prevent additional events from being generated for this poller.
  *
  * @param poller    poller handle
  */
-void DestroyEntryListenerPoller(NT_EntryListenerPoller poller);
+void DestroyListenerPoller(NT_ListenerPoller poller);
 
 /**
- * Create a polled entry listener.
- * The caller is responsible for calling PollEntryListener() to poll.
- *
- * @param poller            poller handle
- * @param prefix            UTF-8 string prefix
- * @param flags             NotifyKind bitmask
- * @return Listener handle
- */
-NT_EntryListener AddPolledEntryListener(NT_EntryListenerPoller poller,
-                                        std::string_view prefix,
-                                        unsigned int flags);
-
-/**
- * Create a polled entry listener.
- * The caller is responsible for calling PollEntryListener() to poll.
- *
- * @param poller            poller handle
- * @param entry             entry handle
- * @param flags             NotifyKind bitmask
- * @return Listener handle
- */
-NT_EntryListener AddPolledEntryListener(NT_EntryListenerPoller poller,
-                                        NT_Entry entry, unsigned int flags);
-
-/**
- * Get the next entry listener event.  This blocks until the next event occurs.
- * This is intended to be used with AddPolledEntryListener(); entry listeners
- * created using AddEntryListener() will not be serviced through this function.
+ * Read notifications.
  *
  * @param poller    poller handle
- * @return Information on the entry listener events.  Only returns empty if an
- *         error occurred (e.g. the instance was invalid or is shutting down).
+ * @return Array of events.  Returns empty array if no events since last call.
  */
-std::vector<EntryNotification> PollEntryListener(NT_EntryListenerPoller poller);
+std::vector<Event> ReadListenerQueue(NT_ListenerPoller poller);
 
 /**
- * Get the next entry listener event.  This blocks until the next event occurs
- * or it times out.  This is intended to be used with AddPolledEntryListener();
- * entry listeners created using AddEntryListener() will not be serviced
- * through this function.
+ * Removes a listener.
  *
- * @param poller      poller handle
- * @param timeout     timeout, in seconds
- * @param timed_out   true if the timeout period elapsed (output)
- * @return Information on the entry listener events.  If empty is returned and
- *         and timed_out is also false, an error occurred (e.g. the instance
- *         was invalid or is shutting down).
+ * @param listener Listener handle to remove
  */
-std::vector<EntryNotification> PollEntryListener(NT_EntryListenerPoller poller,
-                                                 double timeout,
-                                                 bool* timed_out);
+void RemoveListener(NT_Listener listener);
 
 /**
- * Cancel a PollEntryListener call.  This wakes up a call to
- * PollEntryListener for this poller and causes it to immediately return
- * an empty array.
+ * Wait for the listener queue to be empty. This is primarily useful
+ * for deterministic testing. This blocks until either the listener
+ * queue is empty (e.g. there are no more events that need to be passed along to
+ * callbacks or poll queues) or the timeout expires.
  *
- * @param poller  poller handle
- */
-void CancelPollEntryListener(NT_EntryListenerPoller poller);
-
-/**
- * Remove an entry listener.
- *
- * @param entry_listener Listener handle to remove
- */
-void RemoveEntryListener(NT_EntryListener entry_listener);
-
-/**
- * Wait for the entry listener queue to be empty.  This is primarily useful
- * for deterministic testing.  This blocks until either the entry listener
- * queue is empty (e.g. there are no more events that need to be passed along
- * to callbacks or poll queues) or the timeout expires.
- *
- * @param inst      instance handle
- * @param timeout   timeout, in seconds.  Set to 0 for non-blocking behavior,
- *                  or a negative value to block indefinitely
+ * @param handle  handle
+ * @param timeout timeout, in seconds. Set to 0 for non-blocking behavior, or a
+ *                negative value to block indefinitely
  * @return False if timed out, otherwise true.
  */
-bool WaitForEntryListenerQueue(NT_Inst inst, double timeout);
-
-/** @} */
+bool WaitForListenerQueue(NT_Handle handle, double timeout);
 
 /**
- * @defgroup ntcore_connectionlistener_func Connection Listener Functions
- * @{
- */
-
-/**
- * Connection listener callback function.
- * Called when a network connection is made or lost.
+ * Create a listener for changes to topics with names that start with any of
+ * the given prefixes. This creates a corresponding internal subscriber with the
+ * lifetime of the listener.
  *
- * @param conn_listener   connection listener handle returned by callback
- *                        creation function
- * @param connected       true if event is due to connection being established
- * @param conn            connection info
+ * @param inst Instance handle
+ * @param prefixes Topic name string prefixes
+ * @param mask Bitmask of NT_EventFlags values (only topic and value events will
+ *             be generated)
+ * @param callback Listener function
  */
-using ConnectionListenerCallback =
-    std::function<void(NT_ConnectionListener, bool, const ConnectionInfo&)>;
+NT_Listener AddListener(NT_Inst inst,
+                        std::span<const std::string_view> prefixes,
+                        unsigned int mask, ListenerCallback callback);
 
 /**
- * Add a connection listener.
+ * Create a listener.
  *
- * @param inst              instance handle
- * @param callback          listener to add
- * @param immediate_notify  notify listener of all existing connections
+ * Some combinations of handle and mask have no effect:
+ * - connection and log message events are only generated on instances
+ * - topic and value events are only generated on non-instances
+ *
+ * Adding value and topic events on a topic will create a corresponding internal
+ * subscriber with the lifetime of the listener.
+ *
+ * Adding a log message listener through this function will only result in
+ * events at NT_LOG_INFO or higher; for more customized settings, use
+ * AddLogger().
+ *
+ * @param handle Instance, topic, subscriber, multi-subscriber, or entry handle
+ * @param mask Bitmask of NT_EventFlags values
+ * @param callback Listener function
+ */
+NT_Listener AddListener(NT_Handle handle, unsigned int mask,
+                        ListenerCallback callback);
+
+/**
+ * Creates a polled listener. This creates a corresponding internal subscriber
+ * with the lifetime of the listener.
+ * The caller is responsible for calling ReadListenerQueue() to poll.
+ *
+ * @param poller poller handle
+ * @param prefixes array of UTF-8 string prefixes
+ * @param mask Bitmask of NT_EventFlags values (only topic and value events will
+ *             be generated)
  * @return Listener handle
  */
-NT_ConnectionListener AddConnectionListener(
-    NT_Inst inst,
-    std::function<void(const ConnectionNotification& event)> callback,
-    bool immediate_notify);
+NT_Listener AddPolledListener(NT_ListenerPoller poller,
+                              std::span<const std::string_view> prefixes,
+                              unsigned int mask);
 
 /**
- * Create a connection listener poller.
+ * Creates a polled listener.
+ * The caller is responsible for calling ReadListenerQueue() to poll.
  *
- * A poller provides a single queue of poll events.  Events linked to this
- * poller (using AddPolledConnectionListener()) will be stored in the queue and
- * must be collected by calling PollConnectionListener().
- * The returned handle must be destroyed with DestroyConnectionListenerPoller().
+ * Some combinations of handle and mask have no effect:
+ * - connection and log message events are only generated on instances
+ * - topic and value events are only generated on non-instances
  *
- * @param inst      instance handle
- * @return poller handle
+ * Adding value and topic events on a topic will create a corresponding internal
+ * subscriber with the lifetime of the listener.
+ *
+ * Adding a log message listener through this function will only result in
+ * events at NT_LOG_INFO or higher; for more customized settings, use
+ * AddPolledLogger().
+ *
+ * @param poller poller handle
+ * @param handle instance, topic, subscriber, multi-subscriber, or entry handle
+ * @param mask NT_EventFlags bitmask
+ * @return Listener handle
  */
-NT_ConnectionListenerPoller CreateConnectionListenerPoller(NT_Inst inst);
-
-/**
- * Destroy a connection listener poller.  This will abort any blocked polling
- * call and prevent additional events from being generated for this poller.
- *
- * @param poller    poller handle
- */
-void DestroyConnectionListenerPoller(NT_ConnectionListenerPoller poller);
-
-/**
- * Create a polled connection listener.
- * The caller is responsible for calling PollConnectionListener() to poll.
- *
- * @param poller            poller handle
- * @param immediate_notify  notify listener of all existing connections
- */
-NT_ConnectionListener AddPolledConnectionListener(
-    NT_ConnectionListenerPoller poller, bool immediate_notify);
-
-/**
- * Get the next connection event.  This blocks until the next connect or
- * disconnect occurs.  This is intended to be used with
- * AddPolledConnectionListener(); connection listeners created using
- * AddConnectionListener() will not be serviced through this function.
- *
- * @param poller    poller handle
- * @return Information on the connection events.  Only returns empty if an
- *         error occurred (e.g. the instance was invalid or is shutting down).
- */
-std::vector<ConnectionNotification> PollConnectionListener(
-    NT_ConnectionListenerPoller poller);
-
-/**
- * Get the next connection event.  This blocks until the next connect or
- * disconnect occurs or it times out.  This is intended to be used with
- * AddPolledConnectionListener(); connection listeners created using
- * AddConnectionListener() will not be serviced through this function.
- *
- * @param poller      poller handle
- * @param timeout     timeout, in seconds
- * @param timed_out   true if the timeout period elapsed (output)
- * @return Information on the connection events.  If empty is returned and
- *         timed_out is also false, an error occurred (e.g. the instance was
- *         invalid or is shutting down).
- */
-std::vector<ConnectionNotification> PollConnectionListener(
-    NT_ConnectionListenerPoller poller, double timeout, bool* timed_out);
-
-/**
- * Cancel a PollConnectionListener call.  This wakes up a call to
- * PollConnectionListener for this poller and causes it to immediately return
- * an empty array.
- *
- * @param poller  poller handle
- */
-void CancelPollConnectionListener(NT_ConnectionListenerPoller poller);
-
-/**
- * Remove a connection listener.
- *
- * @param conn_listener Listener handle to remove
- */
-void RemoveConnectionListener(NT_ConnectionListener conn_listener);
-
-/**
- * Wait for the connection listener queue to be empty.  This is primarily useful
- * for deterministic testing.  This blocks until either the connection listener
- * queue is empty (e.g. there are no more events that need to be passed along
- * to callbacks or poll queues) or the timeout expires.
- *
- * @param inst      instance handle
- * @param timeout   timeout, in seconds.  Set to 0 for non-blocking behavior,
- *                  or a negative value to block indefinitely
- * @return False if timed out, otherwise true.
- */
-bool WaitForConnectionListenerQueue(NT_Inst inst, double timeout);
-
-/** @} */
-
-/**
- * @defgroup ntcore_rpc_func Remote Procedure Call Functions
- * @{
- */
-
-/**
- * Create a callback-based RPC entry point.  Only valid to use on the server.
- * The callback function will be called when the RPC is called.
- *
- * @param entry     entry handle of RPC entry
- * @param def       RPC definition
- * @param callback  callback function; note the callback function must call
- *                  PostRpcResponse() to provide a response to the call
- */
-void CreateRpc(NT_Entry entry, std::string_view def,
-               std::function<void(const RpcAnswer& answer)> callback);
-
-/**
- * Create a RPC call poller.  Only valid to use on the server.
- *
- * A poller provides a single queue of poll events.  Events linked to this
- * poller (using CreatePolledRpc()) will be stored in the queue and must be
- * collected by calling PollRpc().
- * The returned handle must be destroyed with DestroyRpcCallPoller().
- *
- * @param inst      instance handle
- * @return poller handle
- */
-NT_RpcCallPoller CreateRpcCallPoller(NT_Inst inst);
-
-/**
- * Destroy a RPC call poller.  This will abort any blocked polling call and
- * prevent additional events from being generated for this poller.
- *
- * @param poller    poller handle
- */
-void DestroyRpcCallPoller(NT_RpcCallPoller poller);
-
-/**
- * Create a polled RPC entry point.  Only valid to use on the server.
- * The caller is responsible for calling PollRpc() to poll for servicing
- * incoming RPC calls.
- *
- * @param entry     entry handle of RPC entry
- * @param def       RPC definition
- * @param poller    poller handle
- */
-void CreatePolledRpc(NT_Entry entry, std::string_view def,
-                     NT_RpcCallPoller poller);
-
-/**
- * Get the next incoming RPC call.  This blocks until the next incoming RPC
- * call is received.  This is intended to be used with CreatePolledRpc();
- * RPC calls created using CreateRpc() will not be serviced through this
- * function.  Upon successful return, PostRpcResponse() must be called to
- * send the return value to the caller.
- *
- * @param poller      poller handle
- * @return Information on the next RPC calls.  Only returns empty if an error
- *         occurred (e.g. the instance was invalid or is shutting down).
- */
-std::vector<RpcAnswer> PollRpc(NT_RpcCallPoller poller);
-
-/**
- * Get the next incoming RPC call.  This blocks until the next incoming RPC
- * call is received or it times out.  This is intended to be used with
- * CreatePolledRpc(); RPC calls created using CreateRpc() will not be
- * serviced through this function.  Upon successful return,
- * PostRpcResponse() must be called to send the return value to the caller.
- *
- * @param poller      poller handle
- * @param timeout     timeout, in seconds
- * @param timed_out   true if the timeout period elapsed (output)
- * @return Information on the next RPC calls.  If empty and timed_out is also
- *         false, an error occurred (e.g. the instance was invalid or is
- *         shutting down).
- */
-std::vector<RpcAnswer> PollRpc(NT_RpcCallPoller poller, double timeout,
-                               bool* timed_out);
-
-/**
- * Cancel a PollRpc call.  This wakes up a call to PollRpc for this poller
- * and causes it to immediately return an empty array.
- *
- * @param poller  poller handle
- */
-void CancelPollRpc(NT_RpcCallPoller poller);
-
-/**
- * Wait for the incoming RPC call queue to be empty.  This is primarily useful
- * for deterministic testing.  This blocks until either the RPC call
- * queue is empty (e.g. there are no more events that need to be passed along
- * to callbacks or poll queues) or the timeout expires.
- *
- * @param inst      instance handle
- * @param timeout   timeout, in seconds.  Set to 0 for non-blocking behavior,
- *                  or a negative value to block indefinitely
- * @return False if timed out, otherwise true.
- */
-bool WaitForRpcCallQueue(NT_Inst inst, double timeout);
-
-/**
- * Post RPC response (return value) for a polled RPC.
- * The rpc and call parameters should come from the RpcAnswer returned
- * by PollRpc().
- *
- * @param entry       entry handle of RPC entry (from RpcAnswer)
- * @param call        RPC call handle (from RpcAnswer)
- * @param result      result raw data that will be provided to remote caller
- * @return            true if the response was posted, otherwise false
- */
-bool PostRpcResponse(NT_Entry entry, NT_RpcCall call, std::string_view result);
-
-/**
- * Call a RPC function.  May be used on either the client or server.
- * This function is non-blocking.  Either GetRpcResult() or
- * CancelRpcResult() must be called to either get or ignore the result of
- * the call.
- *
- * @param entry       entry handle of RPC entry
- * @param params      parameter
- * @return RPC call handle (for use with GetRpcResult() or
- *         CancelRpcResult()).
- */
-NT_RpcCall CallRpc(NT_Entry entry, std::string_view params);
-
-/**
- * Get the result (return value) of a RPC call.  This function blocks until
- * the result is received.
- *
- * @param entry       entry handle of RPC entry
- * @param call        RPC call handle returned by CallRpc()
- * @param result      received result (output)
- * @return False on error, true otherwise.
- */
-bool GetRpcResult(NT_Entry entry, NT_RpcCall call, std::string* result);
-
-/**
- * Get the result (return value) of a RPC call.  This function blocks until
- * the result is received or it times out.
- *
- * @param entry       entry handle of RPC entry
- * @param call        RPC call handle returned by CallRpc()
- * @param result      received result (output)
- * @param timeout     timeout, in seconds
- * @param timed_out   true if the timeout period elapsed (output)
- * @return False on error or timeout, true otherwise.
- */
-bool GetRpcResult(NT_Entry entry, NT_RpcCall call, std::string* result,
-                  double timeout, bool* timed_out);
-
-/**
- * Ignore the result of a RPC call.  This function is non-blocking.
- *
- * @param entry       entry handle of RPC entry
- * @param call        RPC call handle returned by CallRpc()
- */
-void CancelRpcResult(NT_Entry entry, NT_RpcCall call);
-
-/**
- * Pack a RPC version 1 definition.
- *
- * @param def         RPC version 1 definition
- * @return Raw packed bytes.
- */
-std::string PackRpcDefinition(const RpcDefinition& def);
-
-/**
- * Unpack a RPC version 1 definition.  This can be used for introspection or
- * validation.
- *
- * @param packed      raw packed bytes
- * @param def         RPC version 1 definition (output)
- * @return True if successfully unpacked, false otherwise.
- */
-bool UnpackRpcDefinition(std::string_view packed, RpcDefinition* def);
-
-/**
- * Pack RPC values as required for RPC version 1 definition messages.
- *
- * @param values      array of values to pack
- * @return Raw packed bytes.
- */
-std::string PackRpcValues(wpi::span<const std::shared_ptr<Value>> values);
-
-/**
- * Unpack RPC values as required for RPC version 1 definition messages.
- *
- * @param packed      raw packed bytes
- * @param types       array of data types (as provided in the RPC definition)
- * @return Array of values.
- */
-std::vector<std::shared_ptr<Value>> UnpackRpcValues(
-    std::string_view packed, wpi::span<const NT_Type> types);
+NT_Listener AddPolledListener(NT_ListenerPoller poller, NT_Handle handle,
+                              unsigned int mask);
 
 /** @} */
 
@@ -975,16 +990,6 @@
  */
 
 /**
- * Set the network identity of this node.
- * This is the name used during the initial connection handshake, and is
- * visible through ConnectionInfo on the remote node.
- *
- * @param inst      instance handle
- * @param name      identity to advertise
- */
-void SetNetworkIdentity(NT_Inst inst, std::string_view name);
-
-/**
  * Get the current network mode.
  *
  * @param inst  instance handle
@@ -1013,10 +1018,12 @@
  *                          null terminated)
  * @param listen_address    the address to listen on, or null to listen on any
  *                          address. (UTF-8 string, null terminated)
- * @param port              port to communicate over.
+ * @param port3             port to communicate over (NT3)
+ * @param port4             port to communicate over (NT4)
  */
 void StartServer(NT_Inst inst, std::string_view persist_filename,
-                 const char* listen_address, unsigned int port);
+                 const char* listen_address, unsigned int port3,
+                 unsigned int port4);
 
 /**
  * Stops the server if it is running.
@@ -1026,41 +1033,22 @@
 void StopServer(NT_Inst inst);
 
 /**
- * Starts a client.  Use SetServer to set the server name and port.
- *
- * @param inst  instance handle
- */
-void StartClient(NT_Inst inst);
-
-/**
- * Starts a client using the specified server and port
- *
- * @param inst        instance handle
- * @param server_name server name (UTF-8 string, null terminated)
- * @param port        port to communicate over
- */
-void StartClient(NT_Inst inst, const char* server_name, unsigned int port);
-
-/**
- * Starts a client using the specified (server, port) combinations.  The
- * client will attempt to connect to each server in round robin fashion.
+ * Starts a NT3 client.  Use SetServer or SetServerTeam to set the server name
+ * and port.
  *
  * @param inst      instance handle
- * @param servers   array of server name and port pairs
+ * @param identity  network identity to advertise (cannot be empty string)
  */
-void StartClient(
-    NT_Inst inst,
-    wpi::span<const std::pair<std::string_view, unsigned int>> servers);
+void StartClient3(NT_Inst inst, std::string_view identity);
 
 /**
- * Starts a client using commonly known robot addresses for the specified
- * team.
+ * Starts a NT4 client.  Use SetServer or SetServerTeam to set the server name
+ * and port.
  *
- * @param inst        instance handle
- * @param team        team number
- * @param port        port to communicate over
+ * @param inst      instance handle
+ * @param identity  network identity to advertise (cannot be empty string)
  */
-void StartClientTeam(NT_Inst inst, unsigned int team, unsigned int port);
+void StartClient4(NT_Inst inst, std::string_view identity);
 
 /**
  * Stops the client if it is running.
@@ -1087,7 +1075,7 @@
  */
 void SetServer(
     NT_Inst inst,
-    wpi::span<const std::pair<std::string_view, unsigned int>> servers);
+    std::span<const std::pair<std::string_view, unsigned int>> servers);
 
 /**
  * Sets server addresses and port for client (without restarting client).
@@ -1105,7 +1093,7 @@
  * server IP address.
  *
  * @param inst  instance handle
- * @param port server port to use in combination with IP from DS
+ * @param port  server port to use in combination with IP from DS
  */
 void StartDSClient(NT_Inst inst, unsigned int port);
 
@@ -1117,20 +1105,23 @@
 void StopDSClient(NT_Inst inst);
 
 /**
- * Set the periodic update rate.
- * Sets how frequently updates are sent to other nodes over the network.
+ * Flush local updates.
+ *
+ * Forces an immediate flush of all local changes to the client/server.
+ * This does not flush to the network.
+ *
+ * Normally this is done on a regularly scheduled interval.
  *
  * @param inst      instance handle
- * @param interval  update interval in seconds (range 0.01 to 1.0)
  */
-void SetUpdateRate(NT_Inst inst, double interval);
+void FlushLocal(NT_Inst inst);
 
 /**
- * Flush Entries.
+ * Flush to network.
  *
  * Forces an immediate flush of all local entry changes to network.
- * Normally this is done on a regularly scheduled interval (see
- * SetUpdateRate()).
+ * Normally this is done on a regularly scheduled interval (set
+ * by update rates on individual publishers).
  *
  * Note: flushes are rate limited to avoid excessive network traffic.  If
  * the time between calls is too short, the flush will occur after the minimum
@@ -1157,63 +1148,18 @@
  */
 bool IsConnected(NT_Inst inst);
 
-/** @} */
-
 /**
- * @defgroup ntcore_file_func File Save/Load Functions
- * @{
- */
-
-/**
- * Save persistent values to a file.  The server automatically does this,
- * but this function provides a way to save persistent values in the same
- * format to a file on either a client or a server.
+ * Get the time offset between server time and local time. Add this value to
+ * local time to get the estimated equivalent server time. In server mode, this
+ * always returns 0. In client mode, this returns the time offset only if the
+ * client and server are connected and have exchanged synchronization messages.
+ * Note the time offset may change over time as it is periodically updated; to
+ * receive updates as events, add a listener to the "time sync" event.
  *
- * @param inst      instance handle
- * @param filename  filename
- * @return error string, or nullptr if successful
+ * @param inst instance handle
+ * @return Time offset in microseconds (optional)
  */
-const char* SavePersistent(NT_Inst inst, std::string_view filename);
-
-/**
- * Load persistent values from a file.  The server automatically does this
- * at startup, but this function provides a way to restore persistent values
- * in the same format from a file at any time on either a client or a server.
- *
- * @param inst      instance handle
- * @param filename  filename
- * @param warn      callback function for warnings
- * @return error string, or nullptr if successful
- */
-const char* LoadPersistent(
-    NT_Inst inst, std::string_view filename,
-    std::function<void(size_t line, const char* msg)> warn);
-
-/**
- * Save table values to a file.  The file format used is identical to
- * that used for SavePersistent.
- *
- * @param inst      instance handle
- * @param filename  filename
- * @param prefix    save only keys starting with this prefix
- * @return error string, or nullptr if successful
- */
-const char* SaveEntries(NT_Inst inst, std::string_view filename,
-                        std::string_view prefix);
-
-/**
- * Load table values from a file.  The file format used is identical to
- * that used for SavePersistent / LoadPersistent.
- *
- * @param inst      instance handle
- * @param filename  filename
- * @param prefix    load only keys starting with this prefix
- * @param warn      callback function for warnings
- * @return error string, or nullptr if successful
- */
-const char* LoadEntries(NT_Inst inst, std::string_view filename,
-                        std::string_view prefix,
-                        std::function<void(size_t line, const char* msg)> warn);
+std::optional<int64_t> GetServerTimeOffset(NT_Inst inst);
 
 /** @} */
 
@@ -1224,12 +1170,90 @@
 
 /**
  * Returns monotonic current time in 1 us increments.
- * This is the same time base used for entry and connection timestamps.
- * This function is a compatibility wrapper around wpi::Now().
+ * This is the same time base used for value and connection timestamps.
+ * This function by default simply wraps wpi::Now(), but if SetNow() is
+ * called, this function instead returns the value passed to SetNow();
+ * this can be used to reduce overhead.
  *
  * @return Timestamp
  */
-uint64_t Now();
+int64_t Now();
+
+/**
+ * Sets the current timestamp used for timestamping values that do not
+ * provide a timestamp (e.g. a value of 0 is passed).  For consistency,
+ * it also results in Now() returning the set value.  This should generally
+ * be used only if the overhead of calling wpi::Now() is a concern.
+ * If used, it should be called periodically with the value of wpi::Now().
+ *
+ * @param timestamp timestamp (1 us increments)
+ */
+void SetNow(int64_t timestamp);
+
+/**
+ * Turns a type string into a type enum value.
+ *
+ * @param typeString type string
+ * @return Type value
+ */
+NT_Type GetTypeFromString(std::string_view typeString);
+
+/**
+ * Turns a type enum value into a type string.
+ *
+ * @param type type enum
+ * @return Type string
+ */
+std::string_view GetStringFromType(NT_Type type);
+
+/** @} */
+
+/**
+ * @defgroup ntcore_data_logger_func Data Logger Functions
+ * @{
+ */
+
+/**
+ * Starts logging entry changes to a DataLog.
+ *
+ * @param inst instance handle
+ * @param log data log object; lifetime must extend until StopEntryDataLog is
+ *            called or the instance is destroyed
+ * @param prefix only store entries with names that start with this prefix;
+ *               the prefix is not included in the data log entry name
+ * @param logPrefix prefix to add to data log entry names
+ * @return Data logger handle
+ */
+NT_DataLogger StartEntryDataLog(NT_Inst inst, wpi::log::DataLog& log,
+                                std::string_view prefix,
+                                std::string_view logPrefix);
+
+/**
+ * Stops logging entry changes to a DataLog.
+ *
+ * @param logger data logger handle
+ */
+void StopEntryDataLog(NT_DataLogger logger);
+
+/**
+ * Starts logging connection changes to a DataLog.
+ *
+ * @param inst instance handle
+ * @param log data log object; lifetime must extend until StopConnectionDataLog
+ *            is called or the instance is destroyed
+ * @param name data log entry name
+ * @return Data logger handle
+ */
+NT_ConnectionDataLogger StartConnectionDataLog(NT_Inst inst,
+                                               wpi::log::DataLog& log,
+                                               std::string_view name);
+
+/**
+ * Stops logging connection changes to a DataLog.
+ *
+ * @param logger data logger handle
+ */
+void StopConnectionDataLog(NT_ConnectionDataLogger logger);
 
 /** @} */
 
@@ -1246,31 +1270,13 @@
  * messages outside this range will be silently ignored.
  *
  * @param inst        instance handle
- * @param func        log callback function
  * @param min_level   minimum log level
  * @param max_level   maximum log level
- * @return Logger handle
+ * @param func        listener callback function
+ * @return Listener handle
  */
-NT_Logger AddLogger(NT_Inst inst,
-                    std::function<void(const LogMessage& msg)> func,
-                    unsigned int min_level, unsigned int max_level);
-
-/**
- * Create a log poller.  A poller provides a single queue of poll events.
- * The returned handle must be destroyed with DestroyLoggerPoller().
- *
- * @param inst      instance handle
- * @return poller handle
- */
-NT_LoggerPoller CreateLoggerPoller(NT_Inst inst);
-
-/**
- * Destroy a log poller.  This will abort any blocked polling call and prevent
- * additional events from being generated for this poller.
- *
- * @param poller    poller handle
- */
-void DestroyLoggerPoller(NT_LoggerPoller poller);
+NT_Listener AddLogger(NT_Inst inst, unsigned int min_level,
+                      unsigned int max_level, ListenerCallback func);
 
 /**
  * Set the log level for a log poller.  Events will only be generated for
@@ -1282,69 +1288,125 @@
  * @param max_level     maximum log level
  * @return Logger handle
  */
-NT_Logger AddPolledLogger(NT_LoggerPoller poller, unsigned int min_level,
-                          unsigned int max_level);
-
-/**
- * Get the next log event.  This blocks until the next log occurs.
- *
- * @param poller    poller handle
- * @return Information on the log events.  Only returns empty if an error
- *         occurred (e.g. the instance was invalid or is shutting down).
- */
-std::vector<LogMessage> PollLogger(NT_LoggerPoller poller);
-
-/**
- * Get the next log event.  This blocks until the next log occurs or it times
- * out.
- *
- * @param poller      poller handle
- * @param timeout     timeout, in seconds
- * @param timed_out   true if the timeout period elapsed (output)
- * @return Information on the log events.  If empty is returned and timed_out
- *         is also false, an error occurred (e.g. the instance was invalid or
- *         is shutting down).
- */
-std::vector<LogMessage> PollLogger(NT_LoggerPoller poller, double timeout,
-                                   bool* timed_out);
-
-/**
- * Cancel a PollLogger call.  This wakes up a call to PollLogger for this
- * poller and causes it to immediately return an empty array.
- *
- * @param poller  poller handle
- */
-void CancelPollLogger(NT_LoggerPoller poller);
-
-/**
- * Remove a logger.
- *
- * @param logger Logger handle to remove
- */
-void RemoveLogger(NT_Logger logger);
-
-/**
- * Wait for the incoming log event queue to be empty.  This is primarily useful
- * for deterministic testing.  This blocks until either the log event
- * queue is empty (e.g. there are no more events that need to be passed along
- * to callbacks or poll queues) or the timeout expires.
- *
- * @param inst      instance handle
- * @param timeout   timeout, in seconds.  Set to 0 for non-blocking behavior,
- *                  or a negative value to block indefinitely
- * @return False if timed out, otherwise true.
- */
-bool WaitForLoggerQueue(NT_Inst inst, double timeout);
+NT_Listener AddPolledLogger(NT_ListenerPoller poller, unsigned int min_level,
+                            unsigned int max_level);
 
 /** @} */
 /** @} */
 
-inline bool RpcAnswer::PostResponse(std::string_view result) const {
-  auto ret = PostRpcResponse(entry, call, result);
-  call = 0;
-  return ret;
-}
+/**
+ * NetworkTables meta-topic decoding functions.
+ */
+namespace meta {
 
+/**
+ * @defgroup ntcore_cpp_meta_api ntcore C++ meta-topic API
+ *
+ * Meta-topic decoders for C++.
+ *
+ * @{
+ */
+
+/**
+ * Subscriber options. Different from PubSubOptions in this reflects only
+ * options that are sent over the network.
+ */
+struct SubscriberOptions {
+  double periodic = 0.1;
+  bool topicsOnly = false;
+  bool sendAll = false;
+  bool prefixMatch = false;
+  // std::string otherStr;
+};
+
+/**
+ * Topic publisher (as published via `$pub$<topic>`).
+ */
+struct TopicPublisher {
+  std::string client;
+  uint64_t pubuid = 0;
+};
+
+/**
+ * Topic subscriber (as published via `$sub$<topic>`).
+ */
+struct TopicSubscriber {
+  std::string client;
+  uint64_t subuid = 0;
+  SubscriberOptions options;
+};
+
+/**
+ * Client publisher (as published via `$clientpub$<client>` or `$serverpub`).
+ */
+struct ClientPublisher {
+  int64_t uid = -1;
+  std::string topic;
+};
+
+/**
+ * Client subscriber (as published via `$clientsub$<client>` or `$serversub`).
+ */
+struct ClientSubscriber {
+  int64_t uid = -1;
+  std::vector<std::string> topics;
+  SubscriberOptions options;
+};
+
+/**
+ * Client (as published via `$clients`).
+ */
+struct Client {
+  std::string id;
+  std::string conn;
+  uint16_t version = 0;
+};
+
+/**
+ * Decodes `$pub$<topic>` meta-topic data.
+ *
+ * @param data data contents
+ * @return Vector of TopicPublishers, or empty optional on decoding error.
+ */
+std::optional<std::vector<TopicPublisher>> DecodeTopicPublishers(
+    std::span<const uint8_t> data);
+
+/**
+ * Decodes `$sub$<topic>` meta-topic data.
+ *
+ * @param data data contents
+ * @return Vector of TopicSubscribers, or empty optional on decoding error.
+ */
+std::optional<std::vector<TopicSubscriber>> DecodeTopicSubscribers(
+    std::span<const uint8_t> data);
+
+/**
+ * Decodes `$clientpub$<topic>` meta-topic data.
+ *
+ * @param data data contents
+ * @return Vector of ClientPublishers, or empty optional on decoding error.
+ */
+std::optional<std::vector<ClientPublisher>> DecodeClientPublishers(
+    std::span<const uint8_t> data);
+
+/**
+ * Decodes `$clientsub$<topic>` meta-topic data.
+ *
+ * @param data data contents
+ * @return Vector of ClientSubscribers, or empty optional on decoding error.
+ */
+std::optional<std::vector<ClientSubscriber>> DecodeClientSubscribers(
+    std::span<const uint8_t> data);
+
+/**
+ * Decodes `$clients` meta-topic data.
+ *
+ * @param data data contents
+ * @return Vector of Clients, or empty optional on decoding error.
+ */
+std::optional<std::vector<Client>> DecodeClients(std::span<const uint8_t> data);
+
+/** @} */
+
+}  // namespace meta
 }  // namespace nt
-
-#endif  // NTCORE_NTCORE_CPP_H_
diff --git a/third_party/allwpilib/ntcore/src/main/native/include/ntcore_test.h b/third_party/allwpilib/ntcore/src/main/native/include/ntcore_test.h
index 65d1243..7e02446 100644
--- a/third_party/allwpilib/ntcore/src/main/native/include/ntcore_test.h
+++ b/third_party/allwpilib/ntcore/src/main/native/include/ntcore_test.h
@@ -2,19 +2,19 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
-#ifndef NTCORE_NTCORE_TEST_H_
-#define NTCORE_NTCORE_TEST_H_
+#pragma once
 
 #include <stdint.h>
 
-#include <string>
-
 #include "ntcore.h"
 
 // Functions in this header are to be used only for testing
 
+#ifdef __cplusplus
 extern "C" {
-struct NT_String* NT_GetStringForTesting(const char* string, int* struct_size);
+#endif
+
+struct NT_String* NT_GetStringForTesting(const char* str, int* struct_size);
 // No need for free as one already exists in main library
 
 struct NT_EntryInfo* NT_GetEntryInfoForTesting(const char* name,
@@ -59,28 +59,6 @@
                                                   int* struct_size);
 // No need for free as one already exists in the main library
 
-struct NT_RpcParamDef* NT_GetRpcParamDefForTesting(const char* name,
-                                                   const struct NT_Value* val,
-                                                   int* struct_size);
-
-void NT_FreeRpcParamDefForTesting(struct NT_RpcParamDef* def);
-
-struct NT_RpcResultDef* NT_GetRpcResultsDefForTesting(const char* name,
-                                                      enum NT_Type type,
-                                                      int* struct_size);
-
-void NT_FreeRpcResultsDefForTesting(struct NT_RpcResultDef* def);
-
-struct NT_RpcDefinition* NT_GetRpcDefinitionForTesting(
-    unsigned int version, const char* name, size_t num_params,
-    const struct NT_RpcParamDef* params, size_t num_results,
-    const struct NT_RpcResultDef* results, int* struct_size);
-// No need for free as one already exists in the main library
-
-struct NT_RpcCallInfo* NT_GetRpcCallInfoForTesting(
-    unsigned int rpc_id, unsigned int call_uid, const char* name,
-    const char* params, size_t params_len, int* struct_size);
-// No need for free as one already exists in the main library
+#ifdef __cplusplus
 }  // extern "C"
-
-#endif  // NTCORE_NTCORE_TEST_H_
+#endif
diff --git a/third_party/allwpilib/ntcore/src/test/java/edu/wpi/first/networktables/ConnectionListenerTest.java b/third_party/allwpilib/ntcore/src/test/java/edu/wpi/first/networktables/ConnectionListenerTest.java
index 3c38853..9fac048 100644
--- a/third_party/allwpilib/ntcore/src/test/java/edu/wpi/first/networktables/ConnectionListenerTest.java
+++ b/third_party/allwpilib/ntcore/src/test/java/edu/wpi/first/networktables/ConnectionListenerTest.java
@@ -11,13 +11,13 @@
 import static org.junit.jupiter.api.Assertions.assertTrue;
 import static org.junit.jupiter.api.Assertions.fail;
 
+import edu.wpi.first.util.WPIUtilJNI;
 import java.util.ArrayList;
+import java.util.EnumSet;
 import java.util.List;
 import org.junit.jupiter.api.AfterEach;
 import org.junit.jupiter.api.BeforeEach;
 import org.junit.jupiter.api.Test;
-import org.junit.jupiter.api.condition.DisabledOnOs;
-import org.junit.jupiter.api.condition.OS;
 import org.junit.jupiter.params.ParameterizedTest;
 import org.junit.jupiter.params.provider.ValueSource;
 
@@ -28,10 +28,7 @@
   @BeforeEach
   void setUp() {
     m_serverInst = NetworkTableInstance.create();
-    m_serverInst.setNetworkIdentity("server");
-
     m_clientInst = NetworkTableInstance.create();
-    m_clientInst.setNetworkIdentity("client");
   }
 
   @AfterEach
@@ -42,13 +39,19 @@
 
   /** Connect to the server. */
   private void connect(int port) {
-    m_serverInst.startServer("connectionlistenertest.ini", "127.0.0.1", port);
-    m_clientInst.startClient("127.0.0.1", port);
+    m_serverInst.startServer("connectionlistenertest.json", "127.0.0.1", 0, port);
+    m_clientInst.startClient4("client");
+    m_clientInst.setServer("127.0.0.1", port);
 
-    // wait for client to report it's started, then wait another 0.1 sec
+    // wait for client to report it's connected, then wait another 0.1 sec
     try {
-      while ((m_clientInst.getNetworkMode() & NetworkTableInstance.kNetModeStarting) != 0) {
+      int count = 0;
+      while (!m_clientInst.isConnected()) {
         Thread.sleep(100);
+        count++;
+        if (count > 30) {
+          throw new InterruptedException();
+        }
       }
       Thread.sleep(100);
     } catch (InterruptedException ex) {
@@ -57,31 +60,31 @@
   }
 
   @Test
-  @DisabledOnOs(OS.WINDOWS)
   void testJNI() {
     // set up the poller
-    int poller = NetworkTablesJNI.createConnectionListenerPoller(m_serverInst.getHandle());
+    int poller = NetworkTablesJNI.createListenerPoller(m_serverInst.getHandle());
     assertNotSame(poller, 0, "bad poller handle");
-    int handle = NetworkTablesJNI.addPolledConnectionListener(poller, false);
+    int handle =
+        NetworkTablesJNI.addListener(
+            poller, m_serverInst.getHandle(), EnumSet.of(NetworkTableEvent.Kind.kConnection));
     assertNotSame(handle, 0, "bad listener handle");
 
     // trigger a connect event
     connect(10020);
 
     // get the event
-    assertTrue(m_serverInst.waitForConnectionListenerQueue(1.0));
-    ConnectionNotification[] events = null;
     try {
-      events = NetworkTablesJNI.pollConnectionListenerTimeout(m_serverInst, poller, 0.0);
+      assertFalse(WPIUtilJNI.waitForObjectTimeout(handle, 1.0));
     } catch (InterruptedException ex) {
-      Thread.currentThread().interrupt();
-      fail("unexpected interrupted exception" + ex);
+      fail("interrupted while waiting for queue");
     }
+    NetworkTableEvent[] events = NetworkTablesJNI.readListenerQueue(m_serverInst, poller);
 
     assertNotNull(events);
     assertEquals(1, events.length);
     assertEquals(handle, events[0].listener);
-    assertTrue(events[0].connected);
+    assertNotNull(events[0].connInfo);
+    assertTrue(events[0].is(NetworkTableEvent.Kind.kConnected));
 
     // trigger a disconnect event
     m_clientInst.stopClient();
@@ -92,50 +95,71 @@
     }
 
     // get the event
-    assertTrue(m_serverInst.waitForConnectionListenerQueue(1.0));
     try {
-      events = NetworkTablesJNI.pollConnectionListenerTimeout(m_serverInst, poller, 0.0);
+      assertFalse(WPIUtilJNI.waitForObjectTimeout(handle, 1.0));
     } catch (InterruptedException ex) {
-      Thread.currentThread().interrupt();
-      fail("unexpected interrupted exception" + ex);
+      fail("interrupted while waiting for queue");
     }
+    events = NetworkTablesJNI.readListenerQueue(m_serverInst, poller);
 
     assertNotNull(events);
     assertEquals(1, events.length);
     assertEquals(handle, events[0].listener);
-    assertFalse(events[0].connected);
+    assertTrue(events[0].is(NetworkTableEvent.Kind.kDisconnected));
   }
 
   private static int threadedPort = 10001;
 
   @ParameterizedTest
-  @DisabledOnOs(OS.WINDOWS)
   @ValueSource(strings = {"127.0.0.1", "127.0.0.1 ", " 127.0.0.1 "})
   void testThreaded(String address) {
-    m_serverInst.startServer("connectionlistenertest.ini", address, threadedPort);
-    List<ConnectionNotification> events = new ArrayList<>();
-    final int handle = m_serverInst.addConnectionListener(events::add, false);
+    m_serverInst.startServer("connectionlistenertest.json", address, 0, threadedPort);
+    List<NetworkTableEvent> events = new ArrayList<>();
+    final int handle =
+        m_serverInst.addConnectionListener(
+            false,
+            e -> {
+              synchronized (events) {
+                events.add(e);
+              }
+            });
 
     // trigger a connect event
-    m_clientInst.startClient(address, threadedPort);
+    m_clientInst.startClient4("client");
+    m_clientInst.setServer(address, threadedPort);
     threadedPort++;
 
-    // wait for client to report it's started, then wait another 0.1 sec
+    // wait for client to report it's connected, then wait another 0.1 sec
     try {
-      while ((m_clientInst.getNetworkMode() & NetworkTableInstance.kNetModeStarting) != 0) {
+      int count = 0;
+      while (!m_clientInst.isConnected()) {
         Thread.sleep(100);
+        count++;
+        if (count > 30) {
+          throw new InterruptedException();
+        }
       }
       Thread.sleep(100);
     } catch (InterruptedException ex) {
       fail("interrupted while waiting for client to start");
     }
-    assertTrue(m_serverInst.waitForConnectionListenerQueue(1.0));
+    try {
+      assertFalse(WPIUtilJNI.waitForObjectTimeout(handle, 1.0));
+    } catch (InterruptedException ex) {
+      fail("interrupted while waiting for queue");
+    }
+
+    // wait for thread
+    m_serverInst.waitForListenerQueue(1.0);
 
     // get the event
-    assertEquals(1, events.size());
-    assertEquals(handle, events.get(0).listener);
-    assertTrue(events.get(0).connected);
-    events.clear();
+    synchronized (events) {
+      assertEquals(1, events.size());
+      assertEquals(handle, events.get(0).listener);
+      assertNotNull(events.get(0).connInfo);
+      assertTrue(events.get(0).is(NetworkTableEvent.Kind.kConnected));
+      events.clear();
+    }
 
     // trigger a disconnect event
     m_clientInst.stopClient();
@@ -145,10 +169,20 @@
       fail("interrupted while waiting for client to stop");
     }
 
+    // wait for thread
+    m_serverInst.waitForListenerQueue(1.0);
+
     // get the event
-    assertTrue(m_serverInst.waitForConnectionListenerQueue(1.0));
-    assertEquals(1, events.size());
-    assertEquals(handle, events.get(0).listener);
-    assertFalse(events.get(0).connected);
+    try {
+      assertFalse(WPIUtilJNI.waitForObjectTimeout(handle, 1.0));
+    } catch (InterruptedException ex) {
+      fail("interrupted while waiting for queue");
+    }
+    synchronized (events) {
+      assertEquals(1, events.size());
+      assertEquals(handle, events.get(0).listener);
+      assertNotNull(events.get(0).connInfo);
+      assertTrue(events.get(0).is(NetworkTableEvent.Kind.kDisconnected));
+    }
   }
 }
diff --git a/third_party/allwpilib/ntcore/src/test/java/edu/wpi/first/networktables/EntryListenerTest.java b/third_party/allwpilib/ntcore/src/test/java/edu/wpi/first/networktables/EntryListenerTest.java
deleted file mode 100644
index 7b31c26..0000000
--- a/third_party/allwpilib/ntcore/src/test/java/edu/wpi/first/networktables/EntryListenerTest.java
+++ /dev/null
@@ -1,83 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.networktables;
-
-import static org.junit.jupiter.api.Assertions.assertAll;
-import static org.junit.jupiter.api.Assertions.assertEquals;
-import static org.junit.jupiter.api.Assertions.assertTrue;
-import static org.junit.jupiter.api.Assertions.fail;
-
-import java.util.ArrayList;
-import java.util.List;
-import org.junit.jupiter.api.AfterEach;
-import org.junit.jupiter.api.BeforeEach;
-import org.junit.jupiter.api.Test;
-
-class EntryListenerTest {
-  private NetworkTableInstance m_serverInst;
-  private NetworkTableInstance m_clientInst;
-
-  @BeforeEach
-  void setUp() {
-    m_serverInst = NetworkTableInstance.create();
-    m_serverInst.setNetworkIdentity("server");
-
-    m_clientInst = NetworkTableInstance.create();
-    m_clientInst.setNetworkIdentity("client");
-  }
-
-  @AfterEach
-  void tearDown() {
-    m_clientInst.close();
-    m_serverInst.close();
-  }
-
-  private void connect() {
-    m_serverInst.startServer("connectionlistenertest.ini", "127.0.0.1", 10010);
-    m_clientInst.startClient("127.0.0.1", 10010);
-
-    // Use connection listener to ensure we've connected
-    int poller = NetworkTablesJNI.createConnectionListenerPoller(m_clientInst.getHandle());
-    NetworkTablesJNI.addPolledConnectionListener(poller, false);
-    try {
-      if (NetworkTablesJNI.pollConnectionListenerTimeout(m_clientInst, poller, 1.0).length == 0) {
-        fail("client didn't connect to server");
-      }
-    } catch (InterruptedException ex) {
-      Thread.currentThread().interrupt();
-      fail("interrupted while waiting for server connection");
-    }
-  }
-
-  /** Test prefix with a new remote. */
-  @Test
-  void testPrefixNewRemote() {
-    connect();
-    List<EntryNotification> events = new ArrayList<>();
-    final int handle = m_serverInst.addEntryListener("/foo", events::add, EntryListenerFlags.kNew);
-
-    // Trigger an event
-    m_clientInst.getEntry("/foo/bar").setDouble(1.0);
-    m_clientInst.getEntry("/baz").setDouble(1.0);
-    m_clientInst.flush();
-    try {
-      Thread.sleep(100);
-    } catch (InterruptedException ex) {
-      fail("interrupted while waiting for entries to update");
-    }
-
-    assertTrue(m_serverInst.waitForEntryListenerQueue(1.0));
-
-    // Check the event
-    assertAll(
-        "Event",
-        () -> assertEquals(1, events.size()),
-        () -> assertEquals(handle, events.get(0).listener),
-        () -> assertEquals(m_serverInst.getEntry("/foo/bar"), events.get(0).getEntry()),
-        () -> assertEquals("/foo/bar", events.get(0).name),
-        () -> assertEquals(NetworkTableValue.makeDouble(1.0), events.get(0).value),
-        () -> assertEquals(EntryListenerFlags.kNew, events.get(0).flags));
-  }
-}
diff --git a/third_party/allwpilib/ntcore/src/test/java/edu/wpi/first/networktables/LoggerTest.java b/third_party/allwpilib/ntcore/src/test/java/edu/wpi/first/networktables/LoggerTest.java
index 1dc26ab..c562291 100644
--- a/third_party/allwpilib/ntcore/src/test/java/edu/wpi/first/networktables/LoggerTest.java
+++ b/third_party/allwpilib/ntcore/src/test/java/edu/wpi/first/networktables/LoggerTest.java
@@ -28,15 +28,21 @@
 
   @Test
   void addMessageTest() {
-    List<LogMessage> msgs = new ArrayList<>();
-    m_clientInst.addLogger(msgs::add, LogMessage.kInfo, 100);
+    List<NetworkTableEvent> msgs = new ArrayList<>();
+    m_clientInst.addLogger(LogMessage.kInfo, 100, msgs::add);
 
-    m_clientInst.startClient("127.0.0.1", 10000);
+    m_clientInst.startClient4("client");
+    m_clientInst.setServer("127.0.0.1", 10000);
 
     // wait for client to report it's started, then wait another 0.1 sec
     try {
-      while ((m_clientInst.getNetworkMode() & NetworkTableInstance.kNetModeStarting) != 0) {
+      int count = 0;
+      while (!m_clientInst.getNetworkMode().contains(NetworkTableInstance.NetworkMode.kClient4)) {
         Thread.sleep(100);
+        count++;
+        if (count > 30) {
+          throw new InterruptedException();
+        }
       }
       Thread.sleep(100);
     } catch (InterruptedException ex) {
diff --git a/third_party/allwpilib/ntcore/src/test/java/edu/wpi/first/networktables/TableListenerTest.java b/third_party/allwpilib/ntcore/src/test/java/edu/wpi/first/networktables/TableListenerTest.java
new file mode 100644
index 0000000..d59e174
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/test/java/edu/wpi/first/networktables/TableListenerTest.java
@@ -0,0 +1,65 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.networktables;
+
+import static org.junit.jupiter.api.Assertions.assertEquals;
+import static org.junit.jupiter.api.Assertions.assertTrue;
+
+import java.util.EnumSet;
+import java.util.concurrent.atomic.AtomicInteger;
+import org.junit.jupiter.api.AfterEach;
+import org.junit.jupiter.api.BeforeEach;
+import org.junit.jupiter.api.Test;
+
+class TableListenerTest {
+  private NetworkTableInstance m_inst;
+
+  @BeforeEach
+  void setUp() {
+    m_inst = NetworkTableInstance.create();
+  }
+
+  @AfterEach
+  void tearDown() {
+    m_inst.close();
+  }
+
+  private void publishTopics() {
+    m_inst.getDoubleTopic("/foo/foovalue").publish();
+    m_inst.getDoubleTopic("/foo/bar/barvalue").publish();
+    m_inst.getDoubleTopic("/baz/bazvalue").publish();
+  }
+
+  @Test
+  void testAddListener() {
+    NetworkTable table = m_inst.getTable("/foo");
+    AtomicInteger count = new AtomicInteger();
+    table.addListener(
+        EnumSet.of(NetworkTableEvent.Kind.kTopic),
+        (atable, key, event) -> {
+          count.incrementAndGet();
+          assertEquals(atable, table);
+          assertEquals(key, "foovalue");
+        });
+    publishTopics();
+    assertTrue(m_inst.waitForListenerQueue(1.0));
+    assertEquals(count.get(), 1);
+  }
+
+  @Test
+  void testAddSubTableListener() {
+    NetworkTable table = m_inst.getTable("/foo");
+    AtomicInteger count = new AtomicInteger();
+    table.addSubTableListener(
+        (atable, key, event) -> {
+          count.incrementAndGet();
+          assertEquals(atable, table);
+          assertEquals(key, "bar");
+        });
+    publishTopics();
+    assertTrue(m_inst.waitForListenerQueue(1.0));
+    assertEquals(count.get(), 1);
+  }
+}
diff --git a/third_party/allwpilib/ntcore/src/test/java/edu/wpi/first/networktables/TimeSyncTest.java b/third_party/allwpilib/ntcore/src/test/java/edu/wpi/first/networktables/TimeSyncTest.java
new file mode 100644
index 0000000..c539d20
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/test/java/edu/wpi/first/networktables/TimeSyncTest.java
@@ -0,0 +1,83 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.networktables;
+
+import static org.junit.jupiter.api.Assertions.assertEquals;
+import static org.junit.jupiter.api.Assertions.assertFalse;
+import static org.junit.jupiter.api.Assertions.assertNotNull;
+import static org.junit.jupiter.api.Assertions.assertTrue;
+
+import org.junit.jupiter.api.AfterEach;
+import org.junit.jupiter.api.BeforeEach;
+import org.junit.jupiter.api.Test;
+
+class TimeSyncTest {
+  private NetworkTableInstance m_inst;
+
+  @BeforeEach
+  void setUp() {
+    m_inst = NetworkTableInstance.create();
+  }
+
+  @AfterEach
+  void tearDown() {
+    m_inst.close();
+  }
+
+  @Test
+  void testLocal() {
+    var offset = m_inst.getServerTimeOffset();
+    assertFalse(offset.isPresent());
+  }
+
+  @Test
+  void testServer() {
+    var poller = new NetworkTableListenerPoller(m_inst);
+    poller.addTimeSyncListener(false);
+
+    m_inst.startServer("timesynctest.json", "127.0.0.1", 0, 10030);
+    var offset = m_inst.getServerTimeOffset();
+    assertTrue(offset.isPresent());
+    assertEquals(0L, offset.getAsLong());
+
+    NetworkTableEvent[] events = poller.readQueue();
+    assertEquals(1, events.length);
+    assertNotNull(events[0].timeSyncData);
+    assertTrue(events[0].timeSyncData.valid);
+    assertEquals(0L, events[0].timeSyncData.serverTimeOffset);
+    assertEquals(0L, events[0].timeSyncData.rtt2);
+
+    m_inst.stopServer();
+    offset = m_inst.getServerTimeOffset();
+    assertFalse(offset.isPresent());
+
+    events = poller.readQueue();
+    assertEquals(1, events.length);
+    assertNotNull(events[0].timeSyncData);
+    assertFalse(events[0].timeSyncData.valid);
+  }
+
+  @Test
+  void testClient3() {
+    m_inst.startClient3("client");
+    var offset = m_inst.getServerTimeOffset();
+    assertFalse(offset.isPresent());
+
+    m_inst.stopClient();
+    offset = m_inst.getServerTimeOffset();
+    assertFalse(offset.isPresent());
+  }
+
+  @Test
+  void testClient4() {
+    m_inst.startClient4("client");
+    var offset = m_inst.getServerTimeOffset();
+    assertFalse(offset.isPresent());
+
+    m_inst.stopClient();
+    offset = m_inst.getServerTimeOffset();
+    assertFalse(offset.isPresent());
+  }
+}
diff --git a/third_party/allwpilib/ntcore/src/test/java/edu/wpi/first/networktables/TopicListenerTest.java b/third_party/allwpilib/ntcore/src/test/java/edu/wpi/first/networktables/TopicListenerTest.java
new file mode 100644
index 0000000..9f1d67f
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/test/java/edu/wpi/first/networktables/TopicListenerTest.java
@@ -0,0 +1,92 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.networktables;
+
+import static org.junit.jupiter.api.Assertions.assertEquals;
+import static org.junit.jupiter.api.Assertions.assertNotNull;
+import static org.junit.jupiter.api.Assertions.assertTrue;
+import static org.junit.jupiter.api.Assertions.fail;
+
+import edu.wpi.first.util.WPIUtilJNI;
+import java.util.EnumSet;
+import org.junit.jupiter.api.AfterEach;
+import org.junit.jupiter.api.BeforeEach;
+import org.junit.jupiter.api.Disabled;
+import org.junit.jupiter.api.Test;
+
+class TopicListenerTest {
+  private NetworkTableInstance m_serverInst;
+  private NetworkTableInstance m_clientInst;
+
+  @BeforeEach
+  void setUp() {
+    m_serverInst = NetworkTableInstance.create();
+    m_clientInst = NetworkTableInstance.create();
+  }
+
+  @AfterEach
+  void tearDown() {
+    m_clientInst.close();
+    m_serverInst.close();
+  }
+
+  private void connect() {
+    m_serverInst.startServer("topiclistenertest.json", "127.0.0.1", 0, 10010);
+    m_clientInst.startClient4("client");
+    m_clientInst.setServer("127.0.0.1", 10010);
+
+    // Use connection listener to ensure we've connected
+    int poller = NetworkTablesJNI.createListenerPoller(m_clientInst.getHandle());
+    NetworkTablesJNI.addListener(
+        poller, m_clientInst.getHandle(), EnumSet.of(NetworkTableEvent.Kind.kConnected));
+    try {
+      if (WPIUtilJNI.waitForObjectTimeout(poller, 1.0)) {
+        fail("client didn't connect to server");
+      }
+    } catch (InterruptedException ex) {
+      Thread.currentThread().interrupt();
+      fail("interrupted while waiting for server connection");
+    }
+  }
+
+  /** Test prefix with a new remote. */
+  @Disabled("unreliable in CI")
+  @Test
+  void testPrefixNewRemote() {
+    connect();
+    final int poller = NetworkTablesJNI.createListenerPoller(m_serverInst.getHandle());
+    final int handle =
+        NetworkTablesJNI.addListener(
+            poller, new String[] {"/foo"}, EnumSet.of(NetworkTableEvent.Kind.kPublish));
+
+    // Trigger an event
+    m_clientInst.getEntry("/foo/bar").setDouble(1.0);
+    m_clientInst.getEntry("/baz").setDouble(1.0);
+    m_clientInst.flush();
+    try {
+      Thread.sleep(100);
+    } catch (InterruptedException ex) {
+      fail("interrupted while waiting for entries to update");
+    }
+
+    try {
+      if (WPIUtilJNI.waitForObjectTimeout(poller, 1.0)) {
+        fail("never got signaled");
+      }
+    } catch (InterruptedException ex) {
+      Thread.currentThread().interrupt();
+      fail("interrupted while waiting for signal");
+    }
+    NetworkTableEvent[] events = NetworkTablesJNI.readListenerQueue(m_serverInst, poller);
+
+    // Check the event
+    assertEquals(1, events.length);
+    assertEquals(handle, events[0].listener);
+    assertNotNull(events[0].topicInfo);
+    assertEquals(m_serverInst.getTopic("/foo/bar"), events[0].topicInfo.getTopic());
+    assertEquals("/foo/bar", events[0].topicInfo.name);
+    assertTrue(events[0].is(NetworkTableEvent.Kind.kPublish));
+  }
+}
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/ConnectionListenerTest.cpp b/third_party/allwpilib/ntcore/src/test/native/cpp/ConnectionListenerTest.cpp
index 14c327c..1561277 100644
--- a/third_party/allwpilib/ntcore/src/test/native/cpp/ConnectionListenerTest.cpp
+++ b/third_party/allwpilib/ntcore/src/test/native/cpp/ConnectionListenerTest.cpp
@@ -5,6 +5,9 @@
 #include <chrono>
 #include <thread>
 
+#include <wpi/Synchronization.h>
+#include <wpi/mutex.h>
+
 #include "TestPrinters.h"
 #include "gtest/gtest.h"
 #include "ntcore_cpp.h"
@@ -12,94 +15,123 @@
 class ConnectionListenerTest : public ::testing::Test {
  public:
   ConnectionListenerTest()
-      : server_inst(nt::CreateInstance()), client_inst(nt::CreateInstance()) {
-    nt::SetNetworkIdentity(server_inst, "server");
-    nt::SetNetworkIdentity(client_inst, "client");
-  }
+      : server_inst(nt::CreateInstance()), client_inst(nt::CreateInstance()) {}
 
   ~ConnectionListenerTest() override {
     nt::DestroyInstance(server_inst);
     nt::DestroyInstance(client_inst);
   }
 
-  void Connect(unsigned int port);
+  void Connect(const char* address, unsigned int port3, unsigned int port4);
 
  protected:
   NT_Inst server_inst;
   NT_Inst client_inst;
 };
 
-void ConnectionListenerTest::Connect(unsigned int port) {
-  nt::StartServer(server_inst, "connectionlistenertest.ini", "127.0.0.1", port);
-  nt::StartClient(client_inst, "127.0.0.1", port);
+void ConnectionListenerTest::Connect(const char* address, unsigned int port3,
+                                     unsigned int port4) {
+  nt::StartServer(server_inst, "connectionlistenertest.ini", address, port3,
+                  port4);
+  nt::StartClient4(client_inst, "client");
+  nt::SetServer(client_inst, address, port4);
 
-  // wait for client to report it's started, then wait another 0.1 sec
-  while ((nt::GetNetworkMode(client_inst) & NT_NET_MODE_STARTING) != 0) {
+  // wait for client to report it's connected, then wait another 0.1 sec
+  int count = 0;
+  while (!nt::IsConnected(client_inst)) {
     std::this_thread::sleep_for(std::chrono::milliseconds(100));
+    if (++count > 30) {
+      FAIL() << "timed out waiting for client to start";
+    }
   }
   std::this_thread::sleep_for(std::chrono::milliseconds(100));
 }
 
 TEST_F(ConnectionListenerTest, Polled) {
   // set up the poller
-  NT_ConnectionListenerPoller poller =
-      nt::CreateConnectionListenerPoller(server_inst);
+  NT_ListenerPoller poller = nt::CreateListenerPoller(server_inst);
   ASSERT_NE(poller, 0u);
-  NT_ConnectionListener handle = nt::AddPolledConnectionListener(poller, false);
+  NT_Listener handle =
+      nt::AddPolledListener(poller, server_inst, nt::EventFlags::kConnection);
   ASSERT_NE(handle, 0u);
 
   // trigger a connect event
-  Connect(10000);
+  Connect("127.0.0.1", 0, 10020);
 
   // get the event
-  ASSERT_TRUE(nt::WaitForConnectionListenerQueue(server_inst, 1.0));
   bool timed_out = false;
-  auto result = nt::PollConnectionListener(poller, 0.1, &timed_out);
-  EXPECT_FALSE(timed_out);
+  ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timed_out));
+  ASSERT_FALSE(timed_out);
+  auto result = nt::ReadListenerQueue(poller);
   ASSERT_EQ(result.size(), 1u);
   EXPECT_EQ(handle, result[0].listener);
-  EXPECT_TRUE(result[0].connected);
+  EXPECT_TRUE(result[0].GetConnectionInfo());
+  EXPECT_EQ(result[0].flags, nt::EventFlags::kConnected);
 
   // trigger a disconnect event
   nt::StopClient(client_inst);
   std::this_thread::sleep_for(std::chrono::milliseconds(100));
 
   // get the event
-  ASSERT_TRUE(nt::WaitForConnectionListenerQueue(server_inst, 1.0));
   timed_out = false;
-  result = nt::PollConnectionListener(poller, 0.1, &timed_out);
-  EXPECT_FALSE(timed_out);
+  ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timed_out));
+  ASSERT_FALSE(timed_out);
+  result = nt::ReadListenerQueue(poller);
   ASSERT_EQ(result.size(), 1u);
   EXPECT_EQ(handle, result[0].listener);
-  EXPECT_FALSE(result[0].connected);
-
-  // trigger a disconnect event
+  EXPECT_TRUE(result[0].GetConnectionInfo());
+  EXPECT_EQ(result[0].flags, nt::EventFlags::kDisconnected);
 }
 
-TEST_F(ConnectionListenerTest, Threaded) {
-  std::vector<nt::ConnectionNotification> result;
-  auto handle = nt::AddConnectionListener(
-      server_inst,
-      [&](const nt::ConnectionNotification& event) { result.push_back(event); },
-      false);
+class ConnectionListenerVariantTest
+    : public ConnectionListenerTest,
+      public ::testing::WithParamInterface<std::pair<const char*, int>> {};
+
+TEST_P(ConnectionListenerVariantTest, Threaded) {
+  wpi::mutex m;
+  std::vector<nt::Event> result;
+  auto handle = nt::AddListener(server_inst, nt::EventFlags::kConnection,
+                                [&](auto& event) {
+                                  std::scoped_lock lock{m};
+                                  result.push_back(event);
+                                });
 
   // trigger a connect event
-  Connect(10001);
+  Connect(GetParam().first, 0, 20001 + GetParam().second);
 
-  ASSERT_TRUE(nt::WaitForConnectionListenerQueue(server_inst, 1.0));
+  bool timed_out = false;
+  ASSERT_TRUE(wpi::WaitForObject(handle, 1.0, &timed_out));
+  ASSERT_FALSE(timed_out);
 
   // get the event
-  ASSERT_EQ(result.size(), 1u);
-  EXPECT_EQ(handle, result[0].listener);
-  EXPECT_TRUE(result[0].connected);
-  result.clear();
+  {
+    std::scoped_lock lock{m};
+    ASSERT_EQ(result.size(), 1u);
+    EXPECT_EQ(handle, result[0].listener);
+    EXPECT_TRUE(result[0].GetConnectionInfo());
+    EXPECT_EQ(result[0].flags, nt::EventFlags::kConnected);
+    result.clear();
+  }
 
   // trigger a disconnect event
   nt::StopClient(client_inst);
   std::this_thread::sleep_for(std::chrono::milliseconds(100));
 
+  // wait for thread
+  nt::WaitForListenerQueue(server_inst, 1.0);
+
   // get the event
-  ASSERT_EQ(result.size(), 1u);
-  EXPECT_EQ(handle, result[0].listener);
-  EXPECT_FALSE(result[0].connected);
+  {
+    std::scoped_lock lock{m};
+    ASSERT_EQ(result.size(), 1u);
+    EXPECT_EQ(handle, result[0].listener);
+    EXPECT_TRUE(result[0].GetConnectionInfo());
+    EXPECT_EQ(result[0].flags, nt::EventFlags::kDisconnected);
+  }
 }
+
+INSTANTIATE_TEST_SUITE_P(ConnectionListenerVariantTests,
+                         ConnectionListenerVariantTest,
+                         testing::Values(std::pair{"127.0.0.1", 0},
+                                         std::pair{"127.0.0.1 ", 1},
+                                         std::pair{" 127.0.0.1 ", 2}));
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/EntryListenerTest.cpp b/third_party/allwpilib/ntcore/src/test/native/cpp/EntryListenerTest.cpp
deleted file mode 100644
index 8349484..0000000
--- a/third_party/allwpilib/ntcore/src/test/native/cpp/EntryListenerTest.cpp
+++ /dev/null
@@ -1,165 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include <chrono>
-#include <thread>
-
-#include "TestPrinters.h"
-#include "ValueMatcher.h"
-#include "gtest/gtest.h"
-#include "ntcore_cpp.h"
-
-class EntryListenerTest : public ::testing::Test {
- public:
-  EntryListenerTest()
-      : server_inst(nt::CreateInstance()), client_inst(nt::CreateInstance()) {
-    nt::SetNetworkIdentity(server_inst, "server");
-    nt::SetNetworkIdentity(client_inst, "client");
-#if 0
-    nt::AddLogger(server_inst,
-                  [](const nt::LogMessage& msg) {
-                    std::fprintf(stderr, "SERVER: %s\n", msg.message.c_str());
-                  },
-                  0, UINT_MAX);
-    nt::AddLogger(client_inst,
-                  [](const nt::LogMessage& msg) {
-                    std::fprintf(stderr, "CLIENT: %s\n", msg.message.c_str());
-                  },
-                  0, UINT_MAX);
-#endif
-  }
-
-  ~EntryListenerTest() override {
-    nt::DestroyInstance(server_inst);
-    nt::DestroyInstance(client_inst);
-  }
-
-  void Connect(unsigned int port);
-
- protected:
-  NT_Inst server_inst;
-  NT_Inst client_inst;
-};
-
-void EntryListenerTest::Connect(unsigned int port) {
-  nt::StartServer(server_inst, "entrylistenertest.ini", "127.0.0.1", port);
-  nt::StartClient(client_inst, "127.0.0.1", port);
-
-  // Use connection listener to ensure we've connected
-  NT_ConnectionListenerPoller poller =
-      nt::CreateConnectionListenerPoller(server_inst);
-  nt::AddPolledConnectionListener(poller, false);
-  bool timed_out = false;
-  if (nt::PollConnectionListener(poller, 1.0, &timed_out).empty()) {
-    FAIL() << "client didn't connect to server";
-  }
-}
-
-TEST_F(EntryListenerTest, EntryNewLocal) {
-  std::vector<nt::EntryNotification> events;
-  auto handle = nt::AddEntryListener(
-      nt::GetEntry(server_inst, "/foo"),
-      [&](const nt::EntryNotification& event) { events.push_back(event); },
-      NT_NOTIFY_NEW | NT_NOTIFY_LOCAL);
-
-  // Trigger an event
-  nt::SetEntryValue(nt::GetEntry(server_inst, "/foo/bar"),
-                    nt::Value::MakeDouble(2.0));
-  nt::SetEntryValue(nt::GetEntry(server_inst, "/foo"),
-                    nt::Value::MakeDouble(1.0));
-
-  ASSERT_TRUE(nt::WaitForEntryListenerQueue(server_inst, 1.0));
-
-  // Check the event
-  ASSERT_EQ(events.size(), 1u);
-  ASSERT_EQ(events[0].listener, handle);
-  ASSERT_EQ(events[0].entry, nt::GetEntry(server_inst, "/foo"));
-  ASSERT_EQ(events[0].name, "/foo");
-  ASSERT_THAT(events[0].value, nt::ValueEq(nt::Value::MakeDouble(1.0)));
-  ASSERT_EQ(events[0].flags, (unsigned int)(NT_NOTIFY_NEW | NT_NOTIFY_LOCAL));
-}
-
-TEST_F(EntryListenerTest, DISABLED_EntryNewRemote) {
-  Connect(10010);
-  if (HasFatalFailure()) {
-    return;
-  }
-  std::vector<nt::EntryNotification> events;
-  auto handle = nt::AddEntryListener(
-      nt::GetEntry(server_inst, "/foo"),
-      [&](const nt::EntryNotification& event) { events.push_back(event); },
-      NT_NOTIFY_NEW);
-
-  // Trigger an event
-  nt::SetEntryValue(nt::GetEntry(client_inst, "/foo/bar"),
-                    nt::Value::MakeDouble(2.0));
-  nt::SetEntryValue(nt::GetEntry(client_inst, "/foo"),
-                    nt::Value::MakeDouble(1.0));
-  nt::Flush(client_inst);
-  std::this_thread::sleep_for(std::chrono::milliseconds(100));
-
-  ASSERT_TRUE(nt::WaitForEntryListenerQueue(server_inst, 1.0));
-
-  // Check the event
-  ASSERT_EQ(events.size(), 1u);
-  ASSERT_EQ(events[0].listener, handle);
-  ASSERT_EQ(events[0].entry, nt::GetEntry(server_inst, "/foo"));
-  ASSERT_EQ(events[0].name, "/foo");
-  ASSERT_THAT(events[0].value, nt::ValueEq(nt::Value::MakeDouble(1.0)));
-  ASSERT_EQ(events[0].flags, NT_NOTIFY_NEW);
-}
-
-TEST_F(EntryListenerTest, PrefixNewLocal) {
-  std::vector<nt::EntryNotification> events;
-  auto handle = nt::AddEntryListener(
-      server_inst, "/foo",
-      [&](const nt::EntryNotification& event) { events.push_back(event); },
-      NT_NOTIFY_NEW | NT_NOTIFY_LOCAL);
-
-  // Trigger an event
-  nt::SetEntryValue(nt::GetEntry(server_inst, "/foo/bar"),
-                    nt::Value::MakeDouble(1.0));
-  nt::SetEntryValue(nt::GetEntry(server_inst, "/baz"),
-                    nt::Value::MakeDouble(1.0));
-
-  ASSERT_TRUE(nt::WaitForEntryListenerQueue(server_inst, 1.0));
-
-  // Check the event
-  ASSERT_EQ(events.size(), 1u);
-  ASSERT_EQ(events[0].listener, handle);
-  ASSERT_EQ(events[0].entry, nt::GetEntry(server_inst, "/foo/bar"));
-  ASSERT_EQ(events[0].name, "/foo/bar");
-  ASSERT_THAT(events[0].value, nt::ValueEq(nt::Value::MakeDouble(1.0)));
-  ASSERT_EQ(events[0].flags, (unsigned int)(NT_NOTIFY_NEW | NT_NOTIFY_LOCAL));
-}
-
-TEST_F(EntryListenerTest, DISABLED_PrefixNewRemote) {
-  Connect(10011);
-  if (HasFatalFailure()) {
-    return;
-  }
-  std::vector<nt::EntryNotification> events;
-  auto handle = nt::AddEntryListener(
-      server_inst, "/foo",
-      [&](const nt::EntryNotification& event) { events.push_back(event); },
-      NT_NOTIFY_NEW);
-
-  // Trigger an event
-  nt::SetEntryValue(nt::GetEntry(client_inst, "/foo/bar"),
-                    nt::Value::MakeDouble(1.0));
-  nt::SetEntryValue(nt::GetEntry(client_inst, "/baz"),
-                    nt::Value::MakeDouble(1.0));
-  nt::Flush(client_inst);
-  std::this_thread::sleep_for(std::chrono::milliseconds(100));
-
-  ASSERT_TRUE(nt::WaitForEntryListenerQueue(server_inst, 1.0));
-
-  // Check the event
-  ASSERT_EQ(events.size(), 1u);
-  ASSERT_EQ(events[0].listener, handle);
-  ASSERT_EQ(events[0].entry, nt::GetEntry(server_inst, "/foo/bar"));
-  ASSERT_EQ(events[0].name, "/foo/bar");
-  ASSERT_THAT(events[0].value, nt::ValueEq(nt::Value::MakeDouble(1.0)));
-  ASSERT_EQ(events[0].flags, NT_NOTIFY_NEW);
-}
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/EntryNotifierTest.cpp b/third_party/allwpilib/ntcore/src/test/native/cpp/EntryNotifierTest.cpp
deleted file mode 100644
index e781b49..0000000
--- a/third_party/allwpilib/ntcore/src/test/native/cpp/EntryNotifierTest.cpp
+++ /dev/null
@@ -1,312 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include <wpi/Logger.h>
-#include <wpi/StringExtras.h>
-
-#include "EntryNotifier.h"
-#include "TestPrinters.h"
-#include "ValueMatcher.h"
-#include "gtest/gtest.h"
-
-using ::testing::_;
-using ::testing::AnyNumber;
-using ::testing::IsNull;
-using ::testing::Return;
-
-namespace nt {
-
-class EntryNotifierTest : public ::testing::Test {
- public:
-  EntryNotifierTest() : notifier(1, logger) { notifier.Start(); }
-
-  void GenerateNotifications();
-
- protected:
-  wpi::Logger logger;
-  EntryNotifier notifier;
-};
-
-void EntryNotifierTest::GenerateNotifications() {
-  // All flags combos that can be generated by Storage
-  static const unsigned int flags[] = {
-      // "normal" notifications
-      NT_NOTIFY_NEW, NT_NOTIFY_DELETE, NT_NOTIFY_UPDATE, NT_NOTIFY_FLAGS,
-      NT_NOTIFY_UPDATE | NT_NOTIFY_FLAGS,
-      // immediate notifications are always "new"
-      NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW,
-      // local notifications can be of any flag combo
-      NT_NOTIFY_LOCAL | NT_NOTIFY_NEW, NT_NOTIFY_LOCAL | NT_NOTIFY_DELETE,
-      NT_NOTIFY_LOCAL | NT_NOTIFY_UPDATE, NT_NOTIFY_LOCAL | NT_NOTIFY_FLAGS,
-      NT_NOTIFY_LOCAL | NT_NOTIFY_UPDATE | NT_NOTIFY_FLAGS};
-  // Generate across keys
-  static const char* keys[] = {"/foo/bar", "/baz", "/boo"};
-
-  auto val = Value::MakeDouble(1);
-
-  // Provide unique key indexes for each key
-  unsigned int keyindex = 5;
-  for (auto key : keys) {
-    for (auto flag : flags) {
-      notifier.NotifyEntry(keyindex, key, val, flag);
-    }
-    ++keyindex;
-  }
-}
-
-TEST_F(EntryNotifierTest, PollEntryMultiple) {
-  auto poller1 = notifier.CreatePoller();
-  auto poller2 = notifier.CreatePoller();
-  auto poller3 = notifier.CreatePoller();
-  auto h1 = notifier.AddPolled(poller1, 6, NT_NOTIFY_NEW);
-  auto h2 = notifier.AddPolled(poller2, 6, NT_NOTIFY_NEW);
-  auto h3 = notifier.AddPolled(poller3, 6, NT_NOTIFY_UPDATE);
-
-  ASSERT_FALSE(notifier.local_notifiers());
-
-  GenerateNotifications();
-
-  ASSERT_TRUE(notifier.WaitForQueue(1.0));
-  bool timed_out = false;
-  auto results1 = notifier.Poll(poller1, 0, &timed_out);
-  ASSERT_FALSE(timed_out);
-  auto results2 = notifier.Poll(poller2, 0, &timed_out);
-  ASSERT_FALSE(timed_out);
-  auto results3 = notifier.Poll(poller3, 0, &timed_out);
-  ASSERT_FALSE(timed_out);
-
-  ASSERT_EQ(results1.size(), 2u);
-  for (const auto& result : results1) {
-    SCOPED_TRACE(::testing::PrintToString(result));
-    EXPECT_EQ(Handle{result.listener}.GetIndex(), (int)h1);
-  }
-
-  ASSERT_EQ(results2.size(), 2u);
-  for (const auto& result : results2) {
-    SCOPED_TRACE(::testing::PrintToString(result));
-    EXPECT_EQ(Handle{result.listener}.GetIndex(), (int)h2);
-  }
-
-  ASSERT_EQ(results3.size(), 2u);
-  for (const auto& result : results3) {
-    SCOPED_TRACE(::testing::PrintToString(result));
-    EXPECT_EQ(Handle{result.listener}.GetIndex(), (int)h3);
-  }
-}
-
-TEST_F(EntryNotifierTest, PollEntryBasic) {
-  auto poller = notifier.CreatePoller();
-  auto g1 = notifier.AddPolled(poller, 6, NT_NOTIFY_NEW);
-  auto g2 = notifier.AddPolled(poller, 6, NT_NOTIFY_DELETE);
-  auto g3 = notifier.AddPolled(poller, 6, NT_NOTIFY_UPDATE);
-  auto g4 = notifier.AddPolled(poller, 6, NT_NOTIFY_FLAGS);
-
-  ASSERT_FALSE(notifier.local_notifiers());
-
-  GenerateNotifications();
-
-  ASSERT_TRUE(notifier.WaitForQueue(1.0));
-  bool timed_out = false;
-  auto results = notifier.Poll(poller, 0, &timed_out);
-  ASSERT_FALSE(timed_out);
-
-  int g1count = 0;
-  int g2count = 0;
-  int g3count = 0;
-  int g4count = 0;
-  for (const auto& result : results) {
-    SCOPED_TRACE(::testing::PrintToString(result));
-    EXPECT_EQ(result.name, "/baz");
-    EXPECT_THAT(result.value, ValueEq(Value::MakeDouble(1)));
-    EXPECT_EQ(Handle{result.entry}.GetType(), Handle::kEntry);
-    EXPECT_EQ(Handle{result.entry}.GetInst(), 1);
-    EXPECT_EQ(Handle{result.entry}.GetIndex(), 6);
-    EXPECT_EQ(Handle{result.listener}.GetType(), Handle::kEntryListener);
-    EXPECT_EQ(Handle{result.listener}.GetInst(), 1);
-    if (Handle{result.listener}.GetIndex() == static_cast<int>(g1)) {
-      ++g1count;
-      EXPECT_TRUE((result.flags & NT_NOTIFY_NEW) != 0);
-    } else if (Handle{result.listener}.GetIndex() == static_cast<int>(g2)) {
-      ++g2count;
-      EXPECT_TRUE((result.flags & NT_NOTIFY_DELETE) != 0);
-    } else if (Handle{result.listener}.GetIndex() == static_cast<int>(g3)) {
-      ++g3count;
-      EXPECT_TRUE((result.flags & NT_NOTIFY_UPDATE) != 0);
-    } else if (Handle{result.listener}.GetIndex() == static_cast<int>(g4)) {
-      ++g4count;
-      EXPECT_TRUE((result.flags & NT_NOTIFY_FLAGS) != 0);
-    } else {
-      ADD_FAILURE() << "unknown listener index";
-    }
-  }
-  EXPECT_EQ(g1count, 2);
-  EXPECT_EQ(g2count, 1);  // NT_NOTIFY_DELETE
-  EXPECT_EQ(g3count, 2);
-  EXPECT_EQ(g4count, 2);
-}
-
-TEST_F(EntryNotifierTest, PollEntryImmediate) {
-  auto poller = notifier.CreatePoller();
-  notifier.AddPolled(poller, 6, NT_NOTIFY_NEW | NT_NOTIFY_IMMEDIATE);
-  notifier.AddPolled(poller, 6, NT_NOTIFY_NEW);
-
-  ASSERT_FALSE(notifier.local_notifiers());
-
-  GenerateNotifications();
-
-  ASSERT_TRUE(notifier.WaitForQueue(1.0));
-  bool timed_out = false;
-  auto results = notifier.Poll(poller, 0, &timed_out);
-  ASSERT_FALSE(timed_out);
-  SCOPED_TRACE(::testing::PrintToString(results));
-  ASSERT_EQ(results.size(), 4u);
-}
-
-TEST_F(EntryNotifierTest, PollEntryLocal) {
-  auto poller = notifier.CreatePoller();
-  notifier.AddPolled(poller, 6, NT_NOTIFY_NEW | NT_NOTIFY_LOCAL);
-  notifier.AddPolled(poller, 6, NT_NOTIFY_NEW);
-
-  ASSERT_TRUE(notifier.local_notifiers());
-
-  GenerateNotifications();
-
-  ASSERT_TRUE(notifier.WaitForQueue(1.0));
-  bool timed_out = false;
-  auto results = notifier.Poll(poller, 0, &timed_out);
-  ASSERT_FALSE(timed_out);
-  SCOPED_TRACE(::testing::PrintToString(results));
-  ASSERT_EQ(results.size(), 6u);
-}
-
-TEST_F(EntryNotifierTest, PollPrefixMultiple) {
-  auto poller1 = notifier.CreatePoller();
-  auto poller2 = notifier.CreatePoller();
-  auto poller3 = notifier.CreatePoller();
-  auto h1 = notifier.AddPolled(poller1, "/foo", NT_NOTIFY_NEW);
-  auto h2 = notifier.AddPolled(poller2, "/foo", NT_NOTIFY_NEW);
-  auto h3 = notifier.AddPolled(poller3, "/foo", NT_NOTIFY_UPDATE);
-
-  ASSERT_FALSE(notifier.local_notifiers());
-
-  GenerateNotifications();
-
-  ASSERT_TRUE(notifier.WaitForQueue(1.0));
-  bool timed_out = false;
-  auto results1 = notifier.Poll(poller1, 0, &timed_out);
-  ASSERT_FALSE(timed_out);
-  auto results2 = notifier.Poll(poller2, 0, &timed_out);
-  ASSERT_FALSE(timed_out);
-  auto results3 = notifier.Poll(poller3, 0, &timed_out);
-  ASSERT_FALSE(timed_out);
-
-  ASSERT_EQ(results1.size(), 2u);
-  for (const auto& result : results1) {
-    SCOPED_TRACE(::testing::PrintToString(result));
-    EXPECT_EQ(Handle{result.listener}.GetIndex(), (int)h1);
-  }
-
-  ASSERT_EQ(results2.size(), 2u);
-  for (const auto& result : results2) {
-    SCOPED_TRACE(::testing::PrintToString(result));
-    EXPECT_EQ(Handle{result.listener}.GetIndex(), (int)h2);
-  }
-
-  ASSERT_EQ(results3.size(), 2u);
-  for (const auto& result : results3) {
-    SCOPED_TRACE(::testing::PrintToString(result));
-    EXPECT_EQ(Handle{result.listener}.GetIndex(), (int)h3);
-  }
-}
-
-TEST_F(EntryNotifierTest, PollPrefixBasic) {
-  auto poller = notifier.CreatePoller();
-  auto g1 = notifier.AddPolled(poller, "/foo", NT_NOTIFY_NEW);
-  auto g2 = notifier.AddPolled(poller, "/foo", NT_NOTIFY_DELETE);
-  auto g3 = notifier.AddPolled(poller, "/foo", NT_NOTIFY_UPDATE);
-  auto g4 = notifier.AddPolled(poller, "/foo", NT_NOTIFY_FLAGS);
-  notifier.AddPolled(poller, "/bar", NT_NOTIFY_NEW);
-  notifier.AddPolled(poller, "/bar", NT_NOTIFY_DELETE);
-  notifier.AddPolled(poller, "/bar", NT_NOTIFY_UPDATE);
-  notifier.AddPolled(poller, "/bar", NT_NOTIFY_FLAGS);
-
-  ASSERT_FALSE(notifier.local_notifiers());
-
-  GenerateNotifications();
-
-  ASSERT_TRUE(notifier.WaitForQueue(1.0));
-  bool timed_out = false;
-  auto results = notifier.Poll(poller, 0, &timed_out);
-  ASSERT_FALSE(timed_out);
-
-  int g1count = 0;
-  int g2count = 0;
-  int g3count = 0;
-  int g4count = 0;
-  for (const auto& result : results) {
-    SCOPED_TRACE(::testing::PrintToString(result));
-    EXPECT_TRUE(wpi::starts_with(result.name, "/foo"));
-    EXPECT_THAT(result.value, ValueEq(Value::MakeDouble(1)));
-    EXPECT_EQ(Handle{result.entry}.GetType(), Handle::kEntry);
-    EXPECT_EQ(Handle{result.entry}.GetInst(), 1);
-    EXPECT_EQ(Handle{result.entry}.GetIndex(), 5);
-    EXPECT_EQ(Handle{result.listener}.GetType(), Handle::kEntryListener);
-    EXPECT_EQ(Handle{result.listener}.GetInst(), 1);
-    if (Handle{result.listener}.GetIndex() == static_cast<int>(g1)) {
-      ++g1count;
-      EXPECT_TRUE((result.flags & NT_NOTIFY_NEW) != 0);
-    } else if (Handle{result.listener}.GetIndex() == static_cast<int>(g2)) {
-      ++g2count;
-      EXPECT_TRUE((result.flags & NT_NOTIFY_DELETE) != 0);
-    } else if (Handle{result.listener}.GetIndex() == static_cast<int>(g3)) {
-      ++g3count;
-      EXPECT_TRUE((result.flags & NT_NOTIFY_UPDATE) != 0);
-    } else if (Handle{result.listener}.GetIndex() == static_cast<int>(g4)) {
-      ++g4count;
-      EXPECT_TRUE((result.flags & NT_NOTIFY_FLAGS) != 0);
-    } else {
-      ADD_FAILURE() << "unknown listener index";
-    }
-  }
-  EXPECT_EQ(g1count, 2);
-  EXPECT_EQ(g2count, 1);  // NT_NOTIFY_DELETE
-  EXPECT_EQ(g3count, 2);
-  EXPECT_EQ(g4count, 2);
-}
-
-TEST_F(EntryNotifierTest, PollPrefixImmediate) {
-  auto poller = notifier.CreatePoller();
-  notifier.AddPolled(poller, "/foo", NT_NOTIFY_NEW | NT_NOTIFY_IMMEDIATE);
-  notifier.AddPolled(poller, "/foo", NT_NOTIFY_NEW);
-
-  ASSERT_FALSE(notifier.local_notifiers());
-
-  GenerateNotifications();
-
-  ASSERT_TRUE(notifier.WaitForQueue(1.0));
-  bool timed_out = false;
-  auto results = notifier.Poll(poller, 0, &timed_out);
-  ASSERT_FALSE(timed_out);
-  SCOPED_TRACE(::testing::PrintToString(results));
-  ASSERT_EQ(results.size(), 4u);
-}
-
-TEST_F(EntryNotifierTest, PollPrefixLocal) {
-  auto poller = notifier.CreatePoller();
-  notifier.AddPolled(poller, "/foo", NT_NOTIFY_NEW | NT_NOTIFY_LOCAL);
-  notifier.AddPolled(poller, "/foo", NT_NOTIFY_NEW);
-
-  ASSERT_TRUE(notifier.local_notifiers());
-
-  GenerateNotifications();
-
-  ASSERT_TRUE(notifier.WaitForQueue(1.0));
-  bool timed_out = false;
-  auto results = notifier.Poll(poller, 0, &timed_out);
-  ASSERT_FALSE(timed_out);
-  SCOPED_TRACE(::testing::PrintToString(results));
-  ASSERT_EQ(results.size(), 6u);
-}
-
-}  // namespace nt
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/LocalStorageTest.cpp b/third_party/allwpilib/ntcore/src/test/native/cpp/LocalStorageTest.cpp
new file mode 100644
index 0000000..5734284
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/test/native/cpp/LocalStorageTest.cpp
@@ -0,0 +1,919 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "LocalStorage.h"
+#include "MockListenerStorage.h"
+#include "MockLogger.h"
+#include "PubSubOptionsMatcher.h"
+#include "SpanMatcher.h"
+#include "TestPrinters.h"
+#include "ValueMatcher.h"
+#include "gmock/gmock.h"
+#include "gtest/gtest.h"
+#include "net/MockNetworkInterface.h"
+#include "ntcore_c.h"
+#include "ntcore_cpp.h"
+
+using ::testing::_;
+using ::testing::AllOf;
+using ::testing::ElementsAre;
+using ::testing::Field;
+using ::testing::IsEmpty;
+using ::testing::Property;
+using ::testing::Return;
+
+namespace nt {
+
+::testing::Matcher<const PubSubOptionsImpl&> IsPubSubOptions(
+    const PubSubOptionsImpl& good) {
+  return AllOf(
+      Field("periodic", &PubSubOptionsImpl::periodicMs, good.periodicMs),
+      Field("pollStorage", &PubSubOptionsImpl::pollStorage, good.pollStorage),
+      Field("sendAll", &PubSubOptionsImpl::sendAll, good.sendAll),
+      Field("keepDuplicates", &PubSubOptionsImpl::keepDuplicates,
+            good.keepDuplicates));
+}
+
+::testing::Matcher<const PubSubOptionsImpl&> IsDefaultPubSubOptions() {
+  static constexpr PubSubOptionsImpl kDefaultPubSubOptionsImpl;
+  return IsPubSubOptions(kDefaultPubSubOptionsImpl);
+}
+
+class LocalStorageTest : public ::testing::Test {
+ public:
+  LocalStorageTest() { storage.StartNetwork(&network); }
+
+  ::testing::StrictMock<net::MockNetworkInterface> network;
+  wpi::MockLogger logger;
+  MockListenerStorage listenerStorage;
+  LocalStorage storage{0, listenerStorage, logger};
+  NT_Topic fooTopic{storage.GetTopic("foo")};
+  NT_Topic barTopic{storage.GetTopic("bar")};
+  NT_Topic bazTopic{storage.GetTopic("baz")};
+};
+
+TEST_F(LocalStorageTest, GetTopicsUnpublished) {
+  EXPECT_TRUE(storage.GetTopics("", 0).empty());
+  EXPECT_TRUE(storage.GetTopics("", {}).empty());
+  EXPECT_TRUE(storage.GetTopicInfo("", 0).empty());
+  EXPECT_TRUE(storage.GetTopicInfo("", {}).empty());
+}
+
+TEST_F(LocalStorageTest, GetTopic2) {
+  auto foo2 = storage.GetTopic("foo");
+  EXPECT_EQ(fooTopic, foo2);
+  EXPECT_NE(fooTopic, barTopic);
+}
+
+TEST_F(LocalStorageTest, GetTopicEmptyName) {
+  EXPECT_EQ(storage.GetTopic(""), 0u);
+}
+
+TEST_F(LocalStorageTest, GetEntryEmptyName) {
+  EXPECT_EQ(storage.GetEntry(""), 0u);
+}
+
+TEST_F(LocalStorageTest, GetEntryCached) {
+  EXPECT_CALL(network, Subscribe(_, wpi::SpanEq({std::string{"tocache"}}),
+                                 IsDefaultPubSubOptions()));
+
+  auto entry1 = storage.GetEntry("tocache");
+  EXPECT_EQ(entry1, storage.GetEntry("tocache"));
+}
+
+TEST_F(LocalStorageTest, GetTopicName) {
+  EXPECT_EQ(storage.GetTopicName(fooTopic), "foo");
+  EXPECT_EQ(storage.GetTopicName(barTopic), "bar");
+}
+
+TEST_F(LocalStorageTest, GetTopicInfoUnpublished) {
+  auto info = storage.GetTopicInfo(fooTopic);
+  EXPECT_EQ(info.topic, fooTopic);
+  EXPECT_EQ(info.name, "foo");
+  EXPECT_EQ(info.type, NT_UNASSIGNED);
+  EXPECT_TRUE(info.type_str.empty());
+  EXPECT_EQ(info.properties, "{}");
+
+  EXPECT_EQ(storage.GetTopicType(fooTopic), NT_UNASSIGNED);
+  EXPECT_TRUE(storage.GetTopicTypeString(fooTopic).empty());
+  EXPECT_FALSE(storage.GetTopicExists(fooTopic));
+}
+
+TEST_F(LocalStorageTest, PublishNewNoProps) {
+  EXPECT_CALL(network, Publish(_, fooTopic, std::string_view{"foo"},
+                               std::string_view{"boolean"}, wpi::json::object(),
+                               IsDefaultPubSubOptions()));
+  storage.Publish(fooTopic, NT_BOOLEAN, "boolean", wpi::json::object(), {});
+
+  auto info = storage.GetTopicInfo(fooTopic);
+  EXPECT_EQ(info.properties, "{}");
+}
+
+TEST_F(LocalStorageTest, PublishNewNoPropsNull) {
+  EXPECT_CALL(network, Publish(_, fooTopic, std::string_view{"foo"},
+                               std::string_view{"boolean"}, wpi::json::object(),
+                               IsDefaultPubSubOptions()));
+  storage.Publish(fooTopic, NT_BOOLEAN, "boolean", {}, {});
+
+  auto info = storage.GetTopicInfo(fooTopic);
+  EXPECT_EQ(info.properties, "{}");
+}
+
+TEST_F(LocalStorageTest, PublishNew) {
+  wpi::json properties = {{"persistent", true}};
+  EXPECT_CALL(network, Publish(_, fooTopic, std::string_view{"foo"},
+                               std::string_view{"boolean"}, properties,
+                               IsDefaultPubSubOptions()));
+  storage.Publish(fooTopic, NT_BOOLEAN, "boolean", {{"persistent", true}}, {});
+
+  auto info = storage.GetTopicInfo(fooTopic);
+  EXPECT_EQ(info.topic, fooTopic);
+  EXPECT_EQ(info.name, "foo");
+  EXPECT_EQ(info.type, NT_BOOLEAN);
+  EXPECT_EQ(info.type_str, "boolean");
+  EXPECT_EQ(info.properties, "{\"persistent\":true}");
+
+  EXPECT_EQ(storage.GetTopicType(fooTopic), NT_BOOLEAN);
+  EXPECT_EQ(storage.GetTopicTypeString(fooTopic), "boolean");
+  EXPECT_TRUE(storage.GetTopicExists(fooTopic));
+}
+
+TEST_F(LocalStorageTest, SubscribeNoTypeLocalPubPost) {
+  EXPECT_CALL(network, Subscribe(_, wpi::SpanEq({std::string{"foo"}}),
+                                 IsDefaultPubSubOptions()));
+  auto sub = storage.Subscribe(fooTopic, NT_UNASSIGNED, "", {});
+
+  EXPECT_CALL(network, Publish(_, fooTopic, std::string_view{"foo"},
+                               std::string_view{"boolean"}, wpi::json::object(),
+                               IsDefaultPubSubOptions()));
+  auto pub = storage.Publish(fooTopic, NT_BOOLEAN, "boolean", {}, {});
+
+  auto val = Value::MakeBoolean(true, 5);
+  EXPECT_CALL(network, SetValue(pub, val));
+  storage.SetEntryValue(pub, val);
+
+  EXPECT_EQ(storage.GetTopicType(fooTopic), NT_BOOLEAN);
+  EXPECT_EQ(storage.GetTopicTypeString(fooTopic), "boolean");
+  EXPECT_TRUE(storage.GetTopicExists(fooTopic));
+
+  auto value = storage.GetEntryValue(sub);
+  ASSERT_TRUE(value.IsBoolean());
+  EXPECT_EQ(value.GetBoolean(), true);
+  EXPECT_EQ(value.time(), 5);
+
+  auto vals = storage.ReadQueueBoolean(sub);
+  ASSERT_EQ(vals.size(), 1u);
+  EXPECT_EQ(vals[0].value, true);
+  EXPECT_EQ(vals[0].time, 5);
+
+  val = Value::MakeBoolean(false, 6);
+  EXPECT_CALL(network, SetValue(pub, val));
+  storage.SetEntryValue(pub, val);
+
+  auto vals2 = storage.ReadQueueInteger(sub);  // mismatched type
+  ASSERT_TRUE(vals2.empty());
+}
+
+TEST_F(LocalStorageTest, SubscribeNoTypeLocalPubPre) {
+  EXPECT_CALL(network, Publish(_, fooTopic, std::string_view{"foo"},
+                               std::string_view{"boolean"}, wpi::json::object(),
+                               IsDefaultPubSubOptions()));
+  auto pub = storage.Publish(fooTopic, NT_BOOLEAN, "boolean", {}, {});
+
+  auto val = Value::MakeBoolean(true, 5);
+  EXPECT_CALL(network, SetValue(pub, val));
+  storage.SetEntryValue(pub, val);
+
+  EXPECT_CALL(network, Subscribe(_, wpi::SpanEq({std::string{"foo"}}),
+                                 IsDefaultPubSubOptions()));
+  auto sub = storage.Subscribe(fooTopic, NT_UNASSIGNED, "", {});
+
+  EXPECT_EQ(storage.GetTopicType(fooTopic), NT_BOOLEAN);
+  EXPECT_EQ(storage.GetTopicTypeString(fooTopic), "boolean");
+  EXPECT_TRUE(storage.GetTopicExists(fooTopic));
+
+  auto value = storage.GetEntryValue(sub);
+  ASSERT_TRUE(value.IsBoolean());
+  EXPECT_EQ(value.GetBoolean(), true);
+  EXPECT_EQ(value.time(), 5);
+
+  auto vals = storage.ReadQueueValue(sub);  // read queue won't get anything
+  ASSERT_TRUE(vals.empty());
+}
+
+TEST_F(LocalStorageTest, EntryNoTypeLocalSet) {
+  EXPECT_CALL(network, Subscribe(_, wpi::SpanEq({std::string{"foo"}}),
+                                 IsDefaultPubSubOptions()));
+  auto entry = storage.GetEntry(fooTopic, NT_UNASSIGNED, "", {});
+
+  // results in a publish and value set
+  auto val = Value::MakeBoolean(true, 5);
+  EXPECT_CALL(network, Publish(_, fooTopic, std::string_view{"foo"},
+                               std::string_view{"boolean"}, wpi::json::object(),
+                               IsDefaultPubSubOptions()));
+  EXPECT_CALL(network, SetValue(_, val));
+  EXPECT_TRUE(storage.SetEntryValue(entry, val));
+
+  EXPECT_EQ(storage.GetTopicType(fooTopic), NT_BOOLEAN);
+  EXPECT_EQ(storage.GetTopicTypeString(fooTopic), "boolean");
+  EXPECT_TRUE(storage.GetTopicExists(fooTopic));
+
+  auto value = storage.GetEntryValue(entry);
+  ASSERT_TRUE(value.IsBoolean());
+  EXPECT_EQ(value.GetBoolean(), true);
+  EXPECT_EQ(value.time(), 5);
+
+  auto vals = storage.ReadQueueBoolean(entry);
+  ASSERT_EQ(vals.size(), 1u);
+  EXPECT_EQ(vals[0].value, true);
+  EXPECT_EQ(vals[0].time, 5);
+
+  // normal set with same type
+  val = Value::MakeBoolean(false, 6);
+  EXPECT_CALL(network, SetValue(_, val));
+  EXPECT_TRUE(storage.SetEntryValue(entry, val));
+
+  auto vals2 = storage.ReadQueueInteger(entry);  // mismatched type
+  ASSERT_TRUE(vals2.empty());
+
+  // cannot change type; won't generate network message
+  EXPECT_FALSE(storage.SetEntryValue(entry, Value::MakeInteger(5, 7)));
+
+  // should not change type or generate queue items
+  EXPECT_EQ(storage.GetTopicType(fooTopic), NT_BOOLEAN);
+  EXPECT_EQ(storage.GetTopicTypeString(fooTopic), "boolean");
+
+  auto vals3 = storage.ReadQueueInteger(entry);  // mismatched type
+  ASSERT_TRUE(vals3.empty());
+}
+
+TEST_F(LocalStorageTest, PubUnpubPub) {
+  EXPECT_CALL(network, Subscribe(_, wpi::SpanEq({std::string{"foo"}}),
+                                 IsDefaultPubSubOptions()));
+  auto sub = storage.Subscribe(fooTopic, NT_INTEGER, "int", {});
+
+  EXPECT_CALL(network, Publish(_, fooTopic, std::string_view{"foo"},
+                               std::string_view{"boolean"}, wpi::json::object(),
+                               IsDefaultPubSubOptions()));
+  EXPECT_CALL(logger, Call(NT_LOG_INFO, _, _,
+                           "local subscribe to 'foo' disabled due to type "
+                           "mismatch (wanted 'int', published as 'boolean')"));
+  auto pub = storage.Publish(fooTopic, NT_BOOLEAN, "boolean", {}, {});
+
+  auto val = Value::MakeBoolean(true, 5);
+  EXPECT_CALL(network, SetValue(pub, val));
+  EXPECT_TRUE(storage.SetEntryValue(pub, val));
+
+  EXPECT_EQ(storage.GetTopicType(fooTopic), NT_BOOLEAN);
+  EXPECT_EQ(storage.GetTopicTypeString(fooTopic), "boolean");
+  EXPECT_TRUE(storage.GetTopicExists(fooTopic));
+
+  EXPECT_TRUE(storage.ReadQueueInteger(sub).empty());
+
+  EXPECT_CALL(network, Unpublish(pub, fooTopic));
+  storage.Unpublish(pub);
+
+  EXPECT_EQ(storage.GetTopicType(fooTopic), NT_UNASSIGNED);
+  EXPECT_EQ(storage.GetTopicTypeString(fooTopic), "");
+  EXPECT_FALSE(storage.GetTopicExists(fooTopic));
+
+  EXPECT_CALL(network, Publish(_, fooTopic, std::string_view{"foo"},
+                               std::string_view{"int"}, wpi::json::object(),
+                               IsDefaultPubSubOptions()));
+  pub = storage.Publish(fooTopic, NT_INTEGER, "int", {}, {});
+
+  val = Value::MakeInteger(3, 5);
+  EXPECT_CALL(network, SetValue(pub, val));
+  EXPECT_TRUE(storage.SetEntryValue(pub, val));
+
+  EXPECT_EQ(storage.GetTopicType(fooTopic), NT_INTEGER);
+  EXPECT_EQ(storage.GetTopicTypeString(fooTopic), "int");
+  EXPECT_TRUE(storage.GetTopicExists(fooTopic));
+
+  EXPECT_EQ(storage.ReadQueueInteger(sub).size(), 1u);
+}
+
+TEST_F(LocalStorageTest, LocalPubConflict) {
+  EXPECT_CALL(network, Publish(_, fooTopic, std::string_view{"foo"},
+                               std::string_view{"boolean"}, wpi::json::object(),
+                               IsDefaultPubSubOptions()));
+  auto pub1 = storage.Publish(fooTopic, NT_BOOLEAN, "boolean", {}, {});
+
+  EXPECT_CALL(logger, Call(NT_LOG_INFO, _, _,
+                           "local publish to 'foo' disabled due to type "
+                           "mismatch (wanted 'int', currently 'boolean')"));
+  auto pub2 = storage.Publish(fooTopic, NT_INTEGER, "int", {}, {});
+
+  EXPECT_EQ(storage.GetTopicType(fooTopic), NT_BOOLEAN);
+  EXPECT_EQ(storage.GetTopicTypeString(fooTopic), "boolean");
+  EXPECT_TRUE(storage.GetTopicExists(fooTopic));
+
+  EXPECT_CALL(network, SetValue(pub1, _));
+
+  EXPECT_TRUE(storage.SetEntryValue(pub1, Value::MakeBoolean(true, 5)));
+  EXPECT_FALSE(storage.SetEntryValue(pub2, Value::MakeInteger(3, 5)));
+
+  // unpublishing pub1 will publish pub2 to the network
+  EXPECT_CALL(network, Unpublish(pub1, fooTopic));
+  EXPECT_CALL(network, Publish(_, fooTopic, std::string_view{"foo"},
+                               std::string_view{"int"}, wpi::json::object(),
+                               IsDefaultPubSubOptions()));
+  storage.Unpublish(pub1);
+
+  EXPECT_EQ(storage.GetTopicType(fooTopic), NT_INTEGER);
+  EXPECT_EQ(storage.GetTopicTypeString(fooTopic), "int");
+  EXPECT_TRUE(storage.GetTopicExists(fooTopic));
+
+  EXPECT_CALL(network, SetValue(pub2, _));
+
+  EXPECT_FALSE(storage.SetEntryValue(pub1, Value::MakeBoolean(true, 5)));
+  EXPECT_TRUE(storage.SetEntryValue(pub2, Value::MakeInteger(3, 5)));
+}
+
+TEST_F(LocalStorageTest, LocalSubConflict) {
+  EXPECT_CALL(network, Publish(_, fooTopic, std::string_view{"foo"},
+                               std::string_view{"boolean"}, wpi::json::object(),
+                               IsDefaultPubSubOptions()));
+  storage.Publish(fooTopic, NT_BOOLEAN, "boolean", {}, {});
+
+  EXPECT_CALL(network, Subscribe(_, wpi::SpanEq({std::string{"foo"}}),
+                                 IsDefaultPubSubOptions()));
+  EXPECT_CALL(logger, Call(NT_LOG_INFO, _, _,
+                           "local subscribe to 'foo' disabled due to type "
+                           "mismatch (wanted 'int', published as 'boolean')"));
+  storage.Subscribe(fooTopic, NT_INTEGER, "int", {});
+}
+
+TEST_F(LocalStorageTest, RemotePubConflict) {
+  EXPECT_CALL(network, Publish(_, fooTopic, std::string_view{"foo"},
+                               std::string_view{"boolean"}, wpi::json::object(),
+                               IsDefaultPubSubOptions()));
+
+  storage.Publish(fooTopic, NT_BOOLEAN, "boolean", {}, {});
+
+  EXPECT_CALL(logger, Call(NT_LOG_INFO, _, _,
+                           "network announce of 'foo' overriding local publish "
+                           "(was 'boolean', now 'int')"));
+
+  storage.NetworkAnnounce("foo", "int", wpi::json::object(), {});
+
+  // network overrides local
+  EXPECT_EQ(storage.GetTopicType(fooTopic), NT_INTEGER);
+  EXPECT_EQ(storage.GetTopicTypeString(fooTopic), "int");
+  EXPECT_TRUE(storage.GetTopicExists(fooTopic));
+
+  EXPECT_CALL(network, Publish(_, fooTopic, std::string_view{"foo"},
+                               std::string_view{"boolean"}, wpi::json::object(),
+                               IsDefaultPubSubOptions()));
+
+  storage.NetworkUnannounce("foo");
+
+  EXPECT_EQ(storage.GetTopicType(fooTopic), NT_BOOLEAN);
+  EXPECT_EQ(storage.GetTopicTypeString(fooTopic), "boolean");
+  EXPECT_TRUE(storage.GetTopicExists(fooTopic));
+}
+
+TEST_F(LocalStorageTest, SubNonExist) {
+  // makes sure no warning is emitted
+  EXPECT_CALL(network, Subscribe(_, wpi::SpanEq({std::string{"foo"}}),
+                                 IsDefaultPubSubOptions()));
+  storage.Subscribe(fooTopic, NT_BOOLEAN, "boolean", {});
+}
+
+TEST_F(LocalStorageTest, SetDefaultSubscribe) {
+  // no publish, no value on wire, this is just handled locally
+  EXPECT_CALL(network, Subscribe(_, wpi::SpanEq({std::string{"foo"}}),
+                                 IsDefaultPubSubOptions()));
+  auto sub = storage.Subscribe(fooTopic, NT_BOOLEAN, "boolean", {});
+  EXPECT_TRUE(storage.SetDefaultEntryValue(sub, Value::MakeBoolean(true)));
+  auto val = storage.GetEntryValue(sub);
+  ASSERT_TRUE(val.IsBoolean());
+  ASSERT_TRUE(val.GetBoolean());
+  ASSERT_EQ(val.time(), 0);
+}
+
+TEST_F(LocalStorageTest, SetDefaultPublish) {
+  EXPECT_CALL(network, Publish(_, fooTopic, std::string_view{"foo"},
+                               std::string_view{"boolean"}, wpi::json::object(),
+                               IsDefaultPubSubOptions()));
+  auto pub = storage.Publish(fooTopic, NT_BOOLEAN, "boolean", {}, {});
+
+  // expect a value across the wire
+  auto expectVal = Value::MakeBoolean(true, 0);
+  EXPECT_CALL(network, SetValue(pub, expectVal));
+  EXPECT_TRUE(storage.SetDefaultEntryValue(pub, Value::MakeBoolean(true)));
+
+  EXPECT_CALL(network, Subscribe(_, _, IsDefaultPubSubOptions()));
+  auto sub = storage.Subscribe(fooTopic, NT_BOOLEAN, "boolean", {});
+  auto val = storage.GetEntryValue(sub);
+  ASSERT_TRUE(val.IsBoolean());
+  ASSERT_TRUE(val.GetBoolean());
+  ASSERT_EQ(val.time(), 0);
+}
+
+TEST_F(LocalStorageTest, SetDefaultEntry) {
+  EXPECT_CALL(network, Subscribe(_, wpi::SpanEq({std::string{"foo"}}),
+                                 IsDefaultPubSubOptions()));
+  auto entry = storage.GetEntry(fooTopic, NT_BOOLEAN, "boolean", {});
+
+  // expect a publish and value
+  EXPECT_CALL(network, Publish(_, fooTopic, std::string_view{"foo"},
+                               std::string_view{"boolean"}, wpi::json::object(),
+                               IsDefaultPubSubOptions()));
+  auto expectVal = Value::MakeBoolean(true, 0);
+  EXPECT_CALL(network, SetValue(_, expectVal));
+  EXPECT_TRUE(storage.SetDefaultEntryValue(entry, Value::MakeBoolean(true)));
+
+  auto val = storage.GetEntryValue(entry);
+  ASSERT_TRUE(val.IsBoolean());
+  ASSERT_TRUE(val.GetBoolean());
+  ASSERT_EQ(val.time(), 0);
+}
+
+TEST_F(LocalStorageTest, SetDefaultEntryUnassigned) {
+  EXPECT_CALL(network, Subscribe(_, wpi::SpanEq({std::string{"foo"}}),
+                                 IsDefaultPubSubOptions()));
+  auto entry = storage.GetEntry(fooTopic, NT_UNASSIGNED, "", {});
+
+  // expect a publish and value
+  EXPECT_CALL(network, Publish(_, fooTopic, std::string_view{"foo"},
+                               std::string_view{"boolean"}, wpi::json::object(),
+                               IsDefaultPubSubOptions()));
+  auto expectVal = Value::MakeBoolean(true, 0);
+  EXPECT_CALL(network, SetValue(_, expectVal));
+  EXPECT_TRUE(storage.SetDefaultEntryValue(entry, Value::MakeBoolean(true)));
+
+  ASSERT_EQ(storage.GetTopicType(fooTopic), NT_BOOLEAN);
+  auto val = storage.GetEntryValue(entry);
+  ASSERT_TRUE(val.IsBoolean());
+  ASSERT_TRUE(val.GetBoolean());
+  ASSERT_EQ(val.time(), 0);
+}
+
+TEST_F(LocalStorageTest, SetDefaultEntryDiffType) {
+  EXPECT_CALL(network, Publish(_, fooTopic, std::string_view{"foo"},
+                               std::string_view{"string"}, wpi::json::object(),
+                               IsDefaultPubSubOptions()));
+  auto pub = storage.Publish(fooTopic, NT_STRING, "string", {}, {});
+
+  EXPECT_FALSE(storage.SetDefaultEntryValue(pub, Value::MakeBoolean(true)));
+  ASSERT_EQ(storage.GetTopicType(fooTopic), NT_STRING);
+}
+
+TEST_F(LocalStorageTest, SetValueEmptyValue) {
+  EXPECT_CALL(network, Publish(_, fooTopic, std::string_view{"foo"},
+                               std::string_view{"string"}, wpi::json::object(),
+                               IsDefaultPubSubOptions()));
+  auto pub = storage.Publish(fooTopic, NT_STRING, "string", {}, {});
+
+  EXPECT_FALSE(storage.SetEntryValue(pub, {}));
+}
+
+TEST_F(LocalStorageTest, SetValueEmptyUntypedEntry) {
+  EXPECT_CALL(network, Subscribe(_, wpi::SpanEq({std::string{"foo"}}),
+                                 IsDefaultPubSubOptions()));
+  auto entry = storage.GetEntry(fooTopic, NT_UNASSIGNED, "", {});
+  EXPECT_FALSE(storage.SetEntryValue(entry, {}));
+}
+
+TEST_F(LocalStorageTest, PublishUntyped) {
+  EXPECT_CALL(
+      logger,
+      Call(
+          NT_LOG_ERROR, _, _,
+          "cannot publish 'foo' with an unassigned type or empty type string"));
+
+  EXPECT_EQ(storage.Publish(fooTopic, NT_UNASSIGNED, "", {}, {}), 0u);
+}
+
+TEST_F(LocalStorageTest, SetValueInvalidHandle) {
+  EXPECT_FALSE(storage.SetEntryValue(0u, {}));
+}
+
+class LocalStorageDuplicatesTest : public LocalStorageTest {
+ public:
+  void SetupPubSub(bool keepPub, bool keepSub);
+  void SetValues();
+
+  NT_Publisher pub;
+  NT_Subscriber sub;
+  Value val1 = Value::MakeDouble(1.0, 10);
+  Value val2 = Value::MakeDouble(1.0, 20);  // duplicate value
+  Value val3 = Value::MakeDouble(2.0, 30);
+};
+
+void LocalStorageDuplicatesTest::SetupPubSub(bool keepPub, bool keepSub) {
+  PubSubOptionsImpl pubOptions;
+  pubOptions.keepDuplicates = keepPub;
+  EXPECT_CALL(network, Publish(_, fooTopic, std::string_view{"foo"},
+                               std::string_view{"double"}, wpi::json::object(),
+                               IsPubSubOptions(pubOptions)));
+  pub = storage.Publish(fooTopic, NT_DOUBLE, "double", {},
+                        {.keepDuplicates = keepPub});
+
+  PubSubOptionsImpl subOptions;
+  subOptions.pollStorage = 10;
+  subOptions.keepDuplicates = keepSub;
+  EXPECT_CALL(network, Subscribe(_, wpi::SpanEq({std::string{"foo"}}),
+                                 IsPubSubOptions(subOptions)));
+  sub = storage.Subscribe(fooTopic, NT_DOUBLE, "double",
+                          {.pollStorage = 10, .keepDuplicates = keepSub});
+}
+
+void LocalStorageDuplicatesTest::SetValues() {
+  storage.SetEntryValue(pub, val1);
+  storage.SetEntryValue(pub, val2);
+  // verify the timestamp was updated
+  EXPECT_EQ(storage.GetEntryLastChange(sub), val2.time());
+  storage.SetEntryValue(pub, val3);
+}
+
+TEST_F(LocalStorageDuplicatesTest, Defaults) {
+  SetupPubSub(false, false);
+
+  EXPECT_CALL(network, SetValue(pub, val1));
+  EXPECT_CALL(network, SetValue(pub, val3));
+  SetValues();
+
+  // verify 2nd update was dropped locally
+  auto values = storage.ReadQueueDouble(sub);
+  ASSERT_EQ(values.size(), 2u);
+  ASSERT_EQ(values[0].value, val1.GetDouble());
+  ASSERT_EQ(values[0].time, val1.time());
+  ASSERT_EQ(values[1].value, val3.GetDouble());
+  ASSERT_EQ(values[1].time, val3.time());
+}
+
+TEST_F(LocalStorageDuplicatesTest, KeepPub) {
+  SetupPubSub(true, false);
+
+  EXPECT_CALL(network, SetValue(pub, val1)).Times(2);
+  // EXPECT_CALL(network, SetValue(pub, val2));
+  EXPECT_CALL(network, SetValue(pub, val3));
+  SetValues();
+
+  // verify all 3 updates were received locally
+  auto values = storage.ReadQueueDouble(sub);
+  ASSERT_EQ(values.size(), 3u);
+}
+
+TEST_F(LocalStorageDuplicatesTest, KeepSub) {
+  SetupPubSub(false, true);
+
+  // second update should NOT go to the network
+  EXPECT_CALL(network, SetValue(pub, val1));
+  EXPECT_CALL(network, SetValue(pub, val3));
+  SetValues();
+
+  // verify all 3 updates were received locally
+  auto values = storage.ReadQueueDouble(sub);
+  ASSERT_EQ(values.size(), 3u);
+}
+
+TEST_F(LocalStorageDuplicatesTest, FromNetwork) {
+  SetupPubSub(false, false);
+
+  // incoming from the network are treated like a normal local publish
+  auto topic = storage.NetworkAnnounce("foo", "double", {{}}, 0);
+  storage.NetworkSetValue(topic, val1);
+  storage.NetworkSetValue(topic, val2);
+  // verify the timestamp was updated
+  EXPECT_EQ(storage.GetEntryLastChange(sub), val2.time());
+  storage.NetworkSetValue(topic, val3);
+
+  // verify 2nd update was dropped locally
+  auto values = storage.ReadQueueDouble(sub);
+  ASSERT_EQ(values.size(), 2u);
+  ASSERT_EQ(values[0].value, val1.GetDouble());
+  ASSERT_EQ(values[0].time, val1.time());
+  ASSERT_EQ(values[1].value, val3.GetDouble());
+  ASSERT_EQ(values[1].time, val3.time());
+}
+
+class LocalStorageNumberVariantsTest : public LocalStorageTest {
+ public:
+  void CreateSubscriber(NT_Handle* handle, std::string_view name, NT_Type type,
+                        std::string_view typeStr);
+  void CreateSubscribers();
+  void CreateSubscribersArray();
+
+  NT_Subscriber sub1, sub2, sub3, sub4;
+  NT_Entry entry;
+
+  struct SubEntry {
+    SubEntry(NT_Handle subentry, NT_Type type, std::string_view name)
+        : subentry{subentry}, type{type}, name{name} {}
+    NT_Handle subentry;
+    NT_Type type;
+    std::string name;
+  };
+  std::vector<SubEntry> subentries;
+};
+
+void LocalStorageNumberVariantsTest::CreateSubscriber(
+    NT_Handle* handle, std::string_view name, NT_Type type,
+    std::string_view typeStr) {
+  *handle = storage.Subscribe(fooTopic, type, typeStr, {});
+  subentries.emplace_back(*handle, type, name);
+}
+
+void LocalStorageNumberVariantsTest::CreateSubscribers() {
+  EXPECT_CALL(logger,
+              Call(NT_LOG_INFO, _, _,
+                   "local subscribe to 'foo' disabled due to type "
+                   "mismatch (wanted 'boolean', published as 'double')"));
+  CreateSubscriber(&sub1, "subDouble", NT_DOUBLE, "double");
+  CreateSubscriber(&sub2, "subInteger", NT_INTEGER, "int");
+  CreateSubscriber(&sub3, "subFloat", NT_FLOAT, "float");
+  CreateSubscriber(&sub4, "subBoolean", NT_BOOLEAN, "boolean");
+  entry = storage.GetEntry("foo");
+  subentries.emplace_back(entry, NT_UNASSIGNED, "entry");
+}
+
+void LocalStorageNumberVariantsTest::CreateSubscribersArray() {
+  EXPECT_CALL(logger,
+              Call(NT_LOG_INFO, _, _,
+                   "local subscribe to 'foo' disabled due to type "
+                   "mismatch (wanted 'boolean[]', published as 'double[]')"));
+  CreateSubscriber(&sub1, "subDouble", NT_DOUBLE_ARRAY, "double[]");
+  CreateSubscriber(&sub2, "subInteger", NT_INTEGER_ARRAY, "int[]");
+  CreateSubscriber(&sub3, "subFloat", NT_FLOAT_ARRAY, "float[]");
+  CreateSubscriber(&sub4, "subBoolean", NT_BOOLEAN_ARRAY, "boolean[]");
+  entry = storage.GetEntry("foo");
+  subentries.emplace_back(entry, NT_UNASSIGNED, "entry");
+}
+
+TEST_F(LocalStorageNumberVariantsTest, GetEntryPubAfter) {
+  EXPECT_CALL(network, Subscribe(_, _, _)).Times(5);
+  EXPECT_CALL(network, Publish(_, _, _, _, _, _)).Times(1);
+  EXPECT_CALL(network, SetValue(_, _)).Times(1);
+  CreateSubscribers();
+  auto pub = storage.Publish(fooTopic, NT_DOUBLE, "double", {}, {});
+  storage.SetEntryValue(pub, Value::MakeDouble(1.0, 50));
+  // all subscribers get the actual type and time
+  for (auto&& subentry : subentries) {
+    SCOPED_TRACE(subentry.name);
+    EXPECT_EQ(storage.GetEntryType(subentry.subentry), NT_DOUBLE);
+    EXPECT_EQ(storage.GetEntryLastChange(subentry.subentry), 50);
+  }
+  // for subscribers, they get a converted value or nothing on mismatch
+  EXPECT_EQ(storage.GetEntryValue(sub1), Value::MakeDouble(1.0, 50));
+  EXPECT_EQ(storage.GetEntryValue(sub2), Value::MakeInteger(1, 50));
+  EXPECT_EQ(storage.GetEntryValue(sub3), Value::MakeFloat(1.0, 50));
+  EXPECT_EQ(storage.GetEntryValue(sub4), Value{});
+  // entrys just get whatever the value is
+  EXPECT_EQ(storage.GetEntryValue(entry), Value::MakeDouble(1.0, 50));
+}
+
+TEST_F(LocalStorageNumberVariantsTest, GetEntryPubBefore) {
+  EXPECT_CALL(network, Subscribe(_, _, _)).Times(5);
+  EXPECT_CALL(network, Publish(_, _, _, _, _, _)).Times(1);
+  EXPECT_CALL(network, SetValue(_, _)).Times(1);
+  auto pub = storage.Publish(fooTopic, NT_DOUBLE, "double", {}, {});
+  CreateSubscribers();
+  storage.SetEntryValue(pub, Value::MakeDouble(1.0, 50));
+  // all subscribers get the actual type and time
+  for (auto&& subentry : subentries) {
+    SCOPED_TRACE(subentry.name);
+    EXPECT_EQ(storage.GetEntryType(subentry.subentry), NT_DOUBLE);
+    EXPECT_EQ(storage.GetEntryLastChange(subentry.subentry), 50);
+  }
+  // for subscribers, they get a converted value or nothing on mismatch
+  EXPECT_EQ(storage.GetEntryValue(sub1), Value::MakeDouble(1.0, 50));
+  EXPECT_EQ(storage.GetEntryValue(sub2), Value::MakeInteger(1, 50));
+  EXPECT_EQ(storage.GetEntryValue(sub3), Value::MakeFloat(1.0, 50));
+  EXPECT_EQ(storage.GetEntryValue(sub4), Value{});
+  // entrys just get whatever the value is
+  EXPECT_EQ(storage.GetEntryValue(entry), Value::MakeDouble(1.0, 50));
+}
+
+template <typename T>
+::testing::Matcher<const T&> TSEq(auto value, int64_t time) {
+  return AllOf(Field("value", &T::value, value), Field("time", &T::time, time));
+}
+
+TEST_F(LocalStorageNumberVariantsTest, GetAtomic) {
+  EXPECT_CALL(network, Subscribe(_, _, _)).Times(5);
+  EXPECT_CALL(network, Publish(_, _, _, _, _, _)).Times(1);
+  EXPECT_CALL(network, SetValue(_, _)).Times(1);
+  auto pub = storage.Publish(fooTopic, NT_DOUBLE, "double", {}, {});
+  CreateSubscribers();
+  storage.SetEntryValue(pub, Value::MakeDouble(1.0, 50));
+
+  for (auto&& subentry : subentries) {
+    SCOPED_TRACE(subentry.name);
+    EXPECT_THAT(storage.GetAtomicDouble(subentry.subentry, 0),
+                TSEq<TimestampedDouble>(1.0, 50));
+    EXPECT_THAT(storage.GetAtomicInteger(subentry.subentry, 0),
+                TSEq<TimestampedInteger>(1, 50));
+    EXPECT_THAT(storage.GetAtomicFloat(subentry.subentry, 0),
+                TSEq<TimestampedFloat>(1.0, 50));
+    EXPECT_THAT(storage.GetAtomicBoolean(subentry.subentry, false),
+                TSEq<TimestampedBoolean>(false, 0));
+  }
+}
+
+template <typename T, typename U>
+::testing::Matcher<const T&> TSSpanEq(std::span<U> value, int64_t time) {
+  return AllOf(
+      Field("value", &T::value, wpi::SpanEq(std::span<const U>(value))),
+      Field("time", &T::time, time));
+}
+
+TEST_F(LocalStorageNumberVariantsTest, GetAtomicArray) {
+  EXPECT_CALL(network, Subscribe(_, _, _)).Times(5);
+  EXPECT_CALL(network, Publish(_, _, _, _, _, _)).Times(1);
+  EXPECT_CALL(network, SetValue(_, _)).Times(1);
+  auto pub = storage.Publish(fooTopic, NT_DOUBLE_ARRAY, "double[]", {}, {});
+  CreateSubscribersArray();
+  storage.SetEntryValue(pub, Value::MakeDoubleArray({1.0}, 50));
+
+  for (auto&& subentry : subentries) {
+    SCOPED_TRACE(subentry.name);
+    double doubleVal = 1.0;
+    EXPECT_THAT(storage.GetAtomicDoubleArray(subentry.subentry, {}),
+                TSSpanEq<TimestampedDoubleArray>(std::span{&doubleVal, 1}, 50));
+    int64_t intVal = 1;
+    EXPECT_THAT(storage.GetAtomicIntegerArray(subentry.subentry, {}),
+                TSSpanEq<TimestampedIntegerArray>(std::span{&intVal, 1}, 50));
+    float floatVal = 1.0;
+    EXPECT_THAT(storage.GetAtomicFloatArray(subentry.subentry, {}),
+                TSSpanEq<TimestampedFloatArray>(std::span{&floatVal, 1}, 50));
+    EXPECT_THAT(storage.GetAtomicBooleanArray(subentry.subentry, {}),
+                TSSpanEq<TimestampedBooleanArray>(std::span<int>{}, 0));
+  }
+}
+
+TEST_F(LocalStorageNumberVariantsTest, ReadQueue) {
+  EXPECT_CALL(network, Subscribe(_, _, _)).Times(5);
+  EXPECT_CALL(network, Publish(_, _, _, _, _, _)).Times(1);
+  EXPECT_CALL(network, SetValue(_, _)).Times(4);
+  auto pub = storage.Publish(fooTopic, NT_DOUBLE, "double", {}, {});
+  CreateSubscribers();
+
+  storage.SetEntryValue(pub, Value::MakeDouble(1.0, 50));
+  for (auto&& subentry : subentries) {
+    SCOPED_TRACE(subentry.name);
+    if (subentry.type == NT_BOOLEAN) {
+      EXPECT_THAT(storage.ReadQueueDouble(subentry.subentry), IsEmpty());
+    } else {
+      EXPECT_THAT(storage.ReadQueueDouble(subentry.subentry),
+                  ElementsAre(TSEq<TimestampedDouble>(1.0, 50)));
+    }
+  }
+
+  storage.SetEntryValue(pub, Value::MakeDouble(2.0, 50));
+  for (auto&& subentry : subentries) {
+    SCOPED_TRACE(subentry.name);
+    if (subentry.type == NT_BOOLEAN) {
+      EXPECT_THAT(storage.ReadQueueInteger(subentry.subentry), IsEmpty());
+    } else {
+      EXPECT_THAT(storage.ReadQueueInteger(subentry.subentry),
+                  ElementsAre(TSEq<TimestampedInteger>(2, 50)));
+    }
+  }
+
+  storage.SetEntryValue(pub, Value::MakeDouble(3.0, 50));
+  for (auto&& subentry : subentries) {
+    SCOPED_TRACE(subentry.name);
+    if (subentry.type == NT_BOOLEAN) {
+      EXPECT_THAT(storage.ReadQueueFloat(subentry.subentry), IsEmpty());
+    } else {
+      EXPECT_THAT(storage.ReadQueueFloat(subentry.subentry),
+                  ElementsAre(TSEq<TimestampedFloat>(3.0, 50)));
+    }
+  }
+
+  storage.SetEntryValue(pub, Value::MakeDouble(4.0, 50));
+  for (auto&& subentry : subentries) {
+    SCOPED_TRACE(subentry.name);
+    EXPECT_THAT(storage.ReadQueueBoolean(subentry.subentry), IsEmpty());
+  }
+}
+
+TEST_F(LocalStorageTest, MultiSubSpecial) {
+  EXPECT_CALL(network, Subscribe(_, _, _)).Times(2);
+  EXPECT_CALL(network, Publish(_, _, _, _, _, _)).Times(2);
+  EXPECT_CALL(network, SetValue(_, _)).Times(2);
+  EXPECT_CALL(listenerStorage, Activate(_, _, _)).Times(2);
+
+  auto subnormal = storage.SubscribeMultiple({{""}}, {});
+  auto subspecial = storage.SubscribeMultiple({{"", "$"}}, {});
+  auto pubnormal = storage.Publish(fooTopic, NT_DOUBLE, "double", {}, {});
+  auto specialTopic = storage.GetTopic("$topic");
+  auto pubspecial = storage.Publish(specialTopic, NT_DOUBLE, "double", {}, {});
+  storage.AddListener(1, subnormal, NT_EVENT_VALUE_ALL);
+  storage.AddListener(2, subspecial, NT_EVENT_VALUE_ALL);
+
+  EXPECT_CALL(
+      listenerStorage,
+      Notify(wpi::SpanEq(std::span<const NT_Listener>{{2}}), _, _, _, _));
+  storage.SetEntryValue(pubspecial, Value::MakeDouble(1.0, 30));
+
+  EXPECT_CALL(
+      listenerStorage,
+      Notify(wpi::SpanEq(std::span<const NT_Listener>{{1}}), _, _, _, _));
+  EXPECT_CALL(
+      listenerStorage,
+      Notify(wpi::SpanEq(std::span<const NT_Listener>{{2}}), _, _, _, _));
+  storage.SetEntryValue(pubnormal, Value::MakeDouble(2.0, 40));
+}
+
+TEST_F(LocalStorageTest, NetworkDuplicateDetect) {
+  EXPECT_CALL(network, Publish(_, _, _, _, _, _));
+  auto pub = storage.Publish(fooTopic, NT_DOUBLE, "double", {}, {});
+  auto remoteTopic =
+      storage.NetworkAnnounce("foo", "double", wpi::json::object(), 0);
+
+  // local set
+  EXPECT_CALL(network, SetValue(_, _));
+  storage.SetEntryValue(pub, Value::MakeDouble(1.0, 50));
+  // 2nd local set with same value - no SetValue call to network
+  storage.SetEntryValue(pub, Value::MakeDouble(1.0, 60));
+  // network set with different value
+  storage.NetworkSetValue(remoteTopic, Value::MakeDouble(2.0, 70));
+  // 3rd local set with same value generates a SetValue call to network
+  EXPECT_CALL(network, SetValue(_, _));
+  storage.SetEntryValue(pub, Value::MakeDouble(1.0, 80));
+}
+
+TEST_F(LocalStorageTest, ReadQueueLocalRemote) {
+  EXPECT_CALL(network, Subscribe(_, _, _)).Times(3);
+  EXPECT_CALL(network, Publish(_, _, _, _, _, _)).Times(1);
+
+  auto subBoth =
+      storage.Subscribe(fooTopic, NT_DOUBLE, "double", kDefaultPubSubOptions);
+  auto subLocal =
+      storage.Subscribe(fooTopic, NT_DOUBLE, "double", {.disableRemote = true});
+  auto subRemote =
+      storage.Subscribe(fooTopic, NT_DOUBLE, "double", {.disableLocal = true});
+  auto pub = storage.Publish(fooTopic, NT_DOUBLE, "double", {}, {});
+  auto remoteTopic =
+      storage.NetworkAnnounce("foo", "double", wpi::json::object(), 0);
+
+  // local set
+  EXPECT_CALL(network, SetValue(_, _));
+  storage.SetEntryValue(pub, Value::MakeDouble(1.0, 50));
+  EXPECT_THAT(storage.ReadQueueDouble(subBoth),
+              ElementsAre(TSEq<TimestampedDouble>(1.0, 50)));
+  EXPECT_THAT(storage.ReadQueueDouble(subLocal),
+              ElementsAre(TSEq<TimestampedDouble>(1.0, 50)));
+  EXPECT_THAT(storage.ReadQueueDouble(subRemote), IsEmpty());
+
+  // network set
+  storage.NetworkSetValue(remoteTopic, Value::MakeDouble(2.0, 60));
+  EXPECT_THAT(storage.ReadQueueDouble(subBoth),
+              ElementsAre(TSEq<TimestampedDouble>(2.0, 60)));
+  EXPECT_THAT(storage.ReadQueueDouble(subRemote),
+              ElementsAre(TSEq<TimestampedDouble>(2.0, 60)));
+  EXPECT_THAT(storage.ReadQueueDouble(subLocal), IsEmpty());
+}
+
+TEST_F(LocalStorageTest, SubExcludePub) {
+  EXPECT_CALL(network, Subscribe(_, _, _)).Times(2);
+  EXPECT_CALL(network, Publish(_, _, _, _, _, _)).Times(1);
+
+  auto pub = storage.Publish(fooTopic, NT_DOUBLE, "double", {}, {});
+  auto subActive = storage.Subscribe(fooTopic, NT_DOUBLE, "double", {});
+  auto subExclude = storage.Subscribe(fooTopic, NT_DOUBLE, "double",
+                                      {.excludePublisher = pub});
+  auto remoteTopic =
+      storage.NetworkAnnounce("foo", "double", wpi::json::object(), 0);
+
+  // local set
+  EXPECT_CALL(network, SetValue(_, _));
+  storage.SetEntryValue(pub, Value::MakeDouble(1.0, 50));
+  EXPECT_THAT(storage.ReadQueueDouble(subActive),
+              ElementsAre(TSEq<TimestampedDouble>(1.0, 50)));
+  EXPECT_THAT(storage.ReadQueueDouble(subExclude), IsEmpty());
+
+  // network set
+  storage.NetworkSetValue(remoteTopic, Value::MakeDouble(2.0, 60));
+  EXPECT_THAT(storage.ReadQueueDouble(subActive),
+              ElementsAre(TSEq<TimestampedDouble>(2.0, 60)));
+  EXPECT_THAT(storage.ReadQueueDouble(subExclude),
+              ElementsAre(TSEq<TimestampedDouble>(2.0, 60)));
+}
+
+TEST_F(LocalStorageTest, EntryExcludeSelf) {
+  EXPECT_CALL(network, Subscribe(_, _, _));
+
+  auto entry =
+      storage.GetEntry(fooTopic, NT_DOUBLE, "double", {.excludeSelf = true});
+  auto remoteTopic =
+      storage.NetworkAnnounce("foo", "double", wpi::json::object(), 0);
+
+  // local set
+  EXPECT_CALL(network, Publish(_, _, _, _, _, _));
+  EXPECT_CALL(network, SetValue(_, _));
+  storage.SetEntryValue(entry, Value::MakeDouble(1.0, 50));
+  EXPECT_THAT(storage.ReadQueueDouble(entry), IsEmpty());
+
+  // network set
+  storage.NetworkSetValue(remoteTopic, Value::MakeDouble(2.0, 60));
+  EXPECT_THAT(storage.ReadQueueDouble(entry),
+              ElementsAre(TSEq<TimestampedDouble>(2.0, 60)));
+}
+
+}  // namespace nt
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/LoggerTest.cpp b/third_party/allwpilib/ntcore/src/test/native/cpp/LoggerTest.cpp
new file mode 100644
index 0000000..a9f499c
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/test/native/cpp/LoggerTest.cpp
@@ -0,0 +1,96 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <wpi/Synchronization.h>
+
+#include "Handle.h"
+#include "TestPrinters.h"
+#include "gtest/gtest.h"
+#include "ntcore_cpp.h"
+
+class LoggerTest : public ::testing::Test {
+ public:
+  LoggerTest() : m_inst(nt::CreateInstance()) {}
+
+  ~LoggerTest() override { nt::DestroyInstance(m_inst); }
+
+  void Generate();
+  void Check(const std::vector<nt::Event>& events, NT_Listener handle,
+             bool infoMsg, bool errMsg);
+
+ protected:
+  NT_Inst m_inst;
+};
+
+void LoggerTest::Generate() {
+  // generate info message
+  nt::StartClient4(m_inst, "");
+
+  // generate error message
+  nt::Publish(nt::Handle(nt::Handle{m_inst}.GetInst(), 5, nt::Handle::kTopic),
+              NT_DOUBLE, "");
+}
+
+void LoggerTest::Check(const std::vector<nt::Event>& events, NT_Listener handle,
+                       bool infoMsg, bool errMsg) {
+  size_t count = (infoMsg ? 1u : 0u) + (errMsg ? 1u : 0u);
+  ASSERT_EQ(events.size(), count);
+  for (size_t i = 0; i < count; ++i) {
+    ASSERT_EQ(events[i].listener, handle);
+    ASSERT_EQ(events[i].flags & nt::EventFlags::kLogMessage,
+              nt::EventFlags::kLogMessage);
+    auto log = events[i].GetLogMessage();
+    ASSERT_TRUE(log);
+    if (infoMsg) {
+      ASSERT_EQ(log->message, "starting network client");
+      ASSERT_EQ(log->level, NT_LOG_INFO);
+      infoMsg = false;
+    } else if (errMsg) {
+      ASSERT_EQ(log->message,
+                "trying to publish invalid topic handle (386924549)");
+      ASSERT_EQ(log->level, NT_LOG_ERROR);
+      errMsg = false;
+    }
+  }
+}
+
+TEST_F(LoggerTest, DefaultLogRange) {
+  auto poller = nt::CreateListenerPoller(m_inst);
+  auto handle =
+      nt::AddPolledListener(poller, m_inst, nt::EventFlags::kLogMessage);
+
+  Generate();
+
+  bool timedOut = false;
+  ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut));
+  auto events = nt::ReadListenerQueue(poller);
+
+  Check(events, handle, true, true);
+}
+
+TEST_F(LoggerTest, InfoOnly) {
+  auto poller = nt::CreateListenerPoller(m_inst);
+  auto handle = nt::AddPolledLogger(poller, NT_LOG_INFO, NT_LOG_INFO);
+
+  Generate();
+
+  bool timedOut = false;
+  ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut));
+  auto events = nt::ReadListenerQueue(poller);
+
+  Check(events, handle, true, false);
+}
+
+TEST_F(LoggerTest, Error) {
+  auto poller = nt::CreateListenerPoller(m_inst);
+  auto handle = nt::AddPolledLogger(poller, NT_LOG_ERROR, 100);
+
+  Generate();
+
+  bool timedOut = false;
+  ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut));
+  auto events = nt::ReadListenerQueue(poller);
+
+  Check(events, handle, false, true);
+}
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/MessageMatcher.cpp b/third_party/allwpilib/ntcore/src/test/native/cpp/MessageMatcher.cpp
deleted file mode 100644
index 69c87a0..0000000
--- a/third_party/allwpilib/ntcore/src/test/native/cpp/MessageMatcher.cpp
+++ /dev/null
@@ -1,51 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "MessageMatcher.h"
-
-namespace nt {
-
-bool MessageMatcher::MatchAndExplain(
-    std::shared_ptr<Message> msg,
-    ::testing::MatchResultListener* listener) const {
-  bool match = true;
-  if (!msg) {
-    return false;
-  }
-  if (msg->str() != goodmsg->str()) {
-    *listener << "str mismatch ";
-    match = false;
-  }
-  if ((!msg->value() && goodmsg->value()) ||
-      (msg->value() && !goodmsg->value()) ||
-      (msg->value() && goodmsg->value() &&
-       *msg->value() != *goodmsg->value())) {
-    *listener << "value mismatch ";
-    match = false;
-  }
-  if (msg->id() != goodmsg->id()) {
-    *listener << "id mismatch ";
-    match = false;
-  }
-  if (msg->flags() != goodmsg->flags()) {
-    *listener << "flags mismatch";
-    match = false;
-  }
-  if (msg->seq_num_uid() != goodmsg->seq_num_uid()) {
-    *listener << "seq_num_uid mismatch";
-    match = false;
-  }
-  return match;
-}
-
-void MessageMatcher::DescribeTo(::std::ostream* os) const {
-  PrintTo(goodmsg, os);
-}
-
-void MessageMatcher::DescribeNegationTo(::std::ostream* os) const {
-  *os << "is not equal to ";
-  PrintTo(goodmsg, os);
-}
-
-}  // namespace nt
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/MessageMatcher.h b/third_party/allwpilib/ntcore/src/test/native/cpp/MessageMatcher.h
deleted file mode 100644
index 7afeeef..0000000
--- a/third_party/allwpilib/ntcore/src/test/native/cpp/MessageMatcher.h
+++ /dev/null
@@ -1,40 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef NTCORE_MESSAGEMATCHER_H_
-#define NTCORE_MESSAGEMATCHER_H_
-
-#include <memory>
-#include <ostream>
-#include <utility>
-
-#include "Message.h"
-#include "TestPrinters.h"
-#include "gmock/gmock.h"
-
-namespace nt {
-
-class MessageMatcher
-    : public ::testing::MatcherInterface<std::shared_ptr<Message>> {
- public:
-  explicit MessageMatcher(std::shared_ptr<Message> goodmsg_)
-      : goodmsg(std::move(goodmsg_)) {}
-
-  bool MatchAndExplain(std::shared_ptr<Message> msg,
-                       ::testing::MatchResultListener* listener) const override;
-  void DescribeTo(::std::ostream* os) const override;
-  void DescribeNegationTo(::std::ostream* os) const override;
-
- private:
-  std::shared_ptr<Message> goodmsg;
-};
-
-inline ::testing::Matcher<std::shared_ptr<Message>> MessageEq(
-    std::shared_ptr<Message> goodmsg) {
-  return ::testing::MakeMatcher(new MessageMatcher(goodmsg));
-}
-
-}  // namespace nt
-
-#endif  // NTCORE_MESSAGEMATCHER_H_
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/MockConnectionList.h b/third_party/allwpilib/ntcore/src/test/native/cpp/MockConnectionList.h
new file mode 100644
index 0000000..cd93343
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/test/native/cpp/MockConnectionList.h
@@ -0,0 +1,24 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <vector>
+
+#include "IConnectionList.h"
+#include "gmock/gmock.h"
+
+namespace nt {
+
+class MockConnectionList : public IConnectionList {
+ public:
+  MOCK_METHOD(int, AddConnection, (const ConnectionInfo& info), (override));
+  MOCK_METHOD(void, RemoveConnection, (int handle), (override));
+  MOCK_METHOD(void, ClearConnections, (), (override));
+  MOCK_METHOD(std::vector<ConnectionInfo>, GetConnections, (),
+              (const, override));
+  MOCK_METHOD(bool, IsConnected, (), (const, override));
+};
+
+}  // namespace nt
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/MockConnectionNotifier.h b/third_party/allwpilib/ntcore/src/test/native/cpp/MockConnectionNotifier.h
deleted file mode 100644
index d632d5c..0000000
--- a/third_party/allwpilib/ntcore/src/test/native/cpp/MockConnectionNotifier.h
+++ /dev/null
@@ -1,27 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef NTCORE_MOCKCONNECTIONNOTIFIER_H_
-#define NTCORE_MOCKCONNECTIONNOTIFIER_H_
-
-#include "IConnectionNotifier.h"
-#include "gmock/gmock.h"
-
-namespace nt {
-
-class MockConnectionNotifier : public IConnectionNotifier {
- public:
-  MOCK_METHOD1(
-      Add,
-      unsigned int(
-          std::function<void(const ConnectionNotification& event)> callback));
-  MOCK_METHOD1(AddPolled, unsigned int(unsigned int poller_uid));
-  MOCK_METHOD3(NotifyConnection,
-               void(bool connected, const ConnectionInfo& conn_info,
-                    unsigned int only_listener));
-};
-
-}  // namespace nt
-
-#endif  // NTCORE_MOCKCONNECTIONNOTIFIER_H_
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/MockDispatcher.h b/third_party/allwpilib/ntcore/src/test/native/cpp/MockDispatcher.h
deleted file mode 100644
index 22b0fba..0000000
--- a/third_party/allwpilib/ntcore/src/test/native/cpp/MockDispatcher.h
+++ /dev/null
@@ -1,24 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef NTCORE_MOCKDISPATCHER_H_
-#define NTCORE_MOCKDISPATCHER_H_
-
-#include <memory>
-
-#include "IDispatcher.h"
-#include "gmock/gmock.h"
-
-namespace nt {
-
-class MockDispatcher : public IDispatcher {
- public:
-  MOCK_METHOD3(QueueOutgoing,
-               void(std::shared_ptr<Message> msg, INetworkConnection* only,
-                    INetworkConnection* except));
-};
-
-}  // namespace nt
-
-#endif  // NTCORE_MOCKDISPATCHER_H_
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/MockEntryNotifier.h b/third_party/allwpilib/ntcore/src/test/native/cpp/MockEntryNotifier.h
deleted file mode 100644
index 58518c6..0000000
--- a/third_party/allwpilib/ntcore/src/test/native/cpp/MockEntryNotifier.h
+++ /dev/null
@@ -1,40 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef NTCORE_MOCKENTRYNOTIFIER_H_
-#define NTCORE_MOCKENTRYNOTIFIER_H_
-
-#include <memory>
-
-#include "IEntryNotifier.h"
-#include "gmock/gmock.h"
-
-namespace nt {
-
-class MockEntryNotifier : public IEntryNotifier {
- public:
-  MOCK_CONST_METHOD0(local_notifiers, bool());
-  MOCK_METHOD3(
-      Add,
-      unsigned int(std::function<void(const EntryNotification& event)> callback,
-                   std::string_view prefix, unsigned int flags));
-  MOCK_METHOD3(
-      Add,
-      unsigned int(std::function<void(const EntryNotification& event)> callback,
-                   unsigned int local_id, unsigned int flags));
-  MOCK_METHOD3(AddPolled,
-               unsigned int(unsigned int poller_uid, std::string_view prefix,
-                            unsigned int flags));
-  MOCK_METHOD3(AddPolled,
-               unsigned int(unsigned int poller_uid, unsigned int local_id,
-                            unsigned int flags));
-  MOCK_METHOD5(NotifyEntry,
-               void(unsigned int local_id, std::string_view name,
-                    std::shared_ptr<Value> value, unsigned int flags,
-                    unsigned int only_listener));
-};
-
-}  // namespace nt
-
-#endif  // NTCORE_MOCKENTRYNOTIFIER_H_
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/MockListenerStorage.h b/third_party/allwpilib/ntcore/src/test/native/cpp/MockListenerStorage.h
new file mode 100644
index 0000000..6e1dc4e
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/test/native/cpp/MockListenerStorage.h
@@ -0,0 +1,45 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <memory>
+#include <span>
+#include <string_view>
+
+#include "IListenerStorage.h"
+#include "gmock/gmock.h"
+
+namespace nt {
+
+class MockListenerStorage : public IListenerStorage {
+ public:
+  MOCK_METHOD(void, Activate,
+              (NT_Listener listenerHandle, unsigned int mask,
+               FinishEventFunc finishEvent),
+              (override));
+  MOCK_METHOD(void, Notify,
+              (std::span<const NT_Listener> handles, unsigned int flags,
+               std::span<ConnectionInfo const* const> infos),
+              (override));
+  MOCK_METHOD(void, Notify,
+              (std::span<const NT_Listener> handles, unsigned int flags,
+               std::span<const TopicInfo> infos),
+              (override));
+  MOCK_METHOD(void, Notify,
+              (std::span<const NT_Listener> handles, unsigned int flags,
+               NT_Topic topic, NT_Handle subentry, const Value& value),
+              (override));
+  MOCK_METHOD(void, Notify,
+              (unsigned int flags, unsigned int level,
+               std::string_view filename, unsigned int line,
+               std::string_view message),
+              (override));
+  MOCK_METHOD(void, NotifyTimeSync,
+              (std::span<const NT_Listener> handles, unsigned int flags,
+               int64_t serverTimeOffset, int64_t rtt2, bool valid),
+              (override));
+};
+
+}  // namespace nt
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/MockLogger.h b/third_party/allwpilib/ntcore/src/test/native/cpp/MockLogger.h
new file mode 100644
index 0000000..f20a12f
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/test/native/cpp/MockLogger.h
@@ -0,0 +1,24 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <wpi/Logger.h>
+
+#include "gmock/gmock.h"
+
+namespace wpi {
+
+class MockLogger : public Logger,
+                   public ::testing::MockFunction<void(
+                       unsigned int level, std::string_view file,
+                       unsigned int line, std::string_view msg)> {
+ public:
+  MockLogger() {
+    SetLogger([this](unsigned int level, const char* file, unsigned int line,
+                     const char* msg) { Call(level, file, line, msg); });
+  }
+};
+
+}  // namespace wpi
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/MockNetworkConnection.h b/third_party/allwpilib/ntcore/src/test/native/cpp/MockNetworkConnection.h
deleted file mode 100644
index be9c2c6..0000000
--- a/third_party/allwpilib/ntcore/src/test/native/cpp/MockNetworkConnection.h
+++ /dev/null
@@ -1,31 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef NTCORE_MOCKNETWORKCONNECTION_H_
-#define NTCORE_MOCKNETWORKCONNECTION_H_
-
-#include <memory>
-
-#include "INetworkConnection.h"
-#include "gmock/gmock.h"
-
-namespace nt {
-
-class MockNetworkConnection : public INetworkConnection {
- public:
-  MOCK_CONST_METHOD0(info, ConnectionInfo());
-
-  MOCK_METHOD1(QueueOutgoing, void(std::shared_ptr<Message> msg));
-  MOCK_METHOD1(PostOutgoing, void(bool keep_alive));
-
-  MOCK_CONST_METHOD0(proto_rev, unsigned int());
-  MOCK_METHOD1(set_proto_rev, void(unsigned int proto_rev));
-
-  MOCK_CONST_METHOD0(state, State());
-  MOCK_METHOD1(set_state, void(State state));
-};
-
-}  // namespace nt
-
-#endif  // NTCORE_MOCKNETWORKCONNECTION_H_
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/MockRpcServer.h b/third_party/allwpilib/ntcore/src/test/native/cpp/MockRpcServer.h
deleted file mode 100644
index be9e512..0000000
--- a/third_party/allwpilib/ntcore/src/test/native/cpp/MockRpcServer.h
+++ /dev/null
@@ -1,26 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef NTCORE_MOCKRPCSERVER_H_
-#define NTCORE_MOCKRPCSERVER_H_
-
-#include "IRpcServer.h"
-#include "gmock/gmock.h"
-
-namespace nt {
-
-class MockRpcServer : public IRpcServer {
- public:
-  MOCK_METHOD0(Start, void());
-  MOCK_METHOD1(RemoveRpc, void(unsigned int rpc_uid));
-  MOCK_METHOD7(ProcessRpc,
-               void(unsigned int local_id, unsigned int call_uid,
-                    std::string_view name, std::string_view params,
-                    const ConnectionInfo& conn, SendResponseFunc send_response,
-                    unsigned int rpc_uid));
-};
-
-}  // namespace nt
-
-#endif  // NTCORE_MOCKRPCSERVER_H_
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/NetworkTableTest.cpp b/third_party/allwpilib/ntcore/src/test/native/cpp/NetworkTableTest.cpp
index 73c4786..aa28afd 100644
--- a/third_party/allwpilib/ntcore/src/test/native/cpp/NetworkTableTest.cpp
+++ b/third_party/allwpilib/ntcore/src/test/native/cpp/NetworkTableTest.cpp
@@ -89,3 +89,15 @@
   ASSERT_TRUE(inst.GetEntry("/testkey").Exists());
   nt::NetworkTableInstance::Destroy(inst);
 }
+
+TEST_F(NetworkTableTest, ResetInstance) {
+  auto inst = nt::NetworkTableInstance::Create();
+  auto nt = inst.GetTable("containskey");
+  ASSERT_FALSE(nt->ContainsKey("testkey"));
+  nt->PutNumber("testkey", 5);
+  ASSERT_TRUE(nt->ContainsKey("testkey"));
+  ASSERT_TRUE(inst.GetEntry("/containskey/testkey").Exists());
+  nt::ResetInstance(inst.GetHandle());
+  ASSERT_FALSE(nt->ContainsKey("testkey"));
+  nt::NetworkTableInstance::Destroy(inst);
+}
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/PubSubOptionsMatcher.cpp b/third_party/allwpilib/ntcore/src/test/native/cpp/PubSubOptionsMatcher.cpp
new file mode 100644
index 0000000..3437a91
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/test/native/cpp/PubSubOptionsMatcher.cpp
@@ -0,0 +1,43 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "PubSubOptionsMatcher.h"
+
+#include "TestPrinters.h"
+
+namespace nt {
+
+bool PubSubOptionsMatcher::MatchAndExplain(
+    const PubSubOptionsImpl& val,
+    ::testing::MatchResultListener* listener) const {
+  bool match = true;
+  if (val.periodicMs != good.periodicMs) {
+    *listener << "periodic mismatch ";
+    match = false;
+  }
+  if (val.pollStorage != good.pollStorage) {
+    *listener << "pollStorage mismatch ";
+    match = false;
+  }
+  if (val.sendAll != good.sendAll) {
+    *listener << "sendAll mismatch ";
+    match = false;
+  }
+  if (val.keepDuplicates != good.keepDuplicates) {
+    *listener << "keepDuplicates mismatch ";
+    match = false;
+  }
+  return match;
+}
+
+void PubSubOptionsMatcher::DescribeTo(::std::ostream* os) const {
+  PrintTo(good, os);
+}
+
+void PubSubOptionsMatcher::DescribeNegationTo(::std::ostream* os) const {
+  *os << "is not equal to ";
+  PrintTo(good, os);
+}
+
+}  // namespace nt
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/PubSubOptionsMatcher.h b/third_party/allwpilib/ntcore/src/test/native/cpp/PubSubOptionsMatcher.h
new file mode 100644
index 0000000..925f17d
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/test/native/cpp/PubSubOptionsMatcher.h
@@ -0,0 +1,35 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <ostream>
+#include <utility>
+
+#include "PubSubOptions.h"
+#include "gmock/gmock.h"
+
+namespace nt {
+
+class PubSubOptionsMatcher
+    : public ::testing::MatcherInterface<const PubSubOptionsImpl&> {
+ public:
+  explicit PubSubOptionsMatcher(PubSubOptionsImpl good)
+      : good{std::move(good)} {}
+
+  bool MatchAndExplain(const PubSubOptionsImpl& val,
+                       ::testing::MatchResultListener* listener) const override;
+  void DescribeTo(::std::ostream* os) const override;
+  void DescribeNegationTo(::std::ostream* os) const override;
+
+ private:
+  PubSubOptionsImpl good;
+};
+
+inline ::testing::Matcher<const PubSubOptionsImpl&> PubSubOptionsEq(
+    PubSubOptionsImpl good) {
+  return ::testing::MakeMatcher(new PubSubOptionsMatcher(std::move(good)));
+}
+
+}  // namespace nt
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/SpanMatcher.h b/third_party/allwpilib/ntcore/src/test/native/cpp/SpanMatcher.h
new file mode 100644
index 0000000..9973c03
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/test/native/cpp/SpanMatcher.h
@@ -0,0 +1,72 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <algorithm>
+#include <initializer_list>
+#include <memory>
+#include <ostream>
+#include <span>
+#include <type_traits>
+#include <utility>
+#include <vector>
+
+#include "TestPrinters.h"
+#include "gmock/gmock.h"
+
+namespace wpi {
+
+template <typename T>
+class SpanMatcher : public ::testing::MatcherInterface<std::span<T>> {
+ public:
+  explicit SpanMatcher(std::span<T> good_) : good{good_.begin(), good_.end()} {}
+
+  bool MatchAndExplain(std::span<T> val,
+                       ::testing::MatchResultListener* listener) const override;
+  void DescribeTo(::std::ostream* os) const override;
+  void DescribeNegationTo(::std::ostream* os) const override;
+
+ private:
+  std::vector<std::remove_cv_t<T>> good;
+};
+
+template <typename T>
+inline ::testing::Matcher<std::span<const T>> SpanEq(std::span<const T> good) {
+  return ::testing::MakeMatcher(new SpanMatcher(good));
+}
+
+template <typename T>
+inline ::testing::Matcher<std::span<const T>> SpanEq(
+    std::initializer_list<const T> good) {
+  return ::testing::MakeMatcher(
+      new SpanMatcher<const T>({good.begin(), good.end()}));
+}
+
+template <typename T>
+bool SpanMatcher<T>::MatchAndExplain(
+    std::span<T> val, ::testing::MatchResultListener* listener) const {
+  if (val.size() != good.size() ||
+      !std::equal(val.begin(), val.end(), good.begin())) {
+    return false;
+  }
+  return true;
+}
+
+template <typename T>
+void SpanMatcher<T>::DescribeTo(::std::ostream* os) const {
+  PrintTo(std::span<T>{good}, os);
+}
+
+template <typename T>
+void SpanMatcher<T>::DescribeNegationTo(::std::ostream* os) const {
+  *os << "is not equal to ";
+  PrintTo(std::span<T>{good}, os);
+}
+
+}  // namespace wpi
+
+inline std::span<const uint8_t> operator"" _us(const char* str, size_t len) {
+  return {reinterpret_cast<const uint8_t*>(str), len};
+}
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/StorageTest.cpp b/third_party/allwpilib/ntcore/src/test/native/cpp/StorageTest.cpp
deleted file mode 100644
index e1ee1c7..0000000
--- a/third_party/allwpilib/ntcore/src/test/native/cpp/StorageTest.cpp
+++ /dev/null
@@ -1,1003 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "StorageTest.h"
-
-#include <wpi/SmallString.h>
-#include <wpi/StringExtras.h>
-#include <wpi/raw_istream.h>
-#include <wpi/raw_ostream.h>
-
-#include "MessageMatcher.h"
-#include "MockNetworkConnection.h"
-#include "Storage.h"
-#include "TestPrinters.h"
-#include "ValueMatcher.h"
-#include "gmock/gmock.h"
-#include "gtest/gtest.h"
-
-using ::testing::_;
-using ::testing::AnyNumber;
-using ::testing::IsNull;
-using ::testing::Return;
-
-namespace nt {
-
-class StorageEmptyTest : public StorageTest,
-                         public ::testing::TestWithParam<bool> {
- public:
-  StorageEmptyTest() {
-    HookOutgoing(GetParam());
-    EXPECT_CALL(notifier, local_notifiers())
-        .Times(AnyNumber())
-        .WillRepeatedly(Return(true));
-  }
-};
-
-class StoragePopulateOneTest : public StorageEmptyTest {
- public:
-  StoragePopulateOneTest() {
-    EXPECT_CALL(dispatcher, QueueOutgoing(_, _, _)).Times(AnyNumber());
-    EXPECT_CALL(notifier, NotifyEntry(_, _, _, _, _)).Times(AnyNumber());
-    EXPECT_CALL(notifier, local_notifiers())
-        .Times(AnyNumber())
-        .WillRepeatedly(Return(false));
-    storage.SetEntryTypeValue("foo", Value::MakeBoolean(true));
-    ::testing::Mock::VerifyAndClearExpectations(&dispatcher);
-    ::testing::Mock::VerifyAndClearExpectations(&notifier);
-    EXPECT_CALL(notifier, local_notifiers())
-        .Times(AnyNumber())
-        .WillRepeatedly(Return(true));
-  }
-};
-
-class StoragePopulatedTest : public StorageEmptyTest {
- public:
-  StoragePopulatedTest() {
-    EXPECT_CALL(dispatcher, QueueOutgoing(_, _, _)).Times(AnyNumber());
-    EXPECT_CALL(notifier, NotifyEntry(_, _, _, _, _)).Times(AnyNumber());
-    EXPECT_CALL(notifier, local_notifiers())
-        .Times(AnyNumber())
-        .WillRepeatedly(Return(false));
-    storage.SetEntryTypeValue("foo", Value::MakeBoolean(true));
-    storage.SetEntryTypeValue("foo2", Value::MakeDouble(0.0));
-    storage.SetEntryTypeValue("bar", Value::MakeDouble(1.0));
-    storage.SetEntryTypeValue("bar2", Value::MakeBoolean(false));
-    ::testing::Mock::VerifyAndClearExpectations(&dispatcher);
-    ::testing::Mock::VerifyAndClearExpectations(&notifier);
-    EXPECT_CALL(notifier, local_notifiers())
-        .Times(AnyNumber())
-        .WillRepeatedly(Return(true));
-  }
-};
-
-class StoragePersistentTest : public StorageEmptyTest {
- public:
-  StoragePersistentTest() {
-    EXPECT_CALL(dispatcher, QueueOutgoing(_, _, _)).Times(AnyNumber());
-    EXPECT_CALL(notifier, NotifyEntry(_, _, _, _, _)).Times(AnyNumber());
-    EXPECT_CALL(notifier, local_notifiers())
-        .Times(AnyNumber())
-        .WillRepeatedly(Return(false));
-    storage.SetEntryTypeValue("boolean/true", Value::MakeBoolean(true));
-    storage.SetEntryTypeValue("boolean/false", Value::MakeBoolean(false));
-    storage.SetEntryTypeValue("double/neg", Value::MakeDouble(-1.5));
-    storage.SetEntryTypeValue("double/zero", Value::MakeDouble(0.0));
-    storage.SetEntryTypeValue("double/big", Value::MakeDouble(1.3e8));
-    storage.SetEntryTypeValue("string/empty", Value::MakeString(""));
-    storage.SetEntryTypeValue("string/normal", Value::MakeString("hello"));
-    storage.SetEntryTypeValue(
-        "string/special", Value::MakeString(std::string_view("\0\3\5\n", 4)));
-    storage.SetEntryTypeValue("string/quoted", Value::MakeString("\"a\""));
-    storage.SetEntryTypeValue("raw/empty", Value::MakeRaw(""));
-    storage.SetEntryTypeValue("raw/normal", Value::MakeRaw("hello"));
-    storage.SetEntryTypeValue("raw/special",
-                              Value::MakeRaw(std::string_view("\0\3\5\n", 4)));
-    storage.SetEntryTypeValue("booleanarr/empty",
-                              Value::MakeBooleanArray(std::vector<int>{}));
-    storage.SetEntryTypeValue("booleanarr/one",
-                              Value::MakeBooleanArray(std::vector<int>{1}));
-    storage.SetEntryTypeValue("booleanarr/two",
-                              Value::MakeBooleanArray(std::vector<int>{1, 0}));
-    storage.SetEntryTypeValue("doublearr/empty",
-                              Value::MakeDoubleArray(std::vector<double>{}));
-    storage.SetEntryTypeValue("doublearr/one",
-                              Value::MakeDoubleArray(std::vector<double>{0.5}));
-    storage.SetEntryTypeValue(
-        "doublearr/two",
-        Value::MakeDoubleArray(std::vector<double>{0.5, -0.25}));
-    storage.SetEntryTypeValue(
-        "stringarr/empty", Value::MakeStringArray(std::vector<std::string>{}));
-    storage.SetEntryTypeValue(
-        "stringarr/one",
-        Value::MakeStringArray(std::vector<std::string>{"hello"}));
-    storage.SetEntryTypeValue(
-        "stringarr/two",
-        Value::MakeStringArray(std::vector<std::string>{"hello", "world\n"}));
-    storage.SetEntryTypeValue(std::string_view("\0\3\5\n", 4),
-                              Value::MakeBoolean(true));
-    storage.SetEntryTypeValue("=", Value::MakeBoolean(true));
-    ::testing::Mock::VerifyAndClearExpectations(&dispatcher);
-    ::testing::Mock::VerifyAndClearExpectations(&notifier);
-    EXPECT_CALL(notifier, local_notifiers())
-        .Times(AnyNumber())
-        .WillRepeatedly(Return(true));
-  }
-};
-
-class MockLoadWarn {
- public:
-  MOCK_METHOD2(Warn, void(size_t line, std::string_view msg));
-};
-
-TEST_P(StorageEmptyTest, Construct) {
-  EXPECT_TRUE(entries().empty());
-  EXPECT_TRUE(idmap().empty());
-}
-
-TEST_P(StorageEmptyTest, StorageEntryInit) {
-  auto entry = GetEntry("foo");
-  EXPECT_FALSE(entry->value);
-  EXPECT_EQ(0u, entry->flags);
-  EXPECT_EQ("foobar", entry->name);  // since GetEntry uses the tmp_entry.
-  EXPECT_EQ(0xffffu, entry->id);
-  EXPECT_EQ(SequenceNumber(), entry->seq_num);
-}
-
-TEST_P(StorageEmptyTest, GetEntryValueNotExist) {
-  EXPECT_FALSE(storage.GetEntryValue("foo"));
-  EXPECT_TRUE(entries().empty());
-  EXPECT_TRUE(idmap().empty());
-}
-
-TEST_P(StorageEmptyTest, GetEntryValueExist) {
-  auto value = Value::MakeBoolean(true);
-  EXPECT_CALL(dispatcher, QueueOutgoing(_, IsNull(), IsNull()));
-  EXPECT_CALL(notifier, NotifyEntry(_, _, _, _, _));
-  storage.SetEntryTypeValue("foo", value);
-  EXPECT_EQ(value, storage.GetEntryValue("foo"));
-}
-
-TEST_P(StorageEmptyTest, SetEntryTypeValueAssignNew) {
-  // brand new entry
-  auto value = Value::MakeBoolean(true);
-  // id assigned if server
-  EXPECT_CALL(dispatcher,
-              QueueOutgoing(MessageEq(Message::EntryAssign(
-                                "foo", GetParam() ? 0 : 0xffff, 1, value, 0)),
-                            IsNull(), IsNull()));
-  EXPECT_CALL(notifier, NotifyEntry(0, std::string_view("foo"), value,
-                                    NT_NOTIFY_NEW | NT_NOTIFY_LOCAL, UINT_MAX));
-
-  storage.SetEntryTypeValue("foo", value);
-  EXPECT_EQ(value, GetEntry("foo")->value);
-  if (GetParam()) {
-    ASSERT_EQ(1u, idmap().size());
-    EXPECT_EQ(value, idmap()[0]->value);
-  } else {
-    EXPECT_TRUE(idmap().empty());
-  }
-}
-
-TEST_P(StoragePopulateOneTest, SetEntryTypeValueAssignTypeChange) {
-  // update with different type results in assignment message
-  auto value = Value::MakeDouble(0.0);
-
-  // id assigned if server; seq_num incremented
-  EXPECT_CALL(dispatcher,
-              QueueOutgoing(MessageEq(Message::EntryAssign(
-                                "foo", GetParam() ? 0 : 0xffff, 2, value, 0)),
-                            IsNull(), IsNull()));
-  EXPECT_CALL(notifier,
-              NotifyEntry(0, std::string_view("foo"), value,
-                          NT_NOTIFY_UPDATE | NT_NOTIFY_LOCAL, UINT_MAX));
-
-  storage.SetEntryTypeValue("foo", value);
-  EXPECT_EQ(value, GetEntry("foo")->value);
-}
-
-TEST_P(StoragePopulateOneTest, SetEntryTypeValueEqualValue) {
-  // update with same type and same value: change value contents but no update
-  // message is issued (minimizing bandwidth usage)
-  auto value = Value::MakeBoolean(true);
-  storage.SetEntryTypeValue("foo", value);
-  EXPECT_EQ(value, GetEntry("foo")->value);
-}
-
-TEST_P(StoragePopulatedTest, SetEntryTypeValueDifferentValue) {
-  // update with same type and different value results in value update message
-  auto value = Value::MakeDouble(1.0);
-
-  // client shouldn't send an update as id not assigned yet
-  if (GetParam()) {
-    // id assigned if server; seq_num incremented
-    EXPECT_CALL(dispatcher,
-                QueueOutgoing(MessageEq(Message::EntryUpdate(1, 2, value)),
-                              IsNull(), IsNull()));
-  }
-  EXPECT_CALL(notifier,
-              NotifyEntry(1, std::string_view("foo2"), value,
-                          NT_NOTIFY_UPDATE | NT_NOTIFY_LOCAL, UINT_MAX));
-  storage.SetEntryTypeValue("foo2", value);
-  EXPECT_EQ(value, GetEntry("foo2")->value);
-
-  if (!GetParam()) {
-    // seq_num should still be incremented
-    EXPECT_EQ(2u, GetEntry("foo2")->seq_num.value());
-  }
-}
-
-TEST_P(StorageEmptyTest, SetEntryTypeValueEmptyName) {
-  auto value = Value::MakeBoolean(true);
-  storage.SetEntryTypeValue("", value);
-  EXPECT_TRUE(entries().empty());
-  EXPECT_TRUE(idmap().empty());
-}
-
-TEST_P(StorageEmptyTest, SetEntryTypeValueEmptyValue) {
-  storage.SetEntryTypeValue("foo", nullptr);
-  EXPECT_TRUE(entries().empty());
-  EXPECT_TRUE(idmap().empty());
-}
-
-TEST_P(StorageEmptyTest, SetEntryValueAssignNew) {
-  // brand new entry
-  auto value = Value::MakeBoolean(true);
-
-  // id assigned if server
-  EXPECT_CALL(dispatcher,
-              QueueOutgoing(MessageEq(Message::EntryAssign(
-                                "foo", GetParam() ? 0 : 0xffff, 1, value, 0)),
-                            IsNull(), IsNull()));
-  EXPECT_CALL(notifier, NotifyEntry(0, std::string_view("foo"), value,
-                                    NT_NOTIFY_NEW | NT_NOTIFY_LOCAL, UINT_MAX));
-
-  EXPECT_TRUE(storage.SetEntryValue("foo", value));
-  EXPECT_EQ(value, GetEntry("foo")->value);
-}
-
-TEST_P(StoragePopulateOneTest, SetEntryValueAssignTypeChange) {
-  // update with different type results in error and no message or notification
-  auto value = Value::MakeDouble(0.0);
-  EXPECT_FALSE(storage.SetEntryValue("foo", value));
-  auto entry = GetEntry("foo");
-  EXPECT_NE(value, entry->value);
-}
-
-TEST_P(StoragePopulateOneTest, SetEntryValueEqualValue) {
-  // update with same type and same value: change value contents but no update
-  // message is issued (minimizing bandwidth usage)
-  auto value = Value::MakeBoolean(true);
-  EXPECT_TRUE(storage.SetEntryValue("foo", value));
-  auto entry = GetEntry("foo");
-  EXPECT_EQ(value, entry->value);
-}
-
-TEST_P(StoragePopulatedTest, SetEntryValueDifferentValue) {
-  // update with same type and different value results in value update message
-  auto value = Value::MakeDouble(1.0);
-
-  // client shouldn't send an update as id not assigned yet
-  if (GetParam()) {
-    // id assigned if server; seq_num incremented
-    EXPECT_CALL(dispatcher,
-                QueueOutgoing(MessageEq(Message::EntryUpdate(1, 2, value)),
-                              IsNull(), IsNull()));
-  }
-  EXPECT_CALL(notifier,
-              NotifyEntry(1, std::string_view("foo2"), value,
-                          NT_NOTIFY_UPDATE | NT_NOTIFY_LOCAL, UINT_MAX));
-
-  EXPECT_TRUE(storage.SetEntryValue("foo2", value));
-  auto entry = GetEntry("foo2");
-  EXPECT_EQ(value, entry->value);
-
-  if (!GetParam()) {
-    // seq_num should still be incremented
-    EXPECT_EQ(2u, GetEntry("foo2")->seq_num.value());
-  }
-}
-
-TEST_P(StorageEmptyTest, SetEntryValueEmptyName) {
-  auto value = Value::MakeBoolean(true);
-  EXPECT_TRUE(storage.SetEntryValue("", value));
-  EXPECT_TRUE(entries().empty());
-  EXPECT_TRUE(idmap().empty());
-}
-
-TEST_P(StorageEmptyTest, SetEntryValueEmptyValue) {
-  EXPECT_TRUE(storage.SetEntryValue("foo", nullptr));
-  EXPECT_TRUE(entries().empty());
-  EXPECT_TRUE(idmap().empty());
-}
-
-TEST_P(StorageEmptyTest, SetDefaultEntryAssignNew) {
-  // brand new entry
-  auto value = Value::MakeBoolean(true);
-
-  // id assigned if server
-  EXPECT_CALL(dispatcher,
-              QueueOutgoing(MessageEq(Message::EntryAssign(
-                                "foo", GetParam() ? 0 : 0xffff, 1, value, 0)),
-                            IsNull(), IsNull()));
-  EXPECT_CALL(notifier, NotifyEntry(0, std::string_view("foo"), value,
-                                    NT_NOTIFY_NEW | NT_NOTIFY_LOCAL, UINT_MAX));
-
-  auto ret_val = storage.SetDefaultEntryValue("foo", value);
-  EXPECT_TRUE(ret_val);
-  EXPECT_EQ(value, GetEntry("foo")->value);
-}
-
-TEST_P(StoragePopulateOneTest, SetDefaultEntryExistsSameType) {
-  // existing entry
-  auto value = Value::MakeBoolean(true);
-  auto ret_val = storage.SetDefaultEntryValue("foo", value);
-  EXPECT_TRUE(ret_val);
-  EXPECT_NE(value, GetEntry("foo")->value);
-}
-
-TEST_P(StoragePopulateOneTest, SetDefaultEntryExistsDifferentType) {
-  // existing entry is boolean
-  auto value = Value::MakeDouble(2.0);
-  auto ret_val = storage.SetDefaultEntryValue("foo", value);
-  EXPECT_FALSE(ret_val);
-  // should not have updated value in table if it already existed.
-  EXPECT_NE(value, GetEntry("foo")->value);
-}
-
-TEST_P(StorageEmptyTest, SetDefaultEntryEmptyName) {
-  auto value = Value::MakeBoolean(true);
-  auto ret_val = storage.SetDefaultEntryValue("", value);
-  EXPECT_FALSE(ret_val);
-  auto entry = GetEntry("foo");
-  EXPECT_FALSE(entry->value);
-  EXPECT_EQ(0u, entry->flags);
-  EXPECT_EQ("foobar", entry->name);  // since GetEntry uses the tmp_entry.
-  EXPECT_EQ(0xffffu, entry->id);
-  EXPECT_EQ(SequenceNumber(), entry->seq_num);
-  EXPECT_TRUE(entries().empty());
-  EXPECT_TRUE(idmap().empty());
-}
-
-TEST_P(StorageEmptyTest, SetDefaultEntryEmptyValue) {
-  auto value = Value::MakeBoolean(true);
-  auto ret_val = storage.SetDefaultEntryValue("", nullptr);
-  EXPECT_FALSE(ret_val);
-  auto entry = GetEntry("foo");
-  EXPECT_FALSE(entry->value);
-  EXPECT_EQ(0u, entry->flags);
-  EXPECT_EQ("foobar", entry->name);  // since GetEntry uses the tmp_entry.
-  EXPECT_EQ(0xffffu, entry->id);
-  EXPECT_EQ(SequenceNumber(), entry->seq_num);
-  EXPECT_TRUE(entries().empty());
-  EXPECT_TRUE(idmap().empty());
-}
-
-TEST_P(StoragePopulatedTest, SetDefaultEntryEmptyName) {
-  auto value = Value::MakeBoolean(true);
-  auto ret_val = storage.SetDefaultEntryValue("", value);
-  EXPECT_FALSE(ret_val);
-  // assert that no entries get added
-  EXPECT_EQ(4u, entries().size());
-  if (GetParam()) {
-    EXPECT_EQ(4u, idmap().size());
-  } else {
-    EXPECT_EQ(0u, idmap().size());
-  }
-}
-
-TEST_P(StoragePopulatedTest, SetDefaultEntryEmptyValue) {
-  auto value = Value::MakeBoolean(true);
-  auto ret_val = storage.SetDefaultEntryValue("", nullptr);
-  EXPECT_FALSE(ret_val);
-  // assert that no entries get added
-  EXPECT_EQ(4u, entries().size());
-  if (GetParam()) {
-    EXPECT_EQ(4u, idmap().size());
-  } else {
-    EXPECT_EQ(0u, idmap().size());
-  }
-}
-
-TEST_P(StorageEmptyTest, SetEntryFlagsNew) {
-  // flags setting doesn't create an entry
-  storage.SetEntryFlags("foo", 0u);
-  EXPECT_TRUE(entries().empty());
-  EXPECT_TRUE(idmap().empty());
-}
-
-TEST_P(StoragePopulateOneTest, SetEntryFlagsEqualValue) {
-  // update with same value: no update message is issued (minimizing bandwidth
-  // usage)
-  storage.SetEntryFlags("foo", 0u);
-  auto entry = GetEntry("foo");
-  EXPECT_EQ(0u, entry->flags);
-}
-
-TEST_P(StoragePopulatedTest, SetEntryFlagsDifferentValue) {
-  // update with different value results in flags update message
-  // client shouldn't send an update as id not assigned yet
-  if (GetParam()) {
-    // id assigned as this is the server
-    EXPECT_CALL(dispatcher, QueueOutgoing(MessageEq(Message::FlagsUpdate(1, 1)),
-                                          IsNull(), IsNull()));
-  }
-  EXPECT_CALL(notifier,
-              NotifyEntry(1, std::string_view("foo2"), _,
-                          NT_NOTIFY_FLAGS | NT_NOTIFY_LOCAL, UINT_MAX));
-  storage.SetEntryFlags("foo2", 1u);
-  EXPECT_EQ(1u, GetEntry("foo2")->flags);
-}
-
-TEST_P(StorageEmptyTest, SetEntryFlagsEmptyName) {
-  storage.SetEntryFlags("", 0u);
-  EXPECT_TRUE(entries().empty());
-  EXPECT_TRUE(idmap().empty());
-}
-
-TEST_P(StorageEmptyTest, GetEntryFlagsNotExist) {
-  EXPECT_EQ(0u, storage.GetEntryFlags("foo"));
-  EXPECT_TRUE(entries().empty());
-  EXPECT_TRUE(idmap().empty());
-}
-
-TEST_P(StoragePopulateOneTest, GetEntryFlagsExist) {
-  EXPECT_CALL(dispatcher, QueueOutgoing(_, _, _)).Times(AnyNumber());
-  EXPECT_CALL(notifier, NotifyEntry(_, _, _, _, _));
-  storage.SetEntryFlags("foo", 1u);
-  ::testing::Mock::VerifyAndClearExpectations(&dispatcher);
-  EXPECT_EQ(1u, storage.GetEntryFlags("foo"));
-}
-
-TEST_P(StorageEmptyTest, DeleteEntryNotExist) {
-  storage.DeleteEntry("foo");
-}
-
-TEST_P(StoragePopulatedTest, DeleteEntryExist) {
-  // client shouldn't send an update as id not assigned yet
-  if (GetParam()) {
-    // id assigned as this is the server
-    EXPECT_CALL(dispatcher, QueueOutgoing(MessageEq(Message::EntryDelete(1)),
-                                          IsNull(), IsNull()));
-  }
-  EXPECT_CALL(
-      notifier,
-      NotifyEntry(1, std::string_view("foo2"), ValueEq(Value::MakeDouble(0)),
-                  NT_NOTIFY_DELETE | NT_NOTIFY_LOCAL, UINT_MAX));
-
-  storage.DeleteEntry("foo2");
-  ASSERT_EQ(1u, entries().count("foo2"));
-  EXPECT_EQ(nullptr, entries()["foo2"]->value);
-  EXPECT_EQ(0xffffu, entries()["foo2"]->id);
-  EXPECT_FALSE(entries()["foo2"]->local_write);
-  if (GetParam()) {
-    ASSERT_TRUE(idmap().size() >= 2);
-    EXPECT_FALSE(idmap()[1]);
-  }
-}
-
-TEST_P(StorageEmptyTest, DeleteAllEntriesEmpty) {
-  storage.DeleteAllEntries();
-  ASSERT_TRUE(entries().empty());
-}
-
-TEST_P(StoragePopulatedTest, DeleteAllEntries) {
-  EXPECT_CALL(dispatcher, QueueOutgoing(MessageEq(Message::ClearEntries()),
-                                        IsNull(), IsNull()));
-  EXPECT_CALL(notifier, NotifyEntry(_, _, _, NT_NOTIFY_DELETE | NT_NOTIFY_LOCAL,
-                                    UINT_MAX))
-      .Times(4);
-
-  storage.DeleteAllEntries();
-  ASSERT_EQ(1u, entries().count("foo2"));
-  EXPECT_EQ(nullptr, entries()["foo2"]->value);
-}
-
-TEST_P(StoragePopulatedTest, DeleteAllEntriesPersistent) {
-  GetEntry("foo2")->flags = NT_PERSISTENT;
-
-  EXPECT_CALL(dispatcher, QueueOutgoing(MessageEq(Message::ClearEntries()),
-                                        IsNull(), IsNull()));
-  EXPECT_CALL(notifier, NotifyEntry(_, _, _, NT_NOTIFY_DELETE | NT_NOTIFY_LOCAL,
-                                    UINT_MAX))
-      .Times(3);
-
-  storage.DeleteAllEntries();
-  ASSERT_EQ(1u, entries().count("foo2"));
-  EXPECT_NE(nullptr, entries()["foo2"]->value);
-}
-
-TEST_P(StoragePopulatedTest, GetEntryInfoAll) {
-  auto info = storage.GetEntryInfo(0, "", 0u);
-  ASSERT_EQ(4u, info.size());
-}
-
-TEST_P(StoragePopulatedTest, GetEntryInfoPrefix) {
-  auto info = storage.GetEntryInfo(0, "foo", 0u);
-  ASSERT_EQ(2u, info.size());
-  if (info[0].name == "foo") {
-    EXPECT_EQ("foo", info[0].name);
-    EXPECT_EQ(NT_BOOLEAN, info[0].type);
-    EXPECT_EQ("foo2", info[1].name);
-    EXPECT_EQ(NT_DOUBLE, info[1].type);
-  } else {
-    EXPECT_EQ("foo2", info[0].name);
-    EXPECT_EQ(NT_DOUBLE, info[0].type);
-    EXPECT_EQ("foo", info[1].name);
-    EXPECT_EQ(NT_BOOLEAN, info[1].type);
-  }
-}
-
-TEST_P(StoragePopulatedTest, GetEntryInfoTypes) {
-  auto info = storage.GetEntryInfo(0, "", NT_DOUBLE);
-  ASSERT_EQ(2u, info.size());
-  EXPECT_EQ(NT_DOUBLE, info[0].type);
-  EXPECT_EQ(NT_DOUBLE, info[1].type);
-  if (info[0].name == "foo2") {
-    EXPECT_EQ("foo2", info[0].name);
-    EXPECT_EQ("bar", info[1].name);
-  } else {
-    EXPECT_EQ("bar", info[0].name);
-    EXPECT_EQ("foo2", info[1].name);
-  }
-}
-
-TEST_P(StoragePopulatedTest, GetEntryInfoPrefixTypes) {
-  auto info = storage.GetEntryInfo(0, "bar", NT_BOOLEAN);
-  ASSERT_EQ(1u, info.size());
-  EXPECT_EQ("bar2", info[0].name);
-  EXPECT_EQ(NT_BOOLEAN, info[0].type);
-}
-
-TEST_P(StoragePersistentTest, SavePersistentEmpty) {
-  wpi::SmallString<256> buf;
-  wpi::raw_svector_ostream oss(buf);
-  storage.SavePersistent(oss, false);
-  ASSERT_EQ("[NetworkTables Storage 3.0]\n", oss.str());
-}
-
-TEST_P(StoragePersistentTest, SavePersistent) {
-  for (auto& i : entries()) {
-    i.getValue()->flags = NT_PERSISTENT;
-  }
-  wpi::SmallString<256> buf;
-  wpi::raw_svector_ostream oss(buf);
-  storage.SavePersistent(oss, false);
-  std::string_view out = oss.str();
-  // std::fputs(out.c_str(), stderr);
-  std::string_view line, rem = out;
-  std::tie(line, rem) = wpi::split(rem, '\n');
-  ASSERT_EQ("[NetworkTables Storage 3.0]", line);
-  std::tie(line, rem) = wpi::split(rem, '\n');
-  ASSERT_EQ("boolean \"\\x00\\x03\\x05\\n\"=true", line);
-  std::tie(line, rem) = wpi::split(rem, '\n');
-  ASSERT_EQ("boolean \"\\x3D\"=true", line);
-  std::tie(line, rem) = wpi::split(rem, '\n');
-  ASSERT_EQ("boolean \"boolean/false\"=false", line);
-  std::tie(line, rem) = wpi::split(rem, '\n');
-  ASSERT_EQ("boolean \"boolean/true\"=true", line);
-  std::tie(line, rem) = wpi::split(rem, '\n');
-  ASSERT_EQ("array boolean \"booleanarr/empty\"=", line);
-  std::tie(line, rem) = wpi::split(rem, '\n');
-  ASSERT_EQ("array boolean \"booleanarr/one\"=true", line);
-  std::tie(line, rem) = wpi::split(rem, '\n');
-  ASSERT_EQ("array boolean \"booleanarr/two\"=true,false", line);
-  std::tie(line, rem) = wpi::split(rem, '\n');
-  ASSERT_EQ("double \"double/big\"=1.3e+08", line);
-  std::tie(line, rem) = wpi::split(rem, '\n');
-  ASSERT_EQ("double \"double/neg\"=-1.5", line);
-  std::tie(line, rem) = wpi::split(rem, '\n');
-  ASSERT_EQ("double \"double/zero\"=0", line);
-  std::tie(line, rem) = wpi::split(rem, '\n');
-  ASSERT_EQ("array double \"doublearr/empty\"=", line);
-  std::tie(line, rem) = wpi::split(rem, '\n');
-  ASSERT_EQ("array double \"doublearr/one\"=0.5", line);
-  std::tie(line, rem) = wpi::split(rem, '\n');
-  ASSERT_EQ("array double \"doublearr/two\"=0.5,-0.25", line);
-  std::tie(line, rem) = wpi::split(rem, '\n');
-  ASSERT_EQ("raw \"raw/empty\"=", line);
-  std::tie(line, rem) = wpi::split(rem, '\n');
-  ASSERT_EQ("raw \"raw/normal\"=aGVsbG8=", line);
-  std::tie(line, rem) = wpi::split(rem, '\n');
-  ASSERT_EQ("raw \"raw/special\"=AAMFCg==", line);
-  std::tie(line, rem) = wpi::split(rem, '\n');
-  ASSERT_EQ("string \"string/empty\"=\"\"", line);
-  std::tie(line, rem) = wpi::split(rem, '\n');
-  ASSERT_EQ("string \"string/normal\"=\"hello\"", line);
-  std::tie(line, rem) = wpi::split(rem, '\n');
-  ASSERT_EQ("string \"string/quoted\"=\"\\\"a\\\"\"", line);
-  std::tie(line, rem) = wpi::split(rem, '\n');
-  ASSERT_EQ("string \"string/special\"=\"\\x00\\x03\\x05\\n\"", line);
-  std::tie(line, rem) = wpi::split(rem, '\n');
-  ASSERT_EQ("array string \"stringarr/empty\"=", line);
-  std::tie(line, rem) = wpi::split(rem, '\n');
-  ASSERT_EQ("array string \"stringarr/one\"=\"hello\"", line);
-  std::tie(line, rem) = wpi::split(rem, '\n');
-  ASSERT_EQ("array string \"stringarr/two\"=\"hello\",\"world\\n\"", line);
-  std::tie(line, rem) = wpi::split(rem, '\n');
-  ASSERT_EQ("", line);
-}
-
-TEST_P(StorageEmptyTest, LoadPersistentBadHeader) {
-  MockLoadWarn warn;
-  auto warn_func = [&](size_t line, const char* msg) { warn.Warn(line, msg); };
-
-  wpi::raw_mem_istream iss("");
-  EXPECT_CALL(
-      warn,
-      Warn(1, std::string_view("header line mismatch, ignoring rest of file")));
-  EXPECT_FALSE(storage.LoadEntries(iss, "", true, warn_func));
-
-  wpi::raw_mem_istream iss2("[NetworkTables");
-  EXPECT_CALL(
-      warn,
-      Warn(1, std::string_view("header line mismatch, ignoring rest of file")));
-
-  EXPECT_FALSE(storage.LoadEntries(iss2, "", true, warn_func));
-  EXPECT_TRUE(entries().empty());
-  EXPECT_TRUE(idmap().empty());
-}
-
-TEST_P(StorageEmptyTest, LoadPersistentCommentHeader) {
-  MockLoadWarn warn;
-  auto warn_func = [&](size_t line, const char* msg) { warn.Warn(line, msg); };
-
-  wpi::raw_mem_istream iss(
-      "\n; comment\n# comment\n[NetworkTables Storage 3.0]\n");
-  EXPECT_TRUE(storage.LoadEntries(iss, "", true, warn_func));
-  EXPECT_TRUE(entries().empty());
-  EXPECT_TRUE(idmap().empty());
-}
-
-TEST_P(StorageEmptyTest, LoadPersistentEmptyName) {
-  MockLoadWarn warn;
-  auto warn_func = [&](size_t line, const char* msg) { warn.Warn(line, msg); };
-
-  wpi::raw_mem_istream iss("[NetworkTables Storage 3.0]\nboolean \"\"=true\n");
-  EXPECT_TRUE(storage.LoadEntries(iss, "", true, warn_func));
-  EXPECT_TRUE(entries().empty());
-  EXPECT_TRUE(idmap().empty());
-}
-
-TEST_P(StorageEmptyTest, LoadPersistentAssign) {
-  MockLoadWarn warn;
-  auto warn_func = [&](size_t line, const char* msg) { warn.Warn(line, msg); };
-
-  auto value = Value::MakeBoolean(true);
-
-  // id assigned if server
-  EXPECT_CALL(dispatcher, QueueOutgoing(MessageEq(Message::EntryAssign(
-                                            "foo", GetParam() ? 0 : 0xffff, 1,
-                                            value, NT_PERSISTENT)),
-                                        IsNull(), IsNull()));
-  EXPECT_CALL(notifier, NotifyEntry(0, std::string_view("foo"),
-                                    ValueEq(Value::MakeBoolean(true)),
-                                    NT_NOTIFY_NEW | NT_NOTIFY_LOCAL, UINT_MAX));
-
-  wpi::raw_mem_istream iss(
-      "[NetworkTables Storage 3.0]\nboolean \"foo\"=true\n");
-  EXPECT_TRUE(storage.LoadEntries(iss, "", true, warn_func));
-  auto entry = GetEntry("foo");
-  EXPECT_EQ(*value, *entry->value);
-  EXPECT_EQ(NT_PERSISTENT, entry->flags);
-}
-
-TEST_P(StoragePopulatedTest, LoadPersistentUpdateFlags) {
-  MockLoadWarn warn;
-  auto warn_func = [&](size_t line, const char* msg) { warn.Warn(line, msg); };
-
-  // client shouldn't send an update as id not assigned yet
-  if (GetParam()) {
-    // id assigned as this is server
-    EXPECT_CALL(dispatcher,
-                QueueOutgoing(MessageEq(Message::FlagsUpdate(1, NT_PERSISTENT)),
-                              IsNull(), IsNull()));
-  }
-  EXPECT_CALL(
-      notifier,
-      NotifyEntry(1, std::string_view("foo2"), ValueEq(Value::MakeDouble(0)),
-                  NT_NOTIFY_FLAGS | NT_NOTIFY_LOCAL, UINT_MAX));
-
-  wpi::raw_mem_istream iss(
-      "[NetworkTables Storage 3.0]\ndouble \"foo2\"=0.0\n");
-  EXPECT_TRUE(storage.LoadEntries(iss, "", true, warn_func));
-  auto entry = GetEntry("foo2");
-  EXPECT_EQ(*Value::MakeDouble(0.0), *entry->value);
-  EXPECT_EQ(NT_PERSISTENT, entry->flags);
-}
-
-TEST_P(StoragePopulatedTest, LoadPersistentUpdateValue) {
-  MockLoadWarn warn;
-  auto warn_func = [&](size_t line, const char* msg) { warn.Warn(line, msg); };
-
-  GetEntry("foo2")->flags = NT_PERSISTENT;
-
-  auto value = Value::MakeDouble(1.0);
-
-  // client shouldn't send an update as id not assigned yet
-  if (GetParam()) {
-    // id assigned as this is the server; seq_num incremented
-    EXPECT_CALL(dispatcher,
-                QueueOutgoing(MessageEq(Message::EntryUpdate(1, 2, value)),
-                              IsNull(), IsNull()));
-  }
-  EXPECT_CALL(
-      notifier,
-      NotifyEntry(1, std::string_view("foo2"), ValueEq(Value::MakeDouble(1)),
-                  NT_NOTIFY_UPDATE | NT_NOTIFY_LOCAL, UINT_MAX));
-
-  wpi::raw_mem_istream iss(
-      "[NetworkTables Storage 3.0]\ndouble \"foo2\"=1.0\n");
-  EXPECT_TRUE(storage.LoadEntries(iss, "", true, warn_func));
-  auto entry = GetEntry("foo2");
-  EXPECT_EQ(*value, *entry->value);
-  EXPECT_EQ(NT_PERSISTENT, entry->flags);
-
-  if (!GetParam()) {
-    // seq_num should still be incremented
-    EXPECT_EQ(2u, GetEntry("foo2")->seq_num.value());
-  }
-}
-
-TEST_P(StoragePopulatedTest, LoadPersistentUpdateValueFlags) {
-  MockLoadWarn warn;
-  auto warn_func = [&](size_t line, const char* msg) { warn.Warn(line, msg); };
-
-  auto value = Value::MakeDouble(1.0);
-
-  // client shouldn't send an update as id not assigned yet
-  if (GetParam()) {
-    // id assigned as this is the server; seq_num incremented
-    EXPECT_CALL(dispatcher,
-                QueueOutgoing(MessageEq(Message::EntryUpdate(1, 2, value)),
-                              IsNull(), IsNull()));
-    EXPECT_CALL(dispatcher,
-                QueueOutgoing(MessageEq(Message::FlagsUpdate(1, NT_PERSISTENT)),
-                              IsNull(), IsNull()));
-  }
-  EXPECT_CALL(
-      notifier,
-      NotifyEntry(1, std::string_view("foo2"), ValueEq(Value::MakeDouble(1)),
-                  NT_NOTIFY_FLAGS | NT_NOTIFY_UPDATE | NT_NOTIFY_LOCAL,
-                  UINT_MAX));
-
-  wpi::raw_mem_istream iss(
-      "[NetworkTables Storage 3.0]\ndouble \"foo2\"=1.0\n");
-  EXPECT_TRUE(storage.LoadEntries(iss, "", true, warn_func));
-  auto entry = GetEntry("foo2");
-  EXPECT_EQ(*value, *entry->value);
-  EXPECT_EQ(NT_PERSISTENT, entry->flags);
-
-  if (!GetParam()) {
-    // seq_num should still be incremented
-    EXPECT_EQ(2u, GetEntry("foo2")->seq_num.value());
-  }
-}
-
-TEST_P(StorageEmptyTest, LoadPersistent) {
-  MockLoadWarn warn;
-  auto warn_func = [&](size_t line, const char* msg) { warn.Warn(line, msg); };
-
-  std::string in = "[NetworkTables Storage 3.0]\n";
-  in += "boolean \"\\x00\\x03\\x05\\n\"=true\n";
-  in += "boolean \"\\x3D\"=true\n";
-  in += "boolean \"boolean/false\"=false\n";
-  in += "boolean \"boolean/true\"=true\n";
-  in += "array boolean \"booleanarr/empty\"=\n";
-  in += "array boolean \"booleanarr/one\"=true\n";
-  in += "array boolean \"booleanarr/two\"=true,false\n";
-  in += "double \"double/big\"=1.3e+08\n";
-  in += "double \"double/neg\"=-1.5\n";
-  in += "double \"double/zero\"=0\n";
-  in += "array double \"doublearr/empty\"=\n";
-  in += "array double \"doublearr/one\"=0.5\n";
-  in += "array double \"doublearr/two\"=0.5,-0.25\n";
-  in += "raw \"raw/empty\"=\n";
-  in += "raw \"raw/normal\"=aGVsbG8=\n";
-  in += "raw \"raw/special\"=AAMFCg==\n";
-  in += "string \"string/empty\"=\"\"\n";
-  in += "string \"string/normal\"=\"hello\"\n";
-  in += "string \"string/special\"=\"\\x00\\x03\\x05\\n\"\n";
-  in += "string \"string/quoted\"=\"\\\"a\\\"\"\n";
-  in += "array string \"stringarr/empty\"=\n";
-  in += "array string \"stringarr/one\"=\"hello\"\n";
-  in += "array string \"stringarr/two\"=\"hello\",\"world\\n\"\n";
-
-  EXPECT_CALL(dispatcher, QueueOutgoing(_, _, _)).Times(23);
-  EXPECT_CALL(notifier,
-              NotifyEntry(_, _, _, NT_NOTIFY_NEW | NT_NOTIFY_LOCAL, UINT_MAX))
-      .Times(23);
-
-  wpi::raw_mem_istream iss(in);
-  EXPECT_TRUE(storage.LoadEntries(iss, "", true, warn_func));
-  ASSERT_EQ(23u, entries().size());
-
-  EXPECT_EQ(*Value::MakeBoolean(true), *storage.GetEntryValue("boolean/true"));
-  EXPECT_EQ(*Value::MakeBoolean(false),
-            *storage.GetEntryValue("boolean/false"));
-  EXPECT_EQ(*Value::MakeDouble(-1.5), *storage.GetEntryValue("double/neg"));
-  EXPECT_EQ(*Value::MakeDouble(0.0), *storage.GetEntryValue("double/zero"));
-  EXPECT_EQ(*Value::MakeDouble(1.3e8), *storage.GetEntryValue("double/big"));
-  EXPECT_EQ(*Value::MakeString(""), *storage.GetEntryValue("string/empty"));
-  EXPECT_EQ(*Value::MakeString("hello"),
-            *storage.GetEntryValue("string/normal"));
-  EXPECT_EQ(*Value::MakeString(std::string_view("\0\3\5\n", 4)),
-            *storage.GetEntryValue("string/special"));
-  EXPECT_EQ(*Value::MakeString("\"a\""),
-            *storage.GetEntryValue("string/quoted"));
-  EXPECT_EQ(*Value::MakeRaw(""), *storage.GetEntryValue("raw/empty"));
-  EXPECT_EQ(*Value::MakeRaw("hello"), *storage.GetEntryValue("raw/normal"));
-  EXPECT_EQ(*Value::MakeRaw(std::string_view("\0\3\5\n", 4)),
-            *storage.GetEntryValue("raw/special"));
-  EXPECT_EQ(*Value::MakeBooleanArray(std::vector<int>{}),
-            *storage.GetEntryValue("booleanarr/empty"));
-  EXPECT_EQ(*Value::MakeBooleanArray(std::vector<int>{1}),
-            *storage.GetEntryValue("booleanarr/one"));
-  EXPECT_EQ(*Value::MakeBooleanArray(std::vector<int>{1, 0}),
-            *storage.GetEntryValue("booleanarr/two"));
-  EXPECT_EQ(*Value::MakeDoubleArray(std::vector<double>{}),
-            *storage.GetEntryValue("doublearr/empty"));
-  EXPECT_EQ(*Value::MakeDoubleArray(std::vector<double>{0.5}),
-            *storage.GetEntryValue("doublearr/one"));
-  EXPECT_EQ(*Value::MakeDoubleArray(std::vector<double>{0.5, -0.25}),
-            *storage.GetEntryValue("doublearr/two"));
-  EXPECT_EQ(*Value::MakeStringArray(std::vector<std::string>{}),
-            *storage.GetEntryValue("stringarr/empty"));
-  EXPECT_EQ(*Value::MakeStringArray(std::vector<std::string>{"hello"}),
-            *storage.GetEntryValue("stringarr/one"));
-  EXPECT_EQ(
-      *Value::MakeStringArray(std::vector<std::string>{"hello", "world\n"}),
-      *storage.GetEntryValue("stringarr/two"));
-  EXPECT_EQ(*Value::MakeBoolean(true),
-            *storage.GetEntryValue(std::string_view("\0\3\5\n", 4)));
-  EXPECT_EQ(*Value::MakeBoolean(true), *storage.GetEntryValue("="));
-}
-
-TEST_P(StorageEmptyTest, LoadPersistentWarn) {
-  MockLoadWarn warn;
-  auto warn_func = [&](size_t line, const char* msg) { warn.Warn(line, msg); };
-
-  wpi::raw_mem_istream iss(
-      "[NetworkTables Storage 3.0]\nboolean \"foo\"=foo\n");
-  EXPECT_CALL(
-      warn, Warn(2, std::string_view(
-                        "unrecognized boolean value, not 'true' or 'false'")));
-  EXPECT_TRUE(storage.LoadEntries(iss, "", true, warn_func));
-
-  EXPECT_TRUE(entries().empty());
-  EXPECT_TRUE(idmap().empty());
-}
-
-TEST_P(StorageEmptyTest, ProcessIncomingEntryAssign) {
-  auto conn = std::make_shared<MockNetworkConnection>();
-  auto value = Value::MakeDouble(1.0);
-  if (GetParam()) {
-    // id assign message reply generated on the server; sent to everyone
-    EXPECT_CALL(
-        dispatcher,
-        QueueOutgoing(MessageEq(Message::EntryAssign("foo", 0, 0, value, 0)),
-                      IsNull(), IsNull()));
-  }
-  EXPECT_CALL(notifier, NotifyEntry(0, std::string_view("foo"), ValueEq(value),
-                                    NT_NOTIFY_NEW, UINT_MAX));
-
-  storage.ProcessIncoming(
-      Message::EntryAssign("foo", GetParam() ? 0xffff : 0, 0, value, 0),
-      conn.get(), conn);
-}
-
-TEST_P(StoragePopulateOneTest, ProcessIncomingEntryAssign) {
-  auto conn = std::make_shared<MockNetworkConnection>();
-  auto value = Value::MakeDouble(1.0);
-  EXPECT_CALL(*conn, proto_rev()).WillRepeatedly(Return(0x0300u));
-  if (GetParam()) {
-    // server broadcasts new value to all *other* connections
-    EXPECT_CALL(
-        dispatcher,
-        QueueOutgoing(MessageEq(Message::EntryAssign("foo", 0, 1, value, 0)),
-                      IsNull(), conn.get()));
-  }
-  EXPECT_CALL(notifier, NotifyEntry(0, std::string_view("foo"), ValueEq(value),
-                                    NT_NOTIFY_UPDATE, UINT_MAX));
-
-  storage.ProcessIncoming(Message::EntryAssign("foo", 0, 1, value, 0),
-                          conn.get(), conn);
-}
-
-TEST_P(StoragePopulateOneTest, ProcessIncomingEntryAssignIgnore) {
-  auto conn = std::make_shared<MockNetworkConnection>();
-  auto value = Value::MakeDouble(1.0);
-  storage.ProcessIncoming(Message::EntryAssign("foo", 0xffff, 1, value, 0),
-                          conn.get(), conn);
-}
-
-TEST_P(StoragePopulateOneTest, ProcessIncomingEntryAssignWithFlags) {
-  auto conn = std::make_shared<MockNetworkConnection>();
-  auto value = Value::MakeDouble(1.0);
-  EXPECT_CALL(*conn, proto_rev()).WillRepeatedly(Return(0x0300u));
-  if (GetParam()) {
-    // server broadcasts new value/flags to all *other* connections
-    EXPECT_CALL(
-        dispatcher,
-        QueueOutgoing(MessageEq(Message::EntryAssign("foo", 0, 1, value, 0x2)),
-                      IsNull(), conn.get()));
-    EXPECT_CALL(notifier,
-                NotifyEntry(0, std::string_view("foo"), ValueEq(value),
-                            NT_NOTIFY_UPDATE | NT_NOTIFY_FLAGS, UINT_MAX));
-  } else {
-    // client forces flags back when an assign message is received for an
-    // existing entry with different flags
-    EXPECT_CALL(dispatcher, QueueOutgoing(MessageEq(Message::FlagsUpdate(0, 0)),
-                                          IsNull(), IsNull()));
-    EXPECT_CALL(notifier,
-                NotifyEntry(0, std::string_view("foo"), ValueEq(value),
-                            NT_NOTIFY_UPDATE, UINT_MAX));
-  }
-
-  storage.ProcessIncoming(Message::EntryAssign("foo", 0, 1, value, 0x2),
-                          conn.get(), conn);
-}
-
-TEST_P(StoragePopulateOneTest, DeleteCheckHandle) {
-  EXPECT_CALL(dispatcher, QueueOutgoing(_, _, _)).Times(AnyNumber());
-  EXPECT_CALL(notifier, NotifyEntry(_, _, _, _, _)).Times(AnyNumber());
-  auto handle = storage.GetEntry("foo");
-  storage.DeleteEntry("foo");
-  storage.SetEntryTypeValue("foo", Value::MakeBoolean(true));
-  ::testing::Mock::VerifyAndClearExpectations(&dispatcher);
-  ::testing::Mock::VerifyAndClearExpectations(&notifier);
-
-  auto handle2 = storage.GetEntry("foo");
-  ASSERT_EQ(handle, handle2);
-}
-
-TEST_P(StoragePopulateOneTest, DeletedEntryFlags) {
-  EXPECT_CALL(dispatcher, QueueOutgoing(_, _, _)).Times(AnyNumber());
-  EXPECT_CALL(notifier, NotifyEntry(_, _, _, _, _)).Times(AnyNumber());
-  auto handle = storage.GetEntry("foo");
-  storage.SetEntryFlags("foo", 2);
-  storage.DeleteEntry("foo");
-  ::testing::Mock::VerifyAndClearExpectations(&dispatcher);
-  ::testing::Mock::VerifyAndClearExpectations(&notifier);
-
-  EXPECT_EQ(storage.GetEntryFlags("foo"), 0u);
-  EXPECT_EQ(storage.GetEntryFlags(handle), 0u);
-  storage.SetEntryFlags("foo", 4);
-  storage.SetEntryFlags(handle, 4);
-  EXPECT_EQ(storage.GetEntryFlags("foo"), 0u);
-  EXPECT_EQ(storage.GetEntryFlags(handle), 0u);
-}
-
-TEST_P(StoragePopulateOneTest, DeletedDeleteAllEntries) {
-  EXPECT_CALL(dispatcher, QueueOutgoing(_, _, _)).Times(AnyNumber());
-  EXPECT_CALL(notifier, NotifyEntry(_, _, _, _, _)).Times(AnyNumber());
-  storage.DeleteEntry("foo");
-  ::testing::Mock::VerifyAndClearExpectations(&dispatcher);
-  ::testing::Mock::VerifyAndClearExpectations(&notifier);
-
-  EXPECT_CALL(dispatcher, QueueOutgoing(MessageEq(Message::ClearEntries()),
-                                        IsNull(), IsNull()));
-  storage.DeleteAllEntries();
-}
-
-TEST_P(StoragePopulateOneTest, DeletedGetEntries) {
-  EXPECT_CALL(dispatcher, QueueOutgoing(_, _, _)).Times(AnyNumber());
-  EXPECT_CALL(notifier, NotifyEntry(_, _, _, _, _)).Times(AnyNumber());
-  storage.DeleteEntry("foo");
-  ::testing::Mock::VerifyAndClearExpectations(&dispatcher);
-  ::testing::Mock::VerifyAndClearExpectations(&notifier);
-
-  EXPECT_TRUE(storage.GetEntries("", 0).empty());
-}
-
-INSTANTIATE_TEST_SUITE_P(StorageEmptyTests, StorageEmptyTest,
-                         ::testing::Bool());
-INSTANTIATE_TEST_SUITE_P(StoragePopulateOneTests, StoragePopulateOneTest,
-                         ::testing::Bool());
-INSTANTIATE_TEST_SUITE_P(StoragePopulatedTests, StoragePopulatedTest,
-                         ::testing::Bool());
-INSTANTIATE_TEST_SUITE_P(StoragePersistentTests, StoragePersistentTest,
-                         ::testing::Bool());
-
-}  // namespace nt
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/StorageTest.h b/third_party/allwpilib/ntcore/src/test/native/cpp/StorageTest.h
index 3a1755f..a0cc737 100644
--- a/third_party/allwpilib/ntcore/src/test/native/cpp/StorageTest.h
+++ b/third_party/allwpilib/ntcore/src/test/native/cpp/StorageTest.h
@@ -2,8 +2,7 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
-#ifndef NTCORE_STORAGETEST_H_
-#define NTCORE_STORAGETEST_H_
+#pragma once
 
 #include <functional>
 #include <memory>
@@ -11,15 +10,13 @@
 
 #include "Log.h"
 #include "MockDispatcher.h"
-#include "MockEntryNotifier.h"
-#include "MockRpcServer.h"
 #include "Storage.h"
 
 namespace nt {
 
 class StorageTest {
  public:
-  StorageTest() : storage(notifier, rpc_server, logger), tmp_entry("foobar") {}
+  StorageTest() : storage(logger), tmp_entry("foobar") {}
 
   Storage::EntriesMap& entries() { return storage.m_entries; }
   Storage::IdMap& idmap() { return storage.m_idmap; }
@@ -32,13 +29,9 @@
   void HookOutgoing(bool server) { storage.SetDispatcher(&dispatcher, server); }
 
   wpi::Logger logger;
-  ::testing::StrictMock<MockEntryNotifier> notifier;
-  ::testing::StrictMock<MockRpcServer> rpc_server;
   ::testing::StrictMock<MockDispatcher> dispatcher;
   Storage storage;
   Storage::Entry tmp_entry;
 };
 
 }  // namespace nt
-
-#endif  // NTCORE_STORAGETEST_H_
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/TableListenerTest.cpp b/third_party/allwpilib/ntcore/src/test/native/cpp/TableListenerTest.cpp
new file mode 100644
index 0000000..7fb1947
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/test/native/cpp/TableListenerTest.cpp
@@ -0,0 +1,60 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <memory>
+
+#include "TestPrinters.h"
+#include "gmock/gmock.h"
+#include "gtest/gtest.h"
+#include "networktables/DoubleTopic.h"
+#include "networktables/NetworkTableInstance.h"
+#include "ntcore_cpp.h"
+
+using ::testing::_;
+
+using MockTableEventListener = testing::MockFunction<void(
+    nt::NetworkTable* table, std::string_view key, const nt::Event& event)>;
+using MockSubTableListener =
+    testing::MockFunction<void(nt::NetworkTable* parent, std::string_view name,
+                               std::shared_ptr<nt::NetworkTable> table)>;
+
+class TableListenerTest : public ::testing::Test {
+ public:
+  TableListenerTest() : m_inst(nt::NetworkTableInstance::Create()) {}
+
+  ~TableListenerTest() override { nt::NetworkTableInstance::Destroy(m_inst); }
+
+  void PublishTopics();
+
+ protected:
+  nt::NetworkTableInstance m_inst;
+  nt::DoublePublisher m_foovalue;
+  nt::DoublePublisher m_barvalue;
+  nt::DoublePublisher m_bazvalue;
+};
+
+void TableListenerTest::PublishTopics() {
+  m_foovalue = m_inst.GetDoubleTopic("/foo/foovalue").Publish();
+  m_barvalue = m_inst.GetDoubleTopic("/foo/bar/barvalue").Publish();
+  m_bazvalue = m_inst.GetDoubleTopic("/baz/bazvalue").Publish();
+}
+
+TEST_F(TableListenerTest, AddListener) {
+  auto table = m_inst.GetTable("/foo");
+  MockTableEventListener listener;
+  table->AddListener(NT_EVENT_TOPIC | NT_EVENT_IMMEDIATE,
+                     listener.AsStdFunction());
+  EXPECT_CALL(listener, Call(table.get(), "foovalue", _));
+  PublishTopics();
+  EXPECT_TRUE(m_inst.WaitForListenerQueue(1.0));
+}
+
+TEST_F(TableListenerTest, AddSubTableListener) {
+  auto table = m_inst.GetTable("/foo");
+  MockSubTableListener listener;
+  table->AddSubTableListener(listener.AsStdFunction());
+  EXPECT_CALL(listener, Call(table.get(), "bar", _));
+  PublishTopics();
+  EXPECT_TRUE(m_inst.WaitForListenerQueue(1.0));
+}
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/TestPrinters.cpp b/third_party/allwpilib/ntcore/src/test/native/cpp/TestPrinters.cpp
index 49b407b..66afe4e 100644
--- a/third_party/allwpilib/ntcore/src/test/native/cpp/TestPrinters.cpp
+++ b/third_party/allwpilib/ntcore/src/test/native/cpp/TestPrinters.cpp
@@ -4,55 +4,56 @@
 
 #include "TestPrinters.h"
 
+#include <wpi/json.h>
+
 #include "Handle.h"
-#include "Message.h"
+#include "PubSubOptions.h"
+#include "net/Message.h"
+#include "net3/Message3.h"
 #include "networktables/NetworkTableValue.h"
 #include "ntcore_cpp.h"
 
+namespace wpi {
+void PrintTo(const json& val, ::std::ostream* os) {
+  *os << val.dump();
+}
+}  // namespace wpi
+
 namespace nt {
 
-void PrintTo(const EntryNotification& event, std::ostream* os) {
-  *os << "EntryNotification{listener=";
+void PrintTo(const Event& event, std::ostream* os) {
+  *os << "Event{listener=";
   PrintTo(Handle{event.listener}, os);
-  *os << ", entry=";
-  PrintTo(Handle{event.entry}, os);
-  *os << ", name=\"" << event.name << "\", flags=" << event.flags << ", value=";
-  PrintTo(event.value, os);
+  *os << ", flags=" << event.flags;
+  // *os << ", name=\"" << event.name << "\", flags=" << event.flags
+  // << "value=";
+  // PrintTo(event.value, os);
   *os << '}';
 }
 
 void PrintTo(const Handle& handle, std::ostream* os) {
   *os << "Handle{";
   switch (handle.GetType()) {
-    case Handle::kConnectionListener:
-      *os << "kConnectionListener";
+    case Handle::kListener:
+      *os << "kListener";
       break;
-    case Handle::kConnectionListenerPoller:
-      *os << "kConnectionListenerPoller";
+    case Handle::kListenerPoller:
+      *os << "kListenerPoller";
       break;
     case Handle::kEntry:
       *os << "kEntry";
       break;
-    case Handle::kEntryListener:
-      *os << "kEntryListener";
-      break;
-    case Handle::kEntryListenerPoller:
-      *os << "kEntryListenerPoller";
-      break;
     case Handle::kInstance:
       *os << "kInstance";
       break;
-    case Handle::kLogger:
-      *os << "kLogger";
+    case Handle::kTopic:
+      *os << "kTopic";
       break;
-    case Handle::kLoggerPoller:
-      *os << "kLoggerPoller";
+    case Handle::kSubscriber:
+      *os << "kSubscriber";
       break;
-    case Handle::kRpcCall:
-      *os << "kRpcCall";
-      break;
-    case Handle::kRpcCallPoller:
-      *os << "kRpcCallPoller";
+    case Handle::kPublisher:
+      *os << "kPublisher";
       break;
     default:
       *os << "UNKNOWN";
@@ -61,46 +62,46 @@
   *os << ", " << handle.GetInst() << ", " << handle.GetIndex() << '}';
 }
 
-void PrintTo(const Message& msg, std::ostream* os) {
+void PrintTo(const net3::Message3& msg, std::ostream* os) {
   *os << "Message{";
   switch (msg.type()) {
-    case Message::kKeepAlive:
+    case net3::Message3::kKeepAlive:
       *os << "kKeepAlive";
       break;
-    case Message::kClientHello:
+    case net3::Message3::kClientHello:
       *os << "kClientHello";
       break;
-    case Message::kProtoUnsup:
+    case net3::Message3::kProtoUnsup:
       *os << "kProtoUnsup";
       break;
-    case Message::kServerHelloDone:
+    case net3::Message3::kServerHelloDone:
       *os << "kServerHelloDone";
       break;
-    case Message::kServerHello:
+    case net3::Message3::kServerHello:
       *os << "kServerHello";
       break;
-    case Message::kClientHelloDone:
+    case net3::Message3::kClientHelloDone:
       *os << "kClientHelloDone";
       break;
-    case Message::kEntryAssign:
+    case net3::Message3::kEntryAssign:
       *os << "kEntryAssign";
       break;
-    case Message::kEntryUpdate:
+    case net3::Message3::kEntryUpdate:
       *os << "kEntryUpdate";
       break;
-    case Message::kFlagsUpdate:
+    case net3::Message3::kFlagsUpdate:
       *os << "kFlagsUpdate";
       break;
-    case Message::kEntryDelete:
+    case net3::Message3::kEntryDelete:
       *os << "kEntryDelete";
       break;
-    case Message::kClearEntries:
+    case net3::Message3::kClearEntries:
       *os << "kClearEntries";
       break;
-    case Message::kExecuteRpc:
+    case net3::Message3::kExecuteRpc:
       *os << "kExecuteRpc";
       break;
-    case Message::kRpcResponse:
+    case net3::Message3::kRpcResponse:
       *os << "kRpcResponse";
       break;
     default:
@@ -120,28 +121,37 @@
     case NT_UNASSIGNED:
       break;
     case NT_BOOLEAN:
-      *os << (value.GetBoolean() ? "true" : "false");
+      *os << "boolean, " << (value.GetBoolean() ? "true" : "false");
       break;
     case NT_DOUBLE:
-      *os << value.GetDouble();
+      *os << "double, " << value.GetDouble();
+      break;
+    case NT_FLOAT:
+      *os << "float, " << value.GetFloat();
+      break;
+    case NT_INTEGER:
+      *os << "int, " << value.GetInteger();
       break;
     case NT_STRING:
-      *os << '"' << value.GetString() << '"';
+      *os << "string, \"" << value.GetString() << '"';
       break;
     case NT_RAW:
-      *os << ::testing::PrintToString(value.GetRaw());
+      *os << "raw, " << ::testing::PrintToString(value.GetRaw());
       break;
     case NT_BOOLEAN_ARRAY:
-      *os << ::testing::PrintToString(value.GetBooleanArray());
+      *os << "boolean[], " << ::testing::PrintToString(value.GetBooleanArray());
       break;
     case NT_DOUBLE_ARRAY:
-      *os << ::testing::PrintToString(value.GetDoubleArray());
+      *os << "double[], " << ::testing::PrintToString(value.GetDoubleArray());
+      break;
+    case NT_FLOAT_ARRAY:
+      *os << "float[], " << ::testing::PrintToString(value.GetFloatArray());
+      break;
+    case NT_INTEGER_ARRAY:
+      *os << "int[], " << ::testing::PrintToString(value.GetIntegerArray());
       break;
     case NT_STRING_ARRAY:
-      *os << ::testing::PrintToString(value.GetStringArray());
-      break;
-    case NT_RPC:
-      *os << ::testing::PrintToString(value.GetRpc());
+      *os << "string[], " << ::testing::PrintToString(value.GetStringArray());
       break;
     default:
       *os << "UNKNOWN TYPE " << value.type();
@@ -150,4 +160,11 @@
   *os << '}';
 }
 
+void PrintTo(const PubSubOptionsImpl& options, std::ostream* os) {
+  *os << "PubSubOptions{periodicMs=" << options.periodicMs
+      << ", pollStorage=" << options.pollStorage
+      << ", sendAll=" << options.sendAll
+      << ", keepDuplicates=" << options.keepDuplicates << '}';
+}
+
 }  // namespace nt
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/TestPrinters.h b/third_party/allwpilib/ntcore/src/test/native/cpp/TestPrinters.h
index 47c9eb4..2b8f1da 100644
--- a/third_party/allwpilib/ntcore/src/test/native/cpp/TestPrinters.h
+++ b/third_party/allwpilib/ntcore/src/test/native/cpp/TestPrinters.h
@@ -2,11 +2,10 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
-#ifndef NTCORE_TESTPRINTERS_H_
-#define NTCORE_TESTPRINTERS_H_
+#pragma once
 
-#include <memory>
 #include <ostream>
+#include <span>
 #include <string>
 #include <string_view>
 
@@ -14,42 +13,53 @@
 
 namespace wpi {
 
+class json;
+
 inline void PrintTo(std::string_view str, ::std::ostream* os) {
   ::testing::internal::PrintStringTo(std::string{str}, os);
 }
 
+template <typename T>
+void PrintTo(std::span<T> val, ::std::ostream* os) {
+  *os << '{';
+  bool first = true;
+  for (auto v : val) {
+    if (first) {
+      first = false;
+    } else {
+      *os << ", ";
+    }
+    *os << ::testing::PrintToString(v);
+  }
+  *os << '}';
+}
+
+void PrintTo(const json& val, ::std::ostream* os);
+
 }  // namespace wpi
 
 namespace nt {
 
-class EntryNotification;
+namespace net3 {
+class Message3;
+}  // namespace net3
+
+namespace net {
+struct ClientMessage;
+struct ServerMessage;
+}  // namespace net
+
+class Event;
 class Handle;
-class Message;
+class PubSubOptionsImpl;
 class Value;
 
-void PrintTo(const EntryNotification& event, std::ostream* os);
+void PrintTo(const Event& event, std::ostream* os);
 void PrintTo(const Handle& handle, std::ostream* os);
-
-void PrintTo(const Message& msg, std::ostream* os);
-
-inline void PrintTo(std::shared_ptr<Message> msg, std::ostream* os) {
-  *os << "shared_ptr{";
-  if (msg) {
-    PrintTo(*msg, os);
-  }
-  *os << '}';
-}
-
+void PrintTo(const net3::Message3& msg, std::ostream* os);
+void PrintTo(const net::ClientMessage& msg, std::ostream* os);
+void PrintTo(const net::ServerMessage& msg, std::ostream* os);
 void PrintTo(const Value& value, std::ostream* os);
-
-inline void PrintTo(std::shared_ptr<Value> value, std::ostream* os) {
-  *os << "shared_ptr{";
-  if (value) {
-    PrintTo(*value, os);
-  }
-  *os << '}';
-}
+void PrintTo(const PubSubOptionsImpl& options, std::ostream* os);
 
 }  // namespace nt
-
-#endif  // NTCORE_TESTPRINTERS_H_
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/TimeSyncTest.cpp b/third_party/allwpilib/ntcore/src/test/native/cpp/TimeSyncTest.cpp
new file mode 100644
index 0000000..54e1f7c
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/test/native/cpp/TimeSyncTest.cpp
@@ -0,0 +1,70 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "gtest/gtest.h"
+#include "networktables/NetworkTableInstance.h"
+#include "networktables/NetworkTableListener.h"
+
+class TimeSyncTest : public ::testing::Test {
+ public:
+  TimeSyncTest() : m_inst(nt::NetworkTableInstance::Create()) {}
+
+  ~TimeSyncTest() override { nt::NetworkTableInstance::Destroy(m_inst); }
+
+ protected:
+  nt::NetworkTableInstance m_inst;
+};
+
+TEST_F(TimeSyncTest, TestLocal) {
+  auto offset = m_inst.GetServerTimeOffset();
+  ASSERT_FALSE(offset);
+}
+
+TEST_F(TimeSyncTest, TestServer) {
+  nt::NetworkTableListenerPoller poller{m_inst};
+  poller.AddTimeSyncListener(false);
+
+  m_inst.StartServer("timesynctest.json", "127.0.0.1", 0, 10030);
+  auto offset = m_inst.GetServerTimeOffset();
+  ASSERT_TRUE(offset);
+  ASSERT_EQ(0, *offset);
+
+  auto events = poller.ReadQueue();
+  ASSERT_EQ(1u, events.size());
+  auto data = events[0].GetTimeSyncEventData();
+  ASSERT_TRUE(data);
+  ASSERT_TRUE(data->valid);
+  ASSERT_EQ(0, data->serverTimeOffset);
+  ASSERT_EQ(0, data->rtt2);
+
+  m_inst.StopServer();
+  offset = m_inst.GetServerTimeOffset();
+  ASSERT_FALSE(offset);
+
+  events = poller.ReadQueue();
+  ASSERT_EQ(1u, events.size());
+  data = events[0].GetTimeSyncEventData();
+  ASSERT_TRUE(data);
+  ASSERT_FALSE(data->valid);
+}
+
+TEST_F(TimeSyncTest, TestClient3) {
+  m_inst.StartClient3("client");
+  auto offset = m_inst.GetServerTimeOffset();
+  ASSERT_FALSE(offset);
+
+  m_inst.StopClient();
+  offset = m_inst.GetServerTimeOffset();
+  ASSERT_FALSE(offset);
+}
+
+TEST_F(TimeSyncTest, TestClient4) {
+  m_inst.StartClient4("client");
+  auto offset = m_inst.GetServerTimeOffset();
+  ASSERT_FALSE(offset);
+
+  m_inst.StopClient();
+  offset = m_inst.GetServerTimeOffset();
+  ASSERT_FALSE(offset);
+}
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/TopicListenerTest.cpp b/third_party/allwpilib/ntcore/src/test/native/cpp/TopicListenerTest.cpp
new file mode 100644
index 0000000..f0a002a
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/test/native/cpp/TopicListenerTest.cpp
@@ -0,0 +1,285 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <chrono>
+#include <thread>
+
+#include <wpi/Synchronization.h>
+#include <wpi/json.h>
+
+#include "TestPrinters.h"
+#include "ValueMatcher.h"
+#include "gtest/gtest.h"
+#include "ntcore_c.h"
+#include "ntcore_cpp.h"
+
+class TopicListenerTest : public ::testing::Test {
+ public:
+  TopicListenerTest()
+      : m_serverInst(nt::CreateInstance()), m_clientInst(nt::CreateInstance()) {
+#if 0
+    nt::AddLogger(m_serverInst, 0, UINT_MAX, [](auto& event) {
+      if (auto msg = event.GetLogMessage()) {
+        std::fprintf(stderr, "SERVER: %s\n", msg->message.c_str());
+      }
+    });
+    nt::AddLogger(m_clientInst, 0, UINT_MAX, [](auto& event) {
+      if (auto msg = event.GetLogMessage()) {
+        std::fprintf(stderr, "CLIENT: %s\n", msg.message.c_str());
+      }
+    });
+#endif
+  }
+
+  ~TopicListenerTest() override {
+    nt::DestroyInstance(m_serverInst);
+    nt::DestroyInstance(m_clientInst);
+  }
+
+  void Connect(unsigned int port);
+  static void PublishTopics(NT_Inst inst);
+  void CheckEvents(const std::vector<nt::Event>& events, NT_Listener handle,
+                   unsigned int flags, std::string_view topicName = "/foo/bar");
+
+ protected:
+  NT_Inst m_serverInst;
+  NT_Inst m_clientInst;
+};
+
+void TopicListenerTest::Connect(unsigned int port) {
+  nt::StartServer(m_serverInst, "topiclistenertest.json", "127.0.0.1", 0, port);
+  nt::StartClient4(m_clientInst, "client");
+  nt::SetServer(m_clientInst, "127.0.0.1", port);
+
+  // Use connection listener to ensure we've connected
+  NT_ListenerPoller poller = nt::CreateListenerPoller(m_clientInst);
+  nt::AddPolledListener(poller, m_clientInst, nt::EventFlags::kConnected);
+  bool timedOut = false;
+  if (!wpi::WaitForObject(poller, 1.0, &timedOut)) {
+    FAIL() << "client didn't connect to server";
+  }
+}
+
+void TopicListenerTest::PublishTopics(NT_Inst inst) {
+  nt::Publish(nt::GetTopic(inst, "/foo/bar"), NT_DOUBLE, "double");
+  nt::Publish(nt::GetTopic(inst, "/foo"), NT_DOUBLE, "double");
+  nt::Publish(nt::GetTopic(inst, "/baz"), NT_DOUBLE, "double");
+}
+
+void TopicListenerTest::CheckEvents(const std::vector<nt::Event>& events,
+                                    NT_Listener handle, unsigned int flags,
+                                    std::string_view topicName) {
+  ASSERT_EQ(events.size(), 1u);
+  ASSERT_EQ(events[0].listener, handle);
+  ASSERT_EQ(events[0].flags, flags);
+  auto topicInfo = events[0].GetTopicInfo();
+  ASSERT_TRUE(topicInfo);
+  ASSERT_EQ(topicInfo->topic, nt::GetTopic(m_serverInst, topicName));
+  ASSERT_EQ(topicInfo->name, topicName);
+}
+
+TEST_F(TopicListenerTest, TopicNewLocal) {
+  auto poller = nt::CreateListenerPoller(m_serverInst);
+  auto handle = nt::AddPolledListener(
+      poller, nt::GetTopic(m_serverInst, "/foo"), nt::EventFlags::kPublish);
+
+  PublishTopics(m_serverInst);
+
+  bool timedOut = false;
+  ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut));
+  auto events = nt::ReadListenerQueue(poller);
+  CheckEvents(events, handle, nt::EventFlags::kPublish, "/foo");
+}
+
+TEST_F(TopicListenerTest, DISABLED_TopicNewRemote) {
+  Connect(10010);
+  if (HasFatalFailure()) {
+    return;
+  }
+  auto poller = nt::CreateListenerPoller(m_serverInst);
+  auto handle = nt::AddPolledListener(
+      poller, nt::GetTopic(m_serverInst, "/foo"), nt::EventFlags::kPublish);
+
+  PublishTopics(m_clientInst);
+
+  nt::Flush(m_clientInst);
+  std::this_thread::sleep_for(std::chrono::milliseconds(100));
+
+  bool timedOut = false;
+  ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut));
+  auto events = nt::ReadListenerQueue(poller);
+  CheckEvents(events, handle, nt::EventFlags::kPublish, "/foo");
+}
+
+TEST_F(TopicListenerTest, TopicPublishImm) {
+  PublishTopics(m_serverInst);
+
+  auto poller = nt::CreateListenerPoller(m_serverInst);
+  auto handle = nt::AddPolledListener(
+      poller, nt::GetTopic(m_serverInst, "/foo"),
+      nt::EventFlags::kPublish | nt::EventFlags::kImmediate);
+
+  bool timedOut = false;
+  ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut));
+  auto events = nt::ReadListenerQueue(poller);
+  CheckEvents(events, handle,
+              nt::EventFlags::kPublish | nt::EventFlags::kImmediate, "/foo");
+}
+
+TEST_F(TopicListenerTest, TopicUnpublishPropsImm) {
+  PublishTopics(m_serverInst);
+
+  auto poller = nt::CreateListenerPoller(m_serverInst);
+  nt::AddPolledListener(poller, nt::GetTopic(m_serverInst, "/foo"),
+                        nt::EventFlags::kUnpublish |
+                            nt::EventFlags::kProperties |
+                            nt::EventFlags::kImmediate);
+
+  bool timedOut = false;
+  ASSERT_FALSE(wpi::WaitForObject(poller, 0.02, &timedOut));
+  auto events = nt::ReadListenerQueue(poller);
+  ASSERT_TRUE(events.empty());
+}
+
+TEST_F(TopicListenerTest, TopicUnpublishLocal) {
+  auto topic = nt::GetTopic(m_serverInst, "/foo");
+
+  auto poller = nt::CreateListenerPoller(m_serverInst);
+  auto handle =
+      nt::AddPolledListener(poller, topic, nt::EventFlags::kUnpublish);
+
+  auto pub = nt::Publish(topic, NT_DOUBLE, "double");
+  nt::Unpublish(pub);
+
+  bool timedOut = false;
+  ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut));
+  auto events = nt::ReadListenerQueue(poller);
+  CheckEvents(events, handle, nt::EventFlags::kUnpublish, "/foo");
+}
+
+TEST_F(TopicListenerTest, DISABLED_TopicUnpublishRemote) {
+  Connect(10010);
+  if (HasFatalFailure()) {
+    return;
+  }
+  auto poller = nt::CreateListenerPoller(m_serverInst);
+  auto handle = nt::AddPolledListener(
+      poller, nt::GetTopic(m_serverInst, "/foo"), nt::EventFlags::kUnpublish);
+
+  auto pub =
+      nt::Publish(nt::GetTopic(m_clientInst, "/foo"), NT_DOUBLE, "double");
+  nt::Flush(m_clientInst);
+  std::this_thread::sleep_for(std::chrono::milliseconds(100));
+
+  nt::Unpublish(pub);
+
+  nt::Flush(m_clientInst);
+  std::this_thread::sleep_for(std::chrono::milliseconds(100));
+
+  bool timedOut = false;
+  ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut));
+  auto events = nt::ReadListenerQueue(poller);
+  CheckEvents(events, handle, nt::EventFlags::kUnpublish, "/foo");
+}
+
+TEST_F(TopicListenerTest, TopicPropertiesLocal) {
+  auto topic = nt::GetTopic(m_serverInst, "/foo");
+
+  auto poller = nt::CreateListenerPoller(m_serverInst);
+  auto handle =
+      nt::AddPolledListener(poller, topic, nt::EventFlags::kProperties);
+
+  nt::SetTopicProperty(topic, "foo", 5);
+
+  bool timedOut = false;
+  ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut));
+  auto events = nt::ReadListenerQueue(poller);
+  CheckEvents(events, handle, nt::EventFlags::kProperties, "/foo");
+}
+
+TEST_F(TopicListenerTest, DISABLED_TopicPropertiesRemote) {
+  Connect(10010);
+  if (HasFatalFailure()) {
+    return;
+  }
+  // the topic needs to actually exist
+  nt::Publish(nt::GetTopic(m_serverInst, "/foo"), NT_BOOLEAN, "boolean");
+
+  auto poller = nt::CreateListenerPoller(m_serverInst);
+  auto handle = nt::AddPolledListener(
+      poller, nt::GetTopic(m_serverInst, "/foo"), nt::EventFlags::kProperties);
+  nt::FlushLocal(m_serverInst);
+
+  nt::SetTopicProperty(nt::GetTopic(m_clientInst, "/foo"), "foo", 5);
+  nt::Flush(m_clientInst);
+  std::this_thread::sleep_for(std::chrono::milliseconds(100));
+
+  bool timedOut = false;
+  ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut));
+  auto events = nt::ReadListenerQueue(poller);
+  CheckEvents(events, handle, nt::EventFlags::kProperties, "/foo");
+}
+
+TEST_F(TopicListenerTest, PrefixPublishLocal) {
+  auto poller = nt::CreateListenerPoller(m_serverInst);
+  auto handle =
+      nt::AddPolledListener(poller, {{"/foo/"}}, nt::EventFlags::kPublish);
+
+  PublishTopics(m_serverInst);
+
+  bool timedOut = false;
+  ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut));
+  auto events = nt::ReadListenerQueue(poller);
+  CheckEvents(events, handle, nt::EventFlags::kPublish);
+}
+
+TEST_F(TopicListenerTest, DISABLED_PrefixPublishRemote) {
+  Connect(10011);
+  if (HasFatalFailure()) {
+    return;
+  }
+  auto poller = nt::CreateListenerPoller(m_serverInst);
+  auto handle =
+      nt::AddPolledListener(poller, {{"/foo/"}}, nt::EventFlags::kPublish);
+
+  PublishTopics(m_clientInst);
+
+  nt::Flush(m_clientInst);
+  std::this_thread::sleep_for(std::chrono::milliseconds(100));
+
+  bool timedOut = false;
+  ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut));
+  auto events = nt::ReadListenerQueue(poller);
+  CheckEvents(events, handle, nt::EventFlags::kPublish);
+}
+
+TEST_F(TopicListenerTest, PrefixPublishImm) {
+  PublishTopics(m_serverInst);
+
+  auto poller = nt::CreateListenerPoller(m_serverInst);
+  auto handle = nt::AddPolledListener(
+      poller, {{"/foo/"}},
+      nt::EventFlags::kPublish | nt::EventFlags::kImmediate);
+
+  bool timedOut = false;
+  ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut));
+  auto events = nt::ReadListenerQueue(poller);
+  CheckEvents(events, handle,
+              nt::EventFlags::kPublish | nt::EventFlags::kImmediate);
+}
+
+TEST_F(TopicListenerTest, PrefixUnpublishPropsImm) {
+  PublishTopics(m_serverInst);
+
+  auto poller = nt::CreateListenerPoller(m_serverInst);
+  nt::AddPolledListener(poller, {{"/foo/"}},
+                        nt::EventFlags::kUnpublish |
+                            nt::EventFlags::kProperties |
+                            nt::EventFlags::kImmediate);
+
+  bool timedOut = false;
+  ASSERT_FALSE(wpi::WaitForObject(poller, 0.02, &timedOut));
+  auto events = nt::ReadListenerQueue(poller);
+  ASSERT_TRUE(events.empty());
+}
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/ValueListenerTest.cpp b/third_party/allwpilib/ntcore/src/test/native/cpp/ValueListenerTest.cpp
new file mode 100644
index 0000000..dbe3201
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/test/native/cpp/ValueListenerTest.cpp
@@ -0,0 +1,409 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <wpi/StringExtras.h>
+#include <wpi/Synchronization.h>
+
+#include "TestPrinters.h"
+#include "ValueMatcher.h"
+#include "gtest/gtest.h"
+#include "ntcore_c.h"
+#include "ntcore_cpp.h"
+
+using ::testing::_;
+using ::testing::AnyNumber;
+using ::testing::IsNull;
+using ::testing::Return;
+
+namespace nt {
+
+// Test only local here; it's more reliable to mock the network
+class ValueListenerTest : public ::testing::Test {
+ public:
+  ValueListenerTest() : m_inst{nt::CreateInstance()} {}
+
+  ~ValueListenerTest() override { nt::DestroyInstance(m_inst); }
+
+ protected:
+  NT_Inst m_inst;
+};
+
+TEST_F(ValueListenerTest, MultiPollSub) {
+  auto topic = nt::GetTopic(m_inst, "foo");
+  auto pub = nt::Publish(topic, NT_DOUBLE, "double");
+  auto sub = nt::Subscribe(topic, NT_DOUBLE, "double");
+
+  auto poller1 = nt::CreateListenerPoller(m_inst);
+  auto poller2 = nt::CreateListenerPoller(m_inst);
+  auto poller3 = nt::CreateListenerPoller(m_inst);
+  auto h1 = nt::AddPolledListener(poller1, sub, nt::EventFlags::kValueLocal);
+  auto h2 = nt::AddPolledListener(poller2, sub, nt::EventFlags::kValueLocal);
+  auto h3 = nt::AddPolledListener(poller3, sub, nt::EventFlags::kValueLocal);
+
+  nt::SetDouble(pub, 0);
+
+  bool timedOut = false;
+  ASSERT_TRUE(wpi::WaitForObject(poller1, 1.0, &timedOut));
+  ASSERT_FALSE(timedOut);
+  ASSERT_TRUE(wpi::WaitForObject(poller2, 1.0, &timedOut));
+  ASSERT_FALSE(timedOut);
+  ASSERT_TRUE(wpi::WaitForObject(poller3, 1.0, &timedOut));
+  ASSERT_FALSE(timedOut);
+  auto results1 = nt::ReadListenerQueue(poller1);
+  auto results2 = nt::ReadListenerQueue(poller2);
+  auto results3 = nt::ReadListenerQueue(poller3);
+
+  ASSERT_EQ(results1.size(), 1u);
+  EXPECT_EQ(results1[0].flags, nt::EventFlags::kValueLocal);
+  EXPECT_EQ(results1[0].listener, h1);
+  auto valueData = results1[0].GetValueEventData();
+  ASSERT_TRUE(valueData);
+  EXPECT_EQ(valueData->subentry, sub);
+  EXPECT_EQ(valueData->topic, topic);
+  EXPECT_EQ(valueData->value, nt::Value::MakeDouble(0.0));
+
+  ASSERT_EQ(results2.size(), 1u);
+  EXPECT_EQ(results2[0].flags, nt::EventFlags::kValueLocal);
+  EXPECT_EQ(results2[0].listener, h2);
+  valueData = results2[0].GetValueEventData();
+  ASSERT_TRUE(valueData);
+  EXPECT_EQ(valueData->subentry, sub);
+  EXPECT_EQ(valueData->topic, topic);
+  EXPECT_EQ(valueData->value, nt::Value::MakeDouble(0.0));
+
+  ASSERT_EQ(results3.size(), 1u);
+  EXPECT_EQ(results3[0].flags, nt::EventFlags::kValueLocal);
+  EXPECT_EQ(results3[0].listener, h3);
+  valueData = results3[0].GetValueEventData();
+  ASSERT_TRUE(valueData);
+  EXPECT_EQ(valueData->subentry, sub);
+  EXPECT_EQ(valueData->topic, topic);
+  EXPECT_EQ(valueData->value, nt::Value::MakeDouble(0.0));
+}
+
+TEST_F(ValueListenerTest, PollMultiSub) {
+  auto topic = nt::GetTopic(m_inst, "foo");
+  auto pub = nt::Publish(topic, NT_DOUBLE, "double");
+  auto sub1 = nt::Subscribe(topic, NT_DOUBLE, "double");
+  auto sub2 = nt::Subscribe(topic, NT_DOUBLE, "double");
+
+  auto poller = nt::CreateListenerPoller(m_inst);
+  auto h1 = nt::AddPolledListener(poller, sub1, nt::EventFlags::kValueLocal);
+  auto h2 = nt::AddPolledListener(poller, sub2, nt::EventFlags::kValueLocal);
+
+  nt::SetDouble(pub, 0);
+
+  bool timedOut = false;
+  ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut));
+  ASSERT_FALSE(timedOut);
+  auto results = nt::ReadListenerQueue(poller);
+
+  ASSERT_EQ(results.size(), 2u);
+  EXPECT_EQ(results[0].flags, nt::EventFlags::kValueLocal);
+  EXPECT_EQ(results[0].listener, h1);
+  auto valueData = results[0].GetValueEventData();
+  ASSERT_TRUE(valueData);
+  EXPECT_EQ(valueData->subentry, sub1);
+  EXPECT_EQ(valueData->topic, topic);
+  EXPECT_EQ(valueData->value, nt::Value::MakeDouble(0.0));
+
+  EXPECT_EQ(results[1].flags, nt::EventFlags::kValueLocal);
+  EXPECT_EQ(results[1].listener, h2);
+  valueData = results[1].GetValueEventData();
+  ASSERT_TRUE(valueData);
+  EXPECT_EQ(valueData->subentry, sub2);
+  EXPECT_EQ(valueData->topic, topic);
+  EXPECT_EQ(valueData->value, nt::Value::MakeDouble(0.0));
+}
+
+TEST_F(ValueListenerTest, PollMultiSubTopic) {
+  auto topic1 = nt::GetTopic(m_inst, "foo");
+  auto topic2 = nt::GetTopic(m_inst, "bar");
+  auto pub1 = nt::Publish(topic1, NT_DOUBLE, "double");
+  auto pub2 = nt::Publish(topic2, NT_DOUBLE, "double");
+  auto sub1 = nt::Subscribe(topic1, NT_DOUBLE, "double");
+  auto sub2 = nt::Subscribe(topic2, NT_DOUBLE, "double");
+
+  auto poller = nt::CreateListenerPoller(m_inst);
+  auto h1 = nt::AddPolledListener(poller, sub1, nt::EventFlags::kValueLocal);
+  auto h2 = nt::AddPolledListener(poller, sub2, nt::EventFlags::kValueLocal);
+
+  nt::SetDouble(pub1, 0);
+  nt::SetDouble(pub2, 1);
+
+  bool timedOut = false;
+  ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut));
+  ASSERT_FALSE(timedOut);
+  auto results = nt::ReadListenerQueue(poller);
+
+  ASSERT_EQ(results.size(), 2u);
+  EXPECT_EQ(results[0].flags, nt::EventFlags::kValueLocal);
+  EXPECT_EQ(results[0].listener, h1);
+  auto valueData = results[0].GetValueEventData();
+  ASSERT_TRUE(valueData);
+  EXPECT_EQ(valueData->subentry, sub1);
+  EXPECT_EQ(valueData->topic, topic1);
+  EXPECT_EQ(valueData->value, nt::Value::MakeDouble(0.0));
+
+  EXPECT_EQ(results[1].flags, nt::EventFlags::kValueLocal);
+  EXPECT_EQ(results[1].listener, h2);
+  valueData = results[1].GetValueEventData();
+  ASSERT_TRUE(valueData);
+  EXPECT_EQ(valueData->subentry, sub2);
+  EXPECT_EQ(valueData->topic, topic2);
+  EXPECT_EQ(valueData->value, nt::Value::MakeDouble(1.0));
+}
+
+TEST_F(ValueListenerTest, PollSubMultiple) {
+  auto topic1 = nt::GetTopic(m_inst, "foo/1");
+  auto topic2 = nt::GetTopic(m_inst, "foo/2");
+  auto pub1 = nt::Publish(topic1, NT_DOUBLE, "double");
+  auto pub2 = nt::Publish(topic2, NT_DOUBLE, "double");
+  auto sub = nt::SubscribeMultiple(m_inst, {{"foo"}});
+
+  auto poller = nt::CreateListenerPoller(m_inst);
+  auto h = nt::AddPolledListener(poller, sub, nt::EventFlags::kValueLocal);
+
+  nt::SetDouble(pub1, 0);
+  nt::SetDouble(pub2, 1);
+
+  bool timedOut = false;
+  ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut));
+  ASSERT_FALSE(timedOut);
+  auto results = nt::ReadListenerQueue(poller);
+
+  ASSERT_EQ(results.size(), 2u);
+  EXPECT_EQ(results[0].flags, nt::EventFlags::kValueLocal);
+  EXPECT_EQ(results[0].listener, h);
+  auto valueData = results[0].GetValueEventData();
+  ASSERT_TRUE(valueData);
+  EXPECT_EQ(valueData->subentry, sub);
+  EXPECT_EQ(valueData->topic, topic1);
+  EXPECT_EQ(valueData->value, nt::Value::MakeDouble(0.0));
+
+  EXPECT_EQ(results[1].flags, nt::EventFlags::kValueLocal);
+  EXPECT_EQ(results[1].listener, h);
+  valueData = results[1].GetValueEventData();
+  ASSERT_TRUE(valueData);
+  EXPECT_EQ(valueData->subentry, sub);
+  EXPECT_EQ(valueData->topic, topic2);
+  EXPECT_EQ(valueData->value, nt::Value::MakeDouble(1.0));
+}
+
+TEST_F(ValueListenerTest, PollSubPrefixCreated) {
+  auto poller = nt::CreateListenerPoller(m_inst);
+  auto h =
+      nt::AddPolledListener(poller, {{"foo"}}, nt::EventFlags::kValueLocal);
+
+  auto topic1 = nt::GetTopic(m_inst, "foo/1");
+  auto topic2 = nt::GetTopic(m_inst, "foo/2");
+  auto topic3 = nt::GetTopic(m_inst, "bar/3");
+  auto pub1 = nt::Publish(topic1, NT_DOUBLE, "double");
+  auto pub2 = nt::Publish(topic2, NT_DOUBLE, "double");
+  auto pub3 = nt::Publish(topic3, NT_DOUBLE, "double");
+
+  nt::SetDouble(pub1, 0);
+  nt::SetDouble(pub2, 1);
+  nt::SetDouble(pub3, 1);
+
+  bool timedOut = false;
+  ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut));
+  ASSERT_FALSE(timedOut);
+  auto results = nt::ReadListenerQueue(poller);
+
+  ASSERT_EQ(results.size(), 2u);
+  EXPECT_EQ(results[0].flags, nt::EventFlags::kValueLocal);
+  EXPECT_EQ(results[0].listener, h);
+  auto valueData = results[0].GetValueEventData();
+  ASSERT_TRUE(valueData);
+  EXPECT_EQ(valueData->topic, topic1);
+  EXPECT_EQ(valueData->value, nt::Value::MakeDouble(0.0));
+
+  EXPECT_EQ(results[1].flags, nt::EventFlags::kValueLocal);
+  EXPECT_EQ(results[1].listener, h);
+  valueData = results[1].GetValueEventData();
+  ASSERT_TRUE(valueData);
+  EXPECT_EQ(valueData->topic, topic2);
+  EXPECT_EQ(valueData->value, nt::Value::MakeDouble(1.0));
+}
+
+TEST_F(ValueListenerTest, PollEntry) {
+  auto entry = nt::GetEntry(m_inst, "foo");
+
+  auto poller = nt::CreateListenerPoller(m_inst);
+  auto h = nt::AddPolledListener(poller, entry, nt::EventFlags::kValueLocal);
+
+  ASSERT_TRUE(nt::SetDouble(entry, 0));
+
+  bool timedOut = false;
+  ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut));
+  ASSERT_FALSE(timedOut);
+  auto results = nt::ReadListenerQueue(poller);
+
+  ASSERT_EQ(results.size(), 1u);
+  EXPECT_EQ(results[0].flags, nt::EventFlags::kValueLocal);
+  EXPECT_EQ(results[0].listener, h);
+  auto valueData = results[0].GetValueEventData();
+  ASSERT_TRUE(valueData);
+  EXPECT_EQ(valueData->subentry, entry);
+  EXPECT_EQ(valueData->topic, nt::GetTopic(m_inst, "foo"));
+  EXPECT_EQ(valueData->value, nt::Value::MakeDouble(0.0));
+}
+
+TEST_F(ValueListenerTest, PollImmediate) {
+  auto entry = nt::GetEntry(m_inst, "foo");
+  ASSERT_TRUE(nt::SetDouble(entry, 0));
+
+  auto poller = nt::CreateListenerPoller(m_inst);
+  auto h = nt::AddPolledListener(
+      poller, entry, nt::EventFlags::kValueLocal | nt::EventFlags::kImmediate);
+
+  bool timedOut = false;
+  ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut));
+  ASSERT_FALSE(timedOut);
+  auto results = nt::ReadListenerQueue(poller);
+
+  ASSERT_EQ(results.size(), 1u);
+  EXPECT_EQ(results[0].flags &
+                (nt::EventFlags::kValueLocal | nt::EventFlags::kImmediate),
+            nt::EventFlags::kValueLocal | nt::EventFlags::kImmediate);
+  EXPECT_EQ(results[0].listener, h);
+  auto valueData = results[0].GetValueEventData();
+  ASSERT_TRUE(valueData);
+  EXPECT_EQ(valueData->subentry, entry);
+  EXPECT_EQ(valueData->topic, nt::GetTopic(m_inst, "foo"));
+  EXPECT_EQ(valueData->value, nt::Value::MakeDouble(0.0));
+}
+
+TEST_F(ValueListenerTest, PollImmediateNoValue) {
+  auto entry = nt::GetEntry(m_inst, "foo");
+
+  auto poller = nt::CreateListenerPoller(m_inst);
+  auto h = nt::AddPolledListener(
+      poller, entry, nt::EventFlags::kValueLocal | nt::EventFlags::kImmediate);
+
+  bool timedOut = false;
+  ASSERT_FALSE(wpi::WaitForObject(poller, 0.02, &timedOut));
+  ASSERT_TRUE(timedOut);
+  auto results = nt::ReadListenerQueue(poller);
+  ASSERT_TRUE(results.empty());
+
+  // now set a value
+  ASSERT_TRUE(nt::SetDouble(entry, 0));
+
+  ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut));
+  results = nt::ReadListenerQueue(poller);
+  ASSERT_FALSE(timedOut);
+
+  ASSERT_EQ(results.size(), 1u);
+  EXPECT_EQ(results[0].flags, nt::EventFlags::kValueLocal);
+  EXPECT_EQ(results[0].listener, h);
+  auto valueData = results[0].GetValueEventData();
+  ASSERT_TRUE(valueData);
+  EXPECT_EQ(valueData->subentry, entry);
+  EXPECT_EQ(valueData->topic, nt::GetTopic(m_inst, "foo"));
+  EXPECT_EQ(valueData->value, nt::Value::MakeDouble(0.0));
+}
+
+TEST_F(ValueListenerTest, PollImmediateSubMultiple) {
+  auto topic1 = nt::GetTopic(m_inst, "foo/1");
+  auto topic2 = nt::GetTopic(m_inst, "foo/2");
+  auto pub1 = nt::Publish(topic1, NT_DOUBLE, "double");
+  auto pub2 = nt::Publish(topic2, NT_DOUBLE, "double");
+  auto sub = nt::SubscribeMultiple(m_inst, {{"foo"}});
+  nt::SetDouble(pub1, 0);
+  nt::SetDouble(pub2, 1);
+
+  auto poller = nt::CreateListenerPoller(m_inst);
+  auto h = nt::AddPolledListener(
+      poller, sub, nt::EventFlags::kValueLocal | nt::EventFlags::kImmediate);
+
+  bool timedOut = false;
+  ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut));
+  ASSERT_FALSE(timedOut);
+  auto results = nt::ReadListenerQueue(poller);
+
+  ASSERT_EQ(results.size(), 2u);
+  EXPECT_EQ(results[0].flags &
+                (nt::EventFlags::kValueLocal | nt::EventFlags::kImmediate),
+            nt::EventFlags::kValueLocal | nt::EventFlags::kImmediate);
+  EXPECT_EQ(results[0].listener, h);
+  auto valueData = results[0].GetValueEventData();
+  ASSERT_TRUE(valueData);
+  EXPECT_EQ(valueData->subentry, sub);
+  EXPECT_EQ(valueData->topic, topic1);
+  EXPECT_EQ(valueData->value, nt::Value::MakeDouble(0.0));
+
+  EXPECT_EQ(results[1].flags &
+                (nt::EventFlags::kValueLocal | nt::EventFlags::kImmediate),
+            nt::EventFlags::kValueLocal | nt::EventFlags::kImmediate);
+  EXPECT_EQ(results[1].listener, h);
+  valueData = results[1].GetValueEventData();
+  ASSERT_TRUE(valueData);
+  EXPECT_EQ(valueData->subentry, sub);
+  EXPECT_EQ(valueData->topic, topic2);
+  EXPECT_EQ(valueData->value, nt::Value::MakeDouble(1.0));
+}
+
+TEST_F(ValueListenerTest, TwoSubOneListener) {
+  auto topic = nt::GetTopic(m_inst, "foo");
+  auto pub = nt::Publish(topic, NT_DOUBLE, "double");
+  auto sub1 = nt::Subscribe(topic, NT_DOUBLE, "double");
+  auto sub2 = nt::Subscribe(topic, NT_DOUBLE, "double");
+  auto sub3 = nt::SubscribeMultiple(m_inst, {{"foo"}});
+
+  auto poller = nt::CreateListenerPoller(m_inst);
+  auto h = nt::AddPolledListener(poller, sub1, nt::EventFlags::kValueLocal);
+  (void)sub2;
+  (void)sub3;
+
+  nt::SetDouble(pub, 0);
+
+  bool timedOut = false;
+  ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut));
+  ASSERT_FALSE(timedOut);
+  auto results = nt::ReadListenerQueue(poller);
+
+  ASSERT_EQ(results.size(), 1u);
+  EXPECT_EQ(results[0].flags & nt::EventFlags::kValueLocal,
+            nt::EventFlags::kValueLocal);
+  EXPECT_EQ(results[0].listener, h);
+  auto valueData = results[0].GetValueEventData();
+  ASSERT_TRUE(valueData);
+  EXPECT_EQ(valueData->subentry, sub1);
+  EXPECT_EQ(valueData->topic, topic);
+  EXPECT_EQ(valueData->value, nt::Value::MakeDouble(0.0));
+}
+
+TEST_F(ValueListenerTest, TwoSubOneMultiListener) {
+  auto topic = nt::GetTopic(m_inst, "foo");
+  auto pub = nt::Publish(topic, NT_DOUBLE, "double");
+  auto sub1 = nt::Subscribe(topic, NT_DOUBLE, "double");
+  auto sub2 = nt::Subscribe(topic, NT_DOUBLE, "double");
+  auto sub3 = nt::SubscribeMultiple(m_inst, {{"foo"}});
+
+  auto poller = nt::CreateListenerPoller(m_inst);
+  auto h = nt::AddPolledListener(poller, sub3, nt::EventFlags::kValueLocal);
+  (void)sub1;
+  (void)sub2;
+
+  nt::SetDouble(pub, 0);
+
+  bool timedOut = false;
+  ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut));
+  ASSERT_FALSE(timedOut);
+  auto results = nt::ReadListenerQueue(poller);
+
+  ASSERT_EQ(results.size(), 1u);
+  EXPECT_EQ(results[0].flags & nt::EventFlags::kValueLocal,
+            nt::EventFlags::kValueLocal);
+  EXPECT_EQ(results[0].listener, h);
+  auto valueData = results[0].GetValueEventData();
+  ASSERT_TRUE(valueData);
+  EXPECT_EQ(valueData->subentry, sub3);
+  EXPECT_EQ(valueData->topic, topic);
+  EXPECT_EQ(valueData->value, nt::Value::MakeDouble(0.0));
+}
+
+}  // namespace nt
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/ValueMatcher.cpp b/third_party/allwpilib/ntcore/src/test/native/cpp/ValueMatcher.cpp
index 1f55c01..7a0d453 100644
--- a/third_party/allwpilib/ntcore/src/test/native/cpp/ValueMatcher.cpp
+++ b/third_party/allwpilib/ntcore/src/test/native/cpp/ValueMatcher.cpp
@@ -9,10 +9,9 @@
 namespace nt {
 
 bool ValueMatcher::MatchAndExplain(
-    std::shared_ptr<Value> val,
-    ::testing::MatchResultListener* listener) const {
+    Value val, ::testing::MatchResultListener* listener) const {
   if ((!val && goodval) || (val && !goodval) ||
-      (val && goodval && *val != *goodval)) {
+      (val && goodval && val != goodval)) {
     return false;
   }
   return true;
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/ValueMatcher.h b/third_party/allwpilib/ntcore/src/test/native/cpp/ValueMatcher.h
index ab68448..c77e04d 100644
--- a/third_party/allwpilib/ntcore/src/test/native/cpp/ValueMatcher.h
+++ b/third_party/allwpilib/ntcore/src/test/native/cpp/ValueMatcher.h
@@ -2,8 +2,7 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
-#ifndef NTCORE_VALUEMATCHER_H_
-#define NTCORE_VALUEMATCHER_H_
+#pragma once
 
 #include <memory>
 #include <ostream>
@@ -14,26 +13,21 @@
 
 namespace nt {
 
-class ValueMatcher
-    : public ::testing::MatcherInterface<std::shared_ptr<Value>> {
+class ValueMatcher : public ::testing::MatcherInterface<Value> {
  public:
-  explicit ValueMatcher(std::shared_ptr<Value> goodval_)
-      : goodval(std::move(goodval_)) {}
+  explicit ValueMatcher(Value goodval_) : goodval(std::move(goodval_)) {}
 
-  bool MatchAndExplain(std::shared_ptr<Value> msg,
+  bool MatchAndExplain(Value msg,
                        ::testing::MatchResultListener* listener) const override;
   void DescribeTo(::std::ostream* os) const override;
   void DescribeNegationTo(::std::ostream* os) const override;
 
  private:
-  std::shared_ptr<Value> goodval;
+  Value goodval;
 };
 
-inline ::testing::Matcher<std::shared_ptr<Value>> ValueEq(
-    std::shared_ptr<Value> goodval) {
+inline ::testing::Matcher<Value> ValueEq(const Value& goodval) {
   return ::testing::MakeMatcher(new ValueMatcher(goodval));
 }
 
 }  // namespace nt
-
-#endif  // NTCORE_VALUEMATCHER_H_
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/ValueTest.cpp b/third_party/allwpilib/ntcore/src/test/native/cpp/ValueTest.cpp
index a9f2218..d49be44 100644
--- a/third_party/allwpilib/ntcore/src/test/native/cpp/ValueTest.cpp
+++ b/third_party/allwpilib/ntcore/src/test/native/cpp/ValueTest.cpp
@@ -12,15 +12,15 @@
 
 using namespace std::string_view_literals;
 
-namespace wpi {
-template <typename T>
-inline bool operator==(span<T> lhs, span<T> rhs) {
+namespace std {  // NOLINT (clang-tidy.cert-dcl58-cpp)
+template <typename T, typename U>
+inline bool operator==(std::span<T> lhs, std::span<U> rhs) {
   if (lhs.size() != rhs.size()) {
     return false;
   }
   return std::equal(lhs.begin(), lhs.end(), rhs.begin());
 }
-}  // namespace wpi
+}  // namespace std
 
 namespace nt {
 
@@ -35,19 +35,19 @@
 
 TEST_F(ValueTest, Boolean) {
   auto v = Value::MakeBoolean(false);
-  ASSERT_EQ(NT_BOOLEAN, v->type());
-  ASSERT_FALSE(v->GetBoolean());
+  ASSERT_EQ(NT_BOOLEAN, v.type());
+  ASSERT_FALSE(v.GetBoolean());
   NT_Value cv;
   NT_InitValue(&cv);
-  ConvertToC(*v, &cv);
+  ConvertToC(v, &cv);
   ASSERT_EQ(NT_BOOLEAN, cv.type);
   ASSERT_EQ(0, cv.data.v_boolean);
 
   v = Value::MakeBoolean(true);
-  ASSERT_EQ(NT_BOOLEAN, v->type());
-  ASSERT_TRUE(v->GetBoolean());
+  ASSERT_EQ(NT_BOOLEAN, v.type());
+  ASSERT_TRUE(v.GetBoolean());
   NT_DisposeValue(&cv);
-  ConvertToC(*v, &cv);
+  ConvertToC(v, &cv);
   ASSERT_EQ(NT_BOOLEAN, cv.type);
   ASSERT_EQ(1, cv.data.v_boolean);
 
@@ -56,19 +56,19 @@
 
 TEST_F(ValueTest, Double) {
   auto v = Value::MakeDouble(0.5);
-  ASSERT_EQ(NT_DOUBLE, v->type());
-  ASSERT_EQ(0.5, v->GetDouble());
+  ASSERT_EQ(NT_DOUBLE, v.type());
+  ASSERT_EQ(0.5, v.GetDouble());
   NT_Value cv;
   NT_InitValue(&cv);
-  ConvertToC(*v, &cv);
+  ConvertToC(v, &cv);
   ASSERT_EQ(NT_DOUBLE, cv.type);
   ASSERT_EQ(0.5, cv.data.v_double);
 
   v = Value::MakeDouble(0.25);
-  ASSERT_EQ(NT_DOUBLE, v->type());
-  ASSERT_EQ(0.25, v->GetDouble());
+  ASSERT_EQ(NT_DOUBLE, v.type());
+  ASSERT_EQ(0.25, v.GetDouble());
   NT_DisposeValue(&cv);
-  ConvertToC(*v, &cv);
+  ConvertToC(v, &cv);
   ASSERT_EQ(NT_DOUBLE, cv.type);
   ASSERT_EQ(0.25, cv.data.v_double);
 
@@ -77,20 +77,20 @@
 
 TEST_F(ValueTest, String) {
   auto v = Value::MakeString("hello");
-  ASSERT_EQ(NT_STRING, v->type());
-  ASSERT_EQ("hello", v->GetString());
+  ASSERT_EQ(NT_STRING, v.type());
+  ASSERT_EQ("hello", v.GetString());
   NT_Value cv;
   NT_InitValue(&cv);
-  ConvertToC(*v, &cv);
+  ConvertToC(v, &cv);
   ASSERT_EQ(NT_STRING, cv.type);
   ASSERT_EQ("hello"sv, cv.data.v_string.str);
   ASSERT_EQ(5u, cv.data.v_string.len);
 
   v = Value::MakeString("goodbye");
-  ASSERT_EQ(NT_STRING, v->type());
-  ASSERT_EQ("goodbye", v->GetString());
+  ASSERT_EQ(NT_STRING, v.type());
+  ASSERT_EQ("goodbye", v.GetString());
   NT_DisposeValue(&cv);
-  ConvertToC(*v, &cv);
+  ConvertToC(v, &cv);
   ASSERT_EQ(NT_STRING, cv.type);
   ASSERT_EQ("goodbye"sv, cv.data.v_string.str);
   ASSERT_EQ(7u, cv.data.v_string.len);
@@ -99,24 +99,28 @@
 }
 
 TEST_F(ValueTest, Raw) {
-  auto v = Value::MakeRaw("hello");
-  ASSERT_EQ(NT_RAW, v->type());
-  ASSERT_EQ("hello", v->GetRaw());
+  std::vector<uint8_t> arr{5, 4, 3, 2, 1};
+  auto v = Value::MakeRaw(arr);
+  ASSERT_EQ(NT_RAW, v.type());
+  ASSERT_EQ(std::span<const uint8_t>(arr), v.GetRaw());
   NT_Value cv;
   NT_InitValue(&cv);
-  ConvertToC(*v, &cv);
+  ConvertToC(v, &cv);
   ASSERT_EQ(NT_RAW, cv.type);
-  ASSERT_EQ("hello"sv, cv.data.v_string.str);
-  ASSERT_EQ(5u, cv.data.v_string.len);
+  ASSERT_EQ(5u, cv.data.v_raw.size);
+  ASSERT_EQ(std::span(reinterpret_cast<const uint8_t*>("\5\4\3\2\1"), 5),
+            std::span(cv.data.v_raw.data, 5));
 
-  v = Value::MakeRaw("goodbye");
-  ASSERT_EQ(NT_RAW, v->type());
-  ASSERT_EQ("goodbye", v->GetRaw());
+  std::vector<uint8_t> arr2{1, 2, 3, 4, 5, 6};
+  v = Value::MakeRaw(arr2);
+  ASSERT_EQ(NT_RAW, v.type());
+  ASSERT_EQ(std::span<const uint8_t>(arr2), v.GetRaw());
   NT_DisposeValue(&cv);
-  ConvertToC(*v, &cv);
+  ConvertToC(v, &cv);
   ASSERT_EQ(NT_RAW, cv.type);
-  ASSERT_EQ("goodbye"sv, cv.data.v_string.str);
-  ASSERT_EQ(7u, cv.data.v_string.len);
+  ASSERT_EQ(6u, cv.data.v_raw.size);
+  ASSERT_EQ(std::span(reinterpret_cast<const uint8_t*>("\1\2\3\4\5\6"), 6),
+            std::span(cv.data.v_raw.data, 6));
 
   NT_DisposeValue(&cv);
 }
@@ -124,11 +128,11 @@
 TEST_F(ValueTest, BooleanArray) {
   std::vector<int> vec{1, 0, 1};
   auto v = Value::MakeBooleanArray(vec);
-  ASSERT_EQ(NT_BOOLEAN_ARRAY, v->type());
-  ASSERT_EQ(wpi::span<const int>(vec), v->GetBooleanArray());
+  ASSERT_EQ(NT_BOOLEAN_ARRAY, v.type());
+  ASSERT_EQ(std::span<const int>(vec), v.GetBooleanArray());
   NT_Value cv;
   NT_InitValue(&cv);
-  ConvertToC(*v, &cv);
+  ConvertToC(v, &cv);
   ASSERT_EQ(NT_BOOLEAN_ARRAY, cv.type);
   ASSERT_EQ(3u, cv.data.arr_boolean.size);
   ASSERT_EQ(vec[0], cv.data.arr_boolean.arr[0]);
@@ -138,10 +142,10 @@
   // assign with same size
   vec = {0, 1, 0};
   v = Value::MakeBooleanArray(vec);
-  ASSERT_EQ(NT_BOOLEAN_ARRAY, v->type());
-  ASSERT_EQ(wpi::span<const int>(vec), v->GetBooleanArray());
+  ASSERT_EQ(NT_BOOLEAN_ARRAY, v.type());
+  ASSERT_EQ(std::span<const int>(vec), v.GetBooleanArray());
   NT_DisposeValue(&cv);
-  ConvertToC(*v, &cv);
+  ConvertToC(v, &cv);
   ASSERT_EQ(NT_BOOLEAN_ARRAY, cv.type);
   ASSERT_EQ(3u, cv.data.arr_boolean.size);
   ASSERT_EQ(vec[0], cv.data.arr_boolean.arr[0]);
@@ -151,10 +155,10 @@
   // assign with different size
   vec = {1, 0};
   v = Value::MakeBooleanArray(vec);
-  ASSERT_EQ(NT_BOOLEAN_ARRAY, v->type());
-  ASSERT_EQ(wpi::span<const int>(vec), v->GetBooleanArray());
+  ASSERT_EQ(NT_BOOLEAN_ARRAY, v.type());
+  ASSERT_EQ(std::span<const int>(vec), v.GetBooleanArray());
   NT_DisposeValue(&cv);
-  ConvertToC(*v, &cv);
+  ConvertToC(v, &cv);
   ASSERT_EQ(NT_BOOLEAN_ARRAY, cv.type);
   ASSERT_EQ(2u, cv.data.arr_boolean.size);
   ASSERT_EQ(vec[0], cv.data.arr_boolean.arr[0]);
@@ -166,11 +170,11 @@
 TEST_F(ValueTest, DoubleArray) {
   std::vector<double> vec{0.5, 0.25, 0.5};
   auto v = Value::MakeDoubleArray(vec);
-  ASSERT_EQ(NT_DOUBLE_ARRAY, v->type());
-  ASSERT_EQ(wpi::span<const double>(vec), v->GetDoubleArray());
+  ASSERT_EQ(NT_DOUBLE_ARRAY, v.type());
+  ASSERT_EQ(std::span<const double>(vec), v.GetDoubleArray());
   NT_Value cv;
   NT_InitValue(&cv);
-  ConvertToC(*v, &cv);
+  ConvertToC(v, &cv);
   ASSERT_EQ(NT_DOUBLE_ARRAY, cv.type);
   ASSERT_EQ(3u, cv.data.arr_double.size);
   ASSERT_EQ(vec[0], cv.data.arr_double.arr[0]);
@@ -180,10 +184,10 @@
   // assign with same size
   vec = {0.25, 0.5, 0.25};
   v = Value::MakeDoubleArray(vec);
-  ASSERT_EQ(NT_DOUBLE_ARRAY, v->type());
-  ASSERT_EQ(wpi::span<const double>(vec), v->GetDoubleArray());
+  ASSERT_EQ(NT_DOUBLE_ARRAY, v.type());
+  ASSERT_EQ(std::span<const double>(vec), v.GetDoubleArray());
   NT_DisposeValue(&cv);
-  ConvertToC(*v, &cv);
+  ConvertToC(v, &cv);
   ASSERT_EQ(NT_DOUBLE_ARRAY, cv.type);
   ASSERT_EQ(3u, cv.data.arr_double.size);
   ASSERT_EQ(vec[0], cv.data.arr_double.arr[0]);
@@ -193,10 +197,10 @@
   // assign with different size
   vec = {0.5, 0.25};
   v = Value::MakeDoubleArray(vec);
-  ASSERT_EQ(NT_DOUBLE_ARRAY, v->type());
-  ASSERT_EQ(wpi::span<const double>(vec), v->GetDoubleArray());
+  ASSERT_EQ(NT_DOUBLE_ARRAY, v.type());
+  ASSERT_EQ(std::span<const double>(vec), v.GetDoubleArray());
   NT_DisposeValue(&cv);
-  ConvertToC(*v, &cv);
+  ConvertToC(v, &cv);
   ASSERT_EQ(NT_DOUBLE_ARRAY, cv.type);
   ASSERT_EQ(2u, cv.data.arr_double.size);
   ASSERT_EQ(vec[0], cv.data.arr_double.arr[0]);
@@ -211,14 +215,14 @@
   vec.push_back("goodbye");
   vec.push_back("string");
   auto v = Value::MakeStringArray(std::move(vec));
-  ASSERT_EQ(NT_STRING_ARRAY, v->type());
-  ASSERT_EQ(3u, v->GetStringArray().size());
-  ASSERT_EQ("hello"sv, v->GetStringArray()[0]);
-  ASSERT_EQ("goodbye"sv, v->GetStringArray()[1]);
-  ASSERT_EQ("string"sv, v->GetStringArray()[2]);
+  ASSERT_EQ(NT_STRING_ARRAY, v.type());
+  ASSERT_EQ(3u, v.GetStringArray().size());
+  ASSERT_EQ("hello"sv, v.GetStringArray()[0]);
+  ASSERT_EQ("goodbye"sv, v.GetStringArray()[1]);
+  ASSERT_EQ("string"sv, v.GetStringArray()[2]);
   NT_Value cv;
   NT_InitValue(&cv);
-  ConvertToC(*v, &cv);
+  ConvertToC(v, &cv);
   ASSERT_EQ(NT_STRING_ARRAY, cv.type);
   ASSERT_EQ(3u, cv.data.arr_string.size);
   ASSERT_EQ("hello"sv, cv.data.arr_string.arr[0].str);
@@ -231,13 +235,13 @@
   vec.push_back("str2");
   vec.push_back("string3");
   v = Value::MakeStringArray(vec);
-  ASSERT_EQ(NT_STRING_ARRAY, v->type());
-  ASSERT_EQ(3u, v->GetStringArray().size());
-  ASSERT_EQ("s1"sv, v->GetStringArray()[0]);
-  ASSERT_EQ("str2"sv, v->GetStringArray()[1]);
-  ASSERT_EQ("string3"sv, v->GetStringArray()[2]);
+  ASSERT_EQ(NT_STRING_ARRAY, v.type());
+  ASSERT_EQ(3u, v.GetStringArray().size());
+  ASSERT_EQ("s1"sv, v.GetStringArray()[0]);
+  ASSERT_EQ("str2"sv, v.GetStringArray()[1]);
+  ASSERT_EQ("string3"sv, v.GetStringArray()[2]);
   NT_DisposeValue(&cv);
-  ConvertToC(*v, &cv);
+  ConvertToC(v, &cv);
   ASSERT_EQ(NT_STRING_ARRAY, cv.type);
   ASSERT_EQ(3u, cv.data.arr_string.size);
   ASSERT_EQ("s1"sv, cv.data.arr_string.arr[0].str);
@@ -249,12 +253,12 @@
   vec.push_back("short");
   vec.push_back("er");
   v = Value::MakeStringArray(std::move(vec));
-  ASSERT_EQ(NT_STRING_ARRAY, v->type());
-  ASSERT_EQ(2u, v->GetStringArray().size());
-  ASSERT_EQ("short"sv, v->GetStringArray()[0]);
-  ASSERT_EQ("er"sv, v->GetStringArray()[1]);
+  ASSERT_EQ(NT_STRING_ARRAY, v.type());
+  ASSERT_EQ(2u, v.GetStringArray().size());
+  ASSERT_EQ("short"sv, v.GetStringArray()[0]);
+  ASSERT_EQ("er"sv, v.GetStringArray()[1]);
   NT_DisposeValue(&cv);
-  ConvertToC(*v, &cv);
+  ConvertToC(v, &cv);
   ASSERT_EQ(NT_STRING_ARRAY, cv.type);
   ASSERT_EQ(2u, cv.data.arr_string.size);
   ASSERT_EQ("short"sv, cv.data.arr_string.arr[0].str);
@@ -286,69 +290,69 @@
 TEST_F(ValueTest, MixedComparison) {
   Value v1;
   auto v2 = Value::MakeBoolean(true);
-  ASSERT_NE(v1, *v2);  // unassigned vs boolean
+  ASSERT_NE(v1, v2);  // unassigned vs boolean
   auto v3 = Value::MakeDouble(0.5);
-  ASSERT_NE(*v2, *v3);  // boolean vs double
+  ASSERT_NE(v2, v3);  // boolean vs double
 }
 
 TEST_F(ValueTest, BooleanComparison) {
   auto v1 = Value::MakeBoolean(true);
   auto v2 = Value::MakeBoolean(true);
-  ASSERT_EQ(*v1, *v2);
+  ASSERT_EQ(v1, v2);
   v2 = Value::MakeBoolean(false);
-  ASSERT_NE(*v1, *v2);
+  ASSERT_NE(v1, v2);
 }
 
 TEST_F(ValueTest, DoubleComparison) {
   auto v1 = Value::MakeDouble(0.25);
   auto v2 = Value::MakeDouble(0.25);
-  ASSERT_EQ(*v1, *v2);
+  ASSERT_EQ(v1, v2);
   v2 = Value::MakeDouble(0.5);
-  ASSERT_NE(*v1, *v2);
+  ASSERT_NE(v1, v2);
 }
 
 TEST_F(ValueTest, StringComparison) {
   auto v1 = Value::MakeString("hello");
   auto v2 = Value::MakeString("hello");
-  ASSERT_EQ(*v1, *v2);
+  ASSERT_EQ(v1, v2);
   v2 = Value::MakeString("world");  // different contents
-  ASSERT_NE(*v1, *v2);
+  ASSERT_NE(v1, v2);
   v2 = Value::MakeString("goodbye");  // different size
-  ASSERT_NE(*v1, *v2);
+  ASSERT_NE(v1, v2);
 }
 
 TEST_F(ValueTest, BooleanArrayComparison) {
   std::vector<int> vec{1, 0, 1};
   auto v1 = Value::MakeBooleanArray(vec);
   auto v2 = Value::MakeBooleanArray(vec);
-  ASSERT_EQ(*v1, *v2);
+  ASSERT_EQ(v1, v2);
 
   // different contents
   vec = {1, 1, 1};
   v2 = Value::MakeBooleanArray(vec);
-  ASSERT_NE(*v1, *v2);
+  ASSERT_NE(v1, v2);
 
   // different size
   vec = {1, 0};
   v2 = Value::MakeBooleanArray(vec);
-  ASSERT_NE(*v1, *v2);
+  ASSERT_NE(v1, v2);
 }
 
 TEST_F(ValueTest, DoubleArrayComparison) {
   std::vector<double> vec{0.5, 0.25, 0.5};
   auto v1 = Value::MakeDoubleArray(vec);
   auto v2 = Value::MakeDoubleArray(vec);
-  ASSERT_EQ(*v1, *v2);
+  ASSERT_EQ(v1, v2);
 
   // different contents
   vec = {0.5, 0.5, 0.5};
   v2 = Value::MakeDoubleArray(vec);
-  ASSERT_NE(*v1, *v2);
+  ASSERT_NE(v1, v2);
 
   // different size
   vec = {0.5, 0.25};
   v2 = Value::MakeDoubleArray(vec);
-  ASSERT_NE(*v1, *v2);
+  ASSERT_NE(v1, v2);
 }
 
 TEST_F(ValueTest, StringArrayComparison) {
@@ -362,7 +366,7 @@
   vec.push_back("goodbye");
   vec.push_back("string");
   auto v2 = Value::MakeStringArray(std::move(vec));
-  ASSERT_EQ(*v1, *v2);
+  ASSERT_EQ(v1, v2);
 
   // different contents
   vec.clear();
@@ -370,7 +374,7 @@
   vec.push_back("goodby2");
   vec.push_back("string");
   v2 = Value::MakeStringArray(std::move(vec));
-  ASSERT_NE(*v1, *v2);
+  ASSERT_NE(v1, v2);
 
   // different sized contents
   vec.clear();
@@ -378,14 +382,14 @@
   vec.push_back("goodbye2");
   vec.push_back("string");
   v2 = Value::MakeStringArray(vec);
-  ASSERT_NE(*v1, *v2);
+  ASSERT_NE(v1, v2);
 
   // different size
   vec.clear();
   vec.push_back("hello");
   vec.push_back("goodbye");
   v2 = Value::MakeStringArray(std::move(vec));
-  ASSERT_NE(*v1, *v2);
+  ASSERT_NE(v1, v2);
 }
 
 }  // namespace nt
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/WireDecoderTest.cpp b/third_party/allwpilib/ntcore/src/test/native/cpp/WireDecoderTest.cpp
deleted file mode 100644
index 313fd98..0000000
--- a/third_party/allwpilib/ntcore/src/test/native/cpp/WireDecoderTest.cpp
+++ /dev/null
@@ -1,647 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include <stdint.h>
-
-#include <cfloat>
-#include <climits>
-#include <string>
-#include <string_view>
-
-#include "TestPrinters.h"
-#include "WireDecoder.h"
-#include "gtest/gtest.h"
-
-using namespace std::string_view_literals;
-
-namespace nt {
-
-class WireDecoderTest : public ::testing::Test {
- protected:
-  WireDecoderTest() {
-    v_boolean = Value::MakeBoolean(true);
-    v_double = Value::MakeDouble(1.0);
-    v_string = Value::MakeString("hello"sv);
-    v_raw = Value::MakeRaw("hello"sv);
-    v_boolean_array = Value::MakeBooleanArray(std::vector<int>{0, 1, 0});
-    v_boolean_array_big = Value::MakeBooleanArray(std::vector<int>(255));
-    v_double_array = Value::MakeDoubleArray(std::vector<double>{0.5, 0.25});
-    v_double_array_big = Value::MakeDoubleArray(std::vector<double>(255));
-
-    std::vector<std::string> sa;
-    sa.push_back("hello");
-    sa.push_back("goodbye");
-    v_string_array = Value::MakeStringArray(std::move(sa));
-
-    sa.clear();
-    for (int i = 0; i < 255; ++i) {
-      sa.push_back("h");
-    }
-    v_string_array_big = Value::MakeStringArray(std::move(sa));
-
-    s_normal = std::string("hello");
-
-    s_long.clear();
-    s_long.append(127, '*');
-    s_long.push_back('x');
-
-    s_big2.clear();
-    s_big2.append(65534, '*');
-    s_big2.push_back('x');
-
-    s_big3.clear();
-    s_big3.append(65534, '*');
-    s_big3.append(3, 'x');
-  }
-
-  std::shared_ptr<Value> v_boolean, v_double, v_string, v_raw;
-  std::shared_ptr<Value> v_boolean_array, v_boolean_array_big;
-  std::shared_ptr<Value> v_double_array, v_double_array_big;
-  std::shared_ptr<Value> v_string_array, v_string_array_big;
-
-  std::string s_normal, s_long, s_big2, s_big3;
-};
-
-TEST_F(WireDecoderTest, Construct) {
-  wpi::raw_mem_istream is("", 0);
-  wpi::Logger logger;
-  WireDecoder d(is, 0x0300u, logger);
-  EXPECT_EQ(nullptr, d.error());
-  EXPECT_EQ(0x0300u, d.proto_rev());
-}
-
-TEST_F(WireDecoderTest, SetProtoRev) {
-  wpi::raw_mem_istream is("", 0);
-  wpi::Logger logger;
-  WireDecoder d(is, 0x0300u, logger);
-  d.set_proto_rev(0x0200u);
-  EXPECT_EQ(0x0200u, d.proto_rev());
-}
-
-TEST_F(WireDecoderTest, Read8) {
-  wpi::raw_mem_istream is("\x05\x01\x00", 3);
-  wpi::Logger logger;
-  WireDecoder d(is, 0x0300u, logger);
-  unsigned int val;
-  ASSERT_TRUE(d.Read8(&val));
-  EXPECT_EQ(5u, val);
-  ASSERT_TRUE(d.Read8(&val));
-  EXPECT_EQ(1u, val);
-  ASSERT_TRUE(d.Read8(&val));
-  EXPECT_EQ(0u, val);
-  ASSERT_FALSE(d.Read8(&val));
-  ASSERT_EQ(nullptr, d.error());
-}
-
-TEST_F(WireDecoderTest, Read16) {
-  wpi::raw_mem_istream is("\x00\x05\x00\x01\x45\x67\x00\x00", 8);
-  wpi::Logger logger;
-  WireDecoder d(is, 0x0300u, logger);
-  unsigned int val;
-  ASSERT_TRUE(d.Read16(&val));
-  EXPECT_EQ(5u, val);
-  ASSERT_TRUE(d.Read16(&val));
-  EXPECT_EQ(1u, val);
-  ASSERT_TRUE(d.Read16(&val));
-  EXPECT_EQ(0x4567u, val);
-  ASSERT_TRUE(d.Read16(&val));
-  EXPECT_EQ(0u, val);
-  ASSERT_FALSE(d.Read16(&val));
-  ASSERT_EQ(nullptr, d.error());
-}
-
-TEST_F(WireDecoderTest, Read32) {
-  wpi::raw_mem_istream is(
-      "\x00\x00\x00\x05\x00\x00\x00\x01\x00\x00\xab\xcd"
-      "\x12\x34\x56\x78\x00\x00\x00\x00",
-      20);
-  wpi::Logger logger;
-  WireDecoder d(is, 0x0300u, logger);
-  uint32_t val;
-  ASSERT_TRUE(d.Read32(&val));
-  EXPECT_EQ(5ul, val);
-  ASSERT_TRUE(d.Read32(&val));
-  EXPECT_EQ(1ul, val);
-  ASSERT_TRUE(d.Read32(&val));
-  EXPECT_EQ(0xabcdul, val);
-  ASSERT_TRUE(d.Read32(&val));
-  EXPECT_EQ(0x12345678ul, val);
-  ASSERT_TRUE(d.Read32(&val));
-  EXPECT_EQ(0ul, val);
-  ASSERT_FALSE(d.Read32(&val));
-  ASSERT_EQ(nullptr, d.error());
-}
-
-TEST_F(WireDecoderTest, ReadDouble) {
-  // values except min and max from
-  // http://www.binaryconvert.com/result_double.html
-  wpi::raw_mem_istream is(
-      "\x00\x00\x00\x00\x00\x00\x00\x00"
-      "\x41\x0c\x13\x80\x00\x00\x00\x00"
-      "\x7f\xf0\x00\x00\x00\x00\x00\x00"
-      "\x00\x10\x00\x00\x00\x00\x00\x00"
-      "\x7f\xef\xff\xff\xff\xff\xff\xff",
-      40);
-  wpi::Logger logger;
-  WireDecoder d(is, 0x0300u, logger);
-  double val;
-  ASSERT_TRUE(d.ReadDouble(&val));
-  EXPECT_EQ(0.0, val);
-  ASSERT_TRUE(d.ReadDouble(&val));
-  EXPECT_EQ(2.3e5, val);
-  ASSERT_TRUE(d.ReadDouble(&val));
-  EXPECT_EQ(std::numeric_limits<double>::infinity(), val);
-  ASSERT_TRUE(d.ReadDouble(&val));
-  EXPECT_EQ(DBL_MIN, val);
-  ASSERT_TRUE(d.ReadDouble(&val));
-  EXPECT_EQ(DBL_MAX, val);
-  ASSERT_FALSE(d.ReadDouble(&val));
-  ASSERT_EQ(nullptr, d.error());
-}
-
-TEST_F(WireDecoderTest, ReadUleb128) {
-  wpi::raw_mem_istream is("\x00\x7f\x80\x01\x80", 5);
-  wpi::Logger logger;
-  WireDecoder d(is, 0x0300u, logger);
-  uint64_t val;
-  ASSERT_TRUE(d.ReadUleb128(&val));
-  EXPECT_EQ(0ul, val);
-  ASSERT_TRUE(d.ReadUleb128(&val));
-  EXPECT_EQ(0x7ful, val);
-  ASSERT_TRUE(d.ReadUleb128(&val));
-  EXPECT_EQ(0x80ul, val);
-  ASSERT_FALSE(d.ReadUleb128(&val));  // partial
-  ASSERT_EQ(nullptr, d.error());
-}
-
-TEST_F(WireDecoderTest, ReadType) {
-  wpi::raw_mem_istream is("\x00\x01\x02\x03\x10\x11\x12\x20", 8);
-  wpi::Logger logger;
-  WireDecoder d(is, 0x0300u, logger);
-  NT_Type val;
-  ASSERT_TRUE(d.ReadType(&val));
-  EXPECT_EQ(NT_BOOLEAN, val);
-  ASSERT_TRUE(d.ReadType(&val));
-  EXPECT_EQ(NT_DOUBLE, val);
-  ASSERT_TRUE(d.ReadType(&val));
-  EXPECT_EQ(NT_STRING, val);
-  ASSERT_TRUE(d.ReadType(&val));
-  EXPECT_EQ(NT_RAW, val);
-  ASSERT_TRUE(d.ReadType(&val));
-  EXPECT_EQ(NT_BOOLEAN_ARRAY, val);
-  ASSERT_TRUE(d.ReadType(&val));
-  EXPECT_EQ(NT_DOUBLE_ARRAY, val);
-  ASSERT_TRUE(d.ReadType(&val));
-  EXPECT_EQ(NT_STRING_ARRAY, val);
-  ASSERT_TRUE(d.ReadType(&val));
-  EXPECT_EQ(NT_RPC, val);
-  ASSERT_FALSE(d.ReadType(&val));
-  ASSERT_EQ(nullptr, d.error());
-}
-
-TEST_F(WireDecoderTest, ReadTypeError) {
-  wpi::raw_mem_istream is("\x30", 1);
-  wpi::Logger logger;
-  WireDecoder d(is, 0x0200u, logger);
-  NT_Type val;
-  ASSERT_FALSE(d.ReadType(&val));
-  EXPECT_EQ(NT_UNASSIGNED, val);
-  ASSERT_NE(nullptr, d.error());
-}
-
-TEST_F(WireDecoderTest, Reset) {
-  wpi::raw_mem_istream is("\x30", 1);
-  wpi::Logger logger;
-  WireDecoder d(is, 0x0200u, logger);
-  NT_Type val;
-  ASSERT_FALSE(d.ReadType(&val));
-  EXPECT_EQ(NT_UNASSIGNED, val);
-  ASSERT_NE(nullptr, d.error());
-  d.Reset();
-  EXPECT_EQ(nullptr, d.error());
-}
-
-TEST_F(WireDecoderTest, ReadBooleanValue2) {
-  wpi::raw_mem_istream is("\x01\x00", 2);
-  wpi::Logger logger;
-  WireDecoder d(is, 0x0200u, logger);
-  auto val = d.ReadValue(NT_BOOLEAN);
-  ASSERT_TRUE(static_cast<bool>(val));
-  EXPECT_EQ(*v_boolean, *val);
-
-  auto v_false = Value::MakeBoolean(false);
-  val = d.ReadValue(NT_BOOLEAN);
-  ASSERT_TRUE(static_cast<bool>(val));
-  EXPECT_EQ(*v_false, *val);
-
-  ASSERT_FALSE(d.ReadValue(NT_BOOLEAN));
-  ASSERT_EQ(nullptr, d.error());
-}
-
-TEST_F(WireDecoderTest, ReadDoubleValue2) {
-  wpi::raw_mem_istream is(
-      "\x3f\xf0\x00\x00\x00\x00\x00\x00"
-      "\x3f\xf0\x00\x00\x00\x00\x00\x00",
-      16);
-  wpi::Logger logger;
-  WireDecoder d(is, 0x0200u, logger);
-  auto val = d.ReadValue(NT_DOUBLE);
-  ASSERT_TRUE(static_cast<bool>(val));
-  EXPECT_EQ(*v_double, *val);
-
-  val = d.ReadValue(NT_DOUBLE);
-  ASSERT_TRUE(static_cast<bool>(val));
-  EXPECT_EQ(*v_double, *val);
-
-  ASSERT_FALSE(d.ReadValue(NT_DOUBLE));
-  ASSERT_EQ(nullptr, d.error());
-}
-
-TEST_F(WireDecoderTest, ReadStringValue2) {
-  wpi::raw_mem_istream is(
-      "\x00\x05hello\x00\x03"
-      "bye\x55",
-      13);
-  wpi::Logger logger;
-  WireDecoder d(is, 0x0200u, logger);
-  auto val = d.ReadValue(NT_STRING);
-  ASSERT_TRUE(static_cast<bool>(val));
-  EXPECT_EQ(*v_string, *val);
-
-  auto v_bye = Value::MakeString("bye"sv);
-  val = d.ReadValue(NT_STRING);
-  ASSERT_TRUE(static_cast<bool>(val));
-  EXPECT_EQ(*v_bye, *val);
-
-  unsigned int b;
-  ASSERT_TRUE(d.Read8(&b));
-  EXPECT_EQ(0x55u, b);
-
-  ASSERT_FALSE(d.ReadValue(NT_STRING));
-  ASSERT_EQ(nullptr, d.error());
-}
-
-TEST_F(WireDecoderTest, ReadBooleanArrayValue2) {
-  wpi::raw_mem_istream is("\x03\x00\x01\x00\x02\x01\x00\xff", 8);
-  wpi::Logger logger;
-  WireDecoder d(is, 0x0200u, logger);
-  auto val = d.ReadValue(NT_BOOLEAN_ARRAY);
-  ASSERT_TRUE(static_cast<bool>(val));
-  EXPECT_EQ(*v_boolean_array, *val);
-
-  auto v_boolean_array2 = Value::MakeBooleanArray(std::vector<int>{1, 0});
-  val = d.ReadValue(NT_BOOLEAN_ARRAY);
-  ASSERT_TRUE(static_cast<bool>(val));
-  EXPECT_EQ(*v_boolean_array2, *val);
-
-  ASSERT_FALSE(d.ReadValue(NT_BOOLEAN_ARRAY));
-  ASSERT_EQ(nullptr, d.error());
-}
-
-TEST_F(WireDecoderTest, ReadBooleanArrayBigValue2) {
-  std::string s;
-  s.push_back('\xff');
-  s.append(255, '\x00');
-  wpi::raw_mem_istream is(s.data(), s.size());
-  wpi::Logger logger;
-  WireDecoder d(is, 0x0200u, logger);
-  auto val = d.ReadValue(NT_BOOLEAN_ARRAY);
-  ASSERT_TRUE(static_cast<bool>(val));
-  EXPECT_EQ(*v_boolean_array_big, *val);
-
-  ASSERT_FALSE(d.ReadValue(NT_BOOLEAN_ARRAY));
-  ASSERT_EQ(nullptr, d.error());
-}
-
-TEST_F(WireDecoderTest, ReadDoubleArrayValue2) {
-  wpi::raw_mem_istream is(
-      "\x02\x3f\xe0\x00\x00\x00\x00\x00\x00"
-      "\x3f\xd0\x00\x00\x00\x00\x00\x00\x55",
-      18);
-  wpi::Logger logger;
-  WireDecoder d(is, 0x0200u, logger);
-  auto val = d.ReadValue(NT_DOUBLE_ARRAY);
-  ASSERT_TRUE(static_cast<bool>(val));
-  EXPECT_EQ(*v_double_array, *val);
-
-  unsigned int b;
-  ASSERT_TRUE(d.Read8(&b));
-  EXPECT_EQ(0x55u, b);
-
-  ASSERT_FALSE(d.ReadValue(NT_DOUBLE_ARRAY));
-  ASSERT_EQ(nullptr, d.error());
-}
-
-TEST_F(WireDecoderTest, ReadDoubleArrayBigValue2) {
-  std::string s;
-  s.push_back('\xff');
-  s.append(255 * 8, '\x00');
-  wpi::raw_mem_istream is(s.data(), s.size());
-  wpi::Logger logger;
-  WireDecoder d(is, 0x0200u, logger);
-  auto val = d.ReadValue(NT_DOUBLE_ARRAY);
-  ASSERT_TRUE(static_cast<bool>(val));
-  EXPECT_EQ(*v_double_array_big, *val);
-
-  ASSERT_FALSE(d.ReadValue(NT_DOUBLE_ARRAY));
-  ASSERT_EQ(nullptr, d.error());
-}
-
-TEST_F(WireDecoderTest, ReadStringArrayValue2) {
-  wpi::raw_mem_istream is("\x02\x00\x05hello\x00\x07goodbye\x55", 18);
-  wpi::Logger logger;
-  WireDecoder d(is, 0x0200u, logger);
-  auto val = d.ReadValue(NT_STRING_ARRAY);
-  ASSERT_TRUE(static_cast<bool>(val));
-  EXPECT_EQ(*v_string_array, *val);
-
-  unsigned int b;
-  ASSERT_TRUE(d.Read8(&b));
-  EXPECT_EQ(0x55u, b);
-
-  ASSERT_FALSE(d.ReadValue(NT_STRING_ARRAY));
-  ASSERT_EQ(nullptr, d.error());
-}
-
-TEST_F(WireDecoderTest, ReadStringArrayBigValue2) {
-  std::string s;
-  s.push_back('\xff');
-  for (int i = 0; i < 255; ++i) {
-    s.append("\x00\x01h", 3);
-  }
-  wpi::raw_mem_istream is(s.data(), s.size());
-  wpi::Logger logger;
-  WireDecoder d(is, 0x0200u, logger);
-  auto val = d.ReadValue(NT_STRING_ARRAY);
-  ASSERT_TRUE(static_cast<bool>(val));
-  EXPECT_EQ(*v_string_array_big, *val);
-
-  ASSERT_FALSE(d.ReadValue(NT_STRING_ARRAY));
-  ASSERT_EQ(nullptr, d.error());
-}
-
-TEST_F(WireDecoderTest, ReadValueError2) {
-  wpi::raw_mem_istream is("", 0);
-  wpi::Logger logger;
-  WireDecoder d(is, 0x0200u, logger);
-  ASSERT_FALSE(d.ReadValue(NT_UNASSIGNED));  // unassigned
-  ASSERT_NE(nullptr, d.error());
-
-  d.Reset();
-  ASSERT_FALSE(d.ReadValue(NT_RAW));  // not supported
-  ASSERT_NE(nullptr, d.error());
-
-  d.Reset();
-  ASSERT_FALSE(d.ReadValue(NT_RPC));  // not supported
-  ASSERT_NE(nullptr, d.error());
-}
-
-TEST_F(WireDecoderTest, ReadBooleanValue3) {
-  wpi::raw_mem_istream is("\x01\x00", 2);
-  wpi::Logger logger;
-  WireDecoder d(is, 0x0300u, logger);
-  auto val = d.ReadValue(NT_BOOLEAN);
-  ASSERT_TRUE(static_cast<bool>(val));
-  EXPECT_EQ(*v_boolean, *val);
-
-  auto v_false = Value::MakeBoolean(false);
-  val = d.ReadValue(NT_BOOLEAN);
-  ASSERT_TRUE(static_cast<bool>(val));
-  EXPECT_EQ(*v_false, *val);
-
-  ASSERT_FALSE(d.ReadValue(NT_BOOLEAN));
-  ASSERT_EQ(nullptr, d.error());
-}
-
-TEST_F(WireDecoderTest, ReadDoubleValue3) {
-  wpi::raw_mem_istream is(
-      "\x3f\xf0\x00\x00\x00\x00\x00\x00"
-      "\x3f\xf0\x00\x00\x00\x00\x00\x00",
-      16);
-  wpi::Logger logger;
-  WireDecoder d(is, 0x0300u, logger);
-  auto val = d.ReadValue(NT_DOUBLE);
-  ASSERT_TRUE(static_cast<bool>(val));
-  EXPECT_EQ(*v_double, *val);
-
-  val = d.ReadValue(NT_DOUBLE);
-  ASSERT_TRUE(static_cast<bool>(val));
-  EXPECT_EQ(*v_double, *val);
-
-  ASSERT_FALSE(d.ReadValue(NT_DOUBLE));
-  ASSERT_EQ(nullptr, d.error());
-}
-
-TEST_F(WireDecoderTest, ReadStringValue3) {
-  wpi::raw_mem_istream is(
-      "\x05hello\x03"
-      "bye\x55",
-      11);
-  wpi::Logger logger;
-  WireDecoder d(is, 0x0300u, logger);
-  auto val = d.ReadValue(NT_STRING);
-  ASSERT_TRUE(static_cast<bool>(val));
-  EXPECT_EQ(*v_string, *val);
-
-  auto v_bye = Value::MakeString("bye"sv);
-  val = d.ReadValue(NT_STRING);
-  ASSERT_TRUE(static_cast<bool>(val));
-  EXPECT_EQ(*v_bye, *val);
-
-  unsigned int b;
-  ASSERT_TRUE(d.Read8(&b));
-  EXPECT_EQ(0x55u, b);
-
-  ASSERT_FALSE(d.ReadValue(NT_STRING));
-  ASSERT_EQ(nullptr, d.error());
-}
-
-TEST_F(WireDecoderTest, ReadRawValue3) {
-  wpi::raw_mem_istream is(
-      "\x05hello\x03"
-      "bye\x55",
-      11);
-  wpi::Logger logger;
-  WireDecoder d(is, 0x0300u, logger);
-  auto val = d.ReadValue(NT_RAW);
-  ASSERT_TRUE(static_cast<bool>(val));
-  EXPECT_EQ(*v_raw, *val);
-
-  auto v_bye = Value::MakeRaw("bye"sv);
-  val = d.ReadValue(NT_RAW);
-  ASSERT_TRUE(static_cast<bool>(val));
-  EXPECT_EQ(*v_bye, *val);
-
-  unsigned int b;
-  ASSERT_TRUE(d.Read8(&b));
-  EXPECT_EQ(0x55u, b);
-
-  ASSERT_FALSE(d.ReadValue(NT_RAW));
-  ASSERT_EQ(nullptr, d.error());
-}
-
-TEST_F(WireDecoderTest, ReadBooleanArrayValue3) {
-  wpi::raw_mem_istream is("\x03\x00\x01\x00\x02\x01\x00\xff", 8);
-  wpi::Logger logger;
-  WireDecoder d(is, 0x0300u, logger);
-  auto val = d.ReadValue(NT_BOOLEAN_ARRAY);
-  ASSERT_TRUE(static_cast<bool>(val));
-  EXPECT_EQ(*v_boolean_array, *val);
-
-  auto v_boolean_array2 = Value::MakeBooleanArray(std::vector<int>{1, 0});
-  val = d.ReadValue(NT_BOOLEAN_ARRAY);
-  ASSERT_TRUE(static_cast<bool>(val));
-  EXPECT_EQ(*v_boolean_array2, *val);
-
-  ASSERT_FALSE(d.ReadValue(NT_BOOLEAN_ARRAY));
-  ASSERT_EQ(nullptr, d.error());
-}
-
-TEST_F(WireDecoderTest, ReadBooleanArrayBigValue3) {
-  std::string s;
-  s.push_back('\xff');
-  s.append(255, '\x00');
-  wpi::raw_mem_istream is(s.data(), s.size());
-  wpi::Logger logger;
-  WireDecoder d(is, 0x0300u, logger);
-  auto val = d.ReadValue(NT_BOOLEAN_ARRAY);
-  ASSERT_TRUE(static_cast<bool>(val));
-  EXPECT_EQ(*v_boolean_array_big, *val);
-
-  ASSERT_FALSE(d.ReadValue(NT_BOOLEAN_ARRAY));
-  ASSERT_EQ(nullptr, d.error());
-}
-
-TEST_F(WireDecoderTest, ReadDoubleArrayValue3) {
-  wpi::raw_mem_istream is(
-      "\x02\x3f\xe0\x00\x00\x00\x00\x00\x00"
-      "\x3f\xd0\x00\x00\x00\x00\x00\x00\x55",
-      18);
-  wpi::Logger logger;
-  WireDecoder d(is, 0x0300u, logger);
-  auto val = d.ReadValue(NT_DOUBLE_ARRAY);
-  ASSERT_TRUE(static_cast<bool>(val));
-  EXPECT_EQ(*v_double_array, *val);
-
-  unsigned int b;
-  ASSERT_TRUE(d.Read8(&b));
-  EXPECT_EQ(0x55u, b);
-
-  ASSERT_FALSE(d.ReadValue(NT_DOUBLE_ARRAY));
-  ASSERT_EQ(nullptr, d.error());
-}
-
-TEST_F(WireDecoderTest, ReadDoubleArrayBigValue3) {
-  std::string s;
-  s.push_back('\xff');
-  s.append(255 * 8, '\x00');
-  wpi::raw_mem_istream is(s.data(), s.size());
-  wpi::Logger logger;
-  WireDecoder d(is, 0x0300u, logger);
-  auto val = d.ReadValue(NT_DOUBLE_ARRAY);
-  ASSERT_TRUE(static_cast<bool>(val));
-  EXPECT_EQ(*v_double_array_big, *val);
-
-  ASSERT_FALSE(d.ReadValue(NT_DOUBLE_ARRAY));
-  ASSERT_EQ(nullptr, d.error());
-}
-
-TEST_F(WireDecoderTest, ReadStringArrayValue3) {
-  wpi::raw_mem_istream is("\x02\x05hello\x07goodbye\x55", 16);
-  wpi::Logger logger;
-  WireDecoder d(is, 0x0300u, logger);
-  auto val = d.ReadValue(NT_STRING_ARRAY);
-  ASSERT_TRUE(static_cast<bool>(val));
-  EXPECT_EQ(*v_string_array, *val);
-
-  unsigned int b;
-  ASSERT_TRUE(d.Read8(&b));
-  EXPECT_EQ(0x55u, b);
-
-  ASSERT_FALSE(d.ReadValue(NT_STRING_ARRAY));
-  ASSERT_EQ(nullptr, d.error());
-}
-
-TEST_F(WireDecoderTest, ReadStringArrayBigValue3) {
-  std::string s;
-  s.push_back('\xff');
-  for (int i = 0; i < 255; ++i) {
-    s.append("\x01h", 2);
-  }
-  wpi::raw_mem_istream is(s.data(), s.size());
-  wpi::Logger logger;
-  WireDecoder d(is, 0x0300u, logger);
-  auto val = d.ReadValue(NT_STRING_ARRAY);
-  ASSERT_TRUE(static_cast<bool>(val));
-  EXPECT_EQ(*v_string_array_big, *val);
-
-  ASSERT_FALSE(d.ReadValue(NT_STRING_ARRAY));
-  ASSERT_EQ(nullptr, d.error());
-}
-
-TEST_F(WireDecoderTest, ReadValueError3) {
-  wpi::raw_mem_istream is("", 0);
-  wpi::Logger logger;
-  WireDecoder d(is, 0x0200u, logger);
-  ASSERT_FALSE(d.ReadValue(NT_UNASSIGNED));  // unassigned
-  ASSERT_NE(nullptr, d.error());
-}
-
-TEST_F(WireDecoderTest, ReadString2) {
-  std::string s;
-  s.append("\x00\x05", 2);
-  s += s_normal;
-  s.append("\x00\x80", 2);
-  s += s_long;
-  s.append("\xff\xff", 2);
-  s += s_big2;
-  s.push_back('\x55');
-  wpi::raw_mem_istream is(s.data(), s.size());
-  wpi::Logger logger;
-  WireDecoder d(is, 0x0200u, logger);
-  std::string outs;
-  ASSERT_TRUE(d.ReadString(&outs));
-  EXPECT_EQ(s_normal, outs);
-  ASSERT_TRUE(d.ReadString(&outs));
-  EXPECT_EQ(s_long, outs);
-  ASSERT_TRUE(d.ReadString(&outs));
-  EXPECT_EQ(s_big2, outs);
-
-  unsigned int b;
-  ASSERT_TRUE(d.Read8(&b));
-  EXPECT_EQ(0x55u, b);
-
-  ASSERT_FALSE(d.ReadString(&outs));
-  ASSERT_EQ(nullptr, d.error());
-}
-
-TEST_F(WireDecoderTest, ReadString3) {
-  std::string s;
-  s.push_back('\x05');
-  s += s_normal;
-  s.append("\x80\x01", 2);
-  s += s_long;
-  s.append("\x81\x80\x04", 3);
-  s += s_big3;
-  s.push_back('\x55');
-  wpi::raw_mem_istream is(s.data(), s.size());
-  wpi::Logger logger;
-  WireDecoder d(is, 0x0300u, logger);
-  std::string outs;
-  ASSERT_TRUE(d.ReadString(&outs));
-  EXPECT_EQ(s_normal, outs);
-  ASSERT_TRUE(d.ReadString(&outs));
-  EXPECT_EQ(s_long, outs);
-  ASSERT_TRUE(d.ReadString(&outs));
-  EXPECT_EQ(s_big3, outs);
-
-  unsigned int b;
-  ASSERT_TRUE(d.Read8(&b));
-  EXPECT_EQ(0x55u, b);
-
-  ASSERT_FALSE(d.ReadString(&outs));
-  ASSERT_EQ(nullptr, d.error());
-}
-
-}  // namespace nt
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/WireEncoderTest.cpp b/third_party/allwpilib/ntcore/src/test/native/cpp/WireEncoderTest.cpp
deleted file mode 100644
index b0cc664..0000000
--- a/third_party/allwpilib/ntcore/src/test/native/cpp/WireEncoderTest.cpp
+++ /dev/null
@@ -1,500 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include <cfloat>
-#include <climits>
-#include <string>
-#include <string_view>
-
-#include <wpi/StringExtras.h>
-
-#include "TestPrinters.h"
-#include "WireEncoder.h"
-#include "gtest/gtest.h"
-
-#define BUFSIZE 1024
-
-using namespace std::string_view_literals;
-
-namespace nt {
-
-class WireEncoderTest : public ::testing::Test {
- protected:
-  WireEncoderTest() {
-    v_empty = std::make_shared<Value>();
-    v_boolean = Value::MakeBoolean(true);
-    v_double = Value::MakeDouble(1.0);
-    v_string = Value::MakeString("hello"sv);
-    v_raw = Value::MakeRaw("hello"sv);
-    v_boolean_array = Value::MakeBooleanArray(std::vector<int>{0, 1, 0});
-    v_boolean_array_big = Value::MakeBooleanArray(std::vector<int>(256));
-    v_double_array = Value::MakeDoubleArray(std::vector<double>{0.5, 0.25});
-    v_double_array_big = Value::MakeDoubleArray(std::vector<double>(256));
-
-    std::vector<std::string> sa;
-    sa.push_back("hello");
-    sa.push_back("goodbye");
-    v_string_array = Value::MakeStringArray(std::move(sa));
-
-    sa.clear();
-    for (int i = 0; i < 256; ++i) {
-      sa.push_back("h");
-    }
-    v_string_array_big = Value::MakeStringArray(std::move(sa));
-
-    s_normal = "hello";
-
-    s_long.clear();
-    s_long.append(127, '*');
-    s_long.push_back('x');
-
-    s_big.clear();
-    s_big.append(65534, '*');
-    s_big.append(3, 'x');
-  }
-
-  std::shared_ptr<Value> v_empty;
-  std::shared_ptr<Value> v_boolean, v_double, v_string, v_raw;
-  std::shared_ptr<Value> v_boolean_array, v_boolean_array_big;
-  std::shared_ptr<Value> v_double_array, v_double_array_big;
-  std::shared_ptr<Value> v_string_array, v_string_array_big;
-
-  std::string s_normal, s_long, s_big;
-};
-
-TEST_F(WireEncoderTest, Construct) {
-  WireEncoder e(0x0300u);
-  EXPECT_EQ(0u, e.size());
-  EXPECT_EQ(nullptr, e.error());
-  EXPECT_EQ(0x0300u, e.proto_rev());
-}
-
-TEST_F(WireEncoderTest, SetProtoRev) {
-  WireEncoder e(0x0300u);
-  e.set_proto_rev(0x0200u);
-  EXPECT_EQ(0x0200u, e.proto_rev());
-}
-
-TEST_F(WireEncoderTest, Write8) {
-  size_t off = BUFSIZE - 1;
-  WireEncoder e(0x0300u);
-  for (size_t i = 0; i < off; ++i) {
-    e.Write8(0u);  // test across Reserve()
-  }
-  e.Write8(5u);
-  e.Write8(0x101u);  // should be truncated
-  e.Write8(0u);
-  ASSERT_EQ(3u, e.size() - off);
-  ASSERT_EQ("\x05\x01\x00"sv, wpi::substr({e.data(), e.size()}, off));
-}
-
-TEST_F(WireEncoderTest, Write16) {
-  size_t off = BUFSIZE - 2;
-  WireEncoder e(0x0300u);
-  for (size_t i = 0; i < off; ++i) {
-    e.Write8(0u);  // test across Reserve()
-  }
-  e.Write16(5u);
-  e.Write16(0x10001u);  // should be truncated
-  e.Write16(0x4567u);
-  e.Write16(0u);
-  ASSERT_EQ(8u, e.size() - off);
-  ASSERT_EQ("\x00\x05\x00\x01\x45\x67\x00\x00"sv,
-            wpi::substr({e.data(), e.size()}, off));
-}
-
-TEST_F(WireEncoderTest, Write32) {
-  size_t off = BUFSIZE - 4;
-  WireEncoder e(0x0300u);
-  for (size_t i = 0; i < off; ++i) {
-    e.Write8(0u);  // test across Reserve()
-  }
-  e.Write32(5ul);
-  e.Write32(1ul);
-  e.Write32(0xabcdul);
-  e.Write32(0x12345678ul);
-  e.Write32(0ul);
-  ASSERT_EQ(20u, e.size() - off);
-  ASSERT_EQ(std::string_view("\x00\x00\x00\x05\x00\x00\x00\x01\x00\x00\xab\xcd"
-                             "\x12\x34\x56\x78\x00\x00\x00\x00",
-                             20),
-            wpi::substr({e.data(), e.size()}, off));
-}
-
-TEST_F(WireEncoderTest, WriteDouble) {
-  size_t off = BUFSIZE - 8;
-  WireEncoder e(0x0300u);
-  for (size_t i = 0; i < off; ++i) {
-    e.Write8(0u);  // test across Reserve()
-  }
-  e.WriteDouble(0.0);
-  e.WriteDouble(2.3e5);
-  e.WriteDouble(std::numeric_limits<double>::infinity());
-  e.WriteDouble(DBL_MIN);
-  e.WriteDouble(DBL_MAX);
-  ASSERT_EQ(40u, e.size() - off);
-  // golden values except min and max from
-  // http://www.binaryconvert.com/result_double.html
-  ASSERT_EQ(std::string_view("\x00\x00\x00\x00\x00\x00\x00\x00"
-                             "\x41\x0c\x13\x80\x00\x00\x00\x00"
-                             "\x7f\xf0\x00\x00\x00\x00\x00\x00"
-                             "\x00\x10\x00\x00\x00\x00\x00\x00"
-                             "\x7f\xef\xff\xff\xff\xff\xff\xff",
-                             40),
-            wpi::substr({e.data(), e.size()}, off));
-}
-
-TEST_F(WireEncoderTest, WriteUleb128) {
-  size_t off = BUFSIZE - 2;
-  WireEncoder e(0x0300u);
-  for (size_t i = 0; i < off; ++i) {
-    e.Write8(0u);  // test across Reserve()
-  }
-  e.WriteUleb128(0ul);
-  e.WriteUleb128(0x7ful);
-  e.WriteUleb128(0x80ul);
-  ASSERT_EQ(4u, e.size() - off);
-  ASSERT_EQ("\x00\x7f\x80\x01"sv, wpi::substr({e.data(), e.size()}, off));
-}
-
-TEST_F(WireEncoderTest, WriteType) {
-  size_t off = BUFSIZE - 1;
-  WireEncoder e(0x0300u);
-  for (size_t i = 0; i < off; ++i) {
-    e.Write8(0u);  // test across Reserve()
-  }
-  e.WriteType(NT_BOOLEAN);
-  e.WriteType(NT_DOUBLE);
-  e.WriteType(NT_STRING);
-  e.WriteType(NT_RAW);
-  e.WriteType(NT_BOOLEAN_ARRAY);
-  e.WriteType(NT_DOUBLE_ARRAY);
-  e.WriteType(NT_STRING_ARRAY);
-  e.WriteType(NT_RPC);
-  ASSERT_EQ(nullptr, e.error());
-  ASSERT_EQ(8u, e.size() - off);
-  ASSERT_EQ("\x00\x01\x02\x03\x10\x11\x12\x20"sv,
-            wpi::substr({e.data(), e.size()}, off));
-}
-
-TEST_F(WireEncoderTest, WriteTypeError) {
-  WireEncoder e(0x0200u);
-  e.WriteType(NT_UNASSIGNED);
-  EXPECT_EQ(0u, e.size());
-  EXPECT_EQ(std::string("unrecognized type"), e.error());
-
-  e.Reset();
-  e.WriteType(NT_RAW);
-  EXPECT_EQ(0u, e.size());
-  EXPECT_EQ(std::string("raw type not supported in protocol < 3.0"), e.error());
-
-  e.Reset();
-  e.WriteType(NT_RPC);
-  EXPECT_EQ(0u, e.size());
-  EXPECT_EQ(std::string("RPC type not supported in protocol < 3.0"), e.error());
-}
-
-TEST_F(WireEncoderTest, Reset) {
-  WireEncoder e(0x0300u);
-  e.WriteType(NT_UNASSIGNED);
-  EXPECT_NE(nullptr, e.error());
-  e.Reset();
-  EXPECT_EQ(nullptr, e.error());
-
-  e.Write8(0u);
-  EXPECT_EQ(1u, e.size());
-  e.Reset();
-  EXPECT_EQ(0u, e.size());
-}
-
-TEST_F(WireEncoderTest, GetValueSize2) {
-  WireEncoder e(0x0200u);
-  EXPECT_EQ(0u, e.GetValueSize(*v_empty));  // empty
-  EXPECT_EQ(1u, e.GetValueSize(*v_boolean));
-  EXPECT_EQ(8u, e.GetValueSize(*v_double));
-  EXPECT_EQ(7u, e.GetValueSize(*v_string));
-  EXPECT_EQ(0u, e.GetValueSize(*v_raw));  // not supported
-
-  EXPECT_EQ(1u + 3u, e.GetValueSize(*v_boolean_array));
-  // truncated
-  EXPECT_EQ(1u + 255u, e.GetValueSize(*v_boolean_array_big));
-
-  EXPECT_EQ(1u + 2u * 8u, e.GetValueSize(*v_double_array));
-  // truncated
-  EXPECT_EQ(1u + 255u * 8u, e.GetValueSize(*v_double_array_big));
-
-  EXPECT_EQ(1u + 7u + 9u, e.GetValueSize(*v_string_array));
-  // truncated
-  EXPECT_EQ(1u + 255u * 3u, e.GetValueSize(*v_string_array_big));
-}
-
-TEST_F(WireEncoderTest, WriteBooleanValue2) {
-  WireEncoder e(0x0200u);
-  e.WriteValue(*v_boolean);
-  auto v_false = Value::MakeBoolean(false);
-  e.WriteValue(*v_false);
-  ASSERT_EQ(nullptr, e.error());
-  ASSERT_EQ(2u, e.size());
-  ASSERT_EQ("\x01\x00"sv, std::string_view(e.data(), e.size()));
-}
-
-TEST_F(WireEncoderTest, WriteDoubleValue2) {
-  WireEncoder e(0x0200u);
-  e.WriteValue(*v_double);
-  ASSERT_EQ(nullptr, e.error());
-  ASSERT_EQ(8u, e.size());
-  ASSERT_EQ("\x3f\xf0\x00\x00\x00\x00\x00\x00"sv,
-            std::string_view(e.data(), e.size()));
-}
-
-TEST_F(WireEncoderTest, WriteStringValue2) {
-  WireEncoder e(0x0200u);
-  e.WriteValue(*v_string);
-  ASSERT_EQ(nullptr, e.error());
-  ASSERT_EQ(7u, e.size());
-  ASSERT_EQ("\x00\x05hello"sv, std::string_view(e.data(), e.size()));
-}
-
-TEST_F(WireEncoderTest, WriteBooleanArrayValue2) {
-  WireEncoder e(0x0200u);
-  e.WriteValue(*v_boolean_array);
-  ASSERT_EQ(nullptr, e.error());
-  ASSERT_EQ(1u + 3u, e.size());
-  ASSERT_EQ("\x03\x00\x01\x00"sv, std::string_view(e.data(), e.size()));
-
-  // truncated
-  e.Reset();
-  e.WriteValue(*v_boolean_array_big);
-  ASSERT_EQ(nullptr, e.error());
-  ASSERT_EQ(1u + 255u, e.size());
-  ASSERT_EQ("\xff\x00"sv, std::string_view(e.data(), 2));
-}
-
-TEST_F(WireEncoderTest, WriteDoubleArrayValue2) {
-  WireEncoder e(0x0200u);
-  e.WriteValue(*v_double_array);
-  ASSERT_EQ(nullptr, e.error());
-  ASSERT_EQ(1u + 2u * 8u, e.size());
-  ASSERT_EQ(std::string_view("\x02\x3f\xe0\x00\x00\x00\x00\x00\x00"
-                             "\x3f\xd0\x00\x00\x00\x00\x00\x00",
-                             17),
-            std::string_view(e.data(), e.size()));
-
-  // truncated
-  e.Reset();
-  e.WriteValue(*v_double_array_big);
-  ASSERT_EQ(nullptr, e.error());
-  ASSERT_EQ(1u + 255u * 8u, e.size());
-  ASSERT_EQ("\xff\x00"sv, std::string_view(e.data(), 2));
-}
-
-TEST_F(WireEncoderTest, WriteStringArrayValue2) {
-  WireEncoder e(0x0200u);
-  e.WriteValue(*v_string_array);
-  ASSERT_EQ(nullptr, e.error());
-  ASSERT_EQ(1u + 7u + 9u, e.size());
-  ASSERT_EQ("\x02\x00\x05hello\x00\x07goodbye"sv,
-            std::string_view(e.data(), e.size()));
-
-  // truncated
-  e.Reset();
-  e.WriteValue(*v_string_array_big);
-  ASSERT_EQ(nullptr, e.error());
-  ASSERT_EQ(1u + 255u * 3u, e.size());
-  ASSERT_EQ("\xff\x00\x01"sv, std::string_view(e.data(), 3));
-}
-
-TEST_F(WireEncoderTest, WriteValueError2) {
-  WireEncoder e(0x0200u);
-  e.WriteValue(*v_empty);  // empty
-  ASSERT_EQ(0u, e.size());
-  ASSERT_NE(nullptr, e.error());
-
-  e.Reset();
-  e.WriteValue(*v_raw);  // not supported
-  ASSERT_EQ(0u, e.size());
-  ASSERT_NE(nullptr, e.error());
-}
-
-TEST_F(WireEncoderTest, GetValueSize3) {
-  WireEncoder e(0x0300u);
-  EXPECT_EQ(0u, e.GetValueSize(*v_empty));  // empty
-  EXPECT_EQ(1u, e.GetValueSize(*v_boolean));
-  EXPECT_EQ(8u, e.GetValueSize(*v_double));
-  EXPECT_EQ(6u, e.GetValueSize(*v_string));
-  EXPECT_EQ(6u, e.GetValueSize(*v_raw));
-
-  EXPECT_EQ(1u + 3u, e.GetValueSize(*v_boolean_array));
-  // truncated
-  EXPECT_EQ(1u + 255u, e.GetValueSize(*v_boolean_array_big));
-
-  EXPECT_EQ(1u + 2u * 8u, e.GetValueSize(*v_double_array));
-  // truncated
-  EXPECT_EQ(1u + 255u * 8u, e.GetValueSize(*v_double_array_big));
-
-  EXPECT_EQ(1u + 6u + 8u, e.GetValueSize(*v_string_array));
-  // truncated
-  EXPECT_EQ(1u + 255u * 2u, e.GetValueSize(*v_string_array_big));
-}
-
-TEST_F(WireEncoderTest, WriteBooleanValue3) {
-  WireEncoder e(0x0300u);
-  e.WriteValue(*v_boolean);
-  auto v_false = Value::MakeBoolean(false);
-  e.WriteValue(*v_false);
-  ASSERT_EQ(nullptr, e.error());
-  ASSERT_EQ(2u, e.size());
-  ASSERT_EQ("\x01\x00"sv, std::string_view(e.data(), e.size()));
-}
-
-TEST_F(WireEncoderTest, WriteDoubleValue3) {
-  WireEncoder e(0x0300u);
-  e.WriteValue(*v_double);
-  ASSERT_EQ(nullptr, e.error());
-  ASSERT_EQ(8u, e.size());
-  ASSERT_EQ("\x3f\xf0\x00\x00\x00\x00\x00\x00"sv,
-            std::string_view(e.data(), e.size()));
-}
-
-TEST_F(WireEncoderTest, WriteStringValue3) {
-  WireEncoder e(0x0300u);
-  e.WriteValue(*v_string);
-  ASSERT_EQ(nullptr, e.error());
-  ASSERT_EQ(6u, e.size());
-  ASSERT_EQ("\x05hello"sv, std::string_view(e.data(), e.size()));
-}
-
-TEST_F(WireEncoderTest, WriteRawValue3) {
-  WireEncoder e(0x0300u);
-  e.WriteValue(*v_raw);
-  ASSERT_EQ(nullptr, e.error());
-  ASSERT_EQ(6u, e.size());
-  ASSERT_EQ("\x05hello"sv, std::string_view(e.data(), e.size()));
-}
-
-TEST_F(WireEncoderTest, WriteBooleanArrayValue3) {
-  WireEncoder e(0x0300u);
-  e.WriteValue(*v_boolean_array);
-  ASSERT_EQ(nullptr, e.error());
-  ASSERT_EQ(1u + 3u, e.size());
-  ASSERT_EQ("\x03\x00\x01\x00"sv, std::string_view(e.data(), e.size()));
-
-  // truncated
-  e.Reset();
-  e.WriteValue(*v_boolean_array_big);
-  ASSERT_EQ(nullptr, e.error());
-  ASSERT_EQ(1u + 255u, e.size());
-  ASSERT_EQ("\xff\x00"sv, std::string_view(e.data(), 2));
-}
-
-TEST_F(WireEncoderTest, WriteDoubleArrayValue3) {
-  WireEncoder e(0x0300u);
-  e.WriteValue(*v_double_array);
-  ASSERT_EQ(nullptr, e.error());
-  ASSERT_EQ(1u + 2u * 8u, e.size());
-  ASSERT_EQ(std::string_view("\x02\x3f\xe0\x00\x00\x00\x00\x00\x00"
-                             "\x3f\xd0\x00\x00\x00\x00\x00\x00",
-                             17),
-            std::string_view(e.data(), e.size()));
-
-  // truncated
-  e.Reset();
-  e.WriteValue(*v_double_array_big);
-  ASSERT_EQ(nullptr, e.error());
-  ASSERT_EQ(1u + 255u * 8u, e.size());
-  ASSERT_EQ("\xff\x00"sv, std::string_view(e.data(), 2));
-}
-
-TEST_F(WireEncoderTest, WriteStringArrayValue3) {
-  WireEncoder e(0x0300u);
-  e.WriteValue(*v_string_array);
-  ASSERT_EQ(nullptr, e.error());
-  ASSERT_EQ(1u + 6u + 8u, e.size());
-  ASSERT_EQ("\x02\x05hello\x07goodbye"sv, std::string_view(e.data(), e.size()));
-
-  // truncated
-  e.Reset();
-  e.WriteValue(*v_string_array_big);
-  ASSERT_EQ(nullptr, e.error());
-  ASSERT_EQ(1u + 255u * 2u, e.size());
-  ASSERT_EQ("\xff\x01"sv, std::string_view(e.data(), 2));
-}
-
-TEST_F(WireEncoderTest, WriteValueError3) {
-  WireEncoder e(0x0300u);
-  e.WriteValue(*v_empty);  // empty
-  ASSERT_EQ(0u, e.size());
-  ASSERT_NE(nullptr, e.error());
-}
-
-TEST_F(WireEncoderTest, GetStringSize2) {
-  // 2-byte length
-  WireEncoder e(0x0200u);
-  EXPECT_EQ(7u, e.GetStringSize(s_normal));
-  EXPECT_EQ(130u, e.GetStringSize(s_long));
-  // truncated
-  EXPECT_EQ(65537u, e.GetStringSize(s_big));
-}
-
-TEST_F(WireEncoderTest, WriteString2) {
-  WireEncoder e(0x0200u);
-  e.WriteString(s_normal);
-  EXPECT_EQ(nullptr, e.error());
-  EXPECT_EQ(7u, e.size());
-  EXPECT_EQ("\x00\x05hello"sv, std::string_view(e.data(), e.size()));
-
-  e.Reset();
-  e.WriteString(s_long);
-  EXPECT_EQ(nullptr, e.error());
-  ASSERT_EQ(130u, e.size());
-  EXPECT_EQ("\x00\x80**"sv, std::string_view(e.data(), 4));
-  EXPECT_EQ('*', e.data()[128]);
-  EXPECT_EQ('x', e.data()[129]);
-
-  // truncated
-  e.Reset();
-  e.WriteString(s_big);
-  EXPECT_EQ(nullptr, e.error());
-  ASSERT_EQ(65537u, e.size());
-  EXPECT_EQ("\xff\xff**"sv, std::string_view(e.data(), 4));
-  EXPECT_EQ('*', e.data()[65535]);
-  EXPECT_EQ('x', e.data()[65536]);
-}
-
-TEST_F(WireEncoderTest, GetStringSize3) {
-  // leb128-encoded length
-  WireEncoder e(0x0300u);
-  EXPECT_EQ(6u, e.GetStringSize(s_normal));
-  EXPECT_EQ(130u, e.GetStringSize(s_long));
-  EXPECT_EQ(65540u, e.GetStringSize(s_big));
-}
-
-TEST_F(WireEncoderTest, WriteString3) {
-  WireEncoder e(0x0300u);
-  e.WriteString(s_normal);
-  EXPECT_EQ(nullptr, e.error());
-  EXPECT_EQ(6u, e.size());
-  EXPECT_EQ("\x05hello"sv, std::string_view(e.data(), e.size()));
-
-  e.Reset();
-  e.WriteString(s_long);
-  EXPECT_EQ(nullptr, e.error());
-  ASSERT_EQ(130u, e.size());
-  EXPECT_EQ("\x80\x01**"sv, std::string_view(e.data(), 4));
-  EXPECT_EQ('*', e.data()[128]);
-  EXPECT_EQ('x', e.data()[129]);
-
-  // NOT truncated
-  e.Reset();
-  e.WriteString(s_big);
-  EXPECT_EQ(nullptr, e.error());
-  ASSERT_EQ(65540u, e.size());
-  EXPECT_EQ("\x81\x80\x04*"sv, std::string_view(e.data(), 4));
-  EXPECT_EQ('*', e.data()[65536]);
-  EXPECT_EQ('x', e.data()[65537]);
-  EXPECT_EQ('x', e.data()[65538]);
-  EXPECT_EQ('x', e.data()[65539]);
-}
-
-}  // namespace nt
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/main.cpp b/third_party/allwpilib/ntcore/src/test/native/cpp/main.cpp
index a3fec50..6d37027 100644
--- a/third_party/allwpilib/ntcore/src/test/native/cpp/main.cpp
+++ b/third_party/allwpilib/ntcore/src/test/native/cpp/main.cpp
@@ -8,14 +8,25 @@
 #include "ntcore.h"
 
 int main(int argc, char** argv) {
-  nt::AddLogger(
-      nt::GetDefaultInstance(),
-      [](const nt::LogMessage& msg) {
-        std::fputs(msg.message.c_str(), stderr);
-        std::fputc('\n', stderr);
-      },
-      0, UINT_MAX);
+  nt::AddLogger(nt::GetDefaultInstance(), 0, UINT_MAX, [](auto& event) {
+    if (auto msg = event.GetLogMessage()) {
+      std::fputs(msg->message.c_str(), stderr);
+      std::fputc('\n', stderr);
+    }
+  });
   ::testing::InitGoogleMock(&argc, argv);
   int ret = RUN_ALL_TESTS();
   return ret;
 }
+
+extern "C" {
+void __ubsan_on_report(void) {
+  FAIL() << "Encountered an undefined behavior sanitizer error";
+}
+void __asan_on_error(void) {
+  FAIL() << "Encountered an address sanitizer error";
+}
+void __tsan_on_report(void) {
+  FAIL() << "Encountered a thread sanitizer error";
+}
+}  // extern "C"
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/net/MockNetworkInterface.h b/third_party/allwpilib/ntcore/src/test/native/cpp/net/MockNetworkInterface.h
new file mode 100644
index 0000000..b033436
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/test/native/cpp/net/MockNetworkInterface.h
@@ -0,0 +1,69 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <string>
+
+#include <wpi/json.h>
+
+#include "PubSubOptions.h"
+#include "gmock/gmock.h"
+#include "net/NetworkInterface.h"
+
+namespace nt::net {
+
+class MockLocalInterface : public LocalInterface {
+ public:
+  MOCK_METHOD(NT_Topic, NetworkAnnounce,
+              (std::string_view name, std::string_view typeStr,
+               const wpi::json& properties, NT_Publisher pubHandle),
+              (override));
+  MOCK_METHOD(void, NetworkUnannounce, (std::string_view name), (override));
+  MOCK_METHOD(void, NetworkPropertiesUpdate,
+              (std::string_view name, const wpi::json& update, bool ack),
+              (override));
+  MOCK_METHOD(void, NetworkSetValue, (NT_Topic topicHandle, const Value& value),
+              (override));
+};
+
+class MockNetworkInterface : public NetworkInterface {
+ public:
+  MOCK_METHOD(void, Publish,
+              (NT_Publisher pubHandle, NT_Topic topicHandle,
+               std::string_view name, std::string_view typeStr,
+               const wpi::json& properties, const PubSubOptionsImpl& options),
+              (override));
+  MOCK_METHOD(void, Unpublish, (NT_Publisher pubHandle, NT_Topic topicHandle),
+              (override));
+  MOCK_METHOD(void, SetProperties,
+              (NT_Topic topicHandle, std::string_view name,
+               const wpi::json& update),
+              (override));
+  MOCK_METHOD(void, Subscribe,
+              (NT_Subscriber subHandle, std::span<const std::string> prefixes,
+               const PubSubOptionsImpl& options),
+              (override));
+  MOCK_METHOD(void, Unsubscribe, (NT_Subscriber subHandle), (override));
+  MOCK_METHOD(void, SetValue, (NT_Publisher pubHandle, const Value& value),
+              (override));
+};
+
+class MockLocalStorage : public ILocalStorage {
+ public:
+  MOCK_METHOD(NT_Topic, NetworkAnnounce,
+              (std::string_view name, std::string_view typeStr,
+               const wpi::json& properties, NT_Publisher pubHandle),
+              (override));
+  MOCK_METHOD(void, NetworkUnannounce, (std::string_view name), (override));
+  MOCK_METHOD(void, NetworkPropertiesUpdate,
+              (std::string_view name, const wpi::json& update, bool ack),
+              (override));
+  MOCK_METHOD(void, NetworkSetValue, (NT_Topic topicHandle, const Value& value),
+              (override));
+  MOCK_METHOD(void, StartNetwork, (NetworkInterface * network), (override));
+  MOCK_METHOD(void, ClearNetwork, (), (override));
+};
+
+}  // namespace nt::net
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/net/MockWireConnection.cpp b/third_party/allwpilib/ntcore/src/test/native/cpp/net/MockWireConnection.cpp
new file mode 100644
index 0000000..a5ddb1f
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/test/native/cpp/net/MockWireConnection.cpp
@@ -0,0 +1,26 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "MockWireConnection.h"
+
+using namespace nt::net;
+
+void MockWireConnection::StartSendText() {
+  if (m_in_text) {
+    m_text_os << ',';
+  } else {
+    m_text_os << '[';
+    m_in_text = true;
+  }
+}
+
+void MockWireConnection::FinishSendText() {
+  if (m_in_text) {
+    m_text_os << ']';
+    m_in_text = false;
+  }
+  m_text_os.flush();
+  Text(m_text);
+  m_text.clear();
+}
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/net/MockWireConnection.h b/third_party/allwpilib/ntcore/src/test/native/cpp/net/MockWireConnection.h
new file mode 100644
index 0000000..3909cab
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/test/native/cpp/net/MockWireConnection.h
@@ -0,0 +1,54 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <stdint.h>
+
+#include <span>
+#include <string>
+#include <string_view>
+#include <vector>
+
+#include <wpi/raw_ostream.h>
+
+#include "gmock/gmock.h"
+#include "net/WireConnection.h"
+
+namespace nt::net {
+
+class MockWireConnection : public WireConnection {
+ public:
+  MockWireConnection() : m_text_os{m_text}, m_binary_os{m_binary} {}
+
+  MOCK_METHOD(bool, Ready, (), (const, override));
+
+  TextWriter SendText() override { return {m_text_os, *this}; }
+  BinaryWriter SendBinary() override { return {m_binary_os, *this}; }
+
+  MOCK_METHOD(void, Text, (std::string_view contents));
+  MOCK_METHOD(void, Binary, (std::span<const uint8_t> contents));
+
+  MOCK_METHOD(void, Flush, (), (override));
+
+  MOCK_METHOD(void, Disconnect, (std::string_view reason), (override));
+
+ protected:
+  void StartSendText() override;
+  void FinishSendText() override;
+  void StartSendBinary() override {}
+  void FinishSendBinary() override {
+    Binary(m_binary);
+    m_binary.resize(0);
+  }
+
+ private:
+  std::string m_text;
+  wpi::raw_string_ostream m_text_os;
+  std::vector<uint8_t> m_binary;
+  wpi::raw_uvector_ostream m_binary_os;
+  bool m_in_text{false};
+};
+
+}  // namespace nt::net
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/net/WireDecoderTest.cpp b/third_party/allwpilib/ntcore/src/test/native/cpp/net/WireDecoderTest.cpp
new file mode 100644
index 0000000..f893302
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/test/native/cpp/net/WireDecoderTest.cpp
@@ -0,0 +1,214 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <wpi/SmallString.h>
+#include <wpi/raw_ostream.h>
+
+#include "../MockLogger.h"
+#include "../TestPrinters.h"
+#include "Handle.h"
+#include "gmock/gmock.h"
+#include "gtest/gtest.h"
+#include "net/Message.h"
+#include "net/WireDecoder.h"
+#include "networktables/NetworkTableValue.h"
+
+using namespace std::string_view_literals;
+using testing::_;
+using testing::MockFunction;
+using testing::StrictMock;
+
+namespace nt {
+
+class MockClientMessageHandler : public net::ClientMessageHandler {
+ public:
+  MOCK_METHOD4(ClientPublish,
+               void(int64_t pubuid, std::string_view name,
+                    std::string_view typeStr, const wpi::json& properties));
+  MOCK_METHOD1(ClientUnpublish, void(int64_t pubuid));
+  MOCK_METHOD2(ClientSetProperties,
+               void(std::string_view name, const wpi::json& update));
+  MOCK_METHOD3(ClientSubscribe,
+               void(int64_t subuid, std::span<const std::string> prefixes,
+                    const PubSubOptionsImpl& options));
+  MOCK_METHOD1(ClientUnsubscribe, void(int64_t subuid));
+};
+
+class MockServerMessageHandler : public net::ServerMessageHandler {
+ public:
+  MOCK_METHOD5(ServerAnnounce,
+               void(std::string_view name, int64_t id, std::string_view typeStr,
+                    const wpi::json& properties,
+                    std::optional<int64_t> pubuid));
+  MOCK_METHOD2(ServerUnannounce, void(std::string_view name, int64_t id));
+  MOCK_METHOD3(ServerPropertiesUpdate,
+               void(std::string_view name, const wpi::json& update, bool ack));
+};
+
+class WireDecodeTextClientTest : public ::testing::Test {
+ public:
+  StrictMock<MockClientMessageHandler> handler;
+  StrictMock<wpi::MockLogger> logger;
+};
+
+class WireDecodeTextServerTest : public ::testing::Test {
+ public:
+  StrictMock<MockServerMessageHandler> handler;
+  StrictMock<wpi::MockLogger> logger;
+};
+
+TEST_F(WireDecodeTextClientTest, EmptyArray) {
+  net::WireDecodeText("[]", handler, logger);
+}
+
+TEST_F(WireDecodeTextClientTest, ErrorEmpty) {
+  EXPECT_CALL(
+      logger,
+      Call(_, _, _,
+           "could not decode JSON message: [json.exception.parse_error.101] "
+           "parse error at 1: syntax error - "
+           "unexpected end of input; expected '[', '{', or a literal"sv));
+  net::WireDecodeText("", handler, logger);
+}
+
+TEST_F(WireDecodeTextClientTest, ErrorBadJson1) {
+  EXPECT_CALL(
+      logger,
+      Call(_, _, _,
+           "could not decode JSON message: [json.exception.parse_error.101] "
+           "parse error at 2: syntax error - "
+           "unexpected end of input; expected '[', '{', or a literal"sv));
+  net::WireDecodeText("[", handler, logger);
+}
+
+TEST_F(WireDecodeTextClientTest, ErrorBadJson2) {
+  EXPECT_CALL(
+      logger,
+      Call(_, _, _,
+           "could not decode JSON message: [json.exception.parse_error.101] "
+           "parse error at 3: syntax error - "
+           "unexpected end of input; expected string literal"sv));
+  net::WireDecodeText("[{", handler, logger);
+}
+
+TEST_F(WireDecodeTextClientTest, ErrorNotArray) {
+  EXPECT_CALL(logger, Call(_, _, _, "expected JSON array at top level"sv));
+  net::WireDecodeText("{}", handler, logger);
+}
+
+TEST_F(WireDecodeTextClientTest, ErrorMessageNotObject) {
+  EXPECT_CALL(logger, Call(_, _, _, "0: expected message to be an object"sv));
+  net::WireDecodeText("[5]", handler, logger);
+}
+
+TEST_F(WireDecodeTextClientTest, ErrorNoMethodKey) {
+  EXPECT_CALL(logger, Call(_, _, _, "0: no method key"sv));
+  net::WireDecodeText("[{}]", handler, logger);
+}
+
+TEST_F(WireDecodeTextClientTest, ErrorMethodNotString) {
+  EXPECT_CALL(logger, Call(_, _, _, "0: method must be a string"sv));
+  net::WireDecodeText("[{\"method\":5}]", handler, logger);
+}
+
+TEST_F(WireDecodeTextClientTest, ErrorNoParamsKey) {
+  EXPECT_CALL(logger, Call(_, _, _, "0: no params key"sv));
+  net::WireDecodeText("[{\"method\":\"a\"}]", handler, logger);
+}
+
+TEST_F(WireDecodeTextClientTest, ErrorParamsNotObject) {
+  EXPECT_CALL(logger, Call(_, _, _, "0: params must be an object"sv));
+  net::WireDecodeText("[{\"method\":\"a\",\"params\":5}]", handler, logger);
+}
+
+TEST_F(WireDecodeTextClientTest, ErrorUnknownMethod) {
+  EXPECT_CALL(logger, Call(_, _, _, "0: unrecognized method 'a'"sv));
+  net::WireDecodeText("[{\"method\":\"a\",\"params\":{}}]", handler, logger);
+}
+
+TEST_F(WireDecodeTextClientTest, PublishPropsEmpty) {
+  EXPECT_CALL(handler,
+              ClientPublish(5, std::string_view{"test"},
+                            std::string_view{"double"}, wpi::json::object()));
+  net::WireDecodeText(
+      "[{\"method\":\"publish\",\"params\":{"
+      "\"name\":\"test\",\"properties\":{},\"pubuid\":5,\"type\":\"double\"}}]",
+      handler, logger);
+
+  EXPECT_CALL(handler,
+              ClientPublish(5, std::string_view{"test"},
+                            std::string_view{"double"}, wpi::json::object()));
+  net::WireDecodeText(
+      "[{\"method\":\"publish\",\"params\":{"
+      "\"name\":\"test\",\"pubuid\":5,\"type\":\"double\"}}]",
+      handler, logger);
+}
+
+TEST_F(WireDecodeTextClientTest, PublishProps) {
+  wpi::json props = {{"k", 6}};
+  EXPECT_CALL(handler, ClientPublish(5, std::string_view{"test"},
+                                     std::string_view{"double"}, props));
+  net::WireDecodeText(
+      "[{\"method\":\"publish\",\"params\":{"
+      "\"name\":\"test\",\"properties\":{\"k\":6},"
+      "\"pubuid\":5,\"type\":\"double\"}}]",
+      handler, logger);
+}
+
+TEST_F(WireDecodeTextClientTest, PublishPropsError) {
+  EXPECT_CALL(logger, Call(_, _, _, "0: properties must be an object"sv));
+  net::WireDecodeText(
+      "[{\"method\":\"publish\",\"params\":{"
+      "\"name\":\"test\",\"properties\":[\"k\"],"
+      "\"pubuid\":5,\"type\":\"double\"}}]",
+      handler, logger);
+}
+
+TEST_F(WireDecodeTextClientTest, PublishError) {
+  EXPECT_CALL(logger, Call(_, _, _, "0: no name key"sv));
+  net::WireDecodeText(
+      "[{\"method\":\"publish\",\"params\":{"
+      "\"pubuid\":5,\"type\":\"double\"}}]",
+      handler, logger);
+
+  EXPECT_CALL(logger, Call(_, _, _, "0: no type key"sv));
+  net::WireDecodeText(
+      "[{\"method\":\"publish\",\"params\":{"
+      "\"name\":\"test\",\"pubuid\":5}}]",
+      handler, logger);
+
+  EXPECT_CALL(logger, Call(_, _, _, "0: no pubuid key"sv));
+  net::WireDecodeText(
+      "[{\"method\":\"publish\",\"params\":{"
+      "\"name\":\"test\",\"type\":\"double\"}}]",
+      handler, logger);
+}
+
+TEST_F(WireDecodeTextClientTest, Unpublish) {
+  EXPECT_CALL(handler, ClientUnpublish(5));
+  net::WireDecodeText("[{\"method\":\"unpublish\",\"params\":{\"pubuid\":5}}]",
+                      handler, logger);
+}
+
+TEST_F(WireDecodeTextClientTest, UnpublishMultiple) {
+  EXPECT_CALL(handler, ClientUnpublish(5));
+  EXPECT_CALL(handler, ClientUnpublish(6));
+  net::WireDecodeText(
+      "[{\"method\":\"unpublish\",\"params\":{\"pubuid\":5}},{\"method\":"
+      "\"unpublish\",\"params\":{\"pubuid\":6}}]",
+      handler, logger);
+}
+
+TEST_F(WireDecodeTextClientTest, UnpublishError) {
+  EXPECT_CALL(logger, Call(_, _, _, "0: no pubuid key"sv));
+  net::WireDecodeText("[{\"method\":\"unpublish\",\"params\":{}}]", handler,
+                      logger);
+
+  EXPECT_CALL(logger, Call(_, _, _, "0: pubuid must be a number"sv));
+  net::WireDecodeText(
+      "[{\"method\":\"unpublish\",\"params\":{\"pubuid\":\"5\"}}]", handler,
+      logger);
+}
+
+}  // namespace nt
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/net/WireEncoderTest.cpp b/third_party/allwpilib/ntcore/src/test/native/cpp/net/WireEncoderTest.cpp
new file mode 100644
index 0000000..9cc3187
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/test/native/cpp/net/WireEncoderTest.cpp
@@ -0,0 +1,293 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <span>
+#include <string>
+#include <string_view>
+#include <vector>
+
+#include <wpi/json.h>
+#include <wpi/raw_ostream.h>
+
+#include "../SpanMatcher.h"
+#include "../TestPrinters.h"
+#include "Handle.h"
+#include "PubSubOptions.h"
+#include "gmock/gmock-matchers.h"
+#include "gtest/gtest.h"
+#include "net/Message.h"
+#include "net/WireEncoder.h"
+#include "networktables/NetworkTableValue.h"
+
+using namespace std::string_view_literals;
+
+namespace nt {
+
+class WireEncoderTextTest : public ::testing::Test {
+ protected:
+  std::string out;
+  wpi::raw_string_ostream os{out};
+  wpi::json GetJson() { return wpi::json::parse(os.str()); }
+};
+
+class WireEncoderBinaryTest : public ::testing::Test {
+ protected:
+  std::vector<uint8_t> out;
+  wpi::raw_uvector_ostream os{out};
+};
+
+TEST_F(WireEncoderTextTest, PublishPropsEmpty) {
+  net::WireEncodePublish(os, 5, "test", "double", wpi::json::object());
+  ASSERT_EQ(
+      os.str(),
+      "{\"method\":\"publish\",\"params\":{"
+      "\"name\":\"test\",\"properties\":{},\"pubuid\":5,\"type\":\"double\"}}");
+}
+
+TEST_F(WireEncoderTextTest, PublishProps) {
+  net::WireEncodePublish(os, 5, "test", "double", {{"k", 6}});
+  ASSERT_EQ(os.str(),
+            "{\"method\":\"publish\",\"params\":{"
+            "\"name\":\"test\",\"properties\":{\"k\":6},"
+            "\"pubuid\":5,\"type\":\"double\"}}");
+}
+
+TEST_F(WireEncoderTextTest, Unpublish) {
+  net::WireEncodeUnpublish(os, 5);
+  ASSERT_EQ(os.str(), "{\"method\":\"unpublish\",\"params\":{\"pubuid\":5}}");
+}
+
+TEST_F(WireEncoderTextTest, SetProperties) {
+  net::WireEncodeSetProperties(os, "test", {{"k", 6}});
+  ASSERT_EQ(os.str(),
+            "{\"method\":\"setproperties\",\"params\":{"
+            "\"name\":\"test\",\"update\":{\"k\":6}}}");
+}
+
+TEST_F(WireEncoderTextTest, Subscribe) {
+  net::WireEncodeSubscribe(os, 5, std::span<const std::string_view>{{"a", "b"}},
+                           PubSubOptions{});
+  ASSERT_EQ(os.str(),
+            "{\"method\":\"subscribe\",\"params\":{"
+            "\"options\":{},\"topics\":[\"a\",\"b\"],\"subuid\":5}}");
+}
+
+TEST_F(WireEncoderTextTest, SubscribeSendAll) {
+  PubSubOptionsImpl options;
+  options.sendAll = true;
+  net::WireEncodeSubscribe(os, 5, std::span<const std::string_view>{{"a", "b"}},
+                           options);
+  ASSERT_EQ(os.str(),
+            "{\"method\":\"subscribe\",\"params\":{"
+            "\"options\":{\"all\":true},\"topics\":[\"a\",\"b\"],"
+            "\"subuid\":5}}");
+}
+
+TEST_F(WireEncoderTextTest, SubscribePeriodic) {
+  PubSubOptionsImpl options;
+  options.periodicMs = 500u;
+  net::WireEncodeSubscribe(os, 5, std::span<const std::string_view>{{"a", "b"}},
+                           options);
+  ASSERT_EQ(os.str(),
+            "{\"method\":\"subscribe\",\"params\":{"
+            "\"options\":{\"periodic\":0.5},\"topics\":[\"a\",\"b\"],"
+            "\"subuid\":5}}");
+}
+
+TEST_F(WireEncoderTextTest, SubscribeAllOptions) {
+  PubSubOptionsImpl options;
+  options.sendAll = true;
+  options.periodicMs = 500u;
+  net::WireEncodeSubscribe(os, 5, std::span<const std::string_view>{{"a", "b"}},
+                           options);
+  ASSERT_EQ(os.str(),
+            "{\"method\":\"subscribe\",\"params\":{"
+            "\"options\":{\"all\":true,\"periodic\":0.5},"
+            "\"topics\":[\"a\",\"b\"],\"subuid\":5}}");
+}
+
+TEST_F(WireEncoderTextTest, Unsubscribe) {
+  net::WireEncodeUnsubscribe(os, 5);
+  ASSERT_EQ(os.str(), "{\"method\":\"unsubscribe\",\"params\":{\"subuid\":5}}");
+}
+
+TEST_F(WireEncoderTextTest, Announce) {
+  net::WireEncodeAnnounce(os, "test", 5, "double", wpi::json::object(),
+                          std::nullopt);
+  ASSERT_EQ(os.str(),
+            "{\"method\":\"announce\",\"params\":{\"id\":5,\"name\":\"test\","
+            "\"properties\":{},\"type\":\"double\"}}");
+}
+
+TEST_F(WireEncoderTextTest, AnnounceProperties) {
+  net::WireEncodeAnnounce(os, "test", 5, "double", {{"k", 6}}, std::nullopt);
+  ASSERT_EQ(os.str(),
+            "{\"method\":\"announce\",\"params\":{\"id\":5,\"name\":\"test\","
+            "\"properties\":{\"k\":6},\"type\":\"double\"}}");
+}
+
+TEST_F(WireEncoderTextTest, AnnouncePubuid) {
+  net::WireEncodeAnnounce(os, "test", 5, "double", wpi::json::object(), 6);
+  ASSERT_EQ(os.str(),
+            "{\"method\":\"announce\",\"params\":{\"id\":5,\"name\":\"test\","
+            "\"properties\":{},\"pubuid\":6,\"type\":\"double\"}}");
+}
+
+TEST_F(WireEncoderTextTest, Unannounce) {
+  net::WireEncodeUnannounce(os, "test", 5);
+  ASSERT_EQ(
+      os.str(),
+      "{\"method\":\"unannounce\",\"params\":{\"id\":5,\"name\":\"test\"}}");
+}
+
+TEST_F(WireEncoderTextTest, MessagePublish) {
+  net::ClientMessage msg{net::PublishMsg{
+      Handle{0, 5, Handle::kPublisher}, 0, "test", "double", {{"k", 6}}, {}}};
+  ASSERT_TRUE(net::WireEncodeText(os, msg));
+  ASSERT_EQ(os.str(),
+            "{\"method\":\"publish\",\"params\":{"
+            "\"name\":\"test\",\"properties\":{\"k\":6},"
+            "\"pubuid\":5,\"type\":\"double\"}}");
+}
+
+TEST_F(WireEncoderTextTest, MessageUnpublish) {
+  net::ClientMessage msg{
+      net::UnpublishMsg{Handle{0, 5, Handle::kPublisher}, 0}};
+  ASSERT_TRUE(net::WireEncodeText(os, msg));
+  ASSERT_EQ(os.str(), "{\"method\":\"unpublish\",\"params\":{\"pubuid\":5}}");
+}
+
+TEST_F(WireEncoderTextTest, MessageSetProperties) {
+  net::ClientMessage msg{net::SetPropertiesMsg{0, "test", {{"k", 6}}}};
+  ASSERT_TRUE(net::WireEncodeText(os, msg));
+  ASSERT_EQ(os.str(),
+            "{\"method\":\"setproperties\",\"params\":{"
+            "\"name\":\"test\",\"update\":{\"k\":6}}}");
+}
+
+TEST_F(WireEncoderTextTest, MessageSubscribe) {
+  net::ClientMessage msg{
+      net::SubscribeMsg{Handle{0, 5, Handle::kSubscriber}, {"a", "b"}, {}}};
+  ASSERT_TRUE(net::WireEncodeText(os, msg));
+  ASSERT_EQ(os.str(),
+            "{\"method\":\"subscribe\",\"params\":{"
+            "\"options\":{},\"topics\":[\"a\",\"b\"],\"subuid\":5}}");
+}
+
+TEST_F(WireEncoderTextTest, MessageUnsubscribe) {
+  net::ClientMessage msg{
+      net::UnsubscribeMsg{Handle{0, 5, Handle::kSubscriber}}};
+  ASSERT_TRUE(net::WireEncodeText(os, msg));
+  ASSERT_EQ(os.str(), "{\"method\":\"unsubscribe\",\"params\":{\"subuid\":5}}");
+}
+
+TEST_F(WireEncoderTextTest, MessageAnnounce) {
+  net::ServerMessage msg{
+      net::AnnounceMsg{"test", 5, "double", std::nullopt, wpi::json::object()}};
+  ASSERT_TRUE(net::WireEncodeText(os, msg));
+  ASSERT_EQ(os.str(),
+            "{\"method\":\"announce\",\"params\":{\"id\":5,\"name\":\"test\","
+            "\"properties\":{},\"type\":\"double\"}}");
+}
+
+TEST_F(WireEncoderTextTest, MessageAnnounceProperties) {
+  net::ServerMessage msg{
+      net::AnnounceMsg{"test", 5, "double", std::nullopt, {{"k", 6}}}};
+  ASSERT_TRUE(net::WireEncodeText(os, msg));
+  ASSERT_EQ(os.str(),
+            "{\"method\":\"announce\",\"params\":{\"id\":5,\"name\":\"test\","
+            "\"properties\":{\"k\":6},\"type\":\"double\"}}");
+}
+
+TEST_F(WireEncoderTextTest, MessageAnnouncePubuid) {
+  net::ServerMessage msg{
+      net::AnnounceMsg{"test", 5, "double", 6, wpi::json::object()}};
+  ASSERT_TRUE(net::WireEncodeText(os, msg));
+  ASSERT_EQ(os.str(),
+            "{\"method\":\"announce\",\"params\":{\"id\":5,\"name\":\"test\","
+            "\"properties\":{},\"pubuid\":6,\"type\":\"double\"}}");
+}
+
+TEST_F(WireEncoderTextTest, MessageUnannounce) {
+  net::ServerMessage msg{net::UnannounceMsg{"test", 5}};
+  ASSERT_TRUE(net::WireEncodeText(os, msg));
+  ASSERT_EQ(
+      os.str(),
+      "{\"method\":\"unannounce\",\"params\":{\"id\":5,\"name\":\"test\"}}");
+}
+
+TEST_F(WireEncoderTextTest, ServerMessageEmpty) {
+  ASSERT_FALSE(net::WireEncodeText(os, net::ServerMessage{}));
+}
+
+TEST_F(WireEncoderTextTest, ServerMessageValue) {
+  net::ServerMessage msg{net::ServerValueMsg{}};
+  ASSERT_FALSE(net::WireEncodeText(os, msg));
+}
+
+TEST_F(WireEncoderBinaryTest, Boolean) {
+  net::WireEncodeBinary(os, 5, 6, Value::MakeBoolean(true));
+  ASSERT_THAT(out, wpi::SpanEq("\x94\x05\x06\x00\xc3"_us));
+}
+
+TEST_F(WireEncoderBinaryTest, Integer) {
+  net::WireEncodeBinary(os, 5, 6, Value::MakeInteger(7));
+  ASSERT_THAT(out, wpi::SpanEq("\x94\x05\x06\x02\x07"_us));
+}
+
+TEST_F(WireEncoderBinaryTest, Float) {
+  net::WireEncodeBinary(os, 5, 6, Value::MakeFloat(2.5));
+  ASSERT_THAT(out, wpi::SpanEq("\x94\x05\x06\x03\xca\x40\x20\x00\x00"_us));
+}
+
+TEST_F(WireEncoderBinaryTest, Double) {
+  net::WireEncodeBinary(os, 5, 6, Value::MakeDouble(2.5));
+  ASSERT_THAT(
+      out,
+      wpi::SpanEq("\x94\x05\x06\x01\xcb\x40\x04\x00\x00\x00\x00\x00\x00"_us));
+}
+
+TEST_F(WireEncoderBinaryTest, String) {
+  net::WireEncodeBinary(os, 5, 6, Value::MakeString("hello"));
+  ASSERT_THAT(out, wpi::SpanEq("\x94\x05\x06\x04\xa5hello"_us));
+}
+
+TEST_F(WireEncoderBinaryTest, Raw) {
+  net::WireEncodeBinary(os, 5, 6, Value::MakeRaw("hello"_us));
+  ASSERT_THAT(out, wpi::SpanEq("\x94\x05\x06\x05\xc4\x05hello"_us));
+}
+
+TEST_F(WireEncoderBinaryTest, BooleanArray) {
+  net::WireEncodeBinary(os, 5, 6, Value::MakeBooleanArray({true, false, true}));
+  ASSERT_THAT(out, wpi::SpanEq("\x94\x05\x06\x10\x93\xc3\xc2\xc3"_us));
+}
+
+TEST_F(WireEncoderBinaryTest, IntegerArray) {
+  net::WireEncodeBinary(os, 5, 6, Value::MakeIntegerArray({1, 2, 4}));
+  ASSERT_THAT(out, wpi::SpanEq("\x94\x05\x06\x12\x93\x01\x02\x04"_us));
+}
+
+TEST_F(WireEncoderBinaryTest, FloatArray) {
+  net::WireEncodeBinary(os, 5, 6, Value::MakeFloatArray({1, 2, 3}));
+  ASSERT_THAT(out, wpi::SpanEq("\x94\x05\x06\x13\x93"
+                               "\xca\x3f\x80\x00\x00"
+                               "\xca\x40\x00\x00\x00"
+                               "\xca\x40\x40\x00\x00"_us));
+}
+
+TEST_F(WireEncoderBinaryTest, DoubleArray) {
+  net::WireEncodeBinary(os, 5, 6, Value::MakeDoubleArray({1, 2, 3}));
+  ASSERT_THAT(out, wpi::SpanEq("\x94\x05\x06\x11\x93"
+                               "\xcb\x3f\xf0\x00\x00\x00\x00\x00\x00"
+                               "\xcb\x40\x00\x00\x00\x00\x00\x00\x00"
+                               "\xcb\x40\x08\x00\x00\x00\x00\x00\x00"_us));
+}
+
+TEST_F(WireEncoderBinaryTest, StringArray) {
+  net::WireEncodeBinary(os, 5, 6, Value::MakeStringArray({"hello", "bye"}));
+  ASSERT_THAT(out, wpi::SpanEq("\x94\x05\x06\x14\x92\xa5hello\xa3"
+                               "bye"_us));
+}
+
+}  // namespace nt
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/net3/MessageMatcher3.cpp b/third_party/allwpilib/ntcore/src/test/native/cpp/net3/MessageMatcher3.cpp
new file mode 100644
index 0000000..d595c6a
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/test/native/cpp/net3/MessageMatcher3.cpp
@@ -0,0 +1,45 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "MessageMatcher3.h"
+
+namespace nt::net3 {
+
+bool MessageMatcher::MatchAndExplain(
+    Message3 msg, ::testing::MatchResultListener* listener) const {
+  bool match = true;
+  if (msg.str() != goodmsg.str()) {
+    *listener << "str mismatch ";
+    match = false;
+  }
+  if ((!msg.value() && goodmsg.value()) || (msg.value() && !goodmsg.value()) ||
+      (msg.value() && goodmsg.value() && msg.value() != goodmsg.value())) {
+    *listener << "value mismatch ";
+    match = false;
+  }
+  if (msg.id() != goodmsg.id()) {
+    *listener << "id mismatch ";
+    match = false;
+  }
+  if (msg.flags() != goodmsg.flags()) {
+    *listener << "flags mismatch";
+    match = false;
+  }
+  if (msg.seq_num_uid() != goodmsg.seq_num_uid()) {
+    *listener << "seq_num_uid mismatch";
+    match = false;
+  }
+  return match;
+}
+
+void MessageMatcher::DescribeTo(::std::ostream* os) const {
+  PrintTo(goodmsg, os);
+}
+
+void MessageMatcher::DescribeNegationTo(::std::ostream* os) const {
+  *os << "is not equal to ";
+  PrintTo(goodmsg, os);
+}
+
+}  // namespace nt::net3
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/net3/MessageMatcher3.h b/third_party/allwpilib/ntcore/src/test/native/cpp/net3/MessageMatcher3.h
new file mode 100644
index 0000000..6b1e770
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/test/native/cpp/net3/MessageMatcher3.h
@@ -0,0 +1,34 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <memory>
+#include <ostream>
+#include <utility>
+
+#include "../TestPrinters.h"
+#include "gmock/gmock.h"
+#include "net3/Message3.h"
+
+namespace nt::net3 {
+
+class MessageMatcher : public ::testing::MatcherInterface<Message3> {
+ public:
+  explicit MessageMatcher(Message3 goodmsg_) : goodmsg(std::move(goodmsg_)) {}
+
+  bool MatchAndExplain(Message3 msg,
+                       ::testing::MatchResultListener* listener) const override;
+  void DescribeTo(::std::ostream* os) const override;
+  void DescribeNegationTo(::std::ostream* os) const override;
+
+ private:
+  Message3 goodmsg;
+};
+
+inline ::testing::Matcher<Message3> MessageEq(Message3 goodmsg) {
+  return ::testing::MakeMatcher(new MessageMatcher(std::move(goodmsg)));
+}
+
+}  // namespace nt::net3
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/net3/MockWireConnection3.h b/third_party/allwpilib/ntcore/src/test/native/cpp/net3/MockWireConnection3.h
new file mode 100644
index 0000000..b7c785f
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/test/native/cpp/net3/MockWireConnection3.h
@@ -0,0 +1,44 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <stdint.h>
+
+#include <span>
+#include <vector>
+
+#include <wpi/raw_ostream.h>
+
+#include "gmock/gmock.h"
+#include "net3/WireConnection3.h"
+
+namespace nt::net3 {
+
+class MockWireConnection3 : public WireConnection3 {
+ public:
+  MockWireConnection3() : m_os{m_data} {}
+
+  MOCK_METHOD(bool, Ready, (), (const, override));
+
+  Writer Send() override { return {m_os, *this}; }
+
+  MOCK_METHOD(void, Data, (std::span<const uint8_t> data));
+
+  MOCK_METHOD(void, Flush, (), (override));
+
+  MOCK_METHOD(void, Disconnect, (std::string_view reason), (override));
+
+ protected:
+  void FinishSend() override {
+    Data(m_data);
+    m_data.resize(0);
+  }
+
+ private:
+  std::vector<uint8_t> m_data;
+  wpi::raw_uvector_ostream m_os;
+};
+
+}  // namespace nt::net3
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/net3/WireDecoder3Test.cpp b/third_party/allwpilib/ntcore/src/test/native/cpp/net3/WireDecoder3Test.cpp
new file mode 100644
index 0000000..1cd6ecb
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/test/native/cpp/net3/WireDecoder3Test.cpp
@@ -0,0 +1,276 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <stdint.h>
+
+#include <cfloat>
+#include <climits>
+#include <string>
+#include <string_view>
+
+#include "../SpanMatcher.h"
+#include "../TestPrinters.h"
+#include "../ValueMatcher.h"
+#include "gmock/gmock.h"
+#include "gtest/gtest.h"
+#include "net3/WireDecoder3.h"
+#include "networktables/NetworkTableValue.h"
+
+using namespace std::string_view_literals;
+using testing::_;
+using testing::MockFunction;
+using testing::StrictMock;
+
+namespace nt {
+
+class MockMessageHandler3 : public net3::MessageHandler3 {
+ public:
+  MOCK_METHOD0(KeepAlive, void());
+  MOCK_METHOD0(ServerHelloDone, void());
+  MOCK_METHOD0(ClientHelloDone, void());
+  MOCK_METHOD0(ClearEntries, void());
+  MOCK_METHOD1(ProtoUnsup, void(unsigned int proto_rev));
+  MOCK_METHOD2(ClientHello,
+               void(std::string_view self_id, unsigned int proto_rev));
+  MOCK_METHOD2(ServerHello, void(unsigned int flags, std::string_view self_id));
+  MOCK_METHOD5(EntryAssign, void(std::string_view name, unsigned int id,
+                                 unsigned int seq_num, const Value& value,
+                                 unsigned int flags));
+  MOCK_METHOD3(EntryUpdate,
+               void(unsigned int id, unsigned int seq_num, const Value& value));
+  MOCK_METHOD2(FlagsUpdate, void(unsigned int id, unsigned int flags));
+  MOCK_METHOD1(EntryDelete, void(unsigned int id));
+  MOCK_METHOD3(ExecuteRpc, void(unsigned int id, unsigned int uid,
+                                std::span<const uint8_t> params));
+  MOCK_METHOD3(RpcResponse, void(unsigned int id, unsigned int uid,
+                                 std::span<const uint8_t> result));
+};
+
+class WireDecoder3Test : public ::testing::Test {
+ protected:
+  StrictMock<MockMessageHandler3> handler;
+  net3::WireDecoder3 decoder{handler};
+
+  void DecodeComplete(std::span<const uint8_t> in) {
+    decoder.Execute(&in);
+    EXPECT_TRUE(in.empty());
+    ASSERT_EQ(decoder.GetError(), "");
+  }
+};
+
+TEST_F(WireDecoder3Test, KeepAlive) {
+  EXPECT_CALL(handler, KeepAlive());
+  DecodeComplete("\x00"_us);
+}
+
+TEST_F(WireDecoder3Test, ClientHello) {
+  EXPECT_CALL(handler, ClientHello(std::string_view{"hello"}, 0x0300u));
+  DecodeComplete("\x01\x03\x00\x05hello"_us);
+}
+
+TEST_F(WireDecoder3Test, ProtoUnsup) {
+  EXPECT_CALL(handler, ProtoUnsup(0x0300u));
+  EXPECT_CALL(handler, ProtoUnsup(0x0200u));
+  DecodeComplete("\x02\x03\x00\x02\x02\x00"_us);
+}
+
+TEST_F(WireDecoder3Test, ServerHelloDone) {
+  EXPECT_CALL(handler, ServerHelloDone());
+  DecodeComplete("\x03"_us);
+}
+
+TEST_F(WireDecoder3Test, ServerHello) {
+  EXPECT_CALL(handler, ServerHello(0x03, std::string_view{"hello"}));
+  DecodeComplete("\x04\x03\x05hello"_us);
+}
+
+TEST_F(WireDecoder3Test, ClientHelloDone) {
+  EXPECT_CALL(handler, ClientHelloDone());
+  DecodeComplete("\x05"_us);
+}
+
+TEST_F(WireDecoder3Test, FlagsUpdate) {
+  EXPECT_CALL(handler, FlagsUpdate(0x5678, 0x03));
+  DecodeComplete("\x12\x56\x78\x03"_us);
+}
+
+TEST_F(WireDecoder3Test, EntryDelete) {
+  EXPECT_CALL(handler, EntryDelete(0x5678));
+  DecodeComplete("\x13\x56\x78"_us);
+}
+
+TEST_F(WireDecoder3Test, ClearEntries) {
+  EXPECT_CALL(handler, ClearEntries());
+  DecodeComplete("\x14\xd0\x6c\xb2\x7a"_us);
+}
+
+TEST_F(WireDecoder3Test, ClearEntriesInvalid) {
+  auto in = "\x14\xd0\x6c\xb2\x7b"_us;
+  decoder.Execute(&in);
+  EXPECT_EQ(decoder.GetError(), "received incorrect CLEAR_ENTRIES magic value");
+}
+
+TEST_F(WireDecoder3Test, ExecuteRpc) {
+  EXPECT_CALL(handler, ExecuteRpc(0x5678, 0x1234, wpi::SpanEq("hello"_us)));
+  DecodeComplete("\x20\x56\x78\x12\x34\x05hello"_us);
+}
+
+TEST_F(WireDecoder3Test, RpcResponse) {
+  EXPECT_CALL(handler, RpcResponse(0x5678, 0x1234, wpi::SpanEq("hello"_us)));
+  DecodeComplete("\x21\x56\x78\x12\x34\x05hello"_us);
+}
+
+TEST_F(WireDecoder3Test, UnknownMessage) {
+  auto in = "\x23"_us;
+  decoder.Execute(&in);
+  EXPECT_EQ(decoder.GetError(), "unrecognized message type: 35");
+}
+
+TEST_F(WireDecoder3Test, EntryAssignBoolean) {
+  EXPECT_CALL(handler, EntryAssign("test"sv, 0x5678, 0x1234,
+                                   Value::MakeBoolean(true), 0x9a));
+  DecodeComplete("\x10\x04test\x00\x56\x78\x12\x34\x9a\x01"_us);
+}
+
+TEST_F(WireDecoder3Test, EntryAssignDouble) {
+  EXPECT_CALL(handler, EntryAssign("test"sv, 0x5678, 0x1234,
+                                   Value::MakeDouble(2.3e5), 0x9a));
+  DecodeComplete(
+      "\x10\x04test\x01\x56\x78\x12\x34"
+      "\x9a\x41\x0c\x13\x80\x00\x00\x00\x00"_us);
+}
+
+TEST_F(WireDecoder3Test, EntryUpdateBoolean) {
+  EXPECT_CALL(handler, EntryUpdate(0x5678, 0x1234, Value::MakeBoolean(true)));
+  DecodeComplete("\x11\x56\x78\x12\x34\x00\x01"_us);
+}
+
+TEST_F(WireDecoder3Test, EntryUpdateDouble) {
+  // values except min and max from
+  // http://www.binaryconvert.com/result_double.html
+  EXPECT_CALL(handler, EntryUpdate(0x5678, 0x1234, Value::MakeDouble(0.0)));
+  DecodeComplete("\x11\x56\x78\x12\x34\x01\x00\x00\x00\x00\x00\x00\x00\x00"_us);
+  EXPECT_CALL(handler, EntryUpdate(0x5678, 0x1234, Value::MakeDouble(2.3e5)));
+  DecodeComplete("\x11\x56\x78\x12\x34\x01\x41\x0c\x13\x80\x00\x00\x00\x00"_us);
+  EXPECT_CALL(
+      handler,
+      EntryUpdate(0x5678, 0x1234,
+                  Value::MakeDouble(std::numeric_limits<double>::infinity())));
+  DecodeComplete("\x11\x56\x78\x12\x34\x01\x7f\xf0\x00\x00\x00\x00\x00\x00"_us);
+  EXPECT_CALL(handler, EntryUpdate(0x5678, 0x1234, Value::MakeDouble(DBL_MIN)));
+  DecodeComplete("\x11\x56\x78\x12\x34\x01\x00\x10\x00\x00\x00\x00\x00\x00"_us);
+  EXPECT_CALL(handler, EntryUpdate(0x5678, 0x1234, Value::MakeDouble(DBL_MAX)));
+  DecodeComplete("\x11\x56\x78\x12\x34\x01\x7f\xef\xff\xff\xff\xff\xff\xff"_us);
+}
+
+TEST_F(WireDecoder3Test, EntryUpdateString) {
+  EXPECT_CALL(handler,
+              EntryUpdate(0x5678, 0x1234, Value::MakeString("hello"sv)));
+  DecodeComplete("\x11\x56\x78\x12\x34\x02\x05hello"_us);
+}
+
+TEST_F(WireDecoder3Test, EntryUpdateString2) {
+  std::vector<uint8_t> in{0x11, 0x56, 0x78, 0x12, 0x34, 0x02, 0x7f};
+  in.insert(in.end(), 127, '*');
+  std::string out(127, '*');
+  EXPECT_CALL(handler,
+              EntryUpdate(0x5678, 0x1234, Value::MakeString(std::move(out))));
+  DecodeComplete(in);
+}
+
+TEST_F(WireDecoder3Test, EntryUpdateStringLarge) {
+  std::vector<uint8_t> in{0x11, 0x56, 0x78, 0x12, 0x34, 0x02, 0x80, 0x01};
+  in.insert(in.end(), 127, '*');
+  in.push_back('x');
+
+  std::string out(127, '*');
+  out.push_back('x');
+
+  EXPECT_CALL(handler,
+              EntryUpdate(0x5678, 0x1234, Value::MakeString(std::move(out))));
+  DecodeComplete(in);
+}
+
+TEST_F(WireDecoder3Test, EntryUpdateStringHuge) {
+  std::vector<uint8_t> in{0x11, 0x56, 0x78, 0x12, 0x34, 0x02, 0x81, 0x80, 0x04};
+  in.insert(in.end(), 65534, '*');
+  in.insert(in.end(), 3, 'x');
+
+  std::string out(65534, '*');
+  out.append(3, 'x');
+
+  EXPECT_CALL(handler,
+              EntryUpdate(0x5678, 0x1234, Value::MakeString(std::move(out))));
+  DecodeComplete(in);
+}
+
+TEST_F(WireDecoder3Test, EntryUpdateRaw) {
+  EXPECT_CALL(handler, EntryUpdate(0x5678, 0x1234, Value::MakeRaw("hello"_us)));
+  DecodeComplete("\x11\x56\x78\x12\x34\x03\x05hello"_us);
+}
+
+TEST_F(WireDecoder3Test, EntryUpdateBooleanArray) {
+  EXPECT_CALL(handler,
+              EntryUpdate(0x5678, 0x1234,
+                          Value::MakeBooleanArray({false, true, false})));
+  DecodeComplete("\x11\x56\x78\x12\x34\x10\x03\x00\x01\x00"_us);
+}
+
+TEST_F(WireDecoder3Test, EntryUpdateBooleanArrayLarge) {
+  std::vector<uint8_t> in{0x11, 0x56, 0x78, 0x12, 0x34, 0x10, 0xff};
+  in.insert(in.end(), 255, 0);
+  std::vector<int> out(255, 0);
+  EXPECT_CALL(handler, EntryUpdate(0x5678, 0x1234,
+                                   Value::MakeBooleanArray(std::move(out))));
+  DecodeComplete(in);
+}
+
+TEST_F(WireDecoder3Test, EntryUpdateDoubleArray) {
+  EXPECT_CALL(handler,
+              EntryUpdate(0x5678, 0x1234, Value::MakeDoubleArray({0.5, 0.25})));
+  DecodeComplete(
+      "\x11\x56\x78\x12\x34\x11\x02"
+      "\x3f\xe0\x00\x00\x00\x00\x00\x00"
+      "\x3f\xd0\x00\x00\x00\x00\x00\x00"_us);
+}
+
+TEST_F(WireDecoder3Test, EntryUpdateDoubleArrayLarge) {
+  std::vector<uint8_t> in{0x11, 0x56, 0x78, 0x12, 0x34, 0x11, 0xff};
+  in.insert(in.end(), 255 * 8, 0);
+  std::vector<double> out(255, 0.0);
+  EXPECT_CALL(handler, EntryUpdate(0x5678, 0x1234,
+                                   Value::MakeDoubleArray(std::move(out))));
+  DecodeComplete(in);
+}
+
+TEST_F(WireDecoder3Test, EntryUpdateStringArray) {
+  EXPECT_CALL(handler, EntryUpdate(0x5678, 0x1234,
+                                   Value::MakeStringArray({"hello", "bye"})));
+  DecodeComplete(
+      "\x11\x56\x78\x12\x34\x12\x02\x05hello\x03"
+      "bye"_us);
+}
+
+TEST_F(WireDecoder3Test, EntryUpdateStringArrayLarge) {
+  std::vector<uint8_t> in{0x11, 0x56, 0x78, 0x12, 0x34, 0x12, 0xff};
+  in.insert(in.end(), 255, 0);
+  std::vector<std::string> out(255, "");
+  EXPECT_CALL(handler, EntryUpdate(0x5678, 0x1234,
+                                   Value::MakeStringArray(std::move(out))));
+  DecodeComplete(in);
+}
+
+TEST_F(WireDecoder3Test, EntryUpdateRpc) {
+  // RPC values are decoded as raw
+  EXPECT_CALL(handler, EntryUpdate(0x5678, 0x1234, Value::MakeRaw("hello"_us)));
+  DecodeComplete("\x11\x56\x78\x12\x34\x20\x05hello"_us);
+}
+
+TEST_F(WireDecoder3Test, EntryUpdateTypeError) {
+  auto in = "\x11\x56\x78\x12\x34\x30\x11"_us;
+  decoder.Execute(&in);
+  ASSERT_EQ(decoder.GetError(), "unrecognized value type");
+}
+
+}  // namespace nt
diff --git a/third_party/allwpilib/ntcore/src/test/native/cpp/net3/WireEncoder3Test.cpp b/third_party/allwpilib/ntcore/src/test/native/cpp/net3/WireEncoder3Test.cpp
new file mode 100644
index 0000000..bb4bfd2
--- /dev/null
+++ b/third_party/allwpilib/ntcore/src/test/native/cpp/net3/WireEncoder3Test.cpp
@@ -0,0 +1,283 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <cfloat>
+#include <climits>
+#include <string>
+#include <string_view>
+#include <vector>
+
+#include <wpi/raw_ostream.h>
+
+#include "../SpanMatcher.h"
+#include "../TestPrinters.h"
+#include "gtest/gtest.h"
+#include "net3/Message3.h"
+#include "net3/WireEncoder3.h"
+#include "networktables/NetworkTableValue.h"
+
+using namespace std::string_view_literals;
+
+namespace nt {
+
+class WireEncoder3Test : public ::testing::Test {
+ protected:
+  std::vector<uint8_t> out;
+  wpi::raw_uvector_ostream os{out};
+};
+
+TEST_F(WireEncoder3Test, Unknown) {
+  net3::WireEncode(os, net3::Message3{});
+  ASSERT_TRUE(out.empty());
+}
+
+TEST_F(WireEncoder3Test, KeepAlive) {
+  net3::WireEncode(os, net3::Message3::KeepAlive());
+  ASSERT_THAT(out, wpi::SpanEq("\x00"_us));
+}
+
+TEST_F(WireEncoder3Test, ClientHello) {
+  net3::WireEncode(os, net3::Message3::ClientHello("hello"));
+  ASSERT_THAT(out, wpi::SpanEq("\x01\x03\x00\x05hello"_us));
+}
+
+TEST_F(WireEncoder3Test, ProtoUnsup) {
+  net3::WireEncode(os, net3::Message3::ProtoUnsup());
+  net3::WireEncode(os, net3::Message3::ProtoUnsup(0x0200u));
+  ASSERT_THAT(out, wpi::SpanEq("\x02\x03\x00\x02\x02\x00"_us));
+}
+
+TEST_F(WireEncoder3Test, ServerHelloDone) {
+  net3::WireEncode(os, net3::Message3::ServerHelloDone());
+  ASSERT_THAT(out, wpi::SpanEq("\x03"_us));
+}
+
+TEST_F(WireEncoder3Test, ServerHello) {
+  net3::WireEncode(os, net3::Message3::ServerHello(0x03, "hello"));
+  ASSERT_THAT(out, wpi::SpanEq("\x04\x03\x05hello"_us));
+}
+
+TEST_F(WireEncoder3Test, ClientHelloDone) {
+  net3::WireEncode(os, net3::Message3::ClientHelloDone());
+  ASSERT_THAT(out, wpi::SpanEq("\x05"_us));
+}
+
+TEST_F(WireEncoder3Test, FlagsUpdate) {
+  net3::WireEncode(os, net3::Message3::FlagsUpdate(0x5678, 0x03));
+  ASSERT_THAT(out, wpi::SpanEq("\x12\x56\x78\x03"_us));
+}
+
+TEST_F(WireEncoder3Test, EntryDelete) {
+  net3::WireEncode(os, net3::Message3::EntryDelete(0x5678));
+  ASSERT_THAT(out, wpi::SpanEq("\x13\x56\x78"_us));
+}
+
+TEST_F(WireEncoder3Test, ClearEntries) {
+  net3::WireEncode(os, net3::Message3::ClearEntries());
+  ASSERT_THAT(out, wpi::SpanEq("\x14\xd0\x6c\xb2\x7a"_us));
+}
+
+TEST_F(WireEncoder3Test, ExecuteRpc) {
+  net3::WireEncode(os, net3::Message3::ExecuteRpc(0x5678, 0x1234, "hello"_us));
+  ASSERT_THAT(out, wpi::SpanEq("\x20\x56\x78\x12\x34\x05hello"_us));
+}
+
+TEST_F(WireEncoder3Test, RpcResponse) {
+  net3::WireEncode(os, net3::Message3::RpcResponse(0x5678, 0x1234, "hello"_us));
+  ASSERT_THAT(out, wpi::SpanEq("\x21\x56\x78\x12\x34\x05hello"_us));
+}
+
+TEST_F(WireEncoder3Test, EntryAssignBoolean) {
+  net3::WireEncode(os,
+                   net3::Message3::EntryAssign("test"sv, 0x5678, 0x1234,
+                                               Value::MakeBoolean(true), 0x9a));
+  ASSERT_THAT(out, wpi::SpanEq("\x10\x04test\x00\x56\x78\x12\x34\x9a\x01"_us));
+}
+
+TEST_F(WireEncoder3Test, EntryAssignDouble) {
+  net3::WireEncode(os,
+                   net3::Message3::EntryAssign("test"sv, 0x5678, 0x1234,
+                                               Value::MakeDouble(2.3e5), 0x9a));
+  ASSERT_THAT(out, wpi::SpanEq("\x10\x04test\x01\x56\x78\x12\x34"
+                               "\x9a\x41\x0c\x13\x80\x00\x00\x00\x00"_us));
+}
+
+TEST_F(WireEncoder3Test, EntryUpdateBoolean) {
+  net3::WireEncode(os, net3::Message3::EntryUpdate(0x5678, 0x1234,
+                                                   Value::MakeBoolean(true)));
+  ASSERT_THAT(out, wpi::SpanEq("\x11\x56\x78\x12\x34\x00\x01"_us));
+}
+
+TEST_F(WireEncoder3Test, EntryUpdateDouble) {
+  // values except min and max from
+  // http://www.binaryconvert.com/result_double.html
+  net3::WireEncode(
+      os, net3::Message3::EntryUpdate(0x5678, 0x1234, Value::MakeDouble(0.0)));
+  ASSERT_THAT(
+      out, wpi::SpanEq(
+               "\x11\x56\x78\x12\x34\x01\x00\x00\x00\x00\x00\x00\x00\x00"_us));
+
+  out.clear();
+  net3::WireEncode(os, net3::Message3::EntryUpdate(0x5678, 0x1234,
+                                                   Value::MakeDouble(2.3e5)));
+  ASSERT_THAT(
+      out, wpi::SpanEq(
+               "\x11\x56\x78\x12\x34\x01\x41\x0c\x13\x80\x00\x00\x00\x00"_us));
+
+  out.clear();
+  net3::WireEncode(
+      os, net3::Message3::EntryUpdate(
+              0x5678, 0x1234,
+              Value::MakeDouble(std::numeric_limits<double>::infinity())));
+  ASSERT_THAT(
+      out, wpi::SpanEq(
+               "\x11\x56\x78\x12\x34\x01\x7f\xf0\x00\x00\x00\x00\x00\x00"_us));
+
+  out.clear();
+  net3::WireEncode(os, net3::Message3::EntryUpdate(0x5678, 0x1234,
+                                                   Value::MakeDouble(DBL_MIN)));
+  ASSERT_THAT(
+      out, wpi::SpanEq(
+               "\x11\x56\x78\x12\x34\x01\x00\x10\x00\x00\x00\x00\x00\x00"_us));
+
+  out.clear();
+  net3::WireEncode(os, net3::Message3::EntryUpdate(0x5678, 0x1234,
+                                                   Value::MakeDouble(DBL_MAX)));
+  ASSERT_THAT(
+      out, wpi::SpanEq(
+               "\x11\x56\x78\x12\x34\x01\x7f\xef\xff\xff\xff\xff\xff\xff"_us));
+}
+
+TEST_F(WireEncoder3Test, EntryUpdateString) {
+  net3::WireEncode(os, net3::Message3::EntryUpdate(
+                           0x5678, 0x1234, Value::MakeString("hello"sv)));
+  ASSERT_THAT(out, wpi::SpanEq("\x11\x56\x78\x12\x34\x02\x05hello"_us));
+}
+
+TEST_F(WireEncoder3Test, EntryUpdateString2) {
+  std::vector<uint8_t> ex{0x11, 0x56, 0x78, 0x12, 0x34, 0x02, 0x7f};
+  ex.insert(ex.end(), 127, '*');
+  std::string in(127, '*');
+  net3::WireEncode(os, net3::Message3::EntryUpdate(
+                           0x5678, 0x1234, Value::MakeString(std::move(in))));
+  ASSERT_THAT(out, ex);
+}
+
+TEST_F(WireEncoder3Test, EntryUpdateStringLarge) {
+  std::vector<uint8_t> ex{0x11, 0x56, 0x78, 0x12, 0x34, 0x02, 0x80, 0x01};
+  ex.insert(ex.end(), 127, '*');
+  ex.push_back('x');
+
+  std::string in(127, '*');
+  in.push_back('x');
+
+  net3::WireEncode(os, net3::Message3::EntryUpdate(
+                           0x5678, 0x1234, Value::MakeString(std::move(in))));
+  ASSERT_THAT(out, ex);
+}
+
+TEST_F(WireEncoder3Test, EntryUpdateStringHuge) {
+  std::vector<uint8_t> ex{0x11, 0x56, 0x78, 0x12, 0x34, 0x02, 0x81, 0x80, 0x04};
+  ex.insert(ex.end(), 65534, '*');
+  ex.insert(ex.end(), 3, 'x');
+
+  std::string in(65534, '*');
+  in.append(3, 'x');
+
+  net3::WireEncode(os, net3::Message3::EntryUpdate(
+                           0x5678, 0x1234, Value::MakeString(std::move(in))));
+  ASSERT_THAT(out, ex);
+}
+
+TEST_F(WireEncoder3Test, EntryUpdateRaw) {
+  net3::WireEncode(os, net3::Message3::EntryUpdate(0x5678, 0x1234,
+                                                   Value::MakeRaw("hello"_us)));
+  ASSERT_THAT(out, wpi::SpanEq("\x11\x56\x78\x12\x34\x03\x05hello"_us));
+}
+
+TEST_F(WireEncoder3Test, EntryUpdateBooleanArray) {
+  net3::WireEncode(
+      os, net3::Message3::EntryUpdate(
+              0x5678, 0x1234, Value::MakeBooleanArray({false, true, false})));
+  ASSERT_THAT(out, wpi::SpanEq("\x11\x56\x78\x12\x34\x10\x03\x00\x01\x00"_us));
+}
+
+TEST_F(WireEncoder3Test, EntryUpdateBooleanArrayLarge) {
+  std::vector<uint8_t> ex{0x11, 0x56, 0x78, 0x12, 0x34, 0x10, 0xff};
+  ex.insert(ex.end(), 255, 0);
+  std::vector<int> in(255, 0);
+  net3::WireEncode(
+      os, net3::Message3::EntryUpdate(0x5678, 0x1234,
+                                      Value::MakeBooleanArray(std::move(in))));
+  ASSERT_THAT(out, ex);
+}
+
+TEST_F(WireEncoder3Test, EntryUpdateBooleanArrayTrunc) {
+  std::vector<uint8_t> ex{0x11, 0x56, 0x78, 0x12, 0x34, 0x10, 0xff};
+  ex.insert(ex.end(), 255, 0);
+  std::vector<int> in(256, 0);
+  net3::WireEncode(
+      os, net3::Message3::EntryUpdate(0x5678, 0x1234,
+                                      Value::MakeBooleanArray(std::move(in))));
+  ASSERT_THAT(out, ex);
+}
+
+TEST_F(WireEncoder3Test, EntryUpdateDoubleArray) {
+  net3::WireEncode(
+      os, net3::Message3::EntryUpdate(0x5678, 0x1234,
+                                      Value::MakeDoubleArray({0.5, 0.25})));
+  ASSERT_THAT(out, wpi::SpanEq("\x11\x56\x78\x12\x34\x11\x02"
+                               "\x3f\xe0\x00\x00\x00\x00\x00\x00"
+                               "\x3f\xd0\x00\x00\x00\x00\x00\x00"_us));
+}
+
+TEST_F(WireEncoder3Test, EntryUpdateDoubleArrayLarge) {
+  std::vector<uint8_t> ex{0x11, 0x56, 0x78, 0x12, 0x34, 0x11, 0xff};
+  ex.insert(ex.end(), 255 * 8, 0);
+  std::vector<double> in(255, 0.0);
+  net3::WireEncode(
+      os, net3::Message3::EntryUpdate(0x5678, 0x1234,
+                                      Value::MakeDoubleArray(std::move(in))));
+  ASSERT_THAT(out, ex);
+}
+
+TEST_F(WireEncoder3Test, EntryUpdateDoubleArrayTrunc) {
+  std::vector<uint8_t> ex{0x11, 0x56, 0x78, 0x12, 0x34, 0x11, 0xff};
+  ex.insert(ex.end(), 255 * 8, 0);
+  std::vector<double> in(256, 0.0);
+  net3::WireEncode(
+      os, net3::Message3::EntryUpdate(0x5678, 0x1234,
+                                      Value::MakeDoubleArray(std::move(in))));
+  ASSERT_THAT(out, ex);
+}
+
+TEST_F(WireEncoder3Test, EntryUpdateStringArray) {
+  net3::WireEncode(
+      os, net3::Message3::EntryUpdate(
+              0x5678, 0x1234, Value::MakeStringArray({"hello", "bye"})));
+  ASSERT_THAT(out, wpi::SpanEq("\x11\x56\x78\x12\x34\x12\x02\x05hello\x03"
+                               "bye"_us));
+}
+
+TEST_F(WireEncoder3Test, EntryUpdateStringArrayLarge) {
+  std::vector<uint8_t> ex{0x11, 0x56, 0x78, 0x12, 0x34, 0x12, 0xff};
+  ex.insert(ex.end(), 255, 0);
+  std::vector<std::string> in(255, "");
+  net3::WireEncode(
+      os, net3::Message3::EntryUpdate(0x5678, 0x1234,
+                                      Value::MakeStringArray(std::move(in))));
+  ASSERT_THAT(out, ex);
+}
+
+TEST_F(WireEncoder3Test, EntryUpdateStringArrayTrunc) {
+  std::vector<uint8_t> ex{0x11, 0x56, 0x78, 0x12, 0x34, 0x12, 0xff};
+  ex.insert(ex.end(), 255, 0);
+  std::vector<std::string> in(256, "");
+  net3::WireEncode(
+      os, net3::Message3::EntryUpdate(0x5678, 0x1234,
+                                      Value::MakeStringArray(std::move(in))));
+  ASSERT_THAT(out, ex);
+}
+
+}  // namespace nt
diff --git a/third_party/allwpilib/ntcoreffi/build.gradle b/third_party/allwpilib/ntcoreffi/build.gradle
new file mode 100644
index 0000000..7a377a7
--- /dev/null
+++ b/third_party/allwpilib/ntcoreffi/build.gradle
@@ -0,0 +1,90 @@
+plugins {
+    id 'c'
+    id 'maven-publish'
+}
+
+apply plugin: 'edu.wpi.first.NativeUtils'
+
+apply from: '../shared/config.gradle'
+
+def symbolFile = project.file("src/main/native/symbols.txt")
+
+nativeUtils {
+    privateExportsConfigs {
+        ntcoreffi {
+            exportsFile = symbolFile
+            performStripAllSymbols = true
+        }
+    }
+}
+
+def generatedHeaders = file("$buildDir/generated/headers")
+def generatedFile = file("$buildDir/generated/headers/ExportedSymbols.h")
+
+def generateSymbols = tasks.register('generateFfiSymbols') {
+    inputs.file(symbolFile)
+    outputs.file(generatedFile)
+
+    doLast {
+        def symbolText = symbolFile as String[]
+        symbolText = symbolText.collect {
+            "AddFunctionToLink(${it});"
+        }.join('\n')
+        symbolText += '\n'
+        generatedFile.text = symbolText
+    }
+}
+
+model {
+    components {
+        ntcoreffi(NativeLibrarySpec) {
+            sources {
+                c {
+                    source {
+                        srcDirs = ['src/main/native/c']
+                        includes = ['**/*.c']
+                    }
+                    exportedHeaders {
+                        srcDir 'src/main/native/include'
+                        srcDir generatedHeaders
+                    }
+                }
+            }
+            binaries.all { binary ->
+                if (binary instanceof StaticLibraryBinarySpec) {
+                    binary.buildable = false
+                    return
+                }
+                binary.tasks.withType(AbstractNativeSourceCompileTask) {
+                    it.dependsOn generateSymbols
+                }
+                project(':ntcore').addNtcoreDependency(binary, 'static')
+                lib project: ':wpinet', library: 'wpinet', linkage: 'static'
+                lib project: ':wpiutil', library: 'wpiutil', linkage: 'static'
+            }
+        }
+    }
+}
+
+def nativeName = 'ntcoreffi'
+def baseArtifactId = nativeName
+def artifactGroupId = "edu.wpi.first.${nativeName}"
+def zipBaseName = "_GROUP_edu_wpi_first_${nativeName}_ID_${nativeName}-cpp_CLS"
+
+model {
+    publishing {
+        def taskList = createComponentZipTasks($.components, [nativeName], zipBaseName, Zip, project, includeStandardZipFormat)
+
+        publications {
+            cpp(MavenPublication) {
+                taskList.each {
+                    artifact it
+                }
+
+                artifactId = "${baseArtifactId}-cpp"
+                groupId artifactGroupId
+                version wpilibVersioning.version.get()
+            }
+        }
+    }
+}
diff --git a/third_party/allwpilib/ntcoreffi/src/main/native/c/ntcoreffi.c b/third_party/allwpilib/ntcoreffi/src/main/native/c/ntcoreffi.c
new file mode 100644
index 0000000..66fe9a2
--- /dev/null
+++ b/third_party/allwpilib/ntcoreffi/src/main/native/c/ntcoreffi.c
@@ -0,0 +1,11 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#define AddFunctionToLink(FuncName) \
+  extern void FuncName(void);       \
+  FuncName()
+
+void DoNotCallMeImOnlyForLinking(void) {
+#include "ExportedSymbols.h"
+}
diff --git a/third_party/allwpilib/ntcoreffi/src/main/native/symbols.txt b/third_party/allwpilib/ntcoreffi/src/main/native/symbols.txt
new file mode 100644
index 0000000..4f6ebeb
--- /dev/null
+++ b/third_party/allwpilib/ntcoreffi/src/main/native/symbols.txt
@@ -0,0 +1,231 @@
+NT_AddListener
+NT_AddListenerMultiple
+NT_AddListenerSingle
+NT_AddLogger
+NT_AddPolledListener
+NT_AddPolledListenerMultiple
+NT_AddPolledListenerSingle
+NT_AddPolledLogger
+NT_AllocateBooleanArray
+NT_AllocateCharArray
+NT_AllocateDoubleArray
+NT_AllocateFloatArray
+NT_AllocateIntegerArray
+NT_AllocateStringArray
+NT_CreateInstance
+NT_CreateListenerPoller
+NT_DeleteTopicProperty
+NT_DestroyInstance
+NT_DestroyListenerPoller
+NT_DisposeConnectionInfoArray
+NT_DisposeEvent
+NT_DisposeEventArray
+NT_DisposeString
+NT_DisposeTimestampedBoolean
+NT_DisposeTimestampedBooleanArray
+NT_DisposeTimestampedDouble
+NT_DisposeTimestampedDoubleArray
+NT_DisposeTimestampedFloat
+NT_DisposeTimestampedFloatArray
+NT_DisposeTimestampedInteger
+NT_DisposeTimestampedIntegerArray
+NT_DisposeTimestampedRaw
+NT_DisposeTimestampedString
+NT_DisposeTimestampedStringArray
+NT_DisposeTopicInfo
+NT_DisposeTopicInfoArray
+NT_DisposeValue
+NT_DisposeValueArray
+NT_Flush
+NT_FlushLocal
+NT_FreeBooleanArray
+NT_FreeCharArray
+NT_FreeConnectionInfoForTesting
+NT_FreeDoubleArray
+NT_FreeFloatArray
+NT_FreeIntegerArray
+NT_FreeQueueBoolean
+NT_FreeQueueBooleanArray
+NT_FreeQueueDouble
+NT_FreeQueueDoubleArray
+NT_FreeQueueFloat
+NT_FreeQueueFloatArray
+NT_FreeQueueInteger
+NT_FreeQueueIntegerArray
+NT_FreeQueueRaw
+NT_FreeQueueString
+NT_FreeQueueStringArray
+NT_FreeStringArray
+NT_FreeTopicInfoForTesting
+NT_GetAtomicBoolean
+NT_GetAtomicBooleanArray
+NT_GetAtomicDouble
+NT_GetAtomicDoubleArray
+NT_GetAtomicFloat
+NT_GetAtomicFloatArray
+NT_GetAtomicInteger
+NT_GetAtomicIntegerArray
+NT_GetAtomicRaw
+NT_GetAtomicString
+NT_GetAtomicStringArray
+NT_GetBoolean
+NT_GetBooleanArray
+NT_GetConnectionInfoForTesting
+NT_GetConnections
+NT_GetDefaultInstance
+NT_GetDouble
+NT_GetDoubleArray
+NT_GetEntry
+NT_GetEntryEx
+NT_GetEntryFlags
+NT_GetEntryLastChange
+NT_GetEntryName
+NT_GetEntryType
+NT_GetEntryValue
+NT_GetFloat
+NT_GetFloatArray
+NT_GetInstanceFromHandle
+NT_GetInteger
+NT_GetIntegerArray
+NT_GetNetworkMode
+NT_GetRaw
+NT_GetServerTimeOffset
+NT_GetString
+NT_GetStringArray
+NT_GetStringForTesting
+NT_GetTopic
+NT_GetTopicExists
+NT_GetTopicFromHandle
+NT_GetTopicInfo
+NT_GetTopicInfoForTesting
+NT_GetTopicInfos
+NT_GetTopicInfosStr
+NT_GetTopicName
+NT_GetTopicPersistent
+NT_GetTopicProperties
+NT_GetTopicProperty
+NT_GetTopicRetained
+NT_GetTopics
+NT_GetTopicsStr
+NT_GetTopicType
+NT_GetTopicTypeString
+NT_GetValueBoolean
+NT_GetValueBooleanArray
+NT_GetValueBooleanArrayForTesting
+NT_GetValueBooleanForTesting
+NT_GetValueDouble
+NT_GetValueDoubleArray
+NT_GetValueDoubleArrayForTesting
+NT_GetValueDoubleForTesting
+NT_GetValueFloat
+NT_GetValueFloatArray
+NT_GetValueInteger
+NT_GetValueIntegerArray
+NT_GetValueRaw
+NT_GetValueRawForTesting
+NT_GetValueString
+NT_GetValueStringArray
+NT_GetValueStringArrayForTesting
+NT_GetValueStringForTesting
+NT_GetValueType
+NT_InitString
+NT_InitValue
+NT_IsConnected
+NT_Meta_DecodeClientPublishers
+NT_Meta_DecodeClientSubscribers
+NT_Meta_DecodeClients
+NT_Meta_DecodeTopicPublishers
+NT_Meta_DecodeTopicSubscribers
+NT_Meta_FreeClientPublishers
+NT_Meta_FreeClientSubscribers
+NT_Meta_FreeClients
+NT_Meta_FreeTopicPublishers
+NT_Meta_FreeTopicSubscribers
+NT_Now
+NT_Publish
+NT_PublishEx
+NT_ReadListenerQueue
+NT_ReadQueueBoolean
+NT_ReadQueueBooleanArray
+NT_ReadQueueDouble
+NT_ReadQueueDoubleArray
+NT_ReadQueueFloat
+NT_ReadQueueFloatArray
+NT_ReadQueueInteger
+NT_ReadQueueIntegerArray
+NT_ReadQueueRaw
+NT_ReadQueueString
+NT_ReadQueueStringArray
+NT_ReadQueueValue
+NT_ReadQueueValuesBoolean
+NT_ReadQueueValuesDouble
+NT_ReadQueueValuesFloat
+NT_ReadQueueValuesInteger
+NT_Release
+NT_ReleaseEntry
+NT_RemoveListener
+NT_SetBoolean
+NT_SetBooleanArray
+NT_SetDefaultBoolean
+NT_SetDefaultBooleanArray
+NT_SetDefaultDouble
+NT_SetDefaultDoubleArray
+NT_SetDefaultEntryValue
+NT_SetDefaultFloat
+NT_SetDefaultFloatArray
+NT_SetDefaultInteger
+NT_SetDefaultIntegerArray
+NT_SetDefaultRaw
+NT_SetDefaultString
+NT_SetDefaultStringArray
+NT_SetDouble
+NT_SetDoubleArray
+NT_SetEntryFlags
+NT_SetEntryValue
+NT_SetFloat
+NT_SetFloatArray
+NT_SetInteger
+NT_SetIntegerArray
+NT_SetNow
+NT_SetRaw
+NT_SetServer
+NT_SetServerMulti
+NT_SetServerTeam
+NT_SetString
+NT_SetStringArray
+NT_SetTopicPersistent
+NT_SetTopicProperties
+NT_SetTopicProperty
+NT_SetTopicRetained
+NT_StartClient3
+NT_StartClient4
+NT_StartDSClient
+NT_StartLocal
+NT_StartServer
+NT_StopClient
+NT_StopDSClient
+NT_StopLocal
+NT_StopServer
+NT_Subscribe
+NT_Unpublish
+NT_Unsubscribe
+NT_WaitForListenerQueue
+WPI_CreateEvent
+WPI_CreateSemaphore
+WPI_CreateSignalObject
+WPI_DestroyEvent
+WPI_DestroySemaphore
+WPI_DestroySignalObject
+WPI_GetSystemTime
+WPI_Now
+WPI_NowDefault
+WPI_ReleaseSemaphore
+WPI_ResetEvent
+WPI_ResetSignalObject
+WPI_SetEvent
+WPI_SetNowImpl
+WPI_SetSignalObject
+WPI_WaitForObject
+WPI_WaitForObjectTimeout
+WPI_WaitForObjects
+WPI_WaitForObjectsTimeout
diff --git a/third_party/allwpilib/outlineviewer/build.gradle b/third_party/allwpilib/outlineviewer/build.gradle
index 5b4ee6e..bb4a4ca 100644
--- a/third_party/allwpilib/outlineviewer/build.gradle
+++ b/third_party/allwpilib/outlineviewer/build.gradle
@@ -1,6 +1,6 @@
 import org.gradle.internal.os.OperatingSystem
 
-if (!project.hasProperty('onlylinuxathena') && !project.hasProperty('onlylinuxraspbian') && !project.hasProperty('onlylinuxaarch64bionic')) {
+if (!project.hasProperty('onlylinuxathena')) {
 
     description = "NetworkTables Viewer"
 
@@ -24,6 +24,8 @@
     def wpilibVersionFileInput = file("src/main/generate/WPILibVersion.cpp.in")
     def wpilibVersionFileOutput = file("$buildDir/generated/main/cpp/WPILibVersion.cpp")
 
+    apply from: "${rootDir}/shared/imgui.gradle"
+
     task generateCppVersion() {
         description = 'Generates the wpilib version class'
         group = 'WPILib'
@@ -93,22 +95,26 @@
                     }
                 }
                 binaries.all {
-                    if (it.targetPlatform.name == nativeUtils.wpi.platforms.roborio || it.targetPlatform.name == nativeUtils.wpi.platforms.raspbian || it.targetPlatform.name == nativeUtils.wpi.platforms.aarch64bionic) {
+                    if (it.targetPlatform.name == nativeUtils.wpi.platforms.roborio) {
                         it.buildable = false
                         return
                     }
                     lib project: ':glass', library: 'glassnt', linkage: 'static'
                     lib project: ':glass', library: 'glass', linkage: 'static'
-                    lib project: ':ntcore', library: 'ntcore', linkage: 'static'
+                    project(':ntcore').addNtcoreDependency(it, 'static')
+                    lib project: ':wpinet', library: 'wpinet', linkage: 'static'
                     lib project: ':wpiutil', library: 'wpiutil', linkage: 'static'
                     lib project: ':wpigui', library: 'wpigui', linkage: 'static'
-                    nativeUtils.useRequiredLibrary(it, 'imgui_static')
+                    nativeUtils.useRequiredLibrary(it, 'imgui')
                     if (it.targetPlatform.operatingSystem.isWindows()) {
                         it.linker.args << 'Gdi32.lib' << 'Shell32.lib' << 'd3d11.lib' << 'd3dcompiler.lib'
                     } else if (it.targetPlatform.operatingSystem.isMacOsX()) {
                         it.linker.args << '-framework' << 'Metal' << '-framework' << 'MetalKit' << '-framework' << 'Cocoa' << '-framework' << 'IOKit' << '-framework' << 'CoreFoundation' << '-framework' << 'CoreVideo' << '-framework' << 'QuartzCore'
                     } else {
                         it.linker.args << '-lX11'
+                        if (it.targetPlatform.name.startsWith('linuxarm')) {
+                            it.linker.args << '-lGL'
+                        }
                     }
                 }
             }
diff --git a/third_party/allwpilib/outlineviewer/publish.gradle b/third_party/allwpilib/outlineviewer/publish.gradle
index aa35009..9c53ae5 100644
--- a/third_party/allwpilib/outlineviewer/publish.gradle
+++ b/third_party/allwpilib/outlineviewer/publish.gradle
@@ -10,7 +10,7 @@
     tasks {
         // Create the run task.
         $.components.outlineviewer.binaries.each { bin ->
-            if (bin.buildable && bin.name.toLowerCase().contains("debug")) {
+            if (bin.buildable && bin.name.toLowerCase().contains("debug") && nativeUtils.isNativeDesktopPlatform(bin.targetPlatform)) {
                 Task run = project.tasks.create("run", Exec) {
                     commandLine bin.tasks.install.runScriptFile.get().asFile.toString()
                 }
@@ -23,20 +23,22 @@
         $.components.each { component ->
             component.binaries.each { binary ->
                 if (binary in NativeExecutableBinarySpec && binary.component.name.contains("outlineviewer")) {
-                    if (binary.buildable && binary.name.contains("Release")) {
+                    if (binary.buildable && (binary.name.contains('Release') || binary.name.contains('release'))) {
                         // We are now in the binary that we want.
                         // This is the default application path for the ZIP task.
                         def applicationPath = binary.executable.file
                         def icon = file("$project.projectDir/src/main/native/mac/ov.icns")
 
                         // Create the macOS bundle.
-                        def bundleTask = project.tasks.create("bundleOutlineViewerOsxApp", Copy) {
+                        def bundleTask = project.tasks.create("bundleOutlineViewerOsxApp" + binary.targetPlatform.architecture.name, Copy) {
                             description("Creates a macOS application bundle for OutlineViewer")
                             from(file("$project.projectDir/Info.plist"))
-                            into(file("$project.buildDir/outputs/bundles/OutlineViewer.app/Contents"))
+                            into(file("$project.buildDir/outputs/bundles/$binary.targetPlatform.architecture.name/OutlineViewer.app/Contents"))
                             into("MacOS") { with copySpec { from binary.executable.file } }
                             into("Resources") { with copySpec { from icon } }
 
+                            inputs.property "HasDeveloperId", project.hasProperty("developerID")
+
                             doLast {
                                 if (project.hasProperty("developerID")) {
                                     // Get path to binary.
@@ -48,7 +50,7 @@
                                             "codesign --force --strict --deep " +
                                             "--timestamp --options=runtime " +
                                             "--verbose -s ${project.findProperty("developerID")} " +
-                                            "$project.buildDir/outputs/bundles/OutlineViewer.app/"
+                                            "$project.buildDir/outputs/bundles/$binary.targetPlatform.architecture.name/OutlineViewer.app/"
                                         ]
                                         commandLine args
                                     }
@@ -58,12 +60,12 @@
 
                         // Reset the application path if we are creating a bundle.
                         if (binary.targetPlatform.operatingSystem.isMacOsX()) {
-                            applicationPath = file("$project.buildDir/outputs/bundles")
+                            applicationPath = file("$project.buildDir/outputs/bundles/$binary.targetPlatform.architecture.name")
                             project.build.dependsOn bundleTask
                         }
 
                         // Create the ZIP.
-                        def task = project.tasks.create("copyOutlineViewerExecutable", Zip) {
+                        def task = project.tasks.create("copyOutlineViewerExecutable" + binary.targetPlatform.architecture.name, Zip) {
                             description("Copies the OutlineViewer executable to the outputs directory.")
                             destinationDirectory = outputsFolder
 
diff --git a/third_party/allwpilib/outlineviewer/src/main/native/cpp/main.cpp b/third_party/allwpilib/outlineviewer/src/main/native/cpp/main.cpp
index 2c2debc..20f4dcc 100644
--- a/third_party/allwpilib/outlineviewer/src/main/native/cpp/main.cpp
+++ b/third_party/allwpilib/outlineviewer/src/main/native/cpp/main.cpp
@@ -39,58 +39,55 @@
 static glass::MainMenuBar gMainMenu;
 
 static void NtInitialize() {
-  // update window title when connection status changes
   auto inst = nt::GetDefaultInstance();
-  auto poller = nt::CreateConnectionListenerPoller(inst);
-  nt::AddPolledConnectionListener(poller, true);
+  auto poller = nt::CreateListenerPoller(inst);
+  nt::AddPolledListener(
+      poller, inst,
+      NT_EVENT_CONNECTION | NT_EVENT_IMMEDIATE | NT_EVENT_LOGMESSAGE);
   gui::AddEarlyExecute([inst, poller] {
     auto win = gui::GetSystemWindow();
     if (!win) {
       return;
     }
-    bool timedOut;
-    for (auto&& event : nt::PollConnectionListener(poller, 0, &timedOut)) {
-      if ((nt::GetNetworkMode(inst) & NT_NET_MODE_SERVER) != 0) {
-        // for server mode, just print number of clients connected
-        glfwSetWindowTitle(win,
-                           fmt::format("OutlineViewer - {} Clients Connected",
-                                       nt::GetConnections(inst).size())
-                               .c_str());
-      } else if (event.connected) {
-        glfwSetWindowTitle(win, fmt::format("OutlineViewer - Connected ({})",
-                                            event.conn.remote_ip)
-                                    .c_str());
-      } else {
-        glfwSetWindowTitle(win, "OutlineViewer - DISCONNECTED");
+    for (auto&& event : nt::ReadListenerQueue(poller)) {
+      if (auto connInfo = event.GetConnectionInfo()) {
+        // update window title when connection status changes
+        if ((nt::GetNetworkMode(inst) & NT_NET_MODE_SERVER) != 0) {
+          // for server mode, just print number of clients connected
+          glfwSetWindowTitle(win,
+                             fmt::format("OutlineViewer - {} Clients Connected",
+                                         nt::GetConnections(inst).size())
+                                 .c_str());
+        } else if ((event.flags & NT_EVENT_CONNECTED) != 0) {
+          glfwSetWindowTitle(win, fmt::format("OutlineViewer - Connected ({})",
+                                              connInfo->remote_ip)
+                                      .c_str());
+        } else {
+          glfwSetWindowTitle(win, "OutlineViewer - DISCONNECTED");
+        }
+      } else if (auto msg = event.GetLogMessage()) {
+        // handle NetworkTables log messages
+        const char* level = "";
+        if (msg->level >= NT_LOG_CRITICAL) {
+          level = "CRITICAL: ";
+        } else if (msg->level >= NT_LOG_ERROR) {
+          level = "ERROR: ";
+        } else if (msg->level >= NT_LOG_WARNING) {
+          level = "WARNING: ";
+        }
+        gLog.Append(fmt::format("{}{} ({}:{})\n", level, msg->message,
+                                msg->filename, msg->line));
       }
     }
   });
 
-  // handle NetworkTables log messages
-  auto logPoller = nt::CreateLoggerPoller(inst);
-  nt::AddPolledLogger(logPoller, NT_LOG_INFO, 100);
-  gui::AddEarlyExecute([logPoller] {
-    bool timedOut;
-    for (auto&& msg : nt::PollLogger(logPoller, 0, &timedOut)) {
-      const char* level = "";
-      if (msg.level >= NT_LOG_CRITICAL) {
-        level = "CRITICAL: ";
-      } else if (msg.level >= NT_LOG_ERROR) {
-        level = "ERROR: ";
-      } else if (msg.level >= NT_LOG_WARNING) {
-        level = "WARNING: ";
-      }
-      gLog.Append(fmt::format("{}{} ({}:{})\n", level, msg.message,
-                              msg.filename, msg.line));
-    }
-  });
-
   // NetworkTables table window
   gModel = std::make_unique<glass::NetworkTablesModel>();
   gui::AddEarlyExecute([] { gModel->Update(); });
 
   // NetworkTables settings window
   gSettings = std::make_unique<glass::NetworkTablesSettings>(
+      "outlineviewer",
       glass::GetStorageRoot().GetChild("NetworkTables Settings"));
   gui::AddEarlyExecute([] { gSettings->Update(); });
 }
@@ -193,6 +190,8 @@
   }
 
   // display table view
+  glass::DisplayNetworkTablesInfo(gModel.get());
+  ImGui::Separator();
   glass::DisplayNetworkTables(gModel.get(), gFlagsSettings.GetFlags());
 
   ImGui::End();
diff --git a/third_party/allwpilib/roborioteamnumbersetter/.styleguide b/third_party/allwpilib/roborioteamnumbersetter/.styleguide
index 1d44898..65af50d 100644
--- a/third_party/allwpilib/roborioteamnumbersetter/.styleguide
+++ b/third_party/allwpilib/roborioteamnumbersetter/.styleguide
@@ -25,4 +25,5 @@
   ^ntcore
   ^wpi/
   ^wpigui
+  ^wpinet/
 }
diff --git a/third_party/allwpilib/roborioteamnumbersetter/CMakeLists.txt b/third_party/allwpilib/roborioteamnumbersetter/CMakeLists.txt
index 3d81f3e..13a079a 100644
--- a/third_party/allwpilib/roborioteamnumbersetter/CMakeLists.txt
+++ b/third_party/allwpilib/roborioteamnumbersetter/CMakeLists.txt
@@ -19,8 +19,8 @@
 
 add_executable(roborioteamnumbersetter ${rtns_src} ${rtns_resources_src} ${rtns_rc} ${APP_ICON_MACOSX})
 wpilib_link_macos_gui(roborioteamnumbersetter)
-target_link_libraries(roborioteamnumbersetter libglass ${LIBSSH_LIBRARIES})
-target_include_directories(roborioteamnumbersetter PRIVATE ${LIBSSH_INCLUDE_DIRS})
+target_link_libraries(roborioteamnumbersetter libglass wpinet ${LIBSSH_LIBRARIES})
+target_include_directories(roborioteamnumbersetter SYSTEM PRIVATE ${LIBSSH_INCLUDE_DIRS})
 
 if (WIN32)
     set_target_properties(roborioteamnumbersetter PROPERTIES WIN32_EXECUTABLE YES)
diff --git a/third_party/allwpilib/roborioteamnumbersetter/build.gradle b/third_party/allwpilib/roborioteamnumbersetter/build.gradle
index 2b1a229..8a7070e 100644
--- a/third_party/allwpilib/roborioteamnumbersetter/build.gradle
+++ b/third_party/allwpilib/roborioteamnumbersetter/build.gradle
@@ -1,6 +1,6 @@
 import org.gradle.internal.os.OperatingSystem
 
-if (!project.hasProperty('onlylinuxathena') && !project.hasProperty('onlylinuxraspbian') && !project.hasProperty('onlylinuxaarch64bionic')) {
+if (!project.hasProperty('onlylinuxathena')) {
 
     description = "roboRIO Team Number Setter"
 
@@ -24,19 +24,8 @@
     def wpilibVersionFileInput = file("src/main/generate/WPILibVersion.cpp.in")
     def wpilibVersionFileOutput = file("$buildDir/generated/main/cpp/WPILibVersion.cpp")
 
-    nativeUtils {
-        nativeDependencyContainer {
-            libssh(getNativeDependencyTypeClass('WPIStaticMavenDependency')) {
-                groupId = "edu.wpi.first.thirdparty.frc2022"
-                artifactId = "libssh"
-                headerClassifier = "headers"
-                sourceClassifier = "sources"
-                ext = "zip"
-                version = '0.95-1'
-                targetPlatforms.addAll(nativeUtils.wpi.platforms.desktopPlatforms)
-            }
-        }
-    }
+    apply from: "${rootDir}/shared/libssh.gradle"
+    apply from: "${rootDir}/shared/imgui.gradle"
 
     task generateCppVersion() {
         description = 'Generates the wpilib version class'
@@ -107,15 +96,16 @@
                     }
                 }
                 binaries.all {
-                    if (it.targetPlatform.name == nativeUtils.wpi.platforms.roborio || it.targetPlatform.name == nativeUtils.wpi.platforms.raspbian || it.targetPlatform.name == nativeUtils.wpi.platforms.aarch64bionic) {
+                    if (it.targetPlatform.name == nativeUtils.wpi.platforms.roborio) {
                         it.buildable = false
                         return
                     }
                     it.cppCompiler.define("LIBSSH_STATIC")
                     lib project: ':glass', library: 'glass', linkage: 'static'
+                    lib project: ':wpinet', library: 'wpinet', linkage: 'static'
                     lib project: ':wpiutil', library: 'wpiutil', linkage: 'static'
                     lib project: ':wpigui', library: 'wpigui', linkage: 'static'
-                    nativeUtils.useRequiredLibrary(it, 'imgui_static', 'libssh')
+                    nativeUtils.useRequiredLibrary(it, 'imgui', 'libssh')
                     if (it.targetPlatform.operatingSystem.isWindows()) {
                         it.linker.args << 'Gdi32.lib' << 'Shell32.lib' << 'd3d11.lib' << 'd3dcompiler.lib'
                         it.linker.args << 'ws2_32.lib' << 'advapi32.lib' << 'crypt32.lib' << 'user32.lib'
@@ -124,6 +114,9 @@
                         it.linker.args << '-framework' << 'Kerberos'
                     } else {
                         it.linker.args << '-lX11'
+                        if (it.targetPlatform.name.startsWith('linuxarm')) {
+                            it.linker.args << '-lGL'
+                        }
                     }
                 }
             }
diff --git a/third_party/allwpilib/roborioteamnumbersetter/publish.gradle b/third_party/allwpilib/roborioteamnumbersetter/publish.gradle
index 3e8e6c3..da6a0f6 100644
--- a/third_party/allwpilib/roborioteamnumbersetter/publish.gradle
+++ b/third_party/allwpilib/roborioteamnumbersetter/publish.gradle
@@ -10,7 +10,7 @@
     tasks {
         // Create the run task.
         $.components.roborioteamnumbersetter.binaries.each { bin ->
-            if (bin.buildable && bin.name.toLowerCase().contains("debug")) {
+            if (bin.buildable && bin.name.toLowerCase().contains("debug") && nativeUtils.isNativeDesktopPlatform(bin.targetPlatform)) {
                 Task run = project.tasks.create("run", Exec) {
                     commandLine bin.tasks.install.runScriptFile.get().asFile.toString()
                 }
@@ -23,20 +23,22 @@
         $.components.each { component ->
             component.binaries.each { binary ->
                 if (binary in NativeExecutableBinarySpec && binary.component.name.contains("roborioteamnumbersetter")) {
-                    if (binary.buildable && binary.name.contains("Release")) {
+                    if (binary.buildable && (binary.name.contains('Release') || binary.name.contains('release'))) {
                         // We are now in the binary that we want.
                         // This is the default application path for the ZIP task.
                         def applicationPath = binary.executable.file
                         def icon = file("$project.projectDir/src/main/native/mac/rtns.icns")
 
                         // Create the macOS bundle.
-                        def bundleTask = project.tasks.create("bundleroboRIOTeamNumberSetterOsxApp", Copy) {
+                        def bundleTask = project.tasks.create("bundleroboRIOTeamNumberSetterOsxApp" + binary.targetPlatform.architecture.name, Copy) {
                             description("Creates a macOS application bundle for roboRIO Team Number Setter")
                             from(file("$project.projectDir/Info.plist"))
-                            into(file("$project.buildDir/outputs/bundles/roboRIOTeamNumberSetter.app/Contents"))
+                            into(file("$project.buildDir/outputs/bundles/$binary.targetPlatform.architecture.name/roboRIOTeamNumberSetter.app/Contents"))
                             into("MacOS") { with copySpec { from binary.executable.file } }
                             into("Resources") { with copySpec { from icon } }
 
+                            inputs.property "HasDeveloperId", project.hasProperty("developerID")
+
                             doLast {
                                 if (project.hasProperty("developerID")) {
                                     // Get path to binary.
@@ -48,7 +50,7 @@
                                             "codesign --force --strict --deep " +
                                             "--timestamp --options=runtime " +
                                             "--verbose -s ${project.findProperty("developerID")} " +
-                                            "$project.buildDir/outputs/bundles/roboRIOTeamNumberSetter.app/"
+                                            "$project.buildDir/outputs/bundles/$binary.targetPlatform.architecture.name/roboRIOTeamNumberSetter.app/"
                                         ]
                                         commandLine args
                                     }
@@ -58,12 +60,12 @@
 
                         // Reset the application path if we are creating a bundle.
                         if (binary.targetPlatform.operatingSystem.isMacOsX()) {
-                            applicationPath = file("$project.buildDir/outputs/bundles")
+                            applicationPath = file("$project.buildDir/outputs/bundles/$binary.targetPlatform.architecture.name")
                             project.build.dependsOn bundleTask
                         }
 
                         // Create the ZIP.
-                        def task = project.tasks.create("copyroboRIOTeamNumberSetterExecutable", Zip) {
+                        def task = project.tasks.create("copyroboRIOTeamNumberSetterExecutable" + binary.targetPlatform.architecture.name, Zip) {
                             description("Copies the roboRIOTeamNumberSetter executable to the outputs directory.")
                             destinationDirectory = outputsFolder
 
diff --git a/third_party/allwpilib/roborioteamnumbersetter/src/main/native/cpp/App.cpp b/third_party/allwpilib/roborioteamnumbersetter/src/main/native/cpp/App.cpp
index f803e22..e6421d5 100644
--- a/third_party/allwpilib/roborioteamnumbersetter/src/main/native/cpp/App.cpp
+++ b/third_party/allwpilib/roborioteamnumbersetter/src/main/native/cpp/App.cpp
@@ -4,6 +4,7 @@
 
 #include <memory>
 #include <string_view>
+#include <unordered_map>
 
 #ifndef _WIN32
 #include <arpa/inet.h>
@@ -19,13 +20,11 @@
 #include <imgui.h>
 #include <libssh/libssh.h>
 #include <wpi/Logger.h>
+#include <wpi/SmallString.h>
 #include <wpi/fs.h>
+#include <wpinet/MulticastServiceResolver.h>
 #include <wpigui.h>
-#include <unordered_map>
-#include <mutex>
-#include "wpi/SmallString.h"
 #include "DeploySession.h"
-#include "wpi/MulticastServiceResolver.h"
 
 namespace gui = wpi::gui;
 
diff --git a/third_party/allwpilib/roborioteamnumbersetter/src/main/native/cpp/DeploySession.cpp b/third_party/allwpilib/roborioteamnumbersetter/src/main/native/cpp/DeploySession.cpp
index 81c69c4..380cfe0 100644
--- a/third_party/allwpilib/roborioteamnumbersetter/src/main/native/cpp/DeploySession.cpp
+++ b/third_party/allwpilib/roborioteamnumbersetter/src/main/native/cpp/DeploySession.cpp
@@ -12,10 +12,10 @@
 #include <fmt/core.h>
 #include <wpi/SmallString.h>
 #include <wpi/StringExtras.h>
-#include <wpi/uv/Error.h>
-#include <wpi/uv/GetAddrInfo.h>
-#include <wpi/uv/Work.h>
-#include <wpi/uv/util.h>
+#include <wpinet/uv/Error.h>
+#include <wpinet/uv/GetAddrInfo.h>
+#include <wpinet/uv/Work.h>
+#include <wpinet/uv/util.h>
 
 #include "SshSession.h"
 
@@ -79,7 +79,7 @@
           session.Open();
           DEBUG("SSH connection to {} was successful.", ip);
 
-          SUCCESS("{}", "roboRIO Connected!");
+          SUCCESS("roboRIO Connected!");
 
           try {
             session.Execute(fmt::format(
@@ -123,7 +123,7 @@
           session.Open();
           DEBUG("SSH connection to {} was successful.", ip);
 
-          SUCCESS("{}", "roboRIO Connected!");
+          SUCCESS("roboRIO Connected!");
 
           try {
             session.Execute(fmt::format("sync ; shutdown -r now"));
@@ -162,7 +162,7 @@
           session.Open();
           DEBUG("SSH connection to {} was successful.", ip);
 
-          SUCCESS("{}", "roboRIO Connected!");
+          SUCCESS("roboRIO Connected!");
 
           try {
             session.Execute(fmt::format(
diff --git a/third_party/allwpilib/roborioteamnumbersetter/src/main/native/cpp/SshSession.cpp b/third_party/allwpilib/roborioteamnumbersetter/src/main/native/cpp/SshSession.cpp
index 2c7661d..6424ce0 100644
--- a/third_party/allwpilib/roborioteamnumbersetter/src/main/native/cpp/SshSession.cpp
+++ b/third_party/allwpilib/roborioteamnumbersetter/src/main/native/cpp/SshSession.cpp
@@ -18,7 +18,7 @@
 
 using namespace sysid;
 
-#define INFO(fmt, ...) WPI_INFO(m_logger, fmt, __VA_ARGS__)
+#define INFO(fmt, ...) WPI_INFO(m_logger, fmt __VA_OPT__(, ) __VA_ARGS__)
 
 SshSession::SshSession(std::string_view host, int port, std::string_view user,
                        std::string_view pass, wpi::Logger& logger)
diff --git a/third_party/allwpilib/settings.gradle b/third_party/allwpilib/settings.gradle
index 2d62f10..818046b 100644
--- a/third_party/allwpilib/settings.gradle
+++ b/third_party/allwpilib/settings.gradle
@@ -1,6 +1,10 @@
 pluginManagement {
     repositories {
         mavenLocal()
+        maven {
+            url = 'https://frcmaven.wpi.edu/artifactory/ex-gradle'
+        }
+        mavenCentral()
         gradlePluginPortal()
     }
 }
@@ -17,6 +21,7 @@
 props.setProperty("org.gradle.internal.native.headers.unresolved.dependencies.ignore", "true");
 
 include 'wpiutil'
+include 'wpinet'
 include 'ntcore'
 include 'hal'
 include 'cscore'
@@ -33,9 +38,7 @@
 include 'glass'
 include 'outlineviewer'
 include 'roborioteamnumbersetter'
-include 'simulation:gz_msgs'
-include 'simulation:frc_gazebo_plugins'
-include 'simulation:halsim_gazebo'
+include 'datalogtool'
 include 'simulation:halsim_ds_socket'
 include 'simulation:halsim_gui'
 include 'simulation:halsim_ws_core'
@@ -43,8 +46,34 @@
 include 'simulation:halsim_ws_server'
 include 'cameraserver'
 include 'cameraserver:multiCameraServer'
-include 'wpilibOldCommands'
 include 'wpilibNewCommands'
 include 'myRobot'
 include 'docs'
 include 'msvcruntime'
+include 'ntcoreffi'
+include 'apriltag'
+
+buildCache {
+    def cred = {
+        if (System.env[it] != null) {
+            return System.env[it]
+        } else {
+            return System.getProperty(it)
+        }
+    }
+    local {
+        enabled = !System.getenv().containsKey("CI")
+    }
+    remote(HttpBuildCache) {
+        url = "https://frcmaven.wpi.edu/artifactory/wpilib-generic-gradle-cache/"
+        String user = cred('ARTIFACTORY_PUBLISH_USERNAME')
+        String pass = cred('ARTIFACTORY_PUBLISH_PASSWORD')
+        if (user && pass) {
+            push = true
+            credentials {
+                username = user
+                password = pass
+            }
+        }
+    }
+}
diff --git a/third_party/allwpilib/shared/apriltaglib.gradle b/third_party/allwpilib/shared/apriltaglib.gradle
new file mode 100644
index 0000000..1e508de
--- /dev/null
+++ b/third_party/allwpilib/shared/apriltaglib.gradle
@@ -0,0 +1,13 @@
+nativeUtils {
+    nativeDependencyContainer {
+        apriltaglib(getNativeDependencyTypeClass('WPIStaticMavenDependency')) {
+            groupId = "edu.wpi.first.thirdparty.frc2023"
+            artifactId = "apriltaglib"
+            headerClassifier = "headers"
+            sourceClassifier = "sources"
+            ext = "zip"
+            version = '3.2.0-3'
+            targetPlatforms.addAll(nativeUtils.wpi.platforms.allPlatforms)
+        }
+    }
+}
diff --git a/third_party/allwpilib/shared/config.gradle b/third_party/allwpilib/shared/config.gradle
index 220ec06..8036cca 100644
--- a/third_party/allwpilib/shared/config.gradle
+++ b/third_party/allwpilib/shared/config.gradle
@@ -2,19 +2,20 @@
 
 nativeUtils.skipInstallPdb = project.hasProperty('buildServer')
 
+if (project.hasProperty('ciDebugOnly')) {
+    toolchainsPlugin.registerReleaseBuildType = false
+}
+
 nativeUtils.addWpiNativeUtils()
-nativeUtils.withRoboRIO()
-nativeUtils.withRaspbian()
-nativeUtils.withBionic()
+nativeUtils.withCrossRoboRIO()
+nativeUtils.withCrossLinuxArm32()
+nativeUtils.withCrossLinuxArm64()
 nativeUtils {
     wpi {
         configureDependencies {
-            wpiVersion = "-1"
-            niLibVersion = "2022.4.0"
-            opencvVersion = "4.5.2-1"
-            googleTestVersion = "1.9.0-5-437e100-1"
-            imguiVersion = "1.86-1"
-            wpimathVersion = "-1"
+            niLibVersion = "2023.3.0"
+            opencvVersion = "4.6.0-3"
+            googleTestVersion = "1.12.1-1"
         }
     }
 }
@@ -29,16 +30,29 @@
 nativeUtils.setSinglePrintPerPlatform()
 nativeUtils.enableSourceLink()
 
+nativeUtils.wpi.addMacMinimumVersionArg()
+
 nativeUtils.platformConfigs.each {
-    if (it.name.contains('windows')) {
-        return
-    }
-    it.linker.args << '-Wl,-rpath,\'$ORIGIN\''
-    if (it.name == 'osxx86-64') {
+    if (it.name.contains('osx')) {
+        it.linker.args << '-Wl,-rpath,\'@loader_path\''
         it.linker.args << "-headerpad_max_install_names"
+    } else if (it.name.contains('linux')) {
+        it.linker.args << '-Wl,-rpath,\'$ORIGIN\''
     }
 }
 
+// NativeUtils adds the following OpenCV warning suppression for Linux, but not
+// for macOS
+// https://github.com/opencv/opencv/issues/20269
+nativeUtils.platformConfigs.osxuniversal.cppCompiler.args.add("-Wno-deprecated-anon-enum-enum-conversion")
+
+// NativeUtils uses the wrong compiler arguments for roboRIO targets, but it's
+// too late to fix NativeUtils for the 2023 season. This temporarily overwrites
+// the flags.
+nativeUtils.platformConfigs.named(nativeUtils.wpi.platforms.roborio).configure {
+    cppCompiler.args.remove('-Wno-error=deprecated-declarations')
+}
+
 nativeUtils.platformConfigs.linuxathena.linker.args.add("-Wl,--fatal-warnings")
 
 model {
diff --git a/third_party/allwpilib/shared/imgui.gradle b/third_party/allwpilib/shared/imgui.gradle
new file mode 100644
index 0000000..04d4265
--- /dev/null
+++ b/third_party/allwpilib/shared/imgui.gradle
@@ -0,0 +1,13 @@
+nativeUtils {
+    nativeDependencyContainer {
+        imgui(getNativeDependencyTypeClass('WPIStaticMavenDependency')) {
+            groupId = "edu.wpi.first.thirdparty.frc2023"
+            artifactId = "imgui"
+            headerClassifier = "headers"
+            sourceClassifier = "sources"
+            ext = "zip"
+            version = '1.89.1-1'
+            targetPlatforms.addAll(nativeUtils.wpi.platforms.allPlatforms)
+        }
+    }
+}
diff --git a/third_party/allwpilib/shared/java/javacommon.gradle b/third_party/allwpilib/shared/java/javacommon.gradle
index a40938c..4c57f1f 100644
--- a/third_party/allwpilib/shared/java/javacommon.gradle
+++ b/third_party/allwpilib/shared/java/javacommon.gradle
@@ -81,12 +81,14 @@
     finalizedBy jacocoTestReport
 }
 
-if (project.hasProperty('onlylinuxathena') || project.hasProperty('onlylinuxraspbian') || project.hasProperty('onlylinuxaarch64bionic')) {
+if (project.hasProperty('onlylinuxathena') || project.hasProperty('onlylinuxarm32') || project.hasProperty('onlylinuxarm64')) {
     test.enabled = false
 }
 
 repositories {
-    mavenCentral()
+    maven {
+        url = 'https://frcmaven.wpi.edu/artifactory/ex-mvn'
+    }
     //maven.url "https://oss.sonatype.org/content/repositories/snapshots/"
 }
 
@@ -99,7 +101,13 @@
         '--release',
         '11',
         '-encoding',
-        'UTF8'
+        'UTF8',
+        "-Werror",
+        "-Xlint:all",
+        // ignore AutoCloseable warnings
+        "-Xlint:-try",
+        // ignore missing serialVersionUID warnings
+        "-Xlint:-serial",
     ]
 }
 
@@ -120,7 +128,7 @@
 build.dependsOn devClasses
 
 jacoco {
-    toolVersion = "0.8.7"
+    toolVersion = "0.8.8"
 }
 
 jacocoTestReport {
diff --git a/third_party/allwpilib/shared/java/javastyle.gradle b/third_party/allwpilib/shared/java/javastyle.gradle
index ffe344c..6259c2a 100644
--- a/third_party/allwpilib/shared/java/javastyle.gradle
+++ b/third_party/allwpilib/shared/java/javastyle.gradle
@@ -2,7 +2,7 @@
     apply plugin: 'checkstyle'
 
     checkstyle {
-        toolVersion = "9.2"
+        toolVersion = "10.1"
         configDirectory = file("${project.rootDir}/styleguide")
         config = resources.text.fromFile(new File(configDirectory.get().getAsFile(), "checkstyle.xml"))
     }
@@ -10,7 +10,7 @@
     apply plugin: 'pmd'
 
     pmd {
-        toolVersion = '6.41.0'
+        toolVersion = '6.44.0'
         consoleOutput = true
         reportsDir = file("$project.buildDir/reports/pmd")
         ruleSetFiles = files(new File(rootDir, "styleguide/pmd-ruleset.xml"))
diff --git a/third_party/allwpilib/shared/jni/setupBuild.gradle b/third_party/allwpilib/shared/jni/setupBuild.gradle
index f897806..4d8894f 100644
--- a/third_party/allwpilib/shared/jni/setupBuild.gradle
+++ b/third_party/allwpilib/shared/jni/setupBuild.gradle
@@ -42,6 +42,9 @@
                 cpp {
                     source {
                         srcDirs 'src/main/native/cpp'
+                        if (project.hasProperty('generatedSources')) {
+                            srcDir generatedSources
+                        }
                         include '**/*.cpp'
                         exclude '**/jni/**/*.cpp'
                     }
@@ -101,15 +104,22 @@
                 baseName = nativeName + 'jni'
             }
 
+            if (project.hasProperty('skipJniSymbols')) {
+                checkSkipSymbols = skipJniSymbols
+            }
+
             enableCheckTask !project.hasProperty('skipJniCheck')
             javaCompileTasks << compileJava
             jniCrossCompileOptions << JniCrossCompileOptions(nativeUtils.wpi.platforms.roborio)
-            jniCrossCompileOptions << JniCrossCompileOptions(nativeUtils.wpi.platforms.raspbian)
-            jniCrossCompileOptions << JniCrossCompileOptions(nativeUtils.wpi.platforms.aarch64bionic)
+            jniCrossCompileOptions << JniCrossCompileOptions(nativeUtils.wpi.platforms.linuxarm32)
+            jniCrossCompileOptions << JniCrossCompileOptions(nativeUtils.wpi.platforms.linuxarm64)
             sources {
                 cpp {
                     source {
                         srcDirs 'src/main/native/cpp'
+                        if (project.hasProperty('generatedSources')) {
+                            srcDir generatedSources
+                        }
                         include '**/jni/**/*.cpp'
                     }
                     exportedHeaders {
@@ -142,15 +152,22 @@
                 baseName = nativeName + 'jni'
             }
 
+            if (project.hasProperty('skipJniSymbols')) {
+                checkSkipSymbols = skipJniSymbols
+            }
+
             enableCheckTask !project.hasProperty('skipJniCheck')
             javaCompileTasks << compileJava
             jniCrossCompileOptions << JniCrossCompileOptions(nativeUtils.wpi.platforms.roborio)
-            jniCrossCompileOptions << JniCrossCompileOptions(nativeUtils.wpi.platforms.raspbian)
-            jniCrossCompileOptions << JniCrossCompileOptions(nativeUtils.wpi.platforms.aarch64bionic)
+            jniCrossCompileOptions << JniCrossCompileOptions(nativeUtils.wpi.platforms.linuxarm32)
+            jniCrossCompileOptions << JniCrossCompileOptions(nativeUtils.wpi.platforms.linuxarm64)
             sources {
                 cpp {
                     source {
                         srcDirs 'src/main/native/cpp'
+                        if (project.hasProperty('generatedSources')) {
+                            srcDir generatedSources
+                        }
                         include '**/jni/**/*.cpp'
                     }
                     exportedHeaders {
@@ -201,8 +218,8 @@
                     lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
                     lib project: ':wpiutil', library: 'wpiutilJNIShared', linkage: 'shared'
                 }
-                if (nativeName == 'hal' && it.targetPlatform.name == nativeUtils.wpi.platforms.roborio) {
-                    nativeUtils.useRequiredLibrary(it, 'ni_link_libraries', 'ni_runtime_libraries')
+                if (project.hasProperty('exeSplitSetup')) {
+                    exeSplitSetup(it)
                 }
             }
         }
@@ -236,9 +253,9 @@
             lib library: nativeName, linkage: 'shared'
             if (!project.hasProperty('noWpiutil')) {
                 lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
-                if (nativeName == 'hal' && it.targetPlatform.name == nativeUtils.wpi.platforms.roborio) {
-                    nativeUtils.useRequiredLibrary(it, 'ni_link_libraries', 'ni_runtime_libraries')
-                }
+            }
+            if (project.hasProperty('exeSplitSetup')) {
+                exeSplitSetup(it)
             }
         }
     }
diff --git a/third_party/allwpilib/shared/libssh.gradle b/third_party/allwpilib/shared/libssh.gradle
new file mode 100644
index 0000000..743dd57
--- /dev/null
+++ b/third_party/allwpilib/shared/libssh.gradle
@@ -0,0 +1,13 @@
+nativeUtils {
+    nativeDependencyContainer {
+        libssh(getNativeDependencyTypeClass('WPIStaticMavenDependency')) {
+            groupId = "edu.wpi.first.thirdparty.frc2023"
+            artifactId = "libssh"
+            headerClassifier = "headers"
+            sourceClassifier = "sources"
+            ext = "zip"
+            version = '0.95-6'
+            targetPlatforms.addAll(nativeUtils.wpi.platforms.allPlatforms)
+        }
+    }
+}
diff --git a/third_party/allwpilib/shared/opencv.gradle b/third_party/allwpilib/shared/opencv.gradle
index ef7715d..40d3c34 100644
--- a/third_party/allwpilib/shared/opencv.gradle
+++ b/third_party/allwpilib/shared/opencv.gradle
@@ -1,4 +1,4 @@
-def opencvVersion = '4.5.2-1'
+def opencvVersion = '4.6.0-2'
 
 if (project.hasProperty('useCpp') && project.useCpp) {
     model {
@@ -22,12 +22,12 @@
 
 if (project.hasProperty('useJava') && project.useJava) {
     dependencies {
-        implementation "edu.wpi.first.thirdparty.frc2022.opencv:opencv-java:${opencvVersion}"
+        implementation "edu.wpi.first.thirdparty.frc2023.opencv:opencv-java:${opencvVersion}"
         if (!project.hasProperty('skipDev') || !project.skipDev) {
-            devImplementation "edu.wpi.first.thirdparty.frc2022.opencv:opencv-java:${opencvVersion}"
+            devImplementation "edu.wpi.first.thirdparty.frc2023.opencv:opencv-java:${opencvVersion}"
         }
         if (project.hasProperty('useDocumentation') && project.useDocumentation) {
-            javaSource "edu.wpi.first.thirdparty.frc2022.opencv:opencv-java:${opencvVersion}:sources"
+            javaSource "edu.wpi.first.thirdparty.frc2023.opencv:opencv-java:${opencvVersion}:sources"
         }
     }
 }
diff --git a/third_party/allwpilib/shared/plugins/setupBuild.gradle b/third_party/allwpilib/shared/plugins/setupBuild.gradle
index 2097ace..91cbf11 100644
--- a/third_party/allwpilib/shared/plugins/setupBuild.gradle
+++ b/third_party/allwpilib/shared/plugins/setupBuild.gradle
@@ -34,6 +34,9 @@
                     if (project.hasProperty('includeNtCore')) {
                         lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
                     }
+                    if (project.hasProperty('includeWpinet')) {
+                        lib project: ':wpinet', library: 'wpinet', linkage: 'shared'
+                    }
                     if (project.hasProperty('includeWpiutil')) {
                         lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
                     }
@@ -54,12 +57,15 @@
                     }
                 }
                 binaries.all {
-                    if (!project.hasProperty('onlylinuxathena') && !project.hasProperty('onlylinuxraspbian')  && !project.hasProperty('onlylinuxaarch64bionic')) {
+                    if (!project.hasProperty('onlylinuxathena')) {
                         project(':hal').addHalDependency(it, 'shared')
                         lib library: pluginName
                         if (project.hasProperty('includeNtCore')) {
                             lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
                         }
+                        if (project.hasProperty('includeWpinet')) {
+                            lib project: ':wpinet', library: 'wpinet', linkage: 'shared'
+                        }
                         lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
                         if (it.targetPlatform.name == nativeUtils.wpi.platforms.roborio) {
                             nativeUtils.useRequiredLibrary(it, 'ni_link_libraries', 'ni_runtime_libraries')
@@ -78,7 +84,7 @@
 model {
     tasks {
         def c = $.components
-        if (!project.hasProperty('onlylinuxathena') && !project.hasProperty('onlylinuxraspbian') && !project.hasProperty('onlylinuxaarch64bionic')) {
+        if (!project.hasProperty('onlylinuxathena')) {
             project.tasks.create('runCpp', Exec) {
                 group = 'WPILib'
                 description = "Run the ${pluginName}Dev executable"
diff --git a/third_party/allwpilib/simulation/CMakeLists.txt b/third_party/allwpilib/simulation/CMakeLists.txt
index 912d7b0..7a54c48 100644
--- a/third_party/allwpilib/simulation/CMakeLists.txt
+++ b/third_party/allwpilib/simulation/CMakeLists.txt
@@ -1,9 +1,6 @@
 if (WITH_GUI)
     add_subdirectory(halsim_gui)
 endif()
-#add_subdirectory(gz_msgs)
-#add_subdirectory(frc_gazebo_plugins)
-#add_subdirectory(halsim_gazebo)
 add_subdirectory(halsim_ds_socket)
 add_subdirectory(halsim_ws_core)
 add_subdirectory(halsim_ws_client)
diff --git a/third_party/allwpilib/simulation/frc_gazebo_plugins/README.md b/third_party/allwpilib/simulation/frc_gazebo_plugins/README.md
deleted file mode 100644
index b89bbc5..0000000
--- a/third_party/allwpilib/simulation/frc_gazebo_plugins/README.md
+++ /dev/null
@@ -1,45 +0,0 @@
-Gazebo plugins for FRC
-======================
-
-These plugins enable the use of the Gazebo physics simulator to model robots,
-and then use WPILIB programming libraries to control those simulated robots.
-
-At the present time, this only builds on Linux, and has a fairly complex
-installation process.
-
-You must have the gazebo development packages available on Linux.
-The gradle build system will automatically skip building this directory
-if those requirements are not met.
-
-This command:
-
-    `./gradlew build -PforceGazebo`
-
-will force it to attempt to build.
-
-TODO:  The meshes for the models are large, and are not hosted in
-the main allwpilib repository.  An alternate method of hosting
-and using is being built at the time of this commit. You must
-manually locate and copy the the models and world from that
-either into /usr/share/frcgazebo or into build/share/frcgazebo
-in order to use this facility.
-
-Once you have built it, then a command like this:
-
-  `simulation/frc_gazebo_plugins/build/bin/frcgazebo PacGoat2014.world`
-
-should run the Gazebo simulation using our plugins against the
-2014 model, with the PacGoat robot on the field.
-
-The halsim_gazebo simulation library will provide a method for
-running robot code to control a simulated robot.
-
-
-TODO:  Package the plugins more nicely, and then put instructions here.
-
-TODO:  Build and package the plugins for Windows.  The key there is to get gazebo
-working on Windows.  This link was a useful trove of information on Windows/Gazebo
-issues as of September, 2017:
-  https://bitbucket.org/osrf/gazebo/issues/2129/visual-studio-2015-compatibility
-
-Note that the sense remains that this will be difficult at best.
diff --git a/third_party/allwpilib/simulation/frc_gazebo_plugins/build.gradle b/third_party/allwpilib/simulation/frc_gazebo_plugins/build.gradle
deleted file mode 100644
index f42b70b..0000000
--- a/third_party/allwpilib/simulation/frc_gazebo_plugins/build.gradle
+++ /dev/null
@@ -1,113 +0,0 @@
-description = "A set of C++ plugins to interface the FRC Simulator with Gazebo."
-
-apply plugin: 'edu.wpi.first.NativeUtils'
-apply plugin: 'cpp'
-apply plugin: "google-test"
-
-ext.skiplinuxathena = true
-ext.skiplinuxraspbian = true
-
-apply from: "${rootDir}/shared/config.gradle"
-
-/* If gz_msgs or gazebo is not available, do not attempt a build */
-def gazebo_version = ""
-def gazebo_cppflags = ""
-def gazebo_linker_args = ""
-
-try {
-    gazebo_version = "pkg-config --modversion gazebo".execute().text.trim()
-    println "Gazebo version is [${gazebo_version}]"
-    gazebo_cppflags = "pkg-config --cflags gazebo".execute().text.split()
-    gazebo_linker_args = "pkg-config --libs gazebo protobuf".execute().text.split()
-} catch(Exception ex) { }
-
-if (project.hasProperty("forceGazebo")) {
-    if (!gazebo_version?.trim()) {
-        println "Gazebo development files are not available. (pkg-config --modversion gazebo failed)"
-        println "forceGazebo set. Forcing build - failure likely."
-    }
-} else {
-    ext.skip_frc_plugins = true
-    println "Skipping FRC Plugins."
-}
-
-evaluationDependsOn(":simulation:gz_msgs")
-def gz_msgs_project = project(":simulation:gz_msgs")
-
-tasks.whenTaskAdded { task ->
-    task.onlyIf { !gz_msgs_project.hasProperty('skip_gz_msgs') && !project.hasProperty('skip_frc_plugins') }
-}
-
-model {
-    components {
-        clock(NativeLibrarySpec)
-        dc_motor(NativeLibrarySpec)
-        encoder(NativeLibrarySpec)
-        gyro(NativeLibrarySpec)
-        limit_switch(NativeLibrarySpec)
-        potentiometer(NativeLibrarySpec)
-        pneumatic_piston(NativeLibrarySpec)
-        rangefinder(NativeLibrarySpec)
-        servo(NativeLibrarySpec)
-        drive_motor(NativeLibrarySpec)
-        all { component ->
-            component.targetBuildTypes 'debug'
-            sources {
-                cpp.lib library:  "${component.name}", linkage: "static"
-            }
-        }
-    }
-
-    /* TODO:  Finish writing the test case */
-
-    /* We pass the name of the .so and a .world file to each test */
-    testSuites {
-        all { test->
-            def library_file
-            testedComponent.binaries.withType(SharedLibraryBinarySpec).each { b->
-                library_file = b.sharedLibraryFile
-            }
-
-            tasks.withType(RunTestExecutable) {
-                args library_file, file("src/${baseName}/world/${baseName}.world")
-            }
-        }
-    }
-
-
-    binaries {
-        all {
-            linker.args gazebo_linker_args
-            cppCompiler.args gazebo_cppflags
-            lib project: ":simulation:gz_msgs", library: "gz_msgs", linkage: "static"
-        }
-
-        /* TODO: build only shared object? Figure out why this doesn't work? */
-        withType(StaticLibraryBinarySpec) {
-            buildable = false
-        }
-
-        withType(GoogleTestTestSuiteBinarySpec) {
-
-            /* We currently only have a test for the clock plugin */
-            /* TODO: learn how to add this back to gmock */
-            //if (it.projectScopedName.contains("clockTest")) {
-            //    buildable = true
-            //    project(':gmock').addGmockToLinker(it)
-            //}
-            //else {
-            buildable = false
-            //}
-        }
-    }
-}
-
-task copyScript(type: Copy, group: "FRC Gazebo", description: "Copy the frcgazebo script to the output directory.") {
-    from "scripts"
-    into "$project.buildDir/bin"
-    fileMode 0755
-}
-
-build.dependsOn copyScript
-
-/* TODO:  Publish this library */
diff --git a/third_party/allwpilib/simulation/frc_gazebo_plugins/frc_gazebo_plugins.doxy b/third_party/allwpilib/simulation/frc_gazebo_plugins/frc_gazebo_plugins.doxy
deleted file mode 100644
index a2ebdd2..0000000
--- a/third_party/allwpilib/simulation/frc_gazebo_plugins/frc_gazebo_plugins.doxy
+++ /dev/null
@@ -1,2303 +0,0 @@
-# Doxyfile 1.8.6
-
-# This file describes the settings to be used by the documentation system
-# doxygen (www.doxygen.org) for a project.
-#
-# All text after a double hash (##) is considered a comment and is placed in
-# front of the TAG it is preceding.
-#
-# All text after a single hash (#) is considered a comment and will be ignored.
-# The format is:
-# TAG = value [value, ...]
-# For lists, items can also be appended using:
-# TAG += value [value, ...]
-# Values that contain spaces should be placed between quotes (\" \").
-
-#---------------------------------------------------------------------------
-# Project related configuration options
-#---------------------------------------------------------------------------
-
-# This tag specifies the encoding used for all characters in the config file
-# that follow. The default is UTF-8 which is also the encoding used for all text
-# before the first occurrence of this tag. Doxygen uses libiconv (or the iconv
-# built into libc) for the transcoding. See http://www.gnu.org/software/libiconv
-# for the list of possible encodings.
-# The default value is: UTF-8.
-
-DOXYFILE_ENCODING      = UTF-8
-
-# The PROJECT_NAME tag is a single word (or a sequence of words surrounded by
-# double-quotes, unless you are using Doxywizard) that should identify the
-# project for which the documentation is generated. This name is used in the
-# title of most generated pages and in a few other places.
-# The default value is: My Project.
-
-PROJECT_NAME           = "FRC Gazebo Plugins"
-
-# The PROJECT_NUMBER tag can be used to enter a project or revision number. This
-# could be handy for archiving the generated documentation or if some version
-# control system is used.
-
-PROJECT_NUMBER         = DEVELOPMENT
-
-# Using the PROJECT_BRIEF tag one can provide an optional one line description
-# for a project that appears at the top of each page and should give viewer a
-# quick idea about the purpose of the project. Keep the description short.
-
-PROJECT_BRIEF          = "Gazebo plugins to enable WPILib to control simulated robots."
-
-# With the PROJECT_LOGO tag one can specify an logo or icon that is included in
-# the documentation. The maximum height of the logo should not exceed 55 pixels
-# and the maximum width should not exceed 200 pixels. Doxygen will copy the logo
-# to the output directory.
-
-PROJECT_LOGO           =
-
-# The OUTPUT_DIRECTORY tag is used to specify the (relative or absolute) path
-# into which the generated documentation will be written. If a relative path is
-# entered, it will be relative to the location where doxygen was started. If
-# left blank the current directory will be used.
-
-OUTPUT_DIRECTORY       = docs
-
-# If the CREATE_SUBDIRS tag is set to YES, then doxygen will create 4096 sub-
-# directories (in 2 levels) under the output directory of each output format and
-# will distribute the generated files over these directories. Enabling this
-# option can be useful when feeding doxygen a huge amount of source files, where
-# putting all generated files in the same directory would otherwise causes
-# performance problems for the file system.
-# The default value is: NO.
-
-CREATE_SUBDIRS         = NO
-
-# The OUTPUT_LANGUAGE tag is used to specify the language in which all
-# documentation generated by doxygen is written. Doxygen will use this
-# information to generate all constant output in the proper language.
-# Possible values are: Afrikaans, Arabic, Armenian, Brazilian, Catalan, Chinese,
-# Chinese-Traditional, Croatian, Czech, Danish, Dutch, English (United States),
-# Esperanto, Farsi (Persian), Finnish, French, German, Greek, Hungarian,
-# Indonesian, Italian, Japanese, Japanese-en (Japanese with English messages),
-# Korean, Korean-en (Korean with English messages), Latvian, Lithuanian,
-# Macedonian, Norwegian, Persian (Farsi), Polish, Portuguese, Romanian, Russian,
-# Serbian, Serbian-Cyrillic, Slovak, Slovene, Spanish, Swedish, Turkish,
-# Ukrainian and Vietnamese.
-# The default value is: English.
-
-OUTPUT_LANGUAGE        = English
-
-# If the BRIEF_MEMBER_DESC tag is set to YES doxygen will include brief member
-# descriptions after the members that are listed in the file and class
-# documentation (similar to Javadoc). Set to NO to disable this.
-# The default value is: YES.
-
-BRIEF_MEMBER_DESC      = YES
-
-# If the REPEAT_BRIEF tag is set to YES doxygen will prepend the brief
-# description of a member or function before the detailed description
-#
-# Note: If both HIDE_UNDOC_MEMBERS and BRIEF_MEMBER_DESC are set to NO, the
-# brief descriptions will be completely suppressed.
-# The default value is: YES.
-
-REPEAT_BRIEF           = YES
-
-# This tag implements a quasi-intelligent brief description abbreviator that is
-# used to form the text in various listings. Each string in this list, if found
-# as the leading text of the brief description, will be stripped from the text
-# and the result, after processing the whole list, is used as the annotated
-# text. Otherwise, the brief description is used as-is. If left blank, the
-# following values are used ($name is automatically replaced with the name of
-# the entity):The $name class, The $name widget, The $name file, is, provides,
-# specifies, contains, represents, a, an and the.
-
-ABBREVIATE_BRIEF       =
-
-# If the ALWAYS_DETAILED_SEC and REPEAT_BRIEF tags are both set to YES then
-# doxygen will generate a detailed section even if there is only a brief
-# description.
-# The default value is: NO.
-
-ALWAYS_DETAILED_SEC    = NO
-
-# If the INLINE_INHERITED_MEMB tag is set to YES, doxygen will show all
-# inherited members of a class in the documentation of that class as if those
-# members were ordinary class members. Constructors, destructors and assignment
-# operators of the base classes will not be shown.
-# The default value is: NO.
-
-INLINE_INHERITED_MEMB  = NO
-
-# If the FULL_PATH_NAMES tag is set to YES doxygen will prepend the full path
-# before files name in the file list and in the header files. If set to NO the
-# shortest path that makes the file name unique will be used
-# The default value is: YES.
-
-FULL_PATH_NAMES        = YES
-
-# The STRIP_FROM_PATH tag can be used to strip a user-defined part of the path.
-# Stripping is only done if one of the specified strings matches the left-hand
-# part of the path. The tag can be used to show relative paths in the file list.
-# If left blank the directory from which doxygen is run is used as the path to
-# strip.
-#
-# Note that you can specify absolute paths here, but also relative paths, which
-# will be relative from the directory where doxygen is started.
-# This tag requires that the tag FULL_PATH_NAMES is set to YES.
-
-STRIP_FROM_PATH        =
-
-# The STRIP_FROM_INC_PATH tag can be used to strip a user-defined part of the
-# path mentioned in the documentation of a class, which tells the reader which
-# header file to include in order to use a class. If left blank only the name of
-# the header file containing the class definition is used. Otherwise one should
-# specify the list of include paths that are normally passed to the compiler
-# using the -I flag.
-
-STRIP_FROM_INC_PATH    =
-
-# If the SHORT_NAMES tag is set to YES, doxygen will generate much shorter (but
-# less readable) file names. This can be useful is your file systems doesn't
-# support long names like on DOS, Mac, or CD-ROM.
-# The default value is: NO.
-
-SHORT_NAMES            = NO
-
-# If the JAVADOC_AUTOBRIEF tag is set to YES then doxygen will interpret the
-# first line (until the first dot) of a Javadoc-style comment as the brief
-# description. If set to NO, the Javadoc-style will behave just like regular Qt-
-# style comments (thus requiring an explicit @brief command for a brief
-# description.)
-# The default value is: NO.
-
-JAVADOC_AUTOBRIEF      = NO
-
-# If the QT_AUTOBRIEF tag is set to YES then doxygen will interpret the first
-# line (until the first dot) of a Qt-style comment as the brief description. If
-# set to NO, the Qt-style will behave just like regular Qt-style comments (thus
-# requiring an explicit \brief command for a brief description.)
-# The default value is: NO.
-
-QT_AUTOBRIEF           = NO
-
-# The MULTILINE_CPP_IS_BRIEF tag can be set to YES to make doxygen treat a
-# multi-line C++ special comment block (i.e. a block of //! or /// comments) as
-# a brief description. This used to be the default behavior. The new default is
-# to treat a multi-line C++ comment block as a detailed description. Set this
-# tag to YES if you prefer the old behavior instead.
-#
-# Note that setting this tag to YES also means that rational rose comments are
-# not recognized any more.
-# The default value is: NO.
-
-MULTILINE_CPP_IS_BRIEF = NO
-
-# If the INHERIT_DOCS tag is set to YES then an undocumented member inherits the
-# documentation from any documented member that it re-implements.
-# The default value is: YES.
-
-INHERIT_DOCS           = YES
-
-# If the SEPARATE_MEMBER_PAGES tag is set to YES, then doxygen will produce a
-# new page for each member. If set to NO, the documentation of a member will be
-# part of the file/class/namespace that contains it.
-# The default value is: NO.
-
-SEPARATE_MEMBER_PAGES  = NO
-
-# The TAB_SIZE tag can be used to set the number of spaces in a tab. Doxygen
-# uses this value to replace tabs by spaces in code fragments.
-# Minimum value: 1, maximum value: 16, default value: 4.
-
-TAB_SIZE               = 4
-
-# This tag can be used to specify a number of aliases that act as commands in
-# the documentation. An alias has the form:
-# name=value
-# For example adding
-# "sideeffect=@par Side Effects:\n"
-# will allow you to put the command \sideeffect (or @sideeffect) in the
-# documentation, which will result in a user-defined paragraph with heading
-# "Side Effects:". You can put \n's in the value part of an alias to insert
-# newlines.
-
-ALIASES                =
-
-# This tag can be used to specify a number of word-keyword mappings (TCL only).
-# A mapping has the form "name=value". For example adding "class=itcl::class"
-# will allow you to use the command class in the itcl::class meaning.
-
-TCL_SUBST              =
-
-# Set the OPTIMIZE_OUTPUT_FOR_C tag to YES if your project consists of C sources
-# only. Doxygen will then generate output that is more tailored for C. For
-# instance, some of the names that are used will be different. The list of all
-# members will be omitted, etc.
-# The default value is: NO.
-
-OPTIMIZE_OUTPUT_FOR_C  = NO
-
-# Set the OPTIMIZE_OUTPUT_JAVA tag to YES if your project consists of Java or
-# Python sources only. Doxygen will then generate output that is more tailored
-# for that language. For instance, namespaces will be presented as packages,
-# qualified scopes will look different, etc.
-# The default value is: NO.
-
-OPTIMIZE_OUTPUT_JAVA   = NO
-
-# Set the OPTIMIZE_FOR_FORTRAN tag to YES if your project consists of Fortran
-# sources. Doxygen will then generate output that is tailored for Fortran.
-# The default value is: NO.
-
-OPTIMIZE_FOR_FORTRAN   = NO
-
-# Set the OPTIMIZE_OUTPUT_VHDL tag to YES if your project consists of VHDL
-# sources. Doxygen will then generate output that is tailored for VHDL.
-# The default value is: NO.
-
-OPTIMIZE_OUTPUT_VHDL   = NO
-
-# Doxygen selects the parser to use depending on the extension of the files it
-# parses. With this tag you can assign which parser to use for a given
-# extension. Doxygen has a built-in mapping, but you can override or extend it
-# using this tag. The format is ext=language, where ext is a file extension, and
-# language is one of the parsers supported by doxygen: IDL, Java, Javascript,
-# C#, C, C++, D, PHP, Objective-C, Python, Fortran, VHDL. For instance to make
-# doxygen treat .inc files as Fortran files (default is PHP), and .f files as C
-# (default is Fortran), use: inc=Fortran f=C.
-#
-# Note For files without extension you can use no_extension as a placeholder.
-#
-# Note that for custom extensions you also need to set FILE_PATTERNS otherwise
-# the files are not read by doxygen.
-
-EXTENSION_MAPPING      =
-
-# If the MARKDOWN_SUPPORT tag is enabled then doxygen pre-processes all comments
-# according to the Markdown format, which allows for more readable
-# documentation. See http://daringfireball.net/projects/markdown/ for details.
-# The output of markdown processing is further processed by doxygen, so you can
-# mix doxygen, HTML, and XML commands with Markdown formatting. Disable only in
-# case of backward compatibilities issues.
-# The default value is: YES.
-
-MARKDOWN_SUPPORT       = YES
-
-# When enabled doxygen tries to link words that correspond to documented
-# classes, or namespaces to their corresponding documentation. Such a link can
-# be prevented in individual cases by by putting a % sign in front of the word
-# or globally by setting AUTOLINK_SUPPORT to NO.
-# The default value is: YES.
-
-AUTOLINK_SUPPORT       = YES
-
-# If you use STL classes (i.e. std::string, std::vector, etc.) but do not want
-# to include (a tag file for) the STL sources as input, then you should set this
-# tag to YES in order to let doxygen match functions declarations and
-# definitions whose arguments contain STL classes (e.g. func(std::string);
-# versus func(std::string) {}). This also make the inheritance and collaboration
-# diagrams that involve STL classes more complete and accurate.
-# The default value is: NO.
-
-BUILTIN_STL_SUPPORT    = NO
-
-# If you use Microsoft's C++/CLI language, you should set this option to YES to
-# enable parsing support.
-# The default value is: NO.
-
-CPP_CLI_SUPPORT        = NO
-
-# Set the SIP_SUPPORT tag to YES if your project consists of sip (see:
-# http://www.riverbankcomputing.co.uk/software/sip/intro) sources only. Doxygen
-# will parse them like normal C++ but will assume all classes use public instead
-# of private inheritance when no explicit protection keyword is present.
-# The default value is: NO.
-
-SIP_SUPPORT            = NO
-
-# For Microsoft's IDL there are propget and propput attributes to indicate
-# getter and setter methods for a property. Setting this option to YES will make
-# doxygen to replace the get and set methods by a property in the documentation.
-# This will only work if the methods are indeed getting or setting a simple
-# type. If this is not the case, or you want to show the methods anyway, you
-# should set this option to NO.
-# The default value is: YES.
-
-IDL_PROPERTY_SUPPORT   = YES
-
-# If member grouping is used in the documentation and the DISTRIBUTE_GROUP_DOC
-# tag is set to YES, then doxygen will reuse the documentation of the first
-# member in the group (if any) for the other members of the group. By default
-# all members of a group must be documented explicitly.
-# The default value is: NO.
-
-DISTRIBUTE_GROUP_DOC   = NO
-
-# Set the SUBGROUPING tag to YES to allow class member groups of the same type
-# (for instance a group of public functions) to be put as a subgroup of that
-# type (e.g. under the Public Functions section). Set it to NO to prevent
-# subgrouping. Alternatively, this can be done per class using the
-# \nosubgrouping command.
-# The default value is: YES.
-
-SUBGROUPING            = YES
-
-# When the INLINE_GROUPED_CLASSES tag is set to YES, classes, structs and unions
-# are shown inside the group in which they are included (e.g. using \ingroup)
-# instead of on a separate page (for HTML and Man pages) or section (for LaTeX
-# and RTF).
-#
-# Note that this feature does not work in combination with
-# SEPARATE_MEMBER_PAGES.
-# The default value is: NO.
-
-INLINE_GROUPED_CLASSES = NO
-
-# When the INLINE_SIMPLE_STRUCTS tag is set to YES, structs, classes, and unions
-# with only public data fields or simple typedef fields will be shown inline in
-# the documentation of the scope in which they are defined (i.e. file,
-# namespace, or group documentation), provided this scope is documented. If set
-# to NO, structs, classes, and unions are shown on a separate page (for HTML and
-# Man pages) or section (for LaTeX and RTF).
-# The default value is: NO.
-
-INLINE_SIMPLE_STRUCTS  = NO
-
-# When TYPEDEF_HIDES_STRUCT tag is enabled, a typedef of a struct, union, or
-# enum is documented as struct, union, or enum with the name of the typedef. So
-# typedef struct TypeS {} TypeT, will appear in the documentation as a struct
-# with name TypeT. When disabled the typedef will appear as a member of a file,
-# namespace, or class. And the struct will be named TypeS. This can typically be
-# useful for C code in case the coding convention dictates that all compound
-# types are typedef'ed and only the typedef is referenced, never the tag name.
-# The default value is: NO.
-
-TYPEDEF_HIDES_STRUCT   = NO
-
-# The size of the symbol lookup cache can be set using LOOKUP_CACHE_SIZE. This
-# cache is used to resolve symbols given their name and scope. Since this can be
-# an expensive process and often the same symbol appears multiple times in the
-# code, doxygen keeps a cache of pre-resolved symbols. If the cache is too small
-# doxygen will become slower. If the cache is too large, memory is wasted. The
-# cache size is given by this formula: 2^(16+LOOKUP_CACHE_SIZE). The valid range
-# is 0..9, the default is 0, corresponding to a cache size of 2^16=65536
-# symbols. At the end of a run doxygen will report the cache usage and suggest
-# the optimal cache size from a speed point of view.
-# Minimum value: 0, maximum value: 9, default value: 0.
-
-LOOKUP_CACHE_SIZE      = 0
-
-#---------------------------------------------------------------------------
-# Build related configuration options
-#---------------------------------------------------------------------------
-
-# If the EXTRACT_ALL tag is set to YES doxygen will assume all entities in
-# documentation are documented, even if no documentation was available. Private
-# class members and static file members will be hidden unless the
-# EXTRACT_PRIVATE respectively EXTRACT_STATIC tags are set to YES.
-# Note: This will also disable the warnings about undocumented members that are
-# normally produced when WARNINGS is set to YES.
-# The default value is: NO.
-
-EXTRACT_ALL            = NO
-
-# If the EXTRACT_PRIVATE tag is set to YES all private members of a class will
-# be included in the documentation.
-# The default value is: NO.
-
-EXTRACT_PRIVATE        = NO
-
-# If the EXTRACT_PACKAGE tag is set to YES all members with package or internal
-# scope will be included in the documentation.
-# The default value is: NO.
-
-EXTRACT_PACKAGE        = NO
-
-# If the EXTRACT_STATIC tag is set to YES all static members of a file will be
-# included in the documentation.
-# The default value is: NO.
-
-EXTRACT_STATIC         = NO
-
-# If the EXTRACT_LOCAL_CLASSES tag is set to YES classes (and structs) defined
-# locally in source files will be included in the documentation. If set to NO
-# only classes defined in header files are included. Does not have any effect
-# for Java sources.
-# The default value is: YES.
-
-EXTRACT_LOCAL_CLASSES  = YES
-
-# This flag is only useful for Objective-C code. When set to YES local methods,
-# which are defined in the implementation section but not in the interface are
-# included in the documentation. If set to NO only methods in the interface are
-# included.
-# The default value is: NO.
-
-EXTRACT_LOCAL_METHODS  = NO
-
-# If this flag is set to YES, the members of anonymous namespaces will be
-# extracted and appear in the documentation as a namespace called
-# 'anonymous_namespace{file}', where file will be replaced with the base name of
-# the file that contains the anonymous namespace. By default anonymous namespace
-# are hidden.
-# The default value is: NO.
-
-EXTRACT_ANON_NSPACES   = NO
-
-# If the HIDE_UNDOC_MEMBERS tag is set to YES, doxygen will hide all
-# undocumented members inside documented classes or files. If set to NO these
-# members will be included in the various overviews, but no documentation
-# section is generated. This option has no effect if EXTRACT_ALL is enabled.
-# The default value is: NO.
-
-HIDE_UNDOC_MEMBERS     = NO
-
-# If the HIDE_UNDOC_CLASSES tag is set to YES, doxygen will hide all
-# undocumented classes that are normally visible in the class hierarchy. If set
-# to NO these classes will be included in the various overviews. This option has
-# no effect if EXTRACT_ALL is enabled.
-# The default value is: NO.
-
-HIDE_UNDOC_CLASSES     = NO
-
-# If the HIDE_FRIEND_COMPOUNDS tag is set to YES, doxygen will hide all friend
-# (class|struct|union) declarations. If set to NO these declarations will be
-# included in the documentation.
-# The default value is: NO.
-
-HIDE_FRIEND_COMPOUNDS  = NO
-
-# If the HIDE_IN_BODY_DOCS tag is set to YES, doxygen will hide any
-# documentation blocks found inside the body of a function. If set to NO these
-# blocks will be appended to the function's detailed documentation block.
-# The default value is: NO.
-
-HIDE_IN_BODY_DOCS      = NO
-
-# The INTERNAL_DOCS tag determines if documentation that is typed after a
-# \internal command is included. If the tag is set to NO then the documentation
-# will be excluded. Set it to YES to include the internal documentation.
-# The default value is: NO.
-
-INTERNAL_DOCS          = NO
-
-# If the CASE_SENSE_NAMES tag is set to NO then doxygen will only generate file
-# names in lower-case letters. If set to YES upper-case letters are also
-# allowed. This is useful if you have classes or files whose names only differ
-# in case and if your file system supports case sensitive file names. Windows
-# and Mac users are advised to set this option to NO.
-# The default value is: system dependent.
-
-CASE_SENSE_NAMES       = YES
-
-# If the HIDE_SCOPE_NAMES tag is set to NO then doxygen will show members with
-# their full class and namespace scopes in the documentation. If set to YES the
-# scope will be hidden.
-# The default value is: NO.
-
-HIDE_SCOPE_NAMES       = NO
-
-# If the SHOW_INCLUDE_FILES tag is set to YES then doxygen will put a list of
-# the files that are included by a file in the documentation of that file.
-# The default value is: YES.
-
-SHOW_INCLUDE_FILES     = YES
-
-# If the SHOW_GROUPED_MEMB_INC tag is set to YES then Doxygen will add for each
-# grouped member an include statement to the documentation, telling the reader
-# which file to include in order to use the member.
-# The default value is: NO.
-
-SHOW_GROUPED_MEMB_INC  = NO
-
-# If the FORCE_LOCAL_INCLUDES tag is set to YES then doxygen will list include
-# files with double quotes in the documentation rather than with sharp brackets.
-# The default value is: NO.
-
-FORCE_LOCAL_INCLUDES   = NO
-
-# If the INLINE_INFO tag is set to YES then a tag [inline] is inserted in the
-# documentation for inline members.
-# The default value is: YES.
-
-INLINE_INFO            = YES
-
-# If the SORT_MEMBER_DOCS tag is set to YES then doxygen will sort the
-# (detailed) documentation of file and class members alphabetically by member
-# name. If set to NO the members will appear in declaration order.
-# The default value is: YES.
-
-SORT_MEMBER_DOCS       = YES
-
-# If the SORT_BRIEF_DOCS tag is set to YES then doxygen will sort the brief
-# descriptions of file, namespace and class members alphabetically by member
-# name. If set to NO the members will appear in declaration order. Note that
-# this will also influence the order of the classes in the class list.
-# The default value is: NO.
-
-SORT_BRIEF_DOCS        = NO
-
-# If the SORT_MEMBERS_CTORS_1ST tag is set to YES then doxygen will sort the
-# (brief and detailed) documentation of class members so that constructors and
-# destructors are listed first. If set to NO the constructors will appear in the
-# respective orders defined by SORT_BRIEF_DOCS and SORT_MEMBER_DOCS.
-# Note: If SORT_BRIEF_DOCS is set to NO this option is ignored for sorting brief
-# member documentation.
-# Note: If SORT_MEMBER_DOCS is set to NO this option is ignored for sorting
-# detailed member documentation.
-# The default value is: NO.
-
-SORT_MEMBERS_CTORS_1ST = NO
-
-# If the SORT_GROUP_NAMES tag is set to YES then doxygen will sort the hierarchy
-# of group names into alphabetical order. If set to NO the group names will
-# appear in their defined order.
-# The default value is: NO.
-
-SORT_GROUP_NAMES       = NO
-
-# If the SORT_BY_SCOPE_NAME tag is set to YES, the class list will be sorted by
-# fully-qualified names, including namespaces. If set to NO, the class list will
-# be sorted only by class name, not including the namespace part.
-# Note: This option is not very useful if HIDE_SCOPE_NAMES is set to YES.
-# Note: This option applies only to the class list, not to the alphabetical
-# list.
-# The default value is: NO.
-
-SORT_BY_SCOPE_NAME     = NO
-
-# If the STRICT_PROTO_MATCHING option is enabled and doxygen fails to do proper
-# type resolution of all parameters of a function it will reject a match between
-# the prototype and the implementation of a member function even if there is
-# only one candidate or it is obvious which candidate to choose by doing a
-# simple string match. By disabling STRICT_PROTO_MATCHING doxygen will still
-# accept a match between prototype and implementation in such cases.
-# The default value is: NO.
-
-STRICT_PROTO_MATCHING  = NO
-
-# The GENERATE_TODOLIST tag can be used to enable ( YES) or disable ( NO) the
-# todo list. This list is created by putting \todo commands in the
-# documentation.
-# The default value is: YES.
-
-GENERATE_TODOLIST      = YES
-
-# The GENERATE_TESTLIST tag can be used to enable ( YES) or disable ( NO) the
-# test list. This list is created by putting \test commands in the
-# documentation.
-# The default value is: YES.
-
-GENERATE_TESTLIST      = YES
-
-# The GENERATE_BUGLIST tag can be used to enable ( YES) or disable ( NO) the bug
-# list. This list is created by putting \bug commands in the documentation.
-# The default value is: YES.
-
-GENERATE_BUGLIST       = YES
-
-# The GENERATE_DEPRECATEDLIST tag can be used to enable ( YES) or disable ( NO)
-# the deprecated list. This list is created by putting \deprecated commands in
-# the documentation.
-# The default value is: YES.
-
-GENERATE_DEPRECATEDLIST= YES
-
-# The ENABLED_SECTIONS tag can be used to enable conditional documentation
-# sections, marked by \if <section_label> ... \endif and \cond <section_label>
-# ... \endcond blocks.
-
-ENABLED_SECTIONS       =
-
-# The MAX_INITIALIZER_LINES tag determines the maximum number of lines that the
-# initial value of a variable or macro / define can have for it to appear in the
-# documentation. If the initializer consists of more lines than specified here
-# it will be hidden. Use a value of 0 to hide initializers completely. The
-# appearance of the value of individual variables and macros / defines can be
-# controlled using \showinitializer or \hideinitializer command in the
-# documentation regardless of this setting.
-# Minimum value: 0, maximum value: 10000, default value: 30.
-
-MAX_INITIALIZER_LINES  = 30
-
-# Set the SHOW_USED_FILES tag to NO to disable the list of files generated at
-# the bottom of the documentation of classes and structs. If set to YES the list
-# will mention the files that were used to generate the documentation.
-# The default value is: YES.
-
-SHOW_USED_FILES        = YES
-
-# Set the SHOW_FILES tag to NO to disable the generation of the Files page. This
-# will remove the Files entry from the Quick Index and from the Folder Tree View
-# (if specified).
-# The default value is: YES.
-
-SHOW_FILES             = YES
-
-# Set the SHOW_NAMESPACES tag to NO to disable the generation of the Namespaces
-# page. This will remove the Namespaces entry from the Quick Index and from the
-# Folder Tree View (if specified).
-# The default value is: YES.
-
-SHOW_NAMESPACES        = YES
-
-# The FILE_VERSION_FILTER tag can be used to specify a program or script that
-# doxygen should invoke to get the current version for each file (typically from
-# the version control system). Doxygen will invoke the program by executing (via
-# popen()) the command command input-file, where command is the value of the
-# FILE_VERSION_FILTER tag, and input-file is the name of an input file provided
-# by doxygen. Whatever the program writes to standard output is used as the file
-# version. For an example see the documentation.
-
-FILE_VERSION_FILTER    =
-
-# The LAYOUT_FILE tag can be used to specify a layout file which will be parsed
-# by doxygen. The layout file controls the global structure of the generated
-# output files in an output format independent way. To create the layout file
-# that represents doxygen's defaults, run doxygen with the -l option. You can
-# optionally specify a file name after the option, if omitted DoxygenLayout.xml
-# will be used as the name of the layout file.
-#
-# Note that if you run doxygen from a directory containing a file called
-# DoxygenLayout.xml, doxygen will parse it automatically even if the LAYOUT_FILE
-# tag is left empty.
-
-LAYOUT_FILE            =
-
-# The CITE_BIB_FILES tag can be used to specify one or more bib files containing
-# the reference definitions. This must be a list of .bib files. The .bib
-# extension is automatically appended if omitted. This requires the bibtex tool
-# to be installed. See also http://en.wikipedia.org/wiki/BibTeX for more info.
-# For LaTeX the style of the bibliography can be controlled using
-# LATEX_BIB_STYLE. To use this feature you need bibtex and perl available in the
-# search path. Do not use file names with spaces, bibtex cannot handle them. See
-# also \cite for info how to create references.
-
-CITE_BIB_FILES         =
-
-#---------------------------------------------------------------------------
-# Configuration options related to warning and progress messages
-#---------------------------------------------------------------------------
-
-# The QUIET tag can be used to turn on/off the messages that are generated to
-# standard output by doxygen. If QUIET is set to YES this implies that the
-# messages are off.
-# The default value is: NO.
-
-QUIET                  = NO
-
-# The WARNINGS tag can be used to turn on/off the warning messages that are
-# generated to standard error ( stderr) by doxygen. If WARNINGS is set to YES
-# this implies that the warnings are on.
-#
-# Tip: Turn warnings on while writing the documentation.
-# The default value is: YES.
-
-WARNINGS               = YES
-
-# If the WARN_IF_UNDOCUMENTED tag is set to YES, then doxygen will generate
-# warnings for undocumented members. If EXTRACT_ALL is set to YES then this flag
-# will automatically be disabled.
-# The default value is: YES.
-
-WARN_IF_UNDOCUMENTED   = YES
-
-# If the WARN_IF_DOC_ERROR tag is set to YES, doxygen will generate warnings for
-# potential errors in the documentation, such as not documenting some parameters
-# in a documented function, or documenting parameters that don't exist or using
-# markup commands wrongly.
-# The default value is: YES.
-
-WARN_IF_DOC_ERROR      = YES
-
-# This WARN_NO_PARAMDOC option can be enabled to get warnings for functions that
-# are documented, but have no documentation for their parameters or return
-# value. If set to NO doxygen will only warn about wrong or incomplete parameter
-# documentation, but not about the absence of documentation.
-# The default value is: NO.
-
-WARN_NO_PARAMDOC       = NO
-
-# The WARN_FORMAT tag determines the format of the warning messages that doxygen
-# can produce. The string should contain the $file, $line, and $text tags, which
-# will be replaced by the file and line number from which the warning originated
-# and the warning text. Optionally the format may contain $version, which will
-# be replaced by the version of the file (if it could be obtained via
-# FILE_VERSION_FILTER)
-# The default value is: $file:$line: $text.
-
-WARN_FORMAT            = "$file:$line: $text"
-
-# The WARN_LOGFILE tag can be used to specify a file to which warning and error
-# messages should be written. If left blank the output is written to standard
-# error (stderr).
-
-WARN_LOGFILE           =
-
-#---------------------------------------------------------------------------
-# Configuration options related to the input files
-#---------------------------------------------------------------------------
-
-# The INPUT tag is used to specify the files and/or directories that contain
-# documented source files. You may enter file names like myfile.cpp or
-# directories like /usr/src/myproject. Separate the files or directories with
-# spaces.
-# Note: If this tag is empty the current directory is searched.
-
-INPUT                  =
-
-# This tag can be used to specify the character encoding of the source files
-# that doxygen parses. Internally doxygen uses the UTF-8 encoding. Doxygen uses
-# libiconv (or the iconv built into libc) for the transcoding. See the libiconv
-# documentation (see: http://www.gnu.org/software/libiconv) for the list of
-# possible encodings.
-# The default value is: UTF-8.
-
-INPUT_ENCODING         = UTF-8
-
-# If the value of the INPUT tag contains directories, you can use the
-# FILE_PATTERNS tag to specify one or more wildcard patterns (like *.cpp and
-# *.h) to filter out the source-files in the directories. If left blank the
-# following patterns are tested:*.c, *.cc, *.cxx, *.cpp, *.c++, *.java, *.ii,
-# *.ixx, *.ipp, *.i++, *.inl, *.idl, *.ddl, *.odl, *.h, *.hh, *.hxx, *.hpp,
-# *.h++, *.cs, *.d, *.php, *.php4, *.php5, *.phtml, *.inc, *.m, *.markdown,
-# *.md, *.mm, *.dox, *.py, *.f90, *.f, *.for, *.tcl, *.vhd, *.vhdl, *.ucf,
-# *.qsf, *.as and *.js.
-
-FILE_PATTERNS          =
-
-# The RECURSIVE tag can be used to specify whether or not subdirectories should
-# be searched for input files as well.
-# The default value is: NO.
-
-RECURSIVE              = YES
-
-# The EXCLUDE tag can be used to specify files and/or directories that should be
-# excluded from the INPUT source files. This way you can easily exclude a
-# subdirectory from a directory tree whose root is specified with the INPUT tag.
-#
-# Note that relative paths are relative to the directory from which doxygen is
-# run.
-
-EXCLUDE                =
-
-# The EXCLUDE_SYMLINKS tag can be used to select whether or not files or
-# directories that are symbolic links (a Unix file system feature) are excluded
-# from the input.
-# The default value is: NO.
-
-EXCLUDE_SYMLINKS       = NO
-
-# If the value of the INPUT tag contains directories, you can use the
-# EXCLUDE_PATTERNS tag to specify one or more wildcard patterns to exclude
-# certain files from those directories.
-#
-# Note that the wildcards are matched against the file with absolute path, so to
-# exclude all test directories for example use the pattern */test/*
-
-EXCLUDE_PATTERNS       =
-
-# The EXCLUDE_SYMBOLS tag can be used to specify one or more symbol names
-# (namespaces, classes, functions, etc.) that should be excluded from the
-# output. The symbol name can be a fully qualified name, a word, or if the
-# wildcard * is used, a substring. Examples: ANamespace, AClass,
-# AClass::ANamespace, ANamespace::*Test
-#
-# Note that the wildcards are matched against the file with absolute path, so to
-# exclude all test directories use the pattern */test/*
-
-EXCLUDE_SYMBOLS        =
-
-# The EXAMPLE_PATH tag can be used to specify one or more files or directories
-# that contain example code fragments that are included (see the \include
-# command).
-
-EXAMPLE_PATH           =
-
-# If the value of the EXAMPLE_PATH tag contains directories, you can use the
-# EXAMPLE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp and
-# *.h) to filter out the source-files in the directories. If left blank all
-# files are included.
-
-EXAMPLE_PATTERNS       =
-
-# If the EXAMPLE_RECURSIVE tag is set to YES then subdirectories will be
-# searched for input files to be used with the \include or \dontinclude commands
-# irrespective of the value of the RECURSIVE tag.
-# The default value is: NO.
-
-EXAMPLE_RECURSIVE      = NO
-
-# The IMAGE_PATH tag can be used to specify one or more files or directories
-# that contain images that are to be included in the documentation (see the
-# \image command).
-
-IMAGE_PATH             =
-
-# The INPUT_FILTER tag can be used to specify a program that doxygen should
-# invoke to filter for each input file. Doxygen will invoke the filter program
-# by executing (via popen()) the command:
-#
-# <filter> <input-file>
-#
-# where <filter> is the value of the INPUT_FILTER tag, and <input-file> is the
-# name of an input file. Doxygen will then use the output that the filter
-# program writes to standard output. If FILTER_PATTERNS is specified, this tag
-# will be ignored.
-#
-# Note that the filter must not add or remove lines; it is applied before the
-# code is scanned, but not when the output code is generated. If lines are added
-# or removed, the anchors will not be placed correctly.
-
-INPUT_FILTER           =
-
-# The FILTER_PATTERNS tag can be used to specify filters on a per file pattern
-# basis. Doxygen will compare the file name with each pattern and apply the
-# filter if there is a match. The filters are a list of the form: pattern=filter
-# (like *.cpp=my_cpp_filter). See INPUT_FILTER for further information on how
-# filters are used. If the FILTER_PATTERNS tag is empty or if none of the
-# patterns match the file name, INPUT_FILTER is applied.
-
-FILTER_PATTERNS        =
-
-# If the FILTER_SOURCE_FILES tag is set to YES, the input filter (if set using
-# INPUT_FILTER ) will also be used to filter the input files that are used for
-# producing the source files to browse (i.e. when SOURCE_BROWSER is set to YES).
-# The default value is: NO.
-
-FILTER_SOURCE_FILES    = NO
-
-# The FILTER_SOURCE_PATTERNS tag can be used to specify source filters per file
-# pattern. A pattern will override the setting for FILTER_PATTERN (if any) and
-# it is also possible to disable source filtering for a specific pattern using
-# *.ext= (so without naming a filter).
-# This tag requires that the tag FILTER_SOURCE_FILES is set to YES.
-
-FILTER_SOURCE_PATTERNS =
-
-# If the USE_MDFILE_AS_MAINPAGE tag refers to the name of a markdown file that
-# is part of the input, its contents will be placed on the main page
-# (index.html). This can be useful if you have a project on for instance GitHub
-# and want to reuse the introduction page also for the doxygen output.
-
-USE_MDFILE_AS_MAINPAGE =
-
-#---------------------------------------------------------------------------
-# Configuration options related to source browsing
-#---------------------------------------------------------------------------
-
-# If the SOURCE_BROWSER tag is set to YES then a list of source files will be
-# generated. Documented entities will be cross-referenced with these sources.
-#
-# Note: To get rid of all source code in the generated output, make sure that
-# also VERBATIM_HEADERS is set to NO.
-# The default value is: NO.
-
-SOURCE_BROWSER         = NO
-
-# Setting the INLINE_SOURCES tag to YES will include the body of functions,
-# classes and enums directly into the documentation.
-# The default value is: NO.
-
-INLINE_SOURCES         = NO
-
-# Setting the STRIP_CODE_COMMENTS tag to YES will instruct doxygen to hide any
-# special comment blocks from generated source code fragments. Normal C, C++ and
-# Fortran comments will always remain visible.
-# The default value is: YES.
-
-STRIP_CODE_COMMENTS    = YES
-
-# If the REFERENCED_BY_RELATION tag is set to YES then for each documented
-# function all documented functions referencing it will be listed.
-# The default value is: NO.
-
-REFERENCED_BY_RELATION = NO
-
-# If the REFERENCES_RELATION tag is set to YES then for each documented function
-# all documented entities called/used by that function will be listed.
-# The default value is: NO.
-
-REFERENCES_RELATION    = NO
-
-# If the REFERENCES_LINK_SOURCE tag is set to YES and SOURCE_BROWSER tag is set
-# to YES, then the hyperlinks from functions in REFERENCES_RELATION and
-# REFERENCED_BY_RELATION lists will link to the source code. Otherwise they will
-# link to the documentation.
-# The default value is: YES.
-
-REFERENCES_LINK_SOURCE = YES
-
-# If SOURCE_TOOLTIPS is enabled (the default) then hovering a hyperlink in the
-# source code will show a tooltip with additional information such as prototype,
-# brief description and links to the definition and documentation. Since this
-# will make the HTML file larger and loading of large files a bit slower, you
-# can opt to disable this feature.
-# The default value is: YES.
-# This tag requires that the tag SOURCE_BROWSER is set to YES.
-
-SOURCE_TOOLTIPS        = YES
-
-# If the USE_HTAGS tag is set to YES then the references to source code will
-# point to the HTML generated by the htags(1) tool instead of doxygen built-in
-# source browser. The htags tool is part of GNU's global source tagging system
-# (see http://www.gnu.org/software/global/global.html). You will need version
-# 4.8.6 or higher.
-#
-# To use it do the following:
-# - Install the latest version of global
-# - Enable SOURCE_BROWSER and USE_HTAGS in the config file
-# - Make sure the INPUT points to the root of the source tree
-# - Run doxygen as normal
-#
-# Doxygen will invoke htags (and that will in turn invoke gtags), so these
-# tools must be available from the command line (i.e. in the search path).
-#
-# The result: instead of the source browser generated by doxygen, the links to
-# source code will now point to the output of htags.
-# The default value is: NO.
-# This tag requires that the tag SOURCE_BROWSER is set to YES.
-
-USE_HTAGS              = NO
-
-# If the VERBATIM_HEADERS tag is set the YES then doxygen will generate a
-# verbatim copy of the header file for each class for which an include is
-# specified. Set to NO to disable this.
-# See also: Section \class.
-# The default value is: YES.
-
-VERBATIM_HEADERS       = YES
-
-#---------------------------------------------------------------------------
-# Configuration options related to the alphabetical class index
-#---------------------------------------------------------------------------
-
-# If the ALPHABETICAL_INDEX tag is set to YES, an alphabetical index of all
-# compounds will be generated. Enable this if the project contains a lot of
-# classes, structs, unions or interfaces.
-# The default value is: YES.
-
-ALPHABETICAL_INDEX     = YES
-
-# The COLS_IN_ALPHA_INDEX tag can be used to specify the number of columns in
-# which the alphabetical index list will be split.
-# Minimum value: 1, maximum value: 20, default value: 5.
-# This tag requires that the tag ALPHABETICAL_INDEX is set to YES.
-
-COLS_IN_ALPHA_INDEX    = 5
-
-# In case all classes in a project start with a common prefix, all classes will
-# be put under the same header in the alphabetical index. The IGNORE_PREFIX tag
-# can be used to specify a prefix (or a list of prefixes) that should be ignored
-# while generating the index headers.
-# This tag requires that the tag ALPHABETICAL_INDEX is set to YES.
-
-IGNORE_PREFIX          =
-
-#---------------------------------------------------------------------------
-# Configuration options related to the HTML output
-#---------------------------------------------------------------------------
-
-# If the GENERATE_HTML tag is set to YES doxygen will generate HTML output
-# The default value is: YES.
-
-GENERATE_HTML          = YES
-
-# The HTML_OUTPUT tag is used to specify where the HTML docs will be put. If a
-# relative path is entered the value of OUTPUT_DIRECTORY will be put in front of
-# it.
-# The default directory is: html.
-# This tag requires that the tag GENERATE_HTML is set to YES.
-
-HTML_OUTPUT            = html
-
-# The HTML_FILE_EXTENSION tag can be used to specify the file extension for each
-# generated HTML page (for example: .htm, .php, .asp).
-# The default value is: .html.
-# This tag requires that the tag GENERATE_HTML is set to YES.
-
-HTML_FILE_EXTENSION    = .html
-
-# The HTML_HEADER tag can be used to specify a user-defined HTML header file for
-# each generated HTML page. If the tag is left blank doxygen will generate a
-# standard header.
-#
-# To get valid HTML the header file that includes any scripts and style sheets
-# that doxygen needs, which is dependent on the configuration options used (e.g.
-# the setting GENERATE_TREEVIEW). It is highly recommended to start with a
-# default header using
-# doxygen -w html new_header.html new_footer.html new_stylesheet.css
-# YourConfigFile
-# and then modify the file new_header.html. See also section "Doxygen usage"
-# for information on how to generate the default header that doxygen normally
-# uses.
-# Note: The header is subject to change so you typically have to regenerate the
-# default header when upgrading to a newer version of doxygen. For a description
-# of the possible markers and block names see the documentation.
-# This tag requires that the tag GENERATE_HTML is set to YES.
-
-HTML_HEADER            =
-
-# The HTML_FOOTER tag can be used to specify a user-defined HTML footer for each
-# generated HTML page. If the tag is left blank doxygen will generate a standard
-# footer. See HTML_HEADER for more information on how to generate a default
-# footer and what special commands can be used inside the footer. See also
-# section "Doxygen usage" for information on how to generate the default footer
-# that doxygen normally uses.
-# This tag requires that the tag GENERATE_HTML is set to YES.
-
-HTML_FOOTER            =
-
-# The HTML_STYLESHEET tag can be used to specify a user-defined cascading style
-# sheet that is used by each HTML page. It can be used to fine-tune the look of
-# the HTML output. If left blank doxygen will generate a default style sheet.
-# See also section "Doxygen usage" for information on how to generate the style
-# sheet that doxygen normally uses.
-# Note: It is recommended to use HTML_EXTRA_STYLESHEET instead of this tag, as
-# it is more robust and this tag (HTML_STYLESHEET) will in the future become
-# obsolete.
-# This tag requires that the tag GENERATE_HTML is set to YES.
-
-HTML_STYLESHEET        =
-
-# The HTML_EXTRA_STYLESHEET tag can be used to specify an additional user-
-# defined cascading style sheet that is included after the standard style sheets
-# created by doxygen. Using this option one can overrule certain style aspects.
-# This is preferred over using HTML_STYLESHEET since it does not replace the
-# standard style sheet and is therefor more robust against future updates.
-# Doxygen will copy the style sheet file to the output directory. For an example
-# see the documentation.
-# This tag requires that the tag GENERATE_HTML is set to YES.
-
-HTML_EXTRA_STYLESHEET  =
-
-# The HTML_EXTRA_FILES tag can be used to specify one or more extra images or
-# other source files which should be copied to the HTML output directory. Note
-# that these files will be copied to the base HTML output directory. Use the
-# $relpath^ marker in the HTML_HEADER and/or HTML_FOOTER files to load these
-# files. In the HTML_STYLESHEET file, use the file name only. Also note that the
-# files will be copied as-is; there are no commands or markers available.
-# This tag requires that the tag GENERATE_HTML is set to YES.
-
-HTML_EXTRA_FILES       =
-
-# The HTML_COLORSTYLE_HUE tag controls the color of the HTML output. Doxygen
-# will adjust the colors in the stylesheet and background images according to
-# this color. Hue is specified as an angle on a colorwheel, see
-# http://en.wikipedia.org/wiki/Hue for more information. For instance the value
-# 0 represents red, 60 is yellow, 120 is green, 180 is cyan, 240 is blue, 300
-# purple, and 360 is red again.
-# Minimum value: 0, maximum value: 359, default value: 220.
-# This tag requires that the tag GENERATE_HTML is set to YES.
-
-HTML_COLORSTYLE_HUE    = 220
-
-# The HTML_COLORSTYLE_SAT tag controls the purity (or saturation) of the colors
-# in the HTML output. For a value of 0 the output will use grayscales only. A
-# value of 255 will produce the most vivid colors.
-# Minimum value: 0, maximum value: 255, default value: 100.
-# This tag requires that the tag GENERATE_HTML is set to YES.
-
-HTML_COLORSTYLE_SAT    = 100
-
-# The HTML_COLORSTYLE_GAMMA tag controls the gamma correction applied to the
-# luminance component of the colors in the HTML output. Values below 100
-# gradually make the output lighter, whereas values above 100 make the output
-# darker. The value divided by 100 is the actual gamma applied, so 80 represents
-# a gamma of 0.8, The value 220 represents a gamma of 2.2, and 100 does not
-# change the gamma.
-# Minimum value: 40, maximum value: 240, default value: 80.
-# This tag requires that the tag GENERATE_HTML is set to YES.
-
-HTML_COLORSTYLE_GAMMA  = 80
-
-# If the HTML_TIMESTAMP tag is set to YES then the footer of each generated HTML
-# page will contain the date and time when the page was generated. Setting this
-# to NO can help when comparing the output of multiple runs.
-# The default value is: YES.
-# This tag requires that the tag GENERATE_HTML is set to YES.
-
-HTML_TIMESTAMP         = YES
-
-# If the HTML_DYNAMIC_SECTIONS tag is set to YES then the generated HTML
-# documentation will contain sections that can be hidden and shown after the
-# page has loaded.
-# The default value is: NO.
-# This tag requires that the tag GENERATE_HTML is set to YES.
-
-HTML_DYNAMIC_SECTIONS  = NO
-
-# With HTML_INDEX_NUM_ENTRIES one can control the preferred number of entries
-# shown in the various tree structured indices initially; the user can expand
-# and collapse entries dynamically later on. Doxygen will expand the tree to
-# such a level that at most the specified number of entries are visible (unless
-# a fully collapsed tree already exceeds this amount). So setting the number of
-# entries 1 will produce a full collapsed tree by default. 0 is a special value
-# representing an infinite number of entries and will result in a full expanded
-# tree by default.
-# Minimum value: 0, maximum value: 9999, default value: 100.
-# This tag requires that the tag GENERATE_HTML is set to YES.
-
-HTML_INDEX_NUM_ENTRIES = 100
-
-# If the GENERATE_DOCSET tag is set to YES, additional index files will be
-# generated that can be used as input for Apple's Xcode 3 integrated development
-# environment (see: http://developer.apple.com/tools/xcode/), introduced with
-# OSX 10.5 (Leopard). To create a documentation set, doxygen will generate a
-# Makefile in the HTML output directory. Running make will produce the docset in
-# that directory and running make install will install the docset in
-# ~/Library/Developer/Shared/Documentation/DocSets so that Xcode will find it at
-# startup. See http://developer.apple.com/tools/creatingdocsetswithdoxygen.html
-# for more information.
-# The default value is: NO.
-# This tag requires that the tag GENERATE_HTML is set to YES.
-
-GENERATE_DOCSET        = NO
-
-# This tag determines the name of the docset feed. A documentation feed provides
-# an umbrella under which multiple documentation sets from a single provider
-# (such as a company or product suite) can be grouped.
-# The default value is: Doxygen generated docs.
-# This tag requires that the tag GENERATE_DOCSET is set to YES.
-
-DOCSET_FEEDNAME        = "Doxygen generated docs"
-
-# This tag specifies a string that should uniquely identify the documentation
-# set bundle. This should be a reverse domain-name style string, e.g.
-# com.mycompany.MyDocSet. Doxygen will append .docset to the name.
-# The default value is: org.doxygen.Project.
-# This tag requires that the tag GENERATE_DOCSET is set to YES.
-
-DOCSET_BUNDLE_ID       = org.doxygen.Project
-
-# The DOCSET_PUBLISHER_ID tag specifies a string that should uniquely identify
-# the documentation publisher. This should be a reverse domain-name style
-# string, e.g. com.mycompany.MyDocSet.documentation.
-# The default value is: org.doxygen.Publisher.
-# This tag requires that the tag GENERATE_DOCSET is set to YES.
-
-DOCSET_PUBLISHER_ID    = org.doxygen.Publisher
-
-# The DOCSET_PUBLISHER_NAME tag identifies the documentation publisher.
-# The default value is: Publisher.
-# This tag requires that the tag GENERATE_DOCSET is set to YES.
-
-DOCSET_PUBLISHER_NAME  = Publisher
-
-# If the GENERATE_HTMLHELP tag is set to YES then doxygen generates three
-# additional HTML index files: index.hhp, index.hhc, and index.hhk. The
-# index.hhp is a project file that can be read by Microsoft's HTML Help Workshop
-# (see: http://www.microsoft.com/en-us/download/details.aspx?id=21138) on
-# Windows.
-#
-# The HTML Help Workshop contains a compiler that can convert all HTML output
-# generated by doxygen into a single compiled HTML file (.chm). Compiled HTML
-# files are now used as the Windows 98 help format, and will replace the old
-# Windows help format (.hlp) on all Windows platforms in the future. Compressed
-# HTML files also contain an index, a table of contents, and you can search for
-# words in the documentation. The HTML workshop also contains a viewer for
-# compressed HTML files.
-# The default value is: NO.
-# This tag requires that the tag GENERATE_HTML is set to YES.
-
-GENERATE_HTMLHELP      = NO
-
-# The CHM_FILE tag can be used to specify the file name of the resulting .chm
-# file. You can add a path in front of the file if the result should not be
-# written to the html output directory.
-# This tag requires that the tag GENERATE_HTMLHELP is set to YES.
-
-CHM_FILE               =
-
-# The HHC_LOCATION tag can be used to specify the location (absolute path
-# including file name) of the HTML help compiler ( hhc.exe). If non-empty
-# doxygen will try to run the HTML help compiler on the generated index.hhp.
-# The file has to be specified with full path.
-# This tag requires that the tag GENERATE_HTMLHELP is set to YES.
-
-HHC_LOCATION           =
-
-# The GENERATE_CHI flag controls if a separate .chi index file is generated (
-# YES) or that it should be included in the master .chm file ( NO).
-# The default value is: NO.
-# This tag requires that the tag GENERATE_HTMLHELP is set to YES.
-
-GENERATE_CHI           = NO
-
-# The CHM_INDEX_ENCODING is used to encode HtmlHelp index ( hhk), content ( hhc)
-# and project file content.
-# This tag requires that the tag GENERATE_HTMLHELP is set to YES.
-
-CHM_INDEX_ENCODING     =
-
-# The BINARY_TOC flag controls whether a binary table of contents is generated (
-# YES) or a normal table of contents ( NO) in the .chm file.
-# The default value is: NO.
-# This tag requires that the tag GENERATE_HTMLHELP is set to YES.
-
-BINARY_TOC             = NO
-
-# The TOC_EXPAND flag can be set to YES to add extra items for group members to
-# the table of contents of the HTML help documentation and to the tree view.
-# The default value is: NO.
-# This tag requires that the tag GENERATE_HTMLHELP is set to YES.
-
-TOC_EXPAND             = NO
-
-# If the GENERATE_QHP tag is set to YES and both QHP_NAMESPACE and
-# QHP_VIRTUAL_FOLDER are set, an additional index file will be generated that
-# can be used as input for Qt's qhelpgenerator to generate a Qt Compressed Help
-# (.qch) of the generated HTML documentation.
-# The default value is: NO.
-# This tag requires that the tag GENERATE_HTML is set to YES.
-
-GENERATE_QHP           = NO
-
-# If the QHG_LOCATION tag is specified, the QCH_FILE tag can be used to specify
-# the file name of the resulting .qch file. The path specified is relative to
-# the HTML output folder.
-# This tag requires that the tag GENERATE_QHP is set to YES.
-
-QCH_FILE               =
-
-# The QHP_NAMESPACE tag specifies the namespace to use when generating Qt Help
-# Project output. For more information please see Qt Help Project / Namespace
-# (see: http://qt-project.org/doc/qt-4.8/qthelpproject.html#namespace).
-# The default value is: org.doxygen.Project.
-# This tag requires that the tag GENERATE_QHP is set to YES.
-
-QHP_NAMESPACE          = org.doxygen.Project
-
-# The QHP_VIRTUAL_FOLDER tag specifies the namespace to use when generating Qt
-# Help Project output. For more information please see Qt Help Project / Virtual
-# Folders (see: http://qt-project.org/doc/qt-4.8/qthelpproject.html#virtual-
-# folders).
-# The default value is: doc.
-# This tag requires that the tag GENERATE_QHP is set to YES.
-
-QHP_VIRTUAL_FOLDER     = doc
-
-# If the QHP_CUST_FILTER_NAME tag is set, it specifies the name of a custom
-# filter to add. For more information please see Qt Help Project / Custom
-# Filters (see: http://qt-project.org/doc/qt-4.8/qthelpproject.html#custom-
-# filters).
-# This tag requires that the tag GENERATE_QHP is set to YES.
-
-QHP_CUST_FILTER_NAME   =
-
-# The QHP_CUST_FILTER_ATTRS tag specifies the list of the attributes of the
-# custom filter to add. For more information please see Qt Help Project / Custom
-# Filters (see: http://qt-project.org/doc/qt-4.8/qthelpproject.html#custom-
-# filters).
-# This tag requires that the tag GENERATE_QHP is set to YES.
-
-QHP_CUST_FILTER_ATTRS  =
-
-# The QHP_SECT_FILTER_ATTRS tag specifies the list of the attributes this
-# project's filter section matches. Qt Help Project / Filter Attributes (see:
-# http://qt-project.org/doc/qt-4.8/qthelpproject.html#filter-attributes).
-# This tag requires that the tag GENERATE_QHP is set to YES.
-
-QHP_SECT_FILTER_ATTRS  =
-
-# The QHG_LOCATION tag can be used to specify the location of Qt's
-# qhelpgenerator. If non-empty doxygen will try to run qhelpgenerator on the
-# generated .qhp file.
-# This tag requires that the tag GENERATE_QHP is set to YES.
-
-QHG_LOCATION           =
-
-# If the GENERATE_ECLIPSEHELP tag is set to YES, additional index files will be
-# generated, together with the HTML files, they form an Eclipse help plugin. To
-# install this plugin and make it available under the help contents menu in
-# Eclipse, the contents of the directory containing the HTML and XML files needs
-# to be copied into the plugins directory of eclipse. The name of the directory
-# within the plugins directory should be the same as the ECLIPSE_DOC_ID value.
-# After copying Eclipse needs to be restarted before the help appears.
-# The default value is: NO.
-# This tag requires that the tag GENERATE_HTML is set to YES.
-
-GENERATE_ECLIPSEHELP   = NO
-
-# A unique identifier for the Eclipse help plugin. When installing the plugin
-# the directory name containing the HTML and XML files should also have this
-# name. Each documentation set should have its own identifier.
-# The default value is: org.doxygen.Project.
-# This tag requires that the tag GENERATE_ECLIPSEHELP is set to YES.
-
-ECLIPSE_DOC_ID         = org.doxygen.Project
-
-# If you want full control over the layout of the generated HTML pages it might
-# be necessary to disable the index and replace it with your own. The
-# DISABLE_INDEX tag can be used to turn on/off the condensed index (tabs) at top
-# of each HTML page. A value of NO enables the index and the value YES disables
-# it. Since the tabs in the index contain the same information as the navigation
-# tree, you can set this option to YES if you also set GENERATE_TREEVIEW to YES.
-# The default value is: NO.
-# This tag requires that the tag GENERATE_HTML is set to YES.
-
-DISABLE_INDEX          = YES
-
-# The GENERATE_TREEVIEW tag is used to specify whether a tree-like index
-# structure should be generated to display hierarchical information. If the tag
-# value is set to YES, a side panel will be generated containing a tree-like
-# index structure (just like the one that is generated for HTML Help). For this
-# to work a browser that supports JavaScript, DHTML, CSS and frames is required
-# (i.e. any modern browser). Windows users are probably better off using the
-# HTML help feature. Via custom stylesheets (see HTML_EXTRA_STYLESHEET) one can
-# further fine-tune the look of the index. As an example, the default style
-# sheet generated by doxygen has an example that shows how to put an image at
-# the root of the tree instead of the PROJECT_NAME. Since the tree basically has
-# the same information as the tab index, you could consider setting
-# DISABLE_INDEX to YES when enabling this option.
-# The default value is: NO.
-# This tag requires that the tag GENERATE_HTML is set to YES.
-
-GENERATE_TREEVIEW      = YES
-
-# The ENUM_VALUES_PER_LINE tag can be used to set the number of enum values that
-# doxygen will group on one line in the generated HTML documentation.
-#
-# Note that a value of 0 will completely suppress the enum values from appearing
-# in the overview section.
-# Minimum value: 0, maximum value: 20, default value: 4.
-# This tag requires that the tag GENERATE_HTML is set to YES.
-
-ENUM_VALUES_PER_LINE   = 4
-
-# If the treeview is enabled (see GENERATE_TREEVIEW) then this tag can be used
-# to set the initial width (in pixels) of the frame in which the tree is shown.
-# Minimum value: 0, maximum value: 1500, default value: 250.
-# This tag requires that the tag GENERATE_HTML is set to YES.
-
-TREEVIEW_WIDTH         = 250
-
-# When the EXT_LINKS_IN_WINDOW option is set to YES doxygen will open links to
-# external symbols imported via tag files in a separate window.
-# The default value is: NO.
-# This tag requires that the tag GENERATE_HTML is set to YES.
-
-EXT_LINKS_IN_WINDOW    = NO
-
-# Use this tag to change the font size of LaTeX formulas included as images in
-# the HTML documentation. When you change the font size after a successful
-# doxygen run you need to manually remove any form_*.png images from the HTML
-# output directory to force them to be regenerated.
-# Minimum value: 8, maximum value: 50, default value: 10.
-# This tag requires that the tag GENERATE_HTML is set to YES.
-
-FORMULA_FONTSIZE       = 10
-
-# Use the FORMULA_TRANPARENT tag to determine whether or not the images
-# generated for formulas are transparent PNGs. Transparent PNGs are not
-# supported properly for IE 6.0, but are supported on all modern browsers.
-#
-# Note that when changing this option you need to delete any form_*.png files in
-# the HTML output directory before the changes have effect.
-# The default value is: YES.
-# This tag requires that the tag GENERATE_HTML is set to YES.
-
-FORMULA_TRANSPARENT    = YES
-
-# Enable the USE_MATHJAX option to render LaTeX formulas using MathJax (see
-# http://www.mathjax.org) which uses client side Javascript for the rendering
-# instead of using prerendered bitmaps. Use this if you do not have LaTeX
-# installed or if you want to formulas look prettier in the HTML output. When
-# enabled you may also need to install MathJax separately and configure the path
-# to it using the MATHJAX_RELPATH option.
-# The default value is: NO.
-# This tag requires that the tag GENERATE_HTML is set to YES.
-
-USE_MATHJAX            = NO
-
-# When MathJax is enabled you can set the default output format to be used for
-# the MathJax output. See the MathJax site (see:
-# http://docs.mathjax.org/en/latest/output.html) for more details.
-# Possible values are: HTML-CSS (which is slower, but has the best
-# compatibility), NativeMML (i.e. MathML) and SVG.
-# The default value is: HTML-CSS.
-# This tag requires that the tag USE_MATHJAX is set to YES.
-
-MATHJAX_FORMAT         = HTML-CSS
-
-# When MathJax is enabled you need to specify the location relative to the HTML
-# output directory using the MATHJAX_RELPATH option. The destination directory
-# should contain the MathJax.js script. For instance, if the mathjax directory
-# is located at the same level as the HTML output directory, then
-# MATHJAX_RELPATH should be ../mathjax. The default value points to the MathJax
-# Content Delivery Network so you can quickly see the result without installing
-# MathJax. However, it is strongly recommended to install a local copy of
-# MathJax from http://www.mathjax.org before deployment.
-# The default value is: http://cdn.mathjax.org/mathjax/latest.
-# This tag requires that the tag USE_MATHJAX is set to YES.
-
-MATHJAX_RELPATH        = http://cdn.mathjax.org/mathjax/latest
-
-# The MATHJAX_EXTENSIONS tag can be used to specify one or more MathJax
-# extension names that should be enabled during MathJax rendering. For example
-# MATHJAX_EXTENSIONS = TeX/AMSmath TeX/AMSsymbols
-# This tag requires that the tag USE_MATHJAX is set to YES.
-
-MATHJAX_EXTENSIONS     =
-
-# The MATHJAX_CODEFILE tag can be used to specify a file with javascript pieces
-# of code that will be used on startup of the MathJax code. See the MathJax site
-# (see: http://docs.mathjax.org/en/latest/output.html) for more details. For an
-# example see the documentation.
-# This tag requires that the tag USE_MATHJAX is set to YES.
-
-MATHJAX_CODEFILE       =
-
-# When the SEARCHENGINE tag is enabled doxygen will generate a search box for
-# the HTML output. The underlying search engine uses javascript and DHTML and
-# should work on any modern browser. Note that when using HTML help
-# (GENERATE_HTMLHELP), Qt help (GENERATE_QHP), or docsets (GENERATE_DOCSET)
-# there is already a search function so this one should typically be disabled.
-# For large projects the javascript based search engine can be slow, then
-# enabling SERVER_BASED_SEARCH may provide a better solution. It is possible to
-# search using the keyboard; to jump to the search box use <access key> + S
-# (what the <access key> is depends on the OS and browser, but it is typically
-# <CTRL>, <ALT>/<option>, or both). Inside the search box use the <cursor down
-# key> to jump into the search results window, the results can be navigated
-# using the <cursor keys>. Press <Enter> to select an item or <escape> to cancel
-# the search. The filter options can be selected when the cursor is inside the
-# search box by pressing <Shift>+<cursor down>. Also here use the <cursor keys>
-# to select a filter and <Enter> or <escape> to activate or cancel the filter
-# option.
-# The default value is: YES.
-# This tag requires that the tag GENERATE_HTML is set to YES.
-
-SEARCHENGINE           = YES
-
-# When the SERVER_BASED_SEARCH tag is enabled the search engine will be
-# implemented using a web server instead of a web client using Javascript. There
-# are two flavours of web server based searching depending on the
-# EXTERNAL_SEARCH setting. When disabled, doxygen will generate a PHP script for
-# searching and an index file used by the script. When EXTERNAL_SEARCH is
-# enabled the indexing and searching needs to be provided by external tools. See
-# the section "External Indexing and Searching" for details.
-# The default value is: NO.
-# This tag requires that the tag SEARCHENGINE is set to YES.
-
-SERVER_BASED_SEARCH    = NO
-
-# When EXTERNAL_SEARCH tag is enabled doxygen will no longer generate the PHP
-# script for searching. Instead the search results are written to an XML file
-# which needs to be processed by an external indexer. Doxygen will invoke an
-# external search engine pointed to by the SEARCHENGINE_URL option to obtain the
-# search results.
-#
-# Doxygen ships with an example indexer ( doxyindexer) and search engine
-# (doxysearch.cgi) which are based on the open source search engine library
-# Xapian (see: http://xapian.org/).
-#
-# See the section "External Indexing and Searching" for details.
-# The default value is: NO.
-# This tag requires that the tag SEARCHENGINE is set to YES.
-
-EXTERNAL_SEARCH        = NO
-
-# The SEARCHENGINE_URL should point to a search engine hosted by a web server
-# which will return the search results when EXTERNAL_SEARCH is enabled.
-#
-# Doxygen ships with an example indexer ( doxyindexer) and search engine
-# (doxysearch.cgi) which are based on the open source search engine library
-# Xapian (see: http://xapian.org/). See the section "External Indexing and
-# Searching" for details.
-# This tag requires that the tag SEARCHENGINE is set to YES.
-
-SEARCHENGINE_URL       =
-
-# When SERVER_BASED_SEARCH and EXTERNAL_SEARCH are both enabled the unindexed
-# search data is written to a file for indexing by an external tool. With the
-# SEARCHDATA_FILE tag the name of this file can be specified.
-# The default file is: searchdata.xml.
-# This tag requires that the tag SEARCHENGINE is set to YES.
-
-SEARCHDATA_FILE        = searchdata.xml
-
-# When SERVER_BASED_SEARCH and EXTERNAL_SEARCH are both enabled the
-# EXTERNAL_SEARCH_ID tag can be used as an identifier for the project. This is
-# useful in combination with EXTRA_SEARCH_MAPPINGS to search through multiple
-# projects and redirect the results back to the right project.
-# This tag requires that the tag SEARCHENGINE is set to YES.
-
-EXTERNAL_SEARCH_ID     =
-
-# The EXTRA_SEARCH_MAPPINGS tag can be used to enable searching through doxygen
-# projects other than the one defined by this configuration file, but that are
-# all added to the same external search index. Each project needs to have a
-# unique id set via EXTERNAL_SEARCH_ID. The search mapping then maps the id of
-# to a relative location where the documentation can be found. The format is:
-# EXTRA_SEARCH_MAPPINGS = tagname1=loc1 tagname2=loc2 ...
-# This tag requires that the tag SEARCHENGINE is set to YES.
-
-EXTRA_SEARCH_MAPPINGS  =
-
-#---------------------------------------------------------------------------
-# Configuration options related to the LaTeX output
-#---------------------------------------------------------------------------
-
-# If the GENERATE_LATEX tag is set to YES doxygen will generate LaTeX output.
-# The default value is: YES.
-
-GENERATE_LATEX         = YES
-
-# The LATEX_OUTPUT tag is used to specify where the LaTeX docs will be put. If a
-# relative path is entered the value of OUTPUT_DIRECTORY will be put in front of
-# it.
-# The default directory is: latex.
-# This tag requires that the tag GENERATE_LATEX is set to YES.
-
-LATEX_OUTPUT           = latex
-
-# The LATEX_CMD_NAME tag can be used to specify the LaTeX command name to be
-# invoked.
-#
-# Note that when enabling USE_PDFLATEX this option is only used for generating
-# bitmaps for formulas in the HTML output, but not in the Makefile that is
-# written to the output directory.
-# The default file is: latex.
-# This tag requires that the tag GENERATE_LATEX is set to YES.
-
-LATEX_CMD_NAME         = latex
-
-# The MAKEINDEX_CMD_NAME tag can be used to specify the command name to generate
-# index for LaTeX.
-# The default file is: makeindex.
-# This tag requires that the tag GENERATE_LATEX is set to YES.
-
-MAKEINDEX_CMD_NAME     = makeindex
-
-# If the COMPACT_LATEX tag is set to YES doxygen generates more compact LaTeX
-# documents. This may be useful for small projects and may help to save some
-# trees in general.
-# The default value is: NO.
-# This tag requires that the tag GENERATE_LATEX is set to YES.
-
-COMPACT_LATEX          = NO
-
-# The PAPER_TYPE tag can be used to set the paper type that is used by the
-# printer.
-# Possible values are: a4 (210 x 297 mm), letter (8.5 x 11 inches), legal (8.5 x
-# 14 inches) and executive (7.25 x 10.5 inches).
-# The default value is: a4.
-# This tag requires that the tag GENERATE_LATEX is set to YES.
-
-PAPER_TYPE             = a4
-
-# The EXTRA_PACKAGES tag can be used to specify one or more LaTeX package names
-# that should be included in the LaTeX output. To get the times font for
-# instance you can specify
-# EXTRA_PACKAGES=times
-# If left blank no extra packages will be included.
-# This tag requires that the tag GENERATE_LATEX is set to YES.
-
-EXTRA_PACKAGES         =
-
-# The LATEX_HEADER tag can be used to specify a personal LaTeX header for the
-# generated LaTeX document. The header should contain everything until the first
-# chapter. If it is left blank doxygen will generate a standard header. See
-# section "Doxygen usage" for information on how to let doxygen write the
-# default header to a separate file.
-#
-# Note: Only use a user-defined header if you know what you are doing! The
-# following commands have a special meaning inside the header: $title,
-# $datetime, $date, $doxygenversion, $projectname, $projectnumber. Doxygen will
-# replace them by respectively the title of the page, the current date and time,
-# only the current date, the version number of doxygen, the project name (see
-# PROJECT_NAME), or the project number (see PROJECT_NUMBER).
-# This tag requires that the tag GENERATE_LATEX is set to YES.
-
-LATEX_HEADER           =
-
-# The LATEX_FOOTER tag can be used to specify a personal LaTeX footer for the
-# generated LaTeX document. The footer should contain everything after the last
-# chapter. If it is left blank doxygen will generate a standard footer.
-#
-# Note: Only use a user-defined footer if you know what you are doing!
-# This tag requires that the tag GENERATE_LATEX is set to YES.
-
-LATEX_FOOTER           =
-
-# The LATEX_EXTRA_FILES tag can be used to specify one or more extra images or
-# other source files which should be copied to the LATEX_OUTPUT output
-# directory. Note that the files will be copied as-is; there are no commands or
-# markers available.
-# This tag requires that the tag GENERATE_LATEX is set to YES.
-
-LATEX_EXTRA_FILES      =
-
-# If the PDF_HYPERLINKS tag is set to YES, the LaTeX that is generated is
-# prepared for conversion to PDF (using ps2pdf or pdflatex). The PDF file will
-# contain links (just like the HTML output) instead of page references. This
-# makes the output suitable for online browsing using a PDF viewer.
-# The default value is: YES.
-# This tag requires that the tag GENERATE_LATEX is set to YES.
-
-PDF_HYPERLINKS         = YES
-
-# If the LATEX_PDFLATEX tag is set to YES, doxygen will use pdflatex to generate
-# the PDF file directly from the LaTeX files. Set this option to YES to get a
-# higher quality PDF documentation.
-# The default value is: YES.
-# This tag requires that the tag GENERATE_LATEX is set to YES.
-
-USE_PDFLATEX           = YES
-
-# If the LATEX_BATCHMODE tag is set to YES, doxygen will add the \batchmode
-# command to the generated LaTeX files. This will instruct LaTeX to keep running
-# if errors occur, instead of asking the user for help. This option is also used
-# when generating formulas in HTML.
-# The default value is: NO.
-# This tag requires that the tag GENERATE_LATEX is set to YES.
-
-LATEX_BATCHMODE        = NO
-
-# If the LATEX_HIDE_INDICES tag is set to YES then doxygen will not include the
-# index chapters (such as File Index, Compound Index, etc.) in the output.
-# The default value is: NO.
-# This tag requires that the tag GENERATE_LATEX is set to YES.
-
-LATEX_HIDE_INDICES     = NO
-
-# If the LATEX_SOURCE_CODE tag is set to YES then doxygen will include source
-# code with syntax highlighting in the LaTeX output.
-#
-# Note that which sources are shown also depends on other settings such as
-# SOURCE_BROWSER.
-# The default value is: NO.
-# This tag requires that the tag GENERATE_LATEX is set to YES.
-
-LATEX_SOURCE_CODE      = NO
-
-# The LATEX_BIB_STYLE tag can be used to specify the style to use for the
-# bibliography, e.g. plainnat, or ieeetr. See
-# http://en.wikipedia.org/wiki/BibTeX and \cite for more info.
-# The default value is: plain.
-# This tag requires that the tag GENERATE_LATEX is set to YES.
-
-LATEX_BIB_STYLE        = plain
-
-#---------------------------------------------------------------------------
-# Configuration options related to the RTF output
-#---------------------------------------------------------------------------
-
-# If the GENERATE_RTF tag is set to YES doxygen will generate RTF output. The
-# RTF output is optimized for Word 97 and may not look too pretty with other RTF
-# readers/editors.
-# The default value is: NO.
-
-GENERATE_RTF           = NO
-
-# The RTF_OUTPUT tag is used to specify where the RTF docs will be put. If a
-# relative path is entered the value of OUTPUT_DIRECTORY will be put in front of
-# it.
-# The default directory is: rtf.
-# This tag requires that the tag GENERATE_RTF is set to YES.
-
-RTF_OUTPUT             = rtf
-
-# If the COMPACT_RTF tag is set to YES doxygen generates more compact RTF
-# documents. This may be useful for small projects and may help to save some
-# trees in general.
-# The default value is: NO.
-# This tag requires that the tag GENERATE_RTF is set to YES.
-
-COMPACT_RTF            = NO
-
-# If the RTF_HYPERLINKS tag is set to YES, the RTF that is generated will
-# contain hyperlink fields. The RTF file will contain links (just like the HTML
-# output) instead of page references. This makes the output suitable for online
-# browsing using Word or some other Word compatible readers that support those
-# fields.
-#
-# Note: WordPad (write) and others do not support links.
-# The default value is: NO.
-# This tag requires that the tag GENERATE_RTF is set to YES.
-
-RTF_HYPERLINKS         = NO
-
-# Load stylesheet definitions from file. Syntax is similar to doxygen's config
-# file, i.e. a series of assignments. You only have to provide replacements,
-# missing definitions are set to their default value.
-#
-# See also section "Doxygen usage" for information on how to generate the
-# default style sheet that doxygen normally uses.
-# This tag requires that the tag GENERATE_RTF is set to YES.
-
-RTF_STYLESHEET_FILE    =
-
-# Set optional variables used in the generation of an RTF document. Syntax is
-# similar to doxygen's config file. A template extensions file can be generated
-# using doxygen -e rtf extensionFile.
-# This tag requires that the tag GENERATE_RTF is set to YES.
-
-RTF_EXTENSIONS_FILE    =
-
-#---------------------------------------------------------------------------
-# Configuration options related to the man page output
-#---------------------------------------------------------------------------
-
-# If the GENERATE_MAN tag is set to YES doxygen will generate man pages for
-# classes and files.
-# The default value is: NO.
-
-GENERATE_MAN           = NO
-
-# The MAN_OUTPUT tag is used to specify where the man pages will be put. If a
-# relative path is entered the value of OUTPUT_DIRECTORY will be put in front of
-# it. A directory man3 will be created inside the directory specified by
-# MAN_OUTPUT.
-# The default directory is: man.
-# This tag requires that the tag GENERATE_MAN is set to YES.
-
-MAN_OUTPUT             = man
-
-# The MAN_EXTENSION tag determines the extension that is added to the generated
-# man pages. In case the manual section does not start with a number, the number
-# 3 is prepended. The dot (.) at the beginning of the MAN_EXTENSION tag is
-# optional.
-# The default value is: .3.
-# This tag requires that the tag GENERATE_MAN is set to YES.
-
-MAN_EXTENSION          = .3
-
-# If the MAN_LINKS tag is set to YES and doxygen generates man output, then it
-# will generate one additional man file for each entity documented in the real
-# man page(s). These additional files only source the real man page, but without
-# them the man command would be unable to find the correct page.
-# The default value is: NO.
-# This tag requires that the tag GENERATE_MAN is set to YES.
-
-MAN_LINKS              = NO
-
-#---------------------------------------------------------------------------
-# Configuration options related to the XML output
-#---------------------------------------------------------------------------
-
-# If the GENERATE_XML tag is set to YES doxygen will generate an XML file that
-# captures the structure of the code including all documentation.
-# The default value is: NO.
-
-GENERATE_XML           = NO
-
-# The XML_OUTPUT tag is used to specify where the XML pages will be put. If a
-# relative path is entered the value of OUTPUT_DIRECTORY will be put in front of
-# it.
-# The default directory is: xml.
-# This tag requires that the tag GENERATE_XML is set to YES.
-
-XML_OUTPUT             = xml
-
-# The XML_SCHEMA tag can be used to specify a XML schema, which can be used by a
-# validating XML parser to check the syntax of the XML files.
-# This tag requires that the tag GENERATE_XML is set to YES.
-
-XML_SCHEMA             =
-
-# The XML_DTD tag can be used to specify a XML DTD, which can be used by a
-# validating XML parser to check the syntax of the XML files.
-# This tag requires that the tag GENERATE_XML is set to YES.
-
-XML_DTD                =
-
-# If the XML_PROGRAMLISTING tag is set to YES doxygen will dump the program
-# listings (including syntax highlighting and cross-referencing information) to
-# the XML output. Note that enabling this will significantly increase the size
-# of the XML output.
-# The default value is: YES.
-# This tag requires that the tag GENERATE_XML is set to YES.
-
-XML_PROGRAMLISTING     = YES
-
-#---------------------------------------------------------------------------
-# Configuration options related to the DOCBOOK output
-#---------------------------------------------------------------------------
-
-# If the GENERATE_DOCBOOK tag is set to YES doxygen will generate Docbook files
-# that can be used to generate PDF.
-# The default value is: NO.
-
-GENERATE_DOCBOOK       = NO
-
-# The DOCBOOK_OUTPUT tag is used to specify where the Docbook pages will be put.
-# If a relative path is entered the value of OUTPUT_DIRECTORY will be put in
-# front of it.
-# The default directory is: docbook.
-# This tag requires that the tag GENERATE_DOCBOOK is set to YES.
-
-DOCBOOK_OUTPUT         = docbook
-
-#---------------------------------------------------------------------------
-# Configuration options for the AutoGen Definitions output
-#---------------------------------------------------------------------------
-
-# If the GENERATE_AUTOGEN_DEF tag is set to YES doxygen will generate an AutoGen
-# Definitions (see http://autogen.sf.net) file that captures the structure of
-# the code including all documentation. Note that this feature is still
-# experimental and incomplete at the moment.
-# The default value is: NO.
-
-GENERATE_AUTOGEN_DEF   = NO
-
-#---------------------------------------------------------------------------
-# Configuration options related to the Perl module output
-#---------------------------------------------------------------------------
-
-# If the GENERATE_PERLMOD tag is set to YES doxygen will generate a Perl module
-# file that captures the structure of the code including all documentation.
-#
-# Note that this feature is still experimental and incomplete at the moment.
-# The default value is: NO.
-
-GENERATE_PERLMOD       = NO
-
-# If the PERLMOD_LATEX tag is set to YES doxygen will generate the necessary
-# Makefile rules, Perl scripts and LaTeX code to be able to generate PDF and DVI
-# output from the Perl module output.
-# The default value is: NO.
-# This tag requires that the tag GENERATE_PERLMOD is set to YES.
-
-PERLMOD_LATEX          = NO
-
-# If the PERLMOD_PRETTY tag is set to YES the Perl module output will be nicely
-# formatted so it can be parsed by a human reader. This is useful if you want to
-# understand what is going on. On the other hand, if this tag is set to NO the
-# size of the Perl module output will be much smaller and Perl will parse it
-# just the same.
-# The default value is: YES.
-# This tag requires that the tag GENERATE_PERLMOD is set to YES.
-
-PERLMOD_PRETTY         = YES
-
-# The names of the make variables in the generated doxyrules.make file are
-# prefixed with the string contained in PERLMOD_MAKEVAR_PREFIX. This is useful
-# so different doxyrules.make files included by the same Makefile don't
-# overwrite each other's variables.
-# This tag requires that the tag GENERATE_PERLMOD is set to YES.
-
-PERLMOD_MAKEVAR_PREFIX =
-
-#---------------------------------------------------------------------------
-# Configuration options related to the preprocessor
-#---------------------------------------------------------------------------
-
-# If the ENABLE_PREPROCESSING tag is set to YES doxygen will evaluate all
-# C-preprocessor directives found in the sources and include files.
-# The default value is: YES.
-
-ENABLE_PREPROCESSING   = YES
-
-# If the MACRO_EXPANSION tag is set to YES doxygen will expand all macro names
-# in the source code. If set to NO only conditional compilation will be
-# performed. Macro expansion can be done in a controlled way by setting
-# EXPAND_ONLY_PREDEF to YES.
-# The default value is: NO.
-# This tag requires that the tag ENABLE_PREPROCESSING is set to YES.
-
-MACRO_EXPANSION        = NO
-
-# If the EXPAND_ONLY_PREDEF and MACRO_EXPANSION tags are both set to YES then
-# the macro expansion is limited to the macros specified with the PREDEFINED and
-# EXPAND_AS_DEFINED tags.
-# The default value is: NO.
-# This tag requires that the tag ENABLE_PREPROCESSING is set to YES.
-
-EXPAND_ONLY_PREDEF     = NO
-
-# If the SEARCH_INCLUDES tag is set to YES the includes files in the
-# INCLUDE_PATH will be searched if a #include is found.
-# The default value is: YES.
-# This tag requires that the tag ENABLE_PREPROCESSING is set to YES.
-
-SEARCH_INCLUDES        = YES
-
-# The INCLUDE_PATH tag can be used to specify one or more directories that
-# contain include files that are not input files but should be processed by the
-# preprocessor.
-# This tag requires that the tag SEARCH_INCLUDES is set to YES.
-
-INCLUDE_PATH           =
-
-# You can use the INCLUDE_FILE_PATTERNS tag to specify one or more wildcard
-# patterns (like *.h and *.hpp) to filter out the header-files in the
-# directories. If left blank, the patterns specified with FILE_PATTERNS will be
-# used.
-# This tag requires that the tag ENABLE_PREPROCESSING is set to YES.
-
-INCLUDE_FILE_PATTERNS  =
-
-# The PREDEFINED tag can be used to specify one or more macro names that are
-# defined before the preprocessor is started (similar to the -D option of e.g.
-# gcc). The argument of the tag is a list of macros of the form: name or
-# name=definition (no spaces). If the definition and the "=" are omitted, "=1"
-# is assumed. To prevent a macro definition from being undefined via #undef or
-# recursively expanded use the := operator instead of the = operator.
-# This tag requires that the tag ENABLE_PREPROCESSING is set to YES.
-
-PREDEFINED             =
-
-# If the MACRO_EXPANSION and EXPAND_ONLY_PREDEF tags are set to YES then this
-# tag can be used to specify a list of macro names that should be expanded. The
-# macro definition that is found in the sources will be used. Use the PREDEFINED
-# tag if you want to use a different macro definition that overrules the
-# definition found in the source code.
-# This tag requires that the tag ENABLE_PREPROCESSING is set to YES.
-
-EXPAND_AS_DEFINED      =
-
-# If the SKIP_FUNCTION_MACROS tag is set to YES then doxygen's preprocessor will
-# remove all references to function-like macros that are alone on a line, have an
-# all uppercase name, and do not end with a semicolon. Such function macros are
-# typically used for boiler-plate code, and will confuse the parser if not
-# removed.
-# The default value is: YES.
-# This tag requires that the tag ENABLE_PREPROCESSING is set to YES.
-
-SKIP_FUNCTION_MACROS   = YES
-
-#---------------------------------------------------------------------------
-# Configuration options related to external references
-#---------------------------------------------------------------------------
-
-# The TAGFILES tag can be used to specify one or more tag files. For each tag
-# file the location of the external documentation should be added. The format of
-# a tag file without this location is as follows:
-# TAGFILES = file1 file2 ...
-# Adding location for the tag files is done as follows:
-# TAGFILES = file1=loc1 "file2 = loc2" ...
-# where loc1 and loc2 can be relative or absolute paths or URLs. See the
-# section "Linking to external documentation" for more information about the use
-# of tag files.
-# Note: Each tag file must have an unique name (where the name does NOT include
-# the path). If a tag file is not located in the directory in which doxygen is
-# run, you must also specify the path to the tagfile here.
-
-TAGFILES               =
-
-# When a file name is specified after GENERATE_TAGFILE, doxygen will create a
-# tag file that is based on the input files it reads. See section "Linking to
-# external documentation" for more information about the usage of tag files.
-
-GENERATE_TAGFILE       =
-
-# If the ALLEXTERNALS tag is set to YES all external class will be listed in the
-# class index. If set to NO only the inherited external classes will be listed.
-# The default value is: NO.
-
-ALLEXTERNALS           = NO
-
-# If the EXTERNAL_GROUPS tag is set to YES all external groups will be listed in
-# the modules index. If set to NO, only the current project's groups will be
-# listed.
-# The default value is: YES.
-
-EXTERNAL_GROUPS        = YES
-
-# If the EXTERNAL_PAGES tag is set to YES all external pages will be listed in
-# the related pages index. If set to NO, only the current project's pages will
-# be listed.
-# The default value is: YES.
-
-EXTERNAL_PAGES         = YES
-
-# The PERL_PATH should be the absolute path and name of the perl script
-# interpreter (i.e. the result of 'which perl').
-# The default file (with absolute path) is: /usr/bin/perl.
-
-PERL_PATH              = /usr/bin/perl
-
-#---------------------------------------------------------------------------
-# Configuration options related to the dot tool
-#---------------------------------------------------------------------------
-
-# If the CLASS_DIAGRAMS tag is set to YES doxygen will generate a class diagram
-# (in HTML and LaTeX) for classes with base or super classes. Setting the tag to
-# NO turns the diagrams off. Note that this option also works with HAVE_DOT
-# disabled, but it is recommended to install and use dot, since it yields more
-# powerful graphs.
-# The default value is: YES.
-
-CLASS_DIAGRAMS         = YES
-
-# You can define message sequence charts within doxygen comments using the \msc
-# command. Doxygen will then run the mscgen tool (see:
-# http://www.mcternan.me.uk/mscgen/)) to produce the chart and insert it in the
-# documentation. The MSCGEN_PATH tag allows you to specify the directory where
-# the mscgen tool resides. If left empty the tool is assumed to be found in the
-# default search path.
-
-MSCGEN_PATH            =
-
-# You can include diagrams made with dia in doxygen documentation. Doxygen will
-# then run dia to produce the diagram and insert it in the documentation. The
-# DIA_PATH tag allows you to specify the directory where the dia binary resides.
-# If left empty dia is assumed to be found in the default search path.
-
-DIA_PATH               =
-
-# If set to YES, the inheritance and collaboration graphs will hide inheritance
-# and usage relations if the target is undocumented or is not a class.
-# The default value is: YES.
-
-HIDE_UNDOC_RELATIONS   = YES
-
-# If you set the HAVE_DOT tag to YES then doxygen will assume the dot tool is
-# available from the path. This tool is part of Graphviz (see:
-# http://www.graphviz.org/), a graph visualization toolkit from AT&T and Lucent
-# Bell Labs. The other options in this section have no effect if this option is
-# set to NO
-# The default value is: NO.
-
-HAVE_DOT               = NO
-
-# The DOT_NUM_THREADS specifies the number of dot invocations doxygen is allowed
-# to run in parallel. When set to 0 doxygen will base this on the number of
-# processors available in the system. You can set it explicitly to a value
-# larger than 0 to get control over the balance between CPU load and processing
-# speed.
-# Minimum value: 0, maximum value: 32, default value: 0.
-# This tag requires that the tag HAVE_DOT is set to YES.
-
-DOT_NUM_THREADS        = 0
-
-# When you want a differently looking font n the dot files that doxygen
-# generates you can specify the font name using DOT_FONTNAME. You need to make
-# sure dot is able to find the font, which can be done by putting it in a
-# standard location or by setting the DOTFONTPATH environment variable or by
-# setting DOT_FONTPATH to the directory containing the font.
-# The default value is: Helvetica.
-# This tag requires that the tag HAVE_DOT is set to YES.
-
-DOT_FONTNAME           = Helvetica
-
-# The DOT_FONTSIZE tag can be used to set the size (in points) of the font of
-# dot graphs.
-# Minimum value: 4, maximum value: 24, default value: 10.
-# This tag requires that the tag HAVE_DOT is set to YES.
-
-DOT_FONTSIZE           = 10
-
-# By default doxygen will tell dot to use the default font as specified with
-# DOT_FONTNAME. If you specify a different font using DOT_FONTNAME you can set
-# the path where dot can find it using this tag.
-# This tag requires that the tag HAVE_DOT is set to YES.
-
-DOT_FONTPATH           =
-
-# If the CLASS_GRAPH tag is set to YES then doxygen will generate a graph for
-# each documented class showing the direct and indirect inheritance relations.
-# Setting this tag to YES will force the CLASS_DIAGRAMS tag to NO.
-# The default value is: YES.
-# This tag requires that the tag HAVE_DOT is set to YES.
-
-CLASS_GRAPH            = YES
-
-# If the COLLABORATION_GRAPH tag is set to YES then doxygen will generate a
-# graph for each documented class showing the direct and indirect implementation
-# dependencies (inheritance, containment, and class references variables) of the
-# class with other documented classes.
-# The default value is: YES.
-# This tag requires that the tag HAVE_DOT is set to YES.
-
-COLLABORATION_GRAPH    = YES
-
-# If the GROUP_GRAPHS tag is set to YES then doxygen will generate a graph for
-# groups, showing the direct groups dependencies.
-# The default value is: YES.
-# This tag requires that the tag HAVE_DOT is set to YES.
-
-GROUP_GRAPHS           = YES
-
-# If the UML_LOOK tag is set to YES doxygen will generate inheritance and
-# collaboration diagrams in a style similar to the OMG's Unified Modeling
-# Language.
-# The default value is: NO.
-# This tag requires that the tag HAVE_DOT is set to YES.
-
-UML_LOOK               = NO
-
-# If the UML_LOOK tag is enabled, the fields and methods are shown inside the
-# class node. If there are many fields or methods and many nodes the graph may
-# become too big to be useful. The UML_LIMIT_NUM_FIELDS threshold limits the
-# number of items for each type to make the size more manageable. Set this to 0
-# for no limit. Note that the threshold may be exceeded by 50% before the limit
-# is enforced. So when you set the threshold to 10, up to 15 fields may appear,
-# but if the number exceeds 15, the total amount of fields shown is limited to
-# 10.
-# Minimum value: 0, maximum value: 100, default value: 10.
-# This tag requires that the tag HAVE_DOT is set to YES.
-
-UML_LIMIT_NUM_FIELDS   = 10
-
-# If the TEMPLATE_RELATIONS tag is set to YES then the inheritance and
-# collaboration graphs will show the relations between templates and their
-# instances.
-# The default value is: NO.
-# This tag requires that the tag HAVE_DOT is set to YES.
-
-TEMPLATE_RELATIONS     = NO
-
-# If the INCLUDE_GRAPH, ENABLE_PREPROCESSING and SEARCH_INCLUDES tags are set to
-# YES then doxygen will generate a graph for each documented file showing the
-# direct and indirect include dependencies of the file with other documented
-# files.
-# The default value is: YES.
-# This tag requires that the tag HAVE_DOT is set to YES.
-
-INCLUDE_GRAPH          = YES
-
-# If the INCLUDED_BY_GRAPH, ENABLE_PREPROCESSING and SEARCH_INCLUDES tags are
-# set to YES then doxygen will generate a graph for each documented file showing
-# the direct and indirect include dependencies of the file with other documented
-# files.
-# The default value is: YES.
-# This tag requires that the tag HAVE_DOT is set to YES.
-
-INCLUDED_BY_GRAPH      = YES
-
-# If the CALL_GRAPH tag is set to YES then doxygen will generate a call
-# dependency graph for every global function or class method.
-#
-# Note that enabling this option will significantly increase the time of a run.
-# So in most cases it will be better to enable call graphs for selected
-# functions only using the \callgraph command.
-# The default value is: NO.
-# This tag requires that the tag HAVE_DOT is set to YES.
-
-CALL_GRAPH             = NO
-
-# If the CALLER_GRAPH tag is set to YES then doxygen will generate a caller
-# dependency graph for every global function or class method.
-#
-# Note that enabling this option will significantly increase the time of a run.
-# So in most cases it will be better to enable caller graphs for selected
-# functions only using the \callergraph command.
-# The default value is: NO.
-# This tag requires that the tag HAVE_DOT is set to YES.
-
-CALLER_GRAPH           = NO
-
-# If the GRAPHICAL_HIERARCHY tag is set to YES then doxygen will graphical
-# hierarchy of all classes instead of a textual one.
-# The default value is: YES.
-# This tag requires that the tag HAVE_DOT is set to YES.
-
-GRAPHICAL_HIERARCHY    = YES
-
-# If the DIRECTORY_GRAPH tag is set to YES then doxygen will show the
-# dependencies a directory has on other directories in a graphical way. The
-# dependency relations are determined by the #include relations between the
-# files in the directories.
-# The default value is: YES.
-# This tag requires that the tag HAVE_DOT is set to YES.
-
-DIRECTORY_GRAPH        = YES
-
-# The DOT_IMAGE_FORMAT tag can be used to set the image format of the images
-# generated by dot.
-# Note: If you choose svg you need to set HTML_FILE_EXTENSION to xhtml in order
-# to make the SVG files visible in IE 9+ (other browsers do not have this
-# requirement).
-# Possible values are: png, jpg, gif and svg.
-# The default value is: png.
-# This tag requires that the tag HAVE_DOT is set to YES.
-
-DOT_IMAGE_FORMAT       = png
-
-# If DOT_IMAGE_FORMAT is set to svg, then this option can be set to YES to
-# enable generation of interactive SVG images that allow zooming and panning.
-#
-# Note that this requires a modern browser other than Internet Explorer. Tested
-# and working are Firefox, Chrome, Safari, and Opera.
-# Note: For IE 9+ you need to set HTML_FILE_EXTENSION to xhtml in order to make
-# the SVG files visible. Older versions of IE do not have SVG support.
-# The default value is: NO.
-# This tag requires that the tag HAVE_DOT is set to YES.
-
-INTERACTIVE_SVG        = NO
-
-# The DOT_PATH tag can be used to specify the path where the dot tool can be
-# found. If left blank, it is assumed the dot tool can be found in the path.
-# This tag requires that the tag HAVE_DOT is set to YES.
-
-DOT_PATH               =
-
-# The DOTFILE_DIRS tag can be used to specify one or more directories that
-# contain dot files that are included in the documentation (see the \dotfile
-# command).
-# This tag requires that the tag HAVE_DOT is set to YES.
-
-DOTFILE_DIRS           =
-
-# The MSCFILE_DIRS tag can be used to specify one or more directories that
-# contain msc files that are included in the documentation (see the \mscfile
-# command).
-
-MSCFILE_DIRS           =
-
-# The DIAFILE_DIRS tag can be used to specify one or more directories that
-# contain dia files that are included in the documentation (see the \diafile
-# command).
-
-DIAFILE_DIRS           =
-
-# The DOT_GRAPH_MAX_NODES tag can be used to set the maximum number of nodes
-# that will be shown in the graph. If the number of nodes in a graph becomes
-# larger than this value, doxygen will truncate the graph, which is visualized
-# by representing a node as a red box. Note that doxygen if the number of direct
-# children of the root node in a graph is already larger than
-# DOT_GRAPH_MAX_NODES then the graph will not be shown at all. Also note that
-# the size of a graph can be further restricted by MAX_DOT_GRAPH_DEPTH.
-# Minimum value: 0, maximum value: 10000, default value: 50.
-# This tag requires that the tag HAVE_DOT is set to YES.
-
-DOT_GRAPH_MAX_NODES    = 50
-
-# The MAX_DOT_GRAPH_DEPTH tag can be used to set the maximum depth of the graphs
-# generated by dot. A depth value of 3 means that only nodes reachable from the
-# root by following a path via at most 3 edges will be shown. Nodes that lay
-# further from the root node will be omitted. Note that setting this option to 1
-# or 2 may greatly reduce the computation time needed for large code bases. Also
-# note that the size of a graph can be further restricted by
-# DOT_GRAPH_MAX_NODES. Using a depth of 0 means no depth restriction.
-# Minimum value: 0, maximum value: 1000, default value: 0.
-# This tag requires that the tag HAVE_DOT is set to YES.
-
-MAX_DOT_GRAPH_DEPTH    = 0
-
-# Set the DOT_TRANSPARENT tag to YES to generate images with a transparent
-# background. This is disabled by default, because dot on Windows does not seem
-# to support this out of the box.
-#
-# Warning: Depending on the platform used, enabling this option may lead to
-# badly anti-aliased labels on the edges of a graph (i.e. they become hard to
-# read).
-# The default value is: NO.
-# This tag requires that the tag HAVE_DOT is set to YES.
-
-DOT_TRANSPARENT        = NO
-
-# Set the DOT_MULTI_TARGETS tag to YES allow dot to generate multiple output
-# files in one run (i.e. multiple -o and -T options on the command line). This
-# makes dot run faster, but since only newer versions of dot (>1.8.10) support
-# this, this feature is disabled by default.
-# The default value is: NO.
-# This tag requires that the tag HAVE_DOT is set to YES.
-
-DOT_MULTI_TARGETS      = YES
-
-# If the GENERATE_LEGEND tag is set to YES doxygen will generate a legend page
-# explaining the meaning of the various boxes and arrows in the dot generated
-# graphs.
-# The default value is: YES.
-# This tag requires that the tag HAVE_DOT is set to YES.
-
-GENERATE_LEGEND        = YES
-
-# If the DOT_CLEANUP tag is set to YES doxygen will remove the intermediate dot
-# files that are used to generate the various graphs.
-# The default value is: YES.
-# This tag requires that the tag HAVE_DOT is set to YES.
-
-DOT_CLEANUP            = YES
diff --git a/third_party/allwpilib/simulation/frc_gazebo_plugins/scripts/frcgazebo b/third_party/allwpilib/simulation/frc_gazebo_plugins/scripts/frcgazebo
deleted file mode 100644
index d0e9a75..0000000
--- a/third_party/allwpilib/simulation/frc_gazebo_plugins/scripts/frcgazebo
+++ /dev/null
@@ -1,63 +0,0 @@
-#!/bin/bash
-#---------------------------------------------------------------------------
-# Copyright (c) 2018 FIRST. All Rights Reserved.
-# Open Source Software - may be modified and shared by FRC teams. The code
-# must be accompanied by the FIRST BSD license file in the root directory of
-# the project.
-#----------------------------------------------------------------------------
-
-#----------------------------------------------------------------------------
-#  Invoke gazebo, giving it the environment variables
-#   it needs to find the FRC plugins and models.
-#----------------------------------------------------------------------------
-usage() {
-    echo $1:  Invoke Gazebo for FRC
-    echo Usage:
-    echo "  $1 name-of-world-file"
-}
-
-d=`dirname "$0"`
-fulldir=`(cd "$d"; pwd)`
-sharedir=/usr/share/frcgazebo
-if [ -d "$fulldir/../share" ] ; then
-    sharedir=`(cd "$fulldir/../share/frcgazebo"; pwd)`
-fi
-
-# While we wait for the frc gazebo models to have a proper
-#  home, we require the user to make them accessible
-if [ ! -d "$sharedir" ] ; then
-    cravedir=`(cd "$fulldir/../"; pwd)`
-    echo Error: you must manually place the models and world into $cravedir/share/frcgazebo
-    exit 2
-fi
-
-libsdir=/invalid/directory
-if [ -d "$fulldir/../libs" ] ; then
-    libsdir=`(cd "$fulldir/../libs"; pwd)`
-fi
-
-#  Use exactly the file they gave us, or find it in ../share/frcgazebo/worlds,
-#    or find it there by adding a .world extension
-world="$1"
-if [ ! -f "$world" ] ; then
-    world="$sharedir/worlds/$1"
-fi
-if [ ! -f "$world" ] ; then
-    world="$sharedir/worlds/$1.world"
-fi
-
-if [ $# -ne 1 -o "x${1:0:1}" = "x-" ] ; then
-    usage `basename $0`
-    exit 1
-fi
-if [ ! -f "$world" ] ; then
-    echo Could not find $1 directly or in $sharedir/worlds
-    exit 2
-fi
-
-export GAZEBO_MODEL_PATH="$sharedir/models":$GAZEBO_MODEL_PATH
-for x in `find "$libsdir" -type d -name shared` ; do
-    export GAZEBO_PLUGIN_PATH="$x:$GAZEBO_PLUGIN_PATH"
-done
-
-gazebo "$world"
diff --git a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/clock/cpp/clock.cpp b/third_party/allwpilib/simulation/frc_gazebo_plugins/src/clock/cpp/clock.cpp
deleted file mode 100644
index d588708..0000000
--- a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/clock/cpp/clock.cpp
+++ /dev/null
@@ -1,41 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "clock.h"
-
-#include <boost/algorithm/string/replace.hpp>
-
-GZ_REGISTER_MODEL_PLUGIN(Clock)
-
-void Clock::Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf) {
-  this->model = model;
-
-  // Parse SDF properties
-  if (sdf->HasElement("topic")) {
-    topic = sdf->Get<std::string>("topic");
-  } else {
-    topic = "~/" + sdf->GetAttribute("name")->GetAsString();
-  }
-
-  gzmsg << "Initializing clock: " << topic << std::endl;
-
-  // Connect to Gazebo transport for messaging
-  std::string scoped_name =
-      model->GetWorld()->Name() + "::" + model->GetScopedName();
-  boost::replace_all(scoped_name, "::", "/");
-  node = gazebo::transport::NodePtr(new gazebo::transport::Node());
-  node->Init(scoped_name);
-  pub = node->Advertise<gazebo::msgs::Float64>(topic);
-
-  // Connect to the world update event.
-  // This will trigger the Update function every Gazebo iteration
-  updateConn = gazebo::event::Events::ConnectWorldUpdateBegin(
-      boost::bind(&Clock::Update, this, _1));
-}
-
-void Clock::Update(const gazebo::common::UpdateInfo& info) {
-  gazebo::msgs::Float64 msg;
-  msg.set_data(info.simTime.Double());
-  pub->Publish(msg);
-}
diff --git a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/clock/headers/clock.h b/third_party/allwpilib/simulation/frc_gazebo_plugins/src/clock/headers/clock.h
deleted file mode 100644
index 3ff7d12..0000000
--- a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/clock/headers/clock.h
+++ /dev/null
@@ -1,55 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <string>
-
-#include <gazebo/gazebo.hh>
-#include <gazebo/physics/physics.hh>
-#include <gazebo/transport/transport.hh>
-
-#include "simulation/gz_msgs/msgs.h"
-
-/**
- * \brief Plugin for publishing the simulation time.
- *
- * This plugin publishes the simualtaion time in seconds every physics
- * update.
- *
- * To add a clock to your robot, add the following XML to your robot
- * model:
- *
- *     <plugin name="my_clock" filename="libclock.so">
- *       <topic>~/my/topic</topic>
- *     </plugin>
- *
- * - `topic`: Optional. Message will be published as a gazebo.msgs.Float64.
- *
- * \todo Make WorldPlugin?
- */
-class Clock : public gazebo::ModelPlugin {
- public:
-  /// \brief Load the clock and configures it according to the sdf.
-  void Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf);
-
-  /// \brief Sends out time each timestep.
-  void Update(const gazebo::common::UpdateInfo& info);
-
- private:
-  /// \brief Publish the time on this topic.
-  std::string topic;
-
-  /// \brief The model to which this is attached.
-  gazebo::physics::ModelPtr model;
-
-  /// \brief Pointer to the world update function.
-  gazebo::event::ConnectionPtr updateConn;
-
-  /// \brief The node on which we're advertising.
-  gazebo::transport::NodePtr node;
-
-  /// \brief Publisher handle.
-  gazebo::transport::PublisherPtr pub;
-};
diff --git a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/clockTest/cpp/ClockTest.cpp b/third_party/allwpilib/simulation/frc_gazebo_plugins/src/clockTest/cpp/ClockTest.cpp
deleted file mode 100644
index 84bde78..0000000
--- a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/clockTest/cpp/ClockTest.cpp
+++ /dev/null
@@ -1,78 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include <simulation/gz_msgs/msgs.h>
-
-#include <gazebo/gazebo.hh>
-#include <gazebo/gazebo_client.hh>
-#include <gazebo/msgs/msgs.hh>
-#include <gazebo/sensors/sensors.hh>
-#include <gazebo/transport/transport.hh>
-
-#include "gtest/gtest.h"
-
-using namespace testing;
-
-static char* library;
-static char* world_sdf;
-static double latest_time;
-
-void cb(gazebo::msgs::ConstFloat64Ptr& msg) {
-  latest_time = msg->data();
-}
-
-TEST(ClockTest, Clock) {
-  gazebo::physics::WorldPtr world;
-
-  ASSERT_TRUE(library);
-  ASSERT_TRUE(!access(library, X_OK | R_OK));
-  ASSERT_TRUE(world_sdf);
-  ASSERT_TRUE(!access(world_sdf, R_OK));
-
-  gazebo::addPlugin(library);
-  ASSERT_TRUE(gazebo::setupServer());
-
-  world = gazebo::loadWorld(world_sdf);
-  ASSERT_TRUE(world != NULL);
-
-  ASSERT_TRUE(gazebo::client::setup());
-
-  gazebo::transport::NodePtr node(new gazebo::transport::Node());
-  node->Init();
-
-  gazebo::transport::SubscriberPtr sub =
-      node->Subscribe("/gazebo/frc/time", cb);
-
-  gazebo::sensors::run_once(true);
-  gazebo::sensors::run_threads();
-  gazebo::common::Time::MSleep(1);
-
-  double start = latest_time;
-
-  for (unsigned int i = 0; i < 1000; ++i) {
-    gazebo::runWorld(world, 1);
-    gazebo::sensors::run_once();
-    gazebo::common::Time::MSleep(1);
-  }
-
-  double end = latest_time;
-
-  ASSERT_TRUE(end > start);
-  ASSERT_TRUE(gazebo::client::shutdown());
-  ASSERT_TRUE(gazebo::shutdown());
-}
-
-int main(int argc, char** argv) {
-  testing::InitGoogleTest(&argc, argv);
-
-  if (argc >= 1) {
-    library = argv[1];
-  }
-
-  if (argc >= 2) {
-    world_sdf = argv[2];
-  }
-
-  return RUN_ALL_TESTS();
-}
diff --git a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/clockTest/world/clockTest.world b/third_party/allwpilib/simulation/frc_gazebo_plugins/src/clockTest/world/clockTest.world
deleted file mode 100644
index e6f7cfd..0000000
--- a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/clockTest/world/clockTest.world
+++ /dev/null
@@ -1,17 +0,0 @@
-<?xml version="1.0" ?>
-<sdf version="1.5">
-    <world name="default">
-        <scene>
-            <ambient>0.2 0.2 0.2 1</ambient>
-            <background>1 1 1 1</background>
-            <shadows>false</shadows>
-            <grid>false</grid>
-            <origin_visual>false</origin_visual>
-        </scene>
-        <model name='Clock'>
-            <plugin name='clock' filename='libclock.so'>
-                <topic>/gazebo/frc/time</topic>
-            </plugin>
-        </model>
-    </world>
-</sdf>
diff --git a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/dc_motor/cpp/dc_motor.cpp b/third_party/allwpilib/simulation/frc_gazebo_plugins/src/dc_motor/cpp/dc_motor.cpp
deleted file mode 100644
index 7951dfc..0000000
--- a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/dc_motor/cpp/dc_motor.cpp
+++ /dev/null
@@ -1,57 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "dc_motor.h"
-
-#include <boost/algorithm/string/replace.hpp>
-
-GZ_REGISTER_MODEL_PLUGIN(DCMotor)
-
-void DCMotor::Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf) {
-  this->model = model;
-  signal = 0;
-
-  // Parse SDF properties
-  joint = model->GetJoint(sdf->Get<std::string>("joint"));
-  if (sdf->HasElement("topic")) {
-    topic = sdf->Get<std::string>("topic");
-  } else {
-    topic = "~/" + sdf->GetAttribute("name")->GetAsString();
-  }
-
-  if (sdf->HasElement("multiplier")) {
-    multiplier = sdf->Get<double>("multiplier");
-  } else {
-    multiplier = 1;
-  }
-
-  gzmsg << "Initializing motor: " << topic << " joint=" << joint->GetName()
-        << " multiplier=" << multiplier << std::endl;
-
-  // Connect to Gazebo transport for messaging
-  std::string scoped_name =
-      model->GetWorld()->Name() + "::" + model->GetScopedName();
-  boost::replace_all(scoped_name, "::", "/");
-  node = gazebo::transport::NodePtr(new gazebo::transport::Node());
-  node->Init(scoped_name);
-  sub = node->Subscribe(topic, &DCMotor::Callback, this);
-
-  // Connect to the world update event.
-  // This will trigger the Update function every Gazebo iteration
-  updateConn = gazebo::event::Events::ConnectWorldUpdateBegin(
-      boost::bind(&DCMotor::Update, this, _1));
-}
-
-void DCMotor::Update(const gazebo::common::UpdateInfo& info) {
-  joint->SetForce(0, signal * multiplier);
-}
-
-void DCMotor::Callback(const gazebo::msgs::ConstFloat64Ptr& msg) {
-  signal = msg->data();
-  if (signal < -1) {
-    signal = -1;
-  } else if (signal > 1) {
-    signal = 1;
-  }
-}
diff --git a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/dc_motor/headers/dc_motor.h b/third_party/allwpilib/simulation/frc_gazebo_plugins/src/dc_motor/headers/dc_motor.h
deleted file mode 100644
index 44440ac..0000000
--- a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/dc_motor/headers/dc_motor.h
+++ /dev/null
@@ -1,70 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <string>
-
-#include <gazebo/gazebo.hh>
-#include <gazebo/physics/physics.hh>
-#include <gazebo/transport/transport.hh>
-
-#include "simulation/gz_msgs/msgs.h"
-
-/**
- * \brief Plugin for controlling a joint with a DC motor.
- *
- * This plugin subscribes to a topic to get a signal in the range
- * [-1,1]. Every physics update the joint's torque is set as
- * multiplier*signal.
- *
- * To add a DC motor to your robot, add the following XML to your
- * robot model:
- *
- *     <plugin name="my_motor" filename="libdc_motor.so">
- *       <joint>Joint Name</joint>
- *       <topic>~/my/topic</topic>
- *       <multiplier>Number</multiplier>
- *     </plugin>
- *
- * - `joint`: Name of the joint this Dc motor is attached to.
- * - `topic`: Optional. Message type should be gazebo.msgs.Float64.
- * - `multiplier`: Optional. Defaults to 1.
- */
-class DCMotor : public gazebo::ModelPlugin {
- public:
-  /// \brief Load the dc motor and configures it according to the sdf.
-  void Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf);
-
-  /// \brief Update the torque on the joint from the dc motor each timestep.
-  void Update(const gazebo::common::UpdateInfo& info);
-
- private:
-  /// \brief Topic to read control signal from.
-  std::string topic;
-
-  /// \brief The pwm signal limited to the range [-1,1].
-  double signal;
-
-  /// \brief The magic torque multiplier. torque=multiplier*signal
-  double multiplier;
-
-  /// \brief The joint that this dc motor drives.
-  gazebo::physics::JointPtr joint;
-
-  /// \brief Callback for receiving msgs and storing the signal.
-  void Callback(const gazebo::msgs::ConstFloat64Ptr& msg);
-
-  /// \brief The model to which this is attached.
-  gazebo::physics::ModelPtr model;
-
-  /// \brief Pointer toe the world update function.
-  gazebo::event::ConnectionPtr updateConn;
-
-  /// \brief The node on which we're advertising.
-  gazebo::transport::NodePtr node;
-
-  /// \brief Subscriber handle.
-  gazebo::transport::SubscriberPtr sub;
-};
diff --git a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/drive_motor/cpp/drive_motor.cpp b/third_party/allwpilib/simulation/frc_gazebo_plugins/src/drive_motor/cpp/drive_motor.cpp
deleted file mode 100644
index 01679e9..0000000
--- a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/drive_motor/cpp/drive_motor.cpp
+++ /dev/null
@@ -1,134 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "drive_motor.h"
-
-#include <boost/algorithm/string/replace.hpp>
-
-GZ_REGISTER_MODEL_PLUGIN(DriveMotor)
-
-void DriveMotor::Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf) {
-  this->model = model;
-  signal = 0;
-
-  // Parse SDF properties
-  joint = model->GetJoint(sdf->Get<std::string>("joint"));
-  if (!joint) {
-    gzerr << "Error initializing drive motor: could not get joint";
-    return;
-  }
-
-  parent = joint->GetParent();
-  if (!parent) {
-    gzerr << "Error initializing drive motor: could not get parent";
-    return;
-  }
-
-  child = joint->GetChild();
-  if (!child) {
-    gzerr << "Error initializing drive motor: could not get child";
-    return;
-  }
-
-  if (sdf->HasElement("topic")) {
-    topic = sdf->Get<std::string>("topic");
-  } else {
-    topic = "~/" + sdf->GetAttribute("name")->GetAsString();
-  }
-
-  if (sdf->HasElement("max_speed")) {
-    maxSpeed = sdf->Get<double>("max_speed");
-  } else {
-    maxSpeed = 0;
-  }
-
-  if (sdf->HasElement("multiplier")) {
-    multiplier = sdf->Get<double>("multiplier");
-  } else {
-    multiplier = 1;
-  }
-
-  if (sdf->HasElement("dx")) {
-    dx = sdf->Get<double>("dx");
-  } else {
-    dx = 0;
-  }
-
-  if (sdf->HasElement("dy")) {
-    dy = sdf->Get<double>("dy");
-  } else {
-    dy = 0;
-  }
-
-  if (sdf->HasElement("dz")) {
-    dz = sdf->Get<double>("dz");
-  } else {
-    dz = 0;
-  }
-
-  gzmsg << "Initializing drive motor: " << topic
-        << " parent=" << parent->GetName() << " directions=" << dx << " " << dy
-        << " " << dz << " multiplier=" << multiplier << std::endl;
-
-  // Connect to Gazebo transport for messaging
-  std::string scoped_name =
-      model->GetWorld()->Name() + "::" + model->GetScopedName();
-  boost::replace_all(scoped_name, "::", "/");
-  node = gazebo::transport::NodePtr(new gazebo::transport::Node());
-  node->Init(scoped_name);
-  sub = node->Subscribe(topic, &DriveMotor::Callback, this);
-
-  // Connect to the world update event.
-  // This will trigger the Update function every Gazebo iteration
-  updateConn = gazebo::event::Events::ConnectWorldUpdateBegin(
-      boost::bind(&DriveMotor::Update, this, _1));
-}
-
-static double computeForce(double input, double velocity, double max) {
-  double output = input;
-  if (max == 0.0) {
-    return output;
-  }
-  if (std::fabs(velocity) >= max) {
-    output = 0;
-  } else {
-    double reduce = (max - std::fabs(velocity)) / max;
-    output *= reduce;
-  }
-  return output;
-}
-
-void DriveMotor::Update(const gazebo::common::UpdateInfo& info) {
-#if GAZEBO_MAJOR_VERSION >= 8
-  ignition::math::Vector3d velocity = parent->RelativeLinearVel();
-#else
-  ignition::math::Vector3d velocity = parent->GetRelativeLinearVel().Ign();
-#endif
-
-  if (signal == 0)
-    return;
-
-  double x = computeForce(signal * dx * multiplier, velocity.X(),
-                          std::fabs(maxSpeed * dx));
-  double y = computeForce(signal * dy * multiplier, velocity.Y(),
-                          std::fabs(maxSpeed * dy));
-  double z = computeForce(signal * dz * multiplier, velocity.Z(),
-                          std::fabs(maxSpeed * dz));
-
-  ignition::math::Vector3d force(x, y, z);
-#if GAZEBO_MAJOR_VERSION >= 8
-  parent->AddLinkForce(force, child->RelativePose().Pos());
-#else
-  parent->AddLinkForce(force, child->GetRelativePose().Ign().Pos());
-#endif
-}
-
-void DriveMotor::Callback(const gazebo::msgs::ConstFloat64Ptr& msg) {
-  signal = msg->data();
-  if (signal < -1) {
-    signal = -1;
-  } else if (signal > 1) {
-    signal = 1;
-  }
-}
diff --git a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/drive_motor/headers/drive_motor.h b/third_party/allwpilib/simulation/frc_gazebo_plugins/src/drive_motor/headers/drive_motor.h
deleted file mode 100644
index 8516961..0000000
--- a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/drive_motor/headers/drive_motor.h
+++ /dev/null
@@ -1,123 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <string>
-
-#include <gazebo/gazebo.hh>
-#include <gazebo/physics/physics.hh>
-#include <gazebo/transport/transport.hh>
-
-#include "simulation/gz_msgs/msgs.h"
-
-/**
- * \brief Plugin for simulating a drive motor
- *
- * This plugin attempts to overcome a limitation in gazebo.
- * That is, most normal FRC robots rely on wheels that have good
- * traction in one direction, and less traction in the opposite
- * direction.
- *
- * Gazebo does not model that well (in fact, drive wheels are
- * quite hard to simulate).
- *
- * So this plugin subscribes to a PWM output signal and applies
- * a force to the chassis at the proscribed point in hopefully
- * the correct direction.  The SDF model can then have lower friction,
- * and it should turn more naturally.
- *
- * This plugin also attempts to simulate the limitations of a drive
- * motor, most notably the maximum speed any given motor can spin at.
- * The initial implemention is quite naive; just a linear reduction
- * in force as a product of velocity/max velocity.
- *
- * Nicely, this plugin let's you generate a force in any of
- * three axes.  That is helpful for simulating a mecanum drive.
- *
- * This plugin subscribes to a topic to get a signal in the range
- * [-1,1]. Every physics update the joint's torque is set as
- * multiplier*signal*direction.
- *
- * To add a drive motor to your robot, add the following XML to your
- * robot model:
- *
- *     <plugin name="my_motor" filename="libdrive_motor.so">
- *       <joint>Joint Name</joint>
- *       <topic>~/my/topic</topic>
- *       <multiplier>Number</multiplier>
- *       <max_speed>Number</max_speed>
- *       <dx>-1, 0, or 1</dx>
- *       <dy>-1, 0, or 1</dy>
- *       <dz>-1, 0, or 1</dz>
- *     </plugin>
- *
- * - `joint`: Name of the joint this Dc motor is attached to.
- * - `topic`: Optional. Message type should be gazebo.msgs.Float64.
- *            A typical topic looks like this:
- *              /gazebo/frc/simulator/pwm/<n>
- * - `multiplier`: Optional. Defaults to 1.  Force applied by this motor.
- *            This is force in Newtons.
- * - `max_speed`:  Optional. Defaults to no maximum.
- *            This is, in theory, meters/second.  Note that friction
- *            and other forces will also slow down a robot.
- *            In practice, this term can be tuned until the robot feels right.
- * - `dx`:  These three constants must be set to either -1, 0, or 1
- * - `dy`:  This controls whether or not the motor produces force
- * - `dz`:  along a given axis, and what direction.  Each defaults to 0.
- *          These are relative to the frame of the parent link of the joint.
- *          So they are usually relative to a chassis.
- *          The force is applied at the point that the joint connects to
- *          the parent link.
- */
-class DriveMotor : public gazebo::ModelPlugin {
- public:
-  /// \brief Load the dc motor and configures it according to the sdf.
-  void Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf);
-
-  /// \brief Update the force on the parent of the joint from each timestep.
-  void Update(const gazebo::common::UpdateInfo& info);
-
- private:
-  /// \brief Topic to read control signal from.
-  std::string topic;
-
-  /// \brief The pwm signal limited to the range [-1,1].
-  double signal;
-
-  /// \brief The robot's maximum speed
-  double maxSpeed;
-
-  /// \brief The magic drive force multipliers. force=multiplier*signal
-  double multiplier;
-
-  /// \brief The directional constants limited to -1, 0, or 1.
-  double dx;
-  double dy;
-  double dz;
-
-  /// \brief The joint that this motor drives.
-  gazebo::physics::JointPtr joint;
-
-  /// \brief The parent of this joint; usually a chassis
-  gazebo::physics::LinkPtr parent;
-
-  /// \brief The child of this joint; usually a wheel
-  gazebo::physics::LinkPtr child;
-
-  /// \brief Callback for receiving msgs and storing the signal.
-  void Callback(const gazebo::msgs::ConstFloat64Ptr& msg);
-
-  /// \brief The model to which this is attached.
-  gazebo::physics::ModelPtr model;
-
-  /// \brief Pointer toe the world update function.
-  gazebo::event::ConnectionPtr updateConn;
-
-  /// \brief The node on which we're advertising.
-  gazebo::transport::NodePtr node;
-
-  /// \brief Subscriber handle.
-  gazebo::transport::SubscriberPtr sub;
-};
diff --git a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/encoder/cpp/encoder.cpp b/third_party/allwpilib/simulation/frc_gazebo_plugins/src/encoder/cpp/encoder.cpp
deleted file mode 100644
index c204701..0000000
--- a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/encoder/cpp/encoder.cpp
+++ /dev/null
@@ -1,99 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "encoder.h"
-
-#include <boost/algorithm/string/replace.hpp>
-
-GZ_REGISTER_MODEL_PLUGIN(Encoder)
-
-void Encoder::Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf) {
-  this->model = model;
-
-  // Parse SDF properties
-  joint = model->GetJoint(sdf->Get<std::string>("joint"));
-  if (sdf->HasElement("topic")) {
-    topic = sdf->Get<std::string>("topic");
-  } else {
-    topic = "~/" + sdf->GetAttribute("name")->GetAsString();
-  }
-
-  if (sdf->HasElement("units")) {
-    radians = sdf->Get<std::string>("units") != "degrees";
-  } else {
-    radians = true;
-  }
-  multiplier = 1.0;
-  zero = GetAngle();
-  stopped = true;
-  stop_value = 0;
-
-  if (sdf->HasElement("multiplier"))
-    multiplier = sdf->Get<double>("multiplier");
-
-  gzmsg << "Initializing encoder: " << topic << " joint=" << joint->GetName()
-        << " radians=" << radians << " multiplier=" << multiplier << std::endl;
-
-  // Connect to Gazebo transport for messaging
-  std::string scoped_name =
-      model->GetWorld()->Name() + "::" + model->GetScopedName();
-  boost::replace_all(scoped_name, "::", "/");
-  node = gazebo::transport::NodePtr(new gazebo::transport::Node());
-  node->Init(scoped_name);
-  command_sub = node->Subscribe(topic + "/control", &Encoder::Callback, this);
-  pos_pub = node->Advertise<gazebo::msgs::Float64>(topic + "/position");
-  vel_pub = node->Advertise<gazebo::msgs::Float64>(topic + "/velocity");
-
-  // Connect to the world update event.
-  // This will trigger the Update function every Gazebo iteration
-  updateConn = gazebo::event::Events::ConnectWorldUpdateBegin(
-      boost::bind(&Encoder::Update, this, _1));
-}
-
-void Encoder::Update(const gazebo::common::UpdateInfo& info) {
-  gazebo::msgs::Float64 pos_msg, vel_msg;
-  if (stopped) {
-    pos_msg.set_data(stop_value * multiplier);
-    pos_pub->Publish(pos_msg);
-    vel_msg.set_data(0);
-    vel_pub->Publish(vel_msg);
-  } else {
-    pos_msg.set_data((GetAngle() - zero) * multiplier);
-    pos_pub->Publish(pos_msg);
-    vel_msg.set_data(GetVelocity() * multiplier);
-    vel_pub->Publish(vel_msg);
-  }
-}
-
-void Encoder::Callback(const gazebo::msgs::ConstStringPtr& msg) {
-  std::string command = msg->data();
-  if (command == "reset") {
-    zero = GetAngle();
-  } else if (command == "start") {
-    stopped = false;
-    zero = (GetAngle() - stop_value);
-  } else if (command == "stop") {
-    stopped = true;
-    stop_value = GetAngle();
-  } else {
-    gzerr << "WARNING: Encoder got unknown command '" << command << "'."
-          << std::endl;
-  }
-}
-
-double Encoder::GetAngle() {
-  if (radians) {
-    return joint->Position(0);
-  } else {
-    return joint->Position(0) * (180.0 / M_PI);
-  }
-}
-
-double Encoder::GetVelocity() {
-  if (radians) {
-    return joint->GetVelocity(0);
-  } else {
-    return joint->GetVelocity(0) * (180.0 / M_PI);
-  }
-}
diff --git a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/encoder/headers/encoder.h b/third_party/allwpilib/simulation/frc_gazebo_plugins/src/encoder/headers/encoder.h
deleted file mode 100644
index 72f3542..0000000
--- a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/encoder/headers/encoder.h
+++ /dev/null
@@ -1,109 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <string>
-
-#include <gazebo/gazebo.hh>
-#include <gazebo/physics/physics.hh>
-#include <gazebo/transport/transport.hh>
-
-#include "simulation/gz_msgs/msgs.h"
-
-/**
- * \brief Plugin for reading the speed and relative angle of a joint.
- *
- * This plugin publishes the angle since last reset and the speed of a
- * given joint to subtopics of the given topic every physics
- * update. There is also a control subtopic that takes three commands:
- * "start", "stop" and "reset":
- *
- * - "start": Start counting ticks from the current count.
- * - "stop":  Stop counting ticks, pauses updates.
- * - "reset": Set the current angle to zero.
- *
- * To add a encoder to your robot, add the following XML to your
- * robot model:
- *
- *     <plugin name="my_encoder" filename="libencoder.so">
- *       <joint>Joint Name</joint>
- *       <topic>~/my/topic</topic>
- *       <units>{degrees, radians}</units>
- *       <multiplier>Number</multiplier>
- *     </plugin>
- *
- * - `joint`: Name of the joint this encoder is attached to.
- * - `topic`: Optional. Used as the root for subtopics. `topic`/position
- * (gazebo.msgs.Float64),
- *            `topic`/velocity (gazebo.msgs.Float64), `topic`/control
- * (gazebo.msgs.String)
- *    The suggested value for topic is of the form
- *       ~/simulator/encoder/dio/<n>
- *    where <n> is the number of the first digital input channel
- *    used to formulate the encoder
- *
- * - `units`: Optional. Defaults to radians.
- * - `multiplier`: Optional. Defaults to 1.
- *     This can be used to make the simulated encoder
- *     return a comparable number of ticks to a 'real' encoder
- *     Useful facts:  A 'degrees' encoder will report 360 ticks/revolution.
- *     The k4X encoder type can add another multiple of 4 into the mix.
- */
-class Encoder : public gazebo::ModelPlugin {
- public:
-  /// \brief Load the encoder and configures it according to the sdf.
-  void Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf);
-
-  /// \brief Sends out the encoder reading each timestep.
-  void Update(const gazebo::common::UpdateInfo& info);
-
- private:
-  /// \brief Root topic for subtopics on this topic.
-  std::string topic;
-
-  /// \brief Whether or not this encoder measures radians or degrees.
-  bool radians;
-
-  /// \brief A factor to multiply this output by.
-  double multiplier;
-
-  /// \brief Whether or not the encoder has been stopped.
-  bool stopped;
-
-  /// \brief The zero value of the encoder.
-  double zero;
-
-  /// \brief The value the encoder stopped counting at
-  double stop_value;
-
-  /// \brief The joint that this encoder measures
-  gazebo::physics::JointPtr joint;
-
-  /// \brief Callback for handling control data
-  void Callback(const gazebo::msgs::ConstStringPtr& msg);
-
-  /// \brief Gets the current angle, taking into account whether to
-  ///        return radians or degrees.
-  double GetAngle();
-
-  /// \brief Gets the current velocity, taking into account whether to
-  ///        return radians/second or degrees/second.
-  double GetVelocity();
-
-  /// \brief The model to which this is attached.
-  gazebo::physics::ModelPtr model;
-
-  /// \brief Pointer to the world update function.
-  gazebo::event::ConnectionPtr updateConn;
-
-  /// \brief The node on which we're advertising.
-  gazebo::transport::NodePtr node;
-
-  /// \brief Subscriber handle.
-  gazebo::transport::SubscriberPtr command_sub;
-
-  /// \brief Publisher handles.
-  gazebo::transport::PublisherPtr pos_pub, vel_pub;
-};
diff --git a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/gyro/cpp/gyro.cpp b/third_party/allwpilib/simulation/frc_gazebo_plugins/src/gyro/cpp/gyro.cpp
deleted file mode 100644
index b30d9b7..0000000
--- a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/gyro/cpp/gyro.cpp
+++ /dev/null
@@ -1,111 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "gyro.h"
-
-#include <boost/algorithm/string/replace.hpp>
-
-GZ_REGISTER_MODEL_PLUGIN(Gyro)
-
-void Gyro::Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf) {
-  this->model = model;
-
-  // Parse SDF properties
-  link = model->GetLink(sdf->Get<std::string>("link"));
-  if (sdf->HasElement("topic")) {
-    topic = sdf->Get<std::string>("topic");
-  } else {
-    topic = "~/" + sdf->GetAttribute("name")->GetAsString();
-  }
-
-  std::string axisString = sdf->Get<std::string>("axis");
-  if (axisString == "roll")
-    axis = Roll;
-  if (axisString == "pitch")
-    axis = Pitch;
-  if (axisString == "yaw")
-    axis = Yaw;
-
-  if (sdf->HasElement("units")) {
-    radians = sdf->Get<std::string>("units") != "degrees";
-  } else {
-    radians = true;
-  }
-  zero = GetAngle();
-
-  gzmsg << "Initializing gyro: " << topic << " link=" << link->GetName()
-        << " axis=" << axis << " radians=" << radians << std::endl;
-
-  // Connect to Gazebo transport for messaging
-  std::string scoped_name =
-      model->GetWorld()->Name() + "::" + model->GetScopedName();
-  boost::replace_all(scoped_name, "::", "/");
-  node = gazebo::transport::NodePtr(new gazebo::transport::Node());
-  node->Init(scoped_name);
-  command_sub = node->Subscribe(topic + "/control", &Gyro::Callback, this);
-  pos_pub = node->Advertise<gazebo::msgs::Float64>(topic + "/position");
-  vel_pub = node->Advertise<gazebo::msgs::Float64>(topic + "/velocity");
-
-  // Connect to the world update event.
-  // This will trigger the Update function every Gazebo iteration
-  updateConn = gazebo::event::Events::ConnectWorldUpdateBegin(
-      boost::bind(&Gyro::Update, this, _1));
-}
-
-void Gyro::Update(const gazebo::common::UpdateInfo& info) {
-  gazebo::msgs::Float64 pos_msg, vel_msg;
-  pos_msg.set_data(Limit(GetAngle() - zero));
-  pos_pub->Publish(pos_msg);
-  vel_msg.set_data(GetVelocity());
-  vel_pub->Publish(vel_msg);
-}
-
-void Gyro::Callback(const gazebo::msgs::ConstStringPtr& msg) {
-  std::string command = msg->data();
-  if (command == "reset") {
-    zero = GetAngle();
-  } else {
-    gzerr << "WARNING: Gyro got unknown command '" << command << "'."
-          << std::endl;
-  }
-}
-
-double Gyro::GetAngle() {
-  if (radians) {
-    return link->WorldCoGPose().Rot().Euler()[axis];
-  } else {
-    return link->WorldCoGPose().Rot().Euler()[axis] * (180.0 / M_PI);
-  }
-}
-
-double Gyro::GetVelocity() {
-  if (radians) {
-    return link->RelativeAngularVel()[axis];
-  } else {
-    return link->RelativeAngularVel()[axis] * (180.0 / M_PI);
-  }
-}
-
-double Gyro::Limit(double value) {
-  if (radians) {
-    while (true) {
-      if (value < -M_PI)
-        value += 2 * M_PI;
-      else if (value > M_PI)
-        value -= 2 * M_PI;
-      else
-        break;
-    }
-  } else {
-    while (true) {
-      if (value < -180)
-        value += 360;
-      else if (value > 180)
-        value -= 360;
-      else
-        break;
-    }
-  }
-  return value;
-}
diff --git a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/gyro/headers/gyro.h b/third_party/allwpilib/simulation/frc_gazebo_plugins/src/gyro/headers/gyro.h
deleted file mode 100644
index adc332b..0000000
--- a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/gyro/headers/gyro.h
+++ /dev/null
@@ -1,95 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <string>
-
-#include <gazebo/gazebo.hh>
-#include <gazebo/physics/physics.hh>
-#include <gazebo/transport/transport.hh>
-
-#include "simulation/gz_msgs/msgs.h"
-
-/// \brief The axis about which to measure rotation.
-enum ROTATION { Roll /*X*/, Pitch /*Y*/, Yaw /*Z*/ };
-
-/**
- * \brief Plugin for reading the speed and relative angle of a link.
- *
- * This plugin publishes the angle since last reset and the speed
- * which a link is rotating about some axis to subtopics of the given
- * topic every physics update. There is also a control topic that
- * takes one command: "reset", which sets the current angle as zero.
- *
- * To add a gyro to your robot, add the following XML to your robot
- * model:
- *
- *     <plugin name="my_gyro" filename="libgyro.so">
- *       <link>Joint Name</link>
- *       <topic>~/my/topic</topic>
- *       <units>{degrees, radians}</units>
- *     </plugin>
- *
- * - `link`: Name of the link this potentiometer is attached to.
- * - `topic`: Optional. Used as the root for subtopics. `topic`/position
- * (gazebo.msgs.Float64),
- *            `topic`/velocity (gazebo.msgs.Float64), `topic`/control
- * (gazebo.msgs.String)
- * - `units`; Optional, defaults to radians.
- */
-class Gyro : public gazebo::ModelPlugin {
- public:
-  /// \brief Load the gyro and configures it according to the sdf.
-  void Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf);
-
-  /// \brief Sends out the gyro reading each timestep.
-  void Update(const gazebo::common::UpdateInfo& info);
-
- private:
-  /// \brief Publish the angle on this topic.
-  std::string topic;
-
-  /// \brief Whether or not this gyro measures radians or degrees.
-  bool radians;
-
-  /// \brief The axis to measure rotation about.
-  ROTATION axis;
-
-  /// \brief The zero value of the gyro.
-  double zero;
-
-  /// \brief The link that this gyro measures
-  gazebo::physics::LinkPtr link;
-
-  /// \brief Callback for handling control data
-  void Callback(const gazebo::msgs::ConstStringPtr& msg);
-
-  /// \brief Gets the current angle, taking into account whether to
-  ///        return radians or degrees.
-  double GetAngle();
-
-  /// \brief Gets the current velocity, taking into account whether to
-  ///        return radians/second or degrees/second.
-  double GetVelocity();
-
-  /// \brief Limit the value to either [-180,180] or [-PI,PI]
-  ///       depending on whether or radians or degrees are being used.
-  double Limit(double value);
-
-  /// \brief The model to which this is attached.
-  gazebo::physics::ModelPtr model;
-
-  /// \brief Pointer to the world update function.
-  gazebo::event::ConnectionPtr updateConn;
-
-  /// \brief The node on which we're advertising.
-  gazebo::transport::NodePtr node;
-
-  /// \brief Subscriber handle.
-  gazebo::transport::SubscriberPtr command_sub;
-
-  /// \brief Publisher handles.
-  gazebo::transport::PublisherPtr pos_pub, vel_pub;
-};
diff --git a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/limit_switch/cpp/external_limit_switch.cpp b/third_party/allwpilib/simulation/frc_gazebo_plugins/src/limit_switch/cpp/external_limit_switch.cpp
deleted file mode 100644
index b15ab71..0000000
--- a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/limit_switch/cpp/external_limit_switch.cpp
+++ /dev/null
@@ -1,19 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "external_limit_switch.h"
-
-#include <string>
-
-ExternalLimitSwitch::ExternalLimitSwitch(sdf::ElementPtr sdf) {
-  sensor = std::dynamic_pointer_cast<gazebo::sensors::ContactSensor>(
-      gazebo::sensors::get_sensor(sdf->Get<std::string>("sensor")));
-
-  gzmsg << "\texternal limit switch: "
-        << " sensor=" << sensor->Name() << std::endl;
-}
-
-bool ExternalLimitSwitch::Get() {
-  return sensor->Contacts().contact().size() > 0;
-}
diff --git a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/limit_switch/cpp/internal_limit_switch.cpp b/third_party/allwpilib/simulation/frc_gazebo_plugins/src/limit_switch/cpp/internal_limit_switch.cpp
deleted file mode 100644
index f01ceb6..0000000
--- a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/limit_switch/cpp/internal_limit_switch.cpp
+++ /dev/null
@@ -1,34 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "internal_limit_switch.h"
-
-#include <string>
-
-InternalLimitSwitch::InternalLimitSwitch(gazebo::physics::ModelPtr model,
-                                         sdf::ElementPtr sdf) {
-  joint = model->GetJoint(sdf->Get<std::string>("joint"));
-  min = sdf->Get<double>("min");
-  max = sdf->Get<double>("max");
-
-  if (sdf->HasElement("units")) {
-    radians = sdf->Get<std::string>("units") != "degrees";
-  } else {
-    radians = true;
-  }
-
-  gzmsg << "\tinternal limit switch: "
-        << " type=" << joint->GetName() << " range=[" << min << "," << max
-        << "] radians=" << radians << std::endl;
-}
-
-bool InternalLimitSwitch::Get() {
-  double value;
-  if (radians) {
-    value = joint->Position(0);
-  } else {
-    value = joint->Position(0) * (180.0 / M_PI);
-  }
-  return value >= min && value <= max;
-}
diff --git a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/limit_switch/cpp/limit_switch.cpp b/third_party/allwpilib/simulation/frc_gazebo_plugins/src/limit_switch/cpp/limit_switch.cpp
deleted file mode 100644
index c380bae..0000000
--- a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/limit_switch/cpp/limit_switch.cpp
+++ /dev/null
@@ -1,54 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "limit_switch.h"
-
-#include <boost/algorithm/string/replace.hpp>
-
-GZ_REGISTER_MODEL_PLUGIN(LimitSwitch)
-
-void LimitSwitch::Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf) {
-  this->model = model;
-
-  // Parse SDF properties
-  if (sdf->HasElement("topic")) {
-    topic = sdf->Get<std::string>("topic");
-  } else {
-    topic = "~/" + sdf->GetAttribute("name")->GetAsString();
-  }
-  invert = sdf->HasElement("invert");
-  std::string type = sdf->Get<std::string>("type");
-
-  gzmsg << "Initializing limit switch: " << topic << " type=" << type
-        << std::endl;
-  if (type == "internal") {
-    ls = new InternalLimitSwitch(model, sdf);
-  } else if (type == "external") {
-    ls = new ExternalLimitSwitch(sdf);
-  } else {
-    gzerr << "WARNING: unsupported limit switch type " << type;
-  }
-
-  // Connect to Gazebo transport for messaging
-  std::string scoped_name =
-      model->GetWorld()->Name() + "::" + model->GetScopedName();
-  boost::replace_all(scoped_name, "::", "/");
-  node = gazebo::transport::NodePtr(new gazebo::transport::Node());
-  node->Init(scoped_name);
-  pub = node->Advertise<gazebo::msgs::Bool>(topic);
-
-  // Connect to the world update event.
-  // This will trigger the Update function every Gazebo iteration
-  updateConn = gazebo::event::Events::ConnectWorldUpdateBegin(
-      boost::bind(&LimitSwitch::Update, this, _1));
-}
-
-void LimitSwitch::Update(const gazebo::common::UpdateInfo& info) {
-  gazebo::msgs::Bool msg;
-  if (invert)
-    msg.set_data(!ls->Get());
-  else
-    msg.set_data(ls->Get());
-  pub->Publish(msg);
-}
diff --git a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/limit_switch/headers/external_limit_switch.h b/third_party/allwpilib/simulation/frc_gazebo_plugins/src/limit_switch/headers/external_limit_switch.h
deleted file mode 100644
index 8a39f61..0000000
--- a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/limit_switch/headers/external_limit_switch.h
+++ /dev/null
@@ -1,26 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <boost/pointer_cast.hpp>
-#include <gazebo/gazebo.hh>
-#include <gazebo/sensors/sensors.hh>
-
-#ifdef _WIN32
-#include <Winsock2.h>
-#endif
-
-#include "switch.h"
-
-class ExternalLimitSwitch : public Switch {
- public:
-  explicit ExternalLimitSwitch(sdf::ElementPtr sdf);
-
-  /// \brief Returns true when the switch is triggered.
-  bool Get() override;
-
- private:
-  gazebo::sensors::ContactSensorPtr sensor;
-};
diff --git a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/limit_switch/headers/internal_limit_switch.h b/third_party/allwpilib/simulation/frc_gazebo_plugins/src/limit_switch/headers/internal_limit_switch.h
deleted file mode 100644
index 11159c7..0000000
--- a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/limit_switch/headers/internal_limit_switch.h
+++ /dev/null
@@ -1,27 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <gazebo/gazebo.hh>
-#include <gazebo/physics/physics.hh>
-
-#ifdef _WIN32
-#include <Winsock2.h>
-#endif
-
-#include "switch.h"
-
-class InternalLimitSwitch : public Switch {
- public:
-  InternalLimitSwitch(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf);
-
-  /// \brief Returns true when the switch is triggered.
-  bool Get() override;
-
- private:
-  gazebo::physics::JointPtr joint;
-  double min, max;
-  bool radians;
-};
diff --git a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/limit_switch/headers/limit_switch.h b/third_party/allwpilib/simulation/frc_gazebo_plugins/src/limit_switch/headers/limit_switch.h
deleted file mode 100644
index 089cfa1..0000000
--- a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/limit_switch/headers/limit_switch.h
+++ /dev/null
@@ -1,96 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <string>
-
-#include <gazebo/gazebo.hh>
-#include <gazebo/physics/physics.hh>
-#include <gazebo/transport/transport.hh>
-
-#include "external_limit_switch.h"
-#include "internal_limit_switch.h"
-#include "simulation/gz_msgs/msgs.h"
-#include "switch.h"
-
-/**
- * \brief Plugin for reading limit switches.
- *
- * This plugin publishes whether or not the limit switch has been
- * triggered every physics update. There are two types of limit switches:
- *
- * - Internal: Measure joint limits. Triggerd if the joint is within
- *             some range.
- * - External: Measure interactions with the outside world. Triggerd
- *             if some link is in collision.
- *
- * To add a limit swithch to your robot, add the following XML to your
- * robot model.
- *
- * Internal:
- *
- *     <plugin name="my_limit_switch" filename="liblimit_switch.so">
- *       <topic>~/my/topic</topic>
- *       <type>internal</type>
- *       <joint>Joint Name</joint>
- *       <units>{degrees, radians}</units>
- *       <min>Number</min>
- *       <max>Number</max>
- *     </plugin>
- *
- * External:
- *
- *     <plugin name="my_limit_switch" filename="liblimit_switch.so">
- *       <topic>~/my/topic</topic>
- *       <type>external</type>
- *       <sensor>Sensor Name</sensor>
- *     </plugin>
- *
- * Common:
- * - `topic`: Optional. Message will be published as a gazebo.msgs.Bool.
- *            Recommended values are of the form:
- *              /gazebo/frc/simulator/dio/n
- * - `type`: Required. The type of limit switch that this is
- * - `invert`: Optional. If given, the output meaning will be inverted
- *
- * Internal
- * - `joint`: Name of the joint this potentiometer is attached to.
- * - `units`: Optional. Defaults to radians.
- * - `min`: Minimum angle considered triggered.
- * - `max`: Maximum angle considered triggered.
- *
- * External
- * - `sensor`: Name of the contact sensor that this limit switch uses.
- */
-class LimitSwitch : public gazebo::ModelPlugin {
- public:
-  /// \brief Load the limit switch and configures it according to the sdf.
-  void Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf);
-
-  /// \brief Sends out the limit switch reading each timestep.
-  void Update(const gazebo::common::UpdateInfo& info);
-
- private:
-  /// \brief Publish the limit switch value on this topic.
-  std::string topic;
-
-  /// \brief LimitSwitch object, currently internal or external.
-  Switch* ls;
-
-  /// \brief Indicate if we should invert the output
-  bool invert;
-
-  /// \brief The model to which this is attached.
-  gazebo::physics::ModelPtr model;
-
-  /// \brief Pointer to the world update function.
-  gazebo::event::ConnectionPtr updateConn;
-
-  /// \brief The node on which we're advertising.
-  gazebo::transport::NodePtr node;
-
-  /// \brief Publisher handle.
-  gazebo::transport::PublisherPtr pub;
-};
diff --git a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/limit_switch/headers/switch.h b/third_party/allwpilib/simulation/frc_gazebo_plugins/src/limit_switch/headers/switch.h
deleted file mode 100644
index cc7018e..0000000
--- a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/limit_switch/headers/switch.h
+++ /dev/null
@@ -1,13 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-class Switch {
- public:
-  virtual ~Switch() = default;
-
-  /// \brief Returns true when the switch is triggered.
-  virtual bool Get() = 0;
-};
diff --git a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/pneumatic_piston/cpp/pneumatic_piston.cpp b/third_party/allwpilib/simulation/frc_gazebo_plugins/src/pneumatic_piston/cpp/pneumatic_piston.cpp
deleted file mode 100644
index a1f8d8d..0000000
--- a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/pneumatic_piston/cpp/pneumatic_piston.cpp
+++ /dev/null
@@ -1,93 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "pneumatic_piston.h"
-
-#include <boost/algorithm/string/replace.hpp>
-#include <gazebo/physics/physics.hh>
-#include <gazebo/transport/transport.hh>
-
-#ifdef _WIN32
-// Ensure that Winsock2.h is included before Windows.h, which can get
-// pulled in by anybody (e.g., Boost).
-#include <Winsock2.h>
-#endif
-
-GZ_REGISTER_MODEL_PLUGIN(PneumaticPiston)
-
-void PneumaticPiston::Load(gazebo::physics::ModelPtr model,
-                           sdf::ElementPtr sdf) {
-  this->model = model;
-  forward_signal = reverse_signal = false;
-
-  // Parse SDF properties
-  joint = model->GetJoint(sdf->Get<std::string>("joint"));
-  if (sdf->HasElement("topic")) {
-    topic = sdf->Get<std::string>("topic");
-  } else {
-    topic = "~/" + sdf->GetAttribute("name")->GetAsString();
-  }
-
-  if (sdf->HasElement("reverse-topic")) {
-    reverse_topic = sdf->Get<std::string>("reverse-topic");
-  } else {
-    reverse_topic.clear();
-  }
-
-  forward_force = sdf->Get<double>("forward-force");
-  if (sdf->HasElement("reverse-force"))
-    reverse_force = -1.0 * sdf->Get<double>("reverse-force");
-
-  if (sdf->HasElement("direction") &&
-      sdf->Get<std::string>("direction") == "reversed") {
-    forward_force = -forward_force;
-    reverse_force = -reverse_force;
-  }
-
-  gzmsg << "Initializing piston: " << topic << " joint=" << joint->GetName()
-        << " forward_force=" << forward_force
-        << " reverse_force=" << reverse_force << std::endl;
-  if (!reverse_topic.empty())
-    gzmsg << "Reversing on topic " << reverse_topic << std::endl;
-
-  // Connect to Gazebo transport for messaging
-  std::string scoped_name =
-      model->GetWorld()->Name() + "::" + model->GetScopedName();
-  boost::replace_all(scoped_name, "::", "/");
-  node = gazebo::transport::NodePtr(new gazebo::transport::Node());
-  node->Init(scoped_name);
-  sub = node->Subscribe(topic, &PneumaticPiston::ForwardCallback, this);
-  if (!reverse_topic.empty())
-    sub_reverse =
-        node->Subscribe(reverse_topic, &PneumaticPiston::ReverseCallback, this);
-
-  // Connect to the world update event.
-  // This will trigger the Update function every Gazebo iteration
-  updateConn = gazebo::event::Events::ConnectWorldUpdateBegin(
-      boost::bind(&PneumaticPiston::Update, this, _1));
-}
-
-void PneumaticPiston::Update(const gazebo::common::UpdateInfo& info) {
-  double force = 0.0;
-  if (forward_signal) {
-    force = forward_force;
-  } else {
-    /* For DoubleSolenoids, the second signal must be present
-       for us to apply the reverse force.  For SingleSolenoids,
-       the lack of the forward signal suffices.
-       Note that a true simulation would not allow a SingleSolenoid to
-       have reverse force, but we put that in the hands of the model builder.*/
-    if (reverse_topic.empty() || reverse_signal)
-      force = reverse_force;
-  }
-  joint->SetForce(0, force);
-}
-
-void PneumaticPiston::ForwardCallback(const gazebo::msgs::ConstBoolPtr& msg) {
-  forward_signal = msg->data();
-}
-
-void PneumaticPiston::ReverseCallback(const gazebo::msgs::ConstBoolPtr& msg) {
-  reverse_signal = msg->data();
-}
diff --git a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/pneumatic_piston/headers/pneumatic_piston.h b/third_party/allwpilib/simulation/frc_gazebo_plugins/src/pneumatic_piston/headers/pneumatic_piston.h
deleted file mode 100644
index bcc02b4..0000000
--- a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/pneumatic_piston/headers/pneumatic_piston.h
+++ /dev/null
@@ -1,99 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <string>
-
-#include <gazebo/gazebo.hh>
-
-#include "simulation/gz_msgs/msgs.h"
-
-/**
- * \brief Plugin for controlling a joint with a pneumatic piston.
- *
- * This plugin subscribes to topics to get the solenoid state for a piston
- *    It needs one signal for the forward signal.  For a double solenoid,
- *    a second signal can be sent.
- *    Each signal is a boolean.
- *
- * Every physics update the joint's torque is set to reflect the
- * signal, using the configured force
- *
- * To add a pneumatic piston to your robot, add the following XML to
- * your robot model:
- *
- *     <plugin name="my_piston" filename="libpneumatic_piston.so">
- *       <joint>Joint Name</joint>
- *       <topic>/gazebo/frc/simulator/pneumatics/1/1</topic>
- *       <reverse-topic>/gazebo/frc/simulator/pneumatics/1/2</reverse-topic>
- *       <direction>{forward, reversed}</direction>
- *       <forward-force>Number</forward-force>
- *       <reverse-force>Number</reverse-force>
- *     </plugin>
- *
- * - `joint`: Name of the joint this piston is attached to.
- * - `topic`: Optional. Forward Solenoid signal name. type gazebo.msgs.Bool.
- *            If not given, the name given for the plugin will be used.
- *            A pattern of /gazebo/frc/simulator/pneumatics/1/n is good.
- *            The first number represents the PCM module.  Only 1 is supported.
- *            The second number represents the channel on the PCM.
- * - `topic-reverse`: Optional. If given, represents the reverse channel.
- *            Message type should be gazebo.msgs.Bool.
- * - `direction`: Optional. Defaults to forward. Reversed if the piston
- *                pushes in the opposite direction of the joint axis.
- * - `forward-force`: Force to apply in the forward direction.
- * - `reverse-force`: Force to apply in the reverse direction.
- *                    For a single solenoid, you would expect '0',
- *                    but we allow model builders to provide a value.
- *
- */
-class PneumaticPiston : public gazebo::ModelPlugin {
- public:
-  /// \brief Load the pneumatic piston and configures it according to the sdf.
-  void Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf);
-
-  /// \brief Updat the force the piston applies on the joint.
-  void Update(const gazebo::common::UpdateInfo& info);
-
- private:
-  /// \brief Topic to read forward control signal from.
-  std::string topic;
-
-  /// \brief Topic to read reverse control signal from.
-  std::string reverse_topic;
-
-  /// \brief Whether the solenoid to open forward is on
-  bool forward_signal;
-
-  /// \brief Whether the solenoid to open in reverse is on
-  bool reverse_signal;
-
-  /// \brief The magic force multipliers for each direction.
-  double forward_force, reverse_force;
-
-  /// \brief The joint that this pneumatic piston actuates.
-  gazebo::physics::JointPtr joint;
-
-  /// \brief Callback for receiving msgs and updating the solenoid state
-  void ForwardCallback(const gazebo::msgs::ConstBoolPtr& msg);
-
-  /// \brief Callback for receiving msgs and updating the reverse solenoid state
-  void ReverseCallback(const gazebo::msgs::ConstBoolPtr& msg);
-
-  /// \brief The model to which this is attached.
-  gazebo::physics::ModelPtr model;
-
-  /// \brief Pointer to the world update function.
-  gazebo::event::ConnectionPtr updateConn;
-
-  /// \brief The node on which we're advertising.
-  gazebo::transport::NodePtr node;
-
-  /// \brief Subscriber handle.
-  gazebo::transport::SubscriberPtr sub;
-
-  /// \brief Subscriber handle for reverse topic
-  gazebo::transport::SubscriberPtr sub_reverse;
-};
diff --git a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/potentiometer/cpp/potentiometer.cpp b/third_party/allwpilib/simulation/frc_gazebo_plugins/src/potentiometer/cpp/potentiometer.cpp
deleted file mode 100644
index 9691a4d..0000000
--- a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/potentiometer/cpp/potentiometer.cpp
+++ /dev/null
@@ -1,66 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "potentiometer.h"
-
-#include <boost/algorithm/string/replace.hpp>
-#include <gazebo/physics/physics.hh>
-#include <gazebo/transport/transport.hh>
-
-#ifdef _WIN32
-// Ensure that Winsock2.h is included before Windows.h, which can get
-// pulled in by anybody (e.g., Boost).
-#include <Winsock2.h>
-#endif
-
-GZ_REGISTER_MODEL_PLUGIN(Potentiometer)
-
-void Potentiometer::Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf) {
-  this->model = model;
-
-  // Parse SDF properties
-  joint = model->GetJoint(sdf->Get<std::string>("joint"));
-  if (sdf->HasElement("topic")) {
-    topic = sdf->Get<std::string>("topic");
-  } else {
-    topic = "~/" + sdf->GetAttribute("name")->GetAsString();
-  }
-
-  if (sdf->HasElement("units")) {
-    radians = sdf->Get<std::string>("units") != "degrees";
-  } else {
-    radians = true;
-  }
-
-  multiplier = 1.0;
-  if (sdf->HasElement("multiplier"))
-    multiplier = sdf->Get<double>("multiplier");
-
-  gzmsg << "Initializing potentiometer: " << topic
-        << " joint=" << joint->GetName() << " radians=" << radians
-        << " multiplier=" << multiplier << std::endl;
-
-  // Connect to Gazebo transport for messaging
-  std::string scoped_name =
-      model->GetWorld()->Name() + "::" + model->GetScopedName();
-  boost::replace_all(scoped_name, "::", "/");
-  node = gazebo::transport::NodePtr(new gazebo::transport::Node());
-  node->Init(scoped_name);
-  pub = node->Advertise<gazebo::msgs::Float64>(topic);
-
-  // Connect to the world update event.
-  // This will trigger the Update function every Gazebo iteration
-  updateConn = gazebo::event::Events::ConnectWorldUpdateBegin(
-      boost::bind(&Potentiometer::Update, this, _1));
-}
-
-void Potentiometer::Update(const gazebo::common::UpdateInfo& info) {
-  gazebo::msgs::Float64 msg;
-  if (radians) {
-    msg.set_data(joint->Position(0) * multiplier);
-  } else {
-    msg.set_data(joint->Position(0) * (180.0 / M_PI) * multiplier);
-  }
-  pub->Publish(msg);
-}
diff --git a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/potentiometer/headers/potentiometer.h b/third_party/allwpilib/simulation/frc_gazebo_plugins/src/potentiometer/headers/potentiometer.h
deleted file mode 100644
index 5fe6d66..0000000
--- a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/potentiometer/headers/potentiometer.h
+++ /dev/null
@@ -1,70 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <string>
-
-#include <gazebo/gazebo.hh>
-
-#include "simulation/gz_msgs/msgs.h"
-
-/**
- * \brief Plugin for reading the angle of a joint.
- *
- * This plugin publishes the angle of a joint to the topic every
- * physics update. Supports reading in either radians or degrees.
- *
- * To add a potentiometer to your robot, add the following XML to your
- * robot model:
- *
- *     <plugin name="my_pot" filename="libpotentiometer.so">
- *       <joint>Joint Name</joint>
- *       <topic>~/my/topic</topic>
- *       <units>{degrees, radians}</units>
- *     </plugin>
- *
- * - `joint`: Name of the joint this potentiometer is attached to.
- * - `topic`: Optional. Message will be published as a gazebo.msgs.Float64.
- *            The default topic name will be the plugin name.
- *            Recommended topic names are of the form:
- *              /gazebo/frc/simulator/analog/n
- *            where n is the analog channel for the pot.
- * - `multiplier`: Optional.  Amount to multiply output with.
- *            Useful when a rotary pot returns something other than an angle
- * - `units`: Optional. Defaults to radians.
- */
-class Potentiometer : public gazebo::ModelPlugin {
- public:
-  /// \brief Load the potentiometer and configures it according to the sdf.
-  void Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf);
-
-  /// \brief Sends out the potentiometer reading each timestep.
-  void Update(const gazebo::common::UpdateInfo& info);
-
- private:
-  /// \brief Publish the angle on this topic.
-  std::string topic;
-
-  /// \brief Whether or not this potentiometer measures radians or degrees.
-  bool radians;
-
-  /// \brief A scaling factor to apply to this potentiometer.
-  double multiplier;
-
-  /// \brief The joint that this potentiometer measures
-  gazebo::physics::JointPtr joint;
-
-  /// \brief The model to which this is attached.
-  gazebo::physics::ModelPtr model;
-
-  /// \brief Pointer to the world update function.
-  gazebo::event::ConnectionPtr updateConn;
-
-  /// \brief The node on which we're advertising.
-  gazebo::transport::NodePtr node;
-
-  /// \brief Publisher handle.
-  gazebo::transport::PublisherPtr pub;
-};
diff --git a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/rangefinder/cpp/rangefinder.cpp b/third_party/allwpilib/simulation/frc_gazebo_plugins/src/rangefinder/cpp/rangefinder.cpp
deleted file mode 100644
index be8bbe6..0000000
--- a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/rangefinder/cpp/rangefinder.cpp
+++ /dev/null
@@ -1,53 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "rangefinder.h"
-
-#include <boost/algorithm/string/replace.hpp>
-#include <gazebo/physics/physics.hh>
-#include <gazebo/sensors/sensors.hh>
-#include <gazebo/transport/transport.hh>
-
-#ifdef _WIN32
-// Ensure that Winsock2.h is included before Windows.h, which can get
-// pulled in by anybody (e.g., Boost).
-#include <Winsock2.h>
-#endif
-
-GZ_REGISTER_MODEL_PLUGIN(Rangefinder)
-
-void Rangefinder::Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf) {
-  this->model = model;
-
-  // Parse SDF properties
-  sensor = std::dynamic_pointer_cast<gazebo::sensors::SonarSensor>(
-      gazebo::sensors::get_sensor(sdf->Get<std::string>("sensor")));
-  if (sdf->HasElement("topic")) {
-    topic = sdf->Get<std::string>("topic");
-  } else {
-    topic = "~/" + sdf->GetAttribute("name")->GetAsString();
-  }
-
-  gzmsg << "Initializing rangefinder: " << topic << " sensor=" << sensor->Name()
-        << std::endl;
-
-  // Connect to Gazebo transport for messaging
-  std::string scoped_name =
-      model->GetWorld()->Name() + "::" + model->GetScopedName();
-  boost::replace_all(scoped_name, "::", "/");
-  node = gazebo::transport::NodePtr(new gazebo::transport::Node());
-  node->Init(scoped_name);
-  pub = node->Advertise<gazebo::msgs::Float64>(topic);
-
-  // Connect to the world update event.
-  // This will trigger the Update function every Gazebo iteration
-  updateConn = gazebo::event::Events::ConnectWorldUpdateBegin(
-      boost::bind(&Rangefinder::Update, this, _1));
-}
-
-void Rangefinder::Update(const gazebo::common::UpdateInfo& info) {
-  gazebo::msgs::Float64 msg;
-  msg.set_data(sensor->Range());
-  pub->Publish(msg);
-}
diff --git a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/rangefinder/headers/rangefinder.h b/third_party/allwpilib/simulation/frc_gazebo_plugins/src/rangefinder/headers/rangefinder.h
deleted file mode 100644
index 6fee59b..0000000
--- a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/rangefinder/headers/rangefinder.h
+++ /dev/null
@@ -1,56 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <string>
-
-#include <gazebo/gazebo.hh>
-
-#include "simulation/gz_msgs/msgs.h"
-
-/**
- * \brief Plugin for reading the range of obstacles.
- *
- * This plugin publishes the range of obstacles detected by a sonar
- * rangefinder every physics update.
- *
- * To add a rangefinder to your robot, add the following XML to your
- * robot model:
- *
- *     <plugin name="my_rangefinder" filename="librangefinder.so">
- *       <sensor>Sensor Name</sensor>
- *       <topic>~/my/topic</topic>
- *     </plugin>
- *
- * - `sensor`: Name of the sonar sensor that this rangefinder uses.
- * - `topic`: Optional. Message will be published as a gazebo.msgs.Float64.
- */
-class Rangefinder : public gazebo::ModelPlugin {
- public:
-  /// \brief Load the rangefinder and configures it according to the sdf.
-  void Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf);
-
-  /// \brief Sends out the rangefinder reading each timestep.
-  void Update(const gazebo::common::UpdateInfo& info);
-
- private:
-  /// \brief Publish the range on this topic.
-  std::string topic;
-
-  /// \brief The sonar sensor that this rangefinder uses
-  gazebo::sensors::SonarSensorPtr sensor;
-
-  /// \brief The model to which this is attached.
-  gazebo::physics::ModelPtr model;
-
-  /// \brief Pointer to the world update function.
-  gazebo::event::ConnectionPtr updateConn;
-
-  /// \brief The node on which we're advertising.
-  gazebo::transport::NodePtr node;
-
-  /// \brief Publisher handle.
-  gazebo::transport::PublisherPtr pub;
-};
diff --git a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/servo/cpp/servo.cpp b/third_party/allwpilib/simulation/frc_gazebo_plugins/src/servo/cpp/servo.cpp
deleted file mode 100644
index e090d0c..0000000
--- a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/servo/cpp/servo.cpp
+++ /dev/null
@@ -1,72 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "servo.h"
-
-#include <boost/algorithm/string/replace.hpp>
-#include <gazebo/physics/physics.hh>
-#include <gazebo/transport/transport.hh>
-
-#ifdef _WIN32
-// Ensure that Winsock2.h is included before Windows.h, which can get
-// pulled in by anybody (e.g., Boost).
-#include <Winsock2.h>
-#endif
-
-GZ_REGISTER_MODEL_PLUGIN(Servo)
-
-void Servo::Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf) {
-  this->model = model;
-  signal = 0;
-
-  // parse SDF Properries
-  joint = model->GetJoint(sdf->Get<std::string>("joint"));
-  if (sdf->HasElement("topic")) {
-    topic = sdf->Get<std::string>("topic");
-  } else {
-    topic = "~/" + sdf->GetAttribute("name")->GetAsString();
-  }
-
-  if (sdf->HasElement("torque")) {
-    torque = sdf->Get<double>("torque");
-  } else {
-    torque = 5;
-  }
-
-  gzmsg << "initializing servo: " << topic << " joint=" << joint->GetName()
-        << " torque=" << torque << std::endl;
-
-  // Connect to Gazebo transport for messaging
-  std::string scoped_name =
-      model->GetWorld()->Name() + "::" + model->GetScopedName();
-  boost::replace_all(scoped_name, "::", "/");
-  node = gazebo::transport::NodePtr(new gazebo::transport::Node());
-  node->Init(scoped_name);
-  sub = node->Subscribe(topic, &Servo::Callback, this);
-
-  // connect to the world update event
-  // this will call update every iteration
-  updateConn = gazebo::event::Events::ConnectWorldUpdateBegin(
-      boost::bind(&Servo::Update, this, _1));
-}
-
-void Servo::Update(const gazebo::common::UpdateInfo& info) {
-  // torque is in kg*cm
-  // joint->SetAngle(0,signal*180);
-  if (joint->Position(0) < signal) {
-    joint->SetForce(0, torque);
-  } else if (joint->Position(0) > signal) {
-    joint->SetForce(0, torque);
-  }
-  joint->SetForce(0, 0);
-}
-
-void Servo::Callback(const gazebo::msgs::ConstFloat64Ptr& msg) {
-  signal = msg->data();
-  if (signal < -1) {
-    signal = -1;
-  } else if (signal > 1) {
-    signal = 1;
-  }
-}
diff --git a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/servo/headers/servo.h b/third_party/allwpilib/simulation/frc_gazebo_plugins/src/servo/headers/servo.h
deleted file mode 100644
index d934385..0000000
--- a/third_party/allwpilib/simulation/frc_gazebo_plugins/src/servo/headers/servo.h
+++ /dev/null
@@ -1,67 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <string>
-
-#include <gazebo/gazebo.hh>
-
-#include "simulation/gz_msgs/msgs.h"
-
-/**
- * \brief Plugin for controlling a servo.
- *
- * This plugin subscribes to a topic to get a signal in the range
- * [-1,1]. Every physics update the joint's torque is set as
- * multiplier*signal.
- *
- * To add a servo to your robot, add the following XML to your robot
- * model:
- *
- *     <plugin name="my_servo" filename="libservo.so">
- *       <joint>Joint Name</joint>
- *       <topic>/gzebo/frc/simulator/pwm/1</topic>
- *       <zero_position>0</zero_position>
- *     </plugin>
- *
- * - `link`: Name of the link the servo is attached to.
- * - `topic`: Optional. Message type should be gazebo.msgs.Float64.
- */
-class Servo : public gazebo::ModelPlugin {
- public:
-  /// \brief load the servo and configure it according to the sdf
-  void Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf);
-
-  /// \brief Update the torque on the joint from the dc motor each timestep.
-  void Update(const gazebo::common::UpdateInfo& info);
-
- private:
-  /// \brief Topic to read control signal from.
-  std::string topic;
-
-  /// \brief the pwm signal limited to the range [-1,1]
-  double signal;
-
-  /// \brief the torque of the motor in kg/cm
-  double torque;
-
-  /// \brief the joint that this servo moves
-  gazebo::physics::JointPtr joint;
-
-  /// \brief Callback for receiving msgs and storing the signal
-  void Callback(const gazebo::msgs::ConstFloat64Ptr& msg);
-
-  /// \brief The model to which this is attached
-  gazebo::physics::ModelPtr model;
-
-  /// \brief The pointer to the world update function
-  gazebo::event::ConnectionPtr updateConn;
-
-  /// \brief The node on which we're advertising torque
-  gazebo::transport::NodePtr node;
-
-  /// \brief The subscriber for the PWM signal
-  gazebo::transport::SubscriberPtr sub;
-};
diff --git a/third_party/allwpilib/simulation/gz_msgs/README.md b/third_party/allwpilib/simulation/gz_msgs/README.md
deleted file mode 100644
index 6850be7..0000000
--- a/third_party/allwpilib/simulation/gz_msgs/README.md
+++ /dev/null
@@ -1,12 +0,0 @@
-gz_msgs
-=======
-gz_msgs is a library that allows the transmission of messages
-to and from Java and C++ programs.
-
-gz_msgs currently requires libprotobuf-dev on Debian like systems.
-
-If it's not found via pkg-config, then it's build is diabled.
-
-You can force it by specifying -PforceGazebo on the gradle command line.
-
-If you are installing FRCSim with the script, then this *should* have be done for you.
diff --git a/third_party/allwpilib/simulation/gz_msgs/build.gradle b/third_party/allwpilib/simulation/gz_msgs/build.gradle
deleted file mode 100644
index 31f3df4..0000000
--- a/third_party/allwpilib/simulation/gz_msgs/build.gradle
+++ /dev/null
@@ -1,99 +0,0 @@
-plugins {
-    id 'cpp'
-    id 'java'
-    id 'com.google.protobuf' version '0.8.17'
-    id 'edu.wpi.first.NativeUtils'
-}
-
-description = "A C++ and Java library to pass FRC Simulation Messages in and out of Gazebo."
-
-/* The simulation does not run on real hardware; so we always skip Athena */
-ext.skiplinuxathena = true
-ext.skiplinuxraspbian = true
-apply from: "${rootDir}/shared/config.gradle"
-
-/* Use a sort of poor man's autoconf to find the protobuf development
- files; on Debian, those are supplied by libprotobuf-dev.
- This should get skipped on Windows.
- TODO:  Add Windows support for the simulation code */
-
-def protobuf_version = ""
-try {
-    protobuf_version = "pkg-config --modversion protobuf".execute().text.trim()
-    println "Protobuf version is [${protobuf_version}]"
-} catch(Exception ex) {
-}
-
-ext.skip_gz_msgs = false
-
-if (project.hasProperty("forceGazebo")) {
-    if (!protobuf_version?.trim()) {
-        println "Protobuf is not available. (pkg-config --modversion protobuf failed)"
-        println "forceGazebo set. Forcing build - failure likely."
-    }
-} else {
-    ext.skip_gz_msgs = true
-    println "Skipping gz msgs."
-}
-
-tasks.whenTaskAdded { task ->
-    task.onlyIf { !project.hasProperty('skip_gz_msgs') }
-}
-
-if (!ext.skip_gz_msgs) {
-    dependencies {
-        implementation "com.google.protobuf:protobuf-java:${protobuf_version}"
-        implementation "com.google.protobuf:protoc:${protobuf_version}"
-    }
-}
-
-/* There is a nice gradle plugin for protobuf, and the protoc tool
- is included; using it simplifies our build process.
- The trick is that we have to use the same version as the system
- copy of libprotobuf-dev */
-protobuf {
-    protoc {
-        artifact = "com.google.protobuf:protoc:${protobuf_version}"
-    }
-
-    generatedFilesBaseDir = "$buildDir/generated"
-    generateProtoTasks {
-        all().each { task ->
-            task.builtins {
-                cpp {
-                    outputSubDir = 'simulation/gz_msgs'
-                }
-            }
-        }
-    }
-}
-
-model {
-    components {
-        gz_msgs(NativeLibrarySpec) {
-            sources {
-                cpp {
-                    source {
-                        srcDir "$buildDir/generated/main/simulation/gz_msgs"
-                        builtBy tasks.generateProto
-                    }
-                    exportedHeaders {
-                        srcDir "src/include"
-                        srcDir "$buildDir/generated/main"
-                    }
-                }
-            }
-            /* We must compile with -fPIC to link the static library into an so */
-            binaries {
-                all {
-                    cppCompiler.args "-fPIC"
-
-                    // Disable -Wzero-length-array on Clang
-                    if (it.targetPlatform.operatingSystem.isMacOsX()) {
-                        it.cppCompiler.args.add('-Wno-error=zero-length-array')
-                    }
-                }
-            }
-        }
-    }
-}
diff --git a/third_party/allwpilib/simulation/gz_msgs/src/include/simulation/gz_msgs/msgs.h b/third_party/allwpilib/simulation/gz_msgs/src/include/simulation/gz_msgs/msgs.h
deleted file mode 100644
index e953ad5..0000000
--- a/third_party/allwpilib/simulation/gz_msgs/src/include/simulation/gz_msgs/msgs.h
+++ /dev/null
@@ -1,47 +0,0 @@
-/* This was originally auto generated by cmake.
-   However, it changes infrequently enough that it makes
-   sense to simply revise it by hand any time we change
-   the protobuf messages expressed in the .proto files */
-
-#ifndef _FRC_MSGS_H_
-#define _FRC_MSGS_H_
-
-#ifdef _WIN32
-  //include this before anything else includes windows.h
-  //putting this here saves putting it in more files
-  #include <Winsock2.h>
-#endif
-
-
- #include "simulation/gz_msgs/bool.pb.h"
- #include "simulation/gz_msgs/driver-station.pb.h"
- #include "simulation/gz_msgs/float64.pb.h"
- #include "simulation/gz_msgs/frc_joystick.pb.h"
-
-
-#include <gazebo/msgs/msgs.hh>
-#include <boost/shared_ptr.hpp>
-
-namespace gazebo {
-  namespace msgs {
-
-    typedef GzString String;
-
-    typedef boost::shared_ptr< gazebo::msgs::String > StringPtr;
-    typedef const boost::shared_ptr< const gazebo::msgs::String > ConstStringPtr;
-
-    typedef boost::shared_ptr< msgs::Float64 > Float64Ptr;
-    typedef const boost::shared_ptr< const msgs::Float64 > ConstFloat64Ptr;
-
-    typedef boost::shared_ptr< msgs::Bool > BoolPtr;
-    typedef const boost::shared_ptr< const msgs::Bool > ConstBoolPtr;
-
-    typedef boost::shared_ptr< msgs::FRCJoystick > FRCJoystickPtr;
-    typedef const boost::shared_ptr< const msgs::FRCJoystick > ConstFRCJoystickPtr;
-
-    typedef boost::shared_ptr< msgs::DriverStation > DriverStationPtr;
-    typedef const boost::shared_ptr< const msgs::DriverStation > ConstDriverStationPtr;
-  }
-}
-
-#endif /* _FRC_MSGS_H_ */
diff --git a/third_party/allwpilib/simulation/gz_msgs/src/main/proto/bool.proto b/third_party/allwpilib/simulation/gz_msgs/src/main/proto/bool.proto
deleted file mode 100644
index 90ab7fa..0000000
--- a/third_party/allwpilib/simulation/gz_msgs/src/main/proto/bool.proto
+++ /dev/null
@@ -1,15 +0,0 @@
-package gazebo.msgs;
-
-/// \ingroup gazebo_msgs
-/// \interface Bool
-/// \brief A message for boolean data
-/// \verbatim
-
-option java_outer_classname = "GzBool";
-
-message Bool
-{
-  required bool data = 1;
-}
-
-/// \endverbatim
diff --git a/third_party/allwpilib/simulation/gz_msgs/src/main/proto/driver-station.proto b/third_party/allwpilib/simulation/gz_msgs/src/main/proto/driver-station.proto
deleted file mode 100644
index 187e056..0000000
--- a/third_party/allwpilib/simulation/gz_msgs/src/main/proto/driver-station.proto
+++ /dev/null
@@ -1,21 +0,0 @@
-package gazebo.msgs;
-
-/// \ingroup gazebo_msgs
-/// \interface DriverStation
-/// \brief A message for DriverStation data
-/// \verbatim
-
-option java_outer_classname = "GzDriverStation";
-
-message DriverStation
-{
-  required bool enabled = 1;
-  enum State {
-    AUTO = 0;
-    TELEOP = 1;
-    TEST = 2;
-  }
-  required State state = 2;
-}
-
-/// \endverbatim
diff --git a/third_party/allwpilib/simulation/gz_msgs/src/main/proto/float64.proto b/third_party/allwpilib/simulation/gz_msgs/src/main/proto/float64.proto
deleted file mode 100644
index dd3ddcc..0000000
--- a/third_party/allwpilib/simulation/gz_msgs/src/main/proto/float64.proto
+++ /dev/null
@@ -1,15 +0,0 @@
-package gazebo.msgs;
-
-/// \ingroup gazebo_msgs
-/// \interface Float64
-/// \brief A message for floating point data
-/// \verbatim
-
-option java_outer_classname = "GzFloat64";
-
-message Float64
-{
-  required double data = 1;
-}
-
-/// \endverbatim
diff --git a/third_party/allwpilib/simulation/gz_msgs/src/main/proto/frc_joystick.proto b/third_party/allwpilib/simulation/gz_msgs/src/main/proto/frc_joystick.proto
deleted file mode 100644
index ec98aba..0000000
--- a/third_party/allwpilib/simulation/gz_msgs/src/main/proto/frc_joystick.proto
+++ /dev/null
@@ -1,16 +0,0 @@
-package gazebo.msgs;
-
-/// \ingroup gazebo_msgs
-/// \interface Joystick
-/// \brief A message for joystick data
-/// \verbatim
-
-option java_outer_classname = "GzFRCJoystick";
-
-message FRCJoystick
-{
-  repeated double axes = 1;
-  repeated bool buttons = 2;
-}
-
-/// \endverbatim
diff --git a/third_party/allwpilib/simulation/halsim_ds_socket/CMakeLists.txt b/third_party/allwpilib/simulation/halsim_ds_socket/CMakeLists.txt
index bc9adb1..6d770d9 100644
--- a/third_party/allwpilib/simulation/halsim_ds_socket/CMakeLists.txt
+++ b/third_party/allwpilib/simulation/halsim_ds_socket/CMakeLists.txt
@@ -7,7 +7,7 @@
 add_library(halsim_ds_socket SHARED ${halsim_ds_socket_src})
 wpilib_target_warnings(halsim_ds_socket)
 set_target_properties(halsim_ds_socket PROPERTIES DEBUG_POSTFIX "d")
-target_link_libraries(halsim_ds_socket PUBLIC hal)
+target_link_libraries(halsim_ds_socket PUBLIC hal wpinet)
 
 target_include_directories(halsim_ds_socket PRIVATE src/main/native/include)
 
diff --git a/third_party/allwpilib/simulation/halsim_ds_socket/build.gradle b/third_party/allwpilib/simulation/halsim_ds_socket/build.gradle
index 63c5576..0e90938 100644
--- a/third_party/allwpilib/simulation/halsim_ds_socket/build.gradle
+++ b/third_party/allwpilib/simulation/halsim_ds_socket/build.gradle
@@ -21,7 +21,7 @@
 model {
     testSuites {
         def comps = $.components
-        if (!project.hasProperty('onlylinuxathena') && !project.hasProperty('onlylinuxraspbian') && !project.hasProperty('onlylinuxaarch64bionic')) {
+        if (!project.hasProperty('onlylinuxathena')) {
             "${pluginName}Test"(GoogleTestTestSuiteSpec) {
                 for(NativeComponentSpec c : comps) {
                     if (c.name == pluginName) {
@@ -44,8 +44,13 @@
         }
     }
     binaries {
+        all {
+            lib project: ':wpinet', library: 'wpinet', linkage: 'shared'
+            lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+        }
         withType(GoogleTestTestSuiteBinarySpec) {
             project(':hal').addHalDependency(it, 'shared')
+            lib project: ':wpinet', library: 'wpinet', linkage: 'shared'
             lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
             lib library: pluginName, linkage: 'shared'
             if (it.targetPlatform.name == nativeUtils.wpi.platforms.roborio) {
diff --git a/third_party/allwpilib/simulation/halsim_ds_socket/src/main/native/cpp/DSCommPacket.cpp b/third_party/allwpilib/simulation/halsim_ds_socket/src/main/native/cpp/DSCommPacket.cpp
index 653565c..004752c 100644
--- a/third_party/allwpilib/simulation/halsim_ds_socket/src/main/native/cpp/DSCommPacket.cpp
+++ b/third_party/allwpilib/simulation/halsim_ds_socket/src/main/native/cpp/DSCommPacket.cpp
@@ -7,12 +7,12 @@
 #include <algorithm>
 #include <chrono>
 #include <cstring>
+#include <span>
 #include <thread>
 #include <vector>
 
 #include <hal/simulation/DriverStationData.h>
 #include <hal/simulation/MockHooks.h>
-#include <wpi/span.h>
 
 using namespace halsim;
 
@@ -45,7 +45,7 @@
   m_alliance_station = static_cast<HAL_AllianceStationID>(station_code);
 }
 
-void DSCommPacket::ReadMatchtimeTag(wpi::span<const uint8_t> tagData) {
+void DSCommPacket::ReadMatchtimeTag(std::span<const uint8_t> tagData) {
   if (tagData.size() < 6) {
     return;
   }
@@ -63,7 +63,7 @@
   m_match_time = matchTime;
 }
 
-void DSCommPacket::ReadJoystickTag(wpi::span<const uint8_t> dataInput,
+void DSCommPacket::ReadJoystickTag(std::span<const uint8_t> dataInput,
                                    int index) {
   DSCommJoystickPacket& stick = m_joystick_packets[index];
   stick.ResetUdp();
@@ -112,7 +112,7 @@
 /*----------------------------------------------------------------------------
 **  Communication methods
 **--------------------------------------------------------------------------*/
-void DSCommPacket::DecodeTCP(wpi::span<const uint8_t> packet) {
+void DSCommPacket::DecodeTCP(std::span<const uint8_t> packet) {
   // No header
   while (!packet.empty()) {
     int tagLength = packet[0] << 8 | packet[1];
@@ -137,7 +137,7 @@
   }
 }
 
-void DSCommPacket::DecodeUDP(wpi::span<const uint8_t> packet) {
+void DSCommPacket::DecodeUDP(std::span<const uint8_t> packet) {
   if (packet.size() < 6) {
     return;
   }
@@ -176,7 +176,7 @@
   }
 }
 
-void DSCommPacket::ReadNewMatchInfoTag(wpi::span<const uint8_t> data) {
+void DSCommPacket::ReadNewMatchInfoTag(std::span<const uint8_t> data) {
   // Size 2 bytes, tag 1 byte
   if (data.size() <= 3) {
     return;
@@ -204,7 +204,7 @@
   HALSIM_SetMatchInfo(&matchInfo);
 }
 
-void DSCommPacket::ReadGameSpecificMessageTag(wpi::span<const uint8_t> data) {
+void DSCommPacket::ReadGameSpecificMessageTag(std::span<const uint8_t> data) {
   // Size 2 bytes, tag 1 byte
   if (data.size() <= 3) {
     return;
@@ -220,7 +220,7 @@
 
   HALSIM_SetMatchInfo(&matchInfo);
 }
-void DSCommPacket::ReadJoystickDescriptionTag(wpi::span<const uint8_t> data) {
+void DSCommPacket::ReadJoystickDescriptionTag(std::span<const uint8_t> data) {
   if (data.size() < 3) {
     return;
   }
diff --git a/third_party/allwpilib/simulation/halsim_ds_socket/src/main/native/cpp/main.cpp b/third_party/allwpilib/simulation/halsim_ds_socket/src/main/native/cpp/main.cpp
index 799cdd9..af84632 100644
--- a/third_party/allwpilib/simulation/halsim_ds_socket/src/main/native/cpp/main.cpp
+++ b/third_party/allwpilib/simulation/halsim_ds_socket/src/main/native/cpp/main.cpp
@@ -21,12 +21,12 @@
 #include <DSCommPacket.h>
 #include <fmt/format.h>
 #include <hal/Extensions.h>
-#include <wpi/EventLoopRunner.h>
-#include <wpi/raw_uv_ostream.h>
-#include <wpi/uv/Tcp.h>
-#include <wpi/uv/Timer.h>
-#include <wpi/uv/Udp.h>
-#include <wpi/uv/util.h>
+#include <wpinet/EventLoopRunner.h>
+#include <wpinet/raw_uv_ostream.h>
+#include <wpinet/uv/Tcp.h>
+#include <wpinet/uv/Timer.h>
+#include <wpinet/uv/Udp.h>
+#include <wpinet/uv/util.h>
 
 #if defined(Win32) || defined(_WIN32)
 #pragma comment(lib, "Ws2_32.lib")
diff --git a/third_party/allwpilib/simulation/halsim_ds_socket/src/main/native/include/DSCommPacket.h b/third_party/allwpilib/simulation/halsim_ds_socket/src/main/native/include/DSCommPacket.h
index 5b8b45d..bfc42c3 100644
--- a/third_party/allwpilib/simulation/halsim_ds_socket/src/main/native/include/DSCommPacket.h
+++ b/third_party/allwpilib/simulation/halsim_ds_socket/src/main/native/include/DSCommPacket.h
@@ -5,11 +5,11 @@
 #pragma once
 
 #include <array>
+#include <span>
 
 #include <DSCommJoystickPacket.h>
 #include <hal/simulation/DriverStationData.h>
-#include <wpi/raw_uv_ostream.h>
-#include <wpi/span.h>
+#include <wpinet/raw_uv_ostream.h>
 
 class DSCommPacketTest;
 
@@ -20,8 +20,8 @@
 
  public:
   DSCommPacket(void);
-  void DecodeTCP(wpi::span<const uint8_t> packet);
-  void DecodeUDP(wpi::span<const uint8_t> packet);
+  void DecodeTCP(std::span<const uint8_t> packet);
+  void DecodeUDP(std::span<const uint8_t> packet);
   void SendUDPToHALSim(void);
   void SetupSendBuffer(wpi::raw_uv_ostream& buf);
 
@@ -53,11 +53,11 @@
   void SetAlliance(uint8_t station_code);
   void SetupSendHeader(wpi::raw_uv_ostream& buf);
   void SetupJoystickTag(wpi::raw_uv_ostream& buf);
-  void ReadMatchtimeTag(wpi::span<const uint8_t> tagData);
-  void ReadJoystickTag(wpi::span<const uint8_t> data, int index);
-  void ReadNewMatchInfoTag(wpi::span<const uint8_t> data);
-  void ReadGameSpecificMessageTag(wpi::span<const uint8_t> data);
-  void ReadJoystickDescriptionTag(wpi::span<const uint8_t> data);
+  void ReadMatchtimeTag(std::span<const uint8_t> tagData);
+  void ReadJoystickTag(std::span<const uint8_t> data, int index);
+  void ReadNewMatchInfoTag(std::span<const uint8_t> data);
+  void ReadGameSpecificMessageTag(std::span<const uint8_t> data);
+  void ReadJoystickDescriptionTag(std::span<const uint8_t> data);
 
   uint8_t m_hi;
   uint8_t m_lo;
diff --git a/third_party/allwpilib/simulation/halsim_ds_socket/src/test/native/cpp/DSCommPacketTest.cpp b/third_party/allwpilib/simulation/halsim_ds_socket/src/test/native/cpp/DSCommPacketTest.cpp
index 84df27c..d1a892a 100644
--- a/third_party/allwpilib/simulation/halsim_ds_socket/src/test/native/cpp/DSCommPacketTest.cpp
+++ b/third_party/allwpilib/simulation/halsim_ds_socket/src/test/native/cpp/DSCommPacketTest.cpp
@@ -11,24 +11,24 @@
 
   void SendJoysticks() { commPacket.SendJoysticks(); }
 
-  halsim::DSCommJoystickPacket& ReadJoystickTag(wpi::span<const uint8_t> data,
+  halsim::DSCommJoystickPacket& ReadJoystickTag(std::span<const uint8_t> data,
                                                 int index) {
     commPacket.ReadJoystickTag(data, index);
     return commPacket.m_joystick_packets[index];
   }
 
   halsim::DSCommJoystickPacket& ReadDescriptorTag(
-      wpi::span<const uint8_t> data) {
+      std::span<const uint8_t> data) {
     commPacket.ReadJoystickDescriptionTag(data);
     return commPacket.m_joystick_packets[data[3]];
   }
 
-  HAL_MatchInfo& ReadNewMatchInfoTag(wpi::span<const uint8_t> data) {
+  HAL_MatchInfo& ReadNewMatchInfoTag(std::span<const uint8_t> data) {
     commPacket.ReadNewMatchInfoTag(data);
     return commPacket.matchInfo;
   }
 
-  HAL_MatchInfo& ReadGameSpecificTag(wpi::span<const uint8_t> data) {
+  HAL_MatchInfo& ReadGameSpecificTag(std::span<const uint8_t> data) {
     commPacket.ReadGameSpecificMessageTag(data);
     return commPacket.matchInfo;
   }
diff --git a/third_party/allwpilib/simulation/halsim_gazebo/build.gradle b/third_party/allwpilib/simulation/halsim_gazebo/build.gradle
deleted file mode 100644
index 8d340d3..0000000
--- a/third_party/allwpilib/simulation/halsim_gazebo/build.gradle
+++ /dev/null
@@ -1,55 +0,0 @@
-description = "A shared object library that will interface between a robot and the Gazebo plugins."
-
-apply plugin: 'edu.wpi.first.NativeUtils'
-apply plugin: 'cpp'
-
-ext.skiplinuxathena = true
-ext.skiplinuxraspbian = true
-ext.pluginName = 'halsim_gazebo'
-
-/* If gz_msgs or gazebo is not available, do not attempt a build */
-def gazebo_version = ""
-def gazebo_cppflags = ""
-def gazebo_linker_args = ""
-
-try {
-    gazebo_version = "pkg-config --modversion gazebo".execute().text.trim()
-    println "Gazebo version is [${gazebo_version}]"
-    gazebo_cppflags = "pkg-config --cflags gazebo".execute().text.split()
-    gazebo_linker_args = "pkg-config --libs gazebo protobuf".execute().text.split()
-} catch(Exception ex) { }
-
-if (project.hasProperty("forceGazebo")) {
-    if (!gazebo_version?.trim()) {
-        println "Gazebo development files are not available. (pkg-config --modversion gazebo failed)"
-        println "forceGazebo set. Forcing build - failure likely."
-    }
-} else {
-    ext.skip_frc_plugins = true
-    println "Skipping FRC Plugins."
-}
-
-evaluationDependsOn(":simulation:gz_msgs")
-def gz_msgs_project = project(":simulation:gz_msgs")
-
-if (!gz_msgs_project.hasProperty('skip_gz_msgs') && !project.hasProperty('skip_frc_plugins')) {
-
-    apply from: "${rootDir}/shared/plugins/setupBuild.gradle"
-}
-
-model {
-    binaries {
-        all {
-            if (it instanceof StaticLibraryBinarySpec) {
-                it.buildable = false
-                return
-            }
-            linker.args gazebo_linker_args
-            cppCompiler.args gazebo_cppflags
-            lib project: ":simulation:gz_msgs", library: "gz_msgs", linkage: "static"
-            lib project: ":wpiutil", library: "wpiutil", linkage: "static"
-        }
-    }
-}
-
-/* TODO: Publish this library */
diff --git a/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/cpp/GazeboAnalogIn.cpp b/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/cpp/GazeboAnalogIn.cpp
deleted file mode 100644
index d9ce9a9..0000000
--- a/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/cpp/GazeboAnalogIn.cpp
+++ /dev/null
@@ -1,42 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "GazeboAnalogIn.h"
-
-#include <fmt/format.h>
-#include <hal/Power.h>
-#include <hal/Value.h>
-#include <hal/simulation/AnalogInData.h>
-#include <hal/simulation/NotifyListener.h>
-
-static void init_callback(const char* name, void* param,
-                          const struct HAL_Value* value) {
-  GazeboAnalogIn* ain = static_cast<GazeboAnalogIn*>(param);
-  ain->SetInitialized(value->data.v_boolean);
-  if (ain->IsInitialized()) {
-    ain->Listen();
-  }
-}
-
-GazeboAnalogIn::GazeboAnalogIn(int index, HALSimGazebo* halsim) {
-  m_index = index;
-  m_halsim = halsim;
-  m_sub = NULL;
-  HALSIM_RegisterAnalogInInitializedCallback(index, init_callback, this, true);
-}
-
-void GazeboAnalogIn::Listen() {
-  if (!m_sub)
-    m_sub = m_halsim->node.Subscribe<gazebo::msgs::Float64>(
-        fmt::format("~/simulator/analog/{}", m_index),
-        &GazeboAnalogIn::Callback, this);
-}
-
-void GazeboAnalogIn::Callback(const gazebo::msgs::ConstFloat64Ptr& msg) {
-  /* This value is going to be divided by the 5V rail in the HAL, so
-     we multiply by that value to make the change neutral */
-  int32_t status = 0;
-  HALSIM_SetAnalogInVoltage(m_index,
-                            msg->data() * HAL_GetUserVoltage5V(&status));
-}
diff --git a/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/cpp/GazeboDIO.cpp b/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/cpp/GazeboDIO.cpp
deleted file mode 100644
index 85d4ea6..0000000
--- a/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/cpp/GazeboDIO.cpp
+++ /dev/null
@@ -1,36 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "GazeboDIO.h"
-
-#include <fmt/format.h>
-#include <hal/Value.h>
-#include <hal/simulation/DIOData.h>
-#include <hal/simulation/NotifyListener.h>
-
-static void init_callback(const char* name, void* param,
-                          const struct HAL_Value* value) {
-  GazeboDIO* dio = static_cast<GazeboDIO*>(param);
-  dio->SetInitialized(value->data.v_boolean);
-  if (dio->IsInitialized()) {
-    dio->Listen();
-  }
-}
-
-GazeboDIO::GazeboDIO(int index, HALSimGazebo* halsim) {
-  m_index = index;
-  m_halsim = halsim;
-  m_sub = NULL;
-  HALSIM_RegisterDIOInitializedCallback(index, init_callback, this, true);
-}
-
-void GazeboDIO::Listen() {
-  if (!m_sub)
-    m_sub = m_halsim->node.Subscribe<gazebo::msgs::Bool>(
-        fmt::format("~/simulator/dio/{}", m_index), &GazeboDIO::Callback, this);
-}
-
-void GazeboDIO::Callback(const gazebo::msgs::ConstBoolPtr& msg) {
-  HALSIM_SetDIOValue(m_index, msg->data());
-}
diff --git a/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/cpp/GazeboEncoder.cpp b/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/cpp/GazeboEncoder.cpp
deleted file mode 100644
index 519bf2b..0000000
--- a/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/cpp/GazeboEncoder.cpp
+++ /dev/null
@@ -1,73 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "GazeboEncoder.h"
-
-#include <fmt/format.h>
-#include <hal/Value.h>
-#include <hal/simulation/EncoderData.h>
-#include <hal/simulation/NotifyListener.h>
-
-static void encoder_init_callback(const char* name, void* param,
-                                  const struct HAL_Value* value) {
-  GazeboEncoder* encoder = static_cast<GazeboEncoder*>(param);
-  encoder->SetInitialized(value->data.v_boolean);
-  if (encoder->IsInitialized()) {
-    encoder->Control("start");
-    encoder->Listen();
-  }
-}
-
-static void encoder_reset_callback(const char* name, void* param,
-                                   const struct HAL_Value* value) {
-  GazeboEncoder* encoder = static_cast<GazeboEncoder*>(param);
-  if (encoder->IsInitialized() && value->data.v_boolean)
-    encoder->Control("reset");
-}
-
-static void encoder_reverse_callback(const char* name, void* param,
-                                     const struct HAL_Value* value) {
-  GazeboEncoder* encoder = static_cast<GazeboEncoder*>(param);
-  if (encoder->IsInitialized())
-    encoder->SetReverse(value->data.v_boolean);
-}
-
-GazeboEncoder::GazeboEncoder(int index, HALSimGazebo* halsim) {
-  m_index = index;
-  m_halsim = halsim;
-  m_reverse = false;
-  m_pub = NULL;
-  m_sub = NULL;
-  HALSIM_RegisterEncoderInitializedCallback(index, encoder_init_callback, this,
-                                            true);
-  HALSIM_RegisterEncoderResetCallback(index, encoder_reset_callback, this,
-                                      true);
-  HALSIM_RegisterEncoderReverseDirectionCallback(
-      index, encoder_reverse_callback, this, true);
-}
-
-void GazeboEncoder::Control(const char* command) {
-  if (!m_pub) {
-    m_pub = m_halsim->node.Advertise<gazebo::msgs::String>(
-        fmt::format("~/simulator/encoder/dio/{}/control",
-                    HALSIM_GetEncoderDigitalChannelA(m_index)));
-    m_pub->WaitForConnection(gazebo::common::Time(1, 0));
-  }
-  gazebo::msgs::String msg;
-  msg.set_data(command);
-  if (m_pub)
-    m_pub->Publish(msg);
-}
-
-void GazeboEncoder::Listen() {
-  if (!m_sub)
-    m_sub = m_halsim->node.Subscribe<gazebo::msgs::Float64>(
-        fmt::format("~/simulator/encoder/dio/{}/position",
-                    HALSIM_GetEncoderDigitalChannelA(m_index)),
-        &GazeboEncoder::Callback, this);
-}
-
-void GazeboEncoder::Callback(const gazebo::msgs::ConstFloat64Ptr& msg) {
-  HALSIM_SetEncoderCount(m_index, msg->data() * (m_reverse ? -1 : 1));
-}
diff --git a/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/cpp/GazeboNode.cpp b/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/cpp/GazeboNode.cpp
deleted file mode 100644
index 1c847ca..0000000
--- a/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/cpp/GazeboNode.cpp
+++ /dev/null
@@ -1,17 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "GazeboNode.h"
-
-bool GazeboNode::Connect() {
-  bool success = gazebo::client::setup();
-
-  if (success) {
-    main = gazebo::transport::NodePtr(new gazebo::transport::Node());
-    main->Init("frc");
-    gazebo::transport::run();
-  }
-
-  return success;
-}
diff --git a/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/cpp/GazeboPCM.cpp b/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/cpp/GazeboPCM.cpp
deleted file mode 100644
index 2549061..0000000
--- a/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/cpp/GazeboPCM.cpp
+++ /dev/null
@@ -1,51 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "GazeboPCM.h"
-
-#include <fmt/format.h>
-#include <hal/Value.h>
-#include <hal/simulation/CTREPCMData.h>
-#include <hal/simulation/NotifyListener.h>
-
-#include "simulation/gz_msgs/msgs.h"
-
-static void init_callback(const char* name, void* param,
-                          const struct HAL_Value* value) {
-  GazeboPCM* pcm = static_cast<GazeboPCM*>(param);
-  pcm->SetInitialized(value->data.v_boolean);
-}
-
-static void output_callback(const char* name, void* param,
-                            const struct HAL_Value* value) {
-  GazeboPCM* pcm = static_cast<GazeboPCM*>(param);
-  if (pcm->IsInitialized())
-    pcm->Publish(value->data.v_boolean);
-}
-
-GazeboPCM::GazeboPCM(int index, int channel, HALSimGazebo* halsim) {
-  m_index = index;
-  m_channel = channel;
-  m_halsim = halsim;
-  m_pub = NULL;
-  HALSIM_RegisterCTREPCMInitializedCallback(index, init_callback, this, true);
-  HALSIM_RegisterCTREPCMSolenoidOutputCallback(index, channel, output_callback,
-                                               this, true);
-}
-
-void GazeboPCM::Publish(bool value) {
-  if (!m_pub) {
-    m_pub = m_halsim->node.Advertise<gazebo::msgs::Bool>(
-        fmt::format("~/simulator/pneumatic/{}/{}", m_index + 1, m_channel));
-    m_pub->WaitForConnection(gazebo::common::Time(1, 0));
-  }
-  gazebo::msgs::Bool msg;
-  msg.set_data(value);
-  if (m_pub)
-    m_pub->Publish(msg);
-}
-
-void GazeboPCM_SetPressureSwitch(int index, bool value) {
-  HALSIM_SetCTREPCMPressureSwitch(index, value);
-}
diff --git a/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/cpp/GazeboPWM.cpp b/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/cpp/GazeboPWM.cpp
deleted file mode 100644
index 0780f07..0000000
--- a/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/cpp/GazeboPWM.cpp
+++ /dev/null
@@ -1,44 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "GazeboPWM.h"
-
-#include <fmt/format.h>
-#include <hal/Value.h>
-#include <hal/simulation/NotifyListener.h>
-#include <hal/simulation/PWMData.h>
-
-#include "simulation/gz_msgs/msgs.h"
-
-static void init_callback(const char* name, void* param,
-                          const struct HAL_Value* value) {
-  GazeboPWM* pwm = static_cast<GazeboPWM*>(param);
-  pwm->SetInitialized(value->data.v_boolean);
-}
-
-static void speed_callback(const char* name, void* param,
-                           const struct HAL_Value* value) {
-  GazeboPWM* pwm = static_cast<GazeboPWM*>(param);
-  if (pwm->IsInitialized())
-    pwm->Publish(value->data.v_double);
-}
-
-GazeboPWM::GazeboPWM(int port, HALSimGazebo* halsim) {
-  m_port = port;
-  m_halsim = halsim;
-  HALSIM_RegisterPWMInitializedCallback(port, init_callback, this, true);
-  HALSIM_RegisterPWMSpeedCallback(port, speed_callback, this, true);
-}
-
-void GazeboPWM::Publish(double value) {
-  if (!m_pub) {
-    m_pub = m_halsim->node.Advertise<gazebo::msgs::Float64>(
-        fmt::format("~/simulator/pwm/{}", m_port));
-    m_pub->WaitForConnection(gazebo::common::Time(1, 0));
-  }
-  gazebo::msgs::Float64 msg;
-  msg.set_data(value);
-  if (m_pub)
-    m_pub->Publish(msg);
-}
diff --git a/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/cpp/main.cpp b/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/cpp/main.cpp
deleted file mode 100644
index a3d0576..0000000
--- a/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/cpp/main.cpp
+++ /dev/null
@@ -1,50 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include <fmt/core.h>
-#include <hal/Ports.h>
-
-#include "GazeboAnalogIn.h"
-#include "GazeboDIO.h"
-#include "GazeboEncoder.h"
-#include "GazeboPCM.h"
-#include "GazeboPWM.h"
-#include "HALSimGazebo.h"
-
-/* Currently, robots never terminate, so we keep a single static object
-   to access Gazebo with and it is never properly released or cleaned up. */
-static HALSimGazebo halsim;
-
-extern "C" {
-int HALSIM_InitExtension(void) {
-  fmt::print("Gazebo Simulator Initializing.\n");
-
-  if (!halsim.node.Connect()) {
-    fmt::print(stderr,
-               "Error: unable to connect to Gazebo.  Is it running?.\n");
-    return -1;
-  }
-  fmt::print("Gazebo Simulator Connected.\n");
-
-  for (int i = 0; i < HALSimGazebo::kPWMCount; i++)
-    halsim.pwms[i] = new GazeboPWM(i, &halsim);
-
-  for (int i = 0; i < HALSimGazebo::kPCMCount; i++)
-    halsim.pcms[i] = new GazeboPCM(0, i, &halsim);
-  GazeboPCM_SetPressureSwitch(0, true);
-
-  for (int i = 0; i < HALSimGazebo::kEncoderCount; i++)
-    halsim.encoders[i] = new GazeboEncoder(i, &halsim);
-
-  int analog_in_count = HAL_GetNumAnalogInputs();
-  for (int i = 0; i < analog_in_count; i++)
-    halsim.analog_inputs.push_back(new GazeboAnalogIn(i, &halsim));
-
-  int dio_count = HAL_GetNumDigitalChannels();
-  for (int i = 0; i < dio_count; i++)
-    halsim.dios.push_back(new GazeboDIO(i, &halsim));
-
-  return 0;
-}
-}  // extern "C"
diff --git a/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/include/GazeboAnalogIn.h b/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/include/GazeboAnalogIn.h
deleted file mode 100644
index c54db0d..0000000
--- a/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/include/GazeboAnalogIn.h
+++ /dev/null
@@ -1,23 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include "HALSimGazebo.h"
-#include "simulation/gz_msgs/msgs.h"
-
-class GazeboAnalogIn {
- public:
-  GazeboAnalogIn(int index, HALSimGazebo* halsim);
-  void SetInitialized(bool value) { m_initialized = value; }
-  bool IsInitialized(void) { return m_initialized; }
-  void Listen(void);
-
- private:
-  HALSimGazebo* m_halsim;
-  int m_index;
-  bool m_initialized;
-  void Callback(const gazebo::msgs::ConstFloat64Ptr& msg);
-  gazebo::transport::SubscriberPtr m_sub;
-};
diff --git a/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/include/GazeboDIO.h b/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/include/GazeboDIO.h
deleted file mode 100644
index 25ef0ad..0000000
--- a/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/include/GazeboDIO.h
+++ /dev/null
@@ -1,23 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include "HALSimGazebo.h"
-#include "simulation/gz_msgs/msgs.h"
-
-class GazeboDIO {
- public:
-  GazeboDIO(int index, HALSimGazebo* halsim);
-  void SetInitialized(bool value) { m_initialized = value; }
-  bool IsInitialized(void) { return m_initialized; }
-  void Listen(void);
-
- private:
-  HALSimGazebo* m_halsim;
-  int m_index;
-  bool m_initialized;
-  void Callback(const gazebo::msgs::ConstBoolPtr& msg);
-  gazebo::transport::SubscriberPtr m_sub;
-};
diff --git a/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/include/GazeboEncoder.h b/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/include/GazeboEncoder.h
deleted file mode 100644
index b25a688..0000000
--- a/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/include/GazeboEncoder.h
+++ /dev/null
@@ -1,29 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include "HALSimGazebo.h"
-#include "simulation/gz_msgs/msgs.h"
-
-class GazeboEncoder {
- public:
-  GazeboEncoder(int index, HALSimGazebo* halsim);
-  void SetInitialized(bool value) { m_initialized = value; }
-  bool IsInitialized(void) { return m_initialized; }
-  void SetReverse(bool value) { m_reverse = value; }
-  void Control(const char* command);
-  void Listen(void);
-
- private:
-  HALSimGazebo* m_halsim;
-  int m_index;
-  bool m_initialized;
-  bool m_reverse;
-
-  void Callback(const gazebo::msgs::ConstFloat64Ptr& msg);
-
-  gazebo::transport::PublisherPtr m_pub;
-  gazebo::transport::SubscriberPtr m_sub;
-};
diff --git a/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/include/GazeboNode.h b/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/include/GazeboNode.h
deleted file mode 100644
index 75acc55..0000000
--- a/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/include/GazeboNode.h
+++ /dev/null
@@ -1,40 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <string>
-
-#include <gazebo/gazebo_client.hh>
-#include <gazebo/transport/transport.hh>
-
-class GazeboNode {
- public:
-  bool Connect();
-
-  template <typename M>
-  gazebo::transport::PublisherPtr Advertise(const std::string& topic,
-                                            int queueLimit = 10,
-                                            bool latch = false) {
-    return main->Advertise<M>(topic, queueLimit, latch);
-  }
-
-  template <typename M, typename T>
-  gazebo::transport::SubscriberPtr Subscribe(
-      const std::string& topic,
-      void (T::*fp)(const boost::shared_ptr<M const>&), T* obj,
-      bool latching = false) {
-    return main->Subscribe(topic, fp, obj, latching);
-  }
-
-  template <typename M>
-  gazebo::transport::SubscriberPtr Subscribe(
-      const std::string& topic, void (*fp)(const boost::shared_ptr<M const>&),
-      bool latching = false) {
-    return main->Subscribe(topic, fp, latching);
-  }
-
- private:
-  gazebo::transport::NodePtr main;
-};
diff --git a/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/include/GazeboPCM.h b/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/include/GazeboPCM.h
deleted file mode 100644
index f964f3f..0000000
--- a/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/include/GazeboPCM.h
+++ /dev/null
@@ -1,26 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include "HALSimGazebo.h"
-
-class GazeboPCM {
- public:
-  GazeboPCM(int index, int channel, HALSimGazebo* halsim);
-  void Publish(bool value);
-  void SetInitialized(bool value) { m_initialized = value; }
-  bool IsInitialized(void) { return m_initialized; }
-
- private:
-  HALSimGazebo* m_halsim;
-  int m_index;
-  int m_channel;
-
-  bool m_initialized;
-
-  gazebo::transport::PublisherPtr m_pub;
-};
-
-void GazeboPCM_SetPressureSwitch(int index, bool value);
diff --git a/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/include/GazeboPWM.h b/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/include/GazeboPWM.h
deleted file mode 100644
index f4b131f..0000000
--- a/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/include/GazeboPWM.h
+++ /dev/null
@@ -1,21 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include "HALSimGazebo.h"
-
-class GazeboPWM {
- public:
-  GazeboPWM(int port, HALSimGazebo* halsim);
-  void SetInitialized(bool value) { m_initialized = value; }
-  bool IsInitialized(void) { return m_initialized; }
-  void Publish(double value);
-
- private:
-  HALSimGazebo* m_halsim;
-  gazebo::transport::PublisherPtr m_pub;
-  bool m_initialized;
-  int m_port;
-};
diff --git a/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/include/HALSimGazebo.h b/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/include/HALSimGazebo.h
deleted file mode 100644
index c1e454a..0000000
--- a/third_party/allwpilib/simulation/halsim_gazebo/src/main/native/include/HALSimGazebo.h
+++ /dev/null
@@ -1,29 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <vector>
-
-#include "GazeboNode.h"
-
-class GazeboPWM;
-class GazeboPCM;
-class GazeboEncoder;
-class GazeboAnalogIn;
-class GazeboDIO;
-
-class HALSimGazebo {
- public:
-  static const int kPWMCount = 20;
-  static const int kPCMCount = 8;
-  static const int kEncoderCount = 8;
-
-  GazeboNode node;
-  GazeboPWM* pwms[kPWMCount];
-  GazeboPCM* pcms[kPCMCount];
-  GazeboEncoder* encoders[kEncoderCount];
-  std::vector<GazeboAnalogIn*> analog_inputs;
-  std::vector<GazeboDIO*> dios;
-};
diff --git a/third_party/allwpilib/simulation/halsim_gui/build.gradle b/third_party/allwpilib/simulation/halsim_gui/build.gradle
index 7c26ac8..a8608e3 100644
--- a/third_party/allwpilib/simulation/halsim_gui/build.gradle
+++ b/third_party/allwpilib/simulation/halsim_gui/build.gradle
@@ -1,4 +1,4 @@
-if (!project.hasProperty('onlylinuxathena') && !project.hasProperty('onlylinuxraspbian') && !project.hasProperty('onlylinuxaarch64bionic')) {
+if (!project.hasProperty('onlylinuxathena')) {
 
     description = "A plugin that creates a simulation gui"
 
@@ -18,6 +18,9 @@
 
     apply from: "${rootDir}/shared/plugins/setupBuild.gradle"
 
+
+    apply from: "${rootDir}/shared/imgui.gradle"
+
     model {
         binaries {
             all {
@@ -25,10 +28,11 @@
                 lib project: ':glass', library: 'glass', linkage: 'static'
                 lib project: ':wpigui', library: 'wpigui', linkage: 'static'
                 lib project: ':wpimath', library: 'wpimath', linkage: 'shared'
-                lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
+                project(':ntcore').addNtcoreDependency(it, 'shared')
+                lib project: ':wpinet', library: 'wpinet', linkage: 'shared'
                 lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
-                nativeUtils.useRequiredLibrary(it, 'imgui_static')
-                if (it.targetPlatform.name == nativeUtils.wpi.platforms.roborio || it.targetPlatform.name == nativeUtils.wpi.platforms.raspbian || it.targetPlatform.name == nativeUtils.wpi.platforms.aarch64bionic) {
+                nativeUtils.useRequiredLibrary(it, 'imgui')
+                if (it.targetPlatform.name == nativeUtils.wpi.platforms.roborio) {
                     it.buildable = false
                     return
                 }
@@ -38,6 +42,9 @@
                     it.linker.args << '-framework' << 'Metal' << '-framework' << 'MetalKit' << '-framework' << 'Cocoa' << '-framework' << 'IOKit' << '-framework' << 'CoreFoundation' << '-framework' << 'CoreVideo' << '-framework' << 'QuartzCore'
                 } else {
                     it.linker.args << '-lX11'
+                    if (it.targetPlatform.name.startsWith('linuxarm')) {
+                        it.linker.args << '-lGL'
+                    }
                 }
             }
         }
diff --git a/third_party/allwpilib/simulation/halsim_gui/src/main/native/cpp/AddressableLEDGui.cpp b/third_party/allwpilib/simulation/halsim_gui/src/main/native/cpp/AddressableLEDGui.cpp
index d6409cd..2528185 100644
--- a/third_party/allwpilib/simulation/halsim_gui/src/main/native/cpp/AddressableLEDGui.cpp
+++ b/third_party/allwpilib/simulation/halsim_gui/src/main/native/cpp/AddressableLEDGui.cpp
@@ -26,7 +26,7 @@
 
   bool IsRunning() override { return HALSIM_GetAddressableLEDRunning(m_index); }
 
-  wpi::span<const Data> GetData(wpi::SmallVectorImpl<Data>&) override {
+  std::span<const Data> GetData(wpi::SmallVectorImpl<Data>&) override {
     size_t length = HALSIM_GetAddressableLEDData(m_index, m_data);
     return {reinterpret_cast<Data*>(m_data), length};
   }
diff --git a/third_party/allwpilib/simulation/halsim_gui/src/main/native/cpp/DriverStationGui.cpp b/third_party/allwpilib/simulation/halsim_gui/src/main/native/cpp/DriverStationGui.cpp
index 866b14a..e7271fd 100644
--- a/third_party/allwpilib/simulation/halsim_gui/src/main/native/cpp/DriverStationGui.cpp
+++ b/third_party/allwpilib/simulation/halsim_gui/src/main/native/cpp/DriverStationGui.cpp
@@ -254,8 +254,8 @@
   void SetAutonomous(bool val) override {
     HALSIM_SetDriverStationAutonomous(val);
   }
-  void SetGameSpecificMessage(const char* val) override {
-    HALSIM_SetGameSpecificMessage(val);
+  void SetGameSpecificMessage(std::string_view val) override {
+    HALSIM_SetGameSpecificMessage(val.data(), val.size());
   }
 
   void Update() override;
diff --git a/third_party/allwpilib/simulation/halsim_gui/src/main/native/cpp/NetworkTablesSimGui.cpp b/third_party/allwpilib/simulation/halsim_gui/src/main/native/cpp/NetworkTablesSimGui.cpp
index 325673a..30f1232 100644
--- a/third_party/allwpilib/simulation/halsim_gui/src/main/native/cpp/NetworkTablesSimGui.cpp
+++ b/third_party/allwpilib/simulation/halsim_gui/src/main/native/cpp/NetworkTablesSimGui.cpp
@@ -16,10 +16,12 @@
 
 static std::unique_ptr<glass::NetworkTablesModel> gNetworkTablesModel;
 static std::unique_ptr<glass::Window> gNetworkTablesWindow;
+static std::unique_ptr<glass::Window> gNetworkTablesInfoWindow;
 
 void NetworkTablesSimGui::Initialize() {
   gNetworkTablesModel = std::make_unique<glass::NetworkTablesModel>();
   wpi::gui::AddEarlyExecute([] { gNetworkTablesModel->Update(); });
+
   gNetworkTablesWindow = std::make_unique<glass::Window>(
       glass::GetStorageRoot().GetChild("NetworkTables View"), "NetworkTables");
   gNetworkTablesWindow->SetView(
@@ -29,9 +31,22 @@
   gNetworkTablesWindow->DisableRenamePopup();
   wpi::gui::AddLateExecute([] { gNetworkTablesWindow->Display(); });
 
+  // NetworkTables info window
+  gNetworkTablesInfoWindow = std::make_unique<glass::Window>(
+      glass::GetStorageRoot().GetChild("NetworkTables Info"),
+      "NetworkTables Info");
+  gNetworkTablesInfoWindow->SetView(glass::MakeFunctionView(
+      [&] { glass::DisplayNetworkTablesInfo(gNetworkTablesModel.get()); }));
+  gNetworkTablesInfoWindow->SetDefaultPos(250, 130);
+  gNetworkTablesInfoWindow->SetDefaultSize(750, 145);
+  gNetworkTablesInfoWindow->SetDefaultVisibility(glass::Window::kHide);
+  gNetworkTablesInfoWindow->DisableRenamePopup();
+  wpi::gui::AddLateExecute([] { gNetworkTablesInfoWindow->Display(); });
+
   wpi::gui::AddWindowScaler([](float scale) {
     // scale default window positions
     gNetworkTablesWindow->ScaleDefault(scale);
+    gNetworkTablesInfoWindow->ScaleDefault(scale);
   });
 }
 
@@ -39,4 +54,7 @@
   if (gNetworkTablesWindow) {
     gNetworkTablesWindow->DisplayMenuItem("NetworkTables View");
   }
+  if (gNetworkTablesInfoWindow) {
+    gNetworkTablesInfoWindow->DisplayMenuItem("NetworkTables Info");
+  }
 }
diff --git a/third_party/allwpilib/simulation/halsim_ws_client/build.gradle b/third_party/allwpilib/simulation/halsim_ws_client/build.gradle
index 7d32586..1fe4d29 100644
--- a/third_party/allwpilib/simulation/halsim_ws_client/build.gradle
+++ b/third_party/allwpilib/simulation/halsim_ws_client/build.gradle
@@ -27,6 +27,7 @@
                     return
                 }
 
+                lib project: ':wpinet', library: 'wpinet', linkage: 'shared'
                 lib project: ":simulation:halsim_ws_core", library: "halsim_ws_core", linkage: "static"
             }
         }
diff --git a/third_party/allwpilib/simulation/halsim_ws_client/src/main/native/cpp/HALSimWS.cpp b/third_party/allwpilib/simulation/halsim_ws_client/src/main/native/cpp/HALSimWS.cpp
index 9c23885..f4c5926 100644
--- a/third_party/allwpilib/simulation/halsim_ws_client/src/main/native/cpp/HALSimWS.cpp
+++ b/third_party/allwpilib/simulation/halsim_ws_client/src/main/native/cpp/HALSimWS.cpp
@@ -8,7 +8,7 @@
 
 #include <fmt/format.h>
 #include <wpi/SmallString.h>
-#include <wpi/uv/util.h>
+#include <wpinet/uv/util.h>
 
 #include "HALSimWSClientConnection.h"
 
diff --git a/third_party/allwpilib/simulation/halsim_ws_client/src/main/native/cpp/HALSimWSClient.cpp b/third_party/allwpilib/simulation/halsim_ws_client/src/main/native/cpp/HALSimWSClient.cpp
index dfa54d2..1df7ebc 100644
--- a/third_party/allwpilib/simulation/halsim_ws_client/src/main/native/cpp/HALSimWSClient.cpp
+++ b/third_party/allwpilib/simulation/halsim_ws_client/src/main/native/cpp/HALSimWSClient.cpp
@@ -19,7 +19,7 @@
 #include <WSProvider_SimDevice.h>
 #include <WSProvider_Solenoid.h>
 #include <WSProvider_dPWM.h>
-#include <wpi/EventLoopRunner.h>
+#include <wpinet/EventLoopRunner.h>
 
 using namespace wpilibws;
 
diff --git a/third_party/allwpilib/simulation/halsim_ws_client/src/main/native/cpp/HALSimWSClientConnection.cpp b/third_party/allwpilib/simulation/halsim_ws_client/src/main/native/cpp/HALSimWSClientConnection.cpp
index 22dadb1..10ea8af 100644
--- a/third_party/allwpilib/simulation/halsim_ws_client/src/main/native/cpp/HALSimWSClientConnection.cpp
+++ b/third_party/allwpilib/simulation/halsim_ws_client/src/main/native/cpp/HALSimWSClientConnection.cpp
@@ -7,7 +7,7 @@
 #include <cstdio>
 
 #include <fmt/format.h>
-#include <wpi/raw_uv_ostream.h>
+#include <wpinet/raw_uv_ostream.h>
 
 #include "HALSimWS.h"
 
diff --git a/third_party/allwpilib/simulation/halsim_ws_client/src/main/native/include/HALSimWS.h b/third_party/allwpilib/simulation/halsim_ws_client/src/main/native/include/HALSimWS.h
index 9563482..5bec17c 100644
--- a/third_party/allwpilib/simulation/halsim_ws_client/src/main/native/include/HALSimWS.h
+++ b/third_party/allwpilib/simulation/halsim_ws_client/src/main/native/include/HALSimWS.h
@@ -10,10 +10,10 @@
 
 #include <WSProviderContainer.h>
 #include <WSProvider_SimDevice.h>
-#include <wpi/uv/Async.h>
-#include <wpi/uv/Loop.h>
-#include <wpi/uv/Tcp.h>
-#include <wpi/uv/Timer.h>
+#include <wpinet/uv/Async.h>
+#include <wpinet/uv/Loop.h>
+#include <wpinet/uv/Tcp.h>
+#include <wpinet/uv/Timer.h>
 
 namespace wpi {
 class json;
diff --git a/third_party/allwpilib/simulation/halsim_ws_client/src/main/native/include/HALSimWSClient.h b/third_party/allwpilib/simulation/halsim_ws_client/src/main/native/include/HALSimWSClient.h
index f048b40..d5cdbbb 100644
--- a/third_party/allwpilib/simulation/halsim_ws_client/src/main/native/include/HALSimWSClient.h
+++ b/third_party/allwpilib/simulation/halsim_ws_client/src/main/native/include/HALSimWSClient.h
@@ -8,7 +8,7 @@
 
 #include <WSProviderContainer.h>
 #include <WSProvider_SimDevice.h>
-#include <wpi/EventLoopRunner.h>
+#include <wpinet/EventLoopRunner.h>
 
 #include "HALSimWS.h"
 
diff --git a/third_party/allwpilib/simulation/halsim_ws_client/src/main/native/include/HALSimWSClientConnection.h b/third_party/allwpilib/simulation/halsim_ws_client/src/main/native/include/HALSimWSClientConnection.h
index dddd885..b712e70 100644
--- a/third_party/allwpilib/simulation/halsim_ws_client/src/main/native/include/HALSimWSClientConnection.h
+++ b/third_party/allwpilib/simulation/halsim_ws_client/src/main/native/include/HALSimWSClientConnection.h
@@ -8,10 +8,10 @@
 #include <utility>
 
 #include <HALSimBaseWebSocketConnection.h>
-#include <wpi/WebSocket.h>
 #include <wpi/mutex.h>
-#include <wpi/uv/Buffer.h>
-#include <wpi/uv/Stream.h>
+#include <wpinet/WebSocket.h>
+#include <wpinet/uv/Buffer.h>
+#include <wpinet/uv/Stream.h>
 
 #include "HALSimWS.h"
 
diff --git a/third_party/allwpilib/simulation/halsim_ws_core/CMakeLists.txt b/third_party/allwpilib/simulation/halsim_ws_core/CMakeLists.txt
index 56b1766..91bcbb2 100644
--- a/third_party/allwpilib/simulation/halsim_ws_core/CMakeLists.txt
+++ b/third_party/allwpilib/simulation/halsim_ws_core/CMakeLists.txt
@@ -7,7 +7,7 @@
 add_library(halsim_ws_core STATIC ${halsim_ws_core_src})
 wpilib_target_warnings(halsim_ws_core)
 set_target_properties(halsim_ws_core PROPERTIES DEBUG_POSTFIX "d" POSITION_INDEPENDENT_CODE ON)
-target_link_libraries(halsim_ws_core PUBLIC hal)
+target_link_libraries(halsim_ws_core PUBLIC hal wpinet)
 
 target_include_directories(halsim_ws_core PUBLIC src/main/native/include)
 
diff --git a/third_party/allwpilib/simulation/halsim_ws_core/build.gradle b/third_party/allwpilib/simulation/halsim_ws_core/build.gradle
index 8e1f7ab..abdfddc 100644
--- a/third_party/allwpilib/simulation/halsim_ws_core/build.gradle
+++ b/third_party/allwpilib/simulation/halsim_ws_core/build.gradle
@@ -8,7 +8,7 @@
 
     ext {
         includeWpiutil = true
-        includeNtCore = true
+        includeWpinet = true
         pluginName = 'halsim_ws_core'
     }
 
@@ -41,6 +41,7 @@
                 }
                 binaries.all {
                     project(':hal').addHalDependency(it, 'shared')
+                    lib project: ':wpinet', library: 'wpinet', linkage: 'shared'
                     lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
                 }
                 appendDebugPathToBinaries(binaries)
diff --git a/third_party/allwpilib/simulation/halsim_ws_core/doc/hardware_ws_api.md b/third_party/allwpilib/simulation/halsim_ws_core/doc/hardware_ws_api.md
index b2b40fc..057b555 100644
--- a/third_party/allwpilib/simulation/halsim_ws_core/doc/hardware_ws_api.md
+++ b/third_party/allwpilib/simulation/halsim_ws_core/doc/hardware_ws_api.md
@@ -219,7 +219,7 @@
 
 [``"PWM"``]:#pwm-output-pwm
 
-PWMs may be used to control either speed controllers or servos.  Typically only one of either ``"<speed"`` (for a speed controller) or ``"<position"`` (for a servo) is used for a given PWM.
+PWMs may be used to control either motor controllers or servos.  Typically only one of either ``"<speed"`` (for a motor controller) or ``"<position"`` (for a servo) is used for a given PWM.
 
 | Data Key        | Type    | Description                                |
 | --------------- | ------- | ------------------------------------------ |
diff --git a/third_party/allwpilib/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_DriverStation.cpp b/third_party/allwpilib/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_DriverStation.cpp
index 6fbc3d7..7307b48 100644
--- a/third_party/allwpilib/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_DriverStation.cpp
+++ b/third_party/allwpilib/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_DriverStation.cpp
@@ -166,8 +166,8 @@
     HALSIM_SetDriverStationMatchTime(it.value());
   }
   if ((it = json.find(">game_data")) != json.end()) {
-    HALSIM_SetGameSpecificMessage(
-        it.value().get_ref<const std::string&>().c_str());
+    std::string message = it.value().get_ref<const std::string&>();
+    HALSIM_SetGameSpecificMessage(message.c_str(), message.length());
   }
 
   // Only notify usercode if we get the new data message
diff --git a/third_party/allwpilib/simulation/halsim_ws_core/src/main/native/include/WSProvider_SimDevice.h b/third_party/allwpilib/simulation/halsim_ws_core/src/main/native/include/WSProvider_SimDevice.h
index c4d4347..3a1ff5f 100644
--- a/third_party/allwpilib/simulation/halsim_ws_core/src/main/native/include/WSProvider_SimDevice.h
+++ b/third_party/allwpilib/simulation/halsim_ws_core/src/main/native/include/WSProvider_SimDevice.h
@@ -12,7 +12,7 @@
 #include <hal/SimDevice.h>
 #include <hal/simulation/SimDeviceData.h>
 #include <wpi/StringMap.h>
-#include <wpi/uv/AsyncFunction.h>
+#include <wpinet/uv/AsyncFunction.h>
 
 #include "WSBaseProvider.h"
 #include "WSProviderContainer.h"
diff --git a/third_party/allwpilib/simulation/halsim_ws_server/build.gradle b/third_party/allwpilib/simulation/halsim_ws_server/build.gradle
index 16cb24e..fbdee04 100644
--- a/third_party/allwpilib/simulation/halsim_ws_server/build.gradle
+++ b/third_party/allwpilib/simulation/halsim_ws_server/build.gradle
@@ -21,7 +21,7 @@
 model {
     testSuites {
         def comps = $.components
-        if (!project.hasProperty('onlylinuxathena') && !project.hasProperty('onlylinuxraspbian') && !project.hasProperty('onlylinuxaarch64bionic')) {
+        if (!project.hasProperty('onlylinuxathena')) {
             "${pluginName}Test"(GoogleTestTestSuiteSpec) {
                 for(NativeComponentSpec c : comps) {
                     if (c.name == pluginName) {
@@ -51,6 +51,7 @@
                 return
             }
 
+            lib project: ':wpinet', library: 'wpinet', linkage: 'shared'
             lib project: ":simulation:halsim_ws_core", library: "halsim_ws_core", linkage: "static"
         }
 
diff --git a/third_party/allwpilib/simulation/halsim_ws_server/src/main/native/cpp/HALSimHttpConnection.cpp b/third_party/allwpilib/simulation/halsim_ws_server/src/main/native/cpp/HALSimHttpConnection.cpp
index 3a2e3b2..77dec08 100644
--- a/third_party/allwpilib/simulation/halsim_ws_server/src/main/native/cpp/HALSimHttpConnection.cpp
+++ b/third_party/allwpilib/simulation/halsim_ws_server/src/main/native/cpp/HALSimHttpConnection.cpp
@@ -9,14 +9,14 @@
 #include <string_view>
 
 #include <fmt/format.h>
-#include <wpi/MimeTypes.h>
 #include <wpi/SmallVector.h>
 #include <wpi/StringExtras.h>
-#include <wpi/UrlParser.h>
 #include <wpi/fs.h>
 #include <wpi/raw_istream.h>
-#include <wpi/raw_uv_ostream.h>
-#include <wpi/uv/Request.h>
+#include <wpinet/MimeTypes.h>
+#include <wpinet/UrlParser.h>
+#include <wpinet/raw_uv_ostream.h>
+#include <wpinet/uv/Request.h>
 
 namespace uv = wpi::uv;
 
diff --git a/third_party/allwpilib/simulation/halsim_ws_server/src/main/native/cpp/HALSimWeb.cpp b/third_party/allwpilib/simulation/halsim_ws_server/src/main/native/cpp/HALSimWeb.cpp
index 43e3b08..8a6df97 100644
--- a/third_party/allwpilib/simulation/halsim_ws_server/src/main/native/cpp/HALSimWeb.cpp
+++ b/third_party/allwpilib/simulation/halsim_ws_server/src/main/native/cpp/HALSimWeb.cpp
@@ -6,12 +6,12 @@
 
 #include <fmt/format.h>
 #include <wpi/SmallString.h>
-#include <wpi/UrlParser.h>
-#include <wpi/WebSocketServer.h>
 #include <wpi/fs.h>
-#include <wpi/raw_uv_ostream.h>
-#include <wpi/uv/Loop.h>
-#include <wpi/uv/Tcp.h>
+#include <wpinet/UrlParser.h>
+#include <wpinet/WebSocketServer.h>
+#include <wpinet/raw_uv_ostream.h>
+#include <wpinet/uv/Loop.h>
+#include <wpinet/uv/Tcp.h>
 
 #include "HALSimHttpConnection.h"
 
diff --git a/third_party/allwpilib/simulation/halsim_ws_server/src/main/native/include/HALSimHttpConnection.h b/third_party/allwpilib/simulation/halsim_ws_server/src/main/native/include/HALSimHttpConnection.h
index 217e2ba..91cfb61 100644
--- a/third_party/allwpilib/simulation/halsim_ws_server/src/main/native/include/HALSimHttpConnection.h
+++ b/third_party/allwpilib/simulation/halsim_ws_server/src/main/native/include/HALSimHttpConnection.h
@@ -10,10 +10,10 @@
 #include <utility>
 
 #include <HALSimBaseWebSocketConnection.h>
-#include <wpi/HttpWebSocketServerConnection.h>
 #include <wpi/mutex.h>
-#include <wpi/uv/AsyncFunction.h>
-#include <wpi/uv/Buffer.h>
+#include <wpinet/HttpWebSocketServerConnection.h>
+#include <wpinet/uv/AsyncFunction.h>
+#include <wpinet/uv/Buffer.h>
 
 #include "HALSimWeb.h"
 
diff --git a/third_party/allwpilib/simulation/halsim_ws_server/src/main/native/include/HALSimWSServer.h b/third_party/allwpilib/simulation/halsim_ws_server/src/main/native/include/HALSimWSServer.h
index 484bfff..842e5b2 100644
--- a/third_party/allwpilib/simulation/halsim_ws_server/src/main/native/include/HALSimWSServer.h
+++ b/third_party/allwpilib/simulation/halsim_ws_server/src/main/native/include/HALSimWSServer.h
@@ -8,7 +8,7 @@
 
 #include <WSProviderContainer.h>
 #include <WSProvider_SimDevice.h>
-#include <wpi/EventLoopRunner.h>
+#include <wpinet/EventLoopRunner.h>
 
 #include "HALSimWeb.h"
 
diff --git a/third_party/allwpilib/simulation/halsim_ws_server/src/main/native/include/HALSimWeb.h b/third_party/allwpilib/simulation/halsim_ws_server/src/main/native/include/HALSimWeb.h
index 83a680e..de5d1f2 100644
--- a/third_party/allwpilib/simulation/halsim_ws_server/src/main/native/include/HALSimWeb.h
+++ b/third_party/allwpilib/simulation/halsim_ws_server/src/main/native/include/HALSimWeb.h
@@ -11,9 +11,9 @@
 #include <WSBaseProvider.h>
 #include <WSProviderContainer.h>
 #include <WSProvider_SimDevice.h>
-#include <wpi/uv/Async.h>
-#include <wpi/uv/Loop.h>
-#include <wpi/uv/Tcp.h>
+#include <wpinet/uv/Async.h>
+#include <wpinet/uv/Loop.h>
+#include <wpinet/uv/Tcp.h>
 
 namespace wpi {
 class json;
diff --git a/third_party/allwpilib/simulation/halsim_ws_server/src/test/native/cpp/WebServerClientTest.cpp b/third_party/allwpilib/simulation/halsim_ws_server/src/test/native/cpp/WebServerClientTest.cpp
index f13a0c6..fff4ae9 100644
--- a/third_party/allwpilib/simulation/halsim_ws_server/src/test/native/cpp/WebServerClientTest.cpp
+++ b/third_party/allwpilib/simulation/halsim_ws_server/src/test/native/cpp/WebServerClientTest.cpp
@@ -8,8 +8,8 @@
 
 #include <fmt/format.h>
 #include <wpi/SmallString.h>
-#include <wpi/raw_uv_ostream.h>
-#include <wpi/uv/util.h>
+#include <wpinet/raw_uv_ostream.h>
+#include <wpinet/uv/util.h>
 
 static constexpr int kTcpConnectAttemptTimeout = 1000;
 
diff --git a/third_party/allwpilib/simulation/halsim_ws_server/src/test/native/cpp/main.cpp b/third_party/allwpilib/simulation/halsim_ws_server/src/test/native/cpp/main.cpp
index ef31ba1..a9f739a 100644
--- a/third_party/allwpilib/simulation/halsim_ws_server/src/test/native/cpp/main.cpp
+++ b/third_party/allwpilib/simulation/halsim_ws_server/src/test/native/cpp/main.cpp
@@ -9,7 +9,7 @@
 #include <hal/HALBase.h>
 #include <hal/Main.h>
 #include <hal/simulation/DIOData.h>
-#include <wpi/uv/Loop.h>
+#include <wpinet/uv/Loop.h>
 
 #include "HALSimWSServer.h"
 #include "WebServerClientTest.h"
@@ -28,7 +28,7 @@
     m_server.Initialize();
 
     // Create and initialize client
-    m_server.runner.ExecSync([=](auto& loop) {
+    m_server.runner.ExecSync([=, this](auto& loop) {
       m_webserverClient = std::make_shared<WebServerClientTest>(loop);
       m_webserverClient->Initialize();
     });
@@ -157,6 +157,8 @@
   using namespace std::chrono_literals;
   std::this_thread::sleep_for(1s);
 
+  HAL_RefreshDSData();
+
   // Compare results
   HAL_ControlWord cw;
   HAL_GetControlWord(&cw);
diff --git a/third_party/allwpilib/simulation/halsim_ws_server/src/test/native/include/WebServerClientTest.h b/third_party/allwpilib/simulation/halsim_ws_server/src/test/native/include/WebServerClientTest.h
index 08db565..cda61dd 100644
--- a/third_party/allwpilib/simulation/halsim_ws_server/src/test/native/include/WebServerClientTest.h
+++ b/third_party/allwpilib/simulation/halsim_ws_server/src/test/native/include/WebServerClientTest.h
@@ -7,14 +7,14 @@
 #include <memory>
 #include <string>
 
-#include <wpi/WebSocket.h>
 #include <wpi/json.h>
-#include <wpi/uv/AsyncFunction.h>
-#include <wpi/uv/Buffer.h>
-#include <wpi/uv/Loop.h>
-#include <wpi/uv/Stream.h>
-#include <wpi/uv/Tcp.h>
-#include <wpi/uv/Timer.h>
+#include <wpinet/WebSocket.h>
+#include <wpinet/uv/AsyncFunction.h>
+#include <wpinet/uv/Buffer.h>
+#include <wpinet/uv/Loop.h>
+#include <wpinet/uv/Stream.h>
+#include <wpinet/uv/Tcp.h>
+#include <wpinet/uv/Timer.h>
 
 namespace wpilibws {
 
diff --git a/third_party/allwpilib/styleguide/checkstyle-suppressions.xml b/third_party/allwpilib/styleguide/checkstyle-suppressions.xml
index 54d4c2b..9a66026 100644
--- a/third_party/allwpilib/styleguide/checkstyle-suppressions.xml
+++ b/third_party/allwpilib/styleguide/checkstyle-suppressions.xml
@@ -6,6 +6,8 @@
   <suppress files=".*test.*" checks="MissingJavadocMethod" />
   <suppress files=".*wpilibjIntegrationTests.*"
     checks="MissingJavadocMethod" />
+  <suppress files="wpimath/*"
+    checks="(LocalVariableName|MemberName|MethodName|MethodTypeParameterName|ParameterName)" />
   <suppress files=".*JNI.*"
-    checks="(LineLength|EmptyLineSeparator|ParameterName|MissingJavadocMethod)" />
+    checks="(EmptyLineSeparator|LineLength|MissingJavadocMethod|ParameterName)" />
 </suppressions>
diff --git a/third_party/allwpilib/styleguide/checkstyle.xml b/third_party/allwpilib/styleguide/checkstyle.xml
index 4b35df8..09e9f23 100644
--- a/third_party/allwpilib/styleguide/checkstyle.xml
+++ b/third_party/allwpilib/styleguide/checkstyle.xml
@@ -109,7 +109,7 @@
                     COMPACT_CTOR_DEF" />
     </module>
     <module name="SuppressionXpathSingleFilter">
-      <!-- suppresion is required till https://github.com/checkstyle/checkstyle/issues/7541 -->
+      <!-- suppression is required till https://github.com/checkstyle/checkstyle/issues/7541 -->
       <property name="id" value="RightCurlyAlone" />
       <property name="query"
         value="//RCURLY[parent::SLIST[count(./*)=1]
@@ -170,19 +170,19 @@
     </module>
     <module name="MemberName">
       <property name="format"
-        value="^(m_[a-z]([a-zA-Z0-9]*)|value)$" />
+        value="^(m_([a-zA-Z]|[a-z][a-zA-Z0-9]+)|value)$" />
       <message key="name.invalidPattern"
         value="Member name ''{0}'' must match pattern ''{1}''." />
     </module>
     <module name="ParameterName">
       <property name="format"
-        value="^[a-z]([a-z0-9][a-zA-Z0-9]*)?$" />
+        value="^([a-zA-Z]|[a-z][a-zA-Z0-9]+)$" />
       <message key="name.invalidPattern"
         value="Parameter name ''{0}'' must match pattern ''{1}''." />
     </module>
     <module name="LambdaParameterName">
       <property name="format"
-        value="^[a-z]([a-z0-9][a-zA-Z0-9]*)?$" />
+        value="^(_?[a-zA-Z]|_?[a-z][a-zA-Z0-9]+)$" />
       <message key="name.invalidPattern"
         value="Lambda parameter name ''{0}'' must match pattern ''{1}''." />
     </module>
@@ -195,26 +195,23 @@
     <module name="LocalVariableName">
       <property name="tokens" value="VARIABLE_DEF" />
       <property name="format"
-        value="^[a-z]([a-z0-9][a-zA-Z0-9]*)?$" />
+        value="^([a-zA-Z][0-9]*|[a-z][a-zA-Z0-9]+)$" />
       <property name="allowOneCharVarInForLoop" value="true" />
       <message key="name.invalidPattern"
         value="Local variable name ''{0}'' must match pattern ''{1}''." />
     </module>
     <module name="ClassTypeParameterName">
-      <property name="format"
-        value="(^[A-Z][0-9]?)$|([A-Z][a-zA-Z0-9]*[T]$)" />
+      <property name="format" value="^[A-Z][a-zA-Z0-9]*$" />
       <message key="name.invalidPattern"
         value="Class type name ''{0}'' must match pattern ''{1}''." />
     </module>
     <module name="MethodTypeParameterName">
-      <property name="format"
-        value="(^[A-Z][0-9]?)$|([A-Z][a-zA-Z0-9]*[T]$)" />
+      <property name="format" value="^[A-Z][a-zA-Z0-9]*$" />
       <message key="name.invalidPattern"
         value="Method type name ''{0}'' must match pattern ''{1}''." />
     </module>
     <module name="InterfaceTypeParameterName">
-      <property name="format"
-        value="(^[A-Z][0-9]?)$|([A-Z][a-zA-Z0-9]*[T]$)" />
+      <property name="format" value="^[A-Z][a-zA-Z0-9]*$" />
       <message key="name.invalidPattern"
         value="Interface type name ''{0}'' must match pattern ''{1}''." />
     </module>
@@ -229,10 +226,6 @@
       <message key="ws.notPreceded"
         value="GenericWhitespace ''{0}'' is not preceded with whitespace." />
     </module>
-    <module name="AbbreviationAsWordInName">
-      <property name="ignoreFinal" value="false" />
-      <property name="allowedAbbreviationLength" value="4" />
-    </module>
     <module name="OverloadMethodsDeclarationOrder" />
     <module name="VariableDeclarationUsageDistance" />
     <module name="MethodParamPad" />
diff --git a/third_party/allwpilib/styleguide/pmd-ruleset.xml b/third_party/allwpilib/styleguide/pmd-ruleset.xml
index 0f37af0..54a4881 100644
--- a/third_party/allwpilib/styleguide/pmd-ruleset.xml
+++ b/third_party/allwpilib/styleguide/pmd-ruleset.xml
@@ -13,15 +13,18 @@
     <exclude name="AccessorClassGeneration" />
     <exclude name="AccessorMethodGeneration" />
     <exclude name="AvoidPrintStackTrace" />
+    <exclude name="AvoidReassigningCatchVariables" />
     <exclude name="AvoidReassigningParameters" />
     <exclude name="AvoidUsingHardCodedIP" />
     <exclude name="ConstantsInInterface" />
     <exclude name="JUnitAssertionsShouldIncludeMessage" />
     <exclude name="JUnitTestContainsTooManyAsserts" />
+    <exclude name="JUnitTestsShouldIncludeAssert" />
     <exclude name="JUnit4TestShouldUseAfterAnnotation" />
     <exclude name="JUnit4TestShouldUseBeforeAnnotation" />
     <exclude name="JUnit4TestShouldUseTestAnnotation" />
     <exclude name="LooseCoupling" />
+    <exclude name="PreserveStackTrace" />
     <exclude name="ReplaceHashtableWithMap" />
     <exclude name="ReplaceVectorWithList" />
     <exclude name="SwitchStmtsShouldHaveDefault" />
@@ -58,6 +61,7 @@
 
   <rule ref="category/java/errorprone.xml">
     <exclude name="AssignmentToNonFinalStatic" />
+    <exclude name="AvoidCatchingThrowable" />
     <exclude name="AvoidDuplicateLiterals" />
     <exclude name="AvoidLiteralsInIfCondition" />
     <exclude name="BeanMembersShouldSerialize" />
@@ -65,6 +69,8 @@
     <exclude name="ConstructorCallsOverridableMethod" />
     <exclude name="DataflowAnomalyAnalysis" />
     <exclude name="DoNotTerminateVM" />
+    <exclude name="EmptyCatchBlock" />
+    <exclude name="EmptyWhileStmt" />
     <exclude name="FinalizeDoesNotCallSuperFinalize" />
     <exclude name="JUnitSpelling" />
     <exclude name="MissingSerialVersionUID" />
diff --git a/third_party/allwpilib/styleguide/spotbugs-exclude.xml b/third_party/allwpilib/styleguide/spotbugs-exclude.xml
index 2393c86..c5e2d20 100644
--- a/third_party/allwpilib/styleguide/spotbugs-exclude.xml
+++ b/third_party/allwpilib/styleguide/spotbugs-exclude.xml
@@ -5,6 +5,10 @@
     <Class name="edu.wpi.first.wpilibj.test.TestSuite" />
   </Match>
   <Match>
+    <Bug pattern="DE_MIGHT_IGNORE" />
+    <Class name="edu.wpi.first.wpilibj.smartdashboard.SendableBuilderImpl$Property" />
+  </Match>
+  <Match>
     <Bug pattern="DM_DEFAULT_ENCODING" />
   </Match>
   <Match>
@@ -14,12 +18,19 @@
     <Bug pattern="DMI_RANDOM_USED_ONLY_ONCE" />
   </Match>
   <Match>
+    <Bug pattern="EC_BAD_ARRAY_COMPARE" />
+    <Class name="edu.wpi.first.math.estimator.SwerveDrivePoseEstimator$InterpolationRecord" />
+  </Match>
+  <Match>
     <Bug pattern="EI_EXPOSE_REP" />
   </Match>
   <Match>
     <Bug pattern="EI_EXPOSE_REP2" />
   </Match>
   <Match>
+    <Bug pattern="FL_FLOATS_AS_LOOP_COUNTERS" />
+  </Match>
+  <Match>
     <Bug pattern="IS2_INCONSISTENT_SYNC" />
     <Source name="MechanismLigament2d.java" />
   </Match>
@@ -58,6 +69,10 @@
     <Source name="SequentialCommandGroup.java" />
   </Match>
   <Match>
+    <Bug pattern="NS_DANGEROUS_NON_SHORT_CIRCUIT" />
+    <Source name="SelectCommand.java" />
+  </Match>
+  <Match>
     <Bug pattern="RV_RETURN_VALUE_IGNORED_BAD_PRACTICE" />
     <Source name="AntJunitLauncher.java" />
   </Match>
@@ -70,9 +85,26 @@
     <Source name="RuntimeLoader.java" />
   </Match>
   <Match>
+    <Bug pattern="SF_SWITCH_FALLTHROUGH" />
+    <Source name="CameraServer.java" />
+  </Match>
+  <Match>
+    <Bug pattern="SSD_DO_NOT_USE_INSTANCE_LOCK_ON_SHARED_STATIC_DATA" />
+    <Source name="Ultrasonic.java" />
+  </Match>
+  <Match>
     <Bug pattern="ST_WRITE_TO_STATIC_FROM_INSTANCE_METHOD" />
   </Match>
   <Match>
+    <Bug pattern="THROWS_METHOD_THROWS_CLAUSE_BASIC_EXCEPTION" />
+  </Match>
+  <Match>
+    <Bug pattern="THROWS_METHOD_THROWS_CLAUSE_THROWABLE" />
+  </Match>
+  <Match>
+    <Bug pattern="THROWS_METHOD_THROWS_RUNTIMEEXCEPTION" />
+  </Match>
+  <Match>
     <Bug pattern="UC_USELESS_VOID_METHOD" />
     <Class name="edu.wpi.first.wpilibj.templates.romitimed.Robot" />
   </Match>
@@ -94,4 +126,11 @@
   <Match>
     <Bug pattern="VA_FORMAT_STRING_USES_NEWLINE" />
   </Match>
+  <Match>
+    <Bug pattern="SC_START_IN_CTOR" />
+  </Match>
+  <Match>
+    <Bug pattern="RV_RETURN_VALUE_OF_PUTIFABSENT_IGNORED" />
+    <Class name="edu.wpi.first.networktables.NetworkTableInstance" />
+  </Match>
 </FindBugsFilter>
diff --git a/third_party/allwpilib/upstream_utils/README.md b/third_party/allwpilib/upstream_utils/README.md
new file mode 100644
index 0000000..587fc9e
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/README.md
@@ -0,0 +1,67 @@
+# Upstream utils
+
+## Layout
+
+Each thirdparty library has a Python script for updating it. They generally:
+
+1. Check out a thirdparty Git repository to a specific commit or tag
+2. Apply patch files to the thirdparty repo to fix things specific to our build
+3. Copy a subset of the thirdparty files into our repo
+4. Comment out any header includes that were invalidated, if needed
+
+`upstream_utils.py` contains utilities common to these update scripts.
+
+Patches are generated in the thirdparty repo with
+`git format-patch --no-signature` so they can be applied as individual commits
+and easily rebased onto newer versions. Each library has its own patch directory
+(e.g., `lib_patches`).
+
+## Updating thirdparty library version
+
+The example below will update a hypothetical library called `lib` to the tag
+`2.0`.
+
+Start in the `upstream_utils` folder. Restore the original repo.
+```bash
+./update_lib.py
+```
+
+Navigate to the repo.
+```bash
+cd /tmp/lib
+```
+
+Fetch the desired version using one of the following methods.
+```bash
+# Fetch a full branch or tag
+git fetch origin 2.0
+
+# Fetch just a tag (useful for expensive-to-clone repos)
+git fetch --depth 1 origin tag 2.0
+```
+
+Rebase any patches onto the new version.
+```bash
+git rebase 2.0
+```
+
+Generate patch files for the new version.
+```bash
+git format-patch 2.0..HEAD
+```
+
+Move the patch files to `upstream_utils`.
+```
+mv *.patch allwpilib/upstream_utils/lib_patches
+```
+
+Navigate back to `upstream_utils`
+```bash
+cd allwpilib/upstream_utils
+```
+
+Modify the version number in the call to `setup_upstream_repo()` in
+`update_lib.py`, then  rerun `update_lib.py` to reimport the thirdparty files.
+```bash
+./update_lib.py
+```
diff --git a/third_party/allwpilib/upstream_utils/drake-dllexport-dare.patch b/third_party/allwpilib/upstream_utils/drake-dllexport-dare.patch
deleted file mode 100644
index a37dacd..0000000
--- a/third_party/allwpilib/upstream_utils/drake-dllexport-dare.patch
+++ /dev/null
@@ -1,28 +0,0 @@
-diff --git b/wpimath/src/main/native/include/drake/math/discrete_algebraic_riccati_equation.h a/wpimath/src/main/native/include/drake/math/discrete_algebraic_riccati_equation.h
-index df7a58b2b..55b8442bf 100644
---- b/wpimath/src/main/native/include/drake/math/discrete_algebraic_riccati_equation.h
-+++ a/wpimath/src/main/native/include/drake/math/discrete_algebraic_riccati_equation.h
-@@ -4,6 +4,7 @@
- #include <cstdlib>
- 
- #include <Eigen/Core>
-+#include <wpi/SymbolExports.h>
- 
- namespace drake {
- namespace math {
-@@ -21,6 +22,7 @@ Based on the Schur Vector approach outlined in this paper:
- "On the Numerical Solution of the Discrete-Time Algebraic Riccati Equation"
- by Thrasyvoulos Pappas, Alan J. Laub, and Nils R. Sandell
- */
-+WPILIB_DLLEXPORT
- Eigen::MatrixXd DiscreteAlgebraicRiccatiEquation(
-     const Eigen::Ref<const Eigen::MatrixXd>& A,
-     const Eigen::Ref<const Eigen::MatrixXd>& B,
-@@ -71,6 +73,7 @@ J = Σ [uₖ] [0 R][uₖ] ΔT
- @throws std::runtime_error if Q − NR⁻¹Nᵀ is not positive semi-definite.
- @throws std::runtime_error if R is not positive definite.
- */
-+WPILIB_DLLEXPORT
- Eigen::MatrixXd DiscreteAlgebraicRiccatiEquation(
-     const Eigen::Ref<const Eigen::MatrixXd>& A,
-     const Eigen::Ref<const Eigen::MatrixXd>& B,
diff --git a/third_party/allwpilib/upstream_utils/drake-replace-dense-with-core.patch b/third_party/allwpilib/upstream_utils/drake-replace-dense-with-core.patch
deleted file mode 100644
index d225597..0000000
--- a/third_party/allwpilib/upstream_utils/drake-replace-dense-with-core.patch
+++ /dev/null
@@ -1,64 +0,0 @@
-diff --git b/wpimath/src/main/native/include/drake/common/is_approx_equal_abstol.h a/wpimath/src/main/native/include/drake/common/is_approx_equal_abstol.h
-index 9af0c4525..b3f369ca0 100644
---- b/wpimath/src/main/native/include/drake/common/is_approx_equal_abstol.h
-+++ a/wpimath/src/main/native/include/drake/common/is_approx_equal_abstol.h
-@@ -2,7 +2,7 @@
- 
- #include <vector>
- 
--#include <Eigen/Dense>
-+#include <Eigen/Core>
- 
- namespace drake {
- 
-diff --git a/wpimath/src/main/native/cpp/drake/math/discrete_algebraic_riccati_equation.cpp b/wpimath/src/main/native/cpp/drake/math/discrete_algebraic_riccati_equation.cpp
-index 9585c4dae..49c2fefe7 100644
---- a/wpimath/src/main/native/cpp/drake/math/discrete_algebraic_riccati_equation.cpp
-+++ b/wpimath/src/main/native/cpp/drake/math/discrete_algebraic_riccati_equation.cpp
-@@ -1,5 +1,8 @@
- #include "drake/math/discrete_algebraic_riccati_equation.h"
- 
-+#include <Eigen/Eigenvalues>
-+#include <Eigen/QR>
-+
- #include "drake/common/drake_assert.h"
- #include "drake/common/drake_throw.h"
- #include "drake/common/is_approx_equal_abstol.h"
-diff --git b/wpimath/src/main/native/include/drake/math/discrete_algebraic_riccati_equation.h a/wpimath/src/main/native/include/drake/math/discrete_algebraic_riccati_equation.h
-index b64bfe75e..fc5efb313 100644
---- b/wpimath/src/main/native/include/drake/math/discrete_algebraic_riccati_equation.h
-+++ a/wpimath/src/main/native/include/drake/math/discrete_algebraic_riccati_equation.h
-@@ -3,7 +3,7 @@
- #include <cmath>
- #include <cstdlib>
- 
--#include <Eigen/Dense>
-+#include <Eigen/Core>
- 
- namespace drake {
- namespace math {
- 
-diff --git b/wpimath/src/test/native/cpp/drake/discrete_algebraic_riccati_equation_test.cpp a/wpimath/src/test/native/cpp/drake/discrete_algebraic_riccati_equation_test.cpp
-index 74aa4b23d..2deb039a0 100644
---- b/wpimath/src/test/native/cpp/drake/discrete_algebraic_riccati_equation_test.cpp
-+++ a/wpimath/src/test/native/cpp/drake/discrete_algebraic_riccati_equation_test.cpp
-@@ -1,5 +1,6 @@
- #include "drake/math/discrete_algebraic_riccati_equation.h"
- 
-+#include <Eigen/Eigenvalues>
- #include <gtest/gtest.h>
- 
- #include "drake/common/test_utilities/eigen_matrix_compare.h"
-diff --git b/wpimath/src/test/native/include/drake/common/test_utilities/eigen_matrix_compare.h a/wpimath/src/test/native/include/drake/common/test_utilities/eigen_matrix_compare.h
-index e3bd85349..d6bcbb8ec 100644
---- b/wpimath/src/test/native/include/drake/common/test_utilities/eigen_matrix_compare.h
-+++ a/wpimath/src/test/native/include/drake/common/test_utilities/eigen_matrix_compare.h
-@@ -4,7 +4,7 @@
- #include <cmath>
- #include <limits>
- 
--#include <Eigen/Dense>
-+#include <Eigen/Core>
- #include <gtest/gtest.h>
- 
- // #include "drake/common/text_logging.h"
diff --git a/third_party/allwpilib/upstream_utils/drake_patches/0001-Replace-Eigen-Dense-with-Eigen-Core.patch b/third_party/allwpilib/upstream_utils/drake_patches/0001-Replace-Eigen-Dense-with-Eigen-Core.patch
new file mode 100644
index 0000000..dcd2e8f
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/drake_patches/0001-Replace-Eigen-Dense-with-Eigen-Core.patch
@@ -0,0 +1,76 @@
+From 02d023c7cdfdfb72ccdbccbac0883b4a1f6ec6d5 Mon Sep 17 00:00:00 2001
+From: Tyler Veness <calcmogul@gmail.com>
+Date: Wed, 18 May 2022 11:13:21 -0700
+Subject: [PATCH 1/2] Replace <Eigen/Dense> with <Eigen/Core>
+
+---
+ common/is_approx_equal_abstol.h                       | 2 +-
+ common/test_utilities/eigen_matrix_compare.h          | 2 +-
+ math/discrete_algebraic_riccati_equation.cc           | 3 +++
+ math/discrete_algebraic_riccati_equation.h            | 2 +-
+ math/test/discrete_algebraic_riccati_equation_test.cc | 1 +
+ 5 files changed, 7 insertions(+), 3 deletions(-)
+
+diff --git a/common/is_approx_equal_abstol.h b/common/is_approx_equal_abstol.h
+index 9af0c45..b3f369c 100644
+--- a/common/is_approx_equal_abstol.h
++++ b/common/is_approx_equal_abstol.h
+@@ -2,7 +2,7 @@
+ 
+ #include <vector>
+ 
+-#include <Eigen/Dense>
++#include <Eigen/Core>
+ 
+ namespace drake {
+ 
+diff --git a/common/test_utilities/eigen_matrix_compare.h b/common/test_utilities/eigen_matrix_compare.h
+index a595da9..c22567d 100644
+--- a/common/test_utilities/eigen_matrix_compare.h
++++ b/common/test_utilities/eigen_matrix_compare.h
+@@ -4,7 +4,7 @@
+ #include <cmath>
+ #include <limits>
+ 
+-#include <Eigen/Dense>
++#include <Eigen/Core>
+ #include <gtest/gtest.h>
+ 
+ #include "drake/common/text_logging.h"
+diff --git a/math/discrete_algebraic_riccati_equation.cc b/math/discrete_algebraic_riccati_equation.cc
+index 901f2ef..20ea2b7 100644
+--- a/math/discrete_algebraic_riccati_equation.cc
++++ b/math/discrete_algebraic_riccati_equation.cc
+@@ -1,5 +1,8 @@
+ #include "drake/math/discrete_algebraic_riccati_equation.h"
+ 
++#include <Eigen/Eigenvalues>
++#include <Eigen/QR>
++
+ #include "drake/common/drake_assert.h"
+ #include "drake/common/drake_throw.h"
+ #include "drake/common/is_approx_equal_abstol.h"
+diff --git a/math/discrete_algebraic_riccati_equation.h b/math/discrete_algebraic_riccati_equation.h
+index 891373f..df7a58b 100644
+--- a/math/discrete_algebraic_riccati_equation.h
++++ b/math/discrete_algebraic_riccati_equation.h
+@@ -3,7 +3,7 @@
+ #include <cmath>
+ #include <cstdlib>
+ 
+-#include <Eigen/Dense>
++#include <Eigen/Core>
+ 
+ namespace drake {
+ namespace math {
+diff --git a/math/test/discrete_algebraic_riccati_equation_test.cc b/math/test/discrete_algebraic_riccati_equation_test.cc
+index 533ced1..e4ecfd2 100644
+--- a/math/test/discrete_algebraic_riccati_equation_test.cc
++++ b/math/test/discrete_algebraic_riccati_equation_test.cc
+@@ -1,5 +1,6 @@
+ #include "drake/math/discrete_algebraic_riccati_equation.h"
+ 
++#include <Eigen/Eigenvalues>
+ #include <gtest/gtest.h>
+ 
+ #include "drake/common/test_utilities/eigen_matrix_compare.h"
diff --git a/third_party/allwpilib/upstream_utils/drake_patches/0002-Add-WPILIB_DLLEXPORT-to-DARE-function-declarations.patch b/third_party/allwpilib/upstream_utils/drake_patches/0002-Add-WPILIB_DLLEXPORT-to-DARE-function-declarations.patch
new file mode 100644
index 0000000..1c7b469
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/drake_patches/0002-Add-WPILIB_DLLEXPORT-to-DARE-function-declarations.patch
@@ -0,0 +1,37 @@
+From b208372a18b37f6cbc49dd45d15adf63c9b60755 Mon Sep 17 00:00:00 2001
+From: Tyler Veness <calcmogul@gmail.com>
+Date: Wed, 18 May 2022 11:15:27 -0700
+Subject: [PATCH 2/2] Add WPILIB_DLLEXPORT to DARE function declarations
+
+---
+ math/discrete_algebraic_riccati_equation.h | 3 +++
+ 1 file changed, 3 insertions(+)
+
+diff --git a/math/discrete_algebraic_riccati_equation.h b/math/discrete_algebraic_riccati_equation.h
+index df7a58b..55b8442 100644
+--- a/math/discrete_algebraic_riccati_equation.h
++++ b/math/discrete_algebraic_riccati_equation.h
+@@ -4,6 +4,7 @@
+ #include <cstdlib>
+ 
+ #include <Eigen/Core>
++#include <wpi/SymbolExports.h>
+ 
+ namespace drake {
+ namespace math {
+@@ -21,6 +22,7 @@ Based on the Schur Vector approach outlined in this paper:
+ "On the Numerical Solution of the Discrete-Time Algebraic Riccati Equation"
+ by Thrasyvoulos Pappas, Alan J. Laub, and Nils R. Sandell
+ */
++WPILIB_DLLEXPORT
+ Eigen::MatrixXd DiscreteAlgebraicRiccatiEquation(
+     const Eigen::Ref<const Eigen::MatrixXd>& A,
+     const Eigen::Ref<const Eigen::MatrixXd>& B,
+@@ -71,6 +73,7 @@ J = Σ [uₖ] [0 R][uₖ] ΔT
+ @throws std::runtime_error if Q − NR⁻¹Nᵀ is not positive semi-definite.
+ @throws std::runtime_error if R is not positive definite.
+ */
++WPILIB_DLLEXPORT
+ Eigen::MatrixXd DiscreteAlgebraicRiccatiEquation(
+     const Eigen::Ref<const Eigen::MatrixXd>& A,
+     const Eigen::Ref<const Eigen::MatrixXd>& B,
diff --git a/third_party/allwpilib/upstream_utils/eigen-maybe-uninitialized.patch b/third_party/allwpilib/upstream_utils/eigen-maybe-uninitialized.patch
deleted file mode 100644
index 27144de..0000000
--- a/third_party/allwpilib/upstream_utils/eigen-maybe-uninitialized.patch
+++ /dev/null
@@ -1,15 +0,0 @@
-diff --git a/wpimath/src/main/native/eigeninclude/Eigen/src/Core/util/DisableStupidWarnings.h b/wpimath/src/main/native/eigeninclude/Eigen/src/Core/util/DisableStupidWarnings.h
-index 74f74cc42..5fe86fa0d 100644
---- a/wpimath/src/main/native/eigeninclude/Eigen/src/Core/util/DisableStupidWarnings.h
-+++ b/wpimath/src/main/native/eigeninclude/Eigen/src/Core/util/DisableStupidWarnings.h
-@@ -61,6 +61,10 @@
-     // See: https://gcc.gnu.org/bugzilla/show_bug.cgi?id=89325
-     #pragma GCC diagnostic ignored "-Wattributes"
-   #endif
-+  #if __GNUC__==11
-+    // This warning is a false positive
-+    #pragma GCC diagnostic ignored "-Wmaybe-uninitialized"
-+  #endif
- #endif
- 
- #if defined __NVCC__
diff --git a/third_party/allwpilib/upstream_utils/eigen_patches/0001-Disable-warnings.patch b/third_party/allwpilib/upstream_utils/eigen_patches/0001-Disable-warnings.patch
new file mode 100644
index 0000000..78a5922
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/eigen_patches/0001-Disable-warnings.patch
@@ -0,0 +1,31 @@
+From 3bfc3d1e3cbc9d7032446cc4aa6246d1c7750901 Mon Sep 17 00:00:00 2001
+From: Tyler Veness <calcmogul@gmail.com>
+Date: Wed, 18 May 2022 09:14:24 -0700
+Subject: [PATCH] Disable warnings
+
+---
+ Eigen/src/Core/util/DisableStupidWarnings.h | 11 +++++++++++
+ 1 file changed, 11 insertions(+)
+
+diff --git a/Eigen/src/Core/util/DisableStupidWarnings.h b/Eigen/src/Core/util/DisableStupidWarnings.h
+index fe0cfec..d973255 100755
+--- a/Eigen/src/Core/util/DisableStupidWarnings.h
++++ b/Eigen/src/Core/util/DisableStupidWarnings.h
+@@ -71,6 +71,17 @@
+     // See: https://gcc.gnu.org/bugzilla/show_bug.cgi?id=89325
+     #pragma GCC diagnostic ignored "-Wattributes"
+   #endif
++  #if __GNUC__>=8
++    #pragma GCC diagnostic ignored "-Wclass-memaccess"
++  #endif
++  #if __GNUC__>=11
++    // This warning is a false positive
++    #pragma GCC diagnostic ignored "-Wmaybe-uninitialized"
++  #endif
++  #if __GNUC__==12
++    // This warning is a false positive
++    #pragma GCC diagnostic ignored "-Warray-bounds"
++  #endif
+ #endif
+ 
+ #if defined __NVCC__
diff --git a/third_party/allwpilib/upstream_utils/fmt-dont-throw-on-write-failure.patch b/third_party/allwpilib/upstream_utils/fmt-dont-throw-on-write-failure.patch
deleted file mode 100644
index 6be3639..0000000
--- a/third_party/allwpilib/upstream_utils/fmt-dont-throw-on-write-failure.patch
+++ /dev/null
@@ -1,42 +0,0 @@
-diff --git a/wpiutil/src/main/native/fmtlib/include/fmt/format-inl.h b/wpiutil/src/main/native/fmtlib/include/fmt/format-inl.h
-index 2c51c50ae..cc89abdd3 100644
---- a/wpiutil/src/main/native/fmtlib/include/fmt/format-inl.h
-+++ b/wpiutil/src/main/native/fmtlib/include/fmt/format-inl.h
-@@ -92,8 +92,7 @@ FMT_FUNC void report_error(format_func func, int error_code,
- // A wrapper around fwrite that throws on error.
- inline void fwrite_fully(const void* ptr, size_t size, size_t count,
-                          FILE* stream) {
--  size_t written = std::fwrite(ptr, size, count, stream);
--  if (written < count) FMT_THROW(system_error(errno, "cannot write to file"));
-+  std::fwrite(ptr, size, count, stream);
- }
- 
- #ifndef FMT_STATIC_THOUSANDS_SEPARATOR
-diff --git a/wpiutil/src/main/native/fmtlib/include/fmt/xchar.h b/wpiutil/src/main/native/fmtlib/include/fmt/xchar.h
-index 55825077f..9acb893fa 100644
---- a/wpiutil/src/main/native/fmtlib/include/fmt/xchar.h
-+++ b/wpiutil/src/main/native/fmtlib/include/fmt/xchar.h
-@@ -207,8 +207,7 @@ inline void vprint(std::FILE* f, wstring_view fmt, wformat_args args) {
-   wmemory_buffer buffer;
-   detail::vformat_to(buffer, fmt, args);
-   buffer.push_back(L'\0');
--  if (std::fputws(buffer.data(), f) == -1)
--    FMT_THROW(system_error(errno, FMT_STRING("cannot write to file")));
-+  std::fputws(buffer.data(), f);
- }
- 
- inline void vprint(wstring_view fmt, wformat_args args) {
-diff --git a/wpiutil/src/main/native/fmtlib/src/os.cpp b/wpiutil/src/main/native/fmtlib/src/os.cpp
-index 04b4dc506..4eb3e1fdd 100644
---- a/wpiutil/src/main/native/fmtlib/src/os.cpp
-+++ b/wpiutil/src/main/native/fmtlib/src/os.cpp
-@@ -277,8 +277,7 @@ std::size_t file::read(void* buffer, std::size_t count) {
- std::size_t file::write(const void* buffer, std::size_t count) {
-   rwresult result = 0;
-   FMT_RETRY(result, FMT_POSIX_CALL(write(fd_, buffer, convert_rwcount(count))));
--  if (result < 0) FMT_THROW(system_error(errno, "cannot write to file"));
--  return detail::to_unsigned(result);
-+  return count;
- }
- 
- file file::dup(int fd) {
diff --git a/third_party/allwpilib/upstream_utils/fmt_patches/0001-Don-t-throw-on-write-failure.patch b/third_party/allwpilib/upstream_utils/fmt_patches/0001-Don-t-throw-on-write-failure.patch
new file mode 100644
index 0000000..edaf575
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/fmt_patches/0001-Don-t-throw-on-write-failure.patch
@@ -0,0 +1,54 @@
+From e685209746aabbbed0a9db54694b8ea1ca504163 Mon Sep 17 00:00:00 2001
+From: Tyler Veness <calcmogul@gmail.com>
+Date: Wed, 18 May 2022 10:21:49 -0700
+Subject: [PATCH 1/2] Don't throw on write failure
+
+---
+ include/fmt/format-inl.h | 4 +---
+ include/fmt/xchar.h      | 3 +--
+ src/os.cc                | 3 +--
+ 3 files changed, 3 insertions(+), 7 deletions(-)
+
+diff --git a/include/fmt/format-inl.h b/include/fmt/format-inl.h
+index 22b1ec8..abe4ff1 100644
+--- a/include/fmt/format-inl.h
++++ b/include/fmt/format-inl.h
+@@ -79,9 +79,7 @@ FMT_FUNC void report_error(format_func func, int error_code,
+ // A wrapper around fwrite that throws on error.
+ inline void fwrite_fully(const void* ptr, size_t size, size_t count,
+                          FILE* stream) {
+-  size_t written = std::fwrite(ptr, size, count, stream);
+-  if (written < count)
+-    FMT_THROW(system_error(errno, FMT_STRING("cannot write to file")));
++  std::fwrite(ptr, size, count, stream);
+ }
+ 
+ #ifndef FMT_STATIC_THOUSANDS_SEPARATOR
+diff --git a/include/fmt/xchar.h b/include/fmt/xchar.h
+index 3b5bc15..fc3c67f 100644
+--- a/include/fmt/xchar.h
++++ b/include/fmt/xchar.h
+@@ -200,8 +200,7 @@ inline void vprint(std::FILE* f, wstring_view fmt, wformat_args args) {
+   wmemory_buffer buffer;
+   detail::vformat_to(buffer, fmt, args);
+   buffer.push_back(L'\0');
+-  if (std::fputws(buffer.data(), f) == -1)
+-    FMT_THROW(system_error(errno, FMT_STRING("cannot write to file")));
++  std::fputws(buffer.data(), f);
+ }
+ 
+ inline void vprint(wstring_view fmt, wformat_args args) {
+diff --git a/src/os.cc b/src/os.cc
+index f388ead..2c49951 100644
+--- a/src/os.cc
++++ b/src/os.cc
+@@ -277,8 +277,7 @@ std::size_t file::read(void* buffer, std::size_t count) {
+ std::size_t file::write(const void* buffer, std::size_t count) {
+   rwresult result = 0;
+   FMT_RETRY(result, FMT_POSIX_CALL(write(fd_, buffer, convert_rwcount(count))));
+-  if (result < 0) FMT_THROW(system_error(errno, "cannot write to file"));
+-  return detail::to_unsigned(result);
++  return count;
+ }
+ 
+ file file::dup(int fd) {
diff --git a/third_party/allwpilib/upstream_utils/fmt_patches/0002-Suppress-C-20-clang-tidy-warning-false-positive.patch b/third_party/allwpilib/upstream_utils/fmt_patches/0002-Suppress-C-20-clang-tidy-warning-false-positive.patch
new file mode 100644
index 0000000..7e25fc0
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/fmt_patches/0002-Suppress-C-20-clang-tidy-warning-false-positive.patch
@@ -0,0 +1,22 @@
+From 1d8e07241d380d13383a6ff479f3895ef49ce514 Mon Sep 17 00:00:00 2001
+From: Tyler Veness <calcmogul@gmail.com>
+Date: Fri, 2 Sep 2022 15:12:54 -0700
+Subject: [PATCH 2/2] Suppress C++20 clang-tidy warning false positive
+
+---
+ include/fmt/core.h | 2 +-
+ 1 file changed, 1 insertion(+), 1 deletion(-)
+
+diff --git a/include/fmt/core.h b/include/fmt/core.h
+index f6a37af..5c210bc 100644
+--- a/include/fmt/core.h
++++ b/include/fmt/core.h
+@@ -2952,7 +2952,7 @@ class format_string_checker {
+       basic_string_view<Char> format_str, ErrorHandler eh)
+       : context_(format_str, num_args, types_, eh),
+         parse_funcs_{&parse_format_specs<Args, parse_context_type>...},
+-        types_{
++        types_{  // NOLINT(clang-analyzer-optin.cplusplus.UninitializedObject)
+             mapped_type_constant<Args,
+                                  basic_format_context<Char*, Char>>::value...} {
+   }
diff --git a/third_party/allwpilib/upstream_utils/libuv_patches/0001-Fix-missing-casts.patch b/third_party/allwpilib/upstream_utils/libuv_patches/0001-Fix-missing-casts.patch
new file mode 100644
index 0000000..6965d0d
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/libuv_patches/0001-Fix-missing-casts.patch
@@ -0,0 +1,1533 @@
+From d5613423f057b088f6b3753f49162947d5559ad9 Mon Sep 17 00:00:00 2001
+From: PJ Reiniger <pj.reiniger@gmail.com>
+Date: Tue, 26 Apr 2022 15:01:25 -0400
+Subject: [PATCH 1/9] Fix missing casts
+
+---
+ include/uv/unix.h              |  2 +-
+ src/fs-poll.c                  | 10 ++++-----
+ src/inet.c                     | 11 +++++-----
+ src/strscpy.c                  |  2 +-
+ src/threadpool.c               |  2 +-
+ src/unix/bsd-ifaddrs.c         |  2 +-
+ src/unix/core.c                | 12 +++++-----
+ src/unix/darwin-proctitle.c    |  5 +++--
+ src/unix/darwin.c              |  2 +-
+ src/unix/epoll.c               |  2 +-
+ src/unix/freebsd.c             |  4 ++--
+ src/unix/fs.c                  | 20 ++++++++---------
+ src/unix/fsevents.c            | 40 +++++++++++++++++-----------------
+ src/unix/getaddrinfo.c         |  8 +++----
+ src/unix/ibmi.c                |  2 +-
+ src/unix/kqueue.c              |  6 ++---
+ src/unix/linux-core.c          |  5 ++---
+ src/unix/linux-inotify.c       |  4 ++--
+ src/unix/loop.c                |  2 +-
+ src/unix/netbsd.c              |  4 ++--
+ src/unix/openbsd.c             |  4 ++--
+ src/unix/pipe.c                |  4 ++--
+ src/unix/poll.c                |  2 +-
+ src/unix/posix-poll.c          |  2 +-
+ src/unix/process.c             |  4 ++--
+ src/unix/proctitle.c           |  2 +-
+ src/unix/random-sysctl-linux.c |  2 +-
+ src/unix/stream.c              | 35 ++++++++++++++---------------
+ src/unix/thread.c              |  7 +++---
+ src/unix/udp.c                 |  8 +++----
+ src/uv-common.c                | 16 +++++++-------
+ src/win/core.c                 |  8 ++++---
+ src/win/fs-event.c             |  4 ++--
+ src/win/fs-fd-hash-inl.h       |  2 +-
+ src/win/fs.c                   | 26 +++++++++++-----------
+ src/win/pipe.c                 | 10 ++++-----
+ src/win/process.c              | 12 +++++-----
+ src/win/tcp.c                  |  2 +-
+ src/win/thread.c               |  4 ++--
+ src/win/util.c                 | 29 ++++++++++++------------
+ 40 files changed, 166 insertions(+), 162 deletions(-)
+
+diff --git a/include/uv/unix.h b/include/uv/unix.h
+index ea37d787..420be86c 100644
+--- a/include/uv/unix.h
++++ b/include/uv/unix.h
+@@ -223,7 +223,7 @@ typedef struct {
+   int backend_fd;                                                             \
+   void* pending_queue[2];                                                     \
+   void* watcher_queue[2];                                                     \
+-  uv__io_t** watchers;                                                        \
++  void** watchers;                                                            \
+   unsigned int nwatchers;                                                     \
+   unsigned int nfds;                                                          \
+   void* wq[2];                                                                \
+diff --git a/src/fs-poll.c b/src/fs-poll.c
+index 1bac1c56..5a39daed 100644
+--- a/src/fs-poll.c
++++ b/src/fs-poll.c
+@@ -77,7 +77,7 @@ int uv_fs_poll_start(uv_fs_poll_t* handle,
+ 
+   loop = handle->loop;
+   len = strlen(path);
+-  ctx = uv__calloc(1, sizeof(*ctx) + len);
++  ctx = (struct poll_ctx*)uv__calloc(1, sizeof(*ctx) + len);
+ 
+   if (ctx == NULL)
+     return UV_ENOMEM;
+@@ -101,7 +101,7 @@ int uv_fs_poll_start(uv_fs_poll_t* handle,
+     goto error;
+ 
+   if (handle->poll_ctx != NULL)
+-    ctx->previous = handle->poll_ctx;
++    ctx->previous = (struct poll_ctx*)handle->poll_ctx;
+   handle->poll_ctx = ctx;
+   uv__handle_start(handle);
+ 
+@@ -119,7 +119,7 @@ int uv_fs_poll_stop(uv_fs_poll_t* handle) {
+   if (!uv_is_active((uv_handle_t*)handle))
+     return 0;
+ 
+-  ctx = handle->poll_ctx;
++  ctx = (struct poll_ctx*)handle->poll_ctx;
+   assert(ctx != NULL);
+   assert(ctx->parent_handle == handle);
+ 
+@@ -144,7 +144,7 @@ int uv_fs_poll_getpath(uv_fs_poll_t* handle, char* buffer, size_t* size) {
+     return UV_EINVAL;
+   }
+ 
+-  ctx = handle->poll_ctx;
++  ctx = (struct poll_ctx*)handle->poll_ctx;
+   assert(ctx != NULL);
+ 
+   required_len = strlen(ctx->path);
+@@ -244,7 +244,7 @@ static void timer_close_cb(uv_handle_t* timer) {
+     if (handle->poll_ctx == NULL && uv__is_closing(handle))
+       uv__make_close_pending((uv_handle_t*)handle);
+   } else {
+-    for (last = handle->poll_ctx, it = last->previous;
++    for (last = (struct poll_ctx*)handle->poll_ctx, it = last->previous;
+          it != ctx;
+          last = it, it = it->previous) {
+       assert(last->previous != NULL);
+diff --git a/src/inet.c b/src/inet.c
+index ddabf22f..ca8b6ac8 100644
+--- a/src/inet.c
++++ b/src/inet.c
+@@ -40,9 +40,9 @@ static int inet_pton6(const char *src, unsigned char *dst);
+ int uv_inet_ntop(int af, const void* src, char* dst, size_t size) {
+   switch (af) {
+   case AF_INET:
+-    return (inet_ntop4(src, dst, size));
++    return (inet_ntop4((const unsigned char*)src, dst, size));
+   case AF_INET6:
+-    return (inet_ntop6(src, dst, size));
++    return (inet_ntop6((const unsigned char*)src, dst, size));
+   default:
+     return UV_EAFNOSUPPORT;
+   }
+@@ -154,10 +154,11 @@ int uv_inet_pton(int af, const char* src, void* dst) {
+ 
+   switch (af) {
+   case AF_INET:
+-    return (inet_pton4(src, dst));
++    return (inet_pton4(src, (unsigned char*)dst));
+   case AF_INET6: {
+     int len;
+-    char tmp[UV__INET6_ADDRSTRLEN], *s, *p;
++    char tmp[UV__INET6_ADDRSTRLEN], *s;
++    const char *p;
+     s = (char*) src;
+     p = strchr(src, '%');
+     if (p != NULL) {
+@@ -168,7 +169,7 @@ int uv_inet_pton(int af, const char* src, void* dst) {
+       memcpy(s, src, len);
+       s[len] = '\0';
+     }
+-    return inet_pton6(s, dst);
++    return inet_pton6(s, (unsigned char*)dst);
+   }
+   default:
+     return UV_EAFNOSUPPORT;
+diff --git a/src/strscpy.c b/src/strscpy.c
+index 20df6fcb..6b4cc3bc 100644
+--- a/src/strscpy.c
++++ b/src/strscpy.c
+@@ -27,7 +27,7 @@ ssize_t uv__strscpy(char* d, const char* s, size_t n) {
+ 
+   for (i = 0; i < n; i++)
+     if ('\0' == (d[i] = s[i]))
+-      return i > SSIZE_MAX ? UV_E2BIG : (ssize_t) i;
++      return i > SSIZE_MAX ? (ssize_t) UV_E2BIG : (ssize_t) i;
+ 
+   if (i == 0)
+     return 0;
+diff --git a/src/threadpool.c b/src/threadpool.c
+index e804c7c4..1241ace1 100644
+--- a/src/threadpool.c
++++ b/src/threadpool.c
+@@ -206,7 +206,7 @@ static void init_threads(void) {
+ 
+   threads = default_threads;
+   if (nthreads > ARRAY_SIZE(default_threads)) {
+-    threads = uv__malloc(nthreads * sizeof(threads[0]));
++    threads = (uv_thread_t*)uv__malloc(nthreads * sizeof(threads[0]));
+     if (threads == NULL) {
+       nthreads = ARRAY_SIZE(default_threads);
+       threads = default_threads;
+diff --git a/src/unix/bsd-ifaddrs.c b/src/unix/bsd-ifaddrs.c
+index 11ca9559..c3dd71a1 100644
+--- a/src/unix/bsd-ifaddrs.c
++++ b/src/unix/bsd-ifaddrs.c
+@@ -92,7 +92,7 @@ int uv_interface_addresses(uv_interface_address_t** addresses, int* count) {
+   }
+ 
+   /* Make sure the memory is initiallized to zero using calloc() */
+-  *addresses = uv__calloc(*count, sizeof(**addresses));
++  *addresses = (uv_interface_address_t*)uv__calloc(*count, sizeof(**addresses));
+ 
+   if (*addresses == NULL) {
+     freeifaddrs(addrs);
+diff --git a/src/unix/core.c b/src/unix/core.c
+index 54c769f3..6353b0e3 100644
+--- a/src/unix/core.c
++++ b/src/unix/core.c
+@@ -824,7 +824,7 @@ static unsigned int next_power_of_two(unsigned int val) {
+ }
+ 
+ static void maybe_resize(uv_loop_t* loop, unsigned int len) {
+-  uv__io_t** watchers;
++  void** watchers;
+   void* fake_watcher_list;
+   void* fake_watcher_count;
+   unsigned int nwatchers;
+@@ -843,8 +843,8 @@ static void maybe_resize(uv_loop_t* loop, unsigned int len) {
+   }
+ 
+   nwatchers = next_power_of_two(len + 2) - 2;
+-  watchers = uv__reallocf(loop->watchers,
+-                          (nwatchers + 2) * sizeof(loop->watchers[0]));
++  watchers = (void**)
++      uv__reallocf(loop->watchers, (nwatchers + 2) * sizeof(loop->watchers[0]));
+ 
+   if (watchers == NULL)
+     abort();
+@@ -1184,7 +1184,7 @@ int uv__getpwuid_r(uv_passwd_t* pwd) {
+    * is frequently 1024 or 4096, so we can just use that directly. The pwent
+    * will not usually be large. */
+   for (bufsize = 2000;; bufsize *= 2) {
+-    buf = uv__malloc(bufsize);
++    buf = (char*)uv__malloc(bufsize);
+ 
+     if (buf == NULL)
+       return UV_ENOMEM;
+@@ -1210,7 +1210,7 @@ int uv__getpwuid_r(uv_passwd_t* pwd) {
+   name_size = strlen(pw.pw_name) + 1;
+   homedir_size = strlen(pw.pw_dir) + 1;
+   shell_size = strlen(pw.pw_shell) + 1;
+-  pwd->username = uv__malloc(name_size + homedir_size + shell_size);
++  pwd->username = (char*)uv__malloc(name_size + homedir_size + shell_size);
+ 
+   if (pwd->username == NULL) {
+     uv__free(buf);
+@@ -1274,7 +1274,7 @@ int uv_os_environ(uv_env_item_t** envitems, int* count) {
+ 
+   for (i = 0; environ[i] != NULL; i++);
+ 
+-  *envitems = uv__calloc(i, sizeof(**envitems));
++  *envitems = (uv_env_item_s*)uv__calloc(i, sizeof(**envitems));
+ 
+   if (*envitems == NULL)
+     return UV_ENOMEM;
+diff --git a/src/unix/darwin-proctitle.c b/src/unix/darwin-proctitle.c
+index 5288083e..9bd55dd7 100644
+--- a/src/unix/darwin-proctitle.c
++++ b/src/unix/darwin-proctitle.c
+@@ -128,8 +128,9 @@ int uv__set_process_title(const char* title) {
+   if (pLSSetApplicationInformationItem == NULL)
+     goto out;
+ 
+-  display_name_key = pCFBundleGetDataPointerForName(launch_services_bundle,
+-                                                    S("_kLSDisplayNameKey"));
++  display_name_key = (CFStringRef*)
++      pCFBundleGetDataPointerForName(launch_services_bundle,
++                                     S("_kLSDisplayNameKey"));
+ 
+   if (display_name_key == NULL || *display_name_key == NULL)
+     goto out;
+diff --git a/src/unix/darwin.c b/src/unix/darwin.c
+index 62f04d31..5fbf7342 100644
+--- a/src/unix/darwin.c
++++ b/src/unix/darwin.c
+@@ -353,7 +353,7 @@ int uv_cpu_info(uv_cpu_info_t** cpu_infos, int* count) {
+     return UV_EINVAL;  /* FIXME(bnoordhuis) Translate error. */
+   }
+ 
+-  *cpu_infos = uv__malloc(numcpus * sizeof(**cpu_infos));
++  *cpu_infos = (uv_cpu_info_t*)uv__malloc(numcpus * sizeof(**cpu_infos));
+   if (!(*cpu_infos)) {
+     vm_deallocate(mach_task_self(), (vm_address_t)info, msg_type);
+     return UV_ENOMEM;
+diff --git a/src/unix/epoll.c b/src/unix/epoll.c
+index 97348e25..4c057fb3 100644
+--- a/src/unix/epoll.c
++++ b/src/unix/epoll.c
+@@ -325,7 +325,7 @@ void uv__io_poll(uv_loop_t* loop, int timeout) {
+       assert(fd >= 0);
+       assert((unsigned) fd < loop->nwatchers);
+ 
+-      w = loop->watchers[fd];
++      w = (uv__io_t*)loop->watchers[fd];
+ 
+       if (w == NULL) {
+         /* File descriptor that we've stopped watching, disarm it.
+diff --git a/src/unix/freebsd.c b/src/unix/freebsd.c
+index 658ff262..6700ff61 100644
+--- a/src/unix/freebsd.c
++++ b/src/unix/freebsd.c
+@@ -215,7 +215,7 @@ int uv_cpu_info(uv_cpu_info_t** cpu_infos, int* count) {
+   if (sysctlbyname("hw.ncpu", &numcpus, &size, NULL, 0))
+     return UV__ERR(errno);
+ 
+-  *cpu_infos = uv__malloc(numcpus * sizeof(**cpu_infos));
++  *cpu_infos = (uv_cpu_info_t*)uv__malloc(numcpus * sizeof(**cpu_infos));
+   if (!(*cpu_infos))
+     return UV_ENOMEM;
+ 
+@@ -232,7 +232,7 @@ int uv_cpu_info(uv_cpu_info_t** cpu_infos, int* count) {
+ 
+   size = maxcpus * CPUSTATES * sizeof(long);
+ 
+-  cp_times = uv__malloc(size);
++  cp_times = (long*)uv__malloc(size);
+   if (cp_times == NULL) {
+     uv__free(*cpu_infos);
+     return UV_ENOMEM;
+diff --git a/src/unix/fs.c b/src/unix/fs.c
+index 933c9c0d..1a615244 100644
+--- a/src/unix/fs.c
++++ b/src/unix/fs.c
+@@ -137,7 +137,7 @@ extern char *mkdtemp(char *template); /* See issue #740 on AIX < 7 */
+       size_t new_path_len;                                                    \
+       path_len = strlen(path) + 1;                                            \
+       new_path_len = strlen(new_path) + 1;                                    \
+-      req->path = uv__malloc(path_len + new_path_len);                        \
++      req->path = (char*)uv__malloc(path_len + new_path_len);                 \
+       if (req->path == NULL)                                                  \
+         return UV_ENOMEM;                                                     \
+       req->new_path = req->path + path_len;                                   \
+@@ -572,7 +572,7 @@ static ssize_t uv__fs_scandir(uv_fs_t* req) {
+ static int uv__fs_opendir(uv_fs_t* req) {
+   uv_dir_t* dir;
+ 
+-  dir = uv__malloc(sizeof(*dir));
++  dir = (uv_dir_t*)uv__malloc(sizeof(*dir));
+   if (dir == NULL)
+     goto error;
+ 
+@@ -596,7 +596,7 @@ static int uv__fs_readdir(uv_fs_t* req) {
+   unsigned int dirent_idx;
+   unsigned int i;
+ 
+-  dir = req->ptr;
++  dir = (uv_dir_t*)req->ptr;
+   dirent_idx = 0;
+ 
+   while (dirent_idx < dir->nentries) {
+@@ -638,7 +638,7 @@ error:
+ static int uv__fs_closedir(uv_fs_t* req) {
+   uv_dir_t* dir;
+ 
+-  dir = req->ptr;
++  dir = (uv_dir_t*)req->ptr;
+ 
+   if (dir->dir != NULL) {
+     closedir(dir->dir);
+@@ -667,7 +667,7 @@ static int uv__fs_statfs(uv_fs_t* req) {
+ #endif /* defined(__sun) */
+     return -1;
+ 
+-  stat_fs = uv__malloc(sizeof(*stat_fs));
++  stat_fs = (uv_statfs_t*)uv__malloc(sizeof(*stat_fs));
+   if (stat_fs == NULL) {
+     errno = ENOMEM;
+     return -1;
+@@ -731,7 +731,7 @@ static ssize_t uv__fs_readlink(uv_fs_t* req) {
+     maxlen = uv__fs_pathmax_size(req->path);
+ #endif
+ 
+-  buf = uv__malloc(maxlen);
++  buf = (char*)uv__malloc(maxlen);
+ 
+   if (buf == NULL) {
+     errno = ENOMEM;
+@@ -751,7 +751,7 @@ static ssize_t uv__fs_readlink(uv_fs_t* req) {
+ 
+   /* Uncommon case: resize to make room for the trailing nul byte. */
+   if (len == maxlen) {
+-    buf = uv__reallocf(buf, len + 1);
++    buf = (char*)uv__reallocf(buf, len + 1);
+ 
+     if (buf == NULL)
+       return -1;
+@@ -774,7 +774,7 @@ static ssize_t uv__fs_realpath(uv_fs_t* req) {
+   ssize_t len;
+ 
+   len = uv__fs_pathmax_size(req->path);
+-  buf = uv__malloc(len + 1);
++  buf = (char*)uv__malloc(len + 1);
+ 
+   if (buf == NULL) {
+     errno = ENOMEM;
+@@ -2010,7 +2010,7 @@ int uv_fs_read(uv_loop_t* loop, uv_fs_t* req,
+   req->nbufs = nbufs;
+   req->bufs = req->bufsml;
+   if (nbufs > ARRAY_SIZE(req->bufsml))
+-    req->bufs = uv__malloc(nbufs * sizeof(*bufs));
++    req->bufs = (uv_buf_t*)uv__malloc(nbufs * sizeof(*bufs));
+ 
+   if (req->bufs == NULL)
+     return UV_ENOMEM;
+@@ -2180,7 +2180,7 @@ int uv_fs_write(uv_loop_t* loop,
+   req->nbufs = nbufs;
+   req->bufs = req->bufsml;
+   if (nbufs > ARRAY_SIZE(req->bufsml))
+-    req->bufs = uv__malloc(nbufs * sizeof(*bufs));
++    req->bufs = (uv_buf_t*)uv__malloc(nbufs * sizeof(*bufs));
+ 
+   if (req->bufs == NULL)
+     return UV_ENOMEM;
+diff --git a/src/unix/fsevents.c b/src/unix/fsevents.c
+index bf4f1f6a..648c8a98 100644
+--- a/src/unix/fsevents.c
++++ b/src/unix/fsevents.c
+@@ -185,7 +185,7 @@ static void (*pFSEventStreamStop)(FSEventStreamRef);
+ static void uv__fsevents_cb(uv_async_t* cb) {
+   uv_fs_event_t* handle;
+ 
+-  handle = cb->data;
++  handle = (uv_fs_event_t*)cb->data;
+ 
+   UV__FSEVENTS_PROCESS(handle, {
+     handle->cb(handle, event->path[0] ? event->path : NULL, event->events, 0);
+@@ -233,10 +233,10 @@ static void uv__fsevents_event_cb(const FSEventStreamRef streamRef,
+   FSEventStreamEventFlags flags;
+   QUEUE head;
+ 
+-  loop = info;
+-  state = loop->cf_state;
++  loop = (uv_loop_t*)info;
++  state = (uv__cf_loop_state_t*)loop->cf_state;
+   assert(state != NULL);
+-  paths = eventPaths;
++  paths = (char**)eventPaths;
+ 
+   /* For each handle */
+   uv_mutex_lock(&state->fsevent_mutex);
+@@ -306,7 +306,7 @@ static void uv__fsevents_event_cb(const FSEventStreamRef streamRef,
+           continue;
+       }
+ 
+-      event = uv__malloc(sizeof(*event) + len);
++      event = (uv__fsevents_event_t*)uv__malloc(sizeof(*event) + len);
+       if (event == NULL)
+         break;
+ 
+@@ -373,7 +373,7 @@ static int uv__fsevents_create_stream(uv_loop_t* loop, CFArrayRef paths) {
+                              flags);
+   assert(ref != NULL);
+ 
+-  state = loop->cf_state;
++  state = (uv__cf_loop_state_t*)loop->cf_state;
+   pFSEventStreamScheduleWithRunLoop(ref,
+                                     state->loop,
+                                     *pkCFRunLoopDefaultMode);
+@@ -392,7 +392,7 @@ static int uv__fsevents_create_stream(uv_loop_t* loop, CFArrayRef paths) {
+ static void uv__fsevents_destroy_stream(uv_loop_t* loop) {
+   uv__cf_loop_state_t* state;
+ 
+-  state = loop->cf_state;
++  state = (uv__cf_loop_state_t*)loop->cf_state;
+ 
+   if (state->fsevent_stream == NULL)
+     return;
+@@ -419,7 +419,7 @@ static void uv__fsevents_reschedule(uv_fs_event_t* handle,
+   int err;
+   unsigned int path_count;
+ 
+-  state = handle->loop->cf_state;
++  state = (uv__cf_loop_state_t*)handle->loop->cf_state;
+   paths = NULL;
+   cf_paths = NULL;
+   err = 0;
+@@ -447,7 +447,7 @@ static void uv__fsevents_reschedule(uv_fs_event_t* handle,
+   uv_mutex_lock(&state->fsevent_mutex);
+   path_count = state->fsevent_handle_count;
+   if (path_count != 0) {
+-    paths = uv__malloc(sizeof(*paths) * path_count);
++    paths = (CFStringRef*)uv__malloc(sizeof(*paths) * path_count);
+     if (paths == NULL) {
+       uv_mutex_unlock(&state->fsevent_mutex);
+       goto final;
+@@ -605,7 +605,7 @@ static int uv__fsevents_loop_init(uv_loop_t* loop) {
+   if (err)
+     return err;
+ 
+-  state = uv__calloc(1, sizeof(*state));
++  state = (uv__cf_loop_state_t*)uv__calloc(1, sizeof(*state));
+   if (state == NULL)
+     return UV_ENOMEM;
+ 
+@@ -707,7 +707,7 @@ void uv__fsevents_loop_delete(uv_loop_t* loop) {
+   }
+ 
+   /* Destroy state */
+-  state = loop->cf_state;
++  state = (uv__cf_loop_state_t*)loop->cf_state;
+   uv_sem_destroy(&state->fsevent_sem);
+   uv_mutex_destroy(&state->fsevent_mutex);
+   pCFRelease(state->signal_source);
+@@ -721,8 +721,8 @@ static void* uv__cf_loop_runner(void* arg) {
+   uv_loop_t* loop;
+   uv__cf_loop_state_t* state;
+ 
+-  loop = arg;
+-  state = loop->cf_state;
++  loop = (uv_loop_t*)arg;
++  state = (uv__cf_loop_state_t*)loop->cf_state;
+   state->loop = pCFRunLoopGetCurrent();
+ 
+   pCFRunLoopAddSource(state->loop,
+@@ -750,8 +750,8 @@ static void uv__cf_loop_cb(void* arg) {
+   QUEUE split_head;
+   uv__cf_loop_signal_t* s;
+ 
+-  loop = arg;
+-  state = loop->cf_state;
++  loop = (uv_loop_t*)arg;
++  state = (uv__cf_loop_state_t*)loop->cf_state;
+ 
+   uv_mutex_lock(&loop->cf_mutex);
+   QUEUE_MOVE(&loop->cf_signals, &split_head);
+@@ -781,7 +781,7 @@ int uv__cf_loop_signal(uv_loop_t* loop,
+   uv__cf_loop_signal_t* item;
+   uv__cf_loop_state_t* state;
+ 
+-  item = uv__malloc(sizeof(*item));
++  item = (uv__cf_loop_signal_t*)uv__malloc(sizeof(*item));
+   if (item == NULL)
+     return UV_ENOMEM;
+ 
+@@ -791,7 +791,7 @@ int uv__cf_loop_signal(uv_loop_t* loop,
+   uv_mutex_lock(&loop->cf_mutex);
+   QUEUE_INSERT_TAIL(&loop->cf_signals, &item->member);
+ 
+-  state = loop->cf_state;
++  state = (uv__cf_loop_state_t*)loop->cf_state;
+   assert(state != NULL);
+   pCFRunLoopSourceSignal(state->signal_source);
+   pCFRunLoopWakeUp(state->loop);
+@@ -825,7 +825,7 @@ int uv__fsevents_init(uv_fs_event_t* handle) {
+    * Events will occur in other thread.
+    * Initialize callback for getting them back into event loop's thread
+    */
+-  handle->cf_cb = uv__malloc(sizeof(*handle->cf_cb));
++  handle->cf_cb = (uv_async_t*)uv__malloc(sizeof(*handle->cf_cb));
+   if (handle->cf_cb == NULL) {
+     err = UV_ENOMEM;
+     goto fail_cf_cb_malloc;
+@@ -841,7 +841,7 @@ int uv__fsevents_init(uv_fs_event_t* handle) {
+     goto fail_cf_mutex_init;
+ 
+   /* Insert handle into the list */
+-  state = handle->loop->cf_state;
++  state = (uv__cf_loop_state_t*)handle->loop->cf_state;
+   uv_mutex_lock(&state->fsevent_mutex);
+   QUEUE_INSERT_TAIL(&state->fsevent_handles, &handle->cf_member);
+   state->fsevent_handle_count++;
+@@ -881,7 +881,7 @@ int uv__fsevents_close(uv_fs_event_t* handle) {
+     return UV_EINVAL;
+ 
+   /* Remove handle from  the list */
+-  state = handle->loop->cf_state;
++  state = (uv__cf_loop_state_t*)handle->loop->cf_state;
+   uv_mutex_lock(&state->fsevent_mutex);
+   QUEUE_REMOVE(&handle->cf_member);
+   state->fsevent_handle_count--;
+diff --git a/src/unix/getaddrinfo.c b/src/unix/getaddrinfo.c
+index 77337ace..41dc3909 100644
+--- a/src/unix/getaddrinfo.c
++++ b/src/unix/getaddrinfo.c
+@@ -172,7 +172,7 @@ int uv_getaddrinfo(uv_loop_t* loop,
+   hostname_len = hostname ? strlen(hostname) + 1 : 0;
+   service_len = service ? strlen(service) + 1 : 0;
+   hints_len = hints ? sizeof(*hints) : 0;
+-  buf = uv__malloc(hostname_len + service_len + hints_len);
++  buf = (char*)uv__malloc(hostname_len + service_len + hints_len);
+ 
+   if (buf == NULL)
+     return UV_ENOMEM;
+@@ -190,17 +190,17 @@ int uv_getaddrinfo(uv_loop_t* loop,
+   len = 0;
+ 
+   if (hints) {
+-    req->hints = memcpy(buf + len, hints, sizeof(*hints));
++    req->hints = (struct addrinfo*)memcpy(buf + len, hints, sizeof(*hints));
+     len += sizeof(*hints);
+   }
+ 
+   if (service) {
+-    req->service = memcpy(buf + len, service, service_len);
++    req->service = (char*)memcpy(buf + len, service, service_len);
+     len += service_len;
+   }
+ 
+   if (hostname)
+-    req->hostname = memcpy(buf + len, hostname, hostname_len);
++    req->hostname = (char*)memcpy(buf + len, hostname, hostname_len);
+ 
+   if (cb) {
+     uv__work_submit(loop,
+diff --git a/src/unix/ibmi.c b/src/unix/ibmi.c
+index 8c6ae636..56af31e9 100644
+--- a/src/unix/ibmi.c
++++ b/src/unix/ibmi.c
+@@ -288,7 +288,7 @@ int uv_cpu_info(uv_cpu_info_t** cpu_infos, int* count) {
+ 
+   numcpus = sysconf(_SC_NPROCESSORS_ONLN);
+ 
+-  *cpu_infos = uv__malloc(numcpus * sizeof(uv_cpu_info_t));
++  *cpu_infos = (uv_cpu_info_t*)uv__malloc(numcpus * sizeof(uv_cpu_info_t));
+   if (!*cpu_infos) {
+     return UV_ENOMEM;
+   }
+diff --git a/src/unix/kqueue.c b/src/unix/kqueue.c
+index 5dac76ae..86eb529b 100644
+--- a/src/unix/kqueue.c
++++ b/src/unix/kqueue.c
+@@ -281,8 +281,8 @@ void uv__io_poll(uv_loop_t* loop, int timeout) {
+     nevents = 0;
+ 
+     assert(loop->watchers != NULL);
+-    loop->watchers[loop->nwatchers] = (void*) events;
+-    loop->watchers[loop->nwatchers + 1] = (void*) (uintptr_t) nfds;
++    loop->watchers[loop->nwatchers] = (uv__io_t*) events;
++    loop->watchers[loop->nwatchers + 1] = (uv__io_t*) (uintptr_t) nfds;
+     for (i = 0; i < nfds; i++) {
+       ev = events + i;
+       fd = ev->ident;
+@@ -304,7 +304,7 @@ void uv__io_poll(uv_loop_t* loop, int timeout) {
+       /* Skip invalidated events, see uv__platform_invalidate_fd */
+       if (fd == -1)
+         continue;
+-      w = loop->watchers[fd];
++      w = (uv__io_t*)loop->watchers[fd];
+ 
+       if (w == NULL) {
+         /* File descriptor that we've stopped watching, disarm it.
+diff --git a/src/unix/linux-core.c b/src/unix/linux-core.c
+index 23a7dafe..85f3fc01 100644
+--- a/src/unix/linux-core.c
++++ b/src/unix/linux-core.c
+@@ -117,7 +117,6 @@ void uv__platform_loop_delete(uv_loop_t* loop) {
+ }
+ 
+ 
+-
+ uint64_t uv__hrtime(uv_clocktype_t type) {
+   static clock_t fast_clock_id = -1;
+   struct timespec t;
+@@ -283,7 +282,7 @@ int uv_cpu_info(uv_cpu_info_t** cpu_infos, int* count) {
+     goto out;
+ 
+   err = UV_ENOMEM;
+-  ci = uv__calloc(numcpus, sizeof(*ci));
++  ci = (uv_cpu_info_t*)uv__calloc(numcpus, sizeof(*ci));
+   if (ci == NULL)
+     goto out;
+ 
+@@ -663,7 +662,7 @@ int uv_interface_addresses(uv_interface_address_t** addresses, int* count) {
+   }
+ 
+   /* Make sure the memory is initiallized to zero using calloc() */
+-  *addresses = uv__calloc(*count, sizeof(**addresses));
++  *addresses = (uv_interface_address_t*)uv__calloc(*count, sizeof(**addresses));
+   if (!(*addresses)) {
+     freeifaddrs(addrs);
+     return UV_ENOMEM;
+diff --git a/src/unix/linux-inotify.c b/src/unix/linux-inotify.c
+index c1bd260e..f5366e96 100644
+--- a/src/unix/linux-inotify.c
++++ b/src/unix/linux-inotify.c
+@@ -281,12 +281,12 @@ int uv_fs_event_start(uv_fs_event_t* handle,
+     goto no_insert;
+ 
+   len = strlen(path) + 1;
+-  w = uv__malloc(sizeof(*w) + len);
++  w = (watcher_list*)uv__malloc(sizeof(*w) + len);
+   if (w == NULL)
+     return UV_ENOMEM;
+ 
+   w->wd = wd;
+-  w->path = memcpy(w + 1, path, len);
++  w->path = (char*)memcpy(w + 1, path, len);
+   QUEUE_INIT(&w->watchers);
+   w->iterating = 0;
+   RB_INSERT(watcher_root, CAST(&handle->loop->inotify_watchers), w);
+diff --git a/src/unix/loop.c b/src/unix/loop.c
+index a88e71c3..2e819cdd 100644
+--- a/src/unix/loop.c
++++ b/src/unix/loop.c
+@@ -148,7 +148,7 @@ int uv_loop_fork(uv_loop_t* loop) {
+ 
+   /* Rearm all the watchers that aren't re-queued by the above. */
+   for (i = 0; i < loop->nwatchers; i++) {
+-    w = loop->watchers[i];
++    w = (uv__io_t*)loop->watchers[i];
+     if (w == NULL)
+       continue;
+ 
+diff --git a/src/unix/netbsd.c b/src/unix/netbsd.c
+index c66333f5..b6886a1c 100644
+--- a/src/unix/netbsd.c
++++ b/src/unix/netbsd.c
+@@ -206,14 +206,14 @@ int uv_cpu_info(uv_cpu_info_t** cpu_infos, int* count) {
+     cpuspeed = 0;
+ 
+   size = numcpus * CPUSTATES * sizeof(*cp_times);
+-  cp_times = uv__malloc(size);
++  cp_times = (u_int64_t*)uv__malloc(size);
+   if (cp_times == NULL)
+     return UV_ENOMEM;
+ 
+   if (sysctlbyname("kern.cp_time", cp_times, &size, NULL, 0))
+     return UV__ERR(errno);
+ 
+-  *cpu_infos = uv__malloc(numcpus * sizeof(**cpu_infos));
++  *cpu_infos = (uv_cpu_info_t*)uv__malloc(numcpus * sizeof(**cpu_infos));
+   if (!(*cpu_infos)) {
+     uv__free(cp_times);
+     uv__free(*cpu_infos);
+diff --git a/src/unix/openbsd.c b/src/unix/openbsd.c
+index f32a94df..62740f73 100644
+--- a/src/unix/openbsd.c
++++ b/src/unix/openbsd.c
+@@ -72,7 +72,7 @@ int uv_exepath(char* buffer, size_t* size) {
+   mypid = getpid();
+   for (;;) {
+     err = UV_ENOMEM;
+-    argsbuf = uv__reallocf(argsbuf, argsbuf_size);
++    argsbuf = (char**)uv__reallocf(argsbuf, argsbuf_size);
+     if (argsbuf == NULL)
+       goto out;
+     mib[0] = CTL_KERN;
+@@ -197,7 +197,7 @@ int uv_cpu_info(uv_cpu_info_t** cpu_infos, int* count) {
+   if (sysctl(which, ARRAY_SIZE(which), &numcpus, &size, NULL, 0))
+     return UV__ERR(errno);
+ 
+-  *cpu_infos = uv__malloc(numcpus * sizeof(**cpu_infos));
++  *cpu_infos = (uv_cpu_info_t*)uv__malloc(numcpus * sizeof(**cpu_infos));
+   if (!(*cpu_infos))
+     return UV_ENOMEM;
+ 
+diff --git a/src/unix/pipe.c b/src/unix/pipe.c
+index e8cfa148..c8ba31da 100644
+--- a/src/unix/pipe.c
++++ b/src/unix/pipe.c
+@@ -309,7 +309,7 @@ int uv_pipe_pending_count(uv_pipe_t* handle) {
+   if (handle->queued_fds == NULL)
+     return 1;
+ 
+-  queued_fds = handle->queued_fds;
++  queued_fds = (uv__stream_queued_fds_t*)(handle->queued_fds);
+   return queued_fds->offset + 1;
+ }
+ 
+@@ -346,7 +346,7 @@ int uv_pipe_chmod(uv_pipe_t* handle, int mode) {
+   if (r != UV_ENOBUFS)
+     return r;
+ 
+-  name_buffer = uv__malloc(name_len);
++  name_buffer = (char*)uv__malloc(name_len);
+   if (name_buffer == NULL)
+     return UV_ENOMEM;
+ 
+diff --git a/src/unix/poll.c b/src/unix/poll.c
+index 7a12e2d1..73647317 100644
+--- a/src/unix/poll.c
++++ b/src/unix/poll.c
+@@ -117,7 +117,7 @@ int uv_poll_stop(uv_poll_t* handle) {
+ 
+ 
+ int uv_poll_start(uv_poll_t* handle, int pevents, uv_poll_cb poll_cb) {
+-  uv__io_t** watchers;
++  void** watchers;
+   uv__io_t* w;
+   int events;
+ 
+diff --git a/src/unix/posix-poll.c b/src/unix/posix-poll.c
+index 0f4bf938..8da038d1 100644
+--- a/src/unix/posix-poll.c
++++ b/src/unix/posix-poll.c
+@@ -61,7 +61,7 @@ static void uv__pollfds_maybe_resize(uv_loop_t* loop) {
+     return;
+ 
+   n = loop->poll_fds_size ? loop->poll_fds_size * 2 : 64;
+-  p = uv__reallocf(loop->poll_fds, n * sizeof(*loop->poll_fds));
++  p = (struct pollfd*)uv__reallocf(loop->poll_fds, n * sizeof(*loop->poll_fds));
+   if (p == NULL)
+     abort();
+ 
+diff --git a/src/unix/process.c b/src/unix/process.c
+index f8415368..0916aa45 100644
+--- a/src/unix/process.c
++++ b/src/unix/process.c
+@@ -403,7 +403,7 @@ static int posix_spawn_can_use_setsid;
+ static void uv__spawn_init_posix_spawn_fncs(void) {
+   /* Try to locate all non-portable functions at runtime */
+   posix_spawn_fncs.file_actions.addchdir_np =
+-    dlsym(RTLD_DEFAULT, "posix_spawn_file_actions_addchdir_np");
++    (int (*)(void* const*, const char*)) dlsym(RTLD_DEFAULT, "posix_spawn_file_actions_addchdir_np");
+ }
+ 
+ 
+@@ -967,7 +967,7 @@ int uv_spawn(uv_loop_t* loop,
+   err = UV_ENOMEM;
+   pipes = pipes_storage;
+   if (stdio_count > (int) ARRAY_SIZE(pipes_storage))
+-    pipes = uv__malloc(stdio_count * sizeof(*pipes));
++    pipes = (int (*)[2])uv__malloc(stdio_count * sizeof(*pipes));
+ 
+   if (pipes == NULL)
+     goto error;
+diff --git a/src/unix/proctitle.c b/src/unix/proctitle.c
+index 9d1f00dd..8cdec753 100644
+--- a/src/unix/proctitle.c
++++ b/src/unix/proctitle.c
+@@ -65,7 +65,7 @@ char** uv_setup_args(int argc, char** argv) {
+   /* Add space for the argv pointers. */
+   size += (argc + 1) * sizeof(char*);
+ 
+-  new_argv = uv__malloc(size);
++  new_argv = (char**)uv__malloc(size);
+   if (new_argv == NULL)
+     return argv;
+ 
+diff --git a/src/unix/random-sysctl-linux.c b/src/unix/random-sysctl-linux.c
+index 66ba8d74..9ef18df0 100644
+--- a/src/unix/random-sysctl-linux.c
++++ b/src/unix/random-sysctl-linux.c
+@@ -48,7 +48,7 @@ int uv__random_sysctl(void* buf, size_t buflen) {
+   char* pe;
+   size_t n;
+ 
+-  p = buf;
++  p = (char*)buf;
+   pe = p + buflen;
+ 
+   while (p < pe) {
+diff --git a/src/unix/stream.c b/src/unix/stream.c
+index b1f6359e..c6cc50e7 100644
+--- a/src/unix/stream.c
++++ b/src/unix/stream.c
+@@ -113,7 +113,7 @@ static void uv__stream_osx_interrupt_select(uv_stream_t* stream) {
+   uv__stream_select_t* s;
+   int r;
+ 
+-  s = stream->select;
++  s = (uv__stream_select_t*)stream->select;
+   if (s == NULL)
+     return;
+ 
+@@ -142,8 +142,8 @@ static void uv__stream_osx_select(void* arg) {
+   int r;
+   int max_fd;
+ 
+-  stream = arg;
+-  s = stream->select;
++  stream = (uv_stream_t*)arg;
++  s = (uv__stream_select_t*)stream->select;
+   fd = s->fd;
+ 
+   if (fd > s->int_fd)
+@@ -320,7 +320,7 @@ int uv__stream_try_select(uv_stream_t* stream, int* fd) {
+   sread_sz = ROUND_UP(max_fd + 1, sizeof(uint32_t) * NBBY) / NBBY;
+   swrite_sz = sread_sz;
+ 
+-  s = uv__malloc(sizeof(*s) + sread_sz + swrite_sz);
++  s = (uv__stream_select_t*)uv__malloc(sizeof(*s) + sread_sz + swrite_sz);
+   if (s == NULL) {
+     err = UV_ENOMEM;
+     goto failed_malloc;
+@@ -605,7 +605,7 @@ done:
+   if (server->queued_fds != NULL) {
+     uv__stream_queued_fds_t* queued_fds;
+ 
+-    queued_fds = server->queued_fds;
++    queued_fds = (uv__stream_queued_fds_t*)(server->queued_fds);
+ 
+     /* Read first */
+     server->accepted_fd = queued_fds->fds[0];
+@@ -844,7 +844,7 @@ static int uv__try_write(uv_stream_t* stream,
+     /* silence aliasing warning */
+     {
+       void* pv = CMSG_DATA(cmsg);
+-      int* pi = pv;
++      int* pi = (int*)pv;
+       *pi = fd_to_send;
+     }
+ 
+@@ -975,11 +975,12 @@ static int uv__stream_queue_fd(uv_stream_t* stream, int fd) {
+   uv__stream_queued_fds_t* queued_fds;
+   unsigned int queue_size;
+ 
+-  queued_fds = stream->queued_fds;
++  queued_fds = (uv__stream_queued_fds_t*)stream->queued_fds;
+   if (queued_fds == NULL) {
+     queue_size = 8;
+-    queued_fds = uv__malloc((queue_size - 1) * sizeof(*queued_fds->fds) +
+-                            sizeof(*queued_fds));
++    queued_fds = (uv__stream_queued_fds_t*)
++        uv__malloc((queue_size - 1) * sizeof(*queued_fds->fds) +
++                   sizeof(*queued_fds));
+     if (queued_fds == NULL)
+       return UV_ENOMEM;
+     queued_fds->size = queue_size;
+@@ -989,9 +990,9 @@ static int uv__stream_queue_fd(uv_stream_t* stream, int fd) {
+     /* Grow */
+   } else if (queued_fds->size == queued_fds->offset) {
+     queue_size = queued_fds->size + 8;
+-    queued_fds = uv__realloc(queued_fds,
+-                             (queue_size - 1) * sizeof(*queued_fds->fds) +
+-                              sizeof(*queued_fds));
++    queued_fds = (uv__stream_queued_fds_t*)
++        uv__realloc(queued_fds, (queue_size - 1) * sizeof(*queued_fds->fds) +
++                    sizeof(*queued_fds));
+ 
+     /*
+      * Allocation failure, report back.
+@@ -1039,7 +1040,7 @@ static int uv__stream_recv_cmsg(uv_stream_t* stream, struct msghdr* msg) {
+ 
+     /* silence aliasing warning */
+     pv = CMSG_DATA(cmsg);
+-    pi = pv;
++    pi = (int*)pv;
+ 
+     /* Count available fds */
+     start = (char*) cmsg;
+@@ -1423,7 +1424,7 @@ int uv_write2(uv_write_t* req,
+ 
+   req->bufs = req->bufsml;
+   if (nbufs > ARRAY_SIZE(req->bufsml))
+-    req->bufs = uv__malloc(nbufs * sizeof(bufs[0]));
++    req->bufs = (uv_buf_t*)uv__malloc(nbufs * sizeof(bufs[0]));
+ 
+   if (req->bufs == NULL)
+     return UV_ENOMEM;
+@@ -1557,7 +1558,7 @@ int uv___stream_fd(const uv_stream_t* handle) {
+          handle->type == UV_TTY ||
+          handle->type == UV_NAMED_PIPE);
+ 
+-  s = handle->select;
++  s = (const uv__stream_select_t*)handle->select;
+   if (s != NULL)
+     return s->fd;
+ 
+@@ -1575,7 +1576,7 @@ void uv__stream_close(uv_stream_t* handle) {
+   if (handle->select != NULL) {
+     uv__stream_select_t* s;
+ 
+-    s = handle->select;
++    s = (uv__stream_select_t*)handle->select;
+ 
+     uv_sem_post(&s->close_sem);
+     uv_sem_post(&s->async_sem);
+@@ -1610,7 +1611,7 @@ void uv__stream_close(uv_stream_t* handle) {
+ 
+   /* Close all queued fds */
+   if (handle->queued_fds != NULL) {
+-    queued_fds = handle->queued_fds;
++    queued_fds = (uv__stream_queued_fds_t*)(handle->queued_fds);
+     for (i = 0; i < queued_fds->offset; i++)
+       uv__close(queued_fds->fds[i]);
+     uv__free(handle->queued_fds);
+diff --git a/src/unix/thread.c b/src/unix/thread.c
+index d89e5cd1..759cd0c2 100644
+--- a/src/unix/thread.c
++++ b/src/unix/thread.c
+@@ -59,7 +59,7 @@ int uv_barrier_init(uv_barrier_t* barrier, unsigned int count) {
+   if (barrier == NULL || count == 0)
+     return UV_EINVAL;
+ 
+-  b = uv__malloc(sizeof(*b));
++  b = (_uv_barrier*)uv__malloc(sizeof(*b));
+   if (b == NULL)
+     return UV_ENOMEM;
+ 
+@@ -275,8 +275,7 @@ int uv_thread_create_ex(uv_thread_t* tid,
+       abort();
+   }
+ 
+-  f.in = entry;
+-  err = pthread_create(tid, attr, f.out, arg);
++  err = pthread_create(tid, attr, (void*(*)(void*)) (void(*)(void)) entry, arg);
+ 
+   if (attr != NULL)
+     pthread_attr_destroy(attr);
+@@ -547,7 +546,7 @@ static int uv__custom_sem_init(uv_sem_t* sem_, unsigned int value) {
+   int err;
+   uv_semaphore_t* sem;
+ 
+-  sem = uv__malloc(sizeof(*sem));
++  sem = (uv_semaphore_t*)uv__malloc(sizeof(*sem));
+   if (sem == NULL)
+     return UV_ENOMEM;
+ 
+diff --git a/src/unix/udp.c b/src/unix/udp.c
+index 4d985b88..a130aeaa 100644
+--- a/src/unix/udp.c
++++ b/src/unix/udp.c
+@@ -227,11 +227,11 @@ static int uv__udp_recvmmsg(uv_udp_t* handle, uv_buf_t* buf) {
+       if (msgs[k].msg_hdr.msg_flags & MSG_TRUNC)
+         flags |= UV_UDP_PARTIAL;
+ 
+-      chunk_buf = uv_buf_init(iov[k].iov_base, iov[k].iov_len);
++      chunk_buf = uv_buf_init((char*) iov[k].iov_base, iov[k].iov_len);
+       handle->recv_cb(handle,
+                       msgs[k].msg_len,
+                       &chunk_buf,
+-                      msgs[k].msg_hdr.msg_name,
++                      (const sockaddr*) msgs[k].msg_hdr.msg_name,
+                       flags);
+     }
+ 
+@@ -281,7 +281,7 @@ static void uv__udp_recvmsg(uv_udp_t* handle) {
+     memset(&peer, 0, sizeof(peer));
+     h.msg_name = &peer;
+     h.msg_namelen = sizeof(peer);
+-    h.msg_iov = (void*) &buf;
++    h.msg_iov = (iovec*) &buf;
+     h.msg_iovlen = 1;
+ 
+     do {
+@@ -765,7 +765,7 @@ int uv__udp_send(uv_udp_send_t* req,
+ 
+   req->bufs = req->bufsml;
+   if (nbufs > ARRAY_SIZE(req->bufsml))
+-    req->bufs = uv__malloc(nbufs * sizeof(bufs[0]));
++    req->bufs = (uv_buf_t*)uv__malloc(nbufs * sizeof(bufs[0]));
+ 
+   if (req->bufs == NULL) {
+     uv__req_unregister(handle->loop, req);
+diff --git a/src/uv-common.c b/src/uv-common.c
+index efc9eb50..dfb606e3 100644
+--- a/src/uv-common.c
++++ b/src/uv-common.c
+@@ -54,10 +54,10 @@ static uv__allocator_t uv__allocator = {
+ 
+ char* uv__strdup(const char* s) {
+   size_t len = strlen(s) + 1;
+-  char* m = uv__malloc(len);
++  char* m = (char*)uv__malloc(len);
+   if (m == NULL)
+     return NULL;
+-  return memcpy(m, s, len);
++  return (char*)memcpy(m, s, len);
+ }
+ 
+ char* uv__strndup(const char* s, size_t n) {
+@@ -65,11 +65,11 @@ char* uv__strndup(const char* s, size_t n) {
+   size_t len = strlen(s);
+   if (n < len)
+     len = n;
+-  m = uv__malloc(len + 1);
++  m = (char*)uv__malloc(len + 1);
+   if (m == NULL)
+     return NULL;
+   m[len] = '\0';
+-  return memcpy(m, s, len);
++  return (char*)memcpy(m, s, len);
+ }
+ 
+ void* uv__malloc(size_t size) {
+@@ -653,7 +653,7 @@ void uv__fs_scandir_cleanup(uv_fs_t* req) {
+ 
+   unsigned int* nbufs = uv__get_nbufs(req);
+ 
+-  dents = req->ptr;
++  dents = (uv__dirent_t**)(req->ptr);
+   if (*nbufs > 0 && *nbufs != (unsigned int) req->result)
+     (*nbufs)--;
+   for (; *nbufs < (unsigned int) req->result; (*nbufs)++)
+@@ -680,7 +680,7 @@ int uv_fs_scandir_next(uv_fs_t* req, uv_dirent_t* ent) {
+   nbufs = uv__get_nbufs(req);
+   assert(nbufs);
+ 
+-  dents = req->ptr;
++  dents = (uv__dirent_t**)(req->ptr);
+ 
+   /* Free previous entity */
+   if (*nbufs > 0)
+@@ -745,7 +745,7 @@ void uv__fs_readdir_cleanup(uv_fs_t* req) {
+   if (req->ptr == NULL)
+     return;
+ 
+-  dir = req->ptr;
++  dir = (uv_dir_t*)req->ptr;
+   dirents = dir->dirents;
+   req->ptr = NULL;
+ 
+@@ -791,7 +791,7 @@ uv_loop_t* uv_default_loop(void) {
+ uv_loop_t* uv_loop_new(void) {
+   uv_loop_t* loop;
+ 
+-  loop = uv__malloc(sizeof(*loop));
++  loop = (uv_loop_t*)uv__malloc(sizeof(*loop));
+   if (loop == NULL)
+     return NULL;
+ 
+diff --git a/src/win/core.c b/src/win/core.c
+index 67af93e6..0752edff 100644
+--- a/src/win/core.c
++++ b/src/win/core.c
+@@ -98,7 +98,8 @@ static int uv__loops_add(uv_loop_t* loop) {
+ 
+   if (uv__loops_size == uv__loops_capacity) {
+     new_capacity = uv__loops_capacity + UV__LOOPS_CHUNK_SIZE;
+-    new_loops = uv__realloc(uv__loops, sizeof(uv_loop_t*) * new_capacity);
++    new_loops = (uv_loop_t**)
++        uv__realloc(uv__loops, sizeof(uv_loop_t*) * new_capacity);
+     if (!new_loops)
+       goto failed_loops_realloc;
+     uv__loops = new_loops;
+@@ -152,7 +153,8 @@ static void uv__loops_remove(uv_loop_t* loop) {
+   smaller_capacity = uv__loops_capacity / 2;
+   if (uv__loops_size >= smaller_capacity)
+     goto loop_removed;
+-  new_loops = uv__realloc(uv__loops, sizeof(uv_loop_t*) * smaller_capacity);
++  new_loops = (uv_loop_t**)
++      uv__realloc(uv__loops, sizeof(uv_loop_t*) * smaller_capacity);
+   if (!new_loops)
+     goto loop_removed;
+   uv__loops = new_loops;
+@@ -261,7 +263,7 @@ int uv_loop_init(uv_loop_t* loop) {
+ 
+   loop->endgame_handles = NULL;
+ 
+-  loop->timer_heap = timer_heap = uv__malloc(sizeof(*timer_heap));
++  loop->timer_heap = timer_heap = (heap*)uv__malloc(sizeof(*timer_heap));
+   if (timer_heap == NULL) {
+     err = UV_ENOMEM;
+     goto fail_timers_alloc;
+diff --git a/src/win/fs-event.c b/src/win/fs-event.c
+index 6758c7c7..15046731 100644
+--- a/src/win/fs-event.c
++++ b/src/win/fs-event.c
+@@ -73,7 +73,7 @@ static void uv__relative_path(const WCHAR* filename,
+   if (dirlen > 0 && dir[dirlen - 1] == '\\')
+     dirlen--;
+   relpathlen = filenamelen - dirlen - 1;
+-  *relpath = uv__malloc((relpathlen + 1) * sizeof(WCHAR));
++  *relpath = (WCHAR*)uv__malloc((relpathlen + 1) * sizeof(WCHAR));
+   if (!*relpath)
+     uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+   wcsncpy(*relpath, filename + dirlen + 1, relpathlen);
+@@ -242,7 +242,7 @@ int uv_fs_event_start(uv_fs_event_t* handle,
+     if (short_path_buffer_len == 0) {
+       goto short_path_done;
+     }
+-    short_path_buffer = uv__malloc(short_path_buffer_len * sizeof(WCHAR));
++    short_path_buffer = (WCHAR*)uv__malloc(short_path_buffer_len * sizeof(WCHAR));
+     if (short_path_buffer == NULL) {
+       goto short_path_done;
+     }
+diff --git a/src/win/fs-fd-hash-inl.h b/src/win/fs-fd-hash-inl.h
+index 0b532af1..703a8d8f 100644
+--- a/src/win/fs-fd-hash-inl.h
++++ b/src/win/fs-fd-hash-inl.h
+@@ -146,7 +146,7 @@ INLINE static void uv__fd_hash_add(int fd, struct uv__fd_info_s* info) {
+ 
+     if (bucket_ptr->size != 0 && i == 0) {
+       struct uv__fd_hash_entry_group_s* new_group_ptr =
+-        uv__malloc(sizeof(*new_group_ptr));
++        (struct uv__fd_hash_entry_group_s*)uv__malloc(sizeof(*new_group_ptr));
+       if (new_group_ptr == NULL) {
+         uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+       }
+diff --git a/src/win/fs.c b/src/win/fs.c
+index 79230799..8374012f 100644
+--- a/src/win/fs.c
++++ b/src/win/fs.c
+@@ -285,7 +285,7 @@ static int fs__wide_to_utf8(WCHAR* w_source_ptr,
+     return 0;
+   }
+ 
+-  target = uv__malloc(target_len + 1);
++  target = (char*)uv__malloc(target_len + 1);
+   if (target == NULL) {
+     SetLastError(ERROR_OUTOFMEMORY);
+     return -1;
+@@ -1464,7 +1464,7 @@ void fs__scandir(uv_fs_t* req) {
+       if (dirents_used >= dirents_size) {
+         size_t new_dirents_size =
+             dirents_size == 0 ? dirents_initial_size : dirents_size << 1;
+-        uv__dirent_t** new_dirents =
++        uv__dirent_t** new_dirents = (uv__dirent_t**)
+             uv__realloc(dirents, new_dirents_size * sizeof *dirents);
+ 
+         if (new_dirents == NULL)
+@@ -1478,7 +1478,7 @@ void fs__scandir(uv_fs_t* req) {
+        * includes room for the first character of the filename, but `utf8_len`
+        * doesn't count the NULL terminator at this point.
+        */
+-      dirent = uv__malloc(sizeof *dirent + utf8_len);
++      dirent = (uv__dirent_t*)uv__malloc(sizeof *dirent + utf8_len);
+       if (dirent == NULL)
+         goto out_of_memory_error;
+ 
+@@ -1589,7 +1589,7 @@ void fs__opendir(uv_fs_t* req) {
+     goto error;
+   }
+ 
+-  dir = uv__malloc(sizeof(*dir));
++  dir = (uv_dir_t*)uv__malloc(sizeof(*dir));
+   if (dir == NULL) {
+     SET_REQ_UV_ERROR(req, UV_ENOMEM, ERROR_OUTOFMEMORY);
+     goto error;
+@@ -1604,7 +1604,7 @@ void fs__opendir(uv_fs_t* req) {
+   else
+     fmt = L"%s\\*";
+ 
+-  find_path = uv__malloc(sizeof(WCHAR) * (len + 4));
++  find_path = (WCHAR*)uv__malloc(sizeof(WCHAR) * (len + 4));
+   if (find_path == NULL) {
+     SET_REQ_UV_ERROR(req, UV_ENOMEM, ERROR_OUTOFMEMORY);
+     goto error;
+@@ -1641,7 +1641,7 @@ void fs__readdir(uv_fs_t* req) {
+   int r;
+ 
+   req->flags |= UV_FS_FREE_PTR;
+-  dir = req->ptr;
++  dir = (uv_dir_t*)req->ptr;
+   dirents = dir->dirents;
+   memset(dirents, 0, dir->nentries * sizeof(*dir->dirents));
+   find_data = &dir->find_data;
+@@ -1698,7 +1698,7 @@ error:
+ void fs__closedir(uv_fs_t* req) {
+   uv_dir_t* dir;
+ 
+-  dir = req->ptr;
++  dir = (uv_dir_t*)req->ptr;
+   FindClose(dir->dir_handle);
+   uv__free(req->ptr);
+   SET_REQ_RESULT(req, 0);
+@@ -2627,7 +2627,7 @@ static ssize_t fs__realpath_handle(HANDLE handle, char** realpath_ptr) {
+     return -1;
+   }
+ 
+-  w_realpath_buf = uv__malloc((w_realpath_len + 1) * sizeof(WCHAR));
++  w_realpath_buf = (WCHAR*)uv__malloc((w_realpath_len + 1) * sizeof(WCHAR));
+   if (w_realpath_buf == NULL) {
+     SetLastError(ERROR_OUTOFMEMORY);
+     return -1;
+@@ -2738,7 +2738,7 @@ retry_get_disk_free_space:
+     }
+ 
+     len = MAX_PATH + 1;
+-    pathw = uv__malloc(len * sizeof(*pathw));
++    pathw = (WCHAR*)uv__malloc(len * sizeof(*pathw));
+     if (pathw == NULL) {
+       SET_REQ_UV_ERROR(req, UV_ENOMEM, ERROR_OUTOFMEMORY);
+       return;
+@@ -2754,7 +2754,7 @@ retry_get_full_path_name:
+       return;
+     } else if (ret > len) {
+       len = ret;
+-      pathw = uv__reallocf(pathw, len * sizeof(*pathw));
++      pathw = (WCHAR*)uv__reallocf(pathw, len * sizeof(*pathw));
+       if (pathw == NULL) {
+         SET_REQ_UV_ERROR(req, UV_ENOMEM, ERROR_OUTOFMEMORY);
+         return;
+@@ -2770,7 +2770,7 @@ retry_get_full_path_name:
+     uv__free(pathw);
+   }
+ 
+-  stat_fs = uv__malloc(sizeof(*stat_fs));
++  stat_fs = (uv_statfs_t*)uv__malloc(sizeof(*stat_fs));
+   if (stat_fs == NULL) {
+     SET_REQ_UV_ERROR(req, UV_ENOMEM, ERROR_OUTOFMEMORY);
+     return;
+@@ -2929,7 +2929,7 @@ int uv_fs_read(uv_loop_t* loop,
+   req->fs.info.nbufs = nbufs;
+   req->fs.info.bufs = req->fs.info.bufsml;
+   if (nbufs > ARRAY_SIZE(req->fs.info.bufsml))
+-    req->fs.info.bufs = uv__malloc(nbufs * sizeof(*bufs));
++    req->fs.info.bufs = (uv_buf_t*)uv__malloc(nbufs * sizeof(*bufs));
+ 
+   if (req->fs.info.bufs == NULL) {
+     SET_REQ_UV_ERROR(req, UV_ENOMEM, ERROR_OUTOFMEMORY);
+@@ -2962,7 +2962,7 @@ int uv_fs_write(uv_loop_t* loop,
+   req->fs.info.nbufs = nbufs;
+   req->fs.info.bufs = req->fs.info.bufsml;
+   if (nbufs > ARRAY_SIZE(req->fs.info.bufsml))
+-    req->fs.info.bufs = uv__malloc(nbufs * sizeof(*bufs));
++    req->fs.info.bufs = (uv_buf_t*)uv__malloc(nbufs * sizeof(*bufs));
+ 
+   if (req->fs.info.bufs == NULL) {
+     SET_REQ_UV_ERROR(req, UV_ENOMEM, ERROR_OUTOFMEMORY);
+diff --git a/src/win/pipe.c b/src/win/pipe.c
+index 99846181..cd77061a 100644
+--- a/src/win/pipe.c
++++ b/src/win/pipe.c
+@@ -728,7 +728,7 @@ int uv_pipe_bind(uv_pipe_t* handle, const char* name) {
+ 
+   /* Convert name to UTF16. */
+   nameSize = MultiByteToWideChar(CP_UTF8, 0, name, -1, NULL, 0) * sizeof(WCHAR);
+-  handle->name = uv__malloc(nameSize);
++  handle->name = (WCHAR*)uv__malloc(nameSize);
+   if (!handle->name) {
+     uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+   }
+@@ -841,7 +841,7 @@ void uv_pipe_connect(uv_connect_t* req, uv_pipe_t* handle,
+ 
+   /* Convert name to UTF16. */
+   nameSize = MultiByteToWideChar(CP_UTF8, 0, name, -1, NULL, 0) * sizeof(WCHAR);
+-  handle->name = uv__malloc(nameSize);
++  handle->name = (WCHAR*)uv__malloc(nameSize);
+   if (!handle->name) {
+     uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+   }
+@@ -1453,7 +1453,7 @@ static int uv__build_coalesced_write_req(uv_write_t* user_req,
+                        data_length;                  /* (c) */
+ 
+   /* Allocate buffer. */
+-  heap_buffer = uv__malloc(heap_buffer_length);
++  heap_buffer = (char*)uv__malloc(heap_buffer_length);
+   if (heap_buffer == NULL)
+     return ERROR_NOT_ENOUGH_MEMORY; /* Maps to UV_ENOMEM. */
+ 
+@@ -1698,7 +1698,7 @@ int uv__pipe_write_ipc(uv_loop_t* loop,
+     bufs = stack_bufs;
+   } else {
+     /* Use heap-allocated buffer array. */
+-    bufs = uv__calloc(buf_count, sizeof(uv_buf_t));
++    bufs = (uv_buf_t*)uv__calloc(buf_count, sizeof(uv_buf_t));
+     if (bufs == NULL)
+       return ERROR_NOT_ENOUGH_MEMORY; /* Maps to UV_ENOMEM. */
+   }
+@@ -2430,7 +2430,7 @@ static int uv__pipe_getname(const uv_pipe_t* handle, char* buffer, size_t* size)
+                                       FileNameInformation);
+   if (nt_status == STATUS_BUFFER_OVERFLOW) {
+     name_size = sizeof(*name_info) + tmp_name_info.FileNameLength;
+-    name_info = uv__malloc(name_size);
++    name_info = (FILE_NAME_INFORMATION*)uv__malloc(name_size);
+     if (!name_info) {
+       *size = 0;
+       err = UV_ENOMEM;
+diff --git a/src/win/process.c b/src/win/process.c
+index 24c63339..e857db3e 100644
+--- a/src/win/process.c
++++ b/src/win/process.c
+@@ -616,8 +616,8 @@ error:
+ 
+ 
+ int env_strncmp(const wchar_t* a, int na, const wchar_t* b) {
+-  wchar_t* a_eq;
+-  wchar_t* b_eq;
++  const wchar_t* a_eq;
++  const wchar_t* b_eq;
+   wchar_t* A;
+   wchar_t* B;
+   int nb;
+@@ -634,8 +634,8 @@ int env_strncmp(const wchar_t* a, int na, const wchar_t* b) {
+   assert(b_eq);
+   nb = b_eq - b;
+ 
+-  A = alloca((na+1) * sizeof(wchar_t));
+-  B = alloca((nb+1) * sizeof(wchar_t));
++  A = (wchar_t*)alloca((na+1) * sizeof(wchar_t));
++  B = (wchar_t*)alloca((nb+1) * sizeof(wchar_t));
+ 
+   r = LCMapStringW(LOCALE_INVARIANT, LCMAP_UPPERCASE, a, na, A, na);
+   assert(r==na);
+@@ -718,7 +718,7 @@ int make_program_env(char* env_block[], WCHAR** dst_ptr) {
+   if (dst_copy == NULL && env_len > 0) {
+     return ERROR_OUTOFMEMORY;
+   }
+-  env_copy = alloca(env_block_count * sizeof(WCHAR*));
++  env_copy = (WCHAR**)alloca(env_block_count * sizeof(WCHAR*));
+ 
+   ptr = dst_copy;
+   ptr_copy = env_copy;
+@@ -772,7 +772,7 @@ int make_program_env(char* env_block[], WCHAR** dst_ptr) {
+   }
+ 
+   /* final pass: copy, in sort order, and inserting required variables */
+-  dst = uv__malloc((1+env_len) * sizeof(WCHAR));
++  dst = (WCHAR*)uv__malloc((1+env_len) * sizeof(WCHAR));
+   if (!dst) {
+     uv__free(dst_copy);
+     return ERROR_OUTOFMEMORY;
+diff --git a/src/win/tcp.c b/src/win/tcp.c
+index b6aa4c51..4cccee42 100644
+--- a/src/win/tcp.c
++++ b/src/win/tcp.c
+@@ -612,7 +612,7 @@ int uv__tcp_listen(uv_tcp_t* handle, int backlog, uv_connection_cb cb) {
+ 
+   if (handle->tcp.serv.accept_reqs == NULL) {
+     handle->tcp.serv.accept_reqs =
+-      uv__malloc(uv_simultaneous_server_accepts * sizeof(uv_tcp_accept_t));
++      (uv_tcp_accept_t*)uv__malloc(uv_simultaneous_server_accepts * sizeof(uv_tcp_accept_t));
+     if (!handle->tcp.serv.accept_reqs) {
+       uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+     }
+diff --git a/src/win/thread.c b/src/win/thread.c
+index d3b1c96b..9ad60c91 100644
+--- a/src/win/thread.c
++++ b/src/win/thread.c
+@@ -98,7 +98,7 @@ static UINT __stdcall uv__thread_start(void* arg) {
+   struct thread_ctx *ctx_p;
+   struct thread_ctx ctx;
+ 
+-  ctx_p = arg;
++  ctx_p = (struct thread_ctx*)arg;
+   ctx = *ctx_p;
+   uv__free(ctx_p);
+ 
+@@ -141,7 +141,7 @@ int uv_thread_create_ex(uv_thread_t* tid,
+       return UV_EINVAL;
+   }
+ 
+-  ctx = uv__malloc(sizeof(*ctx));
++  ctx = (struct thread_ctx*)uv__malloc(sizeof(*ctx));
+   if (ctx == NULL)
+     return UV_ENOMEM;
+ 
+diff --git a/src/win/util.c b/src/win/util.c
+index 99432053..c655f532 100644
+--- a/src/win/util.c
++++ b/src/win/util.c
+@@ -164,7 +164,7 @@ int uv_cwd(char* buffer, size_t* size) {
+   if (utf16_len == 0) {
+     return uv_translate_sys_error(GetLastError());
+   }
+-  utf16_buffer = uv__malloc(utf16_len * sizeof(WCHAR));
++  utf16_buffer = (WCHAR*)uv__malloc(utf16_len * sizeof(WCHAR));
+   if (utf16_buffer == NULL) {
+     return UV_ENOMEM;
+   }
+@@ -242,7 +242,7 @@ int uv_chdir(const char* dir) {
+   if (utf16_len == 0) {
+     return uv_translate_sys_error(GetLastError());
+   }
+-  utf16_buffer = uv__malloc(utf16_len * sizeof(WCHAR));
++  utf16_buffer = (WCHAR*)uv__malloc(utf16_len * sizeof(WCHAR));
+   if (utf16_buffer == NULL) {
+     return UV_ENOMEM;
+   }
+@@ -268,7 +268,7 @@ int uv_chdir(const char* dir) {
+   new_utf16_len = GetCurrentDirectoryW(utf16_len, utf16_buffer);
+   if (new_utf16_len > utf16_len ) {
+     uv__free(utf16_buffer);
+-    utf16_buffer = uv__malloc(new_utf16_len * sizeof(WCHAR));
++    utf16_buffer = (WCHAR*)uv__malloc(new_utf16_len * sizeof(WCHAR));
+     if (utf16_buffer == NULL) {
+       /* When updating the environment variable fails, return UV_OK anyway.
+        * We did successfully change current working directory, only updating
+@@ -573,14 +573,14 @@ int uv_cpu_info(uv_cpu_info_t** cpu_infos_ptr, int* cpu_count_ptr) {
+   GetSystemInfo(&system_info);
+   cpu_count = system_info.dwNumberOfProcessors;
+ 
+-  cpu_infos = uv__calloc(cpu_count, sizeof *cpu_infos);
++  cpu_infos = (uv_cpu_info_t*)uv__calloc(cpu_count, sizeof *cpu_infos);
+   if (cpu_infos == NULL) {
+     err = ERROR_OUTOFMEMORY;
+     goto error;
+   }
+ 
+   sppi_size = cpu_count * sizeof(*sppi);
+-  sppi = uv__malloc(sppi_size);
++  sppi = (SYSTEM_PROCESSOR_PERFORMANCE_INFORMATION*)uv__malloc(sppi_size);
+   if (sppi == NULL) {
+     err = ERROR_OUTOFMEMORY;
+     goto error;
+@@ -802,7 +802,8 @@ int uv_interface_addresses(uv_interface_address_t** addresses_ptr,
+       case ERROR_BUFFER_OVERFLOW:
+         /* This happens when win_address_buf is NULL or too small to hold all
+          * adapters. */
+-        win_address_buf = uv__malloc(win_address_buf_size);
++        win_address_buf =
++            (IP_ADAPTER_ADDRESSES*)uv__malloc(win_address_buf_size);
+         if (win_address_buf == NULL)
+           return UV_ENOMEM;
+ 
+@@ -810,7 +811,7 @@ int uv_interface_addresses(uv_interface_address_t** addresses_ptr,
+ 
+       case ERROR_NO_DATA: {
+         /* No adapters were found. */
+-        uv_address_buf = uv__malloc(1);
++        uv_address_buf = (uv_interface_address_t*)uv__malloc(1);
+         if (uv_address_buf == NULL)
+           return UV_ENOMEM;
+ 
+@@ -887,7 +888,7 @@ int uv_interface_addresses(uv_interface_address_t** addresses_ptr,
+   }
+ 
+   /* Allocate space to store interface data plus adapter names. */
+-  uv_address_buf = uv__malloc(uv_address_buf_size);
++  uv_address_buf = (uv_interface_address_t*)uv__malloc(uv_address_buf_size);
+   if (uv_address_buf == NULL) {
+     uv__free(win_address_buf);
+     return UV_ENOMEM;
+@@ -1131,7 +1132,7 @@ int uv_os_tmpdir(char* buffer, size_t* size) {
+   }
+   /* Include space for terminating null char. */
+   len += 1;
+-  path = uv__malloc(len * sizeof(wchar_t));
++  path = (wchar_t*)uv__malloc(len * sizeof(wchar_t));
+   if (path == NULL) {
+     return UV_ENOMEM;
+   }
+@@ -1221,7 +1222,7 @@ int uv__convert_utf16_to_utf8(const WCHAR* utf16, int utf16len, char** utf8) {
+   /* Allocate the destination buffer adding an extra byte for the terminating
+    * NULL. If utf16len is not -1 WideCharToMultiByte will not add it, so
+    * we do it ourselves always, just in case. */
+-  *utf8 = uv__malloc(bufsize + 1);
++  *utf8 = (char*)uv__malloc(bufsize + 1);
+ 
+   if (*utf8 == NULL)
+     return UV_ENOMEM;
+@@ -1269,7 +1270,7 @@ int uv__convert_utf8_to_utf16(const char* utf8, int utf8len, WCHAR** utf16) {
+   /* Allocate the destination buffer adding an extra byte for the terminating
+    * NULL. If utf8len is not -1 MultiByteToWideChar will not add it, so
+    * we do it ourselves always, just in case. */
+-  *utf16 = uv__malloc(sizeof(WCHAR) * (bufsize + 1));
++  *utf16 = (WCHAR*)uv__malloc(sizeof(WCHAR) * (bufsize + 1));
+ 
+   if (*utf16 == NULL)
+     return UV_ENOMEM;
+@@ -1310,7 +1311,7 @@ int uv__getpwuid_r(uv_passwd_t* pwd) {
+     return uv_translate_sys_error(r);
+   }
+ 
+-  path = uv__malloc(bufsize * sizeof(wchar_t));
++  path = (wchar_t*)uv__malloc(bufsize * sizeof(wchar_t));
+   if (path == NULL) {
+     CloseHandle(token);
+     return UV_ENOMEM;
+@@ -1381,7 +1382,7 @@ int uv_os_environ(uv_env_item_t** envitems, int* count) {
+ 
+   for (penv = env, i = 0; *penv != L'\0'; penv += wcslen(penv) + 1, i++);
+ 
+-  *envitems = uv__calloc(i, sizeof(**envitems));
++  *envitems = (uv_env_item_t*)uv__calloc(i, sizeof(**envitems));
+   if (*envitems == NULL) {
+     FreeEnvironmentStringsW(env);
+     return UV_ENOMEM;
+@@ -1471,7 +1472,7 @@ int uv_os_getenv(const char* name, char* buffer, size_t* size) {
+       uv__free(var);
+ 
+     varlen = 1 + len;
+-    var = uv__malloc(varlen * sizeof(*var));
++    var = (wchar_t*)uv__malloc(varlen * sizeof(*var));
+ 
+     if (var == NULL) {
+       r = UV_ENOMEM;
diff --git a/third_party/allwpilib/upstream_utils/libuv_patches/0002-Fix-warnings.patch b/third_party/allwpilib/upstream_utils/libuv_patches/0002-Fix-warnings.patch
new file mode 100644
index 0000000..fedaea0
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/libuv_patches/0002-Fix-warnings.patch
@@ -0,0 +1,365 @@
+From f7b4492d37b35a64a3a6c5bbbdb375494095b6ff Mon Sep 17 00:00:00 2001
+From: PJ Reiniger <pj.reiniger@gmail.com>
+Date: Tue, 26 Apr 2022 15:09:43 -0400
+Subject: [PATCH 2/9] Fix warnings
+
+---
+ include/uv/win.h    |   5 +++
+ src/idna.c          |   2 +-
+ src/inet.c          |   4 ++
+ src/threadpool.c    |   4 ++
+ src/unix/core.c     |  12 ++++-
+ src/unix/darwin.c   | 106 +++++++++++++++++++++++---------------------
+ src/unix/internal.h |   4 +-
+ src/unix/thread.c   |   6 ---
+ src/uv-common.c     |   8 ++++
+ src/win/fs-event.c  |   2 +
+ src/win/fs.c        |   2 +
+ src/win/pipe.c      |   2 +
+ src/win/process.c   |   2 +
+ src/win/tty.c       |   2 +
+ 14 files changed, 99 insertions(+), 62 deletions(-)
+
+diff --git a/include/uv/win.h b/include/uv/win.h
+index 56a4cf11..10d5e8f1 100644
+--- a/include/uv/win.h
++++ b/include/uv/win.h
+@@ -201,11 +201,16 @@ typedef int (WSAAPI* LPFN_WSARECVFROM)
+              LPWSAOVERLAPPED overlapped,
+              LPWSAOVERLAPPED_COMPLETION_ROUTINE completion_routine);
+ 
++#pragma warning(push)
++#pragma warning(disable : 28251)
++
+ #ifndef _NTDEF_
+   typedef LONG NTSTATUS;
+   typedef NTSTATUS *PNTSTATUS;
+ #endif
+ 
++#pragma warning(pop)
++
+ #ifndef RTL_CONDITION_VARIABLE_INIT
+   typedef PVOID CONDITION_VARIABLE, *PCONDITION_VARIABLE;
+ #endif
+diff --git a/src/idna.c b/src/idna.c
+index 93d982ca..36a39a08 100644
+--- a/src/idna.c
++++ b/src/idna.c
+@@ -106,7 +106,7 @@ static int uv__idna_toascii_label(const char* s, const char* se,
+                                   char** d, char* de) {
+   static const char alphabet[] = "abcdefghijklmnopqrstuvwxyz0123456789";
+   const char* ss;
+-  unsigned c;
++  unsigned c = 0;
+   unsigned h;
+   unsigned k;
+   unsigned n;
+diff --git a/src/inet.c b/src/inet.c
+index ca8b6ac8..1b190255 100644
+--- a/src/inet.c
++++ b/src/inet.c
+@@ -27,6 +27,10 @@
+ #include "uv.h"
+ #include "uv-common.h"
+ 
++#ifdef _WIN32
++#pragma warning(disable : 6001)
++#endif
++
+ #define UV__INET_ADDRSTRLEN         16
+ #define UV__INET6_ADDRSTRLEN        46
+ 
+diff --git a/src/threadpool.c b/src/threadpool.c
+index 1241ace1..718972c3 100644
+--- a/src/threadpool.c
++++ b/src/threadpool.c
+@@ -27,6 +27,10 @@
+ 
+ #include <stdlib.h>
+ 
++#ifdef _WIN32
++#pragma warning(disable: 6001 6011)
++#endif
++
+ #define MAX_THREADPOOL_SIZE 1024
+ 
+ static uv_once_t once = UV_ONCE_INIT;
+diff --git a/src/unix/core.c b/src/unix/core.c
+index 6353b0e3..223c5513 100644
+--- a/src/unix/core.c
++++ b/src/unix/core.c
+@@ -544,6 +544,16 @@ int uv__accept(int sockfd) {
+   return peerfd;
+ }
+ 
++#if defined(__APPLE__)
++#pragma GCC diagnostic push
++#pragma GCC diagnostic ignored "-Wdollar-in-identifier-extension"
++#if defined(__LP64__)
++  extern "C" int close$NOCANCEL(int);
++#else
++  extern "C" int close$NOCANCEL$UNIX2003(int);
++#endif
++#pragma GCC diagnostic pop
++#endif
+ 
+ /* close() on macos has the "interesting" quirk that it fails with EINTR
+  * without closing the file descriptor when a thread is in the cancel state.
+@@ -558,10 +568,8 @@ int uv__close_nocancel(int fd) {
+ #pragma GCC diagnostic push
+ #pragma GCC diagnostic ignored "-Wdollar-in-identifier-extension"
+ #if defined(__LP64__) || TARGET_OS_IPHONE
+-  extern int close$NOCANCEL(int);
+   return close$NOCANCEL(fd);
+ #else
+-  extern int close$NOCANCEL$UNIX2003(int);
+   return close$NOCANCEL$UNIX2003(fd);
+ #endif
+ #pragma GCC diagnostic pop
+diff --git a/src/unix/darwin.c b/src/unix/darwin.c
+index 5fbf7342..eeb35720 100644
+--- a/src/unix/darwin.c
++++ b/src/unix/darwin.c
+@@ -253,64 +253,68 @@ static int uv__get_cpu_speed(uint64_t* speed) {
+ 
+ #define S(s) pCFStringCreateWithCString(NULL, (s), kCFStringEncodingUTF8)
+ 
+-  kr = pIOMasterPort(MACH_PORT_NULL, &mach_port);
+-  assert(kr == KERN_SUCCESS);
+-  CFMutableDictionaryRef classes_to_match
+-      = pIOServiceMatching("IOPlatformDevice");
+-  kr = pIOServiceGetMatchingServices(mach_port, classes_to_match, &it);
+-  assert(kr == KERN_SUCCESS);
+-  service = pIOIteratorNext(it);
+-
+-  CFStringRef device_type_str = S("device_type");
+-  CFStringRef clock_frequency_str = S("clock-frequency");
+-
+-  while (service != 0) {
+-    CFDataRef data;
+-    data = pIORegistryEntryCreateCFProperty(service,
+-                                            device_type_str,
+-                                            NULL,
+-                                            0);
+-    if (data) {
+-      const UInt8* raw = pCFDataGetBytePtr(data);
+-      if (strncmp((char*)raw, "cpu", 3) == 0 ||
+-          strncmp((char*)raw, "processor", 9) == 0) {
+-        CFDataRef freq_ref;
+-        freq_ref = pIORegistryEntryCreateCFProperty(service,
+-                                                    clock_frequency_str,
+-                                                    NULL,
+-                                                    0);
+-        if (freq_ref) {
+-          const UInt8* freq_ref_ptr = pCFDataGetBytePtr(freq_ref);
+-          CFIndex len = pCFDataGetLength(freq_ref);
+-          if (len == 8)
+-            memcpy(speed, freq_ref_ptr, 8);
+-          else if (len == 4) {
+-            uint32_t v;
+-            memcpy(&v, freq_ref_ptr, 4);
+-            *speed = v;
+-          } else {
+-            *speed = 0;
+-          }
++  // Braces ensure goto doesn't jump into device_type_str's and
++  // clock_frequency_str's lifetimes after their initialization
++  {
++    kr = pIOMasterPort(MACH_PORT_NULL, &mach_port);
++    assert(kr == KERN_SUCCESS);
++    CFMutableDictionaryRef classes_to_match
++        = pIOServiceMatching("IOPlatformDevice");
++    kr = pIOServiceGetMatchingServices(mach_port, classes_to_match, &it);
++    assert(kr == KERN_SUCCESS);
++    service = pIOIteratorNext(it);
+ 
+-          pCFRelease(freq_ref);
+-          pCFRelease(data);
+-          break;
++    CFStringRef device_type_str = S("device_type");
++    CFStringRef clock_frequency_str = S("clock-frequency");
++
++    while (service != 0) {
++      CFDataRef data;
++      data = pIORegistryEntryCreateCFProperty(service,
++                                              device_type_str,
++                                              NULL,
++                                              0);
++      if (data) {
++        const UInt8* raw = pCFDataGetBytePtr(data);
++        if (strncmp((char*)raw, "cpu", 3) == 0 ||
++            strncmp((char*)raw, "processor", 9) == 0) {
++          CFDataRef freq_ref;
++          freq_ref = pIORegistryEntryCreateCFProperty(service,
++                                                      clock_frequency_str,
++                                                      NULL,
++                                                      0);
++          if (freq_ref) {
++            const UInt8* freq_ref_ptr = pCFDataGetBytePtr(freq_ref);
++            CFIndex len = pCFDataGetLength(freq_ref);
++            if (len == 8)
++              memcpy(speed, freq_ref_ptr, 8);
++            else if (len == 4) {
++              uint32_t v;
++              memcpy(&v, freq_ref_ptr, 4);
++              *speed = v;
++            } else {
++              *speed = 0;
++            }
++
++            pCFRelease(freq_ref);
++            pCFRelease(data);
++            break;
++          }
+         }
++        pCFRelease(data);
+       }
+-      pCFRelease(data);
+-    }
+ 
+-    service = pIOIteratorNext(it);
+-  }
++      service = pIOIteratorNext(it);
++    }
+ 
+-  pIOObjectRelease(it);
++    pIOObjectRelease(it);
+ 
+-  err = 0;
++    err = 0;
+ 
+-  if (device_type_str != NULL)
+-    pCFRelease(device_type_str);
+-  if (clock_frequency_str != NULL)
+-    pCFRelease(clock_frequency_str);
++    if (device_type_str != NULL)
++      pCFRelease(device_type_str);
++    if (clock_frequency_str != NULL)
++      pCFRelease(clock_frequency_str);
++  }
+ 
+ out:
+   if (core_foundation_handle != NULL)
+diff --git a/src/unix/internal.h b/src/unix/internal.h
+index cee35c21..f9d1666d 100644
+--- a/src/unix/internal.h
++++ b/src/unix/internal.h
+@@ -312,8 +312,8 @@ UV_UNUSED(static void uv__update_time(uv_loop_t* loop)) {
+   loop->time = uv__hrtime(UV_CLOCK_FAST) / 1000000;
+ }
+ 
+-UV_UNUSED(static char* uv__basename_r(const char* path)) {
+-  char* s;
++UV_UNUSED(static const char* uv__basename_r(const char* path)) {
++  const char* s;
+ 
+   s = strrchr(path, '/');
+   if (s == NULL)
+diff --git a/src/unix/thread.c b/src/unix/thread.c
+index 759cd0c2..64726bd6 100644
+--- a/src/unix/thread.c
++++ b/src/unix/thread.c
+@@ -244,12 +244,6 @@ int uv_thread_create_ex(uv_thread_t* tid,
+   size_t stack_size;
+   size_t min_stack_size;
+ 
+-  /* Used to squelch a -Wcast-function-type warning. */
+-  union {
+-    void (*in)(void*);
+-    void* (*out)(void*);
+-  } f;
+-
+   stack_size =
+       params->flags & UV_THREAD_HAS_STACK_SIZE ? params->stack_size : 0;
+ 
+diff --git a/src/uv-common.c b/src/uv-common.c
+index dfb606e3..49026c03 100644
+--- a/src/uv-common.c
++++ b/src/uv-common.c
+@@ -758,6 +758,10 @@ void uv__fs_readdir_cleanup(uv_fs_t* req) {
+   }
+ }
+ 
++#ifdef __clang__
++# pragma clang diagnostic push
++# pragma clang diagnostic ignored "-Wvarargs"
++#endif
+ 
+ int uv_loop_configure(uv_loop_t* loop, uv_loop_option option, ...) {
+   va_list ap;
+@@ -771,6 +775,10 @@ int uv_loop_configure(uv_loop_t* loop, uv_loop_option option, ...) {
+   return err;
+ }
+ 
++#ifdef __clang__
++# pragma clang diagnostic pop
++#endif
++
+ 
+ static uv_loop_t default_loop_struct;
+ static uv_loop_t* default_loop_ptr;
+diff --git a/src/win/fs-event.c b/src/win/fs-event.c
+index 15046731..3244a4e4 100644
+--- a/src/win/fs-event.c
++++ b/src/win/fs-event.c
+@@ -19,6 +19,8 @@
+  * IN THE SOFTWARE.
+  */
+ 
++#define _CRT_NONSTDC_NO_WARNINGS
++
+ #include <assert.h>
+ #include <errno.h>
+ #include <stdio.h>
+diff --git a/src/win/fs.c b/src/win/fs.c
+index 8374012f..f71b3c04 100644
+--- a/src/win/fs.c
++++ b/src/win/fs.c
+@@ -19,6 +19,8 @@
+  * IN THE SOFTWARE.
+  */
+ 
++#define _CRT_NONSTDC_NO_WARNINGS
++
+ #include <assert.h>
+ #include <stdlib.h>
+ #include <direct.h>
+diff --git a/src/win/pipe.c b/src/win/pipe.c
+index cd77061a..f413a72d 100644
+--- a/src/win/pipe.c
++++ b/src/win/pipe.c
+@@ -19,6 +19,8 @@
+  * IN THE SOFTWARE.
+  */
+ 
++#define _CRT_NONSTDC_NO_WARNINGS
++
+ #include <assert.h>
+ #include <io.h>
+ #include <stdio.h>
+diff --git a/src/win/process.c b/src/win/process.c
+index e857db3e..a49016f6 100644
+--- a/src/win/process.c
++++ b/src/win/process.c
+@@ -19,6 +19,8 @@
+  * IN THE SOFTWARE.
+  */
+ 
++#define _CRT_NONSTDC_NO_WARNINGS
++
+ #include <assert.h>
+ #include <io.h>
+ #include <stdio.h>
+diff --git a/src/win/tty.c b/src/win/tty.c
+index 267ca645..d7522668 100644
+--- a/src/win/tty.c
++++ b/src/win/tty.c
+@@ -19,6 +19,8 @@
+  * IN THE SOFTWARE.
+  */
+ 
++#define _CRT_NONSTDC_NO_WARNINGS
++
+ #include <assert.h>
+ #include <io.h>
+ #include <string.h>
diff --git a/third_party/allwpilib/upstream_utils/libuv_patches/0003-Preprocessor-cleanup.patch b/third_party/allwpilib/upstream_utils/libuv_patches/0003-Preprocessor-cleanup.patch
new file mode 100644
index 0000000..f55f5cc
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/libuv_patches/0003-Preprocessor-cleanup.patch
@@ -0,0 +1,179 @@
+From dec4f95751a103f132e9674adf184188ec69176f Mon Sep 17 00:00:00 2001
+From: PJ Reiniger <pj.reiniger@gmail.com>
+Date: Tue, 26 Apr 2022 15:19:14 -0400
+Subject: [PATCH 3/9] Preprocessor cleanup
+
+---
+ include/uv.h        | 18 +-----------------
+ include/uv/unix.h   |  8 --------
+ include/uv/win.h    |  6 +-----
+ src/unix/internal.h |  2 ++
+ src/win/fs.c        |  1 +
+ src/win/tty.c       |  2 ++
+ src/win/util.c      |  8 ++++++++
+ src/win/winsock.c   |  1 +
+ 8 files changed, 16 insertions(+), 30 deletions(-)
+
+diff --git a/include/uv.h b/include/uv.h
+index ee1c94cc..dbaeb1e9 100644
+--- a/include/uv.h
++++ b/include/uv.h
+@@ -23,9 +23,6 @@
+ 
+ #ifndef UV_H
+ #define UV_H
+-#ifdef __cplusplus
+-extern "C" {
+-#endif
+ 
+ #if defined(BUILDING_UV_SHARED) && defined(USING_UV_SHARED)
+ #error "Define either BUILDING_UV_SHARED or USING_UV_SHARED, not both."
+@@ -56,11 +53,7 @@ extern "C" {
+ #include <stddef.h>
+ #include <stdio.h>
+ 
+-#if defined(_MSC_VER) && _MSC_VER < 1600
+-# include "uv/stdint-msvc2008.h"
+-#else
+-# include <stdint.h>
+-#endif
++#include <stdint.h>
+ 
+ #if defined(_WIN32)
+ # include "uv/win.h"
+@@ -767,16 +760,10 @@ UV_EXTERN int uv_tty_get_winsize(uv_tty_t*, int* width, int* height);
+ UV_EXTERN void uv_tty_set_vterm_state(uv_tty_vtermstate_t state);
+ UV_EXTERN int uv_tty_get_vterm_state(uv_tty_vtermstate_t* state);
+ 
+-#ifdef __cplusplus
+-extern "C++" {
+-
+ inline int uv_tty_set_mode(uv_tty_t* handle, int mode) {
+   return uv_tty_set_mode(handle, static_cast<uv_tty_mode_t>(mode));
+ }
+ 
+-}
+-#endif
+-
+ UV_EXTERN uv_handle_type uv_guess_handle(uv_file file);
+ 
+ /*
+@@ -1844,7 +1831,4 @@ UV_EXTERN void uv_loop_set_data(uv_loop_t*, void* data);
+ #undef UV_LOOP_PRIVATE_PLATFORM_FIELDS
+ #undef UV__ERR
+ 
+-#ifdef __cplusplus
+-}
+-#endif
+ #endif /* UV_H */
+diff --git a/include/uv/unix.h b/include/uv/unix.h
+index 420be86c..256fef37 100644
+--- a/include/uv/unix.h
++++ b/include/uv/unix.h
+@@ -47,14 +47,6 @@
+ 
+ #if defined(__linux__)
+ # include "uv/linux.h"
+-#elif defined (__MVS__)
+-# include "uv/os390.h"
+-#elif defined(__PASE__)  /* __PASE__ and _AIX are both defined on IBM i */
+-# include "uv/posix.h"  /* IBM i needs uv/posix.h, not uv/aix.h */
+-#elif defined(_AIX)
+-# include "uv/aix.h"
+-#elif defined(__sun)
+-# include "uv/sunos.h"
+ #elif defined(__APPLE__)
+ # include "uv/darwin.h"
+ #elif defined(__DragonFly__)       || \
+diff --git a/include/uv/win.h b/include/uv/win.h
+index 10d5e8f1..0a33366f 100644
+--- a/include/uv/win.h
++++ b/include/uv/win.h
+@@ -60,11 +60,7 @@ typedef struct pollfd {
+ #include <fcntl.h>
+ #include <sys/stat.h>
+ 
+-#if defined(_MSC_VER) && _MSC_VER < 1600
+-# include "uv/stdint-msvc2008.h"
+-#else
+-# include <stdint.h>
+-#endif
++#include <stdint.h>
+ 
+ #include "uv/tree.h"
+ #include "uv/threadpool.h"
+diff --git a/src/unix/internal.h b/src/unix/internal.h
+index f9d1666d..2b654157 100644
+--- a/src/unix/internal.h
++++ b/src/unix/internal.h
+@@ -192,6 +192,8 @@ struct uv__stream_queued_fds_s {
+ #if defined(__linux__) && O_NDELAY != O_NONBLOCK
+ #undef uv__nonblock
+ #define uv__nonblock uv__nonblock_fcntl
++#undef UV__NONBLOCK_IS_IOCTL
++#define UV__NONBLOCK_IS_FCNTL
+ #endif
+ 
+ /* core */
+diff --git a/src/win/fs.c b/src/win/fs.c
+index f71b3c04..71c9b169 100644
+--- a/src/win/fs.c
++++ b/src/win/fs.c
+@@ -38,6 +38,7 @@
+ #include "handle-inl.h"
+ #include "fs-fd-hash-inl.h"
+ 
++#pragma comment(lib, "Advapi32.lib")
+ 
+ #define UV_FS_FREE_PATHS         0x0002
+ #define UV_FS_FREE_PTR           0x0008
+diff --git a/src/win/tty.c b/src/win/tty.c
+index d7522668..9753784d 100644
+--- a/src/win/tty.c
++++ b/src/win/tty.c
+@@ -42,6 +42,8 @@
+ #include "stream-inl.h"
+ #include "req-inl.h"
+ 
++#pragma comment(lib, "User32.lib")
++
+ #ifndef InterlockedOr
+ # define InterlockedOr _InterlockedOr
+ #endif
+diff --git a/src/win/util.c b/src/win/util.c
+index c655f532..7a5dd2ef 100644
+--- a/src/win/util.c
++++ b/src/win/util.c
+@@ -63,12 +63,20 @@
+ 
+ 
+ /* A RtlGenRandom() by any other name... */
++extern "C" {
+ extern BOOLEAN NTAPI SystemFunction036(PVOID Buffer, ULONG BufferLength);
++}
+ 
+ /* Cached copy of the process title, plus a mutex guarding it. */
+ static char *process_title;
+ static CRITICAL_SECTION process_title_lock;
+ 
++#pragma comment(lib, "Advapi32.lib")
++#pragma comment(lib, "IPHLPAPI.lib")
++#pragma comment(lib, "Psapi.lib")
++#pragma comment(lib, "Userenv.lib")
++#pragma comment(lib, "kernel32.lib")
++
+ /* Frequency of the high-resolution clock. */
+ static uint64_t hrtime_frequency_ = 0;
+ 
+diff --git a/src/win/winsock.c b/src/win/winsock.c
+index a68b0953..7843e9f1 100644
+--- a/src/win/winsock.c
++++ b/src/win/winsock.c
+@@ -25,6 +25,7 @@
+ #include "uv.h"
+ #include "internal.h"
+ 
++#pragma comment(lib, "Ws2_32.lib")
+ 
+ /* Whether there are any non-IFS LSPs stacked on TCP */
+ int uv_tcp_non_ifs_lsp_ipv4;
diff --git a/third_party/allwpilib/upstream_utils/libuv_patches/0004-Cleanup-problematic-language.patch b/third_party/allwpilib/upstream_utils/libuv_patches/0004-Cleanup-problematic-language.patch
new file mode 100644
index 0000000..a29043b
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/libuv_patches/0004-Cleanup-problematic-language.patch
@@ -0,0 +1,61 @@
+From 2d06f216dec3abbeaaabb465b945e09856d1b687 Mon Sep 17 00:00:00 2001
+From: PJ Reiniger <pj.reiniger@gmail.com>
+Date: Tue, 26 Apr 2022 15:24:47 -0400
+Subject: [PATCH 4/9] Cleanup problematic language
+
+---
+ src/unix/tty.c | 21 +++++++++++----------
+ 1 file changed, 11 insertions(+), 10 deletions(-)
+
+diff --git a/src/unix/tty.c b/src/unix/tty.c
+index b4150525..ed81e26a 100644
+--- a/src/unix/tty.c
++++ b/src/unix/tty.c
+@@ -79,7 +79,7 @@ int uv__tcsetattr(int fd, int how, const struct termios *term) {
+   return 0;
+ }
+ 
+-static int uv__tty_is_slave(const int fd) {
++static int uv__tty_is_peripheral(const int fd) {
+   int result;
+ #if defined(__linux__) || defined(__FreeBSD__) || defined(__FreeBSD_kernel__)
+   int dummy;
+@@ -91,15 +91,16 @@ static int uv__tty_is_slave(const int fd) {
+   result = ioctl(fd, TIOCPTYGNAME, &dummy) != 0;
+ #elif defined(__NetBSD__)
+   /*
+-   * NetBSD as an extension returns with ptsname(3) and ptsname_r(3) the slave
+-   * device name for both descriptors, the master one and slave one.
++   * NetBSD as an extension returns with ptsname(3) and ptsname_r(3) the
++   * peripheral device name for both descriptors, the controller one and
++   * peripheral one.
+    *
+    * Implement function to compare major device number with pts devices.
+    *
+    * The major numbers are machine-dependent, on NetBSD/amd64 they are
+    * respectively:
+-   *  - master tty: ptc - major 6
+-   *  - slave tty:  pts - major 5
++   *  - controller tty: ptc - major 6
++   *  - peripheral tty:  pts - major 5
+    */
+ 
+   struct stat sb;
+@@ -174,12 +175,12 @@ int uv_tty_init(uv_loop_t* loop, uv_tty_t* tty, int fd, int unused) {
+    * other processes.
+    */
+   if (type == UV_TTY) {
+-    /* Reopening a pty in master mode won't work either because the reopened
+-     * pty will be in slave mode (*BSD) or reopening will allocate a new
+-     * master/slave pair (Linux). Therefore check if the fd points to a
+-     * slave device.
++    /* Reopening a pty in controller mode won't work either because the reopened
++     * pty will be in peripheral mode (*BSD) or reopening will allocate a new
++     * controller/peripheral pair (Linux). Therefore check if the fd points to a
++     * peripheral device.
+      */
+-    if (uv__tty_is_slave(fd) && ttyname_r(fd, path, sizeof(path)) == 0)
++    if (uv__tty_is_peripheral(fd) && ttyname_r(fd, path, sizeof(path)) == 0)
+       r = uv__open_cloexec(path, mode | O_NOCTTY);
+     else
+       r = -1;
diff --git a/third_party/allwpilib/upstream_utils/libuv_patches/0005-Use-roborio-time.patch b/third_party/allwpilib/upstream_utils/libuv_patches/0005-Use-roborio-time.patch
new file mode 100644
index 0000000..46cc46f
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/libuv_patches/0005-Use-roborio-time.patch
@@ -0,0 +1,42 @@
+From 690d487df2e60a01ab811aba34587466a38caead Mon Sep 17 00:00:00 2001
+From: PJ Reiniger <pj.reiniger@gmail.com>
+Date: Tue, 26 Apr 2022 15:26:03 -0400
+Subject: [PATCH 5/9] Use roborio time
+
+---
+ src/unix/linux-core.c | 8 ++++++++
+ 1 file changed, 8 insertions(+)
+
+diff --git a/src/unix/linux-core.c b/src/unix/linux-core.c
+index 85f3fc01..12ed7ff1 100644
+--- a/src/unix/linux-core.c
++++ b/src/unix/linux-core.c
+@@ -67,6 +67,10 @@
+ # define CLOCK_MONOTONIC_COARSE 6
+ #endif
+ 
++#ifdef __FRC_ROBORIO__
++#include "wpi/timestamp.h"
++#endif
++
+ /* This is rather annoying: CLOCK_BOOTTIME lives in <linux/time.h> but we can't
+  * include that file because it conflicts with <time.h>. We'll just have to
+  * define it ourselves.
+@@ -118,6 +122,9 @@ void uv__platform_loop_delete(uv_loop_t* loop) {
+ 
+ 
+ uint64_t uv__hrtime(uv_clocktype_t type) {
++#ifdef __FRC_ROBORIO__
++  return wpi::Now() * 1000u;
++#else
+   static clock_t fast_clock_id = -1;
+   struct timespec t;
+   clock_t clock_id;
+@@ -151,6 +158,7 @@ done:
+     return 0;  /* Not really possible. */
+ 
+   return t.tv_sec * (uint64_t) 1e9 + t.tv_nsec;
++#endif
+ }
+ 
+ 
diff --git a/third_party/allwpilib/upstream_utils/libuv_patches/0006-Style-comments-cleanup.patch b/third_party/allwpilib/upstream_utils/libuv_patches/0006-Style-comments-cleanup.patch
new file mode 100644
index 0000000..964d944
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/libuv_patches/0006-Style-comments-cleanup.patch
@@ -0,0 +1,102 @@
+From ad60aa8e1c03cc5f0c88159d37f63b0c063927c7 Mon Sep 17 00:00:00 2001
+From: PJ Reiniger <pj.reiniger@gmail.com>
+Date: Tue, 26 Apr 2022 15:28:52 -0400
+Subject: [PATCH 6/9] Style / comments cleanup
+
+---
+ src/fs-poll.c     | 1 +
+ src/unix/core.c   | 1 +
+ src/unix/thread.c | 3 +--
+ src/uv-common.c   | 1 +
+ src/win/process.c | 1 -
+ src/win/winsock.c | 1 +
+ 6 files changed, 5 insertions(+), 3 deletions(-)
+
+diff --git a/src/fs-poll.c b/src/fs-poll.c
+index 5a39daed..1a7ca70d 100644
+--- a/src/fs-poll.c
++++ b/src/fs-poll.c
+@@ -34,6 +34,7 @@
+ #include <stdlib.h>
+ #include <string.h>
+ 
++
+ struct poll_ctx {
+   uv_fs_poll_t* parent_handle;
+   int busy_polling;
+diff --git a/src/unix/core.c b/src/unix/core.c
+index 223c5513..4c23f608 100644
+--- a/src/unix/core.c
++++ b/src/unix/core.c
+@@ -544,6 +544,7 @@ int uv__accept(int sockfd) {
+   return peerfd;
+ }
+ 
++
+ #if defined(__APPLE__)
+ #pragma GCC diagnostic push
+ #pragma GCC diagnostic ignored "-Wdollar-in-identifier-extension"
+diff --git a/src/unix/thread.c b/src/unix/thread.c
+index 64726bd6..392a0715 100644
+--- a/src/unix/thread.c
++++ b/src/unix/thread.c
+@@ -85,7 +85,6 @@ error2:
+   return rc;
+ }
+ 
+-
+ int uv_barrier_wait(uv_barrier_t* barrier) {
+   struct _uv_barrier* b;
+   int last;
+@@ -94,6 +93,7 @@ int uv_barrier_wait(uv_barrier_t* barrier) {
+     return UV_EINVAL;
+ 
+   b = barrier->b;
++  /* Lock the mutex*/
+   uv_mutex_lock(&b->mutex);
+ 
+   if (++b->in == b->threshold) {
+@@ -113,7 +113,6 @@ int uv_barrier_wait(uv_barrier_t* barrier) {
+   return last;
+ }
+ 
+-
+ void uv_barrier_destroy(uv_barrier_t* barrier) {
+   struct _uv_barrier* b;
+ 
+diff --git a/src/uv-common.c b/src/uv-common.c
+index 49026c03..c9a32c03 100644
+--- a/src/uv-common.c
++++ b/src/uv-common.c
+@@ -758,6 +758,7 @@ void uv__fs_readdir_cleanup(uv_fs_t* req) {
+   }
+ }
+ 
++
+ #ifdef __clang__
+ # pragma clang diagnostic push
+ # pragma clang diagnostic ignored "-Wvarargs"
+diff --git a/src/win/process.c b/src/win/process.c
+index a49016f6..8e7835a5 100644
+--- a/src/win/process.c
++++ b/src/win/process.c
+@@ -35,7 +35,6 @@
+ #include "handle-inl.h"
+ #include "req-inl.h"
+ 
+-
+ #define SIGKILL         9
+ 
+ 
+diff --git a/src/win/winsock.c b/src/win/winsock.c
+index 7843e9f1..cda82bc3 100644
+--- a/src/win/winsock.c
++++ b/src/win/winsock.c
+@@ -25,6 +25,7 @@
+ #include "uv.h"
+ #include "internal.h"
+ 
++
+ #pragma comment(lib, "Ws2_32.lib")
+ 
+ /* Whether there are any non-IFS LSPs stacked on TCP */
diff --git a/third_party/allwpilib/upstream_utils/libuv_patches/0007-Squelch-GCC-12.1-warnings.patch b/third_party/allwpilib/upstream_utils/libuv_patches/0007-Squelch-GCC-12.1-warnings.patch
new file mode 100644
index 0000000..92032da
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/libuv_patches/0007-Squelch-GCC-12.1-warnings.patch
@@ -0,0 +1,52 @@
+From ee8a72764f602928cc08d16d661602c0aefde050 Mon Sep 17 00:00:00 2001
+From: Tyler Veness <calcmogul@gmail.com>
+Date: Tue, 17 May 2022 21:36:57 -0700
+Subject: [PATCH 7/9] Squelch GCC 12.1 warnings
+
+---
+ src/unix/stream.c | 9 +++++++++
+ src/uv-common.c   | 9 +++++++++
+ 2 files changed, 18 insertions(+)
+
+diff --git a/src/unix/stream.c b/src/unix/stream.c
+index c6cc50e7..fa25812a 100644
+--- a/src/unix/stream.c
++++ b/src/unix/stream.c
+@@ -938,7 +938,16 @@ static void uv__write_callbacks(uv_stream_t* stream) {
+   if (QUEUE_EMPTY(&stream->write_completed_queue))
+     return;
+ 
++// FIXME: GCC 12.1 gives a possibly real warning, but we don't know how to fix
++// it
++#if __GNUC__ >= 12
++#pragma GCC diagnostic push
++#pragma GCC diagnostic ignored "-Wdangling-pointer="
++#endif  // __GNUC__ >= 12
+   QUEUE_MOVE(&stream->write_completed_queue, &pq);
++#if __GNUC__ >= 12
++#pragma GCC diagnostic pop
++#endif  // __GNUC__ >= 12
+ 
+   while (!QUEUE_EMPTY(&pq)) {
+     /* Pop a req off write_completed_queue. */
+diff --git a/src/uv-common.c b/src/uv-common.c
+index c9a32c03..8ab600df 100644
+--- a/src/uv-common.c
++++ b/src/uv-common.c
+@@ -504,7 +504,16 @@ void uv_walk(uv_loop_t* loop, uv_walk_cb walk_cb, void* arg) {
+   QUEUE* q;
+   uv_handle_t* h;
+ 
++// FIXME: GCC 12.1 gives a possibly real warning, but we don't know how to fix
++// it
++#if __GNUC__ >= 12
++#pragma GCC diagnostic push
++#pragma GCC diagnostic ignored "-Wdangling-pointer="
++#endif  // __GNUC__ >= 12
+   QUEUE_MOVE(&loop->handle_queue, &queue);
++#if __GNUC__ >= 12
++#pragma GCC diagnostic pop
++#endif  // __GNUC__ >= 12
+   while (!QUEUE_EMPTY(&queue)) {
+     q = QUEUE_HEAD(&queue);
+     h = QUEUE_DATA(q, uv_handle_t, handle_queue);
diff --git a/third_party/allwpilib/upstream_utils/libuv_patches/0008-Fix-Win32-warning-suppression-pragma.patch b/third_party/allwpilib/upstream_utils/libuv_patches/0008-Fix-Win32-warning-suppression-pragma.patch
new file mode 100644
index 0000000..bdc5f61
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/libuv_patches/0008-Fix-Win32-warning-suppression-pragma.patch
@@ -0,0 +1,22 @@
+From 49d5945dde1d182fd2d75cdf550120951796cb1f Mon Sep 17 00:00:00 2001
+From: Tyler Veness <calcmogul@gmail.com>
+Date: Sat, 21 May 2022 22:58:06 -0700
+Subject: [PATCH 8/9] Fix Win32 warning suppression pragma
+
+---
+ src/win/util.c | 2 +-
+ 1 file changed, 1 insertion(+), 1 deletion(-)
+
+diff --git a/src/win/util.c b/src/win/util.c
+index 7a5dd2ef..d9888aec 100644
+--- a/src/win/util.c
++++ b/src/win/util.c
+@@ -1750,7 +1750,7 @@ int uv_os_uname(uv_utsname_t* buffer) {
+   } else {
+     /* Silence GetVersionEx() deprecation warning. */
+     #ifdef _MSC_VER
+-    #pragma warning(suppress : 4996)
++    #pragma warning(disable : 4996)
+     #endif
+     if (GetVersionExW(&os_info) == 0) {
+       r = uv_translate_sys_error(GetLastError());
diff --git a/third_party/allwpilib/upstream_utils/libuv_patches/0009-Avoid-unused-variable-warning-on-Mac.patch b/third_party/allwpilib/upstream_utils/libuv_patches/0009-Avoid-unused-variable-warning-on-Mac.patch
new file mode 100644
index 0000000..8db2deb
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/libuv_patches/0009-Avoid-unused-variable-warning-on-Mac.patch
@@ -0,0 +1,21 @@
+From d83eaeff1f53bc3dede8a46a05cdb3ca94d1aac4 Mon Sep 17 00:00:00 2001
+From: Peter Johnson <johnson.peter@gmail.com>
+Date: Sun, 5 Jun 2022 15:40:35 -0700
+Subject: [PATCH 9/9] Avoid unused variable warning on Mac
+
+---
+ src/unix/darwin.c | 1 +
+ 1 file changed, 1 insertion(+)
+
+diff --git a/src/unix/darwin.c b/src/unix/darwin.c
+index eeb35720..ed51a6ad 100644
+--- a/src/unix/darwin.c
++++ b/src/unix/darwin.c
+@@ -257,6 +257,7 @@ static int uv__get_cpu_speed(uint64_t* speed) {
+   // clock_frequency_str's lifetimes after their initialization
+   {
+     kr = pIOMasterPort(MACH_PORT_NULL, &mach_port);
++    (void) kr;
+     assert(kr == KERN_SUCCESS);
+     CFMutableDictionaryRef classes_to_match
+         = pIOServiceMatching("IOPlatformDevice");
diff --git a/third_party/allwpilib/upstream_utils/llvm_patches/0001-Fix-spelling-language-errors.patch b/third_party/allwpilib/upstream_utils/llvm_patches/0001-Fix-spelling-language-errors.patch
new file mode 100644
index 0000000..5d6916d
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/llvm_patches/0001-Fix-spelling-language-errors.patch
@@ -0,0 +1,22 @@
+From 3d09b3d7b78ffc037a32725cc4002976b908d965 Mon Sep 17 00:00:00 2001
+From: PJ Reiniger <pj.reiniger@gmail.com>
+Date: Sat, 7 May 2022 20:50:26 -0400
+Subject: [PATCH 01/28] Fix spelling/language errors
+
+---
+ llvm/include/llvm/Support/ErrorHandling.h | 2 +-
+ 1 file changed, 1 insertion(+), 1 deletion(-)
+
+diff --git a/llvm/include/llvm/Support/ErrorHandling.h b/llvm/include/llvm/Support/ErrorHandling.h
+index f980510d3..6791df6be 100644
+--- a/llvm/include/llvm/Support/ErrorHandling.h
++++ b/llvm/include/llvm/Support/ErrorHandling.h
+@@ -44,7 +44,7 @@ namespace llvm {
+   void install_fatal_error_handler(fatal_error_handler_t handler,
+                                    void *user_data = nullptr);
+ 
+-  /// Restores default error handling behaviour.
++  /// Restores default error handling behavior.
+   void remove_fatal_error_handler();
+ 
+   /// ScopedFatalErrorHandler - This is a simple helper class which just
diff --git a/third_party/allwpilib/upstream_utils/llvm_patches/0002-Remove-StringRef-ArrayRef-and-Optional.patch b/third_party/allwpilib/upstream_utils/llvm_patches/0002-Remove-StringRef-ArrayRef-and-Optional.patch
new file mode 100644
index 0000000..eb5b759
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/llvm_patches/0002-Remove-StringRef-ArrayRef-and-Optional.patch
@@ -0,0 +1,1894 @@
+From afca62cd2f1616bcf2e648dc121a057d59168424 Mon Sep 17 00:00:00 2001
+From: PJ Reiniger <pj.reiniger@gmail.com>
+Date: Sat, 7 May 2022 22:09:18 -0400
+Subject: [PATCH 02/28] Remove StringRef, ArrayRef, and Optional
+
+---
+ llvm/include/llvm/ADT/PointerUnion.h          |  1 -
+ llvm/include/llvm/ADT/SmallSet.h              | 13 ++--
+ llvm/include/llvm/ADT/SmallString.h           | 77 ++++++++++---------
+ llvm/include/llvm/ADT/StringMap.h             | 34 ++++----
+ llvm/include/llvm/ADT/StringMapEntry.h        | 25 +++---
+ llvm/include/llvm/Support/Chrono.h            | 10 +--
+ llvm/include/llvm/Support/Compiler.h          |  2 +-
+ llvm/include/llvm/Support/ConvertUTF.h        | 28 ++++---
+ llvm/include/llvm/Support/DJB.h               |  6 +-
+ llvm/include/llvm/Support/ErrorHandling.h     |  9 +--
+ .../llvm/Support/SmallVectorMemoryBuffer.h    |  6 +-
+ llvm/include/llvm/Support/VersionTuple.h      | 20 ++---
+ .../llvm/Support/Windows/WindowsSupport.h     |  4 +-
+ llvm/include/llvm/Support/raw_ostream.h       | 51 ++++++------
+ llvm/lib/Support/ConvertUTFWrapper.cpp        | 32 ++++----
+ llvm/lib/Support/ErrorHandling.cpp            | 13 ++--
+ llvm/lib/Support/SmallVector.cpp              |  5 +-
+ llvm/lib/Support/StringMap.cpp                | 12 +--
+ llvm/lib/Support/raw_ostream.cpp              | 25 +++---
+ llvm/unittests/ADT/DenseMapTest.cpp           | 25 ------
+ llvm/unittests/ADT/FunctionExtrasTest.cpp     | 12 +--
+ llvm/unittests/ADT/HashingTest.cpp            |  2 +-
+ llvm/unittests/ADT/SmallPtrSetTest.cpp        |  1 -
+ llvm/unittests/ADT/SmallStringTest.cpp        | 50 ++++++------
+ llvm/unittests/ADT/SmallVectorTest.cpp        | 20 +----
+ llvm/unittests/ADT/StringMapTest.cpp          | 32 ++++----
+ llvm/unittests/Support/ConvertUTFTest.cpp     | 37 +++++----
+ 27 files changed, 248 insertions(+), 304 deletions(-)
+
+diff --git a/llvm/include/llvm/ADT/PointerUnion.h b/llvm/include/llvm/ADT/PointerUnion.h
+index 04d566bbc..1d4cc747c 100644
+--- a/llvm/include/llvm/ADT/PointerUnion.h
++++ b/llvm/include/llvm/ADT/PointerUnion.h
+@@ -17,7 +17,6 @@
+ 
+ #include "llvm/ADT/DenseMapInfo.h"
+ #include "llvm/ADT/PointerIntPair.h"
+-#include "llvm/ADT/STLExtras.h"
+ #include "llvm/Support/PointerLikeTypeTraits.h"
+ #include <algorithm>
+ #include <cassert>
+diff --git a/llvm/include/llvm/ADT/SmallSet.h b/llvm/include/llvm/ADT/SmallSet.h
+index 0eed85449..bfe93e997 100644
+--- a/llvm/include/llvm/ADT/SmallSet.h
++++ b/llvm/include/llvm/ADT/SmallSet.h
+@@ -14,15 +14,14 @@
+ #ifndef LLVM_ADT_SMALLSET_H
+ #define LLVM_ADT_SMALLSET_H
+ 
+-#include "llvm/ADT/None.h"
+ #include "llvm/ADT/SmallPtrSet.h"
+ #include "llvm/ADT/SmallVector.h"
+-#include "llvm/ADT/STLExtras.h"
+ #include "llvm/ADT/iterator.h"
+ #include "llvm/Support/Compiler.h"
+ #include "llvm/Support/type_traits.h"
+ #include <cstddef>
+ #include <functional>
++#include <optional>
+ #include <set>
+ #include <type_traits>
+ #include <utility>
+@@ -179,16 +178,16 @@ public:
+   /// concept.
+   // FIXME: Add iterators that abstract over the small and large form, and then
+   // return those here.
+-  std::pair<NoneType, bool> insert(const T &V) {
++  std::pair<std::nullopt_t, bool> insert(const T &V) {
+     if (!isSmall())
+-      return std::make_pair(None, Set.insert(V).second);
++      return std::make_pair(std::nullopt, Set.insert(V).second);
+ 
+     VIterator I = vfind(V);
+     if (I != Vector.end())    // Don't reinsert if it already exists.
+-      return std::make_pair(None, false);
++      return std::make_pair(std::nullopt, false);
+     if (Vector.size() < N) {
+       Vector.push_back(V);
+-      return std::make_pair(None, true);
++      return std::make_pair(std::nullopt, true);
+     }
+ 
+     // Otherwise, grow from vector to set.
+@@ -197,7 +196,7 @@ public:
+       Vector.pop_back();
+     }
+     Set.insert(V);
+-    return std::make_pair(None, true);
++    return std::make_pair(std::nullopt, true);
+   }
+ 
+   template <typename IterT>
+diff --git a/llvm/include/llvm/ADT/SmallString.h b/llvm/include/llvm/ADT/SmallString.h
+index 874968f0a..50cbdade4 100644
+--- a/llvm/include/llvm/ADT/SmallString.h
++++ b/llvm/include/llvm/ADT/SmallString.h
+@@ -15,8 +15,9 @@
+ #define LLVM_ADT_SMALLSTRING_H
+ 
+ #include "llvm/ADT/SmallVector.h"
+-#include "llvm/ADT/StringRef.h"
+ #include <cstddef>
++#include <string>
++#include <string_view>
+ 
+ namespace llvm {
+ 
+@@ -28,11 +29,11 @@ public:
+   /// Default ctor - Initialize to empty.
+   SmallString() = default;
+ 
+-  /// Initialize from a StringRef.
+-  SmallString(StringRef S) : SmallVector<char, InternalLen>(S.begin(), S.end()) {}
++  /// Initialize from a std::string_view.
++  SmallString(std::string_view S) : SmallVector<char, InternalLen>(S.begin(), S.end()) {}
+ 
+-  /// Initialize by concatenating a list of StringRefs.
+-  SmallString(std::initializer_list<StringRef> Refs)
++  /// Initialize by concatenating a list of std::string_views.
++  SmallString(std::initializer_list<std::string_view> Refs)
+       : SmallVector<char, InternalLen>() {
+     this->append(Refs);
+   }
+@@ -47,13 +48,13 @@ public:
+ 
+   using SmallVector<char, InternalLen>::assign;
+ 
+-  /// Assign from a StringRef.
+-  void assign(StringRef RHS) {
++  /// Assign from a std::string_view.
++  void assign(std::string_view RHS) {
+     SmallVectorImpl<char>::assign(RHS.begin(), RHS.end());
+   }
+ 
+-  /// Assign from a list of StringRefs.
+-  void assign(std::initializer_list<StringRef> Refs) {
++  /// Assign from a list of std::string_views.
++  void assign(std::initializer_list<std::string_view> Refs) {
+     this->clear();
+     append(Refs);
+   }
+@@ -64,19 +65,19 @@ public:
+ 
+   using SmallVector<char, InternalLen>::append;
+ 
+-  /// Append from a StringRef.
+-  void append(StringRef RHS) {
++  /// Append from a std::string_view.
++  void append(std::string_view RHS) {
+     SmallVectorImpl<char>::append(RHS.begin(), RHS.end());
+   }
+ 
+-  /// Append from a list of StringRefs.
+-  void append(std::initializer_list<StringRef> Refs) {
++  /// Append from a list of std::string_views.
++  void append(std::initializer_list<std::string_view> Refs) {
+     size_t CurrentSize = this->size();
+     size_t SizeNeeded = CurrentSize;
+-    for (const StringRef &Ref : Refs)
++    for (const std::string_view &Ref : Refs)
+       SizeNeeded += Ref.size();
+     this->resize_for_overwrite(SizeNeeded);
+-    for (const StringRef &Ref : Refs) {
++    for (const std::string_view &Ref : Refs) {
+       std::copy(Ref.begin(), Ref.end(), this->begin() + CurrentSize);
+       CurrentSize += Ref.size();
+     }
+@@ -89,29 +90,29 @@ public:
+ 
+   /// Check for string equality.  This is more efficient than compare() when
+   /// the relative ordering of inequal strings isn't needed.
+-  bool equals(StringRef RHS) const {
++  bool equals(std::string_view RHS) const {
+     return str().equals(RHS);
+   }
+ 
+   /// Check for string equality, ignoring case.
+-  bool equals_insensitive(StringRef RHS) const {
++  bool equals_insensitive(std::string_view RHS) const {
+     return str().equals_insensitive(RHS);
+   }
+ 
+   /// Compare two strings; the result is -1, 0, or 1 if this string is
+   /// lexicographically less than, equal to, or greater than the \p RHS.
+-  int compare(StringRef RHS) const {
++  int compare(std::string_view RHS) const {
+     return str().compare(RHS);
+   }
+ 
+   /// compare_insensitive - Compare two strings, ignoring case.
+-  int compare_insensitive(StringRef RHS) const {
++  int compare_insensitive(std::string_view RHS) const {
+     return str().compare_insensitive(RHS);
+   }
+ 
+   /// compare_numeric - Compare two strings, treating sequences of digits as
+   /// numbers.
+-  int compare_numeric(StringRef RHS) const {
++  int compare_numeric(std::string_view RHS) const {
+     return str().compare_numeric(RHS);
+   }
+ 
+@@ -120,12 +121,12 @@ public:
+   /// @{
+ 
+   /// startswith - Check if this string starts with the given \p Prefix.
+-  bool startswith(StringRef Prefix) const {
++  bool startswith(std::string_view Prefix) const {
+     return str().startswith(Prefix);
+   }
+ 
+   /// endswith - Check if this string ends with the given \p Suffix.
+-  bool endswith(StringRef Suffix) const {
++  bool endswith(std::string_view Suffix) const {
+     return str().endswith(Suffix);
+   }
+ 
+@@ -145,7 +146,7 @@ public:
+   ///
+   /// \returns The index of the first occurrence of \p Str, or npos if not
+   /// found.
+-  size_t find(StringRef Str, size_t From = 0) const {
++  size_t find(std::string_view Str, size_t From = 0) const {
+     return str().find(Str, From);
+   }
+ 
+@@ -153,7 +154,7 @@ public:
+   ///
+   /// \returns The index of the last occurrence of \p C, or npos if not
+   /// found.
+-  size_t rfind(char C, size_t From = StringRef::npos) const {
++  size_t rfind(char C, size_t From = std::string_view::npos) const {
+     return str().rfind(C, From);
+   }
+ 
+@@ -161,7 +162,7 @@ public:
+   ///
+   /// \returns The index of the last occurrence of \p Str, or npos if not
+   /// found.
+-  size_t rfind(StringRef Str) const {
++  size_t rfind(std::string_view Str) const {
+     return str().rfind(Str);
+   }
+ 
+@@ -175,7 +176,7 @@ public:
+   /// not found.
+   ///
+   /// Complexity: O(size() + Chars.size())
+-  size_t find_first_of(StringRef Chars, size_t From = 0) const {
++  size_t find_first_of(std::string_view Chars, size_t From = 0) const {
+     return str().find_first_of(Chars, From);
+   }
+ 
+@@ -189,13 +190,13 @@ public:
+   /// \p Chars, or npos if not found.
+   ///
+   /// Complexity: O(size() + Chars.size())
+-  size_t find_first_not_of(StringRef Chars, size_t From = 0) const {
++  size_t find_first_not_of(std::string_view Chars, size_t From = 0) const {
+     return str().find_first_not_of(Chars, From);
+   }
+ 
+   /// Find the last character in the string that is \p C, or npos if not
+   /// found.
+-  size_t find_last_of(char C, size_t From = StringRef::npos) const {
++  size_t find_last_of(char C, size_t From = std::string_view::npos) const {
+     return str().find_last_of(C, From);
+   }
+ 
+@@ -204,7 +205,7 @@ public:
+   ///
+   /// Complexity: O(size() + Chars.size())
+   size_t find_last_of(
+-      StringRef Chars, size_t From = StringRef::npos) const {
++      std::string_view Chars, size_t From = std::string_view::npos) const {
+     return str().find_last_of(Chars, From);
+   }
+ 
+@@ -219,7 +220,7 @@ public:
+ 
+   /// Return the number of non-overlapped occurrences of \p Str in the
+   /// string.
+-  size_t count(StringRef Str) const {
++  size_t count(std::string_view Str) const {
+     return str().count(Str);
+   }
+ 
+@@ -236,7 +237,7 @@ public:
+   /// \param N The number of characters to included in the substring. If \p N
+   /// exceeds the number of characters remaining in the string, the string
+   /// suffix (starting with \p Start) will be returned.
+-  StringRef substr(size_t Start, size_t N = StringRef::npos) const {
++  std::string_view substr(size_t Start, size_t N = std::string_view::npos) const {
+     return str().substr(Start, N);
+   }
+ 
+@@ -250,14 +251,14 @@ public:
+   /// substring. If this is npos, or less than \p Start, or exceeds the
+   /// number of characters remaining in the string, the string suffix
+   /// (starting with \p Start) will be returned.
+-  StringRef slice(size_t Start, size_t End) const {
++  std::string_view slice(size_t Start, size_t End) const {
+     return str().slice(Start, End);
+   }
+ 
+   // Extra methods.
+ 
+-  /// Explicit conversion to StringRef.
+-  StringRef str() const { return StringRef(this->data(), this->size()); }
++  /// Explicit conversion to std::string_view.
++  std::string_view str() const { return std::string_view(this->begin(), this->size()); }
+ 
+   // TODO: Make this const, if it's safe...
+   const char* c_str() {
+@@ -266,20 +267,20 @@ public:
+     return this->data();
+   }
+ 
+-  /// Implicit conversion to StringRef.
+-  operator StringRef() const { return str(); }
++  /// Implicit conversion to std::string_view.
++  operator std::string_view() const { return str(); }
+ 
+   explicit operator std::string() const {
+     return std::string(this->data(), this->size());
+   }
+ 
+   // Extra operators.
+-  SmallString &operator=(StringRef RHS) {
++  SmallString &operator=(std::string_view RHS) {
+     this->assign(RHS);
+     return *this;
+   }
+ 
+-  SmallString &operator+=(StringRef RHS) {
++  SmallString &operator+=(std::string_view RHS) {
+     this->append(RHS.begin(), RHS.end());
+     return *this;
+   }
+diff --git a/llvm/include/llvm/ADT/StringMap.h b/llvm/include/llvm/ADT/StringMap.h
+index 23248093c..8747cdb35 100644
+--- a/llvm/include/llvm/ADT/StringMap.h
++++ b/llvm/include/llvm/ADT/StringMap.h
+@@ -60,12 +60,12 @@ protected:
+   /// specified bucket will be non-null.  Otherwise, it will be null.  In either
+   /// case, the FullHashValue field of the bucket will be set to the hash value
+   /// of the string.
+-  unsigned LookupBucketFor(StringRef Key);
++  unsigned LookupBucketFor(std::string_view Key);
+ 
+   /// FindKey - Look up the bucket that contains the specified key. If it exists
+   /// in the map, return the bucket number of the key.  Otherwise return -1.
+   /// This does not modify the map.
+-  int FindKey(StringRef Key) const;
++  int FindKey(std::string_view Key) const;
+ 
+   /// RemoveKey - Remove the specified StringMapEntry from the table, but do not
+   /// delete it.  This aborts if the value isn't in the table.
+@@ -73,7 +73,7 @@ protected:
+ 
+   /// RemoveKey - Remove the StringMapEntry for the specified key from the
+   /// table, returning it.  If the key is not in the table, this returns null.
+-  StringMapEntryBase *RemoveKey(StringRef Key);
++  StringMapEntryBase *RemoveKey(std::string_view Key);
+ 
+   /// Allocate the table with the specified number of buckets and otherwise
+   /// setup the map as empty.
+@@ -126,7 +126,7 @@ public:
+       : StringMapImpl(InitialSize, static_cast<unsigned>(sizeof(MapEntryTy))),
+         Allocator(A) {}
+ 
+-  StringMap(std::initializer_list<std::pair<StringRef, ValueTy>> List)
++  StringMap(std::initializer_list<std::pair<std::string_view, ValueTy>> List)
+       : StringMapImpl(List.size(), static_cast<unsigned>(sizeof(MapEntryTy))) {
+     insert(List);
+   }
+@@ -215,14 +215,14 @@ public:
+                       StringMapKeyIterator<ValueTy>(end()));
+   }
+ 
+-  iterator find(StringRef Key) {
++  iterator find(std::string_view Key) {
+     int Bucket = FindKey(Key);
+     if (Bucket == -1)
+       return end();
+     return iterator(TheTable + Bucket, true);
+   }
+ 
+-  const_iterator find(StringRef Key) const {
++  const_iterator find(std::string_view Key) const {
+     int Bucket = FindKey(Key);
+     if (Bucket == -1)
+       return end();
+@@ -231,7 +231,7 @@ public:
+ 
+   /// lookup - Return the entry for the specified key, or a default
+   /// constructed value if no such entry exists.
+-  ValueTy lookup(StringRef Key) const {
++  ValueTy lookup(std::string_view Key) const {
+     const_iterator it = find(Key);
+     if (it != end())
+       return it->second;
+@@ -240,10 +240,10 @@ public:
+ 
+   /// Lookup the ValueTy for the \p Key, or create a default constructed value
+   /// if the key is not in the map.
+-  ValueTy &operator[](StringRef Key) { return try_emplace(Key).first->second; }
++  ValueTy &operator[](std::string_view Key) { return try_emplace(Key).first->second; }
+ 
+   /// count - Return 1 if the element is in the map, 0 otherwise.
+-  size_type count(StringRef Key) const { return find(Key) == end() ? 0 : 1; }
++  size_type count(std::string_view Key) const { return find(Key) == end() ? 0 : 1; }
+ 
+   template <typename InputTy>
+   size_type count(const StringMapEntry<InputTy> &MapEntry) const {
+@@ -293,7 +293,7 @@ public:
+   /// isn't already in the map. The bool component of the returned pair is true
+   /// if and only if the insertion takes place, and the iterator component of
+   /// the pair points to the element with key equivalent to the key of the pair.
+-  std::pair<iterator, bool> insert(std::pair<StringRef, ValueTy> KV) {
++  std::pair<iterator, bool> insert(std::pair<std::string_view, ValueTy> KV) {
+     return try_emplace(KV.first, std::move(KV.second));
+   }
+ 
+@@ -308,14 +308,14 @@ public:
+   ///  Inserts elements from initializer list ilist. If multiple elements in
+   /// the range have keys that compare equivalent, it is unspecified which
+   /// element is inserted
+-  void insert(std::initializer_list<std::pair<StringRef, ValueTy>> List) {
++  void insert(std::initializer_list<std::pair<std::string_view, ValueTy>> List) {
+     insert(List.begin(), List.end());
+   }
+ 
+   /// Inserts an element or assigns to the current element if the key already
+   /// exists. The return type is the same as try_emplace.
+   template <typename V>
+-  std::pair<iterator, bool> insert_or_assign(StringRef Key, V &&Val) {
++  std::pair<iterator, bool> insert_or_assign(std::string_view Key, V &&Val) {
+     auto Ret = try_emplace(Key, std::forward<V>(Val));
+     if (!Ret.second)
+       Ret.first->second = std::forward<V>(Val);
+@@ -327,7 +327,7 @@ public:
+   /// if and only if the insertion takes place, and the iterator component of
+   /// the pair points to the element with key equivalent to the key of the pair.
+   template <typename... ArgsTy>
+-  std::pair<iterator, bool> try_emplace(StringRef Key, ArgsTy &&... Args) {
++  std::pair<iterator, bool> try_emplace(std::string_view Key, ArgsTy &&... Args) {
+     unsigned BucketNo = LookupBucketFor(Key);
+     StringMapEntryBase *&Bucket = TheTable[BucketNo];
+     if (Bucket && Bucket != getTombstoneVal())
+@@ -373,7 +373,7 @@ public:
+     V.Destroy(Allocator);
+   }
+ 
+-  bool erase(StringRef Key) {
++  bool erase(std::string_view Key) {
+     iterator I = find(Key);
+     if (I == end())
+       return false;
+@@ -470,17 +470,17 @@ template <typename ValueTy>
+ class StringMapKeyIterator
+     : public iterator_adaptor_base<StringMapKeyIterator<ValueTy>,
+                                    StringMapConstIterator<ValueTy>,
+-                                   std::forward_iterator_tag, StringRef> {
++                                   std::forward_iterator_tag, std::string_view> {
+   using base = iterator_adaptor_base<StringMapKeyIterator<ValueTy>,
+                                      StringMapConstIterator<ValueTy>,
+-                                     std::forward_iterator_tag, StringRef>;
++                                     std::forward_iterator_tag, std::string_view>;
+ 
+ public:
+   StringMapKeyIterator() = default;
+   explicit StringMapKeyIterator(StringMapConstIterator<ValueTy> Iter)
+       : base(std::move(Iter)) {}
+ 
+-  StringRef operator*() const { return this->wrapped()->getKey(); }
++  std::string_view operator*() const { return this->wrapped()->getKey(); }
+ };
+ 
+ } // end namespace llvm
+diff --git a/llvm/include/llvm/ADT/StringMapEntry.h b/llvm/include/llvm/ADT/StringMapEntry.h
+index 6e13c8618..39976a02b 100644
+--- a/llvm/include/llvm/ADT/StringMapEntry.h
++++ b/llvm/include/llvm/ADT/StringMapEntry.h
+@@ -16,9 +16,8 @@
+ #ifndef LLVM_ADT_STRINGMAPENTRY_H
+ #define LLVM_ADT_STRINGMAPENTRY_H
+ 
+-#include "llvm/ADT/None.h"
+-#include "llvm/ADT/StringRef.h"
+-#include "llvm/ADT/STLFunctionalExtras.h"
++#include <optional>
++#include <string_view>
+ 
+ namespace llvm {
+ 
+@@ -37,13 +36,13 @@ protected:
+   /// type-erase the allocator and put it in a source file.
+   template <typename AllocatorTy>
+   static void *allocateWithKey(size_t EntrySize, size_t EntryAlign,
+-                               StringRef Key, AllocatorTy &Allocator);
++                               std::string_view Key, AllocatorTy &Allocator);
+ };
+ 
+ // Define out-of-line to dissuade inlining.
+ template <typename AllocatorTy>
+ void *StringMapEntryBase::allocateWithKey(size_t EntrySize, size_t EntryAlign,
+-                                          StringRef Key,
++                                          std::string_view Key,
+                                           AllocatorTy &Allocator) {
+   size_t KeyLength = Key.size();
+ 
+@@ -85,13 +84,13 @@ public:
+   void setValue(const ValueTy &V) { second = V; }
+ };
+ 
+-template <> class StringMapEntryStorage<NoneType> : public StringMapEntryBase {
++template <> class StringMapEntryStorage<std::nullopt_t> : public StringMapEntryBase {
+ public:
+-  explicit StringMapEntryStorage(size_t keyLength, NoneType = None)
++  explicit StringMapEntryStorage(size_t keyLength, std::nullopt_t = std::nullopt)
+       : StringMapEntryBase(keyLength) {}
+   StringMapEntryStorage(StringMapEntryStorage &entry) = delete;
+ 
+-  NoneType getValue() const { return None; }
++  std::nullopt_t getValue() const { return std::nullopt; }
+ };
+ 
+ /// StringMapEntry - This is used to represent one value that is inserted into
+@@ -102,8 +101,8 @@ class StringMapEntry final : public StringMapEntryStorage<ValueTy> {
+ public:
+   using StringMapEntryStorage<ValueTy>::StringMapEntryStorage;
+ 
+-  StringRef getKey() const {
+-    return StringRef(getKeyData(), this->getKeyLength());
++  std::string_view getKey() const {
++    return std::string_view(getKeyData(), this->getKeyLength());
+   }
+ 
+   /// getKeyData - Return the start of the string data that is the key for this
+@@ -113,14 +112,14 @@ public:
+     return reinterpret_cast<const char *>(this + 1);
+   }
+ 
+-  StringRef first() const {
+-    return StringRef(getKeyData(), this->getKeyLength());
++  std::string_view first() const {
++    return std::string_view(getKeyData(), this->getKeyLength());
+   }
+ 
+   /// Create a StringMapEntry for the specified key construct the value using
+   /// \p InitiVals.
+   template <typename AllocatorTy, typename... InitTy>
+-  static StringMapEntry *Create(StringRef key, AllocatorTy &allocator,
++  static StringMapEntry *Create(std::string_view key, AllocatorTy &allocator,
+                                 InitTy &&... initVals) {
+     return new (StringMapEntryBase::allocateWithKey(
+         sizeof(StringMapEntry), alignof(StringMapEntry), key, allocator))
+diff --git a/llvm/include/llvm/Support/Chrono.h b/llvm/include/llvm/Support/Chrono.h
+index 9c2bd45d2..a7dea19d9 100644
+--- a/llvm/include/llvm/Support/Chrono.h
++++ b/llvm/include/llvm/Support/Chrono.h
+@@ -70,7 +70,7 @@ raw_ostream &operator<<(raw_ostream &OS, sys::TimePoint<> TP);
+ template <>
+ struct format_provider<sys::TimePoint<>> {
+   static void format(const sys::TimePoint<> &TP, llvm::raw_ostream &OS,
+-                     StringRef Style);
++                     std::string_view Style);
+ };
+ 
+ namespace detail {
+@@ -122,7 +122,7 @@ private:
+     return duration_cast<duration<InternalRep, AsPeriod>>(D).count();
+   }
+ 
+-  static std::pair<InternalRep, StringRef> consumeUnit(StringRef &Style,
++  static std::pair<InternalRep, std::string_view> consumeUnit(std::string_view &Style,
+                                                         const Dur &D) {
+     using namespace std::chrono;
+     if (Style.consume_front("ns"))
+@@ -140,7 +140,7 @@ private:
+     return {D.count(), detail::unit<Period>::value};
+   }
+ 
+-  static bool consumeShowUnit(StringRef &Style) {
++  static bool consumeShowUnit(std::string_view &Style) {
+     if (Style.empty())
+       return true;
+     if (Style.consume_front("-"))
+@@ -152,9 +152,9 @@ private:
+   }
+ 
+ public:
+-  static void format(const Dur &D, llvm::raw_ostream &Stream, StringRef Style) {
++  static void format(const Dur &D, llvm::raw_ostream &Stream, std::string_view Style) {
+     InternalRep count;
+-    StringRef unit;
++    std::string_view unit;
+     std::tie(count, unit) = consumeUnit(Style, D);
+     bool show_unit = consumeShowUnit(Style);
+ 
+diff --git a/llvm/include/llvm/Support/Compiler.h b/llvm/include/llvm/Support/Compiler.h
+index 80b2dfaec..f5d726ec8 100644
+--- a/llvm/include/llvm/Support/Compiler.h
++++ b/llvm/include/llvm/Support/Compiler.h
+@@ -312,7 +312,7 @@
+ #endif
+ 
+ /// LLVM_GSL_POINTER - Apply this to non-owning classes like
+-/// StringRef to enable lifetime warnings.
++/// std::string_view to enable lifetime warnings.
+ #if LLVM_HAS_CPP_ATTRIBUTE(gsl::Pointer)
+ #define LLVM_GSL_POINTER [[gsl::Pointer]]
+ #else
+diff --git a/llvm/include/llvm/Support/ConvertUTF.h b/llvm/include/llvm/Support/ConvertUTF.h
+index 374cdb907..7f1527f51 100644
+--- a/llvm/include/llvm/Support/ConvertUTF.h
++++ b/llvm/include/llvm/Support/ConvertUTF.h
+@@ -89,12 +89,12 @@
+ #ifndef LLVM_SUPPORT_CONVERTUTF_H
+ #define LLVM_SUPPORT_CONVERTUTF_H
+ 
++#include "wpi/span.h"
++
+ #include <cstddef>
+ #include <string>
+-
+-#if defined(_WIN32)
++#include <string_view>
+ #include <system_error>
+-#endif
+ 
+ // Wrap everything in namespace llvm so that programs can link with llvm and
+ // their own version of the unicode libraries.
+@@ -183,12 +183,10 @@ unsigned getNumBytesForUTF8(UTF8 firstByte);
+ /*************************************************************************/
+ /* Below are LLVM-specific wrappers of the functions above. */
+ 
+-template <typename T> class ArrayRef;
+ template <typename T> class SmallVectorImpl;
+-class StringRef;
+ 
+ /**
+- * Convert an UTF8 StringRef to UTF8, UTF16, or UTF32 depending on
++ * Convert an UTF8 string_view to UTF8, UTF16, or UTF32 depending on
+  * WideCharWidth. The converted data is written to ResultPtr, which needs to
+  * point to at least WideCharWidth * (Source.Size() + 1) bytes. On success,
+  * ResultPtr will point one after the end of the copied string. On failure,
+@@ -196,14 +194,14 @@ class StringRef;
+  * the first character which could not be converted.
+  * \return true on success.
+  */
+-bool ConvertUTF8toWide(unsigned WideCharWidth, llvm::StringRef Source,
++bool ConvertUTF8toWide(unsigned WideCharWidth, std::string_view Source,
+                        char *&ResultPtr, const UTF8 *&ErrorPtr);
+ 
+ /**
+-* Converts a UTF-8 StringRef to a std::wstring.
++* Converts a UTF-8 string_view to a std::wstring.
+ * \return true on success.
+ */
+-bool ConvertUTF8toWide(llvm::StringRef Source, std::wstring &Result);
++bool ConvertUTF8toWide(std::string_view Source, std::wstring &Result);
+ 
+ /**
+ * Converts a UTF-8 C-string to a std::wstring.
+@@ -261,7 +259,7 @@ inline ConversionResult convertUTF8Sequence(const UTF8 **source,
+  * Returns true if a blob of text starts with a UTF-16 big or little endian byte
+  * order mark.
+  */
+-bool hasUTF16ByteOrderMark(ArrayRef<char> SrcBytes);
++bool hasUTF16ByteOrderMark(span<const char> SrcBytes);
+ 
+ /**
+  * Converts a stream of raw bytes assumed to be UTF16 into a UTF8 std::string.
+@@ -270,7 +268,7 @@ bool hasUTF16ByteOrderMark(ArrayRef<char> SrcBytes);
+  * \param [out] Out Converted UTF-8 is stored here on success.
+  * \returns true on success
+  */
+-bool convertUTF16ToUTF8String(ArrayRef<char> SrcBytes, std::string &Out);
++bool convertUTF16ToUTF8String(span<const char> SrcBytes, std::string &Out);
+ 
+ /**
+ * Converts a UTF16 string into a UTF8 std::string.
+@@ -279,22 +277,22 @@ bool convertUTF16ToUTF8String(ArrayRef<char> SrcBytes, std::string &Out);
+ * \param [out] Out Converted UTF-8 is stored here on success.
+ * \returns true on success
+ */
+-bool convertUTF16ToUTF8String(ArrayRef<UTF16> Src, std::string &Out);
++bool convertUTF16ToUTF8String(span<const UTF16> Src, std::string &Out);
+ 
+ /**
+  * Converts a UTF-8 string into a UTF-16 string with native endianness.
+  *
+  * \returns true on success
+  */
+-bool convertUTF8ToUTF16String(StringRef SrcUTF8,
++bool convertUTF8ToUTF16String(std::string_view SrcUTF8,
+                               SmallVectorImpl<UTF16> &DstUTF16);
+ 
+ #if defined(_WIN32)
+ namespace sys {
+ namespace windows {
+-std::error_code UTF8ToUTF16(StringRef utf8, SmallVectorImpl<wchar_t> &utf16);
++std::error_code UTF8ToUTF16(std::string_view utf8, SmallVectorImpl<wchar_t> &utf16);
+ /// Convert to UTF16 from the current code page used in the system
+-std::error_code CurCPToUTF16(StringRef utf8, SmallVectorImpl<wchar_t> &utf16);
++std::error_code CurCPToUTF16(std::string_view utf8, SmallVectorImpl<wchar_t> &utf16);
+ std::error_code UTF16ToUTF8(const wchar_t *utf16, size_t utf16_len,
+                             SmallVectorImpl<char> &utf8);
+ /// Convert from UTF16 to the current code page used in the system
+diff --git a/llvm/include/llvm/Support/DJB.h b/llvm/include/llvm/Support/DJB.h
+index 8a04a324a..8737cd144 100644
+--- a/llvm/include/llvm/Support/DJB.h
++++ b/llvm/include/llvm/Support/DJB.h
+@@ -13,13 +13,13 @@
+ #ifndef LLVM_SUPPORT_DJB_H
+ #define LLVM_SUPPORT_DJB_H
+ 
+-#include "llvm/ADT/StringRef.h"
++#include <string_view>
+ 
+ namespace llvm {
+ 
+ /// The Bernstein hash function used by the DWARF accelerator tables.
+-inline uint32_t djbHash(StringRef Buffer, uint32_t H = 5381) {
+-  for (unsigned char C : Buffer.bytes())
++inline uint32_t djbHash(std::string_view Buffer, uint32_t H = 5381) {
++  for (unsigned char C : Buffer)
+     H = (H << 5) + H + C;
+   return H;
+ }
+diff --git a/llvm/include/llvm/Support/ErrorHandling.h b/llvm/include/llvm/Support/ErrorHandling.h
+index 6791df6be..3f726d40b 100644
+--- a/llvm/include/llvm/Support/ErrorHandling.h
++++ b/llvm/include/llvm/Support/ErrorHandling.h
+@@ -15,10 +15,10 @@
+ #define LLVM_SUPPORT_ERRORHANDLING_H
+ 
+ #include "llvm/Support/Compiler.h"
++#include <string>
++#include <string_view>
+ 
+ namespace llvm {
+-  class StringRef;
+-  class Twine;
+ 
+   /// An error handler callback.
+   typedef void (*fatal_error_handler_t)(void *user_data,
+@@ -67,12 +67,11 @@ namespace llvm {
+ /// standard error, followed by a newline.
+ /// After the error handler is called this function will call abort(), it
+ /// does not return.
+-/// NOTE: The std::string variant was removed to avoid a <string> dependency.
+ [[noreturn]] void report_fatal_error(const char *reason,
+                                      bool gen_crash_diag = true);
+-[[noreturn]] void report_fatal_error(StringRef reason,
++[[noreturn]] void report_fatal_error(const std::string &reason,
+                                      bool gen_crash_diag = true);
+-[[noreturn]] void report_fatal_error(const Twine &reason,
++[[noreturn]] void report_fatal_error(std::string_view reason,
+                                      bool gen_crash_diag = true);
+ 
+ /// Installs a new bad alloc error handler that should be used whenever a
+diff --git a/llvm/include/llvm/Support/SmallVectorMemoryBuffer.h b/llvm/include/llvm/Support/SmallVectorMemoryBuffer.h
+index f7f2d4e54..b5e321b5f 100644
+--- a/llvm/include/llvm/Support/SmallVectorMemoryBuffer.h
++++ b/llvm/include/llvm/Support/SmallVectorMemoryBuffer.h
+@@ -35,8 +35,8 @@ public:
+                                 RequiresNullTerminator) {}
+ 
+   /// Construct a named SmallVectorMemoryBuffer from the given SmallVector
+-  /// r-value and StringRef.
+-  SmallVectorMemoryBuffer(SmallVectorImpl<char> &&SV, StringRef Name,
++  /// r-value and std::string_view.
++  SmallVectorMemoryBuffer(SmallVectorImpl<char> &&SV, std::string_view Name,
+                           bool RequiresNullTerminator = true)
+       : SV(std::move(SV)), BufferName(std::string(Name)) {
+     if (RequiresNullTerminator) {
+@@ -49,7 +49,7 @@ public:
+   // Key function.
+   ~SmallVectorMemoryBuffer() override;
+ 
+-  StringRef getBufferIdentifier() const override { return BufferName; }
++  std::string_view getBufferIdentifier() const override { return BufferName; }
+ 
+   BufferKind getBufferKind() const override { return MemoryBuffer_Malloc; }
+ 
+diff --git a/llvm/include/llvm/Support/VersionTuple.h b/llvm/include/llvm/Support/VersionTuple.h
+index 1a1072d22..3d6573bf5 100644
+--- a/llvm/include/llvm/Support/VersionTuple.h
++++ b/llvm/include/llvm/Support/VersionTuple.h
+@@ -16,14 +16,13 @@
+ 
+ #include "llvm/ADT/DenseMapInfo.h"
+ #include "llvm/ADT/Hashing.h"
+-#include "llvm/ADT/Optional.h"
+ #include "llvm/Support/HashBuilder.h"
++#include <optional>
+ #include <string>
+ #include <tuple>
+ 
+ namespace llvm {
+ class raw_ostream;
+-class StringRef;
+ 
+ /// Represents a version number in the form major[.minor[.subminor[.build]]].
+ class VersionTuple {
+@@ -70,23 +69,23 @@ public:
+   unsigned getMajor() const { return Major; }
+ 
+   /// Retrieve the minor version number, if provided.
+-  Optional<unsigned> getMinor() const {
++  std::optional<unsigned> getMinor() const {
+     if (!HasMinor)
+-      return None;
++      return std::nullopt;
+     return Minor;
+   }
+ 
+   /// Retrieve the subminor version number, if provided.
+-  Optional<unsigned> getSubminor() const {
++  std::optional<unsigned> getSubminor() const {
+     if (!HasSubminor)
+-      return None;
++      return std::nullopt;
+     return Subminor;
+   }
+ 
+   /// Retrieve the build version number, if provided.
+-  Optional<unsigned> getBuild() const {
++  std::optional<unsigned> getBuild() const {
+     if (!HasBuild)
+-      return None;
++      return std::nullopt;
+     return Build;
+   }
+ 
+@@ -173,11 +172,6 @@ public:
+ 
+   /// Retrieve a string representation of the version number.
+   std::string getAsString() const;
+-
+-  /// Try to parse the given string as a version number.
+-  /// \returns \c true if the string does not match the regular expression
+-  ///   [0-9]+(\.[0-9]+){0,3}
+-  bool tryParse(StringRef string);
+ };
+ 
+ /// Print a version number.
+diff --git a/llvm/include/llvm/Support/Windows/WindowsSupport.h b/llvm/include/llvm/Support/Windows/WindowsSupport.h
+index 917822678..180803fbd 100644
+--- a/llvm/include/llvm/Support/Windows/WindowsSupport.h
++++ b/llvm/include/llvm/Support/Windows/WindowsSupport.h
+@@ -35,8 +35,6 @@
+ 
+ #include "llvm/ADT/SmallVector.h"
+ #include "llvm/ADT/StringExtras.h"
+-#include "llvm/ADT/StringRef.h"
+-#include "llvm/ADT/Twine.h"
+ #include "llvm/Config/llvm-config.h" // Get build system configuration settings
+ #include "llvm/Support/Allocator.h"
+ #include "llvm/Support/Chrono.h"
+@@ -71,7 +69,7 @@ bool MakeErrMsg(std::string *ErrMsg, const std::string &prefix);
+ [[noreturn]] inline void ReportLastErrorFatal(const char *Msg) {
+   std::string ErrMsg;
+   MakeErrMsg(&ErrMsg, Msg);
+-  llvm::report_fatal_error(Twine(ErrMsg));
++  llvm::report_fatal_error(ErrMsg);
+ }
+ 
+ template <typename HandleTraits>
+diff --git a/llvm/include/llvm/Support/raw_ostream.h b/llvm/include/llvm/Support/raw_ostream.h
+index 58adb41cb..9a1dd7a60 100644
+--- a/llvm/include/llvm/Support/raw_ostream.h
++++ b/llvm/include/llvm/Support/raw_ostream.h
+@@ -14,9 +14,7 @@
+ #define LLVM_SUPPORT_RAW_OSTREAM_H
+ 
+ #include "llvm/ADT/SmallVector.h"
+-#include "llvm/ADT/StringRef.h"
+-#include "llvm/ADT/Optional.h"
+-#include "llvm/Support/DataTypes.h"
++#include "llvm/ADT/span.h"
+ #include <cassert>
+ #include <cstddef>
+ #include <cstdint>
+@@ -210,7 +208,22 @@ public:
+     return *this;
+   }
+ 
+-  raw_ostream &operator<<(StringRef Str) {
++  raw_ostream &operator<<(span<const uint8_t> Arr) {
++    // Inline fast path, particularly for arrays with a known length.
++    size_t Size = Arr.size();
++
++    // Make sure we can use the fast path.
++    if (Size > (size_t)(OutBufEnd - OutBufCur))
++      return write(Arr.data(), Size);
++
++    if (Size) {
++      memcpy(OutBufCur, Arr.data(), Size);
++      OutBufCur += Size;
++    }
++    return *this;
++  }
++
++  raw_ostream &operator<<(std::string_view Str) {
+     // Inline fast path, particularly for strings with a known length.
+     size_t Size = Str.size();
+ 
+@@ -229,7 +242,7 @@ public:
+     // Inline fast path, particularly for constant strings where a sufficiently
+     // smart compiler will simplify strlen.
+ 
+-    return this->operator<<(StringRef(Str));
++    return this->operator<<(std::string_view(Str));
+   }
+ 
+   raw_ostream &operator<<(const std::string &Str) {
+@@ -237,12 +250,6 @@ public:
+     return write(Str.data(), Str.length());
+   }
+ 
+-#if __cplusplus > 201402L
+-  raw_ostream &operator<<(const std::string_view &Str) {
+-    return write(Str.data(), Str.length());
+-  }
+-#endif
+-
+   raw_ostream &operator<<(const SmallVectorImpl<char> &Str) {
+     return write(Str.data(), Str.size());
+   }
+@@ -275,7 +282,7 @@ public:
+ 
+   /// Output \p Str, turning '\\', '\t', '\n', '"', and anything that doesn't
+   /// satisfy llvm::isPrint into an escape sequence.
+-  raw_ostream &write_escaped(StringRef Str, bool UseHexEscapes = false);
++  raw_ostream &write_escaped(std::string_view Str, bool UseHexEscapes = false);
+ 
+   raw_ostream &write(unsigned char C);
+   raw_ostream &write(const char *Ptr, size_t Size);
+@@ -446,7 +453,7 @@ class raw_fd_ostream : public raw_pwrite_stream {
+   bool ShouldClose;
+   bool SupportsSeeking = false;
+   bool IsRegularFile = false;
+-  mutable Optional<bool> HasColors;
++  mutable std::optional<bool> HasColors;
+ 
+ #ifdef _WIN32
+   /// True if this fd refers to a Windows console device. Mintty and other
+@@ -491,14 +498,14 @@ public:
+   /// As a special case, if Filename is "-", then the stream will use
+   /// STDOUT_FILENO instead of opening a file. This will not close the stdout
+   /// descriptor.
+-  raw_fd_ostream(StringRef Filename, std::error_code &EC);
+-  raw_fd_ostream(StringRef Filename, std::error_code &EC,
++  raw_fd_ostream(std::string_view Filename, std::error_code &EC);
++  raw_fd_ostream(std::string_view Filename, std::error_code &EC,
+                  sys::fs::CreationDisposition Disp);
+-  raw_fd_ostream(StringRef Filename, std::error_code &EC,
++  raw_fd_ostream(std::string_view Filename, std::error_code &EC,
+                  sys::fs::FileAccess Access);
+-  raw_fd_ostream(StringRef Filename, std::error_code &EC,
++  raw_fd_ostream(std::string_view Filename, std::error_code &EC,
+                  sys::fs::OpenFlags Flags);
+-  raw_fd_ostream(StringRef Filename, std::error_code &EC,
++  raw_fd_ostream(std::string_view Filename, std::error_code &EC,
+                  sys::fs::CreationDisposition Disp, sys::fs::FileAccess Access,
+                  sys::fs::OpenFlags Flags);
+ 
+@@ -603,7 +610,7 @@ public:
+   /// Open the specified file for reading/writing/seeking. If an error occurs,
+   /// information about the error is put into EC, and the stream should be
+   /// immediately destroyed.
+-  raw_fd_stream(StringRef Filename, std::error_code &EC);
++  raw_fd_stream(std::string_view Filename, std::error_code &EC);
+ 
+   /// This reads the \p Size bytes into a buffer pointed by \p Ptr.
+   ///
+@@ -683,8 +690,8 @@ public:
+ 
+   void flush() = delete;
+ 
+-  /// Return a StringRef for the vector contents.
+-  StringRef str() const { return StringRef(OS.data(), OS.size()); }
++  /// Return a std::string_view for the vector contents.
++  std::string_view str() const { return std::string_view(OS.data(), OS.size()); }
+ 
+   void reserveExtraSpace(uint64_t ExtraSize) override {
+     OS.reserve(tell() + ExtraSize);
+@@ -741,7 +748,7 @@ class Error;
+ /// for other names. For raw_fd_ostream instances, the stream writes to
+ /// a temporary file. The final output file is atomically replaced with the
+ /// temporary file after the \p Write function is finished.
+-Error writeToOutput(StringRef OutputFileName,
++Error writeToOutput(std::string_view OutputFileName,
+                     std::function<Error(raw_ostream &)> Write);
+ 
+ } // end namespace llvm
+diff --git a/llvm/lib/Support/ConvertUTFWrapper.cpp b/llvm/lib/Support/ConvertUTFWrapper.cpp
+index 392c4c489..396ab0c65 100644
+--- a/llvm/lib/Support/ConvertUTFWrapper.cpp
++++ b/llvm/lib/Support/ConvertUTFWrapper.cpp
+@@ -6,24 +6,24 @@
+ //
+ //===----------------------------------------------------------------------===//
+ 
+-#include "llvm/ADT/ArrayRef.h"
+-#include "llvm/ADT/StringRef.h"
++#include "llvm/ADT/span.h"
+ #include "llvm/Support/ConvertUTF.h"
+ #include "llvm/Support/ErrorHandling.h"
+ #include "llvm/Support/SwapByteOrder.h"
+ #include <string>
++#include <string_view>
+ #include <vector>
+ 
+ namespace llvm {
+ 
+-bool ConvertUTF8toWide(unsigned WideCharWidth, llvm::StringRef Source,
++bool ConvertUTF8toWide(unsigned WideCharWidth, std::string_view Source,
+                        char *&ResultPtr, const UTF8 *&ErrorPtr) {
+   assert(WideCharWidth == 1 || WideCharWidth == 2 || WideCharWidth == 4);
+   ConversionResult result = conversionOK;
+   // Copy the character span over.
+   if (WideCharWidth == 1) {
+-    const UTF8 *Pos = reinterpret_cast<const UTF8*>(Source.begin());
+-    if (!isLegalUTF8String(&Pos, reinterpret_cast<const UTF8*>(Source.end()))) {
++    const UTF8 *Pos = reinterpret_cast<const UTF8*>(Source.data());
++    if (!isLegalUTF8String(&Pos, reinterpret_cast<const UTF8*>(Source.data() + Source.size()))) {
+       result = sourceIllegal;
+       ErrorPtr = Pos;
+     } else {
+@@ -77,13 +77,13 @@ bool ConvertCodePointToUTF8(unsigned Source, char *&ResultPtr) {
+   return true;
+ }
+ 
+-bool hasUTF16ByteOrderMark(ArrayRef<char> S) {
++bool hasUTF16ByteOrderMark(span<const char> S) {
+   return (S.size() >= 2 &&
+           ((S[0] == '\xff' && S[1] == '\xfe') ||
+            (S[0] == '\xfe' && S[1] == '\xff')));
+ }
+ 
+-bool convertUTF16ToUTF8String(ArrayRef<char> SrcBytes, std::string &Out) {
++bool convertUTF16ToUTF8String(span<const char> SrcBytes, std::string &Out) {
+   assert(Out.empty());
+ 
+   // Error out on an uneven byte count.
+@@ -134,14 +134,14 @@ bool convertUTF16ToUTF8String(ArrayRef<char> SrcBytes, std::string &Out) {
+   return true;
+ }
+ 
+-bool convertUTF16ToUTF8String(ArrayRef<UTF16> Src, std::string &Out)
++bool convertUTF16ToUTF8String(span<const UTF16> Src, std::string &Out)
+ {
+   return convertUTF16ToUTF8String(
+-      llvm::ArrayRef<char>(reinterpret_cast<const char *>(Src.data()),
++      span<const char>(reinterpret_cast<const char *>(Src.data()),
+       Src.size() * sizeof(UTF16)), Out);
+ }
+ 
+-bool convertUTF8ToUTF16String(StringRef SrcUTF8,
++bool convertUTF8ToUTF16String(std::string_view SrcUTF8,
+                               SmallVectorImpl<UTF16> &DstUTF16) {
+   assert(DstUTF16.empty());
+ 
+@@ -152,8 +152,8 @@ bool convertUTF8ToUTF16String(StringRef SrcUTF8,
+     return true;
+   }
+ 
+-  const UTF8 *Src = reinterpret_cast<const UTF8 *>(SrcUTF8.begin());
+-  const UTF8 *SrcEnd = reinterpret_cast<const UTF8 *>(SrcUTF8.end());
++  const UTF8 *Src = reinterpret_cast<const UTF8 *>(SrcUTF8.data());
++  const UTF8 *SrcEnd = reinterpret_cast<const UTF8 *>(SrcUTF8.data() + SrcUTF8.size());
+ 
+   // Allocate the same number of UTF-16 code units as UTF-8 code units. Encoding
+   // as UTF-16 should always require the same amount or less code units than the
+@@ -184,7 +184,7 @@ static_assert(sizeof(wchar_t) == 1 || sizeof(wchar_t) == 2 ||
+               "Expected wchar_t to be 1, 2, or 4 bytes");
+ 
+ template <typename TResult>
+-static inline bool ConvertUTF8toWideInternal(llvm::StringRef Source,
++static inline bool ConvertUTF8toWideInternal(std::string_view Source,
+                                              TResult &Result) {
+   // Even in the case of UTF-16, the number of bytes in a UTF-8 string is
+   // at least as large as the number of elements in the resulting wide
+@@ -200,7 +200,7 @@ static inline bool ConvertUTF8toWideInternal(llvm::StringRef Source,
+   return true;
+ }
+ 
+-bool ConvertUTF8toWide(llvm::StringRef Source, std::wstring &Result) {
++bool ConvertUTF8toWide(std::string_view Source, std::wstring &Result) {
+   return ConvertUTF8toWideInternal(Source, Result);
+ }
+ 
+@@ -209,7 +209,7 @@ bool ConvertUTF8toWide(const char *Source, std::wstring &Result) {
+     Result.clear();
+     return true;
+   }
+-  return ConvertUTF8toWide(llvm::StringRef(Source), Result);
++  return ConvertUTF8toWide(std::string_view(Source), Result);
+ }
+ 
+ bool convertWideToUTF8(const std::wstring &Source, std::string &Result) {
+@@ -224,7 +224,7 @@ bool convertWideToUTF8(const std::wstring &Source, std::string &Result) {
+     return true;
+   } else if (sizeof(wchar_t) == 2) {
+     return convertUTF16ToUTF8String(
+-        llvm::ArrayRef<UTF16>(reinterpret_cast<const UTF16 *>(Source.data()),
++        span<const UTF16>(reinterpret_cast<const UTF16 *>(Source.data()),
+                               Source.size()),
+         Result);
+   } else if (sizeof(wchar_t) == 4) {
+diff --git a/llvm/lib/Support/ErrorHandling.cpp b/llvm/lib/Support/ErrorHandling.cpp
+index 80c0e0043..8ae8fb8b4 100644
+--- a/llvm/lib/Support/ErrorHandling.cpp
++++ b/llvm/lib/Support/ErrorHandling.cpp
+@@ -14,7 +14,6 @@
+ #include "llvm/Support/ErrorHandling.h"
+ #include "llvm-c/ErrorHandling.h"
+ #include "llvm/ADT/SmallVector.h"
+-#include "llvm/ADT/Twine.h"
+ #include "llvm/Config/config.h"
+ #include "llvm/Support/Debug.h"
+ #include "llvm/Support/Errc.h"
+@@ -80,14 +79,14 @@ void llvm::remove_fatal_error_handler() {
+ }
+ 
+ void llvm::report_fatal_error(const char *Reason, bool GenCrashDiag) {
+-  report_fatal_error(Twine(Reason), GenCrashDiag);
++  report_fatal_error(std::string_view(Reason), GenCrashDiag);
+ }
+ 
+-void llvm::report_fatal_error(StringRef Reason, bool GenCrashDiag) {
+-  report_fatal_error(Twine(Reason), GenCrashDiag);
++void llvm::report_fatal_error(const std::string &Reason, bool GenCrashDiag) {
++  report_fatal_error(std::string_view(Reason), GenCrashDiag);
+ }
+ 
+-void llvm::report_fatal_error(const Twine &Reason, bool GenCrashDiag) {
++void llvm::report_fatal_error(std::string_view Reason, bool GenCrashDiag) {
+   llvm::fatal_error_handler_t handler = nullptr;
+   void* handlerData = nullptr;
+   {
+@@ -101,7 +100,7 @@ void llvm::report_fatal_error(const Twine &Reason, bool GenCrashDiag) {
+   }
+ 
+   if (handler) {
+-    handler(handlerData, Reason.str().c_str(), GenCrashDiag);
++    handler(handlerData, std::string{Reason}.c_str(), GenCrashDiag);
+   } else {
+     // Blast the result out to stderr.  We don't try hard to make sure this
+     // succeeds (e.g. handling EINTR) and we can't use errs() here because
+@@ -109,7 +108,7 @@ void llvm::report_fatal_error(const Twine &Reason, bool GenCrashDiag) {
+     SmallVector<char, 64> Buffer;
+     raw_svector_ostream OS(Buffer);
+     OS << "LLVM ERROR: " << Reason << "\n";
+-    StringRef MessageStr = OS.str();
++    std::string_view MessageStr = OS.str();
+     ssize_t written = ::write(2, MessageStr.data(), MessageStr.size());
+     (void)written; // If something went wrong, we deliberately just give up.
+   }
+diff --git a/llvm/lib/Support/SmallVector.cpp b/llvm/lib/Support/SmallVector.cpp
+index 8cafbc7fa..8bad715e4 100644
+--- a/llvm/lib/Support/SmallVector.cpp
++++ b/llvm/lib/Support/SmallVector.cpp
+@@ -11,7 +11,6 @@
+ //===----------------------------------------------------------------------===//
+ 
+ #include "llvm/ADT/SmallVector.h"
+-#include "llvm/ADT/Twine.h"
+ #include "llvm/Support/MemAlloc.h"
+ #include <cstdint>
+ #ifdef LLVM_ENABLE_EXCEPTIONS
+@@ -67,7 +66,7 @@ static void report_size_overflow(size_t MinSize, size_t MaxSize) {
+ #ifdef LLVM_ENABLE_EXCEPTIONS
+   throw std::length_error(Reason);
+ #else
+-  report_fatal_error(Twine(Reason));
++  report_fatal_error(Reason);
+ #endif
+ }
+ 
+@@ -81,7 +80,7 @@ static void report_at_maximum_capacity(size_t MaxSize) {
+ #ifdef LLVM_ENABLE_EXCEPTIONS
+   throw std::length_error(Reason);
+ #else
+-  report_fatal_error(Twine(Reason));
++  report_fatal_error(Reason);
+ #endif
+ }
+ 
+diff --git a/llvm/lib/Support/StringMap.cpp b/llvm/lib/Support/StringMap.cpp
+index 012c785b4..317f4ee43 100644
+--- a/llvm/lib/Support/StringMap.cpp
++++ b/llvm/lib/Support/StringMap.cpp
+@@ -70,7 +70,7 @@ void StringMapImpl::init(unsigned InitSize) {
+ /// specified bucket will be non-null.  Otherwise, it will be null.  In either
+ /// case, the FullHashValue field of the bucket will be set to the hash value
+ /// of the string.
+-unsigned StringMapImpl::LookupBucketFor(StringRef Name) {
++unsigned StringMapImpl::LookupBucketFor(std::string_view Name) {
+   unsigned HTSize = NumBuckets;
+   if (HTSize == 0) { // Hash table unallocated so far?
+     init(16);
+@@ -110,7 +110,7 @@ unsigned StringMapImpl::LookupBucketFor(StringRef Name) {
+       // Do the comparison like this because Name isn't necessarily
+       // null-terminated!
+       char *ItemStr = (char *)BucketItem + ItemSize;
+-      if (Name == StringRef(ItemStr, BucketItem->getKeyLength())) {
++      if (Name == std::string_view(ItemStr, BucketItem->getKeyLength())) {
+         // We found a match!
+         return BucketNo;
+       }
+@@ -128,7 +128,7 @@ unsigned StringMapImpl::LookupBucketFor(StringRef Name) {
+ /// FindKey - Look up the bucket that contains the specified key. If it exists
+ /// in the map, return the bucket number of the key.  Otherwise return -1.
+ /// This does not modify the map.
+-int StringMapImpl::FindKey(StringRef Key) const {
++int StringMapImpl::FindKey(std::string_view Key) const {
+   unsigned HTSize = NumBuckets;
+   if (HTSize == 0)
+     return -1; // Really empty table?
+@@ -154,7 +154,7 @@ int StringMapImpl::FindKey(StringRef Key) const {
+       // Do the comparison like this because NameStart isn't necessarily
+       // null-terminated!
+       char *ItemStr = (char *)BucketItem + ItemSize;
+-      if (Key == StringRef(ItemStr, BucketItem->getKeyLength())) {
++      if (Key == std::string_view(ItemStr, BucketItem->getKeyLength())) {
+         // We found a match!
+         return BucketNo;
+       }
+@@ -173,14 +173,14 @@ int StringMapImpl::FindKey(StringRef Key) const {
+ /// delete it.  This aborts if the value isn't in the table.
+ void StringMapImpl::RemoveKey(StringMapEntryBase *V) {
+   const char *VStr = (char *)V + ItemSize;
+-  StringMapEntryBase *V2 = RemoveKey(StringRef(VStr, V->getKeyLength()));
++  StringMapEntryBase *V2 = RemoveKey(std::string_view(VStr, V->getKeyLength()));
+   (void)V2;
+   assert(V == V2 && "Didn't find key?");
+ }
+ 
+ /// RemoveKey - Remove the StringMapEntry for the specified key from the
+ /// table, returning it.  If the key is not in the table, this returns null.
+-StringMapEntryBase *StringMapImpl::RemoveKey(StringRef Key) {
++StringMapEntryBase *StringMapImpl::RemoveKey(std::string_view Key) {
+   int Bucket = FindKey(Key);
+   if (Bucket == -1)
+     return nullptr;
+diff --git a/llvm/lib/Support/raw_ostream.cpp b/llvm/lib/Support/raw_ostream.cpp
+index 69d4fe96b..e4c318eb8 100644
+--- a/llvm/lib/Support/raw_ostream.cpp
++++ b/llvm/lib/Support/raw_ostream.cpp
+@@ -159,7 +159,7 @@ raw_ostream &raw_ostream::write_uuid(const uuid_t UUID) {
+ }
+ 
+ 
+-raw_ostream &raw_ostream::write_escaped(StringRef Str,
++raw_ostream &raw_ostream::write_escaped(std::string_view Str,
+                                         bool UseHexEscapes) {
+   for (unsigned char c : Str) {
+     switch (c) {
+@@ -563,7 +563,7 @@ void format_object_base::home() {
+ //  raw_fd_ostream
+ //===----------------------------------------------------------------------===//
+ 
+-static int getFD(StringRef Filename, std::error_code &EC,
++static int getFD(std::string_view Filename, std::error_code &EC,
+                  sys::fs::CreationDisposition Disp, sys::fs::FileAccess Access,
+                  sys::fs::OpenFlags Flags) {
+   assert((Access & sys::fs::FA_Write) &&
+@@ -589,25 +589,25 @@ static int getFD(StringRef Filename, std::error_code &EC,
+   return FD;
+ }
+ 
+-raw_fd_ostream::raw_fd_ostream(StringRef Filename, std::error_code &EC)
++raw_fd_ostream::raw_fd_ostream(std::string_view Filename, std::error_code &EC)
+     : raw_fd_ostream(Filename, EC, sys::fs::CD_CreateAlways, sys::fs::FA_Write,
+                      sys::fs::OF_None) {}
+ 
+-raw_fd_ostream::raw_fd_ostream(StringRef Filename, std::error_code &EC,
++raw_fd_ostream::raw_fd_ostream(std::string_view Filename, std::error_code &EC,
+                                sys::fs::CreationDisposition Disp)
+     : raw_fd_ostream(Filename, EC, Disp, sys::fs::FA_Write, sys::fs::OF_None) {}
+ 
+-raw_fd_ostream::raw_fd_ostream(StringRef Filename, std::error_code &EC,
++raw_fd_ostream::raw_fd_ostream(std::string_view Filename, std::error_code &EC,
+                                sys::fs::FileAccess Access)
+     : raw_fd_ostream(Filename, EC, sys::fs::CD_CreateAlways, Access,
+                      sys::fs::OF_None) {}
+ 
+-raw_fd_ostream::raw_fd_ostream(StringRef Filename, std::error_code &EC,
++raw_fd_ostream::raw_fd_ostream(std::string_view Filename, std::error_code &EC,
+                                sys::fs::OpenFlags Flags)
+     : raw_fd_ostream(Filename, EC, sys::fs::CD_CreateAlways, sys::fs::FA_Write,
+                      Flags) {}
+ 
+-raw_fd_ostream::raw_fd_ostream(StringRef Filename, std::error_code &EC,
++raw_fd_ostream::raw_fd_ostream(std::string_view Filename, std::error_code &EC,
+                                sys::fs::CreationDisposition Disp,
+                                sys::fs::FileAccess Access,
+                                sys::fs::OpenFlags Flags)
+@@ -679,8 +679,7 @@ raw_fd_ostream::~raw_fd_ostream() {
+   // has_error() and clear the error flag with clear_error() before
+   // destructing raw_ostream objects which may have errors.
+   if (has_error())
+-    report_fatal_error(Twine("IO failure on output stream: ") +
+-                           error().message(),
++    report_fatal_error("IO failure on output stream: " + error().message(),
+                        /*gen_crash_diag=*/false);
+ }
+ 
+@@ -699,7 +698,7 @@ raw_fd_ostream::~raw_fd_ostream() {
+ // the input is UTF-8 or transcode from the local codepage to UTF-8 before
+ // quoting it. If they don't, this may mess up the encoding, but this is still
+ // probably the best compromise we can make.
+-static bool write_console_impl(int FD, StringRef Data) {
++static bool write_console_impl(int FD, std::string_view Data) {
+   SmallVector<wchar_t, 256> WideText;
+ 
+   // Fall back to ::write if it wasn't valid UTF-8.
+@@ -742,7 +741,7 @@ void raw_fd_ostream::write_impl(const char *Ptr, size_t Size) {
+   // If this is a Windows console device, try re-encoding from UTF-8 to UTF-16
+   // and using WriteConsoleW. If that fails, fall back to plain write().
+   if (IsWindowsConsole)
+-    if (write_console_impl(FD, StringRef(Ptr, Size)))
++    if (write_console_impl(FD, std::string_view(Ptr, Size)))
+       return;
+ #endif
+ 
+@@ -906,7 +905,7 @@ raw_ostream &llvm::nulls() {
+ // File Streams
+ //===----------------------------------------------------------------------===//
+ 
+-raw_fd_stream::raw_fd_stream(StringRef Filename, std::error_code &EC)
++raw_fd_stream::raw_fd_stream(std::string_view Filename, std::error_code &EC)
+     : raw_fd_ostream(getFD(Filename, EC, sys::fs::CD_CreateAlways,
+                            sys::fs::FA_Write | sys::fs::FA_Read,
+                            sys::fs::OF_None),
+@@ -984,7 +983,7 @@ void buffer_ostream::anchor() {}
+ 
+ void buffer_unique_ostream::anchor() {}
+ 
+-Error llvm::writeToOutput(StringRef OutputFileName,
++Error llvm::writeToOutput(std::string_view OutputFileName,
+                           std::function<Error(raw_ostream &)> Write) {
+   if (OutputFileName == "-")
+     return Write(outs());
+diff --git a/llvm/unittests/ADT/DenseMapTest.cpp b/llvm/unittests/ADT/DenseMapTest.cpp
+index 4dd314c5c..e505b1907 100644
+--- a/llvm/unittests/ADT/DenseMapTest.cpp
++++ b/llvm/unittests/ADT/DenseMapTest.cpp
+@@ -481,31 +481,6 @@ TEST(DenseMapCustomTest, ReserveTest) {
+   }
+ }
+ 
+-// Make sure DenseMap works with StringRef keys.
+-TEST(DenseMapCustomTest, StringRefTest) {
+-  DenseMap<StringRef, int> M;
+-
+-  M["a"] = 1;
+-  M["b"] = 2;
+-  M["c"] = 3;
+-
+-  EXPECT_EQ(3u, M.size());
+-  EXPECT_EQ(1, M.lookup("a"));
+-  EXPECT_EQ(2, M.lookup("b"));
+-  EXPECT_EQ(3, M.lookup("c"));
+-
+-  EXPECT_EQ(0, M.lookup("q"));
+-
+-  // Test the empty string, spelled various ways.
+-  EXPECT_EQ(0, M.lookup(""));
+-  EXPECT_EQ(0, M.lookup(StringRef()));
+-  EXPECT_EQ(0, M.lookup(StringRef("a", 0)));
+-  M[""] = 42;
+-  EXPECT_EQ(42, M.lookup(""));
+-  EXPECT_EQ(42, M.lookup(StringRef()));
+-  EXPECT_EQ(42, M.lookup(StringRef("a", 0)));
+-}
+-
+ // Key traits that allows lookup with either an unsigned or char* key;
+ // In the latter case, "a" == 0, "b" == 1 and so on.
+ struct TestDenseMapInfo {
+diff --git a/llvm/unittests/ADT/FunctionExtrasTest.cpp b/llvm/unittests/ADT/FunctionExtrasTest.cpp
+index fc856a976..aff9d61c7 100644
+--- a/llvm/unittests/ADT/FunctionExtrasTest.cpp
++++ b/llvm/unittests/ADT/FunctionExtrasTest.cpp
+@@ -249,23 +249,23 @@ TEST(UniqueFunctionTest, Const) {
+ 
+   // Overloaded call operator correctly resolved.
+   struct ChooseCorrectOverload {
+-    StringRef operator()() { return "non-const"; }
+-    StringRef operator()() const { return "const"; }
++    std::string_view operator()() { return "non-const"; }
++    std::string_view operator()() const { return "const"; }
+   };
+-  unique_function<StringRef()> ChooseMutable = ChooseCorrectOverload();
++  unique_function<std::string_view()> ChooseMutable = ChooseCorrectOverload();
+   ChooseCorrectOverload A;
+   EXPECT_EQ("non-const", ChooseMutable());
+   EXPECT_EQ("non-const", A());
+-  unique_function<StringRef() const> ChooseConst = ChooseCorrectOverload();
++  unique_function<std::string_view() const> ChooseConst = ChooseCorrectOverload();
+   const ChooseCorrectOverload &X = A;
+   EXPECT_EQ("const", ChooseConst());
+   EXPECT_EQ("const", X());
+ }
+ 
+ // Test that overloads on unique_functions are resolved as expected.
+-std::string returns(StringRef) { return "not a function"; }
++std::string returns(std::string_view) { return "not a function"; }
+ std::string returns(unique_function<double()> F) { return "number"; }
+-std::string returns(unique_function<StringRef()> F) { return "string"; }
++std::string returns(unique_function<std::string_view()> F) { return "string"; }
+ 
+ TEST(UniqueFunctionTest, SFINAE) {
+   EXPECT_EQ("not a function", returns("boo!"));
+diff --git a/llvm/unittests/ADT/HashingTest.cpp b/llvm/unittests/ADT/HashingTest.cpp
+index bb19a5699..0634767a4 100644
+--- a/llvm/unittests/ADT/HashingTest.cpp
++++ b/llvm/unittests/ADT/HashingTest.cpp
+@@ -277,7 +277,7 @@ TEST(HashingTest, HashCombineRangeGoldenTest) {
+ #endif
+   };
+   for (unsigned i = 0; i < sizeof(golden_data)/sizeof(*golden_data); ++i) {
+-    StringRef str = golden_data[i].s;
++    std::string_view str = golden_data[i].s;
+     hash_code hash = hash_combine_range(str.begin(), str.end());
+ #if 0 // Enable this to generate paste-able text for the above structure.
+     std::string member_str = "\"" + str.str() + "\",";
+diff --git a/llvm/unittests/ADT/SmallPtrSetTest.cpp b/llvm/unittests/ADT/SmallPtrSetTest.cpp
+index 414298c4e..6f3c94eed 100644
+--- a/llvm/unittests/ADT/SmallPtrSetTest.cpp
++++ b/llvm/unittests/ADT/SmallPtrSetTest.cpp
+@@ -12,7 +12,6 @@
+ 
+ #include "llvm/ADT/SmallPtrSet.h"
+ #include "llvm/ADT/PointerIntPair.h"
+-#include "llvm/ADT/STLExtras.h"
+ #include "llvm/Support/PointerLikeTypeTraits.h"
+ #include "gtest/gtest.h"
+ 
+diff --git a/llvm/unittests/ADT/SmallStringTest.cpp b/llvm/unittests/ADT/SmallStringTest.cpp
+index b207f582e..bee3875d1 100644
+--- a/llvm/unittests/ADT/SmallStringTest.cpp
++++ b/llvm/unittests/ADT/SmallStringTest.cpp
+@@ -50,43 +50,43 @@ TEST_F(SmallStringTest, AssignRepeated) {
+ }
+ 
+ TEST_F(SmallStringTest, AssignIterPair) {
+-  StringRef abc = "abc";
++  std::string_view abc = "abc";
+   theString.assign(abc.begin(), abc.end());
+   EXPECT_EQ(3u, theString.size());
+   EXPECT_STREQ("abc", theString.c_str());
+ }
+ 
+-TEST_F(SmallStringTest, AssignStringRef) {
+-  StringRef abc = "abc";
++TEST_F(SmallStringTest, AssignStringView) {
++  std::string_view abc = "abc";
+   theString.assign(abc);
+   EXPECT_EQ(3u, theString.size());
+   EXPECT_STREQ("abc", theString.c_str());
+ }
+ 
+ TEST_F(SmallStringTest, AssignSmallVector) {
+-  StringRef abc = "abc";
++  std::string_view abc = "abc";
+   SmallVector<char, 10> abcVec(abc.begin(), abc.end());
+   theString.assign(abcVec);
+   EXPECT_EQ(3u, theString.size());
+   EXPECT_STREQ("abc", theString.c_str());
+ }
+ 
+-TEST_F(SmallStringTest, AssignStringRefs) {
++TEST_F(SmallStringTest, AssignStringViews) {
+   theString.assign({"abc", "def", "ghi"});
+   EXPECT_EQ(9u, theString.size());
+   EXPECT_STREQ("abcdefghi", theString.c_str());
+ }
+ 
+ TEST_F(SmallStringTest, AppendIterPair) {
+-  StringRef abc = "abc";
++  std::string_view abc = "abc";
+   theString.append(abc.begin(), abc.end());
+   theString.append(abc.begin(), abc.end());
+   EXPECT_EQ(6u, theString.size());
+   EXPECT_STREQ("abcabc", theString.c_str());
+ }
+ 
+-TEST_F(SmallStringTest, AppendStringRef) {
+-  StringRef abc = "abc";
++TEST_F(SmallStringTest, AppendStringView) {
++  std::string_view abc = "abc";
+   theString.append(abc);
+   theString.append(abc);
+   EXPECT_EQ(6u, theString.size());
+@@ -94,7 +94,7 @@ TEST_F(SmallStringTest, AppendStringRef) {
+ }
+ 
+ TEST_F(SmallStringTest, AppendSmallVector) {
+-  StringRef abc = "abc";
++  std::string_view abc = "abc";
+   SmallVector<char, 10> abcVec(abc.begin(), abc.end());
+   theString.append(abcVec);
+   theString.append(abcVec);
+@@ -102,11 +102,11 @@ TEST_F(SmallStringTest, AppendSmallVector) {
+   EXPECT_STREQ("abcabc", theString.c_str());
+ }
+ 
+-TEST_F(SmallStringTest, AppendStringRefs) {
++TEST_F(SmallStringTest, AppendStringViews) {
+   theString.append({"abc", "def", "ghi"});
+   EXPECT_EQ(9u, theString.size());
+   EXPECT_STREQ("abcdefghi", theString.c_str());
+-  StringRef Jkl = "jkl";
++  std::string_view Jkl = "jkl";
+   std::string Mno = "mno";
+   SmallString<4> Pqr("pqr");
+   const char *Stu = "stu";
+@@ -115,15 +115,15 @@ TEST_F(SmallStringTest, AppendStringRefs) {
+   EXPECT_STREQ("abcdefghijklmnopqrstu", theString.c_str());
+ }
+ 
+-TEST_F(SmallStringTest, StringRefConversion) {
+-  StringRef abc = "abc";
++TEST_F(SmallStringTest, StringViewConversion) {
++  std::string_view abc = "abc";
+   theString.assign(abc.begin(), abc.end());
+-  StringRef theStringRef = theString;
+-  EXPECT_EQ("abc", theStringRef);
++  std::string_view theStringView = theString;
++  EXPECT_EQ("abc", theStringView);
+ }
+ 
+ TEST_F(SmallStringTest, StdStringConversion) {
+-  StringRef abc = "abc";
++  std::string_view abc = "abc";
+   theString.assign(abc.begin(), abc.end());
+   std::string theStdString = std::string(theString);
+   EXPECT_EQ("abc", theStdString);
+@@ -149,29 +149,29 @@ TEST_F(SmallStringTest, Slice) {
+ TEST_F(SmallStringTest, Find) {
+   theString = "hello";
+   EXPECT_EQ(2U, theString.find('l'));
+-  EXPECT_EQ(StringRef::npos, theString.find('z'));
+-  EXPECT_EQ(StringRef::npos, theString.find("helloworld"));
++  EXPECT_EQ(std::string_view::npos, theString.find('z'));
++  EXPECT_EQ(std::string_view::npos, theString.find("helloworld"));
+   EXPECT_EQ(0U, theString.find("hello"));
+   EXPECT_EQ(1U, theString.find("ello"));
+-  EXPECT_EQ(StringRef::npos, theString.find("zz"));
++  EXPECT_EQ(std::string_view::npos, theString.find("zz"));
+   EXPECT_EQ(2U, theString.find("ll", 2));
+-  EXPECT_EQ(StringRef::npos, theString.find("ll", 3));
++  EXPECT_EQ(std::string_view::npos, theString.find("ll", 3));
+   EXPECT_EQ(0U, theString.find(""));
+ 
+   EXPECT_EQ(3U, theString.rfind('l'));
+-  EXPECT_EQ(StringRef::npos, theString.rfind('z'));
+-  EXPECT_EQ(StringRef::npos, theString.rfind("helloworld"));
++  EXPECT_EQ(std::string_view::npos, theString.rfind('z'));
++  EXPECT_EQ(std::string_view::npos, theString.rfind("helloworld"));
+   EXPECT_EQ(0U, theString.rfind("hello"));
+   EXPECT_EQ(1U, theString.rfind("ello"));
+-  EXPECT_EQ(StringRef::npos, theString.rfind("zz"));
++  EXPECT_EQ(std::string_view::npos, theString.rfind("zz"));
+ 
+   EXPECT_EQ(2U, theString.find_first_of('l'));
+   EXPECT_EQ(1U, theString.find_first_of("el"));
+-  EXPECT_EQ(StringRef::npos, theString.find_first_of("xyz"));
++  EXPECT_EQ(std::string_view::npos, theString.find_first_of("xyz"));
+ 
+   EXPECT_EQ(1U, theString.find_first_not_of('h'));
+   EXPECT_EQ(4U, theString.find_first_not_of("hel"));
+-  EXPECT_EQ(StringRef::npos, theString.find_first_not_of("hello"));
++  EXPECT_EQ(std::string_view::npos, theString.find_first_not_of("hello"));
+ 
+   theString = "hellx xello hell ello world foo bar hello";
+   EXPECT_EQ(36U, theString.find("hello"));
+diff --git a/llvm/unittests/ADT/SmallVectorTest.cpp b/llvm/unittests/ADT/SmallVectorTest.cpp
+index 3fbea5299..fe827546a 100644
+--- a/llvm/unittests/ADT/SmallVectorTest.cpp
++++ b/llvm/unittests/ADT/SmallVectorTest.cpp
+@@ -11,7 +11,7 @@
+ //===----------------------------------------------------------------------===//
+ 
+ #include "llvm/ADT/SmallVector.h"
+-#include "llvm/ADT/ArrayRef.h"
++#include "llvm/ADT/span.h"
+ #include "llvm/Support/Compiler.h"
+ #include "gtest/gtest.h"
+ #include <list>
+@@ -1070,24 +1070,6 @@ TEST(SmallVectorTest, DefaultInlinedElements) {
+   EXPECT_EQ(NestedV[0][0][0], 42);
+ }
+ 
+-TEST(SmallVectorTest, InitializerList) {
+-  SmallVector<int, 2> V1 = {};
+-  EXPECT_TRUE(V1.empty());
+-  V1 = {0, 0};
+-  EXPECT_TRUE(makeArrayRef(V1).equals({0, 0}));
+-  V1 = {-1, -1};
+-  EXPECT_TRUE(makeArrayRef(V1).equals({-1, -1}));
+-
+-  SmallVector<int, 2> V2 = {1, 2, 3, 4};
+-  EXPECT_TRUE(makeArrayRef(V2).equals({1, 2, 3, 4}));
+-  V2.assign({4});
+-  EXPECT_TRUE(makeArrayRef(V2).equals({4}));
+-  V2.append({3, 2});
+-  EXPECT_TRUE(makeArrayRef(V2).equals({4, 3, 2}));
+-  V2.insert(V2.begin() + 1, 5);
+-  EXPECT_TRUE(makeArrayRef(V2).equals({4, 5, 3, 2}));
+-}
+-
+ template <class VectorT>
+ class SmallVectorReferenceInvalidationTest : public SmallVectorTestBase {
+ protected:
+diff --git a/llvm/unittests/ADT/StringMapTest.cpp b/llvm/unittests/ADT/StringMapTest.cpp
+index 817fec6c3..86907ab61 100644
+--- a/llvm/unittests/ADT/StringMapTest.cpp
++++ b/llvm/unittests/ADT/StringMapTest.cpp
+@@ -7,8 +7,6 @@
+ //===----------------------------------------------------------------------===//
+ 
+ #include "llvm/ADT/StringMap.h"
+-#include "llvm/ADT/STLExtras.h"
+-#include "llvm/ADT/Twine.h"
+ #include "llvm/Support/DataTypes.h"
+ #include "gtest/gtest.h"
+ #include <limits>
+@@ -38,10 +36,10 @@ protected:
+ 
+     // Lookup tests
+     EXPECT_EQ(0u, testMap.count(testKey));
+-    EXPECT_EQ(0u, testMap.count(StringRef(testKeyFirst, testKeyLength)));
++    EXPECT_EQ(0u, testMap.count(std::string_view(testKeyFirst, testKeyLength)));
+     EXPECT_EQ(0u, testMap.count(testKeyStr));
+     EXPECT_TRUE(testMap.find(testKey) == testMap.end());
+-    EXPECT_TRUE(testMap.find(StringRef(testKeyFirst, testKeyLength)) == 
++    EXPECT_TRUE(testMap.find(std::string_view(testKeyFirst, testKeyLength)) == 
+                 testMap.end());
+     EXPECT_TRUE(testMap.find(testKeyStr) == testMap.end());
+   }
+@@ -61,10 +59,10 @@ protected:
+ 
+     // Lookup tests
+     EXPECT_EQ(1u, testMap.count(testKey));
+-    EXPECT_EQ(1u, testMap.count(StringRef(testKeyFirst, testKeyLength)));
++    EXPECT_EQ(1u, testMap.count(std::string_view(testKeyFirst, testKeyLength)));
+     EXPECT_EQ(1u, testMap.count(testKeyStr));
+     EXPECT_TRUE(testMap.find(testKey) == testMap.begin());
+-    EXPECT_TRUE(testMap.find(StringRef(testKeyFirst, testKeyLength)) == 
++    EXPECT_TRUE(testMap.find(std::string_view(testKeyFirst, testKeyLength)) == 
+                 testMap.begin());
+     EXPECT_TRUE(testMap.find(testKeyStr) == testMap.begin());
+   }
+@@ -104,10 +102,10 @@ TEST_F(StringMapTest, ConstEmptyMapTest) {
+ 
+   // Lookup tests
+   EXPECT_EQ(0u, constTestMap.count(testKey));
+-  EXPECT_EQ(0u, constTestMap.count(StringRef(testKeyFirst, testKeyLength)));
++  EXPECT_EQ(0u, constTestMap.count(std::string_view(testKeyFirst, testKeyLength)));
+   EXPECT_EQ(0u, constTestMap.count(testKeyStr));
+   EXPECT_TRUE(constTestMap.find(testKey) == constTestMap.end());
+-  EXPECT_TRUE(constTestMap.find(StringRef(testKeyFirst, testKeyLength)) ==
++  EXPECT_TRUE(constTestMap.find(std::string_view(testKeyFirst, testKeyLength)) ==
+               constTestMap.end());
+   EXPECT_TRUE(constTestMap.find(testKeyStr) == constTestMap.end());
+ }
+@@ -235,7 +233,7 @@ TEST_F(StringMapTest, StringMapEntryTest) {
+   MallocAllocator Allocator;
+   StringMap<uint32_t>::value_type *entry =
+       StringMap<uint32_t>::value_type::Create(
+-          StringRef(testKeyFirst, testKeyLength), Allocator, 1u);
++          std::string_view(testKeyFirst, testKeyLength), Allocator, 1u);
+   EXPECT_STREQ(testKey, entry->first().data());
+   EXPECT_EQ(1u, entry->second);
+   entry->Destroy(Allocator);
+@@ -246,7 +244,7 @@ TEST_F(StringMapTest, InsertTest) {
+   SCOPED_TRACE("InsertTest");
+   testMap.insert(
+       StringMap<uint32_t>::value_type::Create(
+-          StringRef(testKeyFirst, testKeyLength),
++          std::string_view(testKeyFirst, testKeyLength),
+           testMap.getAllocator(), 1u));
+   assertSingleItemMap();
+ }
+@@ -316,10 +314,10 @@ TEST_F(StringMapTest, IterMapKeysVector) {
+   Map["C"] = 3;
+   Map["D"] = 3;
+ 
+-  std::vector<StringRef> Keys{Map.keys().begin(), Map.keys().end()};
++  std::vector<std::string_view> Keys{Map.keys().begin(), Map.keys().end()};
+   llvm::sort(Keys);
+ 
+-  std::vector<StringRef> Expected{{"A", "B", "C", "D"}};
++  std::vector<std::string_view> Expected{{"A", "B", "C", "D"}};
+   EXPECT_EQ(Expected, Keys);
+ }
+ 
+@@ -333,7 +331,7 @@ TEST_F(StringMapTest, IterMapKeysSmallVector) {
+   auto Keys = to_vector<4>(Map.keys());
+   llvm::sort(Keys);
+ 
+-  SmallVector<StringRef, 4> Expected = {"A", "B", "C", "D"};
++  SmallVector<std::string_view, 4> Expected = {"A", "B", "C", "D"};
+   EXPECT_EQ(Expected, Keys);
+ }
+ 
+@@ -375,13 +373,13 @@ private:
+ TEST_F(StringMapTest, MoveOnly) {
+   StringMap<MoveOnly> t;
+   t.insert(std::make_pair("Test", MoveOnly(42)));
+-  StringRef Key = "Test";
++  std::string_view Key = "Test";
+   StringMapEntry<MoveOnly>::Create(Key, t.getAllocator(), MoveOnly(42))
+       ->Destroy(t.getAllocator());
+ }
+ 
+ TEST_F(StringMapTest, CtorArg) {
+-  StringRef Key = "Test";
++  std::string_view Key = "Test";
+   MallocAllocator Allocator;
+   StringMapEntry<MoveOnly>::Create(Key, Allocator, Immovable())
+       ->Destroy(Allocator);
+@@ -556,7 +554,7 @@ TEST(StringMapCustomTest, InitialSizeTest) {
+     CountCtorCopyAndMove::Copy = 0;
+     for (int i = 0; i < Size; ++i)
+       Map.insert(std::pair<std::string, CountCtorCopyAndMove>(
+-          std::piecewise_construct, std::forward_as_tuple(Twine(i).str()),
++          std::piecewise_construct, std::forward_as_tuple(std::to_string(i)),
+           std::forward_as_tuple(i)));
+     // After the initial move, the map will move the Elts in the Entry.
+     EXPECT_EQ((unsigned)Size * 2, CountCtorCopyAndMove::Move);
+@@ -625,7 +623,7 @@ TEST(StringMapCustomTest, StringMapEntrySize) {
+   else
+     LargeValue = std::numeric_limits<unsigned>::max() + 1ULL;
+   StringMapEntry<int> LargeEntry(LargeValue);
+-  StringRef Key = LargeEntry.getKey();
++  std::string_view Key = LargeEntry.getKey();
+   EXPECT_EQ(LargeValue, Key.size());
+ 
+   // Test that the entry can hold at least max size_t.
+diff --git a/llvm/unittests/Support/ConvertUTFTest.cpp b/llvm/unittests/Support/ConvertUTFTest.cpp
+index 7bda6ea28..9c798437a 100644
+--- a/llvm/unittests/Support/ConvertUTFTest.cpp
++++ b/llvm/unittests/Support/ConvertUTFTest.cpp
+@@ -7,7 +7,6 @@
+ //===----------------------------------------------------------------------===//
+ 
+ #include "llvm/Support/ConvertUTF.h"
+-#include "llvm/ADT/ArrayRef.h"
+ #include "gtest/gtest.h"
+ #include <string>
+ #include <vector>
+@@ -17,7 +16,7 @@ using namespace llvm;
+ TEST(ConvertUTFTest, ConvertUTF16LittleEndianToUTF8String) {
+   // Src is the look of disapproval.
+   alignas(UTF16) static const char Src[] = "\xff\xfe\xa0\x0c_\x00\xa0\x0c";
+-  ArrayRef<char> Ref(Src, sizeof(Src) - 1);
++  span<const char> Ref(Src, sizeof(Src) - 1);
+   std::string Result;
+   bool Success = convertUTF16ToUTF8String(Ref, Result);
+   EXPECT_TRUE(Success);
+@@ -28,7 +27,7 @@ TEST(ConvertUTFTest, ConvertUTF16LittleEndianToUTF8String) {
+ TEST(ConvertUTFTest, ConvertUTF16BigEndianToUTF8String) {
+   // Src is the look of disapproval.
+   alignas(UTF16) static const char Src[] = "\xfe\xff\x0c\xa0\x00_\x0c\xa0";
+-  ArrayRef<char> Ref(Src, sizeof(Src) - 1);
++  span<const char> Ref(Src, sizeof(Src) - 1);
+   std::string Result;
+   bool Success = convertUTF16ToUTF8String(Ref, Result);
+   EXPECT_TRUE(Success);
+@@ -39,7 +38,7 @@ TEST(ConvertUTFTest, ConvertUTF16BigEndianToUTF8String) {
+ TEST(ConvertUTFTest, ConvertUTF8ToUTF16String) {
+   // Src is the look of disapproval.
+   static const char Src[] = "\xe0\xb2\xa0_\xe0\xb2\xa0";
+-  StringRef Ref(Src, sizeof(Src) - 1);
++  std::string_view Ref(Src, sizeof(Src) - 1);
+   SmallVector<UTF16, 5> Result;
+   bool Success = convertUTF8ToUTF16String(Ref, Result);
+   EXPECT_TRUE(Success);
+@@ -51,37 +50,37 @@ TEST(ConvertUTFTest, ConvertUTF8ToUTF16String) {
+ 
+ TEST(ConvertUTFTest, OddLengthInput) {
+   std::string Result;
+-  bool Success = convertUTF16ToUTF8String(makeArrayRef("xxxxx", 5), Result);
++  bool Success = convertUTF16ToUTF8String(span<const char>("xxxxx", 5), Result);
+   EXPECT_FALSE(Success);
+ }
+ 
+ TEST(ConvertUTFTest, Empty) {
+   std::string Result;
+-  bool Success = convertUTF16ToUTF8String(llvm::ArrayRef<char>(None), Result);
++  bool Success = convertUTF16ToUTF8String(span<const char>(), Result);
+   EXPECT_TRUE(Success);
+   EXPECT_TRUE(Result.empty());
+ }
+ 
+ TEST(ConvertUTFTest, HasUTF16BOM) {
+-  bool HasBOM = hasUTF16ByteOrderMark(makeArrayRef("\xff\xfe", 2));
++  bool HasBOM = hasUTF16ByteOrderMark("\xff\xfe");
+   EXPECT_TRUE(HasBOM);
+-  HasBOM = hasUTF16ByteOrderMark(makeArrayRef("\xfe\xff", 2));
++  HasBOM = hasUTF16ByteOrderMark("\xfe\xff");
+   EXPECT_TRUE(HasBOM);
+-  HasBOM = hasUTF16ByteOrderMark(makeArrayRef("\xfe\xff ", 3));
++  HasBOM = hasUTF16ByteOrderMark("\xfe\xff ");
+   EXPECT_TRUE(HasBOM); // Don't care about odd lengths.
+-  HasBOM = hasUTF16ByteOrderMark(makeArrayRef("\xfe\xff\x00asdf", 6));
++  HasBOM = hasUTF16ByteOrderMark("\xfe\xff\x00asdf");
+   EXPECT_TRUE(HasBOM);
+ 
+-  HasBOM = hasUTF16ByteOrderMark(None);
++  HasBOM = hasUTF16ByteOrderMark("");
+   EXPECT_FALSE(HasBOM);
+-  HasBOM = hasUTF16ByteOrderMark(makeArrayRef("\xfe", 1));
++  HasBOM = hasUTF16ByteOrderMark("\xfe");
+   EXPECT_FALSE(HasBOM);
+ }
+ 
+ TEST(ConvertUTFTest, UTF16WrappersForConvertUTF16ToUTF8String) {
+   // Src is the look of disapproval.
+   alignas(UTF16) static const char Src[] = "\xff\xfe\xa0\x0c_\x00\xa0\x0c";
+-  ArrayRef<UTF16> SrcRef = makeArrayRef((const UTF16 *)Src, 4);
++  span<const UTF16> SrcRef((const UTF16 *)Src, 4);
+   std::string Result;
+   bool Success = convertUTF16ToUTF8String(SrcRef, Result);
+   EXPECT_TRUE(Success);
+@@ -98,7 +97,7 @@ TEST(ConvertUTFTest, ConvertUTF8toWide) {
+   std::wstring Expected(L"\x0ca0_\x0ca0");
+   EXPECT_EQ(Expected, Result);
+   Result.clear();
+-  Success = ConvertUTF8toWide(StringRef(Src, 7), Result);
++  Success = ConvertUTF8toWide(Src, Result);
+   EXPECT_TRUE(Success);
+   EXPECT_EQ(Expected, Result);
+ }
+@@ -147,7 +146,7 @@ struct ConvertUTFResultContainer {
+ };
+ 
+ std::pair<ConversionResult, std::vector<unsigned>>
+-ConvertUTF8ToUnicodeScalarsLenient(StringRef S) {
++ConvertUTF8ToUnicodeScalarsLenient(std::string_view S) {
+   const UTF8 *SourceStart = reinterpret_cast<const UTF8 *>(S.data());
+ 
+   const UTF8 *SourceNext = SourceStart;
+@@ -164,7 +163,7 @@ ConvertUTF8ToUnicodeScalarsLenient(StringRef S) {
+ }
+ 
+ std::pair<ConversionResult, std::vector<unsigned>>
+-ConvertUTF8ToUnicodeScalarsPartialLenient(StringRef S) {
++ConvertUTF8ToUnicodeScalarsPartialLenient(std::string_view S) {
+   const UTF8 *SourceStart = reinterpret_cast<const UTF8 *>(S.data());
+ 
+   const UTF8 *SourceNext = SourceStart;
+@@ -182,7 +181,7 @@ ConvertUTF8ToUnicodeScalarsPartialLenient(StringRef S) {
+ 
+ ::testing::AssertionResult
+ CheckConvertUTF8ToUnicodeScalars(ConvertUTFResultContainer Expected,
+-                                 StringRef S, bool Partial = false) {
++                                 std::string_view S, bool Partial = false) {
+   ConversionResult ErrorCode;
+   std::vector<unsigned> Decoded;
+   if (!Partial)
+@@ -277,7 +276,7 @@ TEST(ConvertUTFTest, UTF8ToUTF32Lenient) {
+   // U+0000 NULL
+   EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+       ConvertUTFResultContainer(conversionOK).withScalars(0x0000),
+-      StringRef("\x00", 1)));
++      std::string_view("\x00", 1)));
+ 
+   // U+0080 PADDING CHARACTER
+   EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+@@ -1051,7 +1050,7 @@ TEST(ConvertUTFTest, UTF8ToUTF32Lenient) {
+   // U+0000 NULL
+   EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+       ConvertUTFResultContainer(conversionOK).withScalars(0x0000),
+-      StringRef("\x00", 1)));
++      std::string_view("\x00", 1)));
+ 
+   // Overlong sequences of the above.
+   EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
diff --git a/third_party/allwpilib/upstream_utils/llvm_patches/0003-Wrap-std-min-max-calls-in-parens-for-Windows-warning.patch b/third_party/allwpilib/upstream_utils/llvm_patches/0003-Wrap-std-min-max-calls-in-parens-for-Windows-warning.patch
new file mode 100644
index 0000000..a67e326
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/llvm_patches/0003-Wrap-std-min-max-calls-in-parens-for-Windows-warning.patch
@@ -0,0 +1,208 @@
+From 5fccde024bea117d90d215390f09c7d779195ea5 Mon Sep 17 00:00:00 2001
+From: PJ Reiniger <pj.reiniger@gmail.com>
+Date: Sat, 7 May 2022 22:12:41 -0400
+Subject: [PATCH 03/28] Wrap std::min/max calls in parens, for Windows warnings
+
+---
+ llvm/include/llvm/ADT/DenseMap.h       |  4 ++--
+ llvm/include/llvm/ADT/SmallVector.h    | 12 ++++++------
+ llvm/include/llvm/Support/ConvertUTF.h |  2 +-
+ llvm/include/llvm/Support/MathExtras.h | 22 +++++++++++-----------
+ llvm/lib/Support/SmallVector.cpp       |  2 +-
+ 5 files changed, 21 insertions(+), 21 deletions(-)
+
+diff --git a/llvm/include/llvm/ADT/DenseMap.h b/llvm/include/llvm/ADT/DenseMap.h
+index 7673b66ca..975c3b97e 100644
+--- a/llvm/include/llvm/ADT/DenseMap.h
++++ b/llvm/include/llvm/ADT/DenseMap.h
+@@ -390,7 +390,7 @@ protected:
+       return 0;
+     // +1 is required because of the strict equality.
+     // For example if NumEntries is 48, we need to return 401.
+-    return NextPowerOf2(NumEntries * 4 / 3 + 1);
++    return static_cast<unsigned>(NextPowerOf2(NumEntries * 4 / 3 + 1));
+   }
+ 
+   void moveFromOldBuckets(BucketT *OldBucketsBegin, BucketT *OldBucketsEnd) {
+@@ -826,7 +826,7 @@ public:
+     // Reduce the number of buckets.
+     unsigned NewNumBuckets = 0;
+     if (OldNumEntries)
+-      NewNumBuckets = std::max(64, 1 << (Log2_32_Ceil(OldNumEntries) + 1));
++      NewNumBuckets = (std::max)(64, 1 << (Log2_32_Ceil(OldNumEntries) + 1));
+     if (NewNumBuckets == NumBuckets) {
+       this->BaseT::initEmpty();
+       return;
+diff --git a/llvm/include/llvm/ADT/SmallVector.h b/llvm/include/llvm/ADT/SmallVector.h
+index a4a790323..8686f7bb5 100644
+--- a/llvm/include/llvm/ADT/SmallVector.h
++++ b/llvm/include/llvm/ADT/SmallVector.h
+@@ -49,12 +49,12 @@ protected:
+ 
+   /// The maximum value of the Size_T used.
+   static constexpr size_t SizeTypeMax() {
+-    return std::numeric_limits<Size_T>::max();
++    return (std::numeric_limits<Size_T>::max)();
+   }
+ 
+   SmallVectorBase() = delete;
+   SmallVectorBase(void *FirstEl, size_t TotalCapacity)
+-      : BeginX(FirstEl), Capacity(TotalCapacity) {}
++      : BeginX(FirstEl), Capacity(static_cast<unsigned>(TotalCapacity)) {}
+ 
+   /// This is a helper for \a grow() that's out of line to reduce code
+   /// duplication.  This function will report a fatal error if it can't grow at
+@@ -79,7 +79,7 @@ protected:
+   /// This does not construct or destroy any elements in the vector.
+   void set_size(size_t N) {
+     assert(N <= capacity());
+-    Size = N;
++    Size = static_cast<unsigned>(N);
+   }
+ };
+ 
+@@ -259,7 +259,7 @@ public:
+ 
+   size_type size_in_bytes() const { return size() * sizeof(T); }
+   size_type max_size() const {
+-    return std::min(this->SizeTypeMax(), size_type(-1) / sizeof(T));
++    return (std::min)(this->SizeTypeMax(), size_type(-1) / sizeof(T));
+   }
+ 
+   size_t capacity_in_bytes() const { return capacity() * sizeof(T); }
+@@ -444,7 +444,7 @@ void SmallVectorTemplateBase<T, TriviallyCopyable>::takeAllocationForGrow(
+     free(this->begin());
+ 
+   this->BeginX = NewElts;
+-  this->Capacity = NewCapacity;
++  this->Capacity = static_cast<unsigned>(NewCapacity);
+ }
+ 
+ /// SmallVectorTemplateBase<TriviallyCopyable = true> - This is where we put
+@@ -693,7 +693,7 @@ public:
+     }
+ 
+     // Assign over existing elements.
+-    std::fill_n(this->begin(), std::min(NumElts, this->size()), Elt);
++    std::fill_n(this->begin(), (std::min)(NumElts, this->size()), Elt);
+     if (NumElts > this->size())
+       std::uninitialized_fill_n(this->end(), NumElts - this->size(), Elt);
+     else if (NumElts < this->size())
+diff --git a/llvm/include/llvm/Support/ConvertUTF.h b/llvm/include/llvm/Support/ConvertUTF.h
+index 7f1527f51..b085c8a17 100644
+--- a/llvm/include/llvm/Support/ConvertUTF.h
++++ b/llvm/include/llvm/Support/ConvertUTF.h
+@@ -112,7 +112,7 @@ namespace llvm {
+ typedef unsigned int    UTF32;  /* at least 32 bits */
+ typedef unsigned short  UTF16;  /* at least 16 bits */
+ typedef unsigned char   UTF8;   /* typically 8 bits */
+-typedef unsigned char   Boolean; /* 0 or 1 */
++typedef bool   Boolean; /* 0 or 1 */
+ 
+ /* Some fundamental constants */
+ #define UNI_REPLACEMENT_CHAR (UTF32)0x0000FFFD
+diff --git a/llvm/include/llvm/Support/MathExtras.h b/llvm/include/llvm/Support/MathExtras.h
+index 753b1998c..db9fbc148 100644
+--- a/llvm/include/llvm/Support/MathExtras.h
++++ b/llvm/include/llvm/Support/MathExtras.h
+@@ -97,7 +97,7 @@ template <typename T, std::size_t SizeOfT> struct TrailingZerosCounter {
+     // Bisection method.
+     unsigned ZeroBits = 0;
+     T Shift = std::numeric_limits<T>::digits >> 1;
+-    T Mask = std::numeric_limits<T>::max() >> Shift;
++    T Mask = (std::numeric_limits<T>::max)() >> Shift;
+     while (Shift) {
+       if ((Val & Mask) == 0) {
+         Val >>= Shift;
+@@ -238,7 +238,7 @@ unsigned countLeadingZeros(T Val, ZeroBehavior ZB = ZB_Width) {
+ ///   valid arguments.
+ template <typename T> T findFirstSet(T Val, ZeroBehavior ZB = ZB_Max) {
+   if (ZB == ZB_Max && Val == 0)
+-    return std::numeric_limits<T>::max();
++    return (std::numeric_limits<T>::max)();
+ 
+   return countTrailingZeros(Val, ZB_Undefined);
+ }
+@@ -279,7 +279,7 @@ template <typename T> T maskLeadingZeros(unsigned N) {
+ ///   valid arguments.
+ template <typename T> T findLastSet(T Val, ZeroBehavior ZB = ZB_Max) {
+   if (ZB == ZB_Max && Val == 0)
+-    return std::numeric_limits<T>::max();
++    return (std::numeric_limits<T>::max)();
+ 
+   // Use ^ instead of - because both gcc and llvm can remove the associated ^
+   // in the __builtin_clz intrinsic on x86.
+@@ -594,26 +594,26 @@ inline double Log2(double Value) {
+ /// (32 bit edition.)
+ /// Ex. Log2_32(32) == 5, Log2_32(1) == 0, Log2_32(0) == -1, Log2_32(6) == 2
+ inline unsigned Log2_32(uint32_t Value) {
+-  return 31 - countLeadingZeros(Value);
++  return static_cast<unsigned>(31 - countLeadingZeros(Value));
+ }
+ 
+ /// Return the floor log base 2 of the specified value, -1 if the value is zero.
+ /// (64 bit edition.)
+ inline unsigned Log2_64(uint64_t Value) {
+-  return 63 - countLeadingZeros(Value);
++  return static_cast<unsigned>(63 - countLeadingZeros(Value));
+ }
+ 
+ /// Return the ceil log base 2 of the specified value, 32 if the value is zero.
+ /// (32 bit edition).
+ /// Ex. Log2_32_Ceil(32) == 5, Log2_32_Ceil(1) == 0, Log2_32_Ceil(6) == 3
+ inline unsigned Log2_32_Ceil(uint32_t Value) {
+-  return 32 - countLeadingZeros(Value - 1);
++  return static_cast<unsigned>(32 - countLeadingZeros(Value - 1));
+ }
+ 
+ /// Return the ceil log base 2 of the specified value, 64 if the value is zero.
+ /// (64 bit edition.)
+ inline unsigned Log2_64_Ceil(uint64_t Value) {
+-  return 64 - countLeadingZeros(Value - 1);
++  return static_cast<unsigned>(64 - countLeadingZeros(Value - 1));
+ }
+ 
+ /// Return the greatest common divisor of the values using Euclid's algorithm.
+@@ -807,7 +807,7 @@ SaturatingAdd(T X, T Y, bool *ResultOverflowed = nullptr) {
+   T Z = X + Y;
+   Overflowed = (Z < X || Z < Y);
+   if (Overflowed)
+-    return std::numeric_limits<T>::max();
++    return (std::numeric_limits<T>::max)();
+   else
+     return Z;
+ }
+@@ -832,7 +832,7 @@ SaturatingMultiply(T X, T Y, bool *ResultOverflowed = nullptr) {
+   // Special case: if X or Y is 0, Log2_64 gives -1, and Log2Z
+   // will necessarily be less than Log2Max as desired.
+   int Log2Z = Log2_64(X) + Log2_64(Y);
+-  const T Max = std::numeric_limits<T>::max();
++  const T Max = (std::numeric_limits<T>::max)();
+   int Log2Max = Log2_64(Max);
+   if (Log2Z < Log2Max) {
+     return X * Y;
+@@ -952,9 +952,9 @@ std::enable_if_t<std::is_signed<T>::value, T> MulOverflow(T X, T Y, T &Result) {
+   // Check how the max allowed absolute value (2^n for negative, 2^(n-1) for
+   // positive) divided by an argument compares to the other.
+   if (IsNegative)
+-    return UX > (static_cast<U>(std::numeric_limits<T>::max()) + U(1)) / UY;
++    return UX > (static_cast<U>((std::numeric_limits<T>::max)()) + U(1)) / UY;
+   else
+-    return UX > (static_cast<U>(std::numeric_limits<T>::max())) / UY;
++    return UX > (static_cast<U>((std::numeric_limits<T>::max)())) / UY;
+ }
+ 
+ } // End llvm namespace
+diff --git a/llvm/lib/Support/SmallVector.cpp b/llvm/lib/Support/SmallVector.cpp
+index 8bad715e4..a2b4899e1 100644
+--- a/llvm/lib/Support/SmallVector.cpp
++++ b/llvm/lib/Support/SmallVector.cpp
+@@ -104,7 +104,7 @@ static size_t getNewCapacity(size_t MinSize, size_t TSize, size_t OldCapacity) {
+   // In theory 2*capacity can overflow if the capacity is 64 bit, but the
+   // original capacity would never be large enough for this to be a problem.
+   size_t NewCapacity = 2 * OldCapacity + 1; // Always grow.
+-  return std::min(std::max(NewCapacity, MinSize), MaxSize);
++  return (std::min)((std::max)(NewCapacity, MinSize), MaxSize);
+ }
+ 
+ // Note: Moving this function into the header may cause performance regression.
diff --git a/third_party/allwpilib/upstream_utils/llvm_patches/0004-Change-unique_function-storage-size.patch b/third_party/allwpilib/upstream_utils/llvm_patches/0004-Change-unique_function-storage-size.patch
new file mode 100644
index 0000000..6e57262
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/llvm_patches/0004-Change-unique_function-storage-size.patch
@@ -0,0 +1,31 @@
+From 376285281b6173ee3d6650d71148bc173e4a9f7a Mon Sep 17 00:00:00 2001
+From: PJ Reiniger <pj.reiniger@gmail.com>
+Date: Sat, 7 May 2022 22:13:55 -0400
+Subject: [PATCH 04/28] Change unique_function storage size
+
+---
+ llvm/include/llvm/ADT/FunctionExtras.h | 4 ++--
+ 1 file changed, 2 insertions(+), 2 deletions(-)
+
+diff --git a/llvm/include/llvm/ADT/FunctionExtras.h b/llvm/include/llvm/ADT/FunctionExtras.h
+index 5a37417dd..8a9d78f41 100644
+--- a/llvm/include/llvm/ADT/FunctionExtras.h
++++ b/llvm/include/llvm/ADT/FunctionExtras.h
+@@ -78,7 +78,7 @@ using EnableIfCallable = std::enable_if_t<llvm::disjunction<
+ 
+ template <typename ReturnT, typename... ParamTs> class UniqueFunctionBase {
+ protected:
+-  static constexpr size_t InlineStorageSize = sizeof(void *) * 3;
++  static constexpr size_t InlineStorageSize = sizeof(void *) * 4;
+ 
+   template <typename T, class = void>
+   struct IsSizeLessThanThresholdT : std::false_type {};
+@@ -157,7 +157,7 @@ protected:
+         "Should always use all of the out-of-line storage for inline storage!");
+ 
+     // For in-line storage, we just provide an aligned character buffer. We
+-    // provide three pointers worth of storage here.
++    // provide four pointers worth of storage here.
+     // This is mutable as an inlined `const unique_function<void() const>` may
+     // still modify its own mutable members.
+     mutable
diff --git a/third_party/allwpilib/upstream_utils/llvm_patches/0005-Threading-updates.patch b/third_party/allwpilib/upstream_utils/llvm_patches/0005-Threading-updates.patch
new file mode 100644
index 0000000..1ccd217
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/llvm_patches/0005-Threading-updates.patch
@@ -0,0 +1,185 @@
+From bc86b62f72cbb76a0911996f4b1c6ce476cd1fac Mon Sep 17 00:00:00 2001
+From: PJ Reiniger <pj.reiniger@gmail.com>
+Date: Sat, 7 May 2022 22:17:19 -0400
+Subject: [PATCH 05/28] Threading updates
+
+- Remove guards for threads and exception
+- Prefer scope gaurd over lock gaurd
+---
+ llvm/include/llvm/Support/Compiler.h |  6 -----
+ llvm/lib/Support/ErrorHandling.cpp   | 38 +++++-----------------------
+ llvm/lib/Support/ManagedStatic.cpp   | 10 ++++----
+ 3 files changed, 11 insertions(+), 43 deletions(-)
+
+diff --git a/llvm/include/llvm/Support/Compiler.h b/llvm/include/llvm/Support/Compiler.h
+index f5d726ec8..ede1cb172 100644
+--- a/llvm/include/llvm/Support/Compiler.h
++++ b/llvm/include/llvm/Support/Compiler.h
+@@ -540,7 +540,6 @@ void AnnotateIgnoreWritesEnd(const char *file, int line);
+ /// initialize to some constant value. In almost all circumstances this is most
+ /// appropriate for use with a pointer, integer, or small aggregation of
+ /// pointers and integers.
+-#if LLVM_ENABLE_THREADS
+ #if __has_feature(cxx_thread_local) || defined(_MSC_VER)
+ #define LLVM_THREAD_LOCAL thread_local
+ #else
+@@ -548,11 +547,6 @@ void AnnotateIgnoreWritesEnd(const char *file, int line);
+ // we only need the restricted functionality that provides.
+ #define LLVM_THREAD_LOCAL __thread
+ #endif
+-#else // !LLVM_ENABLE_THREADS
+-// If threading is disabled entirely, this compiles to nothing and you get
+-// a normal global variable.
+-#define LLVM_THREAD_LOCAL
+-#endif
+ 
+ /// \macro LLVM_ENABLE_EXCEPTIONS
+ /// Whether LLVM is built with exception support.
+diff --git a/llvm/lib/Support/ErrorHandling.cpp b/llvm/lib/Support/ErrorHandling.cpp
+index 8ae8fb8b4..89440b5ab 100644
+--- a/llvm/lib/Support/ErrorHandling.cpp
++++ b/llvm/lib/Support/ErrorHandling.cpp
+@@ -44,7 +44,6 @@ static void *ErrorHandlerUserData = nullptr;
+ static fatal_error_handler_t BadAllocErrorHandler = nullptr;
+ static void *BadAllocErrorHandlerUserData = nullptr;
+ 
+-#if LLVM_ENABLE_THREADS == 1
+ // Mutexes to synchronize installing error handlers and calling error handlers.
+ // Do not use ManagedStatic, or that may allocate memory while attempting to
+ // report an OOM.
+@@ -58,22 +57,17 @@ static void *BadAllocErrorHandlerUserData = nullptr;
+ // builds. We can remove these ifdefs if that script goes away.
+ static std::mutex ErrorHandlerMutex;
+ static std::mutex BadAllocErrorHandlerMutex;
+-#endif
+ 
+ void llvm::install_fatal_error_handler(fatal_error_handler_t handler,
+                                        void *user_data) {
+-#if LLVM_ENABLE_THREADS == 1
+-  std::lock_guard<std::mutex> Lock(ErrorHandlerMutex);
+-#endif
++  std::scoped_lock Lock(ErrorHandlerMutex);
+   assert(!ErrorHandler && "Error handler already registered!\n");
+   ErrorHandler = handler;
+   ErrorHandlerUserData = user_data;
+ }
+ 
+ void llvm::remove_fatal_error_handler() {
+-#if LLVM_ENABLE_THREADS == 1
+-  std::lock_guard<std::mutex> Lock(ErrorHandlerMutex);
+-#endif
++  std::scoped_lock Lock(ErrorHandlerMutex);
+   ErrorHandler = nullptr;
+   ErrorHandlerUserData = nullptr;
+ }
+@@ -92,9 +86,7 @@ void llvm::report_fatal_error(std::string_view Reason, bool GenCrashDiag) {
+   {
+     // Only acquire the mutex while reading the handler, so as not to invoke a
+     // user-supplied callback under a lock.
+-#if LLVM_ENABLE_THREADS == 1
+-    std::lock_guard<std::mutex> Lock(ErrorHandlerMutex);
+-#endif
++    std::scoped_lock Lock(ErrorHandlerMutex);
+     handler = ErrorHandler;
+     handlerData = ErrorHandlerUserData;
+   }
+@@ -123,18 +115,14 @@ void llvm::report_fatal_error(std::string_view Reason, bool GenCrashDiag) {
+ 
+ void llvm::install_bad_alloc_error_handler(fatal_error_handler_t handler,
+                                            void *user_data) {
+-#if LLVM_ENABLE_THREADS == 1
+-  std::lock_guard<std::mutex> Lock(BadAllocErrorHandlerMutex);
+-#endif
++  std::scoped_lock Lock(BadAllocErrorHandlerMutex);
+   assert(!ErrorHandler && "Bad alloc error handler already registered!\n");
+   BadAllocErrorHandler = handler;
+   BadAllocErrorHandlerUserData = user_data;
+ }
+ 
+ void llvm::remove_bad_alloc_error_handler() {
+-#if LLVM_ENABLE_THREADS == 1
+-  std::lock_guard<std::mutex> Lock(BadAllocErrorHandlerMutex);
+-#endif
++  std::scoped_lock Lock(BadAllocErrorHandlerMutex);
+   BadAllocErrorHandler = nullptr;
+   BadAllocErrorHandlerUserData = nullptr;
+ }
+@@ -145,9 +133,7 @@ void llvm::report_bad_alloc_error(const char *Reason, bool GenCrashDiag) {
+   {
+     // Only acquire the mutex while reading the handler, so as not to invoke a
+     // user-supplied callback under a lock.
+-#if LLVM_ENABLE_THREADS == 1
+-    std::lock_guard<std::mutex> Lock(BadAllocErrorHandlerMutex);
+-#endif
++    std::scoped_lock Lock(BadAllocErrorHandlerMutex);
+     Handler = BadAllocErrorHandler;
+     HandlerData = BadAllocErrorHandlerUserData;
+   }
+@@ -157,10 +143,6 @@ void llvm::report_bad_alloc_error(const char *Reason, bool GenCrashDiag) {
+     llvm_unreachable("bad alloc handler should not return");
+   }
+ 
+-#ifdef LLVM_ENABLE_EXCEPTIONS
+-  // If exceptions are enabled, make OOM in malloc look like OOM in new.
+-  throw std::bad_alloc();
+-#else
+   // Don't call the normal error handler. It may allocate memory. Directly write
+   // an OOM to stderr and abort.
+   const char *OOMMessage = "LLVM ERROR: out of memory\n";
+@@ -169,15 +151,8 @@ void llvm::report_bad_alloc_error(const char *Reason, bool GenCrashDiag) {
+   (void)!::write(2, Reason, strlen(Reason));
+   (void)!::write(2, Newline, strlen(Newline));
+   abort();
+-#endif
+ }
+ 
+-#ifdef LLVM_ENABLE_EXCEPTIONS
+-// Do not set custom new handler if exceptions are enabled. In this case OOM
+-// errors are handled by throwing 'std::bad_alloc'.
+-void llvm::install_out_of_memory_new_handler() {
+-}
+-#else
+ // Causes crash on allocation failure. It is called prior to the handler set by
+ // 'install_bad_alloc_error_handler'.
+ static void out_of_memory_new_handler() {
+@@ -192,7 +167,6 @@ void llvm::install_out_of_memory_new_handler() {
+   assert((old == nullptr || old == out_of_memory_new_handler) &&
+          "new-handler already installed");
+ }
+-#endif
+ 
+ void llvm::llvm_unreachable_internal(const char *msg, const char *file,
+                                      unsigned line) {
+diff --git a/llvm/lib/Support/ManagedStatic.cpp b/llvm/lib/Support/ManagedStatic.cpp
+index a6ae67066..fc798b7ec 100644
+--- a/llvm/lib/Support/ManagedStatic.cpp
++++ b/llvm/lib/Support/ManagedStatic.cpp
+@@ -12,23 +12,23 @@
+ 
+ #include "llvm/Support/ManagedStatic.h"
+ #include "llvm/Config/config.h"
+-#include "llvm/Support/Threading.h"
++#include "llvm/Support/mutex.h"
+ #include <cassert>
+ #include <mutex>
+ using namespace llvm;
+ 
+ static const ManagedStaticBase *StaticList = nullptr;
+ 
+-static std::recursive_mutex *getManagedStaticMutex() {
+-  static std::recursive_mutex m;
++static llvm::mutex *getManagedStaticMutex() {
++  static llvm::mutex m;
+   return &m;
+ }
+ 
+ void ManagedStaticBase::RegisterManagedStatic(void *(*Creator)(),
+                                               void (*Deleter)(void*)) const {
+   assert(Creator);
+-  if (llvm_is_multithreaded()) {
+-    std::lock_guard<std::recursive_mutex> Lock(*getManagedStaticMutex());
++  if (1) {
++    std::scoped_lock Lock(*getManagedStaticMutex());
+ 
+     if (!Ptr.load(std::memory_order_relaxed)) {
+       void *Tmp = Creator();
diff --git a/third_party/allwpilib/upstream_utils/llvm_patches/0006-ifdef-guard-safety.patch b/third_party/allwpilib/upstream_utils/llvm_patches/0006-ifdef-guard-safety.patch
new file mode 100644
index 0000000..bcb4950
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/llvm_patches/0006-ifdef-guard-safety.patch
@@ -0,0 +1,341 @@
+From 008e921f77933f475174d74a6b70309c6fbe0771 Mon Sep 17 00:00:00 2001
+From: PJ Reiniger <pj.reiniger@gmail.com>
+Date: Sat, 7 May 2022 22:28:13 -0400
+Subject: [PATCH 06/28] \#ifdef guard safety
+
+Prevents redefinition if someone is pulling in real LLVM, since the macros are in global namespace
+---
+ llvm/include/llvm/Support/Compiler.h | 50 ++++++++++++++++++++++++++++
+ 1 file changed, 50 insertions(+)
+
+diff --git a/llvm/include/llvm/Support/Compiler.h b/llvm/include/llvm/Support/Compiler.h
+index ede1cb172..8b8260b50 100644
+--- a/llvm/include/llvm/Support/Compiler.h
++++ b/llvm/include/llvm/Support/Compiler.h
+@@ -86,6 +86,7 @@
+ /// * 1928: VS2019, version 16.8 + 16.9
+ /// * 1929: VS2019, version 16.10 + 16.11
+ /// * 1930: VS2022, version 17.0
++#ifndef LLVM_MSC_PREREQ
+ #ifdef _MSC_VER
+ #define LLVM_MSC_PREREQ(version) (_MSC_VER >= (version))
+ 
+@@ -99,6 +100,7 @@
+ #else
+ #define LLVM_MSC_PREREQ(version) 0
+ #endif
++#endif
+ 
+ /// Does the compiler support ref-qualifiers for *this?
+ ///
+@@ -112,11 +114,13 @@
+ ///
+ /// This can be used to provide lvalue/rvalue overrides of member functions.
+ /// The rvalue override should be guarded by LLVM_HAS_RVALUE_REFERENCE_THIS
++#ifndef LLVM_LVALUE_FUNCTION
+ #if LLVM_HAS_RVALUE_REFERENCE_THIS
+ #define LLVM_LVALUE_FUNCTION &
+ #else
+ #define LLVM_LVALUE_FUNCTION
+ #endif
++#endif
+ 
+ /// LLVM_LIBRARY_VISIBILITY - If a class marked with this attribute is linked
+ /// into a shared library, then the class should be private to the library and
+@@ -140,21 +144,26 @@
+ #define LLVM_EXTERNAL_VISIBILITY
+ #endif
+ 
++#ifndef LLVM_PREFETCH
+ #if defined(__GNUC__)
+ #define LLVM_PREFETCH(addr, rw, locality) __builtin_prefetch(addr, rw, locality)
+ #else
+ #define LLVM_PREFETCH(addr, rw, locality)
+ #endif
++#endif
+ 
++#ifndef LLVM_ATTRIBUTE_USED
+ #if __has_attribute(used)
+ #define LLVM_ATTRIBUTE_USED __attribute__((__used__))
+ #else
+ #define LLVM_ATTRIBUTE_USED
+ #endif
++#endif
+ 
+ /// LLVM_NODISCARD - Warn if a type or return value is discarded.
+ 
+ // Use the 'nodiscard' attribute in C++17 or newer mode.
++#ifndef LLVM_NODISCARD
+ #if defined(__cplusplus) && __cplusplus > 201402L && LLVM_HAS_CPP_ATTRIBUTE(nodiscard)
+ #define LLVM_NODISCARD [[nodiscard]]
+ #elif LLVM_HAS_CPP_ATTRIBUTE(clang::warn_unused_result)
+@@ -168,6 +177,7 @@
+ #else
+ #define LLVM_NODISCARD
+ #endif
++#endif
+ 
+ // Indicate that a non-static, non-const C++ member function reinitializes
+ // the entire object to a known state, independent of the previous state of
+@@ -190,11 +200,13 @@
+ // more portable solution:
+ //   (void)unused_var_name;
+ // Prefer cast-to-void wherever it is sufficient.
++#ifndef LLVM_ATTRIBUTE_UNUSED
+ #if __has_attribute(unused)
+ #define LLVM_ATTRIBUTE_UNUSED __attribute__((__unused__))
+ #else
+ #define LLVM_ATTRIBUTE_UNUSED
+ #endif
++#endif
+ 
+ // FIXME: Provide this for PE/COFF targets.
+ #if __has_attribute(weak) && !defined(__MINGW32__) && !defined(__CYGWIN__) &&  \
+@@ -204,6 +216,7 @@
+ #define LLVM_ATTRIBUTE_WEAK
+ #endif
+ 
++#ifndef LLVM_READNONE
+ // Prior to clang 3.2, clang did not accept any spelling of
+ // __has_attribute(const), so assume it is supported.
+ #if defined(__clang__) || defined(__GNUC__)
+@@ -212,13 +225,16 @@
+ #else
+ #define LLVM_READNONE
+ #endif
++#endif
+ 
++#ifndef LLVM_READONLY
+ #if __has_attribute(pure) || defined(__GNUC__)
+ // aka 'PURE' but following LLVM Conventions.
+ #define LLVM_READONLY __attribute__((__pure__))
+ #else
+ #define LLVM_READONLY
+ #endif
++#endif
+ 
+ #if __has_attribute(minsize)
+ #define LLVM_ATTRIBUTE_MINSIZE __attribute__((minsize))
+@@ -226,6 +242,7 @@
+ #define LLVM_ATTRIBUTE_MINSIZE
+ #endif
+ 
++#ifndef LLVM_LIKELY
+ #if __has_builtin(__builtin_expect) || defined(__GNUC__)
+ #define LLVM_LIKELY(EXPR) __builtin_expect((bool)(EXPR), true)
+ #define LLVM_UNLIKELY(EXPR) __builtin_expect((bool)(EXPR), false)
+@@ -233,9 +250,11 @@
+ #define LLVM_LIKELY(EXPR) (EXPR)
+ #define LLVM_UNLIKELY(EXPR) (EXPR)
+ #endif
++#endif
+ 
+ /// LLVM_ATTRIBUTE_NOINLINE - On compilers where we have a directive to do so,
+ /// mark a method "not for inlining".
++#ifndef LLVM_ATTRIBUTE_NOINLINE
+ #if __has_attribute(noinline)
+ #define LLVM_ATTRIBUTE_NOINLINE __attribute__((noinline))
+ #elif defined(_MSC_VER)
+@@ -243,9 +262,11 @@
+ #else
+ #define LLVM_ATTRIBUTE_NOINLINE
+ #endif
++#endif
+ 
+ /// LLVM_ATTRIBUTE_ALWAYS_INLINE - On compilers where we have a directive to do
+ /// so, mark a method "always inline" because it is performance sensitive.
++#ifndef LLVM_ATTRIBUTE_ALWAYS_INLINE
+ #if __has_attribute(always_inline)
+ #define LLVM_ATTRIBUTE_ALWAYS_INLINE inline __attribute__((always_inline))
+ #elif defined(_MSC_VER)
+@@ -253,6 +274,7 @@
+ #else
+ #define LLVM_ATTRIBUTE_ALWAYS_INLINE inline
+ #endif
++#endif
+ 
+ /// LLVM_ATTRIBUTE_NO_DEBUG - On compilers where we have a directive to do
+ /// so, mark a method "no debug" because debug info makes the debugger
+@@ -263,6 +285,7 @@
+ #define LLVM_ATTRIBUTE_NODEBUG
+ #endif
+ 
++#ifndef LLVM_ATTRIBUTE_RETURNS_NONNULL
+ #if __has_attribute(returns_nonnull)
+ #define LLVM_ATTRIBUTE_RETURNS_NONNULL __attribute__((returns_nonnull))
+ #elif defined(_MSC_VER)
+@@ -270,9 +293,11 @@
+ #else
+ #define LLVM_ATTRIBUTE_RETURNS_NONNULL
+ #endif
++#endif
+ 
+ /// \macro LLVM_ATTRIBUTE_RETURNS_NOALIAS Used to mark a function as returning a
+ /// pointer that does not alias any other valid pointer.
++#ifndef LLVM_ATTRIBUTE_RETURNS_NOALIAS
+ #ifdef __GNUC__
+ #define LLVM_ATTRIBUTE_RETURNS_NOALIAS __attribute__((__malloc__))
+ #elif defined(_MSC_VER)
+@@ -280,8 +305,10 @@
+ #else
+ #define LLVM_ATTRIBUTE_RETURNS_NOALIAS
+ #endif
++#endif
+ 
+ /// LLVM_FALLTHROUGH - Mark fallthrough cases in switch statements.
++#ifndef LLVM_FALLTHROUGH
+ #if defined(__cplusplus) && __cplusplus > 201402L && LLVM_HAS_CPP_ATTRIBUTE(fallthrough)
+ #define LLVM_FALLTHROUGH [[fallthrough]]
+ #elif LLVM_HAS_CPP_ATTRIBUTE(gnu::fallthrough)
+@@ -293,6 +320,7 @@
+ #else
+ #define LLVM_FALLTHROUGH
+ #endif
++#endif
+ 
+ /// LLVM_REQUIRE_CONSTANT_INITIALIZATION - Apply this to globals to ensure that
+ /// they are constant initialized.
+@@ -321,20 +349,25 @@
+ 
+ /// LLVM_EXTENSION - Support compilers where we have a keyword to suppress
+ /// pedantic diagnostics.
++#ifndef LLVM_EXTENSION
+ #ifdef __GNUC__
+ #define LLVM_EXTENSION __extension__
+ #else
+ #define LLVM_EXTENSION
+ #endif
++#endif
+ 
+ // LLVM_ATTRIBUTE_DEPRECATED(decl, "message")
+ // This macro will be removed.
+ // Use C++14's attribute instead: [[deprecated("message")]]
++#ifndef LLVM_ATTRIBUTE_DEPRECATED
+ #define LLVM_ATTRIBUTE_DEPRECATED(decl, message) [[deprecated(message)]] decl
++#endif
+ 
+ /// LLVM_BUILTIN_UNREACHABLE - On compilers which support it, expands
+ /// to an expression which states that it is undefined behavior for the
+ /// compiler to reach this point.  Otherwise is not defined.
++#ifndef LLVM_BUILTIN_UNREACHABLE
+ #if __has_builtin(__builtin_unreachable) || defined(__GNUC__)
+ # define LLVM_BUILTIN_UNREACHABLE __builtin_unreachable()
+ #elif defined(_MSC_VER)
+@@ -342,9 +375,11 @@
+ #else
+ # define LLVM_BUILTIN_UNREACHABLE
+ #endif
++#endif
+ 
+ /// LLVM_BUILTIN_TRAP - On compilers which support it, expands to an expression
+ /// which causes the program to exit abnormally.
++#ifndef LLVM_BUILTIN_TRAP
+ #if __has_builtin(__builtin_trap) || defined(__GNUC__)
+ # define LLVM_BUILTIN_TRAP __builtin_trap()
+ #elif defined(_MSC_VER)
+@@ -356,10 +391,12 @@
+ #else
+ # define LLVM_BUILTIN_TRAP *(volatile int*)0x11 = 0
+ #endif
++#endif
+ 
+ /// LLVM_BUILTIN_DEBUGTRAP - On compilers which support it, expands to
+ /// an expression which causes the program to break while running
+ /// under a debugger.
++#ifndef LLVM_BUILTIN_DEBUGTRAP
+ #if __has_builtin(__builtin_debugtrap)
+ # define LLVM_BUILTIN_DEBUGTRAP __builtin_debugtrap()
+ #elif defined(_MSC_VER)
+@@ -373,9 +410,11 @@
+ // program to abort if encountered.
+ # define LLVM_BUILTIN_DEBUGTRAP
+ #endif
++#endif
+ 
+ /// \macro LLVM_ASSUME_ALIGNED
+ /// Returns a pointer with an assumed alignment.
++#ifndef LLVM_ASSUME_ALIGNED
+ #if __has_builtin(__builtin_assume_aligned) || defined(__GNUC__)
+ # define LLVM_ASSUME_ALIGNED(p, a) __builtin_assume_aligned(p, a)
+ #elif defined(LLVM_BUILTIN_UNREACHABLE)
+@@ -384,6 +423,7 @@
+ #else
+ # define LLVM_ASSUME_ALIGNED(p, a) (p)
+ #endif
++#endif
+ 
+ /// \macro LLVM_PACKED
+ /// Used to specify a packed structure.
+@@ -403,6 +443,7 @@
+ ///   long long l;
+ /// };
+ /// LLVM_PACKED_END
++#ifndef LLVM_PACKED
+ #ifdef _MSC_VER
+ # define LLVM_PACKED(d) __pragma(pack(push, 1)) d __pragma(pack(pop))
+ # define LLVM_PACKED_START __pragma(pack(push, 1))
+@@ -412,11 +453,13 @@
+ # define LLVM_PACKED_START _Pragma("pack(push, 1)")
+ # define LLVM_PACKED_END   _Pragma("pack(pop)")
+ #endif
++#endif
+ 
+ /// \macro LLVM_PTR_SIZE
+ /// A constant integer equivalent to the value of sizeof(void*).
+ /// Generally used in combination with alignas or when doing computation in the
+ /// preprocessor.
++#ifndef LLVM_PTR_SIZE
+ #ifdef __SIZEOF_POINTER__
+ # define LLVM_PTR_SIZE __SIZEOF_POINTER__
+ #elif defined(_WIN64)
+@@ -428,6 +471,7 @@
+ #else
+ # define LLVM_PTR_SIZE sizeof(void *)
+ #endif
++#endif
+ 
+ /// \macro LLVM_MEMORY_SANITIZER_BUILD
+ /// Whether LLVM itself is built with MemorySanitizer instrumentation.
+@@ -498,11 +542,13 @@ void AnnotateIgnoreWritesEnd(const char *file, int line);
+ 
+ /// \macro LLVM_NO_SANITIZE
+ /// Disable a particular sanitizer for a function.
++#ifndef LLVM_NO_SANITIZE
+ #if __has_attribute(no_sanitize)
+ #define LLVM_NO_SANITIZE(KIND) __attribute__((no_sanitize(KIND)))
+ #else
+ #define LLVM_NO_SANITIZE(KIND)
+ #endif
++#endif
+ 
+ /// Mark debug helper function definitions like dump() that should not be
+ /// stripped from debug builds.
+@@ -510,17 +556,20 @@ void AnnotateIgnoreWritesEnd(const char *file, int line);
+ /// `#if !defined(NDEBUG) || defined(LLVM_ENABLE_DUMP)` so they do always
+ /// get stripped in release builds.
+ // FIXME: Move this to a private config.h as it's not usable in public headers.
++#ifndef LLVM_DUMP_METHOD
+ #if !defined(NDEBUG) || defined(LLVM_ENABLE_DUMP)
+ #define LLVM_DUMP_METHOD LLVM_ATTRIBUTE_NOINLINE LLVM_ATTRIBUTE_USED
+ #else
+ #define LLVM_DUMP_METHOD LLVM_ATTRIBUTE_NOINLINE
+ #endif
++#endif
+ 
+ /// \macro LLVM_PRETTY_FUNCTION
+ /// Gets a user-friendly looking function signature for the current scope
+ /// using the best available method on each platform.  The exact format of the
+ /// resulting string is implementation specific and non-portable, so this should
+ /// only be used, for example, for logging or diagnostics.
++#ifndef LLVM_PRETTY_FUNCTION
+ #if defined(_MSC_VER)
+ #define LLVM_PRETTY_FUNCTION __FUNCSIG__
+ #elif defined(__GNUC__) || defined(__clang__)
+@@ -528,6 +577,7 @@ void AnnotateIgnoreWritesEnd(const char *file, int line);
+ #else
+ #define LLVM_PRETTY_FUNCTION __func__
+ #endif
++#endif
+ 
+ /// \macro LLVM_THREAD_LOCAL
+ /// A thread-local storage specifier which can be used with globals,
diff --git a/third_party/allwpilib/upstream_utils/llvm_patches/0007-Explicitly-use-std.patch b/third_party/allwpilib/upstream_utils/llvm_patches/0007-Explicitly-use-std.patch
new file mode 100644
index 0000000..cfbe9a1
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/llvm_patches/0007-Explicitly-use-std.patch
@@ -0,0 +1,78 @@
+From c26562caae6a685716a8785ad8689833c9996549 Mon Sep 17 00:00:00 2001
+From: PJ Reiniger <pj.reiniger@gmail.com>
+Date: Sat, 7 May 2022 22:37:34 -0400
+Subject: [PATCH 07/28] Explicitly use std::
+
+---
+ llvm/include/llvm/ADT/SmallSet.h       | 2 +-
+ llvm/include/llvm/Support/MathExtras.h | 2 +-
+ llvm/lib/Support/ErrorHandling.cpp     | 2 +-
+ llvm/unittests/ADT/SmallPtrSetTest.cpp | 2 +-
+ llvm/unittests/ADT/StringMapTest.cpp   | 2 +-
+ 5 files changed, 5 insertions(+), 5 deletions(-)
+
+diff --git a/llvm/include/llvm/ADT/SmallSet.h b/llvm/include/llvm/ADT/SmallSet.h
+index bfe93e997..403e108fd 100644
+--- a/llvm/include/llvm/ADT/SmallSet.h
++++ b/llvm/include/llvm/ADT/SmallSet.h
+@@ -270,7 +270,7 @@ bool operator==(const SmallSet<T, LN, C> &LHS, const SmallSet<T, RN, C> &RHS) {
+     return false;
+ 
+   // All elements in LHS must also be in RHS
+-  return all_of(LHS, [&RHS](const T &E) { return RHS.count(E); });
++  return std::all_of(LHS.begin(), LHS.end(), [&RHS](const T &E) { return RHS.count(E); });
+ }
+ 
+ /// Inequality comparison for SmallSet.
+diff --git a/llvm/include/llvm/Support/MathExtras.h b/llvm/include/llvm/Support/MathExtras.h
+index db9fbc148..da843ef79 100644
+--- a/llvm/include/llvm/Support/MathExtras.h
++++ b/llvm/include/llvm/Support/MathExtras.h
+@@ -586,7 +586,7 @@ inline double Log2(double Value) {
+ #if defined(__ANDROID_API__) && __ANDROID_API__ < 18
+   return __builtin_log(Value) / __builtin_log(2.0);
+ #else
+-  return log2(Value);
++  return std::log2(Value);
+ #endif
+ }
+ 
+diff --git a/llvm/lib/Support/ErrorHandling.cpp b/llvm/lib/Support/ErrorHandling.cpp
+index 89440b5ab..f80e28e87 100644
+--- a/llvm/lib/Support/ErrorHandling.cpp
++++ b/llvm/lib/Support/ErrorHandling.cpp
+@@ -210,7 +210,7 @@ void LLVMResetFatalErrorHandler() {
+ // I'd rather not double the line count of the following.
+ #define MAP_ERR_TO_COND(x, y)                                                  \
+   case x:                                                                      \
+-    return make_error_code(errc::y)
++    return std::make_error_code(std::errc::y)
+ 
+ std::error_code llvm::mapWindowsError(unsigned EV) {
+   switch (EV) {
+diff --git a/llvm/unittests/ADT/SmallPtrSetTest.cpp b/llvm/unittests/ADT/SmallPtrSetTest.cpp
+index 6f3c94eed..531f81ab5 100644
+--- a/llvm/unittests/ADT/SmallPtrSetTest.cpp
++++ b/llvm/unittests/ADT/SmallPtrSetTest.cpp
+@@ -298,7 +298,7 @@ TEST(SmallPtrSetTest, dereferenceAndIterate) {
+ 
+   // Sort.  We should hit the first element just once and the final element N
+   // times.
+-  llvm::sort(std::begin(Found), std::end(Found));
++  std::sort(std::begin(Found), std::end(Found));
+   for (auto F = std::begin(Found), E = std::end(Found); F != E; ++F)
+     EXPECT_EQ(F - Found + 1, *F);
+ }
+diff --git a/llvm/unittests/ADT/StringMapTest.cpp b/llvm/unittests/ADT/StringMapTest.cpp
+index 86907ab61..6d0c0942c 100644
+--- a/llvm/unittests/ADT/StringMapTest.cpp
++++ b/llvm/unittests/ADT/StringMapTest.cpp
+@@ -329,7 +329,7 @@ TEST_F(StringMapTest, IterMapKeysSmallVector) {
+   Map["D"] = 3;
+ 
+   auto Keys = to_vector<4>(Map.keys());
+-  llvm::sort(Keys);
++  std::sort(Keys.begin(), Keys.end());
+ 
+   SmallVector<std::string_view, 4> Expected = {"A", "B", "C", "D"};
+   EXPECT_EQ(Expected, Keys);
diff --git a/third_party/allwpilib/upstream_utils/llvm_patches/0008-Remove-format_provider.patch b/third_party/allwpilib/upstream_utils/llvm_patches/0008-Remove-format_provider.patch
new file mode 100644
index 0000000..1e43a8b
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/llvm_patches/0008-Remove-format_provider.patch
@@ -0,0 +1,232 @@
+From f35fcb2c40caceed14437e65131e9fe1cf94deac Mon Sep 17 00:00:00 2001
+From: PJ Reiniger <pj.reiniger@gmail.com>
+Date: Sat, 7 May 2022 22:53:50 -0400
+Subject: [PATCH 08/28] Remove format_provider
+
+---
+ llvm/include/llvm/Support/Chrono.h      | 109 ------------------------
+ llvm/include/llvm/Support/raw_ostream.h |   6 --
+ llvm/unittests/Support/Chrono.cpp       |  61 -------------
+ 3 files changed, 176 deletions(-)
+
+diff --git a/llvm/include/llvm/Support/Chrono.h b/llvm/include/llvm/Support/Chrono.h
+index a7dea19d9..9f9a2b5ca 100644
+--- a/llvm/include/llvm/Support/Chrono.h
++++ b/llvm/include/llvm/Support/Chrono.h
+@@ -10,7 +10,6 @@
+ #define LLVM_SUPPORT_CHRONO_H
+ 
+ #include "llvm/Support/Compiler.h"
+-#include "llvm/Support/FormatProviders.h"
+ 
+ #include <chrono>
+ #include <ctime>
+@@ -59,114 +58,6 @@ toTimePoint(std::time_t T, uint32_t nsec) {
+ 
+ raw_ostream &operator<<(raw_ostream &OS, sys::TimePoint<> TP);
+ 
+-/// Format provider for TimePoint<>
+-///
+-/// The options string is a strftime format string, with extensions:
+-///   - %L is millis: 000-999
+-///   - %f is micros: 000000-999999
+-///   - %N is nanos: 000000000 - 999999999
+-///
+-/// If no options are given, the default format is "%Y-%m-%d %H:%M:%S.%N".
+-template <>
+-struct format_provider<sys::TimePoint<>> {
+-  static void format(const sys::TimePoint<> &TP, llvm::raw_ostream &OS,
+-                     std::string_view Style);
+-};
+-
+-namespace detail {
+-template <typename Period> struct unit { static const char value[]; };
+-template <typename Period> const char unit<Period>::value[] = "";
+-
+-template <> struct unit<std::ratio<3600>> { static const char value[]; };
+-template <> struct unit<std::ratio<60>> { static const char value[]; };
+-template <> struct unit<std::ratio<1>> { static const char value[]; };
+-template <> struct unit<std::milli> { static const char value[]; };
+-template <> struct unit<std::micro> { static const char value[]; };
+-template <> struct unit<std::nano> { static const char value[]; };
+-} // namespace detail
+-
+-/// Implementation of format_provider<T> for duration types.
+-///
+-/// The options string of a duration type has the grammar:
+-///
+-///   duration_options  ::= [unit][show_unit [number_options]]
+-///   unit              ::= `h`|`m`|`s`|`ms|`us`|`ns`
+-///   show_unit         ::= `+` | `-`
+-///   number_options    ::= options string for a integral or floating point type
+-///
+-///   Examples
+-///   =================================
+-///   |  options  | Input | Output    |
+-///   =================================
+-///   | ""        | 1s    | 1 s       |
+-///   | "ms"      | 1s    | 1000 ms   |
+-///   | "ms-"     | 1s    | 1000      |
+-///   | "ms-n"    | 1s    | 1,000     |
+-///   | ""        | 1.0s  | 1.00 s    |
+-///   =================================
+-///
+-///  If the unit of the duration type is not one of the units specified above,
+-///  it is still possible to format it, provided you explicitly request a
+-///  display unit or you request that the unit is not displayed.
+-
+-template <typename Rep, typename Period>
+-struct format_provider<std::chrono::duration<Rep, Period>> {
+-private:
+-  typedef std::chrono::duration<Rep, Period> Dur;
+-  typedef std::conditional_t<std::chrono::treat_as_floating_point<Rep>::value,
+-                             double, intmax_t>
+-      InternalRep;
+-
+-  template <typename AsPeriod> static InternalRep getAs(const Dur &D) {
+-    using namespace std::chrono;
+-    return duration_cast<duration<InternalRep, AsPeriod>>(D).count();
+-  }
+-
+-  static std::pair<InternalRep, std::string_view> consumeUnit(std::string_view &Style,
+-                                                        const Dur &D) {
+-    using namespace std::chrono;
+-    if (Style.consume_front("ns"))
+-      return {getAs<std::nano>(D), "ns"};
+-    if (Style.consume_front("us"))
+-      return {getAs<std::micro>(D), "us"};
+-    if (Style.consume_front("ms"))
+-      return {getAs<std::milli>(D), "ms"};
+-    if (Style.consume_front("s"))
+-      return {getAs<std::ratio<1>>(D), "s"};
+-    if (Style.consume_front("m"))
+-      return {getAs<std::ratio<60>>(D), "m"};
+-    if (Style.consume_front("h"))
+-      return {getAs<std::ratio<3600>>(D), "h"};
+-    return {D.count(), detail::unit<Period>::value};
+-  }
+-
+-  static bool consumeShowUnit(std::string_view &Style) {
+-    if (Style.empty())
+-      return true;
+-    if (Style.consume_front("-"))
+-      return false;
+-    if (Style.consume_front("+"))
+-      return true;
+-    assert(0 && "Unrecognised duration format");
+-    return true;
+-  }
+-
+-public:
+-  static void format(const Dur &D, llvm::raw_ostream &Stream, std::string_view Style) {
+-    InternalRep count;
+-    std::string_view unit;
+-    std::tie(count, unit) = consumeUnit(Style, D);
+-    bool show_unit = consumeShowUnit(Style);
+-
+-    format_provider<InternalRep>::format(count, Stream, Style);
+-
+-    if (show_unit) {
+-      assert(!unit.empty());
+-      Stream << " " << unit;
+-    }
+-  }
+-};
+-
+ } // namespace llvm
+ 
+ #endif // LLVM_SUPPORT_CHRONO_H
+diff --git a/llvm/include/llvm/Support/raw_ostream.h b/llvm/include/llvm/Support/raw_ostream.h
+index 9a1dd7a60..a25ca5b7b 100644
+--- a/llvm/include/llvm/Support/raw_ostream.h
++++ b/llvm/include/llvm/Support/raw_ostream.h
+@@ -28,12 +28,6 @@
+ 
+ namespace llvm {
+ 
+-class Duration;
+-class formatv_object_base;
+-class format_object_base;
+-class FormattedString;
+-class FormattedNumber;
+-class FormattedBytes;
+ template <class T> class LLVM_NODISCARD Expected;
+ 
+ namespace sys {
+diff --git a/llvm/unittests/Support/Chrono.cpp b/llvm/unittests/Support/Chrono.cpp
+index 9a08a5c1b..3c049de18 100644
+--- a/llvm/unittests/Support/Chrono.cpp
++++ b/llvm/unittests/Support/Chrono.cpp
+@@ -30,37 +30,6 @@ TEST(Chrono, TimeTConversion) {
+   EXPECT_EQ(TP, toTimePoint(toTimeT(TP)));
+ }
+ 
+-TEST(Chrono, TimePointFormat) {
+-  using namespace std::chrono;
+-  struct tm TM {};
+-  TM.tm_year = 106;
+-  TM.tm_mon = 0;
+-  TM.tm_mday = 2;
+-  TM.tm_hour = 15;
+-  TM.tm_min = 4;
+-  TM.tm_sec = 5;
+-  TM.tm_isdst = -1;
+-  TimePoint<> T =
+-      system_clock::from_time_t(mktime(&TM)) + nanoseconds(123456789);
+-
+-  // operator<< uses the format YYYY-MM-DD HH:MM:SS.NNNNNNNNN
+-  std::string S;
+-  raw_string_ostream OS(S);
+-  OS << T;
+-  EXPECT_EQ("2006-01-02 15:04:05.123456789", OS.str());
+-
+-  // formatv default style matches operator<<.
+-  EXPECT_EQ("2006-01-02 15:04:05.123456789", formatv("{0}", T).str());
+-  // formatv supports strftime-style format strings.
+-  EXPECT_EQ("15:04:05", formatv("{0:%H:%M:%S}", T).str());
+-  // formatv supports our strftime extensions for sub-second precision.
+-  EXPECT_EQ("123", formatv("{0:%L}", T).str());
+-  EXPECT_EQ("123456", formatv("{0:%f}", T).str());
+-  EXPECT_EQ("123456789", formatv("{0:%N}", T).str());
+-  // our extensions don't interfere with %% escaping.
+-  EXPECT_EQ("%foo", formatv("{0:%%foo}", T).str());
+-}
+-
+ // Test that toTimePoint and toTimeT can be called with a arguments with varying
+ // precisions.
+ TEST(Chrono, ImplicitConversions) {
+@@ -78,34 +47,4 @@ TEST(Chrono, ImplicitConversions) {
+   EXPECT_EQ(TimeT, toTimeT(Nano));
+ }
+ 
+-TEST(Chrono, DurationFormat) {
+-  EXPECT_EQ("1 h", formatv("{0}", hours(1)).str());
+-  EXPECT_EQ("1 m", formatv("{0}", minutes(1)).str());
+-  EXPECT_EQ("1 s", formatv("{0}", seconds(1)).str());
+-  EXPECT_EQ("1 ms", formatv("{0}", milliseconds(1)).str());
+-  EXPECT_EQ("1 us", formatv("{0}", microseconds(1)).str());
+-  EXPECT_EQ("1 ns", formatv("{0}", nanoseconds(1)).str());
+-
+-  EXPECT_EQ("1 s", formatv("{0:+}", seconds(1)).str());
+-  EXPECT_EQ("1", formatv("{0:-}", seconds(1)).str());
+-
+-  EXPECT_EQ("1000 ms", formatv("{0:ms}", seconds(1)).str());
+-  EXPECT_EQ("1000000 us", formatv("{0:us}", seconds(1)).str());
+-  EXPECT_EQ("1000", formatv("{0:ms-}", seconds(1)).str());
+-
+-  EXPECT_EQ("1,000 ms", formatv("{0:+n}", milliseconds(1000)).str());
+-  EXPECT_EQ("0x3e8", formatv("{0:-x}", milliseconds(1000)).str());
+-  EXPECT_EQ("010", formatv("{0:-3}", milliseconds(10)).str());
+-  EXPECT_EQ("10,000", formatv("{0:ms-n}", seconds(10)).str());
+-
+-  EXPECT_EQ("1.00 s", formatv("{0}", duration<float>(1)).str());
+-  EXPECT_EQ("0.123 s", formatv("{0:+3}", duration<float>(0.123f)).str());
+-  EXPECT_EQ("1.230e-01 s", formatv("{0:+e3}", duration<float>(0.123f)).str());
+-
+-  typedef duration<float, std::ratio<60 * 60 * 24 * 14, 1000000>>
+-      microfortnights;
+-  EXPECT_EQ("1.00", formatv("{0:-}", microfortnights(1)).str());
+-  EXPECT_EQ("1209.60 ms", formatv("{0:ms}", microfortnights(1)).str());
+-}
+-
+ } // anonymous namespace
diff --git a/third_party/allwpilib/upstream_utils/llvm_patches/0009-Add-compiler-warning-pragmas.patch b/third_party/allwpilib/upstream_utils/llvm_patches/0009-Add-compiler-warning-pragmas.patch
new file mode 100644
index 0000000..2255dd1
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/llvm_patches/0009-Add-compiler-warning-pragmas.patch
@@ -0,0 +1,228 @@
+From 2c53d8ac36f378fda347f36ef2bc7fbc2038cb93 Mon Sep 17 00:00:00 2001
+From: PJ Reiniger <pj.reiniger@gmail.com>
+Date: Sun, 8 May 2022 13:34:07 -0400
+Subject: [PATCH 09/28] Add compiler warning pragmas
+
+---
+ llvm/include/llvm/ADT/FunctionExtras.h | 11 +++++++++++
+ llvm/include/llvm/ADT/Hashing.h        |  9 +++++++++
+ llvm/include/llvm/ADT/SmallVector.h    |  8 ++++++++
+ llvm/include/llvm/Support/MathExtras.h |  9 +++++++++
+ llvm/include/llvm/Support/MemAlloc.h   | 13 +++++++++++++
+ llvm/lib/Support/raw_ostream.cpp       |  4 ++++
+ llvm/unittests/ADT/DenseMapTest.cpp    |  4 ++++
+ llvm/unittests/ADT/MapVectorTest.cpp   |  7 +++++++
+ llvm/unittests/ADT/SmallVectorTest.cpp |  4 ++++
+ llvm/unittests/Support/AlignOfTest.cpp |  7 +++----
+ 10 files changed, 72 insertions(+), 4 deletions(-)
+
+diff --git a/llvm/include/llvm/ADT/FunctionExtras.h b/llvm/include/llvm/ADT/FunctionExtras.h
+index 8a9d78f41..3efa73587 100644
+--- a/llvm/include/llvm/ADT/FunctionExtras.h
++++ b/llvm/include/llvm/ADT/FunctionExtras.h
+@@ -55,6 +55,13 @@ namespace llvm {
+ ///   It can hold functions with a non-const operator(), like mutable lambdas.
+ template <typename FunctionT> class unique_function;
+ 
++// GCC warns on OutOfLineStorage
++#if defined(__GNUC__) && !defined(__clang__)
++#pragma GCC diagnostic push
++#pragma GCC diagnostic ignored "-Warray-bounds"
++#pragma GCC diagnostic ignored "-Wmaybe-uninitialized"
++#endif
++
+ namespace detail {
+ 
+ template <typename T>
+@@ -411,6 +418,10 @@ public:
+   }
+ };
+ 
++#if defined(__GNUC__) && !defined(__clang__)
++#pragma GCC diagnostic pop
++#endif
++
+ } // end namespace llvm
+ 
+ #endif // LLVM_ADT_FUNCTIONEXTRAS_H
+diff --git a/llvm/include/llvm/ADT/Hashing.h b/llvm/include/llvm/ADT/Hashing.h
+index 74a87a3d8..47ff1b2bc 100644
+--- a/llvm/include/llvm/ADT/Hashing.h
++++ b/llvm/include/llvm/ADT/Hashing.h
+@@ -55,6 +55,11 @@
+ #include <tuple>
+ #include <utility>
+ 
++#ifdef _WIN32
++#pragma warning(push)
++#pragma warning(disable : 26495)
++#endif
++
+ namespace llvm {
+ template <typename T, typename Enable> struct DenseMapInfo;
+ 
+@@ -687,4 +692,8 @@ template <> struct DenseMapInfo<hash_code, void> {
+ 
+ } // namespace llvm
+ 
++#ifdef _WIN32
++#pragma warning(pop)
++#endif
++
+ #endif
+diff --git a/llvm/include/llvm/ADT/SmallVector.h b/llvm/include/llvm/ADT/SmallVector.h
+index 8686f7bb5..1e311ea56 100644
+--- a/llvm/include/llvm/ADT/SmallVector.h
++++ b/llvm/include/llvm/ADT/SmallVector.h
+@@ -14,6 +14,14 @@
+ #ifndef LLVM_ADT_SMALLVECTOR_H
+ #define LLVM_ADT_SMALLVECTOR_H
+ 
++// This file uses std::memcpy() to copy std::pair<unsigned int, unsigned int>.
++// That type is POD, but the standard doesn't guarantee that. GCC doesn't treat
++// the type as POD so it throws a warning. We want to consider this a warning
++// instead of an error.
++#if __GNUC__ >= 8
++#pragma GCC diagnostic warning "-Wclass-memaccess"
++#endif
++
+ #include "llvm/Support/Compiler.h"
+ #include "llvm/Support/type_traits.h"
+ #include <algorithm>
+diff --git a/llvm/include/llvm/Support/MathExtras.h b/llvm/include/llvm/Support/MathExtras.h
+index da843ef79..fac12dd0e 100644
+--- a/llvm/include/llvm/Support/MathExtras.h
++++ b/llvm/include/llvm/Support/MathExtras.h
+@@ -435,6 +435,11 @@ inline uint64_t maxUIntN(uint64_t N) {
+   return UINT64_MAX >> (64 - N);
+ }
+ 
++#ifdef _WIN32
++#pragma warning(push)
++#pragma warning(disable : 4146)
++#endif
++
+ /// Gets the minimum value for a N-bit signed integer.
+ inline int64_t minIntN(int64_t N) {
+   assert(N > 0 && N <= 64 && "integer width out of range");
+@@ -442,6 +447,10 @@ inline int64_t minIntN(int64_t N) {
+   return UINT64_C(1) + ~(UINT64_C(1) << (N - 1));
+ }
+ 
++#ifdef _WIN32
++#pragma warning(pop)
++#endif
++
+ /// Gets the maximum value for a N-bit signed integer.
+ inline int64_t maxIntN(int64_t N) {
+   assert(N > 0 && N <= 64 && "integer width out of range");
+diff --git a/llvm/include/llvm/Support/MemAlloc.h b/llvm/include/llvm/Support/MemAlloc.h
+index d6012bd5a..01007deb8 100644
+--- a/llvm/include/llvm/Support/MemAlloc.h
++++ b/llvm/include/llvm/Support/MemAlloc.h
+@@ -22,6 +22,14 @@
+ 
+ namespace llvm {
+ 
++#ifdef _WIN32
++#pragma warning(push)
++// Warning on NONNULL, report is not known to abort
++#pragma warning(disable : 6387)
++#pragma warning(disable : 28196)
++#pragma warning(disable : 28183)
++#endif
++
+ LLVM_ATTRIBUTE_RETURNS_NONNULL inline void *safe_malloc(size_t Sz) {
+   void *Result = std::malloc(Sz);
+   if (Result == nullptr) {
+@@ -84,4 +92,9 @@ allocate_buffer(size_t Size, size_t Alignment);
+ void deallocate_buffer(void *Ptr, size_t Size, size_t Alignment);
+ 
+ } // namespace llvm
++
++#ifdef _WIN32
++#pragma warning(pop)
++#endif
++
+ #endif
+diff --git a/llvm/lib/Support/raw_ostream.cpp b/llvm/lib/Support/raw_ostream.cpp
+index e4c318eb8..ee01a9522 100644
+--- a/llvm/lib/Support/raw_ostream.cpp
++++ b/llvm/lib/Support/raw_ostream.cpp
+@@ -10,6 +10,10 @@
+ //
+ //===----------------------------------------------------------------------===//
+ 
++#ifdef _WIN32
++#define _CRT_NONSTDC_NO_WARNINGS
++#endif
++
+ #include "llvm/Support/raw_ostream.h"
+ #include "llvm/ADT/STLArrayExtras.h"
+ #include "llvm/ADT/StringExtras.h"
+diff --git a/llvm/unittests/ADT/DenseMapTest.cpp b/llvm/unittests/ADT/DenseMapTest.cpp
+index e505b1907..9fe83a45d 100644
+--- a/llvm/unittests/ADT/DenseMapTest.cpp
++++ b/llvm/unittests/ADT/DenseMapTest.cpp
+@@ -6,6 +6,10 @@
+ //
+ //===----------------------------------------------------------------------===//
+ 
++#if defined(__GNUC__) && !defined(__clang__)
++#pragma GCC diagnostic ignored "-Wmaybe-uninitialized"
++#endif
++
+ #include "llvm/ADT/DenseMap.h"
+ #include "gtest/gtest.h"
+ #include <map>
+diff --git a/llvm/unittests/ADT/MapVectorTest.cpp b/llvm/unittests/ADT/MapVectorTest.cpp
+index 552f9956b..20ebcd753 100644
+--- a/llvm/unittests/ADT/MapVectorTest.cpp
++++ b/llvm/unittests/ADT/MapVectorTest.cpp
+@@ -6,6 +6,13 @@
+ //
+ //===----------------------------------------------------------------------===//
+ 
++#if defined(__GNUC__)
++#pragma GCC diagnostic ignored "-Wpedantic"
++#if !defined(__clang__)
++#pragma GCC diagnostic ignored "-Wmaybe-uninitialized"
++#endif
++#endif
++
+ #include "llvm/ADT/MapVector.h"
+ #include "llvm/ADT/iterator_range.h"
+ #include "gtest/gtest.h"
+diff --git a/llvm/unittests/ADT/SmallVectorTest.cpp b/llvm/unittests/ADT/SmallVectorTest.cpp
+index fe827546a..0e68bad6c 100644
+--- a/llvm/unittests/ADT/SmallVectorTest.cpp
++++ b/llvm/unittests/ADT/SmallVectorTest.cpp
+@@ -17,6 +17,10 @@
+ #include <list>
+ #include <stdarg.h>
+ 
++#if defined(__GNUC__)
++#pragma GCC diagnostic ignored "-Wpedantic"
++#endif
++
+ using namespace llvm;
+ 
+ namespace {
+diff --git a/llvm/unittests/Support/AlignOfTest.cpp b/llvm/unittests/Support/AlignOfTest.cpp
+index f84895c18..6a50205b1 100644
+--- a/llvm/unittests/Support/AlignOfTest.cpp
++++ b/llvm/unittests/Support/AlignOfTest.cpp
+@@ -31,10 +31,9 @@ namespace {
+ #pragma clang diagnostic ignored "-Wunknown-pragmas"
+ #pragma clang diagnostic ignored "-Winaccessible-base"
+ #elif ((__GNUC__ * 100) + __GNUC_MINOR__) >= 402
+-// Pragma based warning suppression was introduced in GGC 4.2.  Additionally
+-// this warning is "enabled by default".  The warning still appears if -Wall is
+-// suppressed.  Apparently GCC suppresses it when -w is specifed, which is odd.
+-#pragma GCC diagnostic warning "-w"
++#pragma GCC diagnostic warning "-Wunknown-pragmas"
++#pragma GCC diagnostic warning "-Winaccessible-base"
++#pragma GCC diagnostic warning "-Wunused-function"
+ #endif
+ 
+ // Define some fixed alignment types to use in these tests.
diff --git a/third_party/allwpilib/upstream_utils/llvm_patches/0010-Remove-unused-functions.patch b/third_party/allwpilib/upstream_utils/llvm_patches/0010-Remove-unused-functions.patch
new file mode 100644
index 0000000..50f5300
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/llvm_patches/0010-Remove-unused-functions.patch
@@ -0,0 +1,762 @@
+From df2dc9fdb3d57e01423104a71a6a1d1d6382644a Mon Sep 17 00:00:00 2001
+From: PJ Reiniger <pj.reiniger@gmail.com>
+Date: Sun, 8 May 2022 13:43:50 -0400
+Subject: [PATCH 10/28] Remove unused functions
+
+---
+ llvm/include/llvm/ADT/SmallString.h      |  80 ------
+ llvm/include/llvm/Support/Errno.h        |   9 -
+ llvm/include/llvm/Support/VersionTuple.h |  40 ---
+ llvm/include/llvm/Support/raw_ostream.h  | 115 +-------
+ llvm/lib/Support/raw_ostream.cpp         | 328 -----------------------
+ 5 files changed, 8 insertions(+), 564 deletions(-)
+
+diff --git a/llvm/include/llvm/ADT/SmallString.h b/llvm/include/llvm/ADT/SmallString.h
+index 50cbdade4..bfa965fd6 100644
+--- a/llvm/include/llvm/ADT/SmallString.h
++++ b/llvm/include/llvm/ADT/SmallString.h
+@@ -88,48 +88,12 @@ public:
+   /// @name String Comparison
+   /// @{
+ 
+-  /// Check for string equality.  This is more efficient than compare() when
+-  /// the relative ordering of inequal strings isn't needed.
+-  bool equals(std::string_view RHS) const {
+-    return str().equals(RHS);
+-  }
+-
+-  /// Check for string equality, ignoring case.
+-  bool equals_insensitive(std::string_view RHS) const {
+-    return str().equals_insensitive(RHS);
+-  }
+-
+   /// Compare two strings; the result is -1, 0, or 1 if this string is
+   /// lexicographically less than, equal to, or greater than the \p RHS.
+   int compare(std::string_view RHS) const {
+     return str().compare(RHS);
+   }
+ 
+-  /// compare_insensitive - Compare two strings, ignoring case.
+-  int compare_insensitive(std::string_view RHS) const {
+-    return str().compare_insensitive(RHS);
+-  }
+-
+-  /// compare_numeric - Compare two strings, treating sequences of digits as
+-  /// numbers.
+-  int compare_numeric(std::string_view RHS) const {
+-    return str().compare_numeric(RHS);
+-  }
+-
+-  /// @}
+-  /// @name String Predicates
+-  /// @{
+-
+-  /// startswith - Check if this string starts with the given \p Prefix.
+-  bool startswith(std::string_view Prefix) const {
+-    return str().startswith(Prefix);
+-  }
+-
+-  /// endswith - Check if this string ends with the given \p Suffix.
+-  bool endswith(std::string_view Suffix) const {
+-    return str().endswith(Suffix);
+-  }
+-
+   /// @}
+   /// @name String Searching
+   /// @{
+@@ -210,50 +174,6 @@ public:
+   }
+ 
+   /// @}
+-  /// @name Helpful Algorithms
+-  /// @{
+-
+-  /// Return the number of occurrences of \p C in the string.
+-  size_t count(char C) const {
+-    return str().count(C);
+-  }
+-
+-  /// Return the number of non-overlapped occurrences of \p Str in the
+-  /// string.
+-  size_t count(std::string_view Str) const {
+-    return str().count(Str);
+-  }
+-
+-  /// @}
+-  /// @name Substring Operations
+-  /// @{
+-
+-  /// Return a reference to the substring from [Start, Start + N).
+-  ///
+-  /// \param Start The index of the starting character in the substring; if
+-  /// the index is npos or greater than the length of the string then the
+-  /// empty substring will be returned.
+-  ///
+-  /// \param N The number of characters to included in the substring. If \p N
+-  /// exceeds the number of characters remaining in the string, the string
+-  /// suffix (starting with \p Start) will be returned.
+-  std::string_view substr(size_t Start, size_t N = std::string_view::npos) const {
+-    return str().substr(Start, N);
+-  }
+-
+-  /// Return a reference to the substring from [Start, End).
+-  ///
+-  /// \param Start The index of the starting character in the substring; if
+-  /// the index is npos or greater than the length of the string then the
+-  /// empty substring will be returned.
+-  ///
+-  /// \param End The index following the last character to include in the
+-  /// substring. If this is npos, or less than \p Start, or exceeds the
+-  /// number of characters remaining in the string, the string suffix
+-  /// (starting with \p Start) will be returned.
+-  std::string_view slice(size_t Start, size_t End) const {
+-    return str().slice(Start, End);
+-  }
+ 
+   // Extra methods.
+ 
+diff --git a/llvm/include/llvm/Support/Errno.h b/llvm/include/llvm/Support/Errno.h
+index 07df6765d..d9bf68bb3 100644
+--- a/llvm/include/llvm/Support/Errno.h
++++ b/llvm/include/llvm/Support/Errno.h
+@@ -20,15 +20,6 @@
+ namespace llvm {
+ namespace sys {
+ 
+-/// Returns a string representation of the errno value, using whatever
+-/// thread-safe variant of strerror() is available.  Be sure to call this
+-/// immediately after the function that set errno, or errno may have been
+-/// overwritten by an intervening call.
+-std::string StrError();
+-
+-/// Like the no-argument version above, but uses \p errnum instead of errno.
+-std::string StrError(int errnum);
+-
+ template <typename FailT, typename Fun, typename... Args>
+ inline decltype(auto) RetryAfterSignal(const FailT &Fail, const Fun &F,
+                                        const Args &... As) {
+diff --git a/llvm/include/llvm/Support/VersionTuple.h b/llvm/include/llvm/Support/VersionTuple.h
+index 3d6573bf5..a28e12adc 100644
+--- a/llvm/include/llvm/Support/VersionTuple.h
++++ b/llvm/include/llvm/Support/VersionTuple.h
+@@ -16,7 +16,6 @@
+ 
+ #include "llvm/ADT/DenseMapInfo.h"
+ #include "llvm/ADT/Hashing.h"
+-#include "llvm/Support/HashBuilder.h"
+ #include <optional>
+ #include <string>
+ #include <tuple>
+@@ -159,45 +158,6 @@ public:
+   friend bool operator>=(const VersionTuple &X, const VersionTuple &Y) {
+     return !(X < Y);
+   }
+-
+-  friend llvm::hash_code hash_value(const VersionTuple &VT) {
+-    return llvm::hash_combine(VT.Major, VT.Minor, VT.Subminor, VT.Build);
+-  }
+-
+-  template <typename HasherT, llvm::support::endianness Endianness>
+-  friend void addHash(HashBuilderImpl<HasherT, Endianness> &HBuilder,
+-                      const VersionTuple &VT) {
+-    HBuilder.add(VT.Major, VT.Minor, VT.Subminor, VT.Build);
+-  }
+-
+-  /// Retrieve a string representation of the version number.
+-  std::string getAsString() const;
+-};
+-
+-/// Print a version number.
+-raw_ostream &operator<<(raw_ostream &Out, const VersionTuple &V);
+-
+-// Provide DenseMapInfo for version tuples.
+-template <> struct DenseMapInfo<VersionTuple> {
+-  static inline VersionTuple getEmptyKey() { return VersionTuple(0x7FFFFFFF); }
+-  static inline VersionTuple getTombstoneKey() {
+-    return VersionTuple(0x7FFFFFFE);
+-  }
+-  static unsigned getHashValue(const VersionTuple &Value) {
+-    unsigned Result = Value.getMajor();
+-    if (auto Minor = Value.getMinor())
+-      Result = detail::combineHashValue(Result, *Minor);
+-    if (auto Subminor = Value.getSubminor())
+-      Result = detail::combineHashValue(Result, *Subminor);
+-    if (auto Build = Value.getBuild())
+-      Result = detail::combineHashValue(Result, *Build);
+-
+-    return Result;
+-  }
+-
+-  static bool isEqual(const VersionTuple &LHS, const VersionTuple &RHS) {
+-    return LHS == RHS;
+-  }
+ };
+ 
+ } // end namespace llvm
+diff --git a/llvm/include/llvm/Support/raw_ostream.h b/llvm/include/llvm/Support/raw_ostream.h
+index a25ca5b7b..d4521c8e2 100644
+--- a/llvm/include/llvm/Support/raw_ostream.h
++++ b/llvm/include/llvm/Support/raw_ostream.h
+@@ -248,32 +248,6 @@ public:
+     return write(Str.data(), Str.size());
+   }
+ 
+-  raw_ostream &operator<<(unsigned long N);
+-  raw_ostream &operator<<(long N);
+-  raw_ostream &operator<<(unsigned long long N);
+-  raw_ostream &operator<<(long long N);
+-  raw_ostream &operator<<(const void *P);
+-
+-  raw_ostream &operator<<(unsigned int N) {
+-    return this->operator<<(static_cast<unsigned long>(N));
+-  }
+-
+-  raw_ostream &operator<<(int N) {
+-    return this->operator<<(static_cast<long>(N));
+-  }
+-
+-  raw_ostream &operator<<(double N);
+-
+-  /// Output \p N in hexadecimal, without any prefix or padding.
+-  raw_ostream &write_hex(unsigned long long N);
+-
+-  // Change the foreground color of text.
+-  raw_ostream &operator<<(Colors C);
+-
+-  /// Output a formatted UUID with dash separators.
+-  using uuid_t = uint8_t[16];
+-  raw_ostream &write_uuid(const uuid_t UUID);
+-
+   /// Output \p Str, turning '\\', '\t', '\n', '"', and anything that doesn't
+   /// satisfy llvm::isPrint into an escape sequence.
+   raw_ostream &write_escaped(std::string_view Str, bool UseHexEscapes = false);
+@@ -281,21 +255,6 @@ public:
+   raw_ostream &write(unsigned char C);
+   raw_ostream &write(const char *Ptr, size_t Size);
+ 
+-  // Formatted output, see the format() function in Support/Format.h.
+-  raw_ostream &operator<<(const format_object_base &Fmt);
+-
+-  // Formatted output, see the leftJustify() function in Support/Format.h.
+-  raw_ostream &operator<<(const FormattedString &);
+-
+-  // Formatted output, see the formatHex() function in Support/Format.h.
+-  raw_ostream &operator<<(const FormattedNumber &);
+-
+-  // Formatted output, see the formatv() function in Support/FormatVariadic.h.
+-  raw_ostream &operator<<(const formatv_object_base &);
+-
+-  // Formatted output, see the format_bytes() function in Support/Format.h.
+-  raw_ostream &operator<<(const FormattedBytes &);
+-
+   /// indent - Insert 'NumSpaces' spaces.
+   raw_ostream &indent(unsigned NumSpaces);
+ 
+@@ -310,14 +269,19 @@ public:
+   /// @param BG if true change the background, default: change foreground
+   /// @returns itself so it can be used within << invocations
+   virtual raw_ostream &changeColor(enum Colors Color, bool Bold = false,
+-                                   bool BG = false);
++                                   bool BG = false)  {
++    (void)Color;
++    (void)Bold;
++    (void)BG;
++    return *this;
++  }
+ 
+   /// Resets the colors to terminal defaults. Call this when you are done
+   /// outputting colored text, or before program exit.
+-  virtual raw_ostream &resetColor();
++  virtual raw_ostream &resetColor() { return *this; }
+ 
+   /// Reverses the foreground and background colors.
+-  virtual raw_ostream &reverseColor();
++  virtual raw_ostream &reverseColor() { return *this; }
+ 
+   /// This function determines if this stream is connected to a "tty" or
+   /// "console" window. That is, the output would be displayed to the user
+@@ -392,10 +356,6 @@ private:
+   /// unused bytes in the buffer.
+   void copy_to_buffer(const char *Ptr, size_t Size);
+ 
+-  /// Compute whether colors should be used and do the necessary work such as
+-  /// flushing. The result is affected by calls to enable_color().
+-  bool prepare_colors();
+-
+   /// Flush the tied-to stream (if present) and then write the required data.
+   void flush_tied_then_write(const char *Ptr, size_t Size);
+ 
+@@ -447,7 +407,6 @@ class raw_fd_ostream : public raw_pwrite_stream {
+   bool ShouldClose;
+   bool SupportsSeeking = false;
+   bool IsRegularFile = false;
+-  mutable std::optional<bool> HasColors;
+ 
+ #ifdef _WIN32
+   /// True if this fd refers to a Windows console device. Mintty and other
+@@ -523,10 +482,6 @@ public:
+   /// to the offset specified from the beginning of the file.
+   uint64_t seek(uint64_t off);
+ 
+-  bool is_displayed() const override;
+-
+-  bool has_colors() const override;
+-
+   std::error_code error() const { return EC; }
+ 
+   /// Return the value of the flag in this raw_fd_ostream indicating whether an
+@@ -545,38 +500,6 @@ public:
+   ///      - from The Zen of Python, by Tim Peters
+   ///
+   void clear_error() { EC = std::error_code(); }
+-
+-  /// Locks the underlying file.
+-  ///
+-  /// @returns RAII object that releases the lock upon leaving the scope, if the
+-  ///          locking was successful. Otherwise returns corresponding
+-  ///          error code.
+-  ///
+-  /// The function blocks the current thread until the lock become available or
+-  /// error occurs.
+-  ///
+-  /// Possible use of this function may be as follows:
+-  ///
+-  ///   @code{.cpp}
+-  ///   if (auto L = stream.lock()) {
+-  ///     // ... do action that require file to be locked.
+-  ///   } else {
+-  ///     handleAllErrors(std::move(L.takeError()), [&](ErrorInfoBase &EIB) {
+-  ///       // ... handle lock error.
+-  ///     });
+-  ///   }
+-  ///   @endcode
+-  LLVM_NODISCARD Expected<sys::fs::FileLocker> lock();
+-
+-  /// Tries to lock the underlying file within the specified period.
+-  ///
+-  /// @returns RAII object that releases the lock upon leaving the scope, if the
+-  ///          locking was successful. Otherwise returns corresponding
+-  ///          error code.
+-  ///
+-  /// It is used as @ref lock.
+-  LLVM_NODISCARD
+-  Expected<sys::fs::FileLocker> tryLockFor(Duration const& Timeout);
+ };
+ 
+ /// This returns a reference to a raw_fd_ostream for standard output. Use it
+@@ -606,17 +529,6 @@ public:
+   /// immediately destroyed.
+   raw_fd_stream(std::string_view Filename, std::error_code &EC);
+ 
+-  /// This reads the \p Size bytes into a buffer pointed by \p Ptr.
+-  ///
+-  /// \param Ptr The start of the buffer to hold data to be read.
+-  ///
+-  /// \param Size The number of bytes to be read.
+-  ///
+-  /// On success, the number of bytes read is returned, and the file position is
+-  /// advanced by this number. On error, -1 is returned, use error() to get the
+-  /// error code.
+-  ssize_t read(char *Ptr, size_t Size);
+-
+   /// Check if \p OS is a pointer of type raw_fd_stream*.
+   static bool classof(const raw_ostream *OS);
+ };
+@@ -734,17 +646,6 @@ public:
+   ~buffer_unique_ostream() override { *OS << str(); }
+ };
+ 
+-class Error;
+-
+-/// This helper creates an output stream and then passes it to \p Write.
+-/// The stream created is based on the specified \p OutputFileName:
+-/// llvm::outs for "-", raw_null_ostream for "/dev/null", and raw_fd_ostream
+-/// for other names. For raw_fd_ostream instances, the stream writes to
+-/// a temporary file. The final output file is atomically replaced with the
+-/// temporary file after the \p Write function is finished.
+-Error writeToOutput(std::string_view OutputFileName,
+-                    std::function<Error(raw_ostream &)> Write);
+-
+ } // end namespace llvm
+ 
+ #endif // LLVM_SUPPORT_RAW_OSTREAM_H
+diff --git a/llvm/lib/Support/raw_ostream.cpp b/llvm/lib/Support/raw_ostream.cpp
+index ee01a9522..875eda7ba 100644
+--- a/llvm/lib/Support/raw_ostream.cpp
++++ b/llvm/lib/Support/raw_ostream.cpp
+@@ -19,7 +19,6 @@
+ #include "llvm/ADT/StringExtras.h"
+ #include "llvm/Config/config.h"
+ #include "llvm/Support/Compiler.h"
+-#include "llvm/Support/Duration.h"
+ #include "llvm/Support/ErrorHandling.h"
+ #include "llvm/Support/FileSystem.h"
+ #include "llvm/Support/Format.h"
+@@ -120,49 +119,6 @@ void raw_ostream::SetBufferAndMode(char *BufferStart, size_t Size,
+   assert(OutBufStart <= OutBufEnd && "Invalid size!");
+ }
+ 
+-raw_ostream &raw_ostream::operator<<(unsigned long N) {
+-  write_integer(*this, static_cast<uint64_t>(N), 0, IntegerStyle::Integer);
+-  return *this;
+-}
+-
+-raw_ostream &raw_ostream::operator<<(long N) {
+-  write_integer(*this, static_cast<int64_t>(N), 0, IntegerStyle::Integer);
+-  return *this;
+-}
+-
+-raw_ostream &raw_ostream::operator<<(unsigned long long N) {
+-  write_integer(*this, static_cast<uint64_t>(N), 0, IntegerStyle::Integer);
+-  return *this;
+-}
+-
+-raw_ostream &raw_ostream::operator<<(long long N) {
+-  write_integer(*this, static_cast<int64_t>(N), 0, IntegerStyle::Integer);
+-  return *this;
+-}
+-
+-raw_ostream &raw_ostream::write_hex(unsigned long long N) {
+-  llvm::write_hex(*this, N, HexPrintStyle::Lower);
+-  return *this;
+-}
+-
+-raw_ostream &raw_ostream::operator<<(Colors C) {
+-  if (C == Colors::RESET)
+-    resetColor();
+-  else
+-    changeColor(C);
+-  return *this;
+-}
+-
+-raw_ostream &raw_ostream::write_uuid(const uuid_t UUID) {
+-  for (int Idx = 0; Idx < 16; ++Idx) {
+-    *this << format("%02" PRIX32, UUID[Idx]);
+-    if (Idx == 3 || Idx == 5 || Idx == 7 || Idx == 9)
+-      *this << "-";
+-  }
+-  return *this;
+-}
+-
+-
+ raw_ostream &raw_ostream::write_escaped(std::string_view Str,
+                                         bool UseHexEscapes) {
+   for (unsigned char c : Str) {
+@@ -308,172 +264,6 @@ void raw_ostream::flush_tied_then_write(const char *Ptr, size_t Size) {
+   write_impl(Ptr, Size);
+ }
+ 
+-// Formatted output.
+-raw_ostream &raw_ostream::operator<<(const format_object_base &Fmt) {
+-  // If we have more than a few bytes left in our output buffer, try
+-  // formatting directly onto its end.
+-  size_t NextBufferSize = 127;
+-  size_t BufferBytesLeft = OutBufEnd - OutBufCur;
+-  if (BufferBytesLeft > 3) {
+-    size_t BytesUsed = Fmt.print(OutBufCur, BufferBytesLeft);
+-
+-    // Common case is that we have plenty of space.
+-    if (BytesUsed <= BufferBytesLeft) {
+-      OutBufCur += BytesUsed;
+-      return *this;
+-    }
+-
+-    // Otherwise, we overflowed and the return value tells us the size to try
+-    // again with.
+-    NextBufferSize = BytesUsed;
+-  }
+-
+-  // If we got here, we didn't have enough space in the output buffer for the
+-  // string.  Try printing into a SmallVector that is resized to have enough
+-  // space.  Iterate until we win.
+-  SmallVector<char, 128> V;
+-
+-  while (true) {
+-    V.resize(NextBufferSize);
+-
+-    // Try formatting into the SmallVector.
+-    size_t BytesUsed = Fmt.print(V.data(), NextBufferSize);
+-
+-    // If BytesUsed fit into the vector, we win.
+-    if (BytesUsed <= NextBufferSize)
+-      return write(V.data(), BytesUsed);
+-
+-    // Otherwise, try again with a new size.
+-    assert(BytesUsed > NextBufferSize && "Didn't grow buffer!?");
+-    NextBufferSize = BytesUsed;
+-  }
+-}
+-
+-raw_ostream &raw_ostream::operator<<(const formatv_object_base &Obj) {
+-  Obj.format(*this);
+-  return *this;
+-}
+-
+-raw_ostream &raw_ostream::operator<<(const FormattedString &FS) {
+-  unsigned LeftIndent = 0;
+-  unsigned RightIndent = 0;
+-  const ssize_t Difference = FS.Width - FS.Str.size();
+-  if (Difference > 0) {
+-    switch (FS.Justify) {
+-    case FormattedString::JustifyNone:
+-      break;
+-    case FormattedString::JustifyLeft:
+-      RightIndent = Difference;
+-      break;
+-    case FormattedString::JustifyRight:
+-      LeftIndent = Difference;
+-      break;
+-    case FormattedString::JustifyCenter:
+-      LeftIndent = Difference / 2;
+-      RightIndent = Difference - LeftIndent;
+-      break;
+-    }
+-  }
+-  indent(LeftIndent);
+-  (*this) << FS.Str;
+-  indent(RightIndent);
+-  return *this;
+-}
+-
+-raw_ostream &raw_ostream::operator<<(const FormattedNumber &FN) {
+-  if (FN.Hex) {
+-    HexPrintStyle Style;
+-    if (FN.Upper && FN.HexPrefix)
+-      Style = HexPrintStyle::PrefixUpper;
+-    else if (FN.Upper && !FN.HexPrefix)
+-      Style = HexPrintStyle::Upper;
+-    else if (!FN.Upper && FN.HexPrefix)
+-      Style = HexPrintStyle::PrefixLower;
+-    else
+-      Style = HexPrintStyle::Lower;
+-    llvm::write_hex(*this, FN.HexValue, Style, FN.Width);
+-  } else {
+-    llvm::SmallString<16> Buffer;
+-    llvm::raw_svector_ostream Stream(Buffer);
+-    llvm::write_integer(Stream, FN.DecValue, 0, IntegerStyle::Integer);
+-    if (Buffer.size() < FN.Width)
+-      indent(FN.Width - Buffer.size());
+-    (*this) << Buffer;
+-  }
+-  return *this;
+-}
+-
+-raw_ostream &raw_ostream::operator<<(const FormattedBytes &FB) {
+-  if (FB.Bytes.empty())
+-    return *this;
+-
+-  size_t LineIndex = 0;
+-  auto Bytes = FB.Bytes;
+-  const size_t Size = Bytes.size();
+-  HexPrintStyle HPS = FB.Upper ? HexPrintStyle::Upper : HexPrintStyle::Lower;
+-  uint64_t OffsetWidth = 0;
+-  if (FB.FirstByteOffset.hasValue()) {
+-    // Figure out how many nibbles are needed to print the largest offset
+-    // represented by this data set, so that we can align the offset field
+-    // to the right width.
+-    size_t Lines = Size / FB.NumPerLine;
+-    uint64_t MaxOffset = *FB.FirstByteOffset + Lines * FB.NumPerLine;
+-    unsigned Power = 0;
+-    if (MaxOffset > 0)
+-      Power = llvm::Log2_64_Ceil(MaxOffset);
+-    OffsetWidth = std::max<uint64_t>(4, llvm::alignTo(Power, 4) / 4);
+-  }
+-
+-  // The width of a block of data including all spaces for group separators.
+-  unsigned NumByteGroups =
+-      alignTo(FB.NumPerLine, FB.ByteGroupSize) / FB.ByteGroupSize;
+-  unsigned BlockCharWidth = FB.NumPerLine * 2 + NumByteGroups - 1;
+-
+-  while (!Bytes.empty()) {
+-    indent(FB.IndentLevel);
+-
+-    if (FB.FirstByteOffset.hasValue()) {
+-      uint64_t Offset = FB.FirstByteOffset.getValue();
+-      llvm::write_hex(*this, Offset + LineIndex, HPS, OffsetWidth);
+-      *this << ": ";
+-    }
+-
+-    auto Line = Bytes.take_front(FB.NumPerLine);
+-
+-    size_t CharsPrinted = 0;
+-    // Print the hex bytes for this line in groups
+-    for (size_t I = 0; I < Line.size(); ++I, CharsPrinted += 2) {
+-      if (I && (I % FB.ByteGroupSize) == 0) {
+-        ++CharsPrinted;
+-        *this << " ";
+-      }
+-      llvm::write_hex(*this, Line[I], HPS, 2);
+-    }
+-
+-    if (FB.ASCII) {
+-      // Print any spaces needed for any bytes that we didn't print on this
+-      // line so that the ASCII bytes are correctly aligned.
+-      assert(BlockCharWidth >= CharsPrinted);
+-      indent(BlockCharWidth - CharsPrinted + 2);
+-      *this << "|";
+-
+-      // Print the ASCII char values for each byte on this line
+-      for (uint8_t Byte : Line) {
+-        if (isPrint(Byte))
+-          *this << static_cast<char>(Byte);
+-        else
+-          *this << '.';
+-      }
+-      *this << '|';
+-    }
+-
+-    Bytes = Bytes.drop_front(Line.size());
+-    LineIndex += Line.size();
+-    if (LineIndex < Size)
+-      *this << '\n';
+-  }
+-  return *this;
+-}
+ 
+ template <char C>
+ static raw_ostream &write_padding(raw_ostream &OS, unsigned NumChars) {
+@@ -506,63 +296,8 @@ raw_ostream &raw_ostream::write_zeros(unsigned NumZeros) {
+   return write_padding<'\0'>(*this, NumZeros);
+ }
+ 
+-bool raw_ostream::prepare_colors() {
+-  // Colors were explicitly disabled.
+-  if (!ColorEnabled)
+-    return false;
+-
+-  // Colors require changing the terminal but this stream is not going to a
+-  // terminal.
+-  if (sys::Process::ColorNeedsFlush() && !is_displayed())
+-    return false;
+-
+-  if (sys::Process::ColorNeedsFlush())
+-    flush();
+-
+-  return true;
+-}
+-
+-raw_ostream &raw_ostream::changeColor(enum Colors colors, bool bold, bool bg) {
+-  if (!prepare_colors())
+-    return *this;
+-
+-  const char *colorcode =
+-      (colors == SAVEDCOLOR)
+-          ? sys::Process::OutputBold(bg)
+-          : sys::Process::OutputColor(static_cast<char>(colors), bold, bg);
+-  if (colorcode)
+-    write(colorcode, strlen(colorcode));
+-  return *this;
+-}
+-
+-raw_ostream &raw_ostream::resetColor() {
+-  if (!prepare_colors())
+-    return *this;
+-
+-  if (const char *colorcode = sys::Process::ResetColor())
+-    write(colorcode, strlen(colorcode));
+-  return *this;
+-}
+-
+-raw_ostream &raw_ostream::reverseColor() {
+-  if (!prepare_colors())
+-    return *this;
+-
+-  if (const char *colorcode = sys::Process::OutputReverse())
+-    write(colorcode, strlen(colorcode));
+-  return *this;
+-}
+-
+ void raw_ostream::anchor() {}
+ 
+-//===----------------------------------------------------------------------===//
+-//  Formatted Output
+-//===----------------------------------------------------------------------===//
+-
+-// Out of line virtual method.
+-void format_object_base::home() {
+-}
+-
+ //===----------------------------------------------------------------------===//
+ //  raw_fd_ostream
+ //===----------------------------------------------------------------------===//
+@@ -854,31 +589,6 @@ size_t raw_fd_ostream::preferred_buffer_size() const {
+ #endif
+ }
+ 
+-bool raw_fd_ostream::is_displayed() const {
+-  return sys::Process::FileDescriptorIsDisplayed(FD);
+-}
+-
+-bool raw_fd_ostream::has_colors() const {
+-  if (!HasColors)
+-    HasColors = sys::Process::FileDescriptorHasColors(FD);
+-  return *HasColors;
+-}
+-
+-Expected<sys::fs::FileLocker> raw_fd_ostream::lock() {
+-  std::error_code EC = sys::fs::lockFile(FD);
+-  if (!EC)
+-    return sys::fs::FileLocker(FD);
+-  return errorCodeToError(EC);
+-}
+-
+-Expected<sys::fs::FileLocker>
+-raw_fd_ostream::tryLockFor(Duration const& Timeout) {
+-  std::error_code EC = sys::fs::tryLockFile(FD, Timeout.getDuration());
+-  if (!EC)
+-    return sys::fs::FileLocker(FD);
+-  return errorCodeToError(EC);
+-}
+-
+ void raw_fd_ostream::anchor() {}
+ 
+ //===----------------------------------------------------------------------===//
+@@ -921,16 +631,6 @@ raw_fd_stream::raw_fd_stream(std::string_view Filename, std::error_code &EC)
+     EC = std::make_error_code(std::errc::invalid_argument);
+ }
+ 
+-ssize_t raw_fd_stream::read(char *Ptr, size_t Size) {
+-  assert(get_fd() >= 0 && "File already closed.");
+-  ssize_t Ret = ::read(get_fd(), (void *)Ptr, Size);
+-  if (Ret >= 0)
+-    inc_pos(Ret);
+-  else
+-    error_detected(std::error_code(errno, std::generic_category()));
+-  return Ret;
+-}
+-
+ bool raw_fd_stream::classof(const raw_ostream *OS) {
+   return OS->get_kind() == OStreamKind::OK_FDStream;
+ }
+@@ -986,31 +686,3 @@ void raw_pwrite_stream::anchor() {}
+ void buffer_ostream::anchor() {}
+ 
+ void buffer_unique_ostream::anchor() {}
+-
+-Error llvm::writeToOutput(std::string_view OutputFileName,
+-                          std::function<Error(raw_ostream &)> Write) {
+-  if (OutputFileName == "-")
+-    return Write(outs());
+-
+-  if (OutputFileName == "/dev/null") {
+-    raw_null_ostream Out;
+-    return Write(Out);
+-  }
+-
+-  unsigned Mode = sys::fs::all_read | sys::fs::all_write | sys::fs::all_exe;
+-  Expected<sys::fs::TempFile> Temp =
+-      sys::fs::TempFile::create(OutputFileName + ".temp-stream-%%%%%%", Mode);
+-  if (!Temp)
+-    return createFileError(OutputFileName, Temp.takeError());
+-
+-  raw_fd_ostream Out(Temp->FD, false);
+-
+-  if (Error E = Write(Out)) {
+-    if (Error DiscardError = Temp->discard())
+-      return joinErrors(std::move(E), std::move(DiscardError));
+-    return E;
+-  }
+-  Out.flush();
+-
+-  return Temp->keep(OutputFileName);
+-}
diff --git a/third_party/allwpilib/upstream_utils/llvm_patches/0011-Detemplatize-SmallVectorBase.patch b/third_party/allwpilib/upstream_utils/llvm_patches/0011-Detemplatize-SmallVectorBase.patch
new file mode 100644
index 0000000..320e500
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/llvm_patches/0011-Detemplatize-SmallVectorBase.patch
@@ -0,0 +1,140 @@
+From ef26f059859d3a0d08b06a70519928bcd5f9bb79 Mon Sep 17 00:00:00 2001
+From: PJ Reiniger <pj.reiniger@gmail.com>
+Date: Thu, 5 May 2022 23:18:34 -0400
+Subject: [PATCH 11/28] Detemplatize SmallVectorBase
+
+---
+ llvm/include/llvm/ADT/SmallVector.h | 21 +++++++-----------
+ llvm/lib/Support/SmallVector.cpp    | 34 +++++------------------------
+ 2 files changed, 13 insertions(+), 42 deletions(-)
+
+diff --git a/llvm/include/llvm/ADT/SmallVector.h b/llvm/include/llvm/ADT/SmallVector.h
+index 1e311ea56..4b6bbdeb2 100644
+--- a/llvm/include/llvm/ADT/SmallVector.h
++++ b/llvm/include/llvm/ADT/SmallVector.h
+@@ -50,14 +50,14 @@ template <typename IteratorT> class iterator_range;
+ /// Using 64 bit size is desirable for cases like SmallVector<char>, where a
+ /// 32 bit size would limit the vector to ~4GB. SmallVectors are used for
+ /// buffering bitcode output - which can exceed 4GB.
+-template <class Size_T> class SmallVectorBase {
++class SmallVectorBase {
+ protected:
+   void *BeginX;
+-  Size_T Size = 0, Capacity;
++  unsigned Size = 0, Capacity;
+ 
+   /// The maximum value of the Size_T used.
+   static constexpr size_t SizeTypeMax() {
+-    return (std::numeric_limits<Size_T>::max)();
++    return (std::numeric_limits<unsigned>::max)();
+   }
+ 
+   SmallVectorBase() = delete;
+@@ -91,15 +91,10 @@ protected:
+   }
+ };
+ 
+-template <class T>
+-using SmallVectorSizeType =
+-    typename std::conditional<sizeof(T) < 4 && sizeof(void *) >= 8, uint64_t,
+-                              uint32_t>::type;
+-
+ /// Figure out the offset of the first element.
+ template <class T, typename = void> struct SmallVectorAlignmentAndSize {
+-  alignas(SmallVectorBase<SmallVectorSizeType<T>>) char Base[sizeof(
+-      SmallVectorBase<SmallVectorSizeType<T>>)];
++  alignas(SmallVectorBase) char Base[sizeof(
++      SmallVectorBase)];
+   alignas(T) char FirstEl[sizeof(T)];
+ };
+ 
+@@ -108,8 +103,8 @@ template <class T, typename = void> struct SmallVectorAlignmentAndSize {
+ /// to avoid unnecessarily requiring T to be complete.
+ template <typename T, typename = void>
+ class SmallVectorTemplateCommon
+-    : public SmallVectorBase<SmallVectorSizeType<T>> {
+-  using Base = SmallVectorBase<SmallVectorSizeType<T>>;
++    : public SmallVectorBase {
++  using Base = SmallVectorBase;
+ 
+   /// Find the address of the first element.  For this pointer math to be valid
+   /// with small-size of 0 for T with lots of alignment, it's important that
+@@ -356,7 +351,7 @@ protected:
+   /// in \p NewCapacity. This is the first section of \a grow().
+   T *mallocForGrow(size_t MinSize, size_t &NewCapacity) {
+     return static_cast<T *>(
+-        SmallVectorBase<SmallVectorSizeType<T>>::mallocForGrow(
++        SmallVectorBase::mallocForGrow(
+             MinSize, sizeof(T), NewCapacity));
+   }
+ 
+diff --git a/llvm/lib/Support/SmallVector.cpp b/llvm/lib/Support/SmallVector.cpp
+index a2b4899e1..bdfc963d7 100644
+--- a/llvm/lib/Support/SmallVector.cpp
++++ b/llvm/lib/Support/SmallVector.cpp
+@@ -51,10 +51,6 @@ static_assert(sizeof(SmallVector<void *, 1>) ==
+                   sizeof(unsigned) * 2 + sizeof(void *) * 2,
+               "wasted space in SmallVector size 1");
+ 
+-static_assert(sizeof(SmallVector<char, 0>) ==
+-                  sizeof(void *) * 2 + sizeof(void *),
+-              "1 byte elements have word-sized type for size and capacity");
+-
+ /// Report that MinSize doesn't fit into this vector's size type. Throws
+ /// std::length_error or calls report_fatal_error.
+ [[noreturn]] static void report_size_overflow(size_t MinSize, size_t MaxSize);
+@@ -85,9 +81,8 @@ static void report_at_maximum_capacity(size_t MaxSize) {
+ }
+ 
+ // Note: Moving this function into the header may cause performance regression.
+-template <class Size_T>
+ static size_t getNewCapacity(size_t MinSize, size_t TSize, size_t OldCapacity) {
+-  constexpr size_t MaxSize = std::numeric_limits<Size_T>::max();
++  constexpr size_t MaxSize = std::numeric_limits<unsigned>::max();
+ 
+   // Ensure we can fit the new capacity.
+   // This is only going to be applicable when the capacity is 32 bit.
+@@ -108,18 +103,16 @@ static size_t getNewCapacity(size_t MinSize, size_t TSize, size_t OldCapacity) {
+ }
+ 
+ // Note: Moving this function into the header may cause performance regression.
+-template <class Size_T>
+-void *SmallVectorBase<Size_T>::mallocForGrow(size_t MinSize, size_t TSize,
++void *SmallVectorBase::mallocForGrow(size_t MinSize, size_t TSize,
+                                              size_t &NewCapacity) {
+-  NewCapacity = getNewCapacity<Size_T>(MinSize, TSize, this->capacity());
++  NewCapacity = getNewCapacity(MinSize, TSize, this->capacity());
+   return llvm::safe_malloc(NewCapacity * TSize);
+ }
+ 
+ // Note: Moving this function into the header may cause performance regression.
+-template <class Size_T>
+-void SmallVectorBase<Size_T>::grow_pod(void *FirstEl, size_t MinSize,
++void SmallVectorBase::grow_pod(void *FirstEl, size_t MinSize,
+                                        size_t TSize) {
+-  size_t NewCapacity = getNewCapacity<Size_T>(MinSize, TSize, this->capacity());
++  size_t NewCapacity = getNewCapacity(MinSize, TSize, this->capacity());
+   void *NewElts;
+   if (BeginX == FirstEl) {
+     NewElts = safe_malloc(NewCapacity * TSize);
+@@ -134,20 +127,3 @@ void SmallVectorBase<Size_T>::grow_pod(void *FirstEl, size_t MinSize,
+   this->BeginX = NewElts;
+   this->Capacity = NewCapacity;
+ }
+-
+-template class llvm::SmallVectorBase<uint32_t>;
+-
+-// Disable the uint64_t instantiation for 32-bit builds.
+-// Both uint32_t and uint64_t instantiations are needed for 64-bit builds.
+-// This instantiation will never be used in 32-bit builds, and will cause
+-// warnings when sizeof(Size_T) > sizeof(size_t).
+-#if SIZE_MAX > UINT32_MAX
+-template class llvm::SmallVectorBase<uint64_t>;
+-
+-// Assertions to ensure this #if stays in sync with SmallVectorSizeType.
+-static_assert(sizeof(SmallVectorSizeType<char>) == sizeof(uint64_t),
+-              "Expected SmallVectorBase<uint64_t> variant to be in use.");
+-#else
+-static_assert(sizeof(SmallVectorSizeType<char>) == sizeof(uint32_t),
+-              "Expected SmallVectorBase<uint32_t> variant to be in use.");
+-#endif
diff --git a/third_party/allwpilib/upstream_utils/llvm_patches/0012-Add-vectors-to-raw_ostream.patch b/third_party/allwpilib/upstream_utils/llvm_patches/0012-Add-vectors-to-raw_ostream.patch
new file mode 100644
index 0000000..cc0bd5d
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/llvm_patches/0012-Add-vectors-to-raw_ostream.patch
@@ -0,0 +1,214 @@
+From 342ebd445bb3dae8b0c119a6126a318ad378a377 Mon Sep 17 00:00:00 2001
+From: PJ Reiniger <pj.reiniger@gmail.com>
+Date: Sun, 8 May 2022 13:48:59 -0400
+Subject: [PATCH 12/28] Add vectors to raw_ostream
+
+---
+ llvm/include/llvm/Support/raw_ostream.h | 115 ++++++++++++++++++++++++
+ llvm/lib/Support/raw_ostream.cpp        |  47 ++++++++++
+ 2 files changed, 162 insertions(+)
+
+diff --git a/llvm/include/llvm/Support/raw_ostream.h b/llvm/include/llvm/Support/raw_ostream.h
+index d4521c8e2..bf5630ab5 100644
+--- a/llvm/include/llvm/Support/raw_ostream.h
++++ b/llvm/include/llvm/Support/raw_ostream.h
+@@ -25,6 +25,7 @@
+ #endif
+ #include <system_error>
+ #include <type_traits>
++#include <vector>
+ 
+ namespace llvm {
+ 
+@@ -248,12 +249,24 @@ public:
+     return write(Str.data(), Str.size());
+   }
+ 
++  raw_ostream &operator<<(const std::vector<uint8_t> &Arr) {
++    // Avoid the fast path, it would only increase code size for a marginal win.
++    return write(Arr.data(), Arr.size());
++  }
++
++  raw_ostream &operator<<(const SmallVectorImpl<uint8_t> &Arr) {
++    return write(Arr.data(), Arr.size());
++  }
++
+   /// Output \p Str, turning '\\', '\t', '\n', '"', and anything that doesn't
+   /// satisfy llvm::isPrint into an escape sequence.
+   raw_ostream &write_escaped(std::string_view Str, bool UseHexEscapes = false);
+ 
+   raw_ostream &write(unsigned char C);
+   raw_ostream &write(const char *Ptr, size_t Size);
++  raw_ostream &write(const uint8_t *Ptr, size_t Size) {
++    return write(reinterpret_cast<const char *>(Ptr), Size);
++  }
+ 
+   /// indent - Insert 'NumSpaces' spaces.
+   raw_ostream &indent(unsigned NumSpaces);
+@@ -604,6 +617,108 @@ public:
+   }
+ };
+ 
++/// A raw_ostream that writes to a vector.  This is a
++/// simple adaptor class. This class does not encounter output errors.
++/// raw_vector_ostream operates without a buffer, delegating all memory
++/// management to the vector. Thus the vector is always up-to-date,
++/// may be used directly and there is no need to call flush().
++class raw_vector_ostream : public raw_pwrite_stream {
++  std::vector<char> &OS;
++
++  /// See raw_ostream::write_impl.
++  void write_impl(const char *Ptr, size_t Size) override;
++
++  void pwrite_impl(const char *Ptr, size_t Size, uint64_t Offset) override;
++
++  /// Return the current position within the stream.
++  uint64_t current_pos() const override;
++
++public:
++  /// Construct a new raw_svector_ostream.
++  ///
++  /// \param O The vector to write to; this should generally have at least 128
++  /// bytes free to avoid any extraneous memory overhead.
++  explicit raw_vector_ostream(std::vector<char> &O) : OS(O) {
++    SetUnbuffered();
++  }
++
++  ~raw_vector_ostream() override = default;
++
++  void flush() = delete;
++
++  /// Return a std::string_view for the vector contents.
++  std::string_view str() { return std::string_view(OS.data(), OS.size()); }
++};
++
++/// A raw_ostream that writes to an SmallVector or SmallString.  This is a
++/// simple adaptor class. This class does not encounter output errors.
++/// raw_svector_ostream operates without a buffer, delegating all memory
++/// management to the SmallString. Thus the SmallString is always up-to-date,
++/// may be used directly and there is no need to call flush().
++class raw_usvector_ostream : public raw_pwrite_stream {
++  SmallVectorImpl<uint8_t> &OS;
++
++  /// See raw_ostream::write_impl.
++  void write_impl(const char *Ptr, size_t Size) override;
++
++  void pwrite_impl(const char *Ptr, size_t Size, uint64_t Offset) override;
++
++  /// Return the current position within the stream.
++  uint64_t current_pos() const override;
++
++public:
++  /// Construct a new raw_svector_ostream.
++  ///
++  /// \param O The vector to write to; this should generally have at least 128
++  /// bytes free to avoid any extraneous memory overhead.
++  explicit raw_usvector_ostream(SmallVectorImpl<uint8_t> &O) : OS(O) {
++    SetUnbuffered();
++  }
++
++  ~raw_usvector_ostream() override = default;
++
++  void flush() = delete;
++
++  /// Return an span for the vector contents.
++  span<uint8_t> array() { return {OS.data(), OS.size()}; }
++  span<const uint8_t> array() const { return {OS.data(), OS.size()}; }
++};
++
++/// A raw_ostream that writes to a vector.  This is a
++/// simple adaptor class. This class does not encounter output errors.
++/// raw_vector_ostream operates without a buffer, delegating all memory
++/// management to the vector. Thus the vector is always up-to-date,
++/// may be used directly and there is no need to call flush().
++class raw_uvector_ostream : public raw_pwrite_stream {
++  std::vector<uint8_t> &OS;
++
++  /// See raw_ostream::write_impl.
++  void write_impl(const char *Ptr, size_t Size) override;
++
++  void pwrite_impl(const char *Ptr, size_t Size, uint64_t Offset) override;
++
++  /// Return the current position within the stream.
++  uint64_t current_pos() const override;
++
++public:
++  /// Construct a new raw_svector_ostream.
++  ///
++  /// \param O The vector to write to; this should generally have at least 128
++  /// bytes free to avoid any extraneous memory overhead.
++  explicit raw_uvector_ostream(std::vector<uint8_t> &O) : OS(O) {
++    SetUnbuffered();
++  }
++
++  ~raw_uvector_ostream() override = default;
++
++  void flush() = delete;
++
++  /// Return a span for the vector contents.
++  span<uint8_t> array() { return {OS.data(), OS.size()}; }
++  span<const uint8_t> array() const { return {OS.data(), OS.size()}; }
++};
++
++
+ /// A raw_ostream that discards all output.
+ class raw_null_ostream : public raw_pwrite_stream {
+   /// See raw_ostream::write_impl.
+diff --git a/llvm/lib/Support/raw_ostream.cpp b/llvm/lib/Support/raw_ostream.cpp
+index 875eda7ba..36faf744c 100644
+--- a/llvm/lib/Support/raw_ostream.cpp
++++ b/llvm/lib/Support/raw_ostream.cpp
+@@ -658,6 +658,53 @@ void raw_svector_ostream::pwrite_impl(const char *Ptr, size_t Size,
+   memcpy(OS.data() + Offset, Ptr, Size);
+ }
+ 
++//===----------------------------------------------------------------------===//
++//  raw_vector_ostream
++//===----------------------------------------------------------------------===//
++
++uint64_t raw_vector_ostream::current_pos() const { return OS.size(); }
++
++void raw_vector_ostream::write_impl(const char *Ptr, size_t Size) {
++  OS.insert(OS.end(), Ptr, Ptr + Size);
++}
++
++void raw_vector_ostream::pwrite_impl(const char *Ptr, size_t Size,
++                                     uint64_t Offset) {
++  memcpy(OS.data() + Offset, Ptr, Size);
++}
++
++//===----------------------------------------------------------------------===//
++//  raw_usvector_ostream
++//===----------------------------------------------------------------------===//
++
++uint64_t raw_usvector_ostream::current_pos() const { return OS.size(); }
++
++void raw_usvector_ostream::write_impl(const char *Ptr, size_t Size) {
++  OS.append(reinterpret_cast<const uint8_t *>(Ptr),
++            reinterpret_cast<const uint8_t *>(Ptr) + Size);
++}
++
++void raw_usvector_ostream::pwrite_impl(const char *Ptr, size_t Size,
++                                       uint64_t Offset) {
++  memcpy(OS.data() + Offset, Ptr, Size);
++}
++
++//===----------------------------------------------------------------------===//
++//  raw_uvector_ostream
++//===----------------------------------------------------------------------===//
++
++uint64_t raw_uvector_ostream::current_pos() const { return OS.size(); }
++
++void raw_uvector_ostream::write_impl(const char *Ptr, size_t Size) {
++  OS.insert(OS.end(), reinterpret_cast<const uint8_t *>(Ptr),
++            reinterpret_cast<const uint8_t *>(Ptr) + Size);
++}
++
++void raw_uvector_ostream::pwrite_impl(const char *Ptr, size_t Size,
++                                      uint64_t Offset) {
++  memcpy(OS.data() + Offset, Ptr, Size);
++}
++
+ //===----------------------------------------------------------------------===//
+ //  raw_null_ostream
+ //===----------------------------------------------------------------------===//
diff --git a/third_party/allwpilib/upstream_utils/llvm_patches/0013-Extra-collections-features.patch b/third_party/allwpilib/upstream_utils/llvm_patches/0013-Extra-collections-features.patch
new file mode 100644
index 0000000..19aef1a
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/llvm_patches/0013-Extra-collections-features.patch
@@ -0,0 +1,162 @@
+From 5db7e9f9370a5e04949846cc68eeb13e2c1db187 Mon Sep 17 00:00:00 2001
+From: PJ Reiniger <pj.reiniger@gmail.com>
+Date: Tue, 3 May 2022 22:16:10 -0400
+Subject: [PATCH 13/28] Extra collections features
+
+---
+ llvm/include/llvm/ADT/StringMap.h | 103 +++++++++++++++++++++++++++++-
+ llvm/lib/Support/raw_ostream.cpp  |   8 +++
+ 2 files changed, 110 insertions(+), 1 deletion(-)
+
+diff --git a/llvm/include/llvm/ADT/StringMap.h b/llvm/include/llvm/ADT/StringMap.h
+index 8747cdb35..16f13f048 100644
+--- a/llvm/include/llvm/ADT/StringMap.h
++++ b/llvm/include/llvm/ADT/StringMap.h
+@@ -42,7 +42,7 @@ protected:
+ 
+ protected:
+   explicit StringMapImpl(unsigned itemSize) : ItemSize(itemSize) {}
+-  StringMapImpl(StringMapImpl &&RHS)
++  StringMapImpl(StringMapImpl &&RHS) noexcept
+       : TheTable(RHS.TheTable), NumBuckets(RHS.NumBuckets),
+         NumItems(RHS.NumItems), NumTombstones(RHS.NumTombstones),
+         ItemSize(RHS.ItemSize) {
+@@ -420,11 +420,27 @@ public:
+     return Tmp;
+   }
+ 
++  DerivedTy &operator--() { // Predecrement
++    --Ptr;
++    ReversePastEmptyBuckets();
++    return static_cast<DerivedTy &>(*this);
++  }
++
++  DerivedTy operator--(int) { // Post-decrement
++    DerivedTy Tmp(Ptr);
++    --*this;
++    return Tmp;
++  }
++
+ private:
+   void AdvancePastEmptyBuckets() {
+     while (*Ptr == nullptr || *Ptr == StringMapImpl::getTombstoneVal())
+       ++Ptr;
+   }
++  void ReversePastEmptyBuckets() {
++    while (*Ptr == nullptr || *Ptr == StringMapImpl::getTombstoneVal())
++      --Ptr;
++  }
+ };
+ 
+ template <typename ValueTy>
+@@ -483,6 +499,91 @@ public:
+   std::string_view operator*() const { return this->wrapped()->getKey(); }
+ };
+ 
++template <typename ValueTy>
++bool operator==(const StringMap<ValueTy>& lhs, const StringMap<ValueTy>& rhs) {
++  // same instance?
++  if (&lhs == &rhs) return true;
++
++  // first check that sizes are identical
++  if (lhs.size() != rhs.size()) return false;
++
++  // copy into vectors and sort by key
++  SmallVector<StringMapConstIterator<ValueTy>, 16> lhs_items;
++  lhs_items.reserve(lhs.size());
++  for (auto i = lhs.begin(), end = lhs.end(); i != end; ++i)
++    lhs_items.push_back(i);
++  std::sort(lhs_items.begin(), lhs_items.end(),
++            [](const StringMapConstIterator<ValueTy>& a,
++               const StringMapConstIterator<ValueTy>& b) {
++              return a->getKey() < b->getKey();
++            });
++
++  SmallVector<StringMapConstIterator<ValueTy>, 16> rhs_items;
++  rhs_items.reserve(rhs.size());
++  for (auto i = rhs.begin(), end = rhs.end(); i != end; ++i)
++    rhs_items.push_back(i);
++  std::sort(rhs_items.begin(), rhs_items.end(),
++            [](const StringMapConstIterator<ValueTy>& a,
++               const StringMapConstIterator<ValueTy>& b) {
++              return a->getKey() < b->getKey();
++            });
++
++  // compare vector keys and values
++  for (auto a = lhs_items.begin(), b = rhs_items.begin(),
++            aend = lhs_items.end(), bend = rhs_items.end();
++       a != aend && b != bend; ++a, ++b) {
++    if ((*a)->first() != (*b)->first() || (*a)->second != (*b)->second)
++      return false;
++  }
++  return true;
++}
++
++template <typename ValueTy>
++inline bool operator!=(const StringMap<ValueTy>& lhs,
++                       const StringMap<ValueTy>& rhs) {
++  return !(lhs == rhs);
++}
++
++template <typename ValueTy>
++bool operator<(const StringMap<ValueTy>& lhs, const StringMap<ValueTy>& rhs) {
++  // same instance?
++  if (&lhs == &rhs) return false;
++
++  // copy into vectors and sort by key
++  SmallVector<std::string_view, 16> lhs_keys;
++  lhs_keys.reserve(lhs.size());
++  for (auto i = lhs.begin(), end = lhs.end(); i != end; ++i)
++    lhs_keys.push_back(i->getKey());
++  std::sort(lhs_keys.begin(), lhs_keys.end());
++
++  SmallVector<std::string_view, 16> rhs_keys;
++  rhs_keys.reserve(rhs.size());
++  for (auto i = rhs.begin(), end = rhs.end(); i != end; ++i)
++    rhs_keys.push_back(i->getKey());
++  std::sort(rhs_keys.begin(), rhs_keys.end());
++
++  // use std::vector comparison
++  return lhs_keys < rhs_keys;
++}
++
++template <typename ValueTy>
++inline bool operator<=(const StringMap<ValueTy>& lhs,
++                       const StringMap<ValueTy>& rhs) {
++  return !(rhs < lhs);
++}
++
++template <typename ValueTy>
++inline bool operator>(const StringMap<ValueTy>& lhs,
++                      const StringMap<ValueTy>& rhs) {
++  return !(lhs <= rhs);
++}
++
++template <typename ValueTy>
++inline bool operator>=(const StringMap<ValueTy>& lhs,
++                       const StringMap<ValueTy>& rhs) {
++  return !(lhs < rhs);
++}
++
+ } // end namespace llvm
+ 
+ #endif // LLVM_ADT_STRINGMAP_H
+diff --git a/llvm/lib/Support/raw_ostream.cpp b/llvm/lib/Support/raw_ostream.cpp
+index 36faf744c..95152849c 100644
+--- a/llvm/lib/Support/raw_ostream.cpp
++++ b/llvm/lib/Support/raw_ostream.cpp
+@@ -76,6 +76,14 @@ constexpr raw_ostream::Colors raw_ostream::WHITE;
+ constexpr raw_ostream::Colors raw_ostream::SAVEDCOLOR;
+ constexpr raw_ostream::Colors raw_ostream::RESET;
+ 
++namespace {
++// Find the length of an array.
++template <class T, std::size_t N>
++constexpr inline size_t array_lengthof(T (&)[N]) {
++  return N;
++}
++}  // namespace
++
+ raw_ostream::~raw_ostream() {
+   // raw_ostream's subclasses should take care to flush the buffer
+   // in their destructors.
diff --git a/third_party/allwpilib/upstream_utils/llvm_patches/0014-EpochTracker-ABI-macro.patch b/third_party/allwpilib/upstream_utils/llvm_patches/0014-EpochTracker-ABI-macro.patch
new file mode 100644
index 0000000..1049911
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/llvm_patches/0014-EpochTracker-ABI-macro.patch
@@ -0,0 +1,22 @@
+From 9951c4b3fea6b2dbe7141070444de8df6ae4ce9b Mon Sep 17 00:00:00 2001
+From: PJ Reiniger <pj.reiniger@gmail.com>
+Date: Wed, 4 May 2022 00:01:00 -0400
+Subject: [PATCH 14/28] EpochTracker ABI macro
+
+---
+ llvm/include/llvm/ADT/EpochTracker.h | 2 +-
+ 1 file changed, 1 insertion(+), 1 deletion(-)
+
+diff --git a/llvm/include/llvm/ADT/EpochTracker.h b/llvm/include/llvm/ADT/EpochTracker.h
+index b06888494..f35461d1c 100644
+--- a/llvm/include/llvm/ADT/EpochTracker.h
++++ b/llvm/include/llvm/ADT/EpochTracker.h
+@@ -22,7 +22,7 @@
+ 
+ namespace llvm {
+ 
+-#if LLVM_ENABLE_ABI_BREAKING_CHECKS
++#ifndef NDEBUG //ifndef LLVM_ENABLE_ABI_BREAKING_CHECKS
+ 
+ /// A base class for data structure classes wishing to make iterators
+ /// ("handles") pointing into themselves fail-fast.  When building without
diff --git a/third_party/allwpilib/upstream_utils/llvm_patches/0015-Delete-numbers-from-MathExtras.patch b/third_party/allwpilib/upstream_utils/llvm_patches/0015-Delete-numbers-from-MathExtras.patch
new file mode 100644
index 0000000..5578739
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/llvm_patches/0015-Delete-numbers-from-MathExtras.patch
@@ -0,0 +1,56 @@
+From 907608f09061ab272b0a127330b1b24e28d50a9f Mon Sep 17 00:00:00 2001
+From: PJ Reiniger <pj.reiniger@gmail.com>
+Date: Thu, 5 May 2022 18:09:45 -0400
+Subject: [PATCH 15/28] Delete numbers from MathExtras
+
+---
+ llvm/include/llvm/Support/MathExtras.h | 36 --------------------------
+ 1 file changed, 36 deletions(-)
+
+diff --git a/llvm/include/llvm/Support/MathExtras.h b/llvm/include/llvm/Support/MathExtras.h
+index fac12dd0e..e8f1f2aca 100644
+--- a/llvm/include/llvm/Support/MathExtras.h
++++ b/llvm/include/llvm/Support/MathExtras.h
+@@ -50,42 +50,6 @@ enum ZeroBehavior {
+   ZB_Width
+ };
+ 
+-/// Mathematical constants.
+-namespace numbers {
+-// TODO: Track C++20 std::numbers.
+-// TODO: Favor using the hexadecimal FP constants (requires C++17).
+-constexpr double e          = 2.7182818284590452354, // (0x1.5bf0a8b145749P+1) https://oeis.org/A001113
+-                 egamma     = .57721566490153286061, // (0x1.2788cfc6fb619P-1) https://oeis.org/A001620
+-                 ln2        = .69314718055994530942, // (0x1.62e42fefa39efP-1) https://oeis.org/A002162
+-                 ln10       = 2.3025850929940456840, // (0x1.24bb1bbb55516P+1) https://oeis.org/A002392
+-                 log2e      = 1.4426950408889634074, // (0x1.71547652b82feP+0)
+-                 log10e     = .43429448190325182765, // (0x1.bcb7b1526e50eP-2)
+-                 pi         = 3.1415926535897932385, // (0x1.921fb54442d18P+1) https://oeis.org/A000796
+-                 inv_pi     = .31830988618379067154, // (0x1.45f306bc9c883P-2) https://oeis.org/A049541
+-                 sqrtpi     = 1.7724538509055160273, // (0x1.c5bf891b4ef6bP+0) https://oeis.org/A002161
+-                 inv_sqrtpi = .56418958354775628695, // (0x1.20dd750429b6dP-1) https://oeis.org/A087197
+-                 sqrt2      = 1.4142135623730950488, // (0x1.6a09e667f3bcdP+0) https://oeis.org/A00219
+-                 inv_sqrt2  = .70710678118654752440, // (0x1.6a09e667f3bcdP-1)
+-                 sqrt3      = 1.7320508075688772935, // (0x1.bb67ae8584caaP+0) https://oeis.org/A002194
+-                 inv_sqrt3  = .57735026918962576451, // (0x1.279a74590331cP-1)
+-                 phi        = 1.6180339887498948482; // (0x1.9e3779b97f4a8P+0) https://oeis.org/A001622
+-constexpr float ef          = 2.71828183F, // (0x1.5bf0a8P+1) https://oeis.org/A001113
+-                egammaf     = .577215665F, // (0x1.2788d0P-1) https://oeis.org/A001620
+-                ln2f        = .693147181F, // (0x1.62e430P-1) https://oeis.org/A002162
+-                ln10f       = 2.30258509F, // (0x1.26bb1cP+1) https://oeis.org/A002392
+-                log2ef      = 1.44269504F, // (0x1.715476P+0)
+-                log10ef     = .434294482F, // (0x1.bcb7b2P-2)
+-                pif         = 3.14159265F, // (0x1.921fb6P+1) https://oeis.org/A000796
+-                inv_pif     = .318309886F, // (0x1.45f306P-2) https://oeis.org/A049541
+-                sqrtpif     = 1.77245385F, // (0x1.c5bf8aP+0) https://oeis.org/A002161
+-                inv_sqrtpif = .564189584F, // (0x1.20dd76P-1) https://oeis.org/A087197
+-                sqrt2f      = 1.41421356F, // (0x1.6a09e6P+0) https://oeis.org/A002193
+-                inv_sqrt2f  = .707106781F, // (0x1.6a09e6P-1)
+-                sqrt3f      = 1.73205081F, // (0x1.bb67aeP+0) https://oeis.org/A002194
+-                inv_sqrt3f  = .577350269F, // (0x1.279a74P-1)
+-                phif        = 1.61803399F; // (0x1.9e377aP+0) https://oeis.org/A001622
+-} // namespace numbers
+-
+ namespace detail {
+ template <typename T, std::size_t SizeOfT> struct TrailingZerosCounter {
+   static unsigned count(T Val, ZeroBehavior) {
diff --git a/third_party/allwpilib/upstream_utils/llvm_patches/0016-Add-lerp-and-sgn.patch b/third_party/allwpilib/upstream_utils/llvm_patches/0016-Add-lerp-and-sgn.patch
new file mode 100644
index 0000000..8dcc9c7
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/llvm_patches/0016-Add-lerp-and-sgn.patch
@@ -0,0 +1,40 @@
+From 9ef10e5b331d00d7d5822afdb70c1f2d9981d772 Mon Sep 17 00:00:00 2001
+From: PJ Reiniger <pj.reiniger@gmail.com>
+Date: Tue, 3 May 2022 22:50:24 -0400
+Subject: [PATCH 16/28] Add lerp and sgn
+
+---
+ llvm/include/llvm/Support/MathExtras.h | 20 ++++++++++++++++++++
+ 1 file changed, 20 insertions(+)
+
+diff --git a/llvm/include/llvm/Support/MathExtras.h b/llvm/include/llvm/Support/MathExtras.h
+index e8f1f2aca..8116c58bd 100644
+--- a/llvm/include/llvm/Support/MathExtras.h
++++ b/llvm/include/llvm/Support/MathExtras.h
+@@ -930,6 +930,26 @@ std::enable_if_t<std::is_signed<T>::value, T> MulOverflow(T X, T Y, T &Result) {
+     return UX > (static_cast<U>((std::numeric_limits<T>::max)())) / UY;
+ }
+ 
++// Typesafe implementation of the signum function.
++// Returns -1 if negative, 1 if positive, 0 if 0.
++template <typename T>
++constexpr int sgn(T val) {
++  return (T(0) < val) - (val < T(0));
++}
++
++/**
++ * Linearly interpolates between two values.
++ *
++ * @param startValue The start value.
++ * @param endValue The end value.
++ * @param t The fraction for interpolation.
++ *
++ * @return The interpolated value.
++ */
++template <typename T>
++constexpr T Lerp(const T& startValue, const T& endValue, double t) {
++  return startValue + (endValue - startValue) * t;
++}
+ } // End llvm namespace
+ 
+ #endif
diff --git a/third_party/allwpilib/upstream_utils/llvm_patches/0017-Fixup-includes.patch b/third_party/allwpilib/upstream_utils/llvm_patches/0017-Fixup-includes.patch
new file mode 100644
index 0000000..f247db0
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/llvm_patches/0017-Fixup-includes.patch
@@ -0,0 +1,168 @@
+From aa30b80d86cb0774efc094646339b54694ab8398 Mon Sep 17 00:00:00 2001
+From: PJ Reiniger <pj.reiniger@gmail.com>
+Date: Sun, 8 May 2022 16:38:11 -0400
+Subject: [PATCH 17/28] Fixup includes
+
+---
+ llvm/include/llvm/ADT/StringMap.h                 |  4 ++++
+ llvm/include/llvm/ADT/StringMapEntry.h            |  4 ++++
+ llvm/include/llvm/Support/PointerLikeTypeTraits.h |  1 +
+ llvm/lib/Support/ConvertUTFWrapper.cpp            |  1 +
+ llvm/lib/Support/ErrorHandling.cpp                |  7 +++----
+ llvm/lib/Support/raw_ostream.cpp                  | 12 ++++++------
+ llvm/unittests/ADT/SmallPtrSetTest.cpp            |  2 ++
+ llvm/unittests/ADT/StringMapTest.cpp              |  1 +
+ llvm/unittests/Support/ConvertUTFTest.cpp         |  2 ++
+ 9 files changed, 24 insertions(+), 10 deletions(-)
+
+diff --git a/llvm/include/llvm/ADT/StringMap.h b/llvm/include/llvm/ADT/StringMap.h
+index 16f13f048..6ae0e39a1 100644
+--- a/llvm/include/llvm/ADT/StringMap.h
++++ b/llvm/include/llvm/ADT/StringMap.h
+@@ -17,6 +17,10 @@
+ #include "llvm/ADT/StringMapEntry.h"
+ #include "llvm/ADT/iterator.h"
+ #include "llvm/Support/AllocatorBase.h"
++#include "llvm/Support/MemAlloc.h"
++#include "llvm/Support/SmallVector.h"
++#include "llvm/Support/iterator.h"
++#include "llvm/Support/iterator_range.h"
+ #include "llvm/Support/PointerLikeTypeTraits.h"
+ #include <initializer_list>
+ #include <iterator>
+diff --git a/llvm/include/llvm/ADT/StringMapEntry.h b/llvm/include/llvm/ADT/StringMapEntry.h
+index 39976a02b..cdefc5449 100644
+--- a/llvm/include/llvm/ADT/StringMapEntry.h
++++ b/llvm/include/llvm/ADT/StringMapEntry.h
+@@ -16,6 +16,10 @@
+ #ifndef LLVM_ADT_STRINGMAPENTRY_H
+ #define LLVM_ADT_STRINGMAPENTRY_H
+ 
++#include "wpi/MemAlloc.h"
++
++#include <cassert>
++#include <cstring>
+ #include <optional>
+ #include <string_view>
+ 
+diff --git a/llvm/include/llvm/Support/PointerLikeTypeTraits.h b/llvm/include/llvm/Support/PointerLikeTypeTraits.h
+index 1b15f930b..acadd5e89 100644
+--- a/llvm/include/llvm/Support/PointerLikeTypeTraits.h
++++ b/llvm/include/llvm/Support/PointerLikeTypeTraits.h
+@@ -16,6 +16,7 @@
+ 
+ #include "llvm/Support/DataTypes.h"
+ #include <cassert>
++#include <cstdint>
+ #include <type_traits>
+ 
+ namespace llvm {
+diff --git a/llvm/lib/Support/ConvertUTFWrapper.cpp b/llvm/lib/Support/ConvertUTFWrapper.cpp
+index 396ab0c65..cff30f16c 100644
+--- a/llvm/lib/Support/ConvertUTFWrapper.cpp
++++ b/llvm/lib/Support/ConvertUTFWrapper.cpp
+@@ -8,6 +8,7 @@
+ 
+ #include "llvm/ADT/span.h"
+ #include "llvm/Support/ConvertUTF.h"
++#include "llvm/Support/SmallVector.h"
+ #include "llvm/Support/ErrorHandling.h"
+ #include "llvm/Support/SwapByteOrder.h"
+ #include <string>
+diff --git a/llvm/lib/Support/ErrorHandling.cpp b/llvm/lib/Support/ErrorHandling.cpp
+index f80e28e87..ec1a1633a 100644
+--- a/llvm/lib/Support/ErrorHandling.cpp
++++ b/llvm/lib/Support/ErrorHandling.cpp
+@@ -28,12 +28,11 @@
+ #include <mutex>
+ #include <new>
+ 
+-#if defined(HAVE_UNISTD_H)
+-# include <unistd.h>
++#ifndef _WIN32
++#include <unistd.h>
+ #endif
+ #if defined(_MSC_VER)
+-# include <io.h>
+-# include <fcntl.h>
++#include <io.h>
+ #endif
+ 
+ using namespace llvm;
+diff --git a/llvm/lib/Support/raw_ostream.cpp b/llvm/lib/Support/raw_ostream.cpp
+index 95152849c..878a3a5e9 100644
+--- a/llvm/lib/Support/raw_ostream.cpp
++++ b/llvm/lib/Support/raw_ostream.cpp
+@@ -15,7 +15,8 @@
+ #endif
+ 
+ #include "llvm/Support/raw_ostream.h"
+-#include "llvm/ADT/STLArrayExtras.h"
++#include "wpi/SmallString.h"
++#include "wpi/SmallVector.h"
+ #include "llvm/ADT/StringExtras.h"
+ #include "llvm/Config/config.h"
+ #include "llvm/Support/Compiler.h"
+@@ -33,12 +34,11 @@
+ #include <sys/stat.h>
+ 
+ // <fcntl.h> may provide O_BINARY.
+-#if defined(HAVE_FCNTL_H)
+ # include <fcntl.h>
+-#endif
+ 
+-#if defined(HAVE_UNISTD_H)
+-# include <unistd.h>
++#ifndef _WIN32
++#include <unistd.h>
++#include <sys/uio.h>
+ #endif
+ 
+ #if defined(__CYGWIN__)
+@@ -60,7 +60,7 @@
+ 
+ #ifdef _WIN32
+ #include "llvm/Support/ConvertUTF.h"
+-#include "llvm/Support/Windows/WindowsSupport.h"
++#include "Windows/WindowsSupport.h"
+ #endif
+ 
+ using namespace llvm;
+diff --git a/llvm/unittests/ADT/SmallPtrSetTest.cpp b/llvm/unittests/ADT/SmallPtrSetTest.cpp
+index 531f81ab5..3db8b6e37 100644
+--- a/llvm/unittests/ADT/SmallPtrSetTest.cpp
++++ b/llvm/unittests/ADT/SmallPtrSetTest.cpp
+@@ -15,6 +15,8 @@
+ #include "llvm/Support/PointerLikeTypeTraits.h"
+ #include "gtest/gtest.h"
+ 
++#include <algorithm>
++
+ using namespace llvm;
+ 
+ TEST(SmallPtrSetTest, Assignment) {
+diff --git a/llvm/unittests/ADT/StringMapTest.cpp b/llvm/unittests/ADT/StringMapTest.cpp
+index 6d0c0942c..de6daf3da 100644
+--- a/llvm/unittests/ADT/StringMapTest.cpp
++++ b/llvm/unittests/ADT/StringMapTest.cpp
+@@ -9,6 +9,7 @@
+ #include "llvm/ADT/StringMap.h"
+ #include "llvm/Support/DataTypes.h"
+ #include "gtest/gtest.h"
++#include <algorithm>
+ #include <limits>
+ #include <tuple>
+ using namespace llvm;
+diff --git a/llvm/unittests/Support/ConvertUTFTest.cpp b/llvm/unittests/Support/ConvertUTFTest.cpp
+index 9c798437a..2fee8ad5c 100644
+--- a/llvm/unittests/Support/ConvertUTFTest.cpp
++++ b/llvm/unittests/Support/ConvertUTFTest.cpp
+@@ -7,6 +7,8 @@
+ //===----------------------------------------------------------------------===//
+ 
+ #include "llvm/Support/ConvertUTF.h"
++#include "llvm/Support/SmallString.h"
++#include "llvm/Support/SmallVector.h"
+ #include "gtest/gtest.h"
+ #include <string>
+ #include <vector>
diff --git a/third_party/allwpilib/upstream_utils/llvm_patches/0018-Use-std-is_trivially_copy_constructible.patch b/third_party/allwpilib/upstream_utils/llvm_patches/0018-Use-std-is_trivially_copy_constructible.patch
new file mode 100644
index 0000000..4e2650e
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/llvm_patches/0018-Use-std-is_trivially_copy_constructible.patch
@@ -0,0 +1,138 @@
+From 1c3e8a6ff8d8b6c054141503c7318d69319d8d41 Mon Sep 17 00:00:00 2001
+From: PJ Reiniger <pj.reiniger@gmail.com>
+Date: Sun, 8 May 2022 16:42:09 -0400
+Subject: [PATCH 18/28] Use std::is_trivially_copy_constructible
+
+---
+ llvm/include/llvm/ADT/PointerIntPair.h  | 12 ----
+ llvm/include/llvm/Support/type_traits.h | 91 +------------------------
+ 2 files changed, 2 insertions(+), 101 deletions(-)
+
+diff --git a/llvm/include/llvm/ADT/PointerIntPair.h b/llvm/include/llvm/ADT/PointerIntPair.h
+index b7ddf8855..a48fb904b 100644
+--- a/llvm/include/llvm/ADT/PointerIntPair.h
++++ b/llvm/include/llvm/ADT/PointerIntPair.h
+@@ -128,18 +128,6 @@ public:
+   }
+ };
+ 
+-// Specialize is_trivially_copyable to avoid limitation of llvm::is_trivially_copyable
+-// when compiled with gcc 4.9.
+-template <typename PointerTy, unsigned IntBits, typename IntType,
+-          typename PtrTraits,
+-          typename Info>
+-struct is_trivially_copyable<PointerIntPair<PointerTy, IntBits, IntType, PtrTraits, Info>> : std::true_type {
+-#ifdef HAVE_STD_IS_TRIVIALLY_COPYABLE
+-  static_assert(std::is_trivially_copyable<PointerIntPair<PointerTy, IntBits, IntType, PtrTraits, Info>>::value,
+-                "inconsistent behavior between llvm:: and std:: implementation of is_trivially_copyable");
+-#endif
+-};
+-
+ 
+ template <typename PointerT, unsigned IntBits, typename PtrTraits>
+ struct PointerIntPairInfo {
+diff --git a/llvm/include/llvm/Support/type_traits.h b/llvm/include/llvm/Support/type_traits.h
+index 7b7d5d991..72a2e84ad 100644
+--- a/llvm/include/llvm/Support/type_traits.h
++++ b/llvm/include/llvm/Support/type_traits.h
+@@ -92,98 +92,11 @@ union trivial_helper {
+ 
+ } // end namespace detail
+ 
+-/// An implementation of `std::is_trivially_copy_constructible` since we have
+-/// users with STLs that don't yet include it.
+ template <typename T>
+-struct is_trivially_copy_constructible
+-    : std::is_copy_constructible<
+-          ::llvm::detail::copy_construction_triviality_helper<T>> {};
+-template <typename T>
+-struct is_trivially_copy_constructible<T &> : std::true_type {};
+-template <typename T>
+-struct is_trivially_copy_constructible<T &&> : std::false_type {};
++using is_trivially_move_constructible = std::is_trivially_move_constructible<T>;
+ 
+-/// An implementation of `std::is_trivially_move_constructible` since we have
+-/// users with STLs that don't yet include it.
+-template <typename T>
+-struct is_trivially_move_constructible
+-    : std::is_move_constructible<
+-          ::llvm::detail::move_construction_triviality_helper<T>> {};
+ template <typename T>
+-struct is_trivially_move_constructible<T &> : std::true_type {};
+-template <typename T>
+-struct is_trivially_move_constructible<T &&> : std::true_type {};
+-
+-
+-template <typename T>
+-struct is_copy_assignable {
+-  template<class F>
+-    static auto get(F*) -> decltype(std::declval<F &>() = std::declval<const F &>(), std::true_type{});
+-    static std::false_type get(...);
+-    static constexpr bool value = decltype(get((T*)nullptr))::value;
+-};
+-
+-template <typename T>
+-struct is_move_assignable {
+-  template<class F>
+-    static auto get(F*) -> decltype(std::declval<F &>() = std::declval<F &&>(), std::true_type{});
+-    static std::false_type get(...);
+-    static constexpr bool value = decltype(get((T*)nullptr))::value;
+-};
+-
+-
+-// An implementation of `std::is_trivially_copyable` since STL version
+-// is not equally supported by all compilers, especially GCC 4.9.
+-// Uniform implementation of this trait is important for ABI compatibility
+-// as it has an impact on SmallVector's ABI (among others).
+-template <typename T>
+-class is_trivially_copyable {
+-
+-  // copy constructors
+-  static constexpr bool has_trivial_copy_constructor =
+-      std::is_copy_constructible<detail::trivial_helper<T>>::value;
+-  static constexpr bool has_deleted_copy_constructor =
+-      !std::is_copy_constructible<T>::value;
+-
+-  // move constructors
+-  static constexpr bool has_trivial_move_constructor =
+-      std::is_move_constructible<detail::trivial_helper<T>>::value;
+-  static constexpr bool has_deleted_move_constructor =
+-      !std::is_move_constructible<T>::value;
+-
+-  // copy assign
+-  static constexpr bool has_trivial_copy_assign =
+-      is_copy_assignable<detail::trivial_helper<T>>::value;
+-  static constexpr bool has_deleted_copy_assign =
+-      !is_copy_assignable<T>::value;
+-
+-  // move assign
+-  static constexpr bool has_trivial_move_assign =
+-      is_move_assignable<detail::trivial_helper<T>>::value;
+-  static constexpr bool has_deleted_move_assign =
+-      !is_move_assignable<T>::value;
+-
+-  // destructor
+-  static constexpr bool has_trivial_destructor =
+-      std::is_destructible<detail::trivial_helper<T>>::value;
+-
+-  public:
+-
+-  static constexpr bool value =
+-      has_trivial_destructor &&
+-      (has_deleted_move_assign || has_trivial_move_assign) &&
+-      (has_deleted_move_constructor || has_trivial_move_constructor) &&
+-      (has_deleted_copy_assign || has_trivial_copy_assign) &&
+-      (has_deleted_copy_constructor || has_trivial_copy_constructor);
+-
+-#ifdef HAVE_STD_IS_TRIVIALLY_COPYABLE
+-  static_assert(value == std::is_trivially_copyable<T>::value,
+-                "inconsistent behavior between llvm:: and std:: implementation of is_trivially_copyable");
+-#endif
+-};
+-template <typename T>
+-class is_trivially_copyable<T*> : public std::true_type {
+-};
++using is_trivially_copy_constructible = std::is_trivially_copy_constructible<T>;
+ 
+ 
+ } // end namespace llvm
diff --git a/third_party/allwpilib/upstream_utils/llvm_patches/0019-Windows-support.patch b/third_party/allwpilib/upstream_utils/llvm_patches/0019-Windows-support.patch
new file mode 100644
index 0000000..07d973b
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/llvm_patches/0019-Windows-support.patch
@@ -0,0 +1,204 @@
+From 36f7f08e257f2b58b2894f165a38ff2a831aed8f Mon Sep 17 00:00:00 2001
+From: PJ Reiniger <pj.reiniger@gmail.com>
+Date: Tue, 3 May 2022 20:22:38 -0400
+Subject: [PATCH 19/28] Windows support
+
+---
+ .../llvm/Support/Windows/WindowsSupport.h     | 45 +++++----
+ llvm/lib/Support/ConvertUTF.cpp               | 95 +++++++++++++++++++
+ 2 files changed, 124 insertions(+), 16 deletions(-)
+
+diff --git a/llvm/include/llvm/Support/Windows/WindowsSupport.h b/llvm/include/llvm/Support/Windows/WindowsSupport.h
+index 180803fbd..31120cfa0 100644
+--- a/llvm/include/llvm/Support/Windows/WindowsSupport.h
++++ b/llvm/include/llvm/Support/Windows/WindowsSupport.h
+@@ -35,8 +35,6 @@
+ 
+ #include "llvm/ADT/SmallVector.h"
+ #include "llvm/ADT/StringExtras.h"
+-#include "llvm/Config/llvm-config.h" // Get build system configuration settings
+-#include "llvm/Support/Allocator.h"
+ #include "llvm/Support/Chrono.h"
+ #include "llvm/Support/Compiler.h"
+ #include "llvm/Support/ErrorHandling.h"
+@@ -44,18 +42,46 @@
+ #include <cassert>
+ #include <string>
+ #include <system_error>
++#define WIN32_NO_STATUS
+ #include <windows.h>
++#undef WIN32_NO_STATUS
++#include <winternl.h>
++#include <ntstatus.h>
+ 
+ // Must be included after windows.h
+ #include <wincrypt.h>
+ 
+ namespace llvm {
+ 
++/// Returns the Windows version as Major.Minor.0.BuildNumber. Uses
++/// RtlGetVersion or GetVersionEx under the hood depending on what is available.
++/// GetVersionEx is deprecated, but this API exposes the build number which can
++/// be useful for working around certain kernel bugs.
++inline llvm::VersionTuple GetWindowsOSVersion() {
++  typedef NTSTATUS(WINAPI* RtlGetVersionPtr)(PRTL_OSVERSIONINFOW);
++  HMODULE hMod = ::GetModuleHandleW(L"ntdll.dll");
++  if (hMod) {
++    auto getVer = (RtlGetVersionPtr)::GetProcAddress(hMod, "RtlGetVersion");
++    if (getVer) {
++      RTL_OSVERSIONINFOEXW info{};
++      info.dwOSVersionInfoSize = sizeof(info);
++      if (getVer((PRTL_OSVERSIONINFOW)&info) == ((NTSTATUS)0x00000000L)) {
++        return llvm::VersionTuple(info.dwMajorVersion, info.dwMinorVersion, 0,
++                                  info.dwBuildNumber);
++      }
++    }
++  }
++  return llvm::VersionTuple(0, 0, 0, 0);
++}
++
+ /// Determines if the program is running on Windows 8 or newer. This
+ /// reimplements one of the helpers in the Windows 8.1 SDK, which are intended
+ /// to supercede raw calls to GetVersionEx. Old SDKs, Cygwin, and MinGW don't
+ /// yet have VersionHelpers.h, so we have our own helper.
+-bool RunningWindows8OrGreater();
++inline bool RunningWindows8OrGreater() {
++  // Windows 8 is version 6.2, service pack 0.
++  return GetWindowsOSVersion() >= llvm::VersionTuple(6, 2, 0, 0);
++}
+ 
+ /// Returns the Windows version as Major.Minor.0.BuildNumber. Uses
+ /// RtlGetVersion or GetVersionEx under the hood depending on what is available.
+@@ -228,19 +254,6 @@ inline FILETIME toFILETIME(TimePoint<> TP) {
+   return Time;
+ }
+ 
+-namespace windows {
+-// Returns command line arguments. Unlike arguments given to main(),
+-// this function guarantees that the returned arguments are encoded in
+-// UTF-8 regardless of the current code page setting.
+-std::error_code GetCommandLineArguments(SmallVectorImpl<const char *> &Args,
+-                                        BumpPtrAllocator &Alloc);
+-
+-/// Convert UTF-8 path to a suitable UTF-16 path for use with the Win32 Unicode
+-/// File API.
+-std::error_code widenPath(const Twine &Path8, SmallVectorImpl<wchar_t> &Path16,
+-                          size_t MaxPathLen = MAX_PATH);
+-
+-} // end namespace windows
+ } // end namespace sys
+ } // end namespace llvm.
+ 
+diff --git a/llvm/lib/Support/ConvertUTF.cpp b/llvm/lib/Support/ConvertUTF.cpp
+index e24a918c5..c906ded91 100644
+--- a/llvm/lib/Support/ConvertUTF.cpp
++++ b/llvm/lib/Support/ConvertUTF.cpp
+@@ -51,6 +51,11 @@
+ #endif
+ #include <assert.h>
+ 
++#ifdef _WIN32
++#include "wpi/WindowsError.h"
++#include "Windows/WindowsSupport.h"
++#endif
++
+ /*
+  * This code extensively uses fall-through switches.
+  * Keep the compiler from warning about that.
+@@ -733,6 +738,96 @@ ConversionResult ConvertUTF8toUTF32(const UTF8 **sourceStart,
+ 
+    --------------------------------------------------------------------- */
+ 
++#ifdef _WIN32
++
++namespace sys {
++namespace windows {
++std::error_code CodePageToUTF16(unsigned codepage,
++                                std::string_view original,
++                                wpi::SmallVectorImpl<wchar_t> &utf16) {
++  if (!original.empty()) {
++    int len = ::MultiByteToWideChar(codepage, MB_ERR_INVALID_CHARS, original.data(),
++                                    original.size(), utf16.begin(), 0);
++
++    if (len == 0) {
++      return mapWindowsError(::GetLastError());
++    }
++
++    utf16.reserve(len + 1);
++    utf16.resize_for_overwrite(len);
++
++    len = ::MultiByteToWideChar(codepage, MB_ERR_INVALID_CHARS, original.data(),
++                                original.size(), utf16.begin(), utf16.size());
++
++    if (len == 0) {
++      return mapWindowsError(::GetLastError());
++    }
++  }
++
++  // Make utf16 null terminated.
++  utf16.push_back(0);
++  utf16.pop_back();
++
++  return std::error_code();
++}
++
++std::error_code UTF8ToUTF16(std::string_view utf8,
++                            wpi::SmallVectorImpl<wchar_t> &utf16) {
++  return CodePageToUTF16(CP_UTF8, utf8, utf16);
++}
++
++std::error_code CurCPToUTF16(std::string_view curcp,
++                            wpi::SmallVectorImpl<wchar_t> &utf16) {
++  return CodePageToUTF16(CP_ACP, curcp, utf16);
++}
++
++static
++std::error_code UTF16ToCodePage(unsigned codepage, const wchar_t *utf16,
++                                size_t utf16_len,
++                                wpi::SmallVectorImpl<char> &converted) {
++  if (utf16_len) {
++    // Get length.
++    int len = ::WideCharToMultiByte(codepage, 0, utf16, utf16_len, converted.begin(),
++                                    0, NULL, NULL);
++
++    if (len == 0) {
++      return mapWindowsError(::GetLastError());
++    }
++
++    converted.reserve(len);
++    converted.resize_for_overwrite(len);
++
++    // Now do the actual conversion.
++    len = ::WideCharToMultiByte(codepage, 0, utf16, utf16_len, converted.data(),
++                                converted.size(), NULL, NULL);
++
++    if (len == 0) {
++      return mapWindowsError(::GetLastError());
++    }
++  }
++
++  // Make the new string null terminated.
++  converted.push_back(0);
++  converted.pop_back();
++
++  return std::error_code();
++}
++
++std::error_code UTF16ToUTF8(const wchar_t *utf16, size_t utf16_len,
++                            wpi::SmallVectorImpl<char> &utf8) {
++  return UTF16ToCodePage(CP_UTF8, utf16, utf16_len, utf8);
++}
++
++std::error_code UTF16ToCurCP(const wchar_t *utf16, size_t utf16_len,
++                             wpi::SmallVectorImpl<char> &curcp) {
++  return UTF16ToCodePage(CP_ACP, utf16, utf16_len, curcp);
++}
++
++} // end namespace windows
++} // end namespace sys
++
++#endif  // _WIN32
++
+ } // namespace llvm
+ 
+ ConvertUTF_RESTORE_WARNINGS
diff --git a/third_party/allwpilib/upstream_utils/llvm_patches/0020-Prefer-fmtlib.patch b/third_party/allwpilib/upstream_utils/llvm_patches/0020-Prefer-fmtlib.patch
new file mode 100644
index 0000000..4315754
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/llvm_patches/0020-Prefer-fmtlib.patch
@@ -0,0 +1,55 @@
+From 8834260a9ee172311cc08d0b4e4e958bf36a260f Mon Sep 17 00:00:00 2001
+From: PJ Reiniger <pj.reiniger@gmail.com>
+Date: Sun, 8 May 2022 16:46:20 -0400
+Subject: [PATCH 20/28] Prefer fmtlib
+
+---
+ llvm/lib/Support/ErrorHandling.cpp | 20 ++++++--------------
+ 1 file changed, 6 insertions(+), 14 deletions(-)
+
+diff --git a/llvm/lib/Support/ErrorHandling.cpp b/llvm/lib/Support/ErrorHandling.cpp
+index ec1a1633a..8de7b726d 100644
+--- a/llvm/lib/Support/ErrorHandling.cpp
++++ b/llvm/lib/Support/ErrorHandling.cpp
+@@ -22,7 +22,7 @@
+ #include "llvm/Support/Signals.h"
+ #include "llvm/Support/Threading.h"
+ #include "llvm/Support/WindowsError.h"
+-#include "llvm/Support/raw_ostream.h"
++#include "fmt/format.h"
+ #include <cassert>
+ #include <cstdlib>
+ #include <mutex>
+@@ -93,15 +93,7 @@ void llvm::report_fatal_error(std::string_view Reason, bool GenCrashDiag) {
+   if (handler) {
+     handler(handlerData, std::string{Reason}.c_str(), GenCrashDiag);
+   } else {
+-    // Blast the result out to stderr.  We don't try hard to make sure this
+-    // succeeds (e.g. handling EINTR) and we can't use errs() here because
+-    // raw ostreams can call report_fatal_error.
+-    SmallVector<char, 64> Buffer;
+-    raw_svector_ostream OS(Buffer);
+-    OS << "LLVM ERROR: " << Reason << "\n";
+-    std::string_view MessageStr = OS.str();
+-    ssize_t written = ::write(2, MessageStr.data(), MessageStr.size());
+-    (void)written; // If something went wrong, we deliberately just give up.
++    fmt::print(stderr, "LLVM ERROR: {}\n", Reason);
+   }
+ 
+   // If we reached here, we are failing ungracefully. Run the interrupt handlers
+@@ -173,11 +165,11 @@ void llvm::llvm_unreachable_internal(const char *msg, const char *file,
+   // llvm_unreachable is intended to be used to indicate "impossible"
+   // situations, and not legitimate runtime errors.
+   if (msg)
+-    dbgs() << msg << "\n";
+-  dbgs() << "UNREACHABLE executed";
++    fmt::print(stderr, "{}\n", msg);
++  std::fputs("UNREACHABLE executed", stderr);
+   if (file)
+-    dbgs() << " at " << file << ":" << line;
+-  dbgs() << "!\n";
++    fmt::print(stderr, " at {}:{}", file, line);
++  fmt::print(stderr, "!\n");
+   abort();
+ #ifdef LLVM_BUILTIN_UNREACHABLE
+   // Windows systems and possibly others don't declare abort() to be noreturn,
diff --git a/third_party/allwpilib/upstream_utils/llvm_patches/0021-Prefer-wpi-s-fs.h.patch b/third_party/allwpilib/upstream_utils/llvm_patches/0021-Prefer-wpi-s-fs.h.patch
new file mode 100644
index 0000000..2f246a0
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/llvm_patches/0021-Prefer-wpi-s-fs.h.patch
@@ -0,0 +1,34 @@
+From 7943842aea1a05a1dd2c2c753378af569c24293b Mon Sep 17 00:00:00 2001
+From: PJ Reiniger <pj.reiniger@gmail.com>
+Date: Sun, 8 May 2022 16:49:36 -0400
+Subject: [PATCH 21/28] Prefer wpi's fs.h
+
+---
+ llvm/include/llvm/Support/raw_ostream.h | 7 ++-----
+ 1 file changed, 2 insertions(+), 5 deletions(-)
+
+diff --git a/llvm/include/llvm/Support/raw_ostream.h b/llvm/include/llvm/Support/raw_ostream.h
+index bf5630ab5..256bcec25 100644
+--- a/llvm/include/llvm/Support/raw_ostream.h
++++ b/llvm/include/llvm/Support/raw_ostream.h
+@@ -27,18 +27,15 @@
+ #include <type_traits>
+ #include <vector>
+ 
+-namespace llvm {
+-
+-template <class T> class LLVM_NODISCARD Expected;
+ 
+-namespace sys {
+ namespace fs {
+ enum FileAccess : unsigned;
+ enum OpenFlags : unsigned;
+ enum CreationDisposition : unsigned;
+ class FileLocker;
+ } // end namespace fs
+-} // end namespace sys
++
++namespace llvm {
+ 
+ /// This class implements an extremely fast bulk output stream that can *only*
+ /// output to a stream.  It does not support seeking, reopening, rewinding, line
diff --git a/third_party/allwpilib/upstream_utils/llvm_patches/0022-Remove-unused-functions.patch b/third_party/allwpilib/upstream_utils/llvm_patches/0022-Remove-unused-functions.patch
new file mode 100644
index 0000000..244148e
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/llvm_patches/0022-Remove-unused-functions.patch
@@ -0,0 +1,283 @@
+From a172c93df929ac6c9f783fd5af1e4df3604c4c66 Mon Sep 17 00:00:00 2001
+From: PJ Reiniger <pj.reiniger@gmail.com>
+Date: Sun, 8 May 2022 19:16:51 -0400
+Subject: [PATCH 22/28] Remove unused functions
+
+---
+ llvm/include/llvm/Support/DJB.h         |  3 -
+ llvm/include/llvm/Support/raw_ostream.h |  5 +-
+ llvm/lib/Support/ErrorHandling.cpp      | 16 -----
+ llvm/lib/Support/raw_ostream.cpp        | 49 +++++++--------
+ llvm/unittests/ADT/SmallStringTest.cpp  | 81 -------------------------
+ 5 files changed, 23 insertions(+), 131 deletions(-)
+
+diff --git a/llvm/include/llvm/Support/DJB.h b/llvm/include/llvm/Support/DJB.h
+index 8737cd144..67b0ae91b 100644
+--- a/llvm/include/llvm/Support/DJB.h
++++ b/llvm/include/llvm/Support/DJB.h
+@@ -24,9 +24,6 @@ inline uint32_t djbHash(std::string_view Buffer, uint32_t H = 5381) {
+   return H;
+ }
+ 
+-/// Computes the Bernstein hash after folding the input according to the Dwarf 5
+-/// standard case folding rules.
+-uint32_t caseFoldingDjbHash(StringRef Buffer, uint32_t H = 5381);
+ } // namespace llvm
+ 
+ #endif // LLVM_SUPPORT_DJB_H
+diff --git a/llvm/include/llvm/Support/raw_ostream.h b/llvm/include/llvm/Support/raw_ostream.h
+index 256bcec25..9b3a87e1b 100644
+--- a/llvm/include/llvm/Support/raw_ostream.h
++++ b/llvm/include/llvm/Support/raw_ostream.h
+@@ -71,7 +71,6 @@ private:
+   /// for a \see write_impl() call to handle the data which has been put into
+   /// this buffer.
+   char *OutBufStart, *OutBufEnd, *OutBufCur;
+-  bool ColorEnabled = false;
+ 
+   /// Optional stream this stream is tied to. If this stream is written to, the
+   /// tied-to stream will be flushed first.
+@@ -304,9 +303,9 @@ public:
+ 
+   // Enable or disable colors. Once enable_colors(false) is called,
+   // changeColor() has no effect until enable_colors(true) is called.
+-  virtual void enable_colors(bool enable) { ColorEnabled = enable; }
++  virtual void enable_colors(bool /*enable*/) {}
+ 
+-  bool colors_enabled() const { return ColorEnabled; }
++  bool colors_enabled() const { return false; }
+ 
+   /// Tie this stream to the specified stream. Replaces any existing tied-to
+   /// stream. Specifying a nullptr unties the stream.
+diff --git a/llvm/lib/Support/ErrorHandling.cpp b/llvm/lib/Support/ErrorHandling.cpp
+index 8de7b726d..bc08199a1 100644
+--- a/llvm/lib/Support/ErrorHandling.cpp
++++ b/llvm/lib/Support/ErrorHandling.cpp
+@@ -178,22 +178,6 @@ void llvm::llvm_unreachable_internal(const char *msg, const char *file,
+ #endif
+ }
+ 
+-static void bindingsErrorHandler(void *user_data, const char *reason,
+-                                 bool gen_crash_diag) {
+-  LLVMFatalErrorHandler handler =
+-      LLVM_EXTENSION reinterpret_cast<LLVMFatalErrorHandler>(user_data);
+-  handler(reason);
+-}
+-
+-void LLVMInstallFatalErrorHandler(LLVMFatalErrorHandler Handler) {
+-  install_fatal_error_handler(bindingsErrorHandler,
+-                              LLVM_EXTENSION reinterpret_cast<void *>(Handler));
+-}
+-
+-void LLVMResetFatalErrorHandler() {
+-  remove_fatal_error_handler();
+-}
+-
+ #ifdef _WIN32
+ 
+ #include <winerror.h>
+diff --git a/llvm/lib/Support/raw_ostream.cpp b/llvm/lib/Support/raw_ostream.cpp
+index 878a3a5e9..632b52235 100644
+--- a/llvm/lib/Support/raw_ostream.cpp
++++ b/llvm/lib/Support/raw_ostream.cpp
+@@ -167,16 +167,6 @@ raw_ostream &raw_ostream::write_escaped(std::string_view Str,
+   return *this;
+ }
+ 
+-raw_ostream &raw_ostream::operator<<(const void *P) {
+-  llvm::write_hex(*this, (uintptr_t)P, HexPrintStyle::PrefixLower);
+-  return *this;
+-}
+-
+-raw_ostream &raw_ostream::operator<<(double N) {
+-  llvm::write_double(*this, N, FloatStyle::Exponent);
+-  return *this;
+-}
+-
+ void raw_ostream::flush_nonempty() {
+   assert(OutBufCur > OutBufStart && "Invalid call to flush_nonempty.");
+   size_t Length = OutBufCur - OutBufStart;
+@@ -321,15 +311,22 @@ static int getFD(std::string_view Filename, std::error_code &EC,
+   if (Filename == "-") {
+     EC = std::error_code();
+     // Change stdout's text/binary mode based on the Flags.
+-    sys::ChangeStdoutMode(Flags);
++    if (!(Flags & fs::OF_Text)) {
++#if defined(_WIN32)
++      _setmode(_fileno(stdout), _O_BINARY);
++#endif
++    }
+     return STDOUT_FILENO;
+   }
+ 
+-  int FD;
+-  if (Access & sys::fs::FA_Read)
+-    EC = sys::fs::openFileForReadWrite(Filename, FD, Disp, Flags);
++  fs::file_t F;
++  if (Access & fs::FA_Read)
++    F = fs::OpenFileForReadWrite(fs::path{std::string_view{Filename.data(), Filename.size()}}, EC, Disp, Flags);
+   else
+-    EC = sys::fs::openFileForWrite(Filename, FD, Disp, Flags);
++    F = fs::OpenFileForWrite(fs::path{std::string_view{Filename.data(), Filename.size()}}, EC, Disp, Flags);
++  if (EC)
++    return -1;
++  int FD = fs::FileToFd(F, EC, Flags);
+   if (EC)
+     return -1;
+ 
+@@ -389,12 +386,8 @@ raw_fd_ostream::raw_fd_ostream(int fd, bool shouldClose, bool unbuffered,
+ 
+   // Get the starting position.
+   off_t loc = ::lseek(FD, 0, SEEK_CUR);
+-  sys::fs::file_status Status;
+-  std::error_code EC = status(FD, Status);
+-  IsRegularFile = Status.type() == sys::fs::file_type::regular_file;
+ #ifdef _WIN32
+-  // MSVCRT's _lseek(SEEK_CUR) doesn't return -1 for pipes.
+-  SupportsSeeking = !EC && IsRegularFile;
++  SupportsSeeking = loc != (off_t)-1 && ::GetFileType(reinterpret_cast<HANDLE>(::_get_osfhandle(FD))) != FILE_TYPE_PIPE;
+ #else
+   SupportsSeeking = !EC && loc != (off_t)-1;
+ #endif
+@@ -407,10 +400,8 @@ raw_fd_ostream::raw_fd_ostream(int fd, bool shouldClose, bool unbuffered,
+ raw_fd_ostream::~raw_fd_ostream() {
+   if (FD >= 0) {
+     flush();
+-    if (ShouldClose) {
+-      if (auto EC = sys::Process::SafelyCloseFileDescriptor(FD))
+-        error_detected(EC);
+-    }
++    if (ShouldClose && ::close(FD) < 0)
++      error_detected(std::error_code(errno, std::generic_category()));
+   }
+ 
+ #ifdef __MINGW32__
+@@ -505,7 +496,11 @@ void raw_fd_ostream::write_impl(const char *Ptr, size_t Size) {
+ 
+   do {
+     size_t ChunkSize = std::min(Size, MaxWriteSize);
++#ifdef _WIN32
++    int ret = ::_write(FD, Ptr, ChunkSize);
++#else
+     ssize_t ret = ::write(FD, Ptr, ChunkSize);
++#endif
+ 
+     if (ret < 0) {
+       // If it's a recoverable error, swallow it and retry the write.
+@@ -540,8 +535,8 @@ void raw_fd_ostream::close() {
+   assert(ShouldClose);
+   ShouldClose = false;
+   flush();
+-  if (auto EC = sys::Process::SafelyCloseFileDescriptor(FD))
+-    error_detected(EC);
++  if (::close(FD) < 0)
++    error_detected(std::error_code(errno, std::generic_category()));
+   FD = -1;
+ }
+ 
+@@ -550,8 +545,6 @@ uint64_t raw_fd_ostream::seek(uint64_t off) {
+   flush();
+ #ifdef _WIN32
+   pos = ::_lseeki64(FD, off, SEEK_SET);
+-#elif defined(HAVE_LSEEK64)
+-  pos = ::lseek64(FD, off, SEEK_SET);
+ #else
+   pos = ::lseek(FD, off, SEEK_SET);
+ #endif
+diff --git a/llvm/unittests/ADT/SmallStringTest.cpp b/llvm/unittests/ADT/SmallStringTest.cpp
+index bee3875d1..87600ea47 100644
+--- a/llvm/unittests/ADT/SmallStringTest.cpp
++++ b/llvm/unittests/ADT/SmallStringTest.cpp
+@@ -129,23 +129,6 @@ TEST_F(SmallStringTest, StdStringConversion) {
+   EXPECT_EQ("abc", theStdString);
+ }
+ 
+-TEST_F(SmallStringTest, Substr) {
+-  theString = "hello";
+-  EXPECT_EQ("lo", theString.substr(3));
+-  EXPECT_EQ("", theString.substr(100));
+-  EXPECT_EQ("hello", theString.substr(0, 100));
+-  EXPECT_EQ("o", theString.substr(4, 10));
+-}
+-
+-TEST_F(SmallStringTest, Slice) {
+-  theString = "hello";
+-  EXPECT_EQ("l", theString.slice(2, 3));
+-  EXPECT_EQ("ell", theString.slice(1, 4));
+-  EXPECT_EQ("llo", theString.slice(2, 100));
+-  EXPECT_EQ("", theString.slice(2, 1));
+-  EXPECT_EQ("", theString.slice(10, 20));
+-}
+-
+ TEST_F(SmallStringTest, Find) {
+   theString = "hello";
+   EXPECT_EQ(2U, theString.find('l'));
+@@ -180,68 +163,4 @@ TEST_F(SmallStringTest, Find) {
+   EXPECT_EQ(0U, theString.find(""));
+ }
+ 
+-TEST_F(SmallStringTest, Count) {
+-  theString = "hello";
+-  EXPECT_EQ(2U, theString.count('l'));
+-  EXPECT_EQ(1U, theString.count('o'));
+-  EXPECT_EQ(0U, theString.count('z'));
+-  EXPECT_EQ(0U, theString.count("helloworld"));
+-  EXPECT_EQ(1U, theString.count("hello"));
+-  EXPECT_EQ(1U, theString.count("ello"));
+-  EXPECT_EQ(0U, theString.count("zz"));
+-}
+-
+-TEST_F(SmallStringTest, Realloc) {
+-  theString = "abcd";
+-  theString.reserve(100);
+-  EXPECT_EQ("abcd", theString);
+-  unsigned const N = 100000;
+-  theString.reserve(N);
+-  for (unsigned i = 0; i < N - 4; ++i)
+-    theString.push_back('y');
+-  EXPECT_EQ("abcdyyy", theString.slice(0, 7));
+-}
+-
+-TEST_F(SmallStringTest, Comparisons) {
+-  EXPECT_EQ(-1, SmallString<10>("aab").compare("aad"));
+-  EXPECT_EQ( 0, SmallString<10>("aab").compare("aab"));
+-  EXPECT_EQ( 1, SmallString<10>("aab").compare("aaa"));
+-  EXPECT_EQ(-1, SmallString<10>("aab").compare("aabb"));
+-  EXPECT_EQ( 1, SmallString<10>("aab").compare("aa"));
+-  EXPECT_EQ( 1, SmallString<10>("\xFF").compare("\1"));
+-
+-  EXPECT_EQ(-1, SmallString<10>("AaB").compare_insensitive("aAd"));
+-  EXPECT_EQ( 0, SmallString<10>("AaB").compare_insensitive("aab"));
+-  EXPECT_EQ( 1, SmallString<10>("AaB").compare_insensitive("AAA"));
+-  EXPECT_EQ(-1, SmallString<10>("AaB").compare_insensitive("aaBb"));
+-  EXPECT_EQ( 1, SmallString<10>("AaB").compare_insensitive("aA"));
+-  EXPECT_EQ( 1, SmallString<10>("\xFF").compare_insensitive("\1"));
+-
+-  EXPECT_EQ(-1, SmallString<10>("aab").compare_numeric("aad"));
+-  EXPECT_EQ( 0, SmallString<10>("aab").compare_numeric("aab"));
+-  EXPECT_EQ( 1, SmallString<10>("aab").compare_numeric("aaa"));
+-  EXPECT_EQ(-1, SmallString<10>("aab").compare_numeric("aabb"));
+-  EXPECT_EQ( 1, SmallString<10>("aab").compare_numeric("aa"));
+-  EXPECT_EQ(-1, SmallString<10>("1").compare_numeric("10"));
+-  EXPECT_EQ( 0, SmallString<10>("10").compare_numeric("10"));
+-  EXPECT_EQ( 0, SmallString<10>("10a").compare_numeric("10a"));
+-  EXPECT_EQ( 1, SmallString<10>("2").compare_numeric("1"));
+-  EXPECT_EQ( 0, SmallString<10>("llvm_v1i64_ty").compare_numeric("llvm_v1i64_ty"));
+-  EXPECT_EQ( 1, SmallString<10>("\xFF").compare_numeric("\1"));
+-  EXPECT_EQ( 1, SmallString<10>("V16").compare_numeric("V1_q0"));
+-  EXPECT_EQ(-1, SmallString<10>("V1_q0").compare_numeric("V16"));
+-  EXPECT_EQ(-1, SmallString<10>("V8_q0").compare_numeric("V16"));
+-  EXPECT_EQ( 1, SmallString<10>("V16").compare_numeric("V8_q0"));
+-  EXPECT_EQ(-1, SmallString<10>("V1_q0").compare_numeric("V8_q0"));
+-  EXPECT_EQ( 1, SmallString<10>("V8_q0").compare_numeric("V1_q0"));
+-}
+-
+-// Check gtest prints SmallString as a string instead of a container of chars.
+-// The code is in utils/unittest/googletest/internal/custom/gtest-printers.h
+-TEST_F(SmallStringTest, GTestPrinter) {
+-  EXPECT_EQ(R"("foo")", ::testing::PrintToString(SmallString<1>("foo")));
+-  const SmallVectorImpl<char> &ErasedSmallString = SmallString<1>("foo");
+-  EXPECT_EQ(R"("foo")", ::testing::PrintToString(ErasedSmallString));
+-}
+-
+ } // namespace
diff --git a/third_party/allwpilib/upstream_utils/llvm_patches/0023-OS-specific-changes.patch b/third_party/allwpilib/upstream_utils/llvm_patches/0023-OS-specific-changes.patch
new file mode 100644
index 0000000..ed58dac
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/llvm_patches/0023-OS-specific-changes.patch
@@ -0,0 +1,43 @@
+From ae08bb29b4d2a8ea15a4b82b909c0f4aee5e9060 Mon Sep 17 00:00:00 2001
+From: PJ Reiniger <pj.reiniger@gmail.com>
+Date: Sun, 8 May 2022 19:30:43 -0400
+Subject: [PATCH 23/28] OS-specific changes
+
+---
+ llvm/lib/Support/ErrorHandling.cpp | 13 +++++++------
+ 1 file changed, 7 insertions(+), 6 deletions(-)
+
+diff --git a/llvm/lib/Support/ErrorHandling.cpp b/llvm/lib/Support/ErrorHandling.cpp
+index bc08199a1..839819094 100644
+--- a/llvm/lib/Support/ErrorHandling.cpp
++++ b/llvm/lib/Support/ErrorHandling.cpp
+@@ -96,12 +96,7 @@ void llvm::report_fatal_error(std::string_view Reason, bool GenCrashDiag) {
+     fmt::print(stderr, "LLVM ERROR: {}\n", Reason);
+   }
+ 
+-  // If we reached here, we are failing ungracefully. Run the interrupt handlers
+-  // to make sure any special cleanups get done, in particular that we remove
+-  // files registered with RemoveFileOnSignal.
+-  sys::RunInterruptHandlers();
+-
+-  abort();
++  exit(1);
+ }
+ 
+ void llvm::install_bad_alloc_error_handler(fatal_error_handler_t handler,
+@@ -138,9 +133,15 @@ void llvm::report_bad_alloc_error(const char *Reason, bool GenCrashDiag) {
+   // an OOM to stderr and abort.
+   const char *OOMMessage = "LLVM ERROR: out of memory\n";
+   const char *Newline = "\n";
++#ifdef _WIN32
++  (void)!::_write(2, OOMMessage, strlen(OOMMessage));
++  (void)!::_write(2, Reason, strlen(Reason));
++  (void)!::_write(2, Newline, strlen(Newline));
++#else
+   (void)!::write(2, OOMMessage, strlen(OOMMessage));
+   (void)!::write(2, Reason, strlen(Reason));
+   (void)!::write(2, Newline, strlen(Newline));
++#endif
+   abort();
+ }
+ 
diff --git a/third_party/allwpilib/upstream_utils/llvm_patches/0024-Use-SmallVector-for-UTF-conversion.patch b/third_party/allwpilib/upstream_utils/llvm_patches/0024-Use-SmallVector-for-UTF-conversion.patch
new file mode 100644
index 0000000..96088d2
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/llvm_patches/0024-Use-SmallVector-for-UTF-conversion.patch
@@ -0,0 +1,152 @@
+From f58b9bad86f61c35cc530ff113ccbb13415261c8 Mon Sep 17 00:00:00 2001
+From: PJ Reiniger <pj.reiniger@gmail.com>
+Date: Mon, 9 May 2022 00:04:30 -0400
+Subject: [PATCH 24/28] Use SmallVector for UTF conversion
+
+---
+ llvm/include/llvm/Support/ConvertUTF.h    |  6 +++---
+ llvm/lib/Support/ConvertUTFWrapper.cpp    |  6 +++---
+ llvm/unittests/Support/ConvertUTFTest.cpp | 22 +++++++++++-----------
+ 3 files changed, 17 insertions(+), 17 deletions(-)
+
+diff --git a/llvm/include/llvm/Support/ConvertUTF.h b/llvm/include/llvm/Support/ConvertUTF.h
+index b085c8a17..c82947006 100644
+--- a/llvm/include/llvm/Support/ConvertUTF.h
++++ b/llvm/include/llvm/Support/ConvertUTF.h
+@@ -213,7 +213,7 @@ bool ConvertUTF8toWide(const char *Source, std::wstring &Result);
+ * Converts a std::wstring to a UTF-8 encoded std::string.
+ * \return true on success.
+ */
+-bool convertWideToUTF8(const std::wstring &Source, std::string &Result);
++bool convertWideToUTF8(const std::wstring &Source, SmallVectorImpl<char> &Result);
+ 
+ 
+ /**
+@@ -268,7 +268,7 @@ bool hasUTF16ByteOrderMark(span<const char> SrcBytes);
+  * \param [out] Out Converted UTF-8 is stored here on success.
+  * \returns true on success
+  */
+-bool convertUTF16ToUTF8String(span<const char> SrcBytes, std::string &Out);
++bool convertUTF16ToUTF8String(span<const char> SrcBytes, SmallVectorImpl<char> &Out);
+ 
+ /**
+ * Converts a UTF16 string into a UTF8 std::string.
+@@ -277,7 +277,7 @@ bool convertUTF16ToUTF8String(span<const char> SrcBytes, std::string &Out);
+ * \param [out] Out Converted UTF-8 is stored here on success.
+ * \returns true on success
+ */
+-bool convertUTF16ToUTF8String(span<const UTF16> Src, std::string &Out);
++bool convertUTF16ToUTF8String(span<const UTF16> Src, SmallVectorImpl<char> &Out);
+ 
+ /**
+  * Converts a UTF-8 string into a UTF-16 string with native endianness.
+diff --git a/llvm/lib/Support/ConvertUTFWrapper.cpp b/llvm/lib/Support/ConvertUTFWrapper.cpp
+index cff30f16c..d3689d92a 100644
+--- a/llvm/lib/Support/ConvertUTFWrapper.cpp
++++ b/llvm/lib/Support/ConvertUTFWrapper.cpp
+@@ -84,7 +84,7 @@ bool hasUTF16ByteOrderMark(span<const char> S) {
+            (S[0] == '\xfe' && S[1] == '\xff')));
+ }
+ 
+-bool convertUTF16ToUTF8String(span<const char> SrcBytes, std::string &Out) {
++bool convertUTF16ToUTF8String(span<const char> SrcBytes, SmallVectorImpl<char> &Out) {
+   assert(Out.empty());
+ 
+   // Error out on an uneven byte count.
+@@ -135,7 +135,7 @@ bool convertUTF16ToUTF8String(span<const char> SrcBytes, std::string &Out) {
+   return true;
+ }
+ 
+-bool convertUTF16ToUTF8String(span<const UTF16> Src, std::string &Out)
++bool convertUTF16ToUTF8String(span<const UTF16> Src, SmallVectorImpl<char> &Out)
+ {
+   return convertUTF16ToUTF8String(
+       span<const char>(reinterpret_cast<const char *>(Src.data()),
+@@ -213,7 +213,7 @@ bool ConvertUTF8toWide(const char *Source, std::wstring &Result) {
+   return ConvertUTF8toWide(std::string_view(Source), Result);
+ }
+ 
+-bool convertWideToUTF8(const std::wstring &Source, std::string &Result) {
++bool convertWideToUTF8(const std::wstring &Source, SmallVectorImpl<char> &Result) {
+   if (sizeof(wchar_t) == 1) {
+     const UTF8 *Start = reinterpret_cast<const UTF8 *>(Source.data());
+     const UTF8 *End =
+diff --git a/llvm/unittests/Support/ConvertUTFTest.cpp b/llvm/unittests/Support/ConvertUTFTest.cpp
+index 2fee8ad5c..7d7650b1c 100644
+--- a/llvm/unittests/Support/ConvertUTFTest.cpp
++++ b/llvm/unittests/Support/ConvertUTFTest.cpp
+@@ -19,22 +19,22 @@ TEST(ConvertUTFTest, ConvertUTF16LittleEndianToUTF8String) {
+   // Src is the look of disapproval.
+   alignas(UTF16) static const char Src[] = "\xff\xfe\xa0\x0c_\x00\xa0\x0c";
+   span<const char> Ref(Src, sizeof(Src) - 1);
+-  std::string Result;
++  SmallString<20> Result;
+   bool Success = convertUTF16ToUTF8String(Ref, Result);
+   EXPECT_TRUE(Success);
+   std::string Expected("\xe0\xb2\xa0_\xe0\xb2\xa0");
+-  EXPECT_EQ(Expected, Result);
++  EXPECT_EQ(Expected, std::string{Result});
+ }
+ 
+ TEST(ConvertUTFTest, ConvertUTF16BigEndianToUTF8String) {
+   // Src is the look of disapproval.
+   alignas(UTF16) static const char Src[] = "\xfe\xff\x0c\xa0\x00_\x0c\xa0";
+   span<const char> Ref(Src, sizeof(Src) - 1);
+-  std::string Result;
++  SmallString<20> Result;
+   bool Success = convertUTF16ToUTF8String(Ref, Result);
+   EXPECT_TRUE(Success);
+   std::string Expected("\xe0\xb2\xa0_\xe0\xb2\xa0");
+-  EXPECT_EQ(Expected, Result);
++  EXPECT_EQ(Expected, std::string{Result});
+ }
+ 
+ TEST(ConvertUTFTest, ConvertUTF8ToUTF16String) {
+@@ -51,16 +51,16 @@ TEST(ConvertUTFTest, ConvertUTF8ToUTF16String) {
+ }
+ 
+ TEST(ConvertUTFTest, OddLengthInput) {
+-  std::string Result;
++  SmallString<20> Result;
+   bool Success = convertUTF16ToUTF8String(span<const char>("xxxxx", 5), Result);
+   EXPECT_FALSE(Success);
+ }
+ 
+ TEST(ConvertUTFTest, Empty) {
+-  std::string Result;
++  SmallString<20> Result;
+   bool Success = convertUTF16ToUTF8String(span<const char>(), Result);
+   EXPECT_TRUE(Success);
+-  EXPECT_TRUE(Result.empty());
++  EXPECT_TRUE(std::string{Result}.empty());
+ }
+ 
+ TEST(ConvertUTFTest, HasUTF16BOM) {
+@@ -83,11 +83,11 @@ TEST(ConvertUTFTest, UTF16WrappersForConvertUTF16ToUTF8String) {
+   // Src is the look of disapproval.
+   alignas(UTF16) static const char Src[] = "\xff\xfe\xa0\x0c_\x00\xa0\x0c";
+   span<const UTF16> SrcRef((const UTF16 *)Src, 4);
+-  std::string Result;
++  SmallString<20> Result;
+   bool Success = convertUTF16ToUTF8String(SrcRef, Result);
+   EXPECT_TRUE(Success);
+   std::string Expected("\xe0\xb2\xa0_\xe0\xb2\xa0");
+-  EXPECT_EQ(Expected, Result);
++  EXPECT_EQ(Expected, std::string{Result});
+ }
+ 
+ TEST(ConvertUTFTest, ConvertUTF8toWide) {
+@@ -107,11 +107,11 @@ TEST(ConvertUTFTest, ConvertUTF8toWide) {
+ TEST(ConvertUTFTest, convertWideToUTF8) {
+   // Src is the look of disapproval.
+   static const wchar_t Src[] = L"\x0ca0_\x0ca0";
+-  std::string Result;
++  SmallString<20> Result;
+   bool Success = convertWideToUTF8(Src, Result);
+   EXPECT_TRUE(Success);
+   std::string Expected("\xe0\xb2\xa0_\xe0\xb2\xa0");
+-  EXPECT_EQ(Expected, Result);
++  EXPECT_EQ(Expected, std::string{Result});
+ }
+ 
+ struct ConvertUTFResultContainer {
diff --git a/third_party/allwpilib/upstream_utils/llvm_patches/0025-Prefer-to-use-static-pointers-in-raw_ostream.patch b/third_party/allwpilib/upstream_utils/llvm_patches/0025-Prefer-to-use-static-pointers-in-raw_ostream.patch
new file mode 100644
index 0000000..36a884c
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/llvm_patches/0025-Prefer-to-use-static-pointers-in-raw_ostream.patch
@@ -0,0 +1,34 @@
+From 35b1a8382240732065790c88a0c515701c1a2beb Mon Sep 17 00:00:00 2001
+From: PJ Reiniger <pj.reiniger@gmail.com>
+Date: Thu, 19 May 2022 00:58:36 -0400
+Subject: [PATCH 25/28] Prefer to use static pointers in raw_ostream
+
+See #1401
+---
+ llvm/lib/Support/raw_ostream.cpp | 8 ++++----
+ 1 file changed, 4 insertions(+), 4 deletions(-)
+
+diff --git a/llvm/lib/Support/raw_ostream.cpp b/llvm/lib/Support/raw_ostream.cpp
+index 632b52235..a703a75ed 100644
+--- a/llvm/lib/Support/raw_ostream.cpp
++++ b/llvm/lib/Support/raw_ostream.cpp
+@@ -599,15 +599,15 @@ void raw_fd_ostream::anchor() {}
+ raw_fd_ostream &llvm::outs() {
+   // Set buffer settings to model stdout behavior.
+   std::error_code EC;
+-  static raw_fd_ostream S("-", EC, sys::fs::OF_None);
++  static raw_fd_ostream* S = new raw_fd_ostream("-", EC, sys::fs::OF_None);
+   assert(!EC);
+-  return S;
++  return *S;
+ }
+ 
+ raw_fd_ostream &llvm::errs() {
+   // Set standard error to be unbuffered and tied to outs() by default.
+-  static raw_fd_ostream S(STDERR_FILENO, false, true);
+-  return S;
++  static raw_fd_ostream* S = new raw_fd_ostream(STDERR_FILENO, false, true);
++  return *S;
+ }
+ 
+ /// nulls() - This returns a reference to a raw_ostream which discards output.
diff --git a/third_party/allwpilib/upstream_utils/llvm_patches/0026-constexpr-endian-byte-swap.patch b/third_party/allwpilib/upstream_utils/llvm_patches/0026-constexpr-endian-byte-swap.patch
new file mode 100644
index 0000000..79e0e7d
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/llvm_patches/0026-constexpr-endian-byte-swap.patch
@@ -0,0 +1,24 @@
+From 34f44d312c918b3b5dd69fc689ec0b628dc712f9 Mon Sep 17 00:00:00 2001
+From: PJ Reiniger <pj.reiniger@gmail.com>
+Date: Thu, 19 May 2022 01:12:41 -0400
+Subject: [PATCH 26/28] constexpr endian byte swap
+
+---
+ llvm/include/llvm/Support/Endian.h | 4 +++-
+ 1 file changed, 3 insertions(+), 1 deletion(-)
+
+diff --git a/llvm/include/llvm/Support/Endian.h b/llvm/include/llvm/Support/Endian.h
+index 5e7c1e961..2e883ff05 100644
+--- a/llvm/include/llvm/Support/Endian.h
++++ b/llvm/include/llvm/Support/Endian.h
+@@ -55,7 +55,9 @@ inline value_type byte_swap(value_type value, endianness endian) {
+ /// Swap the bytes of value to match the given endianness.
+ template<typename value_type, endianness endian>
+ inline value_type byte_swap(value_type value) {
+-  return byte_swap(value, endian);
++  if constexpr ((endian != native) && (endian != system_endianness()))
++    sys::swapByteOrder(value);
++  return value;
+ }
+ 
+ /// Read a value of a particular endianness from memory.
diff --git a/third_party/allwpilib/upstream_utils/llvm_patches/0027-Copy-type-traits-from-STLExtras.h-into-PointerUnion..patch b/third_party/allwpilib/upstream_utils/llvm_patches/0027-Copy-type-traits-from-STLExtras.h-into-PointerUnion..patch
new file mode 100644
index 0000000..9f192a1
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/llvm_patches/0027-Copy-type-traits-from-STLExtras.h-into-PointerUnion..patch
@@ -0,0 +1,69 @@
+From 8f51777a3117a7b010a4cfb2ded1f5d226466f34 Mon Sep 17 00:00:00 2001
+From: Tyler Veness <calcmogul@gmail.com>
+Date: Wed, 10 Aug 2022 17:07:52 -0700
+Subject: [PATCH 27/28] Copy type traits from STLExtras.h into PointerUnion.h
+
+---
+ llvm/include/llvm/ADT/PointerUnion.h | 46 ++++++++++++++++++++++++++++
+ 1 file changed, 46 insertions(+)
+
+diff --git a/llvm/include/llvm/ADT/PointerUnion.h b/llvm/include/llvm/ADT/PointerUnion.h
+index 1d4cc747c..7d090da59 100644
+--- a/llvm/include/llvm/ADT/PointerUnion.h
++++ b/llvm/include/llvm/ADT/PointerUnion.h
+@@ -22,9 +22,55 @@
+ #include <cassert>
+ #include <cstddef>
+ #include <cstdint>
++#include <type_traits>
+ 
+ namespace llvm {
+ 
++namespace detail {
++template <typename T, typename... Us> struct TypesAreDistinct;
++template <typename T, typename... Us>
++struct TypesAreDistinct
++    : std::integral_constant<bool, !std::disjunction_v<std::is_same<T, Us>...> &&
++                                       TypesAreDistinct<Us...>::value> {};
++template <typename T> struct TypesAreDistinct<T> : std::true_type {};
++} // namespace detail
++
++/// Determine if all types in Ts are distinct.
++///
++/// Useful to statically assert when Ts is intended to describe a non-multi set
++/// of types.
++///
++/// Expensive (currently quadratic in sizeof(Ts...)), and so should only be
++/// asserted once per instantiation of a type which requires it.
++template <typename... Ts> struct TypesAreDistinct;
++template <> struct TypesAreDistinct<> : std::true_type {};
++template <typename... Ts>
++struct TypesAreDistinct
++    : std::integral_constant<bool, detail::TypesAreDistinct<Ts...>::value> {};
++
++/// Find the first index where a type appears in a list of types.
++///
++/// FirstIndexOfType<T, Us...>::value is the first index of T in Us.
++///
++/// Typically only meaningful when it is otherwise statically known that the
++/// type pack has no duplicate types. This should be guaranteed explicitly with
++/// static_assert(TypesAreDistinct<Us...>::value).
++///
++/// It is a compile-time error to instantiate when T is not present in Us, i.e.
++/// if is_one_of<T, Us...>::value is false.
++template <typename T, typename... Us> struct FirstIndexOfType;
++template <typename T, typename U, typename... Us>
++struct FirstIndexOfType<T, U, Us...>
++    : std::integral_constant<size_t, 1 + FirstIndexOfType<T, Us...>::value> {};
++template <typename T, typename... Us>
++struct FirstIndexOfType<T, T, Us...> : std::integral_constant<size_t, 0> {};
++
++/// Find the type at a given index in a list of types.
++///
++/// TypeAtIndex<I, Ts...> is the type at index I in Ts.
++template <size_t I, typename... Ts>
++using TypeAtIndex = std::tuple_element_t<I, std::tuple<Ts...>>;
++
+ namespace pointer_union_detail {
+   /// Determine the number of bits required to store integers with values < n.
+   /// This is ceil(log2(n)).
diff --git a/third_party/allwpilib/upstream_utils/llvm_patches/0028-Remove-StringMap-test-for-llvm-sort.patch b/third_party/allwpilib/upstream_utils/llvm_patches/0028-Remove-StringMap-test-for-llvm-sort.patch
new file mode 100644
index 0000000..5c847e1
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/llvm_patches/0028-Remove-StringMap-test-for-llvm-sort.patch
@@ -0,0 +1,34 @@
+From 498e56e09e8f264978831519ff9c8afa701bf208 Mon Sep 17 00:00:00 2001
+From: Tyler Veness <calcmogul@gmail.com>
+Date: Wed, 10 Aug 2022 22:35:00 -0700
+Subject: [PATCH 28/28] Remove StringMap test for llvm::sort()
+
+---
+ llvm/unittests/ADT/StringMapTest.cpp | 14 --------------
+ 1 file changed, 14 deletions(-)
+
+diff --git a/llvm/unittests/ADT/StringMapTest.cpp b/llvm/unittests/ADT/StringMapTest.cpp
+index de6daf3da..ca41631cc 100644
+--- a/llvm/unittests/ADT/StringMapTest.cpp
++++ b/llvm/unittests/ADT/StringMapTest.cpp
+@@ -308,20 +308,6 @@ TEST_F(StringMapTest, InsertOrAssignTest) {
+   EXPECT_EQ(0, try1.first->second.copy);
+ }
+ 
+-TEST_F(StringMapTest, IterMapKeysVector) {
+-  StringMap<int> Map;
+-  Map["A"] = 1;
+-  Map["B"] = 2;
+-  Map["C"] = 3;
+-  Map["D"] = 3;
+-
+-  std::vector<std::string_view> Keys{Map.keys().begin(), Map.keys().end()};
+-  llvm::sort(Keys);
+-
+-  std::vector<std::string_view> Expected{{"A", "B", "C", "D"}};
+-  EXPECT_EQ(Expected, Keys);
+-}
+-
+ TEST_F(StringMapTest, IterMapKeysSmallVector) {
+   StringMap<int> Map;
+   Map["A"] = 1;
diff --git a/third_party/allwpilib/upstream_utils/memory_files/config_impl.hpp b/third_party/allwpilib/upstream_utils/memory_files/config_impl.hpp
new file mode 100644
index 0000000..1f72375
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/memory_files/config_impl.hpp
@@ -0,0 +1,34 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+// Copyright (C) 2015-2020 Jonathan Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#pragma once
+
+#include <cstddef>
+
+//=== options ===//
+#define WPI_MEMORY_CHECK_ALLOCATION_SIZE 1
+#define WPI_MEMORY_IMPL_DEFAULT_ALLOCATOR heap_allocator
+#ifdef NDEBUG
+#define WPI_MEMORY_DEBUG_ASSERT 0
+#define WPI_MEMORY_DEBUG_FILL 0
+#define WPI_MEMORY_DEBUG_FENCE 0
+#define WPI_MEMORY_DEBUG_LEAK_CHECK 0
+#define WPI_MEMORY_DEBUG_POINTER_CHECK 0
+#define WPI_MEMORY_DEBUG_DOUBLE_DEALLOC_CHECK 0
+#else
+#define WPI_MEMORY_DEBUG_ASSERT 1
+#define WPI_MEMORY_DEBUG_FILL 1
+#define WPI_MEMORY_DEBUG_FENCE 8
+#define WPI_MEMORY_DEBUG_LEAK_CHECK 1
+#define WPI_MEMORY_DEBUG_POINTER_CHECK 1
+#define WPI_MEMORY_DEBUG_DOUBLE_DEALLOC_CHECK 1
+#endif
+#define WPI_MEMORY_EXTERN_TEMPLATE 1
+#define WPI_MEMORY_TEMPORARY_STACK_MODE 2
+
+#define WPI_MEMORY_NO_NODE_SIZE 1
diff --git a/third_party/allwpilib/upstream_utils/mpack_patches/0001-Don-t-emit-inline-defs.patch b/third_party/allwpilib/upstream_utils/mpack_patches/0001-Don-t-emit-inline-defs.patch
new file mode 100644
index 0000000..a899a5e
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/mpack_patches/0001-Don-t-emit-inline-defs.patch
@@ -0,0 +1,22 @@
+From 05864e768ca1458c1e24f433d091306a7d47562b Mon Sep 17 00:00:00 2001
+From: PJ Reiniger <pj.reiniger@gmail.com>
+Date: Sat, 29 Oct 2022 12:09:03 -0400
+Subject: [PATCH 1/3] Don't emit inline defs
+
+---
+ src/mpack/mpack-platform.c | 2 +-
+ 1 file changed, 1 insertion(+), 1 deletion(-)
+
+diff --git a/src/mpack/mpack-platform.c b/src/mpack/mpack-platform.c
+index 6599e1f..d4a2fa3 100644
+--- a/src/mpack/mpack-platform.c
++++ b/src/mpack/mpack-platform.c
+@@ -24,7 +24,7 @@
+ // standalone definitions of all (non-static) inline functions in MPack.
+ 
+ #define MPACK_INTERNAL 1
+-#define MPACK_EMIT_INLINE_DEFS 1
++#define MPACK_EMIT_INLINE_DEFS 0
+ 
+ #include "mpack-platform.h"
+ #include "mpack.h"
diff --git a/third_party/allwpilib/upstream_utils/mpack_patches/0002-Update-amalgamation-script.patch b/third_party/allwpilib/upstream_utils/mpack_patches/0002-Update-amalgamation-script.patch
new file mode 100644
index 0000000..eabf154
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/mpack_patches/0002-Update-amalgamation-script.patch
@@ -0,0 +1,24 @@
+From d4d045c843d4b4de747d800e570c32cff3759a80 Mon Sep 17 00:00:00 2001
+From: PJ Reiniger <pj.reiniger@gmail.com>
+Date: Sat, 29 Oct 2022 12:16:36 -0400
+Subject: [PATCH 2/3] Update amalgamation script
+
+---
+ tools/amalgamate.sh | 4 ++--
+ 1 file changed, 2 insertions(+), 2 deletions(-)
+
+diff --git a/tools/amalgamate.sh b/tools/amalgamate.sh
+index 2e24e27..4dfe999 100755
+--- a/tools/amalgamate.sh
++++ b/tools/amalgamate.sh
+@@ -74,8 +74,8 @@ echo -e "#endif\n" >> $HEADER
+ 
+ # assemble source
+ echo -e "#define MPACK_INTERNAL 1" >> $SOURCE
+-echo -e "#define MPACK_EMIT_INLINE_DEFS 1\n" >> $SOURCE
+-echo -e "#include \"mpack.h\"\n" >> $SOURCE
++echo -e "#define MPACK_EMIT_INLINE_DEFS 0\n" >> $SOURCE
++echo -e "#include \"wpi/mpack.h\"\n" >> $SOURCE
+ for f in $SOURCES; do
+     echo -e "\n/* $f.c */" >> $SOURCE
+     sed -e 's@^#include ".*@/* & */@' -e '0,/^ \*\/$/d' src/$f >> $SOURCE
diff --git a/third_party/allwpilib/upstream_utils/mpack_patches/0003-Use-namespace-for-C.patch b/third_party/allwpilib/upstream_utils/mpack_patches/0003-Use-namespace-for-C.patch
new file mode 100644
index 0000000..4adb7f8
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/mpack_patches/0003-Use-namespace-for-C.patch
@@ -0,0 +1,158 @@
+From 37854ea8a4a4b387940719c40bd32792f1e6e027 Mon Sep 17 00:00:00 2001
+From: PJ Reiniger <pj.reiniger@gmail.com>
+Date: Sat, 29 Oct 2022 12:22:50 -0400
+Subject: [PATCH 3/3] Use namespace for C++
+
+---
+ src/mpack/mpack-common.c   | 2 ++
+ src/mpack/mpack-expect.c   | 2 ++
+ src/mpack/mpack-node.c     | 2 ++
+ src/mpack/mpack-platform.c | 2 ++
+ src/mpack/mpack-platform.h | 2 +-
+ src/mpack/mpack-reader.c   | 2 ++
+ src/mpack/mpack-writer.c   | 2 ++
+ src/mpack/mpack-writer.h   | 3 ++-
+ 8 files changed, 15 insertions(+), 2 deletions(-)
+
+diff --git a/src/mpack/mpack-common.c b/src/mpack/mpack-common.c
+index 2c133a3..dc7207f 100644
+--- a/src/mpack/mpack-common.c
++++ b/src/mpack/mpack-common.c
+@@ -24,6 +24,7 @@
+ #include "mpack-common.h"
+ 
+ MPACK_SILENCE_WARNINGS_BEGIN
++namespace mpack {
+ 
+ const char* mpack_error_to_string(mpack_error_t error) {
+     #if MPACK_STRINGS
+@@ -748,4 +749,5 @@ void mpack_print_file_callback(void* context, const char* data, size_t count) {
+ }
+ #endif
+ 
++}  // namespace mpack
+ MPACK_SILENCE_WARNINGS_END
+diff --git a/src/mpack/mpack-expect.c b/src/mpack/mpack-expect.c
+index 81576d1..6232a67 100644
+--- a/src/mpack/mpack-expect.c
++++ b/src/mpack/mpack-expect.c
+@@ -24,6 +24,7 @@
+ #include "mpack-expect.h"
+ 
+ MPACK_SILENCE_WARNINGS_BEGIN
++namespace mpack {
+ 
+ #if MPACK_EXPECT
+ 
+@@ -880,4 +881,5 @@ size_t mpack_expect_key_cstr(mpack_reader_t* reader, const char* keys[], bool fo
+ 
+ #endif
+ 
++}  // namespace mpack
+ MPACK_SILENCE_WARNINGS_END
+diff --git a/src/mpack/mpack-node.c b/src/mpack/mpack-node.c
+index 3d4b0f4..aba9897 100644
+--- a/src/mpack/mpack-node.c
++++ b/src/mpack/mpack-node.c
+@@ -24,6 +24,7 @@
+ #include "mpack-node.h"
+ 
+ MPACK_SILENCE_WARNINGS_BEGIN
++namespace mpack {
+ 
+ #if MPACK_NODE
+ 
+@@ -2401,4 +2402,5 @@ mpack_node_t mpack_node_map_value_at(mpack_node_t node, size_t index) {
+ 
+ #endif
+ 
++}  // namespace mpack
+ MPACK_SILENCE_WARNINGS_END
+diff --git a/src/mpack/mpack-platform.c b/src/mpack/mpack-platform.c
+index d4a2fa3..75d2de3 100644
+--- a/src/mpack/mpack-platform.c
++++ b/src/mpack/mpack-platform.c
+@@ -30,6 +30,7 @@
+ #include "mpack.h"
+ 
+ MPACK_SILENCE_WARNINGS_BEGIN
++namespace mpack {
+ 
+ #if MPACK_DEBUG
+ 
+@@ -218,4 +219,5 @@ void* mpack_realloc(void* old_ptr, size_t used_size, size_t new_size) {
+ }
+ #endif
+ 
++}  // namespace mpack
+ MPACK_SILENCE_WARNINGS_END
+diff --git a/src/mpack/mpack-platform.h b/src/mpack/mpack-platform.h
+index 79604c9..27a2f9e 100644
+--- a/src/mpack/mpack-platform.h
++++ b/src/mpack/mpack-platform.h
+@@ -1043,7 +1043,7 @@ void mpack_assert_fail(const char* message);
+  */
+ 
+ #ifdef __cplusplus
+-    #define MPACK_EXTERN_C_BEGIN extern "C" {
++    #define MPACK_EXTERN_C_BEGIN namespace mpack {
+     #define MPACK_EXTERN_C_END   }
+ #else
+     #define MPACK_EXTERN_C_BEGIN /*nothing*/
+diff --git a/src/mpack/mpack-reader.c b/src/mpack/mpack-reader.c
+index c6d2223..a135879 100644
+--- a/src/mpack/mpack-reader.c
++++ b/src/mpack/mpack-reader.c
+@@ -24,6 +24,7 @@
+ #include "mpack-reader.h"
+ 
+ MPACK_SILENCE_WARNINGS_BEGIN
++namespace mpack {
+ 
+ #if MPACK_READER
+ 
+@@ -1284,4 +1285,5 @@ void mpack_print_stdfile_to_callback(FILE* file, mpack_print_callback_t callback
+ 
+ #endif
+ 
++}  // namespace mpack
+ MPACK_SILENCE_WARNINGS_END
+diff --git a/src/mpack/mpack-writer.c b/src/mpack/mpack-writer.c
+index 4d052b1..9630d9e 100644
+--- a/src/mpack/mpack-writer.c
++++ b/src/mpack/mpack-writer.c
+@@ -24,6 +24,7 @@
+ #include "mpack-writer.h"
+ 
+ MPACK_SILENCE_WARNINGS_BEGIN
++namespace mpack {
+ 
+ #if MPACK_WRITER
+ 
+@@ -1772,4 +1773,5 @@ void mpack_complete_array(mpack_writer_t* writer) {
+ #endif // MPACK_BUILDER
+ #endif // MPACK_WRITER
+ 
++}  // namespace mpack
+ MPACK_SILENCE_WARNINGS_END
+diff --git a/src/mpack/mpack-writer.h b/src/mpack/mpack-writer.h
+index c239ee6..abeee1a 100644
+--- a/src/mpack/mpack-writer.h
++++ b/src/mpack/mpack-writer.h
+@@ -1168,6 +1168,7 @@ MPACK_EXTERN_C_END
+ 
+ #if defined(__cplusplus) || defined(MPACK_DOXYGEN)
+ 
++namespace mpack {
+ /**
+  * @name C++ write overloads
+  * @{
+@@ -1304,7 +1305,7 @@ MPACK_INLINE void mpack_write_kv(mpack_writer_t* writer, const char *key, const
+ /**
+  * @}
+  */
+-
++}  // namespace mpack
+ #endif /* __cplusplus */
+ 
+ /**
diff --git a/third_party/allwpilib/upstream_utils/stack_walker_patches/0001-Apply-PR-35.patch b/third_party/allwpilib/upstream_utils/stack_walker_patches/0001-Apply-PR-35.patch
new file mode 100644
index 0000000..8fe466e
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/stack_walker_patches/0001-Apply-PR-35.patch
@@ -0,0 +1,1353 @@
+From 6e2f70b7bb7c59fe99b7469bf3e3a257876403dc Mon Sep 17 00:00:00 2001
+From: PJ Reiniger <pj.reiniger@gmail.com>
+Date: Sun, 22 May 2022 23:58:57 -0400
+Subject: [PATCH 1/3] Apply PR #35
+
+---
+ .gitignore                              |   9 +
+ Main/StackWalker/StackWalker.cpp        | 642 ++++++++++--------------
+ Main/StackWalker/StackWalker.h          |  40 +-
+ Main/StackWalker/StackWalker_VC2017.sln |  16 +-
+ Main/StackWalker/main.cpp               |   2 +-
+ 5 files changed, 306 insertions(+), 403 deletions(-)
+ create mode 100644 .gitignore
+
+diff --git a/.gitignore b/.gitignore
+new file mode 100644
+index 0000000..5d102c5
+--- /dev/null
++++ b/.gitignore
+@@ -0,0 +1,9 @@
++################################################################################
++# This .gitignore file was automatically created by Microsoft(R) Visual Studio.
++################################################################################
++
++*.suo
++*.db
++*.sqlite
++/Main/StackWalker/_ReSharper.Caches/*
++/.vs/*
+diff --git a/Main/StackWalker/StackWalker.cpp b/Main/StackWalker/StackWalker.cpp
+index 7008ac6..48c7c57 100644
+--- a/Main/StackWalker/StackWalker.cpp
++++ b/Main/StackWalker/StackWalker.cpp
+@@ -1,4 +1,4 @@
+-/**********************************************************************
++/**********************************************************************
+  *
+  * StackWalker.cpp
+  * https://github.com/JochenKalmbach/StackWalker
+@@ -87,162 +87,36 @@
+ #include <stdio.h>
+ #include <stdlib.h>
+ #include <tchar.h>
+-#include <windows.h>
+ #pragma comment(lib, "version.lib") // for "VerQueryValue"
+ #pragma warning(disable : 4826)
+ 
++#ifdef UNICODE
++  #define DBGHELP_TRANSLATE_TCHAR
+ 
+-// If VC7 and later, then use the shipped 'dbghelp.h'-file
++#endif
+ #pragma pack(push, 8)
+-#if _MSC_VER >= 1300
+ #include <dbghelp.h>
+-#else
+-// inline the important dbghelp.h-declarations...
+-typedef enum
+-{
+-  SymNone = 0,
+-  SymCoff,
+-  SymCv,
+-  SymPdb,
+-  SymExport,
+-  SymDeferred,
+-  SymSym,
+-  SymDia,
+-  SymVirtual,
+-  NumSymTypes
+-} SYM_TYPE;
+-typedef struct _IMAGEHLP_LINE64
+-{
+-  DWORD   SizeOfStruct; // set to sizeof(IMAGEHLP_LINE64)
+-  PVOID   Key;          // internal
+-  DWORD   LineNumber;   // line number in file
+-  PCHAR   FileName;     // full filename
+-  DWORD64 Address;      // first instruction of line
+-} IMAGEHLP_LINE64, *PIMAGEHLP_LINE64;
+-typedef struct _IMAGEHLP_MODULE64
+-{
+-  DWORD    SizeOfStruct;         // set to sizeof(IMAGEHLP_MODULE64)
+-  DWORD64  BaseOfImage;          // base load address of module
+-  DWORD    ImageSize;            // virtual size of the loaded module
+-  DWORD    TimeDateStamp;        // date/time stamp from pe header
+-  DWORD    CheckSum;             // checksum from the pe header
+-  DWORD    NumSyms;              // number of symbols in the symbol table
+-  SYM_TYPE SymType;              // type of symbols loaded
+-  CHAR     ModuleName[32];       // module name
+-  CHAR     ImageName[256];       // image name
+-  CHAR     LoadedImageName[256]; // symbol file name
+-} IMAGEHLP_MODULE64, *PIMAGEHLP_MODULE64;
+-typedef struct _IMAGEHLP_SYMBOL64
+-{
+-  DWORD   SizeOfStruct;  // set to sizeof(IMAGEHLP_SYMBOL64)
+-  DWORD64 Address;       // virtual address including dll base address
+-  DWORD   Size;          // estimated size of symbol, can be zero
+-  DWORD   Flags;         // info about the symbols, see the SYMF defines
+-  DWORD   MaxNameLength; // maximum size of symbol name in 'Name'
+-  CHAR    Name[1];       // symbol name (null terminated string)
+-} IMAGEHLP_SYMBOL64, *PIMAGEHLP_SYMBOL64;
+-typedef enum
+-{
+-  AddrMode1616,
+-  AddrMode1632,
+-  AddrModeReal,
+-  AddrModeFlat
+-} ADDRESS_MODE;
+-typedef struct _tagADDRESS64
+-{
+-  DWORD64      Offset;
+-  WORD         Segment;
+-  ADDRESS_MODE Mode;
+-} ADDRESS64, *LPADDRESS64;
+-typedef struct _KDHELP64
+-{
+-  DWORD64 Thread;
+-  DWORD   ThCallbackStack;
+-  DWORD   ThCallbackBStore;
+-  DWORD   NextCallback;
+-  DWORD   FramePointer;
+-  DWORD64 KiCallUserMode;
+-  DWORD64 KeUserCallbackDispatcher;
+-  DWORD64 SystemRangeStart;
+-  DWORD64 Reserved[8];
+-} KDHELP64, *PKDHELP64;
+-typedef struct _tagSTACKFRAME64
+-{
+-  ADDRESS64 AddrPC;         // program counter
+-  ADDRESS64 AddrReturn;     // return address
+-  ADDRESS64 AddrFrame;      // frame pointer
+-  ADDRESS64 AddrStack;      // stack pointer
+-  ADDRESS64 AddrBStore;     // backing store pointer
+-  PVOID     FuncTableEntry; // pointer to pdata/fpo or NULL
+-  DWORD64   Params[4];      // possible arguments to the function
+-  BOOL      Far;            // WOW far call
+-  BOOL      Virtual;        // is this a virtual frame?
+-  DWORD64   Reserved[3];
+-  KDHELP64  KdHelp;
+-} STACKFRAME64, *LPSTACKFRAME64;
+-typedef BOOL(__stdcall* PREAD_PROCESS_MEMORY_ROUTINE64)(HANDLE  hProcess,
+-                                                        DWORD64 qwBaseAddress,
+-                                                        PVOID   lpBuffer,
+-                                                        DWORD   nSize,
+-                                                        LPDWORD lpNumberOfBytesRead);
+-typedef PVOID(__stdcall* PFUNCTION_TABLE_ACCESS_ROUTINE64)(HANDLE hProcess, DWORD64 AddrBase);
+-typedef DWORD64(__stdcall* PGET_MODULE_BASE_ROUTINE64)(HANDLE hProcess, DWORD64 Address);
+-typedef DWORD64(__stdcall* PTRANSLATE_ADDRESS_ROUTINE64)(HANDLE      hProcess,
+-                                                         HANDLE      hThread,
+-                                                         LPADDRESS64 lpaddr);
+-
+-// clang-format off
+-#define SYMOPT_CASE_INSENSITIVE         0x00000001
+-#define SYMOPT_UNDNAME                  0x00000002
+-#define SYMOPT_DEFERRED_LOADS           0x00000004
+-#define SYMOPT_NO_CPP                   0x00000008
+-#define SYMOPT_LOAD_LINES               0x00000010
+-#define SYMOPT_OMAP_FIND_NEAREST        0x00000020
+-#define SYMOPT_LOAD_ANYTHING            0x00000040
+-#define SYMOPT_IGNORE_CVREC             0x00000080
+-#define SYMOPT_NO_UNQUALIFIED_LOADS     0x00000100
+-#define SYMOPT_FAIL_CRITICAL_ERRORS     0x00000200
+-#define SYMOPT_EXACT_SYMBOLS            0x00000400
+-#define SYMOPT_ALLOW_ABSOLUTE_SYMBOLS   0x00000800
+-#define SYMOPT_IGNORE_NT_SYMPATH        0x00001000
+-#define SYMOPT_INCLUDE_32BIT_MODULES    0x00002000
+-#define SYMOPT_PUBLICS_ONLY             0x00004000
+-#define SYMOPT_NO_PUBLICS               0x00008000
+-#define SYMOPT_AUTO_PUBLICS             0x00010000
+-#define SYMOPT_NO_IMAGE_SEARCH          0x00020000
+-#define SYMOPT_SECURE                   0x00040000
+-#define SYMOPT_DEBUG                    0x80000000
+-#define UNDNAME_COMPLETE                 (0x0000) // Enable full undecoration
+-#define UNDNAME_NAME_ONLY                (0x1000) // Crack only the name for primary declaration;
+-// clang-format on
+-
+-#endif // _MSC_VER < 1300
+ #pragma pack(pop)
+ 
+-// Some missing defines (for VC5/6):
+-#ifndef INVALID_FILE_ATTRIBUTES
+-#define INVALID_FILE_ATTRIBUTES ((DWORD)-1)
+-#endif
+ 
+-// secure-CRT_functions are only available starting with VC8
+-#if _MSC_VER < 1400
+-#define strcpy_s(dst, len, src) strcpy(dst, src)
+-#define strncpy_s(dst, len, src, maxLen) strncpy(dst, len, src)
+-#define strcat_s(dst, len, src) strcat(dst, src)
+-#define _snprintf_s _snprintf
+-#define _tcscat_s _tcscat
+-#endif
+-
+-static void MyStrCpy(char* szDest, size_t nMaxDestSize, const char* szSrc)
++static void MyStrCpy(TCHAR* szDest, size_t nMaxDestSize, const TCHAR* szSrc)
+ {
+   if (nMaxDestSize <= 0)
+     return;
+-  strncpy_s(szDest, nMaxDestSize, szSrc, _TRUNCATE);
++  _tcsncpy_s(szDest, nMaxDestSize, szSrc, _TRUNCATE);
+   // INFO: _TRUNCATE will ensure that it is null-terminated;
+   // but with older compilers (<1400) it uses "strncpy" and this does not!)
+   szDest[nMaxDestSize - 1] = 0;
+ } // MyStrCpy
+ 
++#ifdef _UNICODE
++  typedef SYMBOL_INFOW   tSymbolInfo;
++  typedef IMAGEHLP_LINEW64  tImageHelperLine;
++#else
++  typedef SYMBOL_INFO   tSymbolInfo;
++  typedef IMAGEHLP_LINE64  tImageHelperLine;
++#endif
++
+ // Normally it should be enough to use 'CONTEXT_FULL' (better would be 'CONTEXT_ALL')
+ #define USED_CONTEXT_FLAGS CONTEXT_FULL
+ 
+@@ -253,26 +127,26 @@ public:
+   {
+     m_parent = parent;
+     m_hDbhHelp = NULL;
+-    pSC = NULL;
++    symCleanup = NULL;
+     m_hProcess = hProcess;
+     m_szSymPath = NULL;
+-    pSFTA = NULL;
+-    pSGLFA = NULL;
+-    pSGMB = NULL;
+-    pSGMI = NULL;
+-    pSGO = NULL;
+-    pSGSFA = NULL;
+-    pSI = NULL;
+-    pSLM = NULL;
+-    pSSO = NULL;
+-    pSW = NULL;
+-    pUDSN = NULL;
+-    pSGSP = NULL;
++    symFunctionTableAccess64 = NULL;
++    symGetLineFromAddr64 = NULL;
++    symGetModuleBase64 = NULL;
++    symGetModuleInfo64 = NULL;
++    symGetOptions = NULL;
++    symFromAddr = NULL;
++    symInitialize = NULL;
++    symLoadModuleEx = NULL;
++    symSetOptions = NULL;
++    stackWalk64 = NULL;
++    unDecorateSymbolName = NULL;
++    symGetSearchPath = NULL;
+   }
+   ~StackWalkerInternal()
+   {
+-    if (pSC != NULL)
+-      pSC(m_hProcess); // SymCleanup
++    if (symCleanup != NULL)
++      symCleanup(m_hProcess); // SymCleanup
+     if (m_hDbhHelp != NULL)
+       FreeLibrary(m_hDbhHelp);
+     m_hDbhHelp = NULL;
+@@ -281,7 +155,7 @@ public:
+       free(m_szSymPath);
+     m_szSymPath = NULL;
+   }
+-  BOOL Init(LPCSTR szSymPath)
++  BOOL Init(LPCTSTR szSymPath)
+   {
+     if (m_parent == NULL)
+       return FALSE;
+@@ -354,54 +228,72 @@ public:
+       m_hDbhHelp = LoadLibrary(_T("dbghelp.dll"));
+     if (m_hDbhHelp == NULL)
+       return FALSE;
+-    pSI = (tSI)GetProcAddress(m_hDbhHelp, "SymInitialize");
+-    pSC = (tSC)GetProcAddress(m_hDbhHelp, "SymCleanup");
+-
+-    pSW = (tSW)GetProcAddress(m_hDbhHelp, "StackWalk64");
+-    pSGO = (tSGO)GetProcAddress(m_hDbhHelp, "SymGetOptions");
+-    pSSO = (tSSO)GetProcAddress(m_hDbhHelp, "SymSetOptions");
+-
+-    pSFTA = (tSFTA)GetProcAddress(m_hDbhHelp, "SymFunctionTableAccess64");
+-    pSGLFA = (tSGLFA)GetProcAddress(m_hDbhHelp, "SymGetLineFromAddr64");
+-    pSGMB = (tSGMB)GetProcAddress(m_hDbhHelp, "SymGetModuleBase64");
+-    pSGMI = (tSGMI)GetProcAddress(m_hDbhHelp, "SymGetModuleInfo64");
+-    pSGSFA = (tSGSFA)GetProcAddress(m_hDbhHelp, "SymGetSymFromAddr64");
+-    pUDSN = (tUDSN)GetProcAddress(m_hDbhHelp, "UnDecorateSymbolName");
+-    pSLM = (tSLM)GetProcAddress(m_hDbhHelp, "SymLoadModule64");
+-    pSGSP = (tSGSP)GetProcAddress(m_hDbhHelp, "SymGetSearchPath");
+-
+-    if (pSC == NULL || pSFTA == NULL || pSGMB == NULL || pSGMI == NULL || pSGO == NULL ||
+-        pSGSFA == NULL || pSI == NULL || pSSO == NULL || pSW == NULL || pUDSN == NULL ||
+-        pSLM == NULL)
++
++#ifdef _UNICODE
++    static const char strSymInitialize[] = "SymInitializeW";
++    static const char strUnDecorateSymbolName[] = "UnDecorateSymbolNameW";
++    static const char strSymGetSearchPath[] = "SymGetSearchPathW";
++    static const char strSymLoadModuleEx[] = "SymLoadModuleExW";
++    static const char strSymGetLineFromAddr64[] = "SymGetLineFromAddrW64";
++    static const char strSymGetModuleInfo64[] = "SymGetModuleInfoW64";
++    static const char strSymFromAddr[] = "SymFromAddrW";
++#else
++    static const char strSymInitialize[] = "SymInitialize";
++    static const char strUnDecorateSymbolName[] = "UnDecorateSymbolName";
++    static const char strSymGetSearchPath[] = "SymGetSearchPath";
++    static const char strSymLoadModuleEx[] = "SymLoadModuleEx";
++    static const char strSymGetLineFromAddr64[] = "SymGetLineFromAddr64";
++    static const char strSymGetModuleInfo64[] = "SymGetModuleInfo64";
++    static const char strSymFromAddr[] = "SymFromAddr";
++#endif
++    symInitialize = (tSI)GetProcAddress(m_hDbhHelp, strSymInitialize);
++    symCleanup = (tSC)GetProcAddress(m_hDbhHelp, "SymCleanup");
++
++    stackWalk64 = (tSW)GetProcAddress(m_hDbhHelp, "StackWalk64");
++    symGetOptions = (tSGO)GetProcAddress(m_hDbhHelp, "SymGetOptions");
++    symSetOptions = (tSSO)GetProcAddress(m_hDbhHelp, "SymSetOptions");
++
++    symFunctionTableAccess64 = (tSFTA)GetProcAddress(m_hDbhHelp, "SymFunctionTableAccess64");
++    symGetLineFromAddr64 = (tSGLFA)GetProcAddress(m_hDbhHelp, strSymGetLineFromAddr64);
++    symGetModuleBase64 = (tSGMB)GetProcAddress(m_hDbhHelp, "SymGetModuleBase64");
++    symGetModuleInfo64 = (tSGMI)GetProcAddress(m_hDbhHelp, strSymGetModuleInfo64);
++    symFromAddr = (tSFA)GetProcAddress(m_hDbhHelp, strSymFromAddr);
++    unDecorateSymbolName = (tUDSN)GetProcAddress(m_hDbhHelp, strUnDecorateSymbolName);
++    symLoadModuleEx = (tSLM)GetProcAddress(m_hDbhHelp, strSymLoadModuleEx);
++    symGetSearchPath = (tSGSP)GetProcAddress(m_hDbhHelp, strSymGetSearchPath);
++
++    if (symCleanup == NULL || symFunctionTableAccess64 == NULL || symGetModuleBase64 == NULL || symGetModuleInfo64 == NULL || symGetOptions == NULL ||
++        symFromAddr == NULL || symInitialize == NULL || symSetOptions == NULL || stackWalk64 == NULL || unDecorateSymbolName == NULL ||
++        symLoadModuleEx == NULL)
+     {
+       FreeLibrary(m_hDbhHelp);
+       m_hDbhHelp = NULL;
+-      pSC = NULL;
++      symCleanup = NULL;
+       return FALSE;
+     }
+ 
+     // SymInitialize
+     if (szSymPath != NULL)
+-      m_szSymPath = _strdup(szSymPath);
+-    if (this->pSI(m_hProcess, m_szSymPath, FALSE) == FALSE)
+-      this->m_parent->OnDbgHelpErr("SymInitialize", GetLastError(), 0);
++      m_szSymPath = _tcsdup(szSymPath);
++    if (this->symInitialize(m_hProcess, m_szSymPath, FALSE) == FALSE)
++      this->m_parent->OnDbgHelpErr(_T("SymInitialize"), GetLastError(), 0);
+ 
+-    DWORD symOptions = this->pSGO(); // SymGetOptions
++    DWORD symOptions = this->symGetOptions(); // SymGetOptions
+     symOptions |= SYMOPT_LOAD_LINES;
+     symOptions |= SYMOPT_FAIL_CRITICAL_ERRORS;
+     //symOptions |= SYMOPT_NO_PROMPTS;
+     // SymSetOptions
+-    symOptions = this->pSSO(symOptions);
++    symOptions = this->symSetOptions(symOptions);
+ 
+-    char buf[StackWalker::STACKWALK_MAX_NAMELEN] = {0};
+-    if (this->pSGSP != NULL)
++    TCHAR buf[StackWalker::STACKWALK_MAX_NAMELEN] = {0};
++    if (this->symGetSearchPath != NULL)
+     {
+-      if (this->pSGSP(m_hProcess, buf, StackWalker::STACKWALK_MAX_NAMELEN) == FALSE)
+-        this->m_parent->OnDbgHelpErr("SymGetSearchPath", GetLastError(), 0);
++      if (this->symGetSearchPath(m_hProcess, buf, StackWalker::STACKWALK_MAX_NAMELEN) == FALSE)
++        this->m_parent->OnDbgHelpErr(_T("SymGetSearchPath"), GetLastError(), 0);
+     }
+-    char  szUserName[1024] = {0};
++    TCHAR  szUserName[1024] = {0};
+     DWORD dwSize = 1024;
+-    GetUserNameA(szUserName, &dwSize);
++    GetUserName(szUserName, &dwSize);
+     this->m_parent->OnSymInit(buf, symOptions, szUserName);
+ 
+     return TRUE;
+@@ -411,7 +303,7 @@ public:
+ 
+   HMODULE m_hDbhHelp;
+   HANDLE  m_hProcess;
+-  LPSTR   m_szSymPath;
++  LPTSTR   m_szSymPath;
+ 
+ #pragma pack(push, 8)
+   typedef struct IMAGEHLP_MODULE64_V3
+@@ -423,13 +315,13 @@ public:
+     DWORD    CheckSum;             // checksum from the pe header
+     DWORD    NumSyms;              // number of symbols in the symbol table
+     SYM_TYPE SymType;              // type of symbols loaded
+-    CHAR     ModuleName[32];       // module name
+-    CHAR     ImageName[256];       // image name
+-    CHAR     LoadedImageName[256]; // symbol file name
++    TCHAR     ModuleName[32];       // module name
++    TCHAR     ImageName[256];       // image name
++    TCHAR     LoadedImageName[256]; // symbol file name
+     // new elements: 07-Jun-2002
+-    CHAR  LoadedPdbName[256];   // pdb file name
++    TCHAR  LoadedPdbName[256];   // pdb file name
+     DWORD CVSig;                // Signature of the CV record in the debug directories
+-    CHAR  CVData[MAX_PATH * 3]; // Contents of the CV record
++    TCHAR  CVData[MAX_PATH * 3]; // Contents of the CV record
+     DWORD PdbSig;               // Signature of PDB
+     GUID  PdbSig70;             // Signature of PDB (VC 7 and up)
+     DWORD PdbAge;               // DBI age of pdb
+@@ -460,56 +352,59 @@ public:
+ 
+   // SymCleanup()
+   typedef BOOL(__stdcall* tSC)(IN HANDLE hProcess);
+-  tSC pSC;
++  tSC symCleanup;
+ 
+   // SymFunctionTableAccess64()
+   typedef PVOID(__stdcall* tSFTA)(HANDLE hProcess, DWORD64 AddrBase);
+-  tSFTA pSFTA;
++  tSFTA symFunctionTableAccess64;
+ 
+   // SymGetLineFromAddr64()
+   typedef BOOL(__stdcall* tSGLFA)(IN HANDLE hProcess,
+                                   IN DWORD64 dwAddr,
+                                   OUT PDWORD pdwDisplacement,
+-                                  OUT PIMAGEHLP_LINE64 Line);
+-  tSGLFA pSGLFA;
++                                  OUT tImageHelperLine* Line);
++  tSGLFA symGetLineFromAddr64;
+ 
+   // SymGetModuleBase64()
+   typedef DWORD64(__stdcall* tSGMB)(IN HANDLE hProcess, IN DWORD64 dwAddr);
+-  tSGMB pSGMB;
++  tSGMB symGetModuleBase64;
+ 
+   // SymGetModuleInfo64()
+   typedef BOOL(__stdcall* tSGMI)(IN HANDLE hProcess,
+                                  IN DWORD64 dwAddr,
+                                  OUT IMAGEHLP_MODULE64_V3* ModuleInfo);
+-  tSGMI pSGMI;
++  tSGMI symGetModuleInfo64;
+ 
+   // SymGetOptions()
+   typedef DWORD(__stdcall* tSGO)(VOID);
+-  tSGO pSGO;
++  tSGO symGetOptions;
++
+ 
+   // SymGetSymFromAddr64()
+-  typedef BOOL(__stdcall* tSGSFA)(IN HANDLE hProcess,
+-                                  IN DWORD64 dwAddr,
++  typedef BOOL(__stdcall* tSFA)(IN HANDLE hProcess,
++                                  IN DWORD64 Address,
+                                   OUT PDWORD64 pdwDisplacement,
+-                                  OUT PIMAGEHLP_SYMBOL64 Symbol);
+-  tSGSFA pSGSFA;
++                                  OUT tSymbolInfo* Symbol);
++  tSFA symFromAddr;
+ 
+   // SymInitialize()
+-  typedef BOOL(__stdcall* tSI)(IN HANDLE hProcess, IN PSTR UserSearchPath, IN BOOL fInvadeProcess);
+-  tSI pSI;
++  typedef BOOL(__stdcall* tSI)(IN HANDLE hProcess, IN PTSTR UserSearchPath, IN BOOL fInvadeProcess);
++  tSI symInitialize;
+ 
+   // SymLoadModule64()
+   typedef DWORD64(__stdcall* tSLM)(IN HANDLE hProcess,
+                                    IN HANDLE hFile,
+-                                   IN PSTR ImageName,
+-                                   IN PSTR ModuleName,
++                                   IN PTSTR ImageName,
++                                   IN PTSTR ModuleName,
+                                    IN DWORD64 BaseOfDll,
+-                                   IN DWORD SizeOfDll);
+-  tSLM pSLM;
++                                   IN DWORD SizeOfDll,
++                                   IN PMODLOAD_DATA Data,
++                                   IN DWORD         Flags);
++  tSLM symLoadModuleEx;
+ 
+   // SymSetOptions()
+   typedef DWORD(__stdcall* tSSO)(IN DWORD SymOptions);
+-  tSSO pSSO;
++  tSSO symSetOptions;
+ 
+   // StackWalk64()
+   typedef BOOL(__stdcall* tSW)(DWORD                            MachineType,
+@@ -521,17 +416,17 @@ public:
+                                PFUNCTION_TABLE_ACCESS_ROUTINE64 FunctionTableAccessRoutine,
+                                PGET_MODULE_BASE_ROUTINE64       GetModuleBaseRoutine,
+                                PTRANSLATE_ADDRESS_ROUTINE64     TranslateAddress);
+-  tSW pSW;
++  tSW stackWalk64;
+ 
+   // UnDecorateSymbolName()
+-  typedef DWORD(__stdcall WINAPI* tUDSN)(PCSTR DecoratedName,
+-                                         PSTR  UnDecoratedName,
++  typedef DWORD(__stdcall WINAPI* tUDSN)(PCTSTR DecoratedName,
++                                         PTSTR  UnDecoratedName,
+                                          DWORD UndecoratedLength,
+                                          DWORD Flags);
+-  tUDSN pUDSN;
++  tUDSN unDecorateSymbolName;
+ 
+-  typedef BOOL(__stdcall WINAPI* tSGSP)(HANDLE hProcess, PSTR SearchPath, DWORD SearchPathLength);
+-  tSGSP pSGSP;
++  typedef BOOL(__stdcall WINAPI* tSGSP)(HANDLE hProcess, PTSTR SearchPath, DWORD SearchPathLength);
++  tSGSP symGetSearchPath;
+ 
+ private:
+ // **************************************** ToolHelp32 ************************
+@@ -548,8 +443,8 @@ private:
+     BYTE*   modBaseAddr;   // Base address of module in th32ProcessID's context
+     DWORD   modBaseSize;   // Size in bytes of module starting at modBaseAddr
+     HMODULE hModule;       // The hModule of this module in th32ProcessID's context
+-    char    szModule[MAX_MODULE_NAME32 + 1];
+-    char    szExePath[MAX_PATH];
++    TCHAR   szModule[MAX_MODULE_NAME32 + 1];
++    TCHAR   szExePath[MAX_PATH];
+   } MODULEENTRY32;
+   typedef MODULEENTRY32* PMODULEENTRY32;
+   typedef MODULEENTRY32* LPMODULEENTRY32;
+@@ -567,25 +462,31 @@ private:
+     // try both dlls...
+     const TCHAR* dllname[] = {_T("kernel32.dll"), _T("tlhelp32.dll")};
+     HINSTANCE    hToolhelp = NULL;
+-    tCT32S       pCT32S = NULL;
+-    tM32F        pM32F = NULL;
+-    tM32N        pM32N = NULL;
++    tCT32S       createToolhelp32Snapshot = NULL;
++    tM32F        module32First = NULL;
++    tM32N        module32Next = NULL;
+ 
+     HANDLE        hSnap;
+-    MODULEENTRY32 me;
+-    me.dwSize = sizeof(me);
++    MODULEENTRY32 moduleEntry32;
++    moduleEntry32.dwSize = sizeof(moduleEntry32);
+     BOOL   keepGoing;
+-    size_t i;
+ 
+-    for (i = 0; i < (sizeof(dllname) / sizeof(dllname[0])); i++)
++#ifdef _UNICODE
++    static const char strModule32First[] = "Module32FirstW";
++    static const char strModule32Next[] = "Module32NextW";
++ #else
++    static const char strModule32First[] = "Module32First";
++    static const char strModule32Next[] = "Module32Next";
++#endif
++    for (size_t i = 0; i < (sizeof(dllname) / sizeof(dllname[0])); i++)
+     {
+       hToolhelp = LoadLibrary(dllname[i]);
+       if (hToolhelp == NULL)
+         continue;
+-      pCT32S = (tCT32S)GetProcAddress(hToolhelp, "CreateToolhelp32Snapshot");
+-      pM32F = (tM32F)GetProcAddress(hToolhelp, "Module32First");
+-      pM32N = (tM32N)GetProcAddress(hToolhelp, "Module32Next");
+-      if ((pCT32S != NULL) && (pM32F != NULL) && (pM32N != NULL))
++      createToolhelp32Snapshot = (tCT32S)GetProcAddress(hToolhelp, "CreateToolhelp32Snapshot");
++      module32First = (tM32F)GetProcAddress(hToolhelp, strModule32First);  
++      module32Next = (tM32N)GetProcAddress(hToolhelp, strModule32Next); 
++      if ((createToolhelp32Snapshot != NULL) && (module32First != NULL) && (module32Next != NULL))
+         break; // found the functions!
+       FreeLibrary(hToolhelp);
+       hToolhelp = NULL;
+@@ -594,21 +495,21 @@ private:
+     if (hToolhelp == NULL)
+       return FALSE;
+ 
+-    hSnap = pCT32S(TH32CS_SNAPMODULE, pid);
++    hSnap = createToolhelp32Snapshot(TH32CS_SNAPMODULE, pid);
+     if (hSnap == (HANDLE)-1)
+     {
+       FreeLibrary(hToolhelp);
+       return FALSE;
+     }
+ 
+-    keepGoing = !!pM32F(hSnap, &me);
++    keepGoing = !!module32First(hSnap, &moduleEntry32);
+     int cnt = 0;
+     while (keepGoing)
+     {
+-      this->LoadModule(hProcess, me.szExePath, me.szModule, (DWORD64)me.modBaseAddr,
+-                       me.modBaseSize);
++      this->LoadModule(hProcess, moduleEntry32.szExePath, moduleEntry32.szModule, (DWORD64)moduleEntry32.modBaseAddr,
++                       moduleEntry32.modBaseSize);
+       cnt++;
+-      keepGoing = !!pM32N(hSnap, &me);
++      keepGoing = !!module32Next(hSnap, &moduleEntry32);
+     }
+     CloseHandle(hSnap);
+     FreeLibrary(hToolhelp);
+@@ -631,39 +532,41 @@ private:
+     typedef BOOL(__stdcall * tEPM)(HANDLE hProcess, HMODULE * lphModule, DWORD cb,
+                                    LPDWORD lpcbNeeded);
+     // GetModuleFileNameEx()
+-    typedef DWORD(__stdcall * tGMFNE)(HANDLE hProcess, HMODULE hModule, LPSTR lpFilename,
++    typedef DWORD(__stdcall * tGMFNE)(HANDLE hProcess, HMODULE hModule, LPTSTR lpFilename,
+                                       DWORD nSize);
+     // GetModuleBaseName()
+-    typedef DWORD(__stdcall * tGMBN)(HANDLE hProcess, HMODULE hModule, LPSTR lpFilename,
++    typedef DWORD(__stdcall * tGMBN)(HANDLE hProcess, HMODULE hModule, LPTSTR lpFilename,
+                                      DWORD nSize);
+     // GetModuleInformation()
+     typedef BOOL(__stdcall * tGMI)(HANDLE hProcess, HMODULE hModule, LPMODULEINFO pmi, DWORD nSize);
+ 
+-    HINSTANCE hPsapi;
+-    tEPM      pEPM;
+-    tGMFNE    pGMFNE;
+-    tGMBN     pGMBN;
+-    tGMI      pGMI;
+-
+-    DWORD i;
+-    //ModuleEntry e;
++      //ModuleEntry e;
+     DWORD        cbNeeded;
+     MODULEINFO   mi;
+     HMODULE*     hMods = 0;
+-    char*        tt = NULL;
+-    char*        tt2 = NULL;
++    TCHAR*        tt = NULL;
++    TCHAR*        tt2 = NULL;
+     const SIZE_T TTBUFLEN = 8096;
+     int          cnt = 0;
+ 
+-    hPsapi = LoadLibrary(_T("psapi.dll"));
++    HINSTANCE hPsapi = LoadLibrary(_T("psapi.dll"));
+     if (hPsapi == NULL)
+       return FALSE;
+ 
+-    pEPM = (tEPM)GetProcAddress(hPsapi, "EnumProcessModules");
+-    pGMFNE = (tGMFNE)GetProcAddress(hPsapi, "GetModuleFileNameExA");
+-    pGMBN = (tGMFNE)GetProcAddress(hPsapi, "GetModuleBaseNameA");
+-    pGMI = (tGMI)GetProcAddress(hPsapi, "GetModuleInformation");
+-    if ((pEPM == NULL) || (pGMFNE == NULL) || (pGMBN == NULL) || (pGMI == NULL))
++#ifdef _UNICODE
++    static const char strGetModuleFileName[] = "GetModuleFileNameExW";
++    static const char strGetModuleBaseName[] = "GetModuleBaseNameW";
++#else
++    static const char strGetModuleFileName[] = "GetModulefileNameExA";
++    static const char strGetModuleBaseName[] = "GetModuleBaseNameA";
++#endif
++
++    tEPM   enumProcessModules = (tEPM)GetProcAddress(hPsapi, "EnumProcessModules");
++    tGMFNE getModuleFileNameEx = (tGMFNE)GetProcAddress(hPsapi, strGetModuleFileName);
++    tGMBN  getModuleBaseName = (tGMFNE)GetProcAddress(hPsapi, strGetModuleBaseName);
++    tGMI   getModuleInformation = (tGMI)GetProcAddress(hPsapi, "GetModuleInformation");
++    if ((enumProcessModules == NULL) || (getModuleFileNameEx == NULL) ||
++        (getModuleBaseName == NULL) || (getModuleInformation == NULL))
+     {
+       // we couldn't find all functions
+       FreeLibrary(hPsapi);
+@@ -671,12 +574,12 @@ private:
+     }
+ 
+     hMods = (HMODULE*)malloc(sizeof(HMODULE) * (TTBUFLEN / sizeof(HMODULE)));
+-    tt = (char*)malloc(sizeof(char) * TTBUFLEN);
+-    tt2 = (char*)malloc(sizeof(char) * TTBUFLEN);
++    tt = (TCHAR*)malloc(sizeof(TCHAR) * TTBUFLEN);
++    tt2 = (TCHAR*)malloc(sizeof(TCHAR) * TTBUFLEN);
+     if ((hMods == NULL) || (tt == NULL) || (tt2 == NULL))
+       goto cleanup;
+ 
+-    if (!pEPM(hProcess, hMods, TTBUFLEN, &cbNeeded))
++    if (!enumProcessModules(hProcess, hMods, TTBUFLEN, &cbNeeded))
+     {
+       //_ftprintf(fLogFile, _T("%lu: EPM failed, GetLastError = %lu\n"), g_dwShowCount, gle );
+       goto cleanup;
+@@ -688,20 +591,20 @@ private:
+       goto cleanup;
+     }
+ 
+-    for (i = 0; i < cbNeeded / sizeof(hMods[0]); i++)
++    for (DWORD i = 0; i < cbNeeded / sizeof(hMods[0]); i++)
+     {
+       // base address, size
+-      pGMI(hProcess, hMods[i], &mi, sizeof(mi));
++      getModuleInformation(hProcess, hMods[i], &mi, sizeof(mi));
+       // image file name
+       tt[0] = 0;
+-      pGMFNE(hProcess, hMods[i], tt, TTBUFLEN);
++      getModuleFileNameEx(hProcess, hMods[i], tt, TTBUFLEN);
+       // module name
+       tt2[0] = 0;
+-      pGMBN(hProcess, hMods[i], tt2, TTBUFLEN);
++      getModuleBaseName(hProcess, hMods[i], tt2, TTBUFLEN);
+ 
+       DWORD dwRes = this->LoadModule(hProcess, tt, tt2, (DWORD64)mi.lpBaseOfDll, mi.SizeOfImage);
+       if (dwRes != ERROR_SUCCESS)
+-        this->m_parent->OnDbgHelpErr("LoadModule", dwRes, 0);
++        this->m_parent->OnDbgHelpErr(_T("LoadModule"), dwRes, 0);
+       cnt++;
+     }
+ 
+@@ -718,16 +621,16 @@ private:
+     return cnt != 0;
+   } // GetModuleListPSAPI
+ 
+-  DWORD LoadModule(HANDLE hProcess, LPCSTR img, LPCSTR mod, DWORD64 baseAddr, DWORD size)
++  DWORD LoadModule(HANDLE hProcess, LPCTSTR img, LPCTSTR mod, DWORD64 baseAddr, DWORD size)
+   {
+-    CHAR* szImg = _strdup(img);
+-    CHAR* szMod = _strdup(mod);
++    TCHAR* szImg = _tcsdup(img);
++    TCHAR* szMod = _tcsdup(mod);
+     DWORD result = ERROR_SUCCESS;
+     if ((szImg == NULL) || (szMod == NULL))
+       result = ERROR_NOT_ENOUGH_MEMORY;
+     else
+     {
+-      if (pSLM(hProcess, 0, szImg, szMod, baseAddr, size) == 0)
++      if (symLoadModuleEx(hProcess, 0, szImg, szMod, baseAddr, size, 0, 0) == 0)
+         result = GetLastError();
+     }
+     ULONGLONG fileVersion = 0;
+@@ -738,13 +641,13 @@ private:
+       {
+         VS_FIXEDFILEINFO* fInfo = NULL;
+         DWORD             dwHandle;
+-        DWORD             dwSize = GetFileVersionInfoSizeA(szImg, &dwHandle);
++        DWORD             dwSize = GetFileVersionInfoSize(szImg, &dwHandle);
+         if (dwSize > 0)
+         {
+           LPVOID vData = malloc(dwSize);
+           if (vData != NULL)
+           {
+-            if (GetFileVersionInfoA(szImg, dwHandle, dwSize, vData) != 0)
++            if (GetFileVersionInfo(szImg, dwHandle, dwSize, vData) != 0)
+             {
+               UINT  len;
+               TCHAR szSubBlock[] = _T("\\");
+@@ -763,41 +666,41 @@ private:
+ 
+       // Retrieve some additional-infos about the module
+       IMAGEHLP_MODULE64_V3 Module;
+-      const char*          szSymType = "-unknown-";
++      const TCHAR*          szSymType = _T("-unknown-");
+       if (this->GetModuleInfo(hProcess, baseAddr, &Module) != FALSE)
+       {
+         switch (Module.SymType)
+         {
+           case SymNone:
+-            szSymType = "-nosymbols-";
++            szSymType = _T("-nosymbols-");
+             break;
+           case SymCoff: // 1
+-            szSymType = "COFF";
++            szSymType = _T("COFF");
+             break;
+           case SymCv: // 2
+-            szSymType = "CV";
++            szSymType = _T("CV");
+             break;
+           case SymPdb: // 3
+-            szSymType = "PDB";
++            szSymType = _T("PDB");
+             break;
+           case SymExport: // 4
+-            szSymType = "-exported-";
++            szSymType = _T("-exported-");
+             break;
+           case SymDeferred: // 5
+-            szSymType = "-deferred-";
++            szSymType = _T("-deferred-");
+             break;
+           case SymSym: // 6
+-            szSymType = "SYM";
++            szSymType = _T("SYM");
+             break;
+           case 7: // SymDia:
+-            szSymType = "DIA";
++            szSymType = _T("DIA");
+             break;
+           case 8: //SymVirtual:
+-            szSymType = "Virtual";
++            szSymType = _T("Virtual");
+             break;
+         }
+       }
+-      LPCSTR pdbName = Module.LoadedImageName;
++      LPCTSTR pdbName = Module.LoadedImageName;
+       if (Module.LoadedPdbName[0] != 0)
+         pdbName = Module.LoadedPdbName;
+       this->m_parent->OnLoadModule(img, mod, baseAddr, size, result, szSymType, pdbName,
+@@ -823,7 +726,7 @@ public:
+   BOOL GetModuleInfo(HANDLE hProcess, DWORD64 baseAddr, IMAGEHLP_MODULE64_V3* pModuleInfo)
+   {
+     memset(pModuleInfo, 0, sizeof(IMAGEHLP_MODULE64_V3));
+-    if (this->pSGMI == NULL)
++    if (this->symGetModuleInfo64 == NULL)
+     {
+       SetLastError(ERROR_DLL_INIT_FAILED);
+       return FALSE;
+@@ -841,7 +744,7 @@ public:
+     static bool s_useV3Version = true;
+     if (s_useV3Version)
+     {
+-      if (this->pSGMI(hProcess, baseAddr, (IMAGEHLP_MODULE64_V3*)pData) != FALSE)
++      if (this->symGetModuleInfo64(hProcess, baseAddr, (IMAGEHLP_MODULE64_V3*)pData) != FALSE)
+       {
+         // only copy as much memory as is reserved...
+         memcpy(pModuleInfo, pData, sizeof(IMAGEHLP_MODULE64_V3));
+@@ -855,7 +758,7 @@ public:
+     // could not retrieve the bigger structure, try with the smaller one (as defined in VC7.1)...
+     pModuleInfo->SizeOfStruct = sizeof(IMAGEHLP_MODULE64_V2);
+     memcpy(pData, pModuleInfo, sizeof(IMAGEHLP_MODULE64_V2));
+-    if (this->pSGMI(hProcess, baseAddr, (IMAGEHLP_MODULE64_V3*)pData) != FALSE)
++    if (this->symGetModuleInfo64(hProcess, baseAddr, (IMAGEHLP_MODULE64_V3*)pData) != FALSE)
+     {
+       // only copy as much memory as is reserved...
+       memcpy(pModuleInfo, pData, sizeof(IMAGEHLP_MODULE64_V2));
+@@ -880,7 +783,7 @@ StackWalker::StackWalker(DWORD dwProcessId, HANDLE hProcess)
+   this->m_szSymPath = NULL;
+   this->m_MaxRecursionCount = 1000;
+ }
+-StackWalker::StackWalker(int options, LPCSTR szSymPath, DWORD dwProcessId, HANDLE hProcess)
++StackWalker::StackWalker(int options, LPCTSTR szSymPath, DWORD dwProcessId, HANDLE hProcess)
+ {
+   this->m_options = options;
+   this->m_modulesLoaded = FALSE;
+@@ -889,7 +792,7 @@ StackWalker::StackWalker(int options, LPCSTR szSymPath, DWORD dwProcessId, HANDL
+   this->m_dwProcessId = dwProcessId;
+   if (szSymPath != NULL)
+   {
+-    this->m_szSymPath = _strdup(szSymPath);
++    this->m_szSymPath = _tcsdup(szSymPath);
+     this->m_options |= SymBuildPath;
+   }
+   else
+@@ -918,11 +821,11 @@ BOOL StackWalker::LoadModules()
+     return TRUE;
+ 
+   // Build the sym-path:
+-  char* szSymPath = NULL;
++  TCHAR* szSymPath = NULL;
+   if ((this->m_options & SymBuildPath) != 0)
+   {
+     const size_t nSymPathLen = 4096;
+-    szSymPath = (char*)malloc(nSymPathLen);
++    szSymPath = (TCHAR*)malloc(nSymPathLen * sizeof(TCHAR));
+     if (szSymPath == NULL)
+     {
+       SetLastError(ERROR_NOT_ENOUGH_MEMORY);
+@@ -932,27 +835,27 @@ BOOL StackWalker::LoadModules()
+     // Now first add the (optional) provided sympath:
+     if (this->m_szSymPath != NULL)
+     {
+-      strcat_s(szSymPath, nSymPathLen, this->m_szSymPath);
+-      strcat_s(szSymPath, nSymPathLen, ";");
++      _tcscat_s(szSymPath, nSymPathLen, this->m_szSymPath);
++      _tcscat_s(szSymPath, nSymPathLen, _T(";"));
+     }
+ 
+-    strcat_s(szSymPath, nSymPathLen, ".;");
++    _tcscat_s(szSymPath, nSymPathLen, _T(".;"));
+ 
+     const size_t nTempLen = 1024;
+-    char         szTemp[nTempLen];
++    TCHAR         szTemp[nTempLen];
+     // Now add the current directory:
+-    if (GetCurrentDirectoryA(nTempLen, szTemp) > 0)
++    if (GetCurrentDirectory(nTempLen, szTemp) > 0)
+     {
+       szTemp[nTempLen - 1] = 0;
+-      strcat_s(szSymPath, nSymPathLen, szTemp);
+-      strcat_s(szSymPath, nSymPathLen, ";");
++      _tcscat_s(szSymPath, nSymPathLen, szTemp);
++      _tcscat_s(szSymPath, nSymPathLen, _T(";"));
+     }
+ 
+     // Now add the path for the main-module:
+-    if (GetModuleFileNameA(NULL, szTemp, nTempLen) > 0)
++    if (GetModuleFileName(NULL, szTemp, nTempLen) > 0)
+     {
+       szTemp[nTempLen - 1] = 0;
+-      for (char* p = (szTemp + strlen(szTemp) - 1); p >= szTemp; --p)
++      for (TCHAR* p = (szTemp + _tcslen(szTemp) - 1); p >= szTemp; --p)
+       {
+         // locate the rightmost path separator
+         if ((*p == '\\') || (*p == '/') || (*p == ':'))
+@@ -961,48 +864,48 @@ BOOL StackWalker::LoadModules()
+           break;
+         }
+       } // for (search for path separator...)
+-      if (strlen(szTemp) > 0)
++      if (_tcslen(szTemp) > 0)
+       {
+-        strcat_s(szSymPath, nSymPathLen, szTemp);
+-        strcat_s(szSymPath, nSymPathLen, ";");
++        _tcscat_s(szSymPath, nSymPathLen, szTemp);
++        _tcscat_s(szSymPath, nSymPathLen, _T(";"));
+       }
+     }
+-    if (GetEnvironmentVariableA("_NT_SYMBOL_PATH", szTemp, nTempLen) > 0)
++    if (GetEnvironmentVariable(_T("_NT_SYMBOL_PATH"), szTemp, nTempLen) > 0)
+     {
+       szTemp[nTempLen - 1] = 0;
+-      strcat_s(szSymPath, nSymPathLen, szTemp);
+-      strcat_s(szSymPath, nSymPathLen, ";");
++      _tcscat_s(szSymPath, nSymPathLen, szTemp);
++      _tcscat_s(szSymPath, nSymPathLen, _T(";"));
+     }
+-    if (GetEnvironmentVariableA("_NT_ALTERNATE_SYMBOL_PATH", szTemp, nTempLen) > 0)
++    if (GetEnvironmentVariable(_T("_NT_ALTERNATE_SYMBOL_PATH"), szTemp, nTempLen) > 0)
+     {
+       szTemp[nTempLen - 1] = 0;
+-      strcat_s(szSymPath, nSymPathLen, szTemp);
+-      strcat_s(szSymPath, nSymPathLen, ";");
++      _tcscat_s(szSymPath, nSymPathLen, szTemp);
++      _tcscat_s(szSymPath, nSymPathLen, _T(";"));
+     }
+-    if (GetEnvironmentVariableA("SYSTEMROOT", szTemp, nTempLen) > 0)
++    if (GetEnvironmentVariable(_T("SYSTEMROOT"), szTemp, nTempLen) > 0)
+     {
+       szTemp[nTempLen - 1] = 0;
+-      strcat_s(szSymPath, nSymPathLen, szTemp);
+-      strcat_s(szSymPath, nSymPathLen, ";");
++      _tcscat_s(szSymPath, nSymPathLen, szTemp);
++      _tcscat_s(szSymPath, nSymPathLen, _T(";"));
+       // also add the "system32"-directory:
+-      strcat_s(szTemp, nTempLen, "\\system32");
+-      strcat_s(szSymPath, nSymPathLen, szTemp);
+-      strcat_s(szSymPath, nSymPathLen, ";");
++      _tcscat_s(szTemp, nTempLen, _T("\\system32"));
++      _tcscat_s(szSymPath, nSymPathLen, szTemp);
++      _tcscat_s(szSymPath, nSymPathLen, _T(";"));
+     }
+ 
+     if ((this->m_options & SymUseSymSrv) != 0)
+     {
+-      if (GetEnvironmentVariableA("SYSTEMDRIVE", szTemp, nTempLen) > 0)
++      if (GetEnvironmentVariable(_T("SYSTEMDRIVE"), szTemp, nTempLen) > 0)
+       {
+         szTemp[nTempLen - 1] = 0;
+-        strcat_s(szSymPath, nSymPathLen, "SRV*");
+-        strcat_s(szSymPath, nSymPathLen, szTemp);
+-        strcat_s(szSymPath, nSymPathLen, "\\websymbols");
+-        strcat_s(szSymPath, nSymPathLen, "*http://msdl.microsoft.com/download/symbols;");
++        _tcscat_s(szSymPath, nSymPathLen, _T("SRV*"));
++        _tcscat_s(szSymPath, nSymPathLen, szTemp);
++        _tcscat_s(szSymPath, nSymPathLen, _T("\\websymbols"));
++        _tcscat_s(szSymPath, nSymPathLen, _T("*http://msdl.microsoft.com/download/symbols;"));
+       }
+       else
+-        strcat_s(szSymPath, nSymPathLen,
+-                 "SRV*c:\\websymbols*http://msdl.microsoft.com/download/symbols;");
++        _tcscat_s(szSymPath, nSymPathLen,
++                 _T("SRV*c:\\websymbols*http://msdl.microsoft.com/download/symbols;"));
+     }
+   } // if SymBuildPath
+ 
+@@ -1013,7 +916,7 @@ BOOL StackWalker::LoadModules()
+   szSymPath = NULL;
+   if (bRet == FALSE)
+   {
+-    this->OnDbgHelpErr("Error while initializing dbghelp.dll", 0, 0);
++    this->OnDbgHelpErr(_T("Error while initializing dbghelp.dll"), 0, 0);
+     SetLastError(ERROR_DLL_INIT_FAILED);
+     return FALSE;
+   }
+@@ -1038,9 +941,10 @@ BOOL StackWalker::ShowCallstack(HANDLE                    hThread,
+ {
+   CONTEXT                                   c;
+   CallstackEntry                            csEntry;
+-  IMAGEHLP_SYMBOL64*                        pSym = NULL;
++
++  tSymbolInfo* pSym = NULL;
+   StackWalkerInternal::IMAGEHLP_MODULE64_V3 Module;
+-  IMAGEHLP_LINE64                           Line;
++  tImageHelperLine                           Line;
+   int                                       frameNum;
+   bool                                      bLastEntryCalled = true;
+   int                                       curRecursionCount = 0;
+@@ -1125,12 +1029,12 @@ BOOL StackWalker::ShowCallstack(HANDLE                    hThread,
+ #error "Platform not supported!"
+ #endif
+ 
+-  pSym = (IMAGEHLP_SYMBOL64*)malloc(sizeof(IMAGEHLP_SYMBOL64) + STACKWALK_MAX_NAMELEN);
++  pSym = (tSymbolInfo*)malloc(sizeof(tSymbolInfo) + STACKWALK_MAX_NAMELEN*sizeof(TCHAR));
+   if (!pSym)
+     goto cleanup; // not enough memory...
+-  memset(pSym, 0, sizeof(IMAGEHLP_SYMBOL64) + STACKWALK_MAX_NAMELEN);
+-  pSym->SizeOfStruct = sizeof(IMAGEHLP_SYMBOL64);
+-  pSym->MaxNameLength = STACKWALK_MAX_NAMELEN;
++  memset(pSym, 0, sizeof(tSymbolInfo) + STACKWALK_MAX_NAMELEN*sizeof(TCHAR));
++  pSym->SizeOfStruct = sizeof(tSymbolInfo);
++  pSym->MaxNameLen = STACKWALK_MAX_NAMELEN;
+ 
+   memset(&Line, 0, sizeof(Line));
+   Line.SizeOfStruct = sizeof(Line);
+@@ -1145,11 +1049,11 @@ BOOL StackWalker::ShowCallstack(HANDLE                    hThread,
+     // assume that either you are done, or that the stack is so hosed that the next
+     // deeper frame could not be found.
+     // CONTEXT need not to be supplied if imageTyp is IMAGE_FILE_MACHINE_I386!
+-    if (!this->m_sw->pSW(imageType, this->m_hProcess, hThread, &s, &c, myReadProcMem,
+-                         this->m_sw->pSFTA, this->m_sw->pSGMB, NULL))
++    if (!this->m_sw->stackWalk64(imageType, this->m_hProcess, hThread, &s, &c, myReadProcMem,
++                         this->m_sw->symFunctionTableAccess64, this->m_sw->symGetModuleBase64, NULL))
+     {
+       // INFO: "StackWalk64" does not set "GetLastError"...
+-      this->OnDbgHelpErr("StackWalk64", 0, s.AddrPC.Offset);
++      this->OnDbgHelpErr(_T("StackWalk64"), 0, s.AddrPC.Offset);
+       break;
+     }
+ 
+@@ -1167,7 +1071,7 @@ BOOL StackWalker::ShowCallstack(HANDLE                    hThread,
+     {
+       if ((this->m_MaxRecursionCount > 0) && (curRecursionCount > m_MaxRecursionCount))
+       {
+-        this->OnDbgHelpErr("StackWalk64-Endless-Callstack!", 0, s.AddrPC.Offset);
++        this->OnDbgHelpErr(_T("StackWalk64-Endless-Callstack!"), 0, s.AddrPC.Offset);
+         break;
+       }
+       curRecursionCount++;
+@@ -1178,23 +1082,23 @@ BOOL StackWalker::ShowCallstack(HANDLE                    hThread,
+     {
+       // we seem to have a valid PC
+       // show procedure info (SymGetSymFromAddr64())
+-      if (this->m_sw->pSGSFA(this->m_hProcess, s.AddrPC.Offset, &(csEntry.offsetFromSmybol),
++      if (this->m_sw->symFromAddr(this->m_hProcess, s.AddrPC.Offset, &(csEntry.offsetFromSmybol),
+                              pSym) != FALSE)
+       {
+         MyStrCpy(csEntry.name, STACKWALK_MAX_NAMELEN, pSym->Name);
+         // UnDecorateSymbolName()
+-        this->m_sw->pUDSN(pSym->Name, csEntry.undName, STACKWALK_MAX_NAMELEN, UNDNAME_NAME_ONLY);
+-        this->m_sw->pUDSN(pSym->Name, csEntry.undFullName, STACKWALK_MAX_NAMELEN, UNDNAME_COMPLETE);
++        DWORD res = this->m_sw->unDecorateSymbolName(pSym->Name, csEntry.undName, STACKWALK_MAX_NAMELEN, UNDNAME_NAME_ONLY);
++        res = this->m_sw->unDecorateSymbolName(pSym->Name, csEntry.undFullName, STACKWALK_MAX_NAMELEN, UNDNAME_COMPLETE);
+       }
+       else
+       {
+-        this->OnDbgHelpErr("SymGetSymFromAddr64", GetLastError(), s.AddrPC.Offset);
++        this->OnDbgHelpErr(_T("SymGetSymFromAddr64"), GetLastError(), s.AddrPC.Offset);
+       }
+ 
+       // show line number info, NT5.0-method (SymGetLineFromAddr64())
+-      if (this->m_sw->pSGLFA != NULL)
++      if (this->m_sw->symGetLineFromAddr64 != NULL)
+       { // yes, we have SymGetLineFromAddr64()
+-        if (this->m_sw->pSGLFA(this->m_hProcess, s.AddrPC.Offset, &(csEntry.offsetFromLine),
++        if (this->m_sw->symGetLineFromAddr64(this->m_hProcess, s.AddrPC.Offset, &(csEntry.offsetFromLine),
+                                &Line) != FALSE)
+         {
+           csEntry.lineNumber = Line.LineNumber;
+@@ -1202,7 +1106,7 @@ BOOL StackWalker::ShowCallstack(HANDLE                    hThread,
+         }
+         else
+         {
+-          this->OnDbgHelpErr("SymGetLineFromAddr64", GetLastError(), s.AddrPC.Offset);
++          this->OnDbgHelpErr(_T("SymGetLineFromAddr64"), GetLastError(), s.AddrPC.Offset);
+         }
+       } // yes, we have SymGetLineFromAddr64()
+ 
+@@ -1252,7 +1156,7 @@ BOOL StackWalker::ShowCallstack(HANDLE                    hThread,
+       } // got module info OK
+       else
+       {
+-        this->OnDbgHelpErr("SymGetModuleInfo64", GetLastError(), s.AddrPC.Offset);
++        this->OnDbgHelpErr(_T("SymGetModuleInfo64"), GetLastError(), s.AddrPC.Offset);
+       }
+     } // we seem to have a valid PC
+ 
+@@ -1298,20 +1202,20 @@ BOOL StackWalker::ShowObject(LPVOID pObject)
+   }
+ 
+   // SymGetSymFromAddr64() is required
+-  if (this->m_sw->pSGSFA == NULL)
++  if (this->m_sw->symFromAddr == NULL)
+     return FALSE;
+ 
+   // Show object info (SymGetSymFromAddr64())
+   DWORD64            dwAddress = DWORD64(pObject);
+   DWORD64            dwDisplacement = 0;
+-  IMAGEHLP_SYMBOL64* pSym =
+-      (IMAGEHLP_SYMBOL64*)malloc(sizeof(IMAGEHLP_SYMBOL64) + STACKWALK_MAX_NAMELEN);
+-  memset(pSym, 0, sizeof(IMAGEHLP_SYMBOL64) + STACKWALK_MAX_NAMELEN);
+-  pSym->SizeOfStruct = sizeof(IMAGEHLP_SYMBOL64);
+-  pSym->MaxNameLength = STACKWALK_MAX_NAMELEN;
+-  if (this->m_sw->pSGSFA(this->m_hProcess, dwAddress, &dwDisplacement, pSym) == FALSE)
++  tSymbolInfo* pSym =
++      (tSymbolInfo*)malloc(sizeof(tSymbolInfo) + STACKWALK_MAX_NAMELEN*sizeof(TCHAR));
++  memset(pSym, 0, sizeof(tSymbolInfo) + STACKWALK_MAX_NAMELEN*sizeof(TCHAR));
++  pSym->SizeOfStruct = sizeof(tSymbolInfo);
++  pSym->MaxNameLen = STACKWALK_MAX_NAMELEN;
++  if (this->m_sw->symFromAddr(this->m_hProcess, dwAddress, &dwDisplacement, pSym) == FALSE)
+   {
+-    this->OnDbgHelpErr("SymGetSymFromAddr64", GetLastError(), dwAddress);
++    this->OnDbgHelpErr(_T("SymGetSymFromAddr64"), GetLastError(), dwAddress);
+     return FALSE;
+   }
+   // Object name output
+@@ -1342,22 +1246,22 @@ BOOL __stdcall StackWalker::myReadProcMem(HANDLE  hProcess,
+   }
+ }
+ 
+-void StackWalker::OnLoadModule(LPCSTR    img,
+-                               LPCSTR    mod,
++void StackWalker::OnLoadModule(LPCTSTR    img,
++                               LPCTSTR    mod,
+                                DWORD64   baseAddr,
+                                DWORD     size,
+                                DWORD     result,
+-                               LPCSTR    symType,
+-                               LPCSTR    pdbName,
++                               LPCTSTR    symType,
++                               LPCTSTR    pdbName,
+                                ULONGLONG fileVersion)
+ {
+-  CHAR   buffer[STACKWALK_MAX_NAMELEN];
++  TCHAR   buffer[STACKWALK_MAX_NAMELEN];
+   size_t maxLen = STACKWALK_MAX_NAMELEN;
+ #if _MSC_VER >= 1400
+   maxLen = _TRUNCATE;
+ #endif
+   if (fileVersion == 0)
+-    _snprintf_s(buffer, maxLen, "%s:%s (%p), size: %d (result: %d), SymType: '%s', PDB: '%s'\n",
++    _sntprintf_s(buffer, maxLen, _T("%s:%s (%p), size: %d (result: %d), SymType: '%s', PDB: '%s'\n"),
+                 img, mod, (LPVOID)baseAddr, size, result, symType, pdbName);
+   else
+   {
+@@ -1365,9 +1269,9 @@ void StackWalker::OnLoadModule(LPCSTR    img,
+     DWORD v3 = (DWORD)((fileVersion >> 16) & 0xFFFF);
+     DWORD v2 = (DWORD)((fileVersion >> 32) & 0xFFFF);
+     DWORD v1 = (DWORD)((fileVersion >> 48) & 0xFFFF);
+-    _snprintf_s(
++    _sntprintf_s(
+         buffer, maxLen,
+-        "%s:%s (%p), size: %d (result: %d), SymType: '%s', PDB: '%s', fileVersion: %d.%d.%d.%d\n",
++        _T("%s:%s (%p), size: %d (result: %d), SymType: '%s', PDB: '%s', fileVersion: %d.%d.%d.%d\n"),
+         img, mod, (LPVOID)baseAddr, size, result, symType, pdbName, v1, v2, v3, v4);
+   }
+   buffer[STACKWALK_MAX_NAMELEN - 1] = 0; // be sure it is NULL terminated
+@@ -1376,7 +1280,7 @@ void StackWalker::OnLoadModule(LPCSTR    img,
+ 
+ void StackWalker::OnCallstackEntry(CallstackEntryType eType, CallstackEntry& entry)
+ {
+-  CHAR   buffer[STACKWALK_MAX_NAMELEN];
++  TCHAR   buffer[STACKWALK_MAX_NAMELEN];
+   size_t maxLen = STACKWALK_MAX_NAMELEN;
+ #if _MSC_VER >= 1400
+   maxLen = _TRUNCATE;
+@@ -1384,48 +1288,48 @@ void StackWalker::OnCallstackEntry(CallstackEntryType eType, CallstackEntry& ent
+   if ((eType != lastEntry) && (entry.offset != 0))
+   {
+     if (entry.name[0] == 0)
+-      MyStrCpy(entry.name, STACKWALK_MAX_NAMELEN, "(function-name not available)");
++      MyStrCpy(entry.name, STACKWALK_MAX_NAMELEN, _T("(function-name not available)"));
+     if (entry.undName[0] != 0)
+       MyStrCpy(entry.name, STACKWALK_MAX_NAMELEN, entry.undName);
+     if (entry.undFullName[0] != 0)
+       MyStrCpy(entry.name, STACKWALK_MAX_NAMELEN, entry.undFullName);
+     if (entry.lineFileName[0] == 0)
+     {
+-      MyStrCpy(entry.lineFileName, STACKWALK_MAX_NAMELEN, "(filename not available)");
++      MyStrCpy(entry.lineFileName, STACKWALK_MAX_NAMELEN, _T("(filename not available)"));
+       if (entry.moduleName[0] == 0)
+-        MyStrCpy(entry.moduleName, STACKWALK_MAX_NAMELEN, "(module-name not available)");
+-      _snprintf_s(buffer, maxLen, "%p (%s): %s: %s\n", (LPVOID)entry.offset, entry.moduleName,
++        MyStrCpy(entry.moduleName, STACKWALK_MAX_NAMELEN, _T("(module-name not available)"));
++      _sntprintf_s(buffer, maxLen, _T("%p (%s): %s: %s\n"), (LPVOID)entry.offset, entry.moduleName,
+                   entry.lineFileName, entry.name);
+     }
+     else
+-      _snprintf_s(buffer, maxLen, "%s (%d): %s\n", entry.lineFileName, entry.lineNumber,
++      _sntprintf_s(buffer, maxLen, _T("%s (%d): %s\n"), entry.lineFileName, entry.lineNumber,
+                   entry.name);
+     buffer[STACKWALK_MAX_NAMELEN - 1] = 0;
+     OnOutput(buffer);
+   }
+ }
+ 
+-void StackWalker::OnDbgHelpErr(LPCSTR szFuncName, DWORD gle, DWORD64 addr)
++void StackWalker::OnDbgHelpErr(LPCTSTR szFuncName, DWORD gle, DWORD64 addr)
+ {
+-  CHAR   buffer[STACKWALK_MAX_NAMELEN];
++  TCHAR   buffer[STACKWALK_MAX_NAMELEN];
+   size_t maxLen = STACKWALK_MAX_NAMELEN;
+ #if _MSC_VER >= 1400
+   maxLen = _TRUNCATE;
+ #endif
+-  _snprintf_s(buffer, maxLen, "ERROR: %s, GetLastError: %d (Address: %p)\n", szFuncName, gle,
++  _sntprintf_s(buffer, maxLen, _T("ERROR: %s, GetLastError: %d (Address: %p)\n"), szFuncName, gle,
+               (LPVOID)addr);
+   buffer[STACKWALK_MAX_NAMELEN - 1] = 0;
+   OnOutput(buffer);
+ }
+ 
+-void StackWalker::OnSymInit(LPCSTR szSearchPath, DWORD symOptions, LPCSTR szUserName)
++void StackWalker::OnSymInit(LPCTSTR szSearchPath, DWORD symOptions, LPCTSTR szUserName)
+ {
+-  CHAR   buffer[STACKWALK_MAX_NAMELEN];
++  TCHAR   buffer[STACKWALK_MAX_NAMELEN];
+   size_t maxLen = STACKWALK_MAX_NAMELEN;
+ #if _MSC_VER >= 1400
+   maxLen = _TRUNCATE;
+ #endif
+-  _snprintf_s(buffer, maxLen, "SymInit: Symbol-SearchPath: '%s', symOptions: %d, UserName: '%s'\n",
++  _sntprintf_s(buffer, maxLen, _T("SymInit: Symbol-SearchPath: '%s', symOptions: %d, UserName: '%s'\n"),
+               szSearchPath, symOptions, szUserName);
+   buffer[STACKWALK_MAX_NAMELEN - 1] = 0;
+   OnOutput(buffer);
+@@ -1442,16 +1346,16 @@ void StackWalker::OnSymInit(LPCSTR szSearchPath, DWORD symOptions, LPCSTR szUser
+     OnOutput(buffer);
+   }
+ #else
+-  OSVERSIONINFOEXA ver;
+-  ZeroMemory(&ver, sizeof(OSVERSIONINFOEXA));
++  OSVERSIONINFOEX ver;
++  ZeroMemory(&ver, sizeof(OSVERSIONINFOEX));
+   ver.dwOSVersionInfoSize = sizeof(ver);
+ #if _MSC_VER >= 1900
+ #pragma warning(push)
+ #pragma warning(disable : 4996)
+ #endif
+-  if (GetVersionExA((OSVERSIONINFOA*)&ver) != FALSE)
++  if (GetVersionEx((OSVERSIONINFO*)&ver) != FALSE)
+   {
+-    _snprintf_s(buffer, maxLen, "OS-Version: %d.%d.%d (%s) 0x%x-0x%x\n", ver.dwMajorVersion,
++    _sntprintf_s(buffer, maxLen, _T("OS-Version: %d.%d.%d (%s) 0x%x-0x%x\n"), ver.dwMajorVersion,
+                 ver.dwMinorVersion, ver.dwBuildNumber, ver.szCSDVersion, ver.wSuiteMask,
+                 ver.wProductType);
+     buffer[STACKWALK_MAX_NAMELEN - 1] = 0;
+@@ -1463,7 +1367,7 @@ void StackWalker::OnSymInit(LPCSTR szSearchPath, DWORD symOptions, LPCSTR szUser
+ #endif
+ }
+ 
+-void StackWalker::OnOutput(LPCSTR buffer)
++void StackWalker::OnOutput(LPCTSTR buffer)
+ {
+-  OutputDebugStringA(buffer);
++  OutputDebugString(buffer);
+ }
+diff --git a/Main/StackWalker/StackWalker.h b/Main/StackWalker/StackWalker.h
+index 0a004d9..03efcec 100644
+--- a/Main/StackWalker/StackWalker.h
++++ b/Main/StackWalker/StackWalker.h
+@@ -47,16 +47,6 @@
+ #pragma warning(disable : 4091)
+ #endif
+ 
+-// special defines for VC5/6 (if no actual PSDK is installed):
+-#if _MSC_VER < 1300
+-typedef unsigned __int64 DWORD64, *PDWORD64;
+-#if defined(_WIN64)
+-typedef unsigned __int64 SIZE_T, *PSIZE_T;
+-#else
+-typedef unsigned long SIZE_T, *PSIZE_T;
+-#endif
+-#endif // _MSC_VER < 1300
+-
+ class StackWalkerInternal; // forward
+ class StackWalker
+ {
+@@ -96,7 +86,7 @@ public:
+   } StackWalkOptions;
+ 
+   StackWalker(int    options = OptionsAll, // 'int' is by design, to combine the enum-flags
+-              LPCSTR szSymPath = NULL,
++              LPCTSTR szSymPath = NULL,
+               DWORD  dwProcessId = GetCurrentProcessId(),
+               HANDLE hProcess = GetCurrentProcess());
+   StackWalker(DWORD dwProcessId, HANDLE hProcess);
+@@ -137,18 +127,18 @@ protected:
+   typedef struct CallstackEntry
+   {
+     DWORD64 offset; // if 0, we have no valid entry
+-    CHAR    name[STACKWALK_MAX_NAMELEN];
+-    CHAR    undName[STACKWALK_MAX_NAMELEN];
+-    CHAR    undFullName[STACKWALK_MAX_NAMELEN];
++    TCHAR    name[STACKWALK_MAX_NAMELEN];
++    TCHAR    undName[STACKWALK_MAX_NAMELEN];
++    TCHAR    undFullName[STACKWALK_MAX_NAMELEN];
+     DWORD64 offsetFromSmybol;
+     DWORD   offsetFromLine;
+     DWORD   lineNumber;
+-    CHAR    lineFileName[STACKWALK_MAX_NAMELEN];
++    TCHAR    lineFileName[STACKWALK_MAX_NAMELEN];
+     DWORD   symType;
+     LPCSTR  symTypeString;
+-    CHAR    moduleName[STACKWALK_MAX_NAMELEN];
++    TCHAR    moduleName[STACKWALK_MAX_NAMELEN];
+     DWORD64 baseOfImage;
+-    CHAR    loadedImageName[STACKWALK_MAX_NAMELEN];
++    TCHAR    loadedImageName[STACKWALK_MAX_NAMELEN];
+   } CallstackEntry;
+ 
+   typedef enum CallstackEntryType
+@@ -158,24 +148,24 @@ protected:
+     lastEntry
+   } CallstackEntryType;
+ 
+-  virtual void OnSymInit(LPCSTR szSearchPath, DWORD symOptions, LPCSTR szUserName);
+-  virtual void OnLoadModule(LPCSTR    img,
+-                            LPCSTR    mod,
++  virtual void OnSymInit(LPCTSTR szSearchPath, DWORD symOptions, LPCTSTR szUserName);
++  virtual void OnLoadModule(LPCTSTR    img,
++                            LPCTSTR    mod,
+                             DWORD64   baseAddr,
+                             DWORD     size,
+                             DWORD     result,
+-                            LPCSTR    symType,
+-                            LPCSTR    pdbName,
++                            LPCTSTR    symType,
++                            LPCTSTR    pdbName,
+                             ULONGLONG fileVersion);
+   virtual void OnCallstackEntry(CallstackEntryType eType, CallstackEntry& entry);
+-  virtual void OnDbgHelpErr(LPCSTR szFuncName, DWORD gle, DWORD64 addr);
+-  virtual void OnOutput(LPCSTR szText);
++  virtual void OnDbgHelpErr(LPCTSTR szFuncName, DWORD gle, DWORD64 addr);
++  virtual void OnOutput(LPCTSTR szText);
+ 
+   StackWalkerInternal* m_sw;
+   HANDLE               m_hProcess;
+   DWORD                m_dwProcessId;
+   BOOL                 m_modulesLoaded;
+-  LPSTR                m_szSymPath;
++  LPTSTR               m_szSymPath;
+ 
+   int m_options;
+   int m_MaxRecursionCount;
+diff --git a/Main/StackWalker/StackWalker_VC2017.sln b/Main/StackWalker/StackWalker_VC2017.sln
+index 790d550..2209e23 100644
+--- a/Main/StackWalker/StackWalker_VC2017.sln
++++ b/Main/StackWalker/StackWalker_VC2017.sln
+@@ -16,18 +16,18 @@ Global
+ 		Release_VC2017-UNICODE|x64 = Release_VC2017-UNICODE|x64
+ 	EndGlobalSection
+ 	GlobalSection(ProjectConfigurationPlatforms) = postSolution
+-		{89B2BD42-B130-4811-9043-71A8EBC40DE5}.Debug_VC2017|Win32.ActiveCfg = Debug_VC2017-UNICODE|Win32
+-		{89B2BD42-B130-4811-9043-71A8EBC40DE5}.Debug_VC2017|Win32.Build.0 = Debug_VC2017-UNICODE|Win32
+-		{89B2BD42-B130-4811-9043-71A8EBC40DE5}.Debug_VC2017|x64.ActiveCfg = Debug_VC2017-UNICODE|x64
+-		{89B2BD42-B130-4811-9043-71A8EBC40DE5}.Debug_VC2017|x64.Build.0 = Debug_VC2017-UNICODE|x64
++		{89B2BD42-B130-4811-9043-71A8EBC40DE5}.Debug_VC2017|Win32.ActiveCfg = Debug_VC2017|Win32
++		{89B2BD42-B130-4811-9043-71A8EBC40DE5}.Debug_VC2017|Win32.Build.0 = Debug_VC2017|Win32
++		{89B2BD42-B130-4811-9043-71A8EBC40DE5}.Debug_VC2017|x64.ActiveCfg = Debug_VC2017|x64
++		{89B2BD42-B130-4811-9043-71A8EBC40DE5}.Debug_VC2017|x64.Build.0 = Debug_VC2017|x64
+ 		{89B2BD42-B130-4811-9043-71A8EBC40DE5}.Debug_VC2017-UNICODE|Win32.ActiveCfg = Debug_VC2017-UNICODE|Win32
+ 		{89B2BD42-B130-4811-9043-71A8EBC40DE5}.Debug_VC2017-UNICODE|Win32.Build.0 = Debug_VC2017-UNICODE|Win32
+ 		{89B2BD42-B130-4811-9043-71A8EBC40DE5}.Debug_VC2017-UNICODE|x64.ActiveCfg = Debug_VC2017-UNICODE|x64
+ 		{89B2BD42-B130-4811-9043-71A8EBC40DE5}.Debug_VC2017-UNICODE|x64.Build.0 = Debug_VC2017-UNICODE|x64
+-		{89B2BD42-B130-4811-9043-71A8EBC40DE5}.Release_VC2017|Win32.ActiveCfg = Release_VC2017-UNICODE|Win32
+-		{89B2BD42-B130-4811-9043-71A8EBC40DE5}.Release_VC2017|Win32.Build.0 = Release_VC2017-UNICODE|Win32
+-		{89B2BD42-B130-4811-9043-71A8EBC40DE5}.Release_VC2017|x64.ActiveCfg = Release_VC2017-UNICODE|x64
+-		{89B2BD42-B130-4811-9043-71A8EBC40DE5}.Release_VC2017|x64.Build.0 = Release_VC2017-UNICODE|x64
++		{89B2BD42-B130-4811-9043-71A8EBC40DE5}.Release_VC2017|Win32.ActiveCfg = Release_VC2017|Win32
++		{89B2BD42-B130-4811-9043-71A8EBC40DE5}.Release_VC2017|Win32.Build.0 = Release_VC2017|Win32
++		{89B2BD42-B130-4811-9043-71A8EBC40DE5}.Release_VC2017|x64.ActiveCfg = Release_VC2017|x64
++		{89B2BD42-B130-4811-9043-71A8EBC40DE5}.Release_VC2017|x64.Build.0 = Release_VC2017|x64
+ 		{89B2BD42-B130-4811-9043-71A8EBC40DE5}.Release_VC2017-UNICODE|Win32.ActiveCfg = Release_VC2017-UNICODE|Win32
+ 		{89B2BD42-B130-4811-9043-71A8EBC40DE5}.Release_VC2017-UNICODE|Win32.Build.0 = Release_VC2017-UNICODE|Win32
+ 		{89B2BD42-B130-4811-9043-71A8EBC40DE5}.Release_VC2017-UNICODE|x64.ActiveCfg = Release_VC2017-UNICODE|x64
+diff --git a/Main/StackWalker/main.cpp b/Main/StackWalker/main.cpp
+index 220c97b..496021e 100644
+--- a/Main/StackWalker/main.cpp
++++ b/Main/StackWalker/main.cpp
+@@ -33,7 +33,7 @@ void (*pGlobalFuncPtr)() = 0;
+ class StackWalkerToConsole : public StackWalker
+ {
+ protected:
+-  virtual void OnOutput(LPCSTR szText) { printf("%s", szText); }
++  virtual void OnOutput(LPCTSTR szText) { _tprintf(_T("%s"), szText); }
+ };
+ 
+ void Func5()
diff --git a/third_party/allwpilib/upstream_utils/stack_walker_patches/0002-Remove-_M_IX86-checks.patch b/third_party/allwpilib/upstream_utils/stack_walker_patches/0002-Remove-_M_IX86-checks.patch
new file mode 100644
index 0000000..14d7bae
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/stack_walker_patches/0002-Remove-_M_IX86-checks.patch
@@ -0,0 +1,79 @@
+From 238eda525de70b57bade634447c967f4f92bc96d Mon Sep 17 00:00:00 2001
+From: PJ Reiniger <pj.reiniger@gmail.com>
+Date: Mon, 23 May 2022 00:06:45 -0400
+Subject: [PATCH 2/3] Remove _M_IX86 checks
+
+---
+ Main/StackWalker/StackWalker.h | 52 ----------------------------------
+ 1 file changed, 52 deletions(-)
+
+diff --git a/Main/StackWalker/StackWalker.h b/Main/StackWalker/StackWalker.h
+index 03efcec..89be951 100644
+--- a/Main/StackWalker/StackWalker.h
++++ b/Main/StackWalker/StackWalker.h
+@@ -179,57 +179,6 @@ protected:
+   friend StackWalkerInternal;
+ }; // class StackWalker
+ 
+-// The "ugly" assembler-implementation is needed for systems before XP
+-// If you have a new PSDK and you only compile for XP and later, then you can use
+-// the "RtlCaptureContext"
+-// Currently there is no define which determines the PSDK-Version...
+-// So we just use the compiler-version (and assumes that the PSDK is
+-// the one which was installed by the VS-IDE)
+-
+-// INFO: If you want, you can use the RtlCaptureContext if you only target XP and later...
+-//       But I currently use it in x64/IA64 environments...
+-//#if defined(_M_IX86) && (_WIN32_WINNT <= 0x0500) && (_MSC_VER < 1400)
+-
+-#if defined(_M_IX86)
+-#ifdef CURRENT_THREAD_VIA_EXCEPTION
+-// TODO: The following is not a "good" implementation,
+-// because the callstack is only valid in the "__except" block...
+-#define GET_CURRENT_CONTEXT_STACKWALKER_CODEPLEX(c, contextFlags)               \
+-  do                                                                            \
+-  {                                                                             \
+-    memset(&c, 0, sizeof(CONTEXT));                                             \
+-    EXCEPTION_POINTERS* pExp = NULL;                                            \
+-    __try                                                                       \
+-    {                                                                           \
+-      throw 0;                                                                  \
+-    }                                                                           \
+-    __except (((pExp = GetExceptionInformation()) ? EXCEPTION_EXECUTE_HANDLER   \
+-                                                  : EXCEPTION_EXECUTE_HANDLER)) \
+-    {                                                                           \
+-    }                                                                           \
+-    if (pExp != NULL)                                                           \
+-      memcpy(&c, pExp->ContextRecord, sizeof(CONTEXT));                         \
+-    c.ContextFlags = contextFlags;                                              \
+-  } while (0);
+-#else
+-// clang-format off
+-// The following should be enough for walking the callstack...
+-#define GET_CURRENT_CONTEXT_STACKWALKER_CODEPLEX(c, contextFlags) \
+-  do                                                              \
+-  {                                                               \
+-    memset(&c, 0, sizeof(CONTEXT));                               \
+-    c.ContextFlags = contextFlags;                                \
+-    __asm    call x                                               \
+-    __asm x: pop eax                                              \
+-    __asm    mov c.Eip, eax                                       \
+-    __asm    mov c.Ebp, ebp                                       \
+-    __asm    mov c.Esp, esp                                       \
+-  } while (0)
+-// clang-format on
+-#endif
+-
+-#else
+-
+ // The following is defined for x86 (XP and higher), x64 and IA64:
+ #define GET_CURRENT_CONTEXT_STACKWALKER_CODEPLEX(c, contextFlags) \
+   do                                                              \
+@@ -238,7 +187,6 @@ protected:
+     c.ContextFlags = contextFlags;                                \
+     RtlCaptureContext(&c);                                        \
+   } while (0);
+-#endif
+ 
+ #endif //defined(_MSC_VER)
+ 
diff --git a/third_party/allwpilib/upstream_utils/stack_walker_patches/0003-Add-advapi-pragma.patch b/third_party/allwpilib/upstream_utils/stack_walker_patches/0003-Add-advapi-pragma.patch
new file mode 100644
index 0000000..f48ee4e
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/stack_walker_patches/0003-Add-advapi-pragma.patch
@@ -0,0 +1,21 @@
+From 61646f76602a77059c18298caa575b95b702c94c Mon Sep 17 00:00:00 2001
+From: PJ Reiniger <pj.reiniger@gmail.com>
+Date: Tue, 24 May 2022 01:24:31 -0400
+Subject: [PATCH 3/3] Add advapi pragma
+
+---
+ Main/StackWalker/StackWalker.cpp | 1 +
+ 1 file changed, 1 insertion(+)
+
+diff --git a/Main/StackWalker/StackWalker.cpp b/Main/StackWalker/StackWalker.cpp
+index 48c7c57..6f0fbf2 100644
+--- a/Main/StackWalker/StackWalker.cpp
++++ b/Main/StackWalker/StackWalker.cpp
+@@ -88,6 +88,7 @@
+ #include <stdlib.h>
+ #include <tchar.h>
+ #pragma comment(lib, "version.lib") // for "VerQueryValue"
++#pragma comment(lib, "Advapi32.lib") // for "GetUserName"
+ #pragma warning(disable : 4826)
+ 
+ #ifdef UNICODE
diff --git a/third_party/allwpilib/upstream_utils/update_drake.py b/third_party/allwpilib/upstream_utils/update_drake.py
index 069d3a8..1849494 100755
--- a/third_party/allwpilib/upstream_utils/update_drake.py
+++ b/third_party/allwpilib/upstream_utils/update_drake.py
@@ -3,68 +3,97 @@
 import os
 import shutil
 
-from upstream_utils import setup_upstream_repo, comment_out_invalid_includes, walk_cwd_and_copy_if, apply_patches
+from upstream_utils import (
+    get_repo_root,
+    clone_repo,
+    comment_out_invalid_includes,
+    walk_cwd_and_copy_if,
+    git_am,
+)
 
 
 def main():
-    root, repo = setup_upstream_repo("https://github.com/RobotLocomotion/drake",
-                                     "v0.37.0")
-    wpimath = os.path.join(root, "wpimath")
+    upstream_root = clone_repo("https://github.com/RobotLocomotion/drake", "v1.6.0")
+    wpilib_root = get_repo_root()
+    wpimath = os.path.join(wpilib_root, "wpimath")
+
+    # Apply patches to upstream Git repo
+    os.chdir(upstream_root)
+    for f in [
+        "0001-Replace-Eigen-Dense-with-Eigen-Core.patch",
+        "0002-Add-WPILIB_DLLEXPORT-to-DARE-function-declarations.patch",
+    ]:
+        git_am(os.path.join(wpilib_root, "upstream_utils/drake_patches", f))
 
     # Delete old install
     for d in [
-            "src/main/native/cpp/drake", "src/main/native/include/drake",
-            "src/test/native/cpp/drake", "src/test/native/include/drake"
+        "src/main/native/thirdparty/drake/src",
+        "src/main/native/thirdparty/drake/include",
+        "src/test/native/cpp/drake",
+        "src/test/native/include/drake",
     ]:
         shutil.rmtree(os.path.join(wpimath, d), ignore_errors=True)
 
     # Copy drake source files into allwpilib
     src_files = walk_cwd_and_copy_if(
-        lambda dp, f: f in
-        ["drake_assert_and_throw.cc", "discrete_algebraic_riccati_equation.cc"],
-        os.path.join(wpimath, "src/main/native/cpp/drake"))
+        lambda dp, f: f
+        in ["drake_assert_and_throw.cc", "discrete_algebraic_riccati_equation.cc"],
+        os.path.join(wpimath, "src/main/native/thirdparty/drake/src"),
+    )
 
     # Copy drake header files into allwpilib
     include_files = walk_cwd_and_copy_if(
-        lambda dp, f: f in [
-            "drake_assert.h", "drake_assertion_error.h",
-            "is_approx_equal_abstol.h", "never_destroyed.h", "drake_copyable.h",
-            "drake_throw.h", "discrete_algebraic_riccati_equation.h"
-        ], os.path.join(wpimath, "src/main/native/include/drake"))
+        lambda dp, f: f
+        in [
+            "drake_assert.h",
+            "drake_assertion_error.h",
+            "is_approx_equal_abstol.h",
+            "never_destroyed.h",
+            "drake_copyable.h",
+            "drake_throw.h",
+            "discrete_algebraic_riccati_equation.h",
+        ],
+        os.path.join(wpimath, "src/main/native/thirdparty/drake/include/drake"),
+    )
 
     # Copy drake test source files into allwpilib
-    os.chdir(os.path.join(repo, "math/test"))
+    os.chdir(os.path.join(upstream_root, "math/test"))
     test_src_files = walk_cwd_and_copy_if(
         lambda dp, f: f == "discrete_algebraic_riccati_equation_test.cc",
-        os.path.join(wpimath, "src/test/native/cpp/drake"))
-    os.chdir(repo)
+        os.path.join(wpimath, "src/test/native/cpp/drake"),
+    )
+    os.chdir(upstream_root)
 
     # Copy drake test header files into allwpilib
     test_include_files = walk_cwd_and_copy_if(
         lambda dp, f: f == "eigen_matrix_compare.h",
-        os.path.join(wpimath, "src/test/native/include/drake"))
+        os.path.join(wpimath, "src/test/native/include/drake"),
+    )
 
     for f in src_files:
         comment_out_invalid_includes(
-            f, [os.path.join(wpimath, "src/main/native/include")])
+            f, [os.path.join(wpimath, "src/main/native/thirdparty/drake/include")]
+        )
     for f in include_files:
         comment_out_invalid_includes(
-            f, [os.path.join(wpimath, "src/main/native/include")])
+            f, [os.path.join(wpimath, "src/main/native/thirdparty/drake/include")]
+        )
     for f in test_src_files:
-        comment_out_invalid_includes(f, [
-            os.path.join(wpimath, "src/main/native/include"),
-            os.path.join(wpimath, "src/test/native/include")
-        ])
+        comment_out_invalid_includes(
+            f,
+            [
+                os.path.join(wpimath, "src/main/native/thirdparty/drake/include"),
+                os.path.join(wpimath, "src/test/native/include"),
+            ],
+        )
     for f in test_include_files:
-        comment_out_invalid_includes(f, [
-            os.path.join(wpimath, "src/main/native/include"),
-            os.path.join(wpimath, "src/test/native/include")
-        ])
-
-    apply_patches(root, [
-        "upstream_utils/drake-replace-dense-with-core.patch",
-        "upstream_utils/drake-dllexport-dare.patch"
-    ])
+        comment_out_invalid_includes(
+            f,
+            [
+                os.path.join(wpimath, "src/main/native/thirdparty/drake/include"),
+                os.path.join(wpimath, "src/test/native/include"),
+            ],
+        )
 
 
 if __name__ == "__main__":
diff --git a/third_party/allwpilib/upstream_utils/update_eigen.py b/third_party/allwpilib/upstream_utils/update_eigen.py
index 0df72a8..e04689a 100755
--- a/third_party/allwpilib/upstream_utils/update_eigen.py
+++ b/third_party/allwpilib/upstream_utils/update_eigen.py
@@ -4,7 +4,13 @@
 import re
 import shutil
 
-from upstream_utils import setup_upstream_repo, comment_out_invalid_includes, walk_cwd_and_copy_if, apply_patches
+from upstream_utils import (
+    get_repo_root,
+    clone_repo,
+    comment_out_invalid_includes,
+    walk_cwd_and_copy_if,
+    git_am,
+)
 
 
 def eigen_inclusions(dp, f):
@@ -38,8 +44,12 @@
 
     # Include architectures we care about
     if "Core/arch/" in abspath:
-        return ("arch/AVX/" in abspath or "arch/Default" in abspath or
-                "arch/NEON" in abspath or "arch/SSE" in abspath)
+        return (
+            "arch/AVX/" in abspath
+            or "arch/Default" in abspath
+            or "arch/NEON" in abspath
+            or "arch/SSE" in abspath
+        )
 
     # Include the following modules
     modules = [
@@ -47,22 +57,24 @@
         "Core",
         "Eigenvalues",
         "Householder",
+        "IterativeLinearSolvers",
         "Jacobi",
         "LU",
+        "OrderingMethods",
         "QR",
         "SVD",
+        "SparseCholesky",
+        "SparseCore",
+        "SparseLU",
+        "SparseQR",
         "StlSupport",
         "misc",
         "plugins",
     ]
     modules_rgx = r"|".join("/" + m for m in modules)
 
-    # "Std" matches StdDeque, StdList, and StdVector headers
-    if re.search(modules_rgx, abspath) or "Std" in f:
-        return True
-    else:
-        # Exclude all other modules
-        return False
+    # "Std" matches StdDeque, StdList, and StdVector headers. Other modules are excluded.
+    return bool(re.search(modules_rgx, abspath) or "Std" in f)
 
 
 def unsupported_inclusions(dp, f):
@@ -82,39 +94,47 @@
     if f == "CMakeLists.txt" or "README" in f:
         return False
 
-    # Include the AutoDiff and MatrixFunctions modules
-    return "AutoDiff" in abspath or "MatrixFunctions" in abspath
+    # Include the MatrixFunctions module
+    return "MatrixFunctions" in abspath
 
 
 def main():
-    root, repo = setup_upstream_repo("https://gitlab.com/libeigen/eigen.git",
-                                     "3.4.0")
-    wpimath = os.path.join(root, "wpimath")
+    upstream_root = clone_repo("https://gitlab.com/libeigen/eigen.git", "3.4.0")
+    wpilib_root = get_repo_root()
+    wpimath = os.path.join(wpilib_root, "wpimath")
+
+    # Apply patches to upstream Git repo
+    os.chdir(upstream_root)
+    for f in ["0001-Disable-warnings.patch"]:
+        git_am(os.path.join(wpilib_root, "upstream_utils/eigen_patches", f))
 
     # Delete old install
     for d in [
-            "src/main/native/eigeninclude/Eigen",
-            "src/main/native/eigeninclude/unsupported"
+        "src/main/native/thirdparty/eigen/include/Eigen",
+        "src/main/native/thirdparty/eigen/include/unsupported",
     ]:
         shutil.rmtree(os.path.join(wpimath, d), ignore_errors=True)
 
     # Copy Eigen headers into allwpilib
     eigen_files = walk_cwd_and_copy_if(
-        eigen_inclusions, os.path.join(wpimath, "src/main/native/eigeninclude"))
+        eigen_inclusions,
+        os.path.join(wpimath, "src/main/native/thirdparty/eigen/include"),
+    )
 
     # Copy unsupported headers into allwpilib
     unsupported_files = walk_cwd_and_copy_if(
         unsupported_inclusions,
-        os.path.join(wpimath, "src/main/native/eigeninclude"))
+        os.path.join(wpimath, "src/main/native/thirdparty/eigen/include"),
+    )
 
     for f in eigen_files:
         comment_out_invalid_includes(
-            f, [os.path.join(wpimath, "src/main/native/eigeninclude")])
+            f, [os.path.join(wpimath, "src/main/native/thirdparty/eigen/include")]
+        )
     for f in unsupported_files:
         comment_out_invalid_includes(
-            f, [os.path.join(wpimath, "src/main/native/eigeninclude")])
-
-    apply_patches(root, ["upstream_utils/eigen-maybe-uninitialized.patch"])
+            f, [os.path.join(wpimath, "src/main/native/thirdparty/eigen/include")]
+        )
 
 
 if __name__ == "__main__":
diff --git a/third_party/allwpilib/upstream_utils/update_fmt.py b/third_party/allwpilib/upstream_utils/update_fmt.py
index f752b3d..1088c39 100755
--- a/third_party/allwpilib/upstream_utils/update_fmt.py
+++ b/third_party/allwpilib/upstream_utils/update_fmt.py
@@ -3,36 +3,55 @@
 import os
 import shutil
 
-from upstream_utils import setup_upstream_repo, comment_out_invalid_includes, walk_cwd_and_copy_if, apply_patches
+from upstream_utils import (
+    get_repo_root,
+    clone_repo,
+    comment_out_invalid_includes,
+    walk_cwd_and_copy_if,
+    git_am,
+)
 
 
 def main():
-    root, repo = setup_upstream_repo("https://github.com/fmtlib/fmt", "8.1.1")
-    wpiutil = os.path.join(root, "wpiutil")
+    upstream_root = clone_repo("https://github.com/fmtlib/fmt", "9.1.0")
+    wpilib_root = get_repo_root()
+    wpiutil = os.path.join(wpilib_root, "wpiutil")
+
+    # Apply patches to upstream Git repo
+    os.chdir(upstream_root)
+    for f in [
+        "0001-Don-t-throw-on-write-failure.patch",
+        "0002-Suppress-C-20-clang-tidy-warning-false-positive.patch",
+    ]:
+        git_am(os.path.join(wpilib_root, "upstream_utils/fmt_patches", f))
 
     # Delete old install
-    for d in ["src/main/native/fmtlib/src", "src/main/native/fmtlib/include"]:
+    for d in [
+        "src/main/native/thirdparty/fmtlib/src",
+        "src/main/native/thirdparty/fmtlib/include",
+    ]:
         shutil.rmtree(os.path.join(wpiutil, d), ignore_errors=True)
 
     # Copy fmt source files into allwpilib
     src_files = walk_cwd_and_copy_if(
-        lambda dp, f: dp.endswith("src") and f.endswith(".cc") and f !=
-        "fmt.cc", os.path.join(wpiutil, "src/main/native/fmtlib"))
+        lambda dp, f: dp.endswith("src") and f.endswith(".cc") and f != "fmt.cc",
+        os.path.join(wpiutil, "src/main/native/thirdparty/fmtlib"),
+    )
 
     # Copy fmt header files into allwpilib
     include_files = walk_cwd_and_copy_if(
         lambda dp, f: dp.endswith("include/fmt"),
-        os.path.join(wpiutil, "src/main/native/fmtlib"))
+        os.path.join(wpiutil, "src/main/native/thirdparty/fmtlib"),
+    )
 
     for f in src_files:
         comment_out_invalid_includes(
-            f, [os.path.join(wpiutil, "src/main/native/fmtlib/include")])
+            f, [os.path.join(wpiutil, "src/main/native/thirdparty/fmtlib/include")]
+        )
     for f in include_files:
         comment_out_invalid_includes(
-            f, [os.path.join(wpiutil, "src/main/native/fmtlib/include")])
-
-    apply_patches(root,
-                  ["upstream_utils/fmt-dont-throw-on-write-failure.patch"])
+            f, [os.path.join(wpiutil, "src/main/native/thirdparty/fmtlib/include")]
+        )
 
 
 if __name__ == "__main__":
diff --git a/third_party/allwpilib/upstream_utils/update_gcem.py b/third_party/allwpilib/upstream_utils/update_gcem.py
new file mode 100644
index 0000000..ad1cb5a
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/update_gcem.py
@@ -0,0 +1,46 @@
+#!/usr/bin/env python3
+
+import os
+import shutil
+
+from upstream_utils import (
+    get_repo_root,
+    clone_repo,
+    comment_out_invalid_includes,
+    walk_cwd_and_copy_if,
+    git_am,
+)
+
+
+def main():
+    upstream_root = clone_repo("https://github.com/kthohr/gcem.git", "v1.16.0")
+    wpilib_root = get_repo_root()
+    wpimath = os.path.join(wpilib_root, "wpimath")
+
+    # Apply patches to upstream Git repo
+    os.chdir(upstream_root)
+    for f in []:
+        git_am(os.path.join(wpilib_root, "upstream_utils/gcem_patches", f))
+
+    # Delete old install
+    for d in [
+        "src/main/native/thirdparty/gcem/include",
+    ]:
+        shutil.rmtree(os.path.join(wpimath, d), ignore_errors=True)
+
+    # Copy gcem include files into allwpilib
+    include_files = walk_cwd_and_copy_if(
+        lambda dp, f: dp.endswith("include")
+        or dp.endswith("gcem_incl")
+        or dp.endswith("quadrature"),
+        os.path.join(wpimath, "src/main/native/thirdparty/gcem"),
+    )
+
+    for f in include_files:
+        comment_out_invalid_includes(
+            f, [os.path.join(wpimath, "src/main/native/thirdparty/gcem/include")]
+        )
+
+
+if __name__ == "__main__":
+    main()
diff --git a/third_party/allwpilib/upstream_utils/update_libuv.py b/third_party/allwpilib/upstream_utils/update_libuv.py
new file mode 100755
index 0000000..a90a6d7
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/update_libuv.py
@@ -0,0 +1,74 @@
+#!/usr/bin/env python3
+
+import os
+import shutil
+
+from upstream_utils import (
+    get_repo_root,
+    clone_repo,
+    comment_out_invalid_includes,
+    walk_cwd_and_copy_if,
+    git_am,
+)
+
+
+def main():
+    upstream_root = clone_repo("https://github.com/libuv/libuv", "v1.44.2")
+    wpilib_root = get_repo_root()
+    wpinet = os.path.join(wpilib_root, "wpinet")
+
+    # Apply patches to upstream Git repo
+    os.chdir(upstream_root)
+    for f in [
+        "0001-Fix-missing-casts.patch",
+        "0002-Fix-warnings.patch",
+        "0003-Preprocessor-cleanup.patch",
+        "0004-Cleanup-problematic-language.patch",
+        "0005-Use-roborio-time.patch",
+        "0006-Style-comments-cleanup.patch",
+        "0007-Squelch-GCC-12.1-warnings.patch",
+        "0008-Fix-Win32-warning-suppression-pragma.patch",
+        "0009-Avoid-unused-variable-warning-on-Mac.patch",
+    ]:
+        git_am(os.path.join(wpilib_root, "upstream_utils/libuv_patches", f))
+
+    # Delete old install
+    for d in ["src/main/native/thirdparty/libuv"]:
+        shutil.rmtree(os.path.join(wpinet, d), ignore_errors=True)
+
+    include_ignorelist = [
+        "aix.h",
+        "os390.h",
+        "stdint-msvc2008.h",
+        "sunos.h",
+    ]
+
+    include_files = walk_cwd_and_copy_if(
+        lambda dp, f: "include" in dp and f not in include_ignorelist,
+        os.path.join(wpinet, "src/main/native/thirdparty/libuv"),
+    )
+
+    src_ignorelist = [
+        "aix-common.c",
+        "aix.c",
+        "bsd-proctitle.c",
+        "darwin-stub.c",
+        "haiku.c",
+        "hurd.c",
+        "os390-proctitle.c",
+        "os390-syscalls.c",
+        "os390-syscalls.h",
+        "os390.c",
+        "qnx.c",
+        "sunos.c",
+        "sysinfo-loadavg.c",
+        "sysinfo-memory.c",
+    ]
+    src_files = walk_cwd_and_copy_if(
+        lambda dp, f: "src" in dp and "docs" not in dp and f not in src_ignorelist,
+        os.path.join(wpinet, "src/main/native/thirdparty/libuv"),
+    )
+
+
+if __name__ == "__main__":
+    main()
diff --git a/third_party/allwpilib/upstream_utils/update_llvm.py b/third_party/allwpilib/upstream_utils/update_llvm.py
new file mode 100755
index 0000000..c2ebd12
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/update_llvm.py
@@ -0,0 +1,214 @@
+#!/usr/bin/env python3
+
+import os
+import shutil
+
+from upstream_utils import (
+    get_repo_root,
+    clone_repo,
+    comment_out_invalid_includes,
+    walk_cwd_and_copy_if,
+    git_am,
+)
+
+
+def run_global_replacements(wpiutil_llvm_files):
+
+    for wpi_file in wpiutil_llvm_files:
+        with open(wpi_file) as f:
+            content = f.read()
+
+        # Rename namespace from llvm to wpi
+        content = content.replace("namespace llvm", "namespace wpi")
+        content = content.replace("llvm::", "wpi::")
+
+        # Fix #includes
+        content = content.replace('include "llvm/ADT', 'include "wpi')
+        content = content.replace('include "llvm/Config', 'include "wpi')
+        content = content.replace('include "llvm/Support', 'include "wpi')
+
+        # Fix uses of span
+        content = content.replace("span", "std::span")
+        content = content.replace('include "wpi/std::span.h"', "include <span>")
+        if wpi_file.endswith("ConvertUTFWrapper.cpp"):
+            content = content.replace(
+                "const UTF16 *Src = reinterpret_cast<const UTF16 *>(SrcBytes.begin());",
+                "const UTF16 *Src = reinterpret_cast<const UTF16 *>(&*SrcBytes.begin());",
+            )
+            content = content.replace(
+                "const UTF16 *SrcEnd = reinterpret_cast<const UTF16 *>(SrcBytes.end());",
+                "const UTF16 *SrcEnd = reinterpret_cast<const UTF16 *>(&*SrcBytes.begin() + SrcBytes.size());",
+            )
+
+        # Remove unused headers
+        content = content.replace('#include "llvm-c/ErrorHandling.h"\n', "")
+        content = content.replace('#include "wpi/Debug.h"\n', "")
+        content = content.replace('#include "wpi/Error.h"\n', "")
+        content = content.replace('#include "wpi/Format.h"\n', "")
+        content = content.replace('#include "wpi/FormatVariadic.h"\n', "")
+        content = content.replace('#include "wpi/NativeFormatting.h"\n', "")
+        content = content.replace('#include "wpi/Threading.h"\n', "")
+        content = content.replace('#include "wpi/DataTypes.h"\n', "")
+        content = content.replace('#include "wpi/llvm-config.h"\n', "")
+        content = content.replace('#include "wpi/abi-breaking.h"\n', "")
+        content = content.replace('#include "wpi/config.h"\n', "")
+        content = content.replace('#include "wpi/Signals.h"\n', "")
+        content = content.replace('#include "wpi/Process.h"\n', "")
+        content = content.replace('#include "wpi/Path.h"\n', "")
+        content = content.replace('#include "wpi/Program.h"\n', "")
+
+        # Fix include guards
+        content = content.replace("LLVM_ADT_", "WPIUTIL_WPI_")
+        content = content.replace("LLVM_SUPPORT_", "WPIUTIL_WPI_")
+        content = content.replace("LLVM_DEFINED_HAS_FEATURE", "WPI_DEFINED_HAS_FEATURE")
+
+        content = content.replace("const std::string_view &", "std::string_view ")
+        content = content.replace("sys::fs::openFileForRead", "fs::OpenFileForRead")
+        content = content.replace("sys::fs::closeFile", "fs::CloseFile")
+        content = content.replace("sys::fs::", "fs::")
+
+        # Replace wpi/FileSystem.h with wpi/fs.h
+        content = content.replace('include "wpi/FileSystem.h"', 'include "wpi/fs.h"')
+
+        # Replace llvm_unreachable() with wpi_unreachable()
+        content = content.replace("llvm_unreachable", "wpi_unreachable")
+
+        content = content.replace("llvm_is_multithreaded()", "1")
+
+        # Revert message in copyright header
+        content = content.replace("/// Defines the wpi::", "/// Defines the llvm::")
+        content = content.replace("// end llvm namespace", "// end wpi namespace")
+        content = content.replace("// end namespace llvm", "// end namespace wpi")
+        content = content.replace("// End llvm namespace", "// End wpi namespace")
+
+        content = content.replace("fs::openFileForRead", "fs::OpenFileForRead")
+
+        with open(wpi_file, "w") as f:
+            f.write(content)
+
+
+def flattened_llvm_files(llvm, dirs_to_keep):
+    file_lookup = {}
+
+    for dir_to_keep in dirs_to_keep:
+        dir_to_crawl = os.path.join(llvm, dir_to_keep)
+        for root, _, files in os.walk(dir_to_crawl):
+            for f in files:
+                file_lookup[f] = os.path.join(root, f)
+
+    return file_lookup
+
+
+def find_wpiutil_llvm_files(wpiutil_root, subfolder):
+
+    # These files have substantial changes, not worth managing with the patching process
+    ignore_list = [
+        "StringExtras.h",
+        "StringExtras.cpp",
+        "MemoryBuffer.cpp",
+        "MemoryBuffer.h",
+        "SmallVectorMemoryBuffer.h",
+    ]
+
+    wpiutil_files = []
+    for root, _, files in os.walk(os.path.join(wpiutil_root, subfolder)):
+        for f in files:
+            if f not in ignore_list:
+                full_file = os.path.join(root, f)
+                wpiutil_files.append(full_file)
+
+    return wpiutil_files
+
+
+def overwrite_files(wpiutil_files, llvm_files):
+    # Very sparse rips from LLVM sources. Not worth tyring to make match upstream
+    unmatched_files_whitelist = ["fs.h", "fs.cpp", "function_ref.h"]
+
+    for wpi_file in wpiutil_files:
+        wpi_base_name = os.path.basename(wpi_file)
+        if wpi_base_name in llvm_files:
+            shutil.copyfile(llvm_files[wpi_base_name], wpi_file)
+
+        elif wpi_base_name not in unmatched_files_whitelist:
+            print(f"No file match for {wpi_file}, check if LLVM deleted it")
+
+
+def overwrite_source(wpiutil_root, llvm_root):
+    llvm_files = flattened_llvm_files(
+        llvm_root,
+        [
+            "llvm/include/llvm/ADT/",
+            "llvm/include/llvm/Config",
+            "llvm/include/llvm/Support/",
+            "llvm/lib/Support/",
+        ],
+    )
+    wpi_files = find_wpiutil_llvm_files(
+        wpiutil_root, "src/main/native/thirdparty/llvm/include/wpi"
+    ) + find_wpiutil_llvm_files(
+        wpiutil_root, "src/main/native/thirdparty/llvm/cpp/llvm"
+    )
+
+    overwrite_files(wpi_files, llvm_files)
+    run_global_replacements(wpi_files)
+
+
+def overwrite_tests(wpiutil_root, llvm_root):
+    llvm_files = flattened_llvm_files(
+        llvm_root,
+        ["llvm/unittests/ADT/", "llvm/unittests/Config", "llvm/unittests/Support/"],
+    )
+    wpi_files = find_wpiutil_llvm_files(wpiutil_root, "src/test/native/cpp/llvm")
+
+    overwrite_files(wpi_files, llvm_files)
+    run_global_replacements(wpi_files)
+
+
+def main():
+    upstream_root = clone_repo("https://github.com/llvm/llvm-project", "llvmorg-14.0.6")
+    wpilib_root = get_repo_root()
+    wpiutil = os.path.join(wpilib_root, "wpiutil")
+
+    # Apply patches to upstream Git repo
+    os.chdir(upstream_root)
+    for f in [
+        "0001-Fix-spelling-language-errors.patch",
+        "0002-Remove-StringRef-ArrayRef-and-Optional.patch",
+        "0003-Wrap-std-min-max-calls-in-parens-for-Windows-warning.patch",
+        "0004-Change-unique_function-storage-size.patch",
+        "0005-Threading-updates.patch",
+        "0006-ifdef-guard-safety.patch",
+        "0007-Explicitly-use-std.patch",
+        "0008-Remove-format_provider.patch",
+        "0009-Add-compiler-warning-pragmas.patch",
+        "0010-Remove-unused-functions.patch",
+        "0011-Detemplatize-SmallVectorBase.patch",
+        "0012-Add-vectors-to-raw_ostream.patch",
+        "0013-Extra-collections-features.patch",
+        "0014-EpochTracker-ABI-macro.patch",
+        "0015-Delete-numbers-from-MathExtras.patch",
+        "0016-Add-lerp-and-sgn.patch",
+        "0017-Fixup-includes.patch",
+        "0018-Use-std-is_trivially_copy_constructible.patch",
+        "0019-Windows-support.patch",
+        "0020-Prefer-fmtlib.patch",
+        "0021-Prefer-wpi-s-fs.h.patch",
+        "0022-Remove-unused-functions.patch",
+        "0023-OS-specific-changes.patch",
+        "0024-Use-SmallVector-for-UTF-conversion.patch",
+        "0025-Prefer-to-use-static-pointers-in-raw_ostream.patch",
+        "0026-constexpr-endian-byte-swap.patch",
+        "0027-Copy-type-traits-from-STLExtras.h-into-PointerUnion..patch",
+        "0028-Remove-StringMap-test-for-llvm-sort.patch",
+    ]:
+        git_am(
+            os.path.join(wpilib_root, "upstream_utils/llvm_patches", f),
+            use_threeway=True,
+        )
+
+    overwrite_source(wpiutil, upstream_root)
+    overwrite_tests(wpiutil, upstream_root)
+
+
+if __name__ == "__main__":
+    main()
diff --git a/third_party/allwpilib/upstream_utils/update_memory.py b/third_party/allwpilib/upstream_utils/update_memory.py
new file mode 100755
index 0000000..e72717a
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/update_memory.py
@@ -0,0 +1,104 @@
+#!/usr/bin/env python3
+
+import os
+import shutil
+
+from upstream_utils import (
+    get_repo_root,
+    clone_repo,
+    comment_out_invalid_includes,
+    walk_if,
+    copy_to,
+)
+
+
+def run_source_replacements(memory_files):
+    for wpi_file in memory_files:
+        with open(wpi_file) as f:
+            content = f.read()
+
+        # Fix #includes
+        content = content.replace('include "', 'include "wpi/memory/')
+        content = content.replace(
+            "wpi/memory/free_list_utils.hpp", "free_list_utils.hpp"
+        )
+
+        with open(wpi_file, "w") as f:
+            f.write(content)
+
+
+def run_header_replacements(memory_files):
+    for wpi_file in memory_files:
+        if "detail" not in wpi_file:
+            continue
+        with open(wpi_file) as f:
+            content = f.read()
+
+        # Fix #includes
+        content = content.replace('include "config.hpp', 'include "../config.hpp')
+
+        with open(wpi_file, "w") as f:
+            f.write(content)
+
+
+def run_global_replacements(memory_files):
+    for wpi_file in memory_files:
+        with open(wpi_file) as f:
+            content = f.read()
+
+        # Rename namespace from foonathan to wpi
+        content = content.replace("namespace foonathan", "namespace wpi")
+        content = content.replace("foonathan::", "wpi::")
+        content = content.replace("FOONATHAN_", "WPI_")
+
+        # Fix #includes
+        content = content.replace('include "foonathan', 'include "wpi')
+
+        with open(wpi_file, "w") as f:
+            f.write(content)
+
+
+def main():
+    upstream_root = clone_repo("https://github.com/foonathan/memory", "v0.7-2")
+    wpilib_root = get_repo_root()
+    wpiutil = os.path.join(wpilib_root, "wpiutil")
+
+    # Delete old install
+    for d in [
+        "src/main/native/thirdparty/memory/src",
+        "src/main/native/thirdparty/memory/include",
+    ]:
+        shutil.rmtree(os.path.join(wpiutil, d), ignore_errors=True)
+
+    # Copy sources
+    os.chdir(upstream_root)
+    src_files = walk_if("src", lambda dp, f: f.endswith(".cpp") or f.endswith(".hpp"))
+    src_files = copy_to(
+        src_files, os.path.join(wpiutil, "src/main/native/thirdparty/memory")
+    )
+    run_global_replacements(src_files)
+    run_source_replacements(src_files)
+
+    # Copy headers
+    os.chdir(os.path.join(upstream_root, "include", "foonathan"))
+    include_files = walk_if(".", lambda dp, f: f.endswith(".hpp"))
+    include_files = copy_to(
+        include_files,
+        os.path.join(wpiutil, "src/main/native/thirdparty/memory/include/wpi"),
+    )
+    os.chdir(os.path.join("..", ".."))
+    run_global_replacements(include_files)
+    run_header_replacements(include_files)
+
+    # Copy config_impl.hpp
+    shutil.copyfile(
+        os.path.join(wpilib_root, "upstream_utils/memory_files/config_impl.hpp"),
+        os.path.join(
+            wpiutil,
+            "src/main/native/thirdparty/memory/include/wpi/memory/config_impl.hpp",
+        ),
+    )
+
+
+if __name__ == "__main__":
+    main()
diff --git a/third_party/allwpilib/upstream_utils/update_mpack.py b/third_party/allwpilib/upstream_utils/update_mpack.py
new file mode 100755
index 0000000..25eabfc
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/update_mpack.py
@@ -0,0 +1,59 @@
+#!/usr/bin/env python3
+
+import os
+import shutil
+import subprocess
+
+from upstream_utils import (
+    get_repo_root,
+    clone_repo,
+    walk_cwd_and_copy_if,
+    git_am,
+)
+
+
+def main():
+    upstream_root = clone_repo("https://github.com/ludocode/mpack", "v1.1")
+    wpilib_root = get_repo_root()
+    wpiutil = os.path.join(wpilib_root, "wpiutil")
+
+    # Delete old install
+    for d in [
+        "src/main/native/thirdparty/mpack/src",
+        "src/main/native/thirdparty/mpack/include",
+    ]:
+        shutil.rmtree(os.path.join(wpiutil, d), ignore_errors=True)
+
+    # Apply patches to upstream Git repo
+    os.chdir(upstream_root)
+
+    for f in [
+        "0001-Don-t-emit-inline-defs.patch",
+        "0002-Update-amalgamation-script.patch",
+        "0003-Use-namespace-for-C.patch",
+    ]:
+        git_am(
+            os.path.join(wpilib_root, "upstream_utils/mpack_patches", f),
+        )
+
+    # Run the amalgmation script
+    subprocess.check_call(["bash", "tools/amalgamate.sh"])
+
+    # Copy the files
+    amalgamation_source_dir = os.path.join(
+        ".", ".build", "amalgamation", "src", "mpack"
+    )
+    os.chdir(amalgamation_source_dir)
+
+    walk_cwd_and_copy_if(
+        lambda dp, f: f.endswith(".h"),
+        os.path.join(wpiutil, "src/main/native/thirdparty/mpack/include/wpi"),
+    )
+    walk_cwd_and_copy_if(
+        lambda dp, f: f.endswith(".c"),
+        os.path.join(wpiutil, "src/main/native/thirdparty/mpack/src"),
+    )
+
+
+if __name__ == "__main__":
+    main()
diff --git a/third_party/allwpilib/upstream_utils/update_stack_walker.py b/third_party/allwpilib/upstream_utils/update_stack_walker.py
new file mode 100755
index 0000000..95173d2
--- /dev/null
+++ b/third_party/allwpilib/upstream_utils/update_stack_walker.py
@@ -0,0 +1,74 @@
+#!/usr/bin/env python3
+
+import os
+import shutil
+import subprocess
+
+from upstream_utils import (
+    get_repo_root,
+    clone_repo,
+    comment_out_invalid_includes,
+    walk_cwd_and_copy_if,
+    git_am,
+)
+
+
+def crlf_to_lf(stackwalker_dir):
+    for root, _, files in os.walk(stackwalker_dir):
+        if ".git" in root:
+            continue
+
+        for fname in files:
+            filename = os.path.join(root, fname)
+            print(f"Converting CRLF -> LF for {filename}")
+            with open(filename, "rb") as f:
+                content = f.read()
+                content = content.replace(b"\r\n", b"\n")
+
+                with open(filename, "wb") as f:
+                    f.write(content)
+
+    cwd = os.getcwd()
+    os.chdir(stackwalker_dir)
+    subprocess.check_call(["git", "add", "-A"])
+    subprocess.check_call(["git", "commit", "-m", "Fix line endings"])
+    os.chdir(cwd)
+
+
+def main():
+    upstream_root = clone_repo(
+        "https://github.com/JochenKalmbach/StackWalker",
+        "42e7a6e056a9e7aca911a7e9e54e2e4f90bc2652",
+        shallow=False,
+    )
+    wpilib_root = get_repo_root()
+    wpiutil = os.path.join(wpilib_root, "wpiutil")
+
+    # Run CRLF -> LF before trying any patches
+    crlf_to_lf(upstream_root)
+
+    # Apply patches to upstream Git repo
+    os.chdir(upstream_root)
+    for f in [
+        "0001-Apply-PR-35.patch",
+        "0002-Remove-_M_IX86-checks.patch",
+        "0003-Add-advapi-pragma.patch",
+    ]:
+        git_am(
+            os.path.join(wpilib_root, "upstream_utils/stack_walker_patches", f),
+            ignore_whitespace=True,
+        )
+
+    shutil.copy(
+        os.path.join("Main", "StackWalker", "StackWalker.h"),
+        os.path.join(wpiutil, "src/main/native/windows/StackWalker.h"),
+    )
+
+    shutil.copy(
+        os.path.join("Main", "StackWalker", "StackWalker.cpp"),
+        os.path.join(wpiutil, "src/main/native/windows/StackWalker.cpp"),
+    )
+
+
+if __name__ == "__main__":
+    main()
diff --git a/third_party/allwpilib/upstream_utils/upstream_utils.py b/third_party/allwpilib/upstream_utils/upstream_utils.py
index c4ee1ae..6454d54 100644
--- a/third_party/allwpilib/upstream_utils/upstream_utils.py
+++ b/third_party/allwpilib/upstream_utils/upstream_utils.py
@@ -5,24 +5,32 @@
 import tempfile
 
 
-def clone_repo(url, treeish):
-    """Clones a git repo at the given URL into a temp folder and checks out the
-    given tree-ish (either branch or tag).
-
-    The current working directory will be set to the repository folder.
+def clone_repo(url, treeish, shallow=True):
+    """Clones a Git repo at the given URL into a temp folder, checks out the
+    given tree-ish (either branch or tag), then returns the repo root.
 
     Keyword argument:
-    url -- The URL of the git repo
+    url -- The URL of the Git repo
     treeish -- The tree-ish to check out (branch or tag)
+    shallow -- Whether to do a shallow clone
+
+    Returns:
+    root -- root directory of the cloned Git repository
     """
+    cwd = os.getcwd()
     os.chdir(tempfile.gettempdir())
 
     repo = os.path.basename(url)
-    dest = os.path.join(os.getcwd(), repo).removesuffix(".git")
+    dest = os.path.join(os.getcwd(), repo)
+    if dest.endswith(".git"):
+        dest = dest[:-4]
 
     # Clone Git repository into current directory or update it
     if not os.path.exists(dest):
-        subprocess.run(["git", "clone", url, dest])
+        cmd = ["git", "clone"]
+        if shallow:
+            cmd += ["--branch", treeish, "--depth", "1"]
+        subprocess.run(cmd + [url, dest])
         os.chdir(dest)
     else:
         os.chdir(dest)
@@ -33,8 +41,7 @@
     #   From https://gitlab.com/libeigen/eigen.git
     #   77c66e368c7e355f8be299659f57b0ffcaedb505  refs/heads/3.4
     #   3e006bfd31e4389e8c5718c30409cddb65a73b04  refs/heads/master
-    ls_out = subprocess.check_output(["git", "ls-remote",
-                                      "--heads"]).decode().rstrip()
+    ls_out = subprocess.check_output(["git", "ls-remote", "--heads"]).decode().rstrip()
     heads = [x.split()[1] for x in ls_out.split("\n")[1:]]
 
     if f"refs/heads/{treeish}" in heads:
@@ -44,6 +51,9 @@
     else:
         subprocess.run(["git", "checkout", treeish])
 
+    os.chdir(cwd)
+    return dest
+
 
 def get_repo_root():
     """Returns the Git repository root as an absolute path.
@@ -58,26 +68,6 @@
     return ""
 
 
-def setup_upstream_repo(url, treeish):
-    """Clones the given upstream repository, then returns the root of the
-    destination Git repository as well as the cloned upstream Git repository.
-
-    The current working directory will be set to the cloned upstream repository
-    folder.
-
-    Keyword arguments:
-    url -- The URL of the git repo
-    treeish -- The tree-ish to check out (branch or tag)
-
-    Returns:
-    root -- root directory of destination Git repository
-    repo -- root directory of cloned upstream Git repository
-    """
-    root = get_repo_root()
-    clone_repo(url, treeish)
-    return root, os.getcwd()
-
-
 def walk_if(top, pred):
     """Walks the current directory, then returns a list of files for which the
     given predicate is true.
@@ -88,10 +78,7 @@
             True if the file should be included in the output list
     """
     return [
-        os.path.join(dp, f)
-        for dp, dn, fn in os.walk(top)
-        for f in fn
-        if pred(dp, f)
+        os.path.join(dp, f) for dp, dn, fn in os.walk(top) for f in fn if pred(dp, f)
     ]
 
 
@@ -118,6 +105,8 @@
         # Rename .cc file to .cpp
         if dest_file.endswith(".cc"):
             dest_file = os.path.splitext(dest_file)[0] + ".cpp"
+        if dest_file.endswith(".c"):
+            dest_file = os.path.splitext(dest_file)[0] + ".cpp"
 
         # Make leading directory
         dest_dir = os.path.dirname(dest_file)
@@ -166,14 +155,16 @@
         include = match.group(1)
 
         # Write contents from before this match
-        new_contents += old_contents[pos:match.span()[0]]
+        new_contents += old_contents[pos : match.span()[0]]
 
         # Comment out #include if the file doesn't exist in current directory or
         # include root
-        if not os.path.exists(os.path.join(
-                os.path.dirname(filename), include)) and not any(
-                    os.path.exists(os.path.join(include_root, include))
-                    for include_root in include_roots):
+        if not os.path.exists(
+            os.path.join(os.path.dirname(filename), include)
+        ) and not any(
+            os.path.exists(os.path.join(include_root, include))
+            for include_root in include_roots
+        ):
             new_contents += "// "
 
         new_contents += match.group()
@@ -189,13 +180,18 @@
             f.write(new_contents)
 
 
-def apply_patches(root, patches):
-    """Apply list of patches to the destination Git repository.
+def git_am(patch, use_threeway=False, ignore_whitespace=False):
+    """Apply patch to a Git repository in the current directory using "git am".
 
     Keyword arguments:
-    root -- the root directory of the destination Git repository
-    patches -- list of patch files relative to the root
+    patch -- patch file relative to the root
+    use_threeway -- use a three-way merge when applying the patch
+    ignore_whitespace -- ignore whitespace in the patch file
     """
-    os.chdir(root)
-    for patch in patches:
-        subprocess.check_output(["git", "apply", patch])
+    args = ["git", "am"]
+    if use_threeway:
+        args.append("-3")
+    if ignore_whitespace:
+        args.append("--ignore-whitespace")
+
+    subprocess.check_output(args + [patch])
diff --git a/third_party/allwpilib/vcpkg.json b/third_party/allwpilib/vcpkg.json
new file mode 100644
index 0000000..e326359
--- /dev/null
+++ b/third_party/allwpilib/vcpkg.json
@@ -0,0 +1,7 @@
+{
+  "name": "main",
+  "version-string": "latest",
+  "dependencies": [
+    "opencv"
+  ]
+}
diff --git a/third_party/allwpilib/wpigui/build.gradle b/third_party/allwpilib/wpigui/build.gradle
index 5959b67..fb08198 100644
--- a/third_party/allwpilib/wpigui/build.gradle
+++ b/third_party/allwpilib/wpigui/build.gradle
@@ -1,6 +1,6 @@
 import org.gradle.internal.os.OperatingSystem
 
-if (!project.hasProperty('onlylinuxathena') && !project.hasProperty('onlylinuxraspbian') && !project.hasProperty('onlylinuxaarch64bionic')) {
+if (!project.hasProperty('onlylinuxathena')) {
 
     apply plugin: 'cpp'
     if (OperatingSystem.current().isMacOsX()) {
@@ -14,22 +14,10 @@
     }
 
     apply from: "${rootDir}/shared/config.gradle"
+    apply from: "${rootDir}/shared/imgui.gradle"
 
     nativeUtils.exportsConfigs {
         wpigui {
-            x86ExcludeSymbols = [
-                '_CT??_R0?AV_System_error',
-                '_CT??_R0?AVexception',
-                '_CT??_R0?AVfailure',
-                '_CT??_R0?AVruntime_error',
-                '_CT??_R0?AVsystem_error',
-                '_CTA5?AVfailure',
-                '_TI5?AVfailure',
-                '_CT??_R0?AVout_of_range',
-                '_CTA3?AVout_of_range',
-                '_TI3?AVout_of_range',
-                '_CT??_R0?AVbad_cast'
-            ]
             x64ExcludeSymbols = [
                 '_CT??_R0?AV_System_error',
                 '_CT??_R0?AVexception',
@@ -61,8 +49,8 @@
                     }
                 }
                 binaries.all {
-                    nativeUtils.useRequiredLibrary(it, 'imgui_static')
-                    if (it.targetPlatform.name == nativeUtils.wpi.platforms.roborio || it.targetPlatform.name == nativeUtils.wpi.platforms.raspbian || it.targetPlatform.name == nativeUtils.wpi.platforms.aarch64bionic) {
+                    nativeUtils.useRequiredLibrary(it, 'imgui')
+                    if (it.targetPlatform.name == nativeUtils.wpi.platforms.roborio) {
                         it.buildable = false
                         return
                     }
@@ -84,9 +72,18 @@
                                 }
                             }
                         }
+                    } else if (it.targetPlatform.name.startsWith('linuxarm')) {
+                        it.sources {
+                            wpiguiUnixGl2Cpp(CppSourceSet) {
+                                source {
+                                    srcDirs 'src/main/native/opengl2'
+                                    include '*.cpp'
+                                }
+                            }
+                        }
                     } else {
                         it.sources {
-                            wpiguiUnixCpp(CppSourceSet) {
+                            wpiguiUnixGl3Cpp(CppSourceSet) {
                                 source {
                                     srcDirs 'src/main/native/opengl3'
                                     include '*.cpp'
@@ -118,13 +115,13 @@
                 }
                 binaries.all {
                     lib library: 'wpigui'
-                    nativeUtils.useRequiredLibrary(it, 'imgui_static')
+                    nativeUtils.useRequiredLibrary(it, 'imgui')
                 }
             }
         }
         binaries {
             all {
-                if (it.targetPlatform.name == nativeUtils.wpi.platforms.roborio || it.targetPlatform.name == nativeUtils.wpi.platforms.raspbian || it.targetPlatform.name == nativeUtils.wpi.platforms.aarch64bionic) {
+                if (it.targetPlatform.name == nativeUtils.wpi.platforms.roborio) {
                     it.buildable = false
                     return
                 }
@@ -134,6 +131,9 @@
                     it.linker.args << '-framework' << 'Metal' << '-framework' << 'MetalKit' << '-framework' << 'Cocoa' << '-framework' << 'IOKit' << '-framework' << 'CoreFoundation' << '-framework' << 'CoreVideo' << '-framework' << 'QuartzCore'
                 } else {
                     it.linker.args << '-lX11'
+                    if (it.targetPlatform.name.startsWith('linuxarm')) {
+                        it.linker.args << '-lGL'
+                    }
                 }
             }
             withType(SharedLibraryBinarySpec) {
diff --git a/third_party/allwpilib/wpigui/src/main/native/cpp/portable-file-dialogs.cpp b/third_party/allwpilib/wpigui/src/main/native/cpp/portable-file-dialogs.cpp
index 0d94475..2e2ac7b 100644
--- a/third_party/allwpilib/wpigui/src/main/native/cpp/portable-file-dialogs.cpp
+++ b/third_party/allwpilib/wpigui/src/main/native/cpp/portable-file-dialogs.cpp
@@ -5,7 +5,7 @@
 //
 //  Portable File Dialogs
 //
-//  Copyright © 2018—2020 Sam Hocevar <sam@hocevar.net>
+//  Copyright © 2018—2022 Sam Hocevar <sam@hocevar.net>
 //
 //  This library is free software. It comes without any warranty, to
 //  the extent permitted by applicable law. You can redistribute it
@@ -20,13 +20,15 @@
 #ifndef WIN32_LEAN_AND_MEAN
 #   define WIN32_LEAN_AND_MEAN 1
 #endif
-#include <Windows.h>
+#pragma comment(lib, "Advapi32.lib")
+#include <windows.h>
 #include <commdlg.h>
-#include <ShlObj.h>
-#include <ShObjIdl.h> // IFileDialog
+#include <shlobj.h>
+#include <shobjidl.h> // IFileDialog
 #include <shellapi.h>
 #include <strsafe.h>
 #include <future>     // std::async
+#include <userenv.h>  // GetUserProfileDirectory()
 
 #elif __EMSCRIPTEN__
 #include <emscripten.h>
@@ -43,9 +45,11 @@
 #include <cstdio>     // popen()
 #include <cstdlib>    // std::getenv()
 #include <fcntl.h>    // fcntl()
-#include <unistd.h>   // read(), pipe(), dup2()
+#include <unistd.h>   // read(), pipe(), dup2(), getuid()
 #include <csignal>    // ::kill, std::signal
+#include <sys/stat.h> // stat()
 #include <sys/wait.h> // waitpid()
+#include <pwd.h>      // getpwnam()
 #endif
 
 #ifdef _WIN32
@@ -91,7 +95,7 @@
         {
         public:
             proc(dll const &lib, std::string const &sym)
-              : m_proc(reinterpret_cast<T *>(::GetProcAddress(lib.handle, sym.c_str())))
+              : m_proc(reinterpret_cast<T *>((void *)::GetProcAddress(lib.handle, sym.c_str())))
             {}
 
             operator bool() const { return m_proc != nullptr; }
@@ -175,6 +179,7 @@
 #endif
 };
 
+
 // internal free functions implementations
 
 #if _WIN32
@@ -227,8 +232,55 @@
         str.compare(0, prefix.size(), prefix) == 0;
 }
 
+// This is necessary until C++17 which will have std::filesystem::is_directory
+
+static inline bool is_directory(std::string const &path)
+{
+#if _WIN32
+    auto attr = GetFileAttributesA(path.c_str());
+    return attr != INVALID_FILE_ATTRIBUTES && (attr & FILE_ATTRIBUTE_DIRECTORY);
+#elif __EMSCRIPTEN__
+    // TODO
+    return false;
+#else
+    struct stat s;
+    return stat(path.c_str(), &s) == 0 && S_ISDIR(s.st_mode);
+#endif
+}
+
+// This is necessary because getenv is not thread-safe
+
+static inline std::string getenv(std::string const &str)
+{
+#if _WIN32
+    char *buf = nullptr;
+    size_t size = 0;
+    if (_dupenv_s(&buf, &size, str.c_str()) == 0 && buf)
+    {
+        std::string ret(buf);
+        free(buf);
+        return ret;
+    }
+    return "";
+#else
+    auto buf = std::getenv(str.c_str());
+    return buf ? buf : "";
+#endif
+}
+
 } // namespace internal
 
+//
+// The path class provides some platform-specific path constants
+//
+
+class path : protected internal::platform
+{
+public:
+    static std::string home();
+    static std::string separator();
+};
+
 // settings implementation
 
 settings::settings(bool resync)
@@ -237,6 +289,11 @@
 
     if (flags(flag::is_scanned))
         return;
+        
+    auto pfd_verbose = internal::getenv("PFD_VERBOSE");
+    auto match_no = std::regex("(|0|no|false)", std::regex_constants::icase);
+    if (!std::regex_match(pfd_verbose, match_no))
+        flags(flag::is_verbose) = true;
 
 #if _WIN32
     flags(flag::is_vista) = internal::is_vista();
@@ -249,10 +306,10 @@
     // If multiple helpers are available, try to default to the best one
     if (flags(flag::has_zenity) && flags(flag::has_kdialog))
     {
-        auto desktop_name = std::getenv("XDG_SESSION_DESKTOP");
-        if (desktop_name && desktop_name == std::string("gnome"))
+        auto desktop_name = internal::getenv("XDG_SESSION_DESKTOP");
+        if (desktop_name == std::string("gnome"))
             flags(flag::has_kdialog) = false;
-        else if (desktop_name && desktop_name == std::string("KDE"))
+        else if (desktop_name == std::string("KDE"))
             flags(flag::has_zenity) = false;
     }
 #endif
@@ -314,6 +371,59 @@
     return const_cast<bool &>(static_cast<settings const *>(this)->flags(in_flag));
 }
 
+// path implementation
+std::string path::home()
+{
+#if _WIN32
+    // First try the USERPROFILE environment variable
+    auto user_profile = internal::getenv("USERPROFILE");
+    if (user_profile.size() > 0)
+        return user_profile;
+    // Otherwise, try GetUserProfileDirectory()
+    HANDLE token = nullptr;
+    DWORD len = MAX_PATH;
+    char buf[MAX_PATH] = { '\0' };
+    if (OpenProcessToken(GetCurrentProcess(), TOKEN_QUERY, &token))
+    {
+        dll userenv("userenv.dll");
+        dll::proc<BOOL WINAPI (HANDLE, LPSTR, LPDWORD)> get_user_profile_directory(userenv, "GetUserProfileDirectoryA");
+        get_user_profile_directory(token, buf, &len);
+        CloseHandle(token);
+        if (*buf)
+            return buf;
+    }
+#elif __EMSCRIPTEN__
+    return "/";
+#else
+    // First try the HOME environment variable
+    auto home = internal::getenv("HOME");
+    if (home.size() > 0)
+        return home;
+    // Otherwise, try getpwuid_r()
+    size_t len = 4096;
+#if defined(_SC_GETPW_R_SIZE_MAX)
+    auto size_max = sysconf(_SC_GETPW_R_SIZE_MAX);
+    if (size_max != -1)
+        len = size_t(size_max);
+#endif
+    std::vector<char> buf(len);
+    struct passwd pwd, *result;
+    if (getpwuid_r(getuid(), &pwd, buf.data(), buf.size(), &result) == 0)
+        return result->pw_dir;
+#endif
+    return "/";
+}
+
+std::string path::separator()
+{
+#if _WIN32
+    return "\\";
+#else
+    return "/";
+#endif
+}
+
+
 // executor implementation
 
 std::string internal::executor::result(int *exit_code /* = nullptr */)
@@ -333,8 +443,12 @@
         auto previous_windows = m_windows;
         EnumWindows(&enum_windows_callback, (LPARAM)this);
         for (auto hwnd : m_windows)
-            if (previous_windows.find(hwnd) == previous_windows.end())
+            if (previous_windows.find(hwnd) == previous_windows.end()) 
+            {
                 SendMessage(hwnd, WM_CLOSE, 0, 0);
+                // Also send IDNO in case of a Yes/No or Abort/Retry/Ignore messagebox
+                SendMessage(hwnd, WM_COMMAND, IDNO, 0);
+            }
     }
 #elif __EMSCRIPTEN__ || __NX__
     // FIXME: do something
@@ -579,7 +693,7 @@
         // crash with error “default context is already set”.
         sizeof(act_ctx),
         ACTCTX_FLAG_RESOURCE_NAME_VALID | ACTCTX_FLAG_ASSEMBLY_DIRECTORY_VALID,
-        "shell32.dll", 0, 0, sys_dir.c_str(), (LPCSTR)124,
+        "shell32.dll", 0, 0, sys_dir.c_str(), (LPCSTR)124, nullptr, 0,
     };
 
     return ::CreateActCtxA(&act_ctx);
@@ -850,6 +964,13 @@
 
         return "";
     });
+#elif __EMSCRIPTEN__
+    // FIXME: do something
+    (void)in_type;
+    (void)title;
+    (void)default_path;
+    (void)filters;
+    (void)options;
 #else
     auto command = desktop_helper();
 
@@ -872,7 +993,14 @@
         }
 
         if (default_path.size())
-            script += " default location " + osascript_quote(default_path);
+        {
+            if (in_type == type::folder || is_directory(default_path))
+                script += " default location ";
+            else
+                script += " default name ";
+            script += osascript_quote(default_path);
+        }
+
         script += " with prompt " + osascript_quote(title);
 
         if (in_type == type::open)
@@ -896,11 +1024,17 @@
                 if (pat == "*" || pat == "*.*")
                     has_filter = false;
                 else if (internal::starts_with(pat, "*."))
-                    filter_list += (filter_list.size() == 0 ? "" : ",") +
-                                   osascript_quote(pat.substr(2, pat.size() - 2));
+                    filter_list += "," + osascript_quote(pat.substr(2, pat.size() - 2));
             }
             if (has_filter && filter_list.size() > 0)
-                script += " of type {" + filter_list + "}";
+            {
+                // There is a weird AppleScript bug where file extensions of length != 3 are
+                // ignored, e.g. type{"txt"} works, but type{"json"} does not. Fortunately if
+                // the whole list starts with a 3-character extension, everything works again.
+                // We use "///" for such an extension because we are sure it cannot appear in
+                // an actual filename.
+                script += " of type {\"///\"" + filter_list + "}";
+            }
         }
 
         if (in_type == type::open && (options & opt::multiselect))
@@ -922,7 +1056,14 @@
     else if (is_zenity())
     {
         command.push_back("--file-selection");
-        command.push_back("--filename=" + default_path);
+
+        // If the default path is a directory, make sure it ends with "/" otherwise zenity will
+        // open the file dialog in the parent directory.
+        auto filename_arg = "--filename=" + default_path;
+        if (in_type != type::folder && !ends_with(default_path, "/") && internal::is_directory(default_path))
+            filename_arg += "/";
+        command.push_back(filename_arg);
+
         command.push_back("--title");
         command.push_back(title);
         command.push_back("--separator=\n");
@@ -1062,7 +1203,7 @@
     }
 
     // Set the dialog title and option to select folders
-    ifd->SetOptions(FOS_PICKFOLDERS);
+    ifd->SetOptions(FOS_PICKFOLDERS | FOS_FORCEFILESYSTEM);
     ifd->SetTitle(m_wtitle.c_str());
 
     hr = ifd->Show(GetActiveWindow());
@@ -1072,15 +1213,27 @@
         hr = ifd->GetResult(&item);
         if (SUCCEEDED(hr))
         {
-            wchar_t* wselected = nullptr;
-            item->GetDisplayName(SIGDN_FILESYSPATH, &wselected);
-            item->Release();
-
-            if (wselected)
+            wchar_t* wname = nullptr;
+            // This is unlikely to fail because we use FOS_FORCEFILESYSTEM, but try
+            // to output a debug message just in case.
+            if (SUCCEEDED(item->GetDisplayName(SIGDN_FILESYSPATH, &wname)))
             {
-                result = internal::wstr2str(std::wstring(wselected));
-                internal::platform::dll::proc<void WINAPI (LPVOID)>(internal::platform::ole32_dll(), "CoTaskMemFree")(wselected);
+                result = internal::wstr2str(std::wstring(wname));
+                internal::platform::dll::proc<void WINAPI (LPVOID)>(internal::platform::ole32_dll(), "CoTaskMemFree")(wname);
             }
+            else
+            {
+                if (SUCCEEDED(item->GetDisplayName(SIGDN_NORMALDISPLAY, &wname)))
+                {
+                    auto name = internal::wstr2str(std::wstring(wname));
+                    internal::platform::dll::proc<void WINAPI (LPVOID)>(internal::platform::ole32_dll(), "CoTaskMemFree")(wname);
+                    fputs("pfd: failed to get path\n", stderr);
+                }
+                else
+                    fputs("pfd: item of unknown type selected\n", stderr);
+            }
+
+            item->Release();
         }
     }
 
@@ -1161,6 +1314,10 @@
 
     // Display the new icon
     Shell_NotifyIconW(NIM_ADD, nid.get());
+#elif __EMSCRIPTEN__
+    // FIXME: do something
+    (void)title;
+    (void)message;
 #else
     auto command = desktop_helper();
 
@@ -1274,45 +1431,45 @@
     {
         std::string script = "display dialog " + osascript_quote(text) +
                              " with title " + osascript_quote(title);
+        auto if_cancel = button::cancel;
         switch (_choice)
         {
             case choice::ok_cancel:
                 script += "buttons {\"OK\", \"Cancel\"}"
                           " default button \"OK\""
                           " cancel button \"Cancel\"";
-                m_mappings[256] = button::cancel;
                 break;
             case choice::yes_no:
                 script += "buttons {\"Yes\", \"No\"}"
                           " default button \"Yes\""
                           " cancel button \"No\"";
-                m_mappings[256] = button::no;
+                if_cancel = button::no;
                 break;
             case choice::yes_no_cancel:
                 script += "buttons {\"Yes\", \"No\", \"Cancel\"}"
                           " default button \"Yes\""
                           " cancel button \"Cancel\"";
-                m_mappings[256] = button::cancel;
                 break;
             case choice::retry_cancel:
                 script += "buttons {\"Retry\", \"Cancel\"}"
                           " default button \"Retry\""
                           " cancel button \"Cancel\"";
-                m_mappings[256] = button::cancel;
                 break;
             case choice::abort_retry_ignore:
                 script += "buttons {\"Abort\", \"Retry\", \"Ignore\"}"
-                          " default button \"Retry\""
+                          " default button \"Abort\""
                           " cancel button \"Retry\"";
-                m_mappings[256] = button::cancel;
+                if_cancel = button::retry;
                 break;
             case choice::ok: default:
                 script += "buttons {\"OK\"}"
                           " default button \"OK\""
                           " cancel button \"OK\"";
-                m_mappings[256] = button::ok;
+                if_cancel = button::ok;
                 break;
         }
+        m_mappings[1] = if_cancel;
+        m_mappings[256] = if_cancel;
         script += " with icon ";
         switch (_icon)
         {
@@ -1356,6 +1513,7 @@
 
         command.insert(command.end(), { "--title", title,
                                         "--width=300", "--height=0", // sensible defaults
+                                        "--no-markup", // do not interpret text as Pango markup
                                         "--text", text,
                                         "--icon-name=dialog-" + get_icon_name(_icon) });
     }
@@ -1411,8 +1569,7 @@
     auto ret = m_async->result(&exit_code);
     // osascript will say "button returned:Cancel\n"
     // and others will just say "Cancel\n"
-    if (exit_code < 0 || // this means cancel
-        internal::ends_with(ret, "Cancel\n"))
+    if (internal::ends_with(ret, "Cancel\n"))
         return button::cancel;
     if (internal::ends_with(ret, "OK\n"))
         return button::ok;
diff --git a/third_party/allwpilib/wpigui/src/main/native/cpp/wpigui.cpp b/third_party/allwpilib/wpigui/src/main/native/cpp/wpigui.cpp
index b1e1143..a93ca2b 100644
--- a/third_party/allwpilib/wpigui/src/main/native/cpp/wpigui.cpp
+++ b/third_party/allwpilib/wpigui/src/main/native/cpp/wpigui.cpp
@@ -9,7 +9,9 @@
 #include <cstring>
 
 #include <GLFW/glfw3.h>
+#include <IconsFontAwesome6.h>
 #include <imgui.h>
+#include <imgui_FontAwesomeSolid.h>
 #include <imgui_ProggyDotted.h>
 #include <imgui_impl_glfw.h>
 #include <imgui_internal.h>
@@ -104,7 +106,13 @@
 void gui::CreateContext() {
   gContext = new Context;
   AddFont("ProggyDotted", [](ImGuiIO& io, float size, const ImFontConfig* cfg) {
-    return ImGui::AddFontProggyDotted(io, size, cfg);
+    auto font = ImGui::AddFontProggyDotted(io, size, cfg);
+    static const ImWchar icons_ranges[] = {ICON_MIN_FA, ICON_MAX_16_FA, 0};
+    ImFontConfig icons_cfg;
+    icons_cfg.MergeMode = true;
+    icons_cfg.PixelSnapH = true;
+    ImGui::AddFontFontAwesomeSolid(io, size, &icons_cfg, icons_ranges);
+    return font;
   });
   PlatformCreateContext();
 }
@@ -115,7 +123,49 @@
   gContext = nullptr;
 }
 
-bool gui::Initialize(const char* title, int width, int height) {
+static void UpdateFontScale() {
+  // Scale based on OS window content scaling
+  float windowScale = 1.0;
+#ifndef __APPLE__
+  glfwGetWindowContentScale(gContext->window, &windowScale, nullptr);
+#endif
+  // map to closest font size: 0 = 0.5x, 1 = 0.75x, 2 = 1.0x, 3 = 1.25x,
+  // 4 = 1.5x, 5 = 1.75x, 6 = 2x
+  int fontScale =
+      gContext->userScale + static_cast<int>((windowScale - 1.0) * 4);
+  if (fontScale < 0) {
+    fontScale = 0;
+  }
+  if (gContext->fontScale != fontScale) {
+    gContext->reloadFonts = true;
+    gContext->fontScale = fontScale;
+  }
+}
+
+// the range is based on 13px being the "nominal" 100% size and going from
+// ~0.5x (7px) to ~2.0x (25px)
+static void ReloadFonts() {
+  auto& io = ImGui::GetIO();
+  io.Fonts->Clear();
+  gContext->fonts.clear();
+  float size = 7.0f + gContext->fontScale * 3.0f;
+  bool first = true;
+  for (auto&& makeFont : gContext->makeFonts) {
+    if (makeFont.second) {
+      ImFontConfig cfg;
+      std::snprintf(cfg.Name, sizeof(cfg.Name), "%s", makeFont.first);
+      ImFont* font = makeFont.second(io, size, &cfg);
+      if (first) {
+        ImGui::GetIO().FontDefault = font;
+        first = false;
+      }
+      gContext->fonts.emplace_back(font);
+    }
+  }
+}
+
+bool gui::Initialize(const char* title, int width, int height,
+                     ImGuiConfigFlags configFlags) {
   gContext->title = title;
   gContext->width = width;
   gContext->height = height;
@@ -125,6 +175,7 @@
   // Setup window
   glfwSetErrorCallback(ErrorCallback);
   glfwInitHint(GLFW_JOYSTICK_HAT_BUTTONS, GLFW_FALSE);
+  glfwInitHint(GLFW_COCOA_CHDIR_RESOURCES, GLFW_FALSE);
   PlatformGlfwInitHints();
   if (!glfwInit()) {
     return false;
@@ -137,6 +188,7 @@
   ImGui::CreateContext();
   ImPlot::CreateContext();
   ImGuiIO& io = ImGui::GetIO();
+  io.ConfigFlags |= configFlags;
 
   // Hook ini handler to save settings
   ImGuiSettingsHandler iniHandler;
@@ -265,20 +317,9 @@
   SetStyle(static_cast<Style>(gContext->style));
 
   // Load Fonts
-  // this range is based on 13px being the "nominal" 100% size and going from
-  // ~0.5x (7px) to ~2.0x (25px)
-  for (auto&& makeFont : gContext->makeFonts) {
-    if (makeFont.second) {
-      auto& font = gContext->fonts.emplace_back();
-      for (int i = 0; i < Font::kScaledLevels; ++i) {
-        float size = 7.0f + i * 3.0f;
-        ImFontConfig cfg;
-        std::snprintf(cfg.Name, sizeof(cfg.Name), "%s-%d", makeFont.first,
-                      static_cast<int>(size));
-        font.scaled[i] = makeFont.second(io, size, &cfg);
-      }
-    }
-  }
+  UpdateFontScale();
+  ReloadFonts();
+  gContext->reloadFonts = false;  // init renderer will do this
 
   if (!PlatformInitRenderer()) {
     return false;
@@ -293,12 +334,18 @@
     // Poll and handle events (inputs, window resize, etc.)
     glfwPollEvents();
     gContext->isPlatformRendering = true;
+    UpdateFontScale();
+    if (gContext->reloadFonts) {
+      ReloadFonts();
+      // PlatformRenderFrame() will clear reloadFonts flag
+    }
     PlatformRenderFrame();
     gContext->isPlatformRendering = false;
 
+    auto& io = ImGui::GetIO();
+
     // custom saving
     if (gContext->saveSettings) {
-      auto& io = ImGui::GetIO();
       if (io.WantSaveIniSettings) {
         gContext->saveSettings(false);
         io.WantSaveIniSettings = false;  // reset flag
@@ -332,18 +379,6 @@
   // Start the Dear ImGui frame
   ImGui::NewFrame();
 
-  // Scale based on OS window content scaling
-  float windowScale = 1.0;
-#ifndef __APPLE__
-  glfwGetWindowContentScale(gContext->window, &windowScale, nullptr);
-#endif
-  // map to closest font size: 0 = 0.5x, 1 = 0.75x, 2 = 1.0x, 3 = 1.25x,
-  // 4 = 1.5x, 5 = 1.75x, 6 = 2x
-  gContext->fontScale = std::clamp(
-      gContext->userScale + static_cast<int>((windowScale - 1.0) * 4), 0,
-      Font::kScaledLevels - 1);
-  ImGui::GetIO().FontDefault = gContext->fonts[0].scaled[gContext->fontScale];
-
   for (size_t i = 0; i < gContext->earlyExecutors.size(); ++i) {
     auto& execute = gContext->earlyExecutors[i];
     if (execute) {
@@ -427,10 +462,6 @@
   return gContext->makeFonts.size() - 1;
 }
 
-ImFont* gui::GetFont(int font) {
-  return gContext->fonts[font].scaled[gContext->fontScale];
-}
-
 void gui::SetStyle(Style style) {
   gContext->style = static_cast<int>(style);
   switch (style) {
@@ -497,14 +528,11 @@
     }
 
     if (ImGui::BeginMenu("Zoom")) {
-      for (int i = 0; i < Font::kScaledLevels && (25 * (i + 2)) <= 200; ++i) {
+      for (int i = 0; i < kFontScaledLevels && (25 * (i + 2)) <= 200; ++i) {
         char label[20];
         std::snprintf(label, sizeof(label), "%d%%", 25 * (i + 2));
         bool selected = gContext->userScale == i;
-        bool enabled = (gContext->fontScale - gContext->userScale + i) >= 0 &&
-                       (gContext->fontScale - gContext->userScale + i) <
-                           Font::kScaledLevels;
-        if (ImGui::MenuItem(label, nullptr, &selected, enabled)) {
+        if (ImGui::MenuItem(label, nullptr, &selected)) {
           gContext->userScale = i;
         }
       }
diff --git a/third_party/allwpilib/wpigui/src/main/native/cpp/wpigui_openurl.cpp b/third_party/allwpilib/wpigui/src/main/native/cpp/wpigui_openurl.cpp
new file mode 100644
index 0000000..b913ceb
--- /dev/null
+++ b/third_party/allwpilib/wpigui/src/main/native/cpp/wpigui_openurl.cpp
@@ -0,0 +1,28 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpigui_openurl.h"
+
+#if _WIN32
+#ifndef WIN32_LEAN_AND_MEAN
+#define WIN32_LEAN_AND_MEAN 1
+#endif
+#include <Windows.h>
+#include <shellapi.h>
+#else
+#include <unistd.h>
+#endif
+
+void wpi::gui::OpenURL(const std::string& url) {
+#ifdef _WIN32
+  ShellExecuteA(nullptr, "open", url.c_str(), nullptr, nullptr, SW_SHOWNORMAL);
+#else
+#ifdef __APPLE__
+  static constexpr const char* opencmd = "open";
+#else
+  static constexpr const char* opencmd = "xdg-open";
+#endif
+  execlp(opencmd, opencmd, url.c_str(), static_cast<const char*>(nullptr));
+#endif
+}
diff --git a/third_party/allwpilib/wpigui/src/main/native/directx11/wpigui_directx11.cpp b/third_party/allwpilib/wpigui/src/main/native/directx11/wpigui_directx11.cpp
index 771a2ed..0ef2485 100644
--- a/third_party/allwpilib/wpigui/src/main/native/directx11/wpigui_directx11.cpp
+++ b/third_party/allwpilib/wpigui/src/main/native/directx11/wpigui_directx11.cpp
@@ -69,8 +69,9 @@
           nullptr, D3D_DRIVER_TYPE_HARDWARE, nullptr, createDeviceFlags,
           featureLevelArray, 2, D3D11_SDK_VERSION, &sd,
           &gPlatformContext->pSwapChain, &gPlatformContext->pd3dDevice,
-          &featureLevel, &gPlatformContext->pd3dDeviceContext) != S_OK)
+          &featureLevel, &gPlatformContext->pd3dDeviceContext) != S_OK) {
     return false;
+  }
 
   CreateRenderTarget();
   return true;
@@ -133,6 +134,11 @@
 }
 
 void gui::PlatformRenderFrame() {
+  if (gContext->reloadFonts) {
+    ImGui_ImplDX11_InvalidateDeviceObjects();
+    ImGui_ImplDX11_CreateDeviceObjects();
+    gContext->reloadFonts = false;
+  }
   ImGui_ImplDX11_NewFrame();
 
   CommonRenderFrame();
diff --git a/third_party/allwpilib/wpigui/src/main/native/include/wpigui.h b/third_party/allwpilib/wpigui/src/main/native/include/wpigui.h
index d4602b5..db74291 100644
--- a/third_party/allwpilib/wpigui/src/main/native/include/wpigui.h
+++ b/third_party/allwpilib/wpigui/src/main/native/include/wpigui.h
@@ -30,8 +30,10 @@
  * @param title main application window title
  * @param width main application window width
  * @param height main application window height
+ * @param configFlags ImGui configuration flags
  */
-bool Initialize(const char* title, int width, int height);
+bool Initialize(const char* title, int width, int height,
+                ImGuiConfigFlags configFlags = ImGuiConfigFlags_None);
 
 /**
  * Runs main GUI loop.  On some OS'es this must be called from the main thread.
diff --git a/third_party/allwpilib/wpigui/src/main/native/include/wpigui_internal.h b/third_party/allwpilib/wpigui/src/main/native/include/wpigui_internal.h
index 4c8a22c..f4d352b 100644
--- a/third_party/allwpilib/wpigui/src/main/native/include/wpigui_internal.h
+++ b/third_party/allwpilib/wpigui/src/main/native/include/wpigui_internal.h
@@ -26,10 +26,7 @@
   int style = 0;
 };
 
-struct Font {
-  static constexpr int kScaledLevels = 9;
-  ImFont* scaled[kScaledLevels];
-};
+constexpr int kFontScaledLevels = 9;
 
 struct Context : public SavedSettings {
   std::atomic_bool exit{false};
@@ -56,12 +53,14 @@
   std::vector<std::function<void()>> lateExecutors;
 
   int fontScale = 2;  // updated by main loop
-  std::vector<Font> fonts;
+  std::vector<ImFont*> fonts;
 
   std::vector<GLFWimage> icons;
 
   std::string iniPath = "imgui.ini";
   bool resetOnExit = false;
+
+  bool reloadFonts = false;  // reload fonts in next PlatformRenderFrame()
 };
 
 extern Context* gContext;
diff --git a/third_party/allwpilib/wpigui/src/main/native/include/wpigui_openurl.h b/third_party/allwpilib/wpigui/src/main/native/include/wpigui_openurl.h
new file mode 100644
index 0000000..5de0828
--- /dev/null
+++ b/third_party/allwpilib/wpigui/src/main/native/include/wpigui_openurl.h
@@ -0,0 +1,18 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <string>
+
+namespace wpi::gui {
+
+/**
+ * Opens a URL in the default browser.
+ *
+ * @param url URL to open
+ */
+void OpenURL(const std::string& url);
+
+}  // namespace wpi::gui
diff --git a/third_party/allwpilib/wpigui/src/main/native/metal/wpigui_metal.mm b/third_party/allwpilib/wpigui/src/main/native/metal/wpigui_metal.mm
index 95c78c4..a1024ed 100644
--- a/third_party/allwpilib/wpigui/src/main/native/metal/wpigui_metal.mm
+++ b/third_party/allwpilib/wpigui/src/main/native/metal/wpigui_metal.mm
@@ -84,6 +84,12 @@
     id <MTLRenderCommandEncoder> renderEncoder = [commandBuffer renderCommandEncoderWithDescriptor:renderPassDescriptor];
     [renderEncoder pushDebugGroup:@"WPI GUI"];
 
+    if (gContext->reloadFonts) {
+      ImGui_ImplMetal_DestroyFontsTexture();
+      ImGui_ImplMetal_CreateFontsTexture(gPlatformContext->layer.device);
+      gContext->reloadFonts = false;
+    }
+
     // Start the Dear ImGui frame
     ImGui_ImplMetal_NewFrame(renderPassDescriptor);
 
diff --git a/third_party/allwpilib/wpigui/src/main/native/opengl2/wpigui_opengl2.cpp b/third_party/allwpilib/wpigui/src/main/native/opengl2/wpigui_opengl2.cpp
new file mode 100644
index 0000000..afc9fea
--- /dev/null
+++ b/third_party/allwpilib/wpigui/src/main/native/opengl2/wpigui_opengl2.cpp
@@ -0,0 +1,136 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <cstdio>
+
+#include <GLFW/glfw3.h>
+#include <imgui.h>
+#include <imgui_impl_glfw.h>
+#include <imgui_impl_opengl2.h>
+
+#include "wpigui.h"
+#include "wpigui_internal.h"
+
+using namespace wpi::gui;
+
+static bool gPlatformValid = false;
+
+namespace wpi {
+
+void gui::PlatformCreateContext() {}
+
+void gui::PlatformDestroyContext() {}
+
+void gui::PlatformGlfwInitHints() {}
+
+void gui::PlatformGlfwWindowHints() {
+  // GL 2.1
+  glfwWindowHint(GLFW_CONTEXT_VERSION_MAJOR, 2);
+  glfwWindowHint(GLFW_CONTEXT_VERSION_MINOR, 1);
+
+  // enable 4xMSAA
+  glfwWindowHint(GLFW_SAMPLES, 4);
+}
+
+bool gui::PlatformInitRenderer() {
+  glfwMakeContextCurrent(gContext->window);
+
+  glfwSwapInterval(1);  // Enable vsync
+
+  // Turn on multisampling
+  glEnable(GL_MULTISAMPLE);
+
+  // Setup Platform/Renderer bindings
+  ImGui_ImplGlfw_InitForOpenGL(gContext->window, true);
+
+  ImGui_ImplOpenGL2_Init();
+
+  gPlatformValid = true;
+  return true;
+}
+
+void gui::PlatformRenderFrame() {
+  if (gContext->reloadFonts) {
+    ImGui_ImplOpenGL2_DestroyFontsTexture();
+    ImGui_ImplOpenGL2_CreateFontsTexture();
+    gContext->reloadFonts = false;
+  }
+  ImGui_ImplOpenGL2_NewFrame();
+
+  CommonRenderFrame();
+
+  int display_w, display_h;
+  glfwGetFramebufferSize(gContext->window, &display_w, &display_h);
+  glViewport(0, 0, display_w, display_h);
+  glClearColor(gContext->clearColor.x, gContext->clearColor.y,
+               gContext->clearColor.z, gContext->clearColor.w);
+  glClear(GL_COLOR_BUFFER_BIT);
+  ImGui_ImplOpenGL2_RenderDrawData(ImGui::GetDrawData());
+
+  glfwSwapBuffers(gContext->window);
+}
+
+void gui::PlatformShutdown() {
+  gPlatformValid = false;
+  ImGui_ImplOpenGL2_Shutdown();
+}
+
+void gui::PlatformFramebufferSizeChanged(int width, int height) {}
+
+static inline GLenum GLPixelFormat(PixelFormat format) {
+  switch (format) {
+    case kPixelRGBA:
+      return GL_RGBA;
+    case kPixelBGRA:
+      return GL_BGRA;
+    default:
+      return GL_RGBA;
+  }
+}
+
+ImTextureID gui::CreateTexture(PixelFormat format, int width, int height,
+                               const unsigned char* data) {
+  if (!gPlatformValid) {
+    return nullptr;
+  }
+
+  // Create a OpenGL texture identifier
+  GLuint texture;
+  glGenTextures(1, &texture);
+  glBindTexture(GL_TEXTURE_2D, texture);
+
+  // Setup filtering parameters for display
+  glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR);
+  glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR);
+
+  // Upload pixels into texture
+  glPixelStorei(GL_UNPACK_ROW_LENGTH, 0);
+  glTexImage2D(GL_TEXTURE_2D, 0, GL_RGBA, width, height, 0,
+               GLPixelFormat(format), GL_UNSIGNED_BYTE, data);
+
+  return reinterpret_cast<ImTextureID>(static_cast<uintptr_t>(texture));
+}
+
+void gui::UpdateTexture(ImTextureID texture, PixelFormat format, int width,
+                        int height, const unsigned char* data) {
+  GLuint glTexture = static_cast<GLuint>(reinterpret_cast<uintptr_t>(texture));
+  if (glTexture == 0) {
+    return;
+  }
+  glBindTexture(GL_TEXTURE_2D, glTexture);
+  glTexSubImage2D(GL_TEXTURE_2D, 0, 0, 0, width, height, GLPixelFormat(format),
+                  GL_UNSIGNED_BYTE, data);
+}
+
+void gui::DeleteTexture(ImTextureID texture) {
+  if (!gPlatformValid) {
+    return;
+  }
+  GLuint glTexture = static_cast<GLuint>(reinterpret_cast<uintptr_t>(texture));
+  if (glTexture != 0) {
+    glDeleteTextures(1, &glTexture);
+  }
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib/wpigui/src/main/native/opengl3/wpigui_opengl3.cpp b/third_party/allwpilib/wpigui/src/main/native/opengl3/wpigui_opengl3.cpp
index c85ad04..2f75929 100644
--- a/third_party/allwpilib/wpigui/src/main/native/opengl3/wpigui_opengl3.cpp
+++ b/third_party/allwpilib/wpigui/src/main/native/opengl3/wpigui_opengl3.cpp
@@ -76,6 +76,11 @@
 }
 
 void gui::PlatformRenderFrame() {
+  if (gContext->reloadFonts) {
+    ImGui_ImplOpenGL3_DestroyFontsTexture();
+    ImGui_ImplOpenGL3_CreateFontsTexture();
+    gContext->reloadFonts = false;
+  }
   ImGui_ImplOpenGL3_NewFrame();
 
   CommonRenderFrame();
diff --git a/third_party/allwpilib/wpilib-config.cmake.in b/third_party/allwpilib/wpilib-config.cmake.in
index 50feffc..36a9d25 100644
--- a/third_party/allwpilib/wpilib-config.cmake.in
+++ b/third_party/allwpilib/wpilib-config.cmake.in
@@ -2,9 +2,10 @@
 @FILENAME_DEP_REPLACE@
 set(THREADS_PREFER_PTHREAD_FLAG ON)
 find_dependency(Threads)
-@LIBUV_VCPKG_REPLACE@
-@EIGEN_VCPKG_REPLACE@
+@LIBUV_SYSTEM_REPLACE@
+@EIGEN_SYSTEM_REPLACE@
 @WPIUTIL_DEP_REPLACE@
+@WPINET_DEP_REPLACE@
 @NTCORE_DEP_REPLACE@
 @CSCORE_DEP_REPLACE@
 @CAMERASERVER_DEP_REPLACE@
diff --git a/third_party/allwpilib/wpilibNewCommands/CMakeLists.txt b/third_party/allwpilib/wpilibNewCommands/CMakeLists.txt
index d44939f..716c508 100644
--- a/third_party/allwpilib/wpilibNewCommands/CMakeLists.txt
+++ b/third_party/allwpilib/wpilibNewCommands/CMakeLists.txt
@@ -31,7 +31,7 @@
 set_target_properties(wpilibNewCommands PROPERTIES DEBUG_POSTFIX "d")
 set_property(TARGET wpilibNewCommands PROPERTY FOLDER "libraries")
 
-target_compile_features(wpilibNewCommands PUBLIC cxx_std_17)
+target_compile_features(wpilibNewCommands PUBLIC cxx_std_20)
 wpilib_target_warnings(wpilibNewCommands)
 target_link_libraries(wpilibNewCommands wpilibc)
 
diff --git a/third_party/allwpilib/wpilibNewCommands/WPILibNewCommands.json b/third_party/allwpilib/wpilibNewCommands/WPILibNewCommands.json
index fb66227..da4bc52 100644
--- a/third_party/allwpilib/wpilibNewCommands/WPILibNewCommands.json
+++ b/third_party/allwpilib/wpilibNewCommands/WPILibNewCommands.json
@@ -25,12 +25,12 @@
           "skipInvalidPlatforms": true,

           "binaryPlatforms": [

               "linuxathena",

-              "linuxraspbian",

-              "linuxaarch64bionic",

+              "linuxarm32",

+              "linuxarm64",

               "windowsx86-64",

               "windowsx86",

               "linuxx86-64",

-              "osxx86-64"

+              "osxuniversal"

           ]

       }

   ]

diff --git a/third_party/allwpilib/wpilibNewCommands/build.gradle b/third_party/allwpilib/wpilibNewCommands/build.gradle
index 3c9f0c4..82fc470 100644
--- a/third_party/allwpilib/wpilibNewCommands/build.gradle
+++ b/third_party/allwpilib/wpilibNewCommands/build.gradle
@@ -15,12 +15,14 @@
 
 dependencies {
     implementation project(':wpiutil')
+    implementation project(':wpinet')
     implementation project(':ntcore')
     implementation project(':cscore')
     implementation project(':hal')
     implementation project(':wpimath')
     implementation project(':wpilibj')
     devImplementation project(':wpiutil')
+    devImplementation project(':wpinet')
     devImplementation project(':ntcore')
     devImplementation project(':cscore')
     devImplementation project(':hal')
@@ -31,19 +33,6 @@
 
 nativeUtils.exportsConfigs {
     wpilibNewCommands {
-        x86ExcludeSymbols = [
-            '_CT??_R0?AV_System_error',
-            '_CT??_R0?AVexception',
-            '_CT??_R0?AVfailure',
-            '_CT??_R0?AVruntime_error',
-            '_CT??_R0?AVsystem_error',
-            '_CTA5?AVfailure',
-            '_TI5?AVfailure',
-            '_CT??_R0?AVout_of_range',
-            '_CTA3?AVout_of_range',
-            '_TI3?AVout_of_range',
-            '_CT??_R0?AVbad_cast'
-        ]
         x64ExcludeSymbols = [
             '_CT??_R0?AV_System_error',
             '_CT??_R0?AVexception',
@@ -68,13 +57,15 @@
                 return
             }
             lib project: ':wpilibc', library: 'wpilibc', linkage: 'shared'
-            lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
+            project(':ntcore').addNtcoreDependency(it, 'shared')
             project(':hal').addHalDependency(it, 'shared')
             lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+            lib project: ':wpinet', library: 'wpinet', linkage: 'shared'
             lib project: ':wpimath', library: 'wpimath', linkage: 'shared'
 
             if (it.component.name == "${nativeName}Dev") {
-                lib project: ':ntcore', library: 'ntcoreJNIShared', linkage: 'shared'
+                project(':ntcore').addNtcoreJniDependency(it)
+                lib project: ':wpinet', library: 'wpinetJNIShared', linkage: 'shared'
                 lib project: ':wpiutil', library: 'wpiutilJNIShared', linkage: 'shared'
                 project(':hal').addHalJniDependency(it)
             }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Command.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Command.java
index 82c6bc4..0383099 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Command.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Command.java
@@ -4,13 +4,16 @@
 
 package edu.wpi.first.wpilibj2.command;
 
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
+
+import edu.wpi.first.util.function.BooleanConsumer;
 import java.util.Set;
 import java.util.function.BooleanSupplier;
 
 /**
  * A state machine representing a complete action to be performed by the robot. Commands are run by
  * the {@link CommandScheduler}, and can be composed into CommandGroups to allow users to build
- * complicated multi-step actions without the need to roll the state machine logic themselves.
+ * complicated multistep actions without the need to roll the state machine logic themselves.
  *
  * <p>Commands are run synchronously from the main robot loop; no multithreading is used, unless
  * specified explicitly from the command implementation.
@@ -47,14 +50,15 @@
 
   /**
    * Specifies the set of subsystems used by this command. Two commands cannot use the same
-   * subsystem at the same time. If the command is scheduled as interruptible and another command is
-   * scheduled that shares a requirement, the command will be interrupted. Else, the command will
-   * not be scheduled. If no subsystems are required, return an empty set.
+   * subsystem at the same time. If another command is scheduled that shares a requirement, {@link
+   * #getInterruptionBehavior()} will be checked and followed. If no subsystems are required, return
+   * an empty set.
    *
    * <p>Note: it is recommended that user implementations contain the requirements as a field, and
    * return that field here, rather than allocating a new set every time this is called.
    *
    * @return the set of subsystems that are required
+   * @see InterruptionBehavior
    */
   Set<Subsystem> getRequirements();
 
@@ -63,11 +67,11 @@
    * finishes normally, the command will be interrupted and un-scheduled. Note that the timeout only
    * applies to the command returned by this method; the calling command is not itself changed.
    *
-   * <p>Note: This decorator works by composing this command within a CommandGroup. The command
-   * cannot be used independently after being decorated, or be re-decorated with a different
-   * decorator, unless it is manually cleared from the list of grouped commands with {@link
-   * CommandGroupBase#clearGroupedCommand(Command)}. The decorated command can, however, be further
-   * decorated without issue.
+   * <p>Note: This decorator works by adding this command to a composition. The command the
+   * decorator was called on cannot be scheduled independently or be added to a different
+   * composition (namely, decorators), unless it is manually cleared from the list of composed
+   * commands with {@link CommandScheduler#removeComposedCommand(Command)}. The command composition
+   * returned from this method can be further decorated without issue.
    *
    * @param seconds the timeout duration
    * @return the command with the timeout added
@@ -82,11 +86,11 @@
    * that this only applies to the command returned by this method; the calling command is not
    * itself changed.
    *
-   * <p>Note: This decorator works by composing this command within a CommandGroup. The command
-   * cannot be used independently after being decorated, or be re-decorated with a different
-   * decorator, unless it is manually cleared from the list of grouped commands with {@link
-   * CommandGroupBase#clearGroupedCommand(Command)}. The decorated command can, however, be further
-   * decorated without issue.
+   * <p>Note: This decorator works by adding this command to a composition. The command the
+   * decorator was called on cannot be scheduled independently or be added to a different
+   * composition (namely, decorators), unless it is manually cleared from the list of composed
+   * commands with {@link CommandScheduler#removeComposedCommand(Command)}. The command composition
+   * returned from this method can be further decorated without issue.
    *
    * @param condition the interrupt condition
    * @return the command with the interrupt condition added
@@ -101,15 +105,17 @@
    * that this only applies to the command returned by this method; the calling command is not
    * itself changed.
    *
-   * <p>Note: This decorator works by composing this command within a CommandGroup. The command
-   * cannot be used independently after being decorated, or be re-decorated with a different
-   * decorator, unless it is manually cleared from the list of grouped commands with {@link
-   * CommandGroupBase#clearGroupedCommand(Command)}. The decorated command can, however, be further
-   * decorated without issue.
+   * <p>Note: This decorator works by adding this command to a composition. The command the
+   * decorator was called on cannot be scheduled independently or be added to a different
+   * composition (namely, decorators), unless it is manually cleared from the list of composed
+   * commands with {@link CommandScheduler#removeComposedCommand(Command)}. The command composition
+   * returned from this method can be further decorated without issue.
    *
    * @param condition the interrupt condition
    * @return the command with the interrupt condition added
+   * @deprecated Replace with {@link #until(BooleanSupplier)}
    */
+  @Deprecated(since = "2023")
   default ParallelRaceGroup withInterrupt(BooleanSupplier condition) {
     return until(condition);
   }
@@ -117,11 +123,11 @@
   /**
    * Decorates this command with a runnable to run before this command starts.
    *
-   * <p>Note: This decorator works by composing this command within a CommandGroup. The command
-   * cannot be used independently after being decorated, or be re-decorated with a different
-   * decorator, unless it is manually cleared from the list of grouped commands with {@link
-   * CommandGroupBase#clearGroupedCommand(Command)}. The decorated command can, however, be further
-   * decorated without issue.
+   * <p>Note: This decorator works by adding this command to a composition. The command the
+   * decorator was called on cannot be scheduled independently or be added to a different
+   * composition (namely, decorators), unless it is manually cleared from the list of composed
+   * commands with {@link CommandScheduler#removeComposedCommand(Command)}. The command composition
+   * returned from this method can be further decorated without issue.
    *
    * @param toRun the Runnable to run
    * @param requirements the required subsystems
@@ -134,11 +140,11 @@
   /**
    * Decorates this command with another command to run before this command starts.
    *
-   * <p>Note: This decorator works by composing this command within a CommandGroup. The command
-   * cannot be used independently after being decorated, or be re-decorated with a different
-   * decorator, unless it is manually cleared from the list of grouped commands with {@link
-   * CommandGroupBase#clearGroupedCommand(Command)}. The decorated command can, however, be further
-   * decorated without issue.
+   * <p>Note: This decorator works by adding this command to a composition. The command the
+   * decorator was called on cannot be scheduled independently or be added to a different
+   * composition (namely, decorators), unless it is manually cleared from the list of composed
+   * commands with {@link CommandScheduler#removeComposedCommand(Command)}. The command composition
+   * returned from this method can be further decorated without issue.
    *
    * @param before the command to run before this one
    * @return the decorated command
@@ -150,11 +156,11 @@
   /**
    * Decorates this command with a runnable to run after the command finishes.
    *
-   * <p>Note: This decorator works by composing this command within a CommandGroup. The command
-   * cannot be used independently after being decorated, or be re-decorated with a different
-   * decorator, unless it is manually cleared from the list of grouped commands with {@link
-   * CommandGroupBase#clearGroupedCommand(Command)}. The decorated command can, however, be further
-   * decorated without issue.
+   * <p>Note: This decorator works by adding this command to a composition. The command the
+   * decorator was called on cannot be scheduled independently or be added to a different
+   * composition (namely, decorators), unless it is manually cleared from the list of composed
+   * commands with {@link CommandScheduler#removeComposedCommand(Command)}. The command composition
+   * returned from this method can be further decorated without issue.
    *
    * @param toRun the Runnable to run
    * @param requirements the required subsystems
@@ -168,11 +174,11 @@
    * Decorates this command with a set of commands to run after it in sequence. Often more
    * convenient/less-verbose than constructing a new {@link SequentialCommandGroup} explicitly.
    *
-   * <p>Note: This decorator works by composing this command within a CommandGroup. The command
-   * cannot be used independently after being decorated, or be re-decorated with a different
-   * decorator, unless it is manually cleared from the list of grouped commands with {@link
-   * CommandGroupBase#clearGroupedCommand(Command)}. The decorated command can, however, be further
-   * decorated without issue.
+   * <p>Note: This decorator works by adding this command to a composition. The command the
+   * decorator was called on cannot be scheduled independently or be added to a different
+   * composition (namely, decorators), unless it is manually cleared from the list of composed
+   * commands with {@link CommandScheduler#removeComposedCommand(Command)}. The command composition
+   * returned from this method can be further decorated without issue.
    *
    * @param next the commands to run next
    * @return the decorated command
@@ -188,11 +194,11 @@
    * command ends and interrupting all the others. Often more convenient/less-verbose than
    * constructing a new {@link ParallelDeadlineGroup} explicitly.
    *
-   * <p>Note: This decorator works by composing this command within a CommandGroup. The command
-   * cannot be used independently after being decorated, or be re-decorated with a different
-   * decorator, unless it is manually cleared from the list of grouped commands with {@link
-   * CommandGroupBase#clearGroupedCommand(Command)}. The decorated command can, however, be further
-   * decorated without issue.
+   * <p>Note: This decorator works by adding this command to a composition. The command the
+   * decorator was called on cannot be scheduled independently or be added to a different
+   * composition (namely, decorators), unless it is manually cleared from the list of composed
+   * commands with {@link CommandScheduler#removeComposedCommand(Command)}. The command composition
+   * returned from this method can be further decorated without issue.
    *
    * @param parallel the commands to run in parallel
    * @return the decorated command
@@ -206,11 +212,11 @@
    * command ends. Often more convenient/less-verbose than constructing a new {@link
    * ParallelCommandGroup} explicitly.
    *
-   * <p>Note: This decorator works by composing this command within a CommandGroup. The command
-   * cannot be used independently after being decorated, or be re-decorated with a different
-   * decorator, unless it is manually cleared from the list of grouped commands with {@link
-   * CommandGroupBase#clearGroupedCommand(Command)}. The decorated command can, however, be further
-   * decorated without issue.
+   * <p>Note: This decorator works by adding this command to a composition. The command the
+   * decorator was called on cannot be scheduled independently or be added to a different
+   * composition (namely, decorators), unless it is manually cleared from the list of composed
+   * commands with {@link CommandScheduler#removeComposedCommand(Command)}. The command composition
+   * returned from this method can be further decorated without issue.
    *
    * @param parallel the commands to run in parallel
    * @return the decorated command
@@ -226,11 +232,11 @@
    * command ends. Often more convenient/less-verbose than constructing a new {@link
    * ParallelRaceGroup} explicitly.
    *
-   * <p>Note: This decorator works by composing this command within a CommandGroup. The command
-   * cannot be used independently after being decorated, or be re-decorated with a different
-   * decorator, unless it is manually cleared from the list of grouped commands with {@link
-   * CommandGroupBase#clearGroupedCommand(Command)}. The decorated command can, however, be further
-   * decorated without issue.
+   * <p>Note: This decorator works by adding this command to a composition. The command the
+   * decorator was called on cannot be scheduled independently or be added to a different
+   * composition (namely, decorators), unless it is manually cleared from the list of composed
+   * commands with {@link CommandScheduler#removeComposedCommand(Command)}. The command composition
+   * returned from this method can be further decorated without issue.
    *
    * @param parallel the commands to run in parallel
    * @return the decorated command
@@ -245,55 +251,147 @@
    * Decorates this command to run perpetually, ignoring its ordinary end conditions. The decorated
    * command can still be interrupted or canceled.
    *
-   * <p>Note: This decorator works by composing this command within a CommandGroup. The command
-   * cannot be used independently after being decorated, or be re-decorated with a different
-   * decorator, unless it is manually cleared from the list of grouped commands with {@link
-   * CommandGroupBase#clearGroupedCommand(Command)}. The decorated command can, however, be further
-   * decorated without issue.
+   * <p>Note: This decorator works by adding this command to a composition. The command the
+   * decorator was called on cannot be scheduled independently or be added to a different
+   * composition (namely, decorators), unless it is manually cleared from the list of composed
+   * commands with {@link CommandScheduler#removeComposedCommand(Command)}. The command composition
+   * returned from this method can be further decorated without issue.
    *
    * @return the decorated command
+   * @deprecated PerpetualCommand violates the assumption that execute() doesn't get called after
+   *     isFinished() returns true -- an assumption that should be valid. This was unsafe/undefined
+   *     behavior from the start, and RepeatCommand provides an easy way to achieve similar end
+   *     results with slightly different (and safe) semantics.
    */
+  @SuppressWarnings("removal") // PerpetualCommand
+  @Deprecated(forRemoval = true, since = "2023")
   default PerpetualCommand perpetually() {
     return new PerpetualCommand(this);
   }
 
   /**
-   * Decorates this command to run "by proxy" by wrapping it in a {@link ProxyScheduleCommand}. This
-   * is useful for "forking off" from command groups when the user does not wish to extend the
-   * command's requirements to the entire command group.
+   * Decorates this command to run repeatedly, restarting it when it ends, until this command is
+   * interrupted. The decorated command can still be canceled.
+   *
+   * <p>Note: This decorator works by adding this command to a composition. The command the
+   * decorator was called on cannot be scheduled independently or be added to a different
+   * composition (namely, decorators), unless it is manually cleared from the list of composed
+   * commands with {@link CommandScheduler#removeComposedCommand(Command)}. The command composition
+   * returned from this method can be further decorated without issue.
    *
    * @return the decorated command
    */
-  default ProxyScheduleCommand asProxy() {
-    return new ProxyScheduleCommand(this);
+  default RepeatCommand repeatedly() {
+    return new RepeatCommand(this);
   }
 
   /**
-   * Schedules this command.
+   * Decorates this command to run "by proxy" by wrapping it in a {@link ProxyCommand}. This is
+   * useful for "forking off" from command compositions when the user does not wish to extend the
+   * command's requirements to the entire command composition.
    *
-   * @param interruptible whether this command can be interrupted by another command that shares one
-   *     of its requirements
+   * @return the decorated command
    */
-  default void schedule(boolean interruptible) {
-    CommandScheduler.getInstance().schedule(interruptible, this);
-  }
-
-  /** Schedules this command, defaulting to interruptible. */
-  default void schedule() {
-    schedule(true);
+  default ProxyCommand asProxy() {
+    return new ProxyCommand(this);
   }
 
   /**
-   * Cancels this command. Will call the command's interrupted() method. Commands will be canceled
-   * even if they are not marked as interruptible.
+   * Decorates this command to only run if this condition is not met. If the command is already
+   * running and the condition changes to true, the command will not stop running. The requirements
+   * of this command will be kept for the new conditional command.
+   *
+   * @param condition the condition that will prevent the command from running
+   * @return the decorated command
+   */
+  default ConditionalCommand unless(BooleanSupplier condition) {
+    return new ConditionalCommand(new InstantCommand(), this, condition);
+  }
+
+  /**
+   * Decorates this command to run or stop when disabled.
+   *
+   * @param doesRunWhenDisabled true to run when disabled.
+   * @return the decorated command
+   */
+  default WrapperCommand ignoringDisable(boolean doesRunWhenDisabled) {
+    return new WrapperCommand(this) {
+      @Override
+      public boolean runsWhenDisabled() {
+        return doesRunWhenDisabled;
+      }
+    };
+  }
+
+  /**
+   * Decorates this command to have a different {@link InterruptionBehavior interruption behavior}.
+   *
+   * @param interruptBehavior the desired interrupt behavior
+   * @return the decorated command
+   */
+  default WrapperCommand withInterruptBehavior(InterruptionBehavior interruptBehavior) {
+    return new WrapperCommand(this) {
+      @Override
+      public InterruptionBehavior getInterruptionBehavior() {
+        return interruptBehavior;
+      }
+    };
+  }
+
+  /**
+   * Decorates this command with a lambda to call on interrupt or end, following the command's
+   * inherent {@link #end(boolean)} method.
+   *
+   * @param end a lambda accepting a boolean parameter specifying whether the command was
+   *     interrupted.
+   * @return the decorated command
+   */
+  default WrapperCommand finallyDo(BooleanConsumer end) {
+    requireNonNullParam(end, "end", "Command.finallyDo()");
+    return new WrapperCommand(this) {
+      @Override
+      public void end(boolean interrupted) {
+        super.end(interrupted);
+        end.accept(interrupted);
+      }
+    };
+  }
+
+  /**
+   * Decorates this command with a lambda to call on interrupt, following the command's inherent
+   * {@link #end(boolean)} method.
+   *
+   * @param handler a lambda to run when the command is interrupted
+   * @return the decorated command
+   */
+  default WrapperCommand handleInterrupt(Runnable handler) {
+    requireNonNullParam(handler, "handler", "Command.handleInterrupt()");
+    return finallyDo(
+        interrupted -> {
+          if (interrupted) {
+            handler.run();
+          }
+        });
+  }
+
+  /** Schedules this command. */
+  default void schedule() {
+    CommandScheduler.getInstance().schedule(this);
+  }
+
+  /**
+   * Cancels this command. Will call {@link #end(boolean) end(true)}. Commands will be canceled
+   * regardless of {@link InterruptionBehavior interruption behavior}.
+   *
+   * @see CommandScheduler#cancel(Command...)
    */
   default void cancel() {
     CommandScheduler.getInstance().cancel(this);
   }
 
   /**
-   * Whether or not the command is currently scheduled. Note that this does not detect whether the
-   * command is being run by a CommandGroup, only whether it is directly being run by the scheduler.
+   * Whether the command is currently scheduled. Note that this does not detect whether the command
+   * is in a composition, only whether it is directly being run by the scheduler.
    *
    * @return Whether the command is scheduled.
    */
@@ -312,6 +410,16 @@
   }
 
   /**
+   * How the command behaves when another command with a shared requirement is scheduled.
+   *
+   * @return a variant of {@link InterruptionBehavior}, defaulting to {@link
+   *     InterruptionBehavior#kCancelSelf kCancelSelf}.
+   */
+  default InterruptionBehavior getInterruptionBehavior() {
+    return InterruptionBehavior.kCancelSelf;
+  }
+
+  /**
    * Whether the given command should run when the robot is disabled. Override to return true if the
    * command should run when disabled.
    *
@@ -322,11 +430,46 @@
   }
 
   /**
-   * Gets the name of this Command.
+   * Gets the name of this Command. Defaults to the simple class name if not overridden.
    *
-   * @return Name
+   * @return The display name of the Command
    */
   default String getName() {
     return this.getClass().getSimpleName();
   }
+
+  /**
+   * Sets the name of this Command. Nullop if not overridden.
+   *
+   * @param name The display name of the Command.
+   */
+  default void setName(String name) {}
+
+  /**
+   * Decorates this Command with a name.
+   *
+   * @param name name
+   * @return the decorated Command
+   */
+  default WrapperCommand withName(String name) {
+    WrapperCommand wrapper = new WrapperCommand(Command.this) {};
+    wrapper.setName(name);
+    return wrapper;
+  }
+
+  /**
+   * An enum describing the command's behavior when another command with a shared requirement is
+   * scheduled.
+   */
+  enum InterruptionBehavior {
+    /**
+     * This command ends, {@link #end(boolean) end(true)} is called, and the incoming command is
+     * scheduled normally.
+     *
+     * <p>This is the default behavior.
+     */
+    kCancelSelf,
+    /** This command continues, and the incoming command is not scheduled. */
+    kCancelIncoming
+  }
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandBase.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandBase.java
index 619f330..395322a 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandBase.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandBase.java
@@ -4,6 +4,8 @@
 
 package edu.wpi.first.wpilibj2.command;
 
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
+
 import edu.wpi.first.util.sendable.Sendable;
 import edu.wpi.first.util.sendable.SendableBuilder;
 import edu.wpi.first.util.sendable.SendableRegistry;
@@ -29,7 +31,9 @@
    * @param requirements the requirements to add
    */
   public final void addRequirements(Subsystem... requirements) {
-    m_requirements.addAll(Set.of(requirements));
+    for (Subsystem requirement : requirements) {
+      m_requirements.add(requireNonNullParam(requirement, "requirement", "addRequirements"));
+    }
   }
 
   @Override
@@ -47,22 +51,12 @@
    *
    * @param name name
    */
+  @Override
   public void setName(String name) {
     SendableRegistry.setName(this, name);
   }
 
   /**
-   * Decorates this Command with a name. Is an inline function for #setName(String);
-   *
-   * @param name name
-   * @return the decorated Command
-   */
-  public CommandBase withName(String name) {
-    this.setName(name);
-    return this;
-  }
-
-  /**
    * Gets the subsystem name of this Command.
    *
    * @return Subsystem name
@@ -104,6 +98,9 @@
           }
         });
     builder.addBooleanProperty(
-        ".isParented", () -> CommandGroupBase.getGroupedCommands().contains(this), null);
+        ".isParented", () -> CommandScheduler.getInstance().isComposed(this), null);
+    builder.addStringProperty(
+        "interruptBehavior", () -> getInterruptionBehavior().toString(), null);
+    builder.addBooleanProperty("runsWhenDisabled", this::runsWhenDisabled, null);
   }
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandGroupBase.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandGroupBase.java
index ad62554..73a1342 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandGroupBase.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandGroupBase.java
@@ -4,75 +4,15 @@
 
 package edu.wpi.first.wpilibj2.command;
 
-import java.util.Collection;
-import java.util.Collections;
-import java.util.Set;
-import java.util.WeakHashMap;
-
 /**
- * A base for CommandGroups. Statically tracks commands that have been allocated to groups to ensure
- * those commands are not also used independently, which can result in inconsistent command state
- * and unpredictable execution.
+ * A base for CommandGroups.
  *
  * <p>This class is provided by the NewCommands VendorDep
+ *
+ * @deprecated This class is an empty abstraction. Inherit directly from CommandBase/Command.
  */
+@Deprecated(forRemoval = true)
 public abstract class CommandGroupBase extends CommandBase {
-  private static final Set<Command> m_groupedCommands =
-      Collections.newSetFromMap(new WeakHashMap<>());
-
-  static void registerGroupedCommands(Command... commands) {
-    m_groupedCommands.addAll(Set.of(commands));
-  }
-
-  /**
-   * Clears the list of grouped commands, allowing all commands to be freely used again.
-   *
-   * <p>WARNING: Using this haphazardly can result in unexpected/undesirable behavior. Do not use
-   * this unless you fully understand what you are doing.
-   */
-  public static void clearGroupedCommands() {
-    m_groupedCommands.clear();
-  }
-
-  /**
-   * Removes a single command from the list of grouped commands, allowing it to be freely used
-   * again.
-   *
-   * <p>WARNING: Using this haphazardly can result in unexpected/undesirable behavior. Do not use
-   * this unless you fully understand what you are doing.
-   *
-   * @param command the command to remove from the list of grouped commands
-   */
-  public static void clearGroupedCommand(Command command) {
-    m_groupedCommands.remove(command);
-  }
-
-  /**
-   * Requires that the specified commands not have been already allocated to a CommandGroup. Throws
-   * an {@link IllegalArgumentException} if commands have been allocated.
-   *
-   * @param commands The commands to check
-   */
-  public static void requireUngrouped(Command... commands) {
-    requireUngrouped(Set.of(commands));
-  }
-
-  /**
-   * Requires that the specified commands not have been already allocated to a CommandGroup. Throws
-   * an {@link IllegalArgumentException} if commands have been allocated.
-   *
-   * @param commands The commands to check
-   */
-  public static void requireUngrouped(Collection<Command> commands) {
-    if (!Collections.disjoint(commands, getGroupedCommands())) {
-      throw new IllegalArgumentException("Commands cannot be added to more than one CommandGroup");
-    }
-  }
-
-  static Set<Command> getGroupedCommands() {
-    return m_groupedCommands;
-  }
-
   /**
    * Adds the given commands to the command group.
    *
@@ -85,8 +25,10 @@
    *
    * @param commands the commands to include
    * @return the command group
+   * @deprecated Replace with {@link Commands#sequence(Command...)}
    */
-  public static CommandGroupBase sequence(Command... commands) {
+  @Deprecated
+  public static SequentialCommandGroup sequence(Command... commands) {
     return new SequentialCommandGroup(commands);
   }
 
@@ -95,8 +37,10 @@
    *
    * @param commands the commands to include
    * @return the command group
+   * @deprecated Replace with {@link Commands#parallel(Command...)}
    */
-  public static CommandGroupBase parallel(Command... commands) {
+  @Deprecated
+  public static ParallelCommandGroup parallel(Command... commands) {
     return new ParallelCommandGroup(commands);
   }
 
@@ -105,8 +49,10 @@
    *
    * @param commands the commands to include
    * @return the command group
+   * @deprecated Replace with {@link Commands#race(Command...)}
    */
-  public static CommandGroupBase race(Command... commands) {
+  @Deprecated
+  public static ParallelRaceGroup race(Command... commands) {
     return new ParallelRaceGroup(commands);
   }
 
@@ -116,8 +62,10 @@
    * @param deadline the deadline command
    * @param commands the commands to include
    * @return the command group
+   * @deprecated Replace with {@link Commands#deadline(Command, Command...)}
    */
-  public static CommandGroupBase deadline(Command deadline, Command... commands) {
+  @Deprecated
+  public static ParallelDeadlineGroup deadline(Command deadline, Command... commands) {
     return new ParallelDeadlineGroup(deadline, commands);
   }
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandScheduler.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandScheduler.java
index b5c2d3c..15c8606 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandScheduler.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandScheduler.java
@@ -4,18 +4,27 @@
 
 package edu.wpi.first.wpilibj2.command;
 
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
+
 import edu.wpi.first.hal.FRCNetComm.tInstances;
 import edu.wpi.first.hal.FRCNetComm.tResourceType;
 import edu.wpi.first.hal.HAL;
+import edu.wpi.first.networktables.IntegerArrayEntry;
+import edu.wpi.first.networktables.IntegerArrayPublisher;
+import edu.wpi.first.networktables.IntegerArrayTopic;
 import edu.wpi.first.networktables.NTSendable;
 import edu.wpi.first.networktables.NTSendableBuilder;
-import edu.wpi.first.networktables.NetworkTableEntry;
+import edu.wpi.first.networktables.StringArrayPublisher;
+import edu.wpi.first.networktables.StringArrayTopic;
 import edu.wpi.first.util.sendable.SendableRegistry;
+import edu.wpi.first.wpilibj.DriverStation;
 import edu.wpi.first.wpilibj.RobotBase;
 import edu.wpi.first.wpilibj.RobotState;
 import edu.wpi.first.wpilibj.TimedRobot;
 import edu.wpi.first.wpilibj.Watchdog;
+import edu.wpi.first.wpilibj.event.EventLoop;
 import edu.wpi.first.wpilibj.livewindow.LiveWindow;
+import edu.wpi.first.wpilibj2.command.Command.InterruptionBehavior;
 import java.util.ArrayList;
 import java.util.Collection;
 import java.util.Collections;
@@ -25,6 +34,7 @@
 import java.util.List;
 import java.util.Map;
 import java.util.Set;
+import java.util.WeakHashMap;
 import java.util.function.Consumer;
 
 /**
@@ -52,11 +62,12 @@
     return instance;
   }
 
-  // A map from commands to their scheduling state.  Also used as a set of the currently-running
-  // commands.
-  private final Map<Command, CommandState> m_scheduledCommands = new LinkedHashMap<>();
+  private final Set<Command> m_composedCommands = Collections.newSetFromMap(new WeakHashMap<>());
 
-  // A map from required subsystems to their requiring commands.  Also used as a set of the
+  // A set of the currently-running commands.
+  private final Set<Command> m_scheduledCommands = new LinkedHashSet<>();
+
+  // A map from required subsystems to their requiring commands. Also used as a set of the
   // currently-required subsystems.
   private final Map<Subsystem, Command> m_requirements = new LinkedHashMap<>();
 
@@ -64,8 +75,9 @@
   // as a list of currently-registered subsystems.
   private final Map<Subsystem, Command> m_subsystems = new LinkedHashMap<>();
 
+  private final EventLoop m_defaultButtonLoop = new EventLoop();
   // The set of currently-registered buttons that will be polled every iteration.
-  private final Collection<Runnable> m_buttons = new LinkedHashSet<>();
+  private EventLoop m_activeButtonLoop = m_defaultButtonLoop;
 
   private boolean m_disabled;
 
@@ -78,7 +90,7 @@
   // Flag and queues for avoiding ConcurrentModificationException if commands are
   // scheduled/canceled during run
   private boolean m_inRunLoop;
-  private final Map<Command, Boolean> m_toSchedule = new LinkedHashMap<>();
+  private final Set<Command> m_toSchedule = new LinkedHashSet<>();
   private final List<Command> m_toCancel = new ArrayList<>();
 
   private final Watchdog m_watchdog = new Watchdog(TimedRobot.kDefaultPeriod, () -> {});
@@ -91,14 +103,11 @@
           disable();
           cancelAll();
         });
-    LiveWindow.setDisabledListener(
-        () -> {
-          enable();
-        });
+    LiveWindow.setDisabledListener(this::enable);
   }
 
   /**
-   * Changes the period of the loop overrun watchdog. This should be be kept in sync with the
+   * Changes the period of the loop overrun watchdog. This should be kept in sync with the
    * TimedRobot period.
    *
    * @param period Period in seconds.
@@ -115,33 +124,66 @@
   }
 
   /**
+   * Get the default button poll.
+   *
+   * @return a reference to the default {@link EventLoop} object polling buttons.
+   */
+  public EventLoop getDefaultButtonLoop() {
+    return m_defaultButtonLoop;
+  }
+
+  /**
+   * Get the active button poll.
+   *
+   * @return a reference to the current {@link EventLoop} object polling buttons.
+   */
+  public EventLoop getActiveButtonLoop() {
+    return m_activeButtonLoop;
+  }
+
+  /**
+   * Replace the button poll with another one.
+   *
+   * @param loop the new button polling loop object.
+   */
+  public void setActiveButtonLoop(EventLoop loop) {
+    m_activeButtonLoop =
+        requireNonNullParam(loop, "loop", "CommandScheduler" + ".replaceButtonEventLoop");
+  }
+
+  /**
    * Adds a button binding to the scheduler, which will be polled to schedule commands.
    *
    * @param button The button to add
+   * @deprecated Use {@link edu.wpi.first.wpilibj2.command.button.Trigger}
    */
+  @Deprecated(since = "2023")
   public void addButton(Runnable button) {
-    m_buttons.add(button);
+    m_activeButtonLoop.bind(requireNonNullParam(button, "button", "addButton"));
   }
 
-  /** Removes all button bindings from the scheduler. */
+  /**
+   * Removes all button bindings from the scheduler.
+   *
+   * @deprecated call {@link EventLoop#clear()} on {@link #getActiveButtonLoop()} directly instead.
+   */
+  @Deprecated(since = "2023")
   public void clearButtons() {
-    m_buttons.clear();
+    m_activeButtonLoop.clear();
   }
 
   /**
    * Initializes a given command, adds its requirements to the list, and performs the init actions.
    *
    * @param command The command to initialize
-   * @param interruptible Whether the command is interruptible
    * @param requirements The command requirements
    */
-  private void initCommand(Command command, boolean interruptible, Set<Subsystem> requirements) {
-    CommandState scheduledCommand = new CommandState(interruptible);
-    m_scheduledCommands.put(command, scheduledCommand);
-    command.initialize();
+  private void initCommand(Command command, Set<Subsystem> requirements) {
+    m_scheduledCommands.add(command);
     for (Subsystem requirement : requirements) {
       m_requirements.put(requirement, command);
     }
+    command.initialize();
     for (Consumer<Command> action : m_initActions) {
       action.accept(command);
     }
@@ -155,25 +197,25 @@
    * using those requirements have been scheduled as interruptible. If this is the case, they will
    * be interrupted and the command will be scheduled.
    *
-   * @param interruptible whether this command can be interrupted
-   * @param command the command to schedule
+   * @param command the command to schedule. If null, no-op.
    */
-  private void schedule(boolean interruptible, Command command) {
+  private void schedule(Command command) {
+    if (command == null) {
+      DriverStation.reportWarning("Tried to schedule a null command", true);
+      return;
+    }
     if (m_inRunLoop) {
-      m_toSchedule.put(command, interruptible);
+      m_toSchedule.add(command);
       return;
     }
 
-    if (CommandGroupBase.getGroupedCommands().contains(command)) {
-      throw new IllegalArgumentException(
-          "A command that is part of a command group cannot be independently scheduled");
-    }
+    requireNotComposed(command);
 
     // Do nothing if the scheduler is disabled, the robot is disabled and the command doesn't
     // run when disabled, or the command is already scheduled.
     if (m_disabled
-        || RobotState.isDisabled() && !command.runsWhenDisabled()
-        || m_scheduledCommands.containsKey(command)) {
+        || isScheduled(command)
+        || RobotState.isDisabled() && !command.runsWhenDisabled()) {
       return;
     }
 
@@ -181,48 +223,36 @@
 
     // Schedule the command if the requirements are not currently in-use.
     if (Collections.disjoint(m_requirements.keySet(), requirements)) {
-      initCommand(command, interruptible, requirements);
+      initCommand(command, requirements);
     } else {
       // Else check if the requirements that are in use have all have interruptible commands,
       // and if so, interrupt those commands and schedule the new command.
       for (Subsystem requirement : requirements) {
-        if (m_requirements.containsKey(requirement)
-            && !m_scheduledCommands.get(m_requirements.get(requirement)).isInterruptible()) {
+        Command requiring = requiring(requirement);
+        if (requiring != null
+            && requiring.getInterruptionBehavior() == InterruptionBehavior.kCancelIncoming) {
           return;
         }
       }
       for (Subsystem requirement : requirements) {
-        if (m_requirements.containsKey(requirement)) {
-          cancel(m_requirements.get(requirement));
+        Command requiring = requiring(requirement);
+        if (requiring != null) {
+          cancel(requiring);
         }
       }
-      initCommand(command, interruptible, requirements);
+      initCommand(command, requirements);
     }
   }
 
   /**
-   * Schedules multiple commands for execution. Does nothing if the command is already scheduled. If
-   * a command's requirements are not available, it will only be started if all the commands
-   * currently using those requirements have been scheduled as interruptible. If this is the case,
-   * they will be interrupted and the command will be scheduled.
+   * Schedules multiple commands for execution. Does nothing for commands already scheduled.
    *
-   * @param interruptible whether the commands should be interruptible
-   * @param commands the commands to schedule
-   */
-  public void schedule(boolean interruptible, Command... commands) {
-    for (Command command : commands) {
-      schedule(interruptible, command);
-    }
-  }
-
-  /**
-   * Schedules multiple commands for execution, with interruptible defaulted to true. Does nothing
-   * if the command is already scheduled.
-   *
-   * @param commands the commands to schedule
+   * @param commands the commands to schedule. No-op on null.
    */
   public void schedule(Command... commands) {
-    schedule(true, commands);
+    for (Command command : commands) {
+      schedule(command);
+    }
   }
 
   /**
@@ -254,16 +284,16 @@
       m_watchdog.addEpoch(subsystem.getClass().getSimpleName() + ".periodic()");
     }
 
+    // Cache the active instance to avoid concurrency problems if setActiveLoop() is called from
+    // inside the button bindings.
+    EventLoop loopCache = m_activeButtonLoop;
     // Poll buttons for new commands to add.
-    for (Runnable button : m_buttons) {
-      button.run();
-    }
+    loopCache.poll();
     m_watchdog.addEpoch("buttons.run()");
 
     m_inRunLoop = true;
     // Run scheduled commands, remove finished commands.
-    for (Iterator<Command> iterator = m_scheduledCommands.keySet().iterator();
-        iterator.hasNext(); ) {
+    for (Iterator<Command> iterator = m_scheduledCommands.iterator(); iterator.hasNext(); ) {
       Command command = iterator.next();
 
       if (!command.runsWhenDisabled() && RobotState.isDisabled()) {
@@ -296,8 +326,8 @@
     m_inRunLoop = false;
 
     // Schedule/cancel commands from queues populated during loop
-    for (Map.Entry<Command, Boolean> commandInterruptible : m_toSchedule.entrySet()) {
-      schedule(commandInterruptible.getValue(), commandInterruptible.getKey());
+    for (Command command : m_toSchedule) {
+      schedule(command);
     }
 
     for (Command command : m_toCancel) {
@@ -331,6 +361,14 @@
    */
   public void registerSubsystem(Subsystem... subsystems) {
     for (Subsystem subsystem : subsystems) {
+      if (subsystem == null) {
+        DriverStation.reportWarning("Tried to register a null subsystem", true);
+        continue;
+      }
+      if (m_subsystems.containsKey(subsystem)) {
+        DriverStation.reportWarning("Tried to register an already-registered subsystem", true);
+        continue;
+      }
       m_subsystems.put(subsystem, null);
     }
   }
@@ -356,18 +394,49 @@
    * @param defaultCommand the default command to associate with the subsystem
    */
   public void setDefaultCommand(Subsystem subsystem, Command defaultCommand) {
+    if (subsystem == null) {
+      DriverStation.reportWarning("Tried to set a default command for a null subsystem", true);
+      return;
+    }
+    if (defaultCommand == null) {
+      DriverStation.reportWarning("Tried to set a null default command", true);
+      return;
+    }
+
+    requireNotComposed(defaultCommand);
+
     if (!defaultCommand.getRequirements().contains(subsystem)) {
       throw new IllegalArgumentException("Default commands must require their subsystem!");
     }
 
-    if (defaultCommand.isFinished()) {
-      throw new IllegalArgumentException("Default commands should not end!");
+    if (defaultCommand.getInterruptionBehavior() == InterruptionBehavior.kCancelIncoming) {
+      DriverStation.reportWarning(
+          "Registering a non-interruptible default command!\n"
+              + "This will likely prevent any other commands from requiring this subsystem.",
+          true);
+      // Warn, but allow -- there might be a use case for this.
     }
 
     m_subsystems.put(subsystem, defaultCommand);
   }
 
   /**
+   * Removes the default command for a subsystem. The current default command will run until another
+   * command is scheduled that requires the subsystem, at which point the current default command
+   * will not be re-scheduled.
+   *
+   * @param subsystem the subsystem whose default command will be removed
+   */
+  public void removeDefaultCommand(Subsystem subsystem) {
+    if (subsystem == null) {
+      DriverStation.reportWarning("Tried to remove a default command for a null subsystem", true);
+      return;
+    }
+
+    m_subsystems.put(subsystem, null);
+  }
+
+  /**
    * Gets the default command associated with this subsystem. Null if this subsystem has no default
    * command associated with it.
    *
@@ -383,7 +452,7 @@
    * canceled command with {@code true}, indicating they were canceled (as opposed to finishing
    * normally).
    *
-   * <p>Commands will be canceled even if they are not scheduled as interruptible.
+   * <p>Commands will be canceled regardless of {@link InterruptionBehavior interruption behavior}.
    *
    * @param commands the commands to cancel
    */
@@ -394,54 +463,40 @@
     }
 
     for (Command command : commands) {
-      if (!m_scheduledCommands.containsKey(command)) {
+      if (command == null) {
+        DriverStation.reportWarning("Tried to cancel a null command", true);
+        continue;
+      }
+      if (!isScheduled(command)) {
         continue;
       }
 
+      m_scheduledCommands.remove(command);
+      m_requirements.keySet().removeAll(command.getRequirements());
       command.end(true);
       for (Consumer<Command> action : m_interruptActions) {
         action.accept(command);
       }
-      m_scheduledCommands.remove(command);
-      m_requirements.keySet().removeAll(command.getRequirements());
       m_watchdog.addEpoch(command.getName() + ".end(true)");
     }
   }
 
   /** Cancels all commands that are currently scheduled. */
   public void cancelAll() {
-    for (Command command : m_scheduledCommands.keySet().toArray(new Command[0])) {
-      cancel(command);
-    }
-  }
-
-  /**
-   * Returns the time since a given command was scheduled. Note that this only works on commands
-   * that are directly scheduled by the scheduler; it will not work on commands inside of
-   * commandgroups, as the scheduler does not see them.
-   *
-   * @param command the command to query
-   * @return the time since the command was scheduled, in seconds
-   */
-  public double timeSinceScheduled(Command command) {
-    CommandState commandState = m_scheduledCommands.get(command);
-    if (commandState != null) {
-      return commandState.timeSinceInitialized();
-    } else {
-      return -1;
-    }
+    // Copy to array to avoid concurrent modification.
+    cancel(m_scheduledCommands.toArray(new Command[0]));
   }
 
   /**
    * Whether the given commands are running. Note that this only works on commands that are directly
-   * scheduled by the scheduler; it will not work on commands inside of CommandGroups, as the
-   * scheduler does not see them.
+   * scheduled by the scheduler; it will not work on commands inside compositions, as the scheduler
+   * does not see them.
    *
    * @param commands the command to query
    * @return whether the command is currently scheduled
    */
   public boolean isScheduled(Command... commands) {
-    return m_scheduledCommands.keySet().containsAll(Set.of(commands));
+    return m_scheduledCommands.containsAll(Set.of(commands));
   }
 
   /**
@@ -472,7 +527,7 @@
    * @param action the action to perform
    */
   public void onCommandInitialize(Consumer<Command> action) {
-    m_initActions.add(action);
+    m_initActions.add(requireNonNullParam(action, "action", "onCommandInitialize"));
   }
 
   /**
@@ -481,7 +536,7 @@
    * @param action the action to perform
    */
   public void onCommandExecute(Consumer<Command> action) {
-    m_executeActions.add(action);
+    m_executeActions.add(requireNonNullParam(action, "action", "onCommandExecute"));
   }
 
   /**
@@ -490,7 +545,7 @@
    * @param action the action to perform
    */
   public void onCommandInterrupt(Consumer<Command> action) {
-    m_interruptActions.add(action);
+    m_interruptActions.add(requireNonNullParam(action, "action", "onCommandInterrupt"));
   }
 
   /**
@@ -499,42 +554,128 @@
    * @param action the action to perform
    */
   public void onCommandFinish(Consumer<Command> action) {
-    m_finishActions.add(action);
+    m_finishActions.add(requireNonNullParam(action, "action", "onCommandFinish"));
+  }
+
+  /**
+   * Register commands as composed. An exception will be thrown if these commands are scheduled
+   * directly or added to a composition.
+   *
+   * @param commands the commands to register
+   * @throws IllegalArgumentException if the given commands have already been composed.
+   */
+  public void registerComposedCommands(Command... commands) {
+    var commandSet = Set.of(commands);
+    requireNotComposed(commandSet);
+    m_composedCommands.addAll(commandSet);
+  }
+
+  /**
+   * Clears the list of composed commands, allowing all commands to be freely used again.
+   *
+   * <p>WARNING: Using this haphazardly can result in unexpected/undesirable behavior. Do not use
+   * this unless you fully understand what you are doing.
+   */
+  public void clearComposedCommands() {
+    m_composedCommands.clear();
+  }
+
+  /**
+   * Removes a single command from the list of composed commands, allowing it to be freely used
+   * again.
+   *
+   * <p>WARNING: Using this haphazardly can result in unexpected/undesirable behavior. Do not use
+   * this unless you fully understand what you are doing.
+   *
+   * @param command the command to remove from the list of grouped commands
+   */
+  public void removeComposedCommand(Command command) {
+    m_composedCommands.remove(command);
+  }
+
+  /**
+   * Requires that the specified command hasn't been already added to a composition.
+   *
+   * @param command The command to check
+   * @throws IllegalArgumentException if the given commands have already been composed.
+   */
+  public void requireNotComposed(Command command) {
+    if (m_composedCommands.contains(command)) {
+      throw new IllegalArgumentException(
+          "Commands that have been composed may not be added to another composition or scheduled"
+              + "individually!");
+    }
+  }
+
+  /**
+   * Requires that the specified commands not have been already added to a composition.
+   *
+   * @param commands The commands to check
+   * @throws IllegalArgumentException if the given commands have already been composed.
+   */
+  public void requireNotComposed(Collection<Command> commands) {
+    if (!Collections.disjoint(commands, getComposedCommands())) {
+      throw new IllegalArgumentException(
+          "Commands that have been composed may not be added to another composition or scheduled"
+              + "individually!");
+    }
+  }
+
+  /**
+   * Check if the given command has been composed.
+   *
+   * @param command The command to check
+   * @return true if composed
+   * @throws IllegalArgumentException if the given commands have already been composed.
+   */
+  public boolean isComposed(Command command) {
+    return getComposedCommands().contains(command);
+  }
+
+  Set<Command> getComposedCommands() {
+    return m_composedCommands;
   }
 
   @Override
   public void initSendable(NTSendableBuilder builder) {
     builder.setSmartDashboardType("Scheduler");
-    final NetworkTableEntry namesEntry = builder.getEntry("Names");
-    final NetworkTableEntry idsEntry = builder.getEntry("Ids");
-    final NetworkTableEntry cancelEntry = builder.getEntry("Cancel");
+    final StringArrayPublisher namesPub = new StringArrayTopic(builder.getTopic("Names")).publish();
+    final IntegerArrayPublisher idsPub = new IntegerArrayTopic(builder.getTopic("Ids")).publish();
+    final IntegerArrayEntry cancelEntry =
+        new IntegerArrayTopic(builder.getTopic("Cancel")).getEntry(new long[] {});
+    builder.addCloseable(namesPub);
+    builder.addCloseable(idsPub);
+    builder.addCloseable(cancelEntry);
     builder.setUpdateTable(
         () -> {
-          if (namesEntry == null || idsEntry == null || cancelEntry == null) {
+          if (namesPub == null || idsPub == null || cancelEntry == null) {
             return;
           }
 
-          Map<Double, Command> ids = new LinkedHashMap<>();
+          Map<Long, Command> ids = new LinkedHashMap<>();
+          List<String> names = new ArrayList<>();
+          long[] ids2 = new long[m_scheduledCommands.size()];
 
-          for (Command command : m_scheduledCommands.keySet()) {
-            ids.put((double) command.hashCode(), command);
+          int i = 0;
+          for (Command command : m_scheduledCommands) {
+            long id = command.hashCode();
+            ids.put(id, command);
+            names.add(command.getName());
+            ids2[i] = id;
+            i++;
           }
 
-          double[] toCancel = cancelEntry.getDoubleArray(new double[0]);
+          long[] toCancel = cancelEntry.get();
           if (toCancel.length > 0) {
-            for (double hash : toCancel) {
+            for (long hash : toCancel) {
               cancel(ids.get(hash));
               ids.remove(hash);
             }
-            cancelEntry.setDoubleArray(new double[0]);
+            cancelEntry.set(new long[] {});
           }
 
-          List<String> names = new ArrayList<>();
-
-          ids.values().forEach(command -> names.add(command.getName()));
-
-          namesEntry.setStringArray(names.toArray(new String[0]));
-          idsEntry.setNumberArray(ids.keySet().toArray(new Double[0]));
+          namesPub.set(names.toArray(new String[] {}));
+          idsPub.set(ids2);
         });
   }
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandState.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandState.java
deleted file mode 100644
index 173bc54..0000000
--- a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandState.java
+++ /dev/null
@@ -1,42 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj2.command;
-
-import edu.wpi.first.wpilibj.Timer;
-
-/**
- * Class that holds scheduling state for a command. Used internally by the {@link CommandScheduler}.
- *
- * <p>This class is provided by the NewCommands VendorDep
- */
-class CommandState {
-  // The time since this command was initialized.
-  private double m_startTime = -1;
-
-  // Whether or not it is interruptible.
-  private final boolean m_interruptible;
-
-  CommandState(boolean interruptible) {
-    m_interruptible = interruptible;
-    startTiming();
-    startRunning();
-  }
-
-  private void startTiming() {
-    m_startTime = Timer.getFPGATimestamp();
-  }
-
-  synchronized void startRunning() {
-    m_startTime = -1;
-  }
-
-  boolean isInterruptible() {
-    return m_interruptible;
-  }
-
-  double timeSinceInitialized() {
-    return m_startTime != -1 ? Timer.getFPGATimestamp() - m_startTime : -1;
-  }
-}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Commands.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Commands.java
new file mode 100644
index 0000000..737b9cc
--- /dev/null
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Commands.java
@@ -0,0 +1,210 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj2.command;
+
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
+
+import java.util.Map;
+import java.util.function.BooleanSupplier;
+import java.util.function.Supplier;
+
+/**
+ * Namespace for command factory methods.
+ *
+ * <p>For convenience, you might want to static import the members of this class.
+ */
+public final class Commands {
+  /**
+   * Constructs a command that does nothing, finishing immediately.
+   *
+   * @return the command
+   */
+  public static CommandBase none() {
+    return new InstantCommand();
+  }
+
+  // Action Commands
+
+  /**
+   * Constructs a command that runs an action once and finishes.
+   *
+   * @param action the action to run
+   * @param requirements subsystems the action requires
+   * @return the command
+   * @see InstantCommand
+   */
+  public static CommandBase runOnce(Runnable action, Subsystem... requirements) {
+    return new InstantCommand(action, requirements);
+  }
+
+  /**
+   * Constructs a command that runs an action every iteration until interrupted.
+   *
+   * @param action the action to run
+   * @param requirements subsystems the action requires
+   * @return the command
+   * @see RunCommand
+   */
+  public static CommandBase run(Runnable action, Subsystem... requirements) {
+    return new RunCommand(action, requirements);
+  }
+
+  /**
+   * Constructs a command that runs an action once and another action when the command is
+   * interrupted.
+   *
+   * @param start the action to run on start
+   * @param end the action to run on interrupt
+   * @param requirements subsystems the action requires
+   * @return the command
+   * @see StartEndCommand
+   */
+  public static CommandBase startEnd(Runnable start, Runnable end, Subsystem... requirements) {
+    return new StartEndCommand(start, end, requirements);
+  }
+
+  /**
+   * Constructs a command that runs an action every iteration until interrupted, and then runs a
+   * second action.
+   *
+   * @param run the action to run every iteration
+   * @param end the action to run on interrupt
+   * @param requirements subsystems the action requires
+   * @return the command
+   */
+  public static CommandBase runEnd(Runnable run, Runnable end, Subsystem... requirements) {
+    requireNonNullParam(end, "end", "Command.runEnd");
+    return new FunctionalCommand(
+        () -> {}, run, interrupted -> end.run(), () -> false, requirements);
+  }
+
+  /**
+   * Constructs a command that prints a message and finishes.
+   *
+   * @param message the message to print
+   * @return the command
+   * @see PrintCommand
+   */
+  public static CommandBase print(String message) {
+    return new PrintCommand(message);
+  }
+
+  // Idling Commands
+
+  /**
+   * Constructs a command that does nothing, finishing after a specified duration.
+   *
+   * @param seconds after how long the command finishes
+   * @return the command
+   * @see WaitCommand
+   */
+  public static CommandBase waitSeconds(double seconds) {
+    return new WaitCommand(seconds);
+  }
+
+  /**
+   * Constructs a command that does nothing, finishing once a condition becomes true.
+   *
+   * @param condition the condition
+   * @return the command
+   * @see WaitUntilCommand
+   */
+  public static CommandBase waitUntil(BooleanSupplier condition) {
+    return new WaitUntilCommand(condition);
+  }
+
+  // Selector Commands
+
+  /**
+   * Runs one of two commands, based on the boolean selector function.
+   *
+   * @param onTrue the command to run if the selector function returns true
+   * @param onFalse the command to run if the selector function returns false
+   * @param selector the selector function
+   * @return the command
+   * @see ConditionalCommand
+   */
+  public static CommandBase either(Command onTrue, Command onFalse, BooleanSupplier selector) {
+    return new ConditionalCommand(onTrue, onFalse, selector);
+  }
+
+  /**
+   * Runs one of several commands, based on the selector function.
+   *
+   * @param selector the selector function
+   * @param commands map of commands to select from
+   * @return the command
+   * @see SelectCommand
+   */
+  public static CommandBase select(Map<Object, Command> commands, Supplier<Object> selector) {
+    return new SelectCommand(commands, selector);
+  }
+
+  /**
+   * Runs a group of commands in series, one after the other.
+   *
+   * @param commands the commands to include
+   * @return the command group
+   * @see SequentialCommandGroup
+   */
+  public static CommandBase sequence(Command... commands) {
+    return new SequentialCommandGroup(commands);
+  }
+
+  // Command Groups
+
+  /**
+   * Runs a group of commands in series, one after the other. Once the last command ends, the group
+   * is restarted.
+   *
+   * @param commands the commands to include
+   * @return the command group
+   * @see SequentialCommandGroup
+   * @see Command#repeatedly()
+   */
+  public static CommandBase repeatingSequence(Command... commands) {
+    return sequence(commands).repeatedly();
+  }
+
+  /**
+   * Runs a group of commands at the same time. Ends once all commands in the group finish.
+   *
+   * @param commands the commands to include
+   * @return the command
+   * @see ParallelCommandGroup
+   */
+  public static CommandBase parallel(Command... commands) {
+    return new ParallelCommandGroup(commands);
+  }
+
+  /**
+   * Runs a group of commands at the same time. Ends once any command in the group finishes, and
+   * cancels the others.
+   *
+   * @param commands the commands to include
+   * @return the command group
+   * @see ParallelRaceGroup
+   */
+  public static CommandBase race(Command... commands) {
+    return new ParallelRaceGroup(commands);
+  }
+
+  /**
+   * Runs a group of commands at the same time. Ends once a specific command finishes, and cancels
+   * the others.
+   *
+   * @param deadline the deadline command
+   * @param commands the commands to include
+   * @return the command group
+   * @see ParallelDeadlineGroup
+   */
+  public static CommandBase deadline(Command deadline, Command... commands) {
+    return new ParallelDeadlineGroup(deadline, commands);
+  }
+
+  private Commands() {
+    throw new UnsupportedOperationException("This is a utility class");
+  }
+}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ConditionalCommand.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ConditionalCommand.java
index 18d392a..782f217 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ConditionalCommand.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ConditionalCommand.java
@@ -4,23 +4,18 @@
 
 package edu.wpi.first.wpilibj2.command;
 
-import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
-import static edu.wpi.first.wpilibj2.command.CommandGroupBase.requireUngrouped;
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
 
+import edu.wpi.first.util.sendable.SendableBuilder;
 import java.util.function.BooleanSupplier;
 
 /**
- * Runs one of two commands, depending on the value of the given condition when this command is
- * initialized. Does not actually schedule the selected command - rather, the command is run through
- * this command; this ensures that the command will behave as expected if used as part of a
- * CommandGroup. Requires the requirements of both commands, again to ensure proper functioning when
- * used in a CommandGroup. If this is undesired, consider using {@link ScheduleCommand}.
+ * A command composition that runs one of two commands, depending on the value of the given
+ * condition when this command is initialized.
  *
- * <p>As this command contains multiple component commands within it, it is technically a command
- * group; the command instances that are passed to it cannot be added to any other groups, or
- * scheduled individually.
- *
- * <p>As a rule, CommandGroups require the union of the requirements of their component commands.
+ * <p>The rules for command compositions apply: command instances that are passed to it cannot be
+ * added to any other composition or scheduled individually, and the composition requires all
+ * subsystems its components require.
  *
  * <p>This class is provided by the NewCommands VendorDep
  */
@@ -38,13 +33,12 @@
    * @param condition the condition to determine which command to run
    */
   public ConditionalCommand(Command onTrue, Command onFalse, BooleanSupplier condition) {
-    requireUngrouped(onTrue, onFalse);
-
-    CommandGroupBase.registerGroupedCommands(onTrue, onFalse);
-
-    m_onTrue = onTrue;
-    m_onFalse = onFalse;
+    m_onTrue = requireNonNullParam(onTrue, "onTrue", "ConditionalCommand");
+    m_onFalse = requireNonNullParam(onFalse, "onFalse", "ConditionalCommand");
     m_condition = requireNonNullParam(condition, "condition", "ConditionalCommand");
+
+    CommandScheduler.getInstance().registerComposedCommands(onTrue, onFalse);
+
     m_requirements.addAll(m_onTrue.getRequirements());
     m_requirements.addAll(m_onFalse.getRequirements());
   }
@@ -78,4 +72,21 @@
   public boolean runsWhenDisabled() {
     return m_onTrue.runsWhenDisabled() && m_onFalse.runsWhenDisabled();
   }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    super.initSendable(builder);
+    builder.addStringProperty("onTrue", m_onTrue::getName, null);
+    builder.addStringProperty("onFalse", m_onFalse::getName, null);
+    builder.addStringProperty(
+        "selected",
+        () -> {
+          if (m_selectedCommand == null) {
+            return "null";
+          } else {
+            return m_selectedCommand.getName();
+          }
+        },
+        null);
+  }
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/FunctionalCommand.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/FunctionalCommand.java
index d235bfe..fcd4bd7 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/FunctionalCommand.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/FunctionalCommand.java
@@ -4,7 +4,7 @@
 
 package edu.wpi.first.wpilibj2.command;
 
-import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
 
 import java.util.function.BooleanSupplier;
 import java.util.function.Consumer;
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/InstantCommand.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/InstantCommand.java
index 586a2d5..25f7c9a 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/InstantCommand.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/InstantCommand.java
@@ -4,8 +4,6 @@
 
 package edu.wpi.first.wpilibj2.command;
 
-import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
-
 /**
  * A Command that runs instantly; it will initialize, execute once, and end on the same iteration of
  * the scheduler. Users can either pass in a Runnable and a set of requirements, or else subclass
@@ -13,9 +11,7 @@
  *
  * <p>This class is provided by the NewCommands VendorDep
  */
-public class InstantCommand extends CommandBase {
-  private final Runnable m_toRun;
-
+public class InstantCommand extends FunctionalCommand {
   /**
    * Creates a new InstantCommand that runs the given Runnable with the given requirements.
    *
@@ -23,9 +19,7 @@
    * @param requirements the subsystems required by this command
    */
   public InstantCommand(Runnable toRun, Subsystem... requirements) {
-    m_toRun = requireNonNullParam(toRun, "toRun", "InstantCommand");
-
-    addRequirements(requirements);
+    super(toRun, () -> {}, interrupted -> {}, () -> true, requirements);
   }
 
   /**
@@ -33,16 +27,6 @@
    * constructor to call implicitly from subclass constructors.
    */
   public InstantCommand() {
-    m_toRun = () -> {};
-  }
-
-  @Override
-  public void initialize() {
-    m_toRun.run();
-  }
-
-  @Override
-  public final boolean isFinished() {
-    return true;
+    this(() -> {});
   }
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/MecanumControllerCommand.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/MecanumControllerCommand.java
index 18c2a37..f6b6668 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/MecanumControllerCommand.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/MecanumControllerCommand.java
@@ -4,7 +4,7 @@
 
 package edu.wpi.first.wpilibj2.command;
 
-import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
 
 import edu.wpi.first.math.controller.HolonomicDriveController;
 import edu.wpi.first.math.controller.PIDController;
@@ -38,7 +38,6 @@
  *
  * <p>This class is provided by the NewCommands VendorDep
  */
-@SuppressWarnings("MemberName")
 public class MecanumControllerCommand extends CommandBase {
   private final Timer m_timer = new Timer();
   private final boolean m_usePID;
@@ -87,7 +86,6 @@
    *     voltages.
    * @param requirements The subsystems to require.
    */
-  @SuppressWarnings("ParameterName")
   public MecanumControllerCommand(
       Trajectory trajectory,
       Supplier<Pose2d> pose,
@@ -119,11 +117,7 @@
     m_desiredRotation =
         requireNonNullParam(desiredRotation, "desiredRotation", "MecanumControllerCommand");
 
-    m_maxWheelVelocityMetersPerSecond =
-        requireNonNullParam(
-            maxWheelVelocityMetersPerSecond,
-            "maxWheelVelocityMetersPerSecond",
-            "MecanumControllerCommand");
+    m_maxWheelVelocityMetersPerSecond = maxWheelVelocityMetersPerSecond;
 
     m_frontLeftController =
         requireNonNullParam(frontLeftController, "frontLeftController", "MecanumControllerCommand");
@@ -179,7 +173,6 @@
    *     voltages.
    * @param requirements The subsystems to require.
    */
-  @SuppressWarnings("ParameterName")
   public MecanumControllerCommand(
       Trajectory trajectory,
       Supplier<Pose2d> pose,
@@ -221,7 +214,7 @@
    * trajectory. The user should implement a velocity PID on the desired output wheel velocities.
    *
    * <p>Note: The controllers will *not* set the outputVolts to zero upon completion of the path -
-   * this is left to the user, since it is not appropriate for paths with non-stationary end-states.
+   * this is left to the user, since it is not appropriate for paths with nonstationary end-states.
    *
    * @param trajectory The trajectory to follow.
    * @param pose A function that supplies the robot pose - use one of the odometry classes to
@@ -236,7 +229,6 @@
    * @param outputWheelSpeeds A MecanumDriveWheelSpeeds object containing the output wheel speeds.
    * @param requirements The subsystems to require.
    */
-  @SuppressWarnings("ParameterName")
   public MecanumControllerCommand(
       Trajectory trajectory,
       Supplier<Pose2d> pose,
@@ -262,11 +254,7 @@
     m_desiredRotation =
         requireNonNullParam(desiredRotation, "desiredRotation", "MecanumControllerCommand");
 
-    m_maxWheelVelocityMetersPerSecond =
-        requireNonNullParam(
-            maxWheelVelocityMetersPerSecond,
-            "maxWheelVelocityMetersPerSecond",
-            "MecanumControllerCommand");
+    m_maxWheelVelocityMetersPerSecond = maxWheelVelocityMetersPerSecond;
 
     m_frontLeftController = null;
     m_rearLeftController = null;
@@ -290,7 +278,7 @@
    * trajectory. The user should implement a velocity PID on the desired output wheel velocities.
    *
    * <p>Note: The controllers will *not* set the outputVolts to zero upon completion of the path -
-   * this is left to the user, since it is not appropriate for paths with non-stationary end-states.
+   * this is left to the user, since it is not appropriate for paths with nonstationary end-states.
    *
    * <p>Note 2: The final rotation of the robot will be set to the rotation of the final pose in the
    * trajectory. The robot will not follow the rotations from the poses at each timestep. If
@@ -308,7 +296,6 @@
    * @param outputWheelSpeeds A MecanumDriveWheelSpeeds object containing the output wheel speeds.
    * @param requirements The subsystems to require.
    */
-  @SuppressWarnings("ParameterName")
   public MecanumControllerCommand(
       Trajectory trajectory,
       Supplier<Pose2d> pose,
@@ -350,7 +337,6 @@
   }
 
   @Override
-  @SuppressWarnings("LocalVariableName")
   public void execute() {
     double curTime = m_timer.get();
     double dt = curTime - m_prevTime;
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/PIDCommand.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/PIDCommand.java
index f4c10dc..ec184c8 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/PIDCommand.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/PIDCommand.java
@@ -4,7 +4,7 @@
 
 package edu.wpi.first.wpilibj2.command;
 
-import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
 
 import edu.wpi.first.math.controller.PIDController;
 import java.util.Set;
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/PIDSubsystem.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/PIDSubsystem.java
index c15360d..84318de 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/PIDSubsystem.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/PIDSubsystem.java
@@ -4,7 +4,7 @@
 
 package edu.wpi.first.wpilibj2.command;
 
-import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
 
 import edu.wpi.first.math.controller.PIDController;
 
@@ -18,8 +18,6 @@
   protected final PIDController m_controller;
   protected boolean m_enabled;
 
-  private double m_setpoint;
-
   /**
    * Creates a new PIDSubsystem.
    *
@@ -27,8 +25,8 @@
    * @param initialPosition the initial setpoint of the subsystem
    */
   public PIDSubsystem(PIDController controller, double initialPosition) {
-    setSetpoint(initialPosition);
     m_controller = requireNonNullParam(controller, "controller", "PIDSubsystem");
+    setSetpoint(initialPosition);
     addChild("PID Controller", m_controller);
   }
 
@@ -44,7 +42,7 @@
   @Override
   public void periodic() {
     if (m_enabled) {
-      useOutput(m_controller.calculate(getMeasurement(), m_setpoint), m_setpoint);
+      useOutput(m_controller.calculate(getMeasurement()), getSetpoint());
     }
   }
 
@@ -58,7 +56,7 @@
    * @param setpoint the setpoint for the subsystem
    */
   public void setSetpoint(double setpoint) {
-    m_setpoint = setpoint;
+    m_controller.setSetpoint(setpoint);
   }
 
   /**
@@ -67,7 +65,7 @@
    * @return The current setpoint
    */
   public double getSetpoint() {
-    return m_setpoint;
+    return m_controller.getSetpoint();
   }
 
   /**
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelCommandGroup.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelCommandGroup.java
index 688435c..3b36f42 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelCommandGroup.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelCommandGroup.java
@@ -9,23 +9,27 @@
 import java.util.Map;
 
 /**
- * A CommandGroup that runs a set of commands in parallel, ending when the last command ends.
+ * A command composition that runs a set of commands in parallel, ending when the last command ends.
  *
- * <p>As a rule, CommandGroups require the union of the requirements of their component commands.
+ * <p>The rules for command compositions apply: command instances that are passed to it cannot be
+ * added to any other composition or scheduled individually, and the composition requires all
+ * subsystems its components require.
  *
  * <p>This class is provided by the NewCommands VendorDep
  */
+@SuppressWarnings("removal")
 public class ParallelCommandGroup extends CommandGroupBase {
-  // maps commands in this group to whether they are still running
+  // maps commands in this composition to whether they are still running
   private final Map<Command, Boolean> m_commands = new HashMap<>();
   private boolean m_runWhenDisabled = true;
+  private InterruptionBehavior m_interruptBehavior = InterruptionBehavior.kCancelIncoming;
 
   /**
    * Creates a new ParallelCommandGroup. The given commands will be executed simultaneously. The
-   * command group will finish when the last command finishes. If the CommandGroup is interrupted,
-   * only the commands that are still running will be interrupted.
+   * command composition will finish when the last command finishes. If the composition is
+   * interrupted, only the commands that are still running will be interrupted.
    *
-   * @param commands the commands to include in this group.
+   * @param commands the commands to include in this composition.
    */
   public ParallelCommandGroup(Command... commands) {
     addCommands(commands);
@@ -33,28 +37,29 @@
 
   @Override
   public final void addCommands(Command... commands) {
-    requireUngrouped(commands);
-
     if (m_commands.containsValue(true)) {
       throw new IllegalStateException(
-          "Commands cannot be added to a CommandGroup while the group is running");
+          "Commands cannot be added to a composition while it's running");
     }
 
-    registerGroupedCommands(commands);
+    CommandScheduler.getInstance().registerComposedCommands(commands);
 
     for (Command command : commands) {
       if (!Collections.disjoint(command.getRequirements(), m_requirements)) {
         throw new IllegalArgumentException(
-            "Multiple commands in a parallel group cannot" + "require the same subsystems");
+            "Multiple commands in a parallel composition cannot require the same subsystems");
       }
       m_commands.put(command, false);
       m_requirements.addAll(command.getRequirements());
       m_runWhenDisabled &= command.runsWhenDisabled();
+      if (command.getInterruptionBehavior() == InterruptionBehavior.kCancelSelf) {
+        m_interruptBehavior = InterruptionBehavior.kCancelSelf;
+      }
     }
   }
 
   @Override
-  public void initialize() {
+  public final void initialize() {
     for (Map.Entry<Command, Boolean> commandRunning : m_commands.entrySet()) {
       commandRunning.getKey().initialize();
       commandRunning.setValue(true);
@@ -62,7 +67,7 @@
   }
 
   @Override
-  public void execute() {
+  public final void execute() {
     for (Map.Entry<Command, Boolean> commandRunning : m_commands.entrySet()) {
       if (!commandRunning.getValue()) {
         continue;
@@ -76,7 +81,7 @@
   }
 
   @Override
-  public void end(boolean interrupted) {
+  public final void end(boolean interrupted) {
     if (interrupted) {
       for (Map.Entry<Command, Boolean> commandRunning : m_commands.entrySet()) {
         if (commandRunning.getValue()) {
@@ -87,7 +92,7 @@
   }
 
   @Override
-  public boolean isFinished() {
+  public final boolean isFinished() {
     return !m_commands.containsValue(true);
   }
 
@@ -97,8 +102,7 @@
   }
 
   @Override
-  public ParallelCommandGroup alongWith(Command... parallel) {
-    addCommands(parallel);
-    return this;
+  public InterruptionBehavior getInterruptionBehavior() {
+    return m_interruptBehavior;
   }
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelDeadlineGroup.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelDeadlineGroup.java
index 5d54b2f..2e62a9f 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelDeadlineGroup.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelDeadlineGroup.java
@@ -4,32 +4,38 @@
 
 package edu.wpi.first.wpilibj2.command;
 
+import edu.wpi.first.util.sendable.SendableBuilder;
 import java.util.Collections;
 import java.util.HashMap;
 import java.util.Map;
 
 /**
- * A CommandGroup that runs a set of commands in parallel, ending only when a specific command (the
- * "deadline") ends, interrupting all other commands that are still running at that point.
+ * A command composition that runs a set of commands in parallel, ending only when a specific
+ * command (the "deadline") ends, interrupting all other commands that are still running at that
+ * point.
  *
- * <p>As a rule, CommandGroups require the union of the requirements of their component commands.
+ * <p>The rules for command compositions apply: command instances that are passed to it cannot be
+ * added to any other composition or scheduled individually, and the composition requires all
+ * subsystems its components require.
  *
  * <p>This class is provided by the NewCommands VendorDep
  */
+@SuppressWarnings("removal")
 public class ParallelDeadlineGroup extends CommandGroupBase {
-  // maps commands in this group to whether they are still running
+  // maps commands in this composition to whether they are still running
   private final Map<Command, Boolean> m_commands = new HashMap<>();
   private boolean m_runWhenDisabled = true;
   private boolean m_finished = true;
   private Command m_deadline;
+  private InterruptionBehavior m_interruptBehavior = InterruptionBehavior.kCancelIncoming;
 
   /**
    * Creates a new ParallelDeadlineGroup. The given commands (including the deadline) will be
-   * executed simultaneously. The CommandGroup will finish when the deadline finishes, interrupting
-   * all other still-running commands. If the CommandGroup is interrupted, only the commands still
+   * executed simultaneously. The composition will finish when the deadline finishes, interrupting
+   * all other still-running commands. If the composition is interrupted, only the commands still
    * running will be interrupted.
    *
-   * @param deadline the command that determines when the group ends
+   * @param deadline the command that determines when the composition ends
    * @param commands the commands to be executed
    */
   public ParallelDeadlineGroup(Command deadline, Command... commands) {
@@ -55,14 +61,12 @@
 
   @Override
   public final void addCommands(Command... commands) {
-    requireUngrouped(commands);
-
     if (!m_finished) {
       throw new IllegalStateException(
-          "Commands cannot be added to a CommandGroup while the group is running");
+          "Commands cannot be added to a composition while it's running");
     }
 
-    registerGroupedCommands(commands);
+    CommandScheduler.getInstance().registerComposedCommands(commands);
 
     for (Command command : commands) {
       if (!Collections.disjoint(command.getRequirements(), m_requirements)) {
@@ -72,11 +76,14 @@
       m_commands.put(command, false);
       m_requirements.addAll(command.getRequirements());
       m_runWhenDisabled &= command.runsWhenDisabled();
+      if (command.getInterruptionBehavior() == InterruptionBehavior.kCancelSelf) {
+        m_interruptBehavior = InterruptionBehavior.kCancelSelf;
+      }
     }
   }
 
   @Override
-  public void initialize() {
+  public final void initialize() {
     for (Map.Entry<Command, Boolean> commandRunning : m_commands.entrySet()) {
       commandRunning.getKey().initialize();
       commandRunning.setValue(true);
@@ -85,7 +92,7 @@
   }
 
   @Override
-  public void execute() {
+  public final void execute() {
     for (Map.Entry<Command, Boolean> commandRunning : m_commands.entrySet()) {
       if (!commandRunning.getValue()) {
         continue;
@@ -102,7 +109,7 @@
   }
 
   @Override
-  public void end(boolean interrupted) {
+  public final void end(boolean interrupted) {
     for (Map.Entry<Command, Boolean> commandRunning : m_commands.entrySet()) {
       if (commandRunning.getValue()) {
         commandRunning.getKey().end(true);
@@ -111,7 +118,7 @@
   }
 
   @Override
-  public boolean isFinished() {
+  public final boolean isFinished() {
     return m_finished;
   }
 
@@ -121,8 +128,14 @@
   }
 
   @Override
-  public ParallelDeadlineGroup deadlineWith(Command... parallel) {
-    addCommands(parallel);
-    return this;
+  public InterruptionBehavior getInterruptionBehavior() {
+    return m_interruptBehavior;
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    super.initSendable(builder);
+
+    builder.addStringProperty("deadline", m_deadline::getName, null);
   }
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelRaceGroup.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelRaceGroup.java
index be3f909..e5ba80d 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelRaceGroup.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelRaceGroup.java
@@ -9,24 +9,28 @@
 import java.util.Set;
 
 /**
- * A CommandGroup that runs a set of commands in parallel, ending when any one of the commands ends
+ * A composition that runs a set of commands in parallel, ending when any one of the commands ends
  * and interrupting all the others.
  *
- * <p>As a rule, CommandGroups require the union of the requirements of their component commands.
+ * <p>The rules for command compositions apply: command instances that are passed to it cannot be
+ * added to any other composition or scheduled individually, and the composition requires all
+ * subsystems its components require.
  *
  * <p>This class is provided by the NewCommands VendorDep
  */
+@SuppressWarnings("removal")
 public class ParallelRaceGroup extends CommandGroupBase {
   private final Set<Command> m_commands = new HashSet<>();
   private boolean m_runWhenDisabled = true;
   private boolean m_finished = true;
+  private InterruptionBehavior m_interruptBehavior = InterruptionBehavior.kCancelIncoming;
 
   /**
    * Creates a new ParallelCommandRace. The given commands will be executed simultaneously, and will
    * "race to the finish" - the first command to finish ends the entire command, with all other
    * commands being interrupted.
    *
-   * @param commands the commands to include in this group.
+   * @param commands the commands to include in this composition.
    */
   public ParallelRaceGroup(Command... commands) {
     addCommands(commands);
@@ -34,28 +38,29 @@
 
   @Override
   public final void addCommands(Command... commands) {
-    requireUngrouped(commands);
-
     if (!m_finished) {
       throw new IllegalStateException(
-          "Commands cannot be added to a CommandGroup while the group is running");
+          "Commands cannot be added to a composition while it's running!");
     }
 
-    registerGroupedCommands(commands);
+    CommandScheduler.getInstance().registerComposedCommands(commands);
 
     for (Command command : commands) {
       if (!Collections.disjoint(command.getRequirements(), m_requirements)) {
         throw new IllegalArgumentException(
-            "Multiple commands in a parallel group cannot" + " require the same subsystems");
+            "Multiple commands in a parallel composition cannot require the same subsystems");
       }
       m_commands.add(command);
       m_requirements.addAll(command.getRequirements());
       m_runWhenDisabled &= command.runsWhenDisabled();
+      if (command.getInterruptionBehavior() == InterruptionBehavior.kCancelSelf) {
+        m_interruptBehavior = InterruptionBehavior.kCancelSelf;
+      }
     }
   }
 
   @Override
-  public void initialize() {
+  public final void initialize() {
     m_finished = false;
     for (Command command : m_commands) {
       command.initialize();
@@ -63,7 +68,7 @@
   }
 
   @Override
-  public void execute() {
+  public final void execute() {
     for (Command command : m_commands) {
       command.execute();
       if (command.isFinished()) {
@@ -73,14 +78,14 @@
   }
 
   @Override
-  public void end(boolean interrupted) {
+  public final void end(boolean interrupted) {
     for (Command command : m_commands) {
       command.end(!command.isFinished());
     }
   }
 
   @Override
-  public boolean isFinished() {
+  public final boolean isFinished() {
     return m_finished;
   }
 
@@ -90,8 +95,7 @@
   }
 
   @Override
-  public ParallelRaceGroup raceWith(Command... parallel) {
-    addCommands(parallel);
-    return this;
+  public InterruptionBehavior getInterruptionBehavior() {
+    return m_interruptBehavior;
   }
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/PerpetualCommand.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/PerpetualCommand.java
index 7113be6..9fb9019 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/PerpetualCommand.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/PerpetualCommand.java
@@ -4,19 +4,22 @@
 
 package edu.wpi.first.wpilibj2.command;
 
-import static edu.wpi.first.wpilibj2.command.CommandGroupBase.registerGroupedCommands;
-import static edu.wpi.first.wpilibj2.command.CommandGroupBase.requireUngrouped;
-
 /**
  * A command that runs another command in perpetuity, ignoring that command's end conditions. While
- * this class does not extend {@link CommandGroupBase}, it is still considered a CommandGroup, as it
+ * this class does not extend {@link CommandGroupBase}, it is still considered a composition, as it
  * allows one to compose another command within it; the command instances that are passed to it
  * cannot be added to any other groups, or scheduled individually.
  *
  * <p>As a rule, CommandGroups require the union of the requirements of their component commands.
  *
  * <p>This class is provided by the NewCommands VendorDep
+ *
+ * @deprecated PerpetualCommand violates the assumption that execute() doesn't get called after
+ *     isFinished() returns true -- an assumption that should be valid. This was unsafe/undefined
+ *     behavior from the start, and RepeatCommand provides an easy way to achieve similar end
+ *     results with slightly different (and safe) semantics.
  */
+@Deprecated(forRemoval = true, since = "2023")
 public class PerpetualCommand extends CommandBase {
   protected final Command m_command;
 
@@ -27,8 +30,7 @@
    * @param command the command to run perpetually
    */
   public PerpetualCommand(Command command) {
-    requireUngrouped(command);
-    registerGroupedCommands(command);
+    CommandScheduler.getInstance().registerComposedCommands(command);
     m_command = command;
     m_requirements.addAll(command.getRequirements());
   }
@@ -52,9 +54,4 @@
   public boolean runsWhenDisabled() {
     return m_command.runsWhenDisabled();
   }
-
-  @Override
-  public PerpetualCommand perpetually() {
-    return this;
-  }
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProfiledPIDCommand.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProfiledPIDCommand.java
index d637b22..4344913 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProfiledPIDCommand.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProfiledPIDCommand.java
@@ -5,7 +5,7 @@
 package edu.wpi.first.wpilibj2.command;
 
 import static edu.wpi.first.math.trajectory.TrapezoidProfile.State;
-import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
 
 import edu.wpi.first.math.controller.ProfiledPIDController;
 import java.util.Set;
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProfiledPIDSubsystem.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProfiledPIDSubsystem.java
index 0f28d85..283b4bf 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProfiledPIDSubsystem.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProfiledPIDSubsystem.java
@@ -5,7 +5,7 @@
 package edu.wpi.first.wpilibj2.command;
 
 import static edu.wpi.first.math.trajectory.TrapezoidProfile.State;
-import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
 
 import edu.wpi.first.math.controller.ProfiledPIDController;
 import edu.wpi.first.math.trajectory.TrapezoidProfile;
@@ -20,8 +20,6 @@
   protected final ProfiledPIDController m_controller;
   protected boolean m_enabled;
 
-  private TrapezoidProfile.State m_goal;
-
   /**
    * Creates a new ProfiledPIDSubsystem.
    *
@@ -45,7 +43,7 @@
   @Override
   public void periodic() {
     if (m_enabled) {
-      useOutput(m_controller.calculate(getMeasurement(), m_goal), m_controller.getSetpoint());
+      useOutput(m_controller.calculate(getMeasurement()), m_controller.getSetpoint());
     }
   }
 
@@ -59,7 +57,7 @@
    * @param goal The goal state for the subsystem's motion profile.
    */
   public void setGoal(TrapezoidProfile.State goal) {
-    m_goal = goal;
+    m_controller.setGoal(goal);
   }
 
   /**
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProxyCommand.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProxyCommand.java
new file mode 100644
index 0000000..ef6ca5b
--- /dev/null
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProxyCommand.java
@@ -0,0 +1,85 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj2.command;
+
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
+
+import edu.wpi.first.util.sendable.SendableBuilder;
+import java.util.function.Supplier;
+
+/**
+ * Schedules the given command when this command is initialized, and ends when it ends. Useful for
+ * forking off from CommandGroups. If this command is interrupted, it will cancel the command.
+ *
+ * <p>This class is provided by the NewCommands VendorDep
+ */
+public class ProxyCommand extends CommandBase {
+  private final Supplier<Command> m_supplier;
+  private Command m_command;
+
+  /**
+   * Creates a new ProxyCommand that schedules the supplied command when initialized, and ends when
+   * it is no longer scheduled. Useful for lazily creating commands at runtime.
+   *
+   * @param supplier the command supplier
+   */
+  public ProxyCommand(Supplier<Command> supplier) {
+    m_supplier = requireNonNullParam(supplier, "supplier", "ProxyCommand");
+  }
+
+  /**
+   * Creates a new ProxyCommand that schedules the given command when initialized, and ends when it
+   * is no longer scheduled.
+   *
+   * @param command the command to run by proxy
+   */
+  public ProxyCommand(Command command) {
+    this(() -> command);
+    setName("Proxy(" + command.getName() + ")");
+  }
+
+  @Override
+  public void initialize() {
+    m_command = m_supplier.get();
+    m_command.schedule();
+  }
+
+  @Override
+  public void end(boolean interrupted) {
+    if (interrupted) {
+      m_command.cancel();
+    }
+    m_command = null;
+  }
+
+  @Override
+  public void execute() {}
+
+  @Override
+  public boolean isFinished() {
+    // because we're between `initialize` and `end`, `m_command` is necessarily not null
+    // but if called otherwise and m_command is null,
+    // it's UB, so we can do whatever we want -- like return true.
+    return m_command == null || !m_command.isScheduled();
+  }
+
+  /**
+   * Whether the given command should run when the robot is disabled. Override to return true if the
+   * command should run when disabled.
+   *
+   * @return true. Otherwise, this proxy would cancel commands that do run when disabled.
+   */
+  @Override
+  public boolean runsWhenDisabled() {
+    return true;
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    super.initSendable(builder);
+    builder.addStringProperty(
+        "proxied", () -> m_command == null ? "null" : m_command.getName(), null);
+  }
+}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProxyScheduleCommand.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProxyScheduleCommand.java
index 858d9d0..eec1b18 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProxyScheduleCommand.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProxyScheduleCommand.java
@@ -9,7 +9,7 @@
 /**
  * Schedules the given commands when this command is initialized, and ends when all the commands are
  * no longer scheduled. Useful for forking off from CommandGroups. If this command is interrupted,
- * it will cancel all of the commands.
+ * it will cancel all the commands.
  *
  * <p>This class is provided by the NewCommands VendorDep
  */
@@ -22,7 +22,10 @@
    * when they are all no longer scheduled.
    *
    * @param toSchedule the commands to schedule
+   * @deprecated Replace with {@link ProxyCommand}, composing multiple of them in a {@link
+   *     ParallelRaceGroup} if needed.
    */
+  @Deprecated
   public ProxyScheduleCommand(Command... toSchedule) {
     m_toSchedule = Set.of(toSchedule);
   }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RamseteCommand.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RamseteCommand.java
index f5a957d..69e271b 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RamseteCommand.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RamseteCommand.java
@@ -4,7 +4,7 @@
 
 package edu.wpi.first.wpilibj2.command;
 
-import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
 
 import edu.wpi.first.math.controller.PIDController;
 import edu.wpi.first.math.controller.RamseteController;
@@ -14,6 +14,7 @@
 import edu.wpi.first.math.kinematics.DifferentialDriveKinematics;
 import edu.wpi.first.math.kinematics.DifferentialDriveWheelSpeeds;
 import edu.wpi.first.math.trajectory.Trajectory;
+import edu.wpi.first.util.sendable.SendableBuilder;
 import edu.wpi.first.wpilibj.Timer;
 import java.util.function.BiConsumer;
 import java.util.function.Supplier;
@@ -211,4 +212,11 @@
   public boolean isFinished() {
     return m_timer.hasElapsed(m_trajectory.getTotalTimeSeconds());
   }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    super.initSendable(builder);
+    builder.addDoubleProperty("leftVelocity", () -> m_prevSpeeds.leftMetersPerSecond, null);
+    builder.addDoubleProperty("rightVelocity", () -> m_prevSpeeds.rightMetersPerSecond, null);
+  }
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RepeatCommand.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RepeatCommand.java
new file mode 100644
index 0000000..6de06c5
--- /dev/null
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RepeatCommand.java
@@ -0,0 +1,84 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj2.command;
+
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
+
+import edu.wpi.first.util.sendable.SendableBuilder;
+
+/**
+ * A command that runs another command repeatedly, restarting it when it ends, until this command is
+ * interrupted. Command instances that are passed to it cannot be added to any other groups, or
+ * scheduled individually.
+ *
+ * <p>The rules for command compositions apply: command instances that are passed to it cannot be
+ * added to any other composition or scheduled individually,and the composition requires all
+ * subsystems its components require.
+ *
+ * <p>This class is provided by the NewCommands VendorDep
+ */
+public class RepeatCommand extends CommandBase {
+  protected final Command m_command;
+  private boolean m_ended;
+
+  /**
+   * Creates a new RepeatCommand. Will run another command repeatedly, restarting it whenever it
+   * ends, until this command is interrupted.
+   *
+   * @param command the command to run repeatedly
+   */
+  public RepeatCommand(Command command) {
+    m_command = requireNonNullParam(command, "command", "RepeatCommand");
+    CommandScheduler.getInstance().registerComposedCommands(command);
+    m_requirements.addAll(command.getRequirements());
+    setName("Repeat(" + command.getName() + ")");
+  }
+
+  @Override
+  public void initialize() {
+    m_ended = false;
+    m_command.initialize();
+  }
+
+  @Override
+  public void execute() {
+    if (m_ended) {
+      m_ended = false;
+      m_command.initialize();
+    }
+    m_command.execute();
+    if (m_command.isFinished()) {
+      // restart command
+      m_command.end(false);
+      m_ended = true;
+    }
+  }
+
+  @Override
+  public boolean isFinished() {
+    return false;
+  }
+
+  @Override
+  public void end(boolean interrupted) {
+    m_command.end(interrupted);
+  }
+
+  @Override
+  public boolean runsWhenDisabled() {
+    return m_command.runsWhenDisabled();
+  }
+
+  @Override
+  public InterruptionBehavior getInterruptionBehavior() {
+    return m_command.getInterruptionBehavior();
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    super.initSendable(builder);
+    builder.addStringProperty("command", m_command::getName, null);
+  }
+}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RunCommand.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RunCommand.java
index 2ae1c92..c0a17b5 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RunCommand.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RunCommand.java
@@ -4,8 +4,6 @@
 
 package edu.wpi.first.wpilibj2.command;
 
-import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
-
 import java.util.function.BooleanSupplier;
 
 /**
@@ -15,9 +13,7 @@
  *
  * <p>This class is provided by the NewCommands VendorDep
  */
-public class RunCommand extends CommandBase {
-  protected final Runnable m_toRun;
-
+public class RunCommand extends FunctionalCommand {
   /**
    * Creates a new RunCommand. The Runnable will be run continuously until the command ends. Does
    * not run when disabled.
@@ -26,12 +22,6 @@
    * @param requirements the subsystems to require
    */
   public RunCommand(Runnable toRun, Subsystem... requirements) {
-    m_toRun = requireNonNullParam(toRun, "toRun", "RunCommand");
-    addRequirements(requirements);
-  }
-
-  @Override
-  public void execute() {
-    m_toRun.run();
+    super(() -> {}, toRun, interrupted -> {}, () -> false, requirements);
   }
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ScheduleCommand.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ScheduleCommand.java
index 98062f9..a61be2f 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ScheduleCommand.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ScheduleCommand.java
@@ -8,8 +8,8 @@
 
 /**
  * Schedules the given commands when this command is initialized. Useful for forking off from
- * CommandGroups. Note that if run from a CommandGroup, the group will not know about the status of
- * the scheduled commands, and will treat this command as finishing instantly.
+ * CommandGroups. Note that if run from a composition, the composition will not know about the
+ * status of the scheduled commands, and will treat this command as finishing instantly.
  *
  * <p>This class is provided by the NewCommands VendorDep
  */
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SelectCommand.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SelectCommand.java
index e774816..d947701 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SelectCommand.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SelectCommand.java
@@ -4,25 +4,19 @@
 
 package edu.wpi.first.wpilibj2.command;
 
-import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
-import static edu.wpi.first.wpilibj2.command.CommandGroupBase.requireUngrouped;
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
 
+import edu.wpi.first.util.sendable.SendableBuilder;
 import java.util.Map;
 import java.util.function.Supplier;
 
 /**
- * Runs one of a selection of commands, either using a selector and a key to command mapping, or a
- * supplier that returns the command directly at runtime. Does not actually schedule the selected
- * command - rather, the command is run through this command; this ensures that the command will
- * behave as expected if used as part of a CommandGroup. Requires the requirements of all included
- * commands, again to ensure proper functioning when used in a CommandGroup. If this is undesired,
- * consider using {@link ScheduleCommand}.
+ * A command composition that runs one of a selection of commands, either using a selector and a key
+ * to command mapping, or a supplier that returns the command directly at runtime.
  *
- * <p>As this command contains multiple component commands within it, it is technically a command
- * group; the command instances that are passed to it cannot be added to any other groups, or
- * scheduled individually.
- *
- * <p>As a rule, CommandGroups require the union of the requirements of their component commands.
+ * <p>The rules for command compositions apply: command instances that are passed to it cannot be
+ * added to any other composition or scheduled individually, and the composition requires all
+ * subsystems its components require.
  *
  * <p>This class is provided by the NewCommands VendorDep
  */
@@ -31,43 +25,54 @@
   private final Supplier<Object> m_selector;
   private final Supplier<Command> m_toRun;
   private Command m_selectedCommand;
+  private boolean m_runsWhenDisabled = true;
+  private InterruptionBehavior m_interruptBehavior = InterruptionBehavior.kCancelIncoming;
 
   /**
-   * Creates a new selectcommand.
+   * Creates a new SelectCommand.
    *
    * @param commands the map of commands to choose from
    * @param selector the selector to determine which command to run
    */
   public SelectCommand(Map<Object, Command> commands, Supplier<Object> selector) {
-    requireUngrouped(commands.values());
-
-    CommandGroupBase.registerGroupedCommands(commands.values().toArray(new Command[] {}));
-
     m_commands = requireNonNullParam(commands, "commands", "SelectCommand");
     m_selector = requireNonNullParam(selector, "selector", "SelectCommand");
 
+    CommandScheduler.getInstance()
+        .registerComposedCommands(commands.values().toArray(new Command[] {}));
+
     m_toRun = null;
 
     for (Command command : m_commands.values()) {
       m_requirements.addAll(command.getRequirements());
+      m_runsWhenDisabled &= command.runsWhenDisabled();
+      if (command.getInterruptionBehavior() == InterruptionBehavior.kCancelSelf) {
+        m_interruptBehavior = InterruptionBehavior.kCancelSelf;
+      }
     }
   }
 
   /**
-   * Creates a new selectcommand.
+   * Creates a new SelectCommand.
    *
    * @param toRun a supplier providing the command to run
+   * @deprecated Replace with {@link ProxyCommand}
    */
+  @Deprecated
   public SelectCommand(Supplier<Command> toRun) {
     m_commands = null;
     m_selector = null;
     m_toRun = requireNonNullParam(toRun, "toRun", "SelectCommand");
+
+    // we have no way of checking the underlying command, so default.
+    m_runsWhenDisabled = false;
+    m_interruptBehavior = InterruptionBehavior.kCancelSelf;
   }
 
   @Override
   public void initialize() {
     if (m_selector != null) {
-      if (!m_commands.keySet().contains(m_selector.get())) {
+      if (!m_commands.containsKey(m_selector.get())) {
         m_selectedCommand =
             new PrintCommand(
                 "SelectCommand selector value does not correspond to" + " any command!");
@@ -97,14 +102,19 @@
 
   @Override
   public boolean runsWhenDisabled() {
-    if (m_commands != null) {
-      boolean runsWhenDisabled = true;
-      for (Command command : m_commands.values()) {
-        runsWhenDisabled &= command.runsWhenDisabled();
-      }
-      return runsWhenDisabled;
-    } else {
-      return m_toRun.get().runsWhenDisabled();
-    }
+    return m_runsWhenDisabled;
+  }
+
+  @Override
+  public InterruptionBehavior getInterruptionBehavior() {
+    return m_interruptBehavior;
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    super.initSendable(builder);
+
+    builder.addStringProperty(
+        "selected", () -> m_selectedCommand == null ? "null" : m_selectedCommand.getName(), null);
   }
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SequentialCommandGroup.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SequentialCommandGroup.java
index 43426b0..892f94a 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SequentialCommandGroup.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SequentialCommandGroup.java
@@ -4,26 +4,31 @@
 
 package edu.wpi.first.wpilibj2.command;
 
+import edu.wpi.first.util.sendable.SendableBuilder;
 import java.util.ArrayList;
 import java.util.List;
 
 /**
- * A CommandGroups that runs a list of commands in sequence.
+ * A command composition that runs a list of commands in sequence.
  *
- * <p>As a rule, CommandGroups require the union of the requirements of their component commands.
+ * <p>The rules for command compositions apply: command instances that are passed to it cannot be
+ * added to any other composition or scheduled individually, and the composition requires all
+ * subsystems its components require.
  *
  * <p>This class is provided by the NewCommands VendorDep
  */
+@SuppressWarnings("removal")
 public class SequentialCommandGroup extends CommandGroupBase {
   private final List<Command> m_commands = new ArrayList<>();
   private int m_currentCommandIndex = -1;
   private boolean m_runWhenDisabled = true;
+  private InterruptionBehavior m_interruptBehavior = InterruptionBehavior.kCancelIncoming;
 
   /**
    * Creates a new SequentialCommandGroup. The given commands will be run sequentially, with the
-   * CommandGroup finishing when the last command finishes.
+   * composition finishing when the last command finishes.
    *
-   * @param commands the commands to include in this group.
+   * @param commands the commands to include in this composition.
    */
   public SequentialCommandGroup(Command... commands) {
     addCommands(commands);
@@ -31,24 +36,25 @@
 
   @Override
   public final void addCommands(Command... commands) {
-    requireUngrouped(commands);
-
     if (m_currentCommandIndex != -1) {
       throw new IllegalStateException(
-          "Commands cannot be added to a CommandGroup while the group is running");
+          "Commands cannot be added to a composition while it's running");
     }
 
-    registerGroupedCommands(commands);
+    CommandScheduler.getInstance().registerComposedCommands(commands);
 
     for (Command command : commands) {
       m_commands.add(command);
       m_requirements.addAll(command.getRequirements());
       m_runWhenDisabled &= command.runsWhenDisabled();
+      if (command.getInterruptionBehavior() == InterruptionBehavior.kCancelSelf) {
+        m_interruptBehavior = InterruptionBehavior.kCancelSelf;
+      }
     }
   }
 
   @Override
-  public void initialize() {
+  public final void initialize() {
     m_currentCommandIndex = 0;
 
     if (!m_commands.isEmpty()) {
@@ -57,7 +63,7 @@
   }
 
   @Override
-  public void execute() {
+  public final void execute() {
     if (m_commands.isEmpty()) {
       return;
     }
@@ -75,7 +81,7 @@
   }
 
   @Override
-  public void end(boolean interrupted) {
+  public final void end(boolean interrupted) {
     if (interrupted
         && !m_commands.isEmpty()
         && m_currentCommandIndex > -1
@@ -86,7 +92,7 @@
   }
 
   @Override
-  public boolean isFinished() {
+  public final boolean isFinished() {
     return m_currentCommandIndex == m_commands.size();
   }
 
@@ -96,26 +102,14 @@
   }
 
   @Override
-  public SequentialCommandGroup beforeStarting(Command before) {
-    // store all the commands
-    var commands = new ArrayList<Command>();
-    commands.add(before);
-    commands.addAll(m_commands);
-
-    // reset current state
-    commands.forEach(CommandGroupBase::clearGroupedCommand);
-    m_commands.clear();
-    m_requirements.clear();
-    m_runWhenDisabled = true;
-
-    // add them back
-    addCommands(commands.toArray(Command[]::new));
-    return this;
+  public InterruptionBehavior getInterruptionBehavior() {
+    return m_interruptBehavior;
   }
 
   @Override
-  public SequentialCommandGroup andThen(Command... next) {
-    addCommands(next);
-    return this;
+  public void initSendable(SendableBuilder builder) {
+    super.initSendable(builder);
+
+    builder.addIntegerProperty("index", () -> m_currentCommandIndex, null);
   }
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/StartEndCommand.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/StartEndCommand.java
index 8c0b99e..9eff70d 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/StartEndCommand.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/StartEndCommand.java
@@ -4,7 +4,9 @@
 
 package edu.wpi.first.wpilibj2.command;
 
-import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
+
+import java.util.function.Consumer;
 
 /**
  * A command that runs a given runnable when it is initialized, and another runnable when it ends.
@@ -14,10 +16,7 @@
  *
  * <p>This class is provided by the NewCommands VendorDep
  */
-public class StartEndCommand extends CommandBase {
-  protected final Runnable m_onInit;
-  protected final Runnable m_onEnd;
-
+public class StartEndCommand extends FunctionalCommand {
   /**
    * Creates a new StartEndCommand. Will run the given runnables when the command starts and when it
    * ends.
@@ -27,19 +26,16 @@
    * @param requirements the subsystems required by this command
    */
   public StartEndCommand(Runnable onInit, Runnable onEnd, Subsystem... requirements) {
-    m_onInit = requireNonNullParam(onInit, "onInit", "StartEndCommand");
-    m_onEnd = requireNonNullParam(onEnd, "onEnd", "StartEndCommand");
-
-    addRequirements(requirements);
+    super(
+        onInit,
+        () -> {},
+        // we need to do some magic here to null-check `onEnd` before it's captured
+        droppingParameter(requireNonNullParam(onEnd, "onEnd", "StartEndCommand")),
+        () -> false,
+        requirements);
   }
 
-  @Override
-  public void initialize() {
-    m_onInit.run();
-  }
-
-  @Override
-  public void end(boolean interrupted) {
-    m_onEnd.run();
+  private static Consumer<Boolean> droppingParameter(Runnable run) {
+    return bool -> run.run();
   }
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Subsystem.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Subsystem.java
index a42df71..0584ced 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Subsystem.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Subsystem.java
@@ -6,7 +6,7 @@
 
 /**
  * A robot subsystem. Subsystems are the basic unit of robot organization in the Command-based
- * framework; they encapsulate low-level hardware objects (motor controllers, sensors, etc) and
+ * framework; they encapsulate low-level hardware objects (motor controllers, sensors, etc.) and
  * provide methods through which they can be used by {@link Command}s. Subsystems are used by the
  * {@link CommandScheduler}'s resource management system to ensure multiple robot actions are not
  * "fighting" over the same hardware; Commands that use a subsystem should include that subsystem in
@@ -77,4 +77,52 @@
   default void register() {
     CommandScheduler.getInstance().registerSubsystem(this);
   }
+
+  /**
+   * Constructs a command that runs an action once and finishes. Requires this subsystem.
+   *
+   * @param action the action to run
+   * @return the command
+   * @see InstantCommand
+   */
+  default CommandBase runOnce(Runnable action) {
+    return Commands.runOnce(action, this);
+  }
+
+  /**
+   * Constructs a command that runs an action every iteration until interrupted. Requires this
+   * subsystem.
+   *
+   * @param action the action to run
+   * @return the command
+   * @see RunCommand
+   */
+  default CommandBase run(Runnable action) {
+    return Commands.run(action, this);
+  }
+
+  /**
+   * Constructs a command that runs an action once and another action when the command is
+   * interrupted. Requires this subsystem.
+   *
+   * @param start the action to run on start
+   * @param end the action to run on interrupt
+   * @return the command
+   * @see StartEndCommand
+   */
+  default CommandBase startEnd(Runnable start, Runnable end) {
+    return Commands.startEnd(start, end, this);
+  }
+
+  /**
+   * Constructs a command that runs an action every iteration until interrupted, and then runs a
+   * second action. Requires this subsystem.
+   *
+   * @param run the action to run every iteration
+   * @param end the action to run on interrupt
+   * @return the command
+   */
+  default CommandBase runEnd(Runnable run, Runnable end) {
+    return Commands.runEnd(run, end, this);
+  }
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SwerveControllerCommand.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SwerveControllerCommand.java
index 58b786b..850699e 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SwerveControllerCommand.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SwerveControllerCommand.java
@@ -4,7 +4,7 @@
 
 package edu.wpi.first.wpilibj2.command;
 
-import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
 
 import edu.wpi.first.math.controller.HolonomicDriveController;
 import edu.wpi.first.math.controller.PIDController;
@@ -31,7 +31,6 @@
  *
  * <p>This class is provided by the NewCommands VendorDep
  */
-@SuppressWarnings("MemberName")
 public class SwerveControllerCommand extends CommandBase {
   private final Timer m_timer = new Timer();
   private final Trajectory m_trajectory;
@@ -46,8 +45,9 @@
    * trajectory. This command will not return output voltages but rather raw module states from the
    * position controllers which need to be put into a velocity PID.
    *
-   * <p>Note: The controllers will *not* set the outputVolts to zero upon completion of the path-
-   * this is left to the user, since it is not appropriate for paths with nonstationary endstates.
+   * <p>Note: The controllers will *not* set the outputVolts to zero upon completion of the path.
+   * This is left to the user to do since it is not appropriate for paths with nonstationary
+   * endstates.
    *
    * @param trajectory The trajectory to follow.
    * @param pose A function that supplies the robot pose - use one of the odometry classes to
@@ -61,7 +61,6 @@
    * @param outputModuleStates The raw output module states from the position controllers.
    * @param requirements The subsystems to require.
    */
-  @SuppressWarnings("ParameterName")
   public SwerveControllerCommand(
       Trajectory trajectory,
       Supplier<Pose2d> pose,
@@ -72,23 +71,17 @@
       Supplier<Rotation2d> desiredRotation,
       Consumer<SwerveModuleState[]> outputModuleStates,
       Subsystem... requirements) {
-    m_trajectory = requireNonNullParam(trajectory, "trajectory", "SwerveControllerCommand");
-    m_pose = requireNonNullParam(pose, "pose", "SwerveControllerCommand");
-    m_kinematics = requireNonNullParam(kinematics, "kinematics", "SwerveControllerCommand");
-
-    m_controller =
+    this(
+        trajectory,
+        pose,
+        kinematics,
         new HolonomicDriveController(
             requireNonNullParam(xController, "xController", "SwerveControllerCommand"),
             requireNonNullParam(yController, "yController", "SwerveControllerCommand"),
-            requireNonNullParam(thetaController, "thetaController", "SwerveControllerCommand"));
-
-    m_outputModuleStates =
-        requireNonNullParam(outputModuleStates, "outputModuleStates", "SwerveControllerCommand");
-
-    m_desiredRotation =
-        requireNonNullParam(desiredRotation, "desiredRotation", "SwerveControllerCommand");
-
-    addRequirements(requirements);
+            requireNonNullParam(thetaController, "thetaController", "SwerveControllerCommand")),
+        desiredRotation,
+        outputModuleStates,
+        requirements);
   }
 
   /**
@@ -96,8 +89,8 @@
    * trajectory. This command will not return output voltages but rather raw module states from the
    * position controllers which need to be put into a velocity PID.
    *
-   * <p>Note: The controllers will *not* set the outputVolts to zero upon completion of the path-
-   * this is left to the user, since it is not appropriate for paths with nonstationary endstates.
+   * <p>Note: The controllers will *not* set the outputVolts to zero upon completion of the path.
+   * This is left to the user since it is not appropriate for paths with nonstationary endstates.
    *
    * <p>Note 2: The final rotation of the robot will be set to the rotation of the final pose in the
    * trajectory. The robot will not follow the rotations from the poses at each timestep. If
@@ -114,7 +107,6 @@
    * @param outputModuleStates The raw output module states from the position controllers.
    * @param requirements The subsystems to require.
    */
-  @SuppressWarnings("ParameterName")
   public SwerveControllerCommand(
       Trajectory trajectory,
       Supplier<Pose2d> pose,
@@ -137,6 +129,85 @@
         requirements);
   }
 
+  /**
+   * Constructs a new SwerveControllerCommand that when executed will follow the provided
+   * trajectory. This command will not return output voltages but rather raw module states from the
+   * position controllers which need to be put into a velocity PID.
+   *
+   * <p>Note: The controllers will *not* set the outputVolts to zero upon completion of the path-
+   * this is left to the user, since it is not appropriate for paths with nonstationary endstates.
+   *
+   * <p>Note 2: The final rotation of the robot will be set to the rotation of the final pose in the
+   * trajectory. The robot will not follow the rotations from the poses at each timestep. If
+   * alternate rotation behavior is desired, the other constructor with a supplier for rotation
+   * should be used.
+   *
+   * @param trajectory The trajectory to follow.
+   * @param pose A function that supplies the robot pose - use one of the odometry classes to
+   *     provide this.
+   * @param kinematics The kinematics for the robot drivetrain.
+   * @param controller The HolonomicDriveController for the drivetrain.
+   * @param outputModuleStates The raw output module states from the position controllers.
+   * @param requirements The subsystems to require.
+   */
+  public SwerveControllerCommand(
+      Trajectory trajectory,
+      Supplier<Pose2d> pose,
+      SwerveDriveKinematics kinematics,
+      HolonomicDriveController controller,
+      Consumer<SwerveModuleState[]> outputModuleStates,
+      Subsystem... requirements) {
+    this(
+        trajectory,
+        pose,
+        kinematics,
+        controller,
+        () ->
+            trajectory.getStates().get(trajectory.getStates().size() - 1).poseMeters.getRotation(),
+        outputModuleStates,
+        requirements);
+  }
+
+  /**
+   * Constructs a new SwerveControllerCommand that when executed will follow the provided
+   * trajectory. This command will not return output voltages but rather raw module states from the
+   * position controllers which need to be put into a velocity PID.
+   *
+   * <p>Note: The controllers will *not* set the outputVolts to zero upon completion of the path-
+   * this is left to the user, since it is not appropriate for paths with nonstationary endstates.
+   *
+   * @param trajectory The trajectory to follow.
+   * @param pose A function that supplies the robot pose - use one of the odometry classes to
+   *     provide this.
+   * @param kinematics The kinematics for the robot drivetrain.
+   * @param controller The HolonomicDriveController for the drivetrain.
+   * @param desiredRotation The angle that the drivetrain should be facing. This is sampled at each
+   *     time step.
+   * @param outputModuleStates The raw output module states from the position controllers.
+   * @param requirements The subsystems to require.
+   */
+  public SwerveControllerCommand(
+      Trajectory trajectory,
+      Supplier<Pose2d> pose,
+      SwerveDriveKinematics kinematics,
+      HolonomicDriveController controller,
+      Supplier<Rotation2d> desiredRotation,
+      Consumer<SwerveModuleState[]> outputModuleStates,
+      Subsystem... requirements) {
+    m_trajectory = requireNonNullParam(trajectory, "trajectory", "SwerveControllerCommand");
+    m_pose = requireNonNullParam(pose, "pose", "SwerveControllerCommand");
+    m_kinematics = requireNonNullParam(kinematics, "kinematics", "SwerveControllerCommand");
+    m_controller = requireNonNullParam(controller, "controller", "SwerveControllerCommand");
+
+    m_desiredRotation =
+        requireNonNullParam(desiredRotation, "desiredRotation", "SwerveControllerCommand");
+
+    m_outputModuleStates =
+        requireNonNullParam(outputModuleStates, "outputModuleStates", "SwerveControllerCommand");
+
+    addRequirements(requirements);
+  }
+
   @Override
   public void initialize() {
     m_timer.reset();
@@ -144,7 +215,6 @@
   }
 
   @Override
-  @SuppressWarnings("LocalVariableName")
   public void execute() {
     double curTime = m_timer.get();
     var desiredState = m_trajectory.sample(curTime);
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/TrapezoidProfileCommand.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/TrapezoidProfileCommand.java
index afc09d3..7c13973 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/TrapezoidProfileCommand.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/TrapezoidProfileCommand.java
@@ -5,7 +5,7 @@
 package edu.wpi.first.wpilibj2.command;
 
 import static edu.wpi.first.math.trajectory.TrapezoidProfile.State;
-import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
 
 import edu.wpi.first.math.trajectory.TrapezoidProfile;
 import edu.wpi.first.wpilibj.Timer;
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/TrapezoidProfileSubsystem.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/TrapezoidProfileSubsystem.java
index 547ddf6..1db6619 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/TrapezoidProfileSubsystem.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/TrapezoidProfileSubsystem.java
@@ -4,7 +4,7 @@
 
 package edu.wpi.first.wpilibj2.command;
 
-import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
 
 import edu.wpi.first.math.trajectory.TrapezoidProfile;
 
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/WaitCommand.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/WaitCommand.java
index e51d23a..647e87e 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/WaitCommand.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/WaitCommand.java
@@ -4,6 +4,7 @@
 
 package edu.wpi.first.wpilibj2.command;
 
+import edu.wpi.first.util.sendable.SendableBuilder;
 import edu.wpi.first.util.sendable.SendableRegistry;
 import edu.wpi.first.wpilibj.Timer;
 
@@ -47,4 +48,10 @@
   public boolean runsWhenDisabled() {
     return true;
   }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    super.initSendable(builder);
+    builder.addDoubleProperty("duration", () -> m_duration, null);
+  }
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/WaitUntilCommand.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/WaitUntilCommand.java
index ace287a..4d51e62 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/WaitUntilCommand.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/WaitUntilCommand.java
@@ -4,7 +4,7 @@
 
 package edu.wpi.first.wpilibj2.command;
 
-import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
 
 import edu.wpi.first.wpilibj.Timer;
 import java.util.function.BooleanSupplier;
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/WrapperCommand.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/WrapperCommand.java
new file mode 100644
index 0000000..c48871c
--- /dev/null
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/WrapperCommand.java
@@ -0,0 +1,101 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj2.command;
+
+import java.util.Set;
+
+/**
+ * A class used internally to wrap commands while overriding a specific method; all other methods
+ * will call through to the wrapped command.
+ *
+ * <p>The rules for command compositions apply: command instances that are passed to it cannot be
+ * added to any other composition or scheduled individually, and the composition requires all
+ * subsystems its components require.
+ */
+public abstract class WrapperCommand extends CommandBase {
+  protected final Command m_command;
+
+  /**
+   * Wrap a command.
+   *
+   * @param command the command being wrapped. Trying to directly schedule this command or add it to
+   *     a composition will throw an exception.
+   */
+  protected WrapperCommand(Command command) {
+    CommandScheduler.getInstance().registerComposedCommands(command);
+    m_command = command;
+    // copy the wrapped command's name
+    setName(command.getName());
+  }
+
+  /** The initial subroutine of a command. Called once when the command is initially scheduled. */
+  @Override
+  public void initialize() {
+    m_command.initialize();
+  }
+
+  /** The main body of a command. Called repeatedly while the command is scheduled. */
+  @Override
+  public void execute() {
+    m_command.execute();
+  }
+
+  /**
+   * The action to take when the command ends. Called when either the command finishes normally, or
+   * when it interrupted/canceled.
+   *
+   * <p>Do not schedule commands here that share requirements with this command. Use {@link
+   * #andThen(Command...)} instead.
+   *
+   * @param interrupted whether the command was interrupted/canceled
+   */
+  @Override
+  public void end(boolean interrupted) {
+    m_command.end(interrupted);
+  }
+
+  /**
+   * Whether the command has finished. Once a command finishes, the scheduler will call its end()
+   * method and un-schedule it.
+   *
+   * @return whether the command has finished.
+   */
+  @Override
+  public boolean isFinished() {
+    return m_command.isFinished();
+  }
+
+  /**
+   * Specifies the set of subsystems used by this command. Two commands cannot use the same
+   * subsystem at the same time. If the command is scheduled as interruptible and another command is
+   * scheduled that shares a requirement, the command will be interrupted. Else, the command will
+   * not be scheduled. If no subsystems are required, return an empty set.
+   *
+   * <p>Note: it is recommended that user implementations contain the requirements as a field, and
+   * return that field here, rather than allocating a new set every time this is called.
+   *
+   * @return the set of subsystems that are required
+   */
+  @Override
+  public Set<Subsystem> getRequirements() {
+    return m_command.getRequirements();
+  }
+
+  /**
+   * Whether the given command should run when the robot is disabled. Override to return true if the
+   * command should run when disabled.
+   *
+   * @return whether the command should run when the robot is disabled
+   */
+  @Override
+  public boolean runsWhenDisabled() {
+    return m_command.runsWhenDisabled();
+  }
+
+  @Override
+  public InterruptionBehavior getInterruptionBehavior() {
+    return m_command.getInterruptionBehavior();
+  }
+}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/Button.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/Button.java
index a50512f..4e4e11a 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/Button.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/Button.java
@@ -18,20 +18,25 @@
  * operator interface as a common use case of the more generalized Trigger objects. This is a simple
  * wrapper around Trigger with the method names renamed to fit the Button object use.
  *
- * <p>This class is provided by the OldCommands VendorDep
+ * @deprecated Replace with {@link Trigger}.
  */
+@Deprecated
 public class Button extends Trigger {
   /**
-   * Default constructor; creates a button that is never pressed (unless {@link Button#get()} is
-   * overridden).
+   * Default constructor; creates a button that is never pressed.
+   *
+   * @deprecated Replace with {@code new Button(() -> false) }.
    */
+  @Deprecated(since = "2023")
   public Button() {}
 
   /**
    * Creates a new button with the given condition determining whether it is pressed.
    *
-   * @param isPressed returns whether or not the trigger should be active
+   * @param isPressed returns whether the trigger should be active
+   * @deprecated Replace with Trigger.
    */
+  @Deprecated
   public Button(BooleanSupplier isPressed) {
     super(isPressed);
   }
@@ -40,21 +45,10 @@
    * Starts the given command whenever the button is newly pressed.
    *
    * @param command the command to start
-   * @param interruptible whether the command is interruptible
    * @return this button, so calls can be chained
+   * @deprecated Replace with {@link Trigger#onTrue(Command)}
    */
-  public Button whenPressed(final Command command, boolean interruptible) {
-    whenActive(command, interruptible);
-    return this;
-  }
-
-  /**
-   * Starts the given command whenever the button is newly pressed. The command is set to be
-   * interruptible.
-   *
-   * @param command the command to start
-   * @return this button, so calls can be chained
-   */
+  @Deprecated
   public Button whenPressed(final Command command) {
     whenActive(command);
     return this;
@@ -66,7 +60,9 @@
    * @param toRun the runnable to run
    * @param requirements the required subsystems
    * @return this button, so calls can be chained
+   * @deprecated Replace with {@link #onTrue(Command)}, creating the InstantCommand manually
    */
+  @Deprecated
   public Button whenPressed(final Runnable toRun, Subsystem... requirements) {
     whenActive(toRun, requirements);
     return this;
@@ -75,27 +71,15 @@
   /**
    * Constantly starts the given command while the button is held.
    *
-   * <p>{@link Command#schedule(boolean)} will be called repeatedly while the button is held, and
-   * will be canceled when the button is released.
-   *
-   * @param command the command to start
-   * @param interruptible whether the command is interruptible
-   * @return this button, so calls can be chained
-   */
-  public Button whileHeld(final Command command, boolean interruptible) {
-    whileActiveContinuous(command, interruptible);
-    return this;
-  }
-
-  /**
-   * Constantly starts the given command while the button is held.
-   *
-   * <p>{@link Command#schedule(boolean)} will be called repeatedly while the button is held, and
-   * will be canceled when the button is released. The command is set to be interruptible.
+   * <p>{@link Command#schedule()} will be called repeatedly while the button is held, and will be
+   * canceled when the button is released.
    *
    * @param command the command to start
    * @return this button, so calls can be chained
+   * @deprecated Use {@link #whileTrue(Command)} with {@link
+   *     edu.wpi.first.wpilibj2.command.RepeatCommand RepeatCommand}.
    */
+  @Deprecated
   public Button whileHeld(final Command command) {
     whileActiveContinuous(command);
     return this;
@@ -107,7 +91,9 @@
    * @param toRun the runnable to run
    * @param requirements the required subsystems
    * @return this button, so calls can be chained
+   * @deprecated Use {@link #whileTrue(Command)} and construct a RunCommand manually
    */
+  @Deprecated
   public Button whileHeld(final Runnable toRun, Subsystem... requirements) {
     whileActiveContinuous(toRun, requirements);
     return this;
@@ -118,36 +104,12 @@
    * but does not start it again if it ends or is otherwise interrupted.
    *
    * @param command the command to start
-   * @param interruptible whether the command is interruptible
    * @return this button, so calls can be chained
+   * @deprecated Replace with {@link Trigger#whileTrue(Command)}
    */
-  public Button whenHeld(final Command command, boolean interruptible) {
-    whileActiveOnce(command, interruptible);
-    return this;
-  }
-
-  /**
-   * Starts the given command when the button is first pressed, and cancels it when it is released,
-   * but does not start it again if it ends or is otherwise interrupted. The command is set to be
-   * interruptible.
-   *
-   * @param command the command to start
-   * @return this button, so calls can be chained
-   */
+  @Deprecated
   public Button whenHeld(final Command command) {
-    whileActiveOnce(command, true);
-    return this;
-  }
-
-  /**
-   * Starts the command when the button is released.
-   *
-   * @param command the command to start
-   * @param interruptible whether the command is interruptible
-   * @return this button, so calls can be chained
-   */
-  public Button whenReleased(final Command command, boolean interruptible) {
-    whenInactive(command, interruptible);
+    whileActiveOnce(command);
     return this;
   }
 
@@ -156,7 +118,9 @@
    *
    * @param command the command to start
    * @return this button, so calls can be chained
+   * @deprecated Replace with {@link Trigger#onFalse(Command)}
    */
+  @Deprecated
   public Button whenReleased(final Command command) {
     whenInactive(command);
     return this;
@@ -168,31 +132,23 @@
    * @param toRun the runnable to run
    * @param requirements the required subsystems
    * @return this button, so calls can be chained
+   * @deprecated Replace with {@link Trigger#onFalse(Command)}, creating the InstantCommand manually
    */
+  @Deprecated
   public Button whenReleased(final Runnable toRun, Subsystem... requirements) {
     whenInactive(toRun, requirements);
     return this;
   }
 
   /**
-   * Toggles the command whenever the button is pressed (on then off then on).
-   *
-   * @param command the command to start
-   * @param interruptible whether the command is interruptible
-   * @return this button, so calls can be chained
-   */
-  public Button toggleWhenPressed(final Command command, boolean interruptible) {
-    toggleWhenActive(command, interruptible);
-    return this;
-  }
-
-  /**
-   * Toggles the command whenever the button is pressed (on then off then on). The command is set to
-   * be interruptible.
+   * Toggles the command whenever the button is pressed (on, then off, then on). The command is set
+   * to be interruptible.
    *
    * @param command the command to start
    * @return this button, so calls can be chained
+   * @deprecated Replace with {@link Trigger#toggleOnTrue(Command)}
    */
+  @Deprecated
   public Button toggleWhenPressed(final Command command) {
     toggleWhenActive(command);
     return this;
@@ -203,7 +159,9 @@
    *
    * @param command the command to start
    * @return this button, so calls can be chained
+   * @deprecated Instead, pass this as an end condition to {@link Command#until(BooleanSupplier)}.
    */
+  @Deprecated
   public Button cancelWhenPressed(final Command command) {
     cancelWhenActive(command);
     return this;
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/CommandGenericHID.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/CommandGenericHID.java
new file mode 100644
index 0000000..fadff92
--- /dev/null
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/CommandGenericHID.java
@@ -0,0 +1,255 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj2.command.button;
+
+import edu.wpi.first.wpilibj.GenericHID;
+import edu.wpi.first.wpilibj.event.EventLoop;
+import edu.wpi.first.wpilibj2.command.CommandScheduler;
+
+/**
+ * A version of {@link GenericHID} with {@link Trigger} factories for command-based.
+ *
+ * @see GenericHID
+ */
+public class CommandGenericHID {
+  private final GenericHID m_hid;
+
+  /**
+   * Construct an instance of a device.
+   *
+   * @param port The port index on the Driver Station that the device is plugged into.
+   */
+  public CommandGenericHID(int port) {
+    m_hid = new GenericHID(port);
+  }
+
+  /**
+   * Get the underlying GenericHID object.
+   *
+   * @return the wrapped GenericHID object
+   */
+  public GenericHID getHID() {
+    return m_hid;
+  }
+
+  /**
+   * Constructs an event instance around this button's digital signal.
+   *
+   * @param button the button index
+   * @return an event instance representing the button's digital signal attached to the {@link
+   *     CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+   * @see #button(int, EventLoop)
+   */
+  public Trigger button(int button) {
+    return this.button(button, CommandScheduler.getInstance().getDefaultButtonLoop());
+  }
+
+  /**
+   * Constructs an event instance around this button's digital signal.
+   *
+   * @param button the button index
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the button's digital signal attached to the given loop.
+   */
+  public Trigger button(int button, EventLoop loop) {
+    return new Trigger(loop, () -> m_hid.getRawButton(button));
+  }
+
+  /**
+   * Constructs a Trigger instance based around this angle of the default (index 0) POV on the HID,
+   * attached to {@link CommandScheduler#getDefaultButtonLoop() the default command scheduler button
+   * loop}.
+   *
+   * <p>The POV angles start at 0 in the up direction, and increase clockwise (e.g. right is 90,
+   * upper-left is 315).
+   *
+   * @param angle POV angle in degrees, or -1 for the center / not pressed.
+   * @return a Trigger instance based around this angle of a POV on the HID.
+   */
+  public Trigger pov(int angle) {
+    return pov(0, angle, CommandScheduler.getInstance().getDefaultButtonLoop());
+  }
+
+  /**
+   * Constructs a Trigger instance based around this angle of a POV on the HID.
+   *
+   * <p>The POV angles start at 0 in the up direction, and increase clockwise (e.g. right is 90,
+   * upper-left is 315).
+   *
+   * @param pov index of the POV to read (starting at 0). Defaults to 0.
+   * @param angle POV angle in degrees, or -1 for the center / not pressed.
+   * @param loop the event loop instance to attach the event to. Defaults to {@link
+   *     CommandScheduler#getDefaultButtonLoop() the default command scheduler button loop}.
+   * @return a Trigger instance based around this angle of a POV on the HID.
+   */
+  public Trigger pov(int pov, int angle, EventLoop loop) {
+    return new Trigger(loop, () -> m_hid.getPOV(pov) == angle);
+  }
+
+  /**
+   * Constructs a Trigger instance based around the 0 degree angle (up) of the default (index 0) POV
+   * on the HID, attached to {@link CommandScheduler#getDefaultButtonLoop() the default command
+   * scheduler button loop}.
+   *
+   * @return a Trigger instance based around the 0 degree angle of a POV on the HID.
+   */
+  public Trigger povUp() {
+    return pov(0);
+  }
+
+  /**
+   * Constructs a Trigger instance based around the 45 degree angle (right up) of the default (index
+   * 0) POV on the HID, attached to {@link CommandScheduler#getDefaultButtonLoop() the default
+   * command scheduler button loop}.
+   *
+   * @return a Trigger instance based around the 45 degree angle of a POV on the HID.
+   */
+  public Trigger povUpRight() {
+    return pov(45);
+  }
+
+  /**
+   * Constructs a Trigger instance based around the 90 degree angle (right) of the default (index 0)
+   * POV on the HID, attached to {@link CommandScheduler#getDefaultButtonLoop() the default command
+   * scheduler button loop}.
+   *
+   * @return a Trigger instance based around the 90 degree angle of a POV on the HID.
+   */
+  public Trigger povRight() {
+    return pov(90);
+  }
+
+  /**
+   * Constructs a Trigger instance based around the 135 degree angle (right down) of the default
+   * (index 0) POV on the HID, attached to {@link CommandScheduler#getDefaultButtonLoop() the
+   * default command scheduler button loop}.
+   *
+   * @return a Trigger instance based around the 135 degree angle of a POV on the HID.
+   */
+  public Trigger povDownRight() {
+    return pov(135);
+  }
+
+  /**
+   * Constructs a Trigger instance based around the 180 degree angle (down) of the default (index 0)
+   * POV on the HID, attached to {@link CommandScheduler#getDefaultButtonLoop() the default command
+   * scheduler button loop}.
+   *
+   * @return a Trigger instance based around the 180 degree angle of a POV on the HID.
+   */
+  public Trigger povDown() {
+    return pov(180);
+  }
+
+  /**
+   * Constructs a Trigger instance based around the 225 degree angle (down left) of the default
+   * (index 0) POV on the HID, attached to {@link CommandScheduler#getDefaultButtonLoop() the
+   * default command scheduler button loop}.
+   *
+   * @return a Trigger instance based around the 225 degree angle of a POV on the HID.
+   */
+  public Trigger povDownLeft() {
+    return pov(225);
+  }
+
+  /**
+   * Constructs a Trigger instance based around the 270 degree angle (left) of the default (index 0)
+   * POV on the HID, attached to {@link CommandScheduler#getDefaultButtonLoop() the default command
+   * scheduler button loop}.
+   *
+   * @return a Trigger instance based around the 270 degree angle of a POV on the HID.
+   */
+  public Trigger povLeft() {
+    return pov(270);
+  }
+
+  /**
+   * Constructs a Trigger instance based around the 315 degree angle (left up) of the default (index
+   * 0) POV on the HID, attached to {@link CommandScheduler#getDefaultButtonLoop() the default
+   * command scheduler button loop}.
+   *
+   * @return a Trigger instance based around the 315 degree angle of a POV on the HID.
+   */
+  public Trigger povUpLeft() {
+    return pov(315);
+  }
+
+  /**
+   * Constructs a Trigger instance based around the center (not pressed) position of the default
+   * (index 0) POV on the HID, attached to {@link CommandScheduler#getDefaultButtonLoop() the
+   * default command scheduler button loop}.
+   *
+   * @return a Trigger instance based around the center position of a POV on the HID.
+   */
+  public Trigger povCenter() {
+    return pov(-1);
+  }
+
+  /**
+   * Constructs a Trigger instance that is true when the axis value is less than {@code threshold},
+   * attached to {@link CommandScheduler#getDefaultButtonLoop() the default command scheduler button
+   * loop}.
+   *
+   * @param axis The axis to read, starting at 0
+   * @param threshold The value below which this trigger should return true.
+   * @return a Trigger instance that is true when the axis value is less than the provided
+   *     threshold.
+   */
+  public Trigger axisLessThan(int axis, double threshold) {
+    return axisLessThan(axis, threshold, CommandScheduler.getInstance().getDefaultButtonLoop());
+  }
+
+  /**
+   * Constructs a Trigger instance that is true when the axis value is less than {@code threshold},
+   * attached to the given loop.
+   *
+   * @param axis The axis to read, starting at 0
+   * @param threshold The value below which this trigger should return true.
+   * @param loop the event loop instance to attach the trigger to
+   * @return a Trigger instance that is true when the axis value is less than the provided
+   *     threshold.
+   */
+  public Trigger axisLessThan(int axis, double threshold, EventLoop loop) {
+    return m_hid.axisLessThan(axis, threshold, loop).castTo(Trigger::new);
+  }
+
+  /**
+   * Constructs a Trigger instance that is true when the axis value is less than {@code threshold},
+   * attached to {@link CommandScheduler#getDefaultButtonLoop() the default command scheduler button
+   * loop}.
+   *
+   * @param axis The axis to read, starting at 0
+   * @param threshold The value above which this trigger should return true.
+   * @return a Trigger instance that is true when the axis value is greater than the provided
+   *     threshold.
+   */
+  public Trigger axisGreaterThan(int axis, double threshold) {
+    return axisGreaterThan(axis, threshold, CommandScheduler.getInstance().getDefaultButtonLoop());
+  }
+
+  /**
+   * Constructs a Trigger instance that is true when the axis value is greater than {@code
+   * threshold}, attached to the given loop.
+   *
+   * @param axis The axis to read, starting at 0
+   * @param threshold The value above which this trigger should return true.
+   * @param loop the event loop instance to attach the trigger to.
+   * @return a Trigger instance that is true when the axis value is greater than the provided
+   *     threshold.
+   */
+  public Trigger axisGreaterThan(int axis, double threshold, EventLoop loop) {
+    return m_hid.axisGreaterThan(axis, threshold, loop).castTo(Trigger::new);
+  }
+
+  /**
+   * Get the value of the axis.
+   *
+   * @param axis The axis to read, starting at 0.
+   * @return The value of the axis.
+   */
+  public double getRawAxis(int axis) {
+    return m_hid.getRawAxis(axis);
+  }
+}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/CommandJoystick.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/CommandJoystick.java
new file mode 100644
index 0000000..9f3d48a
--- /dev/null
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/CommandJoystick.java
@@ -0,0 +1,247 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj2.command.button;
+
+import edu.wpi.first.wpilibj.Joystick;
+import edu.wpi.first.wpilibj.event.EventLoop;
+import edu.wpi.first.wpilibj2.command.CommandScheduler;
+
+/**
+ * A subclass of {@link Joystick} with {@link Trigger} factories for command-based.
+ *
+ * @see Joystick
+ */
+public class CommandJoystick extends CommandGenericHID {
+  private final Joystick m_hid;
+
+  /**
+   * Construct an instance of a controller.
+   *
+   * @param port The port index on the Driver Station that the controller is plugged into.
+   */
+  public CommandJoystick(int port) {
+    super(port);
+    m_hid = new Joystick(port);
+  }
+
+  /**
+   * Get the underlying GenericHID object.
+   *
+   * @return the wrapped GenericHID object
+   */
+  @Override
+  public Joystick getHID() {
+    return m_hid;
+  }
+
+  /**
+   * Constructs an event instance around the trigger button's digital signal.
+   *
+   * @return an event instance representing the trigger button's digital signal attached to the
+   *     {@link CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+   * @see #trigger(EventLoop)
+   */
+  public Trigger trigger() {
+    return trigger(CommandScheduler.getInstance().getDefaultButtonLoop());
+  }
+
+  /**
+   * Constructs an event instance around the trigger button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the trigger button's digital signal attached to the
+   *     given loop.
+   */
+  public Trigger trigger(EventLoop loop) {
+    return m_hid.trigger(loop).castTo(Trigger::new);
+  }
+
+  /**
+   * Constructs an event instance around the top button's digital signal.
+   *
+   * @return an event instance representing the top button's digital signal attached to the {@link
+   *     CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+   * @see #top(EventLoop)
+   */
+  public Trigger top() {
+    return top(CommandScheduler.getInstance().getDefaultButtonLoop());
+  }
+
+  /**
+   * Constructs an event instance around the top button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the top button's digital signal attached to the given
+   *     loop.
+   */
+  public Trigger top(EventLoop loop) {
+    return m_hid.top(loop).castTo(Trigger::new);
+  }
+
+  /**
+   * Set the channel associated with the X axis.
+   *
+   * @param channel The channel to set the axis to.
+   */
+  public void setXChannel(int channel) {
+    m_hid.setXChannel(channel);
+  }
+
+  /**
+   * Set the channel associated with the Y axis.
+   *
+   * @param channel The channel to set the axis to.
+   */
+  public void setYChannel(int channel) {
+    m_hid.setYChannel(channel);
+  }
+
+  /**
+   * Set the channel associated with the Z axis.
+   *
+   * @param channel The channel to set the axis to.
+   */
+  public void setZChannel(int channel) {
+    m_hid.setZChannel(channel);
+  }
+
+  /**
+   * Set the channel associated with the throttle axis.
+   *
+   * @param channel The channel to set the axis to.
+   */
+  public void setThrottleChannel(int channel) {
+    m_hid.setThrottleChannel(channel);
+  }
+
+  /**
+   * Set the channel associated with the twist axis.
+   *
+   * @param channel The channel to set the axis to.
+   */
+  public void setTwistChannel(int channel) {
+    m_hid.setTwistChannel(channel);
+  }
+
+  /**
+   * Get the channel currently associated with the X axis.
+   *
+   * @return The channel for the axis.
+   */
+  public int getXChannel() {
+    return m_hid.getXChannel();
+  }
+
+  /**
+   * Get the channel currently associated with the Y axis.
+   *
+   * @return The channel for the axis.
+   */
+  public int getYChannel() {
+    return m_hid.getYChannel();
+  }
+
+  /**
+   * Get the channel currently associated with the Z axis.
+   *
+   * @return The channel for the axis.
+   */
+  public int getZChannel() {
+    return m_hid.getZChannel();
+  }
+
+  /**
+   * Get the channel currently associated with the twist axis.
+   *
+   * @return The channel for the axis.
+   */
+  public int getTwistChannel() {
+    return m_hid.getTwistChannel();
+  }
+
+  /**
+   * Get the channel currently associated with the throttle axis.
+   *
+   * @return The channel for the axis.
+   */
+  public int getThrottleChannel() {
+    return m_hid.getThrottleChannel();
+  }
+
+  /**
+   * Get the x position of the HID.
+   *
+   * @return the x position
+   */
+  public double getX() {
+    return m_hid.getX();
+  }
+
+  /**
+   * Get the y position of the HID.
+   *
+   * @return the y position
+   */
+  public double getY() {
+    return m_hid.getY();
+  }
+
+  /**
+   * Get the z position of the HID.
+   *
+   * @return the z position
+   */
+  public double getZ() {
+    return m_hid.getZ();
+  }
+
+  /**
+   * Get the twist value of the current joystick. This depends on the mapping of the joystick
+   * connected to the current port.
+   *
+   * @return The Twist value of the joystick.
+   */
+  public double getTwist() {
+    return m_hid.getTwist();
+  }
+
+  /**
+   * Get the throttle value of the current joystick. This depends on the mapping of the joystick
+   * connected to the current port.
+   *
+   * @return The Throttle value of the joystick.
+   */
+  public double getThrottle() {
+    return m_hid.getThrottle();
+  }
+
+  /**
+   * Get the magnitude of the direction vector formed by the joystick's current position relative to
+   * its origin.
+   *
+   * @return The magnitude of the direction vector
+   */
+  public double getMagnitude() {
+    return m_hid.getMagnitude();
+  }
+
+  /**
+   * Get the direction of the vector formed by the joystick and its origin in radians.
+   *
+   * @return The direction of the vector in radians
+   */
+  public double getDirectionRadians() {
+    return m_hid.getDirectionRadians();
+  }
+
+  /**
+   * Get the direction of the vector formed by the joystick and its origin in degrees.
+   *
+   * @return The direction of the vector in degrees
+   */
+  public double getDirectionDegrees() {
+    return m_hid.getDirectionDegrees();
+  }
+}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/CommandPS4Controller.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/CommandPS4Controller.java
new file mode 100644
index 0000000..a7c0ac7
--- /dev/null
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/CommandPS4Controller.java
@@ -0,0 +1,389 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj2.command.button;
+
+import edu.wpi.first.wpilibj.PS4Controller;
+import edu.wpi.first.wpilibj.event.EventLoop;
+import edu.wpi.first.wpilibj2.command.CommandScheduler;
+
+/**
+ * A version of {@link PS4Controller} with {@link Trigger} factories for command-based.
+ *
+ * @see PS4Controller
+ */
+@SuppressWarnings("MethodName")
+public class CommandPS4Controller extends CommandGenericHID {
+  private final PS4Controller m_hid;
+
+  /**
+   * Construct an instance of a device.
+   *
+   * @param port The port index on the Driver Station that the device is plugged into.
+   */
+  public CommandPS4Controller(int port) {
+    super(port);
+    m_hid = new PS4Controller(port);
+  }
+
+  /**
+   * Get the underlying GenericHID object.
+   *
+   * @return the wrapped GenericHID object
+   */
+  @Override
+  public PS4Controller getHID() {
+    return m_hid;
+  }
+
+  /**
+   * Constructs an event instance around the L2 button's digital signal.
+   *
+   * @return an event instance representing the L2 button's digital signal attached to the {@link
+   *     CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+   */
+  public Trigger L2() {
+    return L2(CommandScheduler.getInstance().getDefaultButtonLoop());
+  }
+
+  /**
+   * Constructs an event instance around the L2 button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the L2 button's digital signal attached to the given
+   *     loop.
+   */
+  public Trigger L2(EventLoop loop) {
+    return m_hid.L2(loop).castTo(Trigger::new);
+  }
+
+  /**
+   * Constructs an event instance around the R2 button's digital signal.
+   *
+   * @return an event instance representing the R2 button's digital signal attached to the {@link
+   *     CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+   */
+  public Trigger R2() {
+    return R2(CommandScheduler.getInstance().getDefaultButtonLoop());
+  }
+
+  /**
+   * Constructs an event instance around the R2 button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the R2 button's digital signal attached to the given
+   *     loop.
+   */
+  public Trigger R2(EventLoop loop) {
+    return m_hid.R2(loop).castTo(Trigger::new);
+  }
+
+  /**
+   * Constructs an event instance around the L1 button's digital signal.
+   *
+   * @return an event instance representing the L1 button's digital signal attached to the {@link
+   *     CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+   */
+  public Trigger L1() {
+    return L1(CommandScheduler.getInstance().getDefaultButtonLoop());
+  }
+
+  /**
+   * Constructs an event instance around the L1 button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the L1 button's digital signal attached to the given
+   *     loop.
+   */
+  public Trigger L1(EventLoop loop) {
+    return m_hid.L1(loop).castTo(Trigger::new);
+  }
+
+  /**
+   * Constructs an event instance around the R1 button's digital signal.
+   *
+   * @return an event instance representing the R1 button's digital signal attached to the {@link
+   *     CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+   */
+  public Trigger R1() {
+    return R1(CommandScheduler.getInstance().getDefaultButtonLoop());
+  }
+
+  /**
+   * Constructs an event instance around the R1 button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the R1 button's digital signal attached to the given
+   *     loop.
+   */
+  public Trigger R1(EventLoop loop) {
+    return m_hid.R1(loop).castTo(Trigger::new);
+  }
+
+  /**
+   * Constructs an event instance around the L3 button's digital signal.
+   *
+   * @return an event instance representing the L3 button's digital signal attached to the {@link
+   *     CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+   */
+  public Trigger L3() {
+    return L3(CommandScheduler.getInstance().getDefaultButtonLoop());
+  }
+
+  /**
+   * Constructs an event instance around the L3 button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the L3 button's digital signal attached to the given
+   *     loop.
+   */
+  public Trigger L3(EventLoop loop) {
+    return m_hid.L3(loop).castTo(Trigger::new);
+  }
+
+  /**
+   * Constructs an event instance around the R3 button's digital signal.
+   *
+   * @return an event instance representing the R3 button's digital signal attached to the {@link
+   *     CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+   */
+  public Trigger R3() {
+    return R3(CommandScheduler.getInstance().getDefaultButtonLoop());
+  }
+
+  /**
+   * Constructs an event instance around the R3 button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the R3 button's digital signal attached to the given
+   *     loop.
+   */
+  public Trigger R3(EventLoop loop) {
+    return m_hid.R3(loop).castTo(Trigger::new);
+  }
+
+  /**
+   * Constructs an event instance around the square button's digital signal.
+   *
+   * @return an event instance representing the square button's digital signal attached to the
+   *     {@link CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+   */
+  public Trigger square() {
+    return square(CommandScheduler.getInstance().getDefaultButtonLoop());
+  }
+
+  /**
+   * Constructs an event instance around the square button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the square button's digital signal attached to the given
+   *     loop.
+   */
+  public Trigger square(EventLoop loop) {
+    return m_hid.square(loop).castTo(Trigger::new);
+  }
+
+  /**
+   * Constructs an event instance around the cross button's digital signal.
+   *
+   * @return an event instance representing the cross button's digital signal attached to the {@link
+   *     CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+   */
+  public Trigger cross() {
+    return cross(CommandScheduler.getInstance().getDefaultButtonLoop());
+  }
+
+  /**
+   * Constructs an event instance around the cross button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the cross button's digital signal attached to the given
+   *     loop.
+   */
+  public Trigger cross(EventLoop loop) {
+    return m_hid.cross(loop).castTo(Trigger::new);
+  }
+
+  /**
+   * Constructs an event instance around the triangle button's digital signal.
+   *
+   * @return an event instance representing the triangle button's digital signal attached to the
+   *     {@link CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+   */
+  public Trigger triangle() {
+    return triangle(CommandScheduler.getInstance().getDefaultButtonLoop());
+  }
+
+  /**
+   * Constructs an event instance around the triangle button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the triangle button's digital signal attached to the
+   *     given loop.
+   */
+  public Trigger triangle(EventLoop loop) {
+    return m_hid.triangle(loop).castTo(Trigger::new);
+  }
+
+  /**
+   * Constructs an event instance around the circle button's digital signal.
+   *
+   * @return an event instance representing the circle button's digital signal attached to the
+   *     {@link CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+   */
+  public Trigger circle() {
+    return circle(CommandScheduler.getInstance().getDefaultButtonLoop());
+  }
+
+  /**
+   * Constructs an event instance around the circle button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the circle button's digital signal attached to the given
+   *     loop.
+   */
+  public Trigger circle(EventLoop loop) {
+    return m_hid.circle(loop).castTo(Trigger::new);
+  }
+
+  /**
+   * Constructs an event instance around the share button's digital signal.
+   *
+   * @return an event instance representing the share button's digital signal attached to the {@link
+   *     CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+   */
+  public Trigger share() {
+    return share(CommandScheduler.getInstance().getDefaultButtonLoop());
+  }
+
+  /**
+   * Constructs an event instance around the share button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the share button's digital signal attached to the given
+   *     loop.
+   */
+  public Trigger share(EventLoop loop) {
+    return m_hid.share(loop).castTo(Trigger::new);
+  }
+
+  /**
+   * Constructs an event instance around the PS button's digital signal.
+   *
+   * @return an event instance representing the PS button's digital signal attached to the {@link
+   *     CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+   */
+  public Trigger PS() {
+    return PS(CommandScheduler.getInstance().getDefaultButtonLoop());
+  }
+
+  /**
+   * Constructs an event instance around the PS button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the PS button's digital signal attached to the given
+   *     loop.
+   */
+  public Trigger PS(EventLoop loop) {
+    return m_hid.PS(loop).castTo(Trigger::new);
+  }
+
+  /**
+   * Constructs an event instance around the options button's digital signal.
+   *
+   * @return an event instance representing the options button's digital signal attached to the
+   *     {@link CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+   */
+  public Trigger options() {
+    return options(CommandScheduler.getInstance().getDefaultButtonLoop());
+  }
+
+  /**
+   * Constructs an event instance around the options button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the options button's digital signal attached to the
+   *     given loop.
+   */
+  public Trigger options(EventLoop loop) {
+    return m_hid.options(loop).castTo(Trigger::new);
+  }
+
+  /**
+   * Constructs an event instance around the touchpad's digital signal.
+   *
+   * @return an event instance representing the touchpad's digital signal attached to the {@link
+   *     CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+   */
+  public Trigger touchpad() {
+    return touchpad(CommandScheduler.getInstance().getDefaultButtonLoop());
+  }
+
+  /**
+   * Constructs an event instance around the touchpad's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the touchpad's digital signal attached to the given
+   *     loop.
+   */
+  public Trigger touchpad(EventLoop loop) {
+    return m_hid.touchpad(loop).castTo(Trigger::new);
+  }
+
+  /**
+   * Get the X axis value of left side of the controller.
+   *
+   * @return the axis value.
+   */
+  public double getLeftX() {
+    return m_hid.getLeftX();
+  }
+
+  /**
+   * Get the X axis value of right side of the controller.
+   *
+   * @return the axis value.
+   */
+  public double getRightX() {
+    return m_hid.getRightX();
+  }
+
+  /**
+   * Get the Y axis value of left side of the controller.
+   *
+   * @return the axis value.
+   */
+  public double getLeftY() {
+    return m_hid.getLeftY();
+  }
+
+  /**
+   * Get the Y axis value of right side of the controller.
+   *
+   * @return the axis value.
+   */
+  public double getRightY() {
+    return m_hid.getRightY();
+  }
+
+  /**
+   * Get the L2 axis value of the controller. Note that this axis is bound to the range of [0, 1] as
+   * opposed to the usual [-1, 1].
+   *
+   * @return the axis value.
+   */
+  public double getL2Axis() {
+    return m_hid.getL2Axis();
+  }
+
+  /**
+   * Get the R2 axis value of the controller. Note that this axis is bound to the range of [0, 1] as
+   * opposed to the usual [-1, 1].
+   *
+   * @return the axis value.
+   */
+  public double getR2Axis() {
+    return m_hid.getR2Axis();
+  }
+}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/CommandXboxController.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/CommandXboxController.java
new file mode 100644
index 0000000..1e83e83
--- /dev/null
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/CommandXboxController.java
@@ -0,0 +1,393 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj2.command.button;
+
+import edu.wpi.first.wpilibj.XboxController;
+import edu.wpi.first.wpilibj.event.EventLoop;
+import edu.wpi.first.wpilibj2.command.CommandScheduler;
+
+/**
+ * A subclass of {@link XboxController} with {@link Trigger} factories for command-based.
+ *
+ * @see XboxController
+ */
+@SuppressWarnings("MethodName")
+public class CommandXboxController extends CommandGenericHID {
+  private final XboxController m_hid;
+
+  /**
+   * Construct an instance of a controller.
+   *
+   * @param port The port index on the Driver Station that the controller is plugged into.
+   */
+  public CommandXboxController(int port) {
+    super(port);
+    m_hid = new XboxController(port);
+  }
+
+  /**
+   * Get the underlying GenericHID object.
+   *
+   * @return the wrapped GenericHID object
+   */
+  @Override
+  public XboxController getHID() {
+    return m_hid;
+  }
+
+  /**
+   * Constructs an event instance around the left bumper's digital signal.
+   *
+   * @return an event instance representing the left bumper's digital signal attached to the {@link
+   *     CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+   * @see #leftBumper(EventLoop)
+   */
+  public Trigger leftBumper() {
+    return leftBumper(CommandScheduler.getInstance().getDefaultButtonLoop());
+  }
+
+  /**
+   * Constructs an event instance around the left bumper's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the right bumper's digital signal attached to the given
+   *     loop.
+   */
+  public Trigger leftBumper(EventLoop loop) {
+    return m_hid.leftBumper(loop).castTo(Trigger::new);
+  }
+
+  /**
+   * Constructs an event instance around the right bumper's digital signal.
+   *
+   * @return an event instance representing the right bumper's digital signal attached to the {@link
+   *     CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+   * @see #rightBumper(EventLoop)
+   */
+  public Trigger rightBumper() {
+    return rightBumper(CommandScheduler.getInstance().getDefaultButtonLoop());
+  }
+
+  /**
+   * Constructs an event instance around the right bumper's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the left bumper's digital signal attached to the given
+   *     loop.
+   */
+  public Trigger rightBumper(EventLoop loop) {
+    return m_hid.rightBumper(loop).castTo(Trigger::new);
+  }
+
+  /**
+   * Constructs an event instance around the left stick button's digital signal.
+   *
+   * @return an event instance representing the left stick button's digital signal attached to the
+   *     {@link CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+   * @see #leftStick(EventLoop)
+   */
+  public Trigger leftStick() {
+    return leftStick(CommandScheduler.getInstance().getDefaultButtonLoop());
+  }
+
+  /**
+   * Constructs an event instance around the left stick button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the left stick button's digital signal attached to the
+   *     given loop.
+   */
+  public Trigger leftStick(EventLoop loop) {
+    return m_hid.leftStick(loop).castTo(Trigger::new);
+  }
+
+  /**
+   * Constructs an event instance around the right stick button's digital signal.
+   *
+   * @return an event instance representing the right stick button's digital signal attached to the
+   *     {@link CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+   * @see #rightStick(EventLoop)
+   */
+  public Trigger rightStick() {
+    return rightStick(CommandScheduler.getInstance().getDefaultButtonLoop());
+  }
+
+  /**
+   * Constructs an event instance around the right stick button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the right stick button's digital signal attached to the
+   *     given loop.
+   */
+  public Trigger rightStick(EventLoop loop) {
+    return m_hid.rightStick(loop).castTo(Trigger::new);
+  }
+
+  /**
+   * Constructs an event instance around the A button's digital signal.
+   *
+   * @return an event instance representing the A button's digital signal attached to the {@link
+   *     CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+   * @see #a(EventLoop)
+   */
+  public Trigger a() {
+    return a(CommandScheduler.getInstance().getDefaultButtonLoop());
+  }
+
+  /**
+   * Constructs an event instance around the A button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the A button's digital signal attached to the given
+   *     loop.
+   */
+  public Trigger a(EventLoop loop) {
+    return m_hid.a(loop).castTo(Trigger::new);
+  }
+
+  /**
+   * Constructs an event instance around the B button's digital signal.
+   *
+   * @return an event instance representing the B button's digital signal attached to the {@link
+   *     CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+   * @see #b(EventLoop)
+   */
+  public Trigger b() {
+    return b(CommandScheduler.getInstance().getDefaultButtonLoop());
+  }
+
+  /**
+   * Constructs an event instance around the B button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the B button's digital signal attached to the given
+   *     loop.
+   */
+  public Trigger b(EventLoop loop) {
+    return m_hid.b(loop).castTo(Trigger::new);
+  }
+
+  /**
+   * Constructs an event instance around the X button's digital signal.
+   *
+   * @return an event instance representing the X button's digital signal attached to the {@link
+   *     CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+   * @see #x(EventLoop)
+   */
+  public Trigger x() {
+    return x(CommandScheduler.getInstance().getDefaultButtonLoop());
+  }
+
+  /**
+   * Constructs an event instance around the X button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the X button's digital signal attached to the given
+   *     loop.
+   */
+  public Trigger x(EventLoop loop) {
+    return m_hid.x(loop).castTo(Trigger::new);
+  }
+
+  /**
+   * Constructs an event instance around the Y button's digital signal.
+   *
+   * @return an event instance representing the Y button's digital signal attached to the {@link
+   *     CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+   * @see #y(EventLoop)
+   */
+  public Trigger y() {
+    return y(CommandScheduler.getInstance().getDefaultButtonLoop());
+  }
+
+  /**
+   * Constructs an event instance around the Y button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the Y button's digital signal attached to the given
+   *     loop.
+   */
+  public Trigger y(EventLoop loop) {
+    return m_hid.y(loop).castTo(Trigger::new);
+  }
+
+  /**
+   * Constructs an event instance around the start button's digital signal.
+   *
+   * @return an event instance representing the start button's digital signal attached to the {@link
+   *     CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+   * @see #start(EventLoop)
+   */
+  public Trigger start() {
+    return start(CommandScheduler.getInstance().getDefaultButtonLoop());
+  }
+
+  /**
+   * Constructs an event instance around the start button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the start button's digital signal attached to the given
+   *     loop.
+   */
+  public Trigger start(EventLoop loop) {
+    return m_hid.start(loop).castTo(Trigger::new);
+  }
+
+  /**
+   * Constructs an event instance around the back button's digital signal.
+   *
+   * @return an event instance representing the back button's digital signal attached to the {@link
+   *     CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+   * @see #back(EventLoop)
+   */
+  public Trigger back() {
+    return back(CommandScheduler.getInstance().getDefaultButtonLoop());
+  }
+
+  /**
+   * Constructs an event instance around the back button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the back button's digital signal attached to the given
+   *     loop.
+   */
+  public Trigger back(EventLoop loop) {
+    return m_hid.back(loop).castTo(Trigger::new);
+  }
+
+  /**
+   * Constructs a Trigger instance around the axis value of the left trigger. The returned trigger
+   * will be true when the axis value is greater than {@code threshold}.
+   *
+   * @param loop the event loop instance to attach the Trigger to.
+   * @param threshold the minimum axis value for the returned {@link Trigger} to be true. This value
+   *     should be in the range [0, 1] where 0 is the unpressed state of the axis.
+   * @return a Trigger instance that is true when the left trigger's axis exceeds the provided
+   *     threshold, attached to the given event loop
+   */
+  public Trigger leftTrigger(EventLoop loop, double threshold) {
+    return m_hid.leftTrigger(threshold, loop).castTo(Trigger::new);
+  }
+
+  /**
+   * Constructs a Trigger instance around the axis value of the left trigger. The returned trigger
+   * will be true when the axis value is greater than {@code threshold}.
+   *
+   * @param threshold the minimum axis value for the returned {@link Trigger} to be true. This value
+   *     should be in the range [0, 1] where 0 is the unpressed state of the axis.
+   * @return a Trigger instance that is true when the left trigger's axis exceeds the provided
+   *     threshold, attached to the {@link CommandScheduler#getDefaultButtonLoop() default scheduler
+   *     button loop}.
+   */
+  public Trigger leftTrigger(double threshold) {
+    return leftTrigger(CommandScheduler.getInstance().getDefaultButtonLoop(), threshold);
+  }
+
+  /**
+   * Constructs a Trigger instance around the axis value of the left trigger. The returned trigger
+   * will be true when the axis value is greater than 0.5.
+   *
+   * @return a Trigger instance that is true when the left trigger's axis exceeds 0.5, attached to
+   *     the {@link CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+   */
+  public Trigger leftTrigger() {
+    return leftTrigger(0.5);
+  }
+
+  /**
+   * Constructs a Trigger instance around the axis value of the right trigger. The returned trigger
+   * will be true when the axis value is greater than {@code threshold}.
+   *
+   * @param threshold the minimum axis value for the returned {@link Trigger} to be true. This value
+   *     should be in the range [0, 1] where 0 is the unpressed state of the axis.
+   * @param loop the event loop instance to attach the Trigger to.
+   * @return a Trigger instance that is true when the right trigger's axis exceeds the provided
+   *     threshold, attached to the given event loop
+   */
+  public Trigger rightTrigger(double threshold, EventLoop loop) {
+    return m_hid.rightTrigger(threshold, loop).castTo(Trigger::new);
+  }
+
+  /**
+   * Constructs a Trigger instance around the axis value of the right trigger. The returned trigger
+   * will be true when the axis value is greater than {@code threshold}.
+   *
+   * @param threshold the minimum axis value for the returned {@link Trigger} to be true. This value
+   *     should be in the range [0, 1] where 0 is the unpressed state of the axis.
+   * @return a Trigger instance that is true when the right trigger's axis exceeds the provided
+   *     threshold, attached to the {@link CommandScheduler#getDefaultButtonLoop() default scheduler
+   *     button loop}.
+   */
+  public Trigger rightTrigger(double threshold) {
+    return rightTrigger(threshold, CommandScheduler.getInstance().getDefaultButtonLoop());
+  }
+
+  /**
+   * Constructs a Trigger instance around the axis value of the right trigger. The returned trigger
+   * will be true when the axis value is greater than 0.5.
+   *
+   * @return a Trigger instance that is true when the right trigger's axis exceeds 0.5, attached to
+   *     the {@link CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+   */
+  public Trigger rightTrigger() {
+    return rightTrigger(0.5);
+  }
+
+  /**
+   * Get the X axis value of left side of the controller.
+   *
+   * @return The axis value.
+   */
+  public double getLeftX() {
+    return m_hid.getLeftX();
+  }
+
+  /**
+   * Get the X axis value of right side of the controller.
+   *
+   * @return The axis value.
+   */
+  public double getRightX() {
+    return m_hid.getRightX();
+  }
+
+  /**
+   * Get the Y axis value of left side of the controller.
+   *
+   * @return The axis value.
+   */
+  public double getLeftY() {
+    return m_hid.getLeftY();
+  }
+
+  /**
+   * Get the Y axis value of right side of the controller.
+   *
+   * @return The axis value.
+   */
+  public double getRightY() {
+    return m_hid.getRightY();
+  }
+
+  /**
+   * Get the left trigger (LT) axis value of the controller. Note that this axis is bound to the
+   * range of [0, 1] as opposed to the usual [-1, 1].
+   *
+   * @return The axis value.
+   */
+  public double getLeftTriggerAxis() {
+    return m_hid.getLeftTriggerAxis();
+  }
+
+  /**
+   * Get the right trigger (RT) axis value of the controller. Note that this axis is bound to the
+   * range of [0, 1] as opposed to the usual [-1, 1].
+   *
+   * @return The axis value.
+   */
+  public double getRightTriggerAxis() {
+    return m_hid.getRightTriggerAxis();
+  }
+}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/InternalButton.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/InternalButton.java
index d856089..3106264 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/InternalButton.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/InternalButton.java
@@ -4,15 +4,19 @@
 
 package edu.wpi.first.wpilibj2.command.button;
 
+import java.util.concurrent.atomic.AtomicBoolean;
+
 /**
  * This class is intended to be used within a program. The programmer can manually set its value.
- * Also includes a setting for whether or not it should invert its value.
+ * Also includes a setting for whether it should invert its value.
  *
  * <p>This class is provided by the NewCommands VendorDep
  */
+@SuppressWarnings("deprecation")
 public class InternalButton extends Button {
-  private boolean m_pressed;
-  private boolean m_inverted;
+  // need to be references, so they can be mutated after being captured in the constructor.
+  private final AtomicBoolean m_pressed;
+  private final AtomicBoolean m_inverted;
 
   /** Creates an InternalButton that is not inverted. */
   public InternalButton() {
@@ -26,19 +30,24 @@
    *     when set to false.
    */
   public InternalButton(boolean inverted) {
-    m_pressed = m_inverted = inverted;
+    this(new AtomicBoolean(), new AtomicBoolean(inverted));
+  }
+
+  /*
+   * Mock constructor so the AtomicBoolean objects can be constructed before the super
+   * constructor invocation.
+   */
+  private InternalButton(AtomicBoolean state, AtomicBoolean inverted) {
+    super(() -> state.get() != inverted.get());
+    this.m_pressed = state;
+    this.m_inverted = inverted;
   }
 
   public void setInverted(boolean inverted) {
-    m_inverted = inverted;
+    m_inverted.set(inverted);
   }
 
   public void setPressed(boolean pressed) {
-    m_pressed = pressed;
-  }
-
-  @Override
-  public boolean get() {
-    return m_pressed ^ m_inverted;
+    m_pressed.set(pressed);
   }
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/JoystickButton.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/JoystickButton.java
index ae4aa1c..f22d443 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/JoystickButton.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/JoystickButton.java
@@ -4,7 +4,7 @@
 
 package edu.wpi.first.wpilibj2.command.button;
 
-import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
 
 import edu.wpi.first.wpilibj.GenericHID;
 
@@ -13,10 +13,8 @@
  *
  * <p>This class is provided by the NewCommands VendorDep
  */
+@SuppressWarnings("deprecation")
 public class JoystickButton extends Button {
-  private final GenericHID m_joystick;
-  private final int m_buttonNumber;
-
   /**
    * Creates a joystick button for triggering commands.
    *
@@ -24,19 +22,7 @@
    * @param buttonNumber The button number (see {@link GenericHID#getRawButton(int) }
    */
   public JoystickButton(GenericHID joystick, int buttonNumber) {
+    super(() -> joystick.getRawButton(buttonNumber));
     requireNonNullParam(joystick, "joystick", "JoystickButton");
-
-    m_joystick = joystick;
-    m_buttonNumber = buttonNumber;
-  }
-
-  /**
-   * Gets the value of the joystick button.
-   *
-   * @return The value of the joystick button
-   */
-  @Override
-  public boolean get() {
-    return m_joystick.getRawButton(m_buttonNumber);
   }
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/NetworkButton.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/NetworkButton.java
index 5c66af6..b21cd97 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/NetworkButton.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/NetworkButton.java
@@ -4,8 +4,11 @@
 
 package edu.wpi.first.wpilibj2.command.button;
 
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
+
+import edu.wpi.first.networktables.BooleanSubscriber;
+import edu.wpi.first.networktables.BooleanTopic;
 import edu.wpi.first.networktables.NetworkTable;
-import edu.wpi.first.networktables.NetworkTableEntry;
 import edu.wpi.first.networktables.NetworkTableInstance;
 
 /**
@@ -13,16 +16,25 @@
  *
  * <p>This class is provided by the NewCommands VendorDep
  */
+@SuppressWarnings("deprecation")
 public class NetworkButton extends Button {
-  private final NetworkTableEntry m_entry;
+  /**
+   * Creates a NetworkButton that commands can be bound to.
+   *
+   * @param topic The boolean topic that contains the value.
+   */
+  public NetworkButton(BooleanTopic topic) {
+    this(topic.subscribe(false));
+  }
 
   /**
    * Creates a NetworkButton that commands can be bound to.
    *
-   * @param entry The entry that is the value.
+   * @param sub The boolean subscriber that provides the value.
    */
-  public NetworkButton(NetworkTableEntry entry) {
-    m_entry = entry;
+  public NetworkButton(BooleanSubscriber sub) {
+    super(() -> sub.getTopic().getInstance().isConnected() && sub.get());
+    requireNonNullParam(sub, "sub", "NetworkButton");
   }
 
   /**
@@ -32,7 +44,7 @@
    * @param field The field that is the value.
    */
   public NetworkButton(NetworkTable table, String field) {
-    this(table.getEntry(field));
+    this(table.getBooleanTopic(field));
   }
 
   /**
@@ -42,11 +54,17 @@
    * @param field The field that is the value.
    */
   public NetworkButton(String table, String field) {
-    this(NetworkTableInstance.getDefault().getTable(table), field);
+    this(NetworkTableInstance.getDefault(), table, field);
   }
 
-  @Override
-  public boolean get() {
-    return m_entry.getInstance().isConnected() && m_entry.getBoolean(false);
+  /**
+   * Creates a NetworkButton that commands can be bound to.
+   *
+   * @param inst The NetworkTable instance to use
+   * @param table The table where the networktable value is located.
+   * @param field The field that is the value.
+   */
+  public NetworkButton(NetworkTableInstance inst, String table, String field) {
+    this(inst.getTable(table), field);
   }
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/POVButton.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/POVButton.java
index 626ac9b..28087ae 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/POVButton.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/POVButton.java
@@ -4,7 +4,7 @@
 
 package edu.wpi.first.wpilibj2.command.button;
 
-import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
 
 import edu.wpi.first.wpilibj.GenericHID;
 
@@ -13,11 +13,8 @@
  *
  * <p>This class is provided by the NewCommands VendorDep
  */
+@SuppressWarnings("deprecation")
 public class POVButton extends Button {
-  private final GenericHID m_joystick;
-  private final int m_angle;
-  private final int m_povNumber;
-
   /**
    * Creates a POV button for triggering commands.
    *
@@ -26,11 +23,8 @@
    * @param povNumber The POV number (see {@link GenericHID#getPOV(int)})
    */
   public POVButton(GenericHID joystick, int angle, int povNumber) {
+    super(() -> joystick.getPOV(povNumber) == angle);
     requireNonNullParam(joystick, "joystick", "POVButton");
-
-    m_joystick = joystick;
-    m_angle = angle;
-    m_povNumber = povNumber;
   }
 
   /**
@@ -42,14 +36,4 @@
   public POVButton(GenericHID joystick, int angle) {
     this(joystick, angle, 0);
   }
-
-  /**
-   * Checks whether the current value of the POV is the target angle.
-   *
-   * @return Whether the value of the POV matches the target angle
-   */
-  @Override
-  public boolean get() {
-    return m_joystick.getPOV(m_povNumber) == m_angle;
-  }
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/Trigger.java b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/Trigger.java
index f36aeb2..19b8b20 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/Trigger.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/Trigger.java
@@ -4,9 +4,11 @@
 
 package edu.wpi.first.wpilibj2.command.button;
 
-import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
 
 import edu.wpi.first.math.filter.Debouncer;
+import edu.wpi.first.wpilibj.event.BooleanEvent;
+import edu.wpi.first.wpilibj.event.EventLoop;
 import edu.wpi.first.wpilibj2.command.Command;
 import edu.wpi.first.wpilibj2.command.CommandScheduler;
 import edu.wpi.first.wpilibj2.command.InstantCommand;
@@ -14,113 +16,262 @@
 import java.util.function.BooleanSupplier;
 
 /**
- * This class provides an easy way to link commands to inputs.
+ * This class provides an easy way to link commands to conditions.
  *
  * <p>It is very easy to link a button to a command. For instance, you could link the trigger button
  * of a joystick to a "score" command.
  *
- * <p>It is encouraged that teams write a subclass of Trigger if they want to have something unusual
- * (for instance, if they want to react to the user holding a button while the robot is reading a
- * certain sensor input). For this, they only have to write the {@link Trigger#get()} method to get
- * the full functionality of the Trigger class.
+ * <p>Triggers can easily be composed for advanced functionality using the {@link
+ * #and(BooleanSupplier)}, {@link #or(BooleanSupplier)}, {@link #negate()} operators.
  *
  * <p>This class is provided by the NewCommands VendorDep
  */
 public class Trigger implements BooleanSupplier {
-  private final BooleanSupplier m_isActive;
+  private final BooleanSupplier m_condition;
+  private final EventLoop m_loop;
 
   /**
-   * Creates a new trigger with the given condition determining whether it is active.
+   * Creates a new trigger based on the given condition.
    *
-   * @param isActive returns whether or not the trigger should be active
+   * @param loop The loop instance that polls this trigger.
+   * @param condition the condition represented by this trigger
    */
-  public Trigger(BooleanSupplier isActive) {
-    m_isActive = isActive;
+  public Trigger(EventLoop loop, BooleanSupplier condition) {
+    m_loop = requireNonNullParam(loop, "loop", "Trigger");
+    m_condition = requireNonNullParam(condition, "condition", "Trigger");
   }
 
   /**
-   * Creates a new trigger that is always inactive. Useful only as a no-arg constructor for
-   * subclasses that will be overriding {@link Trigger#get()} anyway.
+   * Creates a new trigger based on the given condition.
+   *
+   * <p>Polled by the default scheduler button loop.
+   *
+   * @param condition the condition represented by this trigger
    */
+  public Trigger(BooleanSupplier condition) {
+    this(CommandScheduler.getInstance().getDefaultButtonLoop(), condition);
+  }
+
+  /** Creates a new trigger that is always `false`. */
+  @Deprecated
   public Trigger() {
-    m_isActive = () -> false;
+    this(() -> false);
   }
 
   /**
-   * Returns whether or not the trigger is active.
+   * Starts the given command whenever the condition changes from `false` to `true`.
    *
-   * <p>This method will be called repeatedly a command is linked to the Trigger.
-   *
-   * <p>Functionally identical to {@link Trigger#getAsBoolean()}.
-   *
-   * @return whether or not the trigger condition is active.
+   * @param command the command to start
+   * @return this trigger, so calls can be chained
    */
-  public boolean get() {
-    return this.getAsBoolean();
+  public Trigger onTrue(Command command) {
+    requireNonNullParam(command, "command", "onRising");
+    m_loop.bind(
+        new Runnable() {
+          private boolean m_pressedLast = m_condition.getAsBoolean();
+
+          @Override
+          public void run() {
+            boolean pressed = m_condition.getAsBoolean();
+
+            if (!m_pressedLast && pressed) {
+              command.schedule();
+            }
+
+            m_pressedLast = pressed;
+          }
+        });
+    return this;
   }
 
   /**
-   * Returns whether or not the trigger is active.
+   * Starts the given command whenever the condition changes from `true` to `false`.
    *
-   * <p>This method will be called repeatedly a command is linked to the Trigger.
-   *
-   * <p>Functionally identical to {@link Trigger#get()}.
-   *
-   * @return whether or not the trigger condition is active.
+   * @param command the command to start
+   * @return this trigger, so calls can be chained
    */
-  @Override
-  public boolean getAsBoolean() {
-    return m_isActive.getAsBoolean();
+  public Trigger onFalse(Command command) {
+    requireNonNullParam(command, "command", "onFalling");
+    m_loop.bind(
+        new Runnable() {
+          private boolean m_pressedLast = m_condition.getAsBoolean();
+
+          @Override
+          public void run() {
+            boolean pressed = m_condition.getAsBoolean();
+
+            if (m_pressedLast && !pressed) {
+              command.schedule();
+            }
+
+            m_pressedLast = pressed;
+          }
+        });
+    return this;
+  }
+
+  /**
+   * Starts the given command when the condition changes to `true` and cancels it when the condition
+   * changes to `false`.
+   *
+   * <p>Doesn't re-start the command if it ends while the condition is still `true`. If the command
+   * should restart, see {@link edu.wpi.first.wpilibj2.command.RepeatCommand}.
+   *
+   * @param command the command to start
+   * @return this trigger, so calls can be chained
+   */
+  public Trigger whileTrue(Command command) {
+    requireNonNullParam(command, "command", "whileHigh");
+    m_loop.bind(
+        new Runnable() {
+          private boolean m_pressedLast = m_condition.getAsBoolean();
+
+          @Override
+          public void run() {
+            boolean pressed = m_condition.getAsBoolean();
+
+            if (!m_pressedLast && pressed) {
+              command.schedule();
+            } else if (m_pressedLast && !pressed) {
+              command.cancel();
+            }
+
+            m_pressedLast = pressed;
+          }
+        });
+    return this;
+  }
+
+  /**
+   * Starts the given command when the condition changes to `false` and cancels it when the
+   * condition changes to `true`.
+   *
+   * <p>Doesn't re-start the command if it ends while the condition is still `false`. If the command
+   * should restart, see {@link edu.wpi.first.wpilibj2.command.RepeatCommand}.
+   *
+   * @param command the command to start
+   * @return this trigger, so calls can be chained
+   */
+  public Trigger whileFalse(Command command) {
+    requireNonNullParam(command, "command", "whileLow");
+    m_loop.bind(
+        new Runnable() {
+          private boolean m_pressedLast = m_condition.getAsBoolean();
+
+          @Override
+          public void run() {
+            boolean pressed = m_condition.getAsBoolean();
+
+            if (m_pressedLast && !pressed) {
+              command.schedule();
+            } else if (!m_pressedLast && pressed) {
+              command.cancel();
+            }
+
+            m_pressedLast = pressed;
+          }
+        });
+    return this;
+  }
+
+  /**
+   * Toggles a command when the condition changes from `false` to `true`.
+   *
+   * @param command the command to toggle
+   * @return this trigger, so calls can be chained
+   */
+  public Trigger toggleOnTrue(Command command) {
+    requireNonNullParam(command, "command", "toggleOnRising");
+    m_loop.bind(
+        new Runnable() {
+          private boolean m_pressedLast = m_condition.getAsBoolean();
+
+          @Override
+          public void run() {
+            boolean pressed = m_condition.getAsBoolean();
+
+            if (!m_pressedLast && pressed) {
+              if (command.isScheduled()) {
+                command.cancel();
+              } else {
+                command.schedule();
+              }
+            }
+
+            m_pressedLast = pressed;
+          }
+        });
+    return this;
+  }
+
+  /**
+   * Toggles a command when the condition changes from `true` to the low state.
+   *
+   * @param command the command to toggle
+   * @return this trigger, so calls can be chained
+   */
+  public Trigger toggleOnFalse(Command command) {
+    requireNonNullParam(command, "command", "toggleOnFalling");
+    m_loop.bind(
+        new Runnable() {
+          private boolean m_pressedLast = m_condition.getAsBoolean();
+
+          @Override
+          public void run() {
+            boolean pressed = m_condition.getAsBoolean();
+
+            if (m_pressedLast && !pressed) {
+              if (command.isScheduled()) {
+                command.cancel();
+              } else {
+                command.schedule();
+              }
+            }
+
+            m_pressedLast = pressed;
+          }
+        });
+    return this;
   }
 
   /**
    * Starts the given command whenever the trigger just becomes active.
    *
    * @param command the command to start
-   * @param interruptible whether the command is interruptible
    * @return this trigger, so calls can be chained
+   * @deprecated Use {@link #onTrue(Command)} instead.
    */
-  public Trigger whenActive(final Command command, boolean interruptible) {
+  @Deprecated
+  public Trigger whenActive(final Command command) {
     requireNonNullParam(command, "command", "whenActive");
 
-    CommandScheduler.getInstance()
-        .addButton(
-            new Runnable() {
-              private boolean m_pressedLast = get();
+    m_loop.bind(
+        new Runnable() {
+          private boolean m_pressedLast = m_condition.getAsBoolean();
 
-              @Override
-              public void run() {
-                boolean pressed = get();
+          @Override
+          public void run() {
+            boolean pressed = m_condition.getAsBoolean();
 
-                if (!m_pressedLast && pressed) {
-                  command.schedule(interruptible);
-                }
+            if (!m_pressedLast && pressed) {
+              command.schedule();
+            }
 
-                m_pressedLast = pressed;
-              }
-            });
-
+            m_pressedLast = pressed;
+          }
+        });
     return this;
   }
 
   /**
-   * Starts the given command whenever the trigger just becomes active. The command is set to be
-   * interruptible.
-   *
-   * @param command the command to start
-   * @return this trigger, so calls can be chained
-   */
-  public Trigger whenActive(final Command command) {
-    return whenActive(command, true);
-  }
-
-  /**
    * Runs the given runnable whenever the trigger just becomes active.
    *
    * @param toRun the runnable to run
    * @param requirements the required subsystems
    * @return this trigger, so calls can be chained
+   * @deprecated Replace with {@link #onTrue(Command)}, creating the InstantCommand manually
    */
+  @Deprecated
   public Trigger whenActive(final Runnable toRun, Subsystem... requirements) {
     return whenActive(new InstantCommand(toRun, requirements));
   }
@@ -128,57 +279,50 @@
   /**
    * Constantly starts the given command while the button is held.
    *
-   * <p>{@link Command#schedule(boolean)} will be called repeatedly while the trigger is active, and
-   * will be canceled when the trigger becomes inactive.
+   * <p>{@link Command#schedule()} will be called repeatedly while the trigger is active, and will
+   * be canceled when the trigger becomes inactive.
    *
    * @param command the command to start
-   * @param interruptible whether the command is interruptible
    * @return this trigger, so calls can be chained
+   * @deprecated Use {@link #whileTrue(Command)} with {@link
+   *     edu.wpi.first.wpilibj2.command.RepeatCommand RepeatCommand}, or bind {@link
+   *     Command#schedule() command::schedule} to {@link BooleanEvent#ifHigh(Runnable)} (passing no
+   *     requirements).
    */
-  public Trigger whileActiveContinuous(final Command command, boolean interruptible) {
+  @Deprecated
+  public Trigger whileActiveContinuous(final Command command) {
     requireNonNullParam(command, "command", "whileActiveContinuous");
 
-    CommandScheduler.getInstance()
-        .addButton(
-            new Runnable() {
-              private boolean m_pressedLast = get();
+    m_loop.bind(
+        new Runnable() {
+          private boolean m_pressedLast = m_condition.getAsBoolean();
 
-              @Override
-              public void run() {
-                boolean pressed = get();
+          @Override
+          public void run() {
+            boolean pressed = m_condition.getAsBoolean();
 
-                if (pressed) {
-                  command.schedule(interruptible);
-                } else if (m_pressedLast) {
-                  command.cancel();
-                }
+            if (pressed) {
+              command.schedule();
+            } else if (m_pressedLast) {
+              command.cancel();
+            }
 
-                m_pressedLast = pressed;
-              }
-            });
+            m_pressedLast = pressed;
+          }
+        });
+
     return this;
   }
 
   /**
-   * Constantly starts the given command while the button is held.
-   *
-   * <p>{@link Command#schedule(boolean)} will be called repeatedly while the trigger is active, and
-   * will be canceled when the trigger becomes inactive. The command is set to be interruptible.
-   *
-   * @param command the command to start
-   * @return this trigger, so calls can be chained
-   */
-  public Trigger whileActiveContinuous(final Command command) {
-    return whileActiveContinuous(command, true);
-  }
-
-  /**
    * Constantly runs the given runnable while the button is held.
    *
    * @param toRun the runnable to run
    * @param requirements the required subsystems
    * @return this trigger, so calls can be chained
+   * @deprecated Use {@link #whileTrue(Command)} and construct a RunCommand manually
    */
+  @Deprecated
   public Trigger whileActiveContinuous(final Runnable toRun, Subsystem... requirements) {
     return whileActiveContinuous(new InstantCommand(toRun, requirements));
   }
@@ -188,90 +332,72 @@
    * inactive, but does not re-start it in-between.
    *
    * @param command the command to start
-   * @param interruptible whether the command is interruptible
    * @return this trigger, so calls can be chained
+   * @deprecated Use {@link #whileTrue(Command)} instead.
    */
-  public Trigger whileActiveOnce(final Command command, boolean interruptible) {
+  @Deprecated
+  public Trigger whileActiveOnce(final Command command) {
     requireNonNullParam(command, "command", "whileActiveOnce");
 
-    CommandScheduler.getInstance()
-        .addButton(
-            new Runnable() {
-              private boolean m_pressedLast = get();
+    m_loop.bind(
+        new Runnable() {
+          private boolean m_pressedLast = m_condition.getAsBoolean();
 
-              @Override
-              public void run() {
-                boolean pressed = get();
+          @Override
+          public void run() {
+            boolean pressed = m_condition.getAsBoolean();
 
-                if (!m_pressedLast && pressed) {
-                  command.schedule(interruptible);
-                } else if (m_pressedLast && !pressed) {
-                  command.cancel();
-                }
+            if (!m_pressedLast && pressed) {
+              command.schedule();
+            } else if (m_pressedLast && !pressed) {
+              command.cancel();
+            }
 
-                m_pressedLast = pressed;
-              }
-            });
+            m_pressedLast = pressed;
+          }
+        });
     return this;
   }
 
   /**
-   * Starts the given command when the trigger initially becomes active, and ends it when it becomes
-   * inactive, but does not re-start it in-between. The command is set to be interruptible.
-   *
-   * @param command the command to start
-   * @return this trigger, so calls can be chained
-   */
-  public Trigger whileActiveOnce(final Command command) {
-    return whileActiveOnce(command, true);
-  }
-
-  /**
    * Starts the command when the trigger becomes inactive.
    *
    * @param command the command to start
-   * @param interruptible whether the command is interruptible
    * @return this trigger, so calls can be chained
+   * @deprecated Use {@link #onFalse(Command)} instead.
    */
-  public Trigger whenInactive(final Command command, boolean interruptible) {
+  @Deprecated
+  public Trigger whenInactive(final Command command) {
     requireNonNullParam(command, "command", "whenInactive");
 
-    CommandScheduler.getInstance()
-        .addButton(
-            new Runnable() {
-              private boolean m_pressedLast = get();
+    m_loop.bind(
+        new Runnable() {
+          private boolean m_pressedLast = m_condition.getAsBoolean();
 
-              @Override
-              public void run() {
-                boolean pressed = get();
+          @Override
+          public void run() {
+            boolean pressed = m_condition.getAsBoolean();
 
-                if (m_pressedLast && !pressed) {
-                  command.schedule(interruptible);
-                }
+            if (m_pressedLast && !pressed) {
+              command.schedule();
+            }
 
-                m_pressedLast = pressed;
-              }
-            });
+            m_pressedLast = pressed;
+          }
+        });
+
     return this;
   }
 
   /**
-   * Starts the command when the trigger becomes inactive. The command is set to be interruptible.
-   *
-   * @param command the command to start
-   * @return this trigger, so calls can be chained
-   */
-  public Trigger whenInactive(final Command command) {
-    return whenInactive(command, true);
-  }
-
-  /**
    * Runs the given runnable when the trigger becomes inactive.
    *
    * @param toRun the runnable to run
    * @param requirements the required subsystems
    * @return this trigger, so calls can be chained
+   * @deprecated Construct the InstantCommand manually and replace with {@link #onFalse(Command)}
    */
+  @Deprecated
   public Trigger whenInactive(final Runnable toRun, Subsystem... requirements) {
     return whenInactive(new InstantCommand(toRun, requirements));
   }
@@ -280,43 +406,34 @@
    * Toggles a command when the trigger becomes active.
    *
    * @param command the command to toggle
-   * @param interruptible whether the command is interruptible
    * @return this trigger, so calls can be chained
+   * @deprecated Use {@link #toggleOnTrue(Command)} instead.
    */
-  public Trigger toggleWhenActive(final Command command, boolean interruptible) {
+  @Deprecated
+  public Trigger toggleWhenActive(final Command command) {
     requireNonNullParam(command, "command", "toggleWhenActive");
 
-    CommandScheduler.getInstance()
-        .addButton(
-            new Runnable() {
-              private boolean m_pressedLast = get();
+    m_loop.bind(
+        new Runnable() {
+          private boolean m_pressedLast = m_condition.getAsBoolean();
 
-              @Override
-              public void run() {
-                boolean pressed = get();
+          @Override
+          public void run() {
+            boolean pressed = m_condition.getAsBoolean();
 
-                if (!m_pressedLast && pressed) {
-                  if (command.isScheduled()) {
-                    command.cancel();
-                  } else {
-                    command.schedule(interruptible);
-                  }
-                }
-
-                m_pressedLast = pressed;
+            if (!m_pressedLast && pressed) {
+              if (command.isScheduled()) {
+                command.cancel();
+              } else {
+                command.schedule();
               }
-            });
-    return this;
-  }
+            }
 
-  /**
-   * Toggles a command when the trigger becomes active. The command is set to be interruptible.
-   *
-   * @param command the command to toggle
-   * @return this trigger, so calls can be chained
-   */
-  public Trigger toggleWhenActive(final Command command) {
-    return toggleWhenActive(command, true);
+            m_pressedLast = pressed;
+          }
+        });
+
+    return this;
   }
 
   /**
@@ -324,49 +441,54 @@
    *
    * @param command the command to cancel
    * @return this trigger, so calls can be chained
+   * @deprecated Instead, pass this as an end condition to {@link Command#until(BooleanSupplier)}.
    */
+  @Deprecated
   public Trigger cancelWhenActive(final Command command) {
     requireNonNullParam(command, "command", "cancelWhenActive");
 
-    CommandScheduler.getInstance()
-        .addButton(
-            new Runnable() {
-              private boolean m_pressedLast = get();
+    m_loop.bind(
+        new Runnable() {
+          private boolean m_pressedLast = m_condition.getAsBoolean();
 
-              @Override
-              public void run() {
-                boolean pressed = get();
+          @Override
+          public void run() {
+            boolean pressed = m_condition.getAsBoolean();
 
-                if (!m_pressedLast && pressed) {
-                  command.cancel();
-                }
+            if (!m_pressedLast && pressed) {
+              command.cancel();
+            }
 
-                m_pressedLast = pressed;
-              }
-            });
+            m_pressedLast = pressed;
+          }
+        });
+
     return this;
   }
 
-  /**
-   * Composes this trigger with another trigger, returning a new trigger that is active when both
-   * triggers are active.
-   *
-   * @param trigger the trigger to compose with
-   * @return the trigger that is active when both triggers are active
-   */
-  public Trigger and(Trigger trigger) {
-    return new Trigger(() -> get() && trigger.get());
+  @Override
+  public boolean getAsBoolean() {
+    return m_condition.getAsBoolean();
   }
 
   /**
-   * Composes this trigger with another trigger, returning a new trigger that is active when either
-   * trigger is active.
+   * Composes two triggers with logical AND.
    *
-   * @param trigger the trigger to compose with
-   * @return the trigger that is active when either trigger is active
+   * @param trigger the condition to compose with
+   * @return A trigger which is active when both component triggers are active.
    */
-  public Trigger or(Trigger trigger) {
-    return new Trigger(() -> get() || trigger.get());
+  public Trigger and(BooleanSupplier trigger) {
+    return new Trigger(() -> m_condition.getAsBoolean() && trigger.getAsBoolean());
+  }
+
+  /**
+   * Composes two triggers with logical OR.
+   *
+   * @param trigger the condition to compose with
+   * @return A trigger which is active when either component trigger is active.
+   */
+  public Trigger or(BooleanSupplier trigger) {
+    return new Trigger(() -> m_condition.getAsBoolean() || trigger.getAsBoolean());
   }
 
   /**
@@ -376,7 +498,7 @@
    * @return the negated trigger
    */
   public Trigger negate() {
-    return new Trigger(() -> !get());
+    return new Trigger(() -> !m_condition.getAsBoolean());
   }
 
   /**
@@ -401,11 +523,11 @@
   public Trigger debounce(double seconds, Debouncer.DebounceType type) {
     return new Trigger(
         new BooleanSupplier() {
-          Debouncer m_debouncer = new Debouncer(seconds, type);
+          final Debouncer m_debouncer = new Debouncer(seconds, type);
 
           @Override
           public boolean getAsBoolean() {
-            return m_debouncer.calculate(get());
+            return m_debouncer.calculate(m_condition.getAsBoolean());
           }
         });
   }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/Command.cpp b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/Command.cpp
index ea6276b..b173ada 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/Command.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/Command.cpp
@@ -4,16 +4,19 @@
 
 #include "frc2/command/Command.h"
 
+#include "frc2/command/CommandHelper.h"
 #include "frc2/command/CommandScheduler.h"
+#include "frc2/command/ConditionalCommand.h"
 #include "frc2/command/InstantCommand.h"
 #include "frc2/command/ParallelCommandGroup.h"
 #include "frc2/command/ParallelDeadlineGroup.h"
 #include "frc2/command/ParallelRaceGroup.h"
 #include "frc2/command/PerpetualCommand.h"
-#include "frc2/command/ProxyScheduleCommand.h"
+#include "frc2/command/RepeatCommand.h"
 #include "frc2/command/SequentialCommandGroup.h"
 #include "frc2/command/WaitCommand.h"
 #include "frc2/command/WaitUntilCommand.h"
+#include "frc2/command/WrapperCommand.h"
 
 using namespace frc2;
 
@@ -22,7 +25,7 @@
 }
 
 Command& Command::operator=(const Command& rhs) {
-  m_isGrouped = false;
+  m_isComposed = false;
   return *this;
 }
 
@@ -30,69 +33,83 @@
 void Command::Execute() {}
 void Command::End(bool interrupted) {}
 
-ParallelRaceGroup Command::WithTimeout(units::second_t duration) && {
-  std::vector<std::unique_ptr<Command>> temp;
-  temp.emplace_back(std::make_unique<WaitCommand>(duration));
-  temp.emplace_back(std::move(*this).TransferOwnership());
-  return ParallelRaceGroup(std::move(temp));
+CommandPtr Command::WithTimeout(units::second_t duration) && {
+  return std::move(*this).ToPtr().WithTimeout(duration);
 }
 
-ParallelRaceGroup Command::Until(std::function<bool()> condition) && {
-  std::vector<std::unique_ptr<Command>> temp;
-  temp.emplace_back(std::make_unique<WaitUntilCommand>(std::move(condition)));
-  temp.emplace_back(std::move(*this).TransferOwnership());
-  return ParallelRaceGroup(std::move(temp));
+CommandPtr Command::Until(std::function<bool()> condition) && {
+  return std::move(*this).ToPtr().Until(std::move(condition));
 }
 
-ParallelRaceGroup Command::WithInterrupt(std::function<bool()> condition) && {
-  std::vector<std::unique_ptr<Command>> temp;
-  temp.emplace_back(std::make_unique<WaitUntilCommand>(std::move(condition)));
-  temp.emplace_back(std::move(*this).TransferOwnership());
-  return ParallelRaceGroup(std::move(temp));
+CommandPtr Command::IgnoringDisable(bool doesRunWhenDisabled) && {
+  return std::move(*this).ToPtr().IgnoringDisable(doesRunWhenDisabled);
 }
 
-SequentialCommandGroup Command::BeforeStarting(
+CommandPtr Command::WithInterruptBehavior(
+    InterruptionBehavior interruptBehavior) && {
+  return std::move(*this).ToPtr().WithInterruptBehavior(interruptBehavior);
+}
+
+CommandPtr Command::WithInterrupt(std::function<bool()> condition) && {
+  return std::move(*this).ToPtr().Until(std::move(condition));
+}
+
+CommandPtr Command::BeforeStarting(
     std::function<void()> toRun,
     std::initializer_list<Subsystem*> requirements) && {
   return std::move(*this).BeforeStarting(
       std::move(toRun), {requirements.begin(), requirements.end()});
 }
 
-SequentialCommandGroup Command::BeforeStarting(
-    std::function<void()> toRun, wpi::span<Subsystem* const> requirements) && {
-  std::vector<std::unique_ptr<Command>> temp;
-  temp.emplace_back(
-      std::make_unique<InstantCommand>(std::move(toRun), requirements));
-  temp.emplace_back(std::move(*this).TransferOwnership());
-  return SequentialCommandGroup(std::move(temp));
+CommandPtr Command::BeforeStarting(
+    std::function<void()> toRun, std::span<Subsystem* const> requirements) && {
+  return std::move(*this).ToPtr().BeforeStarting(std::move(toRun),
+                                                 requirements);
 }
 
-SequentialCommandGroup Command::AndThen(
-    std::function<void()> toRun,
-    std::initializer_list<Subsystem*> requirements) && {
+CommandPtr Command::AndThen(std::function<void()> toRun,
+                            std::initializer_list<Subsystem*> requirements) && {
   return std::move(*this).AndThen(std::move(toRun),
                                   {requirements.begin(), requirements.end()});
 }
 
-SequentialCommandGroup Command::AndThen(
-    std::function<void()> toRun, wpi::span<Subsystem* const> requirements) && {
-  std::vector<std::unique_ptr<Command>> temp;
-  temp.emplace_back(std::move(*this).TransferOwnership());
-  temp.emplace_back(
-      std::make_unique<InstantCommand>(std::move(toRun), requirements));
-  return SequentialCommandGroup(std::move(temp));
+CommandPtr Command::AndThen(std::function<void()> toRun,
+                            std::span<Subsystem* const> requirements) && {
+  return std::move(*this).ToPtr().AndThen(std::move(toRun), requirements);
 }
 
 PerpetualCommand Command::Perpetually() && {
+  WPI_IGNORE_DEPRECATED
   return PerpetualCommand(std::move(*this).TransferOwnership());
+  WPI_UNIGNORE_DEPRECATED
 }
 
-ProxyScheduleCommand Command::AsProxy() {
-  return ProxyScheduleCommand(this);
+CommandPtr Command::Repeatedly() && {
+  return std::move(*this).ToPtr().Repeatedly();
 }
 
-void Command::Schedule(bool interruptible) {
-  CommandScheduler::GetInstance().Schedule(interruptible, this);
+CommandPtr Command::AsProxy() && {
+  return std::move(*this).ToPtr().AsProxy();
+}
+
+CommandPtr Command::Unless(std::function<bool()> condition) && {
+  return std::move(*this).ToPtr().Unless(std::move(condition));
+}
+
+CommandPtr Command::FinallyDo(std::function<void(bool)> end) && {
+  return std::move(*this).ToPtr().FinallyDo(std::move(end));
+}
+
+CommandPtr Command::HandleInterrupt(std::function<void(void)> handler) && {
+  return std::move(*this).ToPtr().HandleInterrupt(std::move(handler));
+}
+
+CommandPtr Command::WithName(std::string_view name) && {
+  return std::move(*this).ToPtr().WithName(name);
+}
+
+void Command::Schedule() {
+  CommandScheduler::GetInstance().Schedule(this);
 }
 
 void Command::Cancel() {
@@ -115,12 +132,22 @@
   return GetTypeName(*this);
 }
 
+void Command::SetName(std::string_view name) {}
+
+bool Command::IsComposed() const {
+  return m_isComposed;
+}
+
+void Command::SetComposed(bool isComposed) {
+  m_isComposed = isComposed;
+}
+
 bool Command::IsGrouped() const {
-  return m_isGrouped;
+  return IsComposed();
 }
 
 void Command::SetGrouped(bool grouped) {
-  m_isGrouped = grouped;
+  SetComposed(grouped);
 }
 
 namespace frc2 {
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandBase.cpp b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandBase.cpp
index b6f76f3..416c78b 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandBase.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandBase.cpp
@@ -18,7 +18,7 @@
   m_requirements.insert(requirements.begin(), requirements.end());
 }
 
-void CommandBase::AddRequirements(wpi::span<Subsystem* const> requirements) {
+void CommandBase::AddRequirements(std::span<Subsystem* const> requirements) {
   m_requirements.insert(requirements.begin(), requirements.end());
 }
 
@@ -64,4 +64,21 @@
           Cancel();
         }
       });
+  builder.AddBooleanProperty(
+      ".isParented", [this] { return IsComposed(); }, nullptr);
+  builder.AddStringProperty(
+      "interruptBehavior",
+      [this] {
+        switch (GetInterruptionBehavior()) {
+          case Command::InterruptionBehavior::kCancelIncoming:
+            return "kCancelIncoming";
+          case Command::InterruptionBehavior::kCancelSelf:
+            return "kCancelSelf";
+          default:
+            return "Invalid";
+        }
+      },
+      nullptr);
+  builder.AddBooleanProperty(
+      "runsWhenDisabled", [this] { return RunsWhenDisabled(); }, nullptr);
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandGroupBase.cpp b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandGroupBase.cpp
index a3d275d..eb9c293 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandGroupBase.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandGroupBase.cpp
@@ -5,44 +5,3 @@
 #include "frc2/command/CommandGroupBase.h"
 
 using namespace frc2;
-
-bool CommandGroupBase::RequireUngrouped(const Command& command) {
-  if (command.IsGrouped()) {
-    throw FRC_MakeError(
-        frc::err::CommandIllegalUse, "{}",
-        "Commands cannot be added to more than one CommandGroup");
-  }
-  return true;
-}
-
-bool CommandGroupBase::RequireUngrouped(const Command* command) {
-  return RequireUngrouped(*command);
-}
-
-bool CommandGroupBase::RequireUngrouped(
-    wpi::span<const std::unique_ptr<Command>> commands) {
-  bool allUngrouped = true;
-  for (auto&& command : commands) {
-    allUngrouped &= !command.get()->IsGrouped();
-  }
-  if (!allUngrouped) {
-    throw FRC_MakeError(
-        frc::err::CommandIllegalUse, "{}",
-        "Commands cannot be added to more than one CommandGroup");
-  }
-  return allUngrouped;
-}
-
-bool CommandGroupBase::RequireUngrouped(
-    std::initializer_list<const Command*> commands) {
-  bool allUngrouped = true;
-  for (auto&& command : commands) {
-    allUngrouped &= !command->IsGrouped();
-  }
-  if (!allUngrouped) {
-    throw FRC_MakeError(
-        frc::err::CommandIllegalUse, "{}",
-        "Commands cannot be added to more than one CommandGroup");
-  }
-  return allUngrouped;
-}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandPtr.cpp b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandPtr.cpp
new file mode 100644
index 0000000..44150a2
--- /dev/null
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandPtr.cpp
@@ -0,0 +1,270 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc2/command/CommandPtr.h"
+
+#include <frc/Errors.h>
+
+#include "frc2/command/CommandScheduler.h"
+#include "frc2/command/ConditionalCommand.h"
+#include "frc2/command/InstantCommand.h"
+#include "frc2/command/ParallelCommandGroup.h"
+#include "frc2/command/ParallelDeadlineGroup.h"
+#include "frc2/command/ParallelRaceGroup.h"
+#include "frc2/command/PrintCommand.h"
+#include "frc2/command/ProxyCommand.h"
+#include "frc2/command/RepeatCommand.h"
+#include "frc2/command/SequentialCommandGroup.h"
+#include "frc2/command/WaitCommand.h"
+#include "frc2/command/WaitUntilCommand.h"
+#include "frc2/command/WrapperCommand.h"
+
+using namespace frc2;
+
+void CommandPtr::AssertValid() const {
+  if (!m_ptr) {
+    throw FRC_MakeError(frc::err::CommandIllegalUse,
+                        "Moved-from CommandPtr object used!");
+  }
+}
+
+CommandPtr CommandPtr::Repeatedly() && {
+  AssertValid();
+  m_ptr = std::make_unique<RepeatCommand>(std::move(m_ptr));
+  return std::move(*this);
+}
+
+CommandPtr CommandPtr::AsProxy() && {
+  AssertValid();
+  m_ptr = std::make_unique<ProxyCommand>(std::move(m_ptr));
+  return std::move(*this);
+}
+
+class RunsWhenDisabledCommand : public WrapperCommand {
+ public:
+  RunsWhenDisabledCommand(std::unique_ptr<Command>&& command,
+                          bool doesRunWhenDisabled)
+      : WrapperCommand(std::move(command)),
+        m_runsWhenDisabled(doesRunWhenDisabled) {}
+
+  bool RunsWhenDisabled() const override { return m_runsWhenDisabled; }
+
+ private:
+  bool m_runsWhenDisabled;
+};
+
+CommandPtr CommandPtr::IgnoringDisable(bool doesRunWhenDisabled) && {
+  AssertValid();
+  m_ptr = std::make_unique<RunsWhenDisabledCommand>(std::move(m_ptr),
+                                                    doesRunWhenDisabled);
+  return std::move(*this);
+}
+
+using InterruptionBehavior = Command::InterruptionBehavior;
+class InterruptBehaviorCommand : public WrapperCommand {
+ public:
+  InterruptBehaviorCommand(std::unique_ptr<Command>&& command,
+                           InterruptionBehavior interruptBehavior)
+      : WrapperCommand(std::move(command)),
+        m_interruptBehavior(interruptBehavior) {}
+
+  InterruptionBehavior GetInterruptionBehavior() const override {
+    return m_interruptBehavior;
+  }
+
+ private:
+  InterruptionBehavior m_interruptBehavior;
+};
+
+CommandPtr CommandPtr::WithInterruptBehavior(
+    InterruptionBehavior interruptBehavior) && {
+  AssertValid();
+  m_ptr = std::make_unique<InterruptBehaviorCommand>(std::move(m_ptr),
+                                                     interruptBehavior);
+  return std::move(*this);
+}
+
+CommandPtr CommandPtr::AndThen(std::function<void()> toRun,
+                               std::span<Subsystem* const> requirements) && {
+  AssertValid();
+  return std::move(*this).AndThen(CommandPtr(
+      std::make_unique<InstantCommand>(std::move(toRun), requirements)));
+}
+
+CommandPtr CommandPtr::AndThen(
+    std::function<void()> toRun,
+    std::initializer_list<Subsystem*> requirements) && {
+  AssertValid();
+  return std::move(*this).AndThen(CommandPtr(
+      std::make_unique<InstantCommand>(std::move(toRun), requirements)));
+}
+
+CommandPtr CommandPtr::AndThen(CommandPtr&& next) && {
+  AssertValid();
+  std::vector<std::unique_ptr<Command>> temp;
+  temp.emplace_back(std::move(m_ptr));
+  temp.emplace_back(std::move(next).Unwrap());
+  m_ptr = std::make_unique<SequentialCommandGroup>(std::move(temp));
+  return std::move(*this);
+}
+
+CommandPtr CommandPtr::BeforeStarting(
+    std::function<void()> toRun, std::span<Subsystem* const> requirements) && {
+  AssertValid();
+  return std::move(*this).BeforeStarting(CommandPtr(
+      std::make_unique<InstantCommand>(std::move(toRun), requirements)));
+}
+
+CommandPtr CommandPtr::BeforeStarting(
+    std::function<void()> toRun,
+    std::initializer_list<Subsystem*> requirements) && {
+  AssertValid();
+  return std::move(*this).BeforeStarting(CommandPtr(
+      std::make_unique<InstantCommand>(std::move(toRun), requirements)));
+}
+
+CommandPtr CommandPtr::BeforeStarting(CommandPtr&& before) && {
+  AssertValid();
+  std::vector<std::unique_ptr<Command>> temp;
+  temp.emplace_back(std::move(before).Unwrap());
+  temp.emplace_back(std::move(m_ptr));
+  m_ptr = std::make_unique<SequentialCommandGroup>(std::move(temp));
+  return std::move(*this);
+}
+
+CommandPtr CommandPtr::WithTimeout(units::second_t duration) && {
+  AssertValid();
+  std::vector<std::unique_ptr<Command>> temp;
+  temp.emplace_back(std::make_unique<WaitCommand>(duration));
+  temp.emplace_back(std::move(m_ptr));
+  m_ptr = std::make_unique<ParallelRaceGroup>(std::move(temp));
+  return std::move(*this);
+}
+
+CommandPtr CommandPtr::Until(std::function<bool()> condition) && {
+  AssertValid();
+  std::vector<std::unique_ptr<Command>> temp;
+  temp.emplace_back(std::make_unique<WaitUntilCommand>(std::move(condition)));
+  temp.emplace_back(std::move(m_ptr));
+  m_ptr = std::make_unique<ParallelRaceGroup>(std::move(temp));
+  return std::move(*this);
+}
+
+CommandPtr CommandPtr::Unless(std::function<bool()> condition) && {
+  AssertValid();
+  m_ptr = std::make_unique<ConditionalCommand>(
+      std::make_unique<InstantCommand>(), std::move(m_ptr),
+      std::move(condition));
+  return std::move(*this);
+}
+
+CommandPtr CommandPtr::DeadlineWith(CommandPtr&& parallel) && {
+  AssertValid();
+  std::vector<std::unique_ptr<Command>> vec;
+  vec.emplace_back(std::move(parallel).Unwrap());
+  m_ptr =
+      std::make_unique<ParallelDeadlineGroup>(std::move(m_ptr), std::move(vec));
+  return std::move(*this);
+}
+
+CommandPtr CommandPtr::AlongWith(CommandPtr&& parallel) && {
+  AssertValid();
+  std::vector<std::unique_ptr<Command>> vec;
+  vec.emplace_back(std::move(m_ptr));
+  vec.emplace_back(std::move(parallel).Unwrap());
+  m_ptr = std::make_unique<ParallelCommandGroup>(std::move(vec));
+  return std::move(*this);
+}
+
+CommandPtr CommandPtr::RaceWith(CommandPtr&& parallel) && {
+  AssertValid();
+  std::vector<std::unique_ptr<Command>> vec;
+  vec.emplace_back(std::move(m_ptr));
+  vec.emplace_back(std::move(parallel).Unwrap());
+  m_ptr = std::make_unique<ParallelRaceGroup>(std::move(vec));
+  return std::move(*this);
+}
+
+namespace {
+class FinallyCommand : public WrapperCommand {
+ public:
+  FinallyCommand(std::unique_ptr<Command>&& command,
+                 std::function<void(bool)> end)
+      : WrapperCommand(std::move(command)), m_end(std::move(end)) {}
+
+  void End(bool interrupted) override {
+    WrapperCommand::End(interrupted);
+    m_end(interrupted);
+  }
+
+ private:
+  std::function<void(bool)> m_end;
+};
+}  // namespace
+
+CommandPtr CommandPtr::FinallyDo(std::function<void(bool)> end) && {
+  AssertValid();
+  m_ptr = std::make_unique<FinallyCommand>(std::move(m_ptr), std::move(end));
+  return std::move(*this);
+}
+
+CommandPtr CommandPtr::HandleInterrupt(std::function<void(void)> handler) && {
+  AssertValid();
+  return std::move(*this).FinallyDo(
+      [handler = std::move(handler)](bool interrupted) {
+        if (interrupted) {
+          handler();
+        }
+      });
+}
+
+CommandPtr CommandPtr::WithName(std::string_view name) && {
+  AssertValid();
+  WrapperCommand wrapper{std::move(m_ptr)};
+  wrapper.SetName(name);
+  return std::move(wrapper).ToPtr();
+}
+
+CommandBase* CommandPtr::get() const {
+  AssertValid();
+  return m_ptr.get();
+}
+
+std::unique_ptr<CommandBase> CommandPtr::Unwrap() && {
+  AssertValid();
+  return std::move(m_ptr);
+}
+
+void CommandPtr::Schedule() const {
+  AssertValid();
+  CommandScheduler::GetInstance().Schedule(*this);
+}
+
+void CommandPtr::Cancel() const {
+  AssertValid();
+  CommandScheduler::GetInstance().Cancel(*this);
+}
+
+bool CommandPtr::IsScheduled() const {
+  AssertValid();
+  return CommandScheduler::GetInstance().IsScheduled(*this);
+}
+
+bool CommandPtr::HasRequirement(Subsystem* requirement) const {
+  AssertValid();
+  return m_ptr->HasRequirement(requirement);
+}
+
+CommandPtr::operator bool() const {
+  return m_ptr.operator bool();
+}
+
+std::vector<std::unique_ptr<Command>> CommandPtr::UnwrapVector(
+    std::vector<CommandPtr>&& vec) {
+  std::vector<std::unique_ptr<Command>> ptrs;
+  for (auto&& ptr : vec) {
+    ptrs.emplace_back(std::move(ptr).Unwrap());
+  }
+  return ptrs;
+}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandScheduler.cpp b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandScheduler.cpp
index f79fa59..5a4782f 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandScheduler.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandScheduler.cpp
@@ -12,23 +12,22 @@
 #include <frc/livewindow/LiveWindow.h>
 #include <hal/FRCUsageReporting.h>
 #include <hal/HALBase.h>
+#include <networktables/IntegerArrayTopic.h>
 #include <networktables/NTSendableBuilder.h>
-#include <networktables/NetworkTableEntry.h>
+#include <networktables/StringArrayTopic.h>
 #include <wpi/DenseMap.h>
 #include <wpi/SmallVector.h>
 #include <wpi/sendable/SendableRegistry.h>
 
-#include "frc2/command/CommandGroupBase.h"
-#include "frc2/command/CommandState.h"
+#include "frc2/command/CommandPtr.h"
 #include "frc2/command/Subsystem.h"
 
 using namespace frc2;
 
 class CommandScheduler::Impl {
  public:
-  // A map from commands to their scheduling state.  Also used as a set of the
-  // currently-running commands.
-  wpi::DenseMap<Command*, CommandState> scheduledCommands;
+  // A set of the currently-running commands.
+  wpi::SmallSet<Command*, 12> scheduledCommands;
 
   // A map from required subsystems to their requiring commands.  Also used as a
   // set of the currently-required subsystems.
@@ -38,9 +37,10 @@
   // commands.  Also used as a list of currently-registered subsystems.
   wpi::DenseMap<Subsystem*, std::unique_ptr<Command>> subsystems;
 
+  frc::EventLoop defaultButtonLoop;
   // The set of currently-registered buttons that will be polled every
   // iteration.
-  wpi::SmallVector<wpi::unique_function<void()>, 4> buttons;
+  frc::EventLoop* activeButtonLoop{&defaultButtonLoop};
 
   bool disabled{false};
 
@@ -55,7 +55,7 @@
   // scheduled/canceled during run
 
   bool inRunLoop = false;
-  wpi::DenseMap<Command*, bool> toSchedule;
+  wpi::SmallVector<Command*, 4> toSchedule;
   wpi::SmallVector<Command*, 4> toCancel;
 };
 
@@ -95,29 +95,32 @@
   m_watchdog.SetTimeout(period);
 }
 
-void CommandScheduler::AddButton(wpi::unique_function<void()> button) {
-  m_impl->buttons.emplace_back(std::move(button));
+frc::EventLoop* CommandScheduler::GetActiveButtonLoop() const {
+  return m_impl->activeButtonLoop;
+}
+
+void CommandScheduler::SetActiveButtonLoop(frc::EventLoop* loop) {
+  m_impl->activeButtonLoop = loop;
+}
+
+frc::EventLoop* CommandScheduler::GetDefaultButtonLoop() const {
+  return &(m_impl->defaultButtonLoop);
 }
 
 void CommandScheduler::ClearButtons() {
-  m_impl->buttons.clear();
+  m_impl->activeButtonLoop->Clear();
 }
 
-void CommandScheduler::Schedule(bool interruptible, Command* command) {
+void CommandScheduler::Schedule(Command* command) {
   if (m_impl->inRunLoop) {
-    m_impl->toSchedule.try_emplace(command, interruptible);
+    m_impl->toSchedule.emplace_back(command);
     return;
   }
 
-  if (command->IsGrouped()) {
-    throw FRC_MakeError(frc::err::CommandIllegalUse, "{}",
-                        "A command that is part of a command group "
-                        "cannot be independently scheduled");
-    return;
-  }
-  if (m_impl->disabled ||
-      (frc::RobotState::IsDisabled() && !command->RunsWhenDisabled()) ||
-      ContainsKey(m_impl->scheduledCommands, command)) {
+  RequireUngrouped(command);
+
+  if (m_impl->disabled || m_impl->scheduledCommands.contains(command) ||
+      (frc::RobotState::IsDisabled() && !command->RunsWhenDisabled())) {
     return;
   }
 
@@ -130,8 +133,8 @@
   for (auto&& i1 : m_impl->requirements) {
     if (requirements.find(i1.first) != requirements.end()) {
       isDisjoint = false;
-      allInterruptible &=
-          m_impl->scheduledCommands[i1.second].IsInterruptible();
+      allInterruptible &= (i1.second->GetInterruptionBehavior() ==
+                           Command::InterruptionBehavior::kCancelSelf);
       intersection.emplace_back(i1.second);
     }
   }
@@ -142,11 +145,11 @@
         Cancel(cmdToCancel);
       }
     }
-    command->Initialize();
-    m_impl->scheduledCommands[command] = CommandState{interruptible};
+    m_impl->scheduledCommands.insert(command);
     for (auto&& requirement : requirements) {
       m_impl->requirements[requirement] = command;
     }
+    command->Initialize();
     for (auto&& action : m_impl->initActions) {
       action(*command);
     }
@@ -154,36 +157,22 @@
   }
 }
 
-void CommandScheduler::Schedule(Command* command) {
-  Schedule(true, command);
-}
-
-void CommandScheduler::Schedule(bool interruptible,
-                                wpi::span<Command* const> commands) {
+void CommandScheduler::Schedule(std::span<Command* const> commands) {
   for (auto command : commands) {
-    Schedule(interruptible, command);
-  }
-}
-
-void CommandScheduler::Schedule(bool interruptible,
-                                std::initializer_list<Command*> commands) {
-  for (auto command : commands) {
-    Schedule(interruptible, command);
-  }
-}
-
-void CommandScheduler::Schedule(wpi::span<Command* const> commands) {
-  for (auto command : commands) {
-    Schedule(true, command);
+    Schedule(command);
   }
 }
 
 void CommandScheduler::Schedule(std::initializer_list<Command*> commands) {
   for (auto command : commands) {
-    Schedule(true, command);
+    Schedule(command);
   }
 }
 
+void CommandScheduler::Schedule(const CommandPtr& command) {
+  Schedule(command.get());
+}
+
 void CommandScheduler::Run() {
   if (m_impl->disabled) {
     return;
@@ -200,18 +189,16 @@
     m_watchdog.AddEpoch("Subsystem Periodic()");
   }
 
+  // Cache the active instance to avoid concurrency problems if SetActiveLoop()
+  // is called from inside the button bindings.
+  frc::EventLoop* loopCache = m_impl->activeButtonLoop;
   // Poll buttons for new commands to add.
-  for (auto&& button : m_impl->buttons) {
-    button();
-  }
+  loopCache->Poll();
   m_watchdog.AddEpoch("buttons.Run()");
 
   m_impl->inRunLoop = true;
   // Run scheduled commands, remove finished commands.
-  for (auto iterator = m_impl->scheduledCommands.begin();
-       iterator != m_impl->scheduledCommands.end(); iterator++) {
-    Command* command = iterator->getFirst();
-
+  for (Command* command : m_impl->scheduledCommands) {
     if (!command->RunsWhenDisabled() && frc::RobotState::IsDisabled()) {
       Cancel(command);
       continue;
@@ -233,14 +220,14 @@
         m_impl->requirements.erase(requirement);
       }
 
-      m_impl->scheduledCommands.erase(iterator);
+      m_impl->scheduledCommands.erase(command);
       m_watchdog.AddEpoch(command->GetName() + ".End(false)");
     }
   }
   m_impl->inRunLoop = false;
 
-  for (auto&& commandInterruptible : m_impl->toSchedule) {
-    Schedule(commandInterruptible.second, commandInterruptible.first);
+  for (Command* command : m_impl->toSchedule) {
+    Schedule(command);
   }
 
   for (auto&& command : m_impl->toCancel) {
@@ -265,6 +252,11 @@
 }
 
 void CommandScheduler::RegisterSubsystem(Subsystem* subsystem) {
+  if (m_impl->subsystems.find(subsystem) != m_impl->subsystems.end()) {
+    std::puts("Tried to register an already-registered subsystem");
+    return;
+  }
+
   m_impl->subsystems[subsystem] = nullptr;
 }
 
@@ -283,7 +275,7 @@
 }
 
 void CommandScheduler::RegisterSubsystem(
-    wpi::span<Subsystem* const> subsystems) {
+    std::span<Subsystem* const> subsystems) {
   for (auto* subsystem : subsystems) {
     RegisterSubsystem(subsystem);
   }
@@ -297,12 +289,27 @@
 }
 
 void CommandScheduler::UnregisterSubsystem(
-    wpi::span<Subsystem* const> subsystems) {
+    std::span<Subsystem* const> subsystems) {
   for (auto* subsystem : subsystems) {
     UnregisterSubsystem(subsystem);
   }
 }
 
+void CommandScheduler::SetDefaultCommand(Subsystem* subsystem,
+                                         CommandPtr&& defaultCommand) {
+  if (!defaultCommand.get()->HasRequirement(subsystem)) {
+    throw FRC_MakeError(frc::err::CommandIllegalUse, "{}",
+                        "Default commands must require their subsystem!");
+  }
+  RequireUngrouped(defaultCommand.get());
+
+  SetDefaultCommandImpl(subsystem, std::move(defaultCommand).Unwrap());
+}
+
+void CommandScheduler::RemoveDefaultCommand(Subsystem* subsystem) {
+  m_impl->subsystems[subsystem] = nullptr;
+}
+
 Command* CommandScheduler::GetDefaultCommand(const Subsystem* subsystem) const {
   auto&& find = m_impl->subsystems.find(subsystem);
   if (find != m_impl->subsystems.end()) {
@@ -326,20 +333,24 @@
   if (find == m_impl->scheduledCommands.end()) {
     return;
   }
-  command->End(true);
-  for (auto&& action : m_impl->interruptActions) {
-    action(*command);
-  }
-  m_watchdog.AddEpoch(command->GetName() + ".End(true)");
-  m_impl->scheduledCommands.erase(find);
+  m_impl->scheduledCommands.erase(*find);
   for (auto&& requirement : m_impl->requirements) {
     if (requirement.second == command) {
       m_impl->requirements.erase(requirement.first);
     }
   }
+  command->End(true);
+  for (auto&& action : m_impl->interruptActions) {
+    action(*command);
+  }
+  m_watchdog.AddEpoch(command->GetName() + ".End(true)");
 }
 
-void CommandScheduler::Cancel(wpi::span<Command* const> commands) {
+void CommandScheduler::Cancel(const CommandPtr& command) {
+  Cancel(command.get());
+}
+
+void CommandScheduler::Cancel(std::span<Command* const> commands) {
   for (auto command : commands) {
     Cancel(command);
   }
@@ -354,22 +365,13 @@
 void CommandScheduler::CancelAll() {
   wpi::SmallVector<Command*, 16> commands;
   for (auto&& command : m_impl->scheduledCommands) {
-    commands.emplace_back(command.first);
+    commands.emplace_back(command);
   }
   Cancel(commands);
 }
 
-units::second_t CommandScheduler::TimeSinceScheduled(
-    const Command* command) const {
-  auto find = m_impl->scheduledCommands.find(command);
-  if (find != m_impl->scheduledCommands.end()) {
-    return find->second.TimeSinceInitialized();
-  } else {
-    return -1_s;
-  }
-}
 bool CommandScheduler::IsScheduled(
-    wpi::span<const Command* const> commands) const {
+    std::span<const Command* const> commands) const {
   for (auto command : commands) {
     if (!IsScheduled(command)) {
       return false;
@@ -389,8 +391,11 @@
 }
 
 bool CommandScheduler::IsScheduled(const Command* command) const {
-  return m_impl->scheduledCommands.find(command) !=
-         m_impl->scheduledCommands.end();
+  return m_impl->scheduledCommands.contains(command);
+}
+
+bool CommandScheduler::IsScheduled(const CommandPtr& command) const {
+  return m_impl->scheduledCommands.contains(command.get());
 }
 
 Command* CommandScheduler::Requiring(const Subsystem* subsystem) const {
@@ -426,39 +431,70 @@
   m_impl->finishActions.emplace_back(std::move(action));
 }
 
+void CommandScheduler::RequireUngrouped(const Command* command) {
+  if (command->IsComposed()) {
+    throw FRC_MakeError(
+        frc::err::CommandIllegalUse,
+        "Commands cannot be added to more than one CommandGroup");
+  }
+}
+
+void CommandScheduler::RequireUngrouped(
+    std::span<const std::unique_ptr<Command>> commands) {
+  for (auto&& command : commands) {
+    RequireUngrouped(command.get());
+  }
+}
+
+void CommandScheduler::RequireUngrouped(
+    std::initializer_list<const Command*> commands) {
+  for (auto&& command : commands) {
+    RequireUngrouped(command);
+  }
+}
+
 void CommandScheduler::InitSendable(nt::NTSendableBuilder& builder) {
   builder.SetSmartDashboardType("Scheduler");
-  auto namesEntry = builder.GetEntry("Names");
-  auto idsEntry = builder.GetEntry("Ids");
-  auto cancelEntry = builder.GetEntry("Cancel");
+  builder.SetUpdateTable(
+      [this,
+       namesPub = nt::StringArrayTopic{builder.GetTopic("Names")}.Publish(),
+       idsPub = nt::IntegerArrayTopic{builder.GetTopic("Ids")}.Publish(),
+       cancelEntry = nt::IntegerArrayTopic{builder.GetTopic("Cancel")}.GetEntry(
+           {})]() mutable {
+        auto toCancel = cancelEntry.Get();
+        if (!toCancel.empty()) {
+          for (auto cancel : cancelEntry.Get()) {
+            uintptr_t ptrTmp = static_cast<uintptr_t>(cancel);
+            Command* command = reinterpret_cast<Command*>(ptrTmp);
+            if (m_impl->scheduledCommands.find(command) !=
+                m_impl->scheduledCommands.end()) {
+              Cancel(command);
+            }
+          }
+          cancelEntry.Set({});
+        }
 
-  builder.SetUpdateTable([=] {
-    double tmp[1];
-    tmp[0] = 0;
-    auto toCancel = cancelEntry.GetDoubleArray(tmp);
-    for (auto cancel : toCancel) {
-      uintptr_t ptrTmp = static_cast<uintptr_t>(cancel);
-      Command* command = reinterpret_cast<Command*>(ptrTmp);
-      if (m_impl->scheduledCommands.find(command) !=
-          m_impl->scheduledCommands.end()) {
-        Cancel(command);
-      }
-      nt::NetworkTableEntry(cancelEntry).SetDoubleArray({});
-    }
-
-    wpi::SmallVector<std::string, 8> names;
-    wpi::SmallVector<double, 8> ids;
-    for (auto&& command : m_impl->scheduledCommands) {
-      names.emplace_back(command.first->GetName());
-      uintptr_t ptrTmp = reinterpret_cast<uintptr_t>(command.first);
-      ids.emplace_back(static_cast<double>(ptrTmp));
-    }
-    nt::NetworkTableEntry(namesEntry).SetStringArray(names);
-    nt::NetworkTableEntry(idsEntry).SetDoubleArray(ids);
-  });
+        wpi::SmallVector<std::string, 8> names;
+        wpi::SmallVector<int64_t, 8> ids;
+        for (Command* command : m_impl->scheduledCommands) {
+          names.emplace_back(command->GetName());
+          uintptr_t ptrTmp = reinterpret_cast<uintptr_t>(command);
+          ids.emplace_back(static_cast<int64_t>(ptrTmp));
+        }
+        namesPub.Set(names);
+        idsPub.Set(ids);
+      });
 }
 
 void CommandScheduler::SetDefaultCommandImpl(Subsystem* subsystem,
                                              std::unique_ptr<Command> command) {
+  if (command->GetInterruptionBehavior() ==
+      Command::InterruptionBehavior::kCancelIncoming) {
+    std::puts(
+        "Registering a non-interruptible default command!\n"
+        "This will likely prevent any other commands from "
+        "requiring this subsystem.");
+    // Warn, but allow -- there might be a use case for this.
+  }
   m_impl->subsystems[subsystem] = std::move(command);
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandState.cpp b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandState.cpp
deleted file mode 100644
index f53a694..0000000
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandState.cpp
+++ /dev/null
@@ -1,27 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc2/command/CommandState.h"
-
-#include <frc/Timer.h>
-
-using namespace frc2;
-CommandState::CommandState(bool interruptible)
-    : m_interruptible{interruptible} {
-  StartTiming();
-  StartRunning();
-}
-
-void CommandState::StartTiming() {
-  m_startTime = frc::Timer::GetFPGATimestamp();
-}
-
-void CommandState::StartRunning() {
-  m_startTime = -1_s;
-}
-
-units::second_t CommandState::TimeSinceInitialized() const {
-  return m_startTime != -1_s ? frc::Timer::GetFPGATimestamp() - m_startTime
-                             : -1_s;
-}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/Commands.cpp b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/Commands.cpp
new file mode 100644
index 0000000..1932e45
--- /dev/null
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/Commands.cpp
@@ -0,0 +1,124 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc2/command/Commands.h"
+
+#include "frc2/command/ConditionalCommand.h"
+#include "frc2/command/FunctionalCommand.h"
+#include "frc2/command/InstantCommand.h"
+#include "frc2/command/ParallelCommandGroup.h"
+#include "frc2/command/ParallelDeadlineGroup.h"
+#include "frc2/command/ParallelRaceGroup.h"
+#include "frc2/command/PrintCommand.h"
+#include "frc2/command/RunCommand.h"
+#include "frc2/command/SequentialCommandGroup.h"
+#include "frc2/command/WaitCommand.h"
+#include "frc2/command/WaitUntilCommand.h"
+
+using namespace frc2;
+
+// Factories
+
+CommandPtr cmd::None() {
+  return InstantCommand().ToPtr();
+}
+
+CommandPtr cmd::RunOnce(std::function<void()> action,
+                        std::initializer_list<Subsystem*> requirements) {
+  return InstantCommand(std::move(action), requirements).ToPtr();
+}
+
+CommandPtr cmd::RunOnce(std::function<void()> action,
+                        std::span<Subsystem* const> requirements) {
+  return InstantCommand(std::move(action), requirements).ToPtr();
+}
+
+CommandPtr cmd::Run(std::function<void()> action,
+                    std::initializer_list<Subsystem*> requirements) {
+  return RunCommand(std::move(action), requirements).ToPtr();
+}
+
+CommandPtr cmd::Run(std::function<void()> action,
+                    std::span<Subsystem* const> requirements) {
+  return RunCommand(std::move(action), requirements).ToPtr();
+}
+
+CommandPtr cmd::StartEnd(std::function<void()> start, std::function<void()> end,
+                         std::initializer_list<Subsystem*> requirements) {
+  return FunctionalCommand(
+             std::move(start), [] {},
+             [end = std::move(end)](bool interrupted) { end(); },
+             [] { return false; }, requirements)
+      .ToPtr();
+}
+
+CommandPtr cmd::StartEnd(std::function<void()> start, std::function<void()> end,
+                         std::span<Subsystem* const> requirements) {
+  return FunctionalCommand(
+             std::move(start), [] {},
+             [end = std::move(end)](bool interrupted) { end(); },
+             [] { return false; }, requirements)
+      .ToPtr();
+}
+
+CommandPtr cmd::RunEnd(std::function<void()> run, std::function<void()> end,
+                       std::initializer_list<Subsystem*> requirements) {
+  return FunctionalCommand([] {}, std::move(run),
+                           [end = std::move(end)](bool interrupted) { end(); },
+                           [] { return false; }, requirements)
+      .ToPtr();
+}
+
+CommandPtr cmd::RunEnd(std::function<void()> run, std::function<void()> end,
+                       std::span<Subsystem* const> requirements) {
+  return FunctionalCommand([] {}, std::move(run),
+                           [end = std::move(end)](bool interrupted) { end(); },
+                           [] { return false; }, requirements)
+      .ToPtr();
+}
+
+CommandPtr cmd::Print(std::string_view msg) {
+  return PrintCommand(msg).ToPtr();
+}
+
+CommandPtr cmd::Wait(units::second_t duration) {
+  return WaitCommand(duration).ToPtr();
+}
+
+CommandPtr cmd::WaitUntil(std::function<bool()> condition) {
+  return WaitUntilCommand(condition).ToPtr();
+}
+
+CommandPtr cmd::Either(CommandPtr&& onTrue, CommandPtr&& onFalse,
+                       std::function<bool()> selector) {
+  return ConditionalCommand(std::move(onTrue).Unwrap(),
+                            std::move(onFalse).Unwrap(), std::move(selector))
+      .ToPtr();
+}
+
+CommandPtr cmd::Sequence(std::vector<CommandPtr>&& commands) {
+  return SequentialCommandGroup(CommandPtr::UnwrapVector(std::move(commands)))
+      .ToPtr();
+}
+
+CommandPtr cmd::RepeatingSequence(std::vector<CommandPtr>&& commands) {
+  return Sequence(std::move(commands)).Repeatedly();
+}
+
+CommandPtr cmd::Parallel(std::vector<CommandPtr>&& commands) {
+  return ParallelCommandGroup(CommandPtr::UnwrapVector(std::move(commands)))
+      .ToPtr();
+}
+
+CommandPtr cmd::Race(std::vector<CommandPtr>&& commands) {
+  return ParallelRaceGroup(CommandPtr::UnwrapVector(std::move(commands)))
+      .ToPtr();
+}
+
+CommandPtr cmd::Deadline(CommandPtr&& deadline,
+                         std::vector<CommandPtr>&& others) {
+  return ParallelDeadlineGroup(std::move(deadline).Unwrap(),
+                               CommandPtr::UnwrapVector(std::move(others)))
+      .ToPtr();
+}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/ConditionalCommand.cpp b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/ConditionalCommand.cpp
index 30ef410..2610c96 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/ConditionalCommand.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/ConditionalCommand.cpp
@@ -4,21 +4,22 @@
 
 #include "frc2/command/ConditionalCommand.h"
 
+#include <wpi/sendable/SendableBuilder.h>
+
 using namespace frc2;
 
 ConditionalCommand::ConditionalCommand(std::unique_ptr<Command>&& onTrue,
                                        std::unique_ptr<Command>&& onFalse,
                                        std::function<bool()> condition)
     : m_condition{std::move(condition)} {
-  if (!CommandGroupBase::RequireUngrouped({onTrue.get(), onFalse.get()})) {
-    return;
-  }
+  CommandScheduler::GetInstance().RequireUngrouped(
+      {onTrue.get(), onFalse.get()});
 
   m_onTrue = std::move(onTrue);
   m_onFalse = std::move(onFalse);
 
-  m_onTrue->SetGrouped(true);
-  m_onFalse->SetGrouped(true);
+  m_onTrue->SetComposed(true);
+  m_onFalse->SetComposed(true);
 
   m_runsWhenDisabled &= m_onTrue->RunsWhenDisabled();
   m_runsWhenDisabled &= m_onFalse->RunsWhenDisabled();
@@ -51,3 +52,21 @@
 bool ConditionalCommand::RunsWhenDisabled() const {
   return m_runsWhenDisabled;
 }
+
+void ConditionalCommand::InitSendable(wpi::SendableBuilder& builder) {
+  CommandBase::InitSendable(builder);
+  builder.AddStringProperty(
+      "onTrue", [this] { return m_onTrue->GetName(); }, nullptr);
+  builder.AddStringProperty(
+      "onFalse", [this] { return m_onFalse->GetName(); }, nullptr);
+  builder.AddStringProperty(
+      "selected",
+      [this] {
+        if (m_selectedCommand) {
+          return m_selectedCommand->GetName();
+        } else {
+          return std::string{"null"};
+        }
+      },
+      nullptr);
+}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/FunctionalCommand.cpp b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/FunctionalCommand.cpp
index 0c45099..02e8338 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/FunctionalCommand.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/FunctionalCommand.cpp
@@ -21,7 +21,7 @@
                                      std::function<void()> onExecute,
                                      std::function<void(bool)> onEnd,
                                      std::function<bool()> isFinished,
-                                     wpi::span<Subsystem* const> requirements)
+                                     std::span<Subsystem* const> requirements)
     : m_onInit{std::move(onInit)},
       m_onExecute{std::move(onExecute)},
       m_onEnd{std::move(onEnd)},
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/InstantCommand.cpp b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/InstantCommand.cpp
index 1e9d173..7b73239 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/InstantCommand.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/InstantCommand.cpp
@@ -8,22 +8,14 @@
 
 InstantCommand::InstantCommand(std::function<void()> toRun,
                                std::initializer_list<Subsystem*> requirements)
-    : m_toRun{std::move(toRun)} {
-  AddRequirements(requirements);
-}
+    : CommandHelper(
+          std::move(toRun), [] {}, [](bool interrupted) {}, [] { return true; },
+          requirements) {}
 
 InstantCommand::InstantCommand(std::function<void()> toRun,
-                               wpi::span<Subsystem* const> requirements)
-    : m_toRun{std::move(toRun)} {
-  AddRequirements(requirements);
-}
+                               std::span<Subsystem* const> requirements)
+    : CommandHelper(
+          std::move(toRun), [] {}, [](bool interrupted) {}, [] { return true; },
+          requirements) {}
 
-InstantCommand::InstantCommand() : m_toRun{[] {}} {}
-
-void InstantCommand::Initialize() {
-  m_toRun();
-}
-
-bool InstantCommand::IsFinished() {
-  return true;
-}
+InstantCommand::InstantCommand() : InstantCommand([] {}) {}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/MecanumControllerCommand.cpp b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/MecanumControllerCommand.cpp
index 14b5846..d95d596 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/MecanumControllerCommand.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/MecanumControllerCommand.cpp
@@ -7,7 +7,6 @@
 #include <utility>
 
 using namespace frc2;
-using namespace units;
 
 MecanumControllerCommand::MecanumControllerCommand(
     frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
@@ -99,7 +98,7 @@
     std::function<void(units::volt_t, units::volt_t, units::volt_t,
                        units::volt_t)>
         output,
-    wpi::span<Subsystem* const> requirements)
+    std::span<Subsystem* const> requirements)
     : m_trajectory(std::move(trajectory)),
       m_pose(std::move(pose)),
       m_feedforward(feedforward),
@@ -136,7 +135,7 @@
     std::function<void(units::volt_t, units::volt_t, units::volt_t,
                        units::volt_t)>
         output,
-    wpi::span<Subsystem* const> requirements)
+    std::span<Subsystem* const> requirements)
     : m_trajectory(std::move(trajectory)),
       m_pose(std::move(pose)),
       m_feedforward(feedforward),
@@ -209,7 +208,7 @@
     std::function<void(units::meters_per_second_t, units::meters_per_second_t,
                        units::meters_per_second_t, units::meters_per_second_t)>
         output,
-    wpi::span<Subsystem* const> requirements)
+    std::span<Subsystem* const> requirements)
     : m_trajectory(std::move(trajectory)),
       m_pose(std::move(pose)),
       m_kinematics(kinematics),
@@ -230,7 +229,7 @@
     std::function<void(units::meters_per_second_t, units::meters_per_second_t,
                        units::meters_per_second_t, units::meters_per_second_t)>
         output,
-    wpi::span<Subsystem* const> requirements)
+    std::span<Subsystem* const> requirements)
     : m_trajectory(std::move(trajectory)),
       m_pose(std::move(pose)),
       m_kinematics(kinematics),
@@ -269,7 +268,7 @@
 }
 
 void MecanumControllerCommand::Execute() {
-  auto curTime = second_t(m_timer.Get());
+  auto curTime = m_timer.Get();
   auto dt = curTime - m_prevTime;
 
   auto m_desiredState = m_trajectory.Sample(curTime);
@@ -302,21 +301,21 @@
         rearRightSpeedSetpoint,
         (rearRightSpeedSetpoint - m_prevSpeeds.rearRight) / dt);
 
-    auto frontLeftOutput = volt_t(m_frontLeftController->Calculate(
+    auto frontLeftOutput = units::volt_t{m_frontLeftController->Calculate(
                                m_currentWheelSpeeds().frontLeft.value(),
-                               frontLeftSpeedSetpoint.value())) +
+                               frontLeftSpeedSetpoint.value())} +
                            frontLeftFeedforward;
-    auto rearLeftOutput = volt_t(m_rearLeftController->Calculate(
+    auto rearLeftOutput = units::volt_t{m_rearLeftController->Calculate(
                               m_currentWheelSpeeds().rearLeft.value(),
-                              rearLeftSpeedSetpoint.value())) +
+                              rearLeftSpeedSetpoint.value())} +
                           rearLeftFeedforward;
-    auto frontRightOutput = volt_t(m_frontRightController->Calculate(
+    auto frontRightOutput = units::volt_t{m_frontRightController->Calculate(
                                 m_currentWheelSpeeds().frontRight.value(),
-                                frontRightSpeedSetpoint.value())) +
+                                frontRightSpeedSetpoint.value())} +
                             frontRightFeedforward;
-    auto rearRightOutput = volt_t(m_rearRightController->Calculate(
+    auto rearRightOutput = units::volt_t{m_rearRightController->Calculate(
                                m_currentWheelSpeeds().rearRight.value(),
-                               rearRightSpeedSetpoint.value())) +
+                               rearRightSpeedSetpoint.value())} +
                            rearRightFeedforward;
 
     m_outputVolts(frontLeftOutput, rearLeftOutput, frontRightOutput,
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/NotifierCommand.cpp b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/NotifierCommand.cpp
index 37e5bc6..2081d07 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/NotifierCommand.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/NotifierCommand.cpp
@@ -15,7 +15,7 @@
 
 NotifierCommand::NotifierCommand(std::function<void()> toRun,
                                  units::second_t period,
-                                 wpi::span<Subsystem* const> requirements)
+                                 std::span<Subsystem* const> requirements)
     : m_toRun(toRun), m_notifier{std::move(toRun)}, m_period{period} {
   AddRequirements(requirements);
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/PIDCommand.cpp b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/PIDCommand.cpp
index d11735a..672fa47 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/PIDCommand.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/PIDCommand.cpp
@@ -24,7 +24,7 @@
                        std::function<double()> measurementSource,
                        std::function<double()> setpointSource,
                        std::function<void(double)> useOutput,
-                       wpi::span<Subsystem* const> requirements)
+                       std::span<Subsystem* const> requirements)
     : m_controller{std::move(controller)},
       m_measurement{std::move(measurementSource)},
       m_setpoint{std::move(setpointSource)},
@@ -43,7 +43,7 @@
 PIDCommand::PIDCommand(PIDController controller,
                        std::function<double()> measurementSource,
                        double setpoint, std::function<void(double)> useOutput,
-                       wpi::span<Subsystem* const> requirements)
+                       std::span<Subsystem* const> requirements)
     : PIDCommand(
           controller, measurementSource, [setpoint] { return setpoint; },
           useOutput, requirements) {}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/PIDSubsystem.cpp b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/PIDSubsystem.cpp
index 7c820ae..8db032a 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/PIDSubsystem.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/PIDSubsystem.cpp
@@ -16,16 +16,16 @@
 
 void PIDSubsystem::Periodic() {
   if (m_enabled) {
-    UseOutput(m_controller.Calculate(GetMeasurement(), m_setpoint), m_setpoint);
+    UseOutput(m_controller.Calculate(GetMeasurement()), GetSetpoint());
   }
 }
 
 void PIDSubsystem::SetSetpoint(double setpoint) {
-  m_setpoint = setpoint;
+  m_controller.SetSetpoint(setpoint);
 }
 
 double PIDSubsystem::GetSetpoint() const {
-  return m_setpoint;
+  return m_controller.GetSetpoint();
 }
 
 void PIDSubsystem::Enable() {
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/ParallelCommandGroup.cpp b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/ParallelCommandGroup.cpp
index a12d2b4..99e0845 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/ParallelCommandGroup.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/ParallelCommandGroup.cpp
@@ -56,28 +56,33 @@
   return m_runWhenDisabled;
 }
 
+Command::InterruptionBehavior ParallelCommandGroup::GetInterruptionBehavior()
+    const {
+  return m_interruptBehavior;
+}
+
 void ParallelCommandGroup::AddCommands(
     std::vector<std::unique_ptr<Command>>&& commands) {
-  for (auto&& command : commands) {
-    if (!RequireUngrouped(*command)) {
-      return;
-    }
-  }
+  CommandScheduler::GetInstance().RequireUngrouped(commands);
 
   if (isRunning) {
-    throw FRC_MakeError(frc::err::CommandIllegalUse, "{}",
+    throw FRC_MakeError(frc::err::CommandIllegalUse,
                         "Commands cannot be added to a CommandGroup "
                         "while the group is running");
   }
 
   for (auto&& command : commands) {
     if (RequirementsDisjoint(this, command.get())) {
-      command->SetGrouped(true);
+      command->SetComposed(true);
       AddRequirements(command->GetRequirements());
       m_runWhenDisabled &= command->RunsWhenDisabled();
+      if (command->GetInterruptionBehavior() ==
+          Command::InterruptionBehavior::kCancelSelf) {
+        m_interruptBehavior = Command::InterruptionBehavior::kCancelSelf;
+      }
       m_commands.emplace_back(std::move(command), false);
     } else {
-      throw FRC_MakeError(frc::err::CommandIllegalUse, "{}",
+      throw FRC_MakeError(frc::err::CommandIllegalUse,
                           "Multiple commands in a parallel group cannot "
                           "require the same subsystems");
     }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/ParallelDeadlineGroup.cpp b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/ParallelDeadlineGroup.cpp
index 93dd2fd..14c28c3 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/ParallelDeadlineGroup.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/ParallelDeadlineGroup.cpp
@@ -4,6 +4,8 @@
 
 #include "frc2/command/ParallelDeadlineGroup.h"
 
+#include <wpi/sendable/SendableBuilder.h>
+
 using namespace frc2;
 
 ParallelDeadlineGroup::ParallelDeadlineGroup(
@@ -53,26 +55,33 @@
   return m_runWhenDisabled;
 }
 
+Command::InterruptionBehavior ParallelDeadlineGroup::GetInterruptionBehavior()
+    const {
+  return m_interruptBehavior;
+}
+
 void ParallelDeadlineGroup::AddCommands(
     std::vector<std::unique_ptr<Command>>&& commands) {
-  if (!RequireUngrouped(commands)) {
-    return;
-  }
+  CommandScheduler::GetInstance().RequireUngrouped(commands);
 
   if (!m_finished) {
-    throw FRC_MakeError(frc::err::CommandIllegalUse, "{}",
+    throw FRC_MakeError(frc::err::CommandIllegalUse,
                         "Commands cannot be added to a CommandGroup "
                         "while the group is running");
   }
 
   for (auto&& command : commands) {
     if (RequirementsDisjoint(this, command.get())) {
-      command->SetGrouped(true);
+      command->SetComposed(true);
       AddRequirements(command->GetRequirements());
       m_runWhenDisabled &= command->RunsWhenDisabled();
+      if (command->GetInterruptionBehavior() ==
+          Command::InterruptionBehavior::kCancelSelf) {
+        m_interruptBehavior = Command::InterruptionBehavior::kCancelSelf;
+      }
       m_commands.emplace_back(std::move(command), false);
     } else {
-      throw FRC_MakeError(frc::err::CommandIllegalUse, "{}",
+      throw FRC_MakeError(frc::err::CommandIllegalUse,
                           "Multiple commands in a parallel group cannot "
                           "require the same subsystems");
     }
@@ -81,8 +90,15 @@
 
 void ParallelDeadlineGroup::SetDeadline(std::unique_ptr<Command>&& deadline) {
   m_deadline = deadline.get();
-  m_deadline->SetGrouped(true);
+  m_deadline->SetComposed(true);
   m_commands.emplace_back(std::move(deadline), false);
   AddRequirements(m_deadline->GetRequirements());
   m_runWhenDisabled &= m_deadline->RunsWhenDisabled();
 }
+
+void ParallelDeadlineGroup::InitSendable(wpi::SendableBuilder& builder) {
+  CommandBase::InitSendable(builder);
+
+  builder.AddStringProperty(
+      "deadline", [this] { return m_deadline->GetName(); }, nullptr);
+}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/ParallelRaceGroup.cpp b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/ParallelRaceGroup.cpp
index 63c7cbc..df658bc 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/ParallelRaceGroup.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/ParallelRaceGroup.cpp
@@ -43,26 +43,33 @@
   return m_runWhenDisabled;
 }
 
+Command::InterruptionBehavior ParallelRaceGroup::GetInterruptionBehavior()
+    const {
+  return m_interruptBehavior;
+}
+
 void ParallelRaceGroup::AddCommands(
     std::vector<std::unique_ptr<Command>>&& commands) {
-  if (!RequireUngrouped(commands)) {
-    return;
-  }
+  CommandScheduler::GetInstance().RequireUngrouped(commands);
 
   if (isRunning) {
-    throw FRC_MakeError(frc::err::CommandIllegalUse, "{}",
+    throw FRC_MakeError(frc::err::CommandIllegalUse,
                         "Commands cannot be added to a CommandGroup "
                         "while the group is running");
   }
 
   for (auto&& command : commands) {
     if (RequirementsDisjoint(this, command.get())) {
-      command->SetGrouped(true);
+      command->SetComposed(true);
       AddRequirements(command->GetRequirements());
       m_runWhenDisabled &= command->RunsWhenDisabled();
+      if (command->GetInterruptionBehavior() ==
+          Command::InterruptionBehavior::kCancelSelf) {
+        m_interruptBehavior = Command::InterruptionBehavior::kCancelSelf;
+      }
       m_commands.emplace_back(std::move(command));
     } else {
-      throw FRC_MakeError(frc::err::CommandIllegalUse, "{}",
+      throw FRC_MakeError(frc::err::CommandIllegalUse,
                           "Multiple commands in a parallel group cannot "
                           "require the same subsystems");
     }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/PerpetualCommand.cpp b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/PerpetualCommand.cpp
index bd8bb93..2d0af1e 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/PerpetualCommand.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/PerpetualCommand.cpp
@@ -7,11 +7,9 @@
 using namespace frc2;
 
 PerpetualCommand::PerpetualCommand(std::unique_ptr<Command>&& command) {
-  if (!CommandGroupBase::RequireUngrouped(*command)) {
-    return;
-  }
+  CommandScheduler::GetInstance().RequireUngrouped(command.get());
   m_command = std::move(command);
-  m_command->SetGrouped(true);
+  m_command->SetComposed(true);
   AddRequirements(m_command->GetRequirements());
 }
 
@@ -26,7 +24,3 @@
 void PerpetualCommand::End(bool interrupted) {
   m_command->End(interrupted);
 }
-
-PerpetualCommand PerpetualCommand::Perpetually() && {
-  return std::move(*this);
-}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/ProxyCommand.cpp b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/ProxyCommand.cpp
new file mode 100644
index 0000000..cc1b815
--- /dev/null
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/ProxyCommand.cpp
@@ -0,0 +1,55 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc2/command/ProxyCommand.h"
+
+#include <wpi/sendable/SendableBuilder.h>
+
+using namespace frc2;
+
+ProxyCommand::ProxyCommand(wpi::unique_function<Command*()> supplier)
+    : m_supplier(std::move(supplier)) {}
+
+ProxyCommand::ProxyCommand(Command* command)
+    : m_supplier([command] { return command; }) {
+  SetName(std::string{"Proxy("}.append(command->GetName()).append(")"));
+}
+
+ProxyCommand::ProxyCommand(std::unique_ptr<Command> command)
+    : m_supplier([command = std::move(command)] { return command.get(); }) {}
+
+void ProxyCommand::Initialize() {
+  m_command = m_supplier();
+  m_command->Schedule();
+}
+
+void ProxyCommand::End(bool interrupted) {
+  if (interrupted) {
+    m_command->Cancel();
+  }
+  m_command = nullptr;
+}
+
+void ProxyCommand::Execute() {}
+
+bool ProxyCommand::IsFinished() {
+  // because we're between `initialize` and `end`, `m_command` is necessarily
+  // not null but if called otherwise and m_command is null, it's UB, so we can
+  // do whatever we want -- like return true.
+  return m_command == nullptr || !m_command->IsScheduled();
+}
+
+void ProxyCommand::InitSendable(wpi::SendableBuilder& builder) {
+  CommandBase::InitSendable(builder);
+  builder.AddStringProperty(
+      "proxied",
+      [this] {
+        if (m_command) {
+          return m_command->GetName();
+        } else {
+          return std::string{"null"};
+        }
+      },
+      nullptr);
+}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/ProxyScheduleCommand.cpp b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/ProxyScheduleCommand.cpp
index 116ce3c..dd0e2a7 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/ProxyScheduleCommand.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/ProxyScheduleCommand.cpp
@@ -7,7 +7,7 @@
 using namespace frc2;
 
 ProxyScheduleCommand::ProxyScheduleCommand(
-    wpi::span<Command* const> toSchedule) {
+    std::span<Command* const> toSchedule) {
   SetInsert(m_toSchedule, toSchedule);
 }
 
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/RamseteCommand.cpp b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/RamseteCommand.cpp
index 4674031..d46cdd0 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/RamseteCommand.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/RamseteCommand.cpp
@@ -6,8 +6,9 @@
 
 #include <utility>
 
+#include <wpi/sendable/SendableBuilder.h>
+
 using namespace frc2;
-using namespace units;
 
 RamseteCommand::RamseteCommand(
     frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
@@ -16,7 +17,7 @@
     frc::DifferentialDriveKinematics kinematics,
     std::function<frc::DifferentialDriveWheelSpeeds()> wheelSpeeds,
     frc2::PIDController leftController, frc2::PIDController rightController,
-    std::function<void(volt_t, volt_t)> output,
+    std::function<void(units::volt_t, units::volt_t)> output,
     std::initializer_list<Subsystem*> requirements)
     : m_trajectory(std::move(trajectory)),
       m_pose(std::move(pose)),
@@ -38,8 +39,8 @@
     frc::DifferentialDriveKinematics kinematics,
     std::function<frc::DifferentialDriveWheelSpeeds()> wheelSpeeds,
     frc2::PIDController leftController, frc2::PIDController rightController,
-    std::function<void(volt_t, volt_t)> output,
-    wpi::span<Subsystem* const> requirements)
+    std::function<void(units::volt_t, units::volt_t)> output,
+    std::span<Subsystem* const> requirements)
     : m_trajectory(std::move(trajectory)),
       m_pose(std::move(pose)),
       m_controller(controller),
@@ -75,7 +76,7 @@
     frc::DifferentialDriveKinematics kinematics,
     std::function<void(units::meters_per_second_t, units::meters_per_second_t)>
         output,
-    wpi::span<Subsystem* const> requirements)
+    std::span<Subsystem* const> requirements)
     : m_trajectory(std::move(trajectory)),
       m_pose(std::move(pose)),
       m_controller(controller),
@@ -127,13 +128,13 @@
         (targetWheelSpeeds.right - m_prevSpeeds.right) / dt);
 
     auto leftOutput =
-        volt_t(m_leftController->Calculate(m_speeds().left.value(),
-                                           targetWheelSpeeds.left.value())) +
+        units::volt_t{m_leftController->Calculate(
+            m_speeds().left.value(), targetWheelSpeeds.left.value())} +
         leftFeedforward;
 
     auto rightOutput =
-        volt_t(m_rightController->Calculate(m_speeds().right.value(),
-                                            targetWheelSpeeds.right.value())) +
+        units::volt_t{m_rightController->Calculate(
+            m_speeds().right.value(), targetWheelSpeeds.right.value())} +
         rightFeedforward;
 
     m_outputVolts(leftOutput, rightOutput);
@@ -159,3 +160,11 @@
 bool RamseteCommand::IsFinished() {
   return m_timer.HasElapsed(m_trajectory.TotalTime());
 }
+
+void RamseteCommand::InitSendable(wpi::SendableBuilder& builder) {
+  CommandBase::InitSendable(builder);
+  builder.AddDoubleProperty(
+      "leftVelocity", [this] { return m_prevSpeeds.left.value(); }, nullptr);
+  builder.AddDoubleProperty(
+      "rightVelocity", [this] { return m_prevSpeeds.right.value(); }, nullptr);
+}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/RepeatCommand.cpp b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/RepeatCommand.cpp
new file mode 100644
index 0000000..319a7af
--- /dev/null
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/RepeatCommand.cpp
@@ -0,0 +1,57 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc2/command/RepeatCommand.h"
+
+#include <wpi/sendable/SendableBuilder.h>
+
+using namespace frc2;
+
+RepeatCommand::RepeatCommand(std::unique_ptr<Command>&& command) {
+  CommandScheduler::GetInstance().RequireUngrouped(command.get());
+  m_command = std::move(command);
+  m_command->SetComposed(true);
+  AddRequirements(m_command->GetRequirements());
+  SetName(std::string{"Repeat("}.append(m_command->GetName()).append(")"));
+}
+
+void RepeatCommand::Initialize() {
+  m_ended = false;
+  m_command->Initialize();
+}
+
+void RepeatCommand::Execute() {
+  if (m_ended) {
+    m_ended = false;
+    m_command->Initialize();
+  }
+  m_command->Execute();
+  if (m_command->IsFinished()) {
+    // restart command
+    m_command->End(false);
+    m_ended = true;
+  }
+}
+
+bool RepeatCommand::IsFinished() {
+  return false;
+}
+
+void RepeatCommand::End(bool interrupted) {
+  m_command->End(interrupted);
+}
+
+bool RepeatCommand::RunsWhenDisabled() const {
+  return m_command->RunsWhenDisabled();
+}
+
+Command::InterruptionBehavior RepeatCommand::GetInterruptionBehavior() const {
+  return m_command->GetInterruptionBehavior();
+}
+
+void RepeatCommand::InitSendable(wpi::SendableBuilder& builder) {
+  CommandBase::InitSendable(builder);
+  builder.AddStringProperty(
+      "command", [this] { return m_command->GetName(); }, nullptr);
+}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/RunCommand.cpp b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/RunCommand.cpp
index c63e5d6..342362f 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/RunCommand.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/RunCommand.cpp
@@ -8,16 +8,10 @@
 
 RunCommand::RunCommand(std::function<void()> toRun,
                        std::initializer_list<Subsystem*> requirements)
-    : m_toRun{std::move(toRun)} {
-  AddRequirements(requirements);
-}
+    : CommandHelper([] {}, std::move(toRun), [](bool interrupted) {},
+                    [] { return false; }, requirements) {}
 
 RunCommand::RunCommand(std::function<void()> toRun,
-                       wpi::span<Subsystem* const> requirements)
-    : m_toRun{std::move(toRun)} {
-  AddRequirements(requirements);
-}
-
-void RunCommand::Execute() {
-  m_toRun();
-}
+                       std::span<Subsystem* const> requirements)
+    : CommandHelper([] {}, std::move(toRun), [](bool interrupted) {},
+                    [] { return false; }, requirements) {}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/ScheduleCommand.cpp b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/ScheduleCommand.cpp
index ff50bc5..54c3042 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/ScheduleCommand.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/ScheduleCommand.cpp
@@ -6,7 +6,7 @@
 
 using namespace frc2;
 
-ScheduleCommand::ScheduleCommand(wpi::span<Command* const> toSchedule) {
+ScheduleCommand::ScheduleCommand(std::span<Command* const> toSchedule) {
   SetInsert(m_toSchedule, toSchedule);
 }
 
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/SequentialCommandGroup.cpp b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/SequentialCommandGroup.cpp
index 345a415..7888c1d 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/SequentialCommandGroup.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/SequentialCommandGroup.cpp
@@ -4,7 +4,7 @@
 
 #include "frc2/command/SequentialCommandGroup.h"
 
-#include "frc2/command/InstantCommand.h"
+#include <wpi/sendable/SendableBuilder.h>
 
 using namespace frc2;
 
@@ -55,52 +55,35 @@
   return m_runWhenDisabled;
 }
 
+Command::InterruptionBehavior SequentialCommandGroup::GetInterruptionBehavior()
+    const {
+  return m_interruptBehavior;
+}
+
 void SequentialCommandGroup::AddCommands(
     std::vector<std::unique_ptr<Command>>&& commands) {
-  if (!RequireUngrouped(commands)) {
-    return;
-  }
+  CommandScheduler::GetInstance().RequireUngrouped(commands);
 
   if (m_currentCommandIndex != invalid_index) {
-    throw FRC_MakeError(frc::err::CommandIllegalUse, "{}",
+    throw FRC_MakeError(frc::err::CommandIllegalUse,
                         "Commands cannot be added to a CommandGroup "
                         "while the group is running");
   }
 
   for (auto&& command : commands) {
-    command->SetGrouped(true);
+    command->SetComposed(true);
     AddRequirements(command->GetRequirements());
     m_runWhenDisabled &= command->RunsWhenDisabled();
+    if (command->GetInterruptionBehavior() ==
+        Command::InterruptionBehavior::kCancelSelf) {
+      m_interruptBehavior = Command::InterruptionBehavior::kCancelSelf;
+    }
     m_commands.emplace_back(std::move(command));
   }
 }
 
-SequentialCommandGroup SequentialCommandGroup::BeforeStarting(
-    std::function<void()> toRun, wpi::span<Subsystem* const> requirements) && {
-  // store all the commands
-  std::vector<std::unique_ptr<Command>> tmp;
-  tmp.emplace_back(
-      std::make_unique<InstantCommand>(std::move(toRun), requirements));
-  for (auto&& command : m_commands) {
-    command->SetGrouped(false);
-    tmp.emplace_back(std::move(command));
-  }
-
-  // reset current state
-  m_commands.clear();
-  m_requirements.clear();
-  m_runWhenDisabled = true;
-
-  // add the commands back
-  AddCommands(std::move(tmp));
-  return std::move(*this);
-}
-
-SequentialCommandGroup SequentialCommandGroup::AndThen(
-    std::function<void()> toRun, wpi::span<Subsystem* const> requirements) && {
-  std::vector<std::unique_ptr<Command>> tmp;
-  tmp.emplace_back(
-      std::make_unique<InstantCommand>(std::move(toRun), requirements));
-  AddCommands(std::move(tmp));
-  return std::move(*this);
+void SequentialCommandGroup::InitSendable(wpi::SendableBuilder& builder) {
+  CommandBase::InitSendable(builder);
+  builder.AddIntegerProperty(
+      "index", [this] { return m_currentCommandIndex; }, nullptr);
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/StartEndCommand.cpp b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/StartEndCommand.cpp
index dc40200..3d91ac5 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/StartEndCommand.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/StartEndCommand.cpp
@@ -9,27 +9,15 @@
 StartEndCommand::StartEndCommand(std::function<void()> onInit,
                                  std::function<void()> onEnd,
                                  std::initializer_list<Subsystem*> requirements)
-    : m_onInit{std::move(onInit)}, m_onEnd{std::move(onEnd)} {
-  AddRequirements(requirements);
-}
+    : CommandHelper(
+          std::move(onInit), [] {},
+          [onEnd = std::move(onEnd)](bool interrupted) { onEnd(); },
+          [] { return false; }, requirements) {}
 
 StartEndCommand::StartEndCommand(std::function<void()> onInit,
                                  std::function<void()> onEnd,
-                                 wpi::span<Subsystem* const> requirements)
-    : m_onInit{std::move(onInit)}, m_onEnd{std::move(onEnd)} {
-  AddRequirements(requirements);
-}
-
-StartEndCommand::StartEndCommand(const StartEndCommand& other)
-    : CommandHelper(other) {
-  m_onInit = other.m_onInit;
-  m_onEnd = other.m_onEnd;
-}
-
-void StartEndCommand::Initialize() {
-  m_onInit();
-}
-
-void StartEndCommand::End(bool interrupted) {
-  m_onEnd();
-}
+                                 std::span<Subsystem* const> requirements)
+    : CommandHelper(
+          std::move(onInit), [] {},
+          [onEnd = std::move(onEnd)](bool interrupted) { onEnd(); },
+          [] { return false; }, requirements) {}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/Subsystem.cpp b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/Subsystem.cpp
index 51cbddf..3c388bb 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/Subsystem.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/Subsystem.cpp
@@ -4,6 +4,9 @@
 
 #include "frc2/command/Subsystem.h"
 
+#include "frc2/command/CommandPtr.h"
+#include "frc2/command/Commands.h"
+
 using namespace frc2;
 Subsystem::~Subsystem() {
   CommandScheduler::GetInstance().UnregisterSubsystem(this);
@@ -13,6 +16,11 @@
 
 void Subsystem::SimulationPeriodic() {}
 
+void Subsystem::SetDefaultCommand(CommandPtr&& defaultCommand) {
+  CommandScheduler::GetInstance().SetDefaultCommand(this,
+                                                    std::move(defaultCommand));
+}
+
 Command* Subsystem::GetDefaultCommand() const {
   return CommandScheduler::GetInstance().GetDefaultCommand(this);
 }
@@ -24,3 +32,21 @@
 void Subsystem::Register() {
   return CommandScheduler::GetInstance().RegisterSubsystem(this);
 }
+
+CommandPtr Subsystem::RunOnce(std::function<void()> action) {
+  return cmd::RunOnce(std::move(action), {this});
+}
+
+CommandPtr Subsystem::Run(std::function<void()> action) {
+  return cmd::Run(std::move(action), {this});
+}
+
+CommandPtr Subsystem::StartEnd(std::function<void()> start,
+                               std::function<void()> end) {
+  return cmd::StartEnd(std::move(start), std::move(end), {this});
+}
+
+CommandPtr Subsystem::RunEnd(std::function<void()> run,
+                             std::function<void()> end) {
+  return cmd::RunEnd(std::move(run), std::move(end), {this});
+}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/WaitCommand.cpp b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/WaitCommand.cpp
index da03540..94b8b8a 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/WaitCommand.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/WaitCommand.cpp
@@ -6,6 +6,7 @@
 
 #include <fmt/format.h>
 #include <frc/fmt/Units.h>
+#include <wpi/sendable/SendableBuilder.h>
 
 using namespace frc2;
 
@@ -29,3 +30,9 @@
 bool WaitCommand::RunsWhenDisabled() const {
   return true;
 }
+
+void WaitCommand::InitSendable(wpi::SendableBuilder& builder) {
+  CommandBase::InitSendable(builder);
+  builder.AddDoubleProperty(
+      "duration", [this] { return m_duration.value(); }, nullptr);
+}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/WrapperCommand.cpp b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/WrapperCommand.cpp
new file mode 100644
index 0000000..f7928c9
--- /dev/null
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/WrapperCommand.cpp
@@ -0,0 +1,45 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc2/command/WrapperCommand.h"
+
+#include "frc2/command/Command.h"
+
+using namespace frc2;
+
+WrapperCommand::WrapperCommand(std::unique_ptr<Command>&& command) {
+  CommandScheduler::GetInstance().RequireUngrouped(command.get());
+  m_command = std::move(command);
+  m_command->SetComposed(true);
+  // copy the wrapped command's name
+  SetName(m_command->GetName());
+}
+
+void WrapperCommand::Initialize() {
+  m_command->Initialize();
+}
+
+void WrapperCommand::Execute() {
+  m_command->Execute();
+}
+
+bool WrapperCommand::IsFinished() {
+  return m_command->IsFinished();
+}
+
+void WrapperCommand::End(bool interrupted) {
+  m_command->End(interrupted);
+}
+
+bool WrapperCommand::RunsWhenDisabled() const {
+  return m_command->RunsWhenDisabled();
+}
+
+Command::InterruptionBehavior WrapperCommand::GetInterruptionBehavior() const {
+  return m_command->GetInterruptionBehavior();
+}
+
+wpi::SmallSet<Subsystem*, 4> WrapperCommand::GetRequirements() const {
+  return m_command->GetRequirements();
+}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/button/Button.cpp b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/button/Button.cpp
index 955830a..787fc09 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/button/Button.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/button/Button.cpp
@@ -8,68 +8,92 @@
 
 Button::Button(std::function<bool()> isPressed) : Trigger(isPressed) {}
 
-Button Button::WhenPressed(Command* command, bool interruptible) {
-  WhenActive(command, interruptible);
+Button Button::WhenPressed(Command* command) {
+  WPI_IGNORE_DEPRECATED
+  WhenActive(command);
+  WPI_UNIGNORE_DEPRECATED
   return *this;
 }
 
 Button Button::WhenPressed(std::function<void()> toRun,
                            std::initializer_list<Subsystem*> requirements) {
+  WPI_IGNORE_DEPRECATED
   WhenActive(std::move(toRun), requirements);
+  WPI_UNIGNORE_DEPRECATED
   return *this;
 }
 
 Button Button::WhenPressed(std::function<void()> toRun,
-                           wpi::span<Subsystem* const> requirements) {
+                           std::span<Subsystem* const> requirements) {
+  WPI_IGNORE_DEPRECATED
   WhenActive(std::move(toRun), requirements);
+  WPI_UNIGNORE_DEPRECATED
   return *this;
 }
 
-Button Button::WhileHeld(Command* command, bool interruptible) {
-  WhileActiveContinous(command, interruptible);
+Button Button::WhileHeld(Command* command) {
+  WPI_IGNORE_DEPRECATED
+  WhileActiveContinous(command);
+  WPI_UNIGNORE_DEPRECATED
   return *this;
 }
 
 Button Button::WhileHeld(std::function<void()> toRun,
                          std::initializer_list<Subsystem*> requirements) {
+  WPI_IGNORE_DEPRECATED
   WhileActiveContinous(std::move(toRun), requirements);
+  WPI_UNIGNORE_DEPRECATED
   return *this;
 }
 
 Button Button::WhileHeld(std::function<void()> toRun,
-                         wpi::span<Subsystem* const> requirements) {
+                         std::span<Subsystem* const> requirements) {
+  WPI_IGNORE_DEPRECATED
   WhileActiveContinous(std::move(toRun), requirements);
+  WPI_UNIGNORE_DEPRECATED
   return *this;
 }
 
-Button Button::WhenHeld(Command* command, bool interruptible) {
-  WhileActiveOnce(command, interruptible);
+Button Button::WhenHeld(Command* command) {
+  WPI_IGNORE_DEPRECATED
+  WhileActiveOnce(command);
+  WPI_UNIGNORE_DEPRECATED
   return *this;
 }
 
-Button Button::WhenReleased(Command* command, bool interruptible) {
-  WhenInactive(command, interruptible);
+Button Button::WhenReleased(Command* command) {
+  WPI_IGNORE_DEPRECATED
+  WhenInactive(command);
+  WPI_UNIGNORE_DEPRECATED
   return *this;
 }
 
 Button Button::WhenReleased(std::function<void()> toRun,
                             std::initializer_list<Subsystem*> requirements) {
+  WPI_IGNORE_DEPRECATED
   WhenInactive(std::move(toRun), requirements);
+  WPI_UNIGNORE_DEPRECATED
   return *this;
 }
 
 Button Button::WhenReleased(std::function<void()> toRun,
-                            wpi::span<Subsystem* const> requirements) {
+                            std::span<Subsystem* const> requirements) {
+  WPI_IGNORE_DEPRECATED
   WhenInactive(std::move(toRun), requirements);
+  WPI_UNIGNORE_DEPRECATED
   return *this;
 }
 
-Button Button::ToggleWhenPressed(Command* command, bool interruptible) {
-  ToggleWhenActive(command, interruptible);
+Button Button::ToggleWhenPressed(Command* command) {
+  WPI_IGNORE_DEPRECATED
+  ToggleWhenActive(command);
+  WPI_UNIGNORE_DEPRECATED
   return *this;
 }
 
 Button Button::CancelWhenPressed(Command* command) {
+  WPI_IGNORE_DEPRECATED
   CancelWhenActive(command);
+  WPI_UNIGNORE_DEPRECATED
   return *this;
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/button/CommandGenericHID.cpp b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/button/CommandGenericHID.cpp
new file mode 100644
index 0000000..ea5696e
--- /dev/null
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/button/CommandGenericHID.cpp
@@ -0,0 +1,70 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc2/command/button/CommandGenericHID.h"
+
+using namespace frc2;
+
+Trigger CommandGenericHID::Button(int button, frc::EventLoop* loop) const {
+  return GenericHID::Button(button, loop).CastTo<Trigger>();
+}
+
+Trigger CommandGenericHID::POV(int angle, frc::EventLoop* loop) const {
+  return POV(0, angle, loop);
+}
+
+Trigger CommandGenericHID::POV(int pov, int angle, frc::EventLoop* loop) const {
+  return Trigger(loop,
+                 [this, pov, angle] { return this->GetPOV(pov) == angle; });
+}
+
+Trigger CommandGenericHID::POVUp(frc::EventLoop* loop) const {
+  return POV(0, loop);
+}
+
+Trigger CommandGenericHID::POVUpRight(frc::EventLoop* loop) const {
+  return POV(45, loop);
+}
+
+Trigger CommandGenericHID::POVRight(frc::EventLoop* loop) const {
+  return POV(90, loop);
+}
+
+Trigger CommandGenericHID::POVDownRight(frc::EventLoop* loop) const {
+  return POV(135, loop);
+}
+
+Trigger CommandGenericHID::POVDown(frc::EventLoop* loop) const {
+  return POV(180, loop);
+}
+
+Trigger CommandGenericHID::POVDownLeft(frc::EventLoop* loop) const {
+  return POV(225, loop);
+}
+
+Trigger CommandGenericHID::POVLeft(frc::EventLoop* loop) const {
+  return POV(270, loop);
+}
+
+Trigger CommandGenericHID::POVUpLeft(frc::EventLoop* loop) const {
+  return POV(315, loop);
+}
+
+Trigger CommandGenericHID::POVCenter(frc::EventLoop* loop) const {
+  return POV(360, loop);
+}
+
+Trigger CommandGenericHID::AxisLessThan(int axis, double threshold,
+                                        frc::EventLoop* loop) const {
+  return Trigger(loop, [this, axis, threshold]() {
+    return this->GetRawAxis(axis) < threshold;
+  });
+}
+
+Trigger CommandGenericHID::AxisGreaterThan(int axis, double threshold,
+                                           frc::EventLoop* loop) const {
+  return Trigger(loop, [this, axis, threshold]() {
+    return this->GetRawAxis(axis) > threshold;
+  });
+}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/button/CommandJoystick.cpp b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/button/CommandJoystick.cpp
new file mode 100644
index 0000000..9b8ec76
--- /dev/null
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/button/CommandJoystick.cpp
@@ -0,0 +1,19 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc2/command/button/CommandJoystick.h"
+
+using namespace frc2;
+
+Trigger CommandJoystick::Button(int button, frc::EventLoop* loop) const {
+  return GenericHID::Button(button, loop).CastTo<class Trigger>();
+}
+
+Trigger CommandJoystick::Trigger(frc::EventLoop* loop) const {
+  return Joystick::Trigger(loop).CastTo<class Trigger>();
+}
+
+Trigger CommandJoystick::Top(frc::EventLoop* loop) const {
+  return Joystick::Top(loop).CastTo<class Trigger>();
+}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/button/CommandPS4Controller.cpp b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/button/CommandPS4Controller.cpp
new file mode 100644
index 0000000..d04ab66
--- /dev/null
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/button/CommandPS4Controller.cpp
@@ -0,0 +1,63 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc2/command/button/CommandPS4Controller.h"
+
+using namespace frc2;
+
+Trigger CommandPS4Controller::Button(int button, frc::EventLoop* loop) const {
+  return GenericHID::Button(button, loop).CastTo<Trigger>();
+}
+
+Trigger CommandPS4Controller::Square(frc::EventLoop* loop) const {
+  return PS4Controller::Square(loop).CastTo<Trigger>();
+}
+
+Trigger CommandPS4Controller::Cross(frc::EventLoop* loop) const {
+  return PS4Controller::Cross(loop).CastTo<Trigger>();
+}
+
+Trigger CommandPS4Controller::Circle(frc::EventLoop* loop) const {
+  return PS4Controller::Circle(loop).CastTo<Trigger>();
+}
+
+Trigger CommandPS4Controller::Triangle(frc::EventLoop* loop) const {
+  return PS4Controller::Triangle(loop).CastTo<Trigger>();
+}
+
+Trigger CommandPS4Controller::L1(frc::EventLoop* loop) const {
+  return PS4Controller::L1(loop).CastTo<Trigger>();
+}
+
+Trigger CommandPS4Controller::R1(frc::EventLoop* loop) const {
+  return PS4Controller::R1(loop).CastTo<Trigger>();
+}
+
+Trigger CommandPS4Controller::L2(frc::EventLoop* loop) const {
+  return PS4Controller::L2(loop).CastTo<Trigger>();
+}
+
+Trigger CommandPS4Controller::R2(frc::EventLoop* loop) const {
+  return PS4Controller::R2(loop).CastTo<Trigger>();
+}
+
+Trigger CommandPS4Controller::Options(frc::EventLoop* loop) const {
+  return PS4Controller::Options(loop).CastTo<Trigger>();
+}
+
+Trigger CommandPS4Controller::L3(frc::EventLoop* loop) const {
+  return PS4Controller::L3(loop).CastTo<Trigger>();
+}
+
+Trigger CommandPS4Controller::R3(frc::EventLoop* loop) const {
+  return PS4Controller::R3(loop).CastTo<Trigger>();
+}
+
+Trigger CommandPS4Controller::PS(frc::EventLoop* loop) const {
+  return PS4Controller::PS(loop).CastTo<Trigger>();
+}
+
+Trigger CommandPS4Controller::Touchpad(frc::EventLoop* loop) const {
+  return PS4Controller::Touchpad(loop).CastTo<Trigger>();
+}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/button/CommandXboxController.cpp b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/button/CommandXboxController.cpp
new file mode 100644
index 0000000..8c4eba0
--- /dev/null
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/button/CommandXboxController.cpp
@@ -0,0 +1,61 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc2/command/button/CommandXboxController.h"
+
+using namespace frc2;
+
+Trigger CommandXboxController::Button(int button, frc::EventLoop* loop) const {
+  return GenericHID::Button(button, loop).CastTo<Trigger>();
+}
+
+Trigger CommandXboxController::LeftBumper(frc::EventLoop* loop) const {
+  return XboxController::LeftBumper(loop).CastTo<Trigger>();
+}
+
+Trigger CommandXboxController::RightBumper(frc::EventLoop* loop) const {
+  return XboxController::RightBumper(loop).CastTo<Trigger>();
+}
+
+Trigger CommandXboxController::LeftStick(frc::EventLoop* loop) const {
+  return XboxController::LeftStick(loop).CastTo<Trigger>();
+}
+
+Trigger CommandXboxController::RightStick(frc::EventLoop* loop) const {
+  return XboxController::RightStick(loop).CastTo<Trigger>();
+}
+
+Trigger CommandXboxController::A(frc::EventLoop* loop) const {
+  return XboxController::A(loop).CastTo<Trigger>();
+}
+
+Trigger CommandXboxController::B(frc::EventLoop* loop) const {
+  return XboxController::B(loop).CastTo<Trigger>();
+}
+
+Trigger CommandXboxController::X(frc::EventLoop* loop) const {
+  return XboxController::X(loop).CastTo<Trigger>();
+}
+
+Trigger CommandXboxController::Y(frc::EventLoop* loop) const {
+  return XboxController::Y(loop).CastTo<Trigger>();
+}
+
+Trigger CommandXboxController::Back(frc::EventLoop* loop) const {
+  return XboxController::Back(loop).CastTo<Trigger>();
+}
+
+Trigger CommandXboxController::Start(frc::EventLoop* loop) const {
+  return XboxController::Start(loop).CastTo<Trigger>();
+}
+
+Trigger CommandXboxController::LeftTrigger(double threshold,
+                                           frc::EventLoop* loop) const {
+  return XboxController::LeftTrigger(threshold, loop).CastTo<Trigger>();
+}
+
+Trigger CommandXboxController::RightTrigger(double threshold,
+                                            frc::EventLoop* loop) const {
+  return XboxController::RightTrigger(threshold, loop).CastTo<Trigger>();
+}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/button/NetworkButton.cpp b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/button/NetworkButton.cpp
index 3886c62..e26cd14 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/button/NetworkButton.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/button/NetworkButton.cpp
@@ -4,17 +4,27 @@
 
 #include "frc2/command/button/NetworkButton.h"
 
+#include <wpi/deprecated.h>
+
 using namespace frc2;
 
-NetworkButton::NetworkButton(nt::NetworkTableEntry entry)
-    : Button([entry] {
-        return entry.GetInstance().IsConnected() && entry.GetBoolean(false);
+WPI_IGNORE_DEPRECATED
+NetworkButton::NetworkButton(nt::BooleanTopic topic)
+    : NetworkButton(topic.Subscribe(false)) {}
+
+NetworkButton::NetworkButton(nt::BooleanSubscriber sub)
+    : Button([sub = std::make_shared<nt::BooleanSubscriber>(std::move(sub))] {
+        return sub->GetTopic().GetInstance().IsConnected() && sub->Get();
       }) {}
+WPI_UNIGNORE_DEPRECATED
 
 NetworkButton::NetworkButton(std::shared_ptr<nt::NetworkTable> table,
                              std::string_view field)
-    : NetworkButton(table->GetEntry(field)) {}
+    : NetworkButton(table->GetBooleanTopic(field)) {}
 
 NetworkButton::NetworkButton(std::string_view table, std::string_view field)
-    : NetworkButton(nt::NetworkTableInstance::GetDefault().GetTable(table),
-                    field) {}
+    : NetworkButton(nt::NetworkTableInstance::GetDefault(), table, field) {}
+
+NetworkButton::NetworkButton(nt::NetworkTableInstance inst,
+                             std::string_view table, std::string_view field)
+    : NetworkButton(inst.GetTable(table), field) {}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/button/Trigger.cpp b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/button/Trigger.cpp
index e370097..3908daf 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/button/Trigger.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/cpp/frc2/command/button/Trigger.cpp
@@ -8,25 +8,208 @@
 
 #include "frc2/command/InstantCommand.h"
 
+using namespace frc;
 using namespace frc2;
 
 Trigger::Trigger(const Trigger& other) = default;
 
-Trigger Trigger::WhenActive(Command* command, bool interruptible) {
-  CommandScheduler::GetInstance().AddButton(
-      [pressedLast = m_isActive(), *this, command, interruptible]() mutable {
-        bool pressed = m_isActive();
+Trigger Trigger::OnTrue(Command* command) {
+  m_loop->Bind(
+      [condition = m_condition, previous = m_condition(), command]() mutable {
+        bool current = condition();
 
-        if (!pressedLast && pressed) {
-          command->Schedule(interruptible);
+        if (!previous && current) {
+          command->Schedule();
         }
 
-        pressedLast = pressed;
+        previous = current;
       });
-
   return *this;
 }
 
+Trigger Trigger::OnTrue(CommandPtr&& command) {
+  m_loop->Bind([condition = m_condition, previous = m_condition(),
+                command = std::move(command)]() mutable {
+    bool current = condition();
+
+    if (!previous && current) {
+      command.Schedule();
+    }
+
+    previous = current;
+  });
+  return *this;
+}
+
+Trigger Trigger::OnFalse(Command* command) {
+  m_loop->Bind(
+      [condition = m_condition, previous = m_condition(), command]() mutable {
+        bool current = condition();
+
+        if (previous && !current) {
+          command->Schedule();
+        }
+
+        previous = current;
+      });
+  return *this;
+}
+
+Trigger Trigger::OnFalse(CommandPtr&& command) {
+  m_loop->Bind([condition = m_condition, previous = m_condition(),
+                command = std::move(command)]() mutable {
+    bool current = condition();
+
+    if (previous && !current) {
+      command.Schedule();
+    }
+
+    previous = current;
+  });
+  return *this;
+}
+
+Trigger Trigger::WhileTrue(Command* command) {
+  m_loop->Bind(
+      [condition = m_condition, previous = m_condition(), command]() mutable {
+        bool current = condition();
+
+        if (!previous && current) {
+          command->Schedule();
+        } else if (previous && !current) {
+          command->Cancel();
+        }
+
+        previous = current;
+      });
+  return *this;
+}
+
+Trigger Trigger::WhileTrue(CommandPtr&& command) {
+  m_loop->Bind([condition = m_condition, previous = m_condition(),
+                command = std::move(command)]() mutable {
+    bool current = condition();
+
+    if (!previous && current) {
+      command.Schedule();
+    } else if (previous && !current) {
+      command.Cancel();
+    }
+
+    previous = current;
+  });
+  return *this;
+}
+
+Trigger Trigger::WhileFalse(Command* command) {
+  m_loop->Bind(
+      [condition = m_condition, previous = m_condition(), command]() mutable {
+        bool current = condition();
+
+        if (previous && !current) {
+          command->Schedule();
+        } else if (!previous && current) {
+          command->Cancel();
+        }
+
+        previous = current;
+      });
+  return *this;
+}
+
+Trigger Trigger::WhileFalse(CommandPtr&& command) {
+  m_loop->Bind([condition = m_condition, previous = m_condition(),
+                command = std::move(command)]() mutable {
+    bool current = condition();
+
+    if (!previous && current) {
+      command.Schedule();
+    } else if (previous && !current) {
+      command.Cancel();
+    }
+
+    previous = current;
+  });
+  return *this;
+}
+
+Trigger Trigger::ToggleOnTrue(Command* command) {
+  m_loop->Bind([condition = m_condition, previous = m_condition(),
+                command = command]() mutable {
+    bool current = condition();
+
+    if (!previous && current) {
+      if (command->IsScheduled()) {
+        command->Cancel();
+      } else {
+        command->Schedule();
+      }
+    }
+
+    previous = current;
+  });
+  return *this;
+}
+
+Trigger Trigger::ToggleOnTrue(CommandPtr&& command) {
+  m_loop->Bind([condition = m_condition, previous = m_condition(),
+                command = std::move(command)]() mutable {
+    bool current = condition();
+
+    if (!previous && current) {
+      if (command.IsScheduled()) {
+        command.Cancel();
+      } else {
+        command.Schedule();
+      }
+    }
+
+    previous = current;
+  });
+  return *this;
+}
+
+Trigger Trigger::ToggleOnFalse(Command* command) {
+  m_loop->Bind([condition = m_condition, previous = m_condition(),
+                command = command]() mutable {
+    bool current = condition();
+
+    if (previous && !current) {
+      if (command->IsScheduled()) {
+        command->Cancel();
+      } else {
+        command->Schedule();
+      }
+    }
+
+    previous = current;
+  });
+  return *this;
+}
+
+Trigger Trigger::ToggleOnFalse(CommandPtr&& command) {
+  m_loop->Bind([condition = m_condition, previous = m_condition(),
+                command = std::move(command)]() mutable {
+    bool current = condition();
+
+    if (previous && !current) {
+      if (command.IsScheduled()) {
+        command.Cancel();
+      } else {
+        command.Schedule();
+      }
+    }
+
+    previous = current;
+  });
+  return *this;
+}
+
+WPI_IGNORE_DEPRECATED
+Trigger Trigger::WhenActive(Command* command) {
+  return OnTrue(command);
+}
+
 Trigger Trigger::WhenActive(std::function<void()> toRun,
                             std::initializer_list<Subsystem*> requirements) {
   return WhenActive(std::move(toRun),
@@ -34,23 +217,23 @@
 }
 
 Trigger Trigger::WhenActive(std::function<void()> toRun,
-                            wpi::span<Subsystem* const> requirements) {
+                            std::span<Subsystem* const> requirements) {
   return WhenActive(InstantCommand(std::move(toRun), requirements));
 }
 
-Trigger Trigger::WhileActiveContinous(Command* command, bool interruptible) {
-  CommandScheduler::GetInstance().AddButton(
-      [pressedLast = m_isActive(), *this, command, interruptible]() mutable {
-        bool pressed = m_isActive();
+Trigger Trigger::WhileActiveContinous(Command* command) {
+  m_loop->Bind([condition = m_condition, previous = m_condition(),
+                command = std::move(command)]() mutable {
+    bool current = condition();
 
-        if (pressed) {
-          command->Schedule(interruptible);
-        } else if (pressedLast && !pressed) {
-          command->Cancel();
-        }
+    if (current) {
+      command->Schedule();
+    } else if (previous && !current) {
+      command->Cancel();
+    }
 
-        pressedLast = pressed;
-      });
+    previous = current;
+  });
   return *this;
 }
 
@@ -62,36 +245,36 @@
 }
 
 Trigger Trigger::WhileActiveContinous(
-    std::function<void()> toRun, wpi::span<Subsystem* const> requirements) {
+    std::function<void()> toRun, std::span<Subsystem* const> requirements) {
   return WhileActiveContinous(InstantCommand(std::move(toRun), requirements));
 }
 
-Trigger Trigger::WhileActiveOnce(Command* command, bool interruptible) {
-  CommandScheduler::GetInstance().AddButton(
-      [pressedLast = m_isActive(), *this, command, interruptible]() mutable {
-        bool pressed = m_isActive();
+Trigger Trigger::WhileActiveOnce(Command* command) {
+  m_loop->Bind(
+      [condition = m_condition, previous = m_condition(), command]() mutable {
+        bool current = condition();
 
-        if (!pressedLast && pressed) {
-          command->Schedule(interruptible);
-        } else if (pressedLast && !pressed) {
+        if (!previous && current) {
+          command->Schedule();
+        } else if (previous && !current) {
           command->Cancel();
         }
 
-        pressedLast = pressed;
+        previous = current;
       });
   return *this;
 }
 
-Trigger Trigger::WhenInactive(Command* command, bool interruptible) {
-  CommandScheduler::GetInstance().AddButton(
-      [pressedLast = m_isActive(), *this, command, interruptible]() mutable {
-        bool pressed = m_isActive();
+Trigger Trigger::WhenInactive(Command* command) {
+  m_loop->Bind(
+      [condition = m_condition, previous = m_condition(), command]() mutable {
+        bool current = condition();
 
-        if (pressedLast && !pressed) {
-          command->Schedule(interruptible);
+        if (previous && !current) {
+          command->Schedule();
         }
 
-        pressedLast = pressed;
+        previous = current;
       });
   return *this;
 }
@@ -103,46 +286,47 @@
 }
 
 Trigger Trigger::WhenInactive(std::function<void()> toRun,
-                              wpi::span<Subsystem* const> requirements) {
+                              std::span<Subsystem* const> requirements) {
   return WhenInactive(InstantCommand(std::move(toRun), requirements));
 }
 
-Trigger Trigger::ToggleWhenActive(Command* command, bool interruptible) {
-  CommandScheduler::GetInstance().AddButton(
-      [pressedLast = m_isActive(), *this, command, interruptible]() mutable {
-        bool pressed = m_isActive();
+Trigger Trigger::ToggleWhenActive(Command* command) {
+  m_loop->Bind([condition = m_condition, previous = m_condition(),
+                command = command]() mutable {
+    bool current = condition();
 
-        if (!pressedLast && pressed) {
-          if (command->IsScheduled()) {
-            command->Cancel();
-          } else {
-            command->Schedule(interruptible);
-          }
-        }
+    if (!previous && current) {
+      if (command->IsScheduled()) {
+        command->Cancel();
+      } else {
+        command->Schedule();
+      }
+    }
 
-        pressedLast = pressed;
-      });
+    previous = current;
+  });
   return *this;
 }
 
 Trigger Trigger::CancelWhenActive(Command* command) {
-  CommandScheduler::GetInstance().AddButton(
-      [pressedLast = m_isActive(), *this, command]() mutable {
-        bool pressed = m_isActive();
+  m_loop->Bind([condition = m_condition, previous = m_condition(),
+                command = std::move(command)]() mutable {
+    bool current = condition();
 
-        if (!pressedLast && pressed) {
-          command->Cancel();
-        }
+    if (!previous && current) {
+      command->Cancel();
+    }
 
-        pressedLast = pressed;
-      });
+    previous = current;
+  });
   return *this;
 }
+WPI_UNIGNORE_DEPRECATED
 
 Trigger Trigger::Debounce(units::second_t debounceTime,
                           frc::Debouncer::DebounceType type) {
-  return Trigger(
-      [debouncer = frc::Debouncer(debounceTime, type), *this]() mutable {
-        return debouncer.Calculate(m_isActive());
-      });
+  return Trigger(m_loop, [debouncer = frc::Debouncer(debounceTime, type),
+                          condition = m_condition]() mutable {
+    return debouncer.Calculate(condition());
+  });
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/Command.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/Command.h
index f8da728..189433b 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/Command.h
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/Command.h
@@ -7,12 +7,13 @@
 #include <functional>
 #include <initializer_list>
 #include <memory>
+#include <span>
 #include <string>
 
 #include <units/time.h>
 #include <wpi/Demangle.h>
 #include <wpi/SmallSet.h>
-#include <wpi/span.h>
+#include <wpi/deprecated.h>
 
 #include "frc2/command/Subsystem.h"
 
@@ -23,12 +24,7 @@
   return wpi::Demangle(typeid(type).name());
 }
 
-class ParallelCommandGroup;
-class ParallelRaceGroup;
-class ParallelDeadlineGroup;
-class SequentialCommandGroup;
 class PerpetualCommand;
-class ProxyScheduleCommand;
 
 /**
  * A state machine representing a complete action to be performed by the robot.
@@ -36,8 +32,9 @@
  * CommandGroups to allow users to build complicated multi-step actions without
  * the need to roll the state machine logic themselves.
  *
- * <p>Commands are run synchronously from the main robot loop; no multithreading
- * is used, unless specified explicitly from the command implementation.
+ * <p>Commands are run synchronously from the main robot loop; no
+ * multithreading is used, unless specified explicitly from the command
+ * implementation.
  *
  * <p>Note: ALWAYS create a subclass by extending CommandHelper<Base, Subclass>,
  * or decorators will not function!
@@ -86,21 +83,39 @@
   virtual bool IsFinished() { return false; }
 
   /**
-   * Specifies the set of subsystems used by this command.  Two commands cannot
-   * use the same subsystem at the same time.  If the command is scheduled as
-   * interruptible and another command is scheduled that shares a requirement,
-   * the command will be interrupted.  Else, the command will not be scheduled.
-   * If no subsystems are required, return an empty set.
+   * Specifies the set of subsystems used by this command. Two commands cannot
+   * use the same subsystem at the same time. If another command is scheduled
+   * that shares a requirement, GetInterruptionBehavior() will be checked and
+   * followed. If no subsystems are required, return an empty set.
    *
    * <p>Note: it is recommended that user implementations contain the
    * requirements as a field, and return that field here, rather than allocating
    * a new set every time this is called.
    *
    * @return the set of subsystems that are required
+   * @see InterruptionBehavior
    */
   virtual wpi::SmallSet<Subsystem*, 4> GetRequirements() const = 0;
 
   /**
+   * An enum describing the command's behavior when another command with a
+   * shared requirement is scheduled.
+   */
+  enum class InterruptionBehavior {
+    /**
+     * This command ends, End(true) is called, and the incoming command is
+     * scheduled normally.
+     *
+     * <p>This is the default behavior.
+     */
+    kCancelSelf,
+    /** This command continues, and the incoming command is not scheduled. */
+    kCancelIncoming
+  };
+
+  friend class CommandPtr;
+
+  /**
    * Decorates this command with a timeout.  If the specified timeout is
    * exceeded before the command finishes normally, the command will be
    * interrupted and un-scheduled.  Note that the timeout only applies to the
@@ -109,7 +124,7 @@
    * @param duration the timeout duration
    * @return the command with the timeout added
    */
-  virtual ParallelRaceGroup WithTimeout(units::second_t duration) &&;
+  [[nodiscard]] CommandPtr WithTimeout(units::second_t duration) &&;
 
   /**
    * Decorates this command with an interrupt condition.  If the specified
@@ -120,7 +135,7 @@
    * @param condition the interrupt condition
    * @return the command with the interrupt condition added
    */
-  virtual ParallelRaceGroup Until(std::function<bool()> condition) &&;
+  [[nodiscard]] CommandPtr Until(std::function<bool()> condition) &&;
 
   /**
    * Decorates this command with an interrupt condition.  If the specified
@@ -130,8 +145,10 @@
    *
    * @param condition the interrupt condition
    * @return the command with the interrupt condition added
+   * @deprecated Replace with Until()
    */
-  virtual ParallelRaceGroup WithInterrupt(std::function<bool()> condition) &&;
+  WPI_DEPRECATED("Replace with Until()")
+  [[nodiscard]] CommandPtr WithInterrupt(std::function<bool()> condition) &&;
 
   /**
    * Decorates this command with a runnable to run before this command starts.
@@ -140,7 +157,7 @@
    * @param requirements the required subsystems
    * @return the decorated command
    */
-  virtual SequentialCommandGroup BeforeStarting(
+  [[nodiscard]] CommandPtr BeforeStarting(
       std::function<void()> toRun,
       std::initializer_list<Subsystem*> requirements) &&;
 
@@ -151,9 +168,9 @@
    * @param requirements the required subsystems
    * @return the decorated command
    */
-  virtual SequentialCommandGroup BeforeStarting(
+  [[nodiscard]] CommandPtr BeforeStarting(
       std::function<void()> toRun,
-      wpi::span<Subsystem* const> requirements = {}) &&;
+      std::span<Subsystem* const> requirements = {}) &&;
 
   /**
    * Decorates this command with a runnable to run after the command finishes.
@@ -162,7 +179,7 @@
    * @param requirements the required subsystems
    * @return the decorated command
    */
-  virtual SequentialCommandGroup AndThen(
+  [[nodiscard]] CommandPtr AndThen(
       std::function<void()> toRun,
       std::initializer_list<Subsystem*> requirements) &&;
 
@@ -173,51 +190,120 @@
    * @param requirements the required subsystems
    * @return the decorated command
    */
-  virtual SequentialCommandGroup AndThen(
+  [[nodiscard]] CommandPtr AndThen(
       std::function<void()> toRun,
-      wpi::span<Subsystem* const> requirements = {}) &&;
+      std::span<Subsystem* const> requirements = {}) &&;
 
   /**
    * Decorates this command to run perpetually, ignoring its ordinary end
    * conditions.  The decorated command can still be interrupted or canceled.
    *
    * @return the decorated command
+   * @deprecated PerpetualCommand violates the assumption that execute() doesn't
+get called after isFinished() returns true -- an assumption that should be
+valid. This was unsafe/undefined behavior from the start, and RepeatCommand
+provides an easy way to achieve similar end results with slightly different (and
+safe) semantics.
    */
-  virtual PerpetualCommand Perpetually() &&;
+  WPI_DEPRECATED(
+      "PerpetualCommand violates the assumption that execute() doesn't get "
+      "called after isFinished() returns true -- an assumption that should be "
+      "valid."
+      "This was unsafe/undefined behavior from the start, and RepeatCommand "
+      "provides an easy way to achieve similar end results with slightly "
+      "different (and safe) semantics.")
+  PerpetualCommand Perpetually() &&;
 
   /**
-   * Decorates this command to run "by proxy" by wrapping it in a
-   * ProxyScheduleCommand. This is useful for "forking off" from command groups
-   * when the user does not wish to extend the command's requirements to the
-   * entire command group.
+   * Decorates this command to run repeatedly, restarting it when it ends, until
+   * this command is interrupted. The decorated command can still be canceled.
    *
    * @return the decorated command
    */
-  virtual ProxyScheduleCommand AsProxy();
+  [[nodiscard]] CommandPtr Repeatedly() &&;
+
+  /**
+   * Decorates this command to run "by proxy" by wrapping it in a
+   * ProxyCommand. This is useful for "forking off" from command groups
+   * when the user does not wish to extend the command's requirements to the
+   * entire command group.
+   *
+   * <p>This overload transfers command ownership to the returned CommandPtr.
+   *
+   * @return the decorated command
+   */
+  [[nodiscard]] CommandPtr AsProxy() &&;
+
+  /**
+   * Decorates this command to only run if this condition is not met. If the
+   * command is already running and the condition changes to true, the command
+   * will not stop running. The requirements of this command will be kept for
+   * the new conditional command.
+   *
+   * @param condition the condition that will prevent the command from running
+   * @return the decorated command
+   */
+  [[nodiscard]] CommandPtr Unless(std::function<bool()> condition) &&;
+
+  /**
+   * Decorates this command to run or stop when disabled.
+   *
+   * @param doesRunWhenDisabled true to run when disabled.
+   * @return the decorated command
+   */
+  [[nodiscard]] CommandPtr IgnoringDisable(bool doesRunWhenDisabled) &&;
+
+  /**
+   * Decorates this command to run or stop when disabled.
+   *
+   * @param interruptBehavior true to run when disabled.
+   * @return the decorated command
+   */
+  [[nodiscard]] CommandPtr WithInterruptBehavior(
+      Command::InterruptionBehavior interruptBehavior) &&;
+
+  /**
+   * Decorates this command with a lambda to call on interrupt or end, following
+   * the command's inherent Command::End(bool) method.
+   *
+   * @param end a lambda accepting a boolean parameter specifying whether the
+   * command was interrupted.
+   * @return the decorated command
+   */
+  [[nodiscard]] CommandPtr FinallyDo(std::function<void(bool)> end) &&;
+
+  /**
+   * Decorates this command with a lambda to call on interrupt, following the
+   * command's inherent Command::End(bool) method.
+   *
+   * @param handler a lambda to run when the command is interrupted
+   * @return the decorated command
+   */
+  [[nodiscard]] CommandPtr HandleInterrupt(std::function<void()> handler) &&;
+
+  /**
+   * Decorates this Command with a name.
+   *
+   * @param name name
+   * @return the decorated Command
+   */
+  [[nodiscard]] CommandPtr WithName(std::string_view name) &&;
 
   /**
    * Schedules this command.
-   *
-   * @param interruptible whether this command can be interrupted by another
-   * command that shares one of its requirements
    */
-  void Schedule(bool interruptible);
+  void Schedule();
 
   /**
-   * Schedules this command, defaulting to interruptible.
-   */
-  void Schedule() { Schedule(true); }
-
-  /**
-   * Cancels this command.  Will call the command's interrupted() method.
-   * Commands will be canceled even if they are not marked as interruptible.
+   * Cancels this command. Will call End(true). Commands will be canceled
+   * regardless of interruption behavior.
    */
   void Cancel();
 
   /**
-   * Whether or not the command is currently scheduled.  Note that this does not
-   * detect whether the command is being run by a CommandGroup, only whether it
-   * is directly being run by the scheduler.
+   * Whether or not the command is currently scheduled. Note that this does not
+   * detect whether the command is in a composition, only whether it is directly
+   * being run by the scheduler.
    *
    * @return Whether the command is scheduled.
    */
@@ -237,13 +323,32 @@
    * Whether the command is currently grouped in a command group.  Used as extra
    * insurance to prevent accidental independent use of grouped commands.
    */
+  bool IsComposed() const;
+
+  /**
+   * Sets whether the command is currently composed in a command composition.
+   * Can be used to "reclaim" a command if a composition is no longer going to
+   * use it.  NOT ADVISED!
+   */
+  void SetComposed(bool isComposed);
+
+  /**
+   * Whether the command is currently grouped in a command group.  Used as extra
+   * insurance to prevent accidental independent use of grouped commands.
+   *
+   * @deprecated Moved to IsComposed()
+   */
+  WPI_DEPRECATED("Moved to IsComposed()")
   bool IsGrouped() const;
 
   /**
    * Sets whether the command is currently grouped in a command group.  Can be
    * used to "reclaim" a command if a group is no longer going to use it.  NOT
    * ADVISED!
+   *
+   * @deprecated Moved to SetComposed()
    */
+  WPI_DEPRECATED("Moved to SetComposed()")
   void SetGrouped(bool grouped);
 
   /**
@@ -254,8 +359,37 @@
    */
   virtual bool RunsWhenDisabled() const { return false; }
 
+  /**
+   * How the command behaves when another command with a shared requirement is
+   * scheduled.
+   *
+   * @return a variant of InterruptionBehavior, defaulting to kCancelSelf.
+   */
+  virtual InterruptionBehavior GetInterruptionBehavior() const {
+    return InterruptionBehavior::kCancelSelf;
+  }
+
+  /**
+   * Gets the name of this Command. Defaults to the simple class name if not
+   * overridden.
+   *
+   * @return The display name of the Command
+   */
   virtual std::string GetName() const;
 
+  /**
+   * Sets the name of this Command. Nullop if not overridden.
+   *
+   * @param name The display name of the Command.
+   */
+  virtual void SetName(std::string_view name);
+
+  /**
+   * Transfers ownership of this command to a unique pointer.  Used for
+   * decorator methods.
+   */
+  virtual CommandPtr ToPtr() && = 0;
+
  protected:
   /**
    * Transfers ownership of this command to a unique pointer.  Used for
@@ -263,7 +397,7 @@
    */
   virtual std::unique_ptr<Command> TransferOwnership() && = 0;
 
-  bool m_isGrouped = false;
+  bool m_isComposed = false;
 };
 
 /**
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/CommandBase.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/CommandBase.h
index 9050a12..64bd88b 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/CommandBase.h
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/CommandBase.h
@@ -5,13 +5,13 @@
 #pragma once
 
 #include <initializer_list>
+#include <span>
 #include <string>
 #include <string_view>
 
 #include <wpi/SmallSet.h>
 #include <wpi/sendable/Sendable.h>
 #include <wpi/sendable/SendableHelper.h>
-#include <wpi/span.h>
 
 #include "frc2/command/Command.h"
 
@@ -37,7 +37,7 @@
    *
    * @param requirements the Subsystem requirements to add
    */
-  void AddRequirements(wpi::span<Subsystem* const> requirements);
+  void AddRequirements(std::span<Subsystem* const> requirements);
 
   /**
    * Adds the specified Subsystem requirements to the command.
@@ -65,7 +65,7 @@
    *
    * @param name name
    */
-  void SetName(std::string_view name);
+  void SetName(std::string_view name) override;
 
   /**
    * Gets the name of this Command.
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/CommandGroupBase.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/CommandGroupBase.h
index d7ae447..9fe65fa 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/CommandGroupBase.h
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/CommandGroupBase.h
@@ -4,63 +4,25 @@
 
 #pragma once
 
-#include <initializer_list>
 #include <memory>
 #include <vector>
 
-#include <wpi/span.h>
+#include <wpi/deprecated.h>
 
 #include "frc2/command/CommandBase.h"
 
 namespace frc2 {
 
 /**
- * A base for CommandGroups.  Statically tracks commands that have been
- * allocated to groups to ensure those commands are not also used independently,
- * which can result in inconsistent command state and unpredictable execution.
+ * A base for CommandGroups.
  *
  * This class is provided by the NewCommands VendorDep
+ * @deprecated This class is an empty abstraction. Inherit directly from
+ * CommandBase.
  */
 class CommandGroupBase : public CommandBase {
  public:
   /**
-   * Requires that the specified command not have been already allocated to a
-   * CommandGroup. Reports an error if the command is already grouped.
-   *
-   * @param command The command to check
-   * @return True if all the command is ungrouped.
-   */
-  static bool RequireUngrouped(const Command& command);
-
-  /**
-   * Requires that the specified command not have been already allocated to a
-   * CommandGroup. Reports an error if the command is already grouped.
-   *
-   * @param command The command to check
-   * @return True if all the command is ungrouped.
-   */
-  static bool RequireUngrouped(const Command* command);
-
-  /**
-   * Requires that the specified commands not have been already allocated to a
-   * CommandGroup. Reports an error if any of the commands are already grouped.
-   *
-   * @param commands The commands to check
-   * @return True if all the commands are ungrouped.
-   */
-  static bool RequireUngrouped(
-      wpi::span<const std::unique_ptr<Command>> commands);
-
-  /**
-   * Requires that the specified commands not have been already allocated to a
-   * CommandGroup. Reports an error if any of the commands are already grouped.
-   *
-   * @param commands The commands to check
-   * @return True if all the commands are ungrouped.
-   */
-  static bool RequireUngrouped(std::initializer_list<const Command*> commands);
-
-  /**
    * Adds the given commands to the command group.
    *
    * @param commands The commands to add.
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/CommandHelper.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/CommandHelper.h
index 3c5fd7b..76ee6cd 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/CommandHelper.h
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/CommandHelper.h
@@ -9,6 +9,7 @@
 #include <utility>
 
 #include "frc2/command/Command.h"
+#include "frc2/command/CommandPtr.h"
 
 namespace frc2 {
 
@@ -28,6 +29,11 @@
  public:
   CommandHelper() = default;
 
+  CommandPtr ToPtr() && override {
+    return CommandPtr(
+        std::make_unique<CRTP>(std::move(*static_cast<CRTP*>(this))));
+  }
+
  protected:
   std::unique_ptr<Command> TransferOwnership() && override {
     return std::make_unique<CRTP>(std::move(*static_cast<CRTP*>(this)));
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/CommandPtr.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/CommandPtr.h
new file mode 100644
index 0000000..0ab1e97
--- /dev/null
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/CommandPtr.h
@@ -0,0 +1,288 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <functional>
+#include <initializer_list>
+#include <memory>
+#include <span>
+#include <string>
+#include <utility>
+#include <vector>
+
+#include "frc2/command/CommandBase.h"
+
+namespace frc2 {
+/**
+ * A wrapper around std::unique_ptr<Command> so commands have move-only
+ * semantics. Commands should only be stored and passed around when held in a
+ * CommandPtr instance. For more info, see
+ * https://github.com/wpilibsuite/allwpilib/issues/4303.
+ *
+ * Various classes in the command-based library accept a
+ * std::unique_ptr<Command>, use CommandPtr::Unwrap to convert.
+ * CommandPtr::UnwrapVector does the same for vectors.
+ */
+class CommandPtr final {
+ public:
+  explicit CommandPtr(std::unique_ptr<CommandBase>&& command)
+      : m_ptr(std::move(command)) {}
+
+  template <class T, typename = std::enable_if_t<std::is_base_of_v<
+                         Command, std::remove_reference_t<T>>>>
+  explicit CommandPtr(T&& command)
+      : CommandPtr(std::make_unique<std::remove_reference_t<T>>(
+            std::forward<T>(command))) {}
+
+  CommandPtr(CommandPtr&&) = default;
+  CommandPtr& operator=(CommandPtr&&) = default;
+
+  /**
+   * Decorates this command to run repeatedly, restarting it when it ends, until
+   * this command is interrupted. The decorated command can still be canceled.
+   *
+   * @return the decorated command
+   */
+  [[nodiscard]] CommandPtr Repeatedly() &&;
+
+  /**
+   * Decorates this command to run "by proxy" by wrapping it in a
+   * ProxyCommand. This is useful for "forking off" from command groups
+   * when the user does not wish to extend the command's requirements to the
+   * entire command group.
+   *
+   * @return the decorated command
+   */
+  [[nodiscard]] CommandPtr AsProxy() &&;
+
+  /**
+   * Decorates this command to run or stop when disabled.
+   *
+   * @param doesRunWhenDisabled true to run when disabled.
+   * @return the decorated command
+   */
+  [[nodiscard]] CommandPtr IgnoringDisable(bool doesRunWhenDisabled) &&;
+
+  /**
+   * Decorates this command to run or stop when disabled.
+   *
+   * @param interruptBehavior true to run when disabled.
+   * @return the decorated command
+   */
+  [[nodiscard]] CommandPtr WithInterruptBehavior(
+      Command::InterruptionBehavior interruptBehavior) &&;
+
+  /**
+   * Decorates this command with a runnable to run after the command finishes.
+   *
+   * @param toRun the Runnable to run
+   * @param requirements the required subsystems
+   * @return the decorated command
+   */
+  [[nodiscard]] CommandPtr AndThen(
+      std::function<void()> toRun,
+      std::span<Subsystem* const> requirements = {}) &&;
+
+  /**
+   * Decorates this command with a runnable to run after the command finishes.
+   *
+   * @param toRun the Runnable to run
+   * @param requirements the required subsystems
+   * @return the decorated command
+   */
+  [[nodiscard]] CommandPtr AndThen(
+      std::function<void()> toRun,
+      std::initializer_list<Subsystem*> requirements) &&;
+
+  /**
+   * Decorates this command with a set of commands to run after it in sequence.
+   * Often more convenient/less-verbose than constructing a new {@link
+   * SequentialCommandGroup} explicitly.
+   *
+   * @param next the commands to run next
+   * @return the decorated command
+   */
+  [[nodiscard]] CommandPtr AndThen(CommandPtr&& next) &&;
+
+  /**
+   * Decorates this command with a runnable to run before this command starts.
+   *
+   * @param toRun the Runnable to run
+   * @param requirements the required subsystems
+   * @return the decorated command
+   */
+  [[nodiscard]] CommandPtr BeforeStarting(
+      std::function<void()> toRun,
+      std::initializer_list<Subsystem*> requirements) &&;
+
+  /**
+   * Decorates this command with a runnable to run before this command starts.
+   *
+   * @param toRun the Runnable to run
+   * @param requirements the required subsystems
+   * @return the decorated command
+   */
+  [[nodiscard]] CommandPtr BeforeStarting(
+      std::function<void()> toRun,
+      std::span<Subsystem* const> requirements = {}) &&;
+
+  /**
+   * Decorates this command with another command to run before this command
+   * starts.
+   *
+   * @param before the command to run before this one
+   * @return the decorated command
+   */
+  [[nodiscard]] CommandPtr BeforeStarting(CommandPtr&& before) &&;
+
+  /**
+   * Decorates this command with a timeout.  If the specified timeout is
+   * exceeded before the command finishes normally, the command will be
+   * interrupted and un-scheduled.  Note that the timeout only applies to the
+   * command returned by this method; the calling command is not itself changed.
+   *
+   * @param duration the timeout duration
+   * @return the command with the timeout added
+   */
+  [[nodiscard]] CommandPtr WithTimeout(units::second_t duration) &&;
+
+  /**
+   * Decorates this command with an interrupt condition.  If the specified
+   * condition becomes true before the command finishes normally, the command
+   * will be interrupted and un-scheduled. Note that this only applies to the
+   * command returned by this method; the calling command is not itself changed.
+   *
+   * @param condition the interrupt condition
+   * @return the command with the interrupt condition added
+   */
+  [[nodiscard]] CommandPtr Until(std::function<bool()> condition) &&;
+
+  /**
+   * Decorates this command to only run if this condition is not met. If the
+   * command is already running and the condition changes to true, the command
+   * will not stop running. The requirements of this command will be kept for
+   * the new conditional command.
+   *
+   * @param condition the condition that will prevent the command from running
+   * @return the decorated command
+   */
+  [[nodiscard]] CommandPtr Unless(std::function<bool()> condition) &&;
+
+  /**
+   * Decorates this command with a set of commands to run parallel to it, ending
+   * when the calling command ends and interrupting all the others. Often more
+   * convenient/less-verbose than constructing a new {@link
+   * ParallelDeadlineGroup} explicitly.
+   *
+   * @param parallel the commands to run in parallel
+   * @return the decorated command
+   */
+  [[nodiscard]] CommandPtr DeadlineWith(CommandPtr&& parallel) &&;
+
+  /**
+   * Decorates this command with a set of commands to run parallel to it, ending
+   * when the last command ends. Often more convenient/less-verbose than
+   * constructing a new {@link ParallelCommandGroup} explicitly.
+   *
+   * @param parallel the commands to run in parallel
+   * @return the decorated command
+   */
+  [[nodiscard]] CommandPtr AlongWith(CommandPtr&& parallel) &&;
+
+  /**
+   * Decorates this command with a set of commands to run parallel to it, ending
+   * when the first command ends. Often more convenient/less-verbose than
+   * constructing a new {@link ParallelRaceGroup} explicitly.
+   *
+   * @param parallel the commands to run in parallel
+   * @return the decorated command
+   */
+  [[nodiscard]] CommandPtr RaceWith(CommandPtr&& parallel) &&;
+
+  /**
+   * Decorates this command with a lambda to call on interrupt or end, following
+   * the command's inherent Command::End(bool) method.
+   *
+   * @param end a lambda accepting a boolean parameter specifying whether the
+   * command was interrupted.
+   * @return the decorated command
+   */
+  [[nodiscard]] CommandPtr FinallyDo(std::function<void(bool)> end) &&;
+
+  /**
+   * Decorates this command with a lambda to call on interrupt, following the
+   * command's inherent Command::End(bool) method.
+   *
+   * @param handler a lambda to run when the command is interrupted
+   * @return the decorated command
+   */
+  [[nodiscard]] CommandPtr HandleInterrupt(std::function<void()> handler) &&;
+
+  /**
+   * Decorates this Command with a name. Is an inline function for
+   * Command::SetName(std::string_view);
+   *
+   * @param name name
+   * @return the decorated Command
+   */
+  [[nodiscard]] CommandPtr WithName(std::string_view name) &&;
+
+  /**
+   * Get a raw pointer to the held command.
+   */
+  CommandBase* get() const;
+
+  /**
+   * Convert to the underlying unique_ptr.
+   */
+  std::unique_ptr<CommandBase> Unwrap() &&;
+
+  /**
+   * Schedules this command.
+   */
+  void Schedule() const;
+
+  /**
+   * Cancels this command. Will call End(true). Commands will be canceled
+   * regardless of interruption behavior.
+   */
+  void Cancel() const;
+
+  /**
+   * Whether or not the command is currently scheduled. Note that this does not
+   * detect whether the command is in a composition, only whether it is directly
+   * being run by the scheduler.
+   *
+   * @return Whether the command is scheduled.
+   */
+  bool IsScheduled() const;
+
+  /**
+   * Whether the command requires a given subsystem.  Named "HasRequirement"
+   * rather than "requires" to avoid confusion with Command::Requires(Subsystem)
+   * -- this may be able to be changed in a few years.
+   *
+   * @param requirement the subsystem to inquire about
+   * @return whether the subsystem is required
+   */
+  bool HasRequirement(Subsystem* requirement) const;
+
+  /**
+   * Check if this CommandPtr object is valid and wasn't moved-from.
+   */
+  explicit operator bool() const;
+
+  /**
+   * Convert a vector of CommandPtr objects to their underlying unique_ptrs.
+   */
+  static std::vector<std::unique_ptr<Command>> UnwrapVector(
+      std::vector<CommandPtr>&& vec);
+
+ private:
+  std::unique_ptr<CommandBase> m_ptr;
+  void AssertValid() const;
+};
+
+}  // namespace frc2
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/CommandScheduler.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/CommandScheduler.h
index e0abd0f..c0c09c1 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/CommandScheduler.h
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/CommandScheduler.h
@@ -6,18 +6,21 @@
 
 #include <initializer_list>
 #include <memory>
+#include <span>
 #include <utility>
 
 #include <frc/Errors.h>
 #include <frc/Watchdog.h>
+#include <frc/event/EventLoop.h>
 #include <networktables/NTSendable.h>
 #include <units/time.h>
 #include <wpi/FunctionExtras.h>
+#include <wpi/deprecated.h>
 #include <wpi/sendable/SendableHelper.h>
-#include <wpi/span.h>
 
 namespace frc2 {
 class Command;
+class CommandPtr;
 class Subsystem;
 
 /**
@@ -52,73 +55,67 @@
   void SetPeriod(units::second_t period);
 
   /**
-   * Adds a button binding to the scheduler, which will be polled to schedule
-   * commands.
+   * Get the active button poll.
    *
-   * @param button The button to add
+   * @return a reference to the current {@link frc::EventLoop} object polling
+   * buttons.
    */
-  void AddButton(wpi::unique_function<void()> button);
+  frc::EventLoop* GetActiveButtonLoop() const;
+
+  /**
+   * Replace the button poll with another one.
+   *
+   * @param loop the new button polling loop object.
+   */
+  void SetActiveButtonLoop(frc::EventLoop* loop);
+
+  /**
+   * Get the default button poll.
+   *
+   * @return a reference to the default {@link frc::EventLoop} object polling
+   * buttons.
+   */
+  frc::EventLoop* GetDefaultButtonLoop() const;
 
   /**
    * Removes all button bindings from the scheduler.
    */
+  WPI_DEPRECATED("Call Clear on the EventLoop instance directly!")
   void ClearButtons();
 
   /**
-   * Schedules a command for execution.  Does nothing if the command is already
+   * Schedules a command for execution. Does nothing if the command is already
    * scheduled. If a command's requirements are not available, it will only be
-   * started if all the commands currently using those requirements have been
-   * scheduled as interruptible.  If this is the case, they will be interrupted
-   * and the command will be scheduled.
+   * started if all the commands currently using those requirements are
+   * interruptible. If this is the case, they will be interrupted and the
+   * command will be scheduled.
    *
-   * @param interruptible whether this command can be interrupted
-   * @param command       the command to schedule
+   * @param command the command to schedule
    */
-  void Schedule(bool interruptible, Command* command);
+  void Schedule(const CommandPtr& command);
 
   /**
-   * Schedules a command for execution, with interruptible defaulted to true.
-   * Does nothing if the command is already scheduled.
+   * Schedules a command for execution. Does nothing if the command is already
+   * scheduled. If a command's requirements are not available, it will only be
+   * started if all the commands currently using those requirements have been
+   * scheduled as interruptible. If this is the case, they will be interrupted
+   * and the command will be scheduled.
    *
    * @param command the command to schedule
    */
   void Schedule(Command* command);
 
   /**
-   * Schedules multiple commands for execution.  Does nothing if the command is
-   * already scheduled. If a command's requirements are not available, it will
-   * only be started if all the commands currently using those requirements have
-   * been scheduled as interruptible.  If this is the case, they will be
-   * interrupted and the command will be scheduled.
-   *
-   * @param interruptible whether the commands should be interruptible
-   * @param commands      the commands to schedule
-   */
-  void Schedule(bool interruptible, wpi::span<Command* const> commands);
-
-  /**
-   * Schedules multiple commands for execution.  Does nothing if the command is
-   * already scheduled. If a command's requirements are not available, it will
-   * only be started if all the commands currently using those requirements have
-   * been scheduled as interruptible.  If this is the case, they will be
-   * interrupted and the command will be scheduled.
-   *
-   * @param interruptible whether the commands should be interruptible
-   * @param commands      the commands to schedule
-   */
-  void Schedule(bool interruptible, std::initializer_list<Command*> commands);
-
-  /**
-   * Schedules multiple commands for execution, with interruptible defaulted to
-   * true.  Does nothing if the command is already scheduled.
+   * Schedules multiple commands for execution. Does nothing for commands
+   * already scheduled.
    *
    * @param commands the commands to schedule
    */
-  void Schedule(wpi::span<Command* const> commands);
+  void Schedule(std::span<Command* const> commands);
 
   /**
-   * Schedules multiple commands for execution, with interruptible defaulted to
-   * true.  Does nothing if the command is already scheduled.
+   * Schedules multiple commands for execution. Does nothing for commands
+   * already scheduled.
    *
    * @param commands the commands to schedule
    */
@@ -162,10 +159,10 @@
   void UnregisterSubsystem(Subsystem* subsystem);
 
   void RegisterSubsystem(std::initializer_list<Subsystem*> subsystems);
-  void RegisterSubsystem(wpi::span<Subsystem* const> subsystems);
+  void RegisterSubsystem(std::span<Subsystem* const> subsystems);
 
   void UnregisterSubsystem(std::initializer_list<Subsystem*> subsystems);
-  void UnregisterSubsystem(wpi::span<Subsystem* const> subsystems);
+  void UnregisterSubsystem(std::span<Subsystem* const> subsystems);
 
   /**
    * Sets the default command for a subsystem.  Registers that subsystem if it
@@ -182,19 +179,37 @@
                          Command, std::remove_reference_t<T>>>>
   void SetDefaultCommand(Subsystem* subsystem, T&& defaultCommand) {
     if (!defaultCommand.HasRequirement(subsystem)) {
-      throw FRC_MakeError(frc::err::CommandIllegalUse, "{}",
+      throw FRC_MakeError(frc::err::CommandIllegalUse,
                           "Default commands must require their subsystem!");
     }
-    if (defaultCommand.IsFinished()) {
-      throw FRC_MakeError(frc::err::CommandIllegalUse, "{}",
-                          "Default commands should not end!");
-    }
     SetDefaultCommandImpl(subsystem,
                           std::make_unique<std::remove_reference_t<T>>(
                               std::forward<T>(defaultCommand)));
   }
 
   /**
+   * Sets the default command for a subsystem.  Registers that subsystem if it
+   * is not already registered.  Default commands will run whenever there is no
+   * other command currently scheduled that requires the subsystem.  Default
+   * commands should be written to never end (i.e. their IsFinished() method
+   * should return false), as they would simply be re-scheduled if they do.
+   * Default commands must also require their subsystem.
+   *
+   * @param subsystem      the subsystem whose default command will be set
+   * @param defaultCommand the default command to associate with the subsystem
+   */
+  void SetDefaultCommand(Subsystem* subsystem, CommandPtr&& defaultCommand);
+
+  /**
+   * Removes the default command for a subsystem. The current default command
+   * will run until another command is scheduled that requires the subsystem, at
+   * which point the current default command will not be re-scheduled.
+   *
+   * @param subsystem the subsystem whose default command will be removed
+   */
+  void RemoveDefaultCommand(Subsystem* subsystem);
+
+  /**
    * Gets the default command associated with this subsystem.  Null if this
    * subsystem has no default command associated with it.
    *
@@ -223,9 +238,21 @@
    * <p>Commands will be canceled even if they are not scheduled as
    * interruptible.
    *
+   * @param command the command to cancel
+   */
+  void Cancel(const CommandPtr& command);
+
+  /**
+   * Cancels commands. The scheduler will only call Command::End()
+   * method of the canceled command with true, indicating they were
+   * canceled (as opposed to finishing normally).
+   *
+   * <p>Commands will be canceled even if they are not scheduled as
+   * interruptible.
+   *
    * @param commands the commands to cancel
    */
-  void Cancel(wpi::span<Command* const> commands);
+  void Cancel(std::span<Command* const> commands);
 
   /**
    * Cancels commands. The scheduler will only call Command::End()
@@ -245,17 +272,6 @@
   void CancelAll();
 
   /**
-   * Returns the time since a given command was scheduled.  Note that this only
-   * works on commands that are directly scheduled by the scheduler; it will not
-   * work on commands inside of commandgroups, as the scheduler does not see
-   * them.
-   *
-   * @param command the command to query
-   * @return the time since the command was scheduled
-   */
-  units::second_t TimeSinceScheduled(const Command* command) const;
-
-  /**
    * Whether the given commands are running.  Note that this only works on
    * commands that are directly scheduled by the scheduler; it will not work on
    * commands inside of CommandGroups, as the scheduler does not see them.
@@ -263,7 +279,7 @@
    * @param commands the command to query
    * @return whether the command is currently scheduled
    */
-  bool IsScheduled(wpi::span<const Command* const> commands) const;
+  bool IsScheduled(std::span<const Command* const> commands) const;
 
   /**
    * Whether the given commands are running.  Note that this only works on
@@ -286,6 +302,16 @@
   bool IsScheduled(const Command* command) const;
 
   /**
+   * Whether a given command is running.  Note that this only works on commands
+   * that are directly scheduled by the scheduler; it will not work on commands
+   * inside of CommandGroups, as the scheduler does not see them.
+   *
+   * @param command the command to query
+   * @return whether the command is currently scheduled
+   */
+  bool IsScheduled(const CommandPtr& command) const;
+
+  /**
    * Returns the command currently requiring a given subsystem.  Null if no
    * command is currently requiring the subsystem
    *
@@ -334,6 +360,34 @@
    */
   void OnCommandFinish(Action action);
 
+  /**
+   * Requires that the specified command hasn't been already added to a
+   * composition.
+   *
+   * @param command The command to check
+   * @throws if the given commands have already been composed.
+   */
+  void RequireUngrouped(const Command* command);
+
+  /**
+   * Requires that the specified commands not have been already added to a
+   * composition.
+   *
+   * @param commands The commands to check
+   * @throws if the given commands have already been composed.
+   */
+  void RequireUngrouped(std::span<const std::unique_ptr<Command>> commands);
+
+  /**
+   * Requires that the specified commands not have been already added to a
+   * composition.
+   *
+   * @param commands The commands to check
+   * @throws IllegalArgumentException if the given commands have already been
+   * composed.
+   */
+  void RequireUngrouped(std::initializer_list<const Command*> commands);
+
   void InitSendable(nt::NTSendableBuilder& builder) override;
 
  private:
@@ -349,5 +403,8 @@
   frc::Watchdog m_watchdog;
 
   friend class CommandTestBase;
+
+  template <typename T>
+  friend class CommandTestBaseWithParam;
 };
 }  // namespace frc2
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/CommandState.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/CommandState.h
deleted file mode 100644
index e040e4b..0000000
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/CommandState.h
+++ /dev/null
@@ -1,34 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <units/time.h>
-
-namespace frc2 {
-/**
- * Class that holds scheduling state for a command.  Used internally by the
- * CommandScheduler
- *
- * This class is provided by the NewCommands VendorDep
- */
-class CommandState final {
- public:
-  CommandState() = default;
-
-  explicit CommandState(bool interruptible);
-
-  bool IsInterruptible() const { return m_interruptible; }
-
-  // The time since this command was initialized.
-  units::second_t TimeSinceInitialized() const;
-
- private:
-  units::second_t m_startTime = -1_s;
-  bool m_interruptible;
-
-  void StartTiming();
-  void StartRunning();
-};
-}  // namespace frc2
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/Commands.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/Commands.h
new file mode 100644
index 0000000..8b38275
--- /dev/null
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/Commands.h
@@ -0,0 +1,262 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <functional>
+#include <initializer_list>
+#include <span>
+#include <string>
+#include <utility>
+#include <vector>
+
+#include "frc2/command/CommandPtr.h"
+#include "frc2/command/SelectCommand.h"
+
+namespace frc2 {
+class Subsystem;
+
+/**
+ * Namespace for command factories.
+ */
+namespace cmd {
+
+/**
+ * Constructs a command that does nothing, finishing immediately.
+ */
+[[nodiscard]] CommandPtr None();
+
+// Action Commands
+
+/**
+ * Constructs a command that runs an action once and finishes.
+ *
+ * @param action the action to run
+ * @param requirements subsystems the action requires
+ */
+[[nodiscard]] CommandPtr RunOnce(
+    std::function<void()> action,
+    std::initializer_list<Subsystem*> requirements);
+
+/**
+ * Constructs a command that runs an action once and finishes.
+ *
+ * @param action the action to run
+ * @param requirements subsystems the action requires
+ */
+[[nodiscard]] CommandPtr RunOnce(std::function<void()> action,
+                                 std::span<Subsystem* const> requirements = {});
+
+/**
+ * Constructs a command that runs an action every iteration until interrupted.
+ *
+ * @param action the action to run
+ * @param requirements subsystems the action requires
+ */
+[[nodiscard]] CommandPtr Run(std::function<void()> action,
+                             std::initializer_list<Subsystem*> requirements);
+
+/**
+ * Constructs a command that runs an action every iteration until interrupted.
+ *
+ * @param action the action to run
+ * @param requirements subsystems the action requires
+ */
+[[nodiscard]] CommandPtr Run(std::function<void()> action,
+                             std::span<Subsystem* const> requirements = {});
+
+/**
+ * Constructs a command that runs an action once and another action when the
+ * command is interrupted.
+ *
+ * @param start the action to run on start
+ * @param end the action to run on interrupt
+ * @param requirements subsystems the action requires
+ */
+[[nodiscard]] CommandPtr StartEnd(
+    std::function<void()> start, std::function<void()> end,
+    std::initializer_list<Subsystem*> requirements);
+
+/**
+ * Constructs a command that runs an action once and another action when the
+ * command is interrupted.
+ *
+ * @param start the action to run on start
+ * @param end the action to run on interrupt
+ * @param requirements subsystems the action requires
+ */
+[[nodiscard]] CommandPtr StartEnd(
+    std::function<void()> start, std::function<void()> end,
+    std::span<Subsystem* const> requirements = {});
+
+/**
+ * Constructs a command that runs an action every iteration until interrupted,
+ * and then runs a second action.
+ *
+ * @param run the action to run every iteration
+ * @param end the action to run on interrupt
+ * @param requirements subsystems the action requires
+ */
+[[nodiscard]] CommandPtr RunEnd(std::function<void()> run,
+                                std::function<void()> end,
+                                std::initializer_list<Subsystem*> requirements);
+
+/**
+ * Constructs a command that runs an action every iteration until interrupted,
+ * and then runs a second action.
+ *
+ * @param run the action to run every iteration
+ * @param end the action to run on interrupt
+ * @param requirements subsystems the action requires
+ */
+[[nodiscard]] CommandPtr RunEnd(std::function<void()> run,
+                                std::function<void()> end,
+                                std::span<Subsystem* const> requirements = {});
+
+/**
+ * Constructs a command that prints a message and finishes.
+ *
+ * @param msg the message to print
+ */
+[[nodiscard]] CommandPtr Print(std::string_view msg);
+
+// Idling Commands
+
+/**
+ * Constructs a command that does nothing, finishing after a specified duration.
+ *
+ * @param duration after how long the command finishes
+ */
+[[nodiscard]] CommandPtr Wait(units::second_t duration);
+
+/**
+ * Constructs a command that does nothing, finishing once a condition becomes
+ * true.
+ *
+ * @param condition the condition
+ */
+[[nodiscard]] CommandPtr WaitUntil(std::function<bool()> condition);
+
+// Selector Commands
+
+/**
+ * Runs one of two commands, based on the boolean selector function.
+ *
+ * @param onTrue the command to run if the selector function returns true
+ * @param onFalse the command to run if the selector function returns false
+ * @param selector the selector function
+ */
+[[nodiscard]] CommandPtr Either(CommandPtr&& onTrue, CommandPtr&& onFalse,
+                                std::function<bool()> selector);
+
+/**
+ * Runs one of several commands, based on the selector function.
+ *
+ * @param selector the selector function
+ * @param commands map of commands to select from
+ */
+template <typename Key>
+[[nodiscard]] CommandPtr Select(
+    std::function<Key()> selector,
+    std::vector<std::pair<Key, CommandPtr>> commands) {
+  return SelectCommand(std::move(selector),
+                       CommandPtr::UnwrapVector(std::move(commands)))
+      .ToPtr();
+}
+
+// Command Groups
+
+namespace impl {
+
+/**
+ * Create a vector of commands.
+ */
+template <typename... Args>
+std::vector<CommandPtr> MakeVector(Args&&... args) {
+  std::vector<CommandPtr> data;
+  data.reserve(sizeof...(Args));
+  (data.emplace_back(std::forward<Args>(args)), ...);
+  return data;
+}
+
+}  // namespace impl
+
+/**
+ * Runs a group of commands in series, one after the other.
+ */
+[[nodiscard]] CommandPtr Sequence(std::vector<CommandPtr>&& commands);
+
+/**
+ * Runs a group of commands in series, one after the other.
+ */
+template <typename... Args>
+[[nodiscard]] CommandPtr Sequence(Args&&... commands) {
+  return Sequence(impl::MakeVector(std::forward<Args>(commands)...));
+}
+
+/**
+ * Runs a group of commands in series, one after the other. Once the last
+ * command ends, the group is restarted.
+ */
+[[nodiscard]] CommandPtr RepeatingSequence(std::vector<CommandPtr>&& commands);
+
+/**
+ * Runs a group of commands in series, one after the other. Once the last
+ * command ends, the group is restarted.
+ */
+template <typename... Args>
+[[nodiscard]] CommandPtr RepeatingSequence(Args&&... commands) {
+  return RepeatingSequence(impl::MakeVector(std::forward<Args>(commands)...));
+}
+
+/**
+ * Runs a group of commands at the same time. Ends once all commands in the
+ * group finish.
+ */
+[[nodiscard]] CommandPtr Parallel(std::vector<CommandPtr>&& commands);
+
+/**
+ * Runs a group of commands at the same time. Ends once all commands in the
+ * group finish.
+ */
+template <typename... Args>
+[[nodiscard]] CommandPtr Parallel(Args&&... commands) {
+  return Parallel(impl::MakeVector(std::forward<Args>(commands)...));
+}
+
+/**
+ * Runs a group of commands at the same time. Ends once any command in the group
+ * finishes, and cancels the others.
+ */
+[[nodiscard]] CommandPtr Race(std::vector<CommandPtr>&& commands);
+
+/**
+ * Runs a group of commands at the same time. Ends once any command in the group
+ * finishes, and cancels the others.
+ */
+template <typename... Args>
+[[nodiscard]] CommandPtr Race(Args&&... commands) {
+  return Race(impl::MakeVector(std::forward<Args>(commands)...));
+}
+
+/**
+ * Runs a group of commands at the same time. Ends once a specific command
+ * finishes, and cancels the others.
+ */
+[[nodiscard]] CommandPtr Deadline(CommandPtr&& deadline,
+                                  std::vector<CommandPtr>&& others);
+
+/**
+ * Runs a group of commands at the same time. Ends once a specific command
+ * finishes, and cancels the others.
+ */
+template <typename... Args>
+[[nodiscard]] CommandPtr Deadline(CommandPtr&& deadline, Args&&... commands) {
+  return Deadline(std::move(deadline),
+                  impl::MakeVector(std::forward<Args>(commands)...));
+}
+
+}  // namespace cmd
+
+}  // namespace frc2
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/ConditionalCommand.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/ConditionalCommand.h
index 507ce9a..5957950 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/ConditionalCommand.h
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/ConditionalCommand.h
@@ -9,25 +9,17 @@
 #include <utility>
 
 #include "frc2/command/CommandBase.h"
-#include "frc2/command/CommandGroupBase.h"
 #include "frc2/command/CommandHelper.h"
 
 namespace frc2 {
 /**
- * Runs one of two commands, depending on the value of the given condition when
- * this command is initialized.  Does not actually schedule the selected command
- * - rather, the command is run through this command; this ensures that the
- * command will behave as expected if used as part of a CommandGroup.  Requires
- * the requirements of both commands, again to ensure proper functioning when
- * used in a CommandGroup.  If this is undesired, consider using
- * ScheduleCommand.
+ * A command composition that runs one of two commands, depending on the value
+ * of the given condition when this command is initialized.
  *
- * <p>As this command contains multiple component commands within it, it is
- * technically a command group; the command instances that are passed to it
- * cannot be added to any other groups, or scheduled individually.
- *
- * <p>As a rule, CommandGroups require the union of the requirements of their
- * component commands.
+ * <p>The rules for command compositions apply: command instances that are
+ * passed to it are owned by the composition and cannot be added to any other
+ * composition or scheduled individually, and the composition requires all
+ * subsystems its components require.
  *
  * This class is provided by the NewCommands VendorDep
  *
@@ -81,6 +73,8 @@
 
   bool RunsWhenDisabled() const override;
 
+  void InitSendable(wpi::SendableBuilder& builder) override;
+
  private:
   std::unique_ptr<Command> m_onTrue;
   std::unique_ptr<Command> m_onFalse;
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/FunctionalCommand.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/FunctionalCommand.h
index a4891a4..ef2b5b9 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/FunctionalCommand.h
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/FunctionalCommand.h
@@ -6,8 +6,7 @@
 
 #include <functional>
 #include <initializer_list>
-
-#include <wpi/span.h>
+#include <span>
 
 #include "frc2/command/CommandBase.h"
 #include "frc2/command/CommandHelper.h"
@@ -54,7 +53,7 @@
                     std::function<void()> onExecute,
                     std::function<void(bool)> onEnd,
                     std::function<bool()> isFinished,
-                    wpi::span<Subsystem* const> requirements = {});
+                    std::span<Subsystem* const> requirements = {});
 
   FunctionalCommand(FunctionalCommand&& other) = default;
 
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/InstantCommand.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/InstantCommand.h
index c2638da..cae0b3e 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/InstantCommand.h
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/InstantCommand.h
@@ -6,11 +6,10 @@
 
 #include <functional>
 #include <initializer_list>
+#include <span>
 
-#include <wpi/span.h>
-
-#include "frc2/command/CommandBase.h"
 #include "frc2/command/CommandHelper.h"
+#include "frc2/command/FunctionalCommand.h"
 
 namespace frc2 {
 /**
@@ -20,7 +19,7 @@
  *
  * This class is provided by the NewCommands VendorDep
  */
-class InstantCommand : public CommandHelper<CommandBase, InstantCommand> {
+class InstantCommand : public CommandHelper<FunctionalCommand, InstantCommand> {
  public:
   /**
    * Creates a new InstantCommand that runs the given Runnable with the given
@@ -40,7 +39,7 @@
    * @param requirements the subsystems required by this command
    */
   explicit InstantCommand(std::function<void()> toRun,
-                          wpi::span<Subsystem* const> requirements = {});
+                          std::span<Subsystem* const> requirements = {});
 
   InstantCommand(InstantCommand&& other) = default;
 
@@ -51,12 +50,5 @@
    * only as a no-arg constructor to call implicitly from subclass constructors.
    */
   InstantCommand();
-
-  void Initialize() override;
-
-  bool IsFinished() final;
-
- private:
-  std::function<void()> m_toRun;
 };
 }  // namespace frc2
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/MecanumControllerCommand.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/MecanumControllerCommand.h
index 92c569d..8ebdbe0 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/MecanumControllerCommand.h
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/MecanumControllerCommand.h
@@ -6,6 +6,7 @@
 #include <functional>
 #include <initializer_list>
 #include <memory>
+#include <span>
 
 #include <frc/Timer.h>
 #include <frc/controller/HolonomicDriveController.h>
@@ -21,7 +22,6 @@
 #include <units/length.h>
 #include <units/velocity.h>
 #include <units/voltage.h>
-#include <wpi/span.h>
 
 #include "CommandBase.h"
 #include "CommandHelper.h"
@@ -206,7 +206,7 @@
       std::function<void(units::volt_t, units::volt_t, units::volt_t,
                          units::volt_t)>
           output,
-      wpi::span<Subsystem* const> requirements = {});
+      std::span<Subsystem* const> requirements = {});
 
   /**
    * Constructs a new MecanumControllerCommand that when executed will follow
@@ -259,7 +259,7 @@
       std::function<void(units::volt_t, units::volt_t, units::volt_t,
                          units::volt_t)>
           output,
-      wpi::span<Subsystem* const> requirements = {});
+      std::span<Subsystem* const> requirements = {});
 
   /**
    * Constructs a new MecanumControllerCommand that when executed will follow
@@ -268,7 +268,7 @@
    *
    * <p>Note: The controllers will *not* set the outputVolts to zero upon
    * completion of the path - this is left to the user, since it is not
-   * appropriate for paths with non-stationary end-states.
+   * appropriate for paths with nonstationary end-states.
    *
    * @param trajectory       The trajectory to follow.
    * @param pose             A function that supplies the robot pose - use one
@@ -306,7 +306,7 @@
    *
    * <p>Note: The controllers will *not* set the outputVolts to zero upon
    * completion of the path - this is left to the user, since it is not
-   * appropriate for paths with non-stationary end-states.
+   * appropriate for paths with nonstationary end-states.
    *
    * <p>Note 2: The final rotation of the robot will be set to the rotation of
    * the final pose in the trajectory. The robot will not follow the rotations
@@ -346,7 +346,7 @@
    *
    * <p>Note: The controllers will *not* set the outputVolts to zero upon
    * completion of the path - this is left to the user, since it is not
-   * appropriate for paths with non-stationary end-states.
+   * appropriate for paths with nonstationary end-states.
    *
    * @param trajectory       The trajectory to follow.
    * @param pose             A function that supplies the robot pose - use one
@@ -375,7 +375,7 @@
                          units::meters_per_second_t,
                          units::meters_per_second_t)>
           output,
-      wpi::span<Subsystem* const> requirements = {});
+      std::span<Subsystem* const> requirements = {});
 
   /**
    * Constructs a new MecanumControllerCommand that when executed will follow
@@ -384,7 +384,7 @@
    *
    * <p>Note: The controllers will *not* set the outputVolts to zero upon
    * completion of the path - this is left to the user, since it is not
-   * appropriate for paths with non-stationary end-states.
+   * appropriate for paths with nonstationary end-states.
    *
    * <p>Note2: The final rotation of the robot will be set to the rotation of
    * the final pose in the trajectory. The robot will not follow the rotations
@@ -415,7 +415,7 @@
                          units::meters_per_second_t,
                          units::meters_per_second_t)>
           output,
-      wpi::span<Subsystem* const> requirements = {});
+      std::span<Subsystem* const> requirements = {});
 
   void Initialize() override;
 
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/NotifierCommand.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/NotifierCommand.h
index d2be985..607799b 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/NotifierCommand.h
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/NotifierCommand.h
@@ -6,10 +6,10 @@
 
 #include <functional>
 #include <initializer_list>
+#include <span>
 
 #include <frc/Notifier.h>
 #include <units/time.h>
-#include <wpi/span.h>
 
 #include "frc2/command/CommandBase.h"
 #include "frc2/command/CommandHelper.h"
@@ -47,7 +47,7 @@
    * @param requirements the subsystems required by this command
    */
   NotifierCommand(std::function<void()> toRun, units::second_t period,
-                  wpi::span<Subsystem* const> requirements = {});
+                  std::span<Subsystem* const> requirements = {});
 
   NotifierCommand(NotifierCommand&& other);
 
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/PIDCommand.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/PIDCommand.h
index a63d55c..818c50b 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/PIDCommand.h
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/PIDCommand.h
@@ -6,9 +6,9 @@
 
 #include <functional>
 #include <initializer_list>
+#include <span>
 
 #include <frc/controller/PIDController.h>
-#include <wpi/span.h>
 
 #include "frc2/command/CommandBase.h"
 #include "frc2/command/CommandHelper.h"
@@ -56,7 +56,7 @@
              std::function<double()> measurementSource,
              std::function<double()> setpointSource,
              std::function<void(double)> useOutput,
-             wpi::span<Subsystem* const> requirements = {});
+             std::span<Subsystem* const> requirements = {});
 
   /**
    * Creates a new PIDCommand, which controls the given output with a
@@ -86,7 +86,7 @@
   PIDCommand(PIDController controller,
              std::function<double()> measurementSource, double setpoint,
              std::function<void(double)> useOutput,
-             wpi::span<Subsystem* const> requirements = {});
+             std::span<Subsystem* const> requirements = {});
 
   PIDCommand(PIDCommand&& other) = default;
 
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/PIDSubsystem.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/PIDSubsystem.h
index 37571ad..426e3ec 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/PIDSubsystem.h
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/PIDSubsystem.h
@@ -85,8 +85,5 @@
    * @param setpoint the setpoint of the PIDController (for feedforward)
    */
   virtual void UseOutput(double output, double setpoint) = 0;
-
- private:
-  double m_setpoint{0};
 };
 }  // namespace frc2
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/ParallelCommandGroup.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/ParallelCommandGroup.h
index d1f5aa6..943b62f 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/ParallelCommandGroup.h
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/ParallelCommandGroup.h
@@ -18,11 +18,13 @@
 
 namespace frc2 {
 /**
- * A CommandGroup that runs a set of commands in parallel, ending when the last
- * command ends.
+ * A command composition that runs a set of commands in parallel, ending when
+ * the last command ends.
  *
- * <p>As a rule, CommandGroups require the union of the requirements of their
- * component commands.
+ * <p>The rules for command compositions apply: command instances that are
+ * passed to it are owned by the composition and cannot be added to any other
+ * composition or scheduled individually, and the composition requires all
+ * subsystems its components require.
  *
  * This class is provided by the NewCommands VendorDep
  */
@@ -30,23 +32,23 @@
     : public CommandHelper<CommandGroupBase, ParallelCommandGroup> {
  public:
   /**
-   * Creates a new ParallelCommandGroup.  The given commands will be executed
+   * Creates a new ParallelCommandGroup. The given commands will be executed
    * simultaneously. The command group will finish when the last command
-   * finishes.  If the CommandGroup is interrupted, only the commands that are
+   * finishes. If the composition is interrupted, only the commands that are
    * still running will be interrupted.
    *
-   * @param commands the commands to include in this group.
+   * @param commands the commands to include in this composition.
    */
   explicit ParallelCommandGroup(
       std::vector<std::unique_ptr<Command>>&& commands);
 
   /**
-   * Creates a new ParallelCommandGroup.  The given commands will be executed
+   * Creates a new ParallelCommandGroup. The given commands will be executed
    * simultaneously. The command group will finish when the last command
-   * finishes.  If the CommandGroup is interrupted, only the commands that are
+   * finishes. If the composition is interrupted, only the commands that are
    * still running will be interrupted.
    *
-   * @param commands the commands to include in this group.
+   * @param commands the commands to include in this composition.
    */
   template <class... Types,
             typename = std::enable_if_t<std::conjunction_v<
@@ -57,7 +59,7 @@
 
   ParallelCommandGroup(ParallelCommandGroup&& other) = default;
 
-  // No copy constructors for commandgroups
+  // No copy constructors for command groups
   ParallelCommandGroup(const ParallelCommandGroup&) = delete;
 
   // Prevent template expansion from emulating copy ctor
@@ -74,21 +76,25 @@
     AddCommands(std::move(foo));
   }
 
-  void Initialize() override;
+  void Initialize() final;
 
-  void Execute() override;
+  void Execute() final;
 
-  void End(bool interrupted) override;
+  void End(bool interrupted) final;
 
-  bool IsFinished() override;
+  bool IsFinished() final;
 
   bool RunsWhenDisabled() const override;
 
+  Command::InterruptionBehavior GetInterruptionBehavior() const override;
+
  private:
   void AddCommands(std::vector<std::unique_ptr<Command>>&& commands) final;
 
   std::vector<std::pair<std::unique_ptr<Command>, bool>> m_commands;
   bool m_runWhenDisabled{true};
+  Command::InterruptionBehavior m_interruptBehavior{
+      Command::InterruptionBehavior::kCancelIncoming};
   bool isRunning = false;
 };
 }  // namespace frc2
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/ParallelDeadlineGroup.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/ParallelDeadlineGroup.h
index 81d25cb..cfe4b3e 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/ParallelDeadlineGroup.h
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/ParallelDeadlineGroup.h
@@ -18,12 +18,14 @@
 
 namespace frc2 {
 /**
- * A CommandGroup that runs a set of commands in parallel, ending only when a
- * specific command (the "deadline") ends, interrupting all other commands that
- * are still running at that point.
+ * A command composition that runs a set of commands in parallel, ending only
+ * when a specific command (the "deadline") ends, interrupting all other
+ * commands that are still running at that point.
  *
- * <p>As a rule, CommandGroups require the union of the requirements of their
- * component commands.
+ * <p>The rules for command compositions apply: command instances that are
+ * passed to it are owned by the composition and cannot be added to any other
+ * composition or scheduled individually, and the composition requires all
+ * subsystems its components require.
  *
  * This class is provided by the NewCommands VendorDep
  */
@@ -31,25 +33,25 @@
     : public CommandHelper<CommandGroupBase, ParallelDeadlineGroup> {
  public:
   /**
-   * Creates a new ParallelDeadlineGroup.  The given commands (including the
-   * deadline) will be executed simultaneously.  The CommandGroup will finish
-   * when the deadline finishes, interrupting all other still-running commands.
-   * If the CommandGroup is interrupted, only the commands still running will be
+   * Creates a new ParallelDeadlineGroup. The given commands (including the
+   * deadline) will be executed simultaneously. The composition will finish when
+   * the deadline finishes, interrupting all other still-running commands. If
+   * the composition is interrupted, only the commands still running will be
    * interrupted.
    *
-   * @param deadline the command that determines when the group ends
+   * @param deadline the command that determines when the composition ends
    * @param commands the commands to be executed
    */
   ParallelDeadlineGroup(std::unique_ptr<Command>&& deadline,
                         std::vector<std::unique_ptr<Command>>&& commands);
   /**
-   * Creates a new ParallelDeadlineGroup.  The given commands (including the
-   * deadline) will be executed simultaneously.  The CommandGroup will finish
-   * when the deadline finishes, interrupting all other still-running commands.
-   * If the CommandGroup is interrupted, only the commands still running will be
+   * Creates a new ParallelDeadlineGroup. The given commands (including the
+   * deadline) will be executed simultaneously. The composition will finish when
+   * the deadline finishes, interrupting all other still-running commands. If
+   * the composition is interrupted, only the commands still running will be
    * interrupted.
    *
-   * @param deadline the command that determines when the group ends
+   * @param deadline the command that determines when the composition ends
    * @param commands the commands to be executed
    */
   template <class T, class... Types,
@@ -82,16 +84,20 @@
     AddCommands(std::move(foo));
   }
 
-  void Initialize() override;
+  void Initialize() final;
 
-  void Execute() override;
+  void Execute() final;
 
-  void End(bool interrupted) override;
+  void End(bool interrupted) final;
 
-  bool IsFinished() override;
+  bool IsFinished() final;
 
   bool RunsWhenDisabled() const override;
 
+  Command::InterruptionBehavior GetInterruptionBehavior() const override;
+
+  void InitSendable(wpi::SendableBuilder& builder) override;
+
  private:
   void AddCommands(std::vector<std::unique_ptr<Command>>&& commands) final;
 
@@ -100,6 +106,8 @@
   std::vector<std::pair<std::unique_ptr<Command>, bool>> m_commands;
   Command* m_deadline;
   bool m_runWhenDisabled{true};
+  Command::InterruptionBehavior m_interruptBehavior{
+      Command::InterruptionBehavior::kCancelIncoming};
   bool m_finished{true};
 };
 }  // namespace frc2
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/ParallelRaceGroup.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/ParallelRaceGroup.h
index 0092223..d5412cd 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/ParallelRaceGroup.h
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/ParallelRaceGroup.h
@@ -18,11 +18,13 @@
 
 namespace frc2 {
 /**
- * A CommandGroup that runs a set of commands in parallel, ending when any one
- * of the commands ends and interrupting all the others.
+ * A composition that runs a set of commands in parallel, ending when any one of
+ * the commands ends and interrupting all the others.
  *
- * <p>As a rule, CommandGroups require the union of the requirements of their
- * component commands.
+ * <p>The rules for command compositions apply: command instances that are
+ * passed to it are owned by the composition and cannot be added to any other
+ * composition or scheduled individually, and the composition requires all
+ * subsystems its components require.
  *
  * This class is provided by the NewCommands VendorDep
  */
@@ -30,11 +32,11 @@
     : public CommandHelper<CommandGroupBase, ParallelRaceGroup> {
  public:
   /**
-   * Creates a new ParallelCommandRace.  The given commands will be executed
+   * Creates a new ParallelCommandRace. The given commands will be executed
    * simultaneously, and will "race to the finish" - the first command to finish
    * ends the entire command, with all other commands being interrupted.
    *
-   * @param commands the commands to include in this group.
+   * @param commands the commands to include in this composition.
    */
   explicit ParallelRaceGroup(std::vector<std::unique_ptr<Command>>&& commands);
 
@@ -62,21 +64,25 @@
     AddCommands(std::move(foo));
   }
 
-  void Initialize() override;
+  void Initialize() final;
 
-  void Execute() override;
+  void Execute() final;
 
-  void End(bool interrupted) override;
+  void End(bool interrupted) final;
 
-  bool IsFinished() override;
+  bool IsFinished() final;
 
   bool RunsWhenDisabled() const override;
 
+  Command::InterruptionBehavior GetInterruptionBehavior() const override;
+
  private:
   void AddCommands(std::vector<std::unique_ptr<Command>>&& commands) final;
 
   std::vector<std::unique_ptr<Command>> m_commands;
   bool m_runWhenDisabled{true};
+  Command::InterruptionBehavior m_interruptBehavior{
+      Command::InterruptionBehavior::kCancelIncoming};
   bool m_finished{false};
   bool isRunning = false;
 };
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/PerpetualCommand.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/PerpetualCommand.h
index 4818cda..297cb64 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/PerpetualCommand.h
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/PerpetualCommand.h
@@ -13,13 +13,12 @@
 #include <utility>
 
 #include "frc2/command/CommandBase.h"
-#include "frc2/command/CommandGroupBase.h"
 #include "frc2/command/CommandHelper.h"
 
 namespace frc2 {
 /**
  * A command that runs another command in perpetuity, ignoring that command's
- * end conditions.  While this class does not extend {@link CommandGroupBase},
+ * end conditions.  While this class does not extend frc2::CommandGroupBase,
  * it is still considered a CommandGroup, as it allows one to compose another
  * command within it; the command instances that are passed to it cannot be
  * added to any other groups, or scheduled individually.
@@ -28,6 +27,12 @@
  * component commands.
  *
  * This class is provided by the NewCommands VendorDep
+ *
+ * @deprecated PerpetualCommand violates the assumption that execute() doesn't
+get called after isFinished() returns true -- an assumption that should be
+valid. This was unsafe/undefined behavior from the start, and RepeatCommand
+provides an easy way to achieve similar end results with slightly different (and
+safe) semantics.
  */
 class PerpetualCommand : public CommandHelper<CommandBase, PerpetualCommand> {
  public:
@@ -38,7 +43,15 @@
    *
    * @param command the command to run perpetually
    */
+  WPI_DEPRECATED(
+      "PerpetualCommand violates the assumption that execute() doesn't get "
+      "called after isFinished() returns true -- an assumption that should be "
+      "valid."
+      "This was unsafe/undefined behavior from the start, and RepeatCommand "
+      "provides an easy way to achieve similar end results with slightly "
+      "different (and safe) semantics.")
   explicit PerpetualCommand(std::unique_ptr<Command>&& command);
+  WPI_IGNORE_DEPRECATED
 
   /**
    * Creates a new PerpetualCommand.  Will run another command in perpetuity,
@@ -49,9 +62,17 @@
    */
   template <class T, typename = std::enable_if_t<std::is_base_of_v<
                          Command, std::remove_reference_t<T>>>>
+  WPI_DEPRECATED(
+      "PerpetualCommand violates the assumption that execute() doesn't get "
+      "called after isFinished() returns true -- an assumption that should be "
+      "valid."
+      "This was unsafe/undefined behavior from the start, and RepeatCommand "
+      "provides an easy way to achieve similar end results with slightly "
+      "different (and safe) semantics.")
   explicit PerpetualCommand(T&& command)
       : PerpetualCommand(std::make_unique<std::remove_reference_t<T>>(
             std::forward<T>(command))) {}
+  WPI_UNIGNORE_DEPRECATED
 
   PerpetualCommand(PerpetualCommand&& other) = default;
 
@@ -67,8 +88,6 @@
 
   void End(bool interrupted) override;
 
-  PerpetualCommand Perpetually() && override;
-
  private:
   std::unique_ptr<Command> m_command;
 };
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/ProfiledPIDCommand.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/ProfiledPIDCommand.h
index d106ad3..3fbe726 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/ProfiledPIDCommand.h
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/ProfiledPIDCommand.h
@@ -6,11 +6,11 @@
 
 #include <functional>
 #include <initializer_list>
+#include <span>
 #include <utility>
 
 #include <frc/controller/ProfiledPIDController.h>
 #include <units/time.h>
-#include <wpi/span.h>
 
 #include "frc2/command/CommandBase.h"
 #include "frc2/command/CommandHelper.h"
@@ -72,7 +72,7 @@
                      std::function<Distance_t()> measurementSource,
                      std::function<State()> goalSource,
                      std::function<void(double, State)> useOutput,
-                     wpi::span<Subsystem* const> requirements = {})
+                     std::span<Subsystem* const> requirements = {})
       : m_controller{controller},
         m_measurement{std::move(measurementSource)},
         m_goal{std::move(goalSource)},
@@ -116,7 +116,7 @@
                      std::function<Distance_t()> measurementSource,
                      std::function<Distance_t()> goalSource,
                      std::function<void(double, State)> useOutput,
-                     wpi::span<Subsystem* const> requirements = {})
+                     std::span<Subsystem* const> requirements = {})
       : ProfiledPIDCommand(
             controller, measurementSource,
             [goalSource = std::move(goalSource)]() {
@@ -155,7 +155,7 @@
   ProfiledPIDCommand(frc::ProfiledPIDController<Distance> controller,
                      std::function<Distance_t()> measurementSource, State goal,
                      std::function<void(double, State)> useOutput,
-                     wpi::span<Subsystem* const> requirements = {})
+                     std::span<Subsystem* const> requirements = {})
       : ProfiledPIDCommand(
             controller, measurementSource, [goal] { return goal; }, useOutput,
             requirements) {}
@@ -193,7 +193,7 @@
                      std::function<Distance_t()> measurementSource,
                      Distance_t goal,
                      std::function<void(double, State)> useOutput,
-                     wpi::span<Subsystem* const> requirements = {})
+                     std::span<Subsystem* const> requirements = {})
       : ProfiledPIDCommand(
             controller, measurementSource, [goal] { return goal; }, useOutput,
             requirements) {}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/ProfiledPIDSubsystem.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/ProfiledPIDSubsystem.h
index 032ee4b..cfdfc6b 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/ProfiledPIDSubsystem.h
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/ProfiledPIDSubsystem.h
@@ -41,7 +41,7 @@
 
   void Periodic() override {
     if (m_enabled) {
-      UseOutput(m_controller.Calculate(GetMeasurement(), m_goal),
+      UseOutput(m_controller.Calculate(GetMeasurement()),
                 m_controller.GetSetpoint());
     }
   }
@@ -51,14 +51,14 @@
    *
    * @param goal The goal state for the subsystem's motion profile.
    */
-  void SetGoal(State goal) { m_goal = goal; }
+  void SetGoal(State goal) { m_controller.SetGoal(goal); }
 
   /**
    * Sets the goal state for the subsystem.  Goal velocity assumed to be zero.
    *
    * @param goal The goal position for the subsystem's motion profile.
    */
-  void SetGoal(Distance_t goal) { m_goal = State{goal, Velocity_t(0)}; }
+  void SetGoal(Distance_t goal) { SetGoal(State{goal, Velocity_t(0)}); }
 
   /**
    * Enables the PID control. Resets the controller.
@@ -110,8 +110,5 @@
    * feedforward
    */
   virtual void UseOutput(double output, State setpoint) = 0;
-
- private:
-  State m_goal;
 };
 }  // namespace frc2
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/ProxyCommand.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/ProxyCommand.h
new file mode 100644
index 0000000..b4a00a5
--- /dev/null
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/ProxyCommand.h
@@ -0,0 +1,70 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <memory>
+#include <span>
+
+#include <wpi/FunctionExtras.h>
+
+#include "frc2/command/CommandBase.h"
+#include "frc2/command/CommandHelper.h"
+#include "frc2/command/SetUtilities.h"
+
+namespace frc2 {
+/**
+ * Schedules the given command when this command is initialized, and ends when
+ * it ends. Useful for forking off from CommandGroups. If this command is
+ * interrupted, it will cancel the command.
+ *
+ * <p>This class is provided by the NewCommands VendorDep
+ */
+class ProxyCommand : public CommandHelper<CommandBase, ProxyCommand> {
+ public:
+  /**
+   * Creates a new ProxyCommand that schedules the supplied command when
+   * initialized, and ends when it is no longer scheduled. Useful for lazily
+   * creating commands at runtime.
+   *
+   * @param supplier the command supplier
+   */
+  explicit ProxyCommand(wpi::unique_function<Command*()> supplier);
+
+  /**
+   * Creates a new ProxyCommand that schedules the given command when
+   * initialized, and ends when it is no longer scheduled.
+   *
+   * @param command the command to run by proxy
+   */
+  explicit ProxyCommand(Command* command);
+
+  /**
+   * Creates a new ProxyCommand that schedules the given command when
+   * initialized, and ends when it is no longer scheduled.
+   *
+   * <p>Note that this constructor passes ownership of the given command to the
+   * returned ProxyCommand.
+   *
+   * @param command the command to schedule
+   */
+  explicit ProxyCommand(std::unique_ptr<Command> command);
+
+  ProxyCommand(ProxyCommand&& other) = default;
+
+  void Initialize() override;
+
+  void End(bool interrupted) override;
+
+  void Execute() override;
+
+  bool IsFinished() override;
+
+  void InitSendable(wpi::SendableBuilder& builder) override;
+
+ private:
+  wpi::unique_function<Command*()> m_supplier;
+  Command* m_command = nullptr;
+};
+}  // namespace frc2
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/ProxyScheduleCommand.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/ProxyScheduleCommand.h
index afc6f54..f79b549 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/ProxyScheduleCommand.h
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/ProxyScheduleCommand.h
@@ -4,8 +4,11 @@
 
 #pragma once
 
+#include <memory>
+#include <span>
+
 #include <wpi/SmallVector.h>
-#include <wpi/span.h>
+#include <wpi/deprecated.h>
 
 #include "frc2/command/CommandBase.h"
 #include "frc2/command/CommandHelper.h"
@@ -28,15 +31,16 @@
    * initialized, and ends when they are all no longer scheduled.
    *
    * @param toSchedule the commands to schedule
+   * @deprecated Replace with {@link ProxyCommand},
+   * composing multiple of them in a {@link ParallelRaceGroup} if needed.
    */
-  explicit ProxyScheduleCommand(wpi::span<Command* const> toSchedule);
+  WPI_DEPRECATED("Replace with ProxyCommand")
+  explicit ProxyScheduleCommand(std::span<Command* const> toSchedule);
 
   explicit ProxyScheduleCommand(Command* toSchedule);
 
   ProxyScheduleCommand(ProxyScheduleCommand&& other) = default;
 
-  ProxyScheduleCommand(const ProxyScheduleCommand& other) = default;
-
   void Initialize() override;
 
   void End(bool interrupted) override;
@@ -47,6 +51,7 @@
 
  private:
   wpi::SmallVector<Command*, 4> m_toSchedule;
+  std::unique_ptr<Command> m_owning;
   bool m_finished{false};
 };
 }  // namespace frc2
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/RamseteCommand.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/RamseteCommand.h
index 73c5527..d375e11 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/RamseteCommand.h
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/RamseteCommand.h
@@ -7,6 +7,7 @@
 #include <functional>
 #include <initializer_list>
 #include <memory>
+#include <span>
 
 #include <frc/Timer.h>
 #include <frc/controller/PIDController.h>
@@ -17,7 +18,6 @@
 #include <frc/trajectory/Trajectory.h>
 #include <units/length.h>
 #include <units/voltage.h>
-#include <wpi/span.h>
 
 #include "frc2/command/CommandBase.h"
 #include "frc2/command/CommandHelper.h"
@@ -116,7 +116,7 @@
                  frc2::PIDController leftController,
                  frc2::PIDController rightController,
                  std::function<void(units::volt_t, units::volt_t)> output,
-                 wpi::span<Subsystem* const> requirements = {});
+                 std::span<Subsystem* const> requirements = {});
 
   /**
    * Constructs a new RamseteCommand that, when executed, will follow the
@@ -164,7 +164,7 @@
                  std::function<void(units::meters_per_second_t,
                                     units::meters_per_second_t)>
                      output,
-                 wpi::span<Subsystem* const> requirements = {});
+                 std::span<Subsystem* const> requirements = {});
 
   void Initialize() override;
 
@@ -174,6 +174,8 @@
 
   bool IsFinished() override;
 
+  void InitSendable(wpi::SendableBuilder& builder) override;
+
  private:
   frc::Trajectory m_trajectory;
   std::function<frc::Pose2d()> m_pose;
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/RepeatCommand.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/RepeatCommand.h
new file mode 100644
index 0000000..5d353b9
--- /dev/null
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/RepeatCommand.h
@@ -0,0 +1,83 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#ifdef _WIN32
+#pragma warning(push)
+#pragma warning(disable : 4521)
+#endif
+
+#include <memory>
+#include <utility>
+
+#include "frc2/command/CommandBase.h"
+#include "frc2/command/CommandHelper.h"
+
+namespace frc2 {
+/**
+ * A command that runs another command repeatedly, restarting it when it ends,
+ * until this command is interrupted. Command instances that are passed to it
+ * cannot be added to any other groups, or scheduled individually.
+ *
+ * <p>The rules for command compositions apply: command instances that are
+ * passed to it are owned by the composition and cannot be added to any other
+ * composition or scheduled individually, and the composition requires all
+ * subsystems its components require.
+ *
+ * <p>This class is provided by the NewCommands VendorDep
+ */
+class RepeatCommand : public CommandHelper<CommandBase, RepeatCommand> {
+ public:
+  /**
+   * Creates a new RepeatCommand. Will run another command repeatedly,
+   * restarting it whenever it ends, until this command is interrupted.
+   *
+   * @param command the command to run repeatedly
+   */
+  explicit RepeatCommand(std::unique_ptr<Command>&& command);
+
+  /**
+   * Creates a new RepeatCommand. Will run another command repeatedly,
+   * restarting it whenever it ends, until this command is interrupted.
+   *
+   * @param command the command to run repeatedly
+   */
+  template <class T, typename = std::enable_if_t<std::is_base_of_v<
+                         Command, std::remove_reference_t<T>>>>
+  explicit RepeatCommand(T&& command)
+      : RepeatCommand(std::make_unique<std::remove_reference_t<T>>(
+            std::forward<T>(command))) {}
+
+  RepeatCommand(RepeatCommand&& other) = default;
+
+  // No copy constructors for command groups
+  RepeatCommand(const RepeatCommand& other) = delete;
+
+  // Prevent template expansion from emulating copy ctor
+  RepeatCommand(RepeatCommand&) = delete;
+
+  void Initialize() override;
+
+  void Execute() override;
+
+  bool IsFinished() override;
+
+  void End(bool interrupted) override;
+
+  bool RunsWhenDisabled() const override;
+
+  Command::InterruptionBehavior GetInterruptionBehavior() const override;
+
+  void InitSendable(wpi::SendableBuilder& builder) override;
+
+ private:
+  std::unique_ptr<Command> m_command;
+  bool m_ended;
+};
+}  // namespace frc2
+
+#ifdef _WIN32
+#pragma warning(pop)
+#endif
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/RunCommand.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/RunCommand.h
index b9e1efd..3bfecf7 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/RunCommand.h
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/RunCommand.h
@@ -6,11 +6,10 @@
 
 #include <functional>
 #include <initializer_list>
+#include <span>
 
-#include <wpi/span.h>
-
-#include "frc2/command/CommandBase.h"
 #include "frc2/command/CommandHelper.h"
+#include "frc2/command/FunctionalCommand.h"
 
 namespace frc2 {
 /**
@@ -21,7 +20,7 @@
  *
  * This class is provided by the NewCommands VendorDep
  */
-class RunCommand : public CommandHelper<CommandBase, RunCommand> {
+class RunCommand : public CommandHelper<FunctionalCommand, RunCommand> {
  public:
   /**
    * Creates a new RunCommand.  The Runnable will be run continuously until the
@@ -41,15 +40,10 @@
    * @param requirements the subsystems to require
    */
   explicit RunCommand(std::function<void()> toRun,
-                      wpi::span<Subsystem* const> requirements = {});
+                      std::span<Subsystem* const> requirements = {});
 
   RunCommand(RunCommand&& other) = default;
 
   RunCommand(const RunCommand& other) = default;
-
-  void Execute() override;
-
- protected:
-  std::function<void()> m_toRun;
 };
 }  // namespace frc2
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/ScheduleCommand.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/ScheduleCommand.h
index b099fb3..63cc3b3 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/ScheduleCommand.h
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/ScheduleCommand.h
@@ -4,8 +4,9 @@
 
 #pragma once
 
+#include <span>
+
 #include <wpi/SmallVector.h>
-#include <wpi/span.h>
 
 #include "frc2/command/CommandBase.h"
 #include "frc2/command/CommandHelper.h"
@@ -13,10 +14,10 @@
 
 namespace frc2 {
 /**
- * Schedules the given commands when this command is initialized.  Useful for
- * forking off from CommandGroups.  Note that if run from a CommandGroup, the
- * group will not know about the status of the scheduled commands, and will
- * treat this command as finishing instantly.
+ * Schedules the given commands when this command is initialized. Useful for
+ * forking off from CommandGroups. Note that if run from a composition, the
+ * composition will not know about the status of the scheduled commands, and
+ * will treat this command as finishing instantly.
  *
  * This class is provided by the NewCommands VendorDep
  */
@@ -28,7 +29,7 @@
    *
    * @param toSchedule the commands to schedule
    */
-  explicit ScheduleCommand(wpi::span<Command* const> toSchedule);
+  explicit ScheduleCommand(std::span<Command* const> toSchedule);
 
   explicit ScheduleCommand(Command* toSchedule);
 
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/SelectCommand.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/SelectCommand.h
index 6e1b2bd..7079afe 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/SelectCommand.h
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/SelectCommand.h
@@ -10,31 +10,27 @@
 #endif
 
 #include <memory>
+#include <string>
 #include <type_traits>
 #include <unordered_map>
 #include <utility>
 #include <vector>
 
+#include <wpi/sendable/SendableBuilder.h>
+
 #include "frc2/command/CommandBase.h"
-#include "frc2/command/CommandGroupBase.h"
 #include "frc2/command/PrintCommand.h"
 
 namespace frc2 {
 /**
- * Runs one of a selection of commands, either using a selector and a key to
- * command mapping, or a supplier that returns the command directly at runtime.
- * Does not actually schedule the selected command - rather, the command is run
- * through this command; this ensures that the command will behave as expected
- * if used as part of a CommandGroup.  Requires the requirements of all included
- * commands, again to ensure proper functioning when used in a CommandGroup.  If
- * this is undesired, consider using ScheduleCommand.
+ * A command composition that runs one of a selection of commands, either using
+ * a selector and a key to command mapping, or a supplier that returns the
+ * command directly at runtime.
  *
- * <p>As this command contains multiple component commands within it, it is
- * technically a command group; the command instances that are passed to it
- * cannot be added to any other groups, or scheduled individually.
- *
- * <p>As a rule, CommandGroups require the union of the requirements of their
- * component commands.
+ * <p>The rules for command compositions apply: command instances that are
+ * passed to it are owned by the composition and cannot be added to any other
+ * composition or scheduled individually, and the composition requires all
+ * subsystems its components require.
  *
  * This class is provided by the NewCommands VendorDep
  */
@@ -42,7 +38,7 @@
 class SelectCommand : public CommandHelper<CommandBase, SelectCommand<Key>> {
  public:
   /**
-   * Creates a new selectcommand.
+   * Creates a new SelectCommand.
    *
    * @param commands the map of commands to choose from
    * @param selector the selector to determine which command to run
@@ -61,14 +57,16 @@
      ...);
 
     for (auto&& command : foo) {
-      if (!CommandGroupBase::RequireUngrouped(*command.second)) {
-        return;
-      }
+      CommandScheduler::GetInstance().RequireUngrouped(command.second.get());
     }
 
     for (auto&& command : foo) {
       this->AddRequirements(command.second->GetRequirements());
       m_runsWhenDisabled &= command.second->RunsWhenDisabled();
+      if (command.second->GetInterruptionBehavior() ==
+          Command::InterruptionBehavior::kCancelSelf) {
+        m_interruptBehavior = Command::InterruptionBehavior::kCancelSelf;
+      }
       m_commands.emplace(std::move(command.first), std::move(command.second));
     }
   }
@@ -78,14 +76,16 @@
       std::vector<std::pair<Key, std::unique_ptr<Command>>>&& commands)
       : m_selector{std::move(selector)} {
     for (auto&& command : commands) {
-      if (!CommandGroupBase::RequireUngrouped(*command.second)) {
-        return;
-      }
+      CommandScheduler::GetInstance().RequireUngrouped(command.second.get());
     }
 
     for (auto&& command : commands) {
       this->AddRequirements(command.second->GetRequirements());
       m_runsWhenDisabled &= command.second->RunsWhenDisabled();
+      if (command.second->GetInterruptionBehavior() ==
+          Command::InterruptionBehavior::kCancelSelf) {
+        m_interruptBehavior = Command::InterruptionBehavior::kCancelSelf;
+      }
       m_commands.emplace(std::move(command.first), std::move(command.second));
     }
   }
@@ -100,7 +100,10 @@
    * Creates a new selectcommand.
    *
    * @param toRun a supplier providing the command to run
+   * @deprecated Replace with {@link ProxyCommand},
+   * composing multiple of them in a {@link ParallelRaceGroup} if needed.
    */
+  WPI_DEPRECATED("Replace with ProxyCommand")
   explicit SelectCommand(std::function<Command*()> toRun)
       : m_toRun{std::move(toRun)} {}
 
@@ -118,6 +121,25 @@
 
   bool RunsWhenDisabled() const override { return m_runsWhenDisabled; }
 
+  Command::InterruptionBehavior GetInterruptionBehavior() const override {
+    return m_interruptBehavior;
+  }
+
+  void InitSendable(wpi::SendableBuilder& builder) override {
+    CommandBase::InitSendable(builder);
+
+    builder.AddStringProperty(
+        "selected",
+        [this] {
+          if (m_selectedCommand) {
+            return m_selectedCommand->GetName();
+          } else {
+            return std::string{"null"};
+          }
+        },
+        nullptr);
+  }
+
  protected:
   std::unique_ptr<Command> TransferOwnership() && override {
     return std::make_unique<SelectCommand>(std::move(*this));
@@ -129,6 +151,8 @@
   std::function<Command*()> m_toRun;
   Command* m_selectedCommand;
   bool m_runsWhenDisabled = true;
+  Command::InterruptionBehavior m_interruptBehavior{
+      Command::InterruptionBehavior::kCancelIncoming};
 };
 
 template <typename T>
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/SequentialCommandGroup.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/SequentialCommandGroup.h
index 928af8e..ba85b6a 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/SequentialCommandGroup.h
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/SequentialCommandGroup.h
@@ -11,12 +11,11 @@
 
 #include <limits>
 #include <memory>
+#include <span>
 #include <type_traits>
 #include <utility>
 #include <vector>
 
-#include <wpi/span.h>
-
 #include "frc2/command/CommandGroupBase.h"
 #include "frc2/command/CommandHelper.h"
 
@@ -25,10 +24,12 @@
 const size_t invalid_index = std::numeric_limits<size_t>::max();
 
 /**
- * A CommandGroups that runs a list of commands in sequence.
+ * A command composition that runs a list of commands in sequence.
  *
- * <p>As a rule, CommandGroups require the union of the requirements of their
- * component commands.
+ * <p>The rules for command compositions apply: command instances that are
+ * passed to it are owned by the composition and cannot be added to any other
+ * composition or scheduled individually, and the composition requires all
+ * subsystems its components require.
  *
  * This class is provided by the NewCommands VendorDep
  */
@@ -36,21 +37,21 @@
     : public CommandHelper<CommandGroupBase, SequentialCommandGroup> {
  public:
   /**
-   * Creates a new SequentialCommandGroup.  The given commands will be run
-   * sequentially, with the CommandGroup finishing when the last command
+   * Creates a new SequentialCommandGroup. The given commands will be run
+   * sequentially, with the composition finishing when the last command
    * finishes.
    *
-   * @param commands the commands to include in this group.
+   * @param commands the commands to include in this composition.
    */
   explicit SequentialCommandGroup(
       std::vector<std::unique_ptr<Command>>&& commands);
 
   /**
-   * Creates a new SequentialCommandGroup.  The given commands will be run
-   * sequentially, with the CommandGroup finishing when the last command
+   * Creates a new SequentialCommandGroup. The given commands will be run
+   * sequentially, with the composition finishing when the last command
    * finishes.
    *
-   * @param commands the commands to include in this group.
+   * @param commands the commands to include in this composition.
    */
   template <class... Types,
             typename = std::enable_if_t<std::conjunction_v<
@@ -78,25 +79,19 @@
     AddCommands(std::move(foo));
   }
 
-  void Initialize() override;
+  void Initialize() final;
 
-  void Execute() override;
+  void Execute() final;
 
-  void End(bool interrupted) override;
+  void End(bool interrupted) final;
 
-  bool IsFinished() override;
+  bool IsFinished() final;
 
   bool RunsWhenDisabled() const override;
 
-  SequentialCommandGroup BeforeStarting(
-      std::function<void()> toRun,
-      wpi::span<Subsystem* const> requirements = {}) &&
-      override;
+  Command::InterruptionBehavior GetInterruptionBehavior() const override;
 
-  SequentialCommandGroup AndThen(
-      std::function<void()> toRun,
-      wpi::span<Subsystem* const> requirements = {}) &&
-      override;
+  void InitSendable(wpi::SendableBuilder& builder) override;
 
  private:
   void AddCommands(std::vector<std::unique_ptr<Command>>&& commands) final;
@@ -104,6 +99,8 @@
   wpi::SmallVector<std::unique_ptr<Command>, 4> m_commands;
   size_t m_currentCommandIndex{invalid_index};
   bool m_runWhenDisabled{true};
+  Command::InterruptionBehavior m_interruptBehavior{
+      Command::InterruptionBehavior::kCancelIncoming};
 };
 }  // namespace frc2
 
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/SetUtilities.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/SetUtilities.h
index d40fbec..e70e17b 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/SetUtilities.h
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/SetUtilities.h
@@ -4,12 +4,13 @@
 
 #pragma once
 
+#include <span>
+
 #include <wpi/SmallVector.h>
-#include <wpi/span.h>
 
 namespace frc2 {
 template <typename T>
-void SetInsert(wpi::SmallVectorImpl<T*>& vector, wpi::span<T* const> toAdd) {
+void SetInsert(wpi::SmallVectorImpl<T*>& vector, std::span<T* const> toAdd) {
   for (auto addCommand : toAdd) {
     bool exists = false;
     for (auto existingCommand : vector) {
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/StartEndCommand.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/StartEndCommand.h
index e5af2bb..b1f56b2 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/StartEndCommand.h
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/StartEndCommand.h
@@ -6,11 +6,10 @@
 
 #include <functional>
 #include <initializer_list>
+#include <span>
 
-#include <wpi/span.h>
-
-#include "frc2/command/CommandBase.h"
 #include "frc2/command/CommandHelper.h"
+#include "frc2/command/FunctionalCommand.h"
 
 namespace frc2 {
 /**
@@ -22,7 +21,8 @@
  *
  * This class is provided by the NewCommands VendorDep
  */
-class StartEndCommand : public CommandHelper<CommandBase, StartEndCommand> {
+class StartEndCommand
+    : public CommandHelper<FunctionalCommand, StartEndCommand> {
  public:
   /**
    * Creates a new StartEndCommand.  Will run the given runnables when the
@@ -44,18 +44,10 @@
    * @param requirements the subsystems required by this command
    */
   StartEndCommand(std::function<void()> onInit, std::function<void()> onEnd,
-                  wpi::span<Subsystem* const> requirements = {});
+                  std::span<Subsystem* const> requirements = {});
 
   StartEndCommand(StartEndCommand&& other) = default;
 
-  StartEndCommand(const StartEndCommand& other);
-
-  void Initialize() override;
-
-  void End(bool interrupted) override;
-
- protected:
-  std::function<void()> m_onInit;
-  std::function<void()> m_onEnd;
+  StartEndCommand(const StartEndCommand& other) = default;
 };
 }  // namespace frc2
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/Subsystem.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/Subsystem.h
index 7ee9950..0c3a2a3 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/Subsystem.h
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/Subsystem.h
@@ -11,6 +11,7 @@
 
 namespace frc2 {
 class Command;
+class CommandPtr;
 /**
  * A robot subsystem.  Subsystems are the basic unit of robot organization in
  * the Command-based framework; they encapsulate low-level hardware objects
@@ -37,7 +38,7 @@
  */
 class Subsystem {
  public:
-  ~Subsystem();
+  virtual ~Subsystem();
   /**
    * This method is called periodically by the CommandScheduler.  Useful for
    * updating subsystem-specific state that you don't want to offload to a
@@ -72,6 +73,17 @@
   }
 
   /**
+   * Sets the default Command of the subsystem.  The default command will be
+   * automatically scheduled when no other commands are scheduled that require
+   * the subsystem. Default commands should generally not end on their own, i.e.
+   * their IsFinished() method should always return false.  Will automatically
+   * register this subsystem with the CommandScheduler.
+   *
+   * @param defaultCommand the default command to associate with this subsystem
+   */
+  void SetDefaultCommand(CommandPtr&& defaultCommand);
+
+  /**
    * Gets the default command for this subsystem.  Returns null if no default
    * command is currently associated with the subsystem.
    *
@@ -92,5 +104,41 @@
    * Periodic() method to be called when the scheduler runs.
    */
   void Register();
+
+  /**
+   * Constructs a command that runs an action once and finishes. Requires this
+   * subsystem.
+   *
+   * @param action the action to run
+   */
+  [[nodiscard]] CommandPtr RunOnce(std::function<void()> action);
+
+  /**
+   * Constructs a command that runs an action every iteration until interrupted.
+   * Requires this subsystem.
+   *
+   * @param action the action to run
+   */
+  [[nodiscard]] CommandPtr Run(std::function<void()> action);
+
+  /**
+   * Constructs a command that runs an action once and another action when the
+   * command is interrupted. Requires this subsystem.
+   *
+   * @param start the action to run on start
+   * @param end the action to run on interrupt
+   */
+  [[nodiscard]] CommandPtr StartEnd(std::function<void()> start,
+                                    std::function<void()> end);
+
+  /**
+   * Constructs a command that runs an action every iteration until interrupted,
+   * and then runs a second action. Requires this subsystem.
+   *
+   * @param run the action to run every iteration
+   * @param end the action to run on interrupt
+   */
+  [[nodiscard]] CommandPtr RunEnd(std::function<void()> run,
+                                  std::function<void()> end);
 };
 }  // namespace frc2
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/SwerveControllerCommand.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/SwerveControllerCommand.h
index 212beb5..d51ae1e 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/SwerveControllerCommand.h
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/SwerveControllerCommand.h
@@ -6,6 +6,7 @@
 #include <functional>
 #include <initializer_list>
 #include <memory>
+#include <span>
 
 #include <frc/Timer.h>
 #include <frc/controller/HolonomicDriveController.h>
@@ -19,7 +20,6 @@
 #include <units/length.h>
 #include <units/time.h>
 #include <units/voltage.h>
-#include <wpi/span.h>
 
 #include "CommandBase.h"
 #include "CommandHelper.h"
@@ -169,7 +169,7 @@
       std::function<frc::Rotation2d()> desiredRotation,
       std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
           output,
-      wpi::span<Subsystem* const> requirements = {});
+      std::span<Subsystem* const> requirements = {});
 
   /**
    * Constructs a new SwerveControllerCommand that when executed will follow the
@@ -207,7 +207,132 @@
       frc::ProfiledPIDController<units::radians> thetaController,
       std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
           output,
-      wpi::span<Subsystem* const> requirements = {});
+      std::span<Subsystem* const> requirements = {});
+
+  /**
+   * Constructs a new SwerveControllerCommand that when executed will follow the
+   * provided trajectory. This command will not return output voltages but
+   * rather raw module states from the position controllers which need to be put
+   * into a velocity PID.
+   *
+   * <p>Note: The controllers will *not* set the outputVolts to zero upon
+   * completion of the path- this is left to the user, since it is not
+   * appropriate for paths with nonstationary endstates.
+   *
+   * @param trajectory      The trajectory to follow.
+   * @param pose            A function that supplies the robot pose,
+   *                        provided by the odometry class.
+   * @param kinematics      The kinematics for the robot drivetrain.
+   * @param controller      The HolonomicDriveController for the drivetrain.
+   * @param desiredRotation The angle that the drivetrain should be
+   *                        facing. This is sampled at each time step.
+   * @param output          The raw output module states from the
+   *                        position controllers.
+   * @param requirements    The subsystems to require.
+   */
+  SwerveControllerCommand(
+      frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
+      frc::SwerveDriveKinematics<NumModules> kinematics,
+      frc::HolonomicDriveController controller,
+      std::function<frc::Rotation2d()> desiredRotation,
+      std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
+          output,
+      std::initializer_list<Subsystem*> requirements);
+
+  /**
+   * Constructs a new SwerveControllerCommand that when executed will follow the
+   * provided trajectory. This command will not return output voltages but
+   * rather raw module states from the position controllers which need to be put
+   * into a velocity PID.
+   *
+   * <p>Note: The controllers will *not* set the outputVolts to zero upon
+   * completion of the path- this is left to the user, since it is not
+   * appropriate for paths with nonstationary endstates.
+   *
+   * <p>Note 2: The final rotation of the robot will be set to the rotation of
+   * the final pose in the trajectory. The robot will not follow the rotations
+   * from the poses at each timestep. If alternate rotation behavior is desired,
+   * the other constructor with a supplier for rotation should be used.
+   *
+   * @param trajectory      The trajectory to follow.
+   * @param pose            A function that supplies the robot pose,
+   *                        provided by the odometry class.
+   * @param kinematics      The kinematics for the robot drivetrain.
+   * @param controller      The HolonomicDriveController for the drivetrain.
+   * @param output          The raw output module states from the
+   *                        position controllers.
+   * @param requirements    The subsystems to require.
+   */
+  SwerveControllerCommand(
+      frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
+      frc::SwerveDriveKinematics<NumModules> kinematics,
+      frc::HolonomicDriveController controller,
+      std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
+          output,
+      std::initializer_list<Subsystem*> requirements);
+
+  /**
+   * Constructs a new SwerveControllerCommand that when executed will follow the
+   * provided trajectory. This command will not return output voltages but
+   * rather raw module states from the position controllers which need to be put
+   * into a velocity PID.
+   *
+   * <p>Note: The controllers will *not* set the outputVolts to zero upon
+   * completion of the path- this is left to the user, since it is not
+   * appropriate for paths with nonstationary endstates.
+   *
+   *
+   * @param trajectory      The trajectory to follow.
+   * @param pose            A function that supplies the robot pose,
+   *                        provided by the odometry class.
+   * @param kinematics      The kinematics for the robot drivetrain.
+   * @param controller     The HolonomicDriveController for the robot.
+   * @param desiredRotation The angle that the drivetrain should be
+   *                        facing. This is sampled at each time step.
+   * @param output          The raw output module states from the
+   *                        position controllers.
+   * @param requirements    The subsystems to require.
+   */
+  SwerveControllerCommand(
+      frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
+      frc::SwerveDriveKinematics<NumModules> kinematics,
+      frc::HolonomicDriveController controller,
+      std::function<frc::Rotation2d()> desiredRotation,
+      std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
+          output,
+      std::span<Subsystem* const> requirements = {});
+
+  /**
+   * Constructs a new SwerveControllerCommand that when executed will follow the
+   * provided trajectory. This command will not return output voltages but
+   * rather raw module states from the position controllers which need to be put
+   * into a velocity PID.
+   *
+   * <p>Note: The controllers will *not* set the outputVolts to zero upon
+   * completion of the path- this is left to the user, since it is not
+   * appropriate for paths with nonstationary endstates.
+   *
+   * <p>Note 2: The final rotation of the robot will be set to the rotation of
+   * the final pose in the trajectory. The robot will not follow the rotations
+   * from the poses at each timestep. If alternate rotation behavior is desired,
+   * the other constructor with a supplier for rotation should be used.
+   *
+   * @param trajectory      The trajectory to follow.
+   * @param pose            A function that supplies the robot pose,
+   *                        provided by the odometry class.
+   * @param kinematics      The kinematics for the robot drivetrain.
+   * @param controller      The HolonomicDriveController for the drivetrain.
+   * @param output          The raw output module states from the
+   *                        position controllers.
+   * @param requirements    The subsystems to require.
+   */
+  SwerveControllerCommand(
+      frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
+      frc::SwerveDriveKinematics<NumModules> kinematics,
+      frc::HolonomicDriveController controller,
+      std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
+          output,
+      std::span<Subsystem* const> requirements = {});
 
   void Initialize() override;
 
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/SwerveControllerCommand.inc b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/SwerveControllerCommand.inc
index d1c6e78..a644057 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/SwerveControllerCommand.inc
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/SwerveControllerCommand.inc
@@ -53,7 +53,7 @@
     frc::ProfiledPIDController<units::radians> thetaController,
     std::function<frc::Rotation2d()> desiredRotation,
     std::function<void(std::array<frc::SwerveModuleState, NumModules>)> output,
-    wpi::span<Subsystem* const> requirements)
+    std::span<Subsystem* const> requirements)
     : m_trajectory(std::move(trajectory)),
       m_pose(std::move(pose)),
       m_kinematics(kinematics),
@@ -70,7 +70,7 @@
     frc2::PIDController xController, frc2::PIDController yController,
     frc::ProfiledPIDController<units::radians> thetaController,
     std::function<void(std::array<frc::SwerveModuleState, NumModules>)> output,
-    wpi::span<Subsystem* const> requirements)
+    std::span<Subsystem* const> requirements)
     : m_trajectory(std::move(trajectory)),
       m_pose(std::move(pose)),
       m_kinematics(kinematics),
@@ -80,6 +80,70 @@
 }
 
 template <size_t NumModules>
+SwerveControllerCommand<NumModules>::SwerveControllerCommand(
+    frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
+    frc::SwerveDriveKinematics<NumModules> kinematics,
+    frc::HolonomicDriveController controller,
+    std::function<frc::Rotation2d()> desiredRotation,
+    std::function<void(std::array<frc::SwerveModuleState, NumModules>)> output,
+    std::initializer_list<Subsystem*> requirements)
+    : m_trajectory(std::move(trajectory)),
+      m_pose(std::move(pose)),
+      m_kinematics(kinematics),
+      m_controller(std::move(controller)),
+      m_desiredRotation(std::move(desiredRotation)),
+      m_outputStates(output) {
+  this->AddRequirements(requirements);
+}
+
+template <size_t NumModules>
+SwerveControllerCommand<NumModules>::SwerveControllerCommand(
+    frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
+    frc::SwerveDriveKinematics<NumModules> kinematics,
+    frc::HolonomicDriveController controller,
+    std::function<void(std::array<frc::SwerveModuleState, NumModules>)> output,
+    std::initializer_list<Subsystem*> requirements)
+    : m_trajectory(std::move(trajectory)),
+      m_pose(std::move(pose)),
+      m_kinematics(kinematics),
+      m_controller(std::move(controller)),
+      m_outputStates(output) {
+  this->AddRequirements(requirements);
+}
+
+template <size_t NumModules>
+SwerveControllerCommand<NumModules>::SwerveControllerCommand(
+    frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
+    frc::SwerveDriveKinematics<NumModules> kinematics,
+    frc::HolonomicDriveController controller,
+    std::function<frc::Rotation2d()> desiredRotation,
+    std::function<void(std::array<frc::SwerveModuleState, NumModules>)> output,
+    std::span<Subsystem* const> requirements)
+    : m_trajectory(std::move(trajectory)),
+      m_pose(std::move(pose)),
+      m_kinematics(kinematics),
+      m_controller(std::move(controller)),
+      m_desiredRotation(std::move(desiredRotation)),
+      m_outputStates(output) {
+  this->AddRequirements(requirements);
+}
+
+template <size_t NumModules>
+SwerveControllerCommand<NumModules>::SwerveControllerCommand(
+    frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
+    frc::SwerveDriveKinematics<NumModules> kinematics,
+    frc::HolonomicDriveController controller,
+    std::function<void(std::array<frc::SwerveModuleState, NumModules>)> output,
+    std::span<Subsystem* const> requirements)
+    : m_trajectory(std::move(trajectory)),
+      m_pose(std::move(pose)),
+      m_kinematics(kinematics),
+      m_controller(std::move(controller)),
+      m_outputStates(output) {
+  this->AddRequirements(requirements);
+}
+
+template <size_t NumModules>
 void SwerveControllerCommand<NumModules>::Initialize() {
   if (m_desiredRotation == nullptr) {
     m_desiredRotation = [&] {
@@ -92,7 +156,7 @@
 
 template <size_t NumModules>
 void SwerveControllerCommand<NumModules>::Execute() {
-  auto curTime = units::second_t(m_timer.Get());
+  auto curTime = m_timer.Get();
   auto m_desiredState = m_trajectory.Sample(curTime);
 
   auto targetChassisSpeeds =
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/TrapezoidProfileCommand.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/TrapezoidProfileCommand.h
index 3a609be..413553b 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/TrapezoidProfileCommand.h
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/TrapezoidProfileCommand.h
@@ -6,10 +6,10 @@
 
 #include <functional>
 #include <initializer_list>
+#include <span>
 
 #include <frc/Timer.h>
 #include <frc/trajectory/TrapezoidProfile.h>
-#include <wpi/span.h>
 
 #include "frc2/command/CommandBase.h"
 #include "frc2/command/CommandHelper.h"
@@ -58,7 +58,7 @@
    */
   TrapezoidProfileCommand(frc::TrapezoidProfile<Distance> profile,
                           std::function<void(State)> output,
-                          wpi::span<Subsystem* const> requirements = {})
+                          std::span<Subsystem* const> requirements = {})
       : m_profile(profile), m_output(output) {
     this->AddRequirements(requirements);
   }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/WaitCommand.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/WaitCommand.h
index 4670d53..54eddfb 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/WaitCommand.h
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/WaitCommand.h
@@ -40,6 +40,8 @@
 
   bool RunsWhenDisabled() const override;
 
+  void InitSendable(wpi::SendableBuilder& builder) override;
+
  protected:
   frc::Timer m_timer;
 
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/WrapperCommand.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/WrapperCommand.h
new file mode 100644
index 0000000..71dd02f
--- /dev/null
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/WrapperCommand.h
@@ -0,0 +1,77 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#ifdef _WIN32
+#pragma warning(push)
+#pragma warning(disable : 4521)
+#endif
+
+#include <memory>
+#include <utility>
+
+#include "frc2/command/CommandBase.h"
+#include "frc2/command/CommandHelper.h"
+
+namespace frc2 {
+/**
+ * A class used internally to wrap commands while overriding a specific method;
+ * all other methods will call through to the wrapped command.
+ *
+ * <p>Wrapped commands may only be used through the wrapper, trying to directly
+ * schedule them or add them to a group will throw an exception.
+ */
+class WrapperCommand : public CommandHelper<CommandBase, WrapperCommand> {
+ public:
+  /**
+   * Wrap a command.
+   *
+   * @param command the command being wrapped. Trying to directly schedule this
+   * command or add it to a group will throw an exception.
+   */
+  explicit WrapperCommand(std::unique_ptr<Command>&& command);
+
+  /**
+   * Wrap a command.
+   *
+   * @param command the command being wrapped. Trying to directly schedule this
+   * command or add it to a group will throw an exception.
+   */
+  template <class T, typename = std::enable_if_t<std::is_base_of_v<
+                         Command, std::remove_reference_t<T>>>>
+  explicit WrapperCommand(T&& command)
+      : WrapperCommand(std::make_unique<std::remove_reference_t<T>>(
+            std::forward<T>(command))) {}
+
+  WrapperCommand(WrapperCommand&& other) = default;
+
+  // No copy constructors for command groups
+  WrapperCommand(const WrapperCommand& other) = delete;
+
+  // Prevent template expansion from emulating copy ctor
+  WrapperCommand(WrapperCommand&) = delete;
+
+  void Initialize() override;
+
+  void Execute() override;
+
+  bool IsFinished() override;
+
+  void End(bool interrupted) override;
+
+  bool RunsWhenDisabled() const override;
+
+  InterruptionBehavior GetInterruptionBehavior() const override;
+
+  wpi::SmallSet<Subsystem*, 4> GetRequirements() const override;
+
+ protected:
+  std::unique_ptr<Command> m_command;
+};
+}  // namespace frc2
+
+#ifdef _WIN32
+#pragma warning(pop)
+#endif
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/button/Button.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/button/Button.h
index 12a5aa7..0142c44 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/button/Button.h
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/button/Button.h
@@ -6,11 +6,13 @@
 
 #include <functional>
 #include <initializer_list>
+#include <span>
 #include <utility>
 
-#include <wpi/span.h>
+#include <wpi/deprecated.h>
 
 #include "Trigger.h"
+#include "frc2/command/CommandPtr.h"
 
 namespace frc2 {
 class Command;
@@ -28,13 +30,17 @@
    * Create a new button that is pressed when the given condition is true.
    *
    * @param isPressed Whether the button is pressed.
+   * @deprecated Replace with Trigger
    */
+  WPI_DEPRECATED("Replace with Trigger")
   explicit Button(std::function<bool()> isPressed);
 
   /**
    * Create a new button that is pressed active (default constructor) - activity
    *  can be further determined by subclass code.
+   * @deprecated Replace with Trigger
    */
+  WPI_DEPRECATED("Replace with Trigger")
   Button() = default;
 
   /**
@@ -43,10 +49,11 @@
    * of the command.
    *
    * @param command The command to bind.
-   * @param interruptible Whether the command should be interruptible.
    * @return The trigger, for chained calls.
+   * @deprecated Replace with Trigger::OnTrue()
    */
-  Button WhenPressed(Command* command, bool interruptible = true);
+  WPI_DEPRECATED("Replace with Trigger#OnTrue()")
+  Button WhenPressed(Command* command);
 
   /**
    * Binds a command to start when the button is pressed.  Transfers
@@ -55,13 +62,14 @@
    * *copied.*
    *
    * @param command The command to bind.
-   * @param interruptible Whether the command should be interruptible.
    * @return The trigger, for chained calls.
+   * @deprecated Replace with Trigger::OnTrue()
    */
   template <class T, typename = std::enable_if_t<std::is_base_of_v<
                          Command, std::remove_reference_t<T>>>>
-  Button WhenPressed(T&& command, bool interruptible = true) {
-    WhenActive(std::forward<T>(command), interruptible);
+  WPI_DEPRECATED("Replace with Trigger#OnTrue()")
+  Button WhenPressed(T&& command) {
+    WhenActive(std::forward<T>(command));
     return *this;
   }
 
@@ -70,7 +78,9 @@
    *
    * @param toRun the runnable to execute.
    * @param requirements the required subsystems.
+   * @deprecated Replace with Trigger::OnTrue(cmd::RunOnce())
    */
+  WPI_DEPRECATED("Replace with Trigger#OnTrue(cmd::RunOnce())")
   Button WhenPressed(std::function<void()> toRun,
                      std::initializer_list<Subsystem*> requirements);
 
@@ -79,9 +89,11 @@
    *
    * @param toRun the runnable to execute.
    * @param requirements the required subsystems.
+   * @deprecated Replace with Trigger::OnTrue(cmd::RunOnce())
    */
+  WPI_DEPRECATED("Replace with Trigger#OnTrue(cmd::RunOnce())")
   Button WhenPressed(std::function<void()> toRun,
-                     wpi::span<Subsystem* const> requirements = {});
+                     std::span<Subsystem* const> requirements = {});
 
   /**
    * Binds a command to be started repeatedly while the button is pressed, and
@@ -89,10 +101,11 @@
    * users are responsible for the lifespan of the command.
    *
    * @param command The command to bind.
-   * @param interruptible Whether the command should be interruptible.
    * @return The button, for chained calls.
+   * @deprecated Replace with Trigger::WhileTrue(command.Repeatedly())
    */
-  Button WhileHeld(Command* command, bool interruptible = true);
+  WPI_DEPRECATED("Replace with Trigger#WhileTrue(command.Repeatedly())")
+  Button WhileHeld(Command* command);
 
   /**
    * Binds a command to be started repeatedly while the button is pressed, and
@@ -101,13 +114,14 @@
    * will be *moved*, lvalue refs will be *copied.*
    *
    * @param command The command to bind.
-   * @param interruptible Whether the command should be interruptible.
    * @return The button, for chained calls.
+   * @deprecated Replace with Trigger::WhileTrue(command.Repeatedly())
    */
   template <class T, typename = std::enable_if_t<std::is_base_of_v<
                          Command, std::remove_reference_t<T>>>>
-  Button WhileHeld(T&& command, bool interruptible = true) {
-    WhileActiveContinous(std::forward<T>(command), interruptible);
+  WPI_DEPRECATED("Replace with Trigger#WhileTrue(command.Repeatedly())")
+  Button WhileHeld(T&& command) {
+    WhileActiveContinous(std::forward<T>(command));
     return *this;
   }
 
@@ -116,7 +130,9 @@
    *
    * @param toRun the runnable to execute.
    * @param requirements the required subsystems.
+   * @deprecated Replace with Trigger::WhileTrue(cmd::Run())
    */
+  WPI_DEPRECATED("Replace with Trigger#WhileTrue(cmd::Run())")
   Button WhileHeld(std::function<void()> toRun,
                    std::initializer_list<Subsystem*> requirements);
 
@@ -125,9 +141,11 @@
    *
    * @param toRun the runnable to execute.
    * @param requirements the required subsystems.
+   * @deprecated Replace with Trigger::WhileTrue(cmd::Run())
    */
+  WPI_DEPRECATED("Replace with Trigger#WhileTrue(cmd::Run())")
   Button WhileHeld(std::function<void()> toRun,
-                   wpi::span<Subsystem* const> requirements = {});
+                   std::span<Subsystem* const> requirements = {});
 
   /**
    * Binds a command to be started when the button is pressed, and canceled
@@ -135,10 +153,11 @@
    * responsible for the lifespan of the command.
    *
    * @param command The command to bind.
-   * @param interruptible Whether the command should be interruptible.
    * @return The button, for chained calls.
+   * @deprecated Replace with Trigger::WhileTrue()
    */
-  Button WhenHeld(Command* command, bool interruptible = true);
+  WPI_DEPRECATED("Replace with Trigger#WhileTrue()")
+  Button WhenHeld(Command* command);
 
   /**
    * Binds a command to be started when the button is pressed, and canceled
@@ -147,13 +166,14 @@
    * *moved*, lvalue refs will be *copied.*
    *
    * @param command The command to bind.
-   * @param interruptible Whether the command should be interruptible.
    * @return The button, for chained calls.
+   * @deprecated Replace with Trigger::WhileTrue()
    */
   template <class T, typename = std::enable_if_t<std::is_base_of_v<
                          Command, std::remove_reference_t<T>>>>
-  Button WhenHeld(T&& command, bool interruptible = true) {
-    WhileActiveOnce(std::forward<T>(command), interruptible);
+  WPI_DEPRECATED("Replace with Trigger#WhileTrue()")
+  Button WhenHeld(T&& command) {
+    WhileActiveOnce(std::forward<T>(command));
     return *this;
   }
 
@@ -163,10 +183,11 @@
    * of the command.
    *
    * @param command The command to bind.
-   * @param interruptible Whether the command should be interruptible.
    * @return The button, for chained calls.
+   * @deprecated Replace with Trigger::OnFalse()
    */
-  Button WhenReleased(Command* command, bool interruptible = true);
+  WPI_DEPRECATED("Replace with Trigger#OnFalse()")
+  Button WhenReleased(Command* command);
 
   /**
    * Binds a command to start when the button is pressed.  Transfers
@@ -175,13 +196,14 @@
    * *copied.*
    *
    * @param command The command to bind.
-   * @param interruptible Whether the command should be interruptible.
    * @return The button, for chained calls.
+   * @deprecated Replace with Trigger::OnFalse()
    */
   template <class T, typename = std::enable_if_t<std::is_base_of_v<
                          Command, std::remove_reference_t<T>>>>
-  Button WhenReleased(T&& command, bool interruptible = true) {
-    WhenInactive(std::forward<T>(command), interruptible);
+  WPI_DEPRECATED("Replace with Trigger#OnFalse()")
+  Button WhenReleased(T&& command) {
+    WhenInactive(std::forward<T>(command));
     return *this;
   }
 
@@ -190,7 +212,9 @@
    *
    * @param toRun the runnable to execute.
    * @param requirements the required subsystems.
+   * @deprecated Replace with Trigger::OnFalse(cmd::RunOnce())
    */
+  WPI_DEPRECATED("Replace with Trigger#OnFalse(cmd::RunOnce())")
   Button WhenReleased(std::function<void()> toRun,
                       std::initializer_list<Subsystem*> requirements);
 
@@ -199,9 +223,11 @@
    *
    * @param toRun the runnable to execute.
    * @param requirements the required subsystems.
+   * @deprecated Replace with Trigger::OnFalse(cmd::RunOnce())
    */
+  WPI_DEPRECATED("Replace with Trigger#OnFalse(cmd::RunOnce())")
   Button WhenReleased(std::function<void()> toRun,
-                      wpi::span<Subsystem* const> requirements = {});
+                      std::span<Subsystem* const> requirements = {});
 
   /**
    * Binds a command to start when the button is pressed, and be canceled when
@@ -209,25 +235,27 @@
    * responsible for the lifespan of the command.
    *
    * @param command The command to bind.
-   * @param interruptible Whether the command should be interruptible.
    * @return The button, for chained calls.
+   * @deprecated Replace with Trigger::ToggleOnTrue()
    */
-  Button ToggleWhenPressed(Command* command, bool interruptible = true);
+  WPI_DEPRECATED("Replace with Trigger#ToggleOnTrue()")
+  Button ToggleWhenPressed(Command* command);
 
   /**
    * Binds a command to start when the button is pressed, and be canceled when
-   * it is pessed again.  Transfers command ownership to the button scheduler,
+   * it is pressed again.  Transfers command ownership to the button scheduler,
    * so the user does not have to worry about lifespan - rvalue refs will be
    * *moved*, lvalue refs will be *copied.*
    *
    * @param command The command to bind.
-   * @param interruptible Whether the command should be interruptible.
    * @return The button, for chained calls.
+   * @deprecated Replace with Trigger::ToggleOnTrue()
    */
   template <class T, typename = std::enable_if_t<std::is_base_of_v<
                          Command, std::remove_reference_t<T>>>>
-  Button ToggleWhenPressed(T&& command, bool interruptible = true) {
-    ToggleWhenActive(std::forward<T>(command), interruptible);
+  WPI_DEPRECATED("Replace with Trigger#ToggleOnTrue()")
+  Button ToggleWhenPressed(T&& command) {
+    ToggleWhenActive(std::forward<T>(command));
     return *this;
   }
 
@@ -238,7 +266,9 @@
    *
    * @param command The command to bind.
    * @return The button, for chained calls.
+   * @deprecated Pass this as a command end condition with Until() instead.
    */
+  WPI_DEPRECATED("Pass this as a command end condition with Until() instead.")
   Button CancelWhenPressed(Command* command);
 };
 }  // namespace frc2
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/button/CommandGenericHID.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/button/CommandGenericHID.h
new file mode 100644
index 0000000..5c986dd
--- /dev/null
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/button/CommandGenericHID.h
@@ -0,0 +1,219 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+#include <frc/GenericHID.h>
+
+#include "Trigger.h"
+#include "frc2/command/CommandScheduler.h"
+
+namespace frc2 {
+/**
+ * A subclass of {@link GenericHID} with {@link Trigger} factories for
+ * command-based.
+ *
+ * @see GenericHID
+ */
+class CommandGenericHID : public frc::GenericHID {
+ public:
+  using GenericHID::GenericHID;
+
+  /**
+   * Constructs an event instance around this button's digital signal.
+   *
+   * @param button the button index
+   * @param loop the event loop instance to attach the event to. Defaults to the
+   * CommandScheduler's default loop.
+   * @return an event instance representing the button's digital signal attached
+   * to the given loop.
+   */
+  Trigger Button(int button,
+                 frc::EventLoop* loop = CommandScheduler::GetInstance()
+                                            .GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs a Trigger instance based around this angle of a POV on the HID.
+   *
+   * <p>The POV angles start at 0 in the up direction, and increase clockwise
+   * (eg right is 90, upper-left is 315).
+   *
+   * @param loop  the event loop instance to attach the event to. Defaults to
+   * {@link CommandScheduler::GetDefaultButtonLoop() the default command
+   * scheduler button loop}.
+   * @param angle POV angle in degrees, or -1 for the center / not pressed.
+   * @return a Trigger instance based around this angle of a POV on the HID.
+   */
+  Trigger POV(int angle,
+              frc::EventLoop* loop =
+                  CommandScheduler::GetInstance().GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs a Trigger instance based around this angle of a POV on the HID.
+   *
+   * <p>The POV angles start at 0 in the up direction, and increase clockwise
+   * (eg right is 90, upper-left is 315).
+   *
+   * @param loop  the event loop instance to attach the event to. Defaults to
+   * {@link CommandScheduler::GetDefaultButtonLoop() the default command
+   * scheduler button loop}.
+   * @param pov   index of the POV to read (starting at 0). Defaults to 0.
+   * @param angle POV angle in degrees, or -1 for the center / not pressed.
+   * @return a Trigger instance based around this angle of a POV on the HID.
+   */
+  Trigger POV(int pov, int angle,
+              frc::EventLoop* loop =
+                  CommandScheduler::GetInstance().GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs a Trigger instance based around the 0 degree angle (up) of the
+   * default (index 0) POV on the HID.
+   *
+   * @param loop  the event loop instance to attach the event to. Defaults to
+   * {@link CommandScheduler::GetDefaultButtonLoop() the default command
+   * scheduler button loop}.
+   * @return a Trigger instance based around the 0 degree angle of a POV on the
+   * HID.
+   */
+  Trigger POVUp(frc::EventLoop* loop = CommandScheduler::GetInstance()
+                                           .GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs a Trigger instance based around the 45 degree angle (right up)
+   * of the default (index 0) POV on the HID.
+   *
+   * @param loop  the event loop instance to attach the event to. Defaults to
+   * {@link CommandScheduler::GetDefaultButtonLoop() the default command
+   * scheduler button loop}.
+   * @return a Trigger instance based around the 45 degree angle of a POV on the
+   * HID.
+   */
+  Trigger POVUpRight(frc::EventLoop* loop = CommandScheduler::GetInstance()
+                                                .GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs a Trigger instance based around the 90 degree angle (right) of
+   * the default (index 0) POV on the HID.
+   *
+   * @param loop  the event loop instance to attach the event to. Defaults to
+   * {@link CommandScheduler::GetDefaultButtonLoop() the default command
+   * scheduler button loop}.
+   * @return a Trigger instance based around the 90 degree angle of a POV on the
+   * HID.
+   */
+  Trigger POVRight(frc::EventLoop* loop = CommandScheduler::GetInstance()
+                                              .GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs a Trigger instance based around the 135 degree angle (right
+   * down) of the default (index 0) POV on the HID.
+   *
+   * @return a Trigger instance based around the 135 degree angle of a POV on
+   * the HID.
+   */
+  Trigger POVDownRight(
+      frc::EventLoop* loop =
+          CommandScheduler::GetInstance().GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs a Trigger instance based around the 180 degree angle (down) of
+   * the default (index 0) POV on the HID.
+   *
+   * @param loop  the event loop instance to attach the event to. Defaults to
+   * {@link CommandScheduler::GetDefaultButtonLoop() the default command
+   * scheduler button loop}.
+   * @return a Trigger instance based around the 180 degree angle of a POV on
+   * the HID.
+   */
+  Trigger POVDown(frc::EventLoop* loop = CommandScheduler::GetInstance()
+                                             .GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs a Trigger instance based around the 225 degree angle (down left)
+   * of the default (index 0) POV on the HID.
+   *
+   * @param loop  the event loop instance to attach the event to. Defaults to
+   * {@link CommandScheduler::GetDefaultButtonLoop() the default command
+   * scheduler button loop}.
+   * @return a Trigger instance based around the 225 degree angle of a POV on
+   * the HID.
+   */
+  Trigger POVDownLeft(frc::EventLoop* loop = CommandScheduler::GetInstance()
+                                                 .GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs a Trigger instance based around the 270 degree angle (left) of
+   * the default (index 0) POV on the HID.
+   *
+   * @param loop  the event loop instance to attach the event to. Defaults to
+   * {@link CommandScheduler::GetDefaultButtonLoop() the default command
+   * scheduler button loop}.
+   * @return a Trigger instance based around the 270 degree angle of a POV on
+   * the HID.
+   */
+  Trigger POVLeft(frc::EventLoop* loop = CommandScheduler::GetInstance()
+                                             .GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs a Trigger instance based around the 315 degree angle (left up)
+   * of the default (index 0) POV on the HID.
+   *
+   * @param loop  the event loop instance to attach the event to. Defaults to
+   * {@link CommandScheduler::GetDefaultButtonLoop() the default command
+   * scheduler button loop}.
+   * @return a Trigger instance based around the 315 degree angle of a POV on
+   * the HID.
+   */
+  Trigger POVUpLeft(frc::EventLoop* loop = CommandScheduler::GetInstance()
+                                               .GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs a Trigger instance based around the center (not pressed)
+   * position of the default (index 0) POV on the HID.
+   *
+   * @param loop  the event loop instance to attach the event to. Defaults to
+   * {@link CommandScheduler::GetDefaultButtonLoop() the default command
+   * scheduler button loop}.
+   * @return a Trigger instance based around the center position of a POV on the
+   * HID.
+   */
+  Trigger POVCenter(frc::EventLoop* loop = CommandScheduler::GetInstance()
+                                               .GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs a Trigger instance that is true when the axis value is less than
+   * {@code threshold}, attached to {@link
+   * CommandScheduler::GetDefaultButtonLoop() the default command scheduler
+   * button loop}.
+   * @param axis The axis to read, starting at 0.
+   * @param threshold The value below which this trigger should return true.
+   * @param loop  the event loop instance to attach the event to. Defaults to
+   * {@link CommandScheduler::GetDefaultButtonLoop() the default command
+   * scheduler button loop}.
+   * @return a Trigger instance that is true when the axis value is less than
+   * the provided threshold.
+   */
+  Trigger AxisLessThan(
+      int axis, double threshold,
+      frc::EventLoop* loop =
+          CommandScheduler::GetInstance().GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs a Trigger instance that is true when the axis value is greater
+   * than {@code threshold}, attached to {@link
+   * CommandScheduler::GetDefaultButtonLoop() the default command scheduler
+   * button loop}.
+   * @param axis The axis to read, starting at 0.
+   * @param threshold The value below which this trigger should return true.
+   * @param loop  the event loop instance to attach the event to. Defaults to
+   * {@link CommandScheduler::GetDefaultButtonLoop() the default command
+   * scheduler button loop}.
+   * @return a Trigger instance that is true when the axis value is greater than
+   * the provided threshold.
+   */
+  Trigger AxisGreaterThan(
+      int axis, double threshold,
+      frc::EventLoop* loop =
+          CommandScheduler::GetInstance().GetDefaultButtonLoop()) const;
+};
+}  // namespace frc2
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/button/CommandJoystick.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/button/CommandJoystick.h
new file mode 100644
index 0000000..c335f89
--- /dev/null
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/button/CommandJoystick.h
@@ -0,0 +1,58 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+#include <frc/Joystick.h>
+
+#include "Trigger.h"
+#include "frc2/command/CommandScheduler.h"
+
+namespace frc2 {
+/**
+ * A subclass of {@link Joystick} with {@link Trigger} factories for
+ * command-based.
+ *
+ * @see Joystick
+ */
+class CommandJoystick : public frc::Joystick {
+ public:
+  using Joystick::Joystick;
+
+  /**
+   * Constructs an event instance around this button's digital signal.
+   *
+   * @param button the button index
+   * @param loop the event loop instance to attach the event to. Defaults to the
+   * CommandScheduler's default loop.
+   * @return an event instance representing the button's digital signal attached
+   * to the given loop.
+   */
+  class Trigger Button(
+      int button, frc::EventLoop* loop = CommandScheduler::GetInstance()
+                                             .GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs an event instance around the trigger button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to. Defaults to the
+   * CommandScheduler's default loop.
+   * @return an event instance representing the trigger button's digital signal
+   * attached to the given loop.
+   */
+  class Trigger Trigger(
+      frc::EventLoop* loop =
+          CommandScheduler::GetInstance().GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs an event instance around the top button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to. Defaults to the
+   * CommandScheduler's default loop.
+   * @return an event instance representing the top button's digital signal
+   * attached to the given loop.
+   */
+  class Trigger Top(frc::EventLoop* loop = CommandScheduler::GetInstance()
+                                               .GetDefaultButtonLoop()) const;
+};
+}  // namespace frc2
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/button/CommandPS4Controller.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/button/CommandPS4Controller.h
new file mode 100644
index 0000000..befb667
--- /dev/null
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/button/CommandPS4Controller.h
@@ -0,0 +1,178 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+#include <frc/PS4Controller.h>
+
+#include "Trigger.h"
+#include "frc2/command/CommandScheduler.h"
+
+namespace frc2 {
+/**
+ * A subclass of {@link PS4Controller} with {@link Trigger} factories for
+ * command-based.
+ *
+ * @see PS4Controller
+ */
+class CommandPS4Controller : public frc::PS4Controller {
+ public:
+  using PS4Controller::PS4Controller;
+
+  /**
+   * Constructs an event instance around this button's digital signal.
+   *
+   * @param button the button index
+   * @param loop the event loop instance to attach the event to. Defaults to the
+   * CommandScheduler's default loop.
+   * @return an event instance representing the button's digital signal attached
+   * to the given loop.
+   */
+  Trigger Button(int button,
+                 frc::EventLoop* loop = CommandScheduler::GetInstance()
+                                            .GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs an event instance around the square button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to. Defaults to the
+   * CommandScheduler's default loop.
+   * @return an event instance representing the square button's digital signal
+   * attached to the given loop.
+   */
+  Trigger Square(frc::EventLoop* loop = CommandScheduler::GetInstance()
+                                            .GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs an event instance around the cross button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to. Defaults to the
+   * CommandScheduler's default loop.
+   * @return an event instance representing the cross button's digital signal
+   * attached to the given loop.
+   */
+  Trigger Cross(frc::EventLoop* loop = CommandScheduler::GetInstance()
+                                           .GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs an event instance around the circle button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to. Defaults to the
+   * CommandScheduler's default loop.
+   * @return an event instance representing the circle button's digital signal
+   * attached to the given loop.
+   */
+  Trigger Circle(frc::EventLoop* loop = CommandScheduler::GetInstance()
+                                            .GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs an event instance around the triangle button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to. Defaults to the
+   * CommandScheduler's default loop.
+   * @return an event instance representing the triangle button's digital signal
+   * attached to the given loop.
+   */
+  Trigger Triangle(frc::EventLoop* loop = CommandScheduler::GetInstance()
+                                              .GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs an event instance around the L1 button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to. Defaults to the
+   * CommandScheduler's default loop.
+   * @return an event instance representing the L1 button's digital signal
+   * attached to the given loop.
+   */
+  Trigger L1(frc::EventLoop* loop =
+                 CommandScheduler::GetInstance().GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs an event instance around the R1 button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to. Defaults to the
+   * CommandScheduler's default loop.
+   * @return an event instance representing the R1 button's digital signal
+   * attached to the given loop.
+   */
+  Trigger R1(frc::EventLoop* loop =
+                 CommandScheduler::GetInstance().GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs an event instance around the L2 button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to. Defaults to the
+   * CommandScheduler's default loop.
+   * @return an event instance representing the L2 button's digital signal
+   * attached to the given loop.
+   */
+  Trigger L2(frc::EventLoop* loop =
+                 CommandScheduler::GetInstance().GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs an event instance around the R2 button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to. Defaults to the
+   * CommandScheduler's default loop.
+   * @return an event instance representing the R2 button's digital signal
+   * attached to the given loop.
+   */
+  Trigger R2(frc::EventLoop* loop =
+                 CommandScheduler::GetInstance().GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs an event instance around the options button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to. Defaults to the
+   * CommandScheduler's default loop.
+   * @return an event instance representing the options button's digital signal
+   * attached to the given loop.
+   */
+  Trigger Options(frc::EventLoop* loop = CommandScheduler::GetInstance()
+                                             .GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs an event instance around the L3 button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to. Defaults to the
+   * CommandScheduler's default loop.
+   * @return an event instance representing the L3 button's digital signal
+   * attached to the given loop.
+   */
+  Trigger L3(frc::EventLoop* loop =
+                 CommandScheduler::GetInstance().GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs an event instance around the R3 button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to. Defaults to the
+   * CommandScheduler's default loop.
+   * @return an event instance representing the R3 button's digital signal
+   * attached to the given loop.
+   */
+  Trigger R3(frc::EventLoop* loop =
+                 CommandScheduler::GetInstance().GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs an event instance around the PS button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to. Defaults to the
+   * CommandScheduler's default loop.
+   * @return an event instance representing the PS button's digital signal
+   * attached to the given loop.
+   */
+  Trigger PS(frc::EventLoop* loop =
+                 CommandScheduler::GetInstance().GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs an event instance around the touchpad's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to. Defaults to the
+   * CommandScheduler's default loop.
+   * @return an event instance representing the touchpad's digital signal
+   * attached to the given loop.
+   */
+  Trigger Touchpad(frc::EventLoop* loop = CommandScheduler::GetInstance()
+                                              .GetDefaultButtonLoop()) const;
+};
+}  // namespace frc2
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/button/CommandXboxController.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/button/CommandXboxController.h
new file mode 100644
index 0000000..337ec2f
--- /dev/null
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/button/CommandXboxController.h
@@ -0,0 +1,180 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+#include <frc/XboxController.h>
+
+#include "Trigger.h"
+#include "frc2/command/CommandScheduler.h"
+
+namespace frc2 {
+/**
+ * A subclass of {@link XboxController} with {@link Trigger} factories for
+ * command-based.
+ *
+ * @see XboxController
+ */
+class CommandXboxController : public frc::XboxController {
+ public:
+  using XboxController::XboxController;
+
+  /**
+   * Constructs an event instance around this button's digital signal.
+   *
+   * @param button the button index
+   * @param loop the event loop instance to attach the event to. Defaults to the
+   * CommandScheduler's default loop.
+   * @return an event instance representing the button's digital signal attached
+   * to the given loop.
+   */
+  Trigger Button(int button,
+                 frc::EventLoop* loop = CommandScheduler::GetInstance()
+                                            .GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs an event instance around the left bumper's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to. Defaults to the
+   * CommandScheduler's default loop.
+   * @return an event instance representing the left bumper's digital signal
+   * attached to the given loop.
+   */
+  Trigger LeftBumper(frc::EventLoop* loop = CommandScheduler::GetInstance()
+                                                .GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs an event instance around the right bumper's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to. Defaults to the
+   * CommandScheduler's default loop.
+   * @return an event instance representing the right bumper's digital signal
+   * attached to the given loop.
+   */
+  Trigger RightBumper(frc::EventLoop* loop = CommandScheduler::GetInstance()
+                                                 .GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs an event instance around the left stick's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to. Defaults to the
+   * CommandScheduler's default loop.
+   * @return an event instance representing the left stick's digital signal
+   * attached to the given loop.
+   */
+  Trigger LeftStick(frc::EventLoop* loop = CommandScheduler::GetInstance()
+                                               .GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs an event instance around the right stick's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to. Defaults to the
+   * CommandScheduler's default loop.
+   * @return an event instance representing the right stick's digital signal
+   * attached to the given loop.
+   */
+  Trigger RightStick(frc::EventLoop* loop = CommandScheduler::GetInstance()
+                                                .GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs an event instance around the A button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to. Defaults to the
+   * CommandScheduler's default loop.
+   * @return an event instance representing the A button's digital signal
+   * attached to the given loop.
+   */
+  Trigger A(frc::EventLoop* loop =
+                CommandScheduler::GetInstance().GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs an event instance around the B button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to. Defaults to the
+   * CommandScheduler's default loop.
+   * @return an event instance representing the B button's digital signal
+   * attached to the given loop.
+   */
+  Trigger B(frc::EventLoop* loop =
+                CommandScheduler::GetInstance().GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs an event instance around the X button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to. Defaults to the
+   * CommandScheduler's default loop.
+   * @return an event instance representing the X button's digital signal
+   * attached to the given loop.
+   */
+  Trigger X(frc::EventLoop* loop =
+                CommandScheduler::GetInstance().GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs an event instance around the Y button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to. Defaults to the
+   * CommandScheduler's default loop.
+   * @return an event instance representing the Y button's digital signal
+   * attached to the given loop.
+   */
+  Trigger Y(frc::EventLoop* loop =
+                CommandScheduler::GetInstance().GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs an event instance around the back button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to. Defaults to the
+   * CommandScheduler's default loop.
+   * @return an event instance representing the back button's digital signal
+   * attached to the given loop.
+   */
+  Trigger Back(frc::EventLoop* loop = CommandScheduler::GetInstance()
+                                          .GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs an event instance around the start button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to. Defaults to the
+   * CommandScheduler's default loop.
+   * @return an event instance representing the start button's digital signal
+   * attached to the given loop.
+   */
+  Trigger Start(frc::EventLoop* loop = CommandScheduler::GetInstance()
+                                           .GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs a Trigger instance around the axis value of the left trigger.
+   * The returned Trigger will be true when the axis value is greater than
+   * {@code threshold}.
+   *
+   * @param threshold the minimum axis value for the returned Trigger to be
+   * true. This value should be in the range [0, 1] where 0 is the unpressed
+   * state of the axis. Defaults to 0.5.
+   * @param loop the event loop instance to attach the Trigger to. Defaults to
+   * the CommandScheduler's default loop.
+   * @return a Trigger instance that is true when the left trigger's axis
+   * exceeds the provided threshold, attached to the given loop
+   */
+  Trigger LeftTrigger(double threshold = 0.5,
+                      frc::EventLoop* loop = CommandScheduler::GetInstance()
+                                                 .GetDefaultButtonLoop()) const;
+
+  /**
+   * Constructs a Trigger instance around the axis value of the right trigger.
+   * The returned Trigger will be true when the axis value is greater than
+   * {@code threshold}.
+   *
+   * @param threshold the minimum axis value for the returned Trigger to be
+   * true. This value should be in the range [0, 1] where 0 is the unpressed
+   * state of the axis. Defaults to 0.5.
+   * @param loop the event loop instance to attach the Trigger to. Defaults to
+   * the CommandScheduler's default loop.
+   * @return a Trigger instance that is true when the right trigger's axis
+   * exceeds the provided threshold, attached to the given loop
+   */
+  Trigger RightTrigger(
+      double threshold = 0.5,
+      frc::EventLoop* loop =
+          CommandScheduler::GetInstance().GetDefaultButtonLoop()) const;
+};
+}  // namespace frc2
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/button/JoystickButton.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/button/JoystickButton.h
index 7d74358..b5280c0 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/button/JoystickButton.h
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/button/JoystickButton.h
@@ -4,6 +4,7 @@
 
 #pragma once
 #include <frc/GenericHID.h>
+#include <wpi/deprecated.h>
 
 #include "Button.h"
 
@@ -22,11 +23,13 @@
    * Creates a JoystickButton that commands can be bound to.
    *
    * @param joystick The joystick on which the button is located.
-   * @param buttonNumber The number of the button on the joystic.
+   * @param buttonNumber The number of the button on the joystick.
    */
+  WPI_IGNORE_DEPRECATED
   explicit JoystickButton(frc::GenericHID* joystick, int buttonNumber)
       : Button([joystick, buttonNumber] {
           return joystick->GetRawButton(buttonNumber);
         }) {}
+  WPI_UNIGNORE_DEPRECATED
 };
 }  // namespace frc2
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/button/NetworkButton.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/button/NetworkButton.h
index de5044b..3d0378d 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/button/NetworkButton.h
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/button/NetworkButton.h
@@ -7,6 +7,7 @@
 #include <memory>
 #include <string_view>
 
+#include <networktables/BooleanTopic.h>
 #include <networktables/NetworkTable.h>
 #include <networktables/NetworkTableInstance.h>
 
@@ -23,9 +24,16 @@
   /**
    * Creates a NetworkButton that commands can be bound to.
    *
-   * @param entry The entry that is the value.
+   * @param topic The boolean topic that contains the value.
    */
-  explicit NetworkButton(nt::NetworkTableEntry entry);
+  explicit NetworkButton(nt::BooleanTopic topic);
+
+  /**
+   * Creates a NetworkButton that commands can be bound to.
+   *
+   * @param sub The boolean subscriber that provides the value.
+   */
+  explicit NetworkButton(nt::BooleanSubscriber sub);
 
   /**
    * Creates a NetworkButton that commands can be bound to.
@@ -43,5 +51,15 @@
    * @param field The field that is the value.
    */
   NetworkButton(std::string_view table, std::string_view field);
+
+  /**
+   * Creates a NetworkButton that commands can be bound to.
+   *
+   * @param inst The NetworkTable instance to use
+   * @param table The table where the networktable value is located.
+   * @param field The field that is the value.
+   */
+  NetworkButton(nt::NetworkTableInstance inst, std::string_view table,
+                std::string_view field);
 };
 }  // namespace frc2
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/button/POVButton.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/button/POVButton.h
index c0f0e6b..7ee1590 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/button/POVButton.h
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/button/POVButton.h
@@ -4,6 +4,7 @@
 
 #pragma once
 #include <frc/GenericHID.h>
+#include <wpi/deprecated.h>
 
 #include "Button.h"
 
@@ -25,9 +26,11 @@
    * @param angle The angle of the POV corresponding to a button press.
    * @param povNumber The number of the POV on the joystick.
    */
+  WPI_IGNORE_DEPRECATED
   POVButton(frc::GenericHID* joystick, int angle, int povNumber = 0)
       : Button([joystick, angle, povNumber] {
           return joystick->GetPOV(povNumber) == angle;
         }) {}
+  WPI_UNIGNORE_DEPRECATED
 };
 }  // namespace frc2
diff --git a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/button/Trigger.h b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/button/Trigger.h
index d5fcb34..c3a5e86 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/button/Trigger.h
+++ b/third_party/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/button/Trigger.h
@@ -7,11 +7,14 @@
 #include <functional>
 #include <initializer_list>
 #include <memory>
+#include <span>
 #include <utility>
 
+#include <frc/event/BooleanEvent.h>
+#include <frc/event/EventLoop.h>
 #include <frc/filter/Debouncer.h>
 #include <units/time.h>
-#include <wpi/span.h>
+#include <wpi/deprecated.h>
 
 #include "frc2/command/Command.h"
 #include "frc2/command/CommandScheduler.h"
@@ -19,73 +22,226 @@
 namespace frc2 {
 class Command;
 /**
- * A class used to bind command scheduling to events.  The
- * Trigger class is a base for all command-event-binding classes, and so the
- * methods are named fairly abstractly; for purpose-specific wrappers, see
- * Button.
+ * This class provides an easy way to link commands to conditions.
  *
- * This class is provided by the NewCommands VendorDep
+ * <p>It is very easy to link a button to a command. For instance, you could
+ * link the trigger button of a joystick to a "score" command.
  *
- * @see Button
+ * <p>Triggers can easily be composed for advanced functionality using the
+ * {@link #operator!}, {@link #operator||}, {@link #operator&&} operators.
+ *
+ * <p>This class is provided by the NewCommands VendorDep
  */
 class Trigger {
  public:
   /**
-   * Create a new trigger that is active when the given condition is true.
+   * Creates a new trigger based on the given condition.
    *
-   * @param isActive Whether the trigger is active.
+   * <p>Polled by the default scheduler button loop.
+   *
+   * @param condition the condition represented by this trigger
    */
-  explicit Trigger(std::function<bool()> isActive)
-      : m_isActive{std::move(isActive)} {}
+  explicit Trigger(std::function<bool()> condition)
+      : Trigger{CommandScheduler::GetInstance().GetDefaultButtonLoop(),
+                std::move(condition)} {}
 
   /**
-   * Create a new trigger that is never active (default constructor) - activity
-   *  can be further determined by subclass code.
+   * Creates a new trigger based on the given condition.
+   *
+   * @param loop The loop instance that polls this trigger.
+   * @param condition the condition represented by this trigger
    */
-  Trigger() {
-    m_isActive = [] { return false; };
-  }
+  Trigger(frc::EventLoop* loop, std::function<bool()> condition)
+      : m_loop{loop}, m_condition{std::move(condition)} {}
+
+  /**
+   * Create a new trigger that is always `false`.
+   */
+  Trigger() : Trigger([] { return false; }) {}
 
   Trigger(const Trigger& other);
 
   /**
-   * Binds a command to start when the trigger becomes active.  Takes a
+   * Starts the given command whenever the condition changes from `false` to
+   * `true`.
+   *
+   * <p>Takes a raw pointer, and so is non-owning; users are responsible for the
+   * lifespan of the command.
+   *
+   * @param command the command to start
+   * @return this trigger, so calls can be chained
+   */
+  Trigger OnTrue(Command* command);
+
+  /**
+   * Starts the given command whenever the condition changes from `false` to
+   * `true`. Moves command ownership to the button scheduler.
+   *
+   * @param command The command to bind.
+   * @return The trigger, for chained calls.
+   */
+  Trigger OnTrue(CommandPtr&& command);
+
+  /**
+   * Starts the given command whenever the condition changes from `true` to
+   * `false`.
+   *
+   * <p>Takes a raw pointer, and so is non-owning; users are responsible for the
+   * lifespan of the command.
+   *
+   * @param command the command to start
+   * @return this trigger, so calls can be chained
+   */
+  Trigger OnFalse(Command* command);
+
+  /**
+   * Starts the given command whenever the condition changes from `true` to
+   * `false`.
+   *
+   * @param command The command to bind.
+   * @return The trigger, for chained calls.
+   */
+  Trigger OnFalse(CommandPtr&& command);
+
+  /**
+   * Starts the given command when the condition changes to `true` and cancels
+   * it when the condition changes to `false`.
+   *
+   * <p>Doesn't re-start the command if it ends while the condition is still
+   * `true`. If the command should restart, see RepeatCommand.
+   *
+   * <p>Takes a raw pointer, and so is non-owning; users are responsible for the
+   * lifespan of the command.
+   *
+   * @param command the command to start
+   * @return this trigger, so calls can be chained
+   */
+  Trigger WhileTrue(Command* command);
+
+  /**
+   * Starts the given command when the condition changes to `true` and cancels
+   * it when the condition changes to `false`. Moves command ownership to the
+   * button scheduler.
+   *
+   * <p>Doesn't re-start the command if it ends while the condition is still
+   * `true`. If the command should restart, see RepeatCommand.
+   *
+   * @param command The command to bind.
+   * @return The trigger, for chained calls.
+   */
+  Trigger WhileTrue(CommandPtr&& command);
+
+  /**
+   * Starts the given command when the condition changes to `false` and cancels
+   * it when the condition changes to `true`.
+   *
+   * <p>Doesn't re-start the command if it ends while the condition is still
+   * `true`. If the command should restart, see RepeatCommand.
+   *
+   * <p>Takes a raw pointer, and so is non-owning; users are responsible for the
+   * lifespan of the command.
+   *
+   * @param command the command to start
+   * @return this trigger, so calls can be chained
+   */
+  Trigger WhileFalse(Command* command);
+
+  /**
+   * Starts the given command when the condition changes to `false` and cancels
+   * it when the condition changes to `true`. Moves command ownership to the
+   * button scheduler.
+   *
+   * <p>Doesn't re-start the command if it ends while the condition is still
+   * `false`. If the command should restart, see RepeatCommand.
+   *
+   * @param command The command to bind.
+   * @return The trigger, for chained calls.
+   */
+  Trigger WhileFalse(CommandPtr&& command);
+
+  /**
+   * Toggles a command when the condition changes from `false` to `true`.
+   *
+   * <p>Takes a raw pointer, and so is non-owning; users are responsible for the
+   * lifespan of the command.
+   *
+   * @param command the command to toggle
+   * @return this trigger, so calls can be chained
+   */
+  Trigger ToggleOnTrue(Command* command);
+
+  /**
+   * Toggles a command when the condition changes from `false` to `true`.
+   *
+   * <p>Takes a raw pointer, and so is non-owning; users are responsible for the
+   * lifespan of the command.
+   *
+   * @param command the command to toggle
+   * @return this trigger, so calls can be chained
+   */
+  Trigger ToggleOnTrue(CommandPtr&& command);
+
+  /**
+   * Toggles a command when the condition changes from `true` to the low
+   * state.
+   *
+   * <p>Takes a raw pointer, and so is non-owning; users are responsible for the
+   * lifespan of the command.
+   *
+   * @param command the command to toggle
+   * @return this trigger, so calls can be chained
+   */
+  Trigger ToggleOnFalse(Command* command);
+
+  /**
+   * Toggles a command when the condition changes from `true` to the low
+   * state.
+   *
+   * <p>Takes a raw pointer, and so is non-owning; users are responsible for the
+   * lifespan of the command.
+   *
+   * @param command the command to toggle
+   * @return this trigger, so calls can be chained
+   */
+  Trigger ToggleOnFalse(CommandPtr&& command);
+
+  /**
+   * Binds a command to start when the trigger becomes active. Takes a
    * raw pointer, and so is non-owning; users are responsible for the lifespan
    * of the command.
    *
    * @param command The command to bind.
-   * @param interruptible Whether the command should be interruptible.
    * @return The trigger, for chained calls.
+   * @deprecated Use OnTrue(Command) instead
    */
-  Trigger WhenActive(Command* command, bool interruptible = true);
+  WPI_DEPRECATED("Use OnTrue(Command) instead")
+  Trigger WhenActive(Command* command);
 
   /**
-   * Binds a command to start when the trigger becomes active.  Transfers
+   * Binds a command to start when the trigger becomes active. Transfers
    * command ownership to the button scheduler, so the user does not have to
    * worry about lifespan - rvalue refs will be *moved*, lvalue refs will be
    * *copied.*
    *
    * @param command The command to bind.
-   * @param interruptible Whether the command should be interruptible.
    * @return The trigger, for chained calls.
+   * @deprecated Use OnTrue(Command) instead
    */
   template <class T, typename = std::enable_if_t<std::is_base_of_v<
                          Command, std::remove_reference_t<T>>>>
-  Trigger WhenActive(T&& command, bool interruptible = true) {
-    CommandScheduler::GetInstance().AddButton(
-        [pressedLast = m_isActive(), *this,
-         command = std::make_unique<std::remove_reference_t<T>>(
-             std::forward<T>(command)),
-         interruptible]() mutable {
-          bool pressed = m_isActive();
+  WPI_DEPRECATED("Use OnTrue(Command) instead")
+  Trigger WhenActive(T&& command) {
+    m_loop->Bind([condition = m_condition, previous = m_condition(),
+                  command = std::make_unique<std::remove_reference_t<T>>(
+                      std::forward<T>(command))]() mutable {
+      bool current = condition();
 
-          if (!pressedLast && pressed) {
-            command->Schedule(interruptible);
-          }
+      if (!previous && current) {
+        command->Schedule();
+      }
 
-          pressedLast = pressed;
-        });
-
+      previous = current;
+    });
     return *this;
   }
 
@@ -94,7 +250,11 @@
    *
    * @param toRun the runnable to execute.
    * @param requirements the required subsystems.
+   * @deprecated Use OnTrue(Command) instead and construct the InstantCommand
+   * manually
    */
+  WPI_DEPRECATED(
+      "Use OnTrue(Command) instead and construct the InstantCommand manually")
   Trigger WhenActive(std::function<void()> toRun,
                      std::initializer_list<Subsystem*> requirements);
 
@@ -103,9 +263,13 @@
    *
    * @param toRun the runnable to execute.
    * @param requirements the required subsystems.
+   * @deprecated Use OnTrue(Command) instead and construct the InstantCommand
+   * manually
    */
+  WPI_DEPRECATED(
+      "Use OnTrue(Command) instead and construct the InstantCommand manually")
   Trigger WhenActive(std::function<void()> toRun,
-                     wpi::span<Subsystem* const> requirements = {});
+                     std::span<Subsystem* const> requirements = {});
 
   /**
    * Binds a command to be started repeatedly while the trigger is active, and
@@ -113,10 +277,14 @@
    * non-owning; users are responsible for the lifespan of the command.
    *
    * @param command The command to bind.
-   * @param interruptible Whether the command should be interruptible.
    * @return The trigger, for chained calls.
+   * @deprecated Use WhileTrue(Command) with RepeatCommand, or bind
+   command::Schedule with IfHigh(std::function<void()>).
    */
-  Trigger WhileActiveContinous(Command* command, bool interruptible = true);
+  WPI_DEPRECATED(
+      "Use WhileTrue(Command) with RepeatCommand, or bind command::Schedule "
+      "with IfHigh(std::function<void()>).")
+  Trigger WhileActiveContinous(Command* command);
 
   /**
    * Binds a command to be started repeatedly while the trigger is active, and
@@ -125,27 +293,30 @@
    * rvalue refs will be *moved*, lvalue refs will be *copied.*
    *
    * @param command The command to bind.
-   * @param interruptible Whether the command should be interruptible.
    * @return The trigger, for chained calls.
+   * @deprecated Use WhileTrue(Command) with RepeatCommand, or bind
+   command::Schedule with IfHigh(std::function<void()>).
    */
   template <class T, typename = std::enable_if_t<std::is_base_of_v<
                          Command, std::remove_reference_t<T>>>>
-  Trigger WhileActiveContinous(T&& command, bool interruptible = true) {
-    CommandScheduler::GetInstance().AddButton(
-        [pressedLast = m_isActive(), *this,
-         command = std::make_unique<std::remove_reference_t<T>>(
-             std::forward<T>(command)),
-         interruptible]() mutable {
-          bool pressed = m_isActive();
+  WPI_DEPRECATED(
+      "Use WhileTrue(Command) with RepeatCommand, or bind command::Schedule "
+      "with IfHigh(std::function<void()>).")
+  Trigger WhileActiveContinous(T&& command) {
+    m_loop->Bind([condition = m_condition, previous = m_condition(),
+                  command = std::make_unique<std::remove_reference_t<T>>(
+                      std::forward<T>(command))]() mutable {
+      bool current = condition();
 
-          if (pressed) {
-            command->Schedule(interruptible);
-          } else if (pressedLast && !pressed) {
-            command->Cancel();
-          }
+      if (current) {
+        command->Schedule();
+      } else if (previous && !current) {
+        command->Cancel();
+      }
 
-          pressedLast = pressed;
-        });
+      previous = current;
+    });
+
     return *this;
   }
 
@@ -154,7 +325,9 @@
    *
    * @param toRun the runnable to execute.
    * @param requirements the required subsystems.
+   * @deprecated Use WhileTrue(Command) and construct a RunCommand manually
    */
+  WPI_DEPRECATED("Use WhileTrue(Command) and construct a RunCommand manually")
   Trigger WhileActiveContinous(std::function<void()> toRun,
                                std::initializer_list<Subsystem*> requirements);
 
@@ -163,9 +336,11 @@
    *
    * @param toRun the runnable to execute.
    * @param requirements the required subsystems.
+   * @deprecated Use WhileTrue(Command) and construct a RunCommand manually
    */
+  WPI_DEPRECATED("Use WhileTrue(Command) and construct a RunCommand manually")
   Trigger WhileActiveContinous(std::function<void()> toRun,
-                               wpi::span<Subsystem* const> requirements = {});
+                               std::span<Subsystem* const> requirements = {});
 
   /**
    * Binds a command to be started when the trigger becomes active, and
@@ -173,39 +348,39 @@
    * non-owning; users are responsible for the lifespan of the command.
    *
    * @param command The command to bind.
-   * @param interruptible Whether the command should be interruptible.
    * @return The trigger, for chained calls.
+   * @deprecated Use WhileTrue(Command) instead.
    */
-  Trigger WhileActiveOnce(Command* command, bool interruptible = true);
+  WPI_DEPRECATED("Use WhileTrue(Command) instead.")
+  Trigger WhileActiveOnce(Command* command);
 
   /**
    * Binds a command to be started when the trigger becomes active, and
-   * canceled when it becomes inactive.  Transfers command ownership to the
+   * canceled when it becomes inactive. Transfers command ownership to the
    * button scheduler, so the user does not have to worry about lifespan -
    * rvalue refs will be *moved*, lvalue refs will be *copied.*
    *
    * @param command The command to bind.
-   * @param interruptible Whether the command should be interruptible.
    * @return The trigger, for chained calls.
+   * @deprecated Use WhileTrue(Command) instead.
    */
   template <class T, typename = std::enable_if_t<std::is_base_of_v<
                          Command, std::remove_reference_t<T>>>>
-  Trigger WhileActiveOnce(T&& command, bool interruptible = true) {
-    CommandScheduler::GetInstance().AddButton(
-        [pressedLast = m_isActive(), *this,
-         command = std::make_unique<std::remove_reference_t<T>>(
-             std::forward<T>(command)),
-         interruptible]() mutable {
-          bool pressed = m_isActive();
+  WPI_DEPRECATED("Use WhileTrue(Command) instead.")
+  Trigger WhileActiveOnce(T&& command) {
+    m_loop->Bind([condition = m_condition, previous = m_condition(),
+                  command = std::make_unique<std::remove_reference_t<T>>(
+                      std::forward<T>(command))]() mutable {
+      bool current = condition();
 
-          if (!pressedLast && pressed) {
-            command->Schedule(interruptible);
-          } else if (pressedLast && !pressed) {
-            command->Cancel();
-          }
+      if (!previous && current) {
+        command->Schedule();
+      } else if (previous && !current) {
+        command->Cancel();
+      }
 
-          pressedLast = pressed;
-        });
+      previous = current;
+    });
     return *this;
   }
 
@@ -215,10 +390,11 @@
    * of the command.
    *
    * @param command The command to bind.
-   * @param interruptible Whether the command should be interruptible.
    * @return The trigger, for chained calls.
+   * @deprecated Use OnFalse(Command) instead.
    */
-  Trigger WhenInactive(Command* command, bool interruptible = true);
+  WPI_DEPRECATED("Use OnFalse(Command) instead.")
+  Trigger WhenInactive(Command* command);
 
   /**
    * Binds a command to start when the trigger becomes inactive.  Transfers
@@ -227,25 +403,24 @@
    * *copied.*
    *
    * @param command The command to bind.
-   * @param interruptible Whether the command should be interruptible.
    * @return The trigger, for chained calls.
+   * @deprecated Use OnFalse(Command) instead.
    */
   template <class T, typename = std::enable_if_t<std::is_base_of_v<
                          Command, std::remove_reference_t<T>>>>
-  Trigger WhenInactive(T&& command, bool interruptible = true) {
-    CommandScheduler::GetInstance().AddButton(
-        [pressedLast = m_isActive(), *this,
-         command = std::make_unique<std::remove_reference_t<T>>(
-             std::forward<T>(command)),
-         interruptible]() mutable {
-          bool pressed = m_isActive();
+  WPI_DEPRECATED("Use OnFalse(Command) instead.")
+  Trigger WhenInactive(T&& command) {
+    m_loop->Bind([condition = m_condition, previous = m_condition(),
+                  command = std::make_unique<std::remove_reference_t<T>>(
+                      std::forward<T>(command))]() mutable {
+      bool current = condition();
 
-          if (pressedLast && !pressed) {
-            command->Schedule(interruptible);
-          }
+      if (previous && !current) {
+        command->Schedule();
+      }
 
-          pressedLast = pressed;
-        });
+      previous = current;
+    });
     return *this;
   }
 
@@ -254,7 +429,11 @@
    *
    * @param toRun the runnable to execute.
    * @param requirements the required subsystems.
+   * @deprecated Use OnFalse(Command) instead and construct the InstantCommand
+   * manually
    */
+  WPI_DEPRECATED(
+      "Use OnFalse(Command) instead and construct the InstantCommand manually")
   Trigger WhenInactive(std::function<void()> toRun,
                        std::initializer_list<Subsystem*> requirements);
 
@@ -263,20 +442,25 @@
    *
    * @param toRun the runnable to execute.
    * @param requirements the required subsystems.
+   * @deprecated Use OnFalse(Command) instead and construct the InstantCommand
+   * manually
    */
+  WPI_DEPRECATED(
+      "Use OnFalse(Command) instead and construct the InstantCommand manually")
   Trigger WhenInactive(std::function<void()> toRun,
-                       wpi::span<Subsystem* const> requirements = {});
+                       std::span<Subsystem* const> requirements = {});
 
   /**
    * Binds a command to start when the trigger becomes active, and be canceled
-   * when it again becomes active.  Takes a raw pointer, and so is non-owning;
+   * when it again becomes active. Takes a raw pointer, and so is non-owning;
    * users are responsible for the lifespan of the command.
    *
    * @param command The command to bind.
-   * @param interruptible Whether the command should be interruptible.
    * @return The trigger, for chained calls.
+   * @deprecated Use ToggleOnTrue(Command) instead.
    */
-  Trigger ToggleWhenActive(Command* command, bool interruptible = true);
+  WPI_DEPRECATED("Use ToggleOnTrue(Command) instead.")
+  Trigger ToggleWhenActive(Command* command);
 
   /**
    * Binds a command to start when the trigger becomes active, and be canceled
@@ -285,29 +469,29 @@
    * will be *moved*, lvalue refs will be *copied.*
    *
    * @param command The command to bind.
-   * @param interruptible Whether the command should be interruptible.
    * @return The trigger, for chained calls.
+   * @deprecated Use ToggleOnTrue(Command) instead.
    */
   template <class T, typename = std::enable_if_t<std::is_base_of_v<
                          Command, std::remove_reference_t<T>>>>
-  Trigger ToggleWhenActive(T&& command, bool interruptible = true) {
-    CommandScheduler::GetInstance().AddButton(
-        [pressedLast = m_isActive(), *this,
-         command = std::make_unique<std::remove_reference_t<T>>(
-             std::forward<T>(command)),
-         interruptible]() mutable {
-          bool pressed = m_isActive();
+  WPI_DEPRECATED("Use ToggleOnTrue(Command) instead.")
+  Trigger ToggleWhenActive(T&& command) {
+    m_loop->Bind([condition = m_condition, previous = m_condition(),
+                  command = std::make_unique<std::remove_reference_t<T>>(
+                      std::forward<T>(command))]() mutable {
+      bool current = condition();
 
-          if (!pressedLast && pressed) {
-            if (command->IsScheduled()) {
-              command->Cancel();
-            } else {
-              command->Schedule(interruptible);
-            }
-          }
+      if (!previous && current) {
+        if (command->IsScheduled()) {
+          command->Cancel();
+        } else {
+          command->Schedule();
+        }
+      }
 
-          pressedLast = pressed;
-        });
+      previous = current;
+    });
+
     return *this;
   }
 
@@ -318,7 +502,9 @@
    *
    * @param command The command to bind.
    * @return The trigger, for chained calls.
+   * @deprecated Pass this as a command end condition with Until() instead.
    */
+  WPI_DEPRECATED("Pass this as a command end condition with Until() instead.")
   Trigger CancelWhenActive(Command* command);
 
   /**
@@ -326,8 +512,32 @@
    *
    * @return A trigger which is active when both component triggers are active.
    */
+  Trigger operator&&(std::function<bool()> rhs) {
+    return Trigger(m_loop, [condition = m_condition, rhs = std::move(rhs)] {
+      return condition() && rhs();
+    });
+  }
+
+  /**
+   * Composes two triggers with logical AND.
+   *
+   * @return A trigger which is active when both component triggers are active.
+   */
   Trigger operator&&(Trigger rhs) {
-    return Trigger([*this, rhs] { return m_isActive() && rhs.m_isActive(); });
+    return Trigger(m_loop, [condition = m_condition, rhs] {
+      return condition() && rhs.m_condition();
+    });
+  }
+
+  /**
+   * Composes two triggers with logical OR.
+   *
+   * @return A trigger which is active when either component trigger is active.
+   */
+  Trigger operator||(std::function<bool()> rhs) {
+    return Trigger(m_loop, [condition = m_condition, rhs = std::move(rhs)] {
+      return condition() || rhs();
+    });
   }
 
   /**
@@ -336,7 +546,9 @@
    * @return A trigger which is active when either component trigger is active.
    */
   Trigger operator||(Trigger rhs) {
-    return Trigger([*this, rhs] { return m_isActive() || rhs.m_isActive(); });
+    return Trigger(m_loop, [condition = m_condition, rhs] {
+      return condition() || rhs.m_condition();
+    });
   }
 
   /**
@@ -346,7 +558,7 @@
    * and vice-versa.
    */
   Trigger operator!() {
-    return Trigger([*this] { return !m_isActive(); });
+    return Trigger(m_loop, [condition = m_condition] { return !condition(); });
   }
 
   /**
@@ -362,6 +574,7 @@
                        frc::Debouncer::DebounceType::kRising);
 
  private:
-  std::function<bool()> m_isActive;
+  frc::EventLoop* m_loop;
+  std::function<bool()> m_condition;
 };
 }  // namespace frc2
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/MockHardwareExtension.java b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/MockHardwareExtension.java
index b0ffc88..2de1a07 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/MockHardwareExtension.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/MockHardwareExtension.java
@@ -34,5 +34,6 @@
     DriverStationSim.setAutonomous(false);
     DriverStationSim.setEnabled(true);
     DriverStationSim.setTest(true);
+    DriverStationSim.notifyNewData();
   }
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandDecoratorTest.java b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandDecoratorTest.java
index 66593ca..392c23c 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandDecoratorTest.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandDecoratorTest.java
@@ -4,11 +4,14 @@
 
 package edu.wpi.first.wpilibj2.command;
 
+import static org.junit.jupiter.api.Assertions.assertEquals;
 import static org.junit.jupiter.api.Assertions.assertFalse;
 import static org.junit.jupiter.api.Assertions.assertTrue;
 
 import edu.wpi.first.hal.HAL;
 import edu.wpi.first.wpilibj.simulation.SimHooks;
+import java.util.concurrent.atomic.AtomicBoolean;
+import java.util.concurrent.atomic.AtomicInteger;
 import org.junit.jupiter.api.Test;
 import org.junit.jupiter.api.parallel.ResourceLock;
 
@@ -41,77 +44,91 @@
   @Test
   void untilTest() {
     try (CommandScheduler scheduler = new CommandScheduler()) {
-      ConditionHolder condition = new ConditionHolder();
+      AtomicBoolean condition = new AtomicBoolean();
 
-      Command command = new WaitCommand(10).until(condition::getCondition);
+      Command command = new WaitCommand(10).until(condition::get);
 
       scheduler.schedule(command);
       scheduler.run();
       assertTrue(scheduler.isScheduled(command));
-      condition.setCondition(true);
+      condition.set(true);
       scheduler.run();
       assertFalse(scheduler.isScheduled(command));
     }
   }
 
   @Test
+  void ignoringDisableTest() {
+    try (CommandScheduler scheduler = new CommandScheduler()) {
+      var command = new RunCommand(() -> {}).ignoringDisable(true);
+
+      setDSEnabled(false);
+
+      scheduler.schedule(command);
+
+      scheduler.run();
+      assertTrue(scheduler.isScheduled(command));
+    }
+  }
+
+  @Test
   void beforeStartingTest() {
     try (CommandScheduler scheduler = new CommandScheduler()) {
-      ConditionHolder condition = new ConditionHolder();
-      condition.setCondition(false);
+      AtomicBoolean condition = new AtomicBoolean();
+      condition.set(false);
 
       Command command = new InstantCommand();
 
-      scheduler.schedule(command.beforeStarting(() -> condition.setCondition(true)));
+      scheduler.schedule(command.beforeStarting(() -> condition.set(true)));
 
-      assertTrue(condition.getCondition());
+      assertTrue(condition.get());
     }
   }
 
   @Test
   void andThenLambdaTest() {
     try (CommandScheduler scheduler = new CommandScheduler()) {
-      ConditionHolder condition = new ConditionHolder();
-      condition.setCondition(false);
+      AtomicBoolean condition = new AtomicBoolean();
+      condition.set(false);
 
       Command command = new InstantCommand();
 
-      scheduler.schedule(command.andThen(() -> condition.setCondition(true)));
+      scheduler.schedule(command.andThen(() -> condition.set(true)));
 
-      assertFalse(condition.getCondition());
+      assertFalse(condition.get());
 
       scheduler.run();
 
-      assertTrue(condition.getCondition());
+      assertTrue(condition.get());
     }
   }
 
   @Test
   void andThenTest() {
     try (CommandScheduler scheduler = new CommandScheduler()) {
-      ConditionHolder condition = new ConditionHolder();
-      condition.setCondition(false);
+      AtomicBoolean condition = new AtomicBoolean();
+      condition.set(false);
 
       Command command1 = new InstantCommand();
-      Command command2 = new InstantCommand(() -> condition.setCondition(true));
+      Command command2 = new InstantCommand(() -> condition.set(true));
 
       scheduler.schedule(command1.andThen(command2));
 
-      assertFalse(condition.getCondition());
+      assertFalse(condition.get());
 
       scheduler.run();
 
-      assertTrue(condition.getCondition());
+      assertTrue(condition.get());
     }
   }
 
   @Test
   void deadlineWithTest() {
     try (CommandScheduler scheduler = new CommandScheduler()) {
-      ConditionHolder condition = new ConditionHolder();
-      condition.setCondition(false);
+      AtomicBoolean condition = new AtomicBoolean();
+      condition.set(false);
 
-      Command dictator = new WaitUntilCommand(condition::getCondition);
+      Command dictator = new WaitUntilCommand(condition::get);
       Command endsBefore = new InstantCommand();
       Command endsAfter = new WaitUntilCommand(() -> false);
 
@@ -122,7 +139,7 @@
 
       assertTrue(scheduler.isScheduled(group));
 
-      condition.setCondition(true);
+      condition.set(true);
       scheduler.run();
 
       assertFalse(scheduler.isScheduled(group));
@@ -132,10 +149,10 @@
   @Test
   void alongWithTest() {
     try (CommandScheduler scheduler = new CommandScheduler()) {
-      ConditionHolder condition = new ConditionHolder();
-      condition.setCondition(false);
+      AtomicBoolean condition = new AtomicBoolean();
+      condition.set(false);
 
-      Command command1 = new WaitUntilCommand(condition::getCondition);
+      Command command1 = new WaitUntilCommand(condition::get);
       Command command2 = new InstantCommand();
 
       Command group = command1.alongWith(command2);
@@ -145,7 +162,7 @@
 
       assertTrue(scheduler.isScheduled(group));
 
-      condition.setCondition(true);
+      condition.set(true);
       scheduler.run();
 
       assertFalse(scheduler.isScheduled(group));
@@ -167,6 +184,7 @@
     }
   }
 
+  @SuppressWarnings("removal") // Command.perpetually()
   @Test
   void perpetuallyTest() {
     try (CommandScheduler scheduler = new CommandScheduler()) {
@@ -182,4 +200,103 @@
       assertTrue(scheduler.isScheduled(perpetual));
     }
   }
+
+  @Test
+  void unlessTest() {
+    try (CommandScheduler scheduler = new CommandScheduler()) {
+      AtomicBoolean unlessCondition = new AtomicBoolean(true);
+      AtomicBoolean hasRunCondition = new AtomicBoolean(false);
+
+      Command command =
+          new InstantCommand(() -> hasRunCondition.set(true)).unless(unlessCondition::get);
+
+      scheduler.schedule(command);
+      scheduler.run();
+      assertFalse(hasRunCondition.get());
+
+      unlessCondition.set(false);
+      scheduler.schedule(command);
+      scheduler.run();
+      assertTrue(hasRunCondition.get());
+    }
+  }
+
+  @Test
+  void finallyDoTest() {
+    try (CommandScheduler scheduler = new CommandScheduler()) {
+      AtomicInteger first = new AtomicInteger(0);
+      AtomicInteger second = new AtomicInteger(0);
+
+      Command command =
+          new FunctionalCommand(
+                  () -> {},
+                  () -> {},
+                  interrupted -> {
+                    if (!interrupted) {
+                      first.incrementAndGet();
+                    }
+                  },
+                  () -> true)
+              .finallyDo(
+                  interrupted -> {
+                    if (!interrupted) {
+                      // to differentiate between "didn't run" and "ran before command's `end()`
+                      second.addAndGet(1 + first.get());
+                    }
+                  });
+
+      scheduler.schedule(command);
+      assertEquals(0, first.get());
+      assertEquals(0, second.get());
+      scheduler.run();
+      assertEquals(1, first.get());
+      // if `second == 0`, neither of the lambdas ran.
+      // if `second == 1`, the second lambda ran before the first one
+      assertEquals(2, second.get());
+    }
+  }
+
+  // handleInterruptTest() implicitly tests the interrupt=true branch of finallyDo()
+  @Test
+  void handleInterruptTest() {
+    try (CommandScheduler scheduler = new CommandScheduler()) {
+      AtomicInteger first = new AtomicInteger(0);
+      AtomicInteger second = new AtomicInteger(0);
+
+      Command command =
+          new FunctionalCommand(
+                  () -> {},
+                  () -> {},
+                  interrupted -> {
+                    if (interrupted) {
+                      first.incrementAndGet();
+                    }
+                  },
+                  () -> false)
+              .handleInterrupt(
+                  () -> {
+                    // to differentiate between "didn't run" and "ran before command's `end()`
+                    second.addAndGet(1 + first.get());
+                  });
+
+      scheduler.schedule(command);
+      scheduler.run();
+      assertEquals(0, first.get());
+      assertEquals(0, second.get());
+
+      scheduler.cancel(command);
+      assertEquals(1, first.get());
+      // if `second == 0`, neither of the lambdas ran.
+      // if `second == 1`, the second lambda ran before the first one
+      assertEquals(2, second.get());
+    }
+  }
+
+  @Test
+  void withNameTest() {
+    InstantCommand command = new InstantCommand();
+    String name = "Named";
+    Command named = command.withName(name);
+    assertEquals(name, named.getName());
+  }
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandGroupErrorTest.java b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandGroupErrorTest.java
index 4fb44a5..ba4a77b 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandGroupErrorTest.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandGroupErrorTest.java
@@ -24,16 +24,15 @@
 
   @Test
   void commandInGroupExternallyScheduledTest() {
-    try (CommandScheduler scheduler = new CommandScheduler()) {
-      MockCommandHolder command1Holder = new MockCommandHolder(true);
-      Command command1 = command1Holder.getMock();
-      MockCommandHolder command2Holder = new MockCommandHolder(true);
-      Command command2 = command2Holder.getMock();
+    MockCommandHolder command1Holder = new MockCommandHolder(true);
+    Command command1 = command1Holder.getMock();
+    MockCommandHolder command2Holder = new MockCommandHolder(true);
+    Command command2 = command2Holder.getMock();
 
-      new ParallelCommandGroup(command1, command2);
+    new ParallelCommandGroup(command1, command2);
 
-      assertThrows(IllegalArgumentException.class, () -> scheduler.schedule(command1));
-    }
+    assertThrows(
+        IllegalArgumentException.class, () -> CommandScheduler.getInstance().schedule(command1));
   }
 
   @Test
@@ -42,7 +41,7 @@
 
     assertDoesNotThrow(() -> command.withTimeout(10).until(() -> false));
     assertThrows(IllegalArgumentException.class, () -> command.withTimeout(10));
-    CommandGroupBase.clearGroupedCommand(command);
+    CommandScheduler.getInstance().removeComposedCommand(command);
     assertDoesNotThrow(() -> command.withTimeout(10));
   }
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandRequirementsTest.java b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandRequirementsTest.java
index b5058c7..47657e1 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandRequirementsTest.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandRequirementsTest.java
@@ -15,7 +15,7 @@
   @Test
   void requirementInterruptTest() {
     try (CommandScheduler scheduler = new CommandScheduler()) {
-      Subsystem requirement = new TestSubsystem();
+      Subsystem requirement = new SubsystemBase() {};
 
       MockCommandHolder interruptedHolder = new MockCommandHolder(true, requirement);
       Command interrupted = interruptedHolder.getMock();
@@ -42,14 +42,15 @@
   @Test
   void requirementUninterruptibleTest() {
     try (CommandScheduler scheduler = new CommandScheduler()) {
-      Subsystem requirement = new TestSubsystem();
+      Subsystem requirement = new SubsystemBase() {};
 
-      MockCommandHolder interruptedHolder = new MockCommandHolder(true, requirement);
-      Command notInterrupted = interruptedHolder.getMock();
+      Command notInterrupted =
+          new RunCommand(() -> {}, requirement)
+              .withInterruptBehavior(Command.InterruptionBehavior.kCancelIncoming);
       MockCommandHolder interrupterHolder = new MockCommandHolder(true, requirement);
       Command interrupter = interrupterHolder.getMock();
 
-      scheduler.schedule(false, notInterrupted);
+      scheduler.schedule(notInterrupted);
       scheduler.schedule(interrupter);
 
       assertTrue(scheduler.isScheduled(notInterrupted));
@@ -60,15 +61,13 @@
   @Test
   void defaultCommandRequirementErrorTest() {
     try (CommandScheduler scheduler = new CommandScheduler()) {
-      Subsystem system = new TestSubsystem();
+      Subsystem system = new SubsystemBase() {};
 
       Command missingRequirement = new WaitUntilCommand(() -> false);
-      Command ends = new InstantCommand(() -> {}, system);
 
       assertThrows(
           IllegalArgumentException.class,
           () -> scheduler.setDefaultCommand(system, missingRequirement));
-      assertThrows(IllegalArgumentException.class, () -> scheduler.setDefaultCommand(system, ends));
     }
   }
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandScheduleTest.java b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandScheduleTest.java
index a30a6ca..c0295f5 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandScheduleTest.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandScheduleTest.java
@@ -66,7 +66,7 @@
       MockCommandHolder command3Holder = new MockCommandHolder(true);
       Command command3 = command3Holder.getMock();
 
-      scheduler.schedule(true, command1, command2, command3);
+      scheduler.schedule(command1, command2, command3);
       assertTrue(scheduler.isScheduled(command1, command2, command3));
       scheduler.run();
       assertTrue(scheduler.isScheduled(command1, command2, command3));
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandTestBase.java b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandTestBase.java
index 151399d..1d46fb5 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandTestBase.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandTestBase.java
@@ -9,10 +9,11 @@
 
 import edu.wpi.first.wpilibj.DriverStation;
 import edu.wpi.first.wpilibj.simulation.DriverStationSim;
+import edu.wpi.first.wpilibj2.command.Command.InterruptionBehavior;
 import java.util.Set;
 import org.junit.jupiter.api.BeforeEach;
 
-/** Basic setup for all {@link Command tests}." */
+/** Basic setup for all {@link Command tests}. */
 public class CommandTestBase {
   protected CommandTestBase() {}
 
@@ -20,8 +21,8 @@
   void commandSetup() {
     CommandScheduler.getInstance().cancelAll();
     CommandScheduler.getInstance().enable();
-    CommandScheduler.getInstance().clearButtons();
-    CommandGroupBase.clearGroupedCommands();
+    CommandScheduler.getInstance().getActiveButtonLoop().clear();
+    CommandScheduler.getInstance().clearComposedCommands();
 
     setDSEnabled(true);
   }
@@ -31,7 +32,6 @@
 
     DriverStationSim.setEnabled(enabled);
     DriverStationSim.notifyNewData();
-    DriverStation.isNewControlData();
     while (DriverStation.isEnabled() != enabled) {
       try {
         Thread.sleep(1);
@@ -41,8 +41,6 @@
     }
   }
 
-  public static class TestSubsystem extends SubsystemBase {}
-
   public static class MockCommandHolder {
     private final Command m_mockCommand = mock(Command.class);
 
@@ -50,6 +48,7 @@
       when(m_mockCommand.getRequirements()).thenReturn(Set.of(requirements));
       when(m_mockCommand.isFinished()).thenReturn(false);
       when(m_mockCommand.runsWhenDisabled()).thenReturn(runWhenDisabled);
+      when(m_mockCommand.getInterruptionBehavior()).thenReturn(InterruptionBehavior.kCancelSelf);
     }
 
     public Command getMock() {
@@ -60,24 +59,4 @@
       when(m_mockCommand.isFinished()).thenReturn(finished);
     }
   }
-
-  public static class Counter {
-    public int m_counter;
-
-    public void increment() {
-      m_counter++;
-    }
-  }
-
-  public static class ConditionHolder {
-    private boolean m_condition;
-
-    public void setCondition(boolean condition) {
-      m_condition = condition;
-    }
-
-    public boolean getCondition() {
-      return m_condition;
-    }
-  }
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ConditionalCommandTest.java b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ConditionalCommandTest.java
index ccf4205..420a8a7 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ConditionalCommandTest.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ConditionalCommandTest.java
@@ -38,9 +38,9 @@
 
   @Test
   void conditionalCommandRequirementTest() {
-    Subsystem system1 = new TestSubsystem();
-    Subsystem system2 = new TestSubsystem();
-    Subsystem system3 = new TestSubsystem();
+    Subsystem system1 = new SubsystemBase() {};
+    Subsystem system2 = new SubsystemBase() {};
+    Subsystem system3 = new SubsystemBase() {};
 
     try (CommandScheduler scheduler = new CommandScheduler()) {
       MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2);
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/DefaultCommandTest.java b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/DefaultCommandTest.java
index dc910fc..23ae47d 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/DefaultCommandTest.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/DefaultCommandTest.java
@@ -14,7 +14,7 @@
   @Test
   void defaultCommandScheduleTest() {
     try (CommandScheduler scheduler = new CommandScheduler()) {
-      TestSubsystem hasDefaultCommand = new TestSubsystem();
+      Subsystem hasDefaultCommand = new SubsystemBase() {};
 
       MockCommandHolder defaultHolder = new MockCommandHolder(true, hasDefaultCommand);
       Command defaultCommand = defaultHolder.getMock();
@@ -29,7 +29,7 @@
   @Test
   void defaultCommandInterruptResumeTest() {
     try (CommandScheduler scheduler = new CommandScheduler()) {
-      TestSubsystem hasDefaultCommand = new TestSubsystem();
+      Subsystem hasDefaultCommand = new SubsystemBase() {};
 
       MockCommandHolder defaultHolder = new MockCommandHolder(true, hasDefaultCommand);
       Command defaultCommand = defaultHolder.getMock();
@@ -54,7 +54,7 @@
   @Test
   void defaultCommandDisableResumeTest() {
     try (CommandScheduler scheduler = new CommandScheduler()) {
-      TestSubsystem hasDefaultCommand = new TestSubsystem();
+      Subsystem hasDefaultCommand = new SubsystemBase() {};
 
       MockCommandHolder defaultHolder = new MockCommandHolder(false, hasDefaultCommand);
       Command defaultCommand = defaultHolder.getMock();
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/FunctionalCommandTest.java b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/FunctionalCommandTest.java
index e6a073f..f983e8a 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/FunctionalCommandTest.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/FunctionalCommandTest.java
@@ -7,37 +7,38 @@
 import static org.junit.jupiter.api.Assertions.assertFalse;
 import static org.junit.jupiter.api.Assertions.assertTrue;
 
+import java.util.concurrent.atomic.AtomicBoolean;
 import org.junit.jupiter.api.Test;
 
 class FunctionalCommandTest extends CommandTestBase {
   @Test
   void functionalCommandScheduleTest() {
     try (CommandScheduler scheduler = new CommandScheduler()) {
-      ConditionHolder cond1 = new ConditionHolder();
-      ConditionHolder cond2 = new ConditionHolder();
-      ConditionHolder cond3 = new ConditionHolder();
-      ConditionHolder cond4 = new ConditionHolder();
+      AtomicBoolean cond1 = new AtomicBoolean();
+      AtomicBoolean cond2 = new AtomicBoolean();
+      AtomicBoolean cond3 = new AtomicBoolean();
+      AtomicBoolean cond4 = new AtomicBoolean();
 
       FunctionalCommand command =
           new FunctionalCommand(
-              () -> cond1.setCondition(true),
-              () -> cond2.setCondition(true),
-              interrupted -> cond3.setCondition(true),
-              cond4::getCondition);
+              () -> cond1.set(true),
+              () -> cond2.set(true),
+              interrupted -> cond3.set(true),
+              cond4::get);
 
       scheduler.schedule(command);
       scheduler.run();
 
       assertTrue(scheduler.isScheduled(command));
 
-      cond4.setCondition(true);
+      cond4.set(true);
 
       scheduler.run();
 
       assertFalse(scheduler.isScheduled(command));
-      assertTrue(cond1.getCondition());
-      assertTrue(cond2.getCondition());
-      assertTrue(cond3.getCondition());
+      assertTrue(cond1.get());
+      assertTrue(cond2.get());
+      assertTrue(cond3.get());
     }
   }
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/InstantCommandTest.java b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/InstantCommandTest.java
index 88c55a6..813a44a 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/InstantCommandTest.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/InstantCommandTest.java
@@ -7,20 +7,21 @@
 import static org.junit.jupiter.api.Assertions.assertFalse;
 import static org.junit.jupiter.api.Assertions.assertTrue;
 
+import java.util.concurrent.atomic.AtomicBoolean;
 import org.junit.jupiter.api.Test;
 
 class InstantCommandTest extends CommandTestBase {
   @Test
   void instantCommandScheduleTest() {
     try (CommandScheduler scheduler = new CommandScheduler()) {
-      ConditionHolder cond = new ConditionHolder();
+      AtomicBoolean cond = new AtomicBoolean();
 
-      InstantCommand command = new InstantCommand(() -> cond.setCondition(true));
+      InstantCommand command = new InstantCommand(() -> cond.set(true));
 
       scheduler.schedule(command);
       scheduler.run();
 
-      assertTrue(cond.getCondition());
+      assertTrue(cond.get());
       assertFalse(scheduler.isScheduled(command));
     }
   }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/MecanumControllerCommandTest.java b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/MecanumControllerCommandTest.java
index ac158c2..b8ccea5 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/MecanumControllerCommandTest.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/MecanumControllerCommandTest.java
@@ -15,6 +15,7 @@
 import edu.wpi.first.math.geometry.Translation2d;
 import edu.wpi.first.math.kinematics.MecanumDriveKinematics;
 import edu.wpi.first.math.kinematics.MecanumDriveOdometry;
+import edu.wpi.first.math.kinematics.MecanumDriveWheelPositions;
 import edu.wpi.first.math.kinematics.MecanumDriveWheelSpeeds;
 import edu.wpi.first.math.trajectory.TrajectoryConfig;
 import edu.wpi.first.math.trajectory.TrajectoryGenerator;
@@ -43,9 +44,13 @@
   private Rotation2d m_angle = new Rotation2d(0);
 
   private double m_frontLeftSpeed;
+  private double m_frontLeftDistance;
   private double m_rearLeftSpeed;
+  private double m_rearLeftDistance;
   private double m_frontRightSpeed;
+  private double m_frontRightDistance;
   private double m_rearRightSpeed;
+  private double m_rearRightDistance;
 
   private final ProfiledPIDController m_rotController =
       new ProfiledPIDController(1, 0, 0, new TrapezoidProfile.Constraints(3 * Math.PI, Math.PI));
@@ -66,7 +71,10 @@
 
   private final MecanumDriveOdometry m_odometry =
       new MecanumDriveOdometry(
-          m_kinematics, new Rotation2d(0), new Pose2d(0, 0, new Rotation2d(0)));
+          m_kinematics,
+          new Rotation2d(0),
+          new MecanumDriveWheelPositions(),
+          new Pose2d(0, 0, new Rotation2d(0)));
 
   public void setWheelSpeeds(MecanumDriveWheelSpeeds wheelSpeeds) {
     this.m_frontLeftSpeed = wheelSpeeds.frontLeftMetersPerSecond;
@@ -75,13 +83,13 @@
     this.m_rearRightSpeed = wheelSpeeds.rearRightMetersPerSecond;
   }
 
-  public MecanumDriveWheelSpeeds getCurrentWheelSpeeds() {
-    return new MecanumDriveWheelSpeeds(
-        m_frontLeftSpeed, m_frontRightSpeed, m_rearLeftSpeed, m_rearRightSpeed);
+  public MecanumDriveWheelPositions getCurrentWheelDistances() {
+    return new MecanumDriveWheelPositions(
+        m_frontLeftDistance, m_frontRightDistance, m_rearLeftDistance, m_rearRightDistance);
   }
 
   public Pose2d getRobotPose() {
-    m_odometry.updateWithTime(m_timer.get(), m_angle, getCurrentWheelSpeeds());
+    m_odometry.update(m_angle, getCurrentWheelDistances());
     return m_odometry.getPoseMeters();
   }
 
@@ -117,6 +125,10 @@
     while (!command.isFinished()) {
       command.execute();
       m_angle = trajectory.sample(m_timer.get()).poseMeters.getRotation();
+      m_frontLeftDistance += m_frontLeftSpeed * 0.005;
+      m_rearLeftDistance += m_rearLeftSpeed * 0.005;
+      m_frontRightDistance += m_frontRightSpeed * 0.005;
+      m_rearRightDistance += m_rearRightSpeed * 0.005;
       SimHooks.stepTiming(0.005);
     }
     m_timer.stop();
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/MultiCompositionTestBase.java b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/MultiCompositionTestBase.java
new file mode 100644
index 0000000..2b79550
--- /dev/null
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/MultiCompositionTestBase.java
@@ -0,0 +1,115 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj2.command;
+
+import static org.junit.jupiter.api.Assertions.assertEquals;
+import static org.junit.jupiter.params.provider.Arguments.arguments;
+
+import edu.wpi.first.wpilibj2.command.Command.InterruptionBehavior;
+import java.util.stream.Stream;
+import org.junit.jupiter.params.ParameterizedTest;
+import org.junit.jupiter.params.provider.Arguments;
+import org.junit.jupiter.params.provider.MethodSource;
+
+interface MultiCompositionTestBase<T extends Command> extends SingleCompositionTestBase<T> {
+  T compose(Command... members);
+
+  @Override
+  default T composeSingle(Command member) {
+    return compose(member);
+  }
+
+  static Stream<Arguments> interruptible() {
+    return Stream.of(
+        arguments(
+            "AllCancelSelf",
+            InterruptionBehavior.kCancelSelf,
+            new WaitUntilCommand(() -> false)
+                .withInterruptBehavior(InterruptionBehavior.kCancelSelf),
+            new WaitUntilCommand(() -> false)
+                .withInterruptBehavior(InterruptionBehavior.kCancelSelf),
+            new WaitUntilCommand(() -> false)
+                .withInterruptBehavior(InterruptionBehavior.kCancelSelf)),
+        arguments(
+            "AllCancelIncoming",
+            InterruptionBehavior.kCancelIncoming,
+            new WaitUntilCommand(() -> false)
+                .withInterruptBehavior(InterruptionBehavior.kCancelIncoming),
+            new WaitUntilCommand(() -> false)
+                .withInterruptBehavior(InterruptionBehavior.kCancelIncoming),
+            new WaitUntilCommand(() -> false)
+                .withInterruptBehavior(InterruptionBehavior.kCancelIncoming)),
+        arguments(
+            "TwoCancelSelfOneIncoming",
+            InterruptionBehavior.kCancelSelf,
+            new WaitUntilCommand(() -> false)
+                .withInterruptBehavior(InterruptionBehavior.kCancelSelf),
+            new WaitUntilCommand(() -> false)
+                .withInterruptBehavior(InterruptionBehavior.kCancelSelf),
+            new WaitUntilCommand(() -> false)
+                .withInterruptBehavior(InterruptionBehavior.kCancelIncoming)),
+        arguments(
+            "TwoCancelIncomingOneSelf",
+            InterruptionBehavior.kCancelSelf,
+            new WaitUntilCommand(() -> false)
+                .withInterruptBehavior(InterruptionBehavior.kCancelIncoming),
+            new WaitUntilCommand(() -> false)
+                .withInterruptBehavior(InterruptionBehavior.kCancelIncoming),
+            new WaitUntilCommand(() -> false)
+                .withInterruptBehavior(InterruptionBehavior.kCancelSelf)));
+  }
+
+  @MethodSource
+  @ParameterizedTest(name = "interruptible[{index}]: {0}")
+  default void interruptible(
+      @SuppressWarnings("unused") String name,
+      InterruptionBehavior expected,
+      Command command1,
+      Command command2,
+      Command command3) {
+    var command = compose(command1, command2, command3);
+    assertEquals(expected, command.getInterruptionBehavior());
+  }
+
+  static Stream<Arguments> runsWhenDisabled() {
+    return Stream.of(
+        arguments(
+            "AllFalse",
+            false,
+            new WaitUntilCommand(() -> false).ignoringDisable(false),
+            new WaitUntilCommand(() -> false).ignoringDisable(false),
+            new WaitUntilCommand(() -> false).ignoringDisable(false)),
+        arguments(
+            "AllTrue",
+            true,
+            new WaitUntilCommand(() -> false).ignoringDisable(true),
+            new WaitUntilCommand(() -> false).ignoringDisable(true),
+            new WaitUntilCommand(() -> false).ignoringDisable(true)),
+        arguments(
+            "TwoTrueOneFalse",
+            false,
+            new WaitUntilCommand(() -> false).ignoringDisable(true),
+            new WaitUntilCommand(() -> false).ignoringDisable(true),
+            new WaitUntilCommand(() -> false).ignoringDisable(false)),
+        arguments(
+            "TwoFalseOneTrue",
+            false,
+            new WaitUntilCommand(() -> false).ignoringDisable(false),
+            new WaitUntilCommand(() -> false).ignoringDisable(false),
+            new WaitUntilCommand(() -> false).ignoringDisable(true)));
+  }
+
+  @MethodSource
+  @ParameterizedTest(name = "runsWhenDisabled[{index}]: {0}")
+  default void runsWhenDisabled(
+      @SuppressWarnings("unused") String name,
+      boolean expected,
+      Command command1,
+      Command command2,
+      Command command3) {
+    var command = compose(command1, command2, command3);
+    assertEquals(expected, command.runsWhenDisabled());
+  }
+}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/NotifierCommandTest.java b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/NotifierCommandTest.java
index 283a3de..4928cb1 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/NotifierCommandTest.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/NotifierCommandTest.java
@@ -8,6 +8,7 @@
 
 import edu.wpi.first.hal.HAL;
 import edu.wpi.first.wpilibj.simulation.SimHooks;
+import java.util.concurrent.atomic.AtomicInteger;
 import org.junit.jupiter.api.AfterEach;
 import org.junit.jupiter.api.BeforeEach;
 import org.junit.jupiter.api.Test;
@@ -29,9 +30,9 @@
   @ResourceLock("timing")
   void notifierCommandScheduleTest() {
     try (CommandScheduler scheduler = new CommandScheduler()) {
-      Counter counter = new Counter();
+      AtomicInteger counter = new AtomicInteger(0);
 
-      NotifierCommand command = new NotifierCommand(counter::increment, 0.01);
+      NotifierCommand command = new NotifierCommand(counter::incrementAndGet, 0.01);
 
       scheduler.schedule(command);
       for (int i = 0; i < 5; ++i) {
@@ -39,7 +40,7 @@
       }
       scheduler.cancel(command);
 
-      assertEquals(2, counter.m_counter);
+      assertEquals(2, counter.get());
     }
   }
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ParallelCommandGroupTest.java b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ParallelCommandGroupTest.java
index afc32ae..7dc9110 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ParallelCommandGroupTest.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ParallelCommandGroupTest.java
@@ -14,7 +14,8 @@
 
 import org.junit.jupiter.api.Test;
 
-class ParallelCommandGroupTest extends CommandTestBase {
+class ParallelCommandGroupTest extends CommandTestBase
+    implements MultiCompositionTestBase<ParallelCommandGroup> {
   @Test
   void parallelGroupScheduleTest() {
     try (CommandScheduler scheduler = new CommandScheduler()) {
@@ -89,10 +90,10 @@
 
   @Test
   void parallelGroupRequirementTest() {
-    Subsystem system1 = new TestSubsystem();
-    Subsystem system2 = new TestSubsystem();
-    Subsystem system3 = new TestSubsystem();
-    Subsystem system4 = new TestSubsystem();
+    Subsystem system1 = new SubsystemBase() {};
+    Subsystem system2 = new SubsystemBase() {};
+    Subsystem system3 = new SubsystemBase() {};
+    Subsystem system4 = new SubsystemBase() {};
 
     try (CommandScheduler scheduler = new CommandScheduler()) {
       MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2);
@@ -114,9 +115,9 @@
 
   @Test
   void parallelGroupRequirementErrorTest() {
-    Subsystem system1 = new TestSubsystem();
-    Subsystem system2 = new TestSubsystem();
-    Subsystem system3 = new TestSubsystem();
+    Subsystem system1 = new SubsystemBase() {};
+    Subsystem system2 = new SubsystemBase() {};
+    Subsystem system3 = new SubsystemBase() {};
 
     MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2);
     Command command1 = command1Holder.getMock();
@@ -126,4 +127,9 @@
     assertThrows(
         IllegalArgumentException.class, () -> new ParallelCommandGroup(command1, command2));
   }
+
+  @Override
+  public ParallelCommandGroup compose(Command... members) {
+    return new ParallelCommandGroup(members);
+  }
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ParallelDeadlineGroupTest.java b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ParallelDeadlineGroupTest.java
index 1fe3866..6fa644b 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ParallelDeadlineGroupTest.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ParallelDeadlineGroupTest.java
@@ -11,9 +11,11 @@
 import static org.mockito.Mockito.verify;
 import static org.mockito.internal.verification.VerificationModeFactory.times;
 
+import java.util.Arrays;
 import org.junit.jupiter.api.Test;
 
-class ParallelDeadlineGroupTest extends CommandTestBase {
+class ParallelDeadlineGroupTest extends CommandTestBase
+    implements MultiCompositionTestBase<ParallelDeadlineGroup> {
   @Test
   void parallelDeadlineScheduleTest() {
     try (CommandScheduler scheduler = new CommandScheduler()) {
@@ -85,10 +87,10 @@
 
   @Test
   void parallelDeadlineRequirementTest() {
-    Subsystem system1 = new TestSubsystem();
-    Subsystem system2 = new TestSubsystem();
-    Subsystem system3 = new TestSubsystem();
-    Subsystem system4 = new TestSubsystem();
+    Subsystem system1 = new SubsystemBase() {};
+    Subsystem system2 = new SubsystemBase() {};
+    Subsystem system3 = new SubsystemBase() {};
+    Subsystem system4 = new SubsystemBase() {};
 
     try (CommandScheduler scheduler = new CommandScheduler()) {
       MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2);
@@ -110,9 +112,9 @@
 
   @Test
   void parallelDeadlineRequirementErrorTest() {
-    Subsystem system1 = new TestSubsystem();
-    Subsystem system2 = new TestSubsystem();
-    Subsystem system3 = new TestSubsystem();
+    Subsystem system1 = new SubsystemBase() {};
+    Subsystem system2 = new SubsystemBase() {};
+    Subsystem system3 = new SubsystemBase() {};
 
     MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2);
     Command command1 = command1Holder.getMock();
@@ -122,4 +124,9 @@
     assertThrows(
         IllegalArgumentException.class, () -> new ParallelDeadlineGroup(command1, command2));
   }
+
+  @Override
+  public ParallelDeadlineGroup compose(Command... members) {
+    return new ParallelDeadlineGroup(members[0], Arrays.copyOfRange(members, 1, members.length));
+  }
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ParallelRaceGroupTest.java b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ParallelRaceGroupTest.java
index 3201a52..6752496 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ParallelRaceGroupTest.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ParallelRaceGroupTest.java
@@ -16,7 +16,8 @@
 
 import org.junit.jupiter.api.Test;
 
-class ParallelRaceGroupTest extends CommandTestBase {
+class ParallelRaceGroupTest extends CommandTestBase
+    implements MultiCompositionTestBase<ParallelRaceGroup> {
   @Test
   void parallelRaceScheduleTest() {
     try (CommandScheduler scheduler = new CommandScheduler()) {
@@ -91,10 +92,10 @@
 
   @Test
   void parallelRaceRequirementTest() {
-    Subsystem system1 = new TestSubsystem();
-    Subsystem system2 = new TestSubsystem();
-    Subsystem system3 = new TestSubsystem();
-    Subsystem system4 = new TestSubsystem();
+    Subsystem system1 = new SubsystemBase() {};
+    Subsystem system2 = new SubsystemBase() {};
+    Subsystem system3 = new SubsystemBase() {};
+    Subsystem system4 = new SubsystemBase() {};
 
     try (CommandScheduler scheduler = new CommandScheduler()) {
       MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2);
@@ -116,9 +117,9 @@
 
   @Test
   void parallelRaceRequirementErrorTest() {
-    Subsystem system1 = new TestSubsystem();
-    Subsystem system2 = new TestSubsystem();
-    Subsystem system3 = new TestSubsystem();
+    Subsystem system1 = new SubsystemBase() {};
+    Subsystem system2 = new SubsystemBase() {};
+    Subsystem system3 = new SubsystemBase() {};
 
     MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2);
     Command command1 = command1Holder.getMock();
@@ -130,15 +131,15 @@
 
   @Test
   void parallelRaceOnlyCallsEndOnceTest() {
-    Subsystem system1 = new TestSubsystem();
-    Subsystem system2 = new TestSubsystem();
+    Subsystem system1 = new SubsystemBase() {};
+    Subsystem system2 = new SubsystemBase() {};
 
     MockCommandHolder command1Holder = new MockCommandHolder(true, system1);
     Command command1 = command1Holder.getMock();
     MockCommandHolder command2Holder = new MockCommandHolder(true, system2);
     Command command2 = command2Holder.getMock();
-    MockCommandHolder perpetualCommandHolder = new MockCommandHolder(true);
-    Command command3 = new PerpetualCommand(perpetualCommandHolder.getMock());
+    MockCommandHolder command3Holder = new MockCommandHolder(true);
+    Command command3 = command3Holder.getMock();
 
     Command group1 = new SequentialCommandGroup(command1, command2);
     assertNotNull(group1);
@@ -153,6 +154,7 @@
       command2Holder.setFinished(true);
       // at this point the sequential group should be done
       assertDoesNotThrow(() -> scheduler.run());
+      assertFalse(scheduler.isScheduled(group2));
     }
   }
 
@@ -201,4 +203,9 @@
       assertFalse(scheduler.isScheduled(group));
     }
   }
+
+  @Override
+  public ParallelRaceGroup compose(Command... members) {
+    return new ParallelRaceGroup(members);
+  }
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/PerpetualCommandTest.java b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/PerpetualCommandTest.java
index f9e93a3..6b9690b 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/PerpetualCommandTest.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/PerpetualCommandTest.java
@@ -9,6 +9,7 @@
 import org.junit.jupiter.api.Test;
 
 class PerpetualCommandTest extends CommandTestBase {
+  @SuppressWarnings("removal") // PerpetualCommand
   @Test
   void perpetualCommandScheduleTest() {
     try (CommandScheduler scheduler = new CommandScheduler()) {
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ProxyCommandTest.java b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ProxyCommandTest.java
new file mode 100644
index 0000000..c4b43a6
--- /dev/null
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ProxyCommandTest.java
@@ -0,0 +1,49 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj2.command;
+
+import static org.junit.jupiter.api.Assertions.assertFalse;
+import static org.junit.jupiter.api.Assertions.assertTrue;
+import static org.mockito.Mockito.verify;
+
+import java.util.concurrent.atomic.AtomicBoolean;
+import org.junit.jupiter.api.Test;
+
+class ProxyCommandTest extends CommandTestBase {
+  @Test
+  void proxyCommandScheduleTest() {
+    try (CommandScheduler scheduler = new CommandScheduler()) {
+      MockCommandHolder command1Holder = new MockCommandHolder(true);
+      Command command1 = command1Holder.getMock();
+
+      ProxyCommand scheduleCommand = new ProxyCommand(command1);
+
+      scheduler.schedule(scheduleCommand);
+
+      verify(command1).schedule();
+    }
+  }
+
+  @Test
+  void proxyCommandEndTest() {
+    try (CommandScheduler scheduler = CommandScheduler.getInstance()) {
+      AtomicBoolean cond = new AtomicBoolean();
+
+      WaitUntilCommand command = new WaitUntilCommand(cond::get);
+
+      ProxyCommand scheduleCommand = new ProxyCommand(command);
+
+      scheduler.schedule(scheduleCommand);
+
+      scheduler.run();
+      assertTrue(scheduler.isScheduled(scheduleCommand));
+
+      cond.set(true);
+      scheduler.run();
+      scheduler.run();
+      assertFalse(scheduler.isScheduled(scheduleCommand));
+    }
+  }
+}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ProxyScheduleCommandTest.java b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ProxyScheduleCommandTest.java
deleted file mode 100644
index 3c34688..0000000
--- a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ProxyScheduleCommandTest.java
+++ /dev/null
@@ -1,48 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj2.command;
-
-import static org.junit.jupiter.api.Assertions.assertFalse;
-import static org.junit.jupiter.api.Assertions.assertTrue;
-import static org.mockito.Mockito.verify;
-
-import org.junit.jupiter.api.Test;
-
-class ProxyScheduleCommandTest extends CommandTestBase {
-  @Test
-  void proxyScheduleCommandScheduleTest() {
-    try (CommandScheduler scheduler = new CommandScheduler()) {
-      MockCommandHolder command1Holder = new MockCommandHolder(true);
-      Command command1 = command1Holder.getMock();
-
-      ProxyScheduleCommand scheduleCommand = new ProxyScheduleCommand(command1);
-
-      scheduler.schedule(scheduleCommand);
-
-      verify(command1).schedule();
-    }
-  }
-
-  @Test
-  void proxyScheduleCommandEndTest() {
-    try (CommandScheduler scheduler = CommandScheduler.getInstance()) {
-      ConditionHolder cond = new ConditionHolder();
-
-      WaitUntilCommand command = new WaitUntilCommand(cond::getCondition);
-
-      ProxyScheduleCommand scheduleCommand = new ProxyScheduleCommand(command);
-
-      scheduler.schedule(scheduleCommand);
-
-      scheduler.run();
-      assertTrue(scheduler.isScheduled(scheduleCommand));
-
-      cond.setCondition(true);
-      scheduler.run();
-      scheduler.run();
-      assertFalse(scheduler.isScheduled(scheduleCommand));
-    }
-  }
-}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/RepeatCommandTest.java b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/RepeatCommandTest.java
new file mode 100644
index 0000000..f082ddb
--- /dev/null
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/RepeatCommandTest.java
@@ -0,0 +1,71 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj2.command;
+
+import static org.junit.jupiter.api.Assertions.assertEquals;
+
+import java.util.concurrent.atomic.AtomicBoolean;
+import java.util.concurrent.atomic.AtomicInteger;
+import org.junit.jupiter.api.Test;
+
+class RepeatCommandTest extends CommandTestBase
+    implements SingleCompositionTestBase<RepeatCommand> {
+  @Test
+  void callsMethodsCorrectly() {
+    var initCounter = new AtomicInteger(0);
+    var exeCounter = new AtomicInteger(0);
+    var isFinishedCounter = new AtomicInteger(0);
+    var endCounter = new AtomicInteger(0);
+    var isFinishedHook = new AtomicBoolean(false);
+
+    final var command =
+        new FunctionalCommand(
+                initCounter::incrementAndGet,
+                exeCounter::incrementAndGet,
+                interrupted -> endCounter.incrementAndGet(),
+                () -> {
+                  isFinishedCounter.incrementAndGet();
+                  return isFinishedHook.get();
+                })
+            .repeatedly();
+
+    assertEquals(0, initCounter.get());
+    assertEquals(0, exeCounter.get());
+    assertEquals(0, isFinishedCounter.get());
+    assertEquals(0, endCounter.get());
+
+    CommandScheduler.getInstance().schedule(command);
+    assertEquals(1, initCounter.get());
+    assertEquals(0, exeCounter.get());
+    assertEquals(0, isFinishedCounter.get());
+    assertEquals(0, endCounter.get());
+
+    isFinishedHook.set(false);
+    CommandScheduler.getInstance().run();
+    assertEquals(1, initCounter.get());
+    assertEquals(1, exeCounter.get());
+    assertEquals(1, isFinishedCounter.get());
+    assertEquals(0, endCounter.get());
+
+    isFinishedHook.set(true);
+    CommandScheduler.getInstance().run();
+    assertEquals(1, initCounter.get());
+    assertEquals(2, exeCounter.get());
+    assertEquals(2, isFinishedCounter.get());
+    assertEquals(1, endCounter.get());
+
+    isFinishedHook.set(false);
+    CommandScheduler.getInstance().run();
+    assertEquals(2, initCounter.get());
+    assertEquals(3, exeCounter.get());
+    assertEquals(3, isFinishedCounter.get());
+    assertEquals(1, endCounter.get());
+  }
+
+  @Override
+  public RepeatCommand composeSingle(Command member) {
+    return member.repeatedly();
+  }
+}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/RobotDisabledCommandTest.java b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/RobotDisabledCommandTest.java
index b807c71..0914c25 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/RobotDisabledCommandTest.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/RobotDisabledCommandTest.java
@@ -4,7 +4,7 @@
 
 package edu.wpi.first.wpilibj2.command;
 
-import static edu.wpi.first.wpilibj2.command.CommandGroupBase.parallel;
+import static edu.wpi.first.wpilibj2.command.Commands.parallel;
 import static org.junit.jupiter.api.Assertions.assertFalse;
 import static org.junit.jupiter.api.Assertions.assertTrue;
 
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/RunCommandTest.java b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/RunCommandTest.java
index 92e2d75..1f63487 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/RunCommandTest.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/RunCommandTest.java
@@ -6,22 +6,23 @@
 
 import static org.junit.jupiter.api.Assertions.assertEquals;
 
+import java.util.concurrent.atomic.AtomicInteger;
 import org.junit.jupiter.api.Test;
 
 class RunCommandTest extends CommandTestBase {
   @Test
   void runCommandScheduleTest() {
     try (CommandScheduler scheduler = new CommandScheduler()) {
-      Counter counter = new Counter();
+      AtomicInteger counter = new AtomicInteger(0);
 
-      RunCommand command = new RunCommand(counter::increment);
+      RunCommand command = new RunCommand(counter::incrementAndGet);
 
       scheduler.schedule(command);
       scheduler.run();
       scheduler.run();
       scheduler.run();
 
-      assertEquals(3, counter.m_counter);
+      assertEquals(3, counter.get());
     }
   }
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ScheduleCommandTest.java b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ScheduleCommandTest.java
index c9ae4b2..9014bc7 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ScheduleCommandTest.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ScheduleCommandTest.java
@@ -36,7 +36,7 @@
           new SequentialCommandGroup(new InstantCommand(), scheduleCommand);
 
       scheduler.schedule(group);
-      scheduler.schedule(new InstantCommand().perpetually());
+      scheduler.schedule(new RunCommand(() -> {}));
       scheduler.run();
       assertDoesNotThrow(scheduler::run);
     }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SchedulerTest.java b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SchedulerTest.java
index 558ef57..7a62f5e 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SchedulerTest.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SchedulerTest.java
@@ -7,45 +7,46 @@
 import static org.junit.jupiter.api.Assertions.assertDoesNotThrow;
 import static org.junit.jupiter.api.Assertions.assertEquals;
 
+import java.util.concurrent.atomic.AtomicInteger;
 import org.junit.jupiter.api.Test;
 
 class SchedulerTest extends CommandTestBase {
   @Test
   void schedulerLambdaTestNoInterrupt() {
     try (CommandScheduler scheduler = new CommandScheduler()) {
-      Counter counter = new Counter();
+      AtomicInteger counter = new AtomicInteger();
 
-      scheduler.onCommandInitialize(command -> counter.increment());
-      scheduler.onCommandExecute(command -> counter.increment());
-      scheduler.onCommandFinish(command -> counter.increment());
+      scheduler.onCommandInitialize(command -> counter.incrementAndGet());
+      scheduler.onCommandExecute(command -> counter.incrementAndGet());
+      scheduler.onCommandFinish(command -> counter.incrementAndGet());
 
       scheduler.schedule(new InstantCommand());
       scheduler.run();
 
-      assertEquals(counter.m_counter, 3);
+      assertEquals(counter.get(), 3);
     }
   }
 
   @Test
   void schedulerInterruptLambdaTest() {
     try (CommandScheduler scheduler = new CommandScheduler()) {
-      Counter counter = new Counter();
+      AtomicInteger counter = new AtomicInteger();
 
-      scheduler.onCommandInterrupt(command -> counter.increment());
+      scheduler.onCommandInterrupt(command -> counter.incrementAndGet());
 
       Command command = new WaitCommand(10);
 
       scheduler.schedule(command);
       scheduler.cancel(command);
 
-      assertEquals(counter.m_counter, 1);
+      assertEquals(counter.get(), 1);
     }
   }
 
   @Test
   void unregisterSubsystemTest() {
     try (CommandScheduler scheduler = new CommandScheduler()) {
-      Subsystem system = new TestSubsystem();
+      Subsystem system = new SubsystemBase() {};
 
       scheduler.registerSubsystem(system);
       assertDoesNotThrow(() -> scheduler.unregisterSubsystem(system));
@@ -55,9 +56,9 @@
   @Test
   void schedulerCancelAllTest() {
     try (CommandScheduler scheduler = new CommandScheduler()) {
-      Counter counter = new Counter();
+      AtomicInteger counter = new AtomicInteger();
 
-      scheduler.onCommandInterrupt(command -> counter.increment());
+      scheduler.onCommandInterrupt(command -> counter.incrementAndGet());
 
       Command command = new WaitCommand(10);
       Command command2 = new WaitCommand(10);
@@ -66,7 +67,21 @@
       scheduler.schedule(command2);
       scheduler.cancelAll();
 
-      assertEquals(counter.m_counter, 2);
+      assertEquals(counter.get(), 2);
+    }
+  }
+
+  @Test
+  void scheduleScheduledNoOp() {
+    try (CommandScheduler scheduler = new CommandScheduler()) {
+      AtomicInteger counter = new AtomicInteger();
+
+      Command command = Commands.startEnd(counter::incrementAndGet, () -> {});
+
+      scheduler.schedule(command);
+      scheduler.schedule(command);
+
+      assertEquals(counter.get(), 1);
     }
   }
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SchedulingRecursionTest.java b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SchedulingRecursionTest.java
new file mode 100644
index 0000000..28e9e6f
--- /dev/null
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SchedulingRecursionTest.java
@@ -0,0 +1,204 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj2.command;
+
+import static org.junit.jupiter.api.Assertions.assertDoesNotThrow;
+import static org.junit.jupiter.api.Assertions.assertEquals;
+import static org.junit.jupiter.api.Assertions.assertFalse;
+import static org.junit.jupiter.api.Assertions.assertTrue;
+
+import edu.wpi.first.wpilibj2.command.Command.InterruptionBehavior;
+import java.util.concurrent.atomic.AtomicBoolean;
+import java.util.concurrent.atomic.AtomicInteger;
+import org.junit.jupiter.api.Test;
+import org.junit.jupiter.params.ParameterizedTest;
+import org.junit.jupiter.params.provider.EnumSource;
+
+class SchedulingRecursionTest extends CommandTestBase {
+  /**
+   * <a href="https://github.com/wpilibsuite/allwpilib/issues/4259">wpilibsuite/allwpilib#4259</a>.
+   */
+  @EnumSource(InterruptionBehavior.class)
+  @ParameterizedTest
+  void cancelFromInitialize(InterruptionBehavior interruptionBehavior) {
+    try (CommandScheduler scheduler = new CommandScheduler()) {
+      AtomicBoolean hasOtherRun = new AtomicBoolean();
+      Subsystem requirement = new SubsystemBase() {};
+      Command selfCancels =
+          new CommandBase() {
+            {
+              addRequirements(requirement);
+            }
+
+            @Override
+            public void initialize() {
+              scheduler.cancel(this);
+            }
+
+            @Override
+            public InterruptionBehavior getInterruptionBehavior() {
+              return interruptionBehavior;
+            }
+          };
+      Command other = new RunCommand(() -> hasOtherRun.set(true), requirement);
+
+      assertDoesNotThrow(
+          () -> {
+            scheduler.schedule(selfCancels);
+            scheduler.run();
+            scheduler.schedule(other);
+          });
+      assertFalse(scheduler.isScheduled(selfCancels));
+      assertTrue(scheduler.isScheduled(other));
+      scheduler.run();
+      assertTrue(hasOtherRun.get());
+    }
+  }
+
+  @EnumSource(InterruptionBehavior.class)
+  @ParameterizedTest
+  void defaultCommandGetsRescheduledAfterSelfCanceling(InterruptionBehavior interruptionBehavior) {
+    try (CommandScheduler scheduler = new CommandScheduler()) {
+      AtomicBoolean hasOtherRun = new AtomicBoolean();
+      Subsystem requirement = new SubsystemBase() {};
+      Command selfCancels =
+          new CommandBase() {
+            {
+              addRequirements(requirement);
+            }
+
+            @Override
+            public void initialize() {
+              scheduler.cancel(this);
+            }
+
+            @Override
+            public InterruptionBehavior getInterruptionBehavior() {
+              return interruptionBehavior;
+            }
+          };
+      Command other = new RunCommand(() -> hasOtherRun.set(true), requirement);
+      scheduler.setDefaultCommand(requirement, other);
+
+      assertDoesNotThrow(
+          () -> {
+            scheduler.schedule(selfCancels);
+            scheduler.run();
+          });
+      scheduler.run();
+      assertFalse(scheduler.isScheduled(selfCancels));
+      assertTrue(scheduler.isScheduled(other));
+      scheduler.run();
+      assertTrue(hasOtherRun.get());
+    }
+  }
+
+  @Test
+  void cancelFromEnd() {
+    try (CommandScheduler scheduler = new CommandScheduler()) {
+      AtomicInteger counter = new AtomicInteger();
+      Command selfCancels =
+          new CommandBase() {
+            @Override
+            public void end(boolean interrupted) {
+              counter.incrementAndGet();
+              scheduler.cancel(this);
+            }
+          };
+      scheduler.schedule(selfCancels);
+
+      assertDoesNotThrow(() -> scheduler.cancel(selfCancels));
+      assertEquals(1, counter.get());
+      assertFalse(scheduler.isScheduled(selfCancels));
+    }
+  }
+
+  @Test
+  void scheduleFromEndCancel() {
+    try (CommandScheduler scheduler = new CommandScheduler()) {
+      AtomicInteger counter = new AtomicInteger();
+      Subsystem requirement = new SubsystemBase() {};
+      InstantCommand other = new InstantCommand(() -> {}, requirement);
+      Command selfCancels =
+          new CommandBase() {
+            {
+              addRequirements(requirement);
+            }
+
+            @Override
+            public void end(boolean interrupted) {
+              counter.incrementAndGet();
+              scheduler.schedule(other);
+            }
+          };
+
+      scheduler.schedule(selfCancels);
+
+      assertDoesNotThrow(() -> scheduler.cancel(selfCancels));
+      assertEquals(1, counter.get());
+      assertFalse(scheduler.isScheduled(selfCancels));
+    }
+  }
+
+  @Test
+  void scheduleFromEndInterrupt() {
+    try (CommandScheduler scheduler = new CommandScheduler()) {
+      AtomicInteger counter = new AtomicInteger();
+      Subsystem requirement = new SubsystemBase() {};
+      InstantCommand other = new InstantCommand(() -> {}, requirement);
+      Command selfCancels =
+          new CommandBase() {
+            {
+              addRequirements(requirement);
+            }
+
+            @Override
+            public void end(boolean interrupted) {
+              counter.incrementAndGet();
+              scheduler.schedule(other);
+            }
+          };
+
+      scheduler.schedule(selfCancels);
+
+      assertDoesNotThrow(() -> scheduler.schedule(other));
+      assertEquals(1, counter.get());
+      assertFalse(scheduler.isScheduled(selfCancels));
+      assertTrue(scheduler.isScheduled(other));
+    }
+  }
+
+  @ParameterizedTest
+  @EnumSource(InterruptionBehavior.class)
+  void scheduleInitializeFromDefaultCommand(InterruptionBehavior interruptionBehavior) {
+    try (CommandScheduler scheduler = new CommandScheduler()) {
+      AtomicInteger counter = new AtomicInteger();
+      Subsystem requirement = new SubsystemBase() {};
+      Command other =
+          new InstantCommand(() -> {}, requirement).withInterruptBehavior(interruptionBehavior);
+      Command defaultCommand =
+          new CommandBase() {
+            {
+              addRequirements(requirement);
+            }
+
+            @Override
+            public void initialize() {
+              counter.incrementAndGet();
+              scheduler.schedule(other);
+            }
+          };
+
+      scheduler.setDefaultCommand(requirement, defaultCommand);
+
+      scheduler.run();
+      scheduler.run();
+      scheduler.run();
+      assertEquals(3, counter.get());
+      assertFalse(scheduler.isScheduled(defaultCommand));
+      assertTrue(scheduler.isScheduled(other));
+    }
+  }
+}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SelectCommandTest.java b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SelectCommandTest.java
index de40ef8..736f120 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SelectCommandTest.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SelectCommandTest.java
@@ -9,10 +9,11 @@
 import static org.mockito.Mockito.never;
 import static org.mockito.Mockito.verify;
 
+import java.util.HashMap;
 import java.util.Map;
 import org.junit.jupiter.api.Test;
 
-class SelectCommandTest extends CommandTestBase {
+class SelectCommandTest extends CommandTestBase implements MultiCompositionTestBase<SelectCommand> {
   @Test
   void selectCommandTest() {
     try (CommandScheduler scheduler = new CommandScheduler()) {
@@ -74,10 +75,10 @@
 
   @Test
   void selectCommandRequirementTest() {
-    Subsystem system1 = new TestSubsystem();
-    Subsystem system2 = new TestSubsystem();
-    Subsystem system3 = new TestSubsystem();
-    Subsystem system4 = new TestSubsystem();
+    Subsystem system1 = new SubsystemBase() {};
+    Subsystem system2 = new SubsystemBase() {};
+    Subsystem system3 = new SubsystemBase() {};
+    Subsystem system4 = new SubsystemBase() {};
 
     try (CommandScheduler scheduler = new CommandScheduler()) {
       MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2);
@@ -105,4 +106,13 @@
       verify(command3, never()).end(true);
     }
   }
+
+  @Override
+  public SelectCommand compose(Command... members) {
+    var map = new HashMap<Object, Command>();
+    for (int i = 0; i < members.length; i++) {
+      map.put(i, members[i]);
+    }
+    return new SelectCommand(map, () -> 0);
+  }
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SequentialCommandGroupTest.java b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SequentialCommandGroupTest.java
index 811034c..ff578f4 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SequentialCommandGroupTest.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SequentialCommandGroupTest.java
@@ -12,7 +12,8 @@
 
 import org.junit.jupiter.api.Test;
 
-class SequentialCommandGroupTest extends CommandTestBase {
+class SequentialCommandGroupTest extends CommandTestBase
+    implements MultiCompositionTestBase<SequentialCommandGroup> {
   @Test
   void sequentialGroupScheduleTest() {
     try (CommandScheduler scheduler = new CommandScheduler()) {
@@ -99,10 +100,10 @@
 
   @Test
   void sequentialGroupRequirementTest() {
-    Subsystem system1 = new TestSubsystem();
-    Subsystem system2 = new TestSubsystem();
-    Subsystem system3 = new TestSubsystem();
-    Subsystem system4 = new TestSubsystem();
+    Subsystem system1 = new SubsystemBase() {};
+    Subsystem system2 = new SubsystemBase() {};
+    Subsystem system3 = new SubsystemBase() {};
+    Subsystem system4 = new SubsystemBase() {};
 
     try (CommandScheduler scheduler = new CommandScheduler()) {
       MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2);
@@ -121,4 +122,9 @@
       assertTrue(scheduler.isScheduled(command3));
     }
   }
+
+  @Override
+  public SequentialCommandGroup compose(Command... members) {
+    return new SequentialCommandGroup(members);
+  }
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SingleCompositionTestBase.java b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SingleCompositionTestBase.java
new file mode 100644
index 0000000..4e54e3e
--- /dev/null
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SingleCompositionTestBase.java
@@ -0,0 +1,32 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj2.command;
+
+import static org.junit.jupiter.api.Assertions.assertEquals;
+
+import org.junit.jupiter.params.ParameterizedTest;
+import org.junit.jupiter.params.provider.EnumSource;
+import org.junit.jupiter.params.provider.ValueSource;
+
+public interface SingleCompositionTestBase<T extends Command> {
+  T composeSingle(Command member);
+
+  @EnumSource(Command.InterruptionBehavior.class)
+  @ParameterizedTest
+  default void interruptible(Command.InterruptionBehavior interruptionBehavior) {
+    var command =
+        composeSingle(
+            new WaitUntilCommand(() -> false).withInterruptBehavior(interruptionBehavior));
+    assertEquals(interruptionBehavior, command.getInterruptionBehavior());
+  }
+
+  @ValueSource(booleans = {true, false})
+  @ParameterizedTest
+  default void runWhenDisabled(boolean runsWhenDisabled) {
+    var command =
+        composeSingle(new WaitUntilCommand(() -> false).ignoringDisable(runsWhenDisabled));
+    assertEquals(runsWhenDisabled, command.runsWhenDisabled());
+  }
+}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/StartEndCommandTest.java b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/StartEndCommandTest.java
index 60c5c44..db0d792 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/StartEndCommandTest.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/StartEndCommandTest.java
@@ -7,17 +7,17 @@
 import static org.junit.jupiter.api.Assertions.assertFalse;
 import static org.junit.jupiter.api.Assertions.assertTrue;
 
+import java.util.concurrent.atomic.AtomicBoolean;
 import org.junit.jupiter.api.Test;
 
 class StartEndCommandTest extends CommandTestBase {
   @Test
   void startEndCommandScheduleTest() {
     try (CommandScheduler scheduler = new CommandScheduler()) {
-      ConditionHolder cond1 = new ConditionHolder();
-      ConditionHolder cond2 = new ConditionHolder();
+      AtomicBoolean cond1 = new AtomicBoolean();
+      AtomicBoolean cond2 = new AtomicBoolean();
 
-      StartEndCommand command =
-          new StartEndCommand(() -> cond1.setCondition(true), () -> cond2.setCondition(true));
+      StartEndCommand command = new StartEndCommand(() -> cond1.set(true), () -> cond2.set(true));
 
       scheduler.schedule(command);
       scheduler.run();
@@ -27,8 +27,8 @@
       scheduler.cancel(command);
 
       assertFalse(scheduler.isScheduled(command));
-      assertTrue(cond1.getCondition());
-      assertTrue(cond2.getCondition());
+      assertTrue(cond1.get());
+      assertTrue(cond2.get());
     }
   }
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SwerveControllerCommandTest.java b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SwerveControllerCommandTest.java
index 0cf6d67..1367e51 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SwerveControllerCommandTest.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SwerveControllerCommandTest.java
@@ -15,6 +15,7 @@
 import edu.wpi.first.math.geometry.Translation2d;
 import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
 import edu.wpi.first.math.kinematics.SwerveDriveOdometry;
+import edu.wpi.first.math.kinematics.SwerveModulePosition;
 import edu.wpi.first.math.kinematics.SwerveModuleState;
 import edu.wpi.first.math.trajectory.TrajectoryConfig;
 import edu.wpi.first.math.trajectory.TrajectoryGenerator;
@@ -50,6 +51,14 @@
         new SwerveModuleState(0, new Rotation2d(0))
       };
 
+  private SwerveModulePosition[] m_modulePositions =
+      new SwerveModulePosition[] {
+        new SwerveModulePosition(0, new Rotation2d(0)),
+        new SwerveModulePosition(0, new Rotation2d(0)),
+        new SwerveModulePosition(0, new Rotation2d(0)),
+        new SwerveModulePosition(0, new Rotation2d(0))
+      };
+
   private final ProfiledPIDController m_rotController =
       new ProfiledPIDController(1, 0, 0, new TrapezoidProfile.Constraints(3 * Math.PI, Math.PI));
 
@@ -68,7 +77,8 @@
           new Translation2d(-kWheelBase / 2, -kTrackWidth / 2));
 
   private final SwerveDriveOdometry m_odometry =
-      new SwerveDriveOdometry(m_kinematics, new Rotation2d(0), new Pose2d(0, 0, new Rotation2d(0)));
+      new SwerveDriveOdometry(
+          m_kinematics, new Rotation2d(0), m_modulePositions, new Pose2d(0, 0, new Rotation2d(0)));
 
   @SuppressWarnings("PMD.ArrayIsStoredDirectly")
   public void setModuleStates(SwerveModuleState[] moduleStates) {
@@ -76,7 +86,7 @@
   }
 
   public Pose2d getRobotPose() {
-    m_odometry.updateWithTime(m_timer.get(), m_angle, m_moduleStates);
+    m_odometry.update(m_angle, m_modulePositions);
     return m_odometry.getPoseMeters();
   }
 
@@ -111,6 +121,12 @@
     while (!command.isFinished()) {
       command.execute();
       m_angle = trajectory.sample(m_timer.get()).poseMeters.getRotation();
+
+      for (int i = 0; i < m_modulePositions.length; i++) {
+        m_modulePositions[i].distanceMeters += m_moduleStates[i].speedMetersPerSecond * 0.005;
+        m_modulePositions[i].angle = m_moduleStates[i].angle;
+      }
+
       SimHooks.stepTiming(0.005);
     }
     m_timer.stop();
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/WaitUntilCommandTest.java b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/WaitUntilCommandTest.java
index 85539dc..e91ae4e 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/WaitUntilCommandTest.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/WaitUntilCommandTest.java
@@ -7,20 +7,21 @@
 import static org.junit.jupiter.api.Assertions.assertFalse;
 import static org.junit.jupiter.api.Assertions.assertTrue;
 
+import java.util.concurrent.atomic.AtomicBoolean;
 import org.junit.jupiter.api.Test;
 
 class WaitUntilCommandTest extends CommandTestBase {
   @Test
   void waitUntilTest() {
     try (CommandScheduler scheduler = new CommandScheduler()) {
-      ConditionHolder condition = new ConditionHolder();
+      AtomicBoolean condition = new AtomicBoolean();
 
-      Command command = new WaitUntilCommand(condition::getCondition);
+      Command command = new WaitUntilCommand(condition::get);
 
       scheduler.schedule(command);
       scheduler.run();
       assertTrue(scheduler.isScheduled(command));
-      condition.setCondition(true);
+      condition.set(true);
       scheduler.run();
       assertFalse(scheduler.isScheduled(command));
     }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/button/ButtonTest.java b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/button/ButtonTest.java
deleted file mode 100644
index 1a4f05d..0000000
--- a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/button/ButtonTest.java
+++ /dev/null
@@ -1,198 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj2.command.button;
-
-import static org.junit.jupiter.api.Assertions.assertEquals;
-import static org.junit.jupiter.api.Assertions.assertFalse;
-import static org.junit.jupiter.api.Assertions.assertTrue;
-import static org.mockito.Mockito.never;
-import static org.mockito.Mockito.times;
-import static org.mockito.Mockito.verify;
-import static org.mockito.Mockito.when;
-
-import edu.wpi.first.wpilibj.simulation.SimHooks;
-import edu.wpi.first.wpilibj2.command.Command;
-import edu.wpi.first.wpilibj2.command.CommandScheduler;
-import edu.wpi.first.wpilibj2.command.CommandTestBase;
-import org.junit.jupiter.api.Test;
-
-class ButtonTest extends CommandTestBase {
-  @Test
-  void whenPressedTest() {
-    CommandScheduler scheduler = CommandScheduler.getInstance();
-    MockCommandHolder command1Holder = new MockCommandHolder(true);
-    Command command1 = command1Holder.getMock();
-
-    InternalButton button = new InternalButton();
-    button.setPressed(false);
-    button.whenPressed(command1);
-    scheduler.run();
-    verify(command1, never()).schedule(true);
-    button.setPressed(true);
-    scheduler.run();
-    scheduler.run();
-    verify(command1).schedule(true);
-  }
-
-  @Test
-  void whenReleasedTest() {
-    CommandScheduler scheduler = CommandScheduler.getInstance();
-    MockCommandHolder command1Holder = new MockCommandHolder(true);
-    Command command1 = command1Holder.getMock();
-
-    InternalButton button = new InternalButton();
-    button.setPressed(true);
-    button.whenReleased(command1);
-    scheduler.run();
-    verify(command1, never()).schedule(true);
-    button.setPressed(false);
-    scheduler.run();
-    scheduler.run();
-    verify(command1).schedule(true);
-  }
-
-  @Test
-  void whileHeldTest() {
-    CommandScheduler scheduler = CommandScheduler.getInstance();
-    MockCommandHolder command1Holder = new MockCommandHolder(true);
-    Command command1 = command1Holder.getMock();
-
-    InternalButton button = new InternalButton();
-    button.setPressed(false);
-    button.whileHeld(command1);
-    scheduler.run();
-    verify(command1, never()).schedule(true);
-    button.setPressed(true);
-    scheduler.run();
-    scheduler.run();
-    verify(command1, times(2)).schedule(true);
-    button.setPressed(false);
-    scheduler.run();
-    verify(command1).cancel();
-  }
-
-  @Test
-  void whenHeldTest() {
-    CommandScheduler scheduler = CommandScheduler.getInstance();
-    MockCommandHolder command1Holder = new MockCommandHolder(true);
-    Command command1 = command1Holder.getMock();
-
-    InternalButton button = new InternalButton();
-    button.setPressed(false);
-    button.whenHeld(command1);
-    scheduler.run();
-    verify(command1, never()).schedule(true);
-    button.setPressed(true);
-    scheduler.run();
-    scheduler.run();
-    verify(command1).schedule(true);
-    button.setPressed(false);
-    scheduler.run();
-    verify(command1).cancel();
-  }
-
-  @Test
-  void toggleWhenPressedTest() {
-    CommandScheduler scheduler = CommandScheduler.getInstance();
-    MockCommandHolder command1Holder = new MockCommandHolder(true);
-    Command command1 = command1Holder.getMock();
-
-    InternalButton button = new InternalButton();
-    button.setPressed(false);
-    button.toggleWhenPressed(command1);
-    scheduler.run();
-    verify(command1, never()).schedule(true);
-    button.setPressed(true);
-    scheduler.run();
-    when(command1.isScheduled()).thenReturn(true);
-    scheduler.run();
-    verify(command1).schedule(true);
-    button.setPressed(false);
-    scheduler.run();
-    verify(command1, never()).cancel();
-    button.setPressed(true);
-    scheduler.run();
-    verify(command1).cancel();
-  }
-
-  @Test
-  void cancelWhenPressedTest() {
-    CommandScheduler scheduler = CommandScheduler.getInstance();
-    MockCommandHolder command1Holder = new MockCommandHolder(true);
-    Command command1 = command1Holder.getMock();
-
-    InternalButton button = new InternalButton();
-    button.setPressed(false);
-    button.cancelWhenPressed(command1);
-    scheduler.run();
-    verify(command1, never()).cancel();
-    button.setPressed(true);
-    scheduler.run();
-    scheduler.run();
-    verify(command1).cancel();
-  }
-
-  @Test
-  void runnableBindingTest() {
-    InternalButton buttonWhenPressed = new InternalButton();
-    InternalButton buttonWhileHeld = new InternalButton();
-    InternalButton buttonWhenReleased = new InternalButton();
-
-    buttonWhenPressed.setPressed(false);
-    buttonWhileHeld.setPressed(true);
-    buttonWhenReleased.setPressed(true);
-
-    Counter counter = new Counter();
-
-    buttonWhenPressed.whenPressed(counter::increment);
-    buttonWhileHeld.whileHeld(counter::increment);
-    buttonWhenReleased.whenReleased(counter::increment);
-
-    CommandScheduler scheduler = CommandScheduler.getInstance();
-
-    scheduler.run();
-    buttonWhenPressed.setPressed(true);
-    buttonWhenReleased.setPressed(false);
-    scheduler.run();
-
-    assertEquals(counter.m_counter, 4);
-  }
-
-  @Test
-  void buttonCompositionTest() {
-    InternalButton button1 = new InternalButton();
-    InternalButton button2 = new InternalButton();
-
-    button1.setPressed(true);
-    button2.setPressed(false);
-
-    assertFalse(button1.and(button2).get());
-    assertTrue(button1.or(button2).get());
-    assertFalse(button1.negate().get());
-    assertTrue(button1.and(button2.negate()).get());
-  }
-
-  @Test
-  void debounceTest() {
-    CommandScheduler scheduler = CommandScheduler.getInstance();
-    MockCommandHolder commandHolder = new MockCommandHolder(true);
-    Command command = commandHolder.getMock();
-
-    InternalButton button = new InternalButton();
-    Trigger debounced = button.debounce(0.1);
-
-    debounced.whenActive(command);
-
-    button.setPressed(true);
-    scheduler.run();
-    verify(command, never()).schedule(true);
-
-    SimHooks.stepTiming(0.3);
-
-    button.setPressed(true);
-    scheduler.run();
-    verify(command).schedule(true);
-  }
-}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/button/NetworkButtonTest.java b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/button/NetworkButtonTest.java
index 9502977..b9adc13 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/button/NetworkButtonTest.java
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/button/NetworkButtonTest.java
@@ -15,15 +15,17 @@
 import org.junit.jupiter.api.Test;
 
 class NetworkButtonTest extends CommandTestBase {
+  NetworkTableInstance m_inst;
+
   @BeforeEach
   void setup() {
-    NetworkTableInstance.getDefault().startLocal();
+    m_inst = NetworkTableInstance.create();
+    m_inst.startLocal();
   }
 
   @AfterEach
   void teardown() {
-    NetworkTableInstance.getDefault().deleteAllEntries();
-    NetworkTableInstance.getDefault().stopLocal();
+    m_inst.close();
   }
 
   @Test
@@ -31,16 +33,16 @@
     var scheduler = CommandScheduler.getInstance();
     var commandHolder = new MockCommandHolder(true);
     var command = commandHolder.getMock();
-    var entry = NetworkTableInstance.getDefault().getTable("TestTable").getEntry("Test");
+    var pub = m_inst.getTable("TestTable").getBooleanTopic("Test").publish();
 
-    var button = new NetworkButton("TestTable", "Test");
-    entry.setBoolean(false);
-    button.whenPressed(command);
+    var button = new NetworkButton(m_inst, "TestTable", "Test");
+    pub.set(false);
+    button.onTrue(command);
     scheduler.run();
-    verify(command, never()).schedule(true);
-    entry.setBoolean(true);
+    verify(command, never()).schedule();
+    pub.set(true);
     scheduler.run();
     scheduler.run();
-    verify(command).schedule(true);
+    verify(command).schedule();
   }
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/button/TriggerTest.java b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/button/TriggerTest.java
new file mode 100644
index 0000000..82d359c
--- /dev/null
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/button/TriggerTest.java
@@ -0,0 +1,280 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj2.command.button;
+
+import static org.junit.jupiter.api.Assertions.assertEquals;
+import static org.junit.jupiter.api.Assertions.assertFalse;
+import static org.junit.jupiter.api.Assertions.assertTrue;
+import static org.mockito.Mockito.never;
+import static org.mockito.Mockito.verify;
+
+import edu.wpi.first.wpilibj.simulation.SimHooks;
+import edu.wpi.first.wpilibj2.command.Command;
+import edu.wpi.first.wpilibj2.command.CommandScheduler;
+import edu.wpi.first.wpilibj2.command.CommandTestBase;
+import edu.wpi.first.wpilibj2.command.FunctionalCommand;
+import edu.wpi.first.wpilibj2.command.RunCommand;
+import edu.wpi.first.wpilibj2.command.StartEndCommand;
+import edu.wpi.first.wpilibj2.command.WaitUntilCommand;
+import java.util.concurrent.atomic.AtomicBoolean;
+import java.util.concurrent.atomic.AtomicInteger;
+import java.util.function.BooleanSupplier;
+import org.junit.jupiter.api.Test;
+
+class TriggerTest extends CommandTestBase {
+  @Test
+  void onTrueTest() {
+    CommandScheduler scheduler = CommandScheduler.getInstance();
+    AtomicBoolean finished = new AtomicBoolean(false);
+    Command command1 = new WaitUntilCommand(finished::get);
+
+    InternalButton button = new InternalButton();
+    button.setPressed(false);
+    button.onTrue(command1);
+    scheduler.run();
+    assertFalse(command1.isScheduled());
+    button.setPressed(true);
+    scheduler.run();
+    assertTrue(command1.isScheduled());
+    finished.set(true);
+    scheduler.run();
+    assertFalse(command1.isScheduled());
+  }
+
+  @Test
+  void onFalseTest() {
+    CommandScheduler scheduler = CommandScheduler.getInstance();
+    AtomicBoolean finished = new AtomicBoolean(false);
+    Command command1 = new WaitUntilCommand(finished::get);
+
+    InternalButton button = new InternalButton();
+    button.setPressed(true);
+    button.onFalse(command1);
+    scheduler.run();
+    assertFalse(command1.isScheduled());
+    button.setPressed(false);
+    scheduler.run();
+    assertTrue(command1.isScheduled());
+    finished.set(true);
+    scheduler.run();
+    assertFalse(command1.isScheduled());
+  }
+
+  @Test
+  void whileTrueRepeatedlyTest() {
+    CommandScheduler scheduler = CommandScheduler.getInstance();
+    AtomicInteger inits = new AtomicInteger(0);
+    AtomicInteger counter = new AtomicInteger(0);
+    // the repeatedly() here is the point!
+    Command command1 =
+        new FunctionalCommand(
+                inits::incrementAndGet,
+                () -> {},
+                interrupted -> {},
+                () -> counter.incrementAndGet() % 2 == 0)
+            .repeatedly();
+
+    InternalButton button = new InternalButton();
+    button.setPressed(false);
+    button.whileTrue(command1);
+    scheduler.run();
+    assertEquals(0, inits.get());
+    button.setPressed(true);
+    scheduler.run();
+    assertEquals(1, inits.get());
+    scheduler.run();
+    assertEquals(1, inits.get());
+    scheduler.run();
+    assertEquals(2, inits.get());
+    button.setPressed(false);
+    scheduler.run();
+    assertEquals(2, inits.get());
+  }
+
+  @Test
+  void whileTrueLambdaRunTest() {
+    CommandScheduler scheduler = CommandScheduler.getInstance();
+    AtomicInteger counter = new AtomicInteger(0);
+    // the repeatedly() here is the point!
+    Command command1 = new RunCommand(counter::incrementAndGet);
+
+    InternalButton button = new InternalButton();
+    button.setPressed(false);
+    button.whileTrue(command1);
+    scheduler.run();
+    assertEquals(0, counter.get());
+    button.setPressed(true);
+    scheduler.run();
+    assertEquals(1, counter.get());
+    scheduler.run();
+    assertEquals(2, counter.get());
+    button.setPressed(false);
+    scheduler.run();
+    assertEquals(2, counter.get());
+  }
+
+  @Test
+  void whileTrueOnceTest() {
+    CommandScheduler scheduler = CommandScheduler.getInstance();
+    AtomicInteger startCounter = new AtomicInteger(0);
+    AtomicInteger endCounter = new AtomicInteger(0);
+    Command command1 =
+        new StartEndCommand(startCounter::incrementAndGet, endCounter::incrementAndGet);
+
+    InternalButton button = new InternalButton();
+    button.setPressed(false);
+    button.whileTrue(command1);
+    scheduler.run();
+    assertEquals(0, startCounter.get());
+    assertEquals(0, endCounter.get());
+    button.setPressed(true);
+    scheduler.run();
+    scheduler.run();
+    assertEquals(1, startCounter.get());
+    assertEquals(0, endCounter.get());
+    button.setPressed(false);
+    scheduler.run();
+    assertEquals(1, startCounter.get());
+    assertEquals(1, endCounter.get());
+  }
+
+  @Test
+  void toggleOnTrueTest() {
+    CommandScheduler scheduler = CommandScheduler.getInstance();
+    AtomicInteger startCounter = new AtomicInteger(0);
+    AtomicInteger endCounter = new AtomicInteger(0);
+    Command command1 =
+        new StartEndCommand(startCounter::incrementAndGet, endCounter::incrementAndGet);
+
+    InternalButton button = new InternalButton();
+    button.setPressed(false);
+    button.toggleOnTrue(command1);
+    scheduler.run();
+    assertEquals(0, startCounter.get());
+    assertEquals(0, endCounter.get());
+    button.setPressed(true);
+    scheduler.run();
+    scheduler.run();
+    assertEquals(1, startCounter.get());
+    assertEquals(0, endCounter.get());
+    button.setPressed(false);
+    scheduler.run();
+    assertEquals(1, startCounter.get());
+    assertEquals(0, endCounter.get());
+    button.setPressed(true);
+    scheduler.run();
+    assertEquals(1, startCounter.get());
+    assertEquals(1, endCounter.get());
+  }
+
+  @Test
+  void cancelWhenActiveTest() {
+    CommandScheduler scheduler = CommandScheduler.getInstance();
+    AtomicInteger startCounter = new AtomicInteger(0);
+    AtomicInteger endCounter = new AtomicInteger(0);
+
+    InternalButton button = new InternalButton();
+    Command command1 =
+        new StartEndCommand(startCounter::incrementAndGet, endCounter::incrementAndGet)
+            .until(button);
+
+    button.setPressed(false);
+    command1.schedule();
+    scheduler.run();
+    assertEquals(1, startCounter.get());
+    assertEquals(0, endCounter.get());
+    button.setPressed(true);
+    scheduler.run();
+    assertEquals(1, startCounter.get());
+    assertEquals(1, endCounter.get());
+    scheduler.run();
+    assertEquals(1, startCounter.get());
+    assertEquals(1, endCounter.get());
+  }
+
+  // Binding runnables directly is deprecated -- users should create the command manually
+  @SuppressWarnings("deprecation")
+  @Test
+  void runnableBindingTest() {
+    InternalButton buttonWhenActive = new InternalButton();
+    InternalButton buttonWhileActiveContinuous = new InternalButton();
+    InternalButton buttonWhenInactive = new InternalButton();
+
+    buttonWhenActive.setPressed(false);
+    buttonWhileActiveContinuous.setPressed(true);
+    buttonWhenInactive.setPressed(true);
+
+    AtomicInteger counter = new AtomicInteger(0);
+
+    buttonWhenActive.whenPressed(counter::incrementAndGet);
+    buttonWhileActiveContinuous.whileActiveContinuous(counter::incrementAndGet);
+    buttonWhenInactive.whenInactive(counter::incrementAndGet);
+
+    CommandScheduler scheduler = CommandScheduler.getInstance();
+
+    scheduler.run();
+    buttonWhenActive.setPressed(true);
+    buttonWhenInactive.setPressed(false);
+    scheduler.run();
+
+    assertEquals(counter.get(), 4);
+  }
+
+  @Test
+  void triggerCompositionTest() {
+    InternalButton button1 = new InternalButton();
+    InternalButton button2 = new InternalButton();
+
+    button1.setPressed(true);
+    button2.setPressed(false);
+
+    assertFalse(button1.and(button2).getAsBoolean());
+    assertTrue(button1.or(button2).getAsBoolean());
+    assertFalse(button1.negate().getAsBoolean());
+    assertTrue(button1.and(button2.negate()).getAsBoolean());
+  }
+
+  @Test
+  void triggerCompositionSupplierTest() {
+    InternalButton button1 = new InternalButton();
+    BooleanSupplier booleanSupplier = () -> false;
+
+    button1.setPressed(true);
+
+    assertFalse(button1.and(booleanSupplier).getAsBoolean());
+    assertTrue(button1.or(booleanSupplier).getAsBoolean());
+  }
+
+  @Test
+  void debounceTest() {
+    CommandScheduler scheduler = CommandScheduler.getInstance();
+    MockCommandHolder commandHolder = new MockCommandHolder(true);
+    Command command = commandHolder.getMock();
+
+    InternalButton button = new InternalButton();
+    Trigger debounced = button.debounce(0.1);
+
+    debounced.onTrue(command);
+
+    button.setPressed(true);
+    scheduler.run();
+    verify(command, never()).schedule();
+
+    SimHooks.stepTiming(0.3);
+
+    button.setPressed(true);
+    scheduler.run();
+    verify(command).schedule();
+  }
+
+  @Test
+  void booleanSupplierTest() {
+    InternalButton button = new InternalButton();
+
+    assertFalse(button.getAsBoolean());
+    button.setPressed(true);
+    assertTrue(button.getAsBoolean());
+  }
+}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandDecoratorTest.cpp b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandDecoratorTest.cpp
index 4a7c137..5ab184c 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandDecoratorTest.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandDecoratorTest.cpp
@@ -5,6 +5,8 @@
 #include <frc/simulation/SimHooks.h>
 
 #include "CommandTestBase.h"
+#include "frc2/command/ConditionalCommand.h"
+#include "frc2/command/FunctionalCommand.h"
 #include "frc2/command/InstantCommand.h"
 #include "frc2/command/ParallelRaceGroup.h"
 #include "frc2/command/PerpetualCommand.h"
@@ -21,15 +23,15 @@
 
   auto command = RunCommand([] {}, {}).WithTimeout(100_ms);
 
-  scheduler.Schedule(&command);
+  scheduler.Schedule(command);
 
   scheduler.Run();
-  EXPECT_TRUE(scheduler.IsScheduled(&command));
+  EXPECT_TRUE(scheduler.IsScheduled(command));
 
   frc::sim::StepTiming(150_ms);
 
   scheduler.Run();
-  EXPECT_FALSE(scheduler.IsScheduled(&command));
+  EXPECT_FALSE(scheduler.IsScheduled(command));
 
   frc::sim::ResumeTiming();
 }
@@ -41,15 +43,28 @@
 
   auto command = RunCommand([] {}, {}).Until([&finished] { return finished; });
 
-  scheduler.Schedule(&command);
+  scheduler.Schedule(command);
 
   scheduler.Run();
-  EXPECT_TRUE(scheduler.IsScheduled(&command));
+  EXPECT_TRUE(scheduler.IsScheduled(command));
 
   finished = true;
 
   scheduler.Run();
-  EXPECT_FALSE(scheduler.IsScheduled(&command));
+  EXPECT_FALSE(scheduler.IsScheduled(command));
+}
+
+TEST_F(CommandDecoratorTest, IgnoringDisable) {
+  CommandScheduler scheduler = GetScheduler();
+
+  auto command = RunCommand([] {}, {}).IgnoringDisable(true);
+
+  SetDSEnabled(false);
+
+  scheduler.Schedule(command);
+
+  scheduler.Run();
+  EXPECT_TRUE(scheduler.IsScheduled(command));
 }
 
 TEST_F(CommandDecoratorTest, BeforeStarting) {
@@ -60,14 +75,14 @@
   auto command = InstantCommand([] {}, {}).BeforeStarting(
       [&finished] { finished = true; });
 
-  scheduler.Schedule(&command);
+  scheduler.Schedule(command);
 
   EXPECT_TRUE(finished);
 
   scheduler.Run();
   scheduler.Run();
 
-  EXPECT_FALSE(scheduler.IsScheduled(&command));
+  EXPECT_FALSE(scheduler.IsScheduled(command));
 }
 
 TEST_F(CommandDecoratorTest, AndThen) {
@@ -78,21 +93,23 @@
   auto command =
       InstantCommand([] {}, {}).AndThen([&finished] { finished = true; });
 
-  scheduler.Schedule(&command);
+  scheduler.Schedule(command);
 
   EXPECT_FALSE(finished);
 
   scheduler.Run();
   scheduler.Run();
 
-  EXPECT_FALSE(scheduler.IsScheduled(&command));
+  EXPECT_FALSE(scheduler.IsScheduled(command));
   EXPECT_TRUE(finished);
 }
 
 TEST_F(CommandDecoratorTest, Perpetually) {
   CommandScheduler scheduler = GetScheduler();
 
+  WPI_IGNORE_DEPRECATED
   auto command = InstantCommand([] {}, {}).Perpetually();
+  WPI_UNIGNORE_DEPRECATED
 
   scheduler.Schedule(&command);
 
@@ -101,3 +118,90 @@
 
   EXPECT_TRUE(scheduler.IsScheduled(&command));
 }
+
+TEST_F(CommandDecoratorTest, Unless) {
+  CommandScheduler scheduler = GetScheduler();
+
+  bool hasRun = false;
+  bool unlessBool = true;
+
+  auto command =
+      InstantCommand([&hasRun] { hasRun = true; }, {}).Unless([&unlessBool] {
+        return unlessBool;
+      });
+
+  scheduler.Schedule(command);
+  scheduler.Run();
+  EXPECT_FALSE(hasRun);
+
+  unlessBool = false;
+  scheduler.Schedule(command);
+  scheduler.Run();
+  EXPECT_TRUE(hasRun);
+}
+
+TEST_F(CommandDecoratorTest, FinallyDo) {
+  CommandScheduler scheduler = GetScheduler();
+  int first = 0;
+  int second = 0;
+  CommandPtr command = FunctionalCommand([] {}, [] {},
+                                         [&first](bool interrupted) {
+                                           if (!interrupted) {
+                                             first++;
+                                           }
+                                         },
+                                         [] { return true; })
+                           .FinallyDo([&first, &second](bool interrupted) {
+                             if (!interrupted) {
+                               // to differentiate between "didn't run" and "ran
+                               // before command's `end()`
+                               second += 1 + first;
+                             }
+                           });
+
+  scheduler.Schedule(command);
+  EXPECT_EQ(0, first);
+  EXPECT_EQ(0, second);
+  scheduler.Run();
+  EXPECT_EQ(1, first);
+  // if `second == 0`, neither of the lambdas ran.
+  // if `second == 1`, the second lambda ran before the first one
+  EXPECT_EQ(2, second);
+}
+
+// handleInterruptTest() implicitly tests the interrupt=true branch of
+// finallyDo()
+TEST_F(CommandDecoratorTest, HandleInterrupt) {
+  CommandScheduler scheduler = GetScheduler();
+  int first = 0;
+  int second = 0;
+  CommandPtr command = FunctionalCommand([] {}, [] {},
+                                         [&first](bool interrupted) {
+                                           if (interrupted) {
+                                             first++;
+                                           }
+                                         },
+                                         [] { return false; })
+                           .HandleInterrupt([&first, &second] {
+                             // to differentiate between "didn't run" and "ran
+                             // before command's `end()`
+                             second += 1 + first;
+                           });
+
+  scheduler.Schedule(command);
+  scheduler.Run();
+  EXPECT_EQ(0, first);
+  EXPECT_EQ(0, second);
+
+  scheduler.Cancel(command);
+  // if `second == 0`, neither of the lambdas ran.
+  // if `second == 1`, the second lambda ran before the first one
+  EXPECT_EQ(2, second);
+}
+
+TEST_F(CommandDecoratorTest, WithName) {
+  InstantCommand command;
+  std::string name{"Named"};
+  CommandPtr named = std::move(command).WithName(name);
+  EXPECT_EQ(name, named.get()->GetName());
+}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandPtrTest.cpp b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandPtrTest.cpp
new file mode 100644
index 0000000..26077f2
--- /dev/null
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandPtrTest.cpp
@@ -0,0 +1,35 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <frc/Errors.h>
+
+#include "CommandTestBase.h"
+#include "frc2/command/CommandPtr.h"
+#include "frc2/command/CommandScheduler.h"
+#include "frc2/command/Commands.h"
+
+using namespace frc2;
+class CommandPtrTest : public CommandTestBase {};
+
+TEST_F(CommandPtrTest, MovedFrom) {
+  CommandScheduler scheduler = GetScheduler();
+
+  int counter = 0;
+
+  CommandPtr movedFrom = cmd::Run([&counter] { counter++; });
+  CommandPtr movedTo = std::move(movedFrom);
+
+  EXPECT_NO_FATAL_FAILURE(scheduler.Schedule(movedTo));
+  EXPECT_NO_FATAL_FAILURE(scheduler.Run());
+
+  EXPECT_EQ(1, counter);
+  EXPECT_NO_FATAL_FAILURE(scheduler.Cancel(movedTo));
+
+  EXPECT_THROW(scheduler.Schedule(movedFrom), frc::RuntimeError);
+  EXPECT_THROW(movedFrom.IsScheduled(), frc::RuntimeError);
+  EXPECT_THROW(static_cast<void>(std::move(movedFrom).Repeatedly()),
+               frc::RuntimeError);
+
+  EXPECT_EQ(1, counter);
+}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandRequirementsTest.cpp b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandRequirementsTest.cpp
index c812670..79a472f 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandRequirementsTest.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandRequirementsTest.cpp
@@ -7,6 +7,7 @@
 #include "CommandTestBase.h"
 #include "frc2/command/CommandScheduler.h"
 #include "frc2/command/ConditionalCommand.h"
+#include "frc2/command/FunctionalCommand.h"
 #include "frc2/command/InstantCommand.h"
 #include "frc2/command/ParallelCommandGroup.h"
 #include "frc2/command/ParallelDeadlineGroup.h"
@@ -49,26 +50,35 @@
 
   TestSubsystem requirement;
 
-  MockCommand command1({&requirement});
-  MockCommand command2({&requirement});
+  int initCounter = 0;
+  int exeCounter = 0;
+  int endCounter = 0;
 
-  EXPECT_CALL(command1, Initialize());
-  EXPECT_CALL(command1, Execute()).Times(2);
-  EXPECT_CALL(command1, End(true)).Times(0);
-  EXPECT_CALL(command1, End(false)).Times(0);
+  CommandPtr command1 =
+      FunctionalCommand([&initCounter] { initCounter++; },
+                        [&exeCounter] { exeCounter++; },
+                        [&endCounter](bool interruptible) { endCounter++; },
+                        [] { return false; }, {&requirement})
+          .WithInterruptBehavior(
+              Command::InterruptionBehavior::kCancelIncoming);
+  MockCommand command2({&requirement});
 
   EXPECT_CALL(command2, Initialize()).Times(0);
   EXPECT_CALL(command2, Execute()).Times(0);
   EXPECT_CALL(command2, End(true)).Times(0);
   EXPECT_CALL(command2, End(false)).Times(0);
 
-  scheduler.Schedule(false, &command1);
+  scheduler.Schedule(command1);
+  EXPECT_EQ(1, initCounter);
   scheduler.Run();
-  EXPECT_TRUE(scheduler.IsScheduled(&command1));
+  EXPECT_EQ(1, exeCounter);
+  EXPECT_TRUE(scheduler.IsScheduled(command1));
   scheduler.Schedule(&command2);
-  EXPECT_TRUE(scheduler.IsScheduled(&command1));
+  EXPECT_TRUE(scheduler.IsScheduled(command1));
   EXPECT_FALSE(scheduler.IsScheduled(&command2));
   scheduler.Run();
+  EXPECT_EQ(2, exeCounter);
+  EXPECT_EQ(0, endCounter);
 }
 
 TEST_F(CommandRequirementsTest, DefaultCommandRequirementError) {
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandTestBase.cpp b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandTestBase.cpp
index 7ebbb70..6e27d24 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandTestBase.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandTestBase.cpp
@@ -10,7 +10,7 @@
   auto& scheduler = CommandScheduler::GetInstance();
   scheduler.CancelAll();
   scheduler.Enable();
-  scheduler.ClearButtons();
+  scheduler.GetActiveButtonLoop()->Clear();
 }
 
 CommandScheduler CommandTestBase::GetScheduler() {
@@ -19,12 +19,14 @@
 
 void CommandTestBase::SetUp() {
   frc::sim::DriverStationSim::SetEnabled(true);
+  frc::sim::DriverStationSim::NotifyNewData();
 }
 
 void CommandTestBase::TearDown() {
-  CommandScheduler::GetInstance().ClearButtons();
+  CommandScheduler::GetInstance().GetActiveButtonLoop()->Clear();
 }
 
 void CommandTestBase::SetDSEnabled(bool enabled) {
   frc::sim::DriverStationSim::SetEnabled(enabled);
+  frc::sim::DriverStationSim::NotifyNewData();
 }
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandTestBase.h b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandTestBase.h
index a3890f6..a1ab1de 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandTestBase.h
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandTestBase.h
@@ -9,7 +9,7 @@
 
 #include <frc/simulation/DriverStationSim.h>
 
-#include "frc2/command/CommandGroupBase.h"
+#include "frc2/command/CommandHelper.h"
 #include "frc2/command/CommandScheduler.h"
 #include "frc2/command/SetUtilities.h"
 #include "frc2/command/SubsystemBase.h"
@@ -18,6 +18,7 @@
 #include "make_vector.h"
 
 namespace frc2 {
+
 class CommandTestBase : public ::testing::Test {
  public:
   CommandTestBase();
@@ -25,6 +26,86 @@
   class TestSubsystem : public SubsystemBase {};
 
  protected:
+  /**
+   * NOTE: Moving mock objects causes EXPECT_CALL to not work correctly!
+   */
+  class MockCommand : public CommandHelper<CommandBase, MockCommand> {
+   public:
+    MOCK_CONST_METHOD0(GetRequirements, wpi::SmallSet<Subsystem*, 4>());
+    MOCK_METHOD0(IsFinished, bool());
+    MOCK_CONST_METHOD0(RunsWhenDisabled, bool());
+    MOCK_METHOD0(Initialize, void());
+    MOCK_METHOD0(Execute, void());
+    MOCK_METHOD1(End, void(bool interrupted));
+
+    MockCommand() {
+      m_requirements = {};
+      EXPECT_CALL(*this, GetRequirements())
+          .WillRepeatedly(::testing::Return(m_requirements));
+      EXPECT_CALL(*this, IsFinished()).WillRepeatedly(::testing::Return(false));
+      EXPECT_CALL(*this, RunsWhenDisabled())
+          .WillRepeatedly(::testing::Return(true));
+    }
+
+    MockCommand(std::initializer_list<Subsystem*> requirements,
+                bool finished = false, bool runWhenDisabled = true) {
+      m_requirements.insert(requirements.begin(), requirements.end());
+      EXPECT_CALL(*this, GetRequirements())
+          .WillRepeatedly(::testing::Return(m_requirements));
+      EXPECT_CALL(*this, IsFinished())
+          .WillRepeatedly(::testing::Return(finished));
+      EXPECT_CALL(*this, RunsWhenDisabled())
+          .WillRepeatedly(::testing::Return(runWhenDisabled));
+    }
+
+    MockCommand(MockCommand&& other) {
+      EXPECT_CALL(*this, IsFinished())
+          .WillRepeatedly(::testing::Return(other.IsFinished()));
+      EXPECT_CALL(*this, RunsWhenDisabled())
+          .WillRepeatedly(::testing::Return(other.RunsWhenDisabled()));
+      std::swap(m_requirements, other.m_requirements);
+      EXPECT_CALL(*this, GetRequirements())
+          .WillRepeatedly(::testing::Return(m_requirements));
+    }
+
+    MockCommand(const MockCommand& other) : CommandHelper{other} {}
+
+    void SetFinished(bool finished) {
+      EXPECT_CALL(*this, IsFinished())
+          .WillRepeatedly(::testing::Return(finished));
+    }
+
+    ~MockCommand() {  // NOLINT
+      auto& scheduler = CommandScheduler::GetInstance();
+      scheduler.Cancel(this);
+    }
+
+   private:
+    wpi::SmallSet<Subsystem*, 4> m_requirements;
+  };
+
+  CommandScheduler GetScheduler();
+
+  void SetUp() override;
+
+  void TearDown() override;
+
+  void SetDSEnabled(bool enabled);
+};
+
+template <typename T>
+class CommandTestBaseWithParam : public ::testing::TestWithParam<T> {
+ public:
+  CommandTestBaseWithParam() {
+    auto& scheduler = CommandScheduler::GetInstance();
+    scheduler.CancelAll();
+    scheduler.Enable();
+    scheduler.GetActiveButtonLoop()->Clear();
+  }
+
+  class TestSubsystem : public SubsystemBase {};
+
+ protected:
   class MockCommand : public Command {
    public:
     MOCK_CONST_METHOD0(GetRequirements, wpi::SmallSet<Subsystem*, 4>());
@@ -85,12 +166,17 @@
     wpi::SmallSet<Subsystem*, 4> m_requirements;
   };
 
-  CommandScheduler GetScheduler();
+  CommandScheduler GetScheduler() { return CommandScheduler(); }
 
-  void SetUp() override;
+  void SetUp() override { frc::sim::DriverStationSim::SetEnabled(true); }
 
-  void TearDown() override;
+  void TearDown() override {
+    CommandScheduler::GetInstance().GetActiveButtonLoop()->Clear();
+  }
 
-  void SetDSEnabled(bool enabled);
+  void SetDSEnabled(bool enabled) {
+    frc::sim::DriverStationSim::SetEnabled(enabled);
+  }
 };
+
 }  // namespace frc2
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/CompositionTestBase.h b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/CompositionTestBase.h
new file mode 100644
index 0000000..c12922f
--- /dev/null
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/CompositionTestBase.h
@@ -0,0 +1,204 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <memory>
+#include <utility>
+
+#include "CommandTestBase.h"
+#include "frc2/command/Commands.h"
+#include "gtest/gtest.h"
+#include "make_vector.h"
+
+namespace frc2 {
+
+inline namespace single {
+template <typename T>
+class SingleCompositionRunsWhenDisabledTest : public CommandTestBase {};
+
+TYPED_TEST_SUITE_P(SingleCompositionRunsWhenDisabledTest);
+
+TYPED_TEST_P(SingleCompositionRunsWhenDisabledTest, True) {
+  auto param = true;
+  TypeParam command = TypeParam(
+      cmd::WaitUntil([] { return false; }).IgnoringDisable(param).Unwrap());
+  EXPECT_EQ(param, command.RunsWhenDisabled());
+}
+
+TYPED_TEST_P(SingleCompositionRunsWhenDisabledTest, False) {
+  auto param = false;
+  TypeParam command = TypeParam(
+      cmd::WaitUntil([] { return false; }).IgnoringDisable(param).Unwrap());
+  EXPECT_EQ(param, command.RunsWhenDisabled());
+}
+
+REGISTER_TYPED_TEST_SUITE_P(SingleCompositionRunsWhenDisabledTest, True, False);
+
+template <typename T>
+class SingleCompositionInterruptibilityTest : public CommandTestBase {};
+
+TYPED_TEST_SUITE_P(SingleCompositionInterruptibilityTest);
+
+TYPED_TEST_P(SingleCompositionInterruptibilityTest, CancelSelf) {
+  auto param = Command::InterruptionBehavior::kCancelSelf;
+  TypeParam command = TypeParam(cmd::WaitUntil([] { return false; })
+                                    .WithInterruptBehavior(param)
+                                    .Unwrap());
+  EXPECT_EQ(param, command.GetInterruptionBehavior());
+}
+
+TYPED_TEST_P(SingleCompositionInterruptibilityTest, CancelIncoming) {
+  auto param = Command::InterruptionBehavior::kCancelIncoming;
+  TypeParam command = TypeParam(cmd::WaitUntil([] { return false; })
+                                    .WithInterruptBehavior(param)
+                                    .Unwrap());
+  EXPECT_EQ(param, command.GetInterruptionBehavior());
+}
+
+REGISTER_TYPED_TEST_SUITE_P(SingleCompositionInterruptibilityTest, CancelSelf,
+                            CancelIncoming);
+
+#define INSTANTIATE_SINGLE_COMMAND_COMPOSITION_TEST_SUITE(Suite,               \
+                                                          CompositionType)     \
+  INSTANTIATE_TYPED_TEST_SUITE_P(Suite, SingleCompositionInterruptibilityTest, \
+                                 CompositionType);                             \
+  INSTANTIATE_TYPED_TEST_SUITE_P(Suite, SingleCompositionRunsWhenDisabledTest, \
+                                 CompositionType)
+}  // namespace single
+
+inline namespace multi {
+template <typename T>
+class MultiCompositionRunsWhenDisabledTest : public CommandTestBase {};
+
+TYPED_TEST_SUITE_P(MultiCompositionRunsWhenDisabledTest);
+
+TYPED_TEST_P(MultiCompositionRunsWhenDisabledTest, OneTrue) {
+  auto param = true;
+  TypeParam command = TypeParam(CommandPtr::UnwrapVector(cmd::impl::MakeVector(
+      cmd::WaitUntil([] { return false; }).IgnoringDisable(param))));
+  EXPECT_EQ(param, command.RunsWhenDisabled());
+}
+
+TYPED_TEST_P(MultiCompositionRunsWhenDisabledTest, OneFalse) {
+  auto param = false;
+  TypeParam command = TypeParam(CommandPtr::UnwrapVector(cmd::impl::MakeVector(
+      cmd::WaitUntil([] { return false; }).IgnoringDisable(param))));
+  EXPECT_EQ(param, command.RunsWhenDisabled());
+}
+
+TYPED_TEST_P(MultiCompositionRunsWhenDisabledTest, AllTrue) {
+  TypeParam command = TypeParam(CommandPtr::UnwrapVector(cmd::impl::MakeVector(
+      cmd::WaitUntil([] { return false; }).IgnoringDisable(true),
+      cmd::WaitUntil([] { return false; }).IgnoringDisable(true),
+      cmd::WaitUntil([] { return false; }).IgnoringDisable(true))));
+  EXPECT_EQ(true, command.RunsWhenDisabled());
+}
+
+TYPED_TEST_P(MultiCompositionRunsWhenDisabledTest, AllFalse) {
+  TypeParam command = TypeParam(CommandPtr::UnwrapVector(cmd::impl::MakeVector(
+      cmd::WaitUntil([] { return false; }).IgnoringDisable(false),
+      cmd::WaitUntil([] { return false; }).IgnoringDisable(false),
+      cmd::WaitUntil([] { return false; }).IgnoringDisable(false))));
+  EXPECT_EQ(false, command.RunsWhenDisabled());
+}
+
+TYPED_TEST_P(MultiCompositionRunsWhenDisabledTest, TwoTrueOneFalse) {
+  TypeParam command = TypeParam(CommandPtr::UnwrapVector(cmd::impl::MakeVector(
+      cmd::WaitUntil([] { return false; }).IgnoringDisable(true),
+      cmd::WaitUntil([] { return false; }).IgnoringDisable(true),
+      cmd::WaitUntil([] { return false; }).IgnoringDisable(false))));
+  EXPECT_EQ(false, command.RunsWhenDisabled());
+}
+
+TYPED_TEST_P(MultiCompositionRunsWhenDisabledTest, TwoFalseOneTrue) {
+  TypeParam command = TypeParam(CommandPtr::UnwrapVector(cmd::impl::MakeVector(
+      cmd::WaitUntil([] { return false; }).IgnoringDisable(false),
+      cmd::WaitUntil([] { return false; }).IgnoringDisable(false),
+      cmd::WaitUntil([] { return false; }).IgnoringDisable(true))));
+  EXPECT_EQ(false, command.RunsWhenDisabled());
+}
+
+REGISTER_TYPED_TEST_SUITE_P(MultiCompositionRunsWhenDisabledTest, OneTrue,
+                            OneFalse, AllTrue, AllFalse, TwoTrueOneFalse,
+                            TwoFalseOneTrue);
+
+template <typename T>
+class MultiCompositionInterruptibilityTest
+    : public SingleCompositionInterruptibilityTest<T> {};
+
+TYPED_TEST_SUITE_P(MultiCompositionInterruptibilityTest);
+
+TYPED_TEST_P(MultiCompositionInterruptibilityTest, AllCancelSelf) {
+  TypeParam command = TypeParam(CommandPtr::UnwrapVector(cmd::impl::MakeVector(
+      cmd::WaitUntil([] {
+        return false;
+      }).WithInterruptBehavior(Command::InterruptionBehavior::kCancelSelf),
+      cmd::WaitUntil([] {
+        return false;
+      }).WithInterruptBehavior(Command::InterruptionBehavior::kCancelSelf),
+      cmd::WaitUntil([] {
+        return false;
+      }).WithInterruptBehavior(Command::InterruptionBehavior::kCancelSelf))));
+  EXPECT_EQ(Command::InterruptionBehavior::kCancelSelf,
+            command.GetInterruptionBehavior());
+}
+
+TYPED_TEST_P(MultiCompositionInterruptibilityTest, AllCancelIncoming) {
+  TypeParam command = TypeParam(CommandPtr::UnwrapVector(cmd::impl::MakeVector(
+      cmd::WaitUntil([] {
+        return false;
+      }).WithInterruptBehavior(Command::InterruptionBehavior::kCancelIncoming),
+      cmd::WaitUntil([] {
+        return false;
+      }).WithInterruptBehavior(Command::InterruptionBehavior::kCancelIncoming),
+      cmd::WaitUntil([] { return false; })
+          .WithInterruptBehavior(
+              Command::InterruptionBehavior::kCancelIncoming))));
+  EXPECT_EQ(Command::InterruptionBehavior::kCancelIncoming,
+            command.GetInterruptionBehavior());
+}
+
+TYPED_TEST_P(MultiCompositionInterruptibilityTest, TwoCancelSelfOneIncoming) {
+  TypeParam command = TypeParam(CommandPtr::UnwrapVector(cmd::impl::MakeVector(
+      cmd::WaitUntil([] {
+        return false;
+      }).WithInterruptBehavior(Command::InterruptionBehavior::kCancelSelf),
+      cmd::WaitUntil([] {
+        return false;
+      }).WithInterruptBehavior(Command::InterruptionBehavior::kCancelSelf),
+      cmd::WaitUntil([] { return false; })
+          .WithInterruptBehavior(
+              Command::InterruptionBehavior::kCancelIncoming))));
+  EXPECT_EQ(Command::InterruptionBehavior::kCancelSelf,
+            command.GetInterruptionBehavior());
+}
+
+TYPED_TEST_P(MultiCompositionInterruptibilityTest, TwoCancelIncomingOneSelf) {
+  TypeParam command = TypeParam(CommandPtr::UnwrapVector(cmd::impl::MakeVector(
+      cmd::WaitUntil([] {
+        return false;
+      }).WithInterruptBehavior(Command::InterruptionBehavior::kCancelIncoming),
+      cmd::WaitUntil([] {
+        return false;
+      }).WithInterruptBehavior(Command::InterruptionBehavior::kCancelIncoming),
+      cmd::WaitUntil([] {
+        return false;
+      }).WithInterruptBehavior(Command::InterruptionBehavior::kCancelSelf))));
+  EXPECT_EQ(Command::InterruptionBehavior::kCancelSelf,
+            command.GetInterruptionBehavior());
+}
+
+REGISTER_TYPED_TEST_SUITE_P(MultiCompositionInterruptibilityTest, AllCancelSelf,
+                            AllCancelIncoming, TwoCancelSelfOneIncoming,
+                            TwoCancelIncomingOneSelf);
+
+#define INSTANTIATE_MULTI_COMMAND_COMPOSITION_TEST_SUITE(Suite,               \
+                                                         CompositionType)     \
+  INSTANTIATE_TYPED_TEST_SUITE_P(Suite, MultiCompositionInterruptibilityTest, \
+                                 CompositionType);                            \
+  INSTANTIATE_TYPED_TEST_SUITE_P(Suite, MultiCompositionRunsWhenDisabledTest, \
+                                 CompositionType)
+}  // namespace multi
+}  // namespace frc2
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/MecanumControllerCommandTest.cpp b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/MecanumControllerCommandTest.cpp
index 537d892..7f5b590 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/MecanumControllerCommandTest.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/MecanumControllerCommandTest.cpp
@@ -5,6 +5,8 @@
 #include <frc2/command/MecanumControllerCommand.h>
 #include <frc2/command/Subsystem.h>
 
+#include <numbers>
+
 #include <frc/Timer.h>
 #include <frc/controller/PIDController.h>
 #include <frc/controller/ProfiledPIDController.h>
@@ -14,7 +16,6 @@
 #include <frc/kinematics/MecanumDriveOdometry.h>
 #include <frc/simulation/SimHooks.h>
 #include <frc/trajectory/TrajectoryGenerator.h>
-#include <wpi/numbers>
 
 #include "gtest/gtest.h"
 
@@ -31,9 +32,13 @@
   frc::Rotation2d m_angle{0_rad};
 
   units::meters_per_second_t m_frontLeftSpeed = 0.0_mps;
+  units::meter_t m_frontLeftDistance = 0.0_m;
   units::meters_per_second_t m_rearLeftSpeed = 0.0_mps;
+  units::meter_t m_rearLeftDistance = 0.0_m;
   units::meters_per_second_t m_frontRightSpeed = 0.0_mps;
+  units::meter_t m_frontRightDistance = 0.0_m;
   units::meters_per_second_t m_rearRightSpeed = 0.0_mps;
+  units::meter_t m_rearRightDistance = 0.0_m;
 
   frc::ProfiledPIDController<units::radians> m_rotController{
       1, 0, 0,
@@ -54,6 +59,7 @@
       frc::Translation2d{-kWheelBase / 2, -kTrackWidth / 2}};
 
   frc::MecanumDriveOdometry m_odometry{m_kinematics, 0_rad,
+                                       getCurrentWheelDistances(),
                                        frc::Pose2d{0_m, 0_m, 0_rad}};
 
   void SetUp() override { frc::sim::PauseTiming(); }
@@ -65,8 +71,17 @@
                                         m_rearLeftSpeed, m_rearRightSpeed};
   }
 
+  frc::MecanumDriveWheelPositions getCurrentWheelDistances() {
+    return frc::MecanumDriveWheelPositions{
+        m_frontLeftDistance,
+        m_rearLeftDistance,
+        m_frontRightDistance,
+        m_rearRightDistance,
+    };
+  }
+
   frc::Pose2d getRobotPose() {
-    m_odometry.UpdateWithTime(m_timer.Get(), m_angle, getCurrentWheelSpeeds());
+    m_odometry.Update(m_angle, getCurrentWheelDistances());
     return m_odometry.GetPose();
   }
 };
@@ -85,7 +100,7 @@
       trajectory, [&]() { return getRobotPose(); }, m_kinematics,
 
       frc2::PIDController(0.6, 0, 0), frc2::PIDController(0.6, 0, 0),
-      m_rotController, units::meters_per_second_t(8.8),
+      m_rotController, 8.8_mps,
       [&](units::meters_per_second_t frontLeft,
           units::meters_per_second_t rearLeft,
           units::meters_per_second_t frontRight,
@@ -104,6 +119,10 @@
   while (!command.IsFinished()) {
     command.Execute();
     m_angle = trajectory.Sample(m_timer.Get()).pose.Rotation();
+    m_frontLeftDistance += m_frontLeftSpeed * 5_ms;
+    m_rearLeftDistance += m_rearLeftSpeed * 5_ms;
+    m_frontRightDistance += m_frontRightSpeed * 5_ms;
+    m_rearRightDistance += m_rearRightSpeed * 5_ms;
     frc::sim::StepTiming(5_ms);
   }
   m_timer.Stop();
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/POVButtonTest.cpp b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/POVButtonTest.cpp
index 5f6e733..bcb7dec 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/POVButtonTest.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/POVButtonTest.cpp
@@ -26,7 +26,7 @@
   WaitUntilCommand command([&finished] { return finished; });
 
   frc::Joystick joy(1);
-  POVButton(&joy, 90).WhenPressed(&command);
+  POVButton(&joy, 90).OnTrue(&command);
   scheduler.Run();
   EXPECT_FALSE(scheduler.IsScheduled(&command));
 
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/ParallelCommandGroupTest.cpp b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/ParallelCommandGroupTest.cpp
index d6c0295..28d498c 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/ParallelCommandGroupTest.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/ParallelCommandGroupTest.cpp
@@ -3,6 +3,7 @@
 // the WPILib BSD license file in the root directory of this project.
 
 #include "CommandTestBase.h"
+#include "CompositionTestBase.h"
 #include "frc2/command/InstantCommand.h"
 #include "frc2/command/ParallelCommandGroup.h"
 #include "frc2/command/WaitUntilCommand.h"
@@ -115,3 +116,6 @@
   EXPECT_TRUE(scheduler.IsScheduled(&command3));
   EXPECT_FALSE(scheduler.IsScheduled(&group));
 }
+
+INSTANTIATE_MULTI_COMMAND_COMPOSITION_TEST_SUITE(ParallelCommandGroupTest,
+                                                 ParallelCommandGroup);
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/ParallelDeadlineGroupTest.cpp b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/ParallelDeadlineGroupTest.cpp
index 67d8720..4abab33 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/ParallelDeadlineGroupTest.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/ParallelDeadlineGroupTest.cpp
@@ -3,6 +3,7 @@
 // the WPILib BSD license file in the root directory of this project.
 
 #include "CommandTestBase.h"
+#include "CompositionTestBase.h"
 #include "frc2/command/InstantCommand.h"
 #include "frc2/command/ParallelDeadlineGroup.h"
 #include "frc2/command/WaitUntilCommand.h"
@@ -131,3 +132,23 @@
   EXPECT_TRUE(scheduler.IsScheduled(&command3));
   EXPECT_FALSE(scheduler.IsScheduled(&group));
 }
+
+class TestableDeadlineCommand : public ParallelDeadlineGroup {
+  static ParallelDeadlineGroup ToCommand(
+      std::vector<std::unique_ptr<Command>>&& commands) {
+    std::vector<std::unique_ptr<Command>> vec;
+    std::unique_ptr<Command> deadline = std::move(commands[0]);
+    for (unsigned int i = 1; i < commands.size(); i++) {
+      vec.emplace_back(std::move(commands[i]));
+    }
+    return ParallelDeadlineGroup(std::move(deadline), std::move(vec));
+  }
+
+ public:
+  explicit TestableDeadlineCommand(
+      std::vector<std::unique_ptr<Command>>&& commands)
+      : ParallelDeadlineGroup(ToCommand(std::move(commands))) {}
+};
+
+INSTANTIATE_MULTI_COMMAND_COMPOSITION_TEST_SUITE(ParallelDeadlineGroupTest,
+                                                 TestableDeadlineCommand);
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/ParallelRaceGroupTest.cpp b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/ParallelRaceGroupTest.cpp
index 72f4274..3df2147 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/ParallelRaceGroupTest.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/ParallelRaceGroupTest.cpp
@@ -3,6 +3,7 @@
 // the WPILib BSD license file in the root directory of this project.
 
 #include "CommandTestBase.h"
+#include "CompositionTestBase.h"
 #include "frc2/command/InstantCommand.h"
 #include "frc2/command/ParallelRaceGroup.h"
 #include "frc2/command/SequentialCommandGroup.h"
@@ -202,3 +203,6 @@
 
   EXPECT_FALSE(scheduler.IsScheduled(&group));
 }
+
+INSTANTIATE_MULTI_COMMAND_COMPOSITION_TEST_SUITE(ParallelRaceGroupTest,
+                                                 ParallelRaceGroup);
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/PerpetualCommandTest.cpp b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/PerpetualCommandTest.cpp
index 6254b85..b53835b 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/PerpetualCommandTest.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/PerpetualCommandTest.cpp
@@ -14,7 +14,9 @@
 
   bool check = false;
 
+  WPI_IGNORE_DEPRECATED
   PerpetualCommand command{InstantCommand([&check] { check = true; }, {})};
+  WPI_UNIGNORE_DEPRECATED
 
   scheduler.Schedule(&command);
   scheduler.Run();
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/ProxyCommandTest.cpp b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/ProxyCommandTest.cpp
new file mode 100644
index 0000000..81ec9d1
--- /dev/null
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/ProxyCommandTest.cpp
@@ -0,0 +1,80 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <memory>
+
+#include "CommandTestBase.h"
+#include "frc2/command/CommandPtr.h"
+#include "frc2/command/InstantCommand.h"
+#include "frc2/command/ProxyCommand.h"
+#include "frc2/command/WaitUntilCommand.h"
+
+using namespace frc2;
+class ProxyCommandTest : public CommandTestBase {};
+
+TEST_F(ProxyCommandTest, NonOwningCommandSchedule) {
+  CommandScheduler& scheduler = CommandScheduler::GetInstance();
+
+  bool scheduled = false;
+
+  InstantCommand toSchedule([&scheduled] { scheduled = true; }, {});
+
+  ProxyCommand command(&toSchedule);
+
+  scheduler.Schedule(&command);
+  scheduler.Run();
+
+  EXPECT_TRUE(scheduled);
+}
+
+TEST_F(ProxyCommandTest, NonOwningCommandEnd) {
+  CommandScheduler& scheduler = CommandScheduler::GetInstance();
+
+  bool finished = false;
+
+  WaitUntilCommand toSchedule([&finished] { return finished; });
+
+  ProxyCommand command(&toSchedule);
+
+  scheduler.Schedule(&command);
+  scheduler.Run();
+
+  EXPECT_TRUE(scheduler.IsScheduled(&command));
+  finished = true;
+  scheduler.Run();
+  scheduler.Run();
+  EXPECT_FALSE(scheduler.IsScheduled(&command));
+}
+
+TEST_F(ProxyCommandTest, OwningCommandSchedule) {
+  CommandScheduler& scheduler = CommandScheduler::GetInstance();
+
+  bool scheduled = false;
+
+  CommandPtr command =
+      InstantCommand([&scheduled] { scheduled = true; }).AsProxy();
+
+  scheduler.Schedule(command);
+  scheduler.Run();
+
+  EXPECT_TRUE(scheduled);
+}
+
+TEST_F(ProxyCommandTest, OwningCommandEnd) {
+  CommandScheduler& scheduler = CommandScheduler::GetInstance();
+
+  bool finished = false;
+
+  CommandPtr command =
+      WaitUntilCommand([&finished] { return finished; }).AsProxy();
+
+  scheduler.Schedule(command);
+  scheduler.Run();
+
+  EXPECT_TRUE(scheduler.IsScheduled(command));
+  finished = true;
+  scheduler.Run();
+  scheduler.Run();
+  EXPECT_FALSE(scheduler.IsScheduled(command));
+}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/ProxyScheduleCommandTest.cpp b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/ProxyScheduleCommandTest.cpp
deleted file mode 100644
index def7be9..0000000
--- a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/ProxyScheduleCommandTest.cpp
+++ /dev/null
@@ -1,47 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include <regex>
-
-#include "CommandTestBase.h"
-#include "frc2/command/InstantCommand.h"
-#include "frc2/command/ProxyScheduleCommand.h"
-#include "frc2/command/WaitUntilCommand.h"
-
-using namespace frc2;
-class ProxyScheduleCommandTest : public CommandTestBase {};
-
-TEST_F(ProxyScheduleCommandTest, ProxyScheduleCommandSchedule) {
-  CommandScheduler& scheduler = CommandScheduler::GetInstance();
-
-  bool scheduled = false;
-
-  InstantCommand toSchedule([&scheduled] { scheduled = true; }, {});
-
-  ProxyScheduleCommand command(&toSchedule);
-
-  scheduler.Schedule(&command);
-  scheduler.Run();
-
-  EXPECT_TRUE(scheduled);
-}
-
-TEST_F(ProxyScheduleCommandTest, ProxyScheduleCommandEnd) {
-  CommandScheduler& scheduler = CommandScheduler::GetInstance();
-
-  bool finished = false;
-
-  WaitUntilCommand toSchedule([&finished] { return finished; });
-
-  ProxyScheduleCommand command(&toSchedule);
-
-  scheduler.Schedule(&command);
-  scheduler.Run();
-
-  EXPECT_TRUE(scheduler.IsScheduled(&command));
-  finished = true;
-  scheduler.Run();
-  scheduler.Run();
-  EXPECT_FALSE(scheduler.IsScheduled(&command));
-}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/RepeatCommandTest.cpp b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/RepeatCommandTest.cpp
new file mode 100644
index 0000000..b715983
--- /dev/null
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/RepeatCommandTest.cpp
@@ -0,0 +1,66 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "CommandTestBase.h"
+#include "CompositionTestBase.h"
+#include "frc2/command/FunctionalCommand.h"
+#include "frc2/command/RepeatCommand.h"
+
+using namespace frc2;
+class RepeatCommandTest : public CommandTestBase {};
+
+TEST_F(RepeatCommandTest, CallsMethodsCorrectly) {
+  CommandScheduler scheduler = GetScheduler();
+
+  int initCounter = 0;
+  int exeCounter = 0;
+  int isFinishedCounter = 0;
+  int endCounter = 0;
+  bool isFinishedHook = false;
+
+  auto command =
+      FunctionalCommand([&initCounter] { initCounter++; },
+                        [&exeCounter] { exeCounter++; },
+                        [&endCounter](bool interrupted) { endCounter++; },
+                        [&isFinishedCounter, &isFinishedHook] {
+                          isFinishedCounter++;
+                          return isFinishedHook;
+                        })
+          .Repeatedly();
+
+  EXPECT_EQ(0, initCounter);
+  EXPECT_EQ(0, exeCounter);
+  EXPECT_EQ(0, isFinishedCounter);
+  EXPECT_EQ(0, endCounter);
+
+  scheduler.Schedule(command);
+  EXPECT_EQ(1, initCounter);
+  EXPECT_EQ(0, exeCounter);
+  EXPECT_EQ(0, isFinishedCounter);
+  EXPECT_EQ(0, endCounter);
+
+  isFinishedHook = false;
+  scheduler.Run();
+  EXPECT_EQ(1, initCounter);
+  EXPECT_EQ(1, exeCounter);
+  EXPECT_EQ(1, isFinishedCounter);
+  EXPECT_EQ(0, endCounter);
+
+  isFinishedHook = true;
+  scheduler.Run();
+  EXPECT_EQ(1, initCounter);
+  EXPECT_EQ(2, exeCounter);
+  EXPECT_EQ(2, isFinishedCounter);
+  EXPECT_EQ(1, endCounter);
+
+  isFinishedHook = false;
+  scheduler.Run();
+  EXPECT_EQ(2, initCounter);
+  EXPECT_EQ(3, exeCounter);
+  EXPECT_EQ(3, isFinishedCounter);
+  EXPECT_EQ(1, endCounter);
+}
+
+INSTANTIATE_SINGLE_COMMAND_COMPOSITION_TEST_SUITE(RepeatCommandTest,
+                                                  RepeatCommand);
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/SchedulerTest.cpp b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/SchedulerTest.cpp
index c0f1e5a..ce02ba0 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/SchedulerTest.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/SchedulerTest.cpp
@@ -5,6 +5,7 @@
 #include "CommandTestBase.h"
 #include "frc2/command/InstantCommand.h"
 #include "frc2/command/RunCommand.h"
+#include "frc2/command/StartEndCommand.h"
 
 using namespace frc2;
 class SchedulerTest : public CommandTestBase {};
@@ -69,3 +70,16 @@
 
   EXPECT_EQ(counter, 2);
 }
+
+TEST_F(SchedulerTest, ScheduleScheduledNoOp) {
+  CommandScheduler scheduler = GetScheduler();
+
+  int counter = 0;
+
+  StartEndCommand command([&counter] { counter++; }, [] {});
+
+  scheduler.Schedule(&command);
+  scheduler.Schedule(&command);
+
+  EXPECT_EQ(counter, 1);
+}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/SchedulingRecursionTest.cpp b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/SchedulingRecursionTest.cpp
new file mode 100644
index 0000000..4aa5199
--- /dev/null
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/SchedulingRecursionTest.cpp
@@ -0,0 +1,109 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "CommandTestBase.h"
+#include "frc2/command/Command.h"
+#include "frc2/command/CommandHelper.h"
+#include "frc2/command/RunCommand.h"
+#include "gtest/gtest.h"
+
+using namespace frc2;
+
+class SchedulingRecursionTest
+    : public CommandTestBaseWithParam<Command::InterruptionBehavior> {};
+
+class SelfCancellingCommand
+    : public CommandHelper<CommandBase, SelfCancellingCommand> {
+ public:
+  SelfCancellingCommand(CommandScheduler* scheduler, Subsystem* requirement,
+                        Command::InterruptionBehavior interruptionBehavior =
+                            Command::InterruptionBehavior::kCancelSelf)
+      : m_scheduler(scheduler), m_interrupt(interruptionBehavior) {
+    AddRequirements(requirement);
+  }
+
+  void Initialize() override { m_scheduler->Cancel(this); }
+
+  InterruptionBehavior GetInterruptionBehavior() const override {
+    return m_interrupt;
+  }
+
+ private:
+  CommandScheduler* m_scheduler;
+  InterruptionBehavior m_interrupt;
+};
+
+/**
+ * Checks <a
+ * href="https://github.com/wpilibsuite/allwpilib/issues/4259">wpilibsuite/allwpilib#4259</a>.
+ */
+TEST_F(SchedulingRecursionTest, CancelFromInitialize) {
+  CommandScheduler scheduler = GetScheduler();
+  bool hasOtherRun = false;
+  TestSubsystem requirement;
+  auto selfCancels = SelfCancellingCommand(&scheduler, &requirement);
+  RunCommand other =
+      RunCommand([&hasOtherRun] { hasOtherRun = true; }, {&requirement});
+
+  scheduler.Schedule(&selfCancels);
+  scheduler.Run();
+  scheduler.Schedule(&other);
+
+  EXPECT_FALSE(scheduler.IsScheduled(&selfCancels));
+  EXPECT_TRUE(scheduler.IsScheduled(&other));
+  scheduler.Run();
+  EXPECT_TRUE(hasOtherRun);
+}
+
+TEST_P(SchedulingRecursionTest,
+       DISABLED_DefaultCommandGetsRescheduledAfterSelfCanceling) {
+  CommandScheduler scheduler = GetScheduler();
+  bool hasOtherRun = false;
+  TestSubsystem requirement;
+  auto selfCancels =
+      SelfCancellingCommand(&scheduler, &requirement, GetParam());
+  RunCommand other =
+      RunCommand([&hasOtherRun] { hasOtherRun = true; }, {&requirement});
+  scheduler.SetDefaultCommand(&requirement, std::move(other));
+
+  scheduler.Schedule(&selfCancels);
+  scheduler.Run();
+  scheduler.Run();
+  EXPECT_FALSE(scheduler.IsScheduled(&selfCancels));
+  EXPECT_TRUE(scheduler.IsScheduled(scheduler.GetDefaultCommand(&requirement)));
+  scheduler.Run();
+  EXPECT_TRUE(hasOtherRun);
+}
+
+class CancelEndCommand : public CommandHelper<CommandBase, CancelEndCommand> {
+ public:
+  CancelEndCommand(CommandScheduler* scheduler, int& counter)
+      : m_scheduler(scheduler), m_counter(counter) {}
+
+  void End(bool interrupted) override {
+    m_counter++;
+    m_scheduler->Cancel(this);
+  }
+
+ private:
+  CommandScheduler* m_scheduler;
+  int& m_counter;
+};
+
+TEST_F(SchedulingRecursionTest, CancelFromEnd) {
+  CommandScheduler scheduler = GetScheduler();
+  int counter = 0;
+  CancelEndCommand selfCancels{&scheduler, counter};
+
+  scheduler.Schedule(&selfCancels);
+
+  EXPECT_NO_THROW({ scheduler.Cancel(&selfCancels); });
+  EXPECT_EQ(1, counter);
+  EXPECT_FALSE(scheduler.IsScheduled(&selfCancels));
+}
+
+INSTANTIATE_TEST_SUITE_P(
+    SchedulingRecursionTests, SchedulingRecursionTest,
+    testing::Values(Command::InterruptionBehavior::kCancelSelf,
+                    Command::InterruptionBehavior::kCancelIncoming));
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/SelectCommandTest.cpp b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/SelectCommandTest.cpp
index 409e2a6..dfea0d3 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/SelectCommandTest.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/SelectCommandTest.cpp
@@ -3,6 +3,7 @@
 // the WPILib BSD license file in the root directory of this project.
 
 #include "CommandTestBase.h"
+#include "CompositionTestBase.h"
 #include "frc2/command/ConditionalCommand.h"
 #include "frc2/command/InstantCommand.h"
 #include "frc2/command/SelectCommand.h"
@@ -57,3 +58,24 @@
   EXPECT_TRUE(scheduler.IsScheduled(&command3));
   EXPECT_FALSE(scheduler.IsScheduled(&select));
 }
+
+class TestableSelectCommand : public SelectCommand<int> {
+  static std::vector<std::pair<int, std::unique_ptr<Command>>> ZipVector(
+      std::vector<std::unique_ptr<Command>>&& commands) {
+    std::vector<std::pair<int, std::unique_ptr<Command>>> vec;
+    int index = 0;
+    for (auto&& command : commands) {
+      vec.emplace_back(std::make_pair(index, std::move(command)));
+      index++;
+    }
+    return vec;
+  }
+
+ public:
+  explicit TestableSelectCommand(
+      std::vector<std::unique_ptr<Command>>&& commands)
+      : SelectCommand([] { return 0; }, ZipVector(std::move(commands))) {}
+};
+
+INSTANTIATE_MULTI_COMMAND_COMPOSITION_TEST_SUITE(SelectCommandTest,
+                                                 TestableSelectCommand);
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/SequentialCommandGroupTest.cpp b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/SequentialCommandGroupTest.cpp
index 2d88c0a..0048b24 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/SequentialCommandGroupTest.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/SequentialCommandGroupTest.cpp
@@ -3,6 +3,7 @@
 // the WPILib BSD license file in the root directory of this project.
 
 #include "CommandTestBase.h"
+#include "CompositionTestBase.h"
 #include "frc2/command/InstantCommand.h"
 #include "frc2/command/SequentialCommandGroup.h"
 #include "frc2/command/WaitUntilCommand.h"
@@ -132,3 +133,6 @@
   EXPECT_TRUE(scheduler.IsScheduled(&command3));
   EXPECT_FALSE(scheduler.IsScheduled(&group));
 }
+
+INSTANTIATE_MULTI_COMMAND_COMPOSITION_TEST_SUITE(SequentialCommandGroupTest,
+                                                 SequentialCommandGroup);
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/SwerveControllerCommandTest.cpp b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/SwerveControllerCommandTest.cpp
index 93117b8..531e9d2 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/SwerveControllerCommandTest.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/SwerveControllerCommandTest.cpp
@@ -5,6 +5,8 @@
 #include <frc2/command/Subsystem.h>
 #include <frc2/command/SwerveControllerCommand.h>
 
+#include <numbers>
+
 #include <frc/Timer.h>
 #include <frc/controller/PIDController.h>
 #include <frc/controller/ProfiledPIDController.h>
@@ -15,7 +17,6 @@
 #include <frc/kinematics/SwerveModuleState.h>
 #include <frc/simulation/SimHooks.h>
 #include <frc/trajectory/TrajectoryGenerator.h>
-#include <wpi/numbers>
 
 #include "gtest/gtest.h"
 
@@ -35,6 +36,10 @@
       frc::SwerveModuleState{}, frc::SwerveModuleState{},
       frc::SwerveModuleState{}, frc::SwerveModuleState{}};
 
+  wpi::array<frc::SwerveModulePosition, 4> m_modulePositions{
+      frc::SwerveModulePosition{}, frc::SwerveModulePosition{},
+      frc::SwerveModulePosition{}, frc::SwerveModulePosition{}};
+
   frc::ProfiledPIDController<units::radians> m_rotController{
       1, 0, 0,
       frc::TrapezoidProfile<units::radians>::Constraints{
@@ -53,19 +58,15 @@
       frc::Translation2d{-kWheelBase / 2, kTrackWidth / 2},
       frc::Translation2d{-kWheelBase / 2, -kTrackWidth / 2}};
 
-  frc::SwerveDriveOdometry<4> m_odometry{m_kinematics, 0_rad,
+  frc::SwerveDriveOdometry<4> m_odometry{m_kinematics, 0_rad, m_modulePositions,
                                          frc::Pose2d{0_m, 0_m, 0_rad}};
 
   void SetUp() override { frc::sim::PauseTiming(); }
 
   void TearDown() override { frc::sim::ResumeTiming(); }
 
-  wpi::array<frc::SwerveModuleState, 4> getCurrentWheelSpeeds() {
-    return m_moduleStates;
-  }
-
   frc::Pose2d getRobotPose() {
-    m_odometry.UpdateWithTime(m_timer.Get(), m_angle, getCurrentWheelSpeeds());
+    m_odometry.Update(m_angle, m_modulePositions);
     return m_odometry.GetPose();
   }
 };
@@ -94,6 +95,12 @@
   while (!command.IsFinished()) {
     command.Execute();
     m_angle = trajectory.Sample(m_timer.Get()).pose.Rotation();
+
+    for (size_t i = 0; i < m_modulePositions.size(); i++) {
+      m_modulePositions[i].distance += m_moduleStates[i].speed * 5_ms;
+      m_modulePositions[i].angle = m_moduleStates[i].angle;
+    }
+
     frc::sim::StepTiming(5_ms);
   }
   m_timer.Stop();
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/button/ButtonTest.cpp b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/button/ButtonTest.cpp
deleted file mode 100644
index db4276d..0000000
--- a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/button/ButtonTest.cpp
+++ /dev/null
@@ -1,210 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include <frc/simulation/SimHooks.h>
-
-#include "../CommandTestBase.h"
-#include "frc2/command/CommandScheduler.h"
-#include "frc2/command/RunCommand.h"
-#include "frc2/command/WaitUntilCommand.h"
-#include "frc2/command/button/Trigger.h"
-#include "gtest/gtest.h"
-
-using namespace frc2;
-class ButtonTest : public CommandTestBase {};
-
-TEST_F(ButtonTest, WhenPressed) {
-  auto& scheduler = CommandScheduler::GetInstance();
-  bool finished = false;
-  bool pressed = false;
-
-  WaitUntilCommand command([&finished] { return finished; });
-
-  Trigger([&pressed] { return pressed; }).WhenActive(&command);
-  scheduler.Run();
-  EXPECT_FALSE(scheduler.IsScheduled(&command));
-  pressed = true;
-  scheduler.Run();
-  EXPECT_TRUE(scheduler.IsScheduled(&command));
-  finished = true;
-  scheduler.Run();
-  EXPECT_FALSE(scheduler.IsScheduled(&command));
-}
-
-TEST_F(ButtonTest, WhenReleased) {
-  auto& scheduler = CommandScheduler::GetInstance();
-  bool finished = false;
-  bool pressed = false;
-  WaitUntilCommand command([&finished] { return finished; });
-
-  pressed = true;
-  Trigger([&pressed] { return pressed; }).WhenInactive(&command);
-  scheduler.Run();
-  EXPECT_FALSE(scheduler.IsScheduled(&command));
-  pressed = false;
-  scheduler.Run();
-  EXPECT_TRUE(scheduler.IsScheduled(&command));
-  finished = true;
-  scheduler.Run();
-  EXPECT_FALSE(scheduler.IsScheduled(&command));
-}
-
-TEST_F(ButtonTest, WhileHeld) {
-  auto& scheduler = CommandScheduler::GetInstance();
-  bool finished = false;
-  bool pressed = false;
-  WaitUntilCommand command([&finished] { return finished; });
-
-  pressed = false;
-  Trigger([&pressed] { return pressed; }).WhileActiveContinous(&command);
-  scheduler.Run();
-  EXPECT_FALSE(scheduler.IsScheduled(&command));
-  pressed = true;
-  scheduler.Run();
-  EXPECT_TRUE(scheduler.IsScheduled(&command));
-  finished = true;
-  scheduler.Run();
-  finished = false;
-  scheduler.Run();
-  EXPECT_TRUE(scheduler.IsScheduled(&command));
-  pressed = false;
-  scheduler.Run();
-  EXPECT_FALSE(scheduler.IsScheduled(&command));
-}
-
-TEST_F(ButtonTest, WhenHeld) {
-  auto& scheduler = CommandScheduler::GetInstance();
-  bool finished = false;
-  bool pressed = false;
-  WaitUntilCommand command([&finished] { return finished; });
-
-  pressed = false;
-  Trigger([&pressed] { return pressed; }).WhileActiveOnce(&command);
-  scheduler.Run();
-  EXPECT_FALSE(scheduler.IsScheduled(&command));
-  pressed = true;
-  scheduler.Run();
-  EXPECT_TRUE(scheduler.IsScheduled(&command));
-  finished = true;
-  scheduler.Run();
-  finished = false;
-  scheduler.Run();
-  EXPECT_FALSE(scheduler.IsScheduled(&command));
-
-  pressed = false;
-  Trigger([&pressed] { return pressed; }).WhileActiveOnce(&command);
-  pressed = true;
-  scheduler.Run();
-  pressed = false;
-  scheduler.Run();
-  EXPECT_FALSE(scheduler.IsScheduled(&command));
-}
-
-TEST_F(ButtonTest, ToggleWhenPressed) {
-  auto& scheduler = CommandScheduler::GetInstance();
-  bool finished = false;
-  bool pressed = false;
-  WaitUntilCommand command([&finished] { return finished; });
-
-  pressed = false;
-  Trigger([&pressed] { return pressed; }).ToggleWhenActive(&command);
-  scheduler.Run();
-  EXPECT_FALSE(scheduler.IsScheduled(&command));
-  pressed = true;
-  scheduler.Run();
-  EXPECT_TRUE(scheduler.IsScheduled(&command));
-  pressed = false;
-  scheduler.Run();
-  pressed = true;
-  scheduler.Run();
-  EXPECT_FALSE(scheduler.IsScheduled(&command));
-}
-
-TEST_F(ButtonTest, And) {
-  auto& scheduler = CommandScheduler::GetInstance();
-  bool finished = false;
-  bool pressed1 = false;
-  bool pressed2 = false;
-  WaitUntilCommand command([&finished] { return finished; });
-
-  (Trigger([&pressed1] { return pressed1; }) && Trigger([&pressed2] {
-     return pressed2;
-   })).WhenActive(&command);
-  pressed1 = true;
-  scheduler.Run();
-  EXPECT_FALSE(scheduler.IsScheduled(&command));
-  pressed2 = true;
-  scheduler.Run();
-  EXPECT_TRUE(scheduler.IsScheduled(&command));
-}
-
-TEST_F(ButtonTest, Or) {
-  auto& scheduler = CommandScheduler::GetInstance();
-  bool finished = false;
-  bool pressed1 = false;
-  bool pressed2 = false;
-  WaitUntilCommand command1([&finished] { return finished; });
-  WaitUntilCommand command2([&finished] { return finished; });
-
-  (Trigger([&pressed1] { return pressed1; }) || Trigger([&pressed2] {
-     return pressed2;
-   })).WhenActive(&command1);
-  pressed1 = true;
-  scheduler.Run();
-  EXPECT_TRUE(scheduler.IsScheduled(&command1));
-
-  pressed1 = false;
-
-  (Trigger([&pressed1] { return pressed1; }) || Trigger([&pressed2] {
-     return pressed2;
-   })).WhenActive(&command2);
-  pressed2 = true;
-  scheduler.Run();
-  EXPECT_TRUE(scheduler.IsScheduled(&command2));
-}
-
-TEST_F(ButtonTest, Negate) {
-  auto& scheduler = CommandScheduler::GetInstance();
-  bool finished = false;
-  bool pressed = true;
-  WaitUntilCommand command([&finished] { return finished; });
-
-  (!Trigger([&pressed] { return pressed; })).WhenActive(&command);
-  scheduler.Run();
-  EXPECT_FALSE(scheduler.IsScheduled(&command));
-  pressed = false;
-  scheduler.Run();
-  EXPECT_TRUE(scheduler.IsScheduled(&command));
-}
-
-TEST_F(ButtonTest, RValueButton) {
-  auto& scheduler = CommandScheduler::GetInstance();
-  int counter = 0;
-  bool pressed = false;
-
-  RunCommand command([&counter] { counter++; }, {});
-
-  Trigger([&pressed] { return pressed; }).WhenActive(std::move(command));
-  scheduler.Run();
-  EXPECT_EQ(counter, 0);
-  pressed = true;
-  scheduler.Run();
-  EXPECT_EQ(counter, 1);
-}
-
-TEST_F(ButtonTest, Debounce) {
-  auto& scheduler = CommandScheduler::GetInstance();
-  bool pressed = false;
-  RunCommand command([] {});
-
-  Trigger([&pressed] { return pressed; }).Debounce(100_ms).WhenActive(&command);
-  pressed = true;
-  scheduler.Run();
-  EXPECT_FALSE(scheduler.IsScheduled(&command));
-
-  frc::sim::StepTiming(300_ms);
-
-  scheduler.Run();
-  EXPECT_TRUE(scheduler.IsScheduled(&command));
-}
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/button/NetworkButtonTest.cpp b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/button/NetworkButtonTest.cpp
index 7de1084..51da1d2 100644
--- a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/button/NetworkButtonTest.cpp
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/button/NetworkButtonTest.cpp
@@ -14,27 +14,28 @@
 using namespace frc2;
 
 class NetworkButtonTest : public CommandTestBase {
-  void SetUp() override { nt::NetworkTableInstance::GetDefault().StartLocal(); }
-
-  void TearDown() override {
-    nt::NetworkTableInstance::GetDefault().DeleteAllEntries();
-    nt::NetworkTableInstance::GetDefault().StopLocal();
+ public:
+  NetworkButtonTest() {
+    inst = nt::NetworkTableInstance::Create();
+    inst.StartLocal();
   }
+
+  ~NetworkButtonTest() override { nt::NetworkTableInstance::Destroy(inst); }
+
+  nt::NetworkTableInstance inst;
 };
 
 TEST_F(NetworkButtonTest, SetNetworkButton) {
   auto& scheduler = CommandScheduler::GetInstance();
-  auto entry = nt::NetworkTableInstance::GetDefault()
-                   .GetTable("TestTable")
-                   ->GetEntry("Test");
+  auto pub = inst.GetTable("TestTable")->GetBooleanTopic("Test").Publish();
   bool finished = false;
 
   WaitUntilCommand command([&finished] { return finished; });
 
-  NetworkButton("TestTable", "Test").WhenActive(&command);
+  NetworkButton(inst, "TestTable", "Test").OnTrue(&command);
   scheduler.Run();
   EXPECT_FALSE(scheduler.IsScheduled(&command));
-  entry.SetBoolean(true);
+  pub.Set(true);
   scheduler.Run();
   EXPECT_TRUE(scheduler.IsScheduled(&command));
   finished = true;
diff --git a/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/button/TriggerTest.cpp b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/button/TriggerTest.cpp
new file mode 100644
index 0000000..1a0af51
--- /dev/null
+++ b/third_party/allwpilib/wpilibNewCommands/src/test/native/cpp/frc2/command/button/TriggerTest.cpp
@@ -0,0 +1,241 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <frc/simulation/SimHooks.h>
+
+#include "../CommandTestBase.h"
+#include "frc2/command/CommandPtr.h"
+#include "frc2/command/CommandScheduler.h"
+#include "frc2/command/Commands.h"
+#include "frc2/command/RunCommand.h"
+#include "frc2/command/WaitUntilCommand.h"
+#include "frc2/command/button/Trigger.h"
+#include "gtest/gtest.h"
+
+using namespace frc2;
+class TriggerTest : public CommandTestBase {};
+
+TEST_F(TriggerTest, OnTrue) {
+  auto& scheduler = CommandScheduler::GetInstance();
+  bool finished = false;
+  bool pressed = false;
+
+  WaitUntilCommand command([&finished] { return finished; });
+
+  Trigger([&pressed] { return pressed; }).OnTrue(&command);
+  scheduler.Run();
+  EXPECT_FALSE(scheduler.IsScheduled(&command));
+  pressed = true;
+  scheduler.Run();
+  EXPECT_TRUE(scheduler.IsScheduled(&command));
+  finished = true;
+  scheduler.Run();
+  EXPECT_FALSE(scheduler.IsScheduled(&command));
+}
+
+TEST_F(TriggerTest, OnFalse) {
+  auto& scheduler = CommandScheduler::GetInstance();
+  bool finished = false;
+  bool pressed = false;
+  WaitUntilCommand command([&finished] { return finished; });
+
+  pressed = true;
+  Trigger([&pressed] { return pressed; }).OnFalse(&command);
+  scheduler.Run();
+  EXPECT_FALSE(scheduler.IsScheduled(&command));
+  pressed = false;
+  scheduler.Run();
+  EXPECT_TRUE(scheduler.IsScheduled(&command));
+  finished = true;
+  scheduler.Run();
+  EXPECT_FALSE(scheduler.IsScheduled(&command));
+}
+
+TEST_F(TriggerTest, WhileTrueRepeatedly) {
+  auto& scheduler = CommandScheduler::GetInstance();
+  int inits = 0;
+  int counter = 0;
+  bool pressed = false;
+  CommandPtr command =
+      FunctionalCommand([&inits] { inits++; }, [] {}, [](bool interrupted) {},
+                        [&counter] { return ++counter % 2 == 0; })
+          .Repeatedly();
+
+  pressed = false;
+  Trigger([&pressed] { return pressed; }).WhileTrue(std::move(command));
+  scheduler.Run();
+  EXPECT_EQ(0, inits);
+  pressed = true;
+  scheduler.Run();
+  EXPECT_EQ(1, inits);
+  scheduler.Run();
+  EXPECT_EQ(1, inits);
+  scheduler.Run();
+  EXPECT_EQ(2, inits);
+  pressed = false;
+  scheduler.Run();
+  EXPECT_EQ(2, inits);
+}
+
+TEST_F(TriggerTest, WhileTrueLambdaRun) {
+  auto& scheduler = CommandScheduler::GetInstance();
+  int counter = 0;
+  bool pressed = false;
+  CommandPtr command = cmd::Run([&counter] { counter++; });
+
+  pressed = false;
+  Trigger([&pressed] { return pressed; }).WhileTrue(std::move(command));
+  scheduler.Run();
+  EXPECT_EQ(0, counter);
+  pressed = true;
+  scheduler.Run();
+  scheduler.Run();
+  EXPECT_EQ(2, counter);
+  pressed = false;
+  scheduler.Run();
+  EXPECT_EQ(2, counter);
+}
+
+TEST_F(TriggerTest, WhenTrueOnce) {
+  auto& scheduler = CommandScheduler::GetInstance();
+  int startCounter = 0;
+  int endCounter = 0;
+  bool pressed = false;
+
+  CommandPtr command = cmd::StartEnd([&startCounter] { startCounter++; },
+                                     [&endCounter] { endCounter++; });
+
+  pressed = false;
+  Trigger([&pressed] { return pressed; }).WhileTrue(std::move(command));
+  scheduler.Run();
+  EXPECT_EQ(0, startCounter);
+  EXPECT_EQ(0, endCounter);
+  pressed = true;
+  scheduler.Run();
+  scheduler.Run();
+  EXPECT_EQ(1, startCounter);
+  EXPECT_EQ(0, endCounter);
+  pressed = false;
+  scheduler.Run();
+  EXPECT_EQ(1, startCounter);
+  EXPECT_EQ(1, endCounter);
+}
+
+TEST_F(TriggerTest, ToggleOnTrue) {
+  auto& scheduler = CommandScheduler::GetInstance();
+  bool pressed = false;
+  int startCounter = 0;
+  int endCounter = 0;
+  CommandPtr command = cmd::StartEnd([&startCounter] { startCounter++; },
+                                     [&endCounter] { endCounter++; });
+
+  Trigger([&pressed] { return pressed; }).ToggleOnTrue(std::move(command));
+  scheduler.Run();
+  EXPECT_EQ(0, startCounter);
+  EXPECT_EQ(0, endCounter);
+  pressed = true;
+  scheduler.Run();
+  scheduler.Run();
+  EXPECT_EQ(1, startCounter);
+  EXPECT_EQ(0, endCounter);
+  pressed = false;
+  scheduler.Run();
+  EXPECT_EQ(1, startCounter);
+  EXPECT_EQ(0, endCounter);
+  pressed = true;
+  scheduler.Run();
+  EXPECT_EQ(1, startCounter);
+  EXPECT_EQ(1, endCounter);
+}
+
+TEST_F(TriggerTest, And) {
+  auto& scheduler = CommandScheduler::GetInstance();
+  bool finished = false;
+  bool pressed1 = false;
+  bool pressed2 = false;
+  WaitUntilCommand command([&finished] { return finished; });
+
+  (Trigger([&pressed1] { return pressed1; }) && ([&pressed2] {
+     return pressed2;
+   })).OnTrue(&command);
+  pressed1 = true;
+  scheduler.Run();
+  EXPECT_FALSE(scheduler.IsScheduled(&command));
+  pressed2 = true;
+  scheduler.Run();
+  EXPECT_TRUE(scheduler.IsScheduled(&command));
+}
+
+TEST_F(TriggerTest, Or) {
+  auto& scheduler = CommandScheduler::GetInstance();
+  bool finished = false;
+  bool pressed1 = false;
+  bool pressed2 = false;
+  WaitUntilCommand command1([&finished] { return finished; });
+  WaitUntilCommand command2([&finished] { return finished; });
+
+  (Trigger([&pressed1] { return pressed1; }) || ([&pressed2] {
+     return pressed2;
+   })).OnTrue(&command1);
+  pressed1 = true;
+  scheduler.Run();
+  EXPECT_TRUE(scheduler.IsScheduled(&command1));
+
+  pressed1 = false;
+
+  (Trigger([&pressed1] { return pressed1; }) || ([&pressed2] {
+     return pressed2;
+   })).OnTrue(&command2);
+  pressed2 = true;
+  scheduler.Run();
+  EXPECT_TRUE(scheduler.IsScheduled(&command2));
+}
+
+TEST_F(TriggerTest, Negate) {
+  auto& scheduler = CommandScheduler::GetInstance();
+  bool finished = false;
+  bool pressed = true;
+  WaitUntilCommand command([&finished] { return finished; });
+
+  (!Trigger([&pressed] { return pressed; })).OnTrue(&command);
+  scheduler.Run();
+  EXPECT_FALSE(scheduler.IsScheduled(&command));
+  pressed = false;
+  scheduler.Run();
+  EXPECT_TRUE(scheduler.IsScheduled(&command));
+}
+
+// this type of binding is deprecated and identical to OnTrue
+WPI_IGNORE_DEPRECATED
+TEST_F(TriggerTest, RValueTrigger) {
+  auto& scheduler = CommandScheduler::GetInstance();
+  int counter = 0;
+  bool pressed = false;
+
+  RunCommand command([&counter] { counter++; }, {});
+
+  Trigger([&pressed] { return pressed; }).WhenActive(std::move(command));
+  scheduler.Run();
+  EXPECT_EQ(counter, 0);
+  pressed = true;
+  scheduler.Run();
+  EXPECT_EQ(counter, 1);
+}
+WPI_UNIGNORE_DEPRECATED
+
+TEST_F(TriggerTest, Debounce) {
+  auto& scheduler = CommandScheduler::GetInstance();
+  bool pressed = false;
+  RunCommand command([] {});
+
+  Trigger([&pressed] { return pressed; }).Debounce(100_ms).OnTrue(&command);
+  pressed = true;
+  scheduler.Run();
+  EXPECT_FALSE(scheduler.IsScheduled(&command));
+
+  frc::sim::StepTiming(300_ms);
+
+  scheduler.Run();
+  EXPECT_TRUE(scheduler.IsScheduled(&command));
+}
diff --git a/third_party/allwpilib/wpilibOldCommands/CMakeLists.txt b/third_party/allwpilib/wpilibOldCommands/CMakeLists.txt
deleted file mode 100644
index a9b7044..0000000
--- a/third_party/allwpilib/wpilibOldCommands/CMakeLists.txt
+++ /dev/null
@@ -1,59 +0,0 @@
-project(wpilibOldCommands)
-
-include(SubDirList)
-include(CompileWarnings)
-include(AddTest)
-
-if (WITH_JAVA)
-  find_package(Java REQUIRED)
-  include(UseJava)
-  set(CMAKE_JAVA_COMPILE_FLAGS "-encoding" "UTF8" "-Xlint:unchecked")
-
-  file(GLOB_RECURSE JAVA_SOURCES src/main/java/*.java)
-  add_jar(wpilibOldCommands_jar ${JAVA_SOURCES} INCLUDE_JARS hal_jar ntcore_jar cscore_jar cameraserver_jar wpimath_jar wpiutil_jar wpilibj_jar OUTPUT_NAME wpilibOldCommands)
-
-  get_property(WPIlIBOLDCOMMANDS_JAR_FILE TARGET wpilibOldCommands_jar PROPERTY JAR_FILE)
-  install(FILES ${WPIlIBOLDCOMMANDS_JAR_FILE} DESTINATION "${java_lib_dest}")
-
-  set_property(TARGET wpilibOldCommands_jar PROPERTY FOLDER "java")
-
-  if (WITH_FLAT_INSTALL)
-      set (wpilibOldCommands_config_dir ${wpilib_dest})
-  else()
-      set (wpilibOldCommands_config_dir share/wpilibOldCommands)
-  endif()
-
-  install(FILES wpilibOldCommands-config.cmake DESTINATION ${wpilibOldCommands_config_dir})
-endif()
-
-file(GLOB_RECURSE wpilibOldCommands_native_src src/main/native/cpp/*.cpp)
-add_library(wpilibOldCommands ${wpilibOldCommands_native_src})
-set_target_properties(wpilibOldCommands PROPERTIES DEBUG_POSTFIX "d")
-set_property(TARGET wpilibOldCommands PROPERTY FOLDER "libraries")
-
-target_compile_features(wpilibOldCommands PUBLIC cxx_std_17)
-wpilib_target_warnings(wpilibOldCommands)
-target_link_libraries(wpilibOldCommands wpilibc)
-
-target_include_directories(wpilibOldCommands PUBLIC
-                            $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/src/main/native/include>
-                            $<INSTALL_INTERFACE:${include_dest}/wpilibOldCommands>)
-
-install(TARGETS wpilibOldCommands EXPORT wpilibOldCommands DESTINATION "${main_lib_dest}")
-install(DIRECTORY src/main/native/include/ DESTINATION "${include_dest}/wpilibOldCommands")
-
-if (MSVC OR FLAT_INSTALL_WPILIB)
-     set(wpilibOldCommands_config_dir ${wpilib_dest})
- else()
-     set(wpilibOldCommands_config_dir share/wpilibOldCommands)
- endif()
-
- configure_file(wpilibOldCommands-config.cmake.in ${WPILIB_BINARY_DIR}/wpilibOldCommands-config.cmake)
- install(FILES ${WPILIB_BINARY_DIR}/wpilibOldCommands-config.cmake DESTINATION ${wpilibOldCommands_config_dir})
- install(EXPORT wpilibOldCommands DESTINATION ${wpilibOldCommands_config_dir})
-
- if (WITH_TESTS)
-     wpilib_add_test(wpilibOldCommands src/test/native/cpp)
-     target_include_directories(wpilibOldCommands_test PRIVATE src/test/native/include)
-     target_link_libraries(wpilibOldCommands_test wpilibOldCommands gmock_main)
- endif()
diff --git a/third_party/allwpilib/wpilibOldCommands/WPILibOldCommands.json b/third_party/allwpilib/wpilibOldCommands/WPILibOldCommands.json
deleted file mode 100644
index d26cc4b..0000000
--- a/third_party/allwpilib/wpilibOldCommands/WPILibOldCommands.json
+++ /dev/null
@@ -1,37 +0,0 @@
-{

-  "fileName": "WPILibOldCommands.json",

-  "name": "WPILib-Old-Commands",

-  "version": "1.0.0",

-  "uuid": "b066afc2-5c18-43c4-b758-43381fcb275e",

-  "mavenUrls": [],

-  "jsonUrl": "",

-  "javaDependencies": [

-      {

-          "groupId": "edu.wpi.first.wpilibOldCommands",

-          "artifactId": "wpilibOldCommands-java",

-          "version": "wpilib"

-      }

-  ],

-  "jniDependencies": [],

-  "cppDependencies": [

-      {

-          "groupId": "edu.wpi.first.wpilibOldCommands",

-          "artifactId": "wpilibOldCommands-cpp",

-          "version": "wpilib",

-          "libName": "wpilibOldCommands",

-          "headerClassifier": "headers",

-          "sourcesClassifier": "sources",

-          "sharedLibrary": true,

-          "skipInvalidPlatforms": true,

-          "binaryPlatforms": [

-              "linuxathena",

-              "linuxraspbian",

-              "linuxaarch64bionic",

-              "windowsx86-64",

-              "windowsx86",

-              "linuxx86-64",

-              "osxx86-64"

-          ]

-      }

-  ]

-}

diff --git a/third_party/allwpilib/wpilibOldCommands/build.gradle b/third_party/allwpilib/wpilibOldCommands/build.gradle
deleted file mode 100644
index 39870ee..0000000
--- a/third_party/allwpilib/wpilibOldCommands/build.gradle
+++ /dev/null
@@ -1,119 +0,0 @@
-ext {
-    nativeName = 'wpilibOldCommands'
-    devMain = 'edu.wpi.first.wpilibj.commands.DevMain'
-}
-
-evaluationDependsOn(':ntcore')
-evaluationDependsOn(':cscore')
-evaluationDependsOn(':hal')
-evaluationDependsOn(':wpimath')
-evaluationDependsOn(':wpilibc')
-evaluationDependsOn(':cameraserver')
-evaluationDependsOn(':wpilibj')
-
-apply from: "${rootDir}/shared/javacpp/setupBuild.gradle"
-
-dependencies {
-    implementation project(':wpiutil')
-    implementation project(':ntcore')
-    implementation project(':cscore')
-    implementation project(':hal')
-    implementation project(':wpimath')
-    implementation project(':wpilibj')
-    devImplementation project(':wpiutil')
-    devImplementation project(':ntcore')
-    devImplementation project(':cscore')
-    devImplementation project(':hal')
-    devImplementation project(':wpimath')
-    devImplementation project(':wpilibj')
-}
-
-nativeUtils.exportsConfigs {
-    wpilibOldCommands {
-        x86ExcludeSymbols = [
-            '_CT??_R0?AV_System_error',
-            '_CT??_R0?AVexception',
-            '_CT??_R0?AVfailure',
-            '_CT??_R0?AVruntime_error',
-            '_CT??_R0?AVsystem_error',
-            '_CTA5?AVfailure',
-            '_TI5?AVfailure',
-            '_CT??_R0?AVout_of_range',
-            '_CTA3?AVout_of_range',
-            '_TI3?AVout_of_range',
-            '_CT??_R0?AVbad_cast'
-        ]
-        x64ExcludeSymbols = [
-            '_CT??_R0?AV_System_error',
-            '_CT??_R0?AVexception',
-            '_CT??_R0?AVfailure',
-            '_CT??_R0?AVruntime_error',
-            '_CT??_R0?AVsystem_error',
-            '_CTA5?AVfailure',
-            '_TI5?AVfailure',
-            '_CT??_R0?AVout_of_range',
-            '_CTA3?AVout_of_range',
-            '_TI3?AVout_of_range',
-            '_CT??_R0?AVbad_cast'
-        ]
-    }
-}
-
-model {
-    components {}
-    binaries {
-        all {
-            if (!it.buildable || !(it instanceof NativeBinarySpec)) {
-                return
-            }
-            lib project: ':wpilibc', library: 'wpilibc', linkage: 'shared'
-            lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
-            project(':hal').addHalDependency(it, 'shared')
-            lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
-            lib project: ':wpimath', library: 'wpimath', linkage: 'shared'
-
-            if (it.component.name == "${nativeName}Dev") {
-                lib project: ':ntcore', library: 'ntcoreJNIShared', linkage: 'shared'
-                project(':hal').addHalJniDependency(it)
-            }
-
-            if (it instanceof GoogleTestTestSuiteBinarySpec) {
-                nativeUtils.useRequiredLibrary(it, 'opencv_shared')
-                lib project: ':cscore', library: 'cscore', linkage: 'shared'
-            }
-            if ((it instanceof NativeExecutableBinarySpec || it instanceof GoogleTestTestSuiteBinarySpec) && it.targetPlatform.name == nativeUtils.wpi.platforms.roborio) {
-                nativeUtils.useRequiredLibrary(it, 'ni_link_libraries', 'ni_runtime_libraries')
-            }
-        }
-    }
-    tasks {
-        def c = $.components
-        def found = false
-        def systemArch = getCurrentArch()
-        c.each {
-            if (it in NativeExecutableSpec && it.name == "${nativeName}Dev") {
-                it.binaries.each {
-                    if (!found) {
-                        def arch = it.targetPlatform.name
-                        if (arch == systemArch) {
-                            def filePath = it.tasks.install.installDirectory.get().toString() + File.separatorChar + 'lib'
-
-                            found = true
-                        }
-                    }
-                }
-            }
-        }
-    }
-}
-
-test {
-    testLogging {
-        outputs.upToDateWhen {false}
-        showStandardStreams = true
-    }
-}
-
-tasks.withType(JavaCompile) {
-    options.compilerArgs += "-Xlint:-removal"
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/dev/java/edu/wpi/first/wpilibj/commands/DevMain.java b/third_party/allwpilib/wpilibOldCommands/src/dev/java/edu/wpi/first/wpilibj/commands/DevMain.java
deleted file mode 100644
index 719fdcc..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/dev/java/edu/wpi/first/wpilibj/commands/DevMain.java
+++ /dev/null
@@ -1,21 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.commands;
-
-import edu.wpi.first.hal.HALUtil;
-import edu.wpi.first.networktables.NetworkTablesJNI;
-import edu.wpi.first.util.RuntimeDetector;
-
-public final class DevMain {
-  /** Main entry point. */
-  public static void main(String[] args) {
-    System.out.println("Hello World!");
-    System.out.println(RuntimeDetector.getPlatformPath());
-    System.out.println(NetworkTablesJNI.now());
-    System.out.println(HALUtil.getHALRuntimeType());
-  }
-
-  private DevMain() {}
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/dev/native/cpp/main.cpp b/third_party/allwpilib/wpilibOldCommands/src/dev/native/cpp/main.cpp
deleted file mode 100644
index a3e363e..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/dev/native/cpp/main.cpp
+++ /dev/null
@@ -1,5 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-int main() {}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDBase.java b/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDBase.java
deleted file mode 100644
index 03f9367..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDBase.java
+++ /dev/null
@@ -1,817 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj;
-
-import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
-
-import edu.wpi.first.hal.FRCNetComm.tResourceType;
-import edu.wpi.first.hal.HAL;
-import edu.wpi.first.hal.util.BoundaryException;
-import edu.wpi.first.math.filter.LinearFilter;
-import edu.wpi.first.util.sendable.Sendable;
-import edu.wpi.first.util.sendable.SendableBuilder;
-import edu.wpi.first.util.sendable.SendableRegistry;
-import java.util.concurrent.locks.ReentrantLock;
-
-/**
- * Class implements a PID Control Loop.
- *
- * <p>Creates a separate thread which reads the given PIDSource and takes care of the integral
- * calculations, as well as writing the given PIDOutput.
- *
- * <p>This feedback controller runs in discrete time, so time deltas are not used in the integral
- * and derivative calculations. Therefore, the sample rate affects the controller's behavior for a
- * given set of PID constants.
- *
- * <p>This class is provided by the OldCommands VendorDep
- *
- * @deprecated All APIs which use this have been deprecated.
- */
-@Deprecated(since = "2020", forRemoval = true)
-public class PIDBase implements PIDInterface, PIDOutput, Sendable, AutoCloseable {
-  public static final double kDefaultPeriod = 0.05;
-  private static int instances;
-
-  // Factor for "proportional" control
-  @SuppressWarnings("MemberName")
-  private double m_P;
-
-  // Factor for "integral" control
-  @SuppressWarnings("MemberName")
-  private double m_I;
-
-  // Factor for "derivative" control
-  @SuppressWarnings("MemberName")
-  private double m_D;
-
-  // Factor for "feed forward" control
-  @SuppressWarnings("MemberName")
-  private double m_F;
-
-  // |maximum output|
-  private double m_maximumOutput = 1.0;
-
-  // |minimum output|
-  private double m_minimumOutput = -1.0;
-
-  // Maximum input - limit setpoint to this
-  private double m_maximumInput;
-
-  // Minimum input - limit setpoint to this
-  private double m_minimumInput;
-
-  // Input range - difference between maximum and minimum
-  private double m_inputRange;
-
-  // Do the endpoints wrap around? (e.g., absolute encoder)
-  private boolean m_continuous;
-
-  // Is the PID controller enabled
-  protected boolean m_enabled;
-
-  // The prior error (used to compute velocity)
-  private double m_prevError;
-
-  // The sum of the errors for use in the integral calc
-  private double m_totalError;
-
-  // The tolerance object used to check if on target
-  private Tolerance m_tolerance;
-
-  private double m_setpoint;
-  private double m_prevSetpoint;
-
-  private double m_result;
-
-  private LinearFilter m_filter;
-
-  protected ReentrantLock m_thisMutex = new ReentrantLock();
-
-  // Ensures when disable() is called, pidWrite() won't run if calculate()
-  // is already running at that time.
-  protected ReentrantLock m_pidWriteMutex = new ReentrantLock();
-
-  protected PIDSource m_pidInput;
-  protected PIDOutput m_pidOutput;
-  protected Timer m_setpointTimer;
-
-  /**
-   * Tolerance is the type of tolerance used to specify if the PID controller is on target.
-   *
-   * <p>The various implementations of this class such as PercentageTolerance and AbsoluteTolerance
-   * specify types of tolerance specifications to use.
-   */
-  public interface Tolerance {
-    boolean onTarget();
-  }
-
-  /** Used internally for when Tolerance hasn't been set. */
-  public static class NullTolerance implements Tolerance {
-    @Override
-    public boolean onTarget() {
-      throw new IllegalStateException("No tolerance value set when calling onTarget().");
-    }
-  }
-
-  public class PercentageTolerance implements Tolerance {
-    private final double m_percentage;
-
-    PercentageTolerance(double value) {
-      m_percentage = value;
-    }
-
-    @Override
-    public boolean onTarget() {
-      return Math.abs(getError()) < m_percentage / 100 * m_inputRange;
-    }
-  }
-
-  public class AbsoluteTolerance implements Tolerance {
-    private final double m_value;
-
-    AbsoluteTolerance(double value) {
-      m_value = value;
-    }
-
-    @Override
-    public boolean onTarget() {
-      return Math.abs(getError()) < m_value;
-    }
-  }
-
-  /**
-   * Allocate a PID object with the given constants for P, I, D, and F.
-   *
-   * @param Kp the proportional coefficient
-   * @param Ki the integral coefficient
-   * @param Kd the derivative coefficient
-   * @param Kf the feed forward term
-   * @param source The PIDSource object that is used to get values
-   * @param output The PIDOutput object that is set to the output percentage
-   */
-  @SuppressWarnings("ParameterName")
-  public PIDBase(double Kp, double Ki, double Kd, double Kf, PIDSource source, PIDOutput output) {
-    requireNonNullParam(source, "source", "PIDBase");
-    requireNonNullParam(output, "output", "PIDBase");
-
-    m_setpointTimer = new Timer();
-    m_setpointTimer.start();
-
-    m_P = Kp;
-    m_I = Ki;
-    m_D = Kd;
-    m_F = Kf;
-
-    m_pidInput = source;
-    m_filter = LinearFilter.movingAverage(1);
-
-    m_pidOutput = output;
-
-    instances++;
-    HAL.report(tResourceType.kResourceType_PIDController, instances);
-    m_tolerance = new NullTolerance();
-    SendableRegistry.add(this, "PIDController", instances);
-  }
-
-  /**
-   * Allocate a PID object with the given constants for P, I, and D.
-   *
-   * @param Kp the proportional coefficient
-   * @param Ki the integral coefficient
-   * @param Kd the derivative coefficient
-   * @param source the PIDSource object that is used to get values
-   * @param output the PIDOutput object that is set to the output percentage
-   */
-  @SuppressWarnings("ParameterName")
-  public PIDBase(double Kp, double Ki, double Kd, PIDSource source, PIDOutput output) {
-    this(Kp, Ki, Kd, 0.0, source, output);
-  }
-
-  @Override
-  public void close() {
-    SendableRegistry.remove(this);
-  }
-
-  /**
-   * Read the input, calculate the output accordingly, and write to the output. This should only be
-   * called by the PIDTask and is created during initialization.
-   */
-  @SuppressWarnings("LocalVariableName")
-  protected void calculate() {
-    if (m_pidInput == null || m_pidOutput == null) {
-      return;
-    }
-
-    boolean enabled;
-
-    m_thisMutex.lock();
-    try {
-      enabled = m_enabled;
-    } finally {
-      m_thisMutex.unlock();
-    }
-
-    if (enabled) {
-      double input;
-
-      // Storage for function inputs
-      PIDSourceType pidSourceType;
-      double P;
-      double I;
-      double D;
-      double feedForward = calculateFeedForward();
-      double minimumOutput;
-      double maximumOutput;
-
-      // Storage for function input-outputs
-      double prevError;
-      double error;
-      double totalError;
-
-      m_thisMutex.lock();
-      try {
-        input = m_filter.calculate(m_pidInput.pidGet());
-
-        pidSourceType = m_pidInput.getPIDSourceType();
-        P = m_P;
-        I = m_I;
-        D = m_D;
-        minimumOutput = m_minimumOutput;
-        maximumOutput = m_maximumOutput;
-
-        prevError = m_prevError;
-        error = getContinuousError(m_setpoint - input);
-        totalError = m_totalError;
-      } finally {
-        m_thisMutex.unlock();
-      }
-
-      // Storage for function outputs
-      double result;
-
-      if (pidSourceType.equals(PIDSourceType.kRate)) {
-        if (P != 0) {
-          totalError = clamp(totalError + error, minimumOutput / P, maximumOutput / P);
-        }
-
-        result = P * totalError + D * error + feedForward;
-      } else {
-        if (I != 0) {
-          totalError = clamp(totalError + error, minimumOutput / I, maximumOutput / I);
-        }
-
-        result = P * error + I * totalError + D * (error - prevError) + feedForward;
-      }
-
-      result = clamp(result, minimumOutput, maximumOutput);
-
-      // Ensures m_enabled check and pidWrite() call occur atomically
-      m_pidWriteMutex.lock();
-      m_thisMutex.lock();
-      try {
-        if (m_enabled) {
-          // Don't block other PIDController operations on pidWrite()
-          m_thisMutex.unlock();
-
-          m_pidOutput.pidWrite(result);
-        }
-      } finally {
-        if (!m_enabled) {
-          m_thisMutex.unlock();
-        }
-        m_pidWriteMutex.unlock();
-      }
-
-      m_thisMutex.lock();
-      try {
-        m_prevError = error;
-        m_totalError = totalError;
-        m_result = result;
-      } finally {
-        m_thisMutex.unlock();
-      }
-    }
-  }
-
-  /**
-   * Calculate the feed forward term.
-   *
-   * <p>Both of the provided feed forward calculations are velocity feed forwards. If a different
-   * feed forward calculation is desired, the user can override this function and provide his or her
-   * own. This function does no synchronization because the PIDController class only calls it in
-   * synchronized code, so be careful if calling it oneself.
-   *
-   * <p>If a velocity PID controller is being used, the F term should be set to 1 over the maximum
-   * setpoint for the output. If a position PID controller is being used, the F term should be set
-   * to 1 over the maximum speed for the output measured in setpoint units per this controller's
-   * update period (see the default period in this class's constructor).
-   *
-   * @return The feedforward value.
-   */
-  protected double calculateFeedForward() {
-    if (m_pidInput.getPIDSourceType().equals(PIDSourceType.kRate)) {
-      return m_F * getSetpoint();
-    } else {
-      double temp = m_F * getDeltaSetpoint();
-      m_prevSetpoint = m_setpoint;
-      m_setpointTimer.reset();
-      return temp;
-    }
-  }
-
-  /**
-   * Set the PID Controller gain parameters. Set the proportional, integral, and differential
-   * coefficients.
-   *
-   * @param p Proportional coefficient
-   * @param i Integral coefficient
-   * @param d Differential coefficient
-   */
-  @Override
-  @SuppressWarnings("ParameterName")
-  public void setPID(double p, double i, double d) {
-    m_thisMutex.lock();
-    try {
-      m_P = p;
-      m_I = i;
-      m_D = d;
-    } finally {
-      m_thisMutex.unlock();
-    }
-  }
-
-  /**
-   * Set the PID Controller gain parameters. Set the proportional, integral, and differential
-   * coefficients.
-   *
-   * @param p Proportional coefficient
-   * @param i Integral coefficient
-   * @param d Differential coefficient
-   * @param f Feed forward coefficient
-   */
-  @SuppressWarnings("ParameterName")
-  public void setPID(double p, double i, double d, double f) {
-    m_thisMutex.lock();
-    try {
-      m_P = p;
-      m_I = i;
-      m_D = d;
-      m_F = f;
-    } finally {
-      m_thisMutex.unlock();
-    }
-  }
-
-  /**
-   * Set the Proportional coefficient of the PID controller gain.
-   *
-   * @param p Proportional coefficient
-   */
-  @SuppressWarnings("ParameterName")
-  public void setP(double p) {
-    m_thisMutex.lock();
-    try {
-      m_P = p;
-    } finally {
-      m_thisMutex.unlock();
-    }
-  }
-
-  /**
-   * Set the Integral coefficient of the PID controller gain.
-   *
-   * @param i Integral coefficient
-   */
-  @SuppressWarnings("ParameterName")
-  public void setI(double i) {
-    m_thisMutex.lock();
-    try {
-      m_I = i;
-    } finally {
-      m_thisMutex.unlock();
-    }
-  }
-
-  /**
-   * Set the Differential coefficient of the PID controller gain.
-   *
-   * @param d differential coefficient
-   */
-  @SuppressWarnings("ParameterName")
-  public void setD(double d) {
-    m_thisMutex.lock();
-    try {
-      m_D = d;
-    } finally {
-      m_thisMutex.unlock();
-    }
-  }
-
-  /**
-   * Set the Feed forward coefficient of the PID controller gain.
-   *
-   * @param f feed forward coefficient
-   */
-  @SuppressWarnings("ParameterName")
-  public void setF(double f) {
-    m_thisMutex.lock();
-    try {
-      m_F = f;
-    } finally {
-      m_thisMutex.unlock();
-    }
-  }
-
-  /**
-   * Get the Proportional coefficient.
-   *
-   * @return proportional coefficient
-   */
-  @Override
-  public double getP() {
-    m_thisMutex.lock();
-    try {
-      return m_P;
-    } finally {
-      m_thisMutex.unlock();
-    }
-  }
-
-  /**
-   * Get the Integral coefficient.
-   *
-   * @return integral coefficient
-   */
-  @Override
-  public double getI() {
-    m_thisMutex.lock();
-    try {
-      return m_I;
-    } finally {
-      m_thisMutex.unlock();
-    }
-  }
-
-  /**
-   * Get the Differential coefficient.
-   *
-   * @return differential coefficient
-   */
-  @Override
-  public double getD() {
-    m_thisMutex.lock();
-    try {
-      return m_D;
-    } finally {
-      m_thisMutex.unlock();
-    }
-  }
-
-  /**
-   * Get the Feed forward coefficient.
-   *
-   * @return feed forward coefficient
-   */
-  public double getF() {
-    m_thisMutex.lock();
-    try {
-      return m_F;
-    } finally {
-      m_thisMutex.unlock();
-    }
-  }
-
-  /**
-   * Return the current PID result This is always centered on zero and constrained the the max and
-   * min outs.
-   *
-   * @return the latest calculated output
-   */
-  public double get() {
-    m_thisMutex.lock();
-    try {
-      return m_result;
-    } finally {
-      m_thisMutex.unlock();
-    }
-  }
-
-  /**
-   * Set the PID controller to consider the input to be continuous, Rather then using the max and
-   * min input range as constraints, it considers them to be the same point and automatically
-   * calculates the shortest route to the setpoint.
-   *
-   * @param continuous Set to true turns on continuous, false turns off continuous
-   */
-  public void setContinuous(boolean continuous) {
-    if (continuous && m_inputRange <= 0) {
-      throw new IllegalStateException("No input range set when calling setContinuous().");
-    }
-    m_thisMutex.lock();
-    try {
-      m_continuous = continuous;
-    } finally {
-      m_thisMutex.unlock();
-    }
-  }
-
-  /**
-   * Set the PID controller to consider the input to be continuous, Rather then using the max and
-   * min input range as constraints, it considers them to be the same point and automatically
-   * calculates the shortest route to the setpoint.
-   */
-  public void setContinuous() {
-    setContinuous(true);
-  }
-
-  /**
-   * Sets the maximum and minimum values expected from the input and setpoint.
-   *
-   * @param minimumInput the minimum value expected from the input
-   * @param maximumInput the maximum value expected from the input
-   */
-  public void setInputRange(double minimumInput, double maximumInput) {
-    m_thisMutex.lock();
-    try {
-      if (minimumInput > maximumInput) {
-        throw new BoundaryException("Lower bound is greater than upper bound");
-      }
-      m_minimumInput = minimumInput;
-      m_maximumInput = maximumInput;
-      m_inputRange = maximumInput - minimumInput;
-    } finally {
-      m_thisMutex.unlock();
-    }
-
-    setSetpoint(m_setpoint);
-  }
-
-  /**
-   * Sets the minimum and maximum values to write.
-   *
-   * @param minimumOutput the minimum percentage to write to the output
-   * @param maximumOutput the maximum percentage to write to the output
-   */
-  public void setOutputRange(double minimumOutput, double maximumOutput) {
-    m_thisMutex.lock();
-    try {
-      if (minimumOutput > maximumOutput) {
-        throw new BoundaryException("Lower bound is greater than upper bound");
-      }
-      m_minimumOutput = minimumOutput;
-      m_maximumOutput = maximumOutput;
-    } finally {
-      m_thisMutex.unlock();
-    }
-  }
-
-  /**
-   * Set the setpoint for the PIDController.
-   *
-   * @param setpoint the desired setpoint
-   */
-  @Override
-  public void setSetpoint(double setpoint) {
-    m_thisMutex.lock();
-    try {
-      if (m_maximumInput > m_minimumInput) {
-        if (setpoint > m_maximumInput) {
-          m_setpoint = m_maximumInput;
-        } else if (setpoint < m_minimumInput) {
-          m_setpoint = m_minimumInput;
-        } else {
-          m_setpoint = setpoint;
-        }
-      } else {
-        m_setpoint = setpoint;
-      }
-    } finally {
-      m_thisMutex.unlock();
-    }
-  }
-
-  /**
-   * Returns the current setpoint of the PIDController.
-   *
-   * @return the current setpoint
-   */
-  @Override
-  public double getSetpoint() {
-    m_thisMutex.lock();
-    try {
-      return m_setpoint;
-    } finally {
-      m_thisMutex.unlock();
-    }
-  }
-
-  /**
-   * Returns the change in setpoint over time of the PIDController.
-   *
-   * @return the change in setpoint over time
-   */
-  public double getDeltaSetpoint() {
-    m_thisMutex.lock();
-    try {
-      return (m_setpoint - m_prevSetpoint) / m_setpointTimer.get();
-    } finally {
-      m_thisMutex.unlock();
-    }
-  }
-
-  /**
-   * Returns the current difference of the input from the setpoint.
-   *
-   * @return the current error
-   */
-  @Override
-  public double getError() {
-    m_thisMutex.lock();
-    try {
-      return getContinuousError(getSetpoint() - m_filter.calculate(m_pidInput.pidGet()));
-    } finally {
-      m_thisMutex.unlock();
-    }
-  }
-
-  /**
-   * Returns the current difference of the error over the past few iterations. You can specify the
-   * number of iterations to average with setToleranceBuffer() (defaults to 1). getAvgError() is
-   * used for the onTarget() function.
-   *
-   * @return the current average of the error
-   * @deprecated Use getError(), which is now already filtered.
-   */
-  @Deprecated
-  public double getAvgError() {
-    m_thisMutex.lock();
-    try {
-      return getError();
-    } finally {
-      m_thisMutex.unlock();
-    }
-  }
-
-  /**
-   * Sets what type of input the PID controller will use.
-   *
-   * @param pidSource the type of input
-   */
-  public void setPIDSourceType(PIDSourceType pidSource) {
-    m_pidInput.setPIDSourceType(pidSource);
-  }
-
-  /**
-   * Returns the type of input the PID controller is using.
-   *
-   * @return the PID controller input type
-   */
-  public PIDSourceType getPIDSourceType() {
-    return m_pidInput.getPIDSourceType();
-  }
-
-  /**
-   * Set the PID tolerance using a Tolerance object. Tolerance can be specified as a percentage of
-   * the range or as an absolute value. The Tolerance object encapsulates those options in an
-   * object. Use it by creating the type of tolerance that you want to use: setTolerance(new
-   * PIDController.AbsoluteTolerance(0.1))
-   *
-   * @param tolerance A tolerance object of the right type, e.g. PercentTolerance or
-   *     AbsoluteTolerance
-   * @deprecated Use setPercentTolerance() instead.
-   */
-  @Deprecated
-  public void setTolerance(Tolerance tolerance) {
-    m_tolerance = tolerance;
-  }
-
-  /**
-   * Set the absolute error which is considered tolerable for use with OnTarget.
-   *
-   * @param absvalue absolute error which is tolerable in the units of the input object
-   */
-  public void setAbsoluteTolerance(double absvalue) {
-    m_thisMutex.lock();
-    try {
-      m_tolerance = new AbsoluteTolerance(absvalue);
-    } finally {
-      m_thisMutex.unlock();
-    }
-  }
-
-  /**
-   * Set the percentage error which is considered tolerable for use with OnTarget. (Input of 15.0 =
-   * 15 percent)
-   *
-   * @param percentage percent error which is tolerable
-   */
-  public void setPercentTolerance(double percentage) {
-    m_thisMutex.lock();
-    try {
-      m_tolerance = new PercentageTolerance(percentage);
-    } finally {
-      m_thisMutex.unlock();
-    }
-  }
-
-  /**
-   * Set the number of previous error samples to average for tolerancing. When determining whether a
-   * mechanism is on target, the user may want to use a rolling average of previous measurements
-   * instead of a precise position or velocity. This is useful for noisy sensors which return a few
-   * erroneous measurements when the mechanism is on target. However, the mechanism will not
-   * register as on target for at least the specified bufLength cycles.
-   *
-   * @param bufLength Number of previous cycles to average.
-   * @deprecated Use a LinearFilter as the input.
-   */
-  @Deprecated
-  public void setToleranceBuffer(int bufLength) {
-    m_thisMutex.lock();
-    try {
-      m_filter = LinearFilter.movingAverage(bufLength);
-    } finally {
-      m_thisMutex.unlock();
-    }
-  }
-
-  /**
-   * Return true if the error is within the percentage of the total input range, determined by
-   * setTolerance. This assumes that the maximum and minimum input were set using setInput.
-   *
-   * @return true if the error is less than the tolerance
-   */
-  public boolean onTarget() {
-    m_thisMutex.lock();
-    try {
-      return m_tolerance.onTarget();
-    } finally {
-      m_thisMutex.unlock();
-    }
-  }
-
-  /** Reset the previous error, the integral term, and disable the controller. */
-  @Override
-  public void reset() {
-    m_thisMutex.lock();
-    try {
-      m_prevError = 0;
-      m_totalError = 0;
-      m_result = 0;
-    } finally {
-      m_thisMutex.unlock();
-    }
-  }
-
-  /**
-   * Passes the output directly to setSetpoint().
-   *
-   * <p>PIDControllers can be nested by passing a PIDController as another PIDController's output.
-   * In that case, the output of the parent controller becomes the input (i.e., the reference) of
-   * the child.
-   *
-   * <p>It is the caller's responsibility to put the data into a valid form for setSetpoint().
-   */
-  @Override
-  public void pidWrite(double output) {
-    setSetpoint(output);
-  }
-
-  @Override
-  public void initSendable(SendableBuilder builder) {
-    builder.setSmartDashboardType("PIDController");
-    builder.setSafeState(this::reset);
-    builder.addDoubleProperty("p", this::getP, this::setP);
-    builder.addDoubleProperty("i", this::getI, this::setI);
-    builder.addDoubleProperty("d", this::getD, this::setD);
-    builder.addDoubleProperty("f", this::getF, this::setF);
-    builder.addDoubleProperty("setpoint", this::getSetpoint, this::setSetpoint);
-  }
-
-  /**
-   * Wraps error around for continuous inputs. The original error is returned if continuous mode is
-   * disabled. This is an unsynchronized function.
-   *
-   * @param error The current error of the PID controller.
-   * @return Error for continuous inputs.
-   */
-  protected double getContinuousError(double error) {
-    if (m_continuous && m_inputRange > 0) {
-      error %= m_inputRange;
-      if (Math.abs(error) > m_inputRange / 2) {
-        if (error > 0) {
-          return error - m_inputRange;
-        } else {
-          return error + m_inputRange;
-        }
-      }
-    }
-
-    return error;
-  }
-
-  private static double clamp(double value, double low, double high) {
-    return Math.max(low, Math.min(value, high));
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDController.java b/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDController.java
deleted file mode 100644
index 98580ef..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDController.java
+++ /dev/null
@@ -1,182 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj;
-
-import edu.wpi.first.util.sendable.SendableBuilder;
-
-/**
- * Class implements a PID Control Loop.
- *
- * <p>Creates a separate thread which reads the given PIDSource and takes care of the integral
- * calculations, as well as writing the given PIDOutput.
- *
- * <p>This feedback controller runs in discrete time, so time deltas are not used in the integral
- * and derivative calculations. Therefore, the sample rate affects the controller's behavior for a
- * given set of PID constants.
- *
- * <p>This class is provided by the OldCommands VendorDep
- *
- * @deprecated Use {@link edu.wpi.first.math.controller.PIDController} instead.
- */
-@Deprecated(since = "2020", forRemoval = true)
-public class PIDController extends PIDBase implements Controller {
-  Notifier m_controlLoop = new Notifier(this::calculate);
-
-  /**
-   * Allocate a PID object with the given constants for P, I, D, and F.
-   *
-   * @param Kp the proportional coefficient
-   * @param Ki the integral coefficient
-   * @param Kd the derivative coefficient
-   * @param Kf the feed forward term
-   * @param source The PIDSource object that is used to get values
-   * @param output The PIDOutput object that is set to the output percentage
-   * @param period the loop time for doing calculations in seconds. This particularly affects
-   *     calculations of the integral and differential terms. The default is 0.05 (50ms).
-   */
-  @SuppressWarnings("ParameterName")
-  public PIDController(
-      double Kp,
-      double Ki,
-      double Kd,
-      double Kf,
-      PIDSource source,
-      PIDOutput output,
-      double period) {
-    super(Kp, Ki, Kd, Kf, source, output);
-    m_controlLoop.startPeriodic(period);
-  }
-
-  /**
-   * Allocate a PID object with the given constants for P, I, D and period.
-   *
-   * @param Kp the proportional coefficient
-   * @param Ki the integral coefficient
-   * @param Kd the derivative coefficient
-   * @param source the PIDSource object that is used to get values
-   * @param output the PIDOutput object that is set to the output percentage
-   * @param period the loop time for doing calculations in seconds. This particularly affects
-   *     calculations of the integral and differential terms. The default is 0.05 (50ms).
-   */
-  @SuppressWarnings("ParameterName")
-  public PIDController(
-      double Kp, double Ki, double Kd, PIDSource source, PIDOutput output, double period) {
-    this(Kp, Ki, Kd, 0.0, source, output, period);
-  }
-
-  /**
-   * Allocate a PID object with the given constants for P, I, D, using a 50ms period.
-   *
-   * @param Kp the proportional coefficient
-   * @param Ki the integral coefficient
-   * @param Kd the derivative coefficient
-   * @param source The PIDSource object that is used to get values
-   * @param output The PIDOutput object that is set to the output percentage
-   */
-  @SuppressWarnings("ParameterName")
-  public PIDController(double Kp, double Ki, double Kd, PIDSource source, PIDOutput output) {
-    this(Kp, Ki, Kd, source, output, kDefaultPeriod);
-  }
-
-  /**
-   * Allocate a PID object with the given constants for P, I, D, using a 50ms period.
-   *
-   * @param Kp the proportional coefficient
-   * @param Ki the integral coefficient
-   * @param Kd the derivative coefficient
-   * @param Kf the feed forward term
-   * @param source The PIDSource object that is used to get values
-   * @param output The PIDOutput object that is set to the output percentage
-   */
-  @SuppressWarnings("ParameterName")
-  public PIDController(
-      double Kp, double Ki, double Kd, double Kf, PIDSource source, PIDOutput output) {
-    this(Kp, Ki, Kd, Kf, source, output, kDefaultPeriod);
-  }
-
-  @Override
-  public void close() {
-    m_controlLoop.close();
-    m_thisMutex.lock();
-    try {
-      m_pidOutput = null;
-      m_pidInput = null;
-      m_controlLoop = null;
-    } finally {
-      m_thisMutex.unlock();
-    }
-  }
-
-  /** Begin running the PIDController. */
-  @Override
-  public void enable() {
-    m_thisMutex.lock();
-    try {
-      m_enabled = true;
-    } finally {
-      m_thisMutex.unlock();
-    }
-  }
-
-  /** Stop running the PIDController, this sets the output to zero before stopping. */
-  @Override
-  public void disable() {
-    // Ensures m_enabled check and pidWrite() call occur atomically
-    m_pidWriteMutex.lock();
-    try {
-      m_thisMutex.lock();
-      try {
-        m_enabled = false;
-      } finally {
-        m_thisMutex.unlock();
-      }
-
-      m_pidOutput.pidWrite(0);
-    } finally {
-      m_pidWriteMutex.unlock();
-    }
-  }
-
-  /**
-   * Set the enabled state of the PIDController.
-   *
-   * @param enable True to enable the PIDController.
-   */
-  public void setEnabled(boolean enable) {
-    if (enable) {
-      enable();
-    } else {
-      disable();
-    }
-  }
-
-  /**
-   * Return true if PIDController is enabled.
-   *
-   * @return True if PIDController is enabled.
-   */
-  public boolean isEnabled() {
-    m_thisMutex.lock();
-    try {
-      return m_enabled;
-    } finally {
-      m_thisMutex.unlock();
-    }
-  }
-
-  /** Reset the previous error, the integral term, and disable the controller. */
-  @Override
-  public void reset() {
-    disable();
-
-    super.reset();
-  }
-
-  @Override
-  public void initSendable(SendableBuilder builder) {
-    super.initSendable(builder);
-    builder.addBooleanProperty("enabled", this::isEnabled, this::setEnabled);
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDInterface.java b/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDInterface.java
deleted file mode 100644
index 4e7fd90..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDInterface.java
+++ /dev/null
@@ -1,32 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj;
-
-/**
- * Interface for PID Controller.
- *
- * <p>This class is provided by the OldCommands VendorDep
- *
- * @deprecated All APIs which use this have been deprecated.
- */
-@Deprecated(since = "2020", forRemoval = true)
-@SuppressWarnings("SummaryJavadoc")
-public interface PIDInterface {
-  void setPID(double p, double i, double d);
-
-  double getP();
-
-  double getI();
-
-  double getD();
-
-  void setSetpoint(double setpoint);
-
-  double getSetpoint();
-
-  double getError();
-
-  void reset();
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDOutput.java b/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDOutput.java
deleted file mode 100644
index a330daf..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDOutput.java
+++ /dev/null
@@ -1,23 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj;
-
-/**
- * This interface allows PIDController to write it's results to its output.
- *
- * <p>This class is provided by the OldCommands VendorDep
- *
- * @deprecated Use DoubleConsumer and new PIDController class.
- */
-@FunctionalInterface
-@Deprecated(since = "2020", forRemoval = true)
-public interface PIDOutput {
-  /**
-   * Set the output to the value calculated by PIDController.
-   *
-   * @param output the value calculated by PIDController
-   */
-  void pidWrite(double output);
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDSource.java b/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDSource.java
deleted file mode 100644
index e582168..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDSource.java
+++ /dev/null
@@ -1,36 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj;
-
-/**
- * This interface allows for PIDController to automatically read from this object.
- *
- * <p>This class is provided by the OldCommands VendorDep
- *
- * @deprecated Use DoubleSupplier and new PIDController class.
- */
-@Deprecated(since = "2020", forRemoval = true)
-public interface PIDSource {
-  /**
-   * Set which parameter of the device you are using as a process control variable.
-   *
-   * @param pidSource An enum to select the parameter.
-   */
-  void setPIDSourceType(PIDSourceType pidSource);
-
-  /**
-   * Get which parameter of the device you are using as a process control variable.
-   *
-   * @return the currently selected PID source parameter
-   */
-  PIDSourceType getPIDSourceType();
-
-  /**
-   * Get the result to use in PIDController.
-   *
-   * @return the result to use in PIDController
-   */
-  double pidGet();
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDSourceType.java b/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDSourceType.java
deleted file mode 100644
index 3f41eb1..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDSourceType.java
+++ /dev/null
@@ -1,16 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj;
-
-/**
- * A description for the type of output value to provide to a PIDController.
- *
- * <p>This class is provided by the OldCommands VendorDep
- */
-@Deprecated(since = "2020", forRemoval = true)
-public enum PIDSourceType {
-  kDisplacement,
-  kRate
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/buttons/Button.java b/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/buttons/Button.java
deleted file mode 100644
index 8347993..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/buttons/Button.java
+++ /dev/null
@@ -1,69 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.buttons;
-
-import edu.wpi.first.wpilibj.command.Command;
-
-/**
- * This class provides an easy way to link commands to OI inputs.
- *
- * <p>It is very easy to link a button to a command. For instance, you could link the trigger button
- * of a joystick to a "score" command.
- *
- * <p>This class represents a subclass of Trigger that is specifically aimed at buttons on an
- * operator interface as a common use case of the more generalized Trigger objects. This is a simple
- * wrapper around Trigger with the method names renamed to fit the Button object use.
- *
- * <p>This class is provided by the OldCommands VendorDep
- */
-public abstract class Button extends Trigger {
-  /**
-   * Starts the given command whenever the button is newly pressed.
-   *
-   * @param command the command to start
-   */
-  public void whenPressed(final Command command) {
-    whenActive(command);
-  }
-
-  /**
-   * Constantly starts the given command while the button is held.
-   *
-   * <p>{@link Command#start()} will be called repeatedly while the button is held, and will be
-   * canceled when the button is released.
-   *
-   * @param command the command to start
-   */
-  public void whileHeld(final Command command) {
-    whileActive(command);
-  }
-
-  /**
-   * Starts the command when the button is released.
-   *
-   * @param command the command to start
-   */
-  public void whenReleased(final Command command) {
-    whenInactive(command);
-  }
-
-  /**
-   * Toggles the command whenever the button is pressed (on then off then on).
-   *
-   * @param command the command to start
-   */
-  public void toggleWhenPressed(final Command command) {
-    toggleWhenActive(command);
-  }
-
-  /**
-   * Cancel the command when the button is pressed.
-   *
-   * @param command the command to start
-   */
-  public void cancelWhenPressed(final Command command) {
-    cancelWhenActive(command);
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/buttons/InternalButton.java b/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/buttons/InternalButton.java
deleted file mode 100644
index 37cf28d..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/buttons/InternalButton.java
+++ /dev/null
@@ -1,44 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.buttons;
-
-/**
- * This {@link Button} is intended to be used within a program. The programmer can manually set its
- * value. * Also includes a setting for whether or not it should invert its value.
- *
- * <p>This class is provided by the OldCommands VendorDep
- */
-public class InternalButton extends Button {
-  private boolean m_pressed;
-  private boolean m_inverted;
-
-  /** Creates an InternalButton that is not inverted. */
-  public InternalButton() {
-    this(false);
-  }
-
-  /**
-   * Creates an InternalButton which is inverted depending on the input.
-   *
-   * @param inverted if false, then this button is pressed when set to true, otherwise it is pressed
-   *     when set to false.
-   */
-  public InternalButton(boolean inverted) {
-    m_pressed = m_inverted = inverted;
-  }
-
-  public void setInverted(boolean inverted) {
-    m_inverted = inverted;
-  }
-
-  public void setPressed(boolean pressed) {
-    m_pressed = pressed;
-  }
-
-  @Override
-  public boolean get() {
-    return m_pressed ^ m_inverted;
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/buttons/JoystickButton.java b/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/buttons/JoystickButton.java
deleted file mode 100644
index 241683a..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/buttons/JoystickButton.java
+++ /dev/null
@@ -1,38 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.buttons;
-
-import edu.wpi.first.wpilibj.GenericHID;
-
-/**
- * A {@link Button} that gets its state from a {@link GenericHID}.
- *
- * <p>This class is provided by the OldCommands VendorDep
- */
-public class JoystickButton extends Button {
-  private final GenericHID m_joystick;
-  private final int m_buttonNumber;
-
-  /**
-   * Create a joystick button for triggering commands.
-   *
-   * @param joystick The GenericHID object that has the button (e.g. Joystick, KinectStick, etc)
-   * @param buttonNumber The button number (see {@link GenericHID#getRawButton(int) }
-   */
-  public JoystickButton(GenericHID joystick, int buttonNumber) {
-    m_joystick = joystick;
-    m_buttonNumber = buttonNumber;
-  }
-
-  /**
-   * Gets the value of the joystick button.
-   *
-   * @return The value of the joystick button
-   */
-  @Override
-  public boolean get() {
-    return m_joystick.getRawButton(m_buttonNumber);
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/buttons/NetworkButton.java b/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/buttons/NetworkButton.java
deleted file mode 100644
index dd538bf..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/buttons/NetworkButton.java
+++ /dev/null
@@ -1,31 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.buttons;
-
-import edu.wpi.first.networktables.NetworkTable;
-import edu.wpi.first.networktables.NetworkTableEntry;
-import edu.wpi.first.networktables.NetworkTableInstance;
-
-/**
- * A {@link Button} that uses a {@link NetworkTable} boolean field.
- *
- * <p>This class is provided by the OldCommands VendorDep
- */
-public class NetworkButton extends Button {
-  private final NetworkTableEntry m_entry;
-
-  public NetworkButton(String table, String field) {
-    this(NetworkTableInstance.getDefault().getTable(table), field);
-  }
-
-  public NetworkButton(NetworkTable table, String field) {
-    m_entry = table.getEntry(field);
-  }
-
-  @Override
-  public boolean get() {
-    return m_entry.getInstance().isConnected() && m_entry.getBoolean(false);
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/buttons/POVButton.java b/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/buttons/POVButton.java
deleted file mode 100644
index a58ba03..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/buttons/POVButton.java
+++ /dev/null
@@ -1,51 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.buttons;
-
-import edu.wpi.first.wpilibj.GenericHID;
-
-/**
- * A {@link Button} that gets its state from a POV on a {@link GenericHID}.
- *
- * <p>This class is provided by the OldCommands VendorDep
- */
-public class POVButton extends Button {
-  private final GenericHID m_joystick;
-  private final int m_angle;
-  private final int m_povNumber;
-
-  /**
-   * Creates a POV button for triggering commands.
-   *
-   * @param joystick The GenericHID object that has the POV
-   * @param angle The desired angle in degrees (e.g. 90, 270)
-   * @param povNumber The POV number (see {@link GenericHID#getPOV(int)})
-   */
-  public POVButton(GenericHID joystick, int angle, int povNumber) {
-    m_joystick = joystick;
-    m_angle = angle;
-    m_povNumber = povNumber;
-  }
-
-  /**
-   * Creates a POV button for triggering commands. By default, acts on POV 0
-   *
-   * @param joystick The GenericHID object that has the POV
-   * @param angle The desired angle (e.g. 90, 270)
-   */
-  public POVButton(GenericHID joystick, int angle) {
-    this(joystick, angle, 0);
-  }
-
-  /**
-   * Checks whether the current value of the POV is the target angle.
-   *
-   * @return Whether the value of the POV matches the target angle
-   */
-  @Override
-  public boolean get() {
-    return m_joystick.getPOV(m_povNumber) == m_angle;
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/buttons/Trigger.java b/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/buttons/Trigger.java
deleted file mode 100644
index 1024068..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/buttons/Trigger.java
+++ /dev/null
@@ -1,183 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.buttons;
-
-import edu.wpi.first.util.sendable.Sendable;
-import edu.wpi.first.util.sendable.SendableBuilder;
-import edu.wpi.first.wpilibj.command.Command;
-import edu.wpi.first.wpilibj.command.Scheduler;
-
-/**
- * This class provides an easy way to link commands to inputs.
- *
- * <p>It is very easy to link a button to a command. For instance, you could link the trigger button
- * of a joystick to a "score" command.
- *
- * <p>It is encouraged that teams write a subclass of Trigger if they want to have something unusual
- * (for instance, if they want to react to the user holding a button while the robot is reading a
- * certain sensor input). For this, they only have to write the {@link Trigger#get()} method to get
- * the full functionality of the Trigger class.
- *
- * <p>This class is provided by the OldCommands VendorDep
- */
-public abstract class Trigger implements Sendable {
-  private volatile boolean m_sendablePressed;
-
-  /**
-   * Returns whether or not the trigger is active.
-   *
-   * <p>This method will be called repeatedly a command is linked to the Trigger.
-   *
-   * @return whether or not the trigger condition is active.
-   */
-  public abstract boolean get();
-
-  /**
-   * Returns whether get() return true or the internal table for SmartDashboard use is pressed.
-   *
-   * @return whether get() return true or the internal table for SmartDashboard use is pressed.
-   */
-  private boolean grab() {
-    return get() || m_sendablePressed;
-  }
-
-  /**
-   * Starts the given command whenever the trigger just becomes active.
-   *
-   * @param command the command to start
-   */
-  public void whenActive(final Command command) {
-    new ButtonScheduler() {
-      private boolean m_pressedLast = grab();
-
-      @Override
-      public void execute() {
-        boolean pressed = grab();
-
-        if (!m_pressedLast && pressed) {
-          command.start();
-        }
-
-        m_pressedLast = pressed;
-      }
-    }.start();
-  }
-
-  /**
-   * Constantly starts the given command while the button is held.
-   *
-   * <p>{@link Command#start()} will be called repeatedly while the trigger is active, and will be
-   * canceled when the trigger becomes inactive.
-   *
-   * @param command the command to start
-   */
-  public void whileActive(final Command command) {
-    new ButtonScheduler() {
-      private boolean m_pressedLast = grab();
-
-      @Override
-      public void execute() {
-        boolean pressed = grab();
-
-        if (pressed) {
-          command.start();
-        } else if (m_pressedLast && !pressed) {
-          command.cancel();
-        }
-
-        m_pressedLast = pressed;
-      }
-    }.start();
-  }
-
-  /**
-   * Starts the command when the trigger becomes inactive.
-   *
-   * @param command the command to start
-   */
-  public void whenInactive(final Command command) {
-    new ButtonScheduler() {
-      private boolean m_pressedLast = grab();
-
-      @Override
-      public void execute() {
-        boolean pressed = grab();
-
-        if (m_pressedLast && !pressed) {
-          command.start();
-        }
-
-        m_pressedLast = pressed;
-      }
-    }.start();
-  }
-
-  /**
-   * Toggles a command when the trigger becomes active.
-   *
-   * @param command the command to toggle
-   */
-  public void toggleWhenActive(final Command command) {
-    new ButtonScheduler() {
-      private boolean m_pressedLast = grab();
-
-      @Override
-      public void execute() {
-        boolean pressed = grab();
-
-        if (!m_pressedLast && pressed) {
-          if (command.isRunning()) {
-            command.cancel();
-          } else {
-            command.start();
-          }
-        }
-
-        m_pressedLast = pressed;
-      }
-    }.start();
-  }
-
-  /**
-   * Cancels a command when the trigger becomes active.
-   *
-   * @param command the command to cancel
-   */
-  public void cancelWhenActive(final Command command) {
-    new ButtonScheduler() {
-      private boolean m_pressedLast = grab();
-
-      @Override
-      public void execute() {
-        boolean pressed = grab();
-
-        if (!m_pressedLast && pressed) {
-          command.cancel();
-        }
-
-        m_pressedLast = pressed;
-      }
-    }.start();
-  }
-
-  /**
-   * An internal class of {@link Trigger}. The user should ignore this, it is only public to
-   * interface between packages.
-   */
-  public abstract static class ButtonScheduler {
-    public abstract void execute();
-
-    public void start() {
-      Scheduler.getInstance().addButton(this);
-    }
-  }
-
-  @Override
-  public void initSendable(SendableBuilder builder) {
-    builder.setSmartDashboardType("Button");
-    builder.setSafeState(() -> m_sendablePressed = false);
-    builder.addBooleanProperty("pressed", this::grab, value -> m_sendablePressed = value);
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/Command.java b/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/Command.java
deleted file mode 100644
index 8732186..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/Command.java
+++ /dev/null
@@ -1,627 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-import edu.wpi.first.util.sendable.Sendable;
-import edu.wpi.first.util.sendable.SendableBuilder;
-import edu.wpi.first.util.sendable.SendableRegistry;
-import edu.wpi.first.wpilibj.RobotState;
-import edu.wpi.first.wpilibj.Timer;
-import java.util.Enumeration;
-
-/**
- * The Command class is at the very core of the entire command framework. Every command can be
- * started with a call to {@link Command#start() start()}. Once a command is started it will call
- * {@link Command#initialize() initialize()}, and then will repeatedly call {@link Command#execute()
- * execute()} until the {@link Command#isFinished() isFinished()} returns true. Once it does, {@link
- * Command#end() end()} will be called.
- *
- * <p>However, if at any point while it is running {@link Command#cancel() cancel()} is called, then
- * the command will be stopped and {@link Command#interrupted() interrupted()} will be called.
- *
- * <p>If a command uses a {@link Subsystem}, then it should specify that it does so by calling the
- * {@link Command#requires(Subsystem) requires(...)} method in its constructor. Note that a Command
- * may have multiple requirements, and {@link Command#requires(Subsystem) requires(...)} should be
- * called for each one.
- *
- * <p>If a command is running and a new command with shared requirements is started, then one of two
- * things will happen. If the active command is interruptible, then {@link Command#cancel()
- * cancel()} will be called and the command will be removed to make way for the new one. If the
- * active command is not interruptible, the other one will not even be started, and the active one
- * will continue functioning.
- *
- * <p>This class is provided by the OldCommands VendorDep
- *
- * @see Subsystem
- * @see CommandGroup
- * @see IllegalUseOfCommandException
- */
-public abstract class Command implements Sendable, AutoCloseable {
-  /** The time since this command was initialized. */
-  private double m_startTime = -1;
-
-  /** The time (in seconds) before this command "times out" (or -1 if no timeout). */
-  private double m_timeout = -1;
-
-  /** Whether or not this command has been initialized. */
-  private boolean m_initialized;
-
-  /** The required subsystems. */
-  private final Set m_requirements = new Set();
-
-  /** Whether or not it is running. */
-  private boolean m_running;
-
-  /** Whether or not it is interruptible. */
-  private boolean m_interruptible = true;
-
-  /** Whether or not it has been canceled. */
-  private boolean m_canceled;
-
-  /** Whether or not it has been locked. */
-  private boolean m_locked;
-
-  /** Whether this command should run when the robot is disabled. */
-  private boolean m_runWhenDisabled;
-
-  /** Whether or not this command has completed running. */
-  private boolean m_completed;
-
-  /** The {@link CommandGroup} this is in. */
-  private CommandGroup m_parent;
-
-  /** Creates a new command. The name of this command will be set to its class name. */
-  public Command() {
-    String name = getClass().getName();
-    SendableRegistry.add(this, name.substring(name.lastIndexOf('.') + 1));
-  }
-
-  /**
-   * Creates a new command with the given name.
-   *
-   * @param name the name for this command
-   * @throws IllegalArgumentException if name is null
-   */
-  public Command(String name) {
-    if (name == null) {
-      throw new IllegalArgumentException("Name must not be null.");
-    }
-    SendableRegistry.add(this, name);
-  }
-
-  /**
-   * Creates a new command with the given timeout and a default name. The default name is the name
-   * of the class.
-   *
-   * @param timeout the time (in seconds) before this command "times out"
-   * @throws IllegalArgumentException if given a negative timeout
-   * @see Command#isTimedOut() isTimedOut()
-   */
-  public Command(double timeout) {
-    this();
-    if (timeout < 0) {
-      throw new IllegalArgumentException("Timeout must not be negative.  Given:" + timeout);
-    }
-    m_timeout = timeout;
-  }
-
-  /**
-   * Creates a new command with the given timeout and a default name. The default name is the name
-   * of the class.
-   *
-   * @param subsystem the subsystem that this command requires
-   * @throws IllegalArgumentException if given a negative timeout
-   * @see Command#isTimedOut() isTimedOut()
-   */
-  public Command(Subsystem subsystem) {
-    this();
-    requires(subsystem);
-  }
-
-  /**
-   * Creates a new command with the given name.
-   *
-   * @param name the name for this command
-   * @param subsystem the subsystem that this command requires
-   * @throws IllegalArgumentException if name is null
-   */
-  public Command(String name, Subsystem subsystem) {
-    this(name);
-    requires(subsystem);
-  }
-
-  /**
-   * Creates a new command with the given timeout and a default name. The default name is the name
-   * of the class.
-   *
-   * @param timeout the time (in seconds) before this command "times out"
-   * @param subsystem the subsystem that this command requires
-   * @throws IllegalArgumentException if given a negative timeout
-   * @see Command#isTimedOut() isTimedOut()
-   */
-  public Command(double timeout, Subsystem subsystem) {
-    this(timeout);
-    requires(subsystem);
-  }
-
-  /**
-   * Creates a new command with the given name and timeout.
-   *
-   * @param name the name of the command
-   * @param timeout the time (in seconds) before this command "times out"
-   * @throws IllegalArgumentException if given a negative timeout or name was null.
-   * @see Command#isTimedOut() isTimedOut()
-   */
-  public Command(String name, double timeout) {
-    this(name);
-    if (timeout < 0) {
-      throw new IllegalArgumentException("Timeout must not be negative.  Given:" + timeout);
-    }
-    m_timeout = timeout;
-  }
-
-  /**
-   * Creates a new command with the given name and timeout.
-   *
-   * @param name the name of the command
-   * @param timeout the time (in seconds) before this command "times out"
-   * @param subsystem the subsystem that this command requires
-   * @throws IllegalArgumentException if given a negative timeout
-   * @throws IllegalArgumentException if given a negative timeout or name was null.
-   * @see Command#isTimedOut() isTimedOut()
-   */
-  public Command(String name, double timeout, Subsystem subsystem) {
-    this(name, timeout);
-    requires(subsystem);
-  }
-
-  @Override
-  public void close() {
-    SendableRegistry.remove(this);
-  }
-
-  /**
-   * Sets the timeout of this command.
-   *
-   * @param seconds the timeout (in seconds)
-   * @throws IllegalArgumentException if seconds is negative
-   * @see Command#isTimedOut() isTimedOut()
-   */
-  protected final synchronized void setTimeout(double seconds) {
-    if (seconds < 0) {
-      throw new IllegalArgumentException("Seconds must be positive.  Given:" + seconds);
-    }
-    m_timeout = seconds;
-  }
-
-  /**
-   * Returns the time since this command was initialized (in seconds). This function will work even
-   * if there is no specified timeout.
-   *
-   * @return the time since this command was initialized (in seconds).
-   */
-  public final synchronized double timeSinceInitialized() {
-    return m_startTime < 0 ? 0 : Timer.getFPGATimestamp() - m_startTime;
-  }
-
-  /**
-   * This method specifies that the given {@link Subsystem} is used by this command. This method is
-   * crucial to the functioning of the Command System in general.
-   *
-   * <p>Note that the recommended way to call this method is in the constructor.
-   *
-   * @param subsystem the {@link Subsystem} required
-   * @throws IllegalArgumentException if subsystem is null
-   * @throws IllegalUseOfCommandException if this command has started before or if it has been given
-   *     to a {@link CommandGroup}
-   * @see Subsystem
-   */
-  protected synchronized void requires(Subsystem subsystem) {
-    validate("Can not add new requirement to command");
-    if (subsystem != null) {
-      m_requirements.add(subsystem);
-    } else {
-      throw new IllegalArgumentException("Subsystem must not be null.");
-    }
-  }
-
-  /**
-   * Called when the command has been removed. This will call {@link Command#interrupted()
-   * interrupted()} or {@link Command#end() end()}.
-   */
-  synchronized void removed() {
-    if (m_initialized) {
-      if (isCanceled()) {
-        interrupted();
-        _interrupted();
-      } else {
-        end();
-        _end();
-      }
-    }
-    m_initialized = false;
-    m_canceled = false;
-    m_running = false;
-    m_completed = true;
-  }
-
-  /**
-   * The run method is used internally to actually run the commands.
-   *
-   * @return whether or not the command should stay within the {@link Scheduler}.
-   */
-  synchronized boolean run() {
-    if (!m_runWhenDisabled && m_parent == null && RobotState.isDisabled()) {
-      cancel();
-    }
-    if (isCanceled()) {
-      return false;
-    }
-    if (!m_initialized) {
-      m_initialized = true;
-      startTiming();
-      _initialize();
-      initialize();
-    }
-    _execute();
-    execute();
-    return !isFinished();
-  }
-
-  /** The initialize method is called the first time this Command is run after being started. */
-  protected void initialize() {}
-
-  /** A shadow method called before {@link Command#initialize() initialize()}. */
-  @SuppressWarnings("MethodName")
-  void _initialize() {}
-
-  /** The execute method is called repeatedly until this Command either finishes or is canceled. */
-  @SuppressWarnings("MethodName")
-  protected void execute() {}
-
-  /** A shadow method called before {@link Command#execute() execute()}. */
-  @SuppressWarnings("MethodName")
-  void _execute() {}
-
-  /**
-   * Returns whether this command is finished. If it is, then the command will be removed and {@link
-   * Command#end() end()} will be called.
-   *
-   * <p>It may be useful for a team to reference the {@link Command#isTimedOut() isTimedOut()}
-   * method for time-sensitive commands.
-   *
-   * <p>Returning false will result in the command never ending automatically. It may still be
-   * canceled manually or interrupted by another command. Returning true will result in the command
-   * executing once and finishing immediately. We recommend using {@link InstantCommand} for this.
-   *
-   * @return whether this command is finished.
-   * @see Command#isTimedOut() isTimedOut()
-   */
-  protected abstract boolean isFinished();
-
-  /**
-   * Called when the command ended peacefully. This is where you may want to wrap up loose ends,
-   * like shutting off a motor that was being used in the command.
-   */
-  protected void end() {}
-
-  /** A shadow method called after {@link Command#end() end()}. */
-  @SuppressWarnings("MethodName")
-  void _end() {}
-
-  /**
-   * Called when the command ends because somebody called {@link Command#cancel() cancel()} or
-   * another command shared the same requirements as this one, and booted it out.
-   *
-   * <p>This is where you may want to wrap up loose ends, like shutting off a motor that was being
-   * used in the command.
-   *
-   * <p>Generally, it is useful to simply call the {@link Command#end() end()} method within this
-   * method, as done here.
-   */
-  protected void interrupted() {
-    end();
-  }
-
-  /** A shadow method called after {@link Command#interrupted() interrupted()}. */
-  @SuppressWarnings("MethodName")
-  void _interrupted() {}
-
-  /**
-   * Called to indicate that the timer should start. This is called right before {@link
-   * Command#initialize() initialize()} is, inside the {@link Command#run() run()} method.
-   */
-  private void startTiming() {
-    m_startTime = Timer.getFPGATimestamp();
-  }
-
-  /**
-   * Returns whether or not the {@link Command#timeSinceInitialized() timeSinceInitialized()} method
-   * returns a number which is greater than or equal to the timeout for the command. If there is no
-   * timeout, this will always return false.
-   *
-   * @return whether the time has expired
-   */
-  protected synchronized boolean isTimedOut() {
-    return m_timeout != -1 && timeSinceInitialized() >= m_timeout;
-  }
-
-  /**
-   * Returns the requirements (as an {@link Enumeration Enumeration} of {@link Subsystem
-   * Subsystems}) of this command.
-   *
-   * @return the requirements (as an {@link Enumeration Enumeration} of {@link Subsystem
-   *     Subsystems}) of this command
-   */
-  synchronized Enumeration<?> getRequirements() {
-    return m_requirements.getElements();
-  }
-
-  /** Prevents further changes from being made. */
-  synchronized void lockChanges() {
-    m_locked = true;
-  }
-
-  /**
-   * If changes are locked, then this will throw an {@link IllegalUseOfCommandException}.
-   *
-   * @param message the message to say (it is appended by a default message)
-   */
-  synchronized void validate(String message) {
-    if (m_locked) {
-      throw new IllegalUseOfCommandException(
-          message + " after being started or being added to a command group");
-    }
-  }
-
-  /**
-   * Sets the parent of this command. No actual change is made to the group.
-   *
-   * @param parent the parent
-   * @throws IllegalUseOfCommandException if this {@link Command} already is already in a group
-   */
-  synchronized void setParent(CommandGroup parent) {
-    if (m_parent != null) {
-      throw new IllegalUseOfCommandException(
-          "Can not give command to a command group after already being put in a command group");
-    }
-    lockChanges();
-    m_parent = parent;
-  }
-
-  /**
-   * Returns whether the command has a parent.
-   *
-   * @return true if the command has a parent.
-   */
-  synchronized boolean isParented() {
-    return m_parent != null;
-  }
-
-  /**
-   * Clears list of subsystem requirements. This is only used by {@link ConditionalCommand} so
-   * canceling the chosen command works properly in {@link CommandGroup}.
-   */
-  protected void clearRequirements() {
-    m_requirements.clear();
-  }
-
-  /**
-   * Starts up the command. Gets the command ready to start.
-   *
-   * <p>Note that the command will eventually start, however it will not necessarily do so
-   * immediately, and may in fact be canceled before initialize is even called.
-   *
-   * @throws IllegalUseOfCommandException if the command is a part of a CommandGroup
-   */
-  public synchronized void start() {
-    lockChanges();
-    if (m_parent != null) {
-      throw new IllegalUseOfCommandException(
-          "Can not start a command that is a part of a command group");
-    }
-    Scheduler.getInstance().add(this);
-    m_completed = false;
-  }
-
-  /**
-   * This is used internally to mark that the command has been started. The lifecycle of a command
-   * is:
-   *
-   * <p>startRunning() is called. run() is called (multiple times potentially) removed() is called.
-   *
-   * <p>It is very important that startRunning and removed be called in order or some assumptions of
-   * the code will be broken.
-   */
-  synchronized void startRunning() {
-    m_running = true;
-    m_startTime = -1;
-  }
-
-  /**
-   * Returns whether or not the command is running. This may return true even if the command has
-   * just been canceled, as it may not have yet called {@link Command#interrupted()}.
-   *
-   * @return whether or not the command is running
-   */
-  public synchronized boolean isRunning() {
-    return m_running;
-  }
-
-  /**
-   * This will cancel the current command.
-   *
-   * <p>This will cancel the current command eventually. It can be called multiple times. And it can
-   * be called when the command is not running. If the command is running though, then the command
-   * will be marked as canceled and eventually removed.
-   *
-   * <p>A command can not be canceled if it is a part of a command group, you must cancel the
-   * command group instead.
-   *
-   * @throws IllegalUseOfCommandException if this command is a part of a command group
-   */
-  public synchronized void cancel() {
-    if (m_parent != null) {
-      throw new IllegalUseOfCommandException(
-          "Can not manually cancel a command in a command " + "group");
-    }
-    _cancel();
-  }
-
-  /**
-   * This works like cancel(), except that it doesn't throw an exception if it is a part of a
-   * command group. Should only be called by the parent command group.
-   */
-  @SuppressWarnings("MethodName")
-  synchronized void _cancel() {
-    if (isRunning()) {
-      m_canceled = true;
-    }
-  }
-
-  /**
-   * Returns whether or not this has been canceled.
-   *
-   * @return whether or not this has been canceled
-   */
-  public synchronized boolean isCanceled() {
-    return m_canceled;
-  }
-
-  /**
-   * Whether or not this command has completed running.
-   *
-   * @return whether or not this command has completed running.
-   */
-  public synchronized boolean isCompleted() {
-    return m_completed;
-  }
-
-  /**
-   * Returns whether or not this command can be interrupted.
-   *
-   * @return whether or not this command can be interrupted
-   */
-  public synchronized boolean isInterruptible() {
-    return m_interruptible;
-  }
-
-  /**
-   * Sets whether or not this command can be interrupted.
-   *
-   * @param interruptible whether or not this command can be interrupted
-   */
-  protected synchronized void setInterruptible(boolean interruptible) {
-    m_interruptible = interruptible;
-  }
-
-  /**
-   * Checks if the command requires the given {@link Subsystem}.
-   *
-   * @param system the system
-   * @return whether or not the subsystem is required, or false if given null
-   */
-  public synchronized boolean doesRequire(Subsystem system) {
-    return m_requirements.contains(system);
-  }
-
-  /**
-   * Returns the {@link CommandGroup} that this command is a part of. Will return null if this
-   * {@link Command} is not in a group.
-   *
-   * @return the {@link CommandGroup} that this command is a part of (or null if not in group)
-   */
-  public synchronized CommandGroup getGroup() {
-    return m_parent;
-  }
-
-  /**
-   * Sets whether or not this {@link Command} should run when the robot is disabled.
-   *
-   * <p>By default a command will not run when the robot is disabled, and will in fact be canceled.
-   *
-   * @param run whether or not this command should run when the robot is disabled
-   */
-  public void setRunWhenDisabled(boolean run) {
-    m_runWhenDisabled = run;
-  }
-
-  /**
-   * Returns whether or not this {@link Command} will run when the robot is disabled, or if it will
-   * cancel itself.
-   *
-   * @return True if this command will run when the robot is disabled.
-   */
-  public boolean willRunWhenDisabled() {
-    return m_runWhenDisabled;
-  }
-
-  /**
-   * Gets the name of this Command.
-   *
-   * @return Name
-   */
-  public String getName() {
-    return SendableRegistry.getName(this);
-  }
-
-  /**
-   * Sets the name of this Command.
-   *
-   * @param name name
-   */
-  public void setName(String name) {
-    SendableRegistry.setName(this, name);
-  }
-
-  /**
-   * Gets the subsystem name of this Command.
-   *
-   * @return Subsystem name
-   */
-  public String getSubsystem() {
-    return SendableRegistry.getSubsystem(this);
-  }
-
-  /**
-   * Sets the subsystem name of this Command.
-   *
-   * @param subsystem subsystem name
-   */
-  public void setSubsystem(String subsystem) {
-    SendableRegistry.setSubsystem(this, subsystem);
-  }
-
-  /**
-   * The string representation for a {@link Command} is by default its name.
-   *
-   * @return the string representation of this object
-   */
-  @Override
-  public String toString() {
-    return getName();
-  }
-
-  @Override
-  public void initSendable(SendableBuilder builder) {
-    builder.setSmartDashboardType("Command");
-    builder.addStringProperty(".name", this::getName, null);
-    builder.addBooleanProperty(
-        "running",
-        this::isRunning,
-        value -> {
-          if (value) {
-            if (!isRunning()) {
-              start();
-            }
-          } else {
-            if (isRunning()) {
-              cancel();
-            }
-          }
-        });
-    builder.addBooleanProperty(".isParented", this::isParented, null);
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/CommandGroup.java b/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/CommandGroup.java
deleted file mode 100644
index 10f5066..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/CommandGroup.java
+++ /dev/null
@@ -1,410 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-import static java.util.Objects.requireNonNull;
-
-import java.util.Enumeration;
-import java.util.Vector;
-
-/**
- * A {@link CommandGroup} is a list of commands which are executed in sequence.
- *
- * <p>Commands in a {@link CommandGroup} are added using the {@link
- * CommandGroup#addSequential(Command) addSequential(...)} method and are called sequentially.
- * {@link CommandGroup CommandGroups} are themselves {@link Command commands} and can be given to
- * other {@link CommandGroup CommandGroups}.
- *
- * <p>{@link CommandGroup CommandGroups} will carry all of the requirements of their {@link Command
- * subcommands}. Additional requirements can be specified by calling {@link
- * CommandGroup#requires(Subsystem) requires(...)} normally in the constructor.
- *
- * <p>CommandGroups can also execute commands in parallel, simply by adding them using {@link
- * CommandGroup#addParallel(Command) addParallel(...)}.
- *
- * <p>This class is provided by the OldCommands VendorDep
- *
- * @see Command
- * @see Subsystem
- * @see IllegalUseOfCommandException
- */
-public class CommandGroup extends Command {
-  /** The commands in this group (stored in entries). */
-  @SuppressWarnings("PMD.UseArrayListInsteadOfVector")
-  private final Vector<Entry> m_commands = new Vector<>();
-  /*
-   * Intentionally package private
-   */
-  /** The active children in this group (stored in entries). */
-  @SuppressWarnings("PMD.UseArrayListInsteadOfVector")
-  final Vector<Entry> m_children = new Vector<>();
-  /** The current command, -1 signifies that none have been run. */
-  private int m_currentCommandIndex = -1;
-
-  /**
-   * Creates a new {@link CommandGroup CommandGroup}. The name of this command will be set to its
-   * class name.
-   */
-  public CommandGroup() {}
-
-  /**
-   * Creates a new {@link CommandGroup CommandGroup} with the given name.
-   *
-   * @param name the name for this command group
-   * @throws IllegalArgumentException if name is null
-   */
-  public CommandGroup(String name) {
-    super(name);
-  }
-
-  /**
-   * Adds a new {@link Command Command} to the group. The {@link Command Command} will be started
-   * after all the previously added {@link Command Commands}.
-   *
-   * <p>Note that any requirements the given {@link Command Command} has will be added to the group.
-   * For this reason, a {@link Command Command's} requirements can not be changed after being added
-   * to a group.
-   *
-   * <p>It is recommended that this method be called in the constructor.
-   *
-   * @param command The {@link Command Command} to be added
-   * @throws IllegalUseOfCommandException if the group has been started before or been given to
-   *     another group
-   * @throws IllegalArgumentException if command is null
-   */
-  public final synchronized void addSequential(Command command) {
-    validate("Can not add new command to command group");
-    if (command == null) {
-      throw new IllegalArgumentException("Given null command");
-    }
-
-    command.setParent(this);
-
-    m_commands.addElement(new Entry(command, Entry.IN_SEQUENCE));
-    for (Enumeration<?> e = command.getRequirements(); e.hasMoreElements(); ) {
-      requires((Subsystem) e.nextElement());
-    }
-  }
-
-  /**
-   * Adds a new {@link Command Command} to the group with a given timeout. The {@link Command
-   * Command} will be started after all the previously added commands.
-   *
-   * <p>Once the {@link Command Command} is started, it will be run until it finishes or the time
-   * expires, whichever is sooner. Note that the given {@link Command Command} will have no
-   * knowledge that it is on a timer.
-   *
-   * <p>Note that any requirements the given {@link Command Command} has will be added to the group.
-   * For this reason, a {@link Command Command's} requirements can not be changed after being added
-   * to a group.
-   *
-   * <p>It is recommended that this method be called in the constructor.
-   *
-   * @param command The {@link Command Command} to be added
-   * @param timeout The timeout (in seconds)
-   * @throws IllegalUseOfCommandException if the group has been started before or been given to
-   *     another group or if the {@link Command Command} has been started before or been given to
-   *     another group
-   * @throws IllegalArgumentException if command is null or timeout is negative
-   */
-  public final synchronized void addSequential(Command command, double timeout) {
-    validate("Can not add new command to command group");
-    if (command == null) {
-      throw new IllegalArgumentException("Given null command");
-    }
-    if (timeout < 0) {
-      throw new IllegalArgumentException("Can not be given a negative timeout");
-    }
-
-    command.setParent(this);
-
-    m_commands.addElement(new Entry(command, Entry.IN_SEQUENCE, timeout));
-    for (Enumeration<?> e = command.getRequirements(); e.hasMoreElements(); ) {
-      requires((Subsystem) e.nextElement());
-    }
-  }
-
-  /**
-   * Adds a new child {@link Command} to the group. The {@link Command} will be started after all
-   * the previously added {@link Command Commands}.
-   *
-   * <p>Instead of waiting for the child to finish, a {@link CommandGroup} will have it run at the
-   * same time as the subsequent {@link Command Commands}. The child will run until either it
-   * finishes, a new child with conflicting requirements is started, or the main sequence runs a
-   * {@link Command} with conflicting requirements. In the latter two cases, the child will be
-   * canceled even if it says it can't be interrupted.
-   *
-   * <p>Note that any requirements the given {@link Command Command} has will be added to the group.
-   * For this reason, a {@link Command Command's} requirements can not be changed after being added
-   * to a group.
-   *
-   * <p>It is recommended that this method be called in the constructor.
-   *
-   * @param command The command to be added
-   * @throws IllegalUseOfCommandException if the group has been started before or been given to
-   *     another command group
-   * @throws IllegalArgumentException if command is null
-   */
-  public final synchronized void addParallel(Command command) {
-    requireNonNull(command, "Provided command was null");
-    validate("Can not add new command to command group");
-
-    command.setParent(this);
-
-    m_commands.addElement(new Entry(command, Entry.BRANCH_CHILD));
-    for (Enumeration<?> e = command.getRequirements(); e.hasMoreElements(); ) {
-      requires((Subsystem) e.nextElement());
-    }
-  }
-
-  /**
-   * Adds a new child {@link Command} to the group with the given timeout. The {@link Command} will
-   * be started after all the previously added {@link Command Commands}.
-   *
-   * <p>Once the {@link Command Command} is started, it will run until it finishes, is interrupted,
-   * or the time expires, whichever is sooner. Note that the given {@link Command Command} will have
-   * no knowledge that it is on a timer.
-   *
-   * <p>Instead of waiting for the child to finish, a {@link CommandGroup} will have it run at the
-   * same time as the subsequent {@link Command Commands}. The child will run until either it
-   * finishes, the timeout expires, a new child with conflicting requirements is started, or the
-   * main sequence runs a {@link Command} with conflicting requirements. In the latter two cases,
-   * the child will be canceled even if it says it can't be interrupted.
-   *
-   * <p>Note that any requirements the given {@link Command Command} has will be added to the group.
-   * For this reason, a {@link Command Command's} requirements can not be changed after being added
-   * to a group.
-   *
-   * <p>It is recommended that this method be called in the constructor.
-   *
-   * @param command The command to be added
-   * @param timeout The timeout (in seconds)
-   * @throws IllegalUseOfCommandException if the group has been started before or been given to
-   *     another command group
-   * @throws IllegalArgumentException if command is null
-   */
-  public final synchronized void addParallel(Command command, double timeout) {
-    requireNonNull(command, "Provided command was null");
-    if (timeout < 0) {
-      throw new IllegalArgumentException("Can not be given a negative timeout");
-    }
-    validate("Can not add new command to command group");
-
-    command.setParent(this);
-
-    m_commands.addElement(new Entry(command, Entry.BRANCH_CHILD, timeout));
-    for (Enumeration<?> e = command.getRequirements(); e.hasMoreElements(); ) {
-      requires((Subsystem) e.nextElement());
-    }
-  }
-
-  @Override
-  @SuppressWarnings("MethodName")
-  void _initialize() {
-    m_currentCommandIndex = -1;
-  }
-
-  @Override
-  @SuppressWarnings({"MethodName", "PMD.AvoidReassigningLoopVariables"})
-  void _execute() {
-    Entry entry = null;
-    Command cmd = null;
-    boolean firstRun = false;
-    if (m_currentCommandIndex == -1) {
-      firstRun = true;
-      m_currentCommandIndex = 0;
-    }
-
-    while (m_currentCommandIndex < m_commands.size()) {
-      if (cmd != null) {
-        if (entry.isTimedOut()) {
-          cmd._cancel();
-        }
-        if (cmd.run()) {
-          break;
-        } else {
-          cmd.removed();
-          m_currentCommandIndex++;
-          firstRun = true;
-          cmd = null;
-          continue;
-        }
-      }
-
-      entry = m_commands.elementAt(m_currentCommandIndex);
-      cmd = null;
-
-      switch (entry.m_state) {
-        case Entry.IN_SEQUENCE:
-          cmd = entry.m_command;
-          if (firstRun) {
-            cmd.startRunning();
-            cancelConflicts(cmd);
-          }
-          firstRun = false;
-          break;
-        case Entry.BRANCH_PEER:
-          m_currentCommandIndex++;
-          entry.m_command.start();
-          break;
-        case Entry.BRANCH_CHILD:
-          m_currentCommandIndex++;
-          cancelConflicts(entry.m_command);
-          entry.m_command.startRunning();
-          m_children.addElement(entry);
-          break;
-        default:
-          break;
-      }
-    }
-
-    // Run Children
-    for (int i = 0; i < m_children.size(); i++) {
-      entry = m_children.elementAt(i);
-      Command child = entry.m_command;
-      if (entry.isTimedOut()) {
-        child._cancel();
-      }
-      if (!child.run()) {
-        child.removed();
-        m_children.removeElementAt(i--);
-      }
-    }
-  }
-
-  @Override
-  @SuppressWarnings("MethodName")
-  void _end() {
-    // Theoretically, we don't have to check this, but we do if teams override
-    // the isFinished method
-    if (m_currentCommandIndex != -1 && m_currentCommandIndex < m_commands.size()) {
-      Command cmd = m_commands.elementAt(m_currentCommandIndex).m_command;
-      cmd._cancel();
-      cmd.removed();
-    }
-
-    Enumeration<?> children = m_children.elements();
-    while (children.hasMoreElements()) {
-      Command cmd = ((Entry) children.nextElement()).m_command;
-      cmd._cancel();
-      cmd.removed();
-    }
-    m_children.removeAllElements();
-  }
-
-  @Override
-  @SuppressWarnings("MethodName")
-  void _interrupted() {
-    _end();
-  }
-
-  /**
-   * Returns true if all the {@link Command Commands} in this group have been started and have
-   * finished.
-   *
-   * <p>Teams may override this method, although they should probably reference super.isFinished()
-   * if they do.
-   *
-   * @return whether this {@link CommandGroup} is finished
-   */
-  @Override
-  protected boolean isFinished() {
-    return m_currentCommandIndex >= m_commands.size() && m_children.isEmpty();
-  }
-
-  // Can be overwritten by teams
-  @Override
-  protected void initialize() {}
-
-  // Can be overwritten by teams
-  @Override
-  protected void execute() {}
-
-  // Can be overwritten by teams
-  @Override
-  protected void end() {}
-
-  // Can be overwritten by teams
-  @Override
-  protected void interrupted() {}
-
-  /**
-   * Returns whether or not this group is interruptible. A command group will be uninterruptible if
-   * {@link CommandGroup#setInterruptible(boolean) setInterruptible(false)} was called or if it is
-   * currently running an uninterruptible command or child.
-   *
-   * @return whether or not this {@link CommandGroup} is interruptible.
-   */
-  @Override
-  public synchronized boolean isInterruptible() {
-    if (!super.isInterruptible()) {
-      return false;
-    }
-
-    if (m_currentCommandIndex != -1 && m_currentCommandIndex < m_commands.size()) {
-      Command cmd = m_commands.elementAt(m_currentCommandIndex).m_command;
-      if (!cmd.isInterruptible()) {
-        return false;
-      }
-    }
-
-    for (int i = 0; i < m_children.size(); i++) {
-      if (!m_children.elementAt(i).m_command.isInterruptible()) {
-        return false;
-      }
-    }
-
-    return true;
-  }
-
-  @SuppressWarnings("PMD.AvoidReassigningLoopVariables")
-  private void cancelConflicts(Command command) {
-    for (int i = 0; i < m_children.size(); i++) {
-      Command child = m_children.elementAt(i).m_command;
-
-      Enumeration<?> requirements = command.getRequirements();
-
-      while (requirements.hasMoreElements()) {
-        Object requirement = requirements.nextElement();
-        if (child.doesRequire((Subsystem) requirement)) {
-          child._cancel();
-          child.removed();
-          m_children.removeElementAt(i--);
-          break;
-        }
-      }
-    }
-  }
-
-  private static class Entry {
-    private static final int IN_SEQUENCE = 0;
-    private static final int BRANCH_PEER = 1;
-    private static final int BRANCH_CHILD = 2;
-    private final Command m_command;
-    private final int m_state;
-    private final double m_timeout;
-
-    Entry(Command command, int state) {
-      m_command = command;
-      m_state = state;
-      m_timeout = -1;
-    }
-
-    Entry(Command command, int state, double timeout) {
-      m_command = command;
-      m_state = state;
-      m_timeout = timeout;
-    }
-
-    boolean isTimedOut() {
-      if (m_timeout == -1) {
-        return false;
-      } else {
-        double time = m_command.timeSinceInitialized();
-        return time != 0 && time >= m_timeout;
-      }
-    }
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/ConditionalCommand.java b/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/ConditionalCommand.java
deleted file mode 100644
index 79c043d..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/ConditionalCommand.java
+++ /dev/null
@@ -1,163 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-import java.util.Enumeration;
-
-/**
- * A {@link ConditionalCommand} is a {@link Command} that starts one of two commands.
- *
- * <p>A {@link ConditionalCommand} uses m_condition to determine whether it should run m_onTrue or
- * m_onFalse.
- *
- * <p>A {@link ConditionalCommand} adds the proper {@link Command} to the {@link Scheduler} during
- * {@link ConditionalCommand#initialize()} and then {@link ConditionalCommand#isFinished()} will
- * return true once that {@link Command} has finished executing.
- *
- * <p>If no {@link Command} is specified for m_onFalse, the occurrence of that condition will be a
- * no-op.
- *
- * <p>A ConditionalCommand will require the superset of subsystems of the onTrue and onFalse
- * commands.
- *
- * <p>This class is provided by the OldCommands VendorDep
- *
- * @see Command
- * @see Scheduler
- */
-public abstract class ConditionalCommand extends Command {
-  /** The Command to execute if {@link ConditionalCommand#condition()} returns true. */
-  private Command m_onTrue;
-
-  /** The Command to execute if {@link ConditionalCommand#condition()} returns false. */
-  private Command m_onFalse;
-
-  /** Stores command chosen by condition. */
-  private Command m_chosenCommand;
-
-  private void requireAll() {
-    if (m_onTrue != null) {
-      for (Enumeration<?> e = m_onTrue.getRequirements(); e.hasMoreElements(); ) {
-        requires((Subsystem) e.nextElement());
-      }
-    }
-
-    if (m_onFalse != null) {
-      for (Enumeration<?> e = m_onFalse.getRequirements(); e.hasMoreElements(); ) {
-        requires((Subsystem) e.nextElement());
-      }
-    }
-  }
-
-  /**
-   * Creates a new ConditionalCommand with given onTrue and onFalse Commands.
-   *
-   * <p>Users of this constructor should also override condition().
-   *
-   * @param onTrue The Command to execute if {@link ConditionalCommand#condition()} returns true
-   */
-  public ConditionalCommand(Command onTrue) {
-    this(onTrue, null);
-  }
-
-  /**
-   * Creates a new ConditionalCommand with given onTrue and onFalse Commands.
-   *
-   * <p>Users of this constructor should also override condition().
-   *
-   * @param onTrue The Command to execute if {@link ConditionalCommand#condition()} returns true
-   * @param onFalse The Command to execute if {@link ConditionalCommand#condition()} returns false
-   */
-  public ConditionalCommand(Command onTrue, Command onFalse) {
-    m_onTrue = onTrue;
-    m_onFalse = onFalse;
-
-    requireAll();
-  }
-
-  /**
-   * Creates a new ConditionalCommand with given name and onTrue and onFalse Commands.
-   *
-   * <p>Users of this constructor should also override condition().
-   *
-   * @param name the name for this command group
-   * @param onTrue The Command to execute if {@link ConditionalCommand#condition()} returns true
-   */
-  public ConditionalCommand(String name, Command onTrue) {
-    this(name, onTrue, null);
-  }
-
-  /**
-   * Creates a new ConditionalCommand with given name and onTrue and onFalse Commands.
-   *
-   * <p>Users of this constructor should also override condition().
-   *
-   * @param name the name for this command group
-   * @param onTrue The Command to execute if {@link ConditionalCommand#condition()} returns true
-   * @param onFalse The Command to execute if {@link ConditionalCommand#condition()} returns false
-   */
-  public ConditionalCommand(String name, Command onTrue, Command onFalse) {
-    super(name);
-    m_onTrue = onTrue;
-    m_onFalse = onFalse;
-
-    requireAll();
-  }
-
-  /**
-   * The Condition to test to determine which Command to run.
-   *
-   * @return true if m_onTrue should be run or false if m_onFalse should be run.
-   */
-  protected abstract boolean condition();
-
-  /** Calls {@link ConditionalCommand#condition()} and runs the proper command. */
-  @Override
-  protected void _initialize() {
-    if (condition()) {
-      m_chosenCommand = m_onTrue;
-    } else {
-      m_chosenCommand = m_onFalse;
-    }
-
-    if (m_chosenCommand != null) {
-      /*
-       * This is a hack to make canceling the chosen command inside a
-       * CommandGroup work properly
-       */
-      m_chosenCommand.clearRequirements();
-
-      m_chosenCommand.start();
-    }
-    super._initialize();
-  }
-
-  @Override
-  protected synchronized void _cancel() {
-    if (m_chosenCommand != null && m_chosenCommand.isRunning()) {
-      m_chosenCommand.cancel();
-    }
-
-    super._cancel();
-  }
-
-  @Override
-  protected boolean isFinished() {
-    if (m_chosenCommand != null) {
-      return m_chosenCommand.isCompleted();
-    } else {
-      return true;
-    }
-  }
-
-  @Override
-  protected void _interrupted() {
-    if (m_chosenCommand != null && m_chosenCommand.isRunning()) {
-      m_chosenCommand.cancel();
-    }
-
-    super._interrupted();
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/IllegalUseOfCommandException.java b/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/IllegalUseOfCommandException.java
deleted file mode 100644
index 833b4fb..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/IllegalUseOfCommandException.java
+++ /dev/null
@@ -1,32 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-/**
- * This exception will be thrown if a command is used illegally. There are several ways for this to
- * happen.
- *
- * <p>Basically, a command becomes "locked" after it is first started or added to a command group.
- *
- * <p>This exception should be thrown if (after a command has been locked) its requirements change,
- * it is put into multiple command groups, it is started from outside its command group, or it adds
- * a new child.
- *
- * <p>This class is provided by the OldCommands VendorDep
- */
-@SuppressWarnings("serial")
-public class IllegalUseOfCommandException extends RuntimeException {
-  /** Instantiates an {@link IllegalUseOfCommandException}. */
-  public IllegalUseOfCommandException() {}
-
-  /**
-   * Instantiates an {@link IllegalUseOfCommandException} with the given message.
-   *
-   * @param message the message
-   */
-  public IllegalUseOfCommandException(String message) {
-    super(message);
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/InstantCommand.java b/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/InstantCommand.java
deleted file mode 100644
index 42278f6..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/InstantCommand.java
+++ /dev/null
@@ -1,108 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-/**
- * This command will execute once, then finish immediately afterward.
- *
- * <p>Subclassing {@link InstantCommand} is shorthand for returning true from {@link Command
- * isFinished}.
- *
- * <p>This class is provided by the OldCommands VendorDep
- */
-public class InstantCommand extends Command {
-  private Runnable m_func;
-
-  public InstantCommand() {}
-
-  /**
-   * Creates a new {@link InstantCommand InstantCommand} with the given name.
-   *
-   * @param name the name for this command
-   */
-  public InstantCommand(String name) {
-    super(name);
-  }
-
-  /**
-   * Creates a new {@link InstantCommand InstantCommand} with the given requirement.
-   *
-   * @param subsystem the subsystem this command requires
-   */
-  public InstantCommand(Subsystem subsystem) {
-    super(subsystem);
-  }
-
-  /**
-   * Creates a new {@link InstantCommand InstantCommand} with the given name and requirement.
-   *
-   * @param name the name for this command
-   * @param subsystem the subsystem this command requires
-   */
-  public InstantCommand(String name, Subsystem subsystem) {
-    super(name, subsystem);
-  }
-
-  /**
-   * Creates a new {@link InstantCommand InstantCommand}.
-   *
-   * @param func the function to run when {@link Command#initialize() initialize()} is run
-   */
-  public InstantCommand(Runnable func) {
-    m_func = func;
-  }
-
-  /**
-   * Creates a new {@link InstantCommand InstantCommand}.
-   *
-   * @param name the name for this command
-   * @param func the function to run when {@link Command#initialize() initialize()} is run
-   */
-  public InstantCommand(String name, Runnable func) {
-    super(name);
-    m_func = func;
-  }
-
-  /**
-   * Creates a new {@link InstantCommand InstantCommand}.
-   *
-   * @param requirement the subsystem this command requires
-   * @param func the function to run when {@link Command#initialize() initialize()} is run
-   */
-  public InstantCommand(Subsystem requirement, Runnable func) {
-    super(requirement);
-    m_func = func;
-  }
-
-  /**
-   * Creates a new {@link InstantCommand InstantCommand}.
-   *
-   * @param name the name for this command
-   * @param requirement the subsystem this command requires
-   * @param func the function to run when {@link Command#initialize() initialize()} is run
-   */
-  public InstantCommand(String name, Subsystem requirement, Runnable func) {
-    super(name, requirement);
-    m_func = func;
-  }
-
-  @Override
-  protected boolean isFinished() {
-    return true;
-  }
-
-  /**
-   * Trigger the stored function.
-   *
-   * <p>Called just before this Command runs the first time.
-   */
-  @Override
-  protected void _initialize() {
-    super._initialize();
-    if (m_func != null) {
-      m_func.run();
-    }
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/LinkedListElement.java b/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/LinkedListElement.java
deleted file mode 100644
index b657ba7..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/LinkedListElement.java
+++ /dev/null
@@ -1,62 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-/**
- * An element that is in a LinkedList.
- *
- * <p>This class is provided by the OldCommands VendorDep
- */
-class LinkedListElement {
-  private LinkedListElement m_next;
-  private LinkedListElement m_previous;
-  private Command m_data;
-
-  public void setData(Command newData) {
-    m_data = newData;
-  }
-
-  public Command getData() {
-    return m_data;
-  }
-
-  public LinkedListElement getNext() {
-    return m_next;
-  }
-
-  public LinkedListElement getPrevious() {
-    return m_previous;
-  }
-
-  public void add(LinkedListElement listElement) {
-    if (m_next == null) {
-      m_next = listElement;
-      m_next.m_previous = this;
-    } else {
-      m_next.m_previous = listElement;
-      listElement.m_next = m_next;
-      listElement.m_previous = this;
-      m_next = listElement;
-    }
-  }
-
-  @SuppressWarnings("PMD.EmptyIfStmt")
-  public LinkedListElement remove() {
-    if (m_previous == null && m_next == null) {
-      // no-op
-    } else if (m_next == null) {
-      m_previous.m_next = null;
-    } else if (m_previous == null) {
-      m_next.m_previous = null;
-    } else {
-      m_next.m_previous = m_previous;
-      m_previous.m_next = m_next;
-    }
-    LinkedListElement returnNext = m_next;
-    m_next = null;
-    m_previous = null;
-    return returnNext;
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/PIDCommand.java b/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/PIDCommand.java
deleted file mode 100644
index 1f63267..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/PIDCommand.java
+++ /dev/null
@@ -1,268 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-import edu.wpi.first.util.sendable.SendableBuilder;
-import edu.wpi.first.wpilibj.PIDController;
-import edu.wpi.first.wpilibj.PIDOutput;
-import edu.wpi.first.wpilibj.PIDSource;
-import edu.wpi.first.wpilibj.PIDSourceType;
-
-/**
- * This class defines a {@link Command} which interacts heavily with a PID loop.
- *
- * <p>It provides some convenience methods to run an internal {@link PIDController} . It will also
- * start and stop said {@link PIDController} when the {@link PIDCommand} is first initialized and
- * ended/interrupted.
- *
- * <p>This class is provided by the OldCommands VendorDep
- */
-public abstract class PIDCommand extends Command {
-  /** The internal {@link PIDController}. */
-  private final PIDController m_controller;
-  /** An output which calls {@link PIDCommand#usePIDOutput(double)}. */
-  private final PIDOutput m_output = this::usePIDOutput;
-  /** A source which calls {@link PIDCommand#returnPIDInput()}. */
-  private final PIDSource m_source =
-      new PIDSource() {
-        @Override
-        public void setPIDSourceType(PIDSourceType pidSource) {}
-
-        @Override
-        public PIDSourceType getPIDSourceType() {
-          return PIDSourceType.kDisplacement;
-        }
-
-        @Override
-        public double pidGet() {
-          return returnPIDInput();
-        }
-      };
-
-  /**
-   * Instantiates a {@link PIDCommand} that will use the given p, i and d values.
-   *
-   * @param name the name of the command
-   * @param p the proportional value
-   * @param i the integral value
-   * @param d the derivative value
-   */
-  public PIDCommand(String name, double p, double i, double d) {
-    super(name);
-    m_controller = new PIDController(p, i, d, m_source, m_output);
-  }
-
-  /**
-   * Instantiates a {@link PIDCommand} that will use the given p, i and d values. It will also space
-   * the time between PID loop calculations to be equal to the given period.
-   *
-   * @param name the name
-   * @param p the proportional value
-   * @param i the integral value
-   * @param d the derivative value
-   * @param period the time (in seconds) between calculations
-   */
-  public PIDCommand(String name, double p, double i, double d, double period) {
-    super(name);
-    m_controller = new PIDController(p, i, d, m_source, m_output, period);
-  }
-
-  /**
-   * Instantiates a {@link PIDCommand} that will use the given p, i and d values. It will use the
-   * class name as its name.
-   *
-   * @param p the proportional value
-   * @param i the integral value
-   * @param d the derivative value
-   */
-  public PIDCommand(double p, double i, double d) {
-    m_controller = new PIDController(p, i, d, m_source, m_output);
-  }
-
-  /**
-   * Instantiates a {@link PIDCommand} that will use the given p, i and d values. It will use the
-   * class name as its name. It will also space the time between PID loop calculations to be equal
-   * to the given period.
-   *
-   * @param p the proportional value
-   * @param i the integral value
-   * @param d the derivative value
-   * @param period the time (in seconds) between calculations
-   */
-  public PIDCommand(double p, double i, double d, double period) {
-    m_controller = new PIDController(p, i, d, m_source, m_output, period);
-  }
-
-  /**
-   * Instantiates a {@link PIDCommand} that will use the given p, i and d values.
-   *
-   * @param name the name of the command
-   * @param p the proportional value
-   * @param i the integral value
-   * @param d the derivative value
-   * @param subsystem the subsystem that this command requires
-   */
-  public PIDCommand(String name, double p, double i, double d, Subsystem subsystem) {
-    super(name, subsystem);
-    m_controller = new PIDController(p, i, d, m_source, m_output);
-  }
-
-  /**
-   * Instantiates a {@link PIDCommand} that will use the given p, i and d values. It will also space
-   * the time between PID loop calculations to be equal to the given period.
-   *
-   * @param name the name
-   * @param p the proportional value
-   * @param i the integral value
-   * @param d the derivative value
-   * @param period the time (in seconds) between calculations
-   * @param subsystem the subsystem that this command requires
-   */
-  public PIDCommand(String name, double p, double i, double d, double period, Subsystem subsystem) {
-    super(name, subsystem);
-    m_controller = new PIDController(p, i, d, m_source, m_output, period);
-  }
-
-  /**
-   * Instantiates a {@link PIDCommand} that will use the given p, i and d values. It will use the
-   * class name as its name.
-   *
-   * @param p the proportional value
-   * @param i the integral value
-   * @param d the derivative value
-   * @param subsystem the subsystem that this command requires
-   */
-  public PIDCommand(double p, double i, double d, Subsystem subsystem) {
-    super(subsystem);
-    m_controller = new PIDController(p, i, d, m_source, m_output);
-  }
-
-  /**
-   * Instantiates a {@link PIDCommand} that will use the given p, i and d values. It will use the
-   * class name as its name. It will also space the time between PID loop calculations to be equal
-   * to the given period.
-   *
-   * @param p the proportional value
-   * @param i the integral value
-   * @param d the derivative value
-   * @param period the time (in seconds) between calculations
-   * @param subsystem the subsystem that this command requires
-   */
-  public PIDCommand(double p, double i, double d, double period, Subsystem subsystem) {
-    super(subsystem);
-    m_controller = new PIDController(p, i, d, m_source, m_output, period);
-  }
-
-  /**
-   * Returns the {@link PIDController} used by this {@link PIDCommand}. Use this if you would like
-   * to fine tune the pid loop.
-   *
-   * @return the {@link PIDController} used by this {@link PIDCommand}
-   */
-  protected PIDController getPIDController() {
-    return m_controller;
-  }
-
-  @Override
-  @SuppressWarnings("MethodName")
-  void _initialize() {
-    m_controller.enable();
-  }
-
-  @Override
-  @SuppressWarnings("MethodName")
-  void _end() {
-    m_controller.disable();
-  }
-
-  @Override
-  @SuppressWarnings("MethodName")
-  void _interrupted() {
-    _end();
-  }
-
-  /**
-   * Adds the given value to the setpoint. If {@link PIDCommand#setInputRange(double, double)
-   * setInputRange(...)} was used, then the bounds will still be honored by this method.
-   *
-   * @param deltaSetpoint the change in the setpoint
-   */
-  public void setSetpointRelative(double deltaSetpoint) {
-    setSetpoint(getSetpoint() + deltaSetpoint);
-  }
-
-  /**
-   * Sets the setpoint to the given value. If {@link PIDCommand#setInputRange(double, double)
-   * setInputRange(...)} was called, then the given setpoint will be trimmed to fit within the
-   * range.
-   *
-   * @param setpoint the new setpoint
-   */
-  protected void setSetpoint(double setpoint) {
-    m_controller.setSetpoint(setpoint);
-  }
-
-  /**
-   * Returns the setpoint.
-   *
-   * @return the setpoint
-   */
-  protected double getSetpoint() {
-    return m_controller.getSetpoint();
-  }
-
-  /**
-   * Returns the current position.
-   *
-   * @return the current position
-   */
-  protected double getPosition() {
-    return returnPIDInput();
-  }
-
-  /**
-   * Sets the maximum and minimum values expected from the input and setpoint.
-   *
-   * @param minimumInput the minimum value expected from the input and setpoint
-   * @param maximumInput the maximum value expected from the input and setpoint
-   */
-  protected void setInputRange(double minimumInput, double maximumInput) {
-    m_controller.setInputRange(minimumInput, maximumInput);
-  }
-
-  /**
-   * Returns the input for the pid loop.
-   *
-   * <p>It returns the input for the pid loop, so if this command was based off of a gyro, then it
-   * should return the angle of the gyro.
-   *
-   * <p>All subclasses of {@link PIDCommand} must override this method.
-   *
-   * <p>This method will be called in a different thread then the {@link Scheduler} thread.
-   *
-   * @return the value the pid loop should use as input
-   */
-  protected abstract double returnPIDInput();
-
-  /**
-   * Uses the value that the pid loop calculated. The calculated value is the "output" parameter.
-   * This method is a good time to set motor values, maybe something along the lines of <code>
-   * driveline.tankDrive(output, -output)</code>
-   *
-   * <p>All subclasses of {@link PIDCommand} must override this method.
-   *
-   * <p>This method will be called in a different thread then the {@link Scheduler} thread.
-   *
-   * @param output the value the pid loop calculated
-   */
-  protected abstract void usePIDOutput(double output);
-
-  @Override
-  public void initSendable(SendableBuilder builder) {
-    m_controller.initSendable(builder);
-    super.initSendable(builder);
-    builder.setSmartDashboardType("PIDCommand");
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/PIDSubsystem.java b/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/PIDSubsystem.java
deleted file mode 100644
index 2fa18f1..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/PIDSubsystem.java
+++ /dev/null
@@ -1,266 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-import edu.wpi.first.wpilibj.PIDController;
-import edu.wpi.first.wpilibj.PIDOutput;
-import edu.wpi.first.wpilibj.PIDSource;
-import edu.wpi.first.wpilibj.PIDSourceType;
-
-/**
- * This class is designed to handle the case where there is a {@link Subsystem} which uses a single
- * {@link PIDController} almost constantly (for instance, an elevator which attempts to stay at a
- * constant height).
- *
- * <p>It provides some convenience methods to run an internal {@link PIDController} . It also allows
- * access to the internal {@link PIDController} in order to give total control to the programmer.
- *
- * <p>This class is provided by the OldCommands VendorDep
- */
-public abstract class PIDSubsystem extends Subsystem {
-  /** The internal {@link PIDController}. */
-  private final PIDController m_controller;
-  /** An output which calls {@link PIDCommand#usePIDOutput(double)}. */
-  private final PIDOutput m_output = this::usePIDOutput;
-
-  /** A source which calls {@link PIDCommand#returnPIDInput()}. */
-  private final PIDSource m_source =
-      new PIDSource() {
-        @Override
-        public void setPIDSourceType(PIDSourceType pidSource) {}
-
-        @Override
-        public PIDSourceType getPIDSourceType() {
-          return PIDSourceType.kDisplacement;
-        }
-
-        @Override
-        public double pidGet() {
-          return returnPIDInput();
-        }
-      };
-
-  /**
-   * Instantiates a {@link PIDSubsystem} that will use the given p, i and d values.
-   *
-   * @param name the name
-   * @param p the proportional value
-   * @param i the integral value
-   * @param d the derivative value
-   */
-  public PIDSubsystem(String name, double p, double i, double d) {
-    super(name);
-    m_controller = new PIDController(p, i, d, m_source, m_output);
-    addChild("PIDController", m_controller);
-  }
-
-  /**
-   * Instantiates a {@link PIDSubsystem} that will use the given p, i, d, and f values.
-   *
-   * @param name the name
-   * @param p the proportional value
-   * @param i the integral value
-   * @param d the derivative value
-   * @param f the feed forward value
-   */
-  public PIDSubsystem(String name, double p, double i, double d, double f) {
-    super(name);
-    m_controller = new PIDController(p, i, d, f, m_source, m_output);
-    addChild("PIDController", m_controller);
-  }
-
-  /**
-   * Instantiates a {@link PIDSubsystem} that will use the given p, i, d, and f values. It will also
-   * space the time between PID loop calculations to be equal to the given period.
-   *
-   * @param name the name
-   * @param p the proportional value
-   * @param i the integral value
-   * @param d the derivative value
-   * @param f the feed forward value
-   * @param period the time (in seconds) between calculations
-   */
-  public PIDSubsystem(String name, double p, double i, double d, double f, double period) {
-    super(name);
-    m_controller = new PIDController(p, i, d, f, m_source, m_output, period);
-    addChild("PIDController", m_controller);
-  }
-
-  /**
-   * Instantiates a {@link PIDSubsystem} that will use the given p, i and d values. It will use the
-   * class name as its name.
-   *
-   * @param p the proportional value
-   * @param i the integral value
-   * @param d the derivative value
-   */
-  public PIDSubsystem(double p, double i, double d) {
-    m_controller = new PIDController(p, i, d, m_source, m_output);
-    addChild("PIDController", m_controller);
-  }
-
-  /**
-   * Instantiates a {@link PIDSubsystem} that will use the given p, i, d, and f values. It will use
-   * the class name as its name. It will also space the time between PID loop calculations to be
-   * equal to the given period.
-   *
-   * @param p the proportional value
-   * @param i the integral value
-   * @param d the derivative value
-   * @param f the feed forward coefficient
-   * @param period the time (in seconds) between calculations
-   */
-  public PIDSubsystem(double p, double i, double d, double f, double period) {
-    m_controller = new PIDController(p, i, d, f, m_source, m_output, period);
-    addChild("PIDController", m_controller);
-  }
-
-  /**
-   * Instantiates a {@link PIDSubsystem} that will use the given p, i and d values. It will use the
-   * class name as its name. It will also space the time between PID loop calculations to be equal
-   * to the given period.
-   *
-   * @param p the proportional value
-   * @param i the integral value
-   * @param d the derivative value
-   * @param period the time (in seconds) between calculations
-   */
-  public PIDSubsystem(double p, double i, double d, double period) {
-    m_controller = new PIDController(p, i, d, m_source, m_output, period);
-    addChild("PIDController", m_controller);
-  }
-
-  /**
-   * Returns the {@link PIDController} used by this {@link PIDSubsystem}. Use this if you would like
-   * to fine tune the pid loop.
-   *
-   * @return the {@link PIDController} used by this {@link PIDSubsystem}
-   */
-  public PIDController getPIDController() {
-    return m_controller;
-  }
-
-  /**
-   * Adds the given value to the setpoint. If {@link PIDSubsystem#setInputRange(double, double)
-   * setInputRange(...)} was used, then the bounds will still be honored by this method.
-   *
-   * @param deltaSetpoint the change in the setpoint
-   */
-  public void setSetpointRelative(double deltaSetpoint) {
-    setSetpoint(getPosition() + deltaSetpoint);
-  }
-
-  /**
-   * Sets the setpoint to the given value. If {@link PIDSubsystem#setInputRange(double, double)
-   * setInputRange(...)} was called, then the given setpoint will be trimmed to fit within the
-   * range.
-   *
-   * @param setpoint the new setpoint
-   */
-  public void setSetpoint(double setpoint) {
-    m_controller.setSetpoint(setpoint);
-  }
-
-  /**
-   * Returns the setpoint.
-   *
-   * @return the setpoint
-   */
-  public double getSetpoint() {
-    return m_controller.getSetpoint();
-  }
-
-  /**
-   * Returns the current position.
-   *
-   * @return the current position
-   */
-  public double getPosition() {
-    return returnPIDInput();
-  }
-
-  /**
-   * Sets the maximum and minimum values expected from the input.
-   *
-   * @param minimumInput the minimum value expected from the input
-   * @param maximumInput the maximum value expected from the output
-   */
-  public void setInputRange(double minimumInput, double maximumInput) {
-    m_controller.setInputRange(minimumInput, maximumInput);
-  }
-
-  /**
-   * Sets the maximum and minimum values to write.
-   *
-   * @param minimumOutput the minimum value to write to the output
-   * @param maximumOutput the maximum value to write to the output
-   */
-  public void setOutputRange(double minimumOutput, double maximumOutput) {
-    m_controller.setOutputRange(minimumOutput, maximumOutput);
-  }
-
-  /**
-   * Set the absolute error which is considered tolerable for use with OnTarget. The value is in the
-   * same range as the PIDInput values.
-   *
-   * @param t the absolute tolerance
-   */
-  public void setAbsoluteTolerance(double t) {
-    m_controller.setAbsoluteTolerance(t);
-  }
-
-  /**
-   * Set the percentage error which is considered tolerable for use with OnTarget. (Value of 15.0 ==
-   * 15 percent).
-   *
-   * @param p the percent tolerance
-   */
-  public void setPercentTolerance(double p) {
-    m_controller.setPercentTolerance(p);
-  }
-
-  /**
-   * Return true if the error is within the percentage of the total input range, determined by
-   * setTolerance. This assumes that the maximum and minimum input were set using setInput.
-   *
-   * @return true if the error is less than the tolerance
-   */
-  public boolean onTarget() {
-    return m_controller.onTarget();
-  }
-
-  /**
-   * Returns the input for the pid loop.
-   *
-   * <p>It returns the input for the pid loop, so if this Subsystem was based off of a gyro, then it
-   * should return the angle of the gyro.
-   *
-   * <p>All subclasses of {@link PIDSubsystem} must override this method.
-   *
-   * @return the value the pid loop should use as input
-   */
-  protected abstract double returnPIDInput();
-
-  /**
-   * Uses the value that the pid loop calculated. The calculated value is the "output" parameter.
-   * This method is a good time to set motor values, maybe something along the lines of <code>
-   * driveline.tankDrive(output, -output)</code>.
-   *
-   * <p>All subclasses of {@link PIDSubsystem} must override this method.
-   *
-   * @param output the value the pid loop calculated
-   */
-  protected abstract void usePIDOutput(double output);
-
-  /** Enables the internal {@link PIDController}. */
-  public void enable() {
-    m_controller.enable();
-  }
-
-  /** Disables the internal {@link PIDController}. */
-  public void disable() {
-    m_controller.disable();
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/PrintCommand.java b/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/PrintCommand.java
deleted file mode 100644
index d8cbd9d..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/PrintCommand.java
+++ /dev/null
@@ -1,32 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-/**
- * A {@link PrintCommand} is a command which prints out a string when it is initialized, and then
- * immediately finishes. It is useful if you want a {@link CommandGroup} to print out a string when
- * it reaches a certain point.
- *
- * <p>This class is provided by the OldCommands VendorDep
- */
-public class PrintCommand extends InstantCommand {
-  /** The message to print out. */
-  private final String m_message;
-
-  /**
-   * Instantiates a {@link PrintCommand} which will print the given message when it is run.
-   *
-   * @param message the message to print
-   */
-  public PrintCommand(String message) {
-    super("Print(\"" + message + "\"");
-    m_message = message;
-  }
-
-  @Override
-  protected void initialize() {
-    System.out.println(m_message);
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/Scheduler.java b/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/Scheduler.java
deleted file mode 100644
index 351ae99..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/Scheduler.java
+++ /dev/null
@@ -1,347 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-import edu.wpi.first.hal.FRCNetComm.tInstances;
-import edu.wpi.first.hal.FRCNetComm.tResourceType;
-import edu.wpi.first.hal.HAL;
-import edu.wpi.first.networktables.NTSendable;
-import edu.wpi.first.networktables.NTSendableBuilder;
-import edu.wpi.first.networktables.NetworkTableEntry;
-import edu.wpi.first.util.sendable.SendableRegistry;
-import edu.wpi.first.wpilibj.buttons.Trigger.ButtonScheduler;
-import edu.wpi.first.wpilibj.livewindow.LiveWindow;
-import java.util.Enumeration;
-import java.util.Hashtable;
-import java.util.Map;
-import java.util.Vector;
-
-/**
- * The {@link Scheduler} is a singleton which holds the top-level running commands. It is in charge
- * of both calling the command's {@link Command#run() run()} method and to make sure that there are
- * no two commands with conflicting requirements running.
- *
- * <p>It is fine if teams wish to take control of the {@link Scheduler} themselves, all that needs
- * to be done is to call {@link Scheduler#getInstance() Scheduler.getInstance()}.{@link
- * Scheduler#run() run()} often to have {@link Command Commands} function correctly. However, this
- * is already done for you if you use the CommandBased Robot template.
- *
- * <p>This class is provided by the OldCommands VendorDep
- *
- * @see Command
- */
-public final class Scheduler implements NTSendable, AutoCloseable {
-  /** The Singleton Instance. */
-  private static Scheduler instance;
-
-  /**
-   * Returns the {@link Scheduler}, creating it if one does not exist.
-   *
-   * @return the {@link Scheduler}
-   */
-  public static synchronized Scheduler getInstance() {
-    if (instance == null) {
-      instance = new Scheduler();
-    }
-    return instance;
-  }
-
-  /** A hashtable of active {@link Command Commands} to their {@link LinkedListElement}. */
-  private final Map<Command, LinkedListElement> m_commandTable = new Hashtable<>();
-  /** The {@link Set} of all {@link Subsystem Subsystems}. */
-  private final Set m_subsystems = new Set();
-  /** The first {@link Command} in the list. */
-  private LinkedListElement m_firstCommand;
-  /** The last {@link Command} in the list. */
-  private LinkedListElement m_lastCommand;
-  /** Whether or not we are currently adding a command. */
-  private boolean m_adding;
-  /** Whether or not we are currently disabled. */
-  private boolean m_disabled;
-  /** A list of all {@link Command Commands} which need to be added. */
-  @SuppressWarnings("PMD.UseArrayListInsteadOfVector")
-  private final Vector<Command> m_additions = new Vector<>();
-  /**
-   * A list of all {@link edu.wpi.first.wpilibj.buttons.Trigger.ButtonScheduler Buttons}. It is
-   * created lazily.
-   */
-  private Vector<ButtonScheduler> m_buttons;
-
-  private boolean m_runningCommandsChanged;
-
-  /** Instantiates a {@link Scheduler}. */
-  private Scheduler() {
-    HAL.report(tResourceType.kResourceType_Command, tInstances.kCommand_Scheduler);
-    SendableRegistry.addLW(this, "Scheduler");
-    LiveWindow.setEnabledListener(
-        () -> {
-          disable();
-          removeAll();
-        });
-    LiveWindow.setDisabledListener(
-        () -> {
-          enable();
-        });
-  }
-
-  @Override
-  public void close() {
-    SendableRegistry.remove(this);
-    LiveWindow.setEnabledListener(null);
-    LiveWindow.setDisabledListener(null);
-  }
-
-  /**
-   * Adds the command to the {@link Scheduler}. This will not add the {@link Command} immediately,
-   * but will instead wait for the proper time in the {@link Scheduler#run()} loop before doing so.
-   * The command returns immediately and does nothing if given null.
-   *
-   * <p>Adding a {@link Command} to the {@link Scheduler} involves the {@link Scheduler} removing
-   * any {@link Command} which has shared requirements.
-   *
-   * @param command the command to add
-   */
-  public void add(Command command) {
-    if (command != null) {
-      m_additions.addElement(command);
-    }
-  }
-
-  /**
-   * Adds a button to the {@link Scheduler}. The {@link Scheduler} will poll the button during its
-   * {@link Scheduler#run()}.
-   *
-   * @param button the button to add
-   */
-  @SuppressWarnings("PMD.UseArrayListInsteadOfVector")
-  public void addButton(ButtonScheduler button) {
-    if (m_buttons == null) {
-      m_buttons = new Vector<>();
-    }
-    m_buttons.addElement(button);
-  }
-
-  /**
-   * Adds a command immediately to the {@link Scheduler}. This should only be called in the {@link
-   * Scheduler#run()} loop. Any command with conflicting requirements will be removed, unless it is
-   * uninterruptible. Giving <code>null</code> does nothing.
-   *
-   * @param command the {@link Command} to add
-   */
-  @SuppressWarnings("MethodName")
-  private void _add(Command command) {
-    if (command == null) {
-      return;
-    }
-
-    // Check to make sure no adding during adding
-    if (m_adding) {
-      System.err.println("WARNING: Can not start command from cancel method.  Ignoring:" + command);
-      return;
-    }
-
-    // Only add if not already in
-    if (!m_commandTable.containsKey(command)) {
-      // Check that the requirements can be had
-      Enumeration<?> requirements = command.getRequirements();
-      while (requirements.hasMoreElements()) {
-        Subsystem lock = (Subsystem) requirements.nextElement();
-        if (lock.getCurrentCommand() != null && !lock.getCurrentCommand().isInterruptible()) {
-          return;
-        }
-      }
-
-      // Give it the requirements
-      m_adding = true;
-      requirements = command.getRequirements();
-      while (requirements.hasMoreElements()) {
-        Subsystem lock = (Subsystem) requirements.nextElement();
-        if (lock.getCurrentCommand() != null) {
-          lock.getCurrentCommand().cancel();
-          remove(lock.getCurrentCommand());
-        }
-        lock.setCurrentCommand(command);
-      }
-      m_adding = false;
-
-      // Add it to the list
-      LinkedListElement element = new LinkedListElement();
-      element.setData(command);
-      if (m_firstCommand == null) {
-        m_firstCommand = m_lastCommand = element;
-      } else {
-        m_lastCommand.add(element);
-        m_lastCommand = element;
-      }
-      m_commandTable.put(command, element);
-
-      m_runningCommandsChanged = true;
-
-      command.startRunning();
-    }
-  }
-
-  /**
-   * Runs a single iteration of the loop. This method should be called often in order to have a
-   * functioning {@link Command} system. The loop has five stages:
-   *
-   * <ol>
-   *   <li>Poll the Buttons
-   *   <li>Execute/Remove the Commands
-   *   <li>Send values to SmartDashboard
-   *   <li>Add Commands
-   *   <li>Add Defaults
-   * </ol>
-   */
-  public void run() {
-    m_runningCommandsChanged = false;
-
-    if (m_disabled) {
-      return;
-    } // Don't run when m_disabled
-
-    // Get button input (going backwards preserves button priority)
-    if (m_buttons != null) {
-      for (int i = m_buttons.size() - 1; i >= 0; i--) {
-        m_buttons.elementAt(i).execute();
-      }
-    }
-
-    // Call every subsystem's periodic method
-    Enumeration<?> subsystems = m_subsystems.getElements();
-    while (subsystems.hasMoreElements()) {
-      ((Subsystem) subsystems.nextElement()).periodic();
-    }
-
-    // Loop through the commands
-    LinkedListElement element = m_firstCommand;
-    while (element != null) {
-      Command command = element.getData();
-      element = element.getNext();
-      if (!command.run()) {
-        remove(command);
-        m_runningCommandsChanged = true;
-      }
-    }
-
-    // Add the new things
-    for (int i = 0; i < m_additions.size(); i++) {
-      _add(m_additions.elementAt(i));
-    }
-    m_additions.removeAllElements();
-
-    // Add in the defaults
-    Enumeration<?> locks = m_subsystems.getElements();
-    while (locks.hasMoreElements()) {
-      Subsystem lock = (Subsystem) locks.nextElement();
-      if (lock.getCurrentCommand() == null) {
-        _add(lock.getDefaultCommand());
-      }
-      lock.confirmCommand();
-    }
-  }
-
-  /**
-   * Registers a {@link Subsystem} to this {@link Scheduler}, so that the {@link Scheduler} might
-   * know if a default {@link Command} needs to be run. All {@link Subsystem Subsystems} should call
-   * this.
-   *
-   * @param system the system
-   */
-  void registerSubsystem(Subsystem system) {
-    if (system != null) {
-      m_subsystems.add(system);
-    }
-  }
-
-  /**
-   * Removes the {@link Command} from the {@link Scheduler}.
-   *
-   * @param command the command to remove
-   */
-  void remove(Command command) {
-    if (command == null || !m_commandTable.containsKey(command)) {
-      return;
-    }
-    LinkedListElement element = m_commandTable.get(command);
-    m_commandTable.remove(command);
-
-    if (element.equals(m_lastCommand)) {
-      m_lastCommand = element.getPrevious();
-    }
-    if (element.equals(m_firstCommand)) {
-      m_firstCommand = element.getNext();
-    }
-    element.remove();
-
-    Enumeration<?> requirements = command.getRequirements();
-    while (requirements.hasMoreElements()) {
-      ((Subsystem) requirements.nextElement()).setCurrentCommand(null);
-    }
-
-    command.removed();
-  }
-
-  /** Removes all commands. */
-  public void removeAll() {
-    // TODO: Confirm that this works with "uninteruptible" commands
-    while (m_firstCommand != null) {
-      remove(m_firstCommand.getData());
-    }
-  }
-
-  /** Disable the command scheduler. */
-  public void disable() {
-    m_disabled = true;
-  }
-
-  /** Enable the command scheduler. */
-  public void enable() {
-    m_disabled = false;
-  }
-
-  @Override
-  public void initSendable(NTSendableBuilder builder) {
-    builder.setSmartDashboardType("Scheduler");
-    final NetworkTableEntry namesEntry = builder.getEntry("Names");
-    final NetworkTableEntry idsEntry = builder.getEntry("Ids");
-    final NetworkTableEntry cancelEntry = builder.getEntry("Cancel");
-    builder.setUpdateTable(
-        () -> {
-          if (namesEntry != null && idsEntry != null && cancelEntry != null) {
-            // Get the commands to cancel
-            double[] toCancel = cancelEntry.getDoubleArray(new double[0]);
-            if (toCancel.length > 0) {
-              for (LinkedListElement e = m_firstCommand; e != null; e = e.getNext()) {
-                for (double d : toCancel) {
-                  if (e.getData().hashCode() == d) {
-                    e.getData().cancel();
-                  }
-                }
-              }
-              cancelEntry.setDoubleArray(new double[0]);
-            }
-
-            if (m_runningCommandsChanged) {
-              // Set the the running commands
-              int number = 0;
-              for (LinkedListElement e = m_firstCommand; e != null; e = e.getNext()) {
-                number++;
-              }
-              String[] commands = new String[number];
-              double[] ids = new double[number];
-              number = 0;
-              for (LinkedListElement e = m_firstCommand; e != null; e = e.getNext()) {
-                commands[number] = e.getData().getName();
-                ids[number] = e.getData().hashCode();
-                number++;
-              }
-              namesEntry.setStringArray(commands);
-              idsEntry.setDoubleArray(ids);
-            }
-          }
-        });
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/Set.java b/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/Set.java
deleted file mode 100644
index 91180eb..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/Set.java
+++ /dev/null
@@ -1,46 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-import java.util.Enumeration;
-import java.util.Vector;
-
-@SuppressWarnings("all")
-/**
- * A set.
- *
- * <p>This class is provided by the OldCommands VendorDep
- */
-class Set {
-  private Vector m_set = new Vector();
-
-  public Set() {}
-
-  public void add(Object o) {
-    if (m_set.contains(o)) {
-      return;
-    }
-    m_set.addElement(o);
-  }
-
-  public void add(Set s) {
-    Enumeration stuff = s.getElements();
-    for (Enumeration e = stuff; e.hasMoreElements(); ) {
-      add(e.nextElement());
-    }
-  }
-
-  public void clear() {
-    m_set.clear();
-  }
-
-  public boolean contains(Object o) {
-    return m_set.contains(o);
-  }
-
-  public Enumeration getElements() {
-    return m_set.elements();
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/StartCommand.java b/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/StartCommand.java
deleted file mode 100644
index ba6cec4..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/StartCommand.java
+++ /dev/null
@@ -1,32 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-/**
- * A {@link StartCommand} will call the {@link Command#start() start()} method of another command
- * when it is initialized and will finish immediately.
- *
- * <p>This class is provided by the OldCommands VendorDep
- */
-public class StartCommand extends InstantCommand {
-  /** The command to fork. */
-  private final Command m_commandToFork;
-
-  /**
-   * Instantiates a {@link StartCommand} which will start the given command whenever its {@link
-   * Command#initialize() initialize()} is called.
-   *
-   * @param commandToStart the {@link Command} to start
-   */
-  public StartCommand(Command commandToStart) {
-    super("Start(" + commandToStart + ")");
-    m_commandToFork = commandToStart;
-  }
-
-  @Override
-  protected void initialize() {
-    m_commandToFork.start();
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/Subsystem.java b/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/Subsystem.java
deleted file mode 100644
index df5984b..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/Subsystem.java
+++ /dev/null
@@ -1,237 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-import edu.wpi.first.util.sendable.Sendable;
-import edu.wpi.first.util.sendable.SendableBuilder;
-import edu.wpi.first.util.sendable.SendableRegistry;
-import java.util.Collections;
-
-/**
- * This class defines a major component of the robot.
- *
- * <p>A good example of a subsystem is the drivetrain, or a claw if the robot has one.
- *
- * <p>All motors should be a part of a subsystem. For instance, all the wheel motors should be a
- * part of some kind of "Drivetrain" subsystem.
- *
- * <p>Subsystems are used within the command system as requirements for {@link Command}. Only one
- * command which requires a subsystem can run at a time. Also, subsystems can have default commands
- * which are started if there is no command running which requires this subsystem.
- *
- * <p>This class is provided by the OldCommands VendorDep
- *
- * @see Command
- */
-public abstract class Subsystem implements Sendable, AutoCloseable {
-  /** Whether or not getDefaultCommand() was called. */
-  private boolean m_initializedDefaultCommand;
-  /** The current command. */
-  private Command m_currentCommand;
-
-  private boolean m_currentCommandChanged;
-
-  /** The default command. */
-  private Command m_defaultCommand;
-
-  /**
-   * Creates a subsystem with the given name.
-   *
-   * @param name the name of the subsystem
-   */
-  public Subsystem(String name) {
-    SendableRegistry.addLW(this, name, name);
-    Scheduler.getInstance().registerSubsystem(this);
-  }
-
-  /** Creates a subsystem. This will set the name to the name of the class. */
-  public Subsystem() {
-    String name = getClass().getName();
-    name = name.substring(name.lastIndexOf('.') + 1);
-    SendableRegistry.addLW(this, name, name);
-    Scheduler.getInstance().registerSubsystem(this);
-    m_currentCommandChanged = true;
-  }
-
-  @Override
-  public void close() {
-    SendableRegistry.remove(this);
-  }
-
-  /**
-   * Initialize the default command for a subsystem By default subsystems have no default command,
-   * but if they do, the default command is set with this method. It is called on all Subsystems by
-   * CommandBase in the users program after all the Subsystems are created.
-   */
-  protected abstract void initDefaultCommand();
-
-  /** When the run method of the scheduler is called this method will be called. */
-  public void periodic() {
-    // Override me!
-  }
-
-  /**
-   * Sets the default command. If this is not called or is called with null, then there will be no
-   * default command for the subsystem.
-   *
-   * <p><b>WARNING:</b> This should <b>NOT</b> be called in a constructor if the subsystem is a
-   * singleton.
-   *
-   * @param command the default command (or null if there should be none)
-   * @throws IllegalUseOfCommandException if the command does not require the subsystem
-   */
-  public void setDefaultCommand(Command command) {
-    if (command == null) {
-      m_defaultCommand = null;
-    } else {
-      if (!Collections.list(command.getRequirements()).contains(this)) {
-        throw new IllegalUseOfCommandException("A default command must require the subsystem");
-      }
-      m_defaultCommand = command;
-    }
-  }
-
-  /**
-   * Returns the default command (or null if there is none).
-   *
-   * @return the default command
-   */
-  public Command getDefaultCommand() {
-    if (!m_initializedDefaultCommand) {
-      m_initializedDefaultCommand = true;
-      initDefaultCommand();
-    }
-    return m_defaultCommand;
-  }
-
-  /**
-   * Returns the default command name, or empty string is there is none.
-   *
-   * @return the default command name
-   */
-  public String getDefaultCommandName() {
-    Command defaultCommand = getDefaultCommand();
-    if (defaultCommand != null) {
-      return defaultCommand.getName();
-    } else {
-      return "";
-    }
-  }
-
-  /**
-   * Sets the current command.
-   *
-   * @param command the new current command
-   */
-  void setCurrentCommand(Command command) {
-    m_currentCommand = command;
-    m_currentCommandChanged = true;
-  }
-
-  /**
-   * Call this to alert Subsystem that the current command is actually the command. Sometimes, the
-   * {@link Subsystem} is told that it has no command while the {@link Scheduler} is going through
-   * the loop, only to be soon after given a new one. This will avoid that situation.
-   */
-  void confirmCommand() {
-    if (m_currentCommandChanged) {
-      m_currentCommandChanged = false;
-    }
-  }
-
-  /**
-   * Returns the command which currently claims this subsystem.
-   *
-   * @return the command which currently claims this subsystem
-   */
-  public Command getCurrentCommand() {
-    return m_currentCommand;
-  }
-
-  /**
-   * Returns the current command name, or empty string if no current command.
-   *
-   * @return the current command name
-   */
-  public String getCurrentCommandName() {
-    Command currentCommand = getCurrentCommand();
-    if (currentCommand != null) {
-      return currentCommand.getName();
-    } else {
-      return "";
-    }
-  }
-
-  /**
-   * Associate a {@link Sendable} with this Subsystem. Also update the child's name.
-   *
-   * @param name name to give child
-   * @param child sendable
-   */
-  public void addChild(String name, Sendable child) {
-    SendableRegistry.addLW(child, getSubsystem(), name);
-  }
-
-  /**
-   * Associate a {@link Sendable} with this Subsystem.
-   *
-   * @param child sendable
-   */
-  public void addChild(Sendable child) {
-    SendableRegistry.setSubsystem(child, getSubsystem());
-    SendableRegistry.enableLiveWindow(child);
-  }
-
-  /**
-   * Gets the name of this Subsystem.
-   *
-   * @return Name
-   */
-  public String getName() {
-    return SendableRegistry.getName(this);
-  }
-
-  /**
-   * Sets the name of this Subsystem.
-   *
-   * @param name name
-   */
-  public void setName(String name) {
-    SendableRegistry.setName(this, name);
-  }
-
-  /**
-   * Gets the subsystem name of this Subsystem.
-   *
-   * @return Subsystem name
-   */
-  public String getSubsystem() {
-    return SendableRegistry.getSubsystem(this);
-  }
-
-  /**
-   * Sets the subsystem name of this Subsystem.
-   *
-   * @param subsystem subsystem name
-   */
-  public void setSubsystem(String subsystem) {
-    SendableRegistry.setSubsystem(this, subsystem);
-  }
-
-  @Override
-  public String toString() {
-    return getSubsystem();
-  }
-
-  @Override
-  public void initSendable(SendableBuilder builder) {
-    builder.setSmartDashboardType("Subsystem");
-
-    builder.addBooleanProperty(".hasDefault", () -> m_defaultCommand != null, null);
-    builder.addStringProperty(".default", this::getDefaultCommandName, null);
-    builder.addBooleanProperty(".hasCommand", () -> m_currentCommand != null, null);
-    builder.addStringProperty(".command", this::getCurrentCommandName, null);
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/TimedCommand.java b/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/TimedCommand.java
deleted file mode 100644
index 70fb087..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/TimedCommand.java
+++ /dev/null
@@ -1,59 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-/**
- * A {@link TimedCommand} will wait for a timeout before finishing. {@link TimedCommand} is used to
- * execute a command for a given amount of time.
- *
- * <p>This class is provided by the OldCommands VendorDep
- */
-public class TimedCommand extends Command {
-  /**
-   * Instantiates a TimedCommand with the given name and timeout.
-   *
-   * @param name the name of the command
-   * @param timeout the time the command takes to run (seconds)
-   */
-  public TimedCommand(String name, double timeout) {
-    super(name, timeout);
-  }
-
-  /**
-   * Instantiates a TimedCommand with the given timeout.
-   *
-   * @param timeout the time the command takes to run (seconds)
-   */
-  public TimedCommand(double timeout) {
-    super(timeout);
-  }
-
-  /**
-   * Instantiates a TimedCommand with the given name and timeout.
-   *
-   * @param name the name of the command
-   * @param timeout the time the command takes to run (seconds)
-   * @param subsystem the subsystem that this command requires
-   */
-  public TimedCommand(String name, double timeout, Subsystem subsystem) {
-    super(name, timeout, subsystem);
-  }
-
-  /**
-   * Instantiates a TimedCommand with the given timeout.
-   *
-   * @param timeout the time the command takes to run (seconds)
-   * @param subsystem the subsystem that this command requires
-   */
-  public TimedCommand(double timeout, Subsystem subsystem) {
-    super(timeout, subsystem);
-  }
-
-  /** Ends command when timed out. */
-  @Override
-  protected boolean isFinished() {
-    return isTimedOut();
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/WaitCommand.java b/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/WaitCommand.java
deleted file mode 100644
index b19a959..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/WaitCommand.java
+++ /dev/null
@@ -1,34 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-/**
- * A {@link WaitCommand} will wait for a certain amount of time before finishing. It is useful if
- * you want a {@link CommandGroup} to pause for a moment.
- *
- * <p>This class is provided by the OldCommands VendorDep
- *
- * @see CommandGroup
- */
-public class WaitCommand extends TimedCommand {
-  /**
-   * Instantiates a {@link WaitCommand} with the given timeout.
-   *
-   * @param timeout the time the command takes to run (seconds)
-   */
-  public WaitCommand(double timeout) {
-    this("Wait(" + timeout + ")", timeout);
-  }
-
-  /**
-   * Instantiates a {@link WaitCommand} with the given timeout.
-   *
-   * @param name the name of the command
-   * @param timeout the time the command takes to run (seconds)
-   */
-  public WaitCommand(String name, double timeout) {
-    super(name, timeout);
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/WaitForChildren.java b/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/WaitForChildren.java
deleted file mode 100644
index 5b24c5a..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/WaitForChildren.java
+++ /dev/null
@@ -1,22 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-/**
- * This command will only finish if whatever {@link CommandGroup} it is in has no active children.
- * If it is not a part of a {@link CommandGroup}, then it will finish immediately. If it is itself
- * an active child, then the {@link CommandGroup} will never end.
- *
- * <p>This class is useful for the situation where you want to allow anything running in parallel to
- * finish, before continuing in the main {@link CommandGroup} sequence.
- *
- * <p>This class is provided by the OldCommands VendorDep
- */
-public class WaitForChildren extends Command {
-  @Override
-  protected boolean isFinished() {
-    return getGroup() == null || getGroup().m_children.isEmpty();
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/WaitUntilCommand.java b/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/WaitUntilCommand.java
deleted file mode 100644
index 7f617eb..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/WaitUntilCommand.java
+++ /dev/null
@@ -1,28 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-import edu.wpi.first.wpilibj.Timer;
-
-/**
- * WaitUntilCommand - waits until an absolute game time. This will wait until the game clock reaches
- * some value, then continue to the next command.
- *
- * <p>This class is provided by the OldCommands VendorDep
- */
-public class WaitUntilCommand extends Command {
-  private final double m_time;
-
-  public WaitUntilCommand(double time) {
-    super("WaitUntil(" + time + ")");
-    m_time = time;
-  }
-
-  /** Check if we've reached the actual finish time. */
-  @Override
-  public boolean isFinished() {
-    return Timer.getMatchTime() >= m_time;
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDAnalogAccelerometer.java b/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDAnalogAccelerometer.java
deleted file mode 100644
index 22a0611..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDAnalogAccelerometer.java
+++ /dev/null
@@ -1,51 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.pidwrappers;
-
-import edu.wpi.first.wpilibj.AnalogAccelerometer;
-import edu.wpi.first.wpilibj.AnalogInput;
-import edu.wpi.first.wpilibj.PIDSource;
-import edu.wpi.first.wpilibj.PIDSourceType;
-
-/**
- * Wrapper so that PIDSource is implemented for AnalogAccelerometer for old PIDController.
- *
- * <p>This class is provided by the OldCommands VendorDep
- *
- * @deprecated Use {@link edu.wpi.first.math.controller.PIDController} which doesn't require this
- *     wrapper.
- */
-@Deprecated(since = "2022", forRemoval = true)
-public class PIDAnalogAccelerometer extends AnalogAccelerometer implements PIDSource {
-  protected PIDSourceType m_pidSource = PIDSourceType.kDisplacement;
-
-  public PIDAnalogAccelerometer(int channel) {
-    super(channel);
-  }
-
-  public PIDAnalogAccelerometer(AnalogInput channel) {
-    super(channel);
-  }
-
-  @Override
-  public void setPIDSourceType(PIDSourceType pidSource) {
-    m_pidSource = pidSource;
-  }
-
-  @Override
-  public PIDSourceType getPIDSourceType() {
-    return m_pidSource;
-  }
-
-  /**
-   * Get the Acceleration for the PID Source parent.
-   *
-   * @return The current acceleration in Gs.
-   */
-  @Override
-  public double pidGet() {
-    return getAcceleration();
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDAnalogGyro.java b/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDAnalogGyro.java
deleted file mode 100644
index 9881657..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDAnalogGyro.java
+++ /dev/null
@@ -1,73 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.pidwrappers;
-
-import edu.wpi.first.wpilibj.AnalogGyro;
-import edu.wpi.first.wpilibj.AnalogInput;
-import edu.wpi.first.wpilibj.PIDSource;
-import edu.wpi.first.wpilibj.PIDSourceType;
-
-/**
- * Wrapper so that PIDSource is implemented for AnalogGyro for old PIDController.
- *
- * <p>This class is provided by the OldCommands VendorDep
- *
- * @deprecated Use {@link edu.wpi.first.math.controller.PIDController} which doesn't require this
- *     wrapper.
- */
-@Deprecated(since = "2022", forRemoval = true)
-public class PIDAnalogGyro extends AnalogGyro implements PIDSource {
-  private PIDSourceType m_pidSource = PIDSourceType.kDisplacement;
-
-  public PIDAnalogGyro(int channel) {
-    super(channel);
-  }
-
-  public PIDAnalogGyro(AnalogInput channel) {
-    super(channel);
-  }
-
-  public PIDAnalogGyro(int channel, int center, double offset) {
-    super(channel, center, offset);
-  }
-
-  public PIDAnalogGyro(AnalogInput channel, int center, double offset) {
-    super(channel, center, offset);
-  }
-
-  /**
-   * Set which parameter of the gyro you are using as a process control variable. The Gyro class
-   * supports the rate and displacement parameters
-   *
-   * @param pidSource An enum to select the parameter.
-   */
-  @Override
-  public void setPIDSourceType(PIDSourceType pidSource) {
-    m_pidSource = pidSource;
-  }
-
-  @Override
-  public PIDSourceType getPIDSourceType() {
-    return m_pidSource;
-  }
-
-  /**
-   * Get the output of the gyro for use with PIDControllers. May be the angle or rate depending on
-   * the set PIDSourceType
-   *
-   * @return the output according to the gyro
-   */
-  @Override
-  public double pidGet() {
-    switch (m_pidSource) {
-      case kRate:
-        return getRate();
-      case kDisplacement:
-        return getAngle();
-      default:
-        return 0.0;
-    }
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDAnalogInput.java b/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDAnalogInput.java
deleted file mode 100644
index 797be71..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDAnalogInput.java
+++ /dev/null
@@ -1,46 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.pidwrappers;
-
-import edu.wpi.first.wpilibj.AnalogInput;
-import edu.wpi.first.wpilibj.PIDSource;
-import edu.wpi.first.wpilibj.PIDSourceType;
-
-/**
- * Wrapper so that PIDSource is implemented for AnalogInput for old PIDController.
- *
- * <p>This class is provided by the OldCommands VendorDep
- *
- * @deprecated Use {@link edu.wpi.first.math.controller.PIDController} which doesn't require this
- *     wrapper.
- */
-@Deprecated(since = "2022", forRemoval = true)
-public class PIDAnalogInput extends AnalogInput implements PIDSource {
-  protected PIDSourceType m_pidSource = PIDSourceType.kDisplacement;
-
-  public PIDAnalogInput(int channel) {
-    super(channel);
-  }
-
-  @Override
-  public void setPIDSourceType(PIDSourceType pidSource) {
-    m_pidSource = pidSource;
-  }
-
-  @Override
-  public PIDSourceType getPIDSourceType() {
-    return m_pidSource;
-  }
-
-  /**
-   * Get the average voltage for use with PIDController.
-   *
-   * @return the average voltage
-   */
-  @Override
-  public double pidGet() {
-    return getAverageVoltage();
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDAnalogPotentiometer.java b/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDAnalogPotentiometer.java
deleted file mode 100644
index f905e5a..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDAnalogPotentiometer.java
+++ /dev/null
@@ -1,70 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.pidwrappers;
-
-import edu.wpi.first.wpilibj.AnalogInput;
-import edu.wpi.first.wpilibj.AnalogPotentiometer;
-import edu.wpi.first.wpilibj.PIDSource;
-import edu.wpi.first.wpilibj.PIDSourceType;
-
-/**
- * Wrapper so that PIDSource is implemented for AnalogPotentiometer for old PIDController.
- *
- * <p>This class is provided by the OldCommands VendorDep
- *
- * @deprecated Use {@link edu.wpi.first.math.controller.PIDController} which doesn't require this
- *     wrapper.
- */
-@Deprecated(since = "2022", forRemoval = true)
-public class PIDAnalogPotentiometer extends AnalogPotentiometer implements PIDSource {
-  protected PIDSourceType m_pidSource = PIDSourceType.kDisplacement;
-
-  public PIDAnalogPotentiometer(int channel, double fullRange, double offset) {
-    super(channel, fullRange, offset);
-  }
-
-  public PIDAnalogPotentiometer(AnalogInput input, double fullRange, double offset) {
-    super(input, fullRange, offset);
-  }
-
-  public PIDAnalogPotentiometer(int channel, double scale) {
-    super(channel, scale);
-  }
-
-  public PIDAnalogPotentiometer(AnalogInput input, double scale) {
-    super(input, scale);
-  }
-
-  public PIDAnalogPotentiometer(int channel) {
-    super(channel);
-  }
-
-  public PIDAnalogPotentiometer(AnalogInput input) {
-    super(input);
-  }
-
-  @Override
-  public void setPIDSourceType(PIDSourceType pidSource) {
-    if (!pidSource.equals(PIDSourceType.kDisplacement)) {
-      throw new IllegalArgumentException("Only displacement PID is allowed for potentiometers.");
-    }
-    m_pidSource = pidSource;
-  }
-
-  @Override
-  public PIDSourceType getPIDSourceType() {
-    return m_pidSource;
-  }
-
-  /**
-   * Implement the PIDSource interface.
-   *
-   * @return The current reading.
-   */
-  @Override
-  public double pidGet() {
-    return get();
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDEncoder.java b/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDEncoder.java
deleted file mode 100644
index 67c3ed1..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDEncoder.java
+++ /dev/null
@@ -1,109 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.pidwrappers;
-
-import edu.wpi.first.wpilibj.DigitalSource;
-import edu.wpi.first.wpilibj.Encoder;
-import edu.wpi.first.wpilibj.PIDSource;
-import edu.wpi.first.wpilibj.PIDSourceType;
-
-/**
- * Wrapper so that PIDSource is implemented for Encoder for old PIDController.
- *
- * <p>This class is provided by the OldCommands VendorDep
- *
- * @deprecated Use {@link edu.wpi.first.math.controller.PIDController} which doesn't require this
- *     wrapper.
- */
-@Deprecated(since = "2022", forRemoval = true)
-public class PIDEncoder extends Encoder implements PIDSource {
-  private PIDSourceType m_pidSource = PIDSourceType.kDisplacement;
-
-  public PIDEncoder(final int channelA, final int channelB, boolean reverseDirection) {
-    super(channelA, channelB, reverseDirection, EncodingType.k4X);
-  }
-
-  public PIDEncoder(final int channelA, final int channelB) {
-    super(channelA, channelB, false);
-  }
-
-  public PIDEncoder(
-      final int channelA,
-      final int channelB,
-      boolean reverseDirection,
-      final EncodingType encodingType) {
-    super(channelA, channelB, reverseDirection, encodingType);
-  }
-
-  public PIDEncoder(
-      final int channelA, final int channelB, final int indexChannel, boolean reverseDirection) {
-    super(channelA, channelB, indexChannel, reverseDirection);
-  }
-
-  public PIDEncoder(final int channelA, final int channelB, final int indexChannel) {
-    super(channelA, channelB, indexChannel, false);
-  }
-
-  public PIDEncoder(DigitalSource sourceA, DigitalSource sourceB, boolean reverseDirection) {
-    super(sourceA, sourceB, reverseDirection, EncodingType.k4X);
-  }
-
-  public PIDEncoder(DigitalSource sourceA, DigitalSource sourceB) {
-    super(sourceA, sourceB, false);
-  }
-
-  public PIDEncoder(
-      DigitalSource sourceA,
-      DigitalSource sourceB,
-      boolean reverseDirection,
-      final EncodingType encodingType) {
-    super(sourceA, sourceB, reverseDirection, encodingType);
-  }
-
-  public PIDEncoder(
-      DigitalSource sourceA,
-      DigitalSource sourceB,
-      DigitalSource indexSource,
-      boolean reverseDirection) {
-    super(sourceA, sourceB, indexSource, reverseDirection);
-  }
-
-  public PIDEncoder(DigitalSource sourceA, DigitalSource sourceB, DigitalSource indexSource) {
-    super(sourceA, sourceB, indexSource, false);
-  }
-
-  /**
-   * Set which parameter of the encoder you are using as a process control variable. The encoder
-   * class supports the rate and distance parameters.
-   *
-   * @param pidSource An enum to select the parameter.
-   */
-  @Override
-  public void setPIDSourceType(PIDSourceType pidSource) {
-    m_pidSource = pidSource;
-  }
-
-  @Override
-  public PIDSourceType getPIDSourceType() {
-    return m_pidSource;
-  }
-
-  /**
-   * Implement the PIDSource interface.
-   *
-   * @return The current value of the selected source parameter.
-   */
-  @Override
-  public double pidGet() {
-    switch (m_pidSource) {
-      case kDisplacement:
-        return getDistance();
-      case kRate:
-        return getRate();
-      default:
-        return 0.0;
-    }
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDMotorController.java b/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDMotorController.java
deleted file mode 100644
index 11d033b..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDMotorController.java
+++ /dev/null
@@ -1,116 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.pidwrappers;
-
-import edu.wpi.first.util.sendable.Sendable;
-import edu.wpi.first.util.sendable.SendableBuilder;
-import edu.wpi.first.wpilibj.PIDOutput;
-import edu.wpi.first.wpilibj.motorcontrol.MotorController;
-
-/**
- * Wrapper so that PIDOutput is implemented for MotorController for old PIDController.
- *
- * <p>This class is provided by the OldCommands VendorDep
- *
- * @deprecated Use {@link edu.wpi.first.math.controller.PIDController} which doesn't require this
- *     wrapper.
- */
-@Deprecated(since = "2022", forRemoval = true)
-public class PIDMotorController implements PIDOutput, MotorController, Sendable {
-  private final MotorController m_motorController;
-
-  public PIDMotorController(MotorController motorController) {
-    m_motorController = motorController;
-  }
-
-  /**
-   * Write out the PID value as seen in the PIDOutput base object.
-   *
-   * @param output Write out the PWM value as was found in the PIDController
-   */
-  @Override
-  public void pidWrite(double output) {
-    m_motorController.set(output);
-  }
-
-  /**
-   * Common interface for setting the speed of a motor controller.
-   *
-   * @param speed The speed to set. Value should be between -1.0 and 1.0.
-   */
-  @Override
-  public void set(double speed) {
-    m_motorController.set(speed);
-  }
-
-  /**
-   * Sets the voltage output of the MotorController. Compensates for the current bus voltage to
-   * ensure that the desired voltage is output even if the battery voltage is below 12V - highly
-   * useful when the voltage outputs are "meaningful" (e.g. they come from a feedforward
-   * calculation).
-   *
-   * <p>NOTE: This function *must* be called regularly in order for voltage compensation to work
-   * properly - unlike the ordinary set function, it is not "set it and forget it."
-   *
-   * @param outputVolts The voltage to output.
-   */
-  @Override
-  public void setVoltage(double outputVolts) {
-    m_motorController.setVoltage(outputVolts);
-  }
-
-  /**
-   * Common interface for getting the current set speed of a motor controller.
-   *
-   * @return The current set speed. Value is between -1.0 and 1.0.
-   */
-  @Override
-  public double get() {
-    return m_motorController.get();
-  }
-
-  /**
-   * Common interface for inverting direction of a motor controller.
-   *
-   * @param isInverted The state of inversion true is inverted.
-   */
-  @Override
-  public void setInverted(boolean isInverted) {
-    m_motorController.setInverted(isInverted);
-  }
-
-  /**
-   * Common interface for returning if a motor controller is in the inverted state or not.
-   *
-   * @return isInverted The state of the inversion true is inverted.
-   */
-  @Override
-  public boolean getInverted() {
-    return m_motorController.getInverted();
-  }
-
-  /** Disable the motor controller. */
-  @Override
-  public void disable() {
-    m_motorController.disable();
-  }
-
-  /**
-   * Stops motor movement. Motor can be moved again by calling set without having to re-enable the
-   * motor.
-   */
-  @Override
-  public void stopMotor() {
-    m_motorController.stopMotor();
-  }
-
-  @Override
-  public void initSendable(SendableBuilder builder) {
-    builder.setSmartDashboardType("Motor Controller");
-    builder.setActuator(true);
-    builder.setSafeState(this::disable);
-    builder.addDoubleProperty("Value", this::get, this::set);
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDUltrasonic.java b/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDUltrasonic.java
deleted file mode 100644
index e542b68..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDUltrasonic.java
+++ /dev/null
@@ -1,55 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.pidwrappers;
-
-import edu.wpi.first.wpilibj.DigitalInput;
-import edu.wpi.first.wpilibj.DigitalOutput;
-import edu.wpi.first.wpilibj.PIDSource;
-import edu.wpi.first.wpilibj.PIDSourceType;
-import edu.wpi.first.wpilibj.Ultrasonic;
-
-/**
- * Wrapper so that PIDSource is implemented for Ultrasonic for old PIDController.
- *
- * <p>This class is provided by the OldCommands VendorDep
- *
- * @deprecated Use {@link edu.wpi.first.math.controller.PIDController} which doesn't require this
- *     wrapper.
- */
-@Deprecated(since = "2022", forRemoval = true)
-public class PIDUltrasonic extends Ultrasonic implements PIDSource {
-  protected PIDSourceType m_pidSource = PIDSourceType.kDisplacement;
-
-  public PIDUltrasonic(int pingChannel, int echoChannel) {
-    super(pingChannel, echoChannel);
-  }
-
-  public PIDUltrasonic(DigitalOutput pingChannel, DigitalInput echoChannel) {
-    super(pingChannel, echoChannel);
-  }
-
-  @Override
-  public void setPIDSourceType(PIDSourceType pidSource) {
-    if (!pidSource.equals(PIDSourceType.kDisplacement)) {
-      throw new IllegalArgumentException("Only displacement PID is allowed for ultrasonics.");
-    }
-    m_pidSource = pidSource;
-  }
-
-  @Override
-  public PIDSourceType getPIDSourceType() {
-    return m_pidSource;
-  }
-
-  /**
-   * Get the range in the inches for the PIDSource base object.
-   *
-   * @return The range in inches
-   */
-  @Override
-  public double pidGet() {
-    return getRangeInches();
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/PIDBase.cpp b/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/PIDBase.cpp
deleted file mode 100644
index 825d4eb..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/PIDBase.cpp
+++ /dev/null
@@ -1,358 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/PIDBase.h"
-
-#include <algorithm>
-#include <cmath>
-
-#include <hal/FRCUsageReporting.h>
-#include <wpi/sendable/SendableBuilder.h>
-#include <wpi/sendable/SendableRegistry.h>
-
-#include "frc/PIDOutput.h"
-
-using namespace frc;
-
-template <class T>
-constexpr const T& clamp(const T& value, const T& low, const T& high) {
-  return std::max(low, std::min(value, high));
-}
-
-PIDBase::PIDBase(double Kp, double Ki, double Kd, PIDSource& source,
-                 PIDOutput& output)
-    : PIDBase(Kp, Ki, Kd, 0.0, source, output) {}
-
-PIDBase::PIDBase(double Kp, double Ki, double Kd, double Kf, PIDSource& source,
-                 PIDOutput& output) {
-  m_P = Kp;
-  m_I = Ki;
-  m_D = Kd;
-  m_F = Kf;
-
-  m_pidInput = &source;
-  m_filter = LinearFilter<double>::MovingAverage(1);
-
-  m_pidOutput = &output;
-
-  m_setpointTimer.Start();
-
-  static int instances = 0;
-  instances++;
-  HAL_Report(HALUsageReporting::kResourceType_PIDController, instances);
-  wpi::SendableRegistry::Add(this, "PIDController", instances);
-}
-
-double PIDBase::Get() const {
-  std::scoped_lock lock(m_thisMutex);
-  return m_result;
-}
-
-void PIDBase::SetContinuous(bool continuous) {
-  std::scoped_lock lock(m_thisMutex);
-  m_continuous = continuous;
-}
-
-void PIDBase::SetInputRange(double minimumInput, double maximumInput) {
-  {
-    std::scoped_lock lock(m_thisMutex);
-    m_minimumInput = minimumInput;
-    m_maximumInput = maximumInput;
-    m_inputRange = maximumInput - minimumInput;
-  }
-
-  SetSetpoint(m_setpoint);
-}
-
-void PIDBase::SetOutputRange(double minimumOutput, double maximumOutput) {
-  std::scoped_lock lock(m_thisMutex);
-  m_minimumOutput = minimumOutput;
-  m_maximumOutput = maximumOutput;
-}
-
-void PIDBase::SetPID(double p, double i, double d) {
-  {
-    std::scoped_lock lock(m_thisMutex);
-    m_P = p;
-    m_I = i;
-    m_D = d;
-  }
-}
-
-void PIDBase::SetPID(double p, double i, double d, double f) {
-  std::scoped_lock lock(m_thisMutex);
-  m_P = p;
-  m_I = i;
-  m_D = d;
-  m_F = f;
-}
-
-void PIDBase::SetP(double p) {
-  std::scoped_lock lock(m_thisMutex);
-  m_P = p;
-}
-
-void PIDBase::SetI(double i) {
-  std::scoped_lock lock(m_thisMutex);
-  m_I = i;
-}
-
-void PIDBase::SetD(double d) {
-  std::scoped_lock lock(m_thisMutex);
-  m_D = d;
-}
-
-void PIDBase::SetF(double f) {
-  std::scoped_lock lock(m_thisMutex);
-  m_F = f;
-}
-
-double PIDBase::GetP() const {
-  std::scoped_lock lock(m_thisMutex);
-  return m_P;
-}
-
-double PIDBase::GetI() const {
-  std::scoped_lock lock(m_thisMutex);
-  return m_I;
-}
-
-double PIDBase::GetD() const {
-  std::scoped_lock lock(m_thisMutex);
-  return m_D;
-}
-
-double PIDBase::GetF() const {
-  std::scoped_lock lock(m_thisMutex);
-  return m_F;
-}
-
-void PIDBase::SetSetpoint(double setpoint) {
-  {
-    std::scoped_lock lock(m_thisMutex);
-
-    if (m_maximumInput > m_minimumInput) {
-      if (setpoint > m_maximumInput) {
-        m_setpoint = m_maximumInput;
-      } else if (setpoint < m_minimumInput) {
-        m_setpoint = m_minimumInput;
-      } else {
-        m_setpoint = setpoint;
-      }
-    } else {
-      m_setpoint = setpoint;
-    }
-  }
-}
-
-double PIDBase::GetSetpoint() const {
-  std::scoped_lock lock(m_thisMutex);
-  return m_setpoint;
-}
-
-double PIDBase::GetDeltaSetpoint() const {
-  std::scoped_lock lock(m_thisMutex);
-  return (m_setpoint - m_prevSetpoint) / m_setpointTimer.Get().value();
-}
-
-double PIDBase::GetError() const {
-  double setpoint = GetSetpoint();
-  {
-    std::scoped_lock lock(m_thisMutex);
-    return GetContinuousError(setpoint - m_pidInput->PIDGet());
-  }
-}
-
-double PIDBase::GetAvgError() const {
-  return GetError();
-}
-
-void PIDBase::SetPIDSourceType(PIDSourceType pidSource) {
-  m_pidInput->SetPIDSourceType(pidSource);
-}
-
-PIDSourceType PIDBase::GetPIDSourceType() const {
-  return m_pidInput->GetPIDSourceType();
-}
-
-void PIDBase::SetTolerance(double percent) {
-  std::scoped_lock lock(m_thisMutex);
-  m_toleranceType = kPercentTolerance;
-  m_tolerance = percent;
-}
-
-void PIDBase::SetAbsoluteTolerance(double absTolerance) {
-  std::scoped_lock lock(m_thisMutex);
-  m_toleranceType = kAbsoluteTolerance;
-  m_tolerance = absTolerance;
-}
-
-void PIDBase::SetPercentTolerance(double percent) {
-  std::scoped_lock lock(m_thisMutex);
-  m_toleranceType = kPercentTolerance;
-  m_tolerance = percent;
-}
-
-void PIDBase::SetToleranceBuffer(int bufLength) {
-  std::scoped_lock lock(m_thisMutex);
-  m_filter = LinearFilter<double>::MovingAverage(bufLength);
-}
-
-bool PIDBase::OnTarget() const {
-  double error = GetError();
-
-  std::scoped_lock lock(m_thisMutex);
-  switch (m_toleranceType) {
-    case kPercentTolerance:
-      return std::fabs(error) < m_tolerance / 100 * m_inputRange;
-      break;
-    case kAbsoluteTolerance:
-      return std::fabs(error) < m_tolerance;
-      break;
-    case kNoTolerance:
-      // TODO: this case needs an error
-      return false;
-  }
-  return false;
-}
-
-void PIDBase::Reset() {
-  std::scoped_lock lock(m_thisMutex);
-  m_prevError = 0;
-  m_totalError = 0;
-  m_result = 0;
-}
-
-void PIDBase::PIDWrite(double output) {
-  SetSetpoint(output);
-}
-
-void PIDBase::InitSendable(wpi::SendableBuilder& builder) {
-  builder.SetSmartDashboardType("PIDController");
-  builder.SetSafeState([=] { Reset(); });
-  builder.AddDoubleProperty(
-      "p", [=] { return GetP(); }, [=](double value) { SetP(value); });
-  builder.AddDoubleProperty(
-      "i", [=] { return GetI(); }, [=](double value) { SetI(value); });
-  builder.AddDoubleProperty(
-      "d", [=] { return GetD(); }, [=](double value) { SetD(value); });
-  builder.AddDoubleProperty(
-      "f", [=] { return GetF(); }, [=](double value) { SetF(value); });
-  builder.AddDoubleProperty(
-      "setpoint", [=] { return GetSetpoint(); },
-      [=](double value) { SetSetpoint(value); });
-}
-
-void PIDBase::Calculate() {
-  if (m_pidInput == nullptr || m_pidOutput == nullptr) {
-    return;
-  }
-
-  bool enabled;
-  {
-    std::scoped_lock lock(m_thisMutex);
-    enabled = m_enabled;
-  }
-
-  if (enabled) {
-    double input;
-
-    // Storage for function inputs
-    PIDSourceType pidSourceType;
-    double P;
-    double I;
-    double D;
-    double feedForward = CalculateFeedForward();
-    double minimumOutput;
-    double maximumOutput;
-
-    // Storage for function input-outputs
-    double prevError;
-    double error;
-    double totalError;
-
-    {
-      std::scoped_lock lock(m_thisMutex);
-
-      input = m_filter.Calculate(m_pidInput->PIDGet());
-
-      pidSourceType = m_pidInput->GetPIDSourceType();
-      P = m_P;
-      I = m_I;
-      D = m_D;
-      minimumOutput = m_minimumOutput;
-      maximumOutput = m_maximumOutput;
-
-      prevError = m_prevError;
-      error = GetContinuousError(m_setpoint - input);
-      totalError = m_totalError;
-    }
-
-    // Storage for function outputs
-    double result;
-
-    if (pidSourceType == PIDSourceType::kRate) {
-      if (P != 0) {
-        totalError =
-            clamp(totalError + error, minimumOutput / P, maximumOutput / P);
-      }
-
-      result = D * error + P * totalError + feedForward;
-    } else {
-      if (I != 0) {
-        totalError =
-            clamp(totalError + error, minimumOutput / I, maximumOutput / I);
-      }
-
-      result =
-          P * error + I * totalError + D * (error - prevError) + feedForward;
-    }
-
-    result = clamp(result, minimumOutput, maximumOutput);
-
-    {
-      // Ensures m_enabled check and PIDWrite() call occur atomically
-      std::scoped_lock pidWriteLock(m_pidWriteMutex);
-      std::unique_lock mainLock(m_thisMutex);
-      if (m_enabled) {
-        // Don't block other PIDBase operations on PIDWrite()
-        mainLock.unlock();
-
-        m_pidOutput->PIDWrite(result);
-      }
-    }
-
-    std::scoped_lock lock(m_thisMutex);
-    m_prevError = m_error;
-    m_error = error;
-    m_totalError = totalError;
-    m_result = result;
-  }
-}
-
-double PIDBase::CalculateFeedForward() {
-  if (m_pidInput->GetPIDSourceType() == PIDSourceType::kRate) {
-    return m_F * GetSetpoint();
-  } else {
-    double temp = m_F * GetDeltaSetpoint();
-    m_prevSetpoint = m_setpoint;
-    m_setpointTimer.Reset();
-    return temp;
-  }
-}
-
-double PIDBase::GetContinuousError(double error) const {
-  if (m_continuous && m_inputRange != 0) {
-    error = std::fmod(error, m_inputRange);
-    if (std::fabs(error) > m_inputRange / 2) {
-      if (error > 0) {
-        return error - m_inputRange;
-      } else {
-        return error + m_inputRange;
-      }
-    }
-  }
-
-  return error;
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/PIDController.cpp b/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/PIDController.cpp
deleted file mode 100644
index ee8382c..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/PIDController.cpp
+++ /dev/null
@@ -1,84 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/PIDController.h"
-
-#include <wpi/sendable/SendableBuilder.h>
-
-#include "frc/Notifier.h"
-#include "frc/PIDOutput.h"
-
-using namespace frc;
-
-PIDController::PIDController(double Kp, double Ki, double Kd, PIDSource* source,
-                             PIDOutput* output, double period)
-    : PIDController(Kp, Ki, Kd, 0.0, *source, *output, period) {}
-
-PIDController::PIDController(double Kp, double Ki, double Kd, double Kf,
-                             PIDSource* source, PIDOutput* output,
-                             double period)
-    : PIDController(Kp, Ki, Kd, Kf, *source, *output, period) {}
-
-PIDController::PIDController(double Kp, double Ki, double Kd, PIDSource& source,
-                             PIDOutput& output, double period)
-    : PIDController(Kp, Ki, Kd, 0.0, source, output, period) {}
-
-PIDController::PIDController(double Kp, double Ki, double Kd, double Kf,
-                             PIDSource& source, PIDOutput& output,
-                             double period)
-    : PIDBase(Kp, Ki, Kd, Kf, source, output) {
-  m_controlLoop = std::make_unique<Notifier>(&PIDController::Calculate, this);
-  m_controlLoop->StartPeriodic(units::second_t(period));
-}
-
-PIDController::~PIDController() {
-  // Forcefully stopping the notifier so the callback can successfully run.
-  m_controlLoop->Stop();
-}
-
-void PIDController::Enable() {
-  {
-    std::scoped_lock lock(m_thisMutex);
-    m_enabled = true;
-  }
-}
-
-void PIDController::Disable() {
-  {
-    // Ensures m_enabled modification and PIDWrite() call occur atomically
-    std::scoped_lock pidWriteLock(m_pidWriteMutex);
-    {
-      std::scoped_lock mainLock(m_thisMutex);
-      m_enabled = false;
-    }
-
-    m_pidOutput->PIDWrite(0);
-  }
-}
-
-void PIDController::SetEnabled(bool enable) {
-  if (enable) {
-    Enable();
-  } else {
-    Disable();
-  }
-}
-
-bool PIDController::IsEnabled() const {
-  std::scoped_lock lock(m_thisMutex);
-  return m_enabled;
-}
-
-void PIDController::Reset() {
-  Disable();
-
-  PIDBase::Reset();
-}
-
-void PIDController::InitSendable(wpi::SendableBuilder& builder) {
-  PIDBase::InitSendable(builder);
-  builder.AddBooleanProperty(
-      "enabled", [=] { return IsEnabled(); },
-      [=](bool value) { SetEnabled(value); });
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/PIDSource.cpp b/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/PIDSource.cpp
deleted file mode 100644
index 3a9e3ea..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/PIDSource.cpp
+++ /dev/null
@@ -1,15 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/PIDSource.h"
-
-using namespace frc;
-
-void PIDSource::SetPIDSourceType(PIDSourceType pidSource) {
-  m_pidSource = pidSource;
-}
-
-PIDSourceType PIDSource::GetPIDSourceType() const {
-  return m_pidSource;
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/buttons/Button.cpp b/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/buttons/Button.cpp
deleted file mode 100644
index ef2c03d..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/buttons/Button.cpp
+++ /dev/null
@@ -1,27 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/buttons/Button.h"
-
-using namespace frc;
-
-void Button::WhenPressed(Command* command) {
-  WhenActive(command);
-}
-
-void Button::WhileHeld(Command* command) {
-  WhileActive(command);
-}
-
-void Button::WhenReleased(Command* command) {
-  WhenInactive(command);
-}
-
-void Button::CancelWhenPressed(Command* command) {
-  CancelWhenActive(command);
-}
-
-void Button::ToggleWhenPressed(Command* command) {
-  ToggleWhenActive(command);
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/buttons/ButtonScheduler.cpp b/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/buttons/ButtonScheduler.cpp
deleted file mode 100644
index b210c8d..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/buttons/ButtonScheduler.cpp
+++ /dev/null
@@ -1,16 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/buttons/ButtonScheduler.h"
-
-#include "frc/commands/Scheduler.h"
-
-using namespace frc;
-
-ButtonScheduler::ButtonScheduler(bool last, Trigger* button, Command* orders)
-    : m_pressedLast(last), m_button(button), m_command(orders) {}
-
-void ButtonScheduler::Start() {
-  Scheduler::GetInstance()->AddButton(this);
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/buttons/CancelButtonScheduler.cpp b/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/buttons/CancelButtonScheduler.cpp
deleted file mode 100644
index faff376..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/buttons/CancelButtonScheduler.cpp
+++ /dev/null
@@ -1,24 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/buttons/CancelButtonScheduler.h"
-
-#include "frc/buttons/Button.h"
-#include "frc/commands/Command.h"
-
-using namespace frc;
-
-CancelButtonScheduler::CancelButtonScheduler(bool last, Trigger* button,
-                                             Command* orders)
-    : ButtonScheduler(last, button, orders) {}
-
-void CancelButtonScheduler::Execute() {
-  bool pressed = m_button->Grab();
-
-  if (!m_pressedLast && pressed) {
-    m_command->Cancel();
-  }
-
-  m_pressedLast = pressed;
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/buttons/HeldButtonScheduler.cpp b/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/buttons/HeldButtonScheduler.cpp
deleted file mode 100644
index 8fb1064..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/buttons/HeldButtonScheduler.cpp
+++ /dev/null
@@ -1,26 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/buttons/HeldButtonScheduler.h"
-
-#include "frc/buttons/Button.h"
-#include "frc/commands/Command.h"
-
-using namespace frc;
-
-HeldButtonScheduler::HeldButtonScheduler(bool last, Trigger* button,
-                                         Command* orders)
-    : ButtonScheduler(last, button, orders) {}
-
-void HeldButtonScheduler::Execute() {
-  bool pressed = m_button->Grab();
-
-  if (pressed) {
-    m_command->Start();
-  } else if (m_pressedLast && !pressed) {
-    m_command->Cancel();
-  }
-
-  m_pressedLast = pressed;
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/buttons/InternalButton.cpp b/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/buttons/InternalButton.cpp
deleted file mode 100644
index 5adf83c..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/buttons/InternalButton.cpp
+++ /dev/null
@@ -1,22 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/buttons/InternalButton.h"
-
-using namespace frc;
-
-InternalButton::InternalButton(bool inverted)
-    : m_pressed(inverted), m_inverted(inverted) {}
-
-void InternalButton::SetInverted(bool inverted) {
-  m_inverted = inverted;
-}
-
-void InternalButton::SetPressed(bool pressed) {
-  m_pressed = pressed;
-}
-
-bool InternalButton::Get() {
-  return m_pressed ^ m_inverted;
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/buttons/JoystickButton.cpp b/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/buttons/JoystickButton.cpp
deleted file mode 100644
index 459c076..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/buttons/JoystickButton.cpp
+++ /dev/null
@@ -1,14 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/buttons/JoystickButton.h"
-
-using namespace frc;
-
-JoystickButton::JoystickButton(GenericHID* joystick, int buttonNumber)
-    : m_joystick(joystick), m_buttonNumber(buttonNumber) {}
-
-bool JoystickButton::Get() {
-  return m_joystick->GetRawButton(m_buttonNumber);
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/buttons/NetworkButton.cpp b/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/buttons/NetworkButton.cpp
deleted file mode 100644
index f5694a1..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/buttons/NetworkButton.cpp
+++ /dev/null
@@ -1,22 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/buttons/NetworkButton.h"
-
-#include <networktables/NetworkTable.h>
-#include <networktables/NetworkTableInstance.h>
-
-using namespace frc;
-
-NetworkButton::NetworkButton(std::string_view tableName, std::string_view field)
-    : NetworkButton(nt::NetworkTableInstance::GetDefault().GetTable(tableName),
-                    field) {}
-
-NetworkButton::NetworkButton(std::shared_ptr<nt::NetworkTable> table,
-                             std::string_view field)
-    : m_entry(table->GetEntry(field)) {}
-
-bool NetworkButton::Get() {
-  return m_entry.GetInstance().IsConnected() && m_entry.GetBoolean(false);
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/buttons/POVButton.cpp b/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/buttons/POVButton.cpp
deleted file mode 100644
index 67b8cae..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/buttons/POVButton.cpp
+++ /dev/null
@@ -1,14 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/buttons/POVButton.h"
-
-using namespace frc;
-
-POVButton::POVButton(GenericHID& joystick, int angle, int povNumber)
-    : m_joystick(&joystick), m_angle(angle), m_povNumber(povNumber) {}
-
-bool POVButton::Get() {
-  return m_joystick->GetPOV(m_povNumber) == m_angle;
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/buttons/PressedButtonScheduler.cpp b/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/buttons/PressedButtonScheduler.cpp
deleted file mode 100644
index 73705bc..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/buttons/PressedButtonScheduler.cpp
+++ /dev/null
@@ -1,24 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/buttons/PressedButtonScheduler.h"
-
-#include "frc/buttons/Button.h"
-#include "frc/commands/Command.h"
-
-using namespace frc;
-
-PressedButtonScheduler::PressedButtonScheduler(bool last, Trigger* button,
-                                               Command* orders)
-    : ButtonScheduler(last, button, orders) {}
-
-void PressedButtonScheduler::Execute() {
-  bool pressed = m_button->Grab();
-
-  if (!m_pressedLast && pressed) {
-    m_command->Start();
-  }
-
-  m_pressedLast = pressed;
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/buttons/ReleasedButtonScheduler.cpp b/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/buttons/ReleasedButtonScheduler.cpp
deleted file mode 100644
index 647169b..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/buttons/ReleasedButtonScheduler.cpp
+++ /dev/null
@@ -1,24 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/buttons/ReleasedButtonScheduler.h"
-
-#include "frc/buttons/Button.h"
-#include "frc/commands/Command.h"
-
-using namespace frc;
-
-ReleasedButtonScheduler::ReleasedButtonScheduler(bool last, Trigger* button,
-                                                 Command* orders)
-    : ButtonScheduler(last, button, orders) {}
-
-void ReleasedButtonScheduler::Execute() {
-  bool pressed = m_button->Grab();
-
-  if (m_pressedLast && !pressed) {
-    m_command->Start();
-  }
-
-  m_pressedLast = pressed;
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/buttons/ToggleButtonScheduler.cpp b/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/buttons/ToggleButtonScheduler.cpp
deleted file mode 100644
index d17b2e8..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/buttons/ToggleButtonScheduler.cpp
+++ /dev/null
@@ -1,28 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/buttons/ToggleButtonScheduler.h"
-
-#include "frc/buttons/Button.h"
-#include "frc/commands/Command.h"
-
-using namespace frc;
-
-ToggleButtonScheduler::ToggleButtonScheduler(bool last, Trigger* button,
-                                             Command* orders)
-    : ButtonScheduler(last, button, orders) {}
-
-void ToggleButtonScheduler::Execute() {
-  bool pressed = m_button->Grab();
-
-  if (!m_pressedLast && pressed) {
-    if (m_command->IsRunning()) {
-      m_command->Cancel();
-    } else {
-      m_command->Start();
-    }
-  }
-
-  m_pressedLast = pressed;
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/buttons/Trigger.cpp b/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/buttons/Trigger.cpp
deleted file mode 100644
index 9040df6..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/buttons/Trigger.cpp
+++ /dev/null
@@ -1,72 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include <wpi/sendable/SendableBuilder.h>
-
-#include "frc/buttons/Button.h"
-#include "frc/buttons/CancelButtonScheduler.h"
-#include "frc/buttons/HeldButtonScheduler.h"
-#include "frc/buttons/PressedButtonScheduler.h"
-#include "frc/buttons/ReleasedButtonScheduler.h"
-#include "frc/buttons/ToggleButtonScheduler.h"
-
-using namespace frc;
-
-Trigger::Trigger(const Trigger& rhs) : SendableHelper(rhs) {}
-
-Trigger& Trigger::operator=(const Trigger& rhs) {
-  SendableHelper::operator=(rhs);
-  m_sendablePressed = false;
-  return *this;
-}
-
-Trigger::Trigger(Trigger&& rhs)
-    : SendableHelper(std::move(rhs)),
-      m_sendablePressed(rhs.m_sendablePressed.load()) {
-  rhs.m_sendablePressed = false;
-}
-
-Trigger& Trigger::operator=(Trigger&& rhs) {
-  SendableHelper::operator=(std::move(rhs));
-  m_sendablePressed = rhs.m_sendablePressed.load();
-  rhs.m_sendablePressed = false;
-  return *this;
-}
-
-bool Trigger::Grab() {
-  return Get() || m_sendablePressed;
-}
-
-void Trigger::WhenActive(Command* command) {
-  auto pbs = new PressedButtonScheduler(Grab(), this, command);
-  pbs->Start();
-}
-
-void Trigger::WhileActive(Command* command) {
-  auto hbs = new HeldButtonScheduler(Grab(), this, command);
-  hbs->Start();
-}
-
-void Trigger::WhenInactive(Command* command) {
-  auto rbs = new ReleasedButtonScheduler(Grab(), this, command);
-  rbs->Start();
-}
-
-void Trigger::CancelWhenActive(Command* command) {
-  auto cbs = new CancelButtonScheduler(Grab(), this, command);
-  cbs->Start();
-}
-
-void Trigger::ToggleWhenActive(Command* command) {
-  auto tbs = new ToggleButtonScheduler(Grab(), this, command);
-  tbs->Start();
-}
-
-void Trigger::InitSendable(wpi::SendableBuilder& builder) {
-  builder.SetSmartDashboardType("Button");
-  builder.SetSafeState([=] { m_sendablePressed = false; });
-  builder.AddBooleanProperty(
-      "pressed", [=] { return Grab(); },
-      [=](bool value) { m_sendablePressed = value; });
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/Command.cpp b/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/Command.cpp
deleted file mode 100644
index 778f956..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/Command.cpp
+++ /dev/null
@@ -1,315 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/commands/Command.h"
-
-#include <typeinfo>
-
-#include <wpi/sendable/SendableBuilder.h>
-#include <wpi/sendable/SendableRegistry.h>
-
-#include "frc/Errors.h"
-#include "frc/RobotState.h"
-#include "frc/Timer.h"
-#include "frc/commands/CommandGroup.h"
-#include "frc/commands/Scheduler.h"
-#include "frc/livewindow/LiveWindow.h"
-
-using namespace frc;
-
-int Command::m_commandCounter = 0;
-
-Command::Command() : Command("", -1_s) {}
-
-Command::Command(std::string_view name) : Command(name, -1_s) {}
-
-Command::Command(units::second_t timeout) : Command("", timeout) {}
-
-Command::Command(Subsystem& subsystem) : Command("", -1_s) {
-  Requires(&subsystem);
-}
-
-Command::Command(std::string_view name, units::second_t timeout) {
-  // We use -1.0 to indicate no timeout.
-  if (timeout < 0_s && timeout != -1_s) {
-    throw FRC_MakeError(err::ParameterOutOfRange, "timeout {} < 0 s",
-                        timeout.value());
-  }
-
-  m_timeout = timeout;
-
-  // If name contains an empty string
-  if (name.empty()) {
-    wpi::SendableRegistry::Add(this,
-                               fmt::format("Command_{}", typeid(*this).name()));
-  } else {
-    wpi::SendableRegistry::Add(this, name);
-  }
-}
-
-Command::Command(std::string_view name, Subsystem& subsystem)
-    : Command(name, -1_s) {
-  Requires(&subsystem);
-}
-
-Command::Command(units::second_t timeout, Subsystem& subsystem)
-    : Command("", timeout) {
-  Requires(&subsystem);
-}
-
-Command::Command(std::string_view name, units::second_t timeout,
-                 Subsystem& subsystem)
-    : Command(name, timeout) {
-  Requires(&subsystem);
-}
-
-units::second_t Command::TimeSinceInitialized() const {
-  if (m_startTime < 0_s) {
-    return 0_s;
-  } else {
-    return Timer::GetFPGATimestamp() - m_startTime;
-  }
-}
-
-void Command::Requires(Subsystem* subsystem) {
-  if (!AssertUnlocked("Can not add new requirement to command")) {
-    return;
-  }
-
-  if (subsystem != nullptr) {
-    m_requirements.insert(subsystem);
-  } else {
-    throw FRC_MakeError(err::NullParameter, "{}", "subsystem");
-  }
-}
-
-void Command::Start() {
-  LockChanges();
-  if (m_parent != nullptr) {
-    throw FRC_MakeError(
-        err::CommandIllegalUse, "{}",
-        "Can not start a command that is part of a command group");
-  }
-
-  m_completed = false;
-  Scheduler::GetInstance()->AddCommand(this);
-}
-
-bool Command::Run() {
-  if (!m_runWhenDisabled && m_parent == nullptr && RobotState::IsDisabled()) {
-    Cancel();
-  }
-
-  if (IsCanceled()) {
-    return false;
-  }
-
-  if (!m_initialized) {
-    m_initialized = true;
-    StartTiming();
-    _Initialize();
-    Initialize();
-  }
-  _Execute();
-  Execute();
-  return !IsFinished();
-}
-
-void Command::Cancel() {
-  if (m_parent != nullptr) {
-    throw FRC_MakeError(
-        err::CommandIllegalUse, "{}",
-        "Can not cancel a command that is part of a command group");
-  }
-
-  _Cancel();
-}
-
-bool Command::IsRunning() const {
-  return m_running;
-}
-
-bool Command::IsInitialized() const {
-  return m_initialized;
-}
-
-bool Command::IsCompleted() const {
-  return m_completed;
-}
-
-bool Command::IsCanceled() const {
-  return m_canceled;
-}
-
-bool Command::IsInterruptible() const {
-  return m_interruptible;
-}
-
-void Command::SetInterruptible(bool interruptible) {
-  m_interruptible = interruptible;
-}
-
-bool Command::DoesRequire(Subsystem* system) const {
-  return m_requirements.count(system) > 0;
-}
-
-const Command::SubsystemSet& Command::GetRequirements() const {
-  return m_requirements;
-}
-
-CommandGroup* Command::GetGroup() const {
-  return m_parent;
-}
-
-void Command::SetRunWhenDisabled(bool run) {
-  m_runWhenDisabled = run;
-}
-
-bool Command::WillRunWhenDisabled() const {
-  return m_runWhenDisabled;
-}
-
-int Command::GetID() const {
-  return m_commandID;
-}
-
-void Command::SetTimeout(units::second_t timeout) {
-  if (timeout < 0_s) {
-    throw FRC_MakeError(err::ParameterOutOfRange, "timeout {} < 0 s",
-                        timeout.value());
-  } else {
-    m_timeout = timeout;
-  }
-}
-
-bool Command::IsTimedOut() const {
-  return m_timeout != -1_s && TimeSinceInitialized() >= m_timeout;
-}
-
-bool Command::AssertUnlocked(std::string_view message) {
-  if (m_locked) {
-    throw FRC_MakeError(
-        err::CommandIllegalUse,
-        "{} after being started or being added to a command group", message);
-  }
-  return true;
-}
-
-void Command::SetParent(CommandGroup* parent) {
-  if (parent == nullptr) {
-    throw FRC_MakeError(err::NullParameter, "{}", "parent");
-  } else if (m_parent != nullptr) {
-    throw FRC_MakeError(err::CommandIllegalUse, "{}",
-                        "Can not give command to a command group after "
-                        "already being put in a command group");
-  } else {
-    LockChanges();
-    m_parent = parent;
-  }
-}
-
-bool Command::IsParented() const {
-  return m_parent != nullptr;
-}
-
-void Command::ClearRequirements() {
-  m_requirements.clear();
-}
-
-void Command::Initialize() {}
-
-void Command::Execute() {}
-
-void Command::End() {}
-
-void Command::Interrupted() {
-  End();
-}
-
-void Command::_Initialize() {
-  m_completed = false;
-}
-
-void Command::_Interrupted() {
-  m_completed = true;
-}
-
-void Command::_Execute() {}
-
-void Command::_End() {
-  m_completed = true;
-}
-
-void Command::_Cancel() {
-  if (IsRunning()) {
-    m_canceled = true;
-  }
-}
-
-void Command::LockChanges() {
-  m_locked = true;
-}
-
-void Command::Removed() {
-  if (m_initialized) {
-    if (IsCanceled()) {
-      Interrupted();
-      _Interrupted();
-    } else {
-      End();
-      _End();
-    }
-  }
-  m_initialized = false;
-  m_canceled = false;
-  m_running = false;
-  m_completed = true;
-}
-
-void Command::StartRunning() {
-  m_running = true;
-  m_startTime = -1_s;
-  m_completed = false;
-}
-
-void Command::StartTiming() {
-  m_startTime = Timer::GetFPGATimestamp();
-}
-
-std::string Command::GetName() const {
-  return wpi::SendableRegistry::GetName(this);
-}
-
-void Command::SetName(std::string_view name) {
-  wpi::SendableRegistry::SetName(this, name);
-}
-
-std::string Command::GetSubsystem() const {
-  return wpi::SendableRegistry::GetSubsystem(this);
-}
-
-void Command::SetSubsystem(std::string_view name) {
-  wpi::SendableRegistry::SetSubsystem(this, name);
-}
-
-void Command::InitSendable(wpi::SendableBuilder& builder) {
-  builder.SetSmartDashboardType("Command");
-  builder.AddStringProperty(
-      ".name", [=] { return wpi::SendableRegistry::GetName(this); }, nullptr);
-  builder.AddBooleanProperty(
-      "running", [=] { return IsRunning(); },
-      [=](bool value) {
-        if (value) {
-          if (!IsRunning()) {
-            Start();
-          }
-        } else {
-          if (IsRunning()) {
-            Cancel();
-          }
-        }
-      });
-  builder.AddBooleanProperty(
-      ".isParented", [=] { return IsParented(); }, nullptr);
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/CommandGroup.cpp b/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/CommandGroup.cpp
deleted file mode 100644
index 977795d..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/CommandGroup.cpp
+++ /dev/null
@@ -1,269 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/commands/CommandGroup.h"
-
-#include "frc/Errors.h"
-
-using namespace frc;
-
-CommandGroup::CommandGroup(std::string_view name) : Command(name) {}
-
-void CommandGroup::AddSequential(Command* command) {
-  if (!command) {
-    throw FRC_MakeError(err::NullParameter, "{}", "command");
-  }
-  if (!AssertUnlocked("Cannot add new command to command group")) {
-    return;
-  }
-
-  m_commands.emplace_back(command, CommandGroupEntry::kSequence_InSequence);
-
-  command->SetParent(this);
-
-  // Iterate through command->GetRequirements() and call Requires() on each
-  // required subsystem
-  for (auto&& requirement : command->GetRequirements()) {
-    Requires(requirement);
-  }
-}
-
-void CommandGroup::AddSequential(Command* command, units::second_t timeout) {
-  if (!command) {
-    throw FRC_MakeError(err::NullParameter, "{}", "command");
-  }
-  if (!AssertUnlocked("Cannot add new command to command group")) {
-    return;
-  }
-  if (timeout < 0_s) {
-    throw FRC_MakeError(err::ParameterOutOfRange, "timeout {} < 0 s",
-                        timeout.value());
-  }
-
-  m_commands.emplace_back(command, CommandGroupEntry::kSequence_InSequence,
-                          timeout);
-
-  command->SetParent(this);
-
-  // Iterate through command->GetRequirements() and call Requires() on each
-  // required subsystem
-  for (auto&& requirement : command->GetRequirements()) {
-    Requires(requirement);
-  }
-}
-
-void CommandGroup::AddParallel(Command* command) {
-  if (!command) {
-    throw FRC_MakeError(err::NullParameter, "{}", "command");
-    return;
-  }
-  if (!AssertUnlocked("Cannot add new command to command group")) {
-    return;
-  }
-
-  m_commands.emplace_back(command, CommandGroupEntry::kSequence_BranchChild);
-
-  command->SetParent(this);
-
-  // Iterate through command->GetRequirements() and call Requires() on each
-  // required subsystem
-  for (auto&& requirement : command->GetRequirements()) {
-    Requires(requirement);
-  }
-}
-
-void CommandGroup::AddParallel(Command* command, units::second_t timeout) {
-  if (!command) {
-    throw FRC_MakeError(err::NullParameter, "{}", "command");
-  }
-  if (!AssertUnlocked("Cannot add new command to command group")) {
-    return;
-  }
-  if (timeout < 0_s) {
-    throw FRC_MakeError(err::ParameterOutOfRange, "timeout {} < 0 s",
-                        timeout.value());
-  }
-
-  m_commands.emplace_back(command, CommandGroupEntry::kSequence_BranchChild,
-                          timeout);
-
-  command->SetParent(this);
-
-  // Iterate through command->GetRequirements() and call Requires() on each
-  // required subsystem
-  for (auto&& requirement : command->GetRequirements()) {
-    Requires(requirement);
-  }
-}
-
-bool CommandGroup::IsInterruptible() const {
-  if (!Command::IsInterruptible()) {
-    return false;
-  }
-
-  if (m_currentCommandIndex != -1 &&
-      static_cast<size_t>(m_currentCommandIndex) < m_commands.size()) {
-    Command* cmd = m_commands[m_currentCommandIndex].m_command;
-    if (!cmd->IsInterruptible()) {
-      return false;
-    }
-  }
-
-  for (const auto& child : m_children) {
-    if (!child->m_command->IsInterruptible()) {
-      return false;
-    }
-  }
-
-  return true;
-}
-
-int CommandGroup::GetSize() const {
-  return m_children.size();
-}
-
-void CommandGroup::Initialize() {}
-
-void CommandGroup::Execute() {}
-
-bool CommandGroup::IsFinished() {
-  return static_cast<size_t>(m_currentCommandIndex) >= m_commands.size() &&
-         m_children.empty();
-}
-
-void CommandGroup::End() {}
-
-void CommandGroup::Interrupted() {}
-
-void CommandGroup::_Initialize() {
-  m_currentCommandIndex = -1;
-}
-
-void CommandGroup::_Execute() {
-  CommandGroupEntry* entry;
-  Command* cmd = nullptr;
-  bool firstRun = false;
-
-  if (m_currentCommandIndex == -1) {
-    firstRun = true;
-    m_currentCommandIndex = 0;
-  }
-
-  // While there are still commands in this group to run
-  while (static_cast<size_t>(m_currentCommandIndex) < m_commands.size()) {
-    // If a command is prepared to run
-    if (cmd != nullptr) {
-      // If command timed out, cancel it so it's removed from the Scheduler
-      if (entry->IsTimedOut()) {
-        cmd->_Cancel();
-      }
-
-      // If command finished or was canceled, remove it from Scheduler
-      if (cmd->Run()) {
-        break;
-      } else {
-        cmd->Removed();
-
-        // Advance to next command in group
-        m_currentCommandIndex++;
-        firstRun = true;
-        cmd = nullptr;
-        continue;
-      }
-    }
-
-    entry = &m_commands[m_currentCommandIndex];
-    cmd = nullptr;
-
-    switch (entry->m_state) {
-      case CommandGroupEntry::kSequence_InSequence:
-        cmd = entry->m_command;
-        if (firstRun) {
-          cmd->StartRunning();
-          CancelConflicts(cmd);
-          firstRun = false;
-        }
-        break;
-
-      case CommandGroupEntry::kSequence_BranchPeer:
-        // Start executing a parallel command and advance to next entry in group
-        m_currentCommandIndex++;
-        entry->m_command->Start();
-        break;
-
-      case CommandGroupEntry::kSequence_BranchChild:
-        m_currentCommandIndex++;
-
-        /* Causes scheduler to skip children of current command which require
-         * the same subsystems as it
-         */
-        CancelConflicts(entry->m_command);
-        entry->m_command->StartRunning();
-
-        // Add current command entry to list of children of this group
-        m_children.push_back(entry);
-        break;
-    }
-  }
-
-  // Run Children
-  for (auto& entry : m_children) {
-    auto child = entry->m_command;
-    if (entry->IsTimedOut()) {
-      child->_Cancel();
-    }
-
-    // If child finished or was canceled, set it to nullptr. nullptr entries
-    // are removed later.
-    if (!child->Run()) {
-      child->Removed();
-      entry = nullptr;
-    }
-  }
-
-  m_children.erase(std::remove(m_children.begin(), m_children.end(), nullptr),
-                   m_children.end());
-}
-
-void CommandGroup::_End() {
-  // Theoretically, we don't have to check this, but we do if teams override the
-  // IsFinished method
-  if (m_currentCommandIndex != -1 &&
-      static_cast<size_t>(m_currentCommandIndex) < m_commands.size()) {
-    Command* cmd = m_commands[m_currentCommandIndex].m_command;
-    cmd->_Cancel();
-    cmd->Removed();
-  }
-
-  for (auto& child : m_children) {
-    Command* cmd = child->m_command;
-    cmd->_Cancel();
-    cmd->Removed();
-  }
-  m_children.clear();
-}
-
-void CommandGroup::_Interrupted() {
-  _End();
-}
-
-void CommandGroup::CancelConflicts(Command* command) {
-  for (auto childIter = m_children.begin(); childIter != m_children.end();) {
-    Command* child = (*childIter)->m_command;
-    bool erased = false;
-
-    for (auto&& requirement : command->GetRequirements()) {
-      if (child->DoesRequire(requirement)) {
-        child->_Cancel();
-        child->Removed();
-        childIter = m_children.erase(childIter);
-        erased = true;
-        break;
-      }
-    }
-    if (!erased) {
-      childIter++;
-    }
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/CommandGroupEntry.cpp b/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/CommandGroupEntry.cpp
deleted file mode 100644
index 1e6f8c7..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/CommandGroupEntry.cpp
+++ /dev/null
@@ -1,24 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/commands/CommandGroupEntry.h"
-
-#include "frc/commands/Command.h"
-
-using namespace frc;
-
-CommandGroupEntry::CommandGroupEntry(Command* command, Sequence state,
-                                     units::second_t timeout)
-    : m_timeout(timeout), m_command(command), m_state(state) {}
-
-bool CommandGroupEntry::IsTimedOut() const {
-  if (m_timeout < 0_s) {
-    return false;
-  }
-  auto time = m_command->TimeSinceInitialized();
-  if (time == 0_s) {
-    return false;
-  }
-  return time >= m_timeout;
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/ConditionalCommand.cpp b/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/ConditionalCommand.cpp
deleted file mode 100644
index e2867b5..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/ConditionalCommand.cpp
+++ /dev/null
@@ -1,79 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/commands/ConditionalCommand.h"
-
-#include "frc/commands/Scheduler.h"
-
-using namespace frc;
-
-static void RequireAll(Command& command, Command* onTrue, Command* onFalse) {
-  if (onTrue != nullptr) {
-    for (auto requirement : onTrue->GetRequirements()) {
-      command.Requires(requirement);
-    }
-  }
-  if (onFalse != nullptr) {
-    for (auto requirement : onFalse->GetRequirements()) {
-      command.Requires(requirement);
-    }
-  }
-}
-
-ConditionalCommand::ConditionalCommand(Command* onTrue, Command* onFalse) {
-  m_onTrue = onTrue;
-  m_onFalse = onFalse;
-
-  RequireAll(*this, onTrue, onFalse);
-}
-
-ConditionalCommand::ConditionalCommand(std::string_view name, Command* onTrue,
-                                       Command* onFalse)
-    : Command(name) {
-  m_onTrue = onTrue;
-  m_onFalse = onFalse;
-
-  RequireAll(*this, onTrue, onFalse);
-}
-
-void ConditionalCommand::_Initialize() {
-  if (Condition()) {
-    m_chosenCommand = m_onTrue;
-  } else {
-    m_chosenCommand = m_onFalse;
-  }
-
-  if (m_chosenCommand != nullptr) {
-    // This is a hack to make canceling the chosen command inside a
-    // CommandGroup work properly
-    m_chosenCommand->ClearRequirements();
-
-    m_chosenCommand->Start();
-  }
-  Command::_Initialize();
-}
-
-void ConditionalCommand::_Cancel() {
-  if (m_chosenCommand != nullptr && m_chosenCommand->IsRunning()) {
-    m_chosenCommand->Cancel();
-  }
-
-  Command::_Cancel();
-}
-
-bool ConditionalCommand::IsFinished() {
-  if (m_chosenCommand != nullptr) {
-    return m_chosenCommand->IsCompleted();
-  } else {
-    return true;
-  }
-}
-
-void ConditionalCommand::_Interrupted() {
-  if (m_chosenCommand != nullptr && m_chosenCommand->IsRunning()) {
-    m_chosenCommand->Cancel();
-  }
-
-  Command::_Interrupted();
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/InstantCommand.cpp b/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/InstantCommand.cpp
deleted file mode 100644
index d8f3309..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/InstantCommand.cpp
+++ /dev/null
@@ -1,47 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/commands/InstantCommand.h"
-
-#include <utility>
-
-using namespace frc;
-
-InstantCommand::InstantCommand(std::string_view name) : Command(name) {}
-
-InstantCommand::InstantCommand(Subsystem& subsystem) : Command(subsystem) {}
-
-InstantCommand::InstantCommand(std::string_view name, Subsystem& subsystem)
-    : Command(name, subsystem) {}
-
-InstantCommand::InstantCommand(std::function<void()> func)
-    : m_func(std::move(func)) {}
-
-InstantCommand::InstantCommand(Subsystem& subsystem, std::function<void()> func)
-    : InstantCommand(subsystem) {
-  m_func = func;
-}
-
-InstantCommand::InstantCommand(std::string_view name,
-                               std::function<void()> func)
-    : InstantCommand(name) {
-  m_func = func;
-}
-
-InstantCommand::InstantCommand(std::string_view name, Subsystem& subsystem,
-                               std::function<void()> func)
-    : InstantCommand(name, subsystem) {
-  m_func = func;
-}
-
-void InstantCommand::_Initialize() {
-  Command::_Initialize();
-  if (m_func) {
-    m_func();
-  }
-}
-
-bool InstantCommand::IsFinished() {
-  return true;
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/PIDCommand.cpp b/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/PIDCommand.cpp
deleted file mode 100644
index e71556a..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/PIDCommand.cpp
+++ /dev/null
@@ -1,119 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/commands/PIDCommand.h"
-
-#include <wpi/sendable/SendableBuilder.h>
-
-using namespace frc;
-
-PIDCommand::PIDCommand(std::string_view name, double p, double i, double d,
-                       double f, double period)
-    : Command(name) {
-  m_controller = std::make_shared<PIDController>(p, i, d, this, this, period);
-}
-
-PIDCommand::PIDCommand(double p, double i, double d, double f, double period) {
-  m_controller =
-      std::make_shared<PIDController>(p, i, d, f, this, this, period);
-}
-
-PIDCommand::PIDCommand(std::string_view name, double p, double i, double d)
-    : Command(name) {
-  m_controller = std::make_shared<PIDController>(p, i, d, this, this);
-}
-
-PIDCommand::PIDCommand(std::string_view name, double p, double i, double d,
-                       double period)
-    : Command(name) {
-  m_controller = std::make_shared<PIDController>(p, i, d, this, this, period);
-}
-
-PIDCommand::PIDCommand(double p, double i, double d) {
-  m_controller = std::make_shared<PIDController>(p, i, d, this, this);
-}
-
-PIDCommand::PIDCommand(double p, double i, double d, double period) {
-  m_controller = std::make_shared<PIDController>(p, i, d, this, this, period);
-}
-
-PIDCommand::PIDCommand(std::string_view name, double p, double i, double d,
-                       double f, double period, Subsystem& subsystem)
-    : Command(name, subsystem) {
-  m_controller = std::make_shared<PIDController>(p, i, d, this, this, period);
-}
-
-PIDCommand::PIDCommand(double p, double i, double d, double f, double period,
-                       Subsystem& subsystem)
-    : Command(subsystem) {
-  m_controller =
-      std::make_shared<PIDController>(p, i, d, f, this, this, period);
-}
-
-PIDCommand::PIDCommand(std::string_view name, double p, double i, double d,
-                       Subsystem& subsystem)
-    : Command(name, subsystem) {
-  m_controller = std::make_shared<PIDController>(p, i, d, this, this);
-}
-
-PIDCommand::PIDCommand(std::string_view name, double p, double i, double d,
-                       double period, Subsystem& subsystem)
-    : Command(name, subsystem) {
-  m_controller = std::make_shared<PIDController>(p, i, d, this, this, period);
-}
-
-PIDCommand::PIDCommand(double p, double i, double d, Subsystem& subsystem) {
-  m_controller = std::make_shared<PIDController>(p, i, d, this, this);
-}
-
-PIDCommand::PIDCommand(double p, double i, double d, double period,
-                       Subsystem& subsystem) {
-  m_controller = std::make_shared<PIDController>(p, i, d, this, this, period);
-}
-
-void PIDCommand::_Initialize() {
-  m_controller->Enable();
-}
-
-void PIDCommand::_End() {
-  m_controller->Disable();
-}
-
-void PIDCommand::_Interrupted() {
-  _End();
-}
-
-void PIDCommand::SetSetpointRelative(double deltaSetpoint) {
-  SetSetpoint(GetSetpoint() + deltaSetpoint);
-}
-
-void PIDCommand::PIDWrite(double output) {
-  UsePIDOutput(output);
-}
-
-double PIDCommand::PIDGet() {
-  return ReturnPIDInput();
-}
-
-std::shared_ptr<PIDController> PIDCommand::GetPIDController() const {
-  return m_controller;
-}
-
-void PIDCommand::SetSetpoint(double setpoint) {
-  m_controller->SetSetpoint(setpoint);
-}
-
-double PIDCommand::GetSetpoint() const {
-  return m_controller->GetSetpoint();
-}
-
-double PIDCommand::GetPosition() {
-  return ReturnPIDInput();
-}
-
-void PIDCommand::InitSendable(wpi::SendableBuilder& builder) {
-  m_controller->InitSendable(builder);
-  Command::InitSendable(builder);
-  builder.SetSmartDashboardType("PIDCommand");
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/PIDSubsystem.cpp b/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/PIDSubsystem.cpp
deleted file mode 100644
index f76288b..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/PIDSubsystem.cpp
+++ /dev/null
@@ -1,110 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/commands/PIDSubsystem.h"
-
-#include "frc/PIDController.h"
-
-using namespace frc;
-
-PIDSubsystem::PIDSubsystem(std::string_view name, double p, double i, double d)
-    : Subsystem(name) {
-  m_controller = std::make_shared<PIDController>(p, i, d, this, this);
-  AddChild("PIDController", m_controller);
-}
-
-PIDSubsystem::PIDSubsystem(std::string_view name, double p, double i, double d,
-                           double f)
-    : Subsystem(name) {
-  m_controller = std::make_shared<PIDController>(p, i, d, f, this, this);
-  AddChild("PIDController", m_controller);
-}
-
-PIDSubsystem::PIDSubsystem(std::string_view name, double p, double i, double d,
-                           double f, double period)
-    : Subsystem(name) {
-  m_controller =
-      std::make_shared<PIDController>(p, i, d, f, this, this, period);
-  AddChild("PIDController", m_controller);
-}
-
-PIDSubsystem::PIDSubsystem(double p, double i, double d)
-    : Subsystem("PIDSubsystem") {
-  m_controller = std::make_shared<PIDController>(p, i, d, this, this);
-  AddChild("PIDController", m_controller);
-}
-
-PIDSubsystem::PIDSubsystem(double p, double i, double d, double f)
-    : Subsystem("PIDSubsystem") {
-  m_controller = std::make_shared<PIDController>(p, i, d, f, this, this);
-  AddChild("PIDController", m_controller);
-}
-
-PIDSubsystem::PIDSubsystem(double p, double i, double d, double f,
-                           double period)
-    : Subsystem("PIDSubsystem") {
-  m_controller =
-      std::make_shared<PIDController>(p, i, d, f, this, this, period);
-  AddChild("PIDController", m_controller);
-}
-
-void PIDSubsystem::Enable() {
-  m_controller->Enable();
-}
-
-void PIDSubsystem::Disable() {
-  m_controller->Disable();
-}
-
-void PIDSubsystem::PIDWrite(double output) {
-  UsePIDOutput(output);
-}
-
-double PIDSubsystem::PIDGet() {
-  return ReturnPIDInput();
-}
-
-void PIDSubsystem::SetSetpoint(double setpoint) {
-  m_controller->SetSetpoint(setpoint);
-}
-
-void PIDSubsystem::SetSetpointRelative(double deltaSetpoint) {
-  SetSetpoint(GetSetpoint() + deltaSetpoint);
-}
-
-void PIDSubsystem::SetInputRange(double minimumInput, double maximumInput) {
-  m_controller->SetInputRange(minimumInput, maximumInput);
-}
-
-void PIDSubsystem::SetOutputRange(double minimumOutput, double maximumOutput) {
-  m_controller->SetOutputRange(minimumOutput, maximumOutput);
-}
-
-double PIDSubsystem::GetSetpoint() {
-  return m_controller->GetSetpoint();
-}
-
-double PIDSubsystem::GetPosition() {
-  return ReturnPIDInput();
-}
-
-double PIDSubsystem::GetRate() {
-  return ReturnPIDInput();
-}
-
-void PIDSubsystem::SetAbsoluteTolerance(double absValue) {
-  m_controller->SetAbsoluteTolerance(absValue);
-}
-
-void PIDSubsystem::SetPercentTolerance(double percent) {
-  m_controller->SetPercentTolerance(percent);
-}
-
-bool PIDSubsystem::OnTarget() const {
-  return m_controller->OnTarget();
-}
-
-std::shared_ptr<PIDController> PIDSubsystem::GetPIDController() {
-  return m_controller;
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/PrintCommand.cpp b/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/PrintCommand.cpp
deleted file mode 100644
index ca8f49a..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/PrintCommand.cpp
+++ /dev/null
@@ -1,18 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/commands/PrintCommand.h"
-
-#include <fmt/format.h>
-
-using namespace frc;
-
-PrintCommand::PrintCommand(std::string_view message)
-    : InstantCommand(fmt::format("Print \"{}\"", message)) {
-  m_message = message;
-}
-
-void PrintCommand::Initialize() {
-  fmt::print("{}\n", m_message);
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/Scheduler.cpp b/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/Scheduler.cpp
deleted file mode 100644
index 701162c..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/Scheduler.cpp
+++ /dev/null
@@ -1,262 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/commands/Scheduler.h"
-
-#include <algorithm>
-#include <set>
-#include <string>
-#include <vector>
-
-#include <hal/FRCUsageReporting.h>
-#include <networktables/NTSendableBuilder.h>
-#include <networktables/NetworkTableEntry.h>
-#include <wpi/mutex.h>
-#include <wpi/sendable/SendableRegistry.h>
-
-#include "frc/Errors.h"
-#include "frc/buttons/ButtonScheduler.h"
-#include "frc/commands/Command.h"
-#include "frc/commands/Subsystem.h"
-#include "frc/livewindow/LiveWindow.h"
-
-using namespace frc;
-
-struct Scheduler::Impl {
-  void Remove(Command* command);
-  void ProcessCommandAddition(Command* command);
-
-  using SubsystemSet = std::set<Subsystem*>;
-  SubsystemSet subsystems;
-  wpi::mutex buttonsMutex;
-  using ButtonVector = std::vector<std::unique_ptr<ButtonScheduler>>;
-  ButtonVector buttons;
-  using CommandVector = std::vector<Command*>;
-  wpi::mutex additionsMutex;
-  CommandVector additions;
-  using CommandSet = std::set<Command*>;
-  CommandSet commands;
-  bool adding = false;
-  bool enabled = true;
-  std::vector<std::string> commandsBuf;
-  std::vector<double> idsBuf;
-  bool runningCommandsChanged = false;
-};
-
-Scheduler* Scheduler::GetInstance() {
-  static Scheduler instance;
-  return &instance;
-}
-
-void Scheduler::AddCommand(Command* command) {
-  std::scoped_lock lock(m_impl->additionsMutex);
-  if (std::find(m_impl->additions.begin(), m_impl->additions.end(), command) !=
-      m_impl->additions.end()) {
-    return;
-  }
-  m_impl->additions.push_back(command);
-}
-
-void Scheduler::AddButton(ButtonScheduler* button) {
-  std::scoped_lock lock(m_impl->buttonsMutex);
-  m_impl->buttons.emplace_back(button);
-}
-
-void Scheduler::RegisterSubsystem(Subsystem* subsystem) {
-  if (!subsystem) {
-    throw FRC_MakeError(err::NullParameter, "{}", "subsystem");
-  }
-  m_impl->subsystems.insert(subsystem);
-}
-
-void Scheduler::Run() {
-  // Get button input (going backwards preserves button priority)
-  {
-    if (!m_impl->enabled) {
-      return;
-    }
-
-    std::scoped_lock lock(m_impl->buttonsMutex);
-    for (auto& button : m_impl->buttons) {
-      button->Execute();
-    }
-  }
-
-  // Call every subsystem's periodic method
-  for (auto& subsystem : m_impl->subsystems) {
-    subsystem->Periodic();
-  }
-
-  m_impl->runningCommandsChanged = false;
-
-  // Loop through the commands
-  for (auto cmdIter = m_impl->commands.begin();
-       cmdIter != m_impl->commands.end();) {
-    Command* command = *cmdIter;
-    // Increment before potentially removing to keep the iterator valid
-    ++cmdIter;
-    if (!command->Run()) {
-      Remove(command);
-      m_impl->runningCommandsChanged = true;
-    }
-  }
-
-  // Add the new things
-  {
-    std::scoped_lock lock(m_impl->additionsMutex);
-    for (auto& addition : m_impl->additions) {
-      // Check to make sure no adding during adding
-      if (m_impl->adding) {
-        FRC_ReportError(warn::IncompatibleState, "{}",
-                        "Can not start command from cancel method");
-      } else {
-        m_impl->ProcessCommandAddition(addition);
-      }
-    }
-    m_impl->additions.clear();
-  }
-
-  // Add in the defaults
-  for (auto& subsystem : m_impl->subsystems) {
-    if (subsystem->GetCurrentCommand() == nullptr) {
-      if (m_impl->adding) {
-        FRC_ReportError(warn::IncompatibleState, "{}",
-                        "Can not start command from cancel method");
-      } else {
-        m_impl->ProcessCommandAddition(subsystem->GetDefaultCommand());
-      }
-    }
-    subsystem->ConfirmCommand();
-  }
-}
-
-void Scheduler::Remove(Command* command) {
-  if (!command) {
-    throw FRC_MakeError(err::NullParameter, "{}", "command");
-  }
-
-  m_impl->Remove(command);
-}
-
-void Scheduler::RemoveAll() {
-  while (m_impl->commands.size() > 0) {
-    Remove(*m_impl->commands.begin());
-  }
-}
-
-void Scheduler::ResetAll() {
-  RemoveAll();
-  m_impl->subsystems.clear();
-  m_impl->buttons.clear();
-  m_impl->additions.clear();
-  m_impl->commands.clear();
-}
-
-void Scheduler::SetEnabled(bool enabled) {
-  m_impl->enabled = enabled;
-}
-
-void Scheduler::InitSendable(nt::NTSendableBuilder& builder) {
-  builder.SetSmartDashboardType("Scheduler");
-  auto namesEntry = builder.GetEntry("Names");
-  auto idsEntry = builder.GetEntry("Ids");
-  auto cancelEntry = builder.GetEntry("Cancel");
-  builder.SetUpdateTable([=] {
-    // Get the list of possible commands to cancel
-    auto new_toCancel = cancelEntry.GetValue();
-    wpi::span<const double> toCancel;
-    if (new_toCancel) {
-      toCancel = new_toCancel->GetDoubleArray();
-    }
-
-    // Cancel commands whose cancel buttons were pressed on the SmartDashboard
-    if (!toCancel.empty()) {
-      for (auto& command : m_impl->commands) {
-        for (const auto& canceled : toCancel) {
-          if (command->GetID() == canceled) {
-            command->Cancel();
-          }
-        }
-      }
-      nt::NetworkTableEntry(cancelEntry).SetDoubleArray({});
-    }
-
-    // Set the running commands
-    if (m_impl->runningCommandsChanged) {
-      m_impl->commandsBuf.resize(0);
-      m_impl->idsBuf.resize(0);
-      for (const auto& command : m_impl->commands) {
-        m_impl->commandsBuf.emplace_back(
-            wpi::SendableRegistry::GetName(command));
-        m_impl->idsBuf.emplace_back(command->GetID());
-      }
-      nt::NetworkTableEntry(namesEntry).SetStringArray(m_impl->commandsBuf);
-      nt::NetworkTableEntry(idsEntry).SetDoubleArray(m_impl->idsBuf);
-    }
-  });
-}
-
-Scheduler::Scheduler() : m_impl(new Impl) {
-  HAL_Report(HALUsageReporting::kResourceType_Command,
-             HALUsageReporting::kCommand_Scheduler);
-  wpi::SendableRegistry::AddLW(this, "Scheduler");
-  frc::LiveWindow::SetEnabledCallback([this] {
-    this->SetEnabled(false);
-    this->RemoveAll();
-  });
-  frc::LiveWindow::SetDisabledCallback([this] { this->SetEnabled(true); });
-}
-
-Scheduler::~Scheduler() {
-  wpi::SendableRegistry::Remove(this);
-  frc::LiveWindow::SetEnabledCallback(nullptr);
-  frc::LiveWindow::SetDisabledCallback(nullptr);
-}
-
-void Scheduler::Impl::Remove(Command* command) {
-  if (!commands.erase(command)) {
-    return;
-  }
-
-  for (auto&& requirement : command->GetRequirements()) {
-    requirement->SetCurrentCommand(nullptr);
-  }
-
-  command->Removed();
-}
-
-void Scheduler::Impl::ProcessCommandAddition(Command* command) {
-  if (command == nullptr) {
-    return;
-  }
-
-  // Only add if not already in
-  auto found = commands.find(command);
-  if (found == commands.end()) {
-    // Check that the requirements can be had
-    const auto& requirements = command->GetRequirements();
-    for (const auto requirement : requirements) {
-      if (requirement->GetCurrentCommand() != nullptr &&
-          !requirement->GetCurrentCommand()->IsInterruptible()) {
-        return;
-      }
-    }
-
-    // Give it the requirements
-    adding = true;
-    for (auto&& requirement : requirements) {
-      if (requirement->GetCurrentCommand() != nullptr) {
-        requirement->GetCurrentCommand()->Cancel();
-        Remove(requirement->GetCurrentCommand());
-      }
-      requirement->SetCurrentCommand(command);
-    }
-    adding = false;
-
-    commands.insert(command);
-
-    command->StartRunning();
-    runningCommandsChanged = true;
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/StartCommand.cpp b/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/StartCommand.cpp
deleted file mode 100644
index 05dc079..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/StartCommand.cpp
+++ /dev/null
@@ -1,16 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/commands/StartCommand.h"
-
-using namespace frc;
-
-StartCommand::StartCommand(Command* commandToStart)
-    : InstantCommand("StartCommand") {
-  m_commandToFork = commandToStart;
-}
-
-void StartCommand::Initialize() {
-  m_commandToFork->Start();
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/Subsystem.cpp b/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/Subsystem.cpp
deleted file mode 100644
index 824872f..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/Subsystem.cpp
+++ /dev/null
@@ -1,137 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/commands/Subsystem.h"
-
-#include <wpi/sendable/SendableBuilder.h>
-#include <wpi/sendable/SendableRegistry.h>
-
-#include "frc/Errors.h"
-#include "frc/commands/Command.h"
-#include "frc/commands/Scheduler.h"
-#include "frc/livewindow/LiveWindow.h"
-
-using namespace frc;
-
-Subsystem::Subsystem(std::string_view name) {
-  wpi::SendableRegistry::AddLW(this, name, name);
-  Scheduler::GetInstance()->RegisterSubsystem(this);
-}
-
-void Subsystem::SetDefaultCommand(Command* command) {
-  if (command == nullptr) {
-    m_defaultCommand = nullptr;
-  } else {
-    const auto& reqs = command->GetRequirements();
-    if (std::find(reqs.begin(), reqs.end(), this) == reqs.end()) {
-      throw FRC_MakeError(err::CommandIllegalUse, "{}",
-                          "A default command must require the subsystem");
-    }
-
-    m_defaultCommand = command;
-  }
-}
-
-Command* Subsystem::GetDefaultCommand() {
-  if (!m_initializedDefaultCommand) {
-    m_initializedDefaultCommand = true;
-    InitDefaultCommand();
-  }
-  return m_defaultCommand;
-}
-
-std::string Subsystem::GetDefaultCommandName() {
-  Command* defaultCommand = GetDefaultCommand();
-  if (defaultCommand) {
-    return wpi::SendableRegistry::GetName(defaultCommand);
-  } else {
-    return {};
-  }
-}
-
-void Subsystem::SetCurrentCommand(Command* command) {
-  m_currentCommand = command;
-  m_currentCommandChanged = true;
-}
-
-Command* Subsystem::GetCurrentCommand() const {
-  return m_currentCommand;
-}
-
-std::string Subsystem::GetCurrentCommandName() const {
-  Command* currentCommand = GetCurrentCommand();
-  if (currentCommand) {
-    return wpi::SendableRegistry::GetName(currentCommand);
-  } else {
-    return {};
-  }
-}
-
-void Subsystem::Periodic() {}
-
-void Subsystem::InitDefaultCommand() {}
-
-std::string Subsystem::GetName() const {
-  return wpi::SendableRegistry::GetName(this);
-}
-
-void Subsystem::SetName(std::string_view name) {
-  wpi::SendableRegistry::SetName(this, name);
-}
-
-std::string Subsystem::GetSubsystem() const {
-  return wpi::SendableRegistry::GetSubsystem(this);
-}
-
-void Subsystem::SetSubsystem(std::string_view name) {
-  wpi::SendableRegistry::SetSubsystem(this, name);
-}
-
-void Subsystem::AddChild(std::string_view name,
-                         std::shared_ptr<Sendable> child) {
-  AddChild(name, *child);
-}
-
-void Subsystem::AddChild(std::string_view name, wpi::Sendable* child) {
-  AddChild(name, *child);
-}
-
-void Subsystem::AddChild(std::string_view name, wpi::Sendable& child) {
-  wpi::SendableRegistry::AddLW(&child,
-                               wpi::SendableRegistry::GetSubsystem(this), name);
-}
-
-void Subsystem::AddChild(std::shared_ptr<wpi::Sendable> child) {
-  AddChild(*child);
-}
-
-void Subsystem::AddChild(wpi::Sendable* child) {
-  AddChild(*child);
-}
-
-void Subsystem::AddChild(wpi::Sendable& child) {
-  wpi::SendableRegistry::SetSubsystem(
-      &child, wpi::SendableRegistry::GetSubsystem(this));
-  wpi::SendableRegistry::EnableLiveWindow(&child);
-}
-
-void Subsystem::ConfirmCommand() {
-  if (m_currentCommandChanged) {
-    m_currentCommandChanged = false;
-  }
-}
-
-void Subsystem::InitSendable(wpi::SendableBuilder& builder) {
-  builder.SetSmartDashboardType("Subsystem");
-
-  builder.AddBooleanProperty(
-      ".hasDefault", [=] { return m_defaultCommand != nullptr; }, nullptr);
-  builder.AddStringProperty(
-      ".default", [=] { return GetDefaultCommandName(); }, nullptr);
-
-  builder.AddBooleanProperty(
-      ".hasCommand", [=] { return m_currentCommand != nullptr; }, nullptr);
-  builder.AddStringProperty(
-      ".command", [=] { return GetCurrentCommandName(); }, nullptr);
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/TimedCommand.cpp b/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/TimedCommand.cpp
deleted file mode 100644
index 5c2ccd4..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/TimedCommand.cpp
+++ /dev/null
@@ -1,23 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/commands/TimedCommand.h"
-
-using namespace frc;
-
-TimedCommand::TimedCommand(std::string_view name, units::second_t timeout)
-    : Command(name, timeout) {}
-
-TimedCommand::TimedCommand(units::second_t timeout) : Command(timeout) {}
-
-TimedCommand::TimedCommand(std::string_view name, units::second_t timeout,
-                           Subsystem& subsystem)
-    : Command(name, timeout, subsystem) {}
-
-TimedCommand::TimedCommand(units::second_t timeout, Subsystem& subsystem)
-    : Command(timeout, subsystem) {}
-
-bool TimedCommand::IsFinished() {
-  return IsTimedOut();
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/WaitCommand.cpp b/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/WaitCommand.cpp
deleted file mode 100644
index b4d44e0..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/WaitCommand.cpp
+++ /dev/null
@@ -1,15 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/commands/WaitCommand.h"
-
-#include <fmt/format.h>
-
-using namespace frc;
-
-WaitCommand::WaitCommand(units::second_t timeout)
-    : TimedCommand(fmt::format("Wait({})", timeout.value()), timeout) {}
-
-WaitCommand::WaitCommand(std::string_view name, units::second_t timeout)
-    : TimedCommand(name, timeout) {}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/WaitForChildren.cpp b/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/WaitForChildren.cpp
deleted file mode 100644
index e02a630..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/WaitForChildren.cpp
+++ /dev/null
@@ -1,19 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/commands/WaitForChildren.h"
-
-#include "frc/commands/CommandGroup.h"
-
-using namespace frc;
-
-WaitForChildren::WaitForChildren(units::second_t timeout)
-    : Command("WaitForChildren", timeout) {}
-
-WaitForChildren::WaitForChildren(std::string_view name, units::second_t timeout)
-    : Command(name, timeout) {}
-
-bool WaitForChildren::IsFinished() {
-  return GetGroup() == nullptr || GetGroup()->GetSize() == 0;
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/WaitUntilCommand.cpp b/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/WaitUntilCommand.cpp
deleted file mode 100644
index bb127b1..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/commands/WaitUntilCommand.cpp
+++ /dev/null
@@ -1,23 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/commands/WaitUntilCommand.h"
-
-#include "frc/Timer.h"
-
-using namespace frc;
-
-WaitUntilCommand::WaitUntilCommand(units::second_t time)
-    : Command("WaitUntilCommand", time) {
-  m_time = time;
-}
-
-WaitUntilCommand::WaitUntilCommand(std::string_view name, units::second_t time)
-    : Command(name, time) {
-  m_time = time;
-}
-
-bool WaitUntilCommand::IsFinished() {
-  return Timer::GetMatchTime() >= m_time;
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDAnalogAccelerometer.cpp b/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDAnalogAccelerometer.cpp
deleted file mode 100644
index 62801e7..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDAnalogAccelerometer.cpp
+++ /dev/null
@@ -1,11 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/pidwrappers/PIDAnalogAccelerometer.h"
-
-using namespace frc;
-
-double PIDAnalogAccelerometer::PIDGet() {
-  return GetAcceleration();
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDAnalogGyro.cpp b/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDAnalogGyro.cpp
deleted file mode 100644
index d6a9ace..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDAnalogGyro.cpp
+++ /dev/null
@@ -1,18 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.

-// Open Source Software; you can modify and/or share it under the terms of

-// the WPILib BSD license file in the root directory of this project.

-

-#include "frc/pidwrappers/PIDAnalogGyro.h"

-

-using namespace frc;

-

-double PIDAnalogGyro::PIDGet() {

-  switch (GetPIDSourceType()) {

-    case PIDSourceType::kRate:

-      return GetRate();

-    case PIDSourceType::kDisplacement:

-      return GetAngle();

-    default:

-      return 0;

-  }

-}

diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDAnalogInput.cpp b/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDAnalogInput.cpp
deleted file mode 100644
index d8dc716..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDAnalogInput.cpp
+++ /dev/null
@@ -1,11 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.

-// Open Source Software; you can modify and/or share it under the terms of

-// the WPILib BSD license file in the root directory of this project.

-

-#include "frc/pidwrappers/PIDAnalogInput.h"

-

-using namespace frc;

-

-double PIDAnalogInput::PIDGet() {

-  return GetAverageVoltage();

-}

diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDAnalogPotentiometer.cpp b/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDAnalogPotentiometer.cpp
deleted file mode 100644
index 7b44f6b..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDAnalogPotentiometer.cpp
+++ /dev/null
@@ -1,11 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.

-// Open Source Software; you can modify and/or share it under the terms of

-// the WPILib BSD license file in the root directory of this project.

-

-#include "frc/pidwrappers/PIDAnalogPotentiometer.h"

-

-using namespace frc;

-

-double PIDAnalogPotentiometer::PIDGet() {

-  return Get();

-}

diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDEncoder.cpp b/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDEncoder.cpp
deleted file mode 100644
index b98d1c9..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDEncoder.cpp
+++ /dev/null
@@ -1,18 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.

-// Open Source Software; you can modify and/or share it under the terms of

-// the WPILib BSD license file in the root directory of this project.

-

-#include "frc/pidwrappers/PIDEncoder.h"

-

-using namespace frc;

-

-double PIDEncoder::PIDGet() {

-  switch (GetPIDSourceType()) {

-    case PIDSourceType::kDisplacement:

-      return GetDistance();

-    case PIDSourceType::kRate:

-      return GetRate();

-    default:

-      return 0.0;

-  }

-}

diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDMotorController.cpp b/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDMotorController.cpp
deleted file mode 100644
index 68d0be3..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDMotorController.cpp
+++ /dev/null
@@ -1,50 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/pidwrappers/PIDMotorController.h"
-
-#include <fmt/format.h>
-#include <wpi/sendable/SendableBuilder.h>
-#include <wpi/sendable/SendableRegistry.h>
-
-using namespace frc;
-
-PIDMotorController::PIDMotorController(MotorController& motorController)
-    : m_motorController(motorController) {}
-
-void PIDMotorController::Set(double speed) {
-  m_motorController.Set(m_isInverted ? -speed : speed);
-}
-
-double PIDMotorController::Get() const {
-  return m_motorController.Get() * (m_isInverted ? -1.0 : 1.0);
-}
-
-void PIDMotorController::SetInverted(bool isInverted) {
-  m_isInverted = isInverted;
-}
-
-bool PIDMotorController::GetInverted() const {
-  return m_isInverted;
-}
-
-void PIDMotorController::Disable() {
-  m_motorController.Disable();
-}
-
-void PIDMotorController::StopMotor() {
-  Disable();
-}
-
-void PIDMotorController::PIDWrite(double output) {
-  m_motorController.Set(output);
-}
-
-void PIDMotorController::InitSendable(wpi::SendableBuilder& builder) {
-  builder.SetSmartDashboardType("Motor Controller");
-  builder.SetActuator(true);
-  builder.SetSafeState([=] { Disable(); });
-  builder.AddDoubleProperty(
-      "Value", [=] { return Get(); }, [=](double value) { Set(value); });
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDUltrasonic.cpp b/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDUltrasonic.cpp
deleted file mode 100644
index 4c02f17..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDUltrasonic.cpp
+++ /dev/null
@@ -1,11 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.

-// Open Source Software; you can modify and/or share it under the terms of

-// the WPILib BSD license file in the root directory of this project.

-

-#include "frc/pidwrappers/PIDUltrasonic.h"

-

-using namespace frc;

-

-double PIDUltrasonic::PIDGet() {

-  return GetRange().value();

-}

diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/PIDBase.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/PIDBase.h
deleted file mode 100644
index 8c72ae7..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/PIDBase.h
+++ /dev/null
@@ -1,407 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <memory>
-#include <string>
-
-#include <wpi/deprecated.h>
-#include <wpi/mutex.h>
-#include <wpi/sendable/Sendable.h>
-#include <wpi/sendable/SendableHelper.h>
-
-#include "frc/PIDInterface.h"
-#include "frc/PIDOutput.h"
-#include "frc/PIDSource.h"
-#include "frc/Timer.h"
-#include "frc/filter/LinearFilter.h"
-
-namespace frc {
-
-/**
- * Class implements a PID Control Loop.
- *
- * Creates a separate thread which reads the given PIDSource and takes care of
- * the integral calculations, as well as writing the given PIDOutput.
- *
- * This feedback controller runs in discrete time, so time deltas are not used
- * in the integral and derivative calculations. Therefore, the sample rate
- * affects the controller's behavior for a given set of PID constants.
- *
- * This class is provided by the OldCommands VendorDep
- *
- * @deprecated All APIs which use this have been deprecated.
- */
-class PIDBase : public PIDInterface,
-                public PIDOutput,
-                public wpi::Sendable,
-                public wpi::SendableHelper<PIDBase> {
- public:
-  /**
-   * Allocate a PID object with the given constants for P, I, D.
-   *
-   * @param p      the proportional coefficient
-   * @param i      the integral coefficient
-   * @param d      the derivative coefficient
-   * @param source The PIDSource object that is used to get values
-   * @param output The PIDOutput object that is set to the output value
-   */
-  WPI_DEPRECATED("All APIs which use this have been deprecated.")
-  PIDBase(double p, double i, double d, PIDSource& source, PIDOutput& output);
-
-  /**
-   * Allocate a PID object with the given constants for P, I, D.
-   *
-   * @param p      the proportional coefficient
-   * @param i      the integral coefficient
-   * @param d      the derivative coefficient
-   * @param f      the feedforward coefficient
-   * @param source The PIDSource object that is used to get values
-   * @param output The PIDOutput object that is set to the output value
-   */
-  WPI_DEPRECATED("All APIs which use this have been deprecated.")
-  PIDBase(double p, double i, double d, double f, PIDSource& source,
-          PIDOutput& output);
-
-  ~PIDBase() override = default;
-
-  /**
-   * Return the current PID result.
-   *
-   * This is always centered on zero and constrained the the max and min outs.
-   *
-   * @return the latest calculated output
-   */
-  virtual double Get() const;
-
-  /**
-   * Set the PID controller to consider the input to be continuous,
-   *
-   * Rather then using the max and min input range as constraints, it considers
-   * them to be the same point and automatically calculates the shortest route
-   * to the setpoint.
-   *
-   * @param continuous true turns on continuous, false turns off continuous
-   */
-  virtual void SetContinuous(bool continuous = true);
-
-  /**
-   * Sets the maximum and minimum values expected from the input.
-   *
-   * @param minimumInput the minimum value expected from the input
-   * @param maximumInput the maximum value expected from the output
-   */
-  virtual void SetInputRange(double minimumInput, double maximumInput);
-
-  /**
-   * Sets the minimum and maximum values to write.
-   *
-   * @param minimumOutput the minimum value to write to the output
-   * @param maximumOutput the maximum value to write to the output
-   */
-  virtual void SetOutputRange(double minimumOutput, double maximumOutput);
-
-  /**
-   * Set the PID Controller gain parameters.
-   *
-   * Set the proportional, integral, and differential coefficients.
-   *
-   * @param p Proportional coefficient
-   * @param i Integral coefficient
-   * @param d Differential coefficient
-   */
-  void SetPID(double p, double i, double d) override;
-
-  /**
-   * Set the PID Controller gain parameters.
-   *
-   * Set the proportional, integral, and differential coefficients.
-   *
-   * @param p Proportional coefficient
-   * @param i Integral coefficient
-   * @param d Differential coefficient
-   * @param f Feed forward coefficient
-   */
-  virtual void SetPID(double p, double i, double d, double f);
-
-  /**
-   * Set the Proportional coefficient of the PID controller gain.
-   *
-   * @param p proportional coefficient
-   */
-  void SetP(double p);
-
-  /**
-   * Set the Integral coefficient of the PID controller gain.
-   *
-   * @param i integral coefficient
-   */
-  void SetI(double i);
-
-  /**
-   * Set the Differential coefficient of the PID controller gain.
-   *
-   * @param d differential coefficient
-   */
-  void SetD(double d);
-
-  /**
-   * Get the Feed forward coefficient of the PID controller gain.
-   *
-   * @param f Feed forward coefficient
-   */
-  void SetF(double f);
-
-  /**
-   * Get the Proportional coefficient.
-   *
-   * @return proportional coefficient
-   */
-  double GetP() const override;
-
-  /**
-   * Get the Integral coefficient.
-   *
-   * @return integral coefficient
-   */
-  double GetI() const override;
-
-  /**
-   * Get the Differential coefficient.
-   *
-   * @return differential coefficient
-   */
-  double GetD() const override;
-
-  /**
-   * Get the Feed forward coefficient.
-   *
-   * @return Feed forward coefficient
-   */
-  virtual double GetF() const;
-
-  /**
-   * Set the setpoint for the PIDBase.
-   *
-   * @param setpoint the desired setpoint
-   */
-  void SetSetpoint(double setpoint) override;
-
-  /**
-   * Returns the current setpoint of the PIDBase.
-   *
-   * @return the current setpoint
-   */
-  double GetSetpoint() const override;
-
-  /**
-   * Returns the change in setpoint over time of the PIDBase.
-   *
-   * @return the change in setpoint over time
-   */
-  double GetDeltaSetpoint() const;
-
-  /**
-   * Returns the current difference of the input from the setpoint.
-   *
-   * @return the current error
-   */
-  virtual double GetError() const;
-
-  /**
-   * Returns the current average of the error over the past few iterations.
-   *
-   * You can specify the number of iterations to average with
-   * SetToleranceBuffer() (defaults to 1). This is the same value that is used
-   * for OnTarget().
-   *
-   * @return the average error
-   */
-  WPI_DEPRECATED("Use a LinearFilter as the input and GetError().")
-  virtual double GetAvgError() const;
-
-  /**
-   * Sets what type of input the PID controller will use.
-   */
-  virtual void SetPIDSourceType(PIDSourceType pidSource);
-
-  /**
-   * Returns the type of input the PID controller is using.
-   *
-   * @return the PID controller input type
-   */
-  virtual PIDSourceType GetPIDSourceType() const;
-
-  /**
-   * Set the percentage error which is considered tolerable for use with
-   * OnTarget.
-   *
-   * @param percent error which is tolerable
-   */
-  WPI_DEPRECATED("Use SetPercentTolerance() instead.")
-  virtual void SetTolerance(double percent);
-
-  /**
-   * Set the absolute error which is considered tolerable for use with
-   * OnTarget.
-   *
-   * @param absTolerance error which is tolerable
-   */
-  virtual void SetAbsoluteTolerance(double absTolerance);
-
-  /**
-   * Set the percentage error which is considered tolerable for use with
-   * OnTarget.
-   *
-   * @param percent error which is tolerable
-   */
-  virtual void SetPercentTolerance(double percent);
-
-  /**
-   * Set the number of previous error samples to average for tolerancing. When
-   * determining whether a mechanism is on target, the user may want to use a
-   * rolling average of previous measurements instead of a precise position or
-   * velocity. This is useful for noisy sensors which return a few erroneous
-   * measurements when the mechanism is on target. However, the mechanism will
-   * not register as on target for at least the specified bufLength cycles.
-   *
-   * @param bufLength Number of previous cycles to average. Defaults to 1.
-   */
-  WPI_DEPRECATED("Use a LinearDigitalFilter as the input.")
-  virtual void SetToleranceBuffer(int bufLength = 1);
-
-  /**
-   * Return true if the error is within the percentage of the total input range,
-   * determined by SetTolerance. This asssumes that the maximum and minimum
-   * input were set using SetInput.
-   *
-   * Currently this just reports on target as the actual value passes through
-   * the setpoint. Ideally it should be based on being within the tolerance for
-   * some period of time.
-   *
-   * This will return false until at least one input value has been computed.
-   */
-  virtual bool OnTarget() const;
-
-  /**
-   * Reset the previous error, the integral term, and disable the controller.
-   */
-  void Reset() override;
-
-  /**
-   * Passes the output directly to SetSetpoint().
-   *
-   * PIDControllers can be nested by passing a PIDController as another
-   * PIDController's output. In that case, the output of the parent controller
-   * becomes the input (i.e., the reference) of the child.
-   *
-   * It is the caller's responsibility to put the data into a valid form for
-   * SetSetpoint().
-   */
-  void PIDWrite(double output) override;
-
-  void InitSendable(wpi::SendableBuilder& builder) override;
-
- protected:
-  // Is the pid controller enabled
-  bool m_enabled = false;
-
-  mutable wpi::mutex m_thisMutex;
-
-  // Ensures when Disable() is called, PIDWrite() won't run if Calculate()
-  // is already running at that time.
-  mutable wpi::mutex m_pidWriteMutex;
-
-  PIDSource* m_pidInput;
-  PIDOutput* m_pidOutput;
-  Timer m_setpointTimer;
-
-  /**
-   * Read the input, calculate the output accordingly, and write to the output.
-   * This should only be called by the Notifier.
-   */
-  virtual void Calculate();
-
-  /**
-   * Calculate the feed forward term.
-   *
-   * Both of the provided feed forward calculations are velocity feed forwards.
-   * If a different feed forward calculation is desired, the user can override
-   * this function and provide his or her own. This function does no
-   * synchronization because the PIDBase class only calls it in synchronized
-   * code, so be careful if calling it oneself.
-   *
-   * If a velocity PID controller is being used, the F term should be set to 1
-   * over the maximum setpoint for the output. If a position PID controller is
-   * being used, the F term should be set to 1 over the maximum speed for the
-   * output measured in setpoint units per this controller's update period (see
-   * the default period in this class's constructor).
-   */
-  virtual double CalculateFeedForward();
-
-  /**
-   * Wraps error around for continuous inputs. The original error is returned if
-   * continuous mode is disabled. This is an unsynchronized function.
-   *
-   * @param error The current error of the PID controller.
-   * @return Error for continuous inputs.
-   */
-  double GetContinuousError(double error) const;
-
- private:
-  // Factor for "proportional" control
-  double m_P;
-
-  // Factor for "integral" control
-  double m_I;
-
-  // Factor for "derivative" control
-  double m_D;
-
-  // Factor for "feed forward" control
-  double m_F;
-
-  // |maximum output|
-  double m_maximumOutput = 1.0;
-
-  // |minimum output|
-  double m_minimumOutput = -1.0;
-
-  // Maximum input - limit setpoint to this
-  double m_maximumInput = 0;
-
-  // Minimum input - limit setpoint to this
-  double m_minimumInput = 0;
-
-  // input range - difference between maximum and minimum
-  double m_inputRange = 0;
-
-  // Do the endpoints wrap around? eg. Absolute encoder
-  bool m_continuous = false;
-
-  // The prior error (used to compute velocity)
-  double m_prevError = 0;
-
-  // The sum of the errors for use in the integral calc
-  double m_totalError = 0;
-
-  enum {
-    kAbsoluteTolerance,
-    kPercentTolerance,
-    kNoTolerance
-  } m_toleranceType = kNoTolerance;
-
-  // The percetage or absolute error that is considered on target.
-  double m_tolerance = 0.05;
-
-  double m_setpoint = 0;
-  double m_prevSetpoint = 0;
-  double m_error = 0;
-  double m_result = 0;
-
-  LinearFilter<double> m_filter{{}, {}};
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/PIDController.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/PIDController.h
deleted file mode 100644
index 224c5e9..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/PIDController.h
+++ /dev/null
@@ -1,139 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <memory>
-#include <string>
-
-#include <wpi/deprecated.h>
-#include <wpi/mutex.h>
-
-#include "frc/Controller.h"
-#include "frc/Notifier.h"
-#include "frc/PIDBase.h"
-#include "frc/PIDSource.h"
-#include "frc/Timer.h"
-
-namespace frc {
-
-class PIDOutput;
-
-/**
- * Class implements a PID Control Loop.
- *
- * Creates a separate thread which reads the given PIDSource and takes care of
- * the integral calculations, as well as writing the given PIDOutput.
- *
- * This feedback controller runs in discrete time, so time deltas are not used
- * in the integral and derivative calculations. Therefore, the sample rate
- * affects the controller's behavior for a given set of PID constants.
- *
- * This class is provided by the OldCommands VendorDep
- *
- * @deprecated Use frc2::PIDController class instead.
- */
-class PIDController : public PIDBase, public Controller {
- public:
-  /**
-   * Allocate a PID object with the given constants for P, I, D.
-   *
-   * @param p      the proportional coefficient
-   * @param i      the integral coefficient
-   * @param d      the derivative coefficient
-   * @param source The PIDSource object that is used to get values
-   * @param output The PIDOutput object that is set to the output value
-   * @param period the loop time for doing calculations in seconds. This
-   *               particularly affects calculations of the integral and
-   *               differential terms. The default is 0.05 (50ms).
-   */
-  WPI_DEPRECATED("Use frc2::PIDController class instead.")
-  PIDController(double p, double i, double d, PIDSource* source,
-                PIDOutput* output, double period = 0.05);
-
-  /**
-   * Allocate a PID object with the given constants for P, I, D.
-   *
-   * @param p      the proportional coefficient
-   * @param i      the integral coefficient
-   * @param d      the derivative coefficient
-   * @param f      the feedforward coefficient
-   * @param source The PIDSource object that is used to get values
-   * @param output The PIDOutput object that is set to the output value
-   * @param period the loop time for doing calculations in seconds. This
-   *               particularly affects calculations of the integral and
-   *               differential terms. The default is 0.05 (50ms).
-   */
-  WPI_DEPRECATED("Use frc2::PIDController class instead.")
-  PIDController(double p, double i, double d, double f, PIDSource* source,
-                PIDOutput* output, double period = 0.05);
-
-  /**
-   * Allocate a PID object with the given constants for P, I, D.
-   *
-   * @param p      the proportional coefficient
-   * @param i      the integral coefficient
-   * @param d      the derivative coefficient
-   * @param source The PIDSource object that is used to get values
-   * @param output The PIDOutput object that is set to the output value
-   * @param period the loop time for doing calculations in seconds. This
-   *               particularly affects calculations of the integral and
-   *               differential terms. The default is 0.05 (50ms).
-   */
-  WPI_DEPRECATED("Use frc2::PIDController class instead.")
-  PIDController(double p, double i, double d, PIDSource& source,
-                PIDOutput& output, double period = 0.05);
-
-  /**
-   * Allocate a PID object with the given constants for P, I, D.
-   *
-   * @param p      the proportional coefficient
-   * @param i      the integral coefficient
-   * @param d      the derivative coefficient
-   * @param f      the feedforward coefficient
-   * @param source The PIDSource object that is used to get values
-   * @param output The PIDOutput object that is set to the output value
-   * @param period the loop time for doing calculations in seconds. This
-   *               particularly affects calculations of the integral and
-   *               differential terms. The default is 0.05 (50ms).
-   */
-  WPI_DEPRECATED("Use frc2::PIDController class instead.")
-  PIDController(double p, double i, double d, double f, PIDSource& source,
-                PIDOutput& output, double period = 0.05);
-
-  ~PIDController() override;
-
-  /**
-   * Begin running the PIDController.
-   */
-  void Enable() override;
-
-  /**
-   * Stop running the PIDController, this sets the output to zero before
-   * stopping.
-   */
-  void Disable() override;
-
-  /**
-   * Set the enabled state of the PIDController.
-   */
-  void SetEnabled(bool enable);
-
-  /**
-   * Return true if PIDController is enabled.
-   */
-  bool IsEnabled() const;
-
-  /**
-   * Reset the previous error, the integral term, and disable the controller.
-   */
-  void Reset() override;
-
-  void InitSendable(wpi::SendableBuilder& builder) override;
-
- private:
-  std::unique_ptr<Notifier> m_controlLoop;
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/PIDInterface.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/PIDInterface.h
deleted file mode 100644
index 7af3ec6..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/PIDInterface.h
+++ /dev/null
@@ -1,36 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <wpi/deprecated.h>
-
-namespace frc {
-
-/**
- * Interface for PID Control Loop.
- *
- * This class is provided by the OldCommands VendorDep
- *
- * @deprecated All APIs which use this have been deprecated.
- */
-class PIDInterface {
- public:
-  WPI_DEPRECATED("All APIs which use this have been deprecated.")
-  PIDInterface() = default;
-  PIDInterface(PIDInterface&&) = default;
-  PIDInterface& operator=(PIDInterface&&) = default;
-
-  virtual void SetPID(double p, double i, double d) = 0;
-  virtual double GetP() const = 0;
-  virtual double GetI() const = 0;
-  virtual double GetD() const = 0;
-
-  virtual void SetSetpoint(double setpoint) = 0;
-  virtual double GetSetpoint() const = 0;
-
-  virtual void Reset() = 0;
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/PIDOutput.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/PIDOutput.h
deleted file mode 100644
index 3e1e780..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/PIDOutput.h
+++ /dev/null
@@ -1,22 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-namespace frc {
-
-/**
- * PIDOutput interface is a generic output for the PID class.
- *
- * MotorControllers use this class. Users implement this interface to allow for
- * a PIDController to read directly from the inputs.
- *
- * This class is provided by the OldCommands VendorDep
- */
-class PIDOutput {
- public:
-  virtual void PIDWrite(double output) = 0;
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/PIDSource.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/PIDSource.h
deleted file mode 100644
index 52990a1..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/PIDSource.h
+++ /dev/null
@@ -1,38 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-namespace frc {
-
-enum class PIDSourceType { kDisplacement, kRate };
-
-/**
- * PIDSource interface is a generic sensor source for the PID class.
- *
- * All sensors that can be used with the PID class will implement the PIDSource
- * that returns a standard value that will be used in the PID code.
- *
- * This class is provided by the OldCommands VendorDep
- */
-class PIDSource {
- public:
-  virtual ~PIDSource() = default;
-
-  /**
-   * Set which parameter you are using as a process control variable.
-   *
-   * @param pidSource An enum to select the parameter.
-   */
-  virtual void SetPIDSourceType(PIDSourceType pidSource);
-
-  virtual PIDSourceType GetPIDSourceType() const;
-
-  virtual double PIDGet() = 0;
-
- protected:
-  PIDSourceType m_pidSource = PIDSourceType::kDisplacement;
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/buttons/Button.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/buttons/Button.h
deleted file mode 100644
index 51fe098..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/buttons/Button.h
+++ /dev/null
@@ -1,72 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include "frc/buttons/Trigger.h"
-#include "frc/commands/Command.h"
-
-namespace frc {
-
-/**
- * This class provides an easy way to link commands to OI inputs.
- *
- * It is very easy to link a button to a command.  For instance, you could link
- * the trigger button of a joystick to a "score" command.
- *
- * This class represents a subclass of Trigger that is specifically aimed at
- * buttons on an operator interface as a common use case of the more generalized
- * Trigger objects. This is a simple wrapper around Trigger with the method
- * names renamed to fit the Button object use.
- *
- * This class is provided by the OldCommands VendorDep
- */
-class Button : public Trigger {
- public:
-  Button() = default;
-  Button(Button&&) = default;
-  Button& operator=(Button&&) = default;
-
-  /**
-   * Specifies the command to run when a button is first pressed.
-   *
-   * @param command The pointer to the command to run
-   */
-  virtual void WhenPressed(Command* command);
-
-  /**
-   * Specifies the command to be scheduled while the button is pressed.
-   *
-   * The command will be scheduled repeatedly while the button is pressed and
-   * will be canceled when the button is released.
-   *
-   * @param command The pointer to the command to run
-   */
-  virtual void WhileHeld(Command* command);
-
-  /**
-   * Specifies the command to run when the button is released.
-   *
-   * The command will be scheduled a single time.
-   *
-   * @param command The pointer to the command to run
-   */
-  virtual void WhenReleased(Command* command);
-
-  /**
-   * Cancels the specificed command when the button is pressed.
-   *
-   * @param command The command to be canceled
-   */
-  virtual void CancelWhenPressed(Command* command);
-
-  /**
-   * Toggle the specified command when the button is pressed.
-   *
-   * @param command The command to be toggled
-   */
-  virtual void ToggleWhenPressed(Command* command);
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/buttons/ButtonScheduler.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/buttons/ButtonScheduler.h
deleted file mode 100644
index 0c3ad20..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/buttons/ButtonScheduler.h
+++ /dev/null
@@ -1,29 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-namespace frc {
-
-class Trigger;
-class Command;
-
-class ButtonScheduler {
- public:
-  ButtonScheduler(bool last, Trigger* button, Command* orders);
-  virtual ~ButtonScheduler() = default;
-
-  ButtonScheduler(ButtonScheduler&&) = default;
-  ButtonScheduler& operator=(ButtonScheduler&&) = default;
-
-  virtual void Execute() = 0;
-  void Start();
-
- protected:
-  bool m_pressedLast;
-  Trigger* m_button;
-  Command* m_command;
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/buttons/CancelButtonScheduler.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/buttons/CancelButtonScheduler.h
deleted file mode 100644
index c3938eb..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/buttons/CancelButtonScheduler.h
+++ /dev/null
@@ -1,25 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include "frc/buttons/ButtonScheduler.h"
-
-namespace frc {
-
-class Trigger;
-class Command;
-
-class CancelButtonScheduler : public ButtonScheduler {
- public:
-  CancelButtonScheduler(bool last, Trigger* button, Command* orders);
-  ~CancelButtonScheduler() override = default;
-
-  CancelButtonScheduler(CancelButtonScheduler&&) = default;
-  CancelButtonScheduler& operator=(CancelButtonScheduler&&) = default;
-
-  void Execute() override;
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/buttons/HeldButtonScheduler.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/buttons/HeldButtonScheduler.h
deleted file mode 100644
index 721688f..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/buttons/HeldButtonScheduler.h
+++ /dev/null
@@ -1,25 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include "frc/buttons/ButtonScheduler.h"
-
-namespace frc {
-
-class Trigger;
-class Command;
-
-class HeldButtonScheduler : public ButtonScheduler {
- public:
-  HeldButtonScheduler(bool last, Trigger* button, Command* orders);
-  ~HeldButtonScheduler() override = default;
-
-  HeldButtonScheduler(HeldButtonScheduler&&) = default;
-  HeldButtonScheduler& operator=(HeldButtonScheduler&&) = default;
-
-  void Execute() override;
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/buttons/InternalButton.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/buttons/InternalButton.h
deleted file mode 100644
index 05c8348..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/buttons/InternalButton.h
+++ /dev/null
@@ -1,37 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include "frc/buttons/Button.h"
-
-namespace frc {
-
-/**
- * This Button is intended to be used within a program. The programmer can
- * manually set its value. Also includes a setting for whether or not it should
- * invert its value.
- *
- * This class is provided by the OldCommands VendorDep
- */
-class InternalButton : public Button {
- public:
-  InternalButton() = default;
-  explicit InternalButton(bool inverted);
-  ~InternalButton() override = default;
-
-  InternalButton(InternalButton&&) = default;
-  InternalButton& operator=(InternalButton&&) = default;
-
-  void SetInverted(bool inverted);
-  void SetPressed(bool pressed);
-
-  bool Get() override;
-
- private:
-  bool m_pressed = false;
-  bool m_inverted = false;
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/buttons/JoystickButton.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/buttons/JoystickButton.h
deleted file mode 100644
index 7e92cc1..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/buttons/JoystickButton.h
+++ /dev/null
@@ -1,32 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include "frc/GenericHID.h"
-#include "frc/buttons/Button.h"
-
-namespace frc {
-
-/**
- * A Button} that gets its state from a GenericHID.
- *
- * This class is provided by the OldCommands VendorDep
- */
-class JoystickButton : public Button {
- public:
-  JoystickButton(GenericHID* joystick, int buttonNumber);
-  ~JoystickButton() override = default;
-
-  JoystickButton(JoystickButton&&) = default;
-  JoystickButton& operator=(JoystickButton&&) = default;
-
-  bool Get() override;
-
- private:
-  GenericHID* m_joystick;
-  int m_buttonNumber;
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/buttons/NetworkButton.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/buttons/NetworkButton.h
deleted file mode 100644
index e277230..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/buttons/NetworkButton.h
+++ /dev/null
@@ -1,38 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <memory>
-#include <string_view>
-
-#include <networktables/NetworkTable.h>
-#include <networktables/NetworkTableEntry.h>
-
-#include "frc/buttons/Button.h"
-
-namespace frc {
-
-/**
- * A that uses a NetworkTable boolean field.
- *
- * <p>This class is provided by the OldCommands VendorDep
- */
-class NetworkButton : public Button {
- public:
-  NetworkButton(std::string_view tableName, std::string_view field);
-  NetworkButton(std::shared_ptr<nt::NetworkTable> table,
-                std::string_view field);
-  ~NetworkButton() override = default;
-
-  NetworkButton(NetworkButton&&) = default;
-  NetworkButton& operator=(NetworkButton&&) = default;
-
-  bool Get() override;
-
- private:
-  nt::NetworkTableEntry m_entry;
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/buttons/POVButton.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/buttons/POVButton.h
deleted file mode 100644
index 72ff50a..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/buttons/POVButton.h
+++ /dev/null
@@ -1,39 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include "frc/GenericHID.h"
-#include "frc/buttons/Button.h"
-
-namespace frc {
-
-/**
- * A Button that gets its state from a POV on a GenericHID.
- *
- * <p>This class is provided by the OldCommands VendorDep
- */
-class POVButton : public Button {
- public:
-  /**
-   * Creates a POV button for triggering commands.
-   *
-   * @param joystick The GenericHID object that has the POV
-   * @param angle The desired angle in degrees (e.g. 90, 270)
-   * @param povNumber The POV number (@see GenericHID#GetPOV)
-   */
-  POVButton(GenericHID& joystick, int angle, int povNumber = 0);
-  ~POVButton() override = default;
-
-  POVButton(POVButton&&) = default;
-  POVButton& operator=(POVButton&&) = default;
-
-  bool Get() override;
-
- private:
-  GenericHID* m_joystick;
-  int m_angle;
-  int m_povNumber;
-};
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/buttons/PressedButtonScheduler.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/buttons/PressedButtonScheduler.h
deleted file mode 100644
index 378d2c5..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/buttons/PressedButtonScheduler.h
+++ /dev/null
@@ -1,25 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include "frc/buttons/ButtonScheduler.h"
-
-namespace frc {
-
-class Trigger;
-class Command;
-
-class PressedButtonScheduler : public ButtonScheduler {
- public:
-  PressedButtonScheduler(bool last, Trigger* button, Command* orders);
-  ~PressedButtonScheduler() override = default;
-
-  PressedButtonScheduler(PressedButtonScheduler&&) = default;
-  PressedButtonScheduler& operator=(PressedButtonScheduler&&) = default;
-
-  void Execute() override;
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/buttons/ReleasedButtonScheduler.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/buttons/ReleasedButtonScheduler.h
deleted file mode 100644
index 6ed53ee..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/buttons/ReleasedButtonScheduler.h
+++ /dev/null
@@ -1,25 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include "frc/buttons/ButtonScheduler.h"
-
-namespace frc {
-
-class Trigger;
-class Command;
-
-class ReleasedButtonScheduler : public ButtonScheduler {
- public:
-  ReleasedButtonScheduler(bool last, Trigger* button, Command* orders);
-  ~ReleasedButtonScheduler() override = default;
-
-  ReleasedButtonScheduler(ReleasedButtonScheduler&&) = default;
-  ReleasedButtonScheduler& operator=(ReleasedButtonScheduler&&) = default;
-
-  void Execute() override;
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/buttons/ToggleButtonScheduler.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/buttons/ToggleButtonScheduler.h
deleted file mode 100644
index 8df27a9..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/buttons/ToggleButtonScheduler.h
+++ /dev/null
@@ -1,25 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include "frc/buttons/ButtonScheduler.h"
-
-namespace frc {
-
-class Trigger;
-class Command;
-
-class ToggleButtonScheduler : public ButtonScheduler {
- public:
-  ToggleButtonScheduler(bool last, Trigger* button, Command* orders);
-  ~ToggleButtonScheduler() override = default;
-
-  ToggleButtonScheduler(ToggleButtonScheduler&&) = default;
-  ToggleButtonScheduler& operator=(ToggleButtonScheduler&&) = default;
-
-  void Execute() override;
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/buttons/Trigger.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/buttons/Trigger.h
deleted file mode 100644
index 4edceaa..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/buttons/Trigger.h
+++ /dev/null
@@ -1,55 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <atomic>
-
-#include <wpi/sendable/Sendable.h>
-#include <wpi/sendable/SendableHelper.h>
-
-namespace frc {
-
-class Command;
-
-/**
- * This class provides an easy way to link commands to inputs.
- *
- * It is very easy to link a polled input to a command. For instance, you could
- * link the trigger button of a joystick to a "score" command or an encoder
- * reaching a particular value.
- *
- * It is encouraged that teams write a subclass of Trigger if they want to have
- * something unusual (for instance, if they want to react to the user holding
- * a button while the robot is reading a certain sensor input). For this, they
- * only have to write the Trigger::Get() method to get the full functionality of
- * the Trigger class.
- *
- * This class is provided by the OldCommands VendorDep
- */
-class Trigger : public wpi::Sendable, public wpi::SendableHelper<Trigger> {
- public:
-  Trigger() = default;
-  ~Trigger() override = default;
-
-  Trigger(const Trigger& rhs);
-  Trigger& operator=(const Trigger& rhs);
-  Trigger(Trigger&& rhs);
-  Trigger& operator=(Trigger&& rhs);
-
-  bool Grab();
-  virtual bool Get() = 0;
-  void WhenActive(Command* command);
-  void WhileActive(Command* command);
-  void WhenInactive(Command* command);
-  void CancelWhenActive(Command* command);
-  void ToggleWhenActive(Command* command);
-
-  void InitSendable(wpi::SendableBuilder& builder) override;
-
- private:
-  std::atomic_bool m_sendablePressed{false};
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/Command.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/Command.h
deleted file mode 100644
index 3e43cff..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/Command.h
+++ /dev/null
@@ -1,490 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <memory>
-#include <string>
-#include <string_view>
-
-#include <units/time.h>
-#include <wpi/SmallPtrSet.h>
-#include <wpi/sendable/Sendable.h>
-#include <wpi/sendable/SendableHelper.h>
-
-#include "frc/commands/Subsystem.h"
-
-namespace frc {
-
-class CommandGroup;
-
-/**
- * The Command class is at the very core of the entire command framework.
- *
- * Every command can be started with a call to Start(). Once a command is
- * started it will call Initialize(), and then will repeatedly call Execute()
- * until the IsFinished() returns true. Once it does,End() will be called.
- *
- * However, if at any point while it is running Cancel() is called, then the
- * command will be stopped and Interrupted() will be called.
- *
- * If a command uses a Subsystem, then it should specify that it does so by
- * calling the Requires() method in its constructor. Note that a Command may
- * have multiple requirements, and Requires() should be called for each one.
- *
- * If a command is running and a new command with shared requirements is
- * started, then one of two things will happen. If the active command is
- * interruptible, then Cancel() will be called and the command will be removed
- * to make way for the new one. If the active command is not interruptible, the
- * other one will not even be started, and the active one will continue
- * functioning.
- *
- * This class is provided by the OldCommands VendorDep
- *  *
- * @see CommandGroup
- * @see Subsystem
- */
-class Command : public wpi::Sendable, public wpi::SendableHelper<Command> {
-  friend class CommandGroup;
-  friend class Scheduler;
-
- public:
-  /**
-   * Creates a new command.
-   *
-   * The name of this command will be default.
-   */
-  Command();
-
-  /**
-   * Creates a new command with the given name and no timeout.
-   *
-   * @param name the name for this command
-   */
-  explicit Command(std::string_view name);
-
-  /**
-   * Creates a new command with the given timeout and a default name.
-   *
-   * @param timeout the time before this command "times out"
-   * @see IsTimedOut()
-   */
-  explicit Command(units::second_t timeout);
-
-  /**
-   * Creates a new command with the given timeout and a default name.
-   *
-   * @param subsystem the subsystem that the command requires
-   */
-  explicit Command(Subsystem& subsystem);
-
-  /**
-   * Creates a new command with the given name and timeout.
-   *
-   * @param name    the name of the command
-   * @param timeout the time before this command "times out"
-   * @see IsTimedOut()
-   */
-  Command(std::string_view name, units::second_t timeout);
-
-  /**
-   * Creates a new command with the given name and timeout.
-   *
-   * @param name      the name of the command
-   * @param subsystem the subsystem that the command requires
-   */
-  Command(std::string_view name, Subsystem& subsystem);
-
-  /**
-   * Creates a new command with the given name and timeout.
-   *
-   * @param timeout   the time before this command "times out"
-   * @param subsystem the subsystem that the command requires @see IsTimedOut()
-   */
-  Command(units::second_t timeout, Subsystem& subsystem);
-
-  /**
-   * Creates a new command with the given name and timeout.
-   *
-   * @param name      the name of the command
-   * @param timeout   the time before this command "times out"
-   * @param subsystem the subsystem that the command requires @see IsTimedOut()
-   */
-  Command(std::string_view name, units::second_t timeout, Subsystem& subsystem);
-
-  ~Command() override = default;
-
-  Command(Command&&) = default;
-  Command& operator=(Command&&) = default;
-
-  /**
-   * Returns the time since this command was initialized.
-   *
-   * This function will work even if there is no specified timeout.
-   *
-   * @return the time since this command was initialized.
-   */
-  units::second_t TimeSinceInitialized() const;
-
-  /**
-   * This method specifies that the given Subsystem is used by this command.
-   *
-   * This method is crucial to the functioning of the Command System in general.
-   *
-   * Note that the recommended way to call this method is in the constructor.
-   *
-   * @param subsystem The Subsystem required
-   * @see Subsystem
-   */
-  void Requires(Subsystem* subsystem);
-
-  /**
-   * Starts up the command. Gets the command ready to start.
-   *
-   * Note that the command will eventually start, however it will not
-   * necessarily do so immediately, and may in fact be canceled before
-   * initialize is even called.
-   */
-  void Start();
-
-  /**
-   * The run method is used internally to actually run the commands.
-   *
-   * @return Whether or not the command should stay within the Scheduler.
-   */
-  bool Run();
-
-  /**
-   * This will cancel the current command.
-   *
-   * This will cancel the current command eventually. It can be called multiple
-   * times. And it can be called when the command is not running. If the command
-   * is running though, then the command will be marked as canceled and
-   * eventually removed.
-   *
-   * A command can not be canceled if it is a part of a command group, you must
-   * cancel the command group instead.
-   */
-  void Cancel();
-
-  /**
-   * Returns whether or not the command is running.
-   *
-   * This may return true even if the command has just been canceled, as it may
-   * not have yet called Interrupted().
-   *
-   * @return whether or not the command is running
-   */
-  bool IsRunning() const;
-
-  /**
-   * Returns whether or not the command has been initialized.
-   *
-   * @return whether or not the command has been initialized.
-   */
-  bool IsInitialized() const;
-
-  /**
-   * Returns whether or not the command has completed running.
-   *
-   * @return whether or not the command has completed running.
-   */
-  bool IsCompleted() const;
-
-  /**
-   * Returns whether or not this has been canceled.
-   *
-   * @return whether or not this has been canceled
-   */
-  bool IsCanceled() const;
-
-  /**
-   * Returns whether or not this command can be interrupted.
-   *
-   * @return whether or not this command can be interrupted
-   */
-  bool IsInterruptible() const;
-
-  /**
-   * Sets whether or not this command can be interrupted.
-   *
-   * @param interruptible whether or not this command can be interrupted
-   */
-  void SetInterruptible(bool interruptible);
-
-  /**
-   * Checks if the command requires the given Subsystem.
-   *
-   * @param subsystem the subsystem
-   * @return whether or not the subsystem is required (false if given nullptr)
-   */
-  bool DoesRequire(Subsystem* subsystem) const;
-
-  using SubsystemSet = wpi::SmallPtrSetImpl<Subsystem*>;
-
-  /**
-   * Returns the requirements (as an std::set of Subsystem pointers) of this
-   * command.
-   *
-   * @return The requirements (as an std::set of Subsystem pointers) of this
-   *         command
-   */
-  const SubsystemSet& GetRequirements() const;
-
-  /**
-   * Returns the CommandGroup that this command is a part of.
-   *
-   * Will return null if this Command is not in a group.
-   *
-   * @return The CommandGroup that this command is a part of (or null if not in
-   *         group)
-   */
-  CommandGroup* GetGroup() const;
-
-  /**
-   * Sets whether or not this Command should run when the robot is disabled.
-   *
-   * By default a command will not run when the robot is disabled, and will in
-   * fact be canceled.
-   *
-   * @param run Whether this command should run when the robot is disabled.
-   */
-  void SetRunWhenDisabled(bool run);
-
-  /**
-   * Returns whether or not this Command will run when the robot is disabled, or
-   * if it will cancel itself.
-   *
-   * @return Whether this Command will run when the robot is disabled, or if it
-   * will cancel itself.
-   */
-  bool WillRunWhenDisabled() const;
-
-  /**
-   * Get the ID (sequence number) for this command.
-   *
-   * The ID is a unique sequence number that is incremented for each command.
-   *
-   * @return The ID of this command
-   */
-  int GetID() const;
-
- protected:
-  /**
-   * Sets the timeout of this command.
-   *
-   * @param timeout the timeout
-   * @see IsTimedOut()
-   */
-  void SetTimeout(units::second_t timeout);
-
-  /**
-   * Returns whether or not the TimeSinceInitialized() method returns a number
-   * which is greater than or equal to the timeout for the command.
-   *
-   * If there is no timeout, this will always return false.
-   *
-   * @return whether the time has expired
-   */
-  bool IsTimedOut() const;
-
-  /**
-   * If changes are locked, then this will generate a CommandIllegalUse error.
-   *
-   * @param message The message to report on error (it is appended by a default
-   *                message)
-   * @return True if assert passed, false if assert failed.
-   */
-  bool AssertUnlocked(std::string_view message);
-
-  /**
-   * Sets the parent of this command. No actual change is made to the group.
-   *
-   * @param parent the parent
-   */
-  void SetParent(CommandGroup* parent);
-
-  /**
-   * Returns whether the command has a parent.
-   *
-   * @param True if the command has a parent.
-   */
-  bool IsParented() const;
-
-  /**
-   * Clears list of subsystem requirements.
-   *
-   * This is only used by ConditionalCommand so canceling the chosen command
-   * works properly in CommandGroup.
-   */
-  void ClearRequirements();
-
-  /**
-   * The initialize method is called the first time this Command is run after
-   * being started.
-   */
-  virtual void Initialize();
-
-  /**
-   * The execute method is called repeatedly until this Command either finishes
-   * or is canceled.
-   */
-  virtual void Execute();
-
-  /**
-   * Returns whether this command is finished.
-   *
-   * If it is, then the command will be removed and End() will be called.
-   *
-   * It may be useful for a team to reference the IsTimedOut() method for
-   * time-sensitive commands.
-   *
-   * Returning false will result in the command never ending automatically.
-   * It may still be canceled manually or interrupted by another command.
-   * Returning true will result in the command executing once and finishing
-   * immediately. We recommend using InstantCommand for this.
-   *
-   * @return Whether this command is finished.
-   * @see IsTimedOut()
-   */
-  virtual bool IsFinished() = 0;
-
-  /**
-   * Called when the command ended peacefully.
-   *
-   * This is where you may want to wrap up loose ends, like shutting off a motor
-   * that was being used in the command.
-   */
-  virtual void End();
-
-  /**
-   * Called when the command ends because somebody called Cancel() or another
-   * command shared the same requirements as this one, and booted it out.
-   *
-   * This is where you may want to wrap up loose ends, like shutting off a motor
-   * that was being used in the command.
-   *
-   * Generally, it is useful to simply call the End() method within this method,
-   * as done here.
-   */
-  virtual void Interrupted();
-
-  virtual void _Initialize();
-  virtual void _Interrupted();
-  virtual void _Execute();
-  virtual void _End();
-
-  /**
-   * This works like Cancel(), except that it doesn't throw an exception if it
-   * is a part of a command group.
-   *
-   * Should only be called by the parent command group.
-   */
-  virtual void _Cancel();
-
-  friend class ConditionalCommand;
-
- public:
-  /**
-   * Gets the name of this Command.
-   *
-   * @return Name
-   */
-  std::string GetName() const;
-
-  /**
-   * Sets the name of this Command.
-   *
-   * @param name name
-   */
-  void SetName(std::string_view name);
-
-  /**
-   * Gets the subsystem name of this Command.
-   *
-   * @return Subsystem name
-   */
-  std::string GetSubsystem() const;
-
-  /**
-   * Sets the subsystem name of this Command.
-   *
-   * @param subsystem subsystem name
-   */
-  void SetSubsystem(std::string_view subsystem);
-
- private:
-  /**
-   * Prevents further changes from being made.
-   */
-  void LockChanges();
-
-  /**
-   * Called when the command has been removed.
-   *
-   * This will call Interrupted() or End().
-   */
-  void Removed();
-
-  /**
-   * This is used internally to mark that the command has been started.
-   *
-   * The lifecycle of a command is:
-   *
-   * StartRunning() is called. Run() is called (multiple times potentially).
-   * Removed() is called.
-   *
-   * It is very important that StartRunning() and Removed() be called in order
-   * or some assumptions of the code will be broken.
-   */
-  void StartRunning();
-
-  /**
-   * Called to indicate that the timer should start.
-   *
-   * This is called right before Initialize() is, inside the Run() method.
-   */
-  void StartTiming();
-
-  // The time since this command was initialized
-  units::second_t m_startTime = -1_s;
-
-  // The time (in seconds) before this command "times out" (-1 if no timeout)
-  units::second_t m_timeout;
-
-  // Whether or not this command has been initialized
-  bool m_initialized = false;
-
-  // The requirements (or null if no requirements)
-  wpi::SmallPtrSet<Subsystem*, 4> m_requirements;
-
-  // Whether or not it is running
-  bool m_running = false;
-
-  // Whether or not it is interruptible
-  bool m_interruptible = true;
-
-  // Whether or not it has been canceled
-  bool m_canceled = false;
-
-  // Whether or not it has been locked
-  bool m_locked = false;
-
-  // Whether this command should run when the robot is disabled
-  bool m_runWhenDisabled = false;
-
-  // The CommandGroup this is in
-  CommandGroup* m_parent = nullptr;
-
-  // Whether or not this command has completed running
-  bool m_completed = false;
-
-  int m_commandID = m_commandCounter++;
-  static int m_commandCounter;
-
- public:
-  void InitSendable(wpi::SendableBuilder& builder) override;
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/CommandGroup.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/CommandGroup.h
deleted file mode 100644
index f48ddbf..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/CommandGroup.h
+++ /dev/null
@@ -1,180 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <string_view>
-#include <vector>
-
-#include <units/time.h>
-
-#include "frc/commands/Command.h"
-#include "frc/commands/CommandGroupEntry.h"
-
-namespace frc {
-
-/**
- * A CommandGroup is a list of commands which are executed in sequence.
- *
- * Commands in a CommandGroup are added using the AddSequential() method and are
- * called sequentially. CommandGroups are themselves Commands and can be given
- * to other CommandGroups.
- *
- * CommandGroups will carry all of the requirements of their Command
- * subcommands. Additional requirements can be specified by calling Requires()
- * normally in the constructor.
- *
- * CommandGroups can also execute commands in parallel, simply by adding them
- * using AddParallel().
- *
- * This class is provided by the OldCommands VendorDep
- *
- * @see Command
- * @see Subsystem
- */
-class CommandGroup : public Command {
- public:
-  CommandGroup() = default;
-
-  /**
-   * Creates a new CommandGroup with the given name.
-   *
-   * @param name The name for this command group
-   */
-  explicit CommandGroup(std::string_view name);
-
-  ~CommandGroup() override = default;
-
-  CommandGroup(CommandGroup&&) = default;
-  CommandGroup& operator=(CommandGroup&&) = default;
-
-  /**
-   * Adds a new Command to the group. The Command will be started after all the
-   * previously added Commands.
-   *
-   * Note that any requirements the given Command has will be added to the
-   * group. For this reason, a Command's requirements can not be changed after
-   * being added to a group.
-   *
-   * It is recommended that this method be called in the constructor.
-   *
-   * @param command The Command to be added
-   */
-  void AddSequential(Command* command);
-
-  /**
-   * Adds a new Command to the group with a given timeout. The Command will be
-   * started after all the previously added commands.
-   *
-   * Once the Command is started, it will be run until it finishes or the time
-   * expires, whichever is sooner.  Note that the given Command will have no
-   * knowledge that it is on a timer.
-   *
-   * Note that any requirements the given Command has will be added to the
-   * group. For this reason, a Command's requirements can not be changed after
-   * being added to a group.
-   *
-   * It is recommended that this method be called in the constructor.
-   *
-   * @param command The Command to be added
-   * @param timeout The timeout
-   */
-  void AddSequential(Command* command, units::second_t timeout);
-
-  /**
-   * Adds a new child Command to the group. The Command will be started after
-   * all the previously added Commands.
-   *
-   * Instead of waiting for the child to finish, a CommandGroup will have it run
-   * at the same time as the subsequent Commands. The child will run until
-   * either it finishes, a new child with conflicting requirements is started,
-   * or the main sequence runs a Command with conflicting requirements. In the
-   * latter two cases, the child will be canceled even if it says it can't be
-   * interrupted.
-   *
-   * Note that any requirements the given Command has will be added to the
-   * group. For this reason, a Command's requirements can not be changed after
-   * being added to a group.
-   *
-   * It is recommended that this method be called in the constructor.
-   *
-   * @param command The command to be added
-   */
-  void AddParallel(Command* command);
-
-  /**
-   * Adds a new child Command to the group with the given timeout. The Command
-   * will be started after all the previously added Commands.
-   *
-   * Once the Command is started, it will run until it finishes, is interrupted,
-   * or the time expires, whichever is sooner. Note that the given Command will
-   * have no knowledge that it is on a timer.
-   *
-   * Instead of waiting for the child to finish, a CommandGroup will have it run
-   * at the same time as the subsequent Commands. The child will run until
-   * either it finishes, the timeout expires, a new child with conflicting
-   * requirements is started, or the main sequence runs a Command with
-   * conflicting requirements. In the latter two cases, the child will be
-   * canceled even if it says it can't be interrupted.
-   *
-   * Note that any requirements the given Command has will be added to the
-   * group. For this reason, a Command's requirements can not be changed after
-   * being added to a group.
-   *
-   * It is recommended that this method be called in the constructor.
-   *
-   * @param command The command to be added
-   * @param timeout The timeout
-   */
-  void AddParallel(Command* command, units::second_t timeout);
-
-  bool IsInterruptible() const;
-
-  int GetSize() const;
-
- protected:
-  /**
-   * Can be overridden by teams.
-   */
-  void Initialize() override;
-
-  /**
-   * Can be overridden by teams.
-   */
-  void Execute() override;
-
-  /**
-   * Can be overridden by teams.
-   */
-  bool IsFinished() override;
-
-  /**
-   * Can be overridden by teams.
-   */
-  void End() override;
-
-  /**
-   * Can be overridden by teams.
-   */
-  void Interrupted() override;
-
-  void _Initialize() override;
-  void _Execute() override;
-  void _End() override;
-  void _Interrupted() override;
-
- private:
-  void CancelConflicts(Command* command);
-
-  // The commands in this group (stored in entries)
-  std::vector<CommandGroupEntry> m_commands;
-
-  // The active children in this group (stored in entries)
-  std::vector<CommandGroupEntry*> m_children;
-
-  // The current command, -1 signifies that none have been run
-  int m_currentCommandIndex = -1;
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/CommandGroupEntry.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/CommandGroupEntry.h
deleted file mode 100644
index b6162f3..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/CommandGroupEntry.h
+++ /dev/null
@@ -1,35 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <units/time.h>
-
-namespace frc {
-
-class Command;
-
-class CommandGroupEntry {
- public:
-  enum Sequence {
-    kSequence_InSequence,
-    kSequence_BranchPeer,
-    kSequence_BranchChild
-  };
-
-  CommandGroupEntry() = default;
-  CommandGroupEntry(Command* command, Sequence state,
-                    units::second_t timeout = -1_s);
-
-  CommandGroupEntry(CommandGroupEntry&&) = default;
-  CommandGroupEntry& operator=(CommandGroupEntry&&) = default;
-
-  bool IsTimedOut() const;
-
-  units::second_t m_timeout = -1_s;
-  Command* m_command = nullptr;
-  Sequence m_state = kSequence_InSequence;
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/ConditionalCommand.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/ConditionalCommand.h
deleted file mode 100644
index 46e73cb..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/ConditionalCommand.h
+++ /dev/null
@@ -1,83 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <string_view>
-
-#include "frc/commands/Command.h"
-
-namespace frc {
-
-/**
- * A ConditionalCommand is a Command that starts one of two commands.
- *
- * A ConditionalCommand uses the Condition method to determine whether it should
- * run onTrue or onFalse.
- *
- * A ConditionalCommand adds the proper Command to the Scheduler during
- * Initialize() and then IsFinished() will return true once that Command has
- * finished executing.
- *
- * If no Command is specified for onFalse, the occurrence of that condition
- * will be a no-op.
- *
- * A ConditionalCommand will require the superset of subsystems of the onTrue
- * and onFalse commands.
- *
- * This class is provided by the OldCommands VendorDep
- *
- * @see Command
- * @see Scheduler
- */
-class ConditionalCommand : public Command {
- public:
-  /**
-   * Creates a new ConditionalCommand with given onTrue and onFalse Commands.
-   *
-   * @param onTrue  The Command to execute if Condition() returns true
-   * @param onFalse The Command to execute if Condition() returns false
-   */
-  explicit ConditionalCommand(Command* onTrue, Command* onFalse = nullptr);
-
-  /**
-   * Creates a new ConditionalCommand with given onTrue and onFalse Commands.
-   *
-   * @param name    The name for this command group
-   * @param onTrue  The Command to execute if Condition() returns true
-   * @param onFalse The Command to execute if Condition() returns false
-   */
-  ConditionalCommand(std::string_view name, Command* onTrue,
-                     Command* onFalse = nullptr);
-
-  ~ConditionalCommand() override = default;
-
-  ConditionalCommand(ConditionalCommand&&) = default;
-  ConditionalCommand& operator=(ConditionalCommand&&) = default;
-
- protected:
-  /**
-   * The Condition to test to determine which Command to run.
-   *
-   * @return true if m_onTrue should be run or false if m_onFalse should be run.
-   */
-  virtual bool Condition() = 0;
-
-  void _Initialize() override;
-  void _Cancel() override;
-  bool IsFinished() override;
-  void _Interrupted() override;
-
- private:
-  // The Command to execute if Condition() returns true
-  Command* m_onTrue;
-
-  // The Command to execute if Condition() returns false
-  Command* m_onFalse;
-
-  // Stores command chosen by condition
-  Command* m_chosenCommand = nullptr;
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/InstantCommand.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/InstantCommand.h
deleted file mode 100644
index f1683eb..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/InstantCommand.h
+++ /dev/null
@@ -1,91 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <functional>
-#include <string_view>
-
-#include "frc/commands/Command.h"
-#include "frc/commands/Subsystem.h"
-
-namespace frc {
-
-/**
- * This command will execute once, then finish immediately afterward.
- *
- * Subclassing InstantCommand is shorthand for returning true from IsFinished().
- *
- * This class is provided by the OldCommands VendorDep
- */
-class InstantCommand : public Command {
- public:
-  /**
-   * Creates a new InstantCommand with the given name.
-   *
-   * @param name The name for this command
-   */
-  explicit InstantCommand(std::string_view name);
-
-  /**
-   * Creates a new InstantCommand with the given requirement.
-   *
-   * @param subsystem The subsystem that the command requires
-   */
-  explicit InstantCommand(Subsystem& subsystem);
-
-  /**
-   * Creates a new InstantCommand with the given name.
-   *
-   * @param name      The name for this command
-   * @param subsystem The subsystem that the command requires
-   */
-  InstantCommand(std::string_view name, Subsystem& subsystem);
-
-  /**
-   * Create a command that calls the given function when run.
-   *
-   * @param func The function to run when Initialize() is run.
-   */
-  explicit InstantCommand(std::function<void()> func);
-
-  /**
-   * Create a command that calls the given function when run.
-   *
-   * @param subsystem The subsystems that this command runs on.
-   * @param func      The function to run when Initialize() is run.
-   */
-  InstantCommand(Subsystem& subsystem, std::function<void()> func);
-
-  /**
-   * Create a command that calls the given function when run.
-   *
-   * @param name   The name of the command.
-   * @param func   The function to run when Initialize() is run.
-   */
-  InstantCommand(std::string_view name, std::function<void()> func);
-
-  /**
-   * Create a command that calls the given function when run.
-   *
-   * @param name      The name of the command.
-   * @param subsystem The subsystems that this command runs on.
-   * @param func      The function to run when Initialize() is run.
-   */
-  InstantCommand(std::string_view name, Subsystem& subsystem,
-                 std::function<void()> func);
-
-  InstantCommand() = default;
-  ~InstantCommand() override = default;
-
-  InstantCommand(InstantCommand&&) = default;
-  InstantCommand& operator=(InstantCommand&&) = default;
-
- protected:
-  std::function<void()> m_func = nullptr;
-  void _Initialize() override;
-  bool IsFinished() override;
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/PIDCommand.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/PIDCommand.h
deleted file mode 100644
index ba8aa6e..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/PIDCommand.h
+++ /dev/null
@@ -1,79 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <memory>
-#include <string_view>
-
-#include "frc/PIDController.h"
-#include "frc/PIDOutput.h"
-#include "frc/PIDSource.h"
-#include "frc/commands/Command.h"
-
-namespace frc {
-
-/**
- * This class defines aCommand which interacts heavily with a PID loop.
- *
- * It provides some convenience methods to run an internal PIDController . It
- * will also start and stop said PIDController when the PIDCommand is first
- * initialized and ended/interrupted.
- *
- * This class is provided by the OldCommands VendorDep
- */
-class PIDCommand : public Command, public PIDOutput, public PIDSource {
- public:
-  PIDCommand(std::string_view name, double p, double i, double d);
-  PIDCommand(std::string_view name, double p, double i, double d,
-             double period);
-  PIDCommand(std::string_view name, double p, double i, double d, double f,
-             double period);
-  PIDCommand(double p, double i, double d);
-  PIDCommand(double p, double i, double d, double period);
-  PIDCommand(double p, double i, double d, double f, double period);
-  PIDCommand(std::string_view name, double p, double i, double d,
-             Subsystem& subsystem);
-  PIDCommand(std::string_view name, double p, double i, double d, double period,
-             Subsystem& subsystem);
-  PIDCommand(std::string_view name, double p, double i, double d, double f,
-             double period, Subsystem& subsystem);
-  PIDCommand(double p, double i, double d, Subsystem& subsystem);
-  PIDCommand(double p, double i, double d, double period, Subsystem& subsystem);
-  PIDCommand(double p, double i, double d, double f, double period,
-             Subsystem& subsystem);
-  ~PIDCommand() override = default;
-
-  PIDCommand(PIDCommand&&) = default;
-  PIDCommand& operator=(PIDCommand&&) = default;
-
-  void SetSetpointRelative(double deltaSetpoint);
-
-  // PIDOutput interface
-  void PIDWrite(double output) override;
-
-  // PIDSource interface
-  double PIDGet() override;
-
- protected:
-  std::shared_ptr<PIDController> GetPIDController() const;
-  void _Initialize() override;
-  void _Interrupted() override;
-  void _End() override;
-  void SetSetpoint(double setpoint);
-  double GetSetpoint() const;
-  double GetPosition();
-
-  virtual double ReturnPIDInput() = 0;
-  virtual void UsePIDOutput(double output) = 0;
-
- private:
-  // The internal PIDController
-  std::shared_ptr<PIDController> m_controller;
-
- public:
-  void InitSendable(wpi::SendableBuilder& builder) override;
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/PIDSubsystem.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/PIDSubsystem.h
deleted file mode 100644
index b66ad38..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/PIDSubsystem.h
+++ /dev/null
@@ -1,234 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <memory>
-#include <string_view>
-
-#include "frc/PIDController.h"
-#include "frc/PIDOutput.h"
-#include "frc/PIDSource.h"
-#include "frc/commands/Subsystem.h"
-
-namespace frc {
-
-/**
- * This class is designed to handle the case where there is a Subsystem which
- * uses a single PIDController almost constantly (for instance, an elevator
- * which attempts to stay at a constant height).
- *
- * It provides some convenience methods to run an internal PIDController. It
- * also allows access to the internal PIDController in order to give total
- * control to the programmer.
- *
- * This class is provided by the OldCommands VendorDep
- */
-class PIDSubsystem : public Subsystem, public PIDOutput, public PIDSource {
- public:
-  /**
-   * Instantiates a PIDSubsystem that will use the given P, I, and D values.
-   *
-   * @param name the name
-   * @param p    the proportional value
-   * @param i    the integral value
-   * @param d    the derivative value
-   */
-  PIDSubsystem(std::string_view name, double p, double i, double d);
-
-  /**
-   * Instantiates a PIDSubsystem that will use the given P, I, D, and F values.
-   *
-   * @param name the name
-   * @param p    the proportional value
-   * @param i    the integral value
-   * @param d    the derivative value
-   * @param f    the feedforward value
-   */
-  PIDSubsystem(std::string_view name, double p, double i, double d, double f);
-
-  /**
-   * Instantiates a PIDSubsystem that will use the given P, I, D, and F values.
-   *
-   * It will also space the time between PID loop calculations to be equal to
-   * the given period.
-   *
-   * @param name   the name
-   * @param p      the proportional value
-   * @param i      the integral value
-   * @param d      the derivative value
-   * @param f      the feedfoward value
-   * @param period the time (in seconds) between calculations
-   */
-  PIDSubsystem(std::string_view name, double p, double i, double d, double f,
-               double period);
-
-  /**
-   * Instantiates a PIDSubsystem that will use the given P, I, and D values.
-   *
-   * It will use the class name as its name.
-   *
-   * @param p the proportional value
-   * @param i the integral value
-   * @param d the derivative value
-   */
-  PIDSubsystem(double p, double i, double d);
-
-  /**
-   * Instantiates a PIDSubsystem that will use the given P, I, D, and F values.
-   *
-   * It will use the class name as its name.
-   *
-   * @param p the proportional value
-   * @param i the integral value
-   * @param d the derivative value
-   * @param f the feedforward value
-   */
-  PIDSubsystem(double p, double i, double d, double f);
-
-  /**
-   * Instantiates a PIDSubsystem that will use the given P, I, D, and F values.
-   *
-   * It will use the class name as its name. It will also space the time
-   * between PID loop calculations to be equal to the given period.
-   *
-   * @param p      the proportional value
-   * @param i      the integral value
-   * @param d      the derivative value
-   * @param f      the feedforward value
-   * @param period the time (in seconds) between calculations
-   */
-  PIDSubsystem(double p, double i, double d, double f, double period);
-
-  ~PIDSubsystem() override = default;
-
-  PIDSubsystem(PIDSubsystem&&) = default;
-  PIDSubsystem& operator=(PIDSubsystem&&) = default;
-
-  /**
-   * Enables the internal PIDController.
-   */
-  void Enable();
-
-  /**
-   * Disables the internal PIDController.
-   */
-  void Disable();
-
-  // PIDOutput interface
-  void PIDWrite(double output) override;
-
-  // PIDSource interface
-
-  double PIDGet() override;
-
-  /**
-   * Sets the setpoint to the given value.
-   *
-   * If SetRange() was called, then the given setpoint will be trimmed to fit
-   * within the range.
-   *
-   * @param setpoint the new setpoint
-   */
-  void SetSetpoint(double setpoint);
-
-  /**
-   * Adds the given value to the setpoint.
-   *
-   * If SetRange() was used, then the bounds will still be honored by this
-   * method.
-   *
-   * @param deltaSetpoint the change in the setpoint
-   */
-  void SetSetpointRelative(double deltaSetpoint);
-
-  /**
-   * Sets the maximum and minimum values expected from the input.
-   *
-   * @param minimumInput the minimum value expected from the input
-   * @param maximumInput the maximum value expected from the output
-   */
-  void SetInputRange(double minimumInput, double maximumInput);
-
-  /**
-   * Sets the maximum and minimum values to write.
-   *
-   * @param minimumOutput the minimum value to write to the output
-   * @param maximumOutput the maximum value to write to the output
-   */
-  void SetOutputRange(double minimumOutput, double maximumOutput);
-
-  /**
-   * Return the current setpoint.
-   *
-   * @return The current setpoint
-   */
-  double GetSetpoint();
-
-  /**
-   * Returns the current position.
-   *
-   * @return the current position
-   */
-  double GetPosition();
-
-  /**
-   * Returns the current rate.
-   *
-   * @return the current rate
-   */
-  double GetRate();
-
-  /**
-   * Set the absolute error which is considered tolerable for use with
-   * OnTarget.
-   *
-   * @param absValue absolute error which is tolerable
-   */
-  virtual void SetAbsoluteTolerance(double absValue);
-
-  /**
-   * Set the percentage error which is considered tolerable for use with
-   * OnTarget().
-   *
-   * @param percent percentage error which is tolerable
-   */
-  virtual void SetPercentTolerance(double percent);
-
-  /**
-   * Return true if the error is within the percentage of the total input range,
-   * determined by SetTolerance().
-   *
-   * This asssumes that the maximum and minimum input were set using SetInput().
-   * Use OnTarget() in the IsFinished() method of commands that use this
-   * subsystem.
-   *
-   * Currently this just reports on target as the actual value passes through
-   * the setpoint. Ideally it should be based on being within the tolerance for
-   * some period of time.
-   *
-   * @return True if the error is within the percentage tolerance of the input
-   *         range
-   */
-  virtual bool OnTarget() const;
-
- protected:
-  /**
-   * Returns the PIDController used by this PIDSubsystem.
-   *
-   * Use this if you would like to fine tune the PID loop.
-   *
-   * @return The PIDController used by this PIDSubsystem
-   */
-  std::shared_ptr<PIDController> GetPIDController();
-
-  virtual double ReturnPIDInput() = 0;
-  virtual void UsePIDOutput(double output) = 0;
-
- private:
-  // The internal PIDController
-  std::shared_ptr<PIDController> m_controller;
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/PrintCommand.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/PrintCommand.h
deleted file mode 100644
index b72b4c9..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/PrintCommand.h
+++ /dev/null
@@ -1,36 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <string>
-#include <string_view>
-
-#include "frc/commands/InstantCommand.h"
-
-namespace frc {
-
-/**
- * A PrintCommand is a command which prints out a string when it is initialized,
- * and then immediately finishes. It is useful if you want a CommandGroup to
- * print out a string when it reaches a certain point.
- *
- * This class is provided by the OldCommands VendorDep
- */
-class PrintCommand : public InstantCommand {
- public:
-  explicit PrintCommand(std::string_view message);
-  ~PrintCommand() override = default;
-
-  PrintCommand(PrintCommand&&) = default;
-  PrintCommand& operator=(PrintCommand&&) = default;
-
- protected:
-  void Initialize() override;
-
- private:
-  std::string m_message;
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/Scheduler.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/Scheduler.h
deleted file mode 100644
index 1c67df3..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/Scheduler.h
+++ /dev/null
@@ -1,106 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <memory>
-
-#include <networktables/NTSendable.h>
-#include <wpi/sendable/SendableHelper.h>
-
-namespace frc {
-
-class ButtonScheduler;
-class Command;
-class Subsystem;
-
-/**
- * The Scheduler is a singleton which holds the top-level running commands. It
- * is in charge of both calling the command's run() method and to make sure that
- * there are no two commands with conflicting requirements running.
- *
- * It is fine if teams wish to take control of the Scheduler themselves, all
- * that needs to be done is to call frc::Scheduler::getInstance()->run() often
- * to have Commands function correctly. However, this is already done for you if
- * you use the CommandBased Robot template.
- *
- * This class is provided by the OldCommands VendorDep
- */
-class Scheduler : public nt::NTSendable, public wpi::SendableHelper<Scheduler> {
- public:
-  /**
-   * Returns the Scheduler, creating it if one does not exist.
-   *
-   * @return the Scheduler
-   */
-  static Scheduler* GetInstance();
-
-  /**
-   * Add a command to be scheduled later.
-   *
-   * In any pass through the scheduler, all commands are added to the additions
-   * list, then at the end of the pass, they are all scheduled.
-   *
-   * @param command The command to be scheduled
-   */
-  void AddCommand(Command* command);
-
-  void AddButton(ButtonScheduler* button);
-
-  /**
-   * Registers a Subsystem to this Scheduler, so that the Scheduler might know
-   * if a default Command needs to be run.
-   *
-   * All Subsystems should call this.
-   *
-   * @param subsystem the system
-   */
-  void RegisterSubsystem(Subsystem* subsystem);
-
-  /**
-   * Runs a single iteration of the loop.
-   *
-   * This method should be called often in order to have a functioning
-   * Command system. The loop has five stages:
-   *
-   * <ol>
-   *   <li>Poll the Buttons</li>
-   *   <li>Execute/Remove the Commands</li>
-   *   <li>Send values to SmartDashboard</li>
-   *   <li>Add Commands</li>
-   *   <li>Add Defaults</li>
-   * </ol>
-   */
-  void Run();
-
-  /**
-   * Removes the Command from the Scheduler.
-   *
-   * @param command the command to remove
-   */
-  void Remove(Command* command);
-
-  void RemoveAll();
-
-  /**
-   * Completely resets the scheduler. Undefined behavior if running.
-   */
-  void ResetAll();
-
-  void SetEnabled(bool enabled);
-
-  void InitSendable(nt::NTSendableBuilder& builder) override;
-
- private:
-  Scheduler();
-  ~Scheduler() override;
-
-  Scheduler(Scheduler&&) = default;
-  Scheduler& operator=(Scheduler&&) = default;
-
-  struct Impl;
-  std::unique_ptr<Impl> m_impl;
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/StartCommand.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/StartCommand.h
deleted file mode 100644
index 2186fe5..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/StartCommand.h
+++ /dev/null
@@ -1,33 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include "frc/commands/InstantCommand.h"
-
-namespace frc {
-
-/**
- * A PrintCommand is a command which prints out a string when it is initialized,
- * and then immediately finishes. It is useful if you want a CommandGroup to
- * print out a string when it reaches a certain point.
- *
- * This class is provided by the OldCommands VendorDep
- */
-class StartCommand : public InstantCommand {
- public:
-  explicit StartCommand(Command* commandToStart);
-  ~StartCommand() override = default;
-
-  StartCommand(StartCommand&&) = default;
-  StartCommand& operator=(StartCommand&&) = default;
-
- protected:
-  void Initialize() override;
-
- private:
-  Command* m_commandToFork;
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/Subsystem.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/Subsystem.h
deleted file mode 100644
index 6357f0c..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/Subsystem.h
+++ /dev/null
@@ -1,207 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <memory>
-#include <string>
-#include <string_view>
-
-#include <wpi/sendable/Sendable.h>
-#include <wpi/sendable/SendableHelper.h>
-
-namespace frc {
-
-class Command;
-
-/**
- * This class defines a major component of the robot.
- *
- * A good example of a subsystem is the drivetrain, or a claw if the robot has
- * one.
- *
- * All motors should be a part of a subsystem. For instance, all the wheel
- * motors should be a part of some kind of "Drivetrain" subsystem.
- *
- * Subsystems are used within the command system as requirements for Command.
- * Only one command which requires a subsystem can run at a time. Also,
- * subsystems can have default commands which are started if there is no command
- * running which requires this subsystem.
- *
- * This class is provided by the OldCommands VendorDep
- */
-class Subsystem : public wpi::Sendable, public wpi::SendableHelper<Subsystem> {
-  friend class Scheduler;
-
- public:
-  /**
-   * Creates a subsystem with the given name.
-   *
-   * @param name the name of the subsystem
-   */
-  explicit Subsystem(std::string_view name);
-
-  Subsystem(Subsystem&&) = default;
-  Subsystem& operator=(Subsystem&&) = default;
-
-  /**
-   * Sets the default command. If this is not called or is called with null,
-   * then there will be no default command for the subsystem.
-   *
-   * <b>WARNING:</b> This should <b>NOT</b> be called in a constructor if the
-   * subsystem is a singleton.
-   *
-   * @param command the default command (or null if there should be none)
-   */
-  void SetDefaultCommand(Command* command);
-
-  /**
-   * Returns the default command (or null if there is none).
-   *
-   * @return the default command
-   */
-  Command* GetDefaultCommand();
-
-  /**
-   * Returns the default command name, or empty string is there is none.
-   *
-   * @return the default command name
-   */
-  std::string GetDefaultCommandName();
-
-  /**
-   * Sets the current command.
-   *
-   * @param command the new current command
-   */
-  void SetCurrentCommand(Command* command);
-
-  /**
-   * Returns the command which currently claims this subsystem.
-   *
-   * @return the command which currently claims this subsystem
-   */
-  Command* GetCurrentCommand() const;
-
-  /**
-   * Returns the current command name, or empty string if no current command.
-   *
-   * @return the current command name
-   */
-  std::string GetCurrentCommandName() const;
-
-  /**
-   * When the run method of the scheduler is called this method will be called.
-   */
-  virtual void Periodic();
-
-  /**
-   * Initialize the default command for this subsystem.
-   *
-   * This is meant to be the place to call SetDefaultCommand in a subsystem and
-   * will be called on all the subsystems by the CommandBase method before the
-   * program starts running by using the list of all registered Subsystems
-   * inside the Scheduler.
-   *
-   * This should be overridden by a Subsystem that has a default Command
-   */
-  virtual void InitDefaultCommand();
-
-  /**
-   * Gets the name of this Subsystem.
-   *
-   * @return Name
-   */
-  std::string GetName() const;
-
-  /**
-   * Sets the name of this Subsystem.
-   *
-   * @param name name
-   */
-  void SetName(std::string_view name);
-
-  /**
-   * Gets the subsystem name of this Subsystem.
-   *
-   * @return Subsystem name
-   */
-  std::string GetSubsystem() const;
-
-  /**
-   * Sets the subsystem name of this Subsystem.
-   *
-   * @param subsystem subsystem name
-   */
-  void SetSubsystem(std::string_view subsystem);
-
-  /**
-   * Associate a Sendable with this Subsystem.
-   * Also update the child's name.
-   *
-   * @param name name to give child
-   * @param child sendable
-   */
-  void AddChild(std::string_view name, std::shared_ptr<wpi::Sendable> child);
-
-  /**
-   * Associate a Sendable with this Subsystem.
-   * Also update the child's name.
-   *
-   * @param name name to give child
-   * @param child sendable
-   */
-  void AddChild(std::string_view name, wpi::Sendable* child);
-
-  /**
-   * Associate a Sendable with this Subsystem.
-   * Also update the child's name.
-   *
-   * @param name name to give child
-   * @param child sendable
-   */
-  void AddChild(std::string_view name, wpi::Sendable& child);
-
-  /**
-   * Associate a Sendable with this Subsystem.
-   *
-   * @param child sendable
-   */
-  void AddChild(std::shared_ptr<wpi::Sendable> child);
-
-  /**
-   * Associate a Sendable with this Subsystem.
-   *
-   * @param child sendable
-   */
-  void AddChild(wpi::Sendable* child);
-
-  /**
-   * Associate a Sendable with this Subsystem.
-   *
-   * @param child sendable
-   */
-  void AddChild(wpi::Sendable& child);
-
- private:
-  /**
-   * Call this to alert Subsystem that the current command is actually the
-   * command.
-   *
-   * Sometimes, the Subsystem is told that it has no command while the Scheduler
-   * is going through the loop, only to be soon after given a new one. This will
-   * avoid that situation.
-   */
-  void ConfirmCommand();
-
-  Command* m_currentCommand = nullptr;
-  bool m_currentCommandChanged = true;
-  Command* m_defaultCommand = nullptr;
-  bool m_initializedDefaultCommand = false;
-
- public:
-  void InitSendable(wpi::SendableBuilder& builder) override;
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/TimedCommand.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/TimedCommand.h
deleted file mode 100644
index 912bcec..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/TimedCommand.h
+++ /dev/null
@@ -1,69 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <string_view>
-
-#include <units/time.h>
-
-#include "frc/commands/Command.h"
-
-namespace frc {
-
-/**
- * A TimedCommand will wait for a timeout before finishing.
- *
- * TimedCommand is used to execute a command for a given amount of time.
- *
- * This class is provided by the OldCommands VendorDep
- */
-class TimedCommand : public Command {
- public:
-  /**
-   * Creates a new TimedCommand with the given name and timeout.
-   *
-   * @param name    the name of the command
-   * @param timeout the time before this command "times out"
-   */
-  TimedCommand(std::string_view name, units::second_t timeout);
-
-  /**
-   * Creates a new WaitCommand with the given timeout.
-   *
-   * @param timeout the time before this command "times out"
-   */
-  explicit TimedCommand(units::second_t timeout);
-
-  /**
-   * Creates a new TimedCommand with the given name and timeout.
-   *
-   * @param name      the name of the command
-   * @param timeout   the time before this command "times out"
-   * @param subsystem the subsystem that the command requires
-   */
-  TimedCommand(std::string_view name, units::second_t timeout,
-               Subsystem& subsystem);
-
-  /**
-   * Creates a new WaitCommand with the given timeout.
-   *
-   * @param timeout   the time before this command "times out"
-   * @param subsystem the subsystem that the command requires
-   */
-  TimedCommand(units::second_t timeout, Subsystem& subsystem);
-
-  ~TimedCommand() override = default;
-
-  TimedCommand(TimedCommand&&) = default;
-  TimedCommand& operator=(TimedCommand&&) = default;
-
- protected:
-  /**
-   * Ends command when timed out.
-   */
-  bool IsFinished() override;
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/WaitCommand.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/WaitCommand.h
deleted file mode 100644
index 9f4090b..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/WaitCommand.h
+++ /dev/null
@@ -1,44 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <string_view>
-
-#include <units/time.h>
-
-#include "frc/commands/TimedCommand.h"
-
-namespace frc {
-
-/**
- * A WaitCommand will wait for a certain amount of time before finishing. It is
- * useful if you want a CommandGroup to pause for a moment.
- *
- * This class is provided by the OldCommands VendorDep
- */
-class WaitCommand : public TimedCommand {
- public:
-  /**
-   * Creates a new WaitCommand with the given name and timeout.
-   *
-   * @param timeout the time before this command "times out"
-   */
-  explicit WaitCommand(units::second_t timeout);
-
-  /**
-   * Creates a new WaitCommand with the given timeout.
-   *
-   * @param name    the name of the command
-   * @param timeout the time before this command "times out"
-   */
-  WaitCommand(std::string_view name, units::second_t timeout);
-
-  ~WaitCommand() override = default;
-
-  WaitCommand(WaitCommand&&) = default;
-  WaitCommand& operator=(WaitCommand&&) = default;
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/WaitForChildren.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/WaitForChildren.h
deleted file mode 100644
index 775826b..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/WaitForChildren.h
+++ /dev/null
@@ -1,40 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <string_view>
-
-#include <units/time.h>
-
-#include "frc/commands/Command.h"
-
-namespace frc {
-
-/**
- * This command will only finish if whatever CommandGroup it is in has no active
- * children. If it is not a part of a CommandGroup, then it will finish
- * immediately. If it is itself an active child, then the CommandGroup will
- * never end.
- *
- * This class is useful for the situation where you want to allow anything
- * running in parallel to finish, before continuing in the main CommandGroup
- * sequence.
- *
- * This class is provided by the OldCommands VendorDep
- */
-class WaitForChildren : public Command {
- public:
-  explicit WaitForChildren(units::second_t timeout);
-  WaitForChildren(std::string_view name, units::second_t timeout);
-  ~WaitForChildren() override = default;
-
-  WaitForChildren(WaitForChildren&&) = default;
-  WaitForChildren& operator=(WaitForChildren&&) = default;
-
- protected:
-  bool IsFinished() override;
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/WaitUntilCommand.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/WaitUntilCommand.h
deleted file mode 100644
index e9a5cba..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/commands/WaitUntilCommand.h
+++ /dev/null
@@ -1,46 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <string_view>
-
-#include <units/time.h>
-
-#include "frc/commands/Command.h"
-
-namespace frc {
-
-/**
- * A WaitCommand will wait until a certain match time before finishing.
- *
- * This will wait until the game clock reaches some value, then continue to
- * the next command.
- *
- * This class is provided by the OldCommands VendorDep
- *
- * @see CommandGroup
- */
-class WaitUntilCommand : public Command {
- public:
-  explicit WaitUntilCommand(units::second_t time);
-
-  WaitUntilCommand(std::string_view name, units::second_t time);
-
-  ~WaitUntilCommand() override = default;
-
-  WaitUntilCommand(WaitUntilCommand&&) = default;
-  WaitUntilCommand& operator=(WaitUntilCommand&&) = default;
-
- protected:
-  /**
-   * Check if we've reached the actual finish time.
-   */
-  bool IsFinished() override;
-
- private:
-  units::second_t m_time;
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDAnalogAccelerometer.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDAnalogAccelerometer.h
deleted file mode 100644
index d7c0ce8..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDAnalogAccelerometer.h
+++ /dev/null
@@ -1,35 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include "frc/AnalogAccelerometer.h"
-#include "frc/PIDSource.h"
-
-namespace frc {
-
-/**
- * Wrapper so that PIDSource is implemented for AnalogAccelerometer for old
- * PIDController
- *
- * This class is provided by the OldCommands VendorDep
- *
- * @deprecated Use frc2::PIDController class instead which doesn't require this
- * wrapper.
- */
-class WPI_DEPRECATED("Use frc2::PIDController class instead.")
-    PIDAnalogAccelerometer : public PIDSource,
-                             public AnalogAccelerometer {
-  using AnalogAccelerometer::AnalogAccelerometer;
-
- public:
-  /**
-   * Get the Acceleration for the PID Source parent.
-   *
-   * @return The current acceleration in Gs.
-   */
-  double PIDGet() override;
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDAnalogGyro.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDAnalogGyro.h
deleted file mode 100644
index dc73f1e..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDAnalogGyro.h
+++ /dev/null
@@ -1,35 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include "frc/AnalogGyro.h"
-#include "frc/PIDSource.h"
-
-namespace frc {
-
-/**
- * Wrapper so that PIDSource is implemented for AnalogGyro for old PIDController
- *
- * This class is provided by the OldCommands VendorDep
- *
- * @deprecated Use frc2::PIDController class instead which doesn't require this
- * wrapper.
- */
-class WPI_DEPRECATED("Use frc2::PIDController class instead.") PIDAnalogGyro
-    : public PIDSource,
-      public AnalogGyro {
-  using AnalogGyro::AnalogGyro;
-
- public:
-  /**
-   * Get the PIDOutput for the PIDSource base object. Can be set to return
-   * angle or rate using SetPIDSourceType(). Defaults to angle.
-   *
-   * @return The PIDOutput (angle or rate, defaults to angle)
-   */
-  double PIDGet() override;
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDAnalogInput.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDAnalogInput.h
deleted file mode 100644
index ae34e1c..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDAnalogInput.h
+++ /dev/null
@@ -1,35 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include "frc/AnalogInput.h"
-#include "frc/PIDSource.h"
-
-namespace frc {
-
-/**
- * Wrapper so that PIDSource is implemented for AnalogInput for old
- * PIDController
- *
- * This class is provided by the OldCommands VendorDep
- *
- * @deprecated Use frc2::PIDController class instead which doesn't require this
- * wrapper.
- */
-class WPI_DEPRECATED("Use frc2::PIDController class instead.") PIDAnalogInput
-    : public PIDSource,
-      public AnalogInput {
-  using AnalogInput::AnalogInput;
-
- public:
-  /**
-   * Get the Average value for the PID Source base object.
-   *
-   * @return The average voltage.
-   */
-  double PIDGet() override;
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDAnalogPotentiometer.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDAnalogPotentiometer.h
deleted file mode 100644
index cd77b9e..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDAnalogPotentiometer.h
+++ /dev/null
@@ -1,35 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include "frc/AnalogPotentiometer.h"
-#include "frc/PIDSource.h"
-
-namespace frc {
-
-/**
- * Wrapper so that PIDSource is implemented for AnalogPotentiometer for old
- * PIDController
- *
- * This class is provided by the OldCommands VendorDep
- *
- * @deprecated Use frc2::PIDController class instead which doesn't require this
- * wrapper.
- */
-class WPI_DEPRECATED("Use frc2::PIDController class instead.")
-    PIDAnalogPotentiometer : public PIDSource,
-                             public AnalogPotentiometer {
-  using AnalogPotentiometer::AnalogPotentiometer;
-
- public:
-  /**
-   * Implement the PIDSource interface.
-   *
-   * @return The current reading.
-   */
-  double PIDGet() override;
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDEncoder.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDEncoder.h
deleted file mode 100644
index 4e6d5c3..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDEncoder.h
+++ /dev/null
@@ -1,35 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include "frc/Encoder.h"
-#include "frc/PIDSource.h"
-
-namespace frc {
-
-/**
- * Wrapper so that PIDSource is implemented for Encoder for old PIDController
- *
- * This class is provided by the OldCommands VendorDep
- *
- * @deprecated Use frc2::PIDController class instead which doesn't require this
- * wrapper.
- */
-class WPI_DEPRECATED("Use frc2::PIDController class instead.") PIDEncoder
-    : public PIDSource,
-      public Encoder {
-  using Encoder::Encoder;
-
- public:
-  /**
-   * Get the PIDOutput for the PIDSource base object. Can be set to return
-   * distance or rate using SetPIDSourceType(). Defaults to distance.
-   *
-   * @return The PIDOutput (distance or rate, defaults to distance)
-   */
-  double PIDGet() override;
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDMotorController.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDMotorController.h
deleted file mode 100644
index 547264b..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDMotorController.h
+++ /dev/null
@@ -1,69 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <wpi/sendable/Sendable.h>
-#include <wpi/sendable/SendableHelper.h>
-
-#include "frc/PIDOutput.h"
-#include "frc/motorcontrol/MotorController.h"
-
-namespace frc {
-
-/**
- * Wrapper so that PIDOutput is implemented for MotorController for old
- * PIDController
- *
- * This class is provided by the OldCommands VendorDep
- *
- * @deprecated Use frc2::PIDController class instead which doesn't require this
- * wrapper.
- */
-class PIDMotorController : public PIDOutput,
-                           public MotorController,
-                           public wpi::Sendable {
- public:
-  WPI_DEPRECATED("Use frc2::PIDController class instead.")
-  explicit PIDMotorController(MotorController& motorController);
-
-  /**
-   * Set the PWM value.
-   *
-   * The PWM value is set using a range of -1.0 to 1.0, appropriately scaling
-   * the value for the FPGA.
-   *
-   * @param value The speed value between -1.0 and 1.0 to set.
-   */
-  void Set(double value) override;
-
-  /**
-   * Get the recently set value of the PWM. This value is affected by the
-   * inversion property. If you want the value that is sent directly to the
-   * MotorController, use PWM::GetSpeed() instead.
-   *
-   * @return The most recently set value for the PWM between -1.0 and 1.0.
-   */
-  double Get() const override;
-
-  void SetInverted(bool isInverted) override;
-
-  bool GetInverted() const override;
-
-  void Disable() override;
-
-  void StopMotor() override;
-
-  void PIDWrite(double output) override;
-
- protected:
-  void InitSendable(wpi::SendableBuilder& builder) override;
-
- private:
-  bool m_isInverted = false;
-
-  MotorController& m_motorController;
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDUltrasonic.h b/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDUltrasonic.h
deleted file mode 100644
index d3b9fc8..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDUltrasonic.h
+++ /dev/null
@@ -1,34 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include "frc/PIDSource.h"
-#include "frc/Ultrasonic.h"
-
-namespace frc {
-
-/**
- * Wrapper so that PIDSource is implemented for Ultrasonic for old PIDController
- *
- * This class is provided by the OldCommands VendorDep
- *
- * @deprecated Use frc2::PIDController class instead which doesn't require this
- * wrapper.
- */
-class WPI_DEPRECATED("Use frc2::PIDController class instead.") PIDUltrasonic
-    : public PIDSource,
-      public Ultrasonic {
-  using Ultrasonic::Ultrasonic;
-
- public:
-  /**
-   * Get the range for the PIDSource base object.
-   *
-   * @return The range
-   */
-  double PIDGet() override;
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/MockHardwareExtension.java b/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/MockHardwareExtension.java
deleted file mode 100644
index e70f182..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/MockHardwareExtension.java
+++ /dev/null
@@ -1,38 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj;
-
-import edu.wpi.first.hal.HAL;
-import edu.wpi.first.wpilibj.simulation.DriverStationSim;
-import org.junit.jupiter.api.extension.BeforeAllCallback;
-import org.junit.jupiter.api.extension.ExtensionContext;
-import org.junit.jupiter.api.extension.ExtensionContext.Namespace;
-
-public final class MockHardwareExtension implements BeforeAllCallback {
-  private static ExtensionContext getRoot(ExtensionContext context) {
-    return context.getParent().map(MockHardwareExtension::getRoot).orElse(context);
-  }
-
-  @Override
-  public void beforeAll(ExtensionContext context) {
-    getRoot(context)
-        .getStore(Namespace.GLOBAL)
-        .getOrComputeIfAbsent(
-            "HAL Initialized",
-            key -> {
-              initializeHardware();
-              return true;
-            },
-            Boolean.class);
-  }
-
-  private void initializeHardware() {
-    HAL.initialize(500, 0);
-    DriverStationSim.setDsAttached(true);
-    DriverStationSim.setAutonomous(false);
-    DriverStationSim.setEnabled(true);
-    DriverStationSim.setTest(true);
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/AbstractCommandTest.java b/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/AbstractCommandTest.java
deleted file mode 100644
index 55411cc..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/AbstractCommandTest.java
+++ /dev/null
@@ -1,49 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-import static org.junit.jupiter.api.Assertions.assertAll;
-import static org.junit.jupiter.api.Assertions.assertDoesNotThrow;
-import static org.junit.jupiter.api.Assertions.assertEquals;
-
-import org.junit.jupiter.api.BeforeEach;
-
-/** The basic test for all {@link Command} tests. */
-public class AbstractCommandTest {
-  @BeforeEach
-  void commandSetup() {
-    Scheduler.getInstance().removeAll();
-    Scheduler.getInstance().enable();
-  }
-
-  public static class ASubsystem extends Subsystem {
-    Command m_command;
-
-    @Override
-    protected void initDefaultCommand() {
-      if (m_command != null) {
-        setDefaultCommand(m_command);
-      }
-    }
-
-    public void init(Command command) {
-      m_command = command;
-    }
-  }
-
-  protected void assertCommandState(
-      MockCommand command, int initialize, int execute, int isFinished, int end, int interrupted) {
-    assertAll(
-        () -> assertEquals(initialize, command.getInitializeCount()),
-        () -> assertEquals(execute, command.getExecuteCount()),
-        () -> assertEquals(isFinished, command.getIsFinishedCount()),
-        () -> assertEquals(end, command.getEndCount()),
-        () -> assertEquals(interrupted, command.getInterruptedCount()));
-  }
-
-  protected void sleep(int time) {
-    assertDoesNotThrow(() -> Thread.sleep(time));
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/ButtonTest.java b/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/ButtonTest.java
deleted file mode 100644
index 0569268..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/ButtonTest.java
+++ /dev/null
@@ -1,108 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-import edu.wpi.first.wpilibj.buttons.InternalButton;
-import org.junit.jupiter.api.BeforeEach;
-import org.junit.jupiter.api.Test;
-
-/**
- * Test that covers the {@link edu.wpi.first.wpilibj.buttons.Button} with the {@link Command}
- * library.
- */
-class ButtonTest extends AbstractCommandTest {
-  private InternalButton m_button1;
-  private InternalButton m_button2;
-
-  @BeforeEach
-  void setUp() {
-    m_button1 = new InternalButton();
-    m_button2 = new InternalButton();
-  }
-
-  /** Simple Button Test. */
-  @Test
-  void buttonTest() {
-    final MockCommand command1 = new MockCommand();
-    final MockCommand command2 = new MockCommand();
-    final MockCommand command3 = new MockCommand();
-    final MockCommand command4 = new MockCommand();
-
-    m_button1.whenPressed(command1);
-    m_button1.whenReleased(command2);
-    m_button1.whileHeld(command3);
-    m_button2.whileHeld(command4);
-
-    assertCommandState(command1, 0, 0, 0, 0, 0);
-    assertCommandState(command2, 0, 0, 0, 0, 0);
-    assertCommandState(command3, 0, 0, 0, 0, 0);
-    assertCommandState(command4, 0, 0, 0, 0, 0);
-    m_button1.setPressed(true);
-    assertCommandState(command1, 0, 0, 0, 0, 0);
-    assertCommandState(command2, 0, 0, 0, 0, 0);
-    assertCommandState(command3, 0, 0, 0, 0, 0);
-    assertCommandState(command4, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(command1, 0, 0, 0, 0, 0);
-    assertCommandState(command2, 0, 0, 0, 0, 0);
-    assertCommandState(command3, 0, 0, 0, 0, 0);
-    assertCommandState(command4, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(command1, 1, 1, 1, 0, 0);
-    assertCommandState(command2, 0, 0, 0, 0, 0);
-    assertCommandState(command3, 1, 1, 1, 0, 0);
-    assertCommandState(command4, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(command1, 1, 2, 2, 0, 0);
-    assertCommandState(command2, 0, 0, 0, 0, 0);
-    assertCommandState(command3, 1, 2, 2, 0, 0);
-    assertCommandState(command4, 0, 0, 0, 0, 0);
-    m_button2.setPressed(true);
-    Scheduler.getInstance().run();
-    assertCommandState(command1, 1, 3, 3, 0, 0);
-    assertCommandState(command2, 0, 0, 0, 0, 0);
-    assertCommandState(command3, 1, 3, 3, 0, 0);
-    assertCommandState(command4, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(command1, 1, 4, 4, 0, 0);
-    assertCommandState(command2, 0, 0, 0, 0, 0);
-    assertCommandState(command3, 1, 4, 4, 0, 0);
-    assertCommandState(command4, 1, 1, 1, 0, 0);
-    m_button1.setPressed(false);
-    Scheduler.getInstance().run();
-    assertCommandState(command1, 1, 5, 5, 0, 0);
-    assertCommandState(command2, 0, 0, 0, 0, 0);
-    assertCommandState(command3, 1, 4, 4, 0, 1);
-    assertCommandState(command4, 1, 2, 2, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(command1, 1, 6, 6, 0, 0);
-    assertCommandState(command2, 1, 1, 1, 0, 0);
-    assertCommandState(command3, 1, 4, 4, 0, 1);
-    assertCommandState(command4, 1, 3, 3, 0, 0);
-    m_button2.setPressed(false);
-    Scheduler.getInstance().run();
-    assertCommandState(command1, 1, 7, 7, 0, 0);
-    assertCommandState(command2, 1, 2, 2, 0, 0);
-    assertCommandState(command3, 1, 4, 4, 0, 1);
-    assertCommandState(command4, 1, 3, 3, 0, 1);
-    command1.cancel();
-    Scheduler.getInstance().run();
-    assertCommandState(command1, 1, 7, 7, 0, 1);
-    assertCommandState(command2, 1, 3, 3, 0, 0);
-    assertCommandState(command3, 1, 4, 4, 0, 1);
-    assertCommandState(command4, 1, 3, 3, 0, 1);
-    command2.setHasFinished(true);
-    Scheduler.getInstance().run();
-    assertCommandState(command1, 1, 7, 7, 0, 1);
-    assertCommandState(command2, 1, 4, 4, 1, 0);
-    assertCommandState(command3, 1, 4, 4, 0, 1);
-    assertCommandState(command4, 1, 3, 3, 0, 1);
-    Scheduler.getInstance().run();
-    assertCommandState(command1, 1, 7, 7, 0, 1);
-    assertCommandState(command2, 1, 4, 4, 1, 0);
-    assertCommandState(command3, 1, 4, 4, 0, 1);
-    assertCommandState(command4, 1, 3, 3, 0, 1);
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/CommandParallelGroupTest.java b/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/CommandParallelGroupTest.java
deleted file mode 100644
index 04a920c..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/CommandParallelGroupTest.java
+++ /dev/null
@@ -1,48 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-import org.junit.jupiter.api.Test;
-
-/** Ported from the old CrioTest Classes. */
-class CommandParallelGroupTest extends AbstractCommandTest {
-  /** Simple Parallel Command Group With 2 commands one command terminates first. */
-  @Test
-  void parallelCommandGroupWithTwoCommandsTest() {
-    final MockCommand command1 = new MockCommand();
-    final MockCommand command2 = new MockCommand();
-
-    try (CommandGroup commandGroup = new CommandGroup()) {
-      commandGroup.addParallel(command1);
-      commandGroup.addParallel(command2);
-
-      assertCommandState(command1, 0, 0, 0, 0, 0);
-      assertCommandState(command2, 0, 0, 0, 0, 0);
-      commandGroup.start();
-      assertCommandState(command1, 0, 0, 0, 0, 0);
-      assertCommandState(command2, 0, 0, 0, 0, 0);
-      Scheduler.getInstance().run();
-      assertCommandState(command1, 0, 0, 0, 0, 0);
-      assertCommandState(command2, 0, 0, 0, 0, 0);
-      Scheduler.getInstance().run();
-      assertCommandState(command1, 1, 1, 1, 0, 0);
-      assertCommandState(command2, 1, 1, 1, 0, 0);
-      Scheduler.getInstance().run();
-      assertCommandState(command1, 1, 2, 2, 0, 0);
-      assertCommandState(command2, 1, 2, 2, 0, 0);
-      command1.setHasFinished(true);
-      Scheduler.getInstance().run();
-      assertCommandState(command1, 1, 3, 3, 1, 0);
-      assertCommandState(command2, 1, 3, 3, 0, 0);
-      Scheduler.getInstance().run();
-      assertCommandState(command1, 1, 3, 3, 1, 0);
-      assertCommandState(command2, 1, 4, 4, 0, 0);
-      command2.setHasFinished(true);
-      Scheduler.getInstance().run();
-      assertCommandState(command1, 1, 3, 3, 1, 0);
-      assertCommandState(command2, 1, 5, 5, 1, 0);
-    }
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/CommandScheduleTest.java b/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/CommandScheduleTest.java
deleted file mode 100644
index 5592045..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/CommandScheduleTest.java
+++ /dev/null
@@ -1,54 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-import org.junit.jupiter.api.Test;
-
-/** Ported from the old CrioTest Classes. */
-class CommandScheduleTest extends AbstractCommandTest {
-  /**
-   * Simple scheduling of a command and making sure the command is run and successfully terminates.
-   */
-  @Test
-  void runAndTerminateTest() {
-    final MockCommand command = new MockCommand();
-    command.start();
-    assertCommandState(command, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(command, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(command, 1, 1, 1, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(command, 1, 2, 2, 0, 0);
-    command.setHasFinished(true);
-    assertCommandState(command, 1, 2, 2, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(command, 1, 3, 3, 1, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(command, 1, 3, 3, 1, 0);
-  }
-
-  /** Simple scheduling of a command and making sure the command is run and cancels correctly. */
-  @Test
-  void runAndCancelTest() {
-    final MockCommand command = new MockCommand();
-    command.start();
-    assertCommandState(command, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(command, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(command, 1, 1, 1, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(command, 1, 2, 2, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(command, 1, 3, 3, 0, 0);
-    command.cancel();
-    assertCommandState(command, 1, 3, 3, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(command, 1, 3, 3, 0, 1);
-    Scheduler.getInstance().run();
-    assertCommandState(command, 1, 3, 3, 0, 1);
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/CommandSequentialGroupTest.java b/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/CommandSequentialGroupTest.java
deleted file mode 100644
index d8ef933..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/CommandSequentialGroupTest.java
+++ /dev/null
@@ -1,86 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-import java.util.logging.Logger;
-import org.junit.jupiter.api.Test;
-
-/** Ported from the old CrioTest Classes. */
-class CommandSequentialGroupTest extends AbstractCommandTest {
-  private static final Logger logger = Logger.getLogger(CommandSequentialGroupTest.class.getName());
-
-  /**
-   * Simple Command Group With 3 commands that all depend on a subsystem. Some commands have a
-   * timeout.
-   */
-  @Test
-  void testThreeCommandOnSubSystem() {
-    logger.fine("Beginning Test");
-    final ASubsystem subsystem = new ASubsystem();
-
-    logger.finest("Creating Mock Command1");
-    final MockCommand command1 = new MockCommand(subsystem);
-    logger.finest("Creating Mock Command2");
-    final MockCommand command2 = new MockCommand(subsystem);
-    logger.finest("Creating Mock Command3");
-    final MockCommand command3 = new MockCommand(subsystem);
-
-    logger.finest("Creating Command Group");
-    try (CommandGroup commandGroup = new CommandGroup()) {
-      commandGroup.addSequential(command1, 1.0);
-      commandGroup.addSequential(command2, 2.0);
-      commandGroup.addSequential(command3);
-
-      assertCommandState(command1, 0, 0, 0, 0, 0);
-      assertCommandState(command2, 0, 0, 0, 0, 0);
-      assertCommandState(command3, 0, 0, 0, 0, 0);
-      logger.finest("Starting Command group");
-      commandGroup.start();
-      assertCommandState(command1, 0, 0, 0, 0, 0);
-      assertCommandState(command2, 0, 0, 0, 0, 0);
-      assertCommandState(command3, 0, 0, 0, 0, 0);
-      Scheduler.getInstance().run();
-      assertCommandState(command1, 0, 0, 0, 0, 0);
-      assertCommandState(command2, 0, 0, 0, 0, 0);
-      assertCommandState(command3, 0, 0, 0, 0, 0);
-      Scheduler.getInstance().run();
-      assertCommandState(command1, 1, 1, 1, 0, 0);
-      assertCommandState(command2, 0, 0, 0, 0, 0);
-      assertCommandState(command3, 0, 0, 0, 0, 0);
-      sleep(1250); // command 1 timeout
-      Scheduler.getInstance().run();
-      assertCommandState(command1, 1, 1, 1, 0, 1);
-      assertCommandState(command2, 1, 1, 1, 0, 0);
-      assertCommandState(command3, 0, 0, 0, 0, 0);
-
-      Scheduler.getInstance().run();
-      assertCommandState(command1, 1, 1, 1, 0, 1);
-      assertCommandState(command2, 1, 2, 2, 0, 0);
-      assertCommandState(command3, 0, 0, 0, 0, 0);
-      sleep(2500); // command 2 timeout
-      Scheduler.getInstance().run();
-      assertCommandState(command1, 1, 1, 1, 0, 1);
-      assertCommandState(command2, 1, 2, 2, 0, 1);
-      assertCommandState(command3, 1, 1, 1, 0, 0);
-
-      Scheduler.getInstance().run();
-      assertCommandState(command1, 1, 1, 1, 0, 1);
-      assertCommandState(command2, 1, 2, 2, 0, 1);
-      assertCommandState(command3, 1, 2, 2, 0, 0);
-      command3.setHasFinished(true);
-      assertCommandState(command1, 1, 1, 1, 0, 1);
-      assertCommandState(command2, 1, 2, 2, 0, 1);
-      assertCommandState(command3, 1, 2, 2, 0, 0);
-      Scheduler.getInstance().run();
-      assertCommandState(command1, 1, 1, 1, 0, 1);
-      assertCommandState(command2, 1, 2, 2, 0, 1);
-      assertCommandState(command3, 1, 3, 3, 1, 0);
-      Scheduler.getInstance().run();
-      assertCommandState(command1, 1, 1, 1, 0, 1);
-      assertCommandState(command2, 1, 2, 2, 0, 1);
-      assertCommandState(command3, 1, 3, 3, 1, 0);
-    }
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/CommandSupersedeTest.java b/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/CommandSupersedeTest.java
deleted file mode 100644
index 7169c39..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/CommandSupersedeTest.java
+++ /dev/null
@@ -1,92 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-import org.junit.jupiter.api.Test;
-
-/** Ported from the old CrioTest Classes. */
-class CommandSupersedeTest extends AbstractCommandTest {
-  /** Testing one command superseding another because of dependencies. */
-  @Test
-  void oneCommandSupersedingAnotherBecauseOfDependenciesTest() {
-    final ASubsystem subsystem = new ASubsystem();
-
-    final MockCommand command1 = new MockCommand(subsystem);
-
-    final MockCommand command2 = new MockCommand(subsystem);
-
-    assertCommandState(command1, 0, 0, 0, 0, 0);
-    assertCommandState(command2, 0, 0, 0, 0, 0);
-    command1.start();
-    assertCommandState(command1, 0, 0, 0, 0, 0);
-    assertCommandState(command2, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(command1, 0, 0, 0, 0, 0);
-    assertCommandState(command2, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(command1, 1, 1, 1, 0, 0);
-    assertCommandState(command2, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(command1, 1, 2, 2, 0, 0);
-    assertCommandState(command2, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(command1, 1, 3, 3, 0, 0);
-    assertCommandState(command2, 0, 0, 0, 0, 0);
-    command2.start();
-    assertCommandState(command1, 1, 3, 3, 0, 0);
-    assertCommandState(command2, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(command1, 1, 4, 4, 0, 1);
-    assertCommandState(command2, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(command1, 1, 4, 4, 0, 1);
-    assertCommandState(command2, 1, 1, 1, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(command1, 1, 4, 4, 0, 1);
-    assertCommandState(command2, 1, 2, 2, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(command1, 1, 4, 4, 0, 1);
-    assertCommandState(command2, 1, 3, 3, 0, 0);
-  }
-
-  /**
-   * Testing one command failing superseding another because of dependencies because the first
-   * command cannot be interrupted.
-   */
-  @Test
-  @SuppressWarnings("PMD.NonStaticInitializer")
-  void commandFailingSupersedingBecauseFirstCanNotBeInterruptedTest() {
-    final ASubsystem subsystem = new ASubsystem();
-
-    final MockCommand command1 = new MockCommand(subsystem);
-    command1.setInterruptible(false);
-
-    final MockCommand command2 = new MockCommand(subsystem);
-
-    assertCommandState(command1, 0, 0, 0, 0, 0);
-    assertCommandState(command2, 0, 0, 0, 0, 0);
-    command1.start();
-    assertCommandState(command1, 0, 0, 0, 0, 0);
-    assertCommandState(command2, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(command1, 0, 0, 0, 0, 0);
-    assertCommandState(command2, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(command1, 1, 1, 1, 0, 0);
-    assertCommandState(command2, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(command1, 1, 2, 2, 0, 0);
-    assertCommandState(command2, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(command1, 1, 3, 3, 0, 0);
-    assertCommandState(command2, 0, 0, 0, 0, 0);
-    command2.start();
-    assertCommandState(command1, 1, 3, 3, 0, 0);
-    assertCommandState(command2, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(command1, 1, 4, 4, 0, 0);
-    assertCommandState(command2, 0, 0, 0, 0, 0);
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/CommandTimeoutTest.java b/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/CommandTimeoutTest.java
deleted file mode 100644
index 069e099..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/CommandTimeoutTest.java
+++ /dev/null
@@ -1,40 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-import org.junit.jupiter.api.Test;
-
-/** Test a {@link Command} that times out. */
-class CommandTimeoutTest extends AbstractCommandTest {
-  /** Command 2 second Timeout Test. */
-  @Test
-  void twoSecondTimeoutTest() {
-    final ASubsystem subsystem = new ASubsystem();
-
-    final MockCommand command =
-        new MockCommand(subsystem, 2) {
-          @Override
-          public boolean isFinished() {
-            return super.isFinished() || isTimedOut();
-          }
-        };
-
-    command.start();
-    assertCommandState(command, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(command, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(command, 1, 1, 1, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(command, 1, 2, 2, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(command, 1, 3, 3, 0, 0);
-    sleep(2500);
-    Scheduler.getInstance().run();
-    assertCommandState(command, 1, 4, 4, 1, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(command, 1, 4, 4, 1, 0);
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/ConditionalCommandTest.java b/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/ConditionalCommandTest.java
deleted file mode 100644
index 97d3377..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/ConditionalCommandTest.java
+++ /dev/null
@@ -1,345 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-import static org.junit.jupiter.api.Assertions.assertEquals;
-import static org.junit.jupiter.api.Assertions.assertSame;
-import static org.junit.jupiter.api.Assertions.assertTrue;
-
-import org.junit.jupiter.api.BeforeEach;
-import org.junit.jupiter.api.Test;
-
-class ConditionalCommandTest extends AbstractCommandTest {
-  MockConditionalCommand m_command;
-  MockConditionalCommand m_commandNull;
-  MockCommand m_onTrue;
-  MockCommand m_onFalse;
-  MockSubsystem m_subsys;
-
-  @BeforeEach
-  void initCommands() {
-    m_subsys = new MockSubsystem();
-    m_onTrue = new MockCommand(m_subsys);
-    m_onFalse = new MockCommand(m_subsys);
-    m_command = new MockConditionalCommand(m_onTrue, m_onFalse);
-    m_commandNull = new MockConditionalCommand(m_onTrue, null);
-  }
-
-  protected void assertConditionalCommandState(
-      MockConditionalCommand command,
-      int initialize,
-      int execute,
-      int isFinished,
-      int end,
-      int interrupted) {
-    assertEquals(initialize, command.getInitializeCount());
-    assertEquals(execute, command.getExecuteCount());
-    assertEquals(isFinished, command.getIsFinishedCount());
-    assertEquals(end, command.getEndCount());
-    assertEquals(interrupted, command.getInterruptedCount());
-  }
-
-  @Test
-  void onTrueTest() {
-    m_command.setCondition(true);
-
-    Scheduler.getInstance().add(m_command);
-    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run(); // init command and select m_onTrue
-    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run(); // init m_onTrue
-    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 1, 1, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(m_onTrue, 1, 1, 1, 0, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 2, 2, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(m_onTrue, 1, 2, 2, 0, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 3, 3, 0, 0);
-    m_onTrue.setHasFinished(true);
-    Scheduler.getInstance().run();
-    assertCommandState(m_onTrue, 1, 3, 3, 1, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 4, 4, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(m_onTrue, 1, 3, 3, 1, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 5, 5, 1, 0);
-
-    assertTrue(m_onTrue.getInitializeCount() > 0, "Did not initialize the true command");
-    assertSame(m_onFalse.getInitializeCount(), 0, "Initialized the false command");
-  }
-
-  @Test
-  void onFalseTest() {
-    m_command.setCondition(false);
-
-    Scheduler.getInstance().add(m_command);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run(); // init command and select m_onFalse
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run(); // init m_onFalse
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 1, 1, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(m_onFalse, 1, 1, 1, 0, 0);
-    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 2, 2, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(m_onFalse, 1, 2, 2, 0, 0);
-    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 3, 3, 0, 0);
-    m_onFalse.setHasFinished(true);
-    Scheduler.getInstance().run();
-    assertCommandState(m_onFalse, 1, 3, 3, 1, 0);
-    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 4, 4, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(m_onFalse, 1, 3, 3, 1, 0);
-    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 5, 5, 1, 0);
-
-    assertTrue(m_onFalse.getInitializeCount() > 0, "Did not initialize the false command");
-    assertSame(m_onTrue.getInitializeCount(), 0, "Initialized the true command");
-  }
-
-  @Test
-  void cancelSubCommandTest() {
-    m_command.setCondition(true);
-
-    Scheduler.getInstance().add(m_command);
-    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run(); // init command and select m_onTrue
-    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run(); // init m_onTrue
-    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 1, 1, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(m_onTrue, 1, 1, 1, 0, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 2, 2, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(m_onTrue, 1, 2, 2, 0, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 3, 3, 0, 0);
-    m_onTrue.cancel();
-    Scheduler.getInstance().run();
-    assertCommandState(m_onTrue, 1, 2, 2, 0, 1);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 4, 4, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(m_onTrue, 1, 2, 2, 0, 1);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 5, 5, 1, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(m_onTrue, 1, 2, 2, 0, 1);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 5, 5, 1, 0);
-  }
-
-  @Test
-  void cancelRequiresTest() {
-    m_command.setCondition(true);
-
-    Scheduler.getInstance().add(m_command);
-    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run(); // init command and select m_onTrue
-    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run(); // init m_onTrue
-    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 1, 1, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(m_onTrue, 1, 1, 1, 0, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 2, 2, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(m_onTrue, 1, 2, 2, 0, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 3, 3, 0, 0);
-    m_onFalse.start();
-    Scheduler.getInstance().run();
-    assertCommandState(m_onTrue, 1, 3, 3, 0, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 4, 4, 0, 1);
-    Scheduler.getInstance().run();
-    assertCommandState(m_onTrue, 1, 3, 3, 0, 1);
-    assertCommandState(m_onFalse, 1, 1, 1, 0, 0);
-    assertConditionalCommandState(m_command, 1, 4, 4, 0, 1);
-  }
-
-  @Test
-  void cancelCondCommandTest() {
-    m_command.setCondition(true);
-
-    Scheduler.getInstance().add(m_command);
-    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run(); // init command and select m_onTrue
-    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run(); // init m_onTrue
-    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 1, 1, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(m_onTrue, 1, 1, 1, 0, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 2, 2, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(m_onTrue, 1, 2, 2, 0, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 3, 3, 0, 0);
-    m_command.cancel();
-    Scheduler.getInstance().run();
-    assertCommandState(m_onTrue, 1, 2, 2, 0, 1);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 3, 3, 0, 1);
-    Scheduler.getInstance().run();
-    assertCommandState(m_onTrue, 1, 2, 2, 0, 1);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 3, 3, 0, 1);
-  }
-
-  @Test
-  void onTrueTwiceTest() {
-    m_command.setCondition(true);
-
-    Scheduler.getInstance().add(m_command);
-    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run(); // init command and select m_onTrue
-    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run(); // init m_onTrue
-    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 1, 1, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(m_onTrue, 1, 1, 1, 0, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 2, 2, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(m_onTrue, 1, 2, 2, 0, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 3, 3, 0, 0);
-    m_onTrue.setHasFinished(true);
-    Scheduler.getInstance().run();
-    assertCommandState(m_onTrue, 1, 3, 3, 1, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 4, 4, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(m_onTrue, 1, 3, 3, 1, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 5, 5, 1, 0);
-
-    m_onTrue.resetCounters();
-    m_command.resetCounters();
-    m_command.setCondition(true);
-    Scheduler.getInstance().add(m_command);
-    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run(); // init command and select m_onTrue
-    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run(); // init m_onTrue
-    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 1, 1, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(m_onTrue, 1, 1, 1, 0, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 2, 2, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(m_onTrue, 1, 2, 2, 0, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 3, 3, 0, 0);
-    m_onTrue.setHasFinished(true);
-    Scheduler.getInstance().run();
-    assertCommandState(m_onTrue, 1, 3, 3, 1, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 4, 4, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(m_onTrue, 1, 3, 3, 1, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 5, 5, 1, 0);
-  }
-
-  @Test
-  void onTrueInstantTest() {
-    m_command.setCondition(true);
-    m_onTrue.setHasFinished(true);
-
-    Scheduler.getInstance().add(m_command);
-    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run(); // init command and select m_onTrue
-    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run(); // init m_onTrue
-    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 1, 1, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(m_onTrue, 1, 1, 1, 1, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 2, 2, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(m_onTrue, 1, 1, 1, 1, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 3, 3, 1, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(m_onTrue, 1, 1, 1, 1, 0);
-    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_command, 1, 3, 3, 1, 0);
-  }
-
-  @Test
-  void onFalseNullTest() {
-    m_commandNull.setCondition(false);
-
-    Scheduler.getInstance().add(m_commandNull);
-    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_commandNull, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run(); // init command and select m_onFalse
-    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_commandNull, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run(); // init m_onFalse
-    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_commandNull, 1, 1, 1, 1, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
-    assertConditionalCommandState(m_commandNull, 1, 1, 1, 1, 0);
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/DefaultCommandTest.java b/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/DefaultCommandTest.java
deleted file mode 100644
index 8539d44..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/DefaultCommandTest.java
+++ /dev/null
@@ -1,99 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-import org.junit.jupiter.api.Test;
-
-/** Tests the {@link Command} library. */
-class DefaultCommandTest extends AbstractCommandTest {
-  /** Testing of default commands where the interrupting command ends itself. */
-  @Test
-  void defaultCommandWhereTheInteruptingCommandEndsItselfTest() {
-    final ASubsystem subsystem = new ASubsystem();
-
-    final MockCommand defaultCommand = new MockCommand(subsystem);
-
-    final MockCommand anotherCommand = new MockCommand(subsystem);
-    assertCommandState(defaultCommand, 0, 0, 0, 0, 0);
-    subsystem.init(defaultCommand);
-
-    assertCommandState(defaultCommand, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(defaultCommand, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(defaultCommand, 1, 1, 1, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(defaultCommand, 1, 2, 2, 0, 0);
-
-    anotherCommand.start();
-    assertCommandState(defaultCommand, 1, 2, 2, 0, 0);
-    assertCommandState(anotherCommand, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(defaultCommand, 1, 3, 3, 0, 1);
-    assertCommandState(anotherCommand, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(defaultCommand, 1, 3, 3, 0, 1);
-    assertCommandState(anotherCommand, 1, 1, 1, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(defaultCommand, 1, 3, 3, 0, 1);
-    assertCommandState(anotherCommand, 1, 2, 2, 0, 0);
-    anotherCommand.setHasFinished(true);
-    assertCommandState(defaultCommand, 1, 3, 3, 0, 1);
-    assertCommandState(anotherCommand, 1, 2, 2, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(defaultCommand, 1, 3, 3, 0, 1);
-    assertCommandState(anotherCommand, 1, 3, 3, 1, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(defaultCommand, 2, 4, 4, 0, 1);
-    assertCommandState(anotherCommand, 1, 3, 3, 1, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(defaultCommand, 2, 5, 5, 0, 1);
-    assertCommandState(anotherCommand, 1, 3, 3, 1, 0);
-  }
-
-  /** Testing of default commands where the interrupting command is canceled. */
-  @Test
-  void defaultCommandsInterruptingCommandCanceledTest() {
-    final ASubsystem subsystem = new ASubsystem();
-    final MockCommand defaultCommand = new MockCommand(subsystem);
-    final MockCommand anotherCommand = new MockCommand(subsystem);
-
-    assertCommandState(defaultCommand, 0, 0, 0, 0, 0);
-    subsystem.init(defaultCommand);
-    subsystem.initDefaultCommand();
-    assertCommandState(defaultCommand, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(defaultCommand, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(defaultCommand, 1, 1, 1, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(defaultCommand, 1, 2, 2, 0, 0);
-
-    anotherCommand.start();
-    assertCommandState(defaultCommand, 1, 2, 2, 0, 0);
-    assertCommandState(anotherCommand, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(defaultCommand, 1, 3, 3, 0, 1);
-    assertCommandState(anotherCommand, 0, 0, 0, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(defaultCommand, 1, 3, 3, 0, 1);
-    assertCommandState(anotherCommand, 1, 1, 1, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(defaultCommand, 1, 3, 3, 0, 1);
-    assertCommandState(anotherCommand, 1, 2, 2, 0, 0);
-    anotherCommand.cancel();
-    assertCommandState(defaultCommand, 1, 3, 3, 0, 1);
-    assertCommandState(anotherCommand, 1, 2, 2, 0, 0);
-    Scheduler.getInstance().run();
-    assertCommandState(defaultCommand, 1, 3, 3, 0, 1);
-    assertCommandState(anotherCommand, 1, 2, 2, 0, 1);
-    Scheduler.getInstance().run();
-    assertCommandState(defaultCommand, 2, 4, 4, 0, 1);
-    assertCommandState(anotherCommand, 1, 2, 2, 0, 1);
-    Scheduler.getInstance().run();
-    assertCommandState(defaultCommand, 2, 5, 5, 0, 1);
-    assertCommandState(anotherCommand, 1, 2, 2, 0, 1);
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/MockCommand.java b/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/MockCommand.java
deleted file mode 100644
index 5d1715b..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/MockCommand.java
+++ /dev/null
@@ -1,126 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-/**
- * A class to simulate a simple command. The command keeps track of how many times each method was
- * called.
- */
-public class MockCommand extends Command {
-  private int m_initializeCount;
-  private int m_executeCount;
-  private int m_isFinishedCount;
-  private boolean m_hasFinished;
-  private int m_endCount;
-  private int m_interruptedCount;
-
-  public MockCommand(Subsystem subsys) {
-    super();
-    requires(subsys);
-  }
-
-  public MockCommand(Subsystem subsys, double timeout) {
-    this(subsys);
-    setTimeout(timeout);
-  }
-
-  public MockCommand() {
-    super();
-  }
-
-  @Override
-  protected void initialize() {
-    ++m_initializeCount;
-  }
-
-  @Override
-  protected void execute() {
-    ++m_executeCount;
-  }
-
-  @Override
-  protected boolean isFinished() {
-    ++m_isFinishedCount;
-    return isHasFinished();
-  }
-
-  @Override
-  protected void end() {
-    ++m_endCount;
-  }
-
-  @Override
-  protected void interrupted() {
-    ++m_interruptedCount;
-  }
-
-  /** How many times the initialize method has been called. */
-  public int getInitializeCount() {
-    return m_initializeCount;
-  }
-
-  /** If the initialize method has been called at least once. */
-  public boolean hasInitialized() {
-    return getInitializeCount() > 0;
-  }
-
-  /** How many time the execute method has been called. */
-  public int getExecuteCount() {
-    return m_executeCount;
-  }
-
-  /** How many times the isFinished method has been called. */
-  public int getIsFinishedCount() {
-    return m_isFinishedCount;
-  }
-
-  /**
-   * Get what value the isFinished method will return.
-   *
-   * @return what value the isFinished method will return.
-   */
-  public boolean isHasFinished() {
-    return m_hasFinished;
-  }
-
-  /**
-   * Set what value the isFinished method will return.
-   *
-   * @param hasFinished set what value the isFinished method will return.
-   */
-  public void setHasFinished(boolean hasFinished) {
-    m_hasFinished = hasFinished;
-  }
-
-  /** How many times the end method has been called. */
-  public int getEndCount() {
-    return m_endCount;
-  }
-
-  /** If the end method has been called at least once. */
-  public boolean hasEnd() {
-    return getEndCount() > 0;
-  }
-
-  /** How many times the interrupted method has been called. */
-  public int getInterruptedCount() {
-    return m_interruptedCount;
-  }
-
-  /** If the interrupted method has been called at least once. */
-  public boolean hasInterrupted() {
-    return getInterruptedCount() > 0;
-  }
-
-  /** Reset internal counters. */
-  public void resetCounters() {
-    m_initializeCount = 0;
-    m_executeCount = 0;
-    m_isFinishedCount = 0;
-    m_hasFinished = false;
-    m_endCount = 0;
-    m_interruptedCount = 0;
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/MockConditionalCommand.java b/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/MockConditionalCommand.java
deleted file mode 100644
index 8ac2aee..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/MockConditionalCommand.java
+++ /dev/null
@@ -1,103 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-public class MockConditionalCommand extends ConditionalCommand {
-  private boolean m_condition;
-  private int m_initializeCount;
-  private int m_executeCount;
-  private int m_isFinishedCount;
-  private int m_endCount;
-  private int m_interruptedCount;
-
-  public MockConditionalCommand(MockCommand onTrue, MockCommand onFalse) {
-    super(onTrue, onFalse);
-  }
-
-  @Override
-  protected boolean condition() {
-    return m_condition;
-  }
-
-  public void setCondition(boolean condition) {
-    this.m_condition = condition;
-  }
-
-  @Override
-  protected void initialize() {
-    ++m_initializeCount;
-  }
-
-  @Override
-  protected void execute() {
-    ++m_executeCount;
-  }
-
-  @Override
-  protected boolean isFinished() {
-    ++m_isFinishedCount;
-    return super.isFinished();
-  }
-
-  @Override
-  protected void end() {
-    ++m_endCount;
-  }
-
-  @Override
-  protected void interrupted() {
-    ++m_interruptedCount;
-  }
-
-  /** How many times the initialize method has been called. */
-  public int getInitializeCount() {
-    return m_initializeCount;
-  }
-
-  /** If the initialize method has been called at least once. */
-  public boolean hasInitialized() {
-    return getInitializeCount() > 0;
-  }
-
-  /** How many time the execute method has been called. */
-  public int getExecuteCount() {
-    return m_executeCount;
-  }
-
-  /** How many times the isFinished method has been called. */
-  public int getIsFinishedCount() {
-    return m_isFinishedCount;
-  }
-
-  /** How many times the end method has been called. */
-  public int getEndCount() {
-    return m_endCount;
-  }
-
-  /** If the end method has been called at least once. */
-  public boolean hasEnd() {
-    return getEndCount() > 0;
-  }
-
-  /** How many times the interrupted method has been called. */
-  public int getInterruptedCount() {
-    return m_interruptedCount;
-  }
-
-  /** If the interrupted method has been called at least once. */
-  public boolean hasInterrupted() {
-    return getInterruptedCount() > 0;
-  }
-
-  /** Reset internal counters. */
-  public void resetCounters() {
-    m_condition = false;
-    m_initializeCount = 0;
-    m_executeCount = 0;
-    m_isFinishedCount = 0;
-    m_endCount = 0;
-    m_interruptedCount = 0;
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/MockSubsystem.java b/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/MockSubsystem.java
deleted file mode 100644
index e2b1bf7..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/MockSubsystem.java
+++ /dev/null
@@ -1,11 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-/** A class to simulate a simple subsystem. */
-public class MockSubsystem extends Subsystem {
-  @Override
-  protected void initDefaultCommand() {}
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardTabTest.java b/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardTabTest.java
deleted file mode 100644
index c7deb23..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardTabTest.java
+++ /dev/null
@@ -1,146 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.shuffleboard;
-
-import static org.junit.jupiter.api.Assertions.assertAll;
-import static org.junit.jupiter.api.Assertions.assertArrayEquals;
-import static org.junit.jupiter.api.Assertions.assertEquals;
-import static org.junit.jupiter.api.Assertions.assertFalse;
-import static org.junit.jupiter.api.Assertions.assertThrows;
-
-import edu.wpi.first.networktables.NetworkTableEntry;
-import edu.wpi.first.networktables.NetworkTableInstance;
-import edu.wpi.first.util.sendable.Sendable;
-import edu.wpi.first.wpilibj.command.InstantCommand;
-import java.util.HashMap;
-import java.util.Map;
-import org.junit.jupiter.api.AfterEach;
-import org.junit.jupiter.api.BeforeEach;
-import org.junit.jupiter.api.Test;
-
-class ShuffleboardTabTest {
-  private NetworkTableInstance m_ntInstance;
-  private ShuffleboardTab m_tab;
-  private ShuffleboardInstance m_instance;
-
-  @BeforeEach
-  void setup() {
-    m_ntInstance = NetworkTableInstance.create();
-    m_instance = new ShuffleboardInstance(m_ntInstance);
-    m_tab = m_instance.getTab("Tab");
-  }
-
-  @AfterEach
-  void tearDown() {
-    m_ntInstance.close();
-  }
-
-  @Test
-  void testAddDouble() {
-    NetworkTableEntry entry = m_tab.add("Double", 1.0).getEntry();
-    assertAll(
-        () -> assertEquals("/Shuffleboard/Tab/Double", entry.getName()),
-        () -> assertEquals(1.0, entry.getValue().getDouble()));
-  }
-
-  @Test
-  void testAddInteger() {
-    NetworkTableEntry entry = m_tab.add("Int", 1).getEntry();
-    assertAll(
-        () -> assertEquals("/Shuffleboard/Tab/Int", entry.getName()),
-        () -> assertEquals(1.0, entry.getValue().getDouble()));
-  }
-
-  @Test
-  void testAddLong() {
-    NetworkTableEntry entry = m_tab.add("Long", 1L).getEntry();
-    assertAll(
-        () -> assertEquals("/Shuffleboard/Tab/Long", entry.getName()),
-        () -> assertEquals(1.0, entry.getValue().getDouble()));
-  }
-
-  @Test
-  void testAddBoolean() {
-    NetworkTableEntry entry = m_tab.add("Bool", false).getEntry();
-    assertAll(
-        () -> assertEquals("/Shuffleboard/Tab/Bool", entry.getName()),
-        () -> assertFalse(entry.getValue().getBoolean()));
-  }
-
-  @Test
-  void testAddString() {
-    NetworkTableEntry entry = m_tab.add("String", "foobar").getEntry();
-    assertAll(
-        () -> assertEquals("/Shuffleboard/Tab/String", entry.getName()),
-        () -> assertEquals("foobar", entry.getValue().getString()));
-  }
-
-  @Test
-  void testAddNamedSendableWithProperties() {
-    Sendable sendable = new InstantCommand("Command");
-    String widgetType = "Command Widget";
-    m_tab.add(sendable).withWidget(widgetType).withProperties(mapOf("foo", 1234, "bar", "baz"));
-
-    m_instance.update();
-    String meta = "/Shuffleboard/.metadata/Tab/Command";
-
-    assertAll(
-        () ->
-            assertEquals(
-                1234,
-                m_ntInstance.getEntry(meta + "/Properties/foo").getDouble(-1),
-                "Property 'foo' not set correctly"),
-        () ->
-            assertEquals(
-                "baz",
-                m_ntInstance.getEntry(meta + "/Properties/bar").getString(null),
-                "Property 'bar' not set correctly"),
-        () ->
-            assertEquals(
-                widgetType,
-                m_ntInstance.getEntry(meta + "/PreferredComponent").getString(null),
-                "Preferred component not set correctly"));
-  }
-
-  @Test
-  void testAddNumberArray() {
-    NetworkTableEntry entry = m_tab.add("DoubleArray", new double[] {1, 2, 3}).getEntry();
-    assertAll(
-        () -> assertEquals("/Shuffleboard/Tab/DoubleArray", entry.getName()),
-        () -> assertArrayEquals(new double[] {1, 2, 3}, entry.getValue().getDoubleArray()));
-  }
-
-  @Test
-  void testAddBooleanArray() {
-    NetworkTableEntry entry = m_tab.add("BoolArray", new boolean[] {true, false}).getEntry();
-    assertAll(
-        () -> assertEquals("/Shuffleboard/Tab/BoolArray", entry.getName()),
-        () -> assertArrayEquals(new boolean[] {true, false}, entry.getValue().getBooleanArray()));
-  }
-
-  @Test
-  void testAddStringArray() {
-    NetworkTableEntry entry = m_tab.add("StringArray", new String[] {"foo", "bar"}).getEntry();
-    assertAll(
-        () -> assertEquals("/Shuffleboard/Tab/StringArray", entry.getName()),
-        () -> assertArrayEquals(new String[] {"foo", "bar"}, entry.getValue().getStringArray()));
-  }
-
-  @Test
-  void testTitleDuplicates() {
-    m_tab.add("foo", "bar");
-    assertThrows(IllegalArgumentException.class, () -> m_tab.add("foo", "baz"));
-  }
-
-  /** Stub for Java 9 {@code Map.of()}. */
-  @SuppressWarnings("unchecked")
-  private static <K, V> Map<K, V> mapOf(Object... entries) {
-    Map<K, V> map = new HashMap<>();
-    for (int i = 0; i < entries.length; i += 2) {
-      map.put((K) entries[i], (V) entries[i + 1]);
-    }
-    return map;
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/test/native/cpp/main.cpp b/third_party/allwpilib/wpilibOldCommands/src/test/native/cpp/main.cpp
deleted file mode 100644
index 6aea19a..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/test/native/cpp/main.cpp
+++ /dev/null
@@ -1,14 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include <hal/HALBase.h>
-
-#include "gtest/gtest.h"
-
-int main(int argc, char** argv) {
-  HAL_Initialize(500, 0);
-  ::testing::InitGoogleTest(&argc, argv);
-  int ret = RUN_ALL_TESTS();
-  return ret;
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/test/native/cpp/shuffleboard/ShuffleboardTabTest.cpp b/third_party/allwpilib/wpilibOldCommands/src/test/native/cpp/shuffleboard/ShuffleboardTabTest.cpp
deleted file mode 100644
index 4cbad01..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/test/native/cpp/shuffleboard/ShuffleboardTabTest.cpp
+++ /dev/null
@@ -1,111 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include <array>
-#include <memory>
-#include <string>
-
-#include <networktables/NetworkTableEntry.h>
-#include <networktables/NetworkTableInstance.h>
-
-#include "frc/commands/InstantCommand.h"
-#include "frc/shuffleboard/ShuffleboardInstance.h"
-#include "frc/shuffleboard/ShuffleboardTab.h"
-#include "gtest/gtest.h"
-
-using namespace frc;
-
-class ShuffleboardTabTest : public testing::Test {
-  void SetUp() override {
-    m_ntInstance = nt::NetworkTableInstance::Create();
-    m_instance = std::make_unique<detail::ShuffleboardInstance>(m_ntInstance);
-    m_tab = &(m_instance->GetTab("Tab"));
-  }
-
- protected:
-  nt::NetworkTableInstance m_ntInstance;
-  ShuffleboardTab* m_tab;
-  std::unique_ptr<detail::ShuffleboardInstance> m_instance;
-};
-
-TEST_F(ShuffleboardTabTest, AddDouble) {
-  auto entry = m_tab->Add("Double", 1.0).GetEntry();
-  EXPECT_EQ("/Shuffleboard/Tab/Double", entry.GetName());
-  EXPECT_FLOAT_EQ(1.0, entry.GetValue()->GetDouble());
-}
-
-TEST_F(ShuffleboardTabTest, AddInteger) {
-  auto entry = m_tab->Add("Int", 1).GetEntry();
-  EXPECT_EQ("/Shuffleboard/Tab/Int", entry.GetName());
-  EXPECT_FLOAT_EQ(1.0, entry.GetValue()->GetDouble());
-}
-
-TEST_F(ShuffleboardTabTest, AddBoolean) {
-  auto entry = m_tab->Add("Bool", false).GetEntry();
-  EXPECT_EQ("/Shuffleboard/Tab/Bool", entry.GetName());
-  EXPECT_FALSE(entry.GetValue()->GetBoolean());
-}
-
-TEST_F(ShuffleboardTabTest, AddString) {
-  auto entry = m_tab->Add("String", "foobar").GetEntry();
-  EXPECT_EQ("/Shuffleboard/Tab/String", entry.GetName());
-  EXPECT_EQ("foobar", entry.GetValue()->GetString());
-}
-
-TEST_F(ShuffleboardTabTest, AddNamedSendableWithProperties) {
-  InstantCommand sendable("Command");
-  std::string widgetType = "Command Widget";
-  wpi::StringMap<std::shared_ptr<nt::Value>> map;
-  map.try_emplace("foo", nt::Value::MakeDouble(1234));
-  map.try_emplace("bar", nt::Value::MakeString("baz"));
-  m_tab->Add(sendable).WithWidget(widgetType).WithProperties(map);
-
-  m_instance->Update();
-  std::string meta = "/Shuffleboard/.metadata/Tab/Command";
-
-  EXPECT_EQ(1234, m_ntInstance.GetEntry(meta + "/Properties/foo").GetDouble(-1))
-      << "Property 'foo' not set correctly";
-  EXPECT_EQ("baz",
-            m_ntInstance.GetEntry(meta + "/Properties/bar").GetString(""))
-      << "Property 'bar' not set correctly";
-  EXPECT_EQ(widgetType,
-            m_ntInstance.GetEntry(meta + "/PreferredComponent").GetString(""))
-      << "Preferred component not set correctly";
-}
-
-TEST_F(ShuffleboardTabTest, AddNumberArray) {
-  std::array<double, 3> expect = {{1.0, 2.0, 3.0}};
-  auto entry = m_tab->Add("DoubleArray", expect).GetEntry();
-  EXPECT_EQ("/Shuffleboard/Tab/DoubleArray", entry.GetName());
-
-  auto actual = entry.GetValue()->GetDoubleArray();
-  EXPECT_EQ(expect.size(), actual.size());
-  for (size_t i = 0; i < expect.size(); i++) {
-    EXPECT_FLOAT_EQ(expect[i], actual[i]);
-  }
-}
-
-TEST_F(ShuffleboardTabTest, AddBooleanArray) {
-  std::array<bool, 2> expect = {{true, false}};
-  auto entry = m_tab->Add("BoolArray", expect).GetEntry();
-  EXPECT_EQ("/Shuffleboard/Tab/BoolArray", entry.GetName());
-
-  auto actual = entry.GetValue()->GetBooleanArray();
-  EXPECT_EQ(expect.size(), actual.size());
-  for (size_t i = 0; i < expect.size(); i++) {
-    EXPECT_EQ(expect[i], actual[i]);
-  }
-}
-
-TEST_F(ShuffleboardTabTest, AddStringArray) {
-  std::array<std::string, 2> expect = {{"foo", "bar"}};
-  auto entry = m_tab->Add("StringArray", expect).GetEntry();
-  EXPECT_EQ("/Shuffleboard/Tab/StringArray", entry.GetName());
-
-  auto actual = entry.GetValue()->GetStringArray();
-  EXPECT_EQ(expect.size(), actual.size());
-  for (size_t i = 0; i < expect.size(); i++) {
-    EXPECT_EQ(expect[i], actual[i]);
-  }
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/test/native/cpp/shuffleboard/ShuffleboardWidgetTest.cpp b/third_party/allwpilib/wpilibOldCommands/src/test/native/cpp/shuffleboard/ShuffleboardWidgetTest.cpp
deleted file mode 100644
index 9460330..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/test/native/cpp/shuffleboard/ShuffleboardWidgetTest.cpp
+++ /dev/null
@@ -1,61 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include <array>
-#include <memory>
-#include <string>
-
-#include <networktables/NetworkTableEntry.h>
-#include <networktables/NetworkTableInstance.h>
-
-#include "frc/commands/InstantCommand.h"
-#include "frc/shuffleboard/BuiltInWidgets.h"
-#include "frc/shuffleboard/ShuffleboardInstance.h"
-#include "frc/shuffleboard/ShuffleboardTab.h"
-#include "frc/shuffleboard/ShuffleboardWidget.h"
-#include "gtest/gtest.h"
-
-using namespace frc;
-
-class ShuffleboardWidgetTest : public testing::Test {
-  void SetUp() override {
-    m_ntInstance = nt::NetworkTableInstance::Create();
-    m_instance = std::make_unique<detail::ShuffleboardInstance>(m_ntInstance);
-    m_tab = &(m_instance->GetTab("Tab"));
-  }
-
- protected:
-  nt::NetworkTableInstance m_ntInstance;
-  ShuffleboardTab* m_tab;
-  std::unique_ptr<detail::ShuffleboardInstance> m_instance;
-};
-
-TEST_F(ShuffleboardWidgetTest, UseBuiltInWidget) {
-  auto entry =
-      m_tab->Add("Name", "").WithWidget(BuiltInWidgets::kTextView).GetEntry();
-  EXPECT_EQ("/Shuffleboard/Tab/Name", entry.GetName())
-      << "The widget entry has the wrong name";
-}
-
-TEST_F(ShuffleboardWidgetTest, WithProperties) {
-  wpi::StringMap<std::shared_ptr<nt::Value>> properties{
-      std::make_pair("min", nt::Value::MakeDouble(0)),
-      std::make_pair("max", nt::Value::MakeDouble(1))};
-  auto entry =
-      m_tab->Add("WithProperties", "").WithProperties(properties).GetEntry();
-
-  // Update the instance to generate
-  // the metadata entries for the widget properties
-  m_instance->Update();
-
-  auto propertiesTable = m_ntInstance.GetTable(
-      "/Shuffleboard/.metadata/Tab/WithProperties/Properties");
-
-  EXPECT_EQ("/Shuffleboard/Tab/WithProperties", entry.GetName())
-      << "The widget entry has the wrong name";
-  EXPECT_FLOAT_EQ(0, propertiesTable->GetEntry("min").GetDouble(-1))
-      << "The 'min' property should be 0";
-  EXPECT_FLOAT_EQ(1, propertiesTable->GetEntry("max").GetDouble(-1))
-      << "The 'max' property should be 1";
-}
diff --git a/third_party/allwpilib/wpilibOldCommands/src/test/resources/META-INF/services/org.junit.jupiter.api.extension.Extension b/third_party/allwpilib/wpilibOldCommands/src/test/resources/META-INF/services/org.junit.jupiter.api.extension.Extension
deleted file mode 100644
index 981f170..0000000
--- a/third_party/allwpilib/wpilibOldCommands/src/test/resources/META-INF/services/org.junit.jupiter.api.extension.Extension
+++ /dev/null
@@ -1 +0,0 @@
-edu.wpi.first.wpilibj.MockHardwareExtension

diff --git a/third_party/allwpilib/wpilibOldCommands/wpilibOldCommands-config.cmake.in b/third_party/allwpilib/wpilibOldCommands/wpilibOldCommands-config.cmake.in
deleted file mode 100644
index 81dde79..0000000
--- a/third_party/allwpilib/wpilibOldCommands/wpilibOldCommands-config.cmake.in
+++ /dev/null
@@ -1,11 +0,0 @@
-include(CMakeFindDependencyMacro)
-@FILENAME_DEP_REPLACE@
-@WPIUTIL_DEP_REPLACE@
-@NTCORE_DEP_REPLACE@
-@CSCORE_DEP_REPLACE@
-@CAMERASERVER_DEP_REPLACE@
-@HAL_DEP_REPLACE@
-@WPILIBC_DEP_REPLACE@
-@WPIMATH_DEP_REPLACE@
-
-include(${SELF_DIR}/wpilibOldCommands.cmake)
diff --git a/third_party/allwpilib/wpilibc/CMakeLists.txt b/third_party/allwpilib/wpilibc/CMakeLists.txt
index 4c8dfde..8c2c85c 100644
--- a/third_party/allwpilib/wpilibc/CMakeLists.txt
+++ b/third_party/allwpilib/wpilibc/CMakeLists.txt
@@ -47,11 +47,6 @@
     wpilib_add_test(wpilibc src/test/native/cpp)
     target_include_directories(wpilibc_test PRIVATE src/test/native/include)
     target_link_libraries(wpilibc_test wpilibc gmock_main)
-    if (NOT MSVC)
-        target_compile_options(wpilibc_test PRIVATE -Wno-error)
-    else()
-        target_compile_options(wpilibc_test PRIVATE /WX-)
-    endif()
     if (NOT WITH_CSCORE)
         target_compile_definitions(wpilibc_test PRIVATE DYNAMIC_CAMERA_SERVER)
         # Add just the camera server include directory
diff --git a/third_party/allwpilib/wpilibc/build.gradle b/third_party/allwpilib/wpilibc/build.gradle
index c9c2670..4cf4ab2 100644
--- a/third_party/allwpilib/wpilibc/build.gradle
+++ b/third_party/allwpilib/wpilibc/build.gradle
@@ -62,19 +62,6 @@
 
 nativeUtils.exportsConfigs {
     wpilibc {
-        x86ExcludeSymbols = [
-            '_CT??_R0?AV_System_error',
-            '_CT??_R0?AVexception',
-            '_CT??_R0?AVfailure',
-            '_CT??_R0?AVruntime_error',
-            '_CT??_R0?AVsystem_error',
-            '_CTA5?AVfailure',
-            '_TI5?AVfailure',
-            '_CT??_R0?AVout_of_range',
-            '_CTA3?AVout_of_range',
-            '_TI3?AVout_of_range',
-            '_CT??_R0?AVbad_cast'
-        ]
         x64ExcludeSymbols = [
             '_CT??_R0?AV_System_error',
             '_CT??_R0?AVexception',
@@ -98,8 +85,7 @@
                 cpp {
                     source {
                         srcDirs = [
-                            'src/main/native/cpp',
-                            "$buildDir/generated/cpp"
+                            'src/main/native/cpp'
                         ]
                         include '**/*.cpp'
                     }
@@ -113,9 +99,26 @@
                     it.buildable = false
                     return
                 }
+
+                it.sources {
+                    versionSources(CppSourceSet) {
+                        source {
+                            srcDirs = [
+                                "${rootDir}/shared/singlelib",
+                                "$buildDir/generated/cpp"
+                            ]
+                            include '**/*.cpp'
+                        }
+                        exportedHeaders {
+                            srcDirs 'src/main/native/include'
+                        }
+                    }
+                }
+
                 cppCompiler.define 'DYNAMIC_CAMERA_SERVER'
-                lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
+                project(':ntcore').addNtcoreDependency(it, 'shared')
                 project(':hal').addHalDependency(it, 'shared')
+                lib project: ':wpinet', library: 'wpinet', linkage: 'shared'
                 lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
                 lib project: ':wpimath', library: 'wpimath', linkage: 'shared'
             }
@@ -133,8 +136,9 @@
                 }
             }
             binaries.all {
-                lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
+                project(':ntcore').addNtcoreDependency(it, 'shared')
                 project(':hal').addHalDependency(it, 'shared')
+                lib project: ':wpinet', library: 'wpinet', linkage: 'shared'
                 lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
                 lib project: ':wpimath', library: 'wpimath', linkage: 'shared'
 
@@ -169,9 +173,10 @@
                 }
             }
             binaries.all {
-                lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
+                project(':ntcore').addNtcoreDependency(it, 'shared')
                 lib project: ':cscore', library: 'cscore', linkage: 'shared'
                 project(':hal').addHalDependency(it, 'shared')
+                lib project: ':wpinet', library: 'wpinet', linkage: 'shared'
                 lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
                 lib project: ':wpimath', library: 'wpimath', linkage: 'shared'
                 lib project: ':cameraserver', library: 'cameraserver', linkage: 'shared'
@@ -219,9 +224,10 @@
             }
         }
         withType(GoogleTestTestSuiteBinarySpec) {
-            lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
+            project(':ntcore').addNtcoreDependency(it, 'shared')
             lib project: ':cscore', library: 'cscore', linkage: 'shared'
             project(':hal').addHalDependency(it, 'shared')
+            lib project: ':wpinet', library: 'wpinet', linkage: 'shared'
             lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
             lib project: ':wpimath', library: 'wpimath', linkage: 'shared'
             lib project: ':cameraserver', library: 'cameraserver', linkage: 'shared'
diff --git a/third_party/allwpilib/wpilibc/src/dev/native/cpp/main.cpp b/third_party/allwpilib/wpilibc/src/dev/native/cpp/main.cpp
index 28fac9d..fcc55b1 100644
--- a/third_party/allwpilib/wpilibc/src/dev/native/cpp/main.cpp
+++ b/third_party/allwpilib/wpilibc/src/dev/native/cpp/main.cpp
@@ -9,6 +9,6 @@
 
 int main() {
   fmt::print("Hello World\n");
-  fmt::print("{}\n", HAL_GetRuntimeType());
+  fmt::print("{}\n", static_cast<int32_t>(HAL_GetRuntimeType()));
   fmt::print("{}\n", GetWPILibVersion());
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/ADIS16448_IMU.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/ADIS16448_IMU.cpp
index 25d674f..7048720 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/ADIS16448_IMU.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/ADIS16448_IMU.cpp
@@ -22,11 +22,11 @@
 
 #include <algorithm>
 #include <cmath>
+#include <numbers>
 #include <string>
 
 #include <hal/HAL.h>
 #include <networktables/NTSendableBuilder.h>
-#include <wpi/numbers>
 #include <wpi/sendable/SendableRegistry.h>
 
 #include "frc/Errors.h"
@@ -56,14 +56,14 @@
                             const char* function, const S& format,
                             Args&&... args) {
   frc::ReportErrorV(status, file, line, function, format,
-                    fmt::make_args_checked<Args...>(format, args...));
+                    fmt::make_format_args(args...));
 }
 }  // namespace
 
 #define REPORT_WARNING(msg) \
-  ADISReportError(warn::Warning, __FILE__, __LINE__, __FUNCTION__, "{}", msg);
+  ADISReportError(warn::Warning, __FILE__, __LINE__, __FUNCTION__, msg);
 #define REPORT_ERROR(msg) \
-  ADISReportError(err::Error, __FILE__, __LINE__, __FUNCTION__, "{}", msg)
+  ADISReportError(err::Error, __FILE__, __LINE__, __FUNCTION__, msg)
 
 ADIS16448_IMU::ADIS16448_IMU()
     : ADIS16448_IMU(kZ, SPI::Port::kMXP, CalibrationTime::_512ms) {}
@@ -74,6 +74,8 @@
       m_spi_port(port),
       m_simDevice("Gyro:ADIS16448", port) {
   if (m_simDevice) {
+    m_connected =
+        m_simDevice.CreateBoolean("connected", hal::SimDevice::kInput, true);
     m_simGyroAngleX =
         m_simDevice.CreateDouble("gyro_angle_x", hal::SimDevice::kInput, 0.0);
     m_simGyroAngleY =
@@ -102,8 +104,8 @@
     DigitalOutput* m_reset_out = new DigitalOutput(18);  // Drive MXP DIO8 low
     Wait(10_ms);                                         // Wait 10ms
     delete m_reset_out;
-    new DigitalInput(18);  // Set MXP DIO8 high
-    Wait(500_ms);          // Wait 500ms for reset to complete
+    m_reset_in = new DigitalInput(18);  // Set MXP DIO8 high
+    Wait(500_ms);                       // Wait 500ms for reset to complete
 
     ConfigCalTime(cal_time);
 
@@ -143,13 +145,21 @@
 
     // TODO: Find what the proper pin is to turn this LED
     //  Drive MXP PWM5 (IMU ready LED) low (active low)
-    new DigitalOutput(19);
+    m_status_led = new DigitalOutput(19);
   }
 
   // Report usage and post data to DS
   HAL_Report(HALUsageReporting::kResourceType_ADIS16448, 0);
 
   wpi::SendableRegistry::AddLW(this, "ADIS16448", port);
+  m_connected = true;
+}
+
+bool ADIS16448_IMU::IsConnected() const {
+  if (m_simConnected) {
+    return m_simConnected.Get();
+  }
+  return m_connected;
 }
 
 /**
@@ -186,7 +196,7 @@
       while (data_count > 0) {
         /* Dequeue 200 at a time, or the remainder of the buffer if less than
          * 200 */
-        m_spi->ReadAutoReceivedData(trashBuffer, std::min(200, data_count),
+        m_spi->ReadAutoReceivedData(trashBuffer, (std::min)(200, data_count),
                                     0_s);
         /* Update remaining buffer count */
         data_count = m_spi->ReadAutoReceivedData(trashBuffer, 0, 0_s);
@@ -197,9 +207,7 @@
   if (m_spi == nullptr) {
     m_spi = new SPI(m_spi_port);
     m_spi->SetClockRate(1000000);
-    m_spi->SetMSBFirst();
-    m_spi->SetSampleDataOnTrailingEdge();
-    m_spi->SetClockActiveLow();
+    m_spi->SetMode(frc::SPI::Mode::kMode3);
     m_spi->SetChipSelectActiveLow();
     ReadRegister(PROD_ID);  // Dummy read
 
@@ -323,7 +331,7 @@
 void ADIS16448_IMU::Calibrate() {
   std::scoped_lock sync(m_mutex);
   // Calculate the running average
-  int gyroAverageSize = std::min(m_accum_count, m_avg_size);
+  int gyroAverageSize = (std::min)(m_accum_count, m_avg_size);
   double accum_gyro_rate_x = 0.0;
   double accum_gyro_rate_y = 0.0;
   double accum_gyro_rate_z = 0.0;
@@ -387,6 +395,14 @@
 }
 
 void ADIS16448_IMU::Close() {
+  if (m_reset_in != nullptr) {
+    delete m_reset_in;
+    m_reset_in = nullptr;
+  }
+  if (m_status_led != nullptr) {
+    delete m_status_led;
+    m_status_led = nullptr;
+  }
   if (m_thread_active) {
     m_thread_active = false;
     if (m_acquire_task.joinable()) {
@@ -624,29 +640,29 @@
 
 /* Complementary filter functions */
 double ADIS16448_IMU::FormatFastConverge(double compAngle, double accAngle) {
-  if (compAngle > accAngle + wpi::numbers::pi) {
-    compAngle = compAngle - 2.0 * wpi::numbers::pi;
-  } else if (accAngle > compAngle + wpi::numbers::pi) {
-    compAngle = compAngle + 2.0 * wpi::numbers::pi;
+  if (compAngle > accAngle + std::numbers::pi) {
+    compAngle = compAngle - 2.0 * std::numbers::pi;
+  } else if (accAngle > compAngle + std::numbers::pi) {
+    compAngle = compAngle + 2.0 * std::numbers::pi;
   }
   return compAngle;
 }
 
 double ADIS16448_IMU::FormatRange0to2PI(double compAngle) {
-  while (compAngle >= 2 * wpi::numbers::pi) {
-    compAngle = compAngle - 2.0 * wpi::numbers::pi;
+  while (compAngle >= 2 * std::numbers::pi) {
+    compAngle = compAngle - 2.0 * std::numbers::pi;
   }
   while (compAngle < 0.0) {
-    compAngle = compAngle + 2.0 * wpi::numbers::pi;
+    compAngle = compAngle + 2.0 * std::numbers::pi;
   }
   return compAngle;
 }
 
 double ADIS16448_IMU::FormatAccelRange(double accelAngle, double accelZ) {
   if (accelZ < 0.0) {
-    accelAngle = wpi::numbers::pi - accelAngle;
+    accelAngle = std::numbers::pi - accelAngle;
   } else if (accelZ > 0.0 && accelAngle < 0.0) {
-    accelAngle = 2.0 * wpi::numbers::pi + accelAngle;
+    accelAngle = 2.0 * std::numbers::pi + accelAngle;
   }
   return accelAngle;
 }
@@ -657,8 +673,8 @@
   compAngle =
       m_alpha * (compAngle + omega * m_dt) + (1.0 - m_alpha) * accelAngle;
   compAngle = FormatRange0to2PI(compAngle);
-  if (compAngle > wpi::numbers::pi) {
-    compAngle = compAngle - 2.0 * wpi::numbers::pi;
+  if (compAngle > std::numbers::pi) {
+    compAngle = compAngle - 2.0 * std::numbers::pi;
   }
   return compAngle;
 }
@@ -673,7 +689,8 @@
 
   /* Check max */
   if (DecimationSetting > 9) {
-    REPORT_ERROR("Attemted to write an invalid decimation value. Capping at 9");
+    REPORT_ERROR(
+        "Attempted to write an invalid decimation value. Capping at 9");
     DecimationSetting = 9;
   }
 
@@ -867,8 +884,6 @@
  **/
 void ADIS16448_IMU::InitSendable(nt::NTSendableBuilder& builder) {
   builder.SetSmartDashboardType("ADIS16448 IMU");
-  auto yaw_angle = builder.GetEntry("Yaw Angle").GetHandle();
-  builder.SetUpdateTable([=]() {
-    nt::NetworkTableEntry(yaw_angle).SetDouble(GetAngle().value());
-  });
+  builder.AddDoubleProperty(
+      "Yaw Angle", [=, this] { return GetAngle().value(); }, nullptr);
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/ADIS16470_IMU.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/ADIS16470_IMU.cpp
index f48d827..e1cd986 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/ADIS16470_IMU.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/ADIS16470_IMU.cpp
@@ -19,11 +19,11 @@
 #include <frc/Timer.h>
 
 #include <cmath>
+#include <numbers>
 #include <string>
 
 #include <hal/HAL.h>
 #include <networktables/NTSendableBuilder.h>
-#include <wpi/numbers>
 #include <wpi/sendable/SendableRegistry.h>
 
 #include "frc/Errors.h"
@@ -50,14 +50,14 @@
                             const char* function, const S& format,
                             Args&&... args) {
   frc::ReportErrorV(status, file, line, function, format,
-                    fmt::make_args_checked<Args...>(format, args...));
+                    fmt::make_format_args(args...));
 }
 }  // namespace
 
 #define REPORT_WARNING(msg) \
-  ADISReportError(warn::Warning, __FILE__, __LINE__, __FUNCTION__, "{}", msg);
+  ADISReportError(warn::Warning, __FILE__, __LINE__, __FUNCTION__, msg);
 #define REPORT_ERROR(msg) \
-  ADISReportError(err::Error, __FILE__, __LINE__, __FUNCTION__, "{}", msg)
+  ADISReportError(err::Error, __FILE__, __LINE__, __FUNCTION__, msg)
 
 /**
  * Constructor.
@@ -72,6 +72,8 @@
       m_calibration_time(static_cast<uint16_t>(cal_time)),
       m_simDevice("Gyro:ADIS16470", port) {
   if (m_simDevice) {
+    m_connected =
+        m_simDevice.CreateBoolean("connected", hal::SimDevice::kInput, true);
     m_simGyroAngleX =
         m_simDevice.CreateDouble("gyro_angle_x", hal::SimDevice::kInput, 0.0);
     m_simGyroAngleY =
@@ -101,8 +103,8 @@
         new DigitalOutput(27);  // Drive SPI CS2 (IMU RST) low
     Wait(10_ms);                // Wait 10ms
     delete m_reset_out;
-    new DigitalInput(27);  // Set SPI CS2 (IMU RST) high
-    Wait(500_ms);          // Wait 500ms for reset to complete
+    m_reset_in = new DigitalInput(27);  // Set SPI CS2 (IMU RST) high
+    Wait(500_ms);                       // Wait 500ms for reset to complete
 
     // Configure standard SPI
     if (!SwitchToStandardSPI()) {
@@ -140,13 +142,21 @@
     REPORT_WARNING("ADIS16470 IMU Successfully Initialized!");
 
     // Drive SPI CS3 (IMU ready LED) low (active low)
-    new DigitalOutput(28);
+    m_status_led = new DigitalOutput(28);
   }
 
   // Report usage and post data to DS
   HAL_Report(HALUsageReporting::kResourceType_ADIS16470, 0);
 
   wpi::SendableRegistry::AddLW(this, "ADIS16470", port);
+  m_connected = true;
+}
+
+bool ADIS16470_IMU::IsConnected() const {
+  if (m_simConnected) {
+    return m_simConnected.Get();
+  }
+  return m_connected;
 }
 
 /**
@@ -183,9 +193,9 @@
       while (data_count > 0) {
         /* Receive data, max of 200 words at a time (prevent potential segfault)
          */
-        m_spi->ReadAutoReceivedData(trashBuffer, std::min(data_count, 200),
+        m_spi->ReadAutoReceivedData(trashBuffer, (std::min)(data_count, 200),
                                     0_s);
-        /*Get the reamining data count */
+        /*Get the remaining data count */
         data_count = m_spi->ReadAutoReceivedData(trashBuffer, 0, 0_s);
       }
     }
@@ -194,9 +204,7 @@
   if (m_spi == nullptr) {
     m_spi = new SPI(m_spi_port);
     m_spi->SetClockRate(2000000);
-    m_spi->SetMSBFirst();
-    m_spi->SetSampleDataOnTrailingEdge();
-    m_spi->SetClockActiveLow();
+    m_spi->SetMode(frc::SPI::Mode::kMode3);
     m_spi->SetChipSelectActiveLow();
     ReadRegister(PROD_ID);  // Dummy read
 
@@ -441,6 +449,14 @@
 }
 
 void ADIS16470_IMU::Close() {
+  if (m_reset_in != nullptr) {
+    delete m_reset_in;
+    m_reset_in = nullptr;
+  }
+  if (m_status_led != nullptr) {
+    delete m_status_led;
+    m_status_led = nullptr;
+  }
   if (m_thread_active) {
     m_thread_active = false;
     if (m_acquire_task.joinable()) {
@@ -469,7 +485,7 @@
  * @brief Main acquisition loop. Typically called asynchronously and free-wheels
  *while the robot code is active.
  *
- * This is the main acquisiton loop for the IMU. During each iteration, data
+ * This is the main acquisition loop for the IMU. During each iteration, data
  *read using auto SPI is extracted from the FPGA FIFO, split, scaled, and
  *integrated. Each X, Y, and Z value is 32-bits split across 4 indices (bytes)
  *in the buffer. Auto SPI puts one byte in each index location. Each index is
@@ -641,29 +657,29 @@
 
 /* Complementary filter functions */
 double ADIS16470_IMU::FormatFastConverge(double compAngle, double accAngle) {
-  if (compAngle > accAngle + wpi::numbers::pi) {
-    compAngle = compAngle - 2.0 * wpi::numbers::pi;
-  } else if (accAngle > compAngle + wpi::numbers::pi) {
-    compAngle = compAngle + 2.0 * wpi::numbers::pi;
+  if (compAngle > accAngle + std::numbers::pi) {
+    compAngle = compAngle - 2.0 * std::numbers::pi;
+  } else if (accAngle > compAngle + std::numbers::pi) {
+    compAngle = compAngle + 2.0 * std::numbers::pi;
   }
   return compAngle;
 }
 
 double ADIS16470_IMU::FormatRange0to2PI(double compAngle) {
-  while (compAngle >= 2 * wpi::numbers::pi) {
-    compAngle = compAngle - 2.0 * wpi::numbers::pi;
+  while (compAngle >= 2 * std::numbers::pi) {
+    compAngle = compAngle - 2.0 * std::numbers::pi;
   }
   while (compAngle < 0.0) {
-    compAngle = compAngle + 2.0 * wpi::numbers::pi;
+    compAngle = compAngle + 2.0 * std::numbers::pi;
   }
   return compAngle;
 }
 
 double ADIS16470_IMU::FormatAccelRange(double accelAngle, double accelZ) {
   if (accelZ < 0.0) {
-    accelAngle = wpi::numbers::pi - accelAngle;
+    accelAngle = std::numbers::pi - accelAngle;
   } else if (accelZ > 0.0 && accelAngle < 0.0) {
-    accelAngle = 2.0 * wpi::numbers::pi + accelAngle;
+    accelAngle = 2.0 * std::numbers::pi + accelAngle;
   }
   return accelAngle;
 }
@@ -674,8 +690,8 @@
   compAngle =
       m_alpha * (compAngle + omega * m_dt) + (1.0 - m_alpha) * accelAngle;
   compAngle = FormatRange0to2PI(compAngle);
-  if (compAngle > wpi::numbers::pi) {
-    compAngle = compAngle - 2.0 * wpi::numbers::pi;
+  if (compAngle > std::numbers::pi) {
+    compAngle = compAngle - 2.0 * std::numbers::pi;
   }
   return compAngle;
 }
@@ -802,8 +818,6 @@
  **/
 void ADIS16470_IMU::InitSendable(nt::NTSendableBuilder& builder) {
   builder.SetSmartDashboardType("ADIS16470 IMU");
-  auto yaw_angle = builder.GetEntry("Yaw Angle").GetHandle();
-  builder.SetUpdateTable([=]() {
-    nt::NetworkTableEntry(yaw_angle).SetDouble(GetAngle().value());
-  });
+  builder.AddDoubleProperty(
+      "Yaw Angle", [=, this] { return GetAngle().value(); }, nullptr);
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/ADXL345_I2C.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/ADXL345_I2C.cpp
index 484e690..a23846d 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/ADXL345_I2C.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/ADXL345_I2C.cpp
@@ -5,6 +5,7 @@
 #include "frc/ADXL345_I2C.h"
 
 #include <hal/FRCUsageReporting.h>
+#include <networktables/DoubleTopic.h>
 #include <networktables/NTSendableBuilder.h>
 #include <wpi/sendable/SendableRegistry.h>
 
@@ -93,13 +94,13 @@
 
 void ADXL345_I2C::InitSendable(nt::NTSendableBuilder& builder) {
   builder.SetSmartDashboardType("3AxisAccelerometer");
-  auto x = builder.GetEntry("X").GetHandle();
-  auto y = builder.GetEntry("Y").GetHandle();
-  auto z = builder.GetEntry("Z").GetHandle();
-  builder.SetUpdateTable([=] {
-    auto data = GetAccelerations();
-    nt::NetworkTableEntry(x).SetDouble(data.XAxis);
-    nt::NetworkTableEntry(y).SetDouble(data.YAxis);
-    nt::NetworkTableEntry(z).SetDouble(data.ZAxis);
-  });
+  builder.SetUpdateTable(
+      [this, x = nt::DoubleTopic{builder.GetTopic("X")}.Publish(),
+       y = nt::DoubleTopic{builder.GetTopic("Y")}.Publish(),
+       z = nt::DoubleTopic{builder.GetTopic("Z")}.Publish()]() mutable {
+        auto data = GetAccelerations();
+        x.Set(data.XAxis);
+        y.Set(data.YAxis);
+        z.Set(data.ZAxis);
+      });
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/ADXL345_SPI.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/ADXL345_SPI.cpp
index 9a95bcc..1dc4c5b 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/ADXL345_SPI.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/ADXL345_SPI.cpp
@@ -5,6 +5,7 @@
 #include "frc/ADXL345_SPI.h"
 
 #include <hal/FRCUsageReporting.h>
+#include <networktables/DoubleTopic.h>
 #include <networktables/NTSendableBuilder.h>
 #include <wpi/sendable/SendableRegistry.h>
 
@@ -21,9 +22,7 @@
     m_simZ = m_simDevice.CreateDouble("z", hal::SimDevice::kInput, 0.0);
   }
   m_spi.SetClockRate(500000);
-  m_spi.SetMSBFirst();
-  m_spi.SetSampleDataOnTrailingEdge();
-  m_spi.SetClockActiveLow();
+  m_spi.SetMode(frc::SPI::Mode::kMode3);
   m_spi.SetChipSelectActiveHigh();
 
   uint8_t commands[2];
@@ -120,13 +119,13 @@
 
 void ADXL345_SPI::InitSendable(nt::NTSendableBuilder& builder) {
   builder.SetSmartDashboardType("3AxisAccelerometer");
-  auto x = builder.GetEntry("X").GetHandle();
-  auto y = builder.GetEntry("Y").GetHandle();
-  auto z = builder.GetEntry("Z").GetHandle();
-  builder.SetUpdateTable([=] {
-    auto data = GetAccelerations();
-    nt::NetworkTableEntry(x).SetDouble(data.XAxis);
-    nt::NetworkTableEntry(y).SetDouble(data.YAxis);
-    nt::NetworkTableEntry(z).SetDouble(data.ZAxis);
-  });
+  builder.SetUpdateTable(
+      [this, x = nt::DoubleTopic{builder.GetTopic("X")}.Publish(),
+       y = nt::DoubleTopic{builder.GetTopic("Y")}.Publish(),
+       z = nt::DoubleTopic{builder.GetTopic("Z")}.Publish()]() mutable {
+        auto data = GetAccelerations();
+        x.Set(data.XAxis);
+        y.Set(data.YAxis);
+        z.Set(data.ZAxis);
+      });
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/ADXL362.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/ADXL362.cpp
index deda965..fa0a8a3 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/ADXL362.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/ADXL362.cpp
@@ -5,6 +5,7 @@
 #include "frc/ADXL362.h"
 
 #include <hal/FRCUsageReporting.h>
+#include <networktables/DoubleTopic.h>
 #include <networktables/NTSendableBuilder.h>
 #include <wpi/sendable/SendableRegistry.h>
 
@@ -43,9 +44,7 @@
   }
 
   m_spi.SetClockRate(3000000);
-  m_spi.SetMSBFirst();
-  m_spi.SetSampleDataOnTrailingEdge();
-  m_spi.SetClockActiveLow();
+  m_spi.SetMode(frc::SPI::Mode::kMode3);
   m_spi.SetChipSelectActiveLow();
 
   uint8_t commands[3];
@@ -56,7 +55,7 @@
     commands[2] = 0;
     m_spi.Transaction(commands, commands, 3);
     if (commands[2] != 0xF2) {
-      FRC_ReportError(err::Error, "{}", "could not find ADXL362");
+      FRC_ReportError(err::Error, "could not find ADXL362");
       m_gsPerLSB = 0.0;
       return;
     }
@@ -184,13 +183,13 @@
 
 void ADXL362::InitSendable(nt::NTSendableBuilder& builder) {
   builder.SetSmartDashboardType("3AxisAccelerometer");
-  auto x = builder.GetEntry("X").GetHandle();
-  auto y = builder.GetEntry("Y").GetHandle();
-  auto z = builder.GetEntry("Z").GetHandle();
-  builder.SetUpdateTable([=] {
-    auto data = GetAccelerations();
-    nt::NetworkTableEntry(x).SetDouble(data.XAxis);
-    nt::NetworkTableEntry(y).SetDouble(data.YAxis);
-    nt::NetworkTableEntry(z).SetDouble(data.ZAxis);
-  });
+  builder.SetUpdateTable(
+      [this, x = nt::DoubleTopic{builder.GetTopic("X")}.Publish(),
+       y = nt::DoubleTopic{builder.GetTopic("Y")}.Publish(),
+       z = nt::DoubleTopic{builder.GetTopic("Z")}.Publish()]() mutable {
+        auto data = GetAccelerations();
+        x.Set(data.XAxis);
+        y.Set(data.YAxis);
+        z.Set(data.ZAxis);
+      });
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/ADXRS450_Gyro.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/ADXRS450_Gyro.cpp
index 5a2f625..4d4b22d 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/ADXRS450_Gyro.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/ADXRS450_Gyro.cpp
@@ -32,21 +32,21 @@
 ADXRS450_Gyro::ADXRS450_Gyro(SPI::Port port)
     : m_spi(port), m_port(port), m_simDevice("Gyro:ADXRS450", port) {
   if (m_simDevice) {
+    m_simConnected =
+        m_simDevice.CreateBoolean("connected", hal::SimDevice::kInput, true);
     m_simAngle =
         m_simDevice.CreateDouble("angle_x", hal::SimDevice::kInput, 0.0);
     m_simRate = m_simDevice.CreateDouble("rate_x", hal::SimDevice::kInput, 0.0);
   }
 
   m_spi.SetClockRate(3000000);
-  m_spi.SetMSBFirst();
-  m_spi.SetSampleDataOnLeadingEdge();
-  m_spi.SetClockActiveHigh();
+  m_spi.SetMode(frc::SPI::Mode::kMode0);
   m_spi.SetChipSelectActiveLow();
 
   if (!m_simDevice) {
     // Validate the part ID
     if ((ReadRegister(kPIDRegister) & 0xff00) != 0x5200) {
-      FRC_ReportError(err::Error, "{}", "could not find ADXRS450 gyro");
+      FRC_ReportError(err::Error, "could not find ADXRS450 gyro");
       return;
     }
 
@@ -59,6 +59,14 @@
   HAL_Report(HALUsageReporting::kResourceType_ADXRS450, port + 1);
 
   wpi::SendableRegistry::AddLW(this, "ADXRS450_Gyro", port);
+  m_connected = true;
+}
+
+bool ADXRS450_Gyro::IsConnected() const {
+  if (m_simConnected) {
+    return m_simConnected.Get();
+  }
+  return m_connected;
 }
 
 static bool CalcParity(int v) {
@@ -139,5 +147,5 @@
 void ADXRS450_Gyro::InitSendable(wpi::SendableBuilder& builder) {
   builder.SetSmartDashboardType("Gyro");
   builder.AddDoubleProperty(
-      "Value", [=] { return GetAngle(); }, nullptr);
+      "Value", [=, this] { return GetAngle(); }, nullptr);
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/AddressableLED.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/AddressableLED.cpp
index 759c386..538dc10 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/AddressableLED.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/AddressableLED.cpp
@@ -51,9 +51,9 @@
 static_assert(sizeof(AddressableLED::LEDData) == sizeof(HAL_AddressableLEDData),
               "LED Structs MUST be the same size");
 
-void AddressableLED::SetData(wpi::span<const LEDData> ledData) {
+void AddressableLED::SetData(std::span<const LEDData> ledData) {
   int32_t status = 0;
-  HAL_WriteAddressableLEDData(m_handle, ledData.begin(), ledData.size(),
+  HAL_WriteAddressableLEDData(m_handle, ledData.data(), ledData.size(),
                               &status);
   FRC_CheckErrorStatus(status, "Port {}", m_port);
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/AnalogAccelerometer.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/AnalogAccelerometer.cpp
index 0b39e64..ca8af7d 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/AnalogAccelerometer.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/AnalogAccelerometer.cpp
@@ -21,7 +21,7 @@
 AnalogAccelerometer::AnalogAccelerometer(AnalogInput* channel)
     : m_analogInput(channel, wpi::NullDeleter<AnalogInput>()) {
   if (!channel) {
-    throw FRC_MakeError(err::NullParameter, "{}", "channel");
+    throw FRC_MakeError(err::NullParameter, "channel");
   }
   InitAccelerometer();
 }
@@ -29,7 +29,7 @@
 AnalogAccelerometer::AnalogAccelerometer(std::shared_ptr<AnalogInput> channel)
     : m_analogInput(channel) {
   if (!channel) {
-    throw FRC_MakeError(err::NullParameter, "{}", "channel");
+    throw FRC_MakeError(err::NullParameter, "channel");
   }
   InitAccelerometer();
 }
@@ -49,7 +49,7 @@
 void AnalogAccelerometer::InitSendable(wpi::SendableBuilder& builder) {
   builder.SetSmartDashboardType("Accelerometer");
   builder.AddDoubleProperty(
-      "Value", [=] { return GetAcceleration(); }, nullptr);
+      "Value", [=, this] { return GetAcceleration(); }, nullptr);
 }
 
 void AnalogAccelerometer::InitAccelerometer() {
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/AnalogEncoder.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/AnalogEncoder.cpp
index 5f26e87..0c29bea 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/AnalogEncoder.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/AnalogEncoder.cpp
@@ -10,6 +10,7 @@
 #include "frc/AnalogInput.h"
 #include "frc/Counter.h"
 #include "frc/Errors.h"
+#include "frc/RobotController.h"
 
 using namespace frc;
 
@@ -42,6 +43,8 @@
 
   if (m_simDevice) {
     m_simPosition = m_simDevice.CreateDouble("Position", false, 0.0);
+    m_simAbsolutePosition =
+        m_simDevice.CreateDouble("absPosition", hal::SimDevice::kInput, 0.0);
   }
 
   m_analogTrigger.SetLimitsVoltage(1.25, 3.75);
@@ -54,6 +57,11 @@
                                m_analogInput->GetChannel());
 }
 
+static bool DoubleEquals(double a, double b) {
+  constexpr double epsilon = 0.00001;
+  return std::abs(a - b) < epsilon;
+}
+
 units::turn_t AnalogEncoder::Get() const {
   if (m_simPosition) {
     return units::turn_t{m_simPosition.Get()};
@@ -66,7 +74,8 @@
     auto pos = m_analogInput->GetVoltage();
     auto counter2 = m_counter.Get();
     auto pos2 = m_analogInput->GetVoltage();
-    if (counter == counter2 && pos == pos2) {
+    if (counter == counter2 && DoubleEquals(pos, pos2)) {
+      pos = pos / frc::RobotController::GetVoltage5V();
       units::turn_t turns{counter + pos - m_positionOffset};
       m_lastPosition = turns;
       return turns;
@@ -74,16 +83,28 @@
   }
 
   FRC_ReportError(
-      warn::Warning, "{}",
+      warn::Warning,
       "Failed to read Analog Encoder. Potential Speed Overrun. Returning last "
       "value");
   return m_lastPosition;
 }
 
+double AnalogEncoder::GetAbsolutePosition() const {
+  if (m_simAbsolutePosition) {
+    return m_simAbsolutePosition.Get();
+  }
+
+  return m_analogInput->GetVoltage() / frc::RobotController::GetVoltage5V();
+}
+
 double AnalogEncoder::GetPositionOffset() const {
   return m_positionOffset;
 }
 
+void AnalogEncoder::SetPositionOffset(double offset) {
+  m_positionOffset = std::clamp(offset, 0.0, 1.0);
+}
+
 void AnalogEncoder::SetDistancePerRotation(double distancePerRotation) {
   m_distancePerRotation = distancePerRotation;
 }
@@ -98,7 +119,8 @@
 
 void AnalogEncoder::Reset() {
   m_counter.Reset();
-  m_positionOffset = m_analogInput->GetVoltage();
+  m_positionOffset =
+      m_analogInput->GetVoltage() / frc::RobotController::GetVoltage5V();
 }
 
 int AnalogEncoder::GetChannel() const {
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/AnalogGyro.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/AnalogGyro.cpp
index 106293b..cab9f94 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/AnalogGyro.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/AnalogGyro.cpp
@@ -33,7 +33,7 @@
 AnalogGyro::AnalogGyro(std::shared_ptr<AnalogInput> channel)
     : m_analog(channel) {
   if (!channel) {
-    throw FRC_MakeError(err::NullParameter, "{}", "channel");
+    throw FRC_MakeError(err::NullParameter, "channel");
   }
   InitGyro();
   Calibrate();
@@ -48,7 +48,7 @@
                        double offset)
     : m_analog(channel) {
   if (!channel) {
-    throw FRC_MakeError(err::NullParameter, "{}", "channel");
+    throw FRC_MakeError(err::NullParameter, "channel");
   }
   InitGyro();
   int32_t status = 0;
@@ -140,5 +140,5 @@
 void AnalogGyro::InitSendable(wpi::SendableBuilder& builder) {
   builder.SetSmartDashboardType("Gyro");
   builder.AddDoubleProperty(
-      "Value", [=] { return GetAngle(); }, nullptr);
+      "Value", [=, this] { return GetAngle(); }, nullptr);
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/AnalogInput.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/AnalogInput.cpp
index dfa5764..2ecb2df 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/AnalogInput.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/AnalogInput.cpp
@@ -180,13 +180,13 @@
 void AnalogInput::SetSampleRate(double samplesPerSecond) {
   int32_t status = 0;
   HAL_SetAnalogSampleRate(samplesPerSecond, &status);
-  FRC_CheckErrorStatus(status, "{}", "SetSampleRate");
+  FRC_CheckErrorStatus(status, "SetSampleRate");
 }
 
 double AnalogInput::GetSampleRate() {
   int32_t status = 0;
   double sampleRate = HAL_GetAnalogSampleRate(&status);
-  FRC_CheckErrorStatus(status, "{}", "GetSampleRate");
+  FRC_CheckErrorStatus(status, "GetSampleRate");
   return sampleRate;
 }
 
@@ -197,5 +197,5 @@
 void AnalogInput::InitSendable(wpi::SendableBuilder& builder) {
   builder.SetSmartDashboardType("Analog Input");
   builder.AddDoubleProperty(
-      "Value", [=] { return GetAverageVoltage(); }, nullptr);
+      "Value", [=, this] { return GetAverageVoltage(); }, nullptr);
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/AnalogOutput.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/AnalogOutput.cpp
index a391271..90f538b 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/AnalogOutput.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/AnalogOutput.cpp
@@ -61,6 +61,6 @@
 void AnalogOutput::InitSendable(wpi::SendableBuilder& builder) {
   builder.SetSmartDashboardType("Analog Output");
   builder.AddDoubleProperty(
-      "Value", [=] { return GetVoltage(); },
-      [=](double value) { SetVoltage(value); });
+      "Value", [=, this] { return GetVoltage(); },
+      [=, this](double value) { SetVoltage(value); });
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/AnalogPotentiometer.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/AnalogPotentiometer.cpp
index ba94613..d43c84f 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/AnalogPotentiometer.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/AnalogPotentiometer.cpp
@@ -46,5 +46,5 @@
 void AnalogPotentiometer::InitSendable(wpi::SendableBuilder& builder) {
   builder.SetSmartDashboardType("Analog Input");
   builder.AddDoubleProperty(
-      "Value", [=] { return Get(); }, nullptr);
+      "Value", [=, this] { return Get(); }, nullptr);
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/AnalogTriggerOutput.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/AnalogTriggerOutput.cpp
index 93d1969..ccb44b5 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/AnalogTriggerOutput.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/AnalogTriggerOutput.cpp
@@ -18,7 +18,7 @@
   bool result = HAL_GetAnalogTriggerOutput(
       m_trigger->m_trigger, static_cast<HAL_AnalogTriggerType>(m_outputType),
       &status);
-  FRC_CheckErrorStatus(status, "{}", "Get");
+  FRC_CheckErrorStatus(status, "Get");
   return result;
 }
 
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/BuiltInAccelerometer.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/BuiltInAccelerometer.cpp
index 1b8da85..4284e89 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/BuiltInAccelerometer.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/BuiltInAccelerometer.cpp
@@ -23,7 +23,7 @@
 
 void BuiltInAccelerometer::SetRange(Range range) {
   if (range == kRange_16G) {
-    throw FRC_MakeError(err::ParameterOutOfRange, "{}",
+    throw FRC_MakeError(err::ParameterOutOfRange,
                         "16G range not supported (use k2G, k4G, or k8G)");
   }
 
@@ -47,9 +47,9 @@
 void BuiltInAccelerometer::InitSendable(wpi::SendableBuilder& builder) {
   builder.SetSmartDashboardType("3AxisAccelerometer");
   builder.AddDoubleProperty(
-      "X", [=] { return GetX(); }, nullptr);
+      "X", [=, this] { return GetX(); }, nullptr);
   builder.AddDoubleProperty(
-      "Y", [=] { return GetY(); }, nullptr);
+      "Y", [=, this] { return GetY(); }, nullptr);
   builder.AddDoubleProperty(
-      "Z", [=] { return GetZ(); }, nullptr);
+      "Z", [=, this] { return GetZ(); }, nullptr);
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/CAN.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/CAN.cpp
index e26ca37..fc4a821 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/CAN.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/CAN.cpp
@@ -45,20 +45,20 @@
 void CAN::WritePacket(const uint8_t* data, int length, int apiId) {
   int32_t status = 0;
   HAL_WriteCANPacket(m_handle, data, length, apiId, &status);
-  FRC_CheckErrorStatus(status, "{}", "WritePacket");
+  FRC_CheckErrorStatus(status, "WritePacket");
 }
 
 void CAN::WritePacketRepeating(const uint8_t* data, int length, int apiId,
                                int repeatMs) {
   int32_t status = 0;
   HAL_WriteCANPacketRepeating(m_handle, data, length, apiId, repeatMs, &status);
-  FRC_CheckErrorStatus(status, "{}", "WritePacketRepeating");
+  FRC_CheckErrorStatus(status, "WritePacketRepeating");
 }
 
 void CAN::WriteRTRFrame(int length, int apiId) {
   int32_t status = 0;
   HAL_WriteCANRTRFrame(m_handle, length, apiId, &status);
-  FRC_CheckErrorStatus(status, "{}", "WriteRTRFrame");
+  FRC_CheckErrorStatus(status, "WriteRTRFrame");
 }
 
 int CAN::WritePacketNoError(const uint8_t* data, int length, int apiId) {
@@ -83,7 +83,7 @@
 void CAN::StopPacketRepeating(int apiId) {
   int32_t status = 0;
   HAL_StopCANPacketRepeating(m_handle, apiId, &status);
-  FRC_CheckErrorStatus(status, "{}", "StopPacketRepeating");
+  FRC_CheckErrorStatus(status, "StopPacketRepeating");
 }
 
 bool CAN::ReadPacketNew(int apiId, CANData* data) {
@@ -94,7 +94,7 @@
     return false;
   }
   if (status != 0) {
-    FRC_CheckErrorStatus(status, "{}", "ReadPacketNew");
+    FRC_CheckErrorStatus(status, "ReadPacketNew");
     return false;
   } else {
     return true;
@@ -109,7 +109,7 @@
     return false;
   }
   if (status != 0) {
-    FRC_CheckErrorStatus(status, "{}", "ReadPacketLatest");
+    FRC_CheckErrorStatus(status, "ReadPacketLatest");
     return false;
   } else {
     return true;
@@ -125,7 +125,7 @@
     return false;
   }
   if (status != 0) {
-    FRC_CheckErrorStatus(status, "{}", "ReadPacketTimeout");
+    FRC_CheckErrorStatus(status, "ReadPacketTimeout");
     return false;
   } else {
     return true;
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/Compressor.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/Compressor.cpp
index d994b14..2479ffc 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/Compressor.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/Compressor.cpp
@@ -29,18 +29,16 @@
     : Compressor{PneumaticsBase::GetDefaultForType(moduleType), moduleType} {}
 
 Compressor::~Compressor() {
-  m_module->UnreserveCompressor();
-}
-
-void Compressor::Start() {
-  EnableDigital();
-}
-
-void Compressor::Stop() {
-  Disable();
+  if (m_module) {
+    m_module->UnreserveCompressor();
+  }
 }
 
 bool Compressor::Enabled() const {
+  return IsEnabled();
+}
+
+bool Compressor::IsEnabled() const {
   return m_module->GetCompressor();
 }
 
@@ -85,7 +83,7 @@
 void Compressor::InitSendable(wpi::SendableBuilder& builder) {
   builder.SetSmartDashboardType("Compressor");
   builder.AddBooleanProperty(
-      "Enabled", [=] { return Enabled(); }, nullptr);
+      "Enabled", [this] { return IsEnabled(); }, nullptr);
   builder.AddBooleanProperty(
-      "Pressure switch", [=]() { return GetPressureSwitchValue(); }, nullptr);
+      "Pressure switch", [this] { return GetPressureSwitchValue(); }, nullptr);
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/Counter.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/Counter.cpp
index a1ad9e7..2e9c916 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/Counter.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/Counter.cpp
@@ -22,7 +22,7 @@
   int32_t status = 0;
   m_counter = HAL_InitializeCounter(static_cast<HAL_Counter_Mode>(mode),
                                     &m_index, &status);
-  FRC_CheckErrorStatus(status, "{}", "InitializeCounter");
+  FRC_CheckErrorStatus(status, "InitializeCounter");
 
   SetMaxPeriod(0.5_s);
 
@@ -64,7 +64,7 @@
                  std::shared_ptr<DigitalSource> downSource, bool inverted)
     : Counter(kExternalDirection) {
   if (encodingType != k1X && encodingType != k2X) {
-    throw FRC_MakeError(err::ParameterOutOfRange, "{}",
+    throw FRC_MakeError(err::ParameterOutOfRange,
                         "Counter only supports 1X and 2X quadrature decoding");
   }
   SetUpSource(upSource);
@@ -79,7 +79,7 @@
     HAL_SetCounterAverageSize(m_counter, 2, &status);
   }
 
-  FRC_CheckErrorStatus(status, "{}", "Counter constructor");
+  FRC_CheckErrorStatus(status, "Counter constructor");
   SetDownSourceEdge(inverted, true);
 }
 
@@ -92,7 +92,7 @@
 
   int32_t status = 0;
   HAL_FreeCounter(m_counter, &status);
-  FRC_ReportError(status, "{}", "Counter destructor");
+  FRC_ReportError(status, "Counter destructor");
 }
 
 void Counter::SetUpSource(int channel) {
@@ -124,7 +124,7 @@
                          static_cast<HAL_AnalogTriggerType>(
                              source->GetAnalogTriggerTypeForRouting()),
                          &status);
-  FRC_CheckErrorStatus(status, "{}", "SetUpSource");
+  FRC_CheckErrorStatus(status, "SetUpSource");
 }
 
 void Counter::SetUpSource(DigitalSource& source) {
@@ -135,19 +135,19 @@
 void Counter::SetUpSourceEdge(bool risingEdge, bool fallingEdge) {
   if (m_upSource == nullptr) {
     throw FRC_MakeError(
-        err::NullParameter, "{}",
+        err::NullParameter,
         "Must set non-nullptr UpSource before setting UpSourceEdge");
   }
   int32_t status = 0;
   HAL_SetCounterUpSourceEdge(m_counter, risingEdge, fallingEdge, &status);
-  FRC_CheckErrorStatus(status, "{}", "SetUpSourceEdge");
+  FRC_CheckErrorStatus(status, "SetUpSourceEdge");
 }
 
 void Counter::ClearUpSource() {
   m_upSource.reset();
   int32_t status = 0;
   HAL_ClearCounterUpSource(m_counter, &status);
-  FRC_CheckErrorStatus(status, "{}", "ClearUpSource");
+  FRC_CheckErrorStatus(status, "ClearUpSource");
 }
 
 void Counter::SetDownSource(int channel) {
@@ -184,37 +184,37 @@
                            static_cast<HAL_AnalogTriggerType>(
                                source->GetAnalogTriggerTypeForRouting()),
                            &status);
-  FRC_CheckErrorStatus(status, "{}", "SetDownSource");
+  FRC_CheckErrorStatus(status, "SetDownSource");
 }
 
 void Counter::SetDownSourceEdge(bool risingEdge, bool fallingEdge) {
   if (m_downSource == nullptr) {
     throw FRC_MakeError(
-        err::NullParameter, "{}",
+        err::NullParameter,
         "Must set non-nullptr DownSource before setting DownSourceEdge");
   }
   int32_t status = 0;
   HAL_SetCounterDownSourceEdge(m_counter, risingEdge, fallingEdge, &status);
-  FRC_CheckErrorStatus(status, "{}", "SetDownSourceEdge");
+  FRC_CheckErrorStatus(status, "SetDownSourceEdge");
 }
 
 void Counter::ClearDownSource() {
   m_downSource.reset();
   int32_t status = 0;
   HAL_ClearCounterDownSource(m_counter, &status);
-  FRC_CheckErrorStatus(status, "{}", "ClearDownSource");
+  FRC_CheckErrorStatus(status, "ClearDownSource");
 }
 
 void Counter::SetUpDownCounterMode() {
   int32_t status = 0;
   HAL_SetCounterUpDownMode(m_counter, &status);
-  FRC_CheckErrorStatus(status, "{}", "SetUpDownCounterMode");
+  FRC_CheckErrorStatus(status, "SetUpDownCounterMode");
 }
 
 void Counter::SetExternalDirectionMode() {
   int32_t status = 0;
   HAL_SetCounterExternalDirectionMode(m_counter, &status);
-  FRC_CheckErrorStatus(status, "{}", "SetExternalDirectionMode");
+  FRC_CheckErrorStatus(status, "SetExternalDirectionMode");
 }
 
 void Counter::SetSemiPeriodMode(bool highSemiPeriod) {
@@ -227,7 +227,7 @@
 void Counter::SetPulseLengthMode(double threshold) {
   int32_t status = 0;
   HAL_SetCounterPulseLengthMode(m_counter, threshold, &status);
-  FRC_CheckErrorStatus(status, "{}", "SetPulseLengthMode");
+  FRC_CheckErrorStatus(status, "SetPulseLengthMode");
 }
 
 void Counter::SetReverseDirection(bool reverseDirection) {
@@ -252,7 +252,7 @@
 int Counter::GetSamplesToAverage() const {
   int32_t status = 0;
   int samples = HAL_GetCounterSamplesToAverage(m_counter, &status);
-  FRC_CheckErrorStatus(status, "{}", "GetSamplesToAverage");
+  FRC_CheckErrorStatus(status, "GetSamplesToAverage");
   return samples;
 }
 
@@ -263,51 +263,51 @@
 int Counter::Get() const {
   int32_t status = 0;
   int value = HAL_GetCounter(m_counter, &status);
-  FRC_CheckErrorStatus(status, "{}", "Get");
+  FRC_CheckErrorStatus(status, "Get");
   return value;
 }
 
 void Counter::Reset() {
   int32_t status = 0;
   HAL_ResetCounter(m_counter, &status);
-  FRC_CheckErrorStatus(status, "{}", "Reset");
+  FRC_CheckErrorStatus(status, "Reset");
 }
 
 units::second_t Counter::GetPeriod() const {
   int32_t status = 0;
   double value = HAL_GetCounterPeriod(m_counter, &status);
-  FRC_CheckErrorStatus(status, "{}", "GetPeriod");
+  FRC_CheckErrorStatus(status, "GetPeriod");
   return units::second_t{value};
 }
 
 void Counter::SetMaxPeriod(units::second_t maxPeriod) {
   int32_t status = 0;
   HAL_SetCounterMaxPeriod(m_counter, maxPeriod.value(), &status);
-  FRC_CheckErrorStatus(status, "{}", "SetMaxPeriod");
+  FRC_CheckErrorStatus(status, "SetMaxPeriod");
 }
 
 void Counter::SetUpdateWhenEmpty(bool enabled) {
   int32_t status = 0;
   HAL_SetCounterUpdateWhenEmpty(m_counter, enabled, &status);
-  FRC_CheckErrorStatus(status, "{}", "SetUpdateWhenEmpty");
+  FRC_CheckErrorStatus(status, "SetUpdateWhenEmpty");
 }
 
 bool Counter::GetStopped() const {
   int32_t status = 0;
   bool value = HAL_GetCounterStopped(m_counter, &status);
-  FRC_CheckErrorStatus(status, "{}", "GetStopped");
+  FRC_CheckErrorStatus(status, "GetStopped");
   return value;
 }
 
 bool Counter::GetDirection() const {
   int32_t status = 0;
   bool value = HAL_GetCounterDirection(m_counter, &status);
-  FRC_CheckErrorStatus(status, "{}", "GetDirection");
+  FRC_CheckErrorStatus(status, "GetDirection");
   return value;
 }
 
 void Counter::InitSendable(wpi::SendableBuilder& builder) {
   builder.SetSmartDashboardType("Counter");
   builder.AddDoubleProperty(
-      "Value", [=] { return Get(); }, nullptr);
+      "Value", [=, this] { return Get(); }, nullptr);
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/DMA.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/DMA.cpp
index 80c0adb..ce6c532 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/DMA.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/DMA.cpp
@@ -27,7 +27,7 @@
 DMA::DMA() {
   int32_t status = 0;
   dmaHandle = HAL_InitializeDMA(&status);
-  FRC_CheckErrorStatus(status, "{}", "InitializeDMA");
+  FRC_CheckErrorStatus(status, "InitializeDMA");
 }
 
 DMA::~DMA() {
@@ -37,74 +37,74 @@
 void DMA::SetPause(bool pause) {
   int32_t status = 0;
   HAL_SetDMAPause(dmaHandle, pause, &status);
-  FRC_CheckErrorStatus(status, "{}", "SetPause");
+  FRC_CheckErrorStatus(status, "SetPause");
 }
 
 void DMA::SetTimedTrigger(units::second_t seconds) {
   int32_t status = 0;
   HAL_SetDMATimedTrigger(dmaHandle, seconds.value(), &status);
-  FRC_CheckErrorStatus(status, "{}", "SetTimedTrigger");
+  FRC_CheckErrorStatus(status, "SetTimedTrigger");
 }
 
 void DMA::SetTimedTriggerCycles(int cycles) {
   int32_t status = 0;
   HAL_SetDMATimedTriggerCycles(dmaHandle, cycles, &status);
-  FRC_CheckErrorStatus(status, "{}", "SetTimedTriggerCycles");
+  FRC_CheckErrorStatus(status, "SetTimedTriggerCycles");
 }
 
 void DMA::AddEncoder(const Encoder* encoder) {
   int32_t status = 0;
   HAL_AddDMAEncoder(dmaHandle, encoder->m_encoder, &status);
-  FRC_CheckErrorStatus(status, "{}", "AddEncoder");
+  FRC_CheckErrorStatus(status, "AddEncoder");
 }
 
 void DMA::AddEncoderPeriod(const Encoder* encoder) {
   int32_t status = 0;
   HAL_AddDMAEncoderPeriod(dmaHandle, encoder->m_encoder, &status);
-  FRC_CheckErrorStatus(status, "{}", "AddEncoderPeriod");
+  FRC_CheckErrorStatus(status, "AddEncoderPeriod");
 }
 
 void DMA::AddCounter(const Counter* counter) {
   int32_t status = 0;
   HAL_AddDMACounter(dmaHandle, counter->m_counter, &status);
-  FRC_CheckErrorStatus(status, "{}", "AddCounter");
+  FRC_CheckErrorStatus(status, "AddCounter");
 }
 
 void DMA::AddCounterPeriod(const Counter* counter) {
   int32_t status = 0;
   HAL_AddDMACounterPeriod(dmaHandle, counter->m_counter, &status);
-  FRC_CheckErrorStatus(status, "{}", "AddCounterPeriod");
+  FRC_CheckErrorStatus(status, "AddCounterPeriod");
 }
 
 void DMA::AddDigitalSource(const DigitalSource* digitalSource) {
   int32_t status = 0;
   HAL_AddDMADigitalSource(dmaHandle, digitalSource->GetPortHandleForRouting(),
                           &status);
-  FRC_CheckErrorStatus(status, "{}", "AddDigitalSource");
+  FRC_CheckErrorStatus(status, "AddDigitalSource");
 }
 
 void DMA::AddDutyCycle(const DutyCycle* dutyCycle) {
   int32_t status = 0;
   HAL_AddDMADutyCycle(dmaHandle, dutyCycle->m_handle, &status);
-  FRC_CheckErrorStatus(status, "{}", "AddDutyCycle");
+  FRC_CheckErrorStatus(status, "AddDutyCycle");
 }
 
 void DMA::AddAnalogInput(const AnalogInput* analogInput) {
   int32_t status = 0;
   HAL_AddDMAAnalogInput(dmaHandle, analogInput->m_port, &status);
-  FRC_CheckErrorStatus(status, "{}", "AddAnalogInput");
+  FRC_CheckErrorStatus(status, "AddAnalogInput");
 }
 
 void DMA::AddAveragedAnalogInput(const AnalogInput* analogInput) {
   int32_t status = 0;
   HAL_AddDMAAveragedAnalogInput(dmaHandle, analogInput->m_port, &status);
-  FRC_CheckErrorStatus(status, "{}", "AddAveragedAnalogInput");
+  FRC_CheckErrorStatus(status, "AddAveragedAnalogInput");
 }
 
 void DMA::AddAnalogAccumulator(const AnalogInput* analogInput) {
   int32_t status = 0;
   HAL_AddDMAAnalogAccumulator(dmaHandle, analogInput->m_port, &status);
-  FRC_CheckErrorStatus(status, "{}", "AddAnalogAccumulator");
+  FRC_CheckErrorStatus(status, "AddAnalogAccumulator");
 }
 
 int DMA::SetExternalTrigger(DigitalSource* source, bool rising, bool falling) {
@@ -114,7 +114,7 @@
                                 static_cast<HAL_AnalogTriggerType>(
                                     source->GetAnalogTriggerTypeForRouting()),
                                 rising, falling, &status);
-  FRC_CheckErrorStatus(status, "{}", "SetExternalTrigger");
+  FRC_CheckErrorStatus(status, "SetExternalTrigger");
   return idx;
 }
 
@@ -124,7 +124,7 @@
   int32_t idx = HAL_SetDMAExternalTrigger(
       dmaHandle, source->GetPwm()->m_handle,
       HAL_AnalogTriggerType::HAL_Trigger_kInWindow, rising, falling, &status);
-  FRC_CheckErrorStatus(status, "{}", "SetPWmEdgeTrigger");
+  FRC_CheckErrorStatus(status, "SetPWmEdgeTrigger");
   return idx;
 }
 
@@ -133,30 +133,30 @@
   int32_t idx = HAL_SetDMAExternalTrigger(
       dmaHandle, source->m_handle, HAL_AnalogTriggerType::HAL_Trigger_kInWindow,
       rising, falling, &status);
-  FRC_CheckErrorStatus(status, "{}", "SetPWmEdgeTrigger");
+  FRC_CheckErrorStatus(status, "SetPWmEdgeTrigger");
   return idx;
 }
 
 void DMA::ClearSensors() {
   int32_t status = 0;
   HAL_ClearDMASensors(dmaHandle, &status);
-  FRC_CheckErrorStatus(status, "{}", "ClearSensors");
+  FRC_CheckErrorStatus(status, "ClearSensors");
 }
 
 void DMA::ClearExternalTriggers() {
   int32_t status = 0;
   HAL_ClearDMAExternalTriggers(dmaHandle, &status);
-  FRC_CheckErrorStatus(status, "{}", "ClearExternalTriggers");
+  FRC_CheckErrorStatus(status, "ClearExternalTriggers");
 }
 
 void DMA::Start(int queueDepth) {
   int32_t status = 0;
   HAL_StartDMA(dmaHandle, queueDepth, &status);
-  FRC_CheckErrorStatus(status, "{}", "Start");
+  FRC_CheckErrorStatus(status, "Start");
 }
 
 void DMA::Stop() {
   int32_t status = 0;
   HAL_StopDMA(dmaHandle, &status);
-  FRC_CheckErrorStatus(status, "{}", "Stop");
+  FRC_CheckErrorStatus(status, "Stop");
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/DataLogManager.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/DataLogManager.cpp
new file mode 100644
index 0000000..b92faa3
--- /dev/null
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/DataLogManager.cpp
@@ -0,0 +1,317 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/DataLogManager.h"
+
+#include <algorithm>
+#include <ctime>
+#include <random>
+
+#include <fmt/chrono.h>
+#include <fmt/format.h>
+#include <networktables/NetworkTableInstance.h>
+#include <wpi/DataLog.h>
+#include <wpi/SafeThread.h>
+#include <wpi/StringExtras.h>
+#include <wpi/fs.h>
+#include <wpi/timestamp.h>
+
+#include "frc/DriverStation.h"
+#include "frc/Filesystem.h"
+
+using namespace frc;
+
+namespace {
+
+struct Thread final : public wpi::SafeThread {
+  Thread(std::string_view dir, std::string_view filename, double period);
+
+  void Main() final;
+
+  void StartNTLog();
+  void StopNTLog();
+
+  std::string m_logDir;
+  bool m_filenameOverride;
+  wpi::log::DataLog m_log;
+  bool m_ntLoggerEnabled = false;
+  NT_DataLogger m_ntEntryLogger = 0;
+  NT_ConnectionDataLogger m_ntConnLogger = 0;
+  wpi::log::StringLogEntry m_messageLog;
+};
+
+struct Instance {
+  Instance(std::string_view dir, std::string_view filename, double period);
+  wpi::SafeThreadOwner<Thread> owner;
+};
+
+}  // namespace
+
+// if less than this much free space, delete log files until there is this much
+// free space OR there are this many files remaining.
+static constexpr uintmax_t kFreeSpaceThreshold = 50000000;
+static constexpr int kFileCountThreshold = 10;
+
+static std::string MakeLogDir(std::string_view dir) {
+  if (!dir.empty()) {
+    return std::string{dir};
+  }
+#ifdef __FRC_ROBORIO__
+  // prefer a mounted USB drive if one is accessible
+  constexpr std::string_view usbDir{"/u"};
+  std::error_code ec;
+  auto s = fs::status(usbDir, ec);
+  if (!ec && fs::is_directory(s) &&
+      (s.permissions() & fs::perms::others_write) != fs::perms::none) {
+    return std::string{usbDir};
+  }
+#endif
+  return frc::filesystem::GetOperatingDirectory();
+}
+
+static std::string MakeLogFilename(std::string_view filenameOverride) {
+  if (!filenameOverride.empty()) {
+    return std::string{filenameOverride};
+  }
+  static std::random_device dev;
+  static std::mt19937 rng(dev());
+  std::uniform_int_distribution<int> dist(0, 15);
+  const char* v = "0123456789abcdef";
+  std::string filename = "FRC_TBD_";
+  for (int i = 0; i < 16; i++) {
+    filename += v[dist(rng)];
+  }
+  filename += ".wpilog";
+  return filename;
+}
+
+Thread::Thread(std::string_view dir, std::string_view filename, double period)
+    : m_logDir{dir},
+      m_filenameOverride{!filename.empty()},
+      m_log{dir, MakeLogFilename(filename), period},
+      m_messageLog{m_log, "messages"} {
+  StartNTLog();
+}
+
+void Thread::Main() {
+  // based on free disk space, scan for "old" FRC_*.wpilog files and remove
+  {
+    uintmax_t freeSpace = fs::space(m_logDir).free;
+    if (freeSpace < kFreeSpaceThreshold) {
+      // Delete oldest FRC_*.wpilog files (ignore FRC_TBD_*.wpilog as we just
+      // created one)
+      std::vector<fs::directory_entry> entries;
+      std::error_code ec;
+      for (auto&& entry : fs::directory_iterator{m_logDir, ec}) {
+        auto stem = entry.path().stem().string();
+        if (wpi::starts_with(stem, "FRC_") &&
+            entry.path().extension() == ".wpilog" &&
+            !wpi::starts_with(stem, "FRC_TBD_")) {
+          entries.emplace_back(entry);
+        }
+      }
+      std::sort(entries.begin(), entries.end(),
+                [](const auto& a, const auto& b) {
+                  return a.last_write_time() < b.last_write_time();
+                });
+
+      int count = entries.size();
+      for (auto&& entry : entries) {
+        --count;
+        if (count < kFileCountThreshold) {
+          break;
+        }
+        auto size = entry.file_size();
+        if (fs::remove(entry.path(), ec)) {
+          freeSpace += size;
+          if (freeSpace >= kFreeSpaceThreshold) {
+            break;
+          }
+        } else {
+          fmt::print(stderr, "DataLogManager: could not delete {}\n",
+                     entry.path().string());
+        }
+      }
+    }
+  }
+
+  int timeoutCount = 0;
+  bool paused = false;
+  int dsAttachCount = 0;
+  int fmsAttachCount = 0;
+  bool dsRenamed = m_filenameOverride;
+  bool fmsRenamed = m_filenameOverride;
+  int sysTimeCount = 0;
+  wpi::log::IntegerLogEntry sysTimeEntry{
+      m_log, "systemTime",
+      "{\"source\":\"DataLogManager\",\"format\":\"time_t_us\"}"};
+
+  wpi::Event newDataEvent;
+  DriverStation::ProvideRefreshedDataEventHandle(newDataEvent.GetHandle());
+
+  for (;;) {
+    bool timedOut = false;
+    bool newData =
+        wpi::WaitForObject(newDataEvent.GetHandle(), 0.25, &timedOut);
+    if (!m_active) {
+      break;
+    }
+    if (!newData) {
+      ++timeoutCount;
+      // pause logging after being disconnected for 10 seconds
+      if (timeoutCount > 40 && !paused) {
+        timeoutCount = 0;
+        paused = true;
+        m_log.Pause();
+      }
+      continue;
+    }
+    // when we connect to the DS, resume logging
+    timeoutCount = 0;
+    if (paused) {
+      paused = false;
+      m_log.Resume();
+    }
+
+    if (!dsRenamed) {
+      // track DS attach
+      if (DriverStation::IsDSAttached()) {
+        ++dsAttachCount;
+      } else {
+        dsAttachCount = 0;
+      }
+      if (dsAttachCount > 50) {  // 1 second
+        std::time_t now = std::time(nullptr);
+        auto tm = std::gmtime(&now);
+        if (tm->tm_year > 100) {
+          // assume local clock is now synchronized to DS, so rename based on
+          // local time
+          m_log.SetFilename(fmt::format("FRC_{:%Y%m%d_%H%M%S}.wpilog", *tm));
+          dsRenamed = true;
+        } else {
+          dsAttachCount = 0;  // wait a bit and try again
+        }
+      }
+    }
+
+    if (!fmsRenamed) {
+      // track FMS attach
+      if (DriverStation::IsFMSAttached()) {
+        ++fmsAttachCount;
+      } else {
+        fmsAttachCount = 0;
+      }
+      if (fmsAttachCount > 100) {  // 2 seconds
+        // match info comes through TCP, so we need to double-check we've
+        // actually received it
+        auto matchType = DriverStation::GetMatchType();
+        if (matchType != DriverStation::kNone) {
+          // rename per match info
+          char matchTypeChar;
+          switch (matchType) {
+            case DriverStation::kPractice:
+              matchTypeChar = 'P';
+              break;
+            case DriverStation::kQualification:
+              matchTypeChar = 'Q';
+              break;
+            case DriverStation::kElimination:
+              matchTypeChar = 'E';
+              break;
+            default:
+              matchTypeChar = '_';
+              break;
+          }
+          std::time_t now = std::time(nullptr);
+          m_log.SetFilename(
+              fmt::format("FRC_{:%Y%m%d_%H%M%S}_{}_{}{}.wpilog",
+                          *std::gmtime(&now), DriverStation::GetEventName(),
+                          matchTypeChar, DriverStation::GetMatchNumber()));
+          fmsRenamed = true;
+          dsRenamed = true;  // don't override FMS rename
+        }
+      }
+    }
+
+    // Write system time every ~5 seconds
+    ++sysTimeCount;
+    if (sysTimeCount >= 250) {
+      sysTimeCount = 0;
+      sysTimeEntry.Append(wpi::GetSystemTime(), wpi::Now());
+    }
+  }
+  DriverStation::RemoveRefreshedDataEventHandle(newDataEvent.GetHandle());
+}
+
+void Thread::StartNTLog() {
+  if (!m_ntLoggerEnabled) {
+    m_ntLoggerEnabled = true;
+    auto inst = nt::NetworkTableInstance::GetDefault();
+    m_ntEntryLogger = inst.StartEntryDataLog(m_log, "", "NT:");
+    m_ntConnLogger = inst.StartConnectionDataLog(m_log, "NTConnection");
+  }
+}
+
+void Thread::StopNTLog() {
+  if (m_ntLoggerEnabled) {
+    m_ntLoggerEnabled = false;
+    nt::NetworkTableInstance::StopEntryDataLog(m_ntEntryLogger);
+    nt::NetworkTableInstance::StopConnectionDataLog(m_ntConnLogger);
+  }
+}
+
+Instance::Instance(std::string_view dir, std::string_view filename,
+                   double period) {
+  // Delete all previously existing FRC_TBD_*.wpilog files. These only exist
+  // when the robot never connects to the DS, so they are very unlikely to
+  // have useful data and just clutter the filesystem.
+  auto logDir = MakeLogDir(dir);
+  std::error_code ec;
+  for (auto&& entry : fs::directory_iterator{logDir, ec}) {
+    if (wpi::starts_with(entry.path().stem().string(), "FRC_TBD_") &&
+        entry.path().extension() == ".wpilog") {
+      if (!fs::remove(entry, ec)) {
+        fmt::print(stderr, "DataLogManager: could not delete {}\n",
+                   entry.path().string());
+      }
+    }
+  }
+
+  owner.Start(logDir, filename, period);
+}
+
+static Instance& GetInstance(std::string_view dir = "",
+                             std::string_view filename = "",
+                             double period = 0.25) {
+  static Instance instance(dir, filename, period);
+  return instance;
+}
+
+void DataLogManager::Start(std::string_view dir, std::string_view filename,
+                           double period) {
+  GetInstance(dir, filename, period);
+}
+
+void DataLogManager::Log(std::string_view message) {
+  GetInstance().owner.GetThread()->m_messageLog.Append(message);
+  fmt::print("{}\n", message);
+}
+
+wpi::log::DataLog& DataLogManager::GetLog() {
+  return GetInstance().owner.GetThread()->m_log;
+}
+
+std::string DataLogManager::GetLogDir() {
+  return GetInstance().owner.GetThread()->m_logDir;
+}
+
+void DataLogManager::LogNetworkTables(bool enabled) {
+  if (auto thr = GetInstance().owner.GetThread()) {
+    if (enabled) {
+      thr->StartNTLog();
+    } else if (!enabled) {
+      thr->StopNTLog();
+    }
+  }
+}
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/DigitalGlitchFilter.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/DigitalGlitchFilter.cpp
index 3294a99..4abb7cf 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/DigitalGlitchFilter.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/DigitalGlitchFilter.cpp
@@ -56,7 +56,7 @@
     // We don't support GlitchFilters on AnalogTriggers.
     if (input->IsAnalogTrigger()) {
       throw FRC_MakeError(
-          -1, "{}", "Analog Triggers not supported for DigitalGlitchFilters");
+          -1, "Analog Triggers not supported for DigitalGlitchFilters");
     }
     int32_t status = 0;
     HAL_SetFilterSelect(input->GetPortHandleForRouting(), requestedIndex,
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/DigitalInput.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/DigitalInput.cpp
index 86f1c3a..0275741 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/DigitalInput.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/DigitalInput.cpp
@@ -69,5 +69,5 @@
 void DigitalInput::InitSendable(wpi::SendableBuilder& builder) {
   builder.SetSmartDashboardType("Digital Input");
   builder.AddBooleanProperty(
-      "Value", [=] { return Get(); }, nullptr);
+      "Value", [=, this] { return Get(); }, nullptr);
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/DigitalOutput.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/DigitalOutput.cpp
index 5810e30..fc69e35 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/DigitalOutput.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/DigitalOutput.cpp
@@ -76,9 +76,9 @@
   return m_channel;
 }
 
-void DigitalOutput::Pulse(double length) {
+void DigitalOutput::Pulse(units::second_t pulseLength) {
   int32_t status = 0;
-  HAL_Pulse(m_handle, length, &status);
+  HAL_Pulse(m_handle, pulseLength.to<double>(), &status);
   FRC_CheckErrorStatus(status, "Channel {}", m_channel);
 }
 
@@ -95,6 +95,23 @@
   FRC_CheckErrorStatus(status, "Channel {}", m_channel);
 }
 
+void DigitalOutput::EnablePPS(double dutyCycle) {
+  if (m_pwmGenerator != HAL_kInvalidHandle) {
+    return;
+  }
+
+  int32_t status = 0;
+
+  m_pwmGenerator = HAL_AllocateDigitalPWM(&status);
+  FRC_CheckErrorStatus(status, "Channel {}", m_channel);
+
+  HAL_SetDigitalPWMPPS(m_pwmGenerator, dutyCycle, &status);
+  FRC_CheckErrorStatus(status, "Channel {}", m_channel);
+
+  HAL_SetDigitalPWMOutputChannel(m_pwmGenerator, m_channel, &status);
+  FRC_CheckErrorStatus(status, "Channel {}", m_channel);
+}
+
 void DigitalOutput::EnablePWM(double initialDutyCycle) {
   if (m_pwmGenerator != HAL_kInvalidHandle) {
     return;
@@ -143,5 +160,6 @@
 void DigitalOutput::InitSendable(wpi::SendableBuilder& builder) {
   builder.SetSmartDashboardType("Digital Output");
   builder.AddBooleanProperty(
-      "Value", [=] { return Get(); }, [=](bool value) { Set(value); });
+      "Value", [=, this] { return Get(); },
+      [=, this](bool value) { Set(value); });
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/DoubleSolenoid.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/DoubleSolenoid.cpp
index 212673a..c111622 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/DoubleSolenoid.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/DoubleSolenoid.cpp
@@ -65,7 +65,9 @@
                      forwardChannel, reverseChannel} {}
 
 DoubleSolenoid::~DoubleSolenoid() {
-  m_module->UnreserveSolenoids(m_mask);
+  if (m_module) {
+    m_module->UnreserveSolenoids(m_mask);
+  }
 }
 
 void DoubleSolenoid::Set(Value value) {
@@ -127,10 +129,10 @@
 void DoubleSolenoid::InitSendable(wpi::SendableBuilder& builder) {
   builder.SetSmartDashboardType("Double Solenoid");
   builder.SetActuator(true);
-  builder.SetSafeState([=] { Set(kOff); });
+  builder.SetSafeState([=, this] { Set(kOff); });
   builder.AddSmallStringProperty(
       "Value",
-      [=](wpi::SmallVectorImpl<char>& buf) -> std::string_view {
+      [=, this](wpi::SmallVectorImpl<char>& buf) -> std::string_view {
         switch (Get()) {
           case kForward:
             return "Forward";
@@ -140,7 +142,7 @@
             return "Off";
         }
       },
-      [=](std::string_view value) {
+      [=, this](std::string_view value) {
         Value lvalue = kOff;
         if (value == "Forward") {
           lvalue = kForward;
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/DriverStation.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/DriverStation.cpp
index 37fc65f..aead343 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/DriverStation.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/DriverStation.cpp
@@ -9,6 +9,7 @@
 #include <array>
 #include <atomic>
 #include <chrono>
+#include <span>
 #include <string>
 #include <string_view>
 #include <thread>
@@ -19,11 +20,16 @@
 #include <hal/DriverStationTypes.h>
 #include <hal/HALBase.h>
 #include <hal/Power.h>
+#include <networktables/BooleanTopic.h>
+#include <networktables/IntegerTopic.h>
 #include <networktables/NetworkTable.h>
-#include <networktables/NetworkTableEntry.h>
 #include <networktables/NetworkTableInstance.h>
+#include <networktables/StringTopic.h>
+#include <wpi/DataLog.h>
+#include <wpi/EventVector.h>
 #include <wpi/condition_variable.h>
 #include <wpi/mutex.h>
+#include <wpi/timestamp.h>
 
 #include "frc/Errors.h"
 #include "frc/MotorSafety.h"
@@ -34,63 +40,87 @@
 namespace {
 // A simple class which caches the previous value written to an NT entry
 // Used to prevent redundant, repeated writes of the same value
-template <class T>
+template <typename Topic>
 class MatchDataSenderEntry {
  public:
   MatchDataSenderEntry(const std::shared_ptr<nt::NetworkTable>& table,
-                       std::string_view key, const T& initialVal) {
-    static_assert(std::is_same_v<T, bool> || std::is_same_v<T, double> ||
-                      std::is_same_v<T, std::string>,
-                  "Invalid type for MatchDataSenderEntry - must be "
-                  "to bool, double or std::string");
-
-    ntEntry = table->GetEntry(key);
-    if constexpr (std::is_same_v<T, bool>) {
-      ntEntry.ForceSetBoolean(initialVal);
-    } else if constexpr (std::is_same_v<T, double>) {
-      ntEntry.ForceSetDouble(initialVal);
-    } else if constexpr (std::is_same_v<T, std::string>) {
-      ntEntry.ForceSetString(initialVal);
-    }
-    prevVal = initialVal;
+                       std::string_view key,
+                       typename Topic::ParamType initialVal)
+      : publisher{Topic{table->GetTopic(key)}.Publish()}, prevVal{initialVal} {
+    publisher.Set(initialVal);
   }
 
-  void Set(const T& val) {
+  void Set(typename Topic::ParamType val) {
     if (val != prevVal) {
-      SetValue(val);
+      publisher.Set(val);
       prevVal = val;
     }
   }
 
  private:
-  nt::NetworkTableEntry ntEntry;
-  T prevVal;
-
-  void SetValue(bool val) { ntEntry.SetBoolean(val); }
-  void SetValue(double val) { ntEntry.SetDouble(val); }
-  void SetValue(std::string_view val) { ntEntry.SetString(val); }
+  typename Topic::PublisherType publisher;
+  typename Topic::ValueType prevVal;
 };
 
 struct MatchDataSender {
   std::shared_ptr<nt::NetworkTable> table =
       nt::NetworkTableInstance::GetDefault().GetTable("FMSInfo");
-  MatchDataSenderEntry<std::string> typeMetaData{table, ".type", "FMSInfo"};
-  MatchDataSenderEntry<std::string> gameSpecificMessage{
+  MatchDataSenderEntry<nt::StringTopic> typeMetaData{table, ".type", "FMSInfo"};
+  MatchDataSenderEntry<nt::StringTopic> gameSpecificMessage{
       table, "GameSpecificMessage", ""};
-  MatchDataSenderEntry<std::string> eventName{table, "EventName", ""};
-  MatchDataSenderEntry<double> matchNumber{table, "MatchNumber", 0.0};
-  MatchDataSenderEntry<double> replayNumber{table, "ReplayNumber", 0.0};
-  MatchDataSenderEntry<double> matchType{table, "MatchType", 0.0};
-  MatchDataSenderEntry<bool> alliance{table, "IsRedAlliance", true};
-  MatchDataSenderEntry<double> station{table, "StationNumber", 1.0};
-  MatchDataSenderEntry<double> controlWord{table, "FMSControlData", 0.0};
+  MatchDataSenderEntry<nt::StringTopic> eventName{table, "EventName", ""};
+  MatchDataSenderEntry<nt::IntegerTopic> matchNumber{table, "MatchNumber", 0};
+  MatchDataSenderEntry<nt::IntegerTopic> replayNumber{table, "ReplayNumber", 0};
+  MatchDataSenderEntry<nt::IntegerTopic> matchType{table, "MatchType", 0};
+  MatchDataSenderEntry<nt::BooleanTopic> alliance{table, "IsRedAlliance", true};
+  MatchDataSenderEntry<nt::IntegerTopic> station{table, "StationNumber", 1};
+  MatchDataSenderEntry<nt::IntegerTopic> controlWord{table, "FMSControlData",
+                                                     0};
+};
+
+class JoystickLogSender {
+ public:
+  void Init(wpi::log::DataLog& log, unsigned int stick, int64_t timestamp);
+  void Send(uint64_t timestamp);
+
+ private:
+  void AppendButtons(HAL_JoystickButtons buttons, uint64_t timestamp);
+  void AppendPOVs(const HAL_JoystickPOVs& povs, uint64_t timestamp);
+
+  unsigned int m_stick;
+  HAL_JoystickButtons m_prevButtons;
+  HAL_JoystickAxes m_prevAxes;
+  HAL_JoystickPOVs m_prevPOVs;
+  wpi::log::BooleanArrayLogEntry m_logButtons;
+  wpi::log::FloatArrayLogEntry m_logAxes;
+  wpi::log::IntegerArrayLogEntry m_logPOVs;
+};
+
+class DataLogSender {
+ public:
+  void Init(wpi::log::DataLog& log, bool logJoysticks, int64_t timestamp);
+  void Send(uint64_t timestamp);
+
+ private:
+  std::atomic_bool m_initialized{false};
+
+  HAL_ControlWord m_prevControlWord;
+  wpi::log::BooleanLogEntry m_logEnabled;
+  wpi::log::BooleanLogEntry m_logAutonomous;
+  wpi::log::BooleanLogEntry m_logTest;
+  wpi::log::BooleanLogEntry m_logEstop;
+
+  bool m_logJoysticks;
+  std::array<JoystickLogSender, DriverStation::kJoystickPorts> m_joysticks;
 };
 
 struct Instance {
   Instance();
   ~Instance();
 
+  wpi::EventVector refreshEvents;
   MatchDataSender matchDataSender;
+  std::atomic<DataLogSender*> dataLogSender{nullptr};
 
   // Joystick button rising/falling edge flags
   wpi::mutex buttonEdgeMutex;
@@ -99,14 +129,6 @@
   std::array<uint32_t, DriverStation::kJoystickPorts> joystickButtonsPressed;
   std::array<uint32_t, DriverStation::kJoystickPorts> joystickButtonsReleased;
 
-  // Internal Driver Station thread
-  std::thread dsThread;
-  std::atomic<bool> isRunning{false};
-
-  mutable wpi::mutex waitForDataMutex;
-  wpi::condition_variable waitForDataCond;
-  int waitForDataCounter = 0;
-
   bool silenceJoystickWarning = false;
 
   // Robot state status variables
@@ -126,7 +148,6 @@
   return instance;
 }
 
-static void Run();
 static void SendMatchData();
 
 /**
@@ -140,8 +161,7 @@
 template <typename S, typename... Args>
 static inline void ReportJoystickUnpluggedError(const S& format,
                                                 Args&&... args) {
-  ReportJoystickUnpluggedErrorV(
-      format, fmt::make_args_checked<Args...>(format, args...));
+  ReportJoystickUnpluggedErrorV(format, fmt::make_format_args(args...));
 }
 
 /**
@@ -155,17 +175,7 @@
 template <typename S, typename... Args>
 static inline void ReportJoystickUnpluggedWarning(const S& format,
                                                   Args&&... args) {
-  ReportJoystickUnpluggedWarningV(
-      format, fmt::make_args_checked<Args...>(format, args...));
-}
-
-static int& GetDSLastCount() {
-  // There is a rollover error condition here. At Packet# = n * (uintmax), this
-  // will return false when instead it should return true. However, this at a
-  // 20ms rate occurs once every 2.7 years of DS connected runtime, so not
-  // worth the cycles to check.
-  thread_local int lastCount{0};
-  return lastCount;
+  ReportJoystickUnpluggedWarningV(format, fmt::make_format_args(args...));
 }
 
 Instance::Instance() {
@@ -179,21 +189,12 @@
     previousButtonStates[i].count = 0;
     previousButtonStates[i].buttons = 0;
   }
-
-  dsThread = std::thread(&Run);
 }
 
 Instance::~Instance() {
-  isRunning = false;
-  // Trigger a DS mutex release in case there is no driver station running.
-  HAL_ReleaseDSMutex();
-  dsThread.join();
-}
-
-DriverStation& DriverStation::GetInstance() {
-  ::GetInstance();
-  static DriverStation instance;
-  return instance;
+  if (dataLogSender) {
+    delete dataLogSender.load();
+  }
 }
 
 bool DriverStation::GetStickButton(int stick, int button) {
@@ -419,11 +420,15 @@
     FRC_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick);
     return -1;
   }
+  if (axis < 0 || axis >= HAL_kMaxJoystickAxes) {
+    FRC_ReportError(warn::BadJoystickAxis, "axis {} out of range", axis);
+    return -1;
+  }
 
   HAL_JoystickDescriptor descriptor;
   HAL_GetJoystickDescriptor(stick, &descriptor);
 
-  return static_cast<bool>(descriptor.axisTypes);
+  return descriptor.axisTypes[axis];
 }
 
 bool DriverStation::IsJoystickConnected(int stick) {
@@ -461,20 +466,12 @@
   return controlWord.autonomous && controlWord.enabled;
 }
 
-bool DriverStation::IsOperatorControl() {
-  return IsTeleop();
-}
-
 bool DriverStation::IsTeleop() {
   HAL_ControlWord controlWord;
   HAL_GetControlWord(&controlWord);
   return !(controlWord.autonomous || controlWord.test);
 }
 
-bool DriverStation::IsOperatorControlEnabled() {
-  return IsTeleopEnabled();
-}
-
 bool DriverStation::IsTeleopEnabled() {
   HAL_ControlWord controlWord;
   HAL_GetControlWord(&controlWord);
@@ -493,18 +490,6 @@
   return controlWord.dsAttached;
 }
 
-bool DriverStation::IsNewControlData() {
-  auto& inst = ::GetInstance();
-  std::unique_lock lock(inst.waitForDataMutex);
-  int& lastCount = GetDSLastCount();
-  int currentCount = inst.waitForDataCounter;
-  if (lastCount == currentCount) {
-    return false;
-  }
-  lastCount = currentCount;
-  return true;
-}
-
 bool DriverStation::IsFMSAttached() {
   HAL_ControlWord controlWord;
   HAL_GetControlWord(&controlWord);
@@ -577,36 +562,6 @@
   }
 }
 
-void DriverStation::WaitForData() {
-  WaitForData(0_s);
-}
-
-bool DriverStation::WaitForData(units::second_t timeout) {
-  auto& inst = ::GetInstance();
-  auto timeoutTime = std::chrono::steady_clock::now() +
-                     std::chrono::steady_clock::duration{timeout};
-
-  std::unique_lock lock(inst.waitForDataMutex);
-  int& lastCount = GetDSLastCount();
-  int currentCount = inst.waitForDataCounter;
-  if (lastCount != currentCount) {
-    lastCount = currentCount;
-    return true;
-  }
-  while (inst.waitForDataCounter == currentCount) {
-    if (timeout > 0_s) {
-      auto timedOut = inst.waitForDataCond.wait_until(lock, timeoutTime);
-      if (timedOut == std::cv_status::timeout) {
-        return false;
-      }
-    } else {
-      inst.waitForDataCond.wait(lock);
-    }
-  }
-  lastCount = inst.waitForDataCounter;
-  return true;
-}
-
 double DriverStation::GetMatchTime() {
   int32_t status = 0;
   return HAL_GetMatchTime(&status);
@@ -615,46 +570,19 @@
 double DriverStation::GetBatteryVoltage() {
   int32_t status = 0;
   double voltage = HAL_GetVinVoltage(&status);
-  FRC_CheckErrorStatus(status, "{}", "getVinVoltage");
+  FRC_CheckErrorStatus(status, "getVinVoltage");
 
   return voltage;
 }
 
-void DriverStation::InDisabled(bool entering) {
-  ::GetInstance().userInDisabled = entering;
-}
-
-void DriverStation::InAutonomous(bool entering) {
-  ::GetInstance().userInAutonomous = entering;
-}
-
-void DriverStation::InOperatorControl(bool entering) {
-  InTeleop(entering);
-}
-
-void DriverStation::InTeleop(bool entering) {
-  ::GetInstance().userInTeleop = entering;
-}
-
-void DriverStation::InTest(bool entering) {
-  ::GetInstance().userInTest = entering;
-}
-
-void DriverStation::WakeupWaitForData() {
-  auto& inst = ::GetInstance();
-  std::scoped_lock waitLock(inst.waitForDataMutex);
-  // Nofify all threads
-  inst.waitForDataCounter++;
-  inst.waitForDataCond.notify_all();
-}
-
 /**
  * Copy data from the DS task for the user.
  *
  * If no new data exists, it will just be returned, otherwise
  * the data will be copied from the DS polling loop.
  */
-void GetData() {
+void DriverStation::RefreshData() {
+  HAL_RefreshDSData();
   auto& inst = ::GetInstance();
   {
     // Compute the pressed and released buttons
@@ -676,8 +604,22 @@
     }
   }
 
-  DriverStation::WakeupWaitForData();
+  inst.refreshEvents.Wakeup();
+
   SendMatchData();
+  if (auto sender = inst.dataLogSender.load()) {
+    sender->Send(wpi::Now());
+  }
+}
+
+void DriverStation::ProvideRefreshedDataEventHandle(WPI_EventHandle handle) {
+  auto& inst = ::GetInstance();
+  inst.refreshEvents.Add(handle);
+}
+
+void DriverStation::RemoveRefreshedDataEventHandle(WPI_EventHandle handle) {
+  auto& inst = ::GetInstance();
+  inst.refreshEvents.Remove(handle);
 }
 
 void DriverStation::SilenceJoystickConnectionWarning(bool silence) {
@@ -688,6 +630,24 @@
   return !IsFMSAttached() && ::GetInstance().silenceJoystickWarning;
 }
 
+void DriverStation::StartDataLog(wpi::log::DataLog& log, bool logJoysticks) {
+  auto& inst = ::GetInstance();
+  // Note: cannot safely replace, because we wouldn't know when to delete the
+  // "old" one. Instead do a compare and exchange with nullptr. We check first
+  // with a simple load to avoid the new in the common case.
+  if (inst.dataLogSender.load()) {
+    return;
+  }
+  DataLogSender* oldSender = nullptr;
+  DataLogSender* newSender = new DataLogSender;
+  inst.dataLogSender.compare_exchange_strong(oldSender, newSender);
+  if (oldSender) {
+    delete newSender;  // already had a sender
+  } else {
+    newSender->Init(log, logJoysticks, wpi::Now());
+  }
+}
+
 void ReportJoystickUnpluggedErrorV(fmt::string_view format,
                                    fmt::format_args args) {
   auto& inst = GetInstance();
@@ -710,37 +670,6 @@
   }
 }
 
-void Run() {
-  auto& inst = GetInstance();
-  inst.isRunning = true;
-  int safetyCounter = 0;
-  while (inst.isRunning) {
-    HAL_WaitForDSData();
-    GetData();
-
-    if (DriverStation::IsDisabled()) {
-      safetyCounter = 0;
-    }
-
-    if (++safetyCounter >= 4) {
-      MotorSafety::CheckMotors();
-      safetyCounter = 0;
-    }
-    if (inst.userInDisabled) {
-      HAL_ObserveUserProgramDisabled();
-    }
-    if (inst.userInAutonomous) {
-      HAL_ObserveUserProgramAutonomous();
-    }
-    if (inst.userInTeleop) {
-      HAL_ObserveUserProgramTeleop();
-    }
-    if (inst.userInTest) {
-      HAL_ObserveUserProgramTest();
-    }
-  }
-}
-
 void SendMatchData() {
   int32_t status = 0;
   HAL_AllianceStationID alliance = HAL_GetAllianceStation(&status);
@@ -793,3 +722,131 @@
   std::memcpy(&wordInt, &ctlWord, sizeof(wordInt));
   inst.matchDataSender.controlWord.Set(wordInt);
 }
+
+void JoystickLogSender::Init(wpi::log::DataLog& log, unsigned int stick,
+                             int64_t timestamp) {
+  m_stick = stick;
+
+  m_logButtons = wpi::log::BooleanArrayLogEntry{
+      log, fmt::format("DS:joystick{}/buttons", stick), timestamp};
+  m_logAxes = wpi::log::FloatArrayLogEntry{
+      log, fmt::format("DS:joystick{}/axes", stick), timestamp};
+  m_logPOVs = wpi::log::IntegerArrayLogEntry{
+      log, fmt::format("DS:joystick{}/povs", stick), timestamp};
+
+  HAL_GetJoystickButtons(m_stick, &m_prevButtons);
+  HAL_GetJoystickAxes(m_stick, &m_prevAxes);
+  HAL_GetJoystickPOVs(m_stick, &m_prevPOVs);
+  AppendButtons(m_prevButtons, timestamp);
+  m_logAxes.Append(
+      std::span<const float>{m_prevAxes.axes,
+                             static_cast<size_t>(m_prevAxes.count)},
+      timestamp);
+  AppendPOVs(m_prevPOVs, timestamp);
+}
+
+void JoystickLogSender::Send(uint64_t timestamp) {
+  HAL_JoystickButtons buttons;
+  HAL_GetJoystickButtons(m_stick, &buttons);
+  if (buttons.count != m_prevButtons.count ||
+      buttons.buttons != m_prevButtons.buttons) {
+    AppendButtons(buttons, timestamp);
+  }
+  m_prevButtons = buttons;
+
+  HAL_JoystickAxes axes;
+  HAL_GetJoystickAxes(m_stick, &axes);
+  if (axes.count != m_prevAxes.count ||
+      std::memcmp(axes.axes, m_prevAxes.axes,
+                  sizeof(axes.axes[0]) * axes.count) != 0) {
+    m_logAxes.Append(
+        std::span<const float>{axes.axes, static_cast<size_t>(axes.count)},
+        timestamp);
+  }
+  m_prevAxes = axes;
+
+  HAL_JoystickPOVs povs;
+  HAL_GetJoystickPOVs(m_stick, &povs);
+  if (povs.count != m_prevPOVs.count ||
+      std::memcmp(povs.povs, m_prevPOVs.povs,
+                  sizeof(povs.povs[0]) * povs.count) != 0) {
+    AppendPOVs(povs, timestamp);
+  }
+  m_prevPOVs = povs;
+}
+
+void JoystickLogSender::AppendButtons(HAL_JoystickButtons buttons,
+                                      uint64_t timestamp) {
+  uint8_t buttonsArr[32];
+  for (unsigned int i = 0; i < buttons.count; ++i) {
+    buttonsArr[i] = (buttons.buttons & (1u << i)) != 0;
+  }
+  m_logButtons.Append(std::span<const uint8_t>{buttonsArr, buttons.count},
+                      timestamp);
+}
+
+void JoystickLogSender::AppendPOVs(const HAL_JoystickPOVs& povs,
+                                   uint64_t timestamp) {
+  int64_t povsArr[HAL_kMaxJoystickPOVs];
+  for (int i = 0; i < povs.count; ++i) {
+    povsArr[i] = povs.povs[i];
+  }
+  m_logPOVs.Append(
+      std::span<const int64_t>{povsArr, static_cast<size_t>(povs.count)},
+      timestamp);
+}
+
+void DataLogSender::Init(wpi::log::DataLog& log, bool logJoysticks,
+                         int64_t timestamp) {
+  m_logEnabled = wpi::log::BooleanLogEntry{log, "DS:enabled", timestamp};
+  m_logAutonomous = wpi::log::BooleanLogEntry{log, "DS:autonomous", timestamp};
+  m_logTest = wpi::log::BooleanLogEntry{log, "DS:test", timestamp};
+  m_logEstop = wpi::log::BooleanLogEntry{log, "DS:estop", timestamp};
+
+  // append initial control word values
+  HAL_GetControlWord(&m_prevControlWord);
+  m_logEnabled.Append(m_prevControlWord.enabled, timestamp);
+  m_logAutonomous.Append(m_prevControlWord.autonomous, timestamp);
+  m_logTest.Append(m_prevControlWord.test, timestamp);
+  m_logEstop.Append(m_prevControlWord.eStop, timestamp);
+
+  m_logJoysticks = logJoysticks;
+  if (logJoysticks) {
+    unsigned int i = 0;
+    for (auto&& joystick : m_joysticks) {
+      joystick.Init(log, i++, timestamp);
+    }
+  }
+
+  m_initialized = true;
+}
+
+void DataLogSender::Send(uint64_t timestamp) {
+  if (!m_initialized) {
+    return;
+  }
+
+  // append control word value changes
+  HAL_ControlWord ctlWord;
+  HAL_GetControlWord(&ctlWord);
+  if (ctlWord.enabled != m_prevControlWord.enabled) {
+    m_logEnabled.Append(ctlWord.enabled, timestamp);
+  }
+  if (ctlWord.autonomous != m_prevControlWord.autonomous) {
+    m_logAutonomous.Append(ctlWord.autonomous, timestamp);
+  }
+  if (ctlWord.test != m_prevControlWord.test) {
+    m_logTest.Append(ctlWord.test, timestamp);
+  }
+  if (ctlWord.eStop != m_prevControlWord.eStop) {
+    m_logEstop.Append(ctlWord.eStop, timestamp);
+  }
+  m_prevControlWord = ctlWord;
+
+  if (m_logJoysticks) {
+    // append joystick value changes
+    for (auto&& joystick : m_joysticks) {
+      joystick.Send(timestamp);
+    }
+  }
+}
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/DutyCycle.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/DutyCycle.cpp
index a8375e0..88f6b56 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/DutyCycle.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/DutyCycle.cpp
@@ -17,7 +17,7 @@
 DutyCycle::DutyCycle(DigitalSource* source)
     : m_source{source, wpi::NullDeleter<DigitalSource>()} {
   if (!m_source) {
-    throw FRC_MakeError(err::NullParameter, "{}", "source");
+    throw FRC_MakeError(err::NullParameter, "source");
   }
   InitDutyCycle();
 }
@@ -30,7 +30,7 @@
 DutyCycle::DutyCycle(std::shared_ptr<DigitalSource> source)
     : m_source{std::move(source)} {
   if (!m_source) {
-    throw FRC_MakeError(err::NullParameter, "{}", "source");
+    throw FRC_MakeError(err::NullParameter, "source");
   }
   InitDutyCycle();
 }
@@ -73,11 +73,11 @@
   return retVal;
 }
 
-unsigned int DutyCycle::GetOutputRaw() const {
+units::second_t DutyCycle::GetHighTime() const {
   int32_t status = 0;
-  auto retVal = HAL_GetDutyCycleOutputRaw(m_handle, &status);
+  auto retVal = HAL_GetDutyCycleHighTime(m_handle, &status);
   FRC_CheckErrorStatus(status, "Channel {}", GetSourceChannel());
-  return retVal;
+  return units::nanosecond_t{static_cast<double>(retVal)};
 }
 
 unsigned int DutyCycle::GetOutputScaleFactor() const {
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/DutyCycleEncoder.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/DutyCycleEncoder.cpp
index 452f5cd..b1c943e 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/DutyCycleEncoder.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/DutyCycleEncoder.cpp
@@ -60,6 +60,8 @@
         m_simDevice.CreateDouble("position", hal::SimDevice::kInput, 0.0);
     m_simDistancePerRotation = m_simDevice.CreateDouble(
         "distance_per_rot", hal::SimDevice::kOutput, 1.0);
+    m_simAbsolutePosition =
+        m_simDevice.CreateDouble("absPosition", hal::SimDevice::kInput, 0.0);
     m_simIsConnected =
         m_simDevice.CreateBoolean("connected", hal::SimDevice::kInput, true);
   } else {
@@ -76,6 +78,11 @@
                                m_dutyCycle->GetSourceChannel());
 }
 
+static bool DoubleEquals(double a, double b) {
+  constexpr double epsilon = 0.00001;
+  return std::abs(a - b) < epsilon;
+}
+
 units::turn_t DutyCycleEncoder::Get() const {
   if (m_simPosition) {
     return units::turn_t{m_simPosition.Get()};
@@ -88,15 +95,9 @@
     auto pos = m_dutyCycle->GetOutput();
     auto counter2 = m_counter->Get();
     auto pos2 = m_dutyCycle->GetOutput();
-    if (counter == counter2 && pos == pos2) {
+    if (counter == counter2 && DoubleEquals(pos, pos2)) {
       // map sensor range
-      if (pos < m_sensorMin) {
-        pos = m_sensorMin;
-      }
-      if (pos > m_sensorMax) {
-        pos = m_sensorMax;
-      }
-      pos = (pos - m_sensorMin) / (m_sensorMax - m_sensorMin);
+      pos = MapSensorRange(pos);
       units::turn_t turns{counter + pos - m_positionOffset};
       m_lastPosition = turns;
       return turns;
@@ -104,12 +105,39 @@
   }
 
   FRC_ReportError(
-      warn::Warning, "{}",
+      warn::Warning,
       "Failed to read DutyCycle Encoder. Potential Speed Overrun. Returning "
       "last value");
   return m_lastPosition;
 }
 
+double DutyCycleEncoder::MapSensorRange(double pos) const {
+  if (pos < m_sensorMin) {
+    pos = m_sensorMin;
+  }
+  if (pos > m_sensorMax) {
+    pos = m_sensorMax;
+  }
+  pos = (pos - m_sensorMin) / (m_sensorMax - m_sensorMin);
+  return pos;
+}
+
+double DutyCycleEncoder::GetAbsolutePosition() const {
+  if (m_simAbsolutePosition) {
+    return m_simAbsolutePosition.Get();
+  }
+
+  return MapSensorRange(m_dutyCycle->GetOutput());
+}
+
+double DutyCycleEncoder::GetPositionOffset() const {
+  return m_positionOffset;
+}
+
+void DutyCycleEncoder::SetPositionOffset(double offset) {
+  m_positionOffset = std::clamp(offset, 0.0, 1.0);
+}
+
 void DutyCycleEncoder::SetDutyCycleRange(double min, double max) {
   m_sensorMin = std::clamp(min, 0.0, 1.0);
   m_sensorMax = std::clamp(max, 0.0, 1.0);
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/Encoder.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/Encoder.cpp
index bef6d76..c644070 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/Encoder.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/Encoder.cpp
@@ -31,10 +31,10 @@
     : m_aSource(aSource, wpi::NullDeleter<DigitalSource>()),
       m_bSource(bSource, wpi::NullDeleter<DigitalSource>()) {
   if (!m_aSource) {
-    throw FRC_MakeError(err::NullParameter, "{}", "aSource");
+    throw FRC_MakeError(err::NullParameter, "aSource");
   }
   if (!m_bSource) {
-    throw FRC_MakeError(err::NullParameter, "{}", "bSource");
+    throw FRC_MakeError(err::NullParameter, "bSource");
   }
   InitEncoder(reverseDirection, encodingType);
 }
@@ -51,10 +51,10 @@
                  EncodingType encodingType)
     : m_aSource(std::move(aSource)), m_bSource(std::move(bSource)) {
   if (!m_aSource) {
-    throw FRC_MakeError(err::NullParameter, "{}", "aSource");
+    throw FRC_MakeError(err::NullParameter, "aSource");
   }
   if (!m_bSource) {
-    throw FRC_MakeError(err::NullParameter, "{}", "bSource");
+    throw FRC_MakeError(err::NullParameter, "bSource");
   }
   InitEncoder(reverseDirection, encodingType);
 }
@@ -62,100 +62,100 @@
 Encoder::~Encoder() {
   int32_t status = 0;
   HAL_FreeEncoder(m_encoder, &status);
-  FRC_ReportError(status, "{}", "FreeEncoder");
+  FRC_ReportError(status, "FreeEncoder");
 }
 
 int Encoder::Get() const {
   int32_t status = 0;
   int value = HAL_GetEncoder(m_encoder, &status);
-  FRC_CheckErrorStatus(status, "{}", "Get");
+  FRC_CheckErrorStatus(status, "Get");
   return value;
 }
 
 void Encoder::Reset() {
   int32_t status = 0;
   HAL_ResetEncoder(m_encoder, &status);
-  FRC_CheckErrorStatus(status, "{}", "Reset");
+  FRC_CheckErrorStatus(status, "Reset");
 }
 
 units::second_t Encoder::GetPeriod() const {
   int32_t status = 0;
   double value = HAL_GetEncoderPeriod(m_encoder, &status);
-  FRC_CheckErrorStatus(status, "{}", "GetPeriod");
+  FRC_CheckErrorStatus(status, "GetPeriod");
   return units::second_t{value};
 }
 
 void Encoder::SetMaxPeriod(units::second_t maxPeriod) {
   int32_t status = 0;
   HAL_SetEncoderMaxPeriod(m_encoder, maxPeriod.value(), &status);
-  FRC_CheckErrorStatus(status, "{}", "SetMaxPeriod");
+  FRC_CheckErrorStatus(status, "SetMaxPeriod");
 }
 
 bool Encoder::GetStopped() const {
   int32_t status = 0;
   bool value = HAL_GetEncoderStopped(m_encoder, &status);
-  FRC_CheckErrorStatus(status, "{}", "GetStopped");
+  FRC_CheckErrorStatus(status, "GetStopped");
   return value;
 }
 
 bool Encoder::GetDirection() const {
   int32_t status = 0;
   bool value = HAL_GetEncoderDirection(m_encoder, &status);
-  FRC_CheckErrorStatus(status, "{}", "GetDirection");
+  FRC_CheckErrorStatus(status, "GetDirection");
   return value;
 }
 
 int Encoder::GetRaw() const {
   int32_t status = 0;
   int value = HAL_GetEncoderRaw(m_encoder, &status);
-  FRC_CheckErrorStatus(status, "{}", "GetRaw");
+  FRC_CheckErrorStatus(status, "GetRaw");
   return value;
 }
 
 int Encoder::GetEncodingScale() const {
   int32_t status = 0;
   int val = HAL_GetEncoderEncodingScale(m_encoder, &status);
-  FRC_CheckErrorStatus(status, "{}", "GetEncodingScale");
+  FRC_CheckErrorStatus(status, "GetEncodingScale");
   return val;
 }
 
 double Encoder::GetDistance() const {
   int32_t status = 0;
   double value = HAL_GetEncoderDistance(m_encoder, &status);
-  FRC_CheckErrorStatus(status, "{}", "GetDistance");
+  FRC_CheckErrorStatus(status, "GetDistance");
   return value;
 }
 
 double Encoder::GetRate() const {
   int32_t status = 0;
   double value = HAL_GetEncoderRate(m_encoder, &status);
-  FRC_CheckErrorStatus(status, "{}", "GetRate");
+  FRC_CheckErrorStatus(status, "GetRate");
   return value;
 }
 
 void Encoder::SetMinRate(double minRate) {
   int32_t status = 0;
   HAL_SetEncoderMinRate(m_encoder, minRate, &status);
-  FRC_CheckErrorStatus(status, "{}", "SetMinRate");
+  FRC_CheckErrorStatus(status, "SetMinRate");
 }
 
 void Encoder::SetDistancePerPulse(double distancePerPulse) {
   int32_t status = 0;
   HAL_SetEncoderDistancePerPulse(m_encoder, distancePerPulse, &status);
-  FRC_CheckErrorStatus(status, "{}", "SetDistancePerPulse");
+  FRC_CheckErrorStatus(status, "SetDistancePerPulse");
 }
 
 double Encoder::GetDistancePerPulse() const {
   int32_t status = 0;
   double distancePerPulse = HAL_GetEncoderDistancePerPulse(m_encoder, &status);
-  FRC_CheckErrorStatus(status, "{}", "GetDistancePerPulse");
+  FRC_CheckErrorStatus(status, "GetDistancePerPulse");
   return distancePerPulse;
 }
 
 void Encoder::SetReverseDirection(bool reverseDirection) {
   int32_t status = 0;
   HAL_SetEncoderReverseDirection(m_encoder, reverseDirection, &status);
-  FRC_CheckErrorStatus(status, "{}", "SetReverseDirection");
+  FRC_CheckErrorStatus(status, "SetReverseDirection");
 }
 
 void Encoder::SetSamplesToAverage(int samplesToAverage) {
@@ -167,13 +167,13 @@
   }
   int32_t status = 0;
   HAL_SetEncoderSamplesToAverage(m_encoder, samplesToAverage, &status);
-  FRC_CheckErrorStatus(status, "{}", "SetSamplesToAverage");
+  FRC_CheckErrorStatus(status, "SetSamplesToAverage");
 }
 
 int Encoder::GetSamplesToAverage() const {
   int32_t status = 0;
   int result = HAL_GetEncoderSamplesToAverage(m_encoder, &status);
-  FRC_CheckErrorStatus(status, "{}", "GetSamplesToAverage");
+  FRC_CheckErrorStatus(status, "GetSamplesToAverage");
   return result;
 }
 
@@ -192,7 +192,7 @@
                                 source.GetAnalogTriggerTypeForRouting()),
                             static_cast<HAL_EncoderIndexingType>(type),
                             &status);
-  FRC_CheckErrorStatus(status, "{}", "SetIndexSource");
+  FRC_CheckErrorStatus(status, "SetIndexSource");
 }
 
 void Encoder::SetSimDevice(HAL_SimDeviceHandle device) {
@@ -202,14 +202,14 @@
 int Encoder::GetFPGAIndex() const {
   int32_t status = 0;
   int val = HAL_GetEncoderFPGAIndex(m_encoder, &status);
-  FRC_CheckErrorStatus(status, "{}", "GetFPGAIndex");
+  FRC_CheckErrorStatus(status, "GetFPGAIndex");
   return val;
 }
 
 void Encoder::InitSendable(wpi::SendableBuilder& builder) {
   int32_t status = 0;
   HAL_EncoderEncodingType type = HAL_GetEncoderEncodingType(m_encoder, &status);
-  FRC_CheckErrorStatus(status, "{}", "GetEncodingType");
+  FRC_CheckErrorStatus(status, "GetEncodingType");
   if (type == HAL_EncoderEncodingType::HAL_Encoder_k4X) {
     builder.SetSmartDashboardType("Quadrature Encoder");
   } else {
@@ -217,11 +217,12 @@
   }
 
   builder.AddDoubleProperty(
-      "Speed", [=] { return GetRate(); }, nullptr);
+      "Speed", [=, this] { return GetRate(); }, nullptr);
   builder.AddDoubleProperty(
-      "Distance", [=] { return GetDistance(); }, nullptr);
+      "Distance", [=, this] { return GetDistance(); }, nullptr);
   builder.AddDoubleProperty(
-      "Distance per Tick", [=] { return GetDistancePerPulse(); }, nullptr);
+      "Distance per Tick", [=, this] { return GetDistancePerPulse(); },
+      nullptr);
 }
 
 void Encoder::InitEncoder(bool reverseDirection, EncodingType encodingType) {
@@ -235,7 +236,7 @@
           m_bSource->GetAnalogTriggerTypeForRouting()),
       reverseDirection, static_cast<HAL_EncoderEncodingType>(encodingType),
       &status);
-  FRC_CheckErrorStatus(status, "{}", "InitEncoder");
+  FRC_CheckErrorStatus(status, "InitEncoder");
 
   HAL_Report(HALUsageReporting::kResourceType_Encoder, GetFPGAIndex() + 1,
              encodingType);
@@ -245,6 +246,6 @@
 double Encoder::DecodingScaleFactor() const {
   int32_t status = 0;
   double val = HAL_GetEncoderDecodingScaleFactor(m_encoder, &status);
-  FRC_CheckErrorStatus(status, "{}", "DecodingScaleFactor");
+  FRC_CheckErrorStatus(status, "DecodingScaleFactor");
   return val;
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/GenericHID.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/GenericHID.cpp
index 6c186eb..f4d26b6 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/GenericHID.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/GenericHID.cpp
@@ -8,6 +8,7 @@
 
 #include "frc/DriverStation.h"
 #include "frc/Errors.h"
+#include "frc/event/BooleanEvent.h"
 
 using namespace frc;
 
@@ -30,6 +31,11 @@
   return DriverStation::GetStickButtonReleased(m_port, button);
 }
 
+BooleanEvent GenericHID::Button(int button, EventLoop* loop) const {
+  return BooleanEvent(loop,
+                      [this, button]() { return this->GetRawButton(button); });
+}
+
 double GenericHID::GetRawAxis(int axis) const {
   return DriverStation::GetStickAxis(m_port, axis);
 }
@@ -38,6 +44,65 @@
   return DriverStation::GetStickPOV(m_port, pov);
 }
 
+BooleanEvent GenericHID::POV(int angle, EventLoop* loop) const {
+  return POV(0, angle, loop);
+}
+
+BooleanEvent GenericHID::POV(int pov, int angle, EventLoop* loop) const {
+  return BooleanEvent(
+      loop, [this, pov, angle] { return this->GetPOV(pov) == angle; });
+}
+
+BooleanEvent GenericHID::POVUp(EventLoop* loop) const {
+  return POV(0, loop);
+}
+
+BooleanEvent GenericHID::POVUpRight(EventLoop* loop) const {
+  return POV(45, loop);
+}
+
+BooleanEvent GenericHID::POVRight(EventLoop* loop) const {
+  return POV(90, loop);
+}
+
+BooleanEvent GenericHID::POVDownRight(EventLoop* loop) const {
+  return POV(135, loop);
+}
+
+BooleanEvent GenericHID::POVDown(EventLoop* loop) const {
+  return POV(180, loop);
+}
+
+BooleanEvent GenericHID::POVDownLeft(EventLoop* loop) const {
+  return POV(225, loop);
+}
+
+BooleanEvent GenericHID::POVLeft(EventLoop* loop) const {
+  return POV(270, loop);
+}
+
+BooleanEvent GenericHID::POVUpLeft(EventLoop* loop) const {
+  return POV(315, loop);
+}
+
+BooleanEvent GenericHID::POVCenter(EventLoop* loop) const {
+  return POV(360, loop);
+}
+
+BooleanEvent GenericHID::AxisLessThan(int axis, double threshold,
+                                      EventLoop* loop) const {
+  return BooleanEvent(loop, [this, axis, threshold]() {
+    return this->GetRawAxis(axis) < threshold;
+  });
+}
+
+BooleanEvent GenericHID::AxisGreaterThan(int axis, double threshold,
+                                         EventLoop* loop) const {
+  return BooleanEvent(loop, [this, axis, threshold]() {
+    return this->GetRawAxis(axis) > threshold;
+  });
+}
+
 int GenericHID::GetAxisCount() const {
   return DriverStation::GetStickAxisCount(m_port);
 }
@@ -83,15 +148,17 @@
 }
 
 void GenericHID::SetRumble(RumbleType type, double value) {
-  if (value < 0) {
-    value = 0;
-  } else if (value > 1) {
-    value = 1;
-  }
+  value = std::clamp(value, 0.0, 1.0);
+  double rumbleValue = value * 65535;
+
   if (type == kLeftRumble) {
-    m_leftRumble = value * 65535;
+    m_leftRumble = rumbleValue;
+  } else if (type == kRightRumble) {
+    m_rightRumble = rumbleValue;
   } else {
-    m_rightRumble = value * 65535;
+    m_leftRumble = rumbleValue;
+    m_rightRumble = rumbleValue;
   }
+
   HAL_SetJoystickOutputs(m_port, m_outputs, m_leftRumble, m_rightRumble);
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/I2C.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/I2C.cpp
index dcfb2b8..da26c0c 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/I2C.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/I2C.cpp
@@ -18,14 +18,14 @@
   int32_t status = 0;
 
   if (port == I2C::Port::kOnboard) {
-    FRC_ReportError(warn::Warning, "{}",
+    FRC_ReportError(warn::Warning,
                     "Onboard I2C port is subject to system lockups. See Known "
                     "Issues page for "
                     "details");
   }
 
   HAL_InitializeI2C(m_port, &status);
-  FRC_CheckErrorStatus(status, "Port {}", port);
+  FRC_CheckErrorStatus(status, "Port {}", static_cast<int>(port));
 
   HAL_Report(HALUsageReporting::kResourceType_I2C, deviceAddress);
 }
@@ -74,7 +74,7 @@
     throw FRC_MakeError(err::ParameterOutOfRange, "count {}", count);
   }
   if (!buffer) {
-    throw FRC_MakeError(err::NullParameter, "{}", "buffer");
+    throw FRC_MakeError(err::NullParameter, "buffer");
   }
   uint8_t regAddr = registerAddress;
   return Transaction(&regAddr, sizeof(regAddr), buffer, count);
@@ -85,7 +85,7 @@
     throw FRC_MakeError(err::ParameterOutOfRange, "count {}", count);
   }
   if (!buffer) {
-    throw FRC_MakeError(err::NullParameter, "{}", "buffer");
+    throw FRC_MakeError(err::NullParameter, "buffer");
   }
   return HAL_ReadI2C(m_port, m_deviceAddress, buffer, count) < 0;
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/IterativeRobotBase.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/IterativeRobotBase.cpp
index 47eb299..0bccb0b 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/IterativeRobotBase.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/IterativeRobotBase.cpp
@@ -4,6 +4,8 @@
 
 #include "frc/IterativeRobotBase.h"
 
+#include <frc/DriverStation.h>
+
 #include <fmt/format.h>
 #include <hal/DriverStation.h>
 #include <networktables/NetworkTableInstance.h>
@@ -16,9 +18,6 @@
 
 using namespace frc;
 
-IterativeRobotBase::IterativeRobotBase(double period)
-    : IterativeRobotBase(units::second_t(period)) {}
-
 IterativeRobotBase::IterativeRobotBase(units::second_t period)
     : m_period(period),
       m_watchdog(period, [this] { PrintLoopOverrunMessage(); }) {}
@@ -95,11 +94,24 @@
   m_ntFlushEnabled = enabled;
 }
 
+void IterativeRobotBase::EnableLiveWindowInTest(bool testLW) {
+  if (IsTest()) {
+    throw FRC_MakeError(err::IncompatibleMode,
+                        "Can't configure test mode while in test mode!");
+  }
+  m_lwEnabledInTest = testLW;
+}
+
+bool IterativeRobotBase::IsLiveWindowEnabledInTest() {
+  return m_lwEnabledInTest;
+}
+
 units::second_t IterativeRobotBase::GetPeriod() const {
   return m_period;
 }
 
 void IterativeRobotBase::LoopFunc() {
+  DriverStation::RefreshData();
   m_watchdog.Reset();
 
   // Get current mode
@@ -125,8 +137,10 @@
     } else if (m_lastMode == Mode::kTeleop) {
       TeleopExit();
     } else if (m_lastMode == Mode::kTest) {
-      LiveWindow::SetEnabled(false);
-      Shuffleboard::DisableActuatorWidgets();
+      if (m_lwEnabledInTest) {
+        LiveWindow::SetEnabled(false);
+        Shuffleboard::DisableActuatorWidgets();
+      }
       TestExit();
     }
 
@@ -141,8 +155,10 @@
       TeleopInit();
       m_watchdog.AddEpoch("TeleopInit()");
     } else if (mode == Mode::kTest) {
-      LiveWindow::SetEnabled(true);
-      Shuffleboard::EnableActuatorWidgets();
+      if (m_lwEnabledInTest) {
+        LiveWindow::SetEnabled(true);
+        Shuffleboard::EnableActuatorWidgets();
+      }
       TestInit();
       m_watchdog.AddEpoch("TestInit()");
     }
@@ -190,7 +206,7 @@
 
   // Flush NetworkTables
   if (m_ntFlushEnabled) {
-    nt::NetworkTableInstance::GetDefault().Flush();
+    nt::NetworkTableInstance::GetDefault().FlushLocal();
   }
 
   // Warn on loop time overruns
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/Joystick.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/Joystick.cpp
index 48f0c77..0eff226 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/Joystick.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/Joystick.cpp
@@ -5,9 +5,11 @@
 #include "frc/Joystick.h"
 
 #include <cmath>
+#include <numbers>
 
 #include <hal/FRCUsageReporting.h>
-#include <wpi/numbers>
+
+#include "frc/event/BooleanEvent.h"
 
 using namespace frc;
 
@@ -93,6 +95,10 @@
   return GetRawButtonReleased(Button::kTrigger);
 }
 
+BooleanEvent Joystick::Trigger(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetTrigger(); });
+}
+
 bool Joystick::GetTop() const {
   return GetRawButton(Button::kTop);
 }
@@ -105,8 +111,12 @@
   return GetRawButtonReleased(Button::kTop);
 }
 
+BooleanEvent Joystick::Top(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetTop(); });
+}
+
 double Joystick::GetMagnitude() const {
-  return std::sqrt(std::pow(GetX(), 2) + std::pow(GetY(), 2));
+  return std::hypot(GetX(), GetY());
 }
 
 double Joystick::GetDirectionRadians() const {
@@ -114,5 +124,5 @@
 }
 
 double Joystick::GetDirectionDegrees() const {
-  return (180 / wpi::numbers::pi) * GetDirectionRadians();
+  return (180 / std::numbers::pi) * GetDirectionRadians();
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/MotorSafety.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/MotorSafety.cpp
index 388a887..368092b 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/MotorSafety.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/MotorSafety.cpp
@@ -7,6 +7,8 @@
 #include <algorithm>
 #include <utility>
 
+#include <hal/DriverStation.h>
+#include <wpi/SafeThread.h>
 #include <wpi/SmallPtrSet.h>
 
 #include "frc/DriverStation.h"
@@ -14,26 +16,87 @@
 
 using namespace frc;
 
-static wpi::SmallPtrSet<MotorSafety*, 32> instanceList;
-static wpi::mutex listMutex;
+namespace {
+class Thread : public wpi::SafeThread {
+ public:
+  Thread() {}
+  void Main() override;
+};
+
+void Thread::Main() {
+  wpi::Event event{false, false};
+  HAL_ProvideNewDataEventHandle(event.GetHandle());
+
+  int safetyCounter = 0;
+  while (m_active) {
+    bool timedOut = false;
+    bool signaled = wpi::WaitForObject(event.GetHandle(), 0.1, &timedOut);
+    if (signaled) {
+      HAL_ControlWord controlWord;
+      std::memset(&controlWord, 0, sizeof(controlWord));
+      HAL_GetControlWord(&controlWord);
+      if (!(controlWord.enabled && controlWord.dsAttached)) {
+        safetyCounter = 0;
+      }
+      if (++safetyCounter >= 4) {
+        MotorSafety::CheckMotors();
+        safetyCounter = 0;
+      }
+    } else {
+      safetyCounter = 0;
+    }
+  }
+
+  HAL_RemoveNewDataEventHandle(event.GetHandle());
+}
+}  // namespace
+
+static std::atomic_bool gShutdown{false};
+
+namespace {
+struct MotorSafetyManager {
+  ~MotorSafetyManager() { gShutdown = true; }
+
+  wpi::SafeThreadOwner<Thread> thread;
+  wpi::SmallPtrSet<MotorSafety*, 32> instanceList;
+  wpi::mutex listMutex;
+  bool threadStarted = false;
+};
+}  // namespace
+
+static MotorSafetyManager& GetManager() {
+  static MotorSafetyManager manager;
+  return manager;
+}
 
 #ifndef __FRC_ROBORIO__
 namespace frc::impl {
 void ResetMotorSafety() {
-  std::scoped_lock lock(listMutex);
-  instanceList.clear();
+  auto& manager = GetManager();
+  std::scoped_lock lock(manager.listMutex);
+  manager.instanceList.clear();
+  manager.thread.Stop();
+  manager.thread.Join();
+  manager.thread = wpi::SafeThreadOwner<Thread>{};
+  manager.threadStarted = false;
 }
 }  // namespace frc::impl
 #endif
 
 MotorSafety::MotorSafety() {
-  std::scoped_lock lock(listMutex);
-  instanceList.insert(this);
+  auto& manager = GetManager();
+  std::scoped_lock lock(manager.listMutex);
+  manager.instanceList.insert(this);
+  if (!manager.threadStarted) {
+    manager.threadStarted = true;
+    manager.thread.Start();
+  }
 }
 
 MotorSafety::~MotorSafety() {
-  std::scoped_lock lock(listMutex);
-  instanceList.erase(this);
+  auto& manager = GetManager();
+  std::scoped_lock lock(manager.listMutex);
+  manager.instanceList.erase(this);
 }
 
 MotorSafety::MotorSafety(MotorSafety&& rhs)
@@ -96,7 +159,9 @@
   }
 
   if (stopTime < Timer::GetFPGATimestamp()) {
-    FRC_ReportError(err::Timeout, "{}... Output not updated often enough",
+    FRC_ReportError(err::Timeout,
+                    "{}... Output not updated often enough. See "
+                    "https://docs.wpilib.org/motorsafety for more information.",
                     GetDescription());
 
     try {
@@ -111,8 +176,9 @@
 }
 
 void MotorSafety::CheckMotors() {
-  std::scoped_lock lock(listMutex);
-  for (auto elem : instanceList) {
+  auto& manager = GetManager();
+  std::scoped_lock lock(manager.listMutex);
+  for (auto elem : manager.instanceList) {
     elem->Check();
   }
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/Notifier.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/Notifier.cpp
index 441f750..d837752 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/Notifier.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/Notifier.cpp
@@ -7,6 +7,7 @@
 #include <utility>
 
 #include <fmt/format.h>
+#include <hal/DriverStation.h>
 #include <hal/FRCUsageReporting.h>
 #include <hal/Notifier.h>
 #include <hal/Threads.h>
@@ -18,14 +19,14 @@
 
 Notifier::Notifier(std::function<void()> handler) {
   if (!handler) {
-    throw FRC_MakeError(err::NullParameter, "{}", "handler");
+    throw FRC_MakeError(err::NullParameter, "handler");
   }
   m_handler = handler;
   int32_t status = 0;
   m_notifier = HAL_InitializeNotifier(&status);
-  FRC_CheckErrorStatus(status, "{}", "InitializeNotifier");
+  FRC_CheckErrorStatus(status, "InitializeNotifier");
 
-  m_thread = std::thread([=] {
+  m_thread = std::thread([=, this] {
     for (;;) {
       int32_t status = 0;
       HAL_NotifierHandle notifier = m_notifier.load();
@@ -60,14 +61,14 @@
 
 Notifier::Notifier(int priority, std::function<void()> handler) {
   if (!handler) {
-    throw FRC_MakeError(err::NullParameter, "{}", "handler");
+    throw FRC_MakeError(err::NullParameter, "handler");
   }
   m_handler = handler;
   int32_t status = 0;
   m_notifier = HAL_InitializeNotifier(&status);
-  FRC_CheckErrorStatus(status, "{}", "InitializeNotifier");
+  FRC_CheckErrorStatus(status, "InitializeNotifier");
 
-  m_thread = std::thread([=] {
+  m_thread = std::thread([=, this] {
     int32_t status = 0;
     HAL_SetCurrentThreadPriority(true, priority, &status);
     for (;;) {
@@ -95,7 +96,21 @@
 
       // call callback
       if (handler) {
-        handler();
+        try {
+          handler();
+        } catch (const frc::RuntimeError& e) {
+          e.Report();
+          FRC_ReportError(
+              err::Error,
+              "Error in Notifier thread."
+              "  The above stacktrace can help determine where the error "
+              "occurred.\n"
+              "  See https://wpilib.org/stacktrace for more information.\n");
+          throw;
+        } catch (const std::exception& e) {
+          HAL_SendError(1, err::Error, 0, e.what(), "", "", 1);
+          throw;
+        }
       }
     }
   });
@@ -106,7 +121,7 @@
   // atomically set handle to 0, then clean
   HAL_NotifierHandle handle = m_notifier.exchange(0);
   HAL_StopNotifier(handle, &status);
-  FRC_ReportError(status, "{}", "StopNotifier");
+  FRC_ReportError(status, "StopNotifier");
 
   // Join the thread to ensure the handler has exited.
   if (m_thread.joinable()) {
@@ -172,7 +187,7 @@
   m_periodic = false;
   int32_t status = 0;
   HAL_CancelNotifierAlarm(m_notifier, &status);
-  FRC_CheckErrorStatus(status, "{}", "CancelNotifierAlarm");
+  FRC_CheckErrorStatus(status, "CancelNotifierAlarm");
 }
 
 void Notifier::UpdateAlarm(uint64_t triggerTime) {
@@ -183,7 +198,7 @@
     return;
   }
   HAL_UpdateNotifierAlarm(notifier, triggerTime, &status);
-  FRC_CheckErrorStatus(status, "{}", "UpdateNotifierAlarm");
+  FRC_CheckErrorStatus(status, "UpdateNotifierAlarm");
 }
 
 void Notifier::UpdateAlarm() {
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/PS4Controller.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/PS4Controller.cpp
index 91fd304..e59e18c 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/PS4Controller.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/PS4Controller.cpp
@@ -6,6 +6,8 @@
 
 #include <hal/FRCUsageReporting.h>
 
+#include "frc/event/BooleanEvent.h"
+
 using namespace frc;
 
 PS4Controller::PS4Controller(int port) : GenericHID(port) {
@@ -48,6 +50,10 @@
   return GetRawButtonReleased(Button::kSquare);
 }
 
+BooleanEvent PS4Controller::Square(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetSquareButton(); });
+}
+
 bool PS4Controller::GetCrossButton() const {
   return GetRawButton(Button::kCross);
 }
@@ -60,6 +66,10 @@
   return GetRawButtonReleased(Button::kCross);
 }
 
+BooleanEvent PS4Controller::Cross(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetCrossButton(); });
+}
+
 bool PS4Controller::GetCircleButton() const {
   return GetRawButton(Button::kCircle);
 }
@@ -72,6 +82,10 @@
   return GetRawButtonReleased(Button::kCircle);
 }
 
+BooleanEvent PS4Controller::Circle(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetCircleButton(); });
+}
+
 bool PS4Controller::GetTriangleButton() const {
   return GetRawButton(Button::kTriangle);
 }
@@ -84,6 +98,10 @@
   return GetRawButtonReleased(Button::kTriangle);
 }
 
+BooleanEvent PS4Controller::Triangle(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetTriangleButton(); });
+}
+
 bool PS4Controller::GetL1Button() const {
   return GetRawButton(Button::kL1);
 }
@@ -96,6 +114,10 @@
   return GetRawButtonReleased(Button::kL1);
 }
 
+BooleanEvent PS4Controller::L1(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetL1Button(); });
+}
+
 bool PS4Controller::GetR1Button() const {
   return GetRawButton(Button::kR1);
 }
@@ -108,6 +130,10 @@
   return GetRawButtonReleased(Button::kR1);
 }
 
+BooleanEvent PS4Controller::R1(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetR1Button(); });
+}
+
 bool PS4Controller::GetL2Button() const {
   return GetRawButton(Button::kL2);
 }
@@ -120,6 +146,10 @@
   return GetRawButtonReleased(Button::kL2);
 }
 
+BooleanEvent PS4Controller::L2(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetL2Button(); });
+}
+
 bool PS4Controller::GetR2Button() const {
   return GetRawButton(Button::kR2);
 }
@@ -132,6 +162,10 @@
   return GetRawButtonReleased(Button::kR2);
 }
 
+BooleanEvent PS4Controller::R2(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetR2Button(); });
+}
+
 bool PS4Controller::GetShareButton() const {
   return GetRawButton(Button::kShare);
 }
@@ -144,6 +178,10 @@
   return GetRawButtonReleased(Button::kShare);
 }
 
+BooleanEvent PS4Controller::Share(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetShareButton(); });
+}
+
 bool PS4Controller::GetOptionsButton() const {
   return GetRawButton(Button::kOptions);
 }
@@ -156,6 +194,10 @@
   return GetRawButtonReleased(Button::kOptions);
 }
 
+BooleanEvent PS4Controller::Options(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetOptionsButton(); });
+}
+
 bool PS4Controller::GetL3Button() const {
   return GetRawButton(Button::kL3);
 }
@@ -168,6 +210,10 @@
   return GetRawButtonReleased(Button::kL3);
 }
 
+BooleanEvent PS4Controller::L3(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetL3Button(); });
+}
+
 bool PS4Controller::GetR3Button() const {
   return GetRawButton(Button::kR3);
 }
@@ -180,6 +226,10 @@
   return GetRawButtonReleased(Button::kR3);
 }
 
+BooleanEvent PS4Controller::R3(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetR3Button(); });
+}
+
 bool PS4Controller::GetPSButton() const {
   return GetRawButton(Button::kPS);
 }
@@ -192,6 +242,10 @@
   return GetRawButtonReleased(Button::kPS);
 }
 
+BooleanEvent PS4Controller::PS(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetPSButton(); });
+}
+
 bool PS4Controller::GetTouchpad() const {
   return GetRawButton(Button::kTouchpad);
 }
@@ -203,3 +257,7 @@
 bool PS4Controller::GetTouchpadReleased() {
   return GetRawButtonReleased(Button::kTouchpad);
 }
+
+BooleanEvent PS4Controller::Touchpad(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetTouchpad(); });
+}
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/PWM.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/PWM.cpp
index 393accc..5c5e6f5 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/PWM.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/PWM.cpp
@@ -117,7 +117,7 @@
       break;
     default:
       throw FRC_MakeError(err::InvalidParameter, "PeriodMultiplier value {}",
-                          mult);
+                          static_cast<int>(mult));
   }
 
   FRC_CheckErrorStatus(status, "Channel {}", m_channel);
@@ -166,7 +166,8 @@
 void PWM::InitSendable(wpi::SendableBuilder& builder) {
   builder.SetSmartDashboardType("PWM");
   builder.SetActuator(true);
-  builder.SetSafeState([=] { SetDisabled(); });
+  builder.SetSafeState([=, this] { SetDisabled(); });
   builder.AddDoubleProperty(
-      "Value", [=] { return GetRaw(); }, [=](double value) { SetRaw(value); });
+      "Value", [=, this] { return GetRaw(); },
+      [=, this](double value) { SetRaw(value); });
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/PneumaticHub.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/PneumaticHub.cpp
index 0f32e1e..ec008cf 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/PneumaticHub.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/PneumaticHub.cpp
@@ -4,6 +4,8 @@
 
 #include "frc/PneumaticHub.h"
 
+#include <array>
+
 #include <fmt/format.h>
 #include <hal/REVPH.h>
 #include <wpi/NullDeleter.h>
@@ -146,7 +148,7 @@
     units::pounds_per_square_inch_t minPressure,
     units::pounds_per_square_inch_t maxPressure) {
   if (minPressure >= maxPressure) {
-    throw FRC_MakeError(err::InvalidParameter, "{}",
+    throw FRC_MakeError(err::InvalidParameter,
                         "maxPressure must be greater than minPresure");
   }
   if (minPressure < 0_psi || minPressure > 120_psi) {
@@ -171,7 +173,7 @@
     units::pounds_per_square_inch_t minPressure,
     units::pounds_per_square_inch_t maxPressure) {
   if (minPressure >= maxPressure) {
-    throw FRC_MakeError(err::InvalidParameter, "{}",
+    throw FRC_MakeError(err::InvalidParameter,
                         "maxPressure must be greater than minPresure");
   }
   if (minPressure < 0_psi || minPressure > 120_psi) {
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/PowerDistribution.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/PowerDistribution.cpp
index 21101f2..ba4cb38 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/PowerDistribution.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/PowerDistribution.cpp
@@ -195,7 +195,7 @@
   for (int i = 0; i < numChannels; ++i) {
     builder.AddDoubleProperty(
         fmt::format("Chan{}", i),
-        [=] {
+        [=, this] {
           int32_t lStatus = 0;
           return HAL_GetPowerDistributionChannelCurrent(m_handle, i, &lStatus);
         },
@@ -203,25 +203,25 @@
   }
   builder.AddDoubleProperty(
       "Voltage",
-      [=] {
+      [=, this] {
         int32_t lStatus = 0;
         return HAL_GetPowerDistributionVoltage(m_handle, &lStatus);
       },
       nullptr);
   builder.AddDoubleProperty(
       "TotalCurrent",
-      [=] {
+      [=, this] {
         int32_t lStatus = 0;
         return HAL_GetPowerDistributionTotalCurrent(m_handle, &lStatus);
       },
       nullptr);
   builder.AddBooleanProperty(
       "SwitchableChannel",
-      [=] {
+      [=, this] {
         int32_t lStatus = 0;
         return HAL_GetPowerDistributionSwitchableChannel(m_handle, &lStatus);
       },
-      [=](bool value) {
+      [=, this](bool value) {
         int32_t lStatus = 0;
         HAL_SetPowerDistributionSwitchableChannel(m_handle, value, &lStatus);
       });
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/Preferences.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/Preferences.cpp
index 4663875..cfb5964 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/Preferences.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/Preferences.cpp
@@ -6,9 +6,13 @@
 
 #include <algorithm>
 
+#include <fmt/format.h>
 #include <hal/FRCUsageReporting.h>
+#include <networktables/MultiSubscriber.h>
 #include <networktables/NetworkTable.h>
 #include <networktables/NetworkTableInstance.h>
+#include <networktables/NetworkTableListener.h>
+#include <networktables/StringTopic.h>
 
 using namespace frc;
 
@@ -21,7 +25,10 @@
 
   std::shared_ptr<nt::NetworkTable> table{
       nt::NetworkTableInstance::GetDefault().GetTable(kTableName)};
-  NT_EntryListener listener;
+  nt::StringPublisher typePublisher{table->GetStringTopic(".type").Publish()};
+  nt::MultiSubscriber tableSubscriber{nt::NetworkTableInstance::GetDefault(),
+                                      {{fmt::format("{}/", table->GetPath())}}};
+  nt::NetworkTableListener listener;
 };
 }  // namespace
 
@@ -38,40 +45,33 @@
 }  // namespace frc::impl
 #endif
 
-Preferences* Preferences::GetInstance() {
-  ::GetInstance();
-  static Preferences instance;
-  return &instance;
-}
-
 std::vector<std::string> Preferences::GetKeys() {
   return ::GetInstance().table->GetKeys();
 }
 
 std::string Preferences::GetString(std::string_view key,
                                    std::string_view defaultValue) {
-  return ::GetInstance().table->GetString(key, defaultValue);
+  return ::GetInstance().table->GetEntry(key).GetString(defaultValue);
 }
 
 int Preferences::GetInt(std::string_view key, int defaultValue) {
-  return static_cast<int>(::GetInstance().table->GetNumber(key, defaultValue));
+  return ::GetInstance().table->GetEntry(key).GetInteger(defaultValue);
 }
 
 double Preferences::GetDouble(std::string_view key, double defaultValue) {
-  return ::GetInstance().table->GetNumber(key, defaultValue);
+  return ::GetInstance().table->GetEntry(key).GetDouble(defaultValue);
 }
 
 float Preferences::GetFloat(std::string_view key, float defaultValue) {
-  return ::GetInstance().table->GetNumber(key, defaultValue);
+  return ::GetInstance().table->GetEntry(key).GetFloat(defaultValue);
 }
 
 bool Preferences::GetBoolean(std::string_view key, bool defaultValue) {
-  return ::GetInstance().table->GetBoolean(key, defaultValue);
+  return ::GetInstance().table->GetEntry(key).GetBoolean(defaultValue);
 }
 
 int64_t Preferences::GetLong(std::string_view key, int64_t defaultValue) {
-  return static_cast<int64_t>(
-      ::GetInstance().table->GetNumber(key, defaultValue));
+  return ::GetInstance().table->GetEntry(key).GetInteger(defaultValue);
 }
 
 void Preferences::SetString(std::string_view key, std::string_view value) {
@@ -80,10 +80,6 @@
   entry.SetPersistent();
 }
 
-void Preferences::PutString(std::string_view key, std::string_view value) {
-  SetString(key, value);
-}
-
 void Preferences::InitString(std::string_view key, std::string_view value) {
   auto entry = ::GetInstance().table->GetEntry(key);
   entry.SetDefaultString(value);
@@ -92,17 +88,13 @@
 
 void Preferences::SetInt(std::string_view key, int value) {
   auto entry = ::GetInstance().table->GetEntry(key);
-  entry.SetDouble(value);
+  entry.SetInteger(value);
   entry.SetPersistent();
 }
 
-void Preferences::PutInt(std::string_view key, int value) {
-  SetInt(key, value);
-}
-
 void Preferences::InitInt(std::string_view key, int value) {
   auto entry = ::GetInstance().table->GetEntry(key);
-  entry.SetDefaultDouble(value);
+  entry.SetDefaultInteger(value);
   entry.SetPersistent();
 }
 
@@ -112,10 +104,6 @@
   entry.SetPersistent();
 }
 
-void Preferences::PutDouble(std::string_view key, double value) {
-  SetDouble(key, value);
-}
-
 void Preferences::InitDouble(std::string_view key, double value) {
   auto entry = ::GetInstance().table->GetEntry(key);
   entry.SetDefaultDouble(value);
@@ -124,17 +112,13 @@
 
 void Preferences::SetFloat(std::string_view key, float value) {
   auto entry = ::GetInstance().table->GetEntry(key);
-  entry.SetDouble(value);
+  entry.SetFloat(value);
   entry.SetPersistent();
 }
 
-void Preferences::PutFloat(std::string_view key, float value) {
-  SetFloat(key, value);
-}
-
 void Preferences::InitFloat(std::string_view key, float value) {
   auto entry = ::GetInstance().table->GetEntry(key);
-  entry.SetDefaultDouble(value);
+  entry.SetDefaultFloat(value);
   entry.SetPersistent();
 }
 
@@ -144,10 +128,6 @@
   entry.SetPersistent();
 }
 
-void Preferences::PutBoolean(std::string_view key, bool value) {
-  SetBoolean(key, value);
-}
-
 void Preferences::InitBoolean(std::string_view key, bool value) {
   auto entry = ::GetInstance().table->GetEntry(key);
   entry.SetDefaultBoolean(value);
@@ -156,17 +136,13 @@
 
 void Preferences::SetLong(std::string_view key, int64_t value) {
   auto entry = ::GetInstance().table->GetEntry(key);
-  entry.SetDouble(value);
+  entry.SetInteger(value);
   entry.SetPersistent();
 }
 
-void Preferences::PutLong(std::string_view key, int64_t value) {
-  SetLong(key, value);
-}
-
 void Preferences::InitLong(std::string_view key, int64_t value) {
   auto entry = ::GetInstance().table->GetEntry(key);
-  entry.SetDefaultDouble(value);
+  entry.SetDefaultInteger(value);
   entry.SetPersistent();
 }
 
@@ -175,7 +151,9 @@
 }
 
 void Preferences::Remove(std::string_view key) {
-  ::GetInstance().table->Delete(key);
+  auto entry = ::GetInstance().table->GetEntry(key);
+  entry.ClearPersistent();
+  entry.Unpublish();
 }
 
 void Preferences::RemoveAll() {
@@ -187,11 +165,15 @@
 }
 
 Instance::Instance() {
-  table->GetEntry(".type").SetString("RobotPreferences");
-  listener = table->AddEntryListener(
-      [=](nt::NetworkTable* table, std::string_view name,
-          nt::NetworkTableEntry entry, std::shared_ptr<nt::Value> value,
-          int flags) { entry.SetPersistent(); },
-      NT_NOTIFY_NEW | NT_NOTIFY_IMMEDIATE);
+  typePublisher.Set("RobotPreferences");
+  listener = nt::NetworkTableListener::CreateListener(
+      tableSubscriber, NT_EVENT_PUBLISH | NT_EVENT_IMMEDIATE,
+      [typeTopic = typePublisher.GetTopic().GetHandle()](auto& event) {
+        if (auto topicInfo = event.GetTopicInfo()) {
+          if (topicInfo->topic != typeTopic) {
+            nt::SetTopicPersistent(topicInfo->topic, true);
+          }
+        }
+      });
   HAL_Report(HALUsageReporting::kResourceType_Preferences, 0);
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/Relay.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/Relay.cpp
index 9bec566..3dfbe64 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/Relay.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/Relay.cpp
@@ -175,10 +175,10 @@
 void Relay::InitSendable(wpi::SendableBuilder& builder) {
   builder.SetSmartDashboardType("Relay");
   builder.SetActuator(true);
-  builder.SetSafeState([=] { Set(kOff); });
+  builder.SetSafeState([=, this] { Set(kOff); });
   builder.AddSmallStringProperty(
       "Value",
-      [=](wpi::SmallVectorImpl<char>& buf) -> std::string_view {
+      [=, this](wpi::SmallVectorImpl<char>& buf) -> std::string_view {
         switch (Get()) {
           case kOn:
             return "On";
@@ -190,7 +190,7 @@
             return "Off";
         }
       },
-      [=](std::string_view value) {
+      [=, this](std::string_view value) {
         if (value == "Off") {
           Set(kOff);
         } else if (value == "Forward") {
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/RobotController.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/RobotController.cpp
index 8bc2d6b..da6e364 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/RobotController.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/RobotController.cpp
@@ -4,6 +4,8 @@
 
 #include "frc/RobotController.h"
 
+#include <cstddef>
+
 #include <hal/CAN.h>
 #include <hal/HALBase.h>
 #include <hal/Power.h>
@@ -15,161 +17,174 @@
 int RobotController::GetFPGAVersion() {
   int32_t status = 0;
   int version = HAL_GetFPGAVersion(&status);
-  FRC_CheckErrorStatus(status, "{}", "GetFPGAVersion");
+  FRC_CheckErrorStatus(status, "GetFPGAVersion");
   return version;
 }
 
 int64_t RobotController::GetFPGARevision() {
   int32_t status = 0;
   int64_t revision = HAL_GetFPGARevision(&status);
-  FRC_CheckErrorStatus(status, "{}", "GetFPGARevision");
+  FRC_CheckErrorStatus(status, "GetFPGARevision");
   return revision;
 }
 
+std::string RobotController::GetSerialNumber() {
+  // Serial number is 8 characters
+  char serialNum[9];
+  size_t len = HAL_GetSerialNumber(serialNum, sizeof(serialNum));
+  return std::string(serialNum, len);
+}
+
+std::string RobotController::GetComments() {
+  char comments[65];
+  size_t len = HAL_GetComments(comments, sizeof(comments));
+  return std::string(comments, len);
+}
+
 uint64_t RobotController::GetFPGATime() {
   int32_t status = 0;
   uint64_t time = HAL_GetFPGATime(&status);
-  FRC_CheckErrorStatus(status, "{}", "GetFPGATime");
+  FRC_CheckErrorStatus(status, "GetFPGATime");
   return time;
 }
 
 bool RobotController::GetUserButton() {
   int32_t status = 0;
   bool value = HAL_GetFPGAButton(&status);
-  FRC_CheckErrorStatus(status, "{}", "GetUserButton");
+  FRC_CheckErrorStatus(status, "GetUserButton");
   return value;
 }
 
 units::volt_t RobotController::GetBatteryVoltage() {
   int32_t status = 0;
   double retVal = HAL_GetVinVoltage(&status);
-  FRC_CheckErrorStatus(status, "{}", "GetBatteryVoltage");
+  FRC_CheckErrorStatus(status, "GetBatteryVoltage");
   return units::volt_t{retVal};
 }
 
 bool RobotController::IsSysActive() {
   int32_t status = 0;
   bool retVal = HAL_GetSystemActive(&status);
-  FRC_CheckErrorStatus(status, "{}", "IsSysActive");
+  FRC_CheckErrorStatus(status, "IsSysActive");
   return retVal;
 }
 
 bool RobotController::IsBrownedOut() {
   int32_t status = 0;
   bool retVal = HAL_GetBrownedOut(&status);
-  FRC_CheckErrorStatus(status, "{}", "IsBrownedOut");
+  FRC_CheckErrorStatus(status, "IsBrownedOut");
   return retVal;
 }
 
 double RobotController::GetInputVoltage() {
   int32_t status = 0;
   double retVal = HAL_GetVinVoltage(&status);
-  FRC_CheckErrorStatus(status, "{}", "GetInputVoltage");
+  FRC_CheckErrorStatus(status, "GetInputVoltage");
   return retVal;
 }
 
 double RobotController::GetInputCurrent() {
   int32_t status = 0;
   double retVal = HAL_GetVinCurrent(&status);
-  FRC_CheckErrorStatus(status, "{}", "GetInputCurrent");
+  FRC_CheckErrorStatus(status, "GetInputCurrent");
   return retVal;
 }
 
 double RobotController::GetVoltage3V3() {
   int32_t status = 0;
   double retVal = HAL_GetUserVoltage3V3(&status);
-  FRC_CheckErrorStatus(status, "{}", "GetVoltage3V3");
+  FRC_CheckErrorStatus(status, "GetVoltage3V3");
   return retVal;
 }
 
 double RobotController::GetCurrent3V3() {
   int32_t status = 0;
   double retVal = HAL_GetUserCurrent3V3(&status);
-  FRC_CheckErrorStatus(status, "{}", "GetCurrent3V3");
+  FRC_CheckErrorStatus(status, "GetCurrent3V3");
   return retVal;
 }
 
 bool RobotController::GetEnabled3V3() {
   int32_t status = 0;
   bool retVal = HAL_GetUserActive3V3(&status);
-  FRC_CheckErrorStatus(status, "{}", "GetEnabled3V3");
+  FRC_CheckErrorStatus(status, "GetEnabled3V3");
   return retVal;
 }
 
 int RobotController::GetFaultCount3V3() {
   int32_t status = 0;
   int retVal = HAL_GetUserCurrentFaults3V3(&status);
-  FRC_CheckErrorStatus(status, "{}", "GetFaultCount3V3");
+  FRC_CheckErrorStatus(status, "GetFaultCount3V3");
   return retVal;
 }
 
 double RobotController::GetVoltage5V() {
   int32_t status = 0;
   double retVal = HAL_GetUserVoltage5V(&status);
-  FRC_CheckErrorStatus(status, "{}", "GetVoltage5V");
+  FRC_CheckErrorStatus(status, "GetVoltage5V");
   return retVal;
 }
 
 double RobotController::GetCurrent5V() {
   int32_t status = 0;
   double retVal = HAL_GetUserCurrent5V(&status);
-  FRC_CheckErrorStatus(status, "{}", "GetCurrent5V");
+  FRC_CheckErrorStatus(status, "GetCurrent5V");
   return retVal;
 }
 
 bool RobotController::GetEnabled5V() {
   int32_t status = 0;
   bool retVal = HAL_GetUserActive5V(&status);
-  FRC_CheckErrorStatus(status, "{}", "GetEnabled5V");
+  FRC_CheckErrorStatus(status, "GetEnabled5V");
   return retVal;
 }
 
 int RobotController::GetFaultCount5V() {
   int32_t status = 0;
   int retVal = HAL_GetUserCurrentFaults5V(&status);
-  FRC_CheckErrorStatus(status, "{}", "GetFaultCount5V");
+  FRC_CheckErrorStatus(status, "GetFaultCount5V");
   return retVal;
 }
 
 double RobotController::GetVoltage6V() {
   int32_t status = 0;
   double retVal = HAL_GetUserVoltage6V(&status);
-  FRC_CheckErrorStatus(status, "{}", "GetVoltage6V");
+  FRC_CheckErrorStatus(status, "GetVoltage6V");
   return retVal;
 }
 
 double RobotController::GetCurrent6V() {
   int32_t status = 0;
   double retVal = HAL_GetUserCurrent6V(&status);
-  FRC_CheckErrorStatus(status, "{}", "GetCurrent6V");
+  FRC_CheckErrorStatus(status, "GetCurrent6V");
   return retVal;
 }
 
 bool RobotController::GetEnabled6V() {
   int32_t status = 0;
   bool retVal = HAL_GetUserActive6V(&status);
-  FRC_CheckErrorStatus(status, "{}", "GetEnabled6V");
+  FRC_CheckErrorStatus(status, "GetEnabled6V");
   return retVal;
 }
 
 int RobotController::GetFaultCount6V() {
   int32_t status = 0;
   int retVal = HAL_GetUserCurrentFaults6V(&status);
-  FRC_CheckErrorStatus(status, "{}", "GetFaultCount6V");
+  FRC_CheckErrorStatus(status, "GetFaultCount6V");
   return retVal;
 }
 
 units::volt_t RobotController::GetBrownoutVoltage() {
   int32_t status = 0;
   double retVal = HAL_GetBrownoutVoltage(&status);
-  FRC_CheckErrorStatus(status, "{}", "GetBrownoutVoltage");
-  return units::volt_t(retVal);
+  FRC_CheckErrorStatus(status, "GetBrownoutVoltage");
+  return units::volt_t{retVal};
 }
 
 void RobotController::SetBrownoutVoltage(units::volt_t brownoutVoltage) {
   int32_t status = 0;
   HAL_SetBrownoutVoltage(brownoutVoltage.value(), &status);
-  FRC_CheckErrorStatus(status, "{}", "SetBrownoutVoltage");
+  FRC_CheckErrorStatus(status, "SetBrownoutVoltage");
 }
 
 CANStatus RobotController::GetCANStatus() {
@@ -181,7 +196,7 @@
   uint32_t transmitErrorCount = 0;
   HAL_CAN_GetCANStatus(&percentBusUtilization, &busOffCount, &txFullCount,
                        &receiveErrorCount, &transmitErrorCount, &status);
-  FRC_CheckErrorStatus(status, "{}", "GetCANStatus");
+  FRC_CheckErrorStatus(status, "GetCANStatus");
   return {percentBusUtilization, static_cast<int>(busOffCount),
           static_cast<int>(txFullCount), static_cast<int>(receiveErrorCount),
           static_cast<int>(transmitErrorCount)};
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/RobotState.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/RobotState.cpp
index 651a644..ede314c 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/RobotState.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/RobotState.cpp
@@ -20,10 +20,6 @@
   return DriverStation::IsEStopped();
 }
 
-bool RobotState::IsOperatorControl() {
-  return IsTeleop();
-}
-
 bool RobotState::IsTeleop() {
   return DriverStation::IsTeleop();
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/SPI.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/SPI.cpp
index bdcee45..29cd006 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/SPI.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/SPI.cpp
@@ -25,7 +25,7 @@
  public:
   Accumulator(HAL_SPIPort port, int xferSize, int validMask, int validValue,
               int dataShift, int dataSize, bool isSigned, bool bigEndian)
-      : m_notifier([=] {
+      : m_notifier([=, this] {
           std::scoped_lock lock(m_mutex);
           Update();
         }),
@@ -77,7 +77,7 @@
     // get amount of data available
     int32_t numToRead =
         HAL_ReadSPIAutoReceivedData(m_port, m_buf, 0, 0, &status);
-    FRC_CheckErrorStatus(status, "Port {}", m_port);
+    FRC_CheckErrorStatus(status, "Port {}", static_cast<int>(m_port));
 
     // only get whole responses; +1 is for timestamp
     numToRead -= numToRead % m_xferSize;
@@ -91,7 +91,7 @@
 
     // read buffered data
     HAL_ReadSPIAutoReceivedData(m_port, m_buf, numToRead, 0, &status);
-    FRC_CheckErrorStatus(status, "Port {}", m_port);
+    FRC_CheckErrorStatus(status, "Port {}", static_cast<int>(m_port));
 
     // loop over all responses
     for (int32_t off = 0; off < numToRead; off += m_xferSize) {
@@ -158,7 +158,8 @@
 SPI::SPI(Port port) : m_port(static_cast<HAL_SPIPort>(port)) {
   int32_t status = 0;
   HAL_InitializeSPI(m_port, &status);
-  FRC_CheckErrorStatus(status, "Port {}", m_port);
+  HAL_SetSPIMode(m_port, m_mode);
+  FRC_CheckErrorStatus(status, "Port {}", static_cast<int>(m_port));
 
   HAL_Report(HALUsageReporting::kResourceType_SPI,
              static_cast<uint8_t>(port) + 1);
@@ -177,55 +178,58 @@
 }
 
 void SPI::SetMSBFirst() {
-  m_msbFirst = true;
-  HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+  FRC_ReportError(1, "SetMSBFirst not supported by roboRIO {}",
+                  static_cast<int>(m_port));
 }
 
 void SPI::SetLSBFirst() {
-  m_msbFirst = false;
-  HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+  FRC_ReportError(1, "SetLSBFirst not supported by roboRIO {}",
+                  static_cast<int>(m_port));
 }
 
 void SPI::SetSampleDataOnLeadingEdge() {
-  m_sampleOnTrailing = false;
-  HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+  int mode = m_mode;
+  mode &= 2;
+  m_mode = static_cast<HAL_SPIMode>(mode);
+  HAL_SetSPIMode(m_port, m_mode);
 }
 
 void SPI::SetSampleDataOnTrailingEdge() {
-  m_sampleOnTrailing = true;
-  HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
-}
-
-void SPI::SetSampleDataOnFalling() {
-  m_sampleOnTrailing = true;
-  HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
-}
-
-void SPI::SetSampleDataOnRising() {
-  m_sampleOnTrailing = false;
-  HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+  int mode = m_mode;
+  mode |= 2;
+  m_mode = static_cast<HAL_SPIMode>(mode);
+  HAL_SetSPIMode(m_port, m_mode);
 }
 
 void SPI::SetClockActiveLow() {
-  m_clockIdleHigh = true;
-  HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+  int mode = m_mode;
+  mode |= 1;
+  m_mode = static_cast<HAL_SPIMode>(mode);
+  HAL_SetSPIMode(m_port, m_mode);
 }
 
 void SPI::SetClockActiveHigh() {
-  m_clockIdleHigh = false;
-  HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+  int mode = m_mode;
+  mode &= 1;
+  m_mode = static_cast<HAL_SPIMode>(mode);
+  HAL_SetSPIMode(m_port, m_mode);
+}
+
+void SPI::SetMode(Mode mode) {
+  m_mode = static_cast<HAL_SPIMode>(mode & 0x3);
+  HAL_SetSPIMode(m_port, m_mode);
 }
 
 void SPI::SetChipSelectActiveHigh() {
   int32_t status = 0;
   HAL_SetSPIChipSelectActiveHigh(m_port, &status);
-  FRC_CheckErrorStatus(status, "Port {}", m_port);
+  FRC_CheckErrorStatus(status, "Port {}", static_cast<int>(m_port));
 }
 
 void SPI::SetChipSelectActiveLow() {
   int32_t status = 0;
   HAL_SetSPIChipSelectActiveLow(m_port, &status);
-  FRC_CheckErrorStatus(status, "Port {}", m_port);
+  FRC_CheckErrorStatus(status, "Port {}", static_cast<int>(m_port));
 }
 
 int SPI::Write(uint8_t* data, int size) {
@@ -255,31 +259,27 @@
 void SPI::InitAuto(int bufferSize) {
   int32_t status = 0;
   HAL_InitSPIAuto(m_port, bufferSize, &status);
-  FRC_CheckErrorStatus(status, "Port {}", m_port);
+  FRC_CheckErrorStatus(status, "Port {}", static_cast<int>(m_port));
 }
 
 void SPI::FreeAuto() {
   int32_t status = 0;
   HAL_FreeSPIAuto(m_port, &status);
-  FRC_CheckErrorStatus(status, "Port {}", m_port);
+  FRC_CheckErrorStatus(status, "Port {}", static_cast<int>(m_port));
 }
 
-void SPI::SetAutoTransmitData(wpi::span<const uint8_t> dataToSend,
+void SPI::SetAutoTransmitData(std::span<const uint8_t> dataToSend,
                               int zeroSize) {
   int32_t status = 0;
   HAL_SetSPIAutoTransmitData(m_port, dataToSend.data(), dataToSend.size(),
                              zeroSize, &status);
-  FRC_CheckErrorStatus(status, "Port {}", m_port);
+  FRC_CheckErrorStatus(status, "Port {}", static_cast<int>(m_port));
 }
 
 void SPI::StartAutoRate(units::second_t period) {
   int32_t status = 0;
   HAL_StartSPIAutoRate(m_port, period.value(), &status);
-  FRC_CheckErrorStatus(status, "Port {}", m_port);
-}
-
-void SPI::StartAutoRate(double period) {
-  StartAutoRate(units::second_t(period));
+  FRC_CheckErrorStatus(status, "Port {}", static_cast<int>(m_port));
 }
 
 void SPI::StartAutoTrigger(DigitalSource& source, bool rising, bool falling) {
@@ -288,19 +288,19 @@
                           static_cast<HAL_AnalogTriggerType>(
                               source.GetAnalogTriggerTypeForRouting()),
                           rising, falling, &status);
-  FRC_CheckErrorStatus(status, "Port {}", m_port);
+  FRC_CheckErrorStatus(status, "Port {}", static_cast<int>(m_port));
 }
 
 void SPI::StopAuto() {
   int32_t status = 0;
   HAL_StopSPIAuto(m_port, &status);
-  FRC_CheckErrorStatus(status, "Port {}", m_port);
+  FRC_CheckErrorStatus(status, "Port {}", static_cast<int>(m_port));
 }
 
 void SPI::ForceAutoRead() {
   int32_t status = 0;
   HAL_ForceSPIAutoRead(m_port, &status);
-  FRC_CheckErrorStatus(status, "Port {}", m_port);
+  FRC_CheckErrorStatus(status, "Port {}", static_cast<int>(m_port));
 }
 
 int SPI::ReadAutoReceivedData(uint32_t* buffer, int numToRead,
@@ -308,14 +308,14 @@
   int32_t status = 0;
   int32_t val = HAL_ReadSPIAutoReceivedData(m_port, buffer, numToRead,
                                             timeout.value(), &status);
-  FRC_CheckErrorStatus(status, "Port {}", m_port);
+  FRC_CheckErrorStatus(status, "Port {}", static_cast<int>(m_port));
   return val;
 }
 
 int SPI::GetAutoDroppedCount() {
   int32_t status = 0;
   int32_t val = HAL_GetSPIAutoDroppedCount(m_port, &status);
-  FRC_CheckErrorStatus(status, "Port {}", m_port);
+  FRC_CheckErrorStatus(status, "Port {}", static_cast<int>(m_port));
   return val;
 }
 
@@ -324,7 +324,7 @@
   int32_t status = 0;
   HAL_ConfigureSPIAutoStall(m_port, csToSclkTicks, stallTicks, pow2BytesPerRead,
                             &status);
-  FRC_CheckErrorStatus(status, "Port {}", m_port);
+  FRC_CheckErrorStatus(status, "Port {}", static_cast<int>(m_port));
 }
 
 void SPI::InitAccumulator(units::second_t period, int cmd, int xferSize,
@@ -355,13 +355,6 @@
   m_accum->m_notifier.StartPeriodic(period * kAccumulateDepth / 2);
 }
 
-void SPI::InitAccumulator(double period, int cmd, int xferSize, int validMask,
-                          int validValue, int dataShift, int dataSize,
-                          bool isSigned, bool bigEndian) {
-  InitAccumulator(units::second_t(period), cmd, xferSize, validMask, validValue,
-                  dataShift, dataSize, isSigned, bigEndian);
-}
-
 void SPI::FreeAccumulator() {
   m_accum.reset(nullptr);
   FreeAuto();
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/SerialPort.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/SerialPort.cpp
index fb984f1..698a440 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/SerialPort.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/SerialPort.cpp
@@ -20,15 +20,16 @@
 
   m_portHandle =
       HAL_InitializeSerialPort(static_cast<HAL_SerialPort>(port), &status);
-  FRC_CheckErrorStatus(status, "Port {}", port);
+  FRC_CheckErrorStatus(status, "Port {}", static_cast<int>(port));
   HAL_SetSerialBaudRate(m_portHandle, baudRate, &status);
   FRC_CheckErrorStatus(status, "SetSerialBaudRate {}", baudRate);
   HAL_SetSerialDataBits(m_portHandle, dataBits, &status);
   FRC_CheckErrorStatus(status, "SetSerialDataBits {}", dataBits);
   HAL_SetSerialParity(m_portHandle, parity, &status);
-  FRC_CheckErrorStatus(status, "SetSerialParity {}", parity);
+  FRC_CheckErrorStatus(status, "SetSerialParity {}", static_cast<int>(parity));
   HAL_SetSerialStopBits(m_portHandle, stopBits, &status);
-  FRC_CheckErrorStatus(status, "SetSerialStopBits {}", stopBits);
+  FRC_CheckErrorStatus(status, "SetSerialStopBits {}",
+                       static_cast<int>(stopBits));
 
   // Set the default timeout to 5 seconds.
   SetTimeout(5_s);
@@ -50,15 +51,16 @@
   m_portHandle =
       HAL_InitializeSerialPortDirect(static_cast<HAL_SerialPort>(port),
                                      std::string(portName).c_str(), &status);
-  FRC_CheckErrorStatus(status, "Port {}", port);
+  FRC_CheckErrorStatus(status, "Port {}", static_cast<int>(port));
   HAL_SetSerialBaudRate(m_portHandle, baudRate, &status);
   FRC_CheckErrorStatus(status, "SetSerialBaudRate {}", baudRate);
   HAL_SetSerialDataBits(m_portHandle, dataBits, &status);
   FRC_CheckErrorStatus(status, "SetSerialDataBits {}", dataBits);
   HAL_SetSerialParity(m_portHandle, parity, &status);
-  FRC_CheckErrorStatus(status, "SetSerialParity {}", parity);
+  FRC_CheckErrorStatus(status, "SetSerialParity {}", static_cast<int>(parity));
   HAL_SetSerialStopBits(m_portHandle, stopBits, &status);
-  FRC_CheckErrorStatus(status, "SetSerialStopBits {}", stopBits);
+  FRC_CheckErrorStatus(status, "SetSerialStopBits {}",
+                       static_cast<int>(stopBits));
 
   // Set the default timeout to 5 seconds.
   SetTimeout(5_s);
@@ -75,13 +77,14 @@
 SerialPort::~SerialPort() {
   int32_t status = 0;
   HAL_CloseSerial(m_portHandle, &status);
-  FRC_ReportError(status, "{}", "CloseSerial");
+  FRC_ReportError(status, "CloseSerial");
 }
 
 void SerialPort::SetFlowControl(SerialPort::FlowControl flowControl) {
   int32_t status = 0;
   HAL_SetSerialFlowControl(m_portHandle, flowControl, &status);
-  FRC_CheckErrorStatus(status, "SetFlowControl {}", flowControl);
+  FRC_CheckErrorStatus(status, "SetFlowControl {}",
+                       static_cast<int>(flowControl));
 }
 
 void SerialPort::EnableTermination(char terminator) {
@@ -93,20 +96,20 @@
 void SerialPort::DisableTermination() {
   int32_t status = 0;
   HAL_DisableSerialTermination(m_portHandle, &status);
-  FRC_CheckErrorStatus(status, "{}", "DisableTermination");
+  FRC_CheckErrorStatus(status, "DisableTermination");
 }
 
 int SerialPort::GetBytesReceived() {
   int32_t status = 0;
   int retVal = HAL_GetSerialBytesReceived(m_portHandle, &status);
-  FRC_CheckErrorStatus(status, "{}", "GetBytesReceived");
+  FRC_CheckErrorStatus(status, "GetBytesReceived");
   return retVal;
 }
 
 int SerialPort::Read(char* buffer, int count) {
   int32_t status = 0;
   int retVal = HAL_ReadSerial(m_portHandle, buffer, count, &status);
-  FRC_CheckErrorStatus(status, "{}", "Read");
+  FRC_CheckErrorStatus(status, "Read");
   return retVal;
 }
 
@@ -118,14 +121,14 @@
   int32_t status = 0;
   int retVal =
       HAL_WriteSerial(m_portHandle, buffer.data(), buffer.size(), &status);
-  FRC_CheckErrorStatus(status, "{}", "Write");
+  FRC_CheckErrorStatus(status, "Write");
   return retVal;
 }
 
 void SerialPort::SetTimeout(units::second_t timeout) {
   int32_t status = 0;
   HAL_SetSerialTimeout(m_portHandle, timeout.value(), &status);
-  FRC_CheckErrorStatus(status, "{}", "SetTimeout");
+  FRC_CheckErrorStatus(status, "SetTimeout");
 }
 
 void SerialPort::SetReadBufferSize(int size) {
@@ -143,17 +146,17 @@
 void SerialPort::SetWriteBufferMode(SerialPort::WriteBufferMode mode) {
   int32_t status = 0;
   HAL_SetSerialWriteMode(m_portHandle, mode, &status);
-  FRC_CheckErrorStatus(status, "SetWriteBufferMode {}", mode);
+  FRC_CheckErrorStatus(status, "SetWriteBufferMode {}", static_cast<int>(mode));
 }
 
 void SerialPort::Flush() {
   int32_t status = 0;
   HAL_FlushSerial(m_portHandle, &status);
-  FRC_CheckErrorStatus(status, "{}", "Flush");
+  FRC_CheckErrorStatus(status, "Flush");
 }
 
 void SerialPort::Reset() {
   int32_t status = 0;
   HAL_ClearSerial(m_portHandle, &status);
-  FRC_CheckErrorStatus(status, "{}", "Reset");
+  FRC_CheckErrorStatus(status, "Reset");
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/Servo.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/Servo.cpp
index c410bff..4a292b9 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/Servo.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/Servo.cpp
@@ -64,7 +64,8 @@
 void Servo::InitSendable(wpi::SendableBuilder& builder) {
   builder.SetSmartDashboardType("Servo");
   builder.AddDoubleProperty(
-      "Value", [=] { return Get(); }, [=](double value) { Set(value); });
+      "Value", [=, this] { return Get(); },
+      [=, this](double value) { Set(value); });
 }
 
 double Servo::GetServoAngleRange() const {
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/Solenoid.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/Solenoid.cpp
index 49000c2..819f79a 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/Solenoid.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/Solenoid.cpp
@@ -39,7 +39,9 @@
                channel} {}
 
 Solenoid::~Solenoid() {
-  m_module->UnreserveSolenoids(m_mask);
+  if (m_module) {
+    m_module->UnreserveSolenoids(m_mask);
+  }
 }
 
 void Solenoid::Set(bool on) {
@@ -75,7 +77,8 @@
 void Solenoid::InitSendable(wpi::SendableBuilder& builder) {
   builder.SetSmartDashboardType("Solenoid");
   builder.SetActuator(true);
-  builder.SetSafeState([=] { Set(false); });
+  builder.SetSafeState([=, this] { Set(false); });
   builder.AddBooleanProperty(
-      "Value", [=] { return Get(); }, [=](bool value) { Set(value); });
+      "Value", [=, this] { return Get(); },
+      [=, this](bool value) { Set(value); });
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/SpeedController.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/SpeedController.cpp
deleted file mode 100644
index e0b0cb2..0000000
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/SpeedController.cpp
+++ /dev/null
@@ -1,13 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/SpeedController.h"
-
-#include <frc/RobotController.h>
-
-using namespace frc;
-
-void SpeedController::SetVoltage(units::volt_t output) {
-  Set(output / units::volt_t(RobotController::GetInputVoltage()));
-}
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/SpeedControllerGroup.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/SpeedControllerGroup.cpp
deleted file mode 100644
index c3704df..0000000
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/SpeedControllerGroup.cpp
+++ /dev/null
@@ -1,69 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/SpeedControllerGroup.h"
-
-#include <wpi/sendable/SendableBuilder.h>
-#include <wpi/sendable/SendableRegistry.h>
-
-using namespace frc;
-
-// Can't use a delegated constructor here because of an MSVC bug.
-// https://developercommunity.visualstudio.com/content/problem/583/compiler-bug-with-delegating-a-constructor.html
-
-SpeedControllerGroup::SpeedControllerGroup(
-    std::vector<std::reference_wrapper<SpeedController>>&& speedControllers)
-    : m_speedControllers(std::move(speedControllers)) {
-  Initialize();
-}
-
-void SpeedControllerGroup::Initialize() {
-  for (auto& speedController : m_speedControllers) {
-    wpi::SendableRegistry::AddChild(this, &speedController.get());
-  }
-  static int instances = 0;
-  ++instances;
-  wpi::SendableRegistry::Add(this, "SpeedControllerGroup", instances);
-}
-
-void SpeedControllerGroup::Set(double speed) {
-  for (auto speedController : m_speedControllers) {
-    speedController.get().Set(m_isInverted ? -speed : speed);
-  }
-}
-
-double SpeedControllerGroup::Get() const {
-  if (!m_speedControllers.empty()) {
-    return m_speedControllers.front().get().Get() * (m_isInverted ? -1 : 1);
-  }
-  return 0.0;
-}
-
-void SpeedControllerGroup::SetInverted(bool isInverted) {
-  m_isInverted = isInverted;
-}
-
-bool SpeedControllerGroup::GetInverted() const {
-  return m_isInverted;
-}
-
-void SpeedControllerGroup::Disable() {
-  for (auto speedController : m_speedControllers) {
-    speedController.get().Disable();
-  }
-}
-
-void SpeedControllerGroup::StopMotor() {
-  for (auto speedController : m_speedControllers) {
-    speedController.get().StopMotor();
-  }
-}
-
-void SpeedControllerGroup::InitSendable(wpi::SendableBuilder& builder) {
-  builder.SetSmartDashboardType("Speed Controller");
-  builder.SetActuator(true);
-  builder.SetSafeState([=] { StopMotor(); });
-  builder.AddDoubleProperty(
-      "Value", [=] { return Get(); }, [=](double value) { Set(value); });
-}
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/SynchronousInterrupt.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/SynchronousInterrupt.cpp
index 49acd84..a6ab212 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/SynchronousInterrupt.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/SynchronousInterrupt.cpp
@@ -21,7 +21,7 @@
 SynchronousInterrupt::SynchronousInterrupt(DigitalSource* source)
     : m_source{source, wpi::NullDeleter<DigitalSource>()} {
   if (m_source == nullptr) {
-    FRC_CheckErrorStatus(frc::err::NullParameter, "{}", "Source is null");
+    FRC_CheckErrorStatus(frc::err::NullParameter, "Source is null");
   } else {
     InitSynchronousInterrupt();
   }
@@ -30,7 +30,7 @@
     std::shared_ptr<DigitalSource> source)
     : m_source{std::move(source)} {
   if (m_source == nullptr) {
-    FRC_CheckErrorStatus(frc::err::NullParameter, "{}", "Source is null");
+    FRC_CheckErrorStatus(frc::err::NullParameter, "Source is null");
   } else {
     InitSynchronousInterrupt();
   }
@@ -39,14 +39,14 @@
 void SynchronousInterrupt::InitSynchronousInterrupt() {
   int32_t status = 0;
   m_handle = HAL_InitializeInterrupts(&status);
-  FRC_CheckErrorStatus(status, "{}", "Interrupt failed to initialize");
+  FRC_CheckErrorStatus(status, "Interrupt failed to initialize");
   HAL_RequestInterrupts(m_handle, m_source->GetPortHandleForRouting(),
                         static_cast<HAL_AnalogTriggerType>(
                             m_source->GetAnalogTriggerTypeForRouting()),
                         &status);
-  FRC_CheckErrorStatus(status, "{}", "Interrupt request failed");
+  FRC_CheckErrorStatus(status, "Interrupt request failed");
   HAL_SetInterruptUpSourceEdge(m_handle, true, false, &status);
-  FRC_CheckErrorStatus(status, "{}", "Interrupt setting up source edge failed");
+  FRC_CheckErrorStatus(status, "Interrupt setting up source edge failed");
 }
 
 SynchronousInterrupt::~SynchronousInterrupt() {
@@ -79,19 +79,19 @@
                                              bool fallingEdge) {
   int32_t status = 0;
   HAL_SetInterruptUpSourceEdge(m_handle, risingEdge, fallingEdge, &status);
-  FRC_CheckErrorStatus(status, "{}", "Interrupt setting edges failed");
+  FRC_CheckErrorStatus(status, "Interrupt setting edges failed");
 }
 
 void SynchronousInterrupt::WakeupWaitingInterrupt() {
   int32_t status = 0;
   HAL_ReleaseWaitingInterrupt(m_handle, &status);
-  FRC_CheckErrorStatus(status, "{}", "Interrupt wakeup failed");
+  FRC_CheckErrorStatus(status, "Interrupt wakeup failed");
 }
 
 units::second_t SynchronousInterrupt::GetRisingTimestamp() {
   int32_t status = 0;
   auto ts = HAL_ReadInterruptRisingTimestamp(m_handle, &status);
-  FRC_CheckErrorStatus(status, "{}", "Interrupt rising timestamp failed");
+  FRC_CheckErrorStatus(status, "Interrupt rising timestamp failed");
   units::microsecond_t ms{static_cast<double>(ts)};
   return ms;
 }
@@ -99,7 +99,7 @@
 units::second_t SynchronousInterrupt::GetFallingTimestamp() {
   int32_t status = 0;
   auto ts = HAL_ReadInterruptFallingTimestamp(m_handle, &status);
-  FRC_CheckErrorStatus(status, "{}", "Interrupt falling timestamp failed");
+  FRC_CheckErrorStatus(status, "Interrupt falling timestamp failed");
   units::microsecond_t ms{static_cast<double>(ts)};
   return ms;
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/Threads.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/Threads.cpp
index 2b9c151..3ecab55 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/Threads.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/Threads.cpp
@@ -16,7 +16,7 @@
   HAL_Bool rt = false;
   auto native = thread.native_handle();
   auto ret = HAL_GetThreadPriority(&native, &rt, &status);
-  FRC_CheckErrorStatus(status, "{}", "GetThreadPriority");
+  FRC_CheckErrorStatus(status, "GetThreadPriority");
   *isRealTime = rt;
   return ret;
 }
@@ -25,7 +25,7 @@
   int32_t status = 0;
   HAL_Bool rt = false;
   auto ret = HAL_GetCurrentThreadPriority(&rt, &status);
-  FRC_CheckErrorStatus(status, "{}", "GetCurrentThreadPriority");
+  FRC_CheckErrorStatus(status, "GetCurrentThreadPriority");
   *isRealTime = rt;
   return ret;
 }
@@ -34,14 +34,14 @@
   int32_t status = 0;
   auto native = thread.native_handle();
   auto ret = HAL_SetThreadPriority(&native, realTime, priority, &status);
-  FRC_CheckErrorStatus(status, "{}", "SetThreadPriority");
+  FRC_CheckErrorStatus(status, "SetThreadPriority");
   return ret;
 }
 
 bool SetCurrentThreadPriority(bool realTime, int priority) {
   int32_t status = 0;
   auto ret = HAL_SetCurrentThreadPriority(realTime, priority, &status);
-  FRC_CheckErrorStatus(status, "{}", "SetCurrentThreadPriority");
+  FRC_CheckErrorStatus(status, "SetCurrentThreadPriority");
   return ret;
 }
 
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/TimedRobot.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/TimedRobot.cpp
index 93e6698..0b7b9cb 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/TimedRobot.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/TimedRobot.cpp
@@ -40,7 +40,7 @@
     HAL_UpdateNotifierAlarm(
         m_notifier, static_cast<uint64_t>(callback.expirationTime * 1e6),
         &status);
-    FRC_CheckErrorStatus(status, "{}", "UpdateNotifierAlarm");
+    FRC_CheckErrorStatus(status, "UpdateNotifierAlarm");
 
     uint64_t curTime = HAL_WaitForNotifierAlarm(m_notifier, &status);
     if (curTime == 0 || status != 0) {
@@ -70,15 +70,13 @@
   HAL_StopNotifier(m_notifier, &status);
 }
 
-TimedRobot::TimedRobot(double period) : TimedRobot(units::second_t(period)) {}
-
 TimedRobot::TimedRobot(units::second_t period) : IterativeRobotBase(period) {
   m_startTime = Timer::GetFPGATimestamp();
-  AddPeriodic([=] { LoopFunc(); }, period);
+  AddPeriodic([=, this] { LoopFunc(); }, period);
 
   int32_t status = 0;
   m_notifier = HAL_InitializeNotifier(&status);
-  FRC_CheckErrorStatus(status, "{}", "InitializeNotifier");
+  FRC_CheckErrorStatus(status, "InitializeNotifier");
   HAL_SetNotifierName(m_notifier, "TimedRobot", &status);
 
   HAL_Report(HALUsageReporting::kResourceType_Framework,
@@ -89,7 +87,7 @@
   int32_t status = 0;
 
   HAL_StopNotifier(m_notifier, &status);
-  FRC_ReportError(status, "{}", "StopNotifier");
+  FRC_ReportError(status, "StopNotifier");
 
   HAL_CleanNotifier(m_notifier, &status);
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/Timer.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/Timer.cpp
index bbd2262..3863de4 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/Timer.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/Timer.cpp
@@ -21,9 +21,9 @@
   using std::chrono::duration_cast;
   using std::chrono::system_clock;
 
-  return units::second_t(
+  return units::second_t{
       duration_cast<duration<double>>(system_clock::now().time_since_epoch())
-          .count());
+          .count()};
 }
 
 }  // namespace frc
@@ -65,10 +65,6 @@
   return Get() >= period;
 }
 
-bool Timer::HasPeriodPassed(units::second_t period) {
-  return AdvanceIfElapsed(period);
-}
-
 bool Timer::AdvanceIfElapsed(units::second_t period) {
   if (Get() >= period) {
     // Advance the start time by the period.
@@ -82,9 +78,9 @@
 
 units::second_t Timer::GetFPGATimestamp() {
   // FPGA returns the timestamp in microseconds
-  return units::second_t(frc::RobotController::GetFPGATime() * 1.0e-6);
+  return units::second_t{frc::RobotController::GetFPGATime() * 1.0e-6};
 }
 
 units::second_t Timer::GetMatchTime() {
-  return units::second_t(frc::DriverStation::GetMatchTime());
+  return units::second_t{frc::DriverStation::GetMatchTime()};
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/Ultrasonic.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/Ultrasonic.cpp
index 02035dd..a034fc3 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/Ultrasonic.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/Ultrasonic.cpp
@@ -39,10 +39,10 @@
       m_echoChannel(echoChannel, wpi::NullDeleter<DigitalInput>()),
       m_counter(m_echoChannel) {
   if (!pingChannel) {
-    throw FRC_MakeError(err::NullParameter, "{}", "pingChannel");
+    throw FRC_MakeError(err::NullParameter, "pingChannel");
   }
   if (!echoChannel) {
-    throw FRC_MakeError(err::NullParameter, "{}", "echoChannel");
+    throw FRC_MakeError(err::NullParameter, "echoChannel");
   }
   Initialize();
 }
@@ -86,7 +86,7 @@
 
 void Ultrasonic::Ping() {
   if (m_automaticEnabled) {
-    throw FRC_MakeError(err::IncompatibleMode, "{}",
+    throw FRC_MakeError(err::IncompatibleMode,
                         "cannot call Ping() in automatic mode");
   }
 
@@ -120,11 +120,6 @@
     }
 
     m_thread = std::thread(&Ultrasonic::UltrasonicChecker);
-
-    // TODO: Currently, lvuser does not have permissions to set task priorities.
-    // Until that is the case, uncommenting this will break user code that calls
-    // Ultrasonic::SetAutomicMode().
-    // m_task.SetPriority(kPriority);
   } else {
     // Wait for background task to stop running
     if (m_thread.joinable()) {
@@ -162,7 +157,8 @@
 void Ultrasonic::InitSendable(wpi::SendableBuilder& builder) {
   builder.SetSmartDashboardType("Ultrasonic");
   builder.AddDoubleProperty(
-      "Value", [=] { return units::inch_t{GetRange()}.value(); }, nullptr);
+      "Value", [=, this] { return units::inch_t{GetRange()}.value(); },
+      nullptr);
 }
 
 void Ultrasonic::Initialize() {
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/Watchdog.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/Watchdog.cpp
index 854f9e9..37e2536 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/Watchdog.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/Watchdog.cpp
@@ -47,10 +47,10 @@
 Watchdog::Impl::Impl() {
   int32_t status = 0;
   m_notifier = HAL_InitializeNotifier(&status);
-  FRC_CheckErrorStatus(status, "{}", "starting watchdog notifier");
+  FRC_CheckErrorStatus(status, "starting watchdog notifier");
   HAL_SetNotifierName(m_notifier, "Watchdog", &status);
 
-  m_thread = std::thread([=] { Main(); });
+  m_thread = std::thread([=, this] { Main(); });
 }
 
 Watchdog::Impl::~Impl() {
@@ -58,7 +58,7 @@
   // atomically set handle to 0, then clean
   HAL_NotifierHandle handle = m_notifier.exchange(0);
   HAL_StopNotifier(handle, &status);
-  FRC_ReportError(status, "{}", "stopping watchdog notifier");
+  FRC_ReportError(status, "stopping watchdog notifier");
 
   // Join the thread to ensure the handler has exited.
   if (m_thread.joinable()) {
@@ -84,7 +84,7 @@
                               1e6),
         &status);
   }
-  FRC_CheckErrorStatus(status, "{}", "updating watchdog notifier alarm");
+  FRC_CheckErrorStatus(status, "updating watchdog notifier alarm");
 }
 
 void Watchdog::Impl::Main() {
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/XboxController.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/XboxController.cpp
index a08225b..f10419f 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/XboxController.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/XboxController.cpp
@@ -6,6 +6,8 @@
 
 #include <hal/FRCUsageReporting.h>
 
+#include "frc/event/BooleanEvent.h"
+
 using namespace frc;
 
 XboxController::XboxController(int port) : GenericHID(port) {
@@ -60,6 +62,14 @@
   return GetRawButtonReleased(Button::kRightBumper);
 }
 
+BooleanEvent XboxController::LeftBumper(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetLeftBumper(); });
+}
+
+BooleanEvent XboxController::RightBumper(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetRightBumper(); });
+}
+
 bool XboxController::GetLeftStickButton() const {
   return GetRawButton(Button::kLeftStick);
 }
@@ -84,6 +94,14 @@
   return GetRawButtonReleased(Button::kRightStick);
 }
 
+BooleanEvent XboxController::LeftStick(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetLeftStickButton(); });
+}
+
+BooleanEvent XboxController::RightStick(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetRightStickButton(); });
+}
+
 bool XboxController::GetAButton() const {
   return GetRawButton(Button::kA);
 }
@@ -96,6 +114,10 @@
   return GetRawButtonReleased(Button::kA);
 }
 
+BooleanEvent XboxController::A(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetAButton(); });
+}
+
 bool XboxController::GetBButton() const {
   return GetRawButton(Button::kB);
 }
@@ -108,6 +130,10 @@
   return GetRawButtonReleased(Button::kB);
 }
 
+BooleanEvent XboxController::B(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetBButton(); });
+}
+
 bool XboxController::GetXButton() const {
   return GetRawButton(Button::kX);
 }
@@ -120,6 +146,10 @@
   return GetRawButtonReleased(Button::kX);
 }
 
+BooleanEvent XboxController::X(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetXButton(); });
+}
+
 bool XboxController::GetYButton() const {
   return GetRawButton(Button::kY);
 }
@@ -132,6 +162,10 @@
   return GetRawButtonReleased(Button::kY);
 }
 
+BooleanEvent XboxController::Y(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetYButton(); });
+}
+
 bool XboxController::GetBackButton() const {
   return GetRawButton(Button::kBack);
 }
@@ -144,6 +178,10 @@
   return GetRawButtonReleased(Button::kBack);
 }
 
+BooleanEvent XboxController::Back(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetBackButton(); });
+}
+
 bool XboxController::GetStartButton() const {
   return GetRawButton(Button::kStart);
 }
@@ -155,3 +193,29 @@
 bool XboxController::GetStartButtonReleased() {
   return GetRawButtonReleased(Button::kStart);
 }
+
+BooleanEvent XboxController::Start(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetStartButton(); });
+}
+
+BooleanEvent XboxController::LeftTrigger(double threshold,
+                                         EventLoop* loop) const {
+  return BooleanEvent(loop, [this, threshold]() {
+    return this->GetLeftTriggerAxis() > threshold;
+  });
+}
+
+BooleanEvent XboxController::LeftTrigger(EventLoop* loop) const {
+  return this->LeftTrigger(0.5, loop);
+}
+
+BooleanEvent XboxController::RightTrigger(double threshold,
+                                          EventLoop* loop) const {
+  return BooleanEvent(loop, [this, threshold]() {
+    return this->GetRightTriggerAxis() > threshold;
+  });
+}
+
+BooleanEvent XboxController::RightTrigger(EventLoop* loop) const {
+  return this->RightTrigger(0.5, loop);
+}
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/counter/ExternalDirectionCounter.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/counter/ExternalDirectionCounter.cpp
index 8c7bb58..24709aa 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/counter/ExternalDirectionCounter.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/counter/ExternalDirectionCounter.cpp
@@ -24,10 +24,10 @@
     std::shared_ptr<DigitalSource> countSource,
     std::shared_ptr<DigitalSource> directionSource) {
   if (countSource == nullptr) {
-    throw FRC_MakeError(err::NullParameter, "{}", "countSource");
+    throw FRC_MakeError(err::NullParameter, "countSource");
   }
   if (directionSource == nullptr) {
-    throw FRC_MakeError(err::NullParameter, "{}", "directionSource");
+    throw FRC_MakeError(err::NullParameter, "directionSource");
   }
 
   m_countSource = countSource;
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/counter/Tachometer.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/counter/Tachometer.cpp
index a52bea5..90324f5 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/counter/Tachometer.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/counter/Tachometer.cpp
@@ -19,7 +19,7 @@
     : Tachometer({&source, wpi::NullDeleter<DigitalSource>()}) {}
 Tachometer::Tachometer(std::shared_ptr<DigitalSource> source) {
   if (source == nullptr) {
-    throw FRC_MakeError(err::NullParameter, "{}", "source");
+    throw FRC_MakeError(err::NullParameter, "source");
   }
 
   m_source = source;
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp
index eed9495..8cce62e 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp
@@ -12,20 +12,12 @@
 #include <wpi/sendable/SendableRegistry.h>
 
 #include "frc/MathUtil.h"
-#include "frc/SpeedController.h"
+#include "frc/motorcontrol/MotorController.h"
 
 using namespace frc;
 
-#if defined(_MSC_VER)
-#pragma warning(disable : 4996)  // was declared deprecated
-#elif defined(__clang__)
-#pragma clang diagnostic ignored "-Wdeprecated-declarations"
-#elif defined(__GNUC__)
-#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
-#endif
-
-DifferentialDrive::DifferentialDrive(SpeedController& leftMotor,
-                                     SpeedController& rightMotor)
+DifferentialDrive::DifferentialDrive(MotorController& leftMotor,
+                                     MotorController& rightMotor)
     : m_leftMotor(&leftMotor), m_rightMotor(&rightMotor) {
   wpi::SendableRegistry::AddChild(this, m_leftMotor);
   wpi::SendableRegistry::AddChild(this, m_rightMotor);
@@ -106,39 +98,19 @@
     zRotation = std::copysign(zRotation * zRotation, zRotation);
   }
 
-  double leftSpeed;
-  double rightSpeed;
+  double leftSpeed = xSpeed - zRotation;
+  double rightSpeed = xSpeed + zRotation;
 
-  double maxInput =
-      std::copysign(std::max(std::abs(xSpeed), std::abs(zRotation)), xSpeed);
-
-  // Sign is used because `xSpeed >= 0.0` succeeds for -0.0
-  if (!std::signbit(xSpeed)) {
-    // First quadrant, else second quadrant
-    if (!std::signbit(zRotation)) {
-      leftSpeed = maxInput;
-      rightSpeed = xSpeed - zRotation;
-    } else {
-      leftSpeed = xSpeed + zRotation;
-      rightSpeed = maxInput;
-    }
-  } else {
-    // Third quadrant, else fourth quadrant
-    if (!std::signbit(zRotation)) {
-      leftSpeed = xSpeed + zRotation;
-      rightSpeed = maxInput;
-    } else {
-      leftSpeed = maxInput;
-      rightSpeed = xSpeed - zRotation;
-    }
+  // Find the maximum possible value of (throttle + turn) along the vector that
+  // the joystick is pointing, then desaturate the wheel speeds
+  double greaterInput = (std::max)(std::abs(xSpeed), std::abs(zRotation));
+  double lesserInput = (std::min)(std::abs(xSpeed), std::abs(zRotation));
+  if (greaterInput == 0.0) {
+    return {0.0, 0.0};
   }
-
-  // Normalize the wheel speeds
-  double maxMagnitude = std::max(std::abs(leftSpeed), std::abs(rightSpeed));
-  if (maxMagnitude > 1.0) {
-    leftSpeed /= maxMagnitude;
-    rightSpeed /= maxMagnitude;
-  }
+  double saturatedInput = (greaterInput + lesserInput) / greaterInput;
+  leftSpeed /= saturatedInput;
+  rightSpeed /= saturatedInput;
 
   return {leftSpeed, rightSpeed};
 }
@@ -152,14 +124,14 @@
   double rightSpeed = 0.0;
 
   if (allowTurnInPlace) {
-    leftSpeed = xSpeed + zRotation;
-    rightSpeed = xSpeed - zRotation;
+    leftSpeed = xSpeed - zRotation;
+    rightSpeed = xSpeed + zRotation;
   } else {
-    leftSpeed = xSpeed + std::abs(xSpeed) * zRotation;
-    rightSpeed = xSpeed - std::abs(xSpeed) * zRotation;
+    leftSpeed = xSpeed - std::abs(xSpeed) * zRotation;
+    rightSpeed = xSpeed + std::abs(xSpeed) * zRotation;
   }
 
-  // Normalize wheel speeds
+  // Desaturate wheel speeds
   double maxMagnitude = std::max(std::abs(leftSpeed), std::abs(rightSpeed));
   if (maxMagnitude > 1.0) {
     leftSpeed /= maxMagnitude;
@@ -197,11 +169,11 @@
 void DifferentialDrive::InitSendable(wpi::SendableBuilder& builder) {
   builder.SetSmartDashboardType("DifferentialDrive");
   builder.SetActuator(true);
-  builder.SetSafeState([=] { StopMotor(); });
+  builder.SetSafeState([=, this] { StopMotor(); });
   builder.AddDoubleProperty(
-      "Left Motor Speed", [=] { return m_leftMotor->Get(); },
-      [=](double value) { m_leftMotor->Set(value); });
+      "Left Motor Speed", [=, this] { return m_leftMotor->Get(); },
+      [=, this](double value) { m_leftMotor->Set(value); });
   builder.AddDoubleProperty(
-      "Right Motor Speed", [=] { return m_rightMotor->Get(); },
-      [=](double value) { m_rightMotor->Set(value); });
+      "Right Motor Speed", [=, this] { return m_rightMotor->Get(); },
+      [=, this](double value) { m_rightMotor->Set(value); });
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/drive/KilloughDrive.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/drive/KilloughDrive.cpp
deleted file mode 100644
index 268ae64..0000000
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/drive/KilloughDrive.cpp
+++ /dev/null
@@ -1,134 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/drive/KilloughDrive.h"
-
-#include <algorithm>
-#include <cmath>
-
-#include <hal/FRCUsageReporting.h>
-#include <wpi/numbers>
-#include <wpi/sendable/SendableBuilder.h>
-#include <wpi/sendable/SendableRegistry.h>
-
-#include "frc/MathUtil.h"
-#include "frc/SpeedController.h"
-
-using namespace frc;
-
-#if defined(_MSC_VER)
-#pragma warning(disable : 4996)  // was declared deprecated
-#elif defined(__clang__)
-#pragma clang diagnostic ignored "-Wdeprecated-declarations"
-#elif defined(__GNUC__)
-#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
-#endif
-
-KilloughDrive::KilloughDrive(SpeedController& leftMotor,
-                             SpeedController& rightMotor,
-                             SpeedController& backMotor)
-    : KilloughDrive(leftMotor, rightMotor, backMotor, kDefaultLeftMotorAngle,
-                    kDefaultRightMotorAngle, kDefaultBackMotorAngle) {}
-
-KilloughDrive::KilloughDrive(SpeedController& leftMotor,
-                             SpeedController& rightMotor,
-                             SpeedController& backMotor, double leftMotorAngle,
-                             double rightMotorAngle, double backMotorAngle)
-    : m_leftMotor(&leftMotor),
-      m_rightMotor(&rightMotor),
-      m_backMotor(&backMotor) {
-  m_leftVec = {std::cos(leftMotorAngle * (wpi::numbers::pi / 180.0)),
-               std::sin(leftMotorAngle * (wpi::numbers::pi / 180.0))};
-  m_rightVec = {std::cos(rightMotorAngle * (wpi::numbers::pi / 180.0)),
-                std::sin(rightMotorAngle * (wpi::numbers::pi / 180.0))};
-  m_backVec = {std::cos(backMotorAngle * (wpi::numbers::pi / 180.0)),
-               std::sin(backMotorAngle * (wpi::numbers::pi / 180.0))};
-  wpi::SendableRegistry::AddChild(this, m_leftMotor);
-  wpi::SendableRegistry::AddChild(this, m_rightMotor);
-  wpi::SendableRegistry::AddChild(this, m_backMotor);
-  static int instances = 0;
-  ++instances;
-  wpi::SendableRegistry::AddLW(this, "KilloughDrive", instances);
-}
-
-void KilloughDrive::DriveCartesian(double ySpeed, double xSpeed,
-                                   double zRotation, double gyroAngle) {
-  if (!reported) {
-    HAL_Report(HALUsageReporting::kResourceType_RobotDrive,
-               HALUsageReporting::kRobotDrive2_KilloughCartesian, 3);
-    reported = true;
-  }
-
-  ySpeed = ApplyDeadband(ySpeed, m_deadband);
-  xSpeed = ApplyDeadband(xSpeed, m_deadband);
-
-  auto [left, right, back] =
-      DriveCartesianIK(ySpeed, xSpeed, zRotation, gyroAngle);
-
-  m_leftMotor->Set(left * m_maxOutput);
-  m_rightMotor->Set(right * m_maxOutput);
-  m_backMotor->Set(back * m_maxOutput);
-
-  Feed();
-}
-
-void KilloughDrive::DrivePolar(double magnitude, double angle,
-                               double zRotation) {
-  if (!reported) {
-    HAL_Report(HALUsageReporting::kResourceType_RobotDrive,
-               HALUsageReporting::kRobotDrive2_KilloughPolar, 3);
-    reported = true;
-  }
-
-  DriveCartesian(magnitude * std::sin(angle * (wpi::numbers::pi / 180.0)),
-                 magnitude * std::cos(angle * (wpi::numbers::pi / 180.0)),
-                 zRotation, 0.0);
-}
-
-KilloughDrive::WheelSpeeds KilloughDrive::DriveCartesianIK(double ySpeed,
-                                                           double xSpeed,
-                                                           double zRotation,
-                                                           double gyroAngle) {
-  ySpeed = std::clamp(ySpeed, -1.0, 1.0);
-  xSpeed = std::clamp(xSpeed, -1.0, 1.0);
-
-  // Compensate for gyro angle.
-  Vector2d input{ySpeed, xSpeed};
-  input.Rotate(-gyroAngle);
-
-  double wheelSpeeds[3];
-  wheelSpeeds[kLeft] = input.ScalarProject(m_leftVec) + zRotation;
-  wheelSpeeds[kRight] = input.ScalarProject(m_rightVec) + zRotation;
-  wheelSpeeds[kBack] = input.ScalarProject(m_backVec) + zRotation;
-
-  Desaturate(wheelSpeeds);
-
-  return {wheelSpeeds[kLeft], wheelSpeeds[kRight], wheelSpeeds[kBack]};
-}
-
-void KilloughDrive::StopMotor() {
-  m_leftMotor->StopMotor();
-  m_rightMotor->StopMotor();
-  m_backMotor->StopMotor();
-  Feed();
-}
-
-std::string KilloughDrive::GetDescription() const {
-  return "KilloughDrive";
-}
-
-void KilloughDrive::InitSendable(wpi::SendableBuilder& builder) {
-  builder.SetSmartDashboardType("KilloughDrive");
-  builder.SetActuator(true);
-  builder.SetSafeState([=] { StopMotor(); });
-  builder.AddDoubleProperty(
-      "Left Motor Speed", [=] { return m_leftMotor->Get(); },
-      [=](double value) { m_leftMotor->Set(value); });
-  builder.AddDoubleProperty(
-      "Right Motor Speed", [=] { return m_rightMotor->Get(); },
-      [=](double value) { m_rightMotor->Set(value); });
-  builder.AddDoubleProperty(
-      "Back Motor Speed", [=] { return m_backMotor->Get(); },
-      [=](double value) { m_backMotor->Set(value); });
-}
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp
index 70e90d4..2bf6a3f 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp
@@ -5,31 +5,21 @@
 #include "frc/drive/MecanumDrive.h"
 
 #include <algorithm>
-#include <cmath>
 
 #include <hal/FRCUsageReporting.h>
-#include <wpi/numbers>
 #include <wpi/sendable/SendableBuilder.h>
 #include <wpi/sendable/SendableRegistry.h>
 
 #include "frc/MathUtil.h"
-#include "frc/SpeedController.h"
-#include "frc/drive/Vector2d.h"
+#include "frc/geometry/Translation2d.h"
+#include "frc/motorcontrol/MotorController.h"
 
 using namespace frc;
 
-#if defined(_MSC_VER)
-#pragma warning(disable : 4996)  // was declared deprecated
-#elif defined(__clang__)
-#pragma clang diagnostic ignored "-Wdeprecated-declarations"
-#elif defined(__GNUC__)
-#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
-#endif
-
-MecanumDrive::MecanumDrive(SpeedController& frontLeftMotor,
-                           SpeedController& rearLeftMotor,
-                           SpeedController& frontRightMotor,
-                           SpeedController& rearRightMotor)
+MecanumDrive::MecanumDrive(MotorController& frontLeftMotor,
+                           MotorController& rearLeftMotor,
+                           MotorController& frontRightMotor,
+                           MotorController& rearRightMotor)
     : m_frontLeftMotor(&frontLeftMotor),
       m_rearLeftMotor(&rearLeftMotor),
       m_frontRightMotor(&frontRightMotor),
@@ -43,19 +33,19 @@
   wpi::SendableRegistry::AddLW(this, "MecanumDrive", instances);
 }
 
-void MecanumDrive::DriveCartesian(double ySpeed, double xSpeed,
-                                  double zRotation, double gyroAngle) {
+void MecanumDrive::DriveCartesian(double xSpeed, double ySpeed,
+                                  double zRotation, Rotation2d gyroAngle) {
   if (!reported) {
     HAL_Report(HALUsageReporting::kResourceType_RobotDrive,
                HALUsageReporting::kRobotDrive2_MecanumCartesian, 4);
     reported = true;
   }
 
-  ySpeed = ApplyDeadband(ySpeed, m_deadband);
   xSpeed = ApplyDeadband(xSpeed, m_deadband);
+  ySpeed = ApplyDeadband(ySpeed, m_deadband);
 
   auto [frontLeft, frontRight, rearLeft, rearRight] =
-      DriveCartesianIK(ySpeed, xSpeed, zRotation, gyroAngle);
+      DriveCartesianIK(xSpeed, ySpeed, zRotation, gyroAngle);
 
   m_frontLeftMotor->Set(frontLeft * m_maxOutput);
   m_frontRightMotor->Set(frontRight * m_maxOutput);
@@ -65,7 +55,7 @@
   Feed();
 }
 
-void MecanumDrive::DrivePolar(double magnitude, double angle,
+void MecanumDrive::DrivePolar(double magnitude, Rotation2d angle,
                               double zRotation) {
   if (!reported) {
     HAL_Report(HALUsageReporting::kResourceType_RobotDrive,
@@ -73,9 +63,8 @@
     reported = true;
   }
 
-  DriveCartesian(magnitude * std::cos(angle * (wpi::numbers::pi / 180.0)),
-                 magnitude * std::sin(angle * (wpi::numbers::pi / 180.0)),
-                 zRotation, 0.0);
+  DriveCartesian(magnitude * angle.Cos(), magnitude * angle.Sin(), zRotation,
+                 0_rad);
 }
 
 void MecanumDrive::StopMotor() {
@@ -86,22 +75,23 @@
   Feed();
 }
 
-MecanumDrive::WheelSpeeds MecanumDrive::DriveCartesianIK(double ySpeed,
-                                                         double xSpeed,
+MecanumDrive::WheelSpeeds MecanumDrive::DriveCartesianIK(double xSpeed,
+                                                         double ySpeed,
                                                          double zRotation,
-                                                         double gyroAngle) {
-  ySpeed = std::clamp(ySpeed, -1.0, 1.0);
+                                                         Rotation2d gyroAngle) {
   xSpeed = std::clamp(xSpeed, -1.0, 1.0);
+  ySpeed = std::clamp(ySpeed, -1.0, 1.0);
 
   // Compensate for gyro angle.
-  Vector2d input{ySpeed, xSpeed};
-  input.Rotate(-gyroAngle);
+  auto input =
+      Translation2d{units::meter_t{xSpeed}, units::meter_t{ySpeed}}.RotateBy(
+          -gyroAngle);
 
   double wheelSpeeds[4];
-  wheelSpeeds[kFrontLeft] = input.x + input.y + zRotation;
-  wheelSpeeds[kFrontRight] = input.x - input.y - zRotation;
-  wheelSpeeds[kRearLeft] = input.x - input.y + zRotation;
-  wheelSpeeds[kRearRight] = input.x + input.y - zRotation;
+  wheelSpeeds[kFrontLeft] = input.X().value() + input.Y().value() + zRotation;
+  wheelSpeeds[kFrontRight] = input.X().value() - input.Y().value() - zRotation;
+  wheelSpeeds[kRearLeft] = input.X().value() - input.Y().value() + zRotation;
+  wheelSpeeds[kRearRight] = input.X().value() + input.Y().value() - zRotation;
 
   Desaturate(wheelSpeeds);
 
@@ -116,17 +106,17 @@
 void MecanumDrive::InitSendable(wpi::SendableBuilder& builder) {
   builder.SetSmartDashboardType("MecanumDrive");
   builder.SetActuator(true);
-  builder.SetSafeState([=] { StopMotor(); });
+  builder.SetSafeState([=, this] { StopMotor(); });
   builder.AddDoubleProperty(
-      "Front Left Motor Speed", [=] { return m_frontLeftMotor->Get(); },
-      [=](double value) { m_frontLeftMotor->Set(value); });
+      "Front Left Motor Speed", [=, this] { return m_frontLeftMotor->Get(); },
+      [=, this](double value) { m_frontLeftMotor->Set(value); });
   builder.AddDoubleProperty(
-      "Front Right Motor Speed", [=] { return m_frontRightMotor->Get(); },
-      [=](double value) { m_frontRightMotor->Set(value); });
+      "Front Right Motor Speed", [=, this] { return m_frontRightMotor->Get(); },
+      [=, this](double value) { m_frontRightMotor->Set(value); });
   builder.AddDoubleProperty(
-      "Rear Left Motor Speed", [=] { return m_rearLeftMotor->Get(); },
-      [=](double value) { m_rearLeftMotor->Set(value); });
+      "Rear Left Motor Speed", [=, this] { return m_rearLeftMotor->Get(); },
+      [=, this](double value) { m_rearLeftMotor->Set(value); });
   builder.AddDoubleProperty(
-      "Rear Right Motor Speed", [=] { return m_rearRightMotor->Get(); },
-      [=](double value) { m_rearRightMotor->Set(value); });
+      "Rear Right Motor Speed", [=, this] { return m_rearRightMotor->Get(); },
+      [=, this](double value) { m_rearRightMotor->Set(value); });
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/drive/RobotDriveBase.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/drive/RobotDriveBase.cpp
index 97ea0ee..fbd0c6e 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/drive/RobotDriveBase.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/drive/RobotDriveBase.cpp
@@ -10,7 +10,6 @@
 
 #include <hal/FRCUsageReporting.h>
 
-#include "frc/MathUtil.h"
 #include "frc/motorcontrol/MotorController.h"
 
 using namespace frc;
@@ -31,11 +30,7 @@
   Feed();
 }
 
-double RobotDriveBase::ApplyDeadband(double value, double deadband) {
-  return frc::ApplyDeadband(value, deadband);
-}
-
-void RobotDriveBase::Desaturate(wpi::span<double> wheelSpeeds) {
+void RobotDriveBase::Desaturate(std::span<double> wheelSpeeds) {
   double maxMagnitude = std::abs(wheelSpeeds[0]);
   for (size_t i = 1; i < wheelSpeeds.size(); i++) {
     double temp = std::abs(wheelSpeeds[i]);
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/drive/Vector2d.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/drive/Vector2d.cpp
deleted file mode 100644
index a342dc2..0000000
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/drive/Vector2d.cpp
+++ /dev/null
@@ -1,38 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/drive/Vector2d.h"
-
-#include <cmath>
-
-#include <wpi/numbers>
-
-using namespace frc;
-
-Vector2d::Vector2d(double x, double y) {
-  this->x = x;
-  this->y = y;
-}
-
-void Vector2d::Rotate(double angle) {
-  double cosA = std::cos(angle * (wpi::numbers::pi / 180.0));
-  double sinA = std::sin(angle * (wpi::numbers::pi / 180.0));
-  double out[2];
-  out[0] = x * cosA - y * sinA;
-  out[1] = x * sinA + y * cosA;
-  x = out[0];
-  y = out[1];
-}
-
-double Vector2d::Dot(const Vector2d& vec) const {
-  return x * vec.x + y * vec.y;
-}
-
-double Vector2d::Magnitude() const {
-  return std::sqrt(x * x + y * y);
-}
-
-double Vector2d::ScalarProject(const Vector2d& vec) const {
-  return Dot(vec) / vec.Magnitude();
-}
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/event/BooleanEvent.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/event/BooleanEvent.cpp
new file mode 100644
index 0000000..5b8ce63
--- /dev/null
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/event/BooleanEvent.cpp
@@ -0,0 +1,68 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/event/BooleanEvent.h"
+
+using namespace frc;
+
+BooleanEvent::BooleanEvent(EventLoop* loop, std::function<bool()> condition)
+    : m_loop(loop), m_condition(std::move(condition)) {}
+
+BooleanEvent::operator std::function<bool()>() {
+  return m_condition;
+}
+
+bool BooleanEvent::GetAsBoolean() const {
+  return m_condition();
+}
+
+void BooleanEvent::IfHigh(std::function<void()> action) {
+  m_loop->Bind([condition = m_condition, action = std::move(action)] {
+    if (condition()) {
+      action();
+    }
+  });
+}
+
+BooleanEvent BooleanEvent::operator!() {
+  return BooleanEvent(this->m_loop, [lhs = m_condition] { return !lhs(); });
+}
+
+BooleanEvent BooleanEvent::operator&&(std::function<bool()> rhs) {
+  return BooleanEvent(this->m_loop,
+                      [lhs = m_condition, rhs] { return lhs() && rhs(); });
+}
+
+BooleanEvent BooleanEvent::operator||(std::function<bool()> rhs) {
+  return BooleanEvent(this->m_loop,
+                      [lhs = m_condition, rhs] { return lhs() || rhs(); });
+}
+
+BooleanEvent BooleanEvent::Rising() {
+  return BooleanEvent(
+      this->m_loop, [lhs = m_condition, m_previous = m_condition()]() mutable {
+        bool present = lhs();
+        bool past = m_previous;
+        m_previous = present;
+        return !past && present;
+      });
+}
+
+BooleanEvent BooleanEvent::Falling() {
+  return BooleanEvent(
+      this->m_loop, [lhs = m_condition, m_previous = m_condition()]() mutable {
+        bool present = lhs();
+        bool past = m_previous;
+        m_previous = present;
+        return past && !present;
+      });
+}
+
+BooleanEvent BooleanEvent::Debounce(units::second_t debounceTime,
+                                    frc::Debouncer::DebounceType type) {
+  return BooleanEvent(
+      this->m_loop,
+      [debouncer = frc::Debouncer(debounceTime, type),
+       lhs = m_condition]() mutable { return debouncer.Calculate(lhs()); });
+}
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/event/EventLoop.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/event/EventLoop.cpp
new file mode 100644
index 0000000..5af79c9
--- /dev/null
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/event/EventLoop.cpp
@@ -0,0 +1,23 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/event/EventLoop.h"
+
+using namespace frc;
+
+EventLoop::EventLoop() {}
+
+void EventLoop::Bind(wpi::unique_function<void()> action) {
+  m_bindings.emplace_back(std::move(action));
+}
+
+void EventLoop::Poll() {
+  for (wpi::unique_function<void()>& action : m_bindings) {
+    action();
+  }
+}
+
+void EventLoop::Clear() {
+  m_bindings.clear();
+}
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/event/NetworkBooleanEvent.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/event/NetworkBooleanEvent.cpp
new file mode 100644
index 0000000..d910361
--- /dev/null
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/event/NetworkBooleanEvent.cpp
@@ -0,0 +1,40 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/event/NetworkBooleanEvent.h"
+
+#include <networktables/BooleanTopic.h>
+#include <networktables/NetworkTable.h>
+#include <networktables/NetworkTableInstance.h>
+
+using namespace frc;
+
+NetworkBooleanEvent::NetworkBooleanEvent(EventLoop* loop,
+                                         nt::BooleanTopic topic)
+    : NetworkBooleanEvent{loop, topic.Subscribe(false)} {}
+
+NetworkBooleanEvent::NetworkBooleanEvent(EventLoop* loop,
+                                         nt::BooleanSubscriber sub)
+    : BooleanEvent{
+          loop,
+          [sub = std::make_shared<nt::BooleanSubscriber>(std::move(sub))] {
+            return sub->GetTopic().GetInstance().IsConnected() && sub->Get();
+          }} {}
+
+NetworkBooleanEvent::NetworkBooleanEvent(
+    EventLoop* loop, std::shared_ptr<nt::NetworkTable> table,
+    std::string_view topicName)
+    : NetworkBooleanEvent{loop, table->GetBooleanTopic(topicName)} {}
+
+NetworkBooleanEvent::NetworkBooleanEvent(EventLoop* loop,
+                                         std::string_view tableName,
+                                         std::string_view topicName)
+    : NetworkBooleanEvent{loop, nt::NetworkTableInstance::GetDefault(),
+                          tableName, topicName} {}
+
+NetworkBooleanEvent::NetworkBooleanEvent(EventLoop* loop,
+                                         nt::NetworkTableInstance inst,
+                                         std::string_view tableName,
+                                         std::string_view topicName)
+    : NetworkBooleanEvent{loop, inst.GetTable(tableName), topicName} {}
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/internal/DriverStationModeThread.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/internal/DriverStationModeThread.cpp
new file mode 100644
index 0000000..4085658
--- /dev/null
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/internal/DriverStationModeThread.cpp
@@ -0,0 +1,64 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/internal/DriverStationModeThread.h"
+
+#include <hal/DriverStation.h>
+#include <wpi/Synchronization.h>
+
+#include "frc/DriverStation.h"
+
+using namespace frc::internal;
+
+DriverStationModeThread::DriverStationModeThread() {
+  m_keepAlive = true;
+  m_thread = std::thread{[&] { Run(); }};
+}
+
+DriverStationModeThread::~DriverStationModeThread() {
+  m_keepAlive = false;
+  if (m_thread.joinable()) {
+    m_thread.join();
+  }
+}
+
+void DriverStationModeThread::InAutonomous(bool entering) {
+  m_userInAutonomous = entering;
+}
+void DriverStationModeThread::InDisabled(bool entering) {
+  m_userInDisabled = entering;
+}
+
+void DriverStationModeThread::InTeleop(bool entering) {
+  m_userInTeleop = entering;
+}
+
+void DriverStationModeThread::InTest(bool entering) {
+  m_userInTest = entering;
+}
+
+void DriverStationModeThread::Run() {
+  wpi::Event event{false, false};
+  HAL_ProvideNewDataEventHandle(event.GetHandle());
+
+  while (m_keepAlive.load()) {
+    bool timedOut = false;
+    wpi::WaitForObject(event.GetHandle(), 0.1, &timedOut);
+    frc::DriverStation::RefreshData();
+    if (m_userInDisabled) {
+      HAL_ObserveUserProgramDisabled();
+    }
+    if (m_userInAutonomous) {
+      HAL_ObserveUserProgramAutonomous();
+    }
+    if (m_userInTeleop) {
+      HAL_ObserveUserProgramTeleop();
+    }
+    if (m_userInTest) {
+      HAL_ObserveUserProgramTest();
+    }
+  }
+
+  HAL_RemoveNewDataEventHandle(event.GetHandle());
+}
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/livewindow/LiveWindow.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/livewindow/LiveWindow.cpp
index ac1c8ad..0a4e1b8 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/livewindow/LiveWindow.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/livewindow/LiveWindow.cpp
@@ -4,9 +4,10 @@
 
 #include "frc/livewindow/LiveWindow.h"
 
+#include <networktables/BooleanTopic.h>
 #include <networktables/NetworkTable.h>
-#include <networktables/NetworkTableEntry.h>
 #include <networktables/NetworkTableInstance.h>
+#include <networktables/StringTopic.h>
 #include <wpi/mutex.h>
 #include <wpi/sendable/Sendable.h>
 #include <wpi/sendable/SendableRegistry.h>
@@ -18,13 +19,16 @@
 namespace {
 struct Component {
   bool firstTime = true;
-  bool telemetryEnabled = true;
+  bool telemetryEnabled = false;
+  nt::StringPublisher namePub;
+  nt::StringPublisher typePub;
 };
 
 struct Instance {
   Instance() {
     wpi::SendableRegistry::SetLiveWindowBuilderFactory(
         [] { return std::make_unique<SendableBuilderImpl>(); });
+    enabledPub.Set(false);
   }
 
   wpi::mutex mutex;
@@ -35,11 +39,12 @@
       nt::NetworkTableInstance::GetDefault().GetTable("LiveWindow");
   std::shared_ptr<nt::NetworkTable> statusTable =
       liveWindowTable->GetSubTable(".status");
-  nt::NetworkTableEntry enabledEntry = statusTable->GetEntry("LW Enabled");
+  nt::BooleanPublisher enabledPub =
+      statusTable->GetBooleanTopic("LW Enabled").Publish();
 
   bool startLiveWindow = false;
   bool liveWindowEnabled = false;
-  bool telemetryEnabled = true;
+  bool telemetryEnabled = false;
 
   std::function<void()> enabled;
   std::function<void()> disabled;
@@ -75,12 +80,6 @@
   return data;
 }
 
-LiveWindow* LiveWindow::GetInstance() {
-  ::GetInstance();
-  static LiveWindow instance;
-  return &instance;
-}
-
 void LiveWindow::SetEnabledCallback(std::function<void()> func) {
   ::GetInstance().enabled = func;
 }
@@ -115,6 +114,18 @@
   });
 }
 
+void LiveWindow::EnableAllTelemetry() {
+  auto& inst = ::GetInstance();
+  std::scoped_lock lock(inst.mutex);
+  inst.telemetryEnabled = true;
+  wpi::SendableRegistry::ForeachLiveWindow(inst.dataHandle, [&](auto& cbdata) {
+    if (!cbdata.data) {
+      cbdata.data = std::make_shared<Component>();
+    }
+    std::static_pointer_cast<Component>(cbdata.data)->telemetryEnabled = true;
+  });
+}
+
 bool LiveWindow::IsEnabled() {
   auto& inst = ::GetInstance();
   std::scoped_lock lock(inst.mutex);
@@ -145,7 +156,7 @@
       inst.disabled();
     }
   }
-  inst.enabledEntry.SetBoolean(enabled);
+  inst.enabledPub.Set(enabled);
 }
 
 void LiveWindow::UpdateValues() {
@@ -192,10 +203,12 @@
       } else {
         table = ssTable->GetSubTable(cbdata.name);
       }
-      table->GetEntry(".name").SetString(cbdata.name);
+      comp.namePub = nt::StringTopic{table->GetTopic(".name")}.Publish();
+      comp.namePub.Set(cbdata.name);
       static_cast<SendableBuilderImpl&>(cbdata.builder).SetTable(table);
       cbdata.sendable->InitSendable(cbdata.builder);
-      ssTable->GetEntry(".type").SetString("LW Subsystem");
+      comp.typePub = nt::StringTopic{ssTable->GetTopic(".type")}.Publish();
+      comp.typePub.Set("LW Subsystem");
 
       comp.firstTime = false;
     }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/motorcontrol/MotorController.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/motorcontrol/MotorController.cpp
new file mode 100644
index 0000000..9d20144
--- /dev/null
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/motorcontrol/MotorController.cpp
@@ -0,0 +1,13 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/motorcontrol/MotorController.h"
+
+#include <frc/RobotController.h>
+
+using namespace frc;
+
+void MotorController::SetVoltage(units::volt_t output) {
+  Set(output / RobotController::GetBatteryVoltage());
+}
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/motorcontrol/MotorControllerGroup.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/motorcontrol/MotorControllerGroup.cpp
index b7f26d1..f855d14 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/motorcontrol/MotorControllerGroup.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/motorcontrol/MotorControllerGroup.cpp
@@ -33,6 +33,12 @@
   }
 }
 
+void MotorControllerGroup::SetVoltage(units::volt_t output) {
+  for (auto motorController : m_motorControllers) {
+    motorController.get().SetVoltage(m_isInverted ? -output : output);
+  }
+}
+
 double MotorControllerGroup::Get() const {
   if (!m_motorControllers.empty()) {
     return m_motorControllers.front().get().Get() * (m_isInverted ? -1 : 1);
@@ -63,7 +69,8 @@
 void MotorControllerGroup::InitSendable(wpi::SendableBuilder& builder) {
   builder.SetSmartDashboardType("Motor Controller");
   builder.SetActuator(true);
-  builder.SetSafeState([=] { StopMotor(); });
+  builder.SetSafeState([=, this] { StopMotor(); });
   builder.AddDoubleProperty(
-      "Value", [=] { return Get(); }, [=](double value) { Set(value); });
+      "Value", [=, this] { return Get(); },
+      [=, this](double value) { Set(value); });
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/motorcontrol/NidecBrushless.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/motorcontrol/NidecBrushless.cpp
index 21164eb..01c70d0 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/motorcontrol/NidecBrushless.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/motorcontrol/NidecBrushless.cpp
@@ -73,7 +73,8 @@
 void NidecBrushless::InitSendable(wpi::SendableBuilder& builder) {
   builder.SetSmartDashboardType("Nidec Brushless");
   builder.SetActuator(true);
-  builder.SetSafeState([=] { StopMotor(); });
+  builder.SetSafeState([=, this] { StopMotor(); });
   builder.AddDoubleProperty(
-      "Value", [=] { return Get(); }, [=](double value) { Set(value); });
+      "Value", [=, this] { return Get(); },
+      [=, this](double value) { Set(value); });
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/motorcontrol/PWMMotorController.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/motorcontrol/PWMMotorController.cpp
index f9ff4b8..3692f75 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/motorcontrol/PWMMotorController.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/motorcontrol/PWMMotorController.cpp
@@ -12,6 +12,7 @@
 
 void PWMMotorController::Set(double speed) {
   m_pwm.SetSpeed(m_isInverted ? -speed : speed);
+  Feed();
 }
 
 double PWMMotorController::Get() const {
@@ -31,7 +32,8 @@
 }
 
 void PWMMotorController::StopMotor() {
-  Disable();
+  // Don't use Set(0) as that will feed the watch kitty
+  m_pwm.SetSpeed(0);
 }
 
 std::string PWMMotorController::GetDescription() const {
@@ -54,7 +56,8 @@
 void PWMMotorController::InitSendable(wpi::SendableBuilder& builder) {
   builder.SetSmartDashboardType("Motor Controller");
   builder.SetActuator(true);
-  builder.SetSafeState([=] { Disable(); });
+  builder.SetSafeState([=, this] { Disable(); });
   builder.AddDoubleProperty(
-      "Value", [=] { return Get(); }, [=](double value) { Set(value); });
+      "Value", [=, this] { return Get(); },
+      [=, this](double value) { Set(value); });
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/shuffleboard/RecordingController.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/shuffleboard/RecordingController.cpp
index 834c4be..fb1ef9c 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/shuffleboard/RecordingController.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/shuffleboard/RecordingController.cpp
@@ -9,40 +9,40 @@
 using namespace frc;
 using namespace frc::detail;
 
-RecordingController::RecordingController(nt::NetworkTableInstance ntInstance)
-    : m_recordingControlEntry(), m_recordingFileNameFormatEntry() {
+RecordingController::RecordingController(nt::NetworkTableInstance ntInstance) {
   m_recordingControlEntry =
-      ntInstance.GetEntry("/Shuffleboard/.recording/RecordData");
+      ntInstance.GetBooleanTopic("/Shuffleboard/.recording/RecordData")
+          .Publish();
   m_recordingFileNameFormatEntry =
-      ntInstance.GetEntry("/Shuffleboard/.recording/FileNameFormat");
+      ntInstance.GetStringTopic("/Shuffleboard/.recording/FileNameFormat")
+          .Publish();
   m_eventsTable = ntInstance.GetTable("/Shuffleboard/.recording/events");
 }
 
 void RecordingController::StartRecording() {
-  m_recordingControlEntry.SetBoolean(true);
+  m_recordingControlEntry.Set(true);
 }
 
 void RecordingController::StopRecording() {
-  m_recordingControlEntry.SetBoolean(false);
+  m_recordingControlEntry.Set(false);
 }
 
 void RecordingController::SetRecordingFileNameFormat(std::string_view format) {
-  m_recordingFileNameFormatEntry.SetString(format);
+  m_recordingFileNameFormatEntry.Set(format);
 }
 
 void RecordingController::ClearRecordingFileNameFormat() {
-  m_recordingFileNameFormatEntry.Delete();
+  m_recordingFileNameFormatEntry.Set("");
 }
 
 void RecordingController::AddEventMarker(
     std::string_view name, std::string_view description,
     ShuffleboardEventImportance importance) {
   if (name.empty()) {
-    FRC_ReportError(err::Error, "{}",
-                    "Shuffleboard event name was not specified");
+    FRC_ReportError(err::Error, "Shuffleboard event name was not specified");
     return;
   }
   m_eventsTable->GetSubTable(name)->GetEntry("Info").SetStringArray(
-      {std::string{description},
-       std::string{ShuffleboardEventImportanceName(importance)}});
+      {{std::string{description},
+        std::string{ShuffleboardEventImportanceName(importance)}}});
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/shuffleboard/Shuffleboard.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/shuffleboard/Shuffleboard.cpp
index 16b404c..9135012 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/shuffleboard/Shuffleboard.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/shuffleboard/Shuffleboard.cpp
@@ -63,10 +63,24 @@
   AddEventMarker(name, "", importance);
 }
 
-detail::ShuffleboardInstance& Shuffleboard::GetInstance() {
-  static detail::ShuffleboardInstance inst(
+static std::unique_ptr<detail::ShuffleboardInstance>& GetInstanceHolder() {
+  static std::unique_ptr<detail::ShuffleboardInstance> instance =
+      std::make_unique<detail::ShuffleboardInstance>(
+          nt::NetworkTableInstance::GetDefault());
+  return instance;
+}
+
+#ifndef __FRC_ROBORIO__
+namespace frc::impl {
+void ResetShuffleboardInstance() {
+  GetInstanceHolder() = std::make_unique<detail::ShuffleboardInstance>(
       nt::NetworkTableInstance::GetDefault());
-  return inst;
+}
+}  // namespace frc::impl
+#endif
+
+detail::ShuffleboardInstance& Shuffleboard::GetInstance() {
+  return *GetInstanceHolder();
 }
 
 detail::RecordingController& Shuffleboard::GetRecordingController() {
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardComponentBase.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardComponentBase.cpp
index 940f6ab..c43fc90 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardComponentBase.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardComponentBase.cpp
@@ -22,27 +22,21 @@
     return;
   }
   // Component type
-  if (GetType() == "") {
-    metaTable->GetEntry("PreferredComponent").Delete();
-  } else {
-    metaTable->GetEntry("PreferredComponent").ForceSetString(GetType());
+  if (!GetType().empty()) {
+    metaTable->GetEntry("PreferredComponent").SetString(GetType());
   }
 
   // Tile size
-  if (m_width <= 0 || m_height <= 0) {
-    metaTable->GetEntry("Size").Delete();
-  } else {
+  if (m_width > 0 && m_height > 0) {
     metaTable->GetEntry("Size").SetDoubleArray(
-        {static_cast<double>(m_width), static_cast<double>(m_height)});
+        {{static_cast<double>(m_width), static_cast<double>(m_height)}});
   }
 
   // Tile position
-  if (m_column < 0 || m_row < 0) {
-    metaTable->GetEntry("Position").Delete();
-  } else {
+  if (m_column >= 0 && m_row >= 0) {
     metaTable->GetEntry("Position")
         .SetDoubleArray(
-            {static_cast<double>(m_column), static_cast<double>(m_row)});
+            {{static_cast<double>(m_column), static_cast<double>(m_row)}});
   }
 
   // Custom properties
@@ -63,7 +57,7 @@
   return m_type;
 }
 
-const wpi::StringMap<std::shared_ptr<nt::Value>>&
-ShuffleboardComponentBase::GetProperties() const {
+const wpi::StringMap<nt::Value>& ShuffleboardComponentBase::GetProperties()
+    const {
   return m_properties;
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardContainer.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardContainer.cpp
index 004f7c5..ca3c6d6 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardContainer.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardContainer.cpp
@@ -4,6 +4,7 @@
 
 #include "frc/shuffleboard/ShuffleboardContainer.h"
 
+#include <ntcore_cpp.h>
 #include <wpi/sendable/SendableRegistry.h>
 
 #include "frc/Errors.h"
@@ -69,19 +70,20 @@
 ComplexWidget& ShuffleboardContainer::Add(wpi::Sendable& sendable) {
   auto name = wpi::SendableRegistry::GetName(&sendable);
   if (name.empty()) {
-    FRC_ReportError(err::Error, "{}", "Sendable must have a name");
+    FRC_ReportError(err::Error, "Sendable must have a name");
   }
   return Add(name, sendable);
 }
 
-SimpleWidget& ShuffleboardContainer::Add(
-    std::string_view title, std::shared_ptr<nt::Value> defaultValue) {
+SimpleWidget& ShuffleboardContainer::Add(std::string_view title,
+                                         const nt::Value& defaultValue) {
   CheckTitle(title);
 
   auto widget = std::make_unique<SimpleWidget>(*this, title);
   auto ptr = widget.get();
   m_components.emplace_back(std::move(widget));
-  ptr->GetEntry().SetDefaultValue(defaultValue);
+  ptr->GetEntry(nt::GetStringFromType(defaultValue.type()))
+      ->SetDefault(defaultValue);
   return *ptr;
 }
 
@@ -96,8 +98,13 @@
 }
 
 SimpleWidget& ShuffleboardContainer::Add(std::string_view title,
+                                         float defaultValue) {
+  return Add(title, nt::Value::MakeFloat(defaultValue));
+}
+
+SimpleWidget& ShuffleboardContainer::Add(std::string_view title,
                                          int defaultValue) {
-  return Add(title, nt::Value::MakeDouble(defaultValue));
+  return Add(title, nt::Value::MakeInteger(defaultValue));
 }
 
 SimpleWidget& ShuffleboardContainer::Add(std::string_view title,
@@ -111,29 +118,39 @@
 }
 
 SimpleWidget& ShuffleboardContainer::Add(std::string_view title,
-                                         wpi::span<const bool> defaultValue) {
+                                         std::span<const bool> defaultValue) {
   return Add(title, nt::Value::MakeBooleanArray(defaultValue));
 }
 
 SimpleWidget& ShuffleboardContainer::Add(std::string_view title,
-                                         wpi::span<const double> defaultValue) {
+                                         std::span<const double> defaultValue) {
   return Add(title, nt::Value::MakeDoubleArray(defaultValue));
 }
 
+SimpleWidget& ShuffleboardContainer::Add(std::string_view title,
+                                         std::span<const float> defaultValue) {
+  return Add(title, nt::Value::MakeFloatArray(defaultValue));
+}
+
 SimpleWidget& ShuffleboardContainer::Add(
-    std::string_view title, wpi::span<const std::string> defaultValue) {
+    std::string_view title, std::span<const int64_t> defaultValue) {
+  return Add(title, nt::Value::MakeIntegerArray(defaultValue));
+}
+
+SimpleWidget& ShuffleboardContainer::Add(
+    std::string_view title, std::span<const std::string> defaultValue) {
   return Add(title, nt::Value::MakeStringArray(defaultValue));
 }
 
 SuppliedValueWidget<std::string>& ShuffleboardContainer::AddString(
     std::string_view title, std::function<std::string()> supplier) {
-  static auto setter = [](nt::NetworkTableEntry entry, std::string value) {
+  static auto setter = [](nt::GenericPublisher& entry, std::string value) {
     entry.SetString(value);
   };
 
   CheckTitle(title);
   auto widget = std::make_unique<SuppliedValueWidget<std::string>>(
-      *this, title, supplier, setter);
+      *this, title, "string", supplier, setter);
   auto ptr = widget.get();
   m_components.emplace_back(std::move(widget));
   return *ptr;
@@ -141,13 +158,46 @@
 
 SuppliedValueWidget<double>& ShuffleboardContainer::AddNumber(
     std::string_view title, std::function<double()> supplier) {
-  static auto setter = [](nt::NetworkTableEntry entry, double value) {
+  return AddDouble(title, std::move(supplier));
+}
+
+SuppliedValueWidget<double>& ShuffleboardContainer::AddDouble(
+    std::string_view title, std::function<double()> supplier) {
+  static auto setter = [](nt::GenericPublisher& entry, double value) {
     entry.SetDouble(value);
   };
 
   CheckTitle(title);
-  auto widget = std::make_unique<SuppliedValueWidget<double>>(*this, title,
-                                                              supplier, setter);
+  auto widget = std::make_unique<SuppliedValueWidget<double>>(
+      *this, title, "double", supplier, setter);
+  auto ptr = widget.get();
+  m_components.emplace_back(std::move(widget));
+  return *ptr;
+}
+
+SuppliedValueWidget<float>& ShuffleboardContainer::AddFloat(
+    std::string_view title, std::function<float()> supplier) {
+  static auto setter = [](nt::GenericPublisher& entry, float value) {
+    entry.SetFloat(value);
+  };
+
+  CheckTitle(title);
+  auto widget = std::make_unique<SuppliedValueWidget<float>>(
+      *this, title, "float", supplier, setter);
+  auto ptr = widget.get();
+  m_components.emplace_back(std::move(widget));
+  return *ptr;
+}
+
+SuppliedValueWidget<int64_t>& ShuffleboardContainer::AddInteger(
+    std::string_view title, std::function<int64_t()> supplier) {
+  static auto setter = [](nt::GenericPublisher& entry, int64_t value) {
+    entry.SetInteger(value);
+  };
+
+  CheckTitle(title);
+  auto widget = std::make_unique<SuppliedValueWidget<int64_t>>(
+      *this, title, "int", supplier, setter);
   auto ptr = widget.get();
   m_components.emplace_back(std::move(widget));
   return *ptr;
@@ -155,13 +205,13 @@
 
 SuppliedValueWidget<bool>& ShuffleboardContainer::AddBoolean(
     std::string_view title, std::function<bool()> supplier) {
-  static auto setter = [](nt::NetworkTableEntry entry, bool value) {
+  static auto setter = [](nt::GenericPublisher& entry, bool value) {
     entry.SetBoolean(value);
   };
 
   CheckTitle(title);
-  auto widget = std::make_unique<SuppliedValueWidget<bool>>(*this, title,
-                                                            supplier, setter);
+  auto widget = std::make_unique<SuppliedValueWidget<bool>>(
+      *this, title, "boolean", supplier, setter);
   auto ptr = widget.get();
   m_components.emplace_back(std::move(widget));
   return *ptr;
@@ -171,14 +221,14 @@
 ShuffleboardContainer::AddStringArray(
     std::string_view title,
     std::function<std::vector<std::string>()> supplier) {
-  static auto setter = [](nt::NetworkTableEntry entry,
+  static auto setter = [](nt::GenericPublisher& entry,
                           std::vector<std::string> value) {
     entry.SetStringArray(value);
   };
 
   CheckTitle(title);
   auto widget = std::make_unique<SuppliedValueWidget<std::vector<std::string>>>(
-      *this, title, supplier, setter);
+      *this, title, "string[]", supplier, setter);
   auto ptr = widget.get();
   m_components.emplace_back(std::move(widget));
   return *ptr;
@@ -186,14 +236,50 @@
 
 SuppliedValueWidget<std::vector<double>>& ShuffleboardContainer::AddNumberArray(
     std::string_view title, std::function<std::vector<double>()> supplier) {
-  static auto setter = [](nt::NetworkTableEntry entry,
+  return AddDoubleArray(title, std::move(supplier));
+}
+
+SuppliedValueWidget<std::vector<double>>& ShuffleboardContainer::AddDoubleArray(
+    std::string_view title, std::function<std::vector<double>()> supplier) {
+  static auto setter = [](nt::GenericPublisher& entry,
                           std::vector<double> value) {
     entry.SetDoubleArray(value);
   };
 
   CheckTitle(title);
   auto widget = std::make_unique<SuppliedValueWidget<std::vector<double>>>(
-      *this, title, supplier, setter);
+      *this, title, "double[]", supplier, setter);
+  auto ptr = widget.get();
+  m_components.emplace_back(std::move(widget));
+  return *ptr;
+}
+
+SuppliedValueWidget<std::vector<float>>& ShuffleboardContainer::AddFloatArray(
+    std::string_view title, std::function<std::vector<float>()> supplier) {
+  static auto setter = [](nt::GenericPublisher& entry,
+                          std::vector<float> value) {
+    entry.SetFloatArray(value);
+  };
+
+  CheckTitle(title);
+  auto widget = std::make_unique<SuppliedValueWidget<std::vector<float>>>(
+      *this, title, "float[]", supplier, setter);
+  auto ptr = widget.get();
+  m_components.emplace_back(std::move(widget));
+  return *ptr;
+}
+
+SuppliedValueWidget<std::vector<int64_t>>&
+ShuffleboardContainer::AddIntegerArray(
+    std::string_view title, std::function<std::vector<int64_t>()> supplier) {
+  static auto setter = [](nt::GenericPublisher& entry,
+                          std::vector<int64_t> value) {
+    entry.SetIntegerArray(value);
+  };
+
+  CheckTitle(title);
+  auto widget = std::make_unique<SuppliedValueWidget<std::vector<int64_t>>>(
+      *this, title, "int[]", supplier, setter);
   auto ptr = widget.get();
   m_components.emplace_back(std::move(widget));
   return *ptr;
@@ -201,36 +287,43 @@
 
 SuppliedValueWidget<std::vector<int>>& ShuffleboardContainer::AddBooleanArray(
     std::string_view title, std::function<std::vector<int>()> supplier) {
-  static auto setter = [](nt::NetworkTableEntry entry, std::vector<int> value) {
+  static auto setter = [](nt::GenericPublisher& entry, std::vector<int> value) {
     entry.SetBooleanArray(value);
   };
 
   CheckTitle(title);
   auto widget = std::make_unique<SuppliedValueWidget<std::vector<int>>>(
-      *this, title, supplier, setter);
+      *this, title, "boolean[]", supplier, setter);
   auto ptr = widget.get();
   m_components.emplace_back(std::move(widget));
   return *ptr;
 }
 
-SuppliedValueWidget<std::string_view>& ShuffleboardContainer::AddRaw(
-    std::string_view title, std::function<std::string_view()> supplier) {
-  static auto setter = [](nt::NetworkTableEntry entry, std::string_view value) {
-    entry.SetRaw(value);
-  };
+SuppliedValueWidget<std::vector<uint8_t>>& ShuffleboardContainer::AddRaw(
+    std::string_view title, std::function<std::vector<uint8_t>()> supplier) {
+  return AddRaw(title, "raw", std::move(supplier));
+}
+
+SuppliedValueWidget<std::vector<uint8_t>>& ShuffleboardContainer::AddRaw(
+    std::string_view title, std::string_view typeString,
+    std::function<std::vector<uint8_t>()> supplier) {
+  static auto setter = [](nt::GenericPublisher& entry,
+                          std::vector<uint8_t> value) { entry.SetRaw(value); };
 
   CheckTitle(title);
-  auto widget = std::make_unique<SuppliedValueWidget<std::string_view>>(
-      *this, title, supplier, setter);
+  auto widget = std::make_unique<SuppliedValueWidget<std::vector<uint8_t>>>(
+      *this, title, typeString, supplier, setter);
   auto ptr = widget.get();
   m_components.emplace_back(std::move(widget));
   return *ptr;
 }
 
 SimpleWidget& ShuffleboardContainer::AddPersistent(
-    std::string_view title, std::shared_ptr<nt::Value> defaultValue) {
+    std::string_view title, const nt::Value& defaultValue) {
   auto& widget = Add(title, defaultValue);
-  widget.GetEntry().SetPersistent();
+  widget.GetEntry(nt::GetStringFromType(defaultValue.type()))
+      ->GetTopic()
+      .SetPersistent(true);
   return widget;
 }
 
@@ -245,8 +338,13 @@
 }
 
 SimpleWidget& ShuffleboardContainer::AddPersistent(std::string_view title,
+                                                   float defaultValue) {
+  return AddPersistent(title, nt::Value::MakeFloat(defaultValue));
+}
+
+SimpleWidget& ShuffleboardContainer::AddPersistent(std::string_view title,
                                                    int defaultValue) {
-  return AddPersistent(title, nt::Value::MakeDouble(defaultValue));
+  return AddPersistent(title, nt::Value::MakeInteger(defaultValue));
 }
 
 SimpleWidget& ShuffleboardContainer::AddPersistent(
@@ -255,17 +353,27 @@
 }
 
 SimpleWidget& ShuffleboardContainer::AddPersistent(
-    std::string_view title, wpi::span<const bool> defaultValue) {
+    std::string_view title, std::span<const bool> defaultValue) {
   return AddPersistent(title, nt::Value::MakeBooleanArray(defaultValue));
 }
 
 SimpleWidget& ShuffleboardContainer::AddPersistent(
-    std::string_view title, wpi::span<const double> defaultValue) {
+    std::string_view title, std::span<const double> defaultValue) {
   return AddPersistent(title, nt::Value::MakeDoubleArray(defaultValue));
 }
 
 SimpleWidget& ShuffleboardContainer::AddPersistent(
-    std::string_view title, wpi::span<const std::string> defaultValue) {
+    std::string_view title, std::span<const float> defaultValue) {
+  return AddPersistent(title, nt::Value::MakeFloatArray(defaultValue));
+}
+
+SimpleWidget& ShuffleboardContainer::AddPersistent(
+    std::string_view title, std::span<const int64_t> defaultValue) {
+  return AddPersistent(title, nt::Value::MakeIntegerArray(defaultValue));
+}
+
+SimpleWidget& ShuffleboardContainer::AddPersistent(
+    std::string_view title, std::span<const std::string> defaultValue) {
   return AddPersistent(title, nt::Value::MakeStringArray(defaultValue));
 }
 
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardInstance.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardInstance.cpp
index 083b4a2..a315b90 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardInstance.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardInstance.cpp
@@ -46,7 +46,7 @@
     for (auto& entry : m_impl->tabs) {
       tabTitles.emplace_back(entry.second->GetTitle());
     }
-    m_impl->rootMetaTable->GetEntry("Tabs").ForceSetStringArray(tabTitles);
+    m_impl->rootMetaTable->GetEntry("Tabs").SetStringArray(tabTitles);
     m_impl->tabsChanged = false;
   }
   for (auto& entry : m_impl->tabs) {
@@ -75,9 +75,9 @@
 }
 
 void ShuffleboardInstance::SelectTab(int index) {
-  m_impl->rootMetaTable->GetEntry("Selected").ForceSetDouble(index);
+  m_impl->rootMetaTable->GetEntry("Selected").SetDouble(index);
 }
 
 void ShuffleboardInstance::SelectTab(std::string_view title) {
-  m_impl->rootMetaTable->GetEntry("Selected").ForceSetString(title);
+  m_impl->rootMetaTable->GetEntry("Selected").SetString(title);
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardWidget.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardWidget.cpp
index 31e4b11..bb475fd 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardWidget.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardWidget.cpp
@@ -20,7 +20,7 @@
     "ComboBox Chooser",
     "Split Button Chooser",
     "Encoder",
-    "Speed Controller",
+    "Motor Controller",
     "Command",
     "PID Command",
     "PID Controller",
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/shuffleboard/SimpleWidget.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/shuffleboard/SimpleWidget.cpp
index 390c9c4..c62b76d 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/shuffleboard/SimpleWidget.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/shuffleboard/SimpleWidget.cpp
@@ -14,18 +14,26 @@
                            std::string_view title)
     : ShuffleboardValue(title), ShuffleboardWidget(parent, title), m_entry() {}
 
-nt::NetworkTableEntry SimpleWidget::GetEntry() {
+nt::GenericEntry* SimpleWidget::GetEntry() {
   if (!m_entry) {
     ForceGenerate();
   }
-  return m_entry;
+  return &m_entry;
+}
+
+nt::GenericEntry* SimpleWidget::GetEntry(std::string_view typeString) {
+  if (!m_entry) {
+    m_typeString = typeString;
+    ForceGenerate();
+  }
+  return &m_entry;
 }
 
 void SimpleWidget::BuildInto(std::shared_ptr<nt::NetworkTable> parentTable,
                              std::shared_ptr<nt::NetworkTable> metaTable) {
   BuildMetadata(metaTable);
   if (!m_entry) {
-    m_entry = parentTable->GetEntry(GetTitle());
+    m_entry = parentTable->GetTopic(GetTitle()).GetGenericEntry(m_typeString);
   }
 }
 
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/AnalogEncoderSim.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/AnalogEncoderSim.cpp
index 049241e..435e29e 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/AnalogEncoderSim.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/AnalogEncoderSim.cpp
@@ -27,6 +27,5 @@
 }
 
 frc::Rotation2d AnalogEncoderSim::GetPosition() {
-  units::radian_t rads = GetTurns();
-  return frc::Rotation2d{rads};
+  return units::radian_t{GetTurns()};
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/CTREPCMSim.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/CTREPCMSim.cpp
index 9c7450b..0081928 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/CTREPCMSim.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/CTREPCMSim.cpp
@@ -14,12 +14,13 @@
 using namespace frc;
 using namespace frc::sim;
 
-CTREPCMSim::CTREPCMSim() : m_index{SensorUtil::GetDefaultCTREPCMModule()} {}
+CTREPCMSim::CTREPCMSim()
+    : PneumaticsBaseSim{SensorUtil::GetDefaultCTREPCMModule()} {}
 
-CTREPCMSim::CTREPCMSim(int module) : m_index{module} {}
+CTREPCMSim::CTREPCMSim(int module) : PneumaticsBaseSim{module} {}
 
 CTREPCMSim::CTREPCMSim(const PneumaticsBase& pneumatics)
-    : m_index{pneumatics.GetModuleNumber()} {}
+    : PneumaticsBaseSim{pneumatics.GetModuleNumber()} {}
 
 std::unique_ptr<CallbackStore> CTREPCMSim::RegisterInitializedCallback(
     NotifyCallback callback, bool initialNotify) {
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/DCMotorSim.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/DCMotorSim.cpp
index 7860e32..bda2020 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/DCMotorSim.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/DCMotorSim.cpp
@@ -42,5 +42,5 @@
 }
 
 void DCMotorSim::SetInputVoltage(units::volt_t voltage) {
-  SetInput(Eigen::Vector<double, 1>{voltage.value()});
+  SetInput(Vectord<1>{voltage.value()});
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/DifferentialDrivetrainSim.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/DifferentialDrivetrainSim.cpp
index 78b9dc7..b6c95dc 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/DifferentialDrivetrainSim.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/DifferentialDrivetrainSim.cpp
@@ -41,8 +41,7 @@
               driveMotor, mass, wheelRadius, trackWidth / 2.0, J, gearing),
           trackWidth, driveMotor, gearing, wheelRadius, measurementStdDevs) {}
 
-Eigen::Vector<double, 2> DifferentialDrivetrainSim::ClampInput(
-    const Eigen::Vector<double, 2>& u) {
+Vectord<2> DifferentialDrivetrainSim::ClampInput(const Vectord<2>& u) {
   return frc::DesaturateInputVector<2>(u,
                                        frc::RobotController::GetInputVoltage());
 }
@@ -66,11 +65,11 @@
   return m_currentGearing;
 }
 
-Eigen::Vector<double, 7> DifferentialDrivetrainSim::GetOutput() const {
+Vectord<7> DifferentialDrivetrainSim::GetOutput() const {
   return m_y;
 }
 
-Eigen::Vector<double, 7> DifferentialDrivetrainSim::GetState() const {
+Vectord<7> DifferentialDrivetrainSim::GetState() const {
   return m_x;
 }
 
@@ -83,20 +82,20 @@
 }
 
 Rotation2d DifferentialDrivetrainSim::GetHeading() const {
-  return Rotation2d(units::radian_t(GetOutput(State::kHeading)));
+  return units::radian_t{GetOutput(State::kHeading)};
 }
 
 Pose2d DifferentialDrivetrainSim::GetPose() const {
-  return Pose2d(units::meter_t(GetOutput(State::kX)),
-                units::meter_t(GetOutput(State::kY)), GetHeading());
+  return Pose2d{units::meter_t{GetOutput(State::kX)},
+                units::meter_t{GetOutput(State::kY)}, GetHeading()};
 }
 
 units::ampere_t DifferentialDrivetrainSim::GetLeftCurrentDraw() const {
   auto loadIleft =
       m_motor.Current(
-          units::radians_per_second_t(m_x(State::kLeftVelocity) *
-                                      m_currentGearing / m_wheelRadius.value()),
-          units::volt_t(m_u(0))) *
+          units::radians_per_second_t{m_x(State::kLeftVelocity) *
+                                      m_currentGearing / m_wheelRadius.value()},
+          units::volt_t{m_u(0)}) *
       wpi::sgn(m_u(0));
 
   return loadIleft;
@@ -105,9 +104,9 @@
 units::ampere_t DifferentialDrivetrainSim::GetRightCurrentDraw() const {
   auto loadIRight =
       m_motor.Current(
-          units::radians_per_second_t(m_x(State::kRightVelocity) *
-                                      m_currentGearing / m_wheelRadius.value()),
-          units::volt_t(m_u(1))) *
+          units::radians_per_second_t{m_x(State::kRightVelocity) *
+                                      m_currentGearing / m_wheelRadius.value()},
+          units::volt_t{m_u(1)}) *
       wpi::sgn(m_u(1));
 
   return loadIRight;
@@ -116,8 +115,7 @@
   return GetLeftCurrentDraw() + GetRightCurrentDraw();
 }
 
-void DifferentialDrivetrainSim::SetState(
-    const Eigen::Vector<double, 7>& state) {
+void DifferentialDrivetrainSim::SetState(const Vectord<7>& state) {
   m_x = state;
 }
 
@@ -129,19 +127,19 @@
   m_x(State::kRightPosition) = 0;
 }
 
-Eigen::Vector<double, 7> DifferentialDrivetrainSim::Dynamics(
-    const Eigen::Vector<double, 7>& x, const Eigen::Vector<double, 2>& u) {
-  // Because G^2 can be factored out of A, we can divide by the old ratio
+Vectord<7> DifferentialDrivetrainSim::Dynamics(const Vectord<7>& x,
+                                               const Vectord<2>& u) {
+  // Because G² can be factored out of A, we can divide by the old ratio
   // squared and multiply by the new ratio squared to get a new drivetrain
   // model.
-  Eigen::Matrix<double, 4, 2> B;
+  Matrixd<4, 2> B;
   B.block<2, 2>(0, 0) = m_plant.B() * m_currentGearing * m_currentGearing /
                         m_originalGearing / m_originalGearing;
   B.block<2, 2>(2, 0).setZero();
 
   // Because G can be factored out of B, we can divide by the old ratio and
   // multiply by the new ratio to get a new drivetrain model.
-  Eigen::Matrix<double, 4, 4> A;
+  Matrixd<4, 4> A;
   A.block<2, 2>(0, 0) = m_plant.A() * m_currentGearing / m_originalGearing;
 
   A.block<2, 2>(2, 0).setIdentity();
@@ -149,7 +147,7 @@
 
   double v = (x(State::kLeftVelocity) + x(State::kRightVelocity)) / 2.0;
 
-  Eigen::Vector<double, 7> xdot;
+  Vectord<7> xdot;
   xdot(0) = v * std::cos(x(State::kHeading));
   xdot(1) = v * std::sin(x(State::kHeading));
   xdot(2) =
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/DoubleSolenoidSim.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/DoubleSolenoidSim.cpp
new file mode 100644
index 0000000..da99867
--- /dev/null
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/DoubleSolenoidSim.cpp
@@ -0,0 +1,48 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/simulation/DoubleSolenoidSim.h"
+
+#include "frc/PneumaticsBase.h"
+
+using namespace frc;
+using namespace frc::sim;
+
+DoubleSolenoidSim::DoubleSolenoidSim(
+    std::shared_ptr<PneumaticsBaseSim> moduleSim, int fwd, int rev)
+    : m_module{std::move(moduleSim)}, m_fwd{fwd}, m_rev{rev} {}
+
+DoubleSolenoidSim::DoubleSolenoidSim(int module, PneumaticsModuleType type,
+                                     int fwd, int rev)
+    : m_module{PneumaticsBaseSim::GetForType(module, type)},
+      m_fwd{fwd},
+      m_rev{rev} {}
+
+DoubleSolenoidSim::DoubleSolenoidSim(PneumaticsModuleType type, int fwd,
+                                     int rev)
+    : m_module{PneumaticsBaseSim::GetForType(
+          PneumaticsBase::GetDefaultForType(type), type)},
+      m_fwd{fwd},
+      m_rev{rev} {}
+
+DoubleSolenoid::Value DoubleSolenoidSim::Get() const {
+  bool fwdState = m_module->GetSolenoidOutput(m_fwd);
+  bool revState = m_module->GetSolenoidOutput(m_rev);
+  if (fwdState && !revState) {
+    return DoubleSolenoid::Value::kForward;
+  } else if (!fwdState && revState) {
+    return DoubleSolenoid::Value::kReverse;
+  } else {
+    return DoubleSolenoid::Value::kOff;
+  }
+}
+
+void DoubleSolenoidSim::Set(DoubleSolenoid::Value output) {
+  m_module->SetSolenoidOutput(m_fwd, output == DoubleSolenoid::Value::kForward);
+  m_module->SetSolenoidOutput(m_rev, output == DoubleSolenoid::Value::kReverse);
+}
+
+std::shared_ptr<PneumaticsBaseSim> DoubleSolenoidSim::GetModuleSim() const {
+  return m_module;
+}
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/DriverStationSim.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/DriverStationSim.cpp
index 5f2c645..345204a 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/DriverStationSim.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/DriverStationSim.cpp
@@ -7,6 +7,7 @@
 #include <memory>
 #include <utility>
 
+#include <hal/DriverStation.h>
 #include <hal/simulation/DriverStationData.h>
 #include <hal/simulation/MockHooks.h>
 
@@ -154,8 +155,12 @@
 }
 
 void DriverStationSim::NotifyNewData() {
+  wpi::Event waitEvent{true};
+  HAL_ProvideNewDataEventHandle(waitEvent.GetHandle());
   HALSIM_NotifyDriverStationNewData();
-  DriverStation::WaitForData();
+  wpi::WaitForObject(waitEvent.GetHandle());
+  HAL_RemoveNewDataEventHandle(waitEvent.GetHandle());
+  frc::DriverStation::RefreshData();
 }
 
 void DriverStationSim::SetSendError(bool shouldSend) {
@@ -229,20 +234,20 @@
   HALSIM_SetJoystickType(stick, type);
 }
 
-void DriverStationSim::SetJoystickName(int stick, const char* name) {
-  HALSIM_SetJoystickName(stick, name);
+void DriverStationSim::SetJoystickName(int stick, std::string_view name) {
+  HALSIM_SetJoystickName(stick, name.data(), name.size());
 }
 
 void DriverStationSim::SetJoystickAxisType(int stick, int axis, int type) {
   HALSIM_SetJoystickAxisType(stick, axis, type);
 }
 
-void DriverStationSim::SetGameSpecificMessage(const char* message) {
-  HALSIM_SetGameSpecificMessage(message);
+void DriverStationSim::SetGameSpecificMessage(std::string_view message) {
+  HALSIM_SetGameSpecificMessage(message.data(), message.size());
 }
 
-void DriverStationSim::SetEventName(const char* name) {
-  HALSIM_SetEventName(name);
+void DriverStationSim::SetEventName(std::string_view name) {
+  HALSIM_SetEventName(name.data(), name.size());
 }
 
 void DriverStationSim::SetMatchType(DriverStation::MatchType type) {
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/ElevatorSim.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/ElevatorSim.cpp
index a2d5c66..529fb1a 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/ElevatorSim.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/ElevatorSim.cpp
@@ -15,19 +15,20 @@
 ElevatorSim::ElevatorSim(const LinearSystem<2, 1, 1>& plant,
                          const DCMotor& gearbox, double gearing,
                          units::meter_t drumRadius, units::meter_t minHeight,
-                         units::meter_t maxHeight,
+                         units::meter_t maxHeight, bool simulateGravity,
                          const std::array<double, 1>& measurementStdDevs)
     : LinearSystemSim(plant, measurementStdDevs),
       m_gearbox(gearbox),
       m_drumRadius(drumRadius),
       m_minHeight(minHeight),
       m_maxHeight(maxHeight),
-      m_gearing(gearing) {}
+      m_gearing(gearing),
+      m_simulateGravity(simulateGravity) {}
 
 ElevatorSim::ElevatorSim(const DCMotor& gearbox, double gearing,
                          units::kilogram_t carriageMass,
                          units::meter_t drumRadius, units::meter_t minHeight,
-                         units::meter_t maxHeight,
+                         units::meter_t maxHeight, bool simulateGravity,
                          const std::array<double, 1>& measurementStdDevs)
     : LinearSystemSim(LinearSystemId::ElevatorSystem(gearbox, carriageMass,
                                                      drumRadius, gearing),
@@ -36,7 +37,8 @@
       m_drumRadius(drumRadius),
       m_minHeight(minHeight),
       m_maxHeight(maxHeight),
-      m_gearing(gearing) {}
+      m_gearing(gearing),
+      m_simulateGravity(simulateGravity) {}
 
 bool ElevatorSim::WouldHitLowerLimit(units::meter_t elevatorHeight) const {
   return elevatorHeight < m_minHeight;
@@ -47,11 +49,11 @@
 }
 
 bool ElevatorSim::HasHitLowerLimit() const {
-  return WouldHitLowerLimit(units::meter_t(m_y(0)));
+  return WouldHitLowerLimit(units::meter_t{m_y(0)});
 }
 
 bool ElevatorSim::HasHitUpperLimit() const {
-  return WouldHitUpperLimit(units::meter_t(m_y(0)));
+  return WouldHitUpperLimit(units::meter_t{m_y(0)});
 }
 
 units::meter_t ElevatorSim::GetPosition() const {
@@ -78,25 +80,27 @@
 }
 
 void ElevatorSim::SetInputVoltage(units::volt_t voltage) {
-  SetInput(Eigen::Vector<double, 1>{voltage.value()});
+  SetInput(Vectord<1>{voltage.value()});
 }
 
-Eigen::Vector<double, 2> ElevatorSim::UpdateX(
-    const Eigen::Vector<double, 2>& currentXhat,
-    const Eigen::Vector<double, 1>& u, units::second_t dt) {
+Vectord<2> ElevatorSim::UpdateX(const Vectord<2>& currentXhat,
+                                const Vectord<1>& u, units::second_t dt) {
   auto updatedXhat = RKDP(
-      [&](const Eigen::Vector<double, 2>& x,
-          const Eigen::Vector<double, 1>& u_) -> Eigen::Vector<double, 2> {
-        return m_plant.A() * x + m_plant.B() * u_ +
-               Eigen::Vector<double, 2>{0.0, -9.8};
+      [&](const Vectord<2>& x, const Vectord<1>& u_) -> Vectord<2> {
+        Vectord<2> xdot = m_plant.A() * x + m_plant.B() * u;
+
+        if (m_simulateGravity) {
+          xdot += Vectord<2>{0.0, -9.8};
+        }
+        return xdot;
       },
       currentXhat, u, dt);
   // Check for collision after updating x-hat.
-  if (WouldHitLowerLimit(units::meter_t(updatedXhat(0)))) {
-    return Eigen::Vector<double, 2>{m_minHeight.value(), 0.0};
+  if (WouldHitLowerLimit(units::meter_t{updatedXhat(0)})) {
+    return Vectord<2>{m_minHeight.value(), 0.0};
   }
-  if (WouldHitUpperLimit(units::meter_t(updatedXhat(0)))) {
-    return Eigen::Vector<double, 2>{m_maxHeight.value(), 0.0};
+  if (WouldHitUpperLimit(units::meter_t{updatedXhat(0)})) {
+    return Vectord<2>{m_maxHeight.value(), 0.0};
   }
   return updatedXhat;
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/FlywheelSim.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/FlywheelSim.cpp
index f4371b1..95dcb9e 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/FlywheelSim.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/FlywheelSim.cpp
@@ -38,5 +38,5 @@
 }
 
 void FlywheelSim::SetInputVoltage(units::volt_t voltage) {
-  SetInput(Eigen::Vector<double, 1>{voltage.value()});
+  SetInput(Vectord<1>{voltage.value()});
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/PS4ControllerSim.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/PS4ControllerSim.cpp
index 3403755..fecac9d 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/PS4ControllerSim.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/PS4ControllerSim.cpp
@@ -13,11 +13,13 @@
     : GenericHIDSim{joystick} {
   SetAxisCount(6);
   SetButtonCount(14);
+  SetPOVCount(1);
 }
 
 PS4ControllerSim::PS4ControllerSim(int port) : GenericHIDSim{port} {
   SetAxisCount(6);
   SetButtonCount(14);
+  SetPOVCount(1);
 }
 
 void PS4ControllerSim::SetLeftX(double value) {
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/PWMSim.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/PWMSim.cpp
index f5d69db..3fafa8e 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/PWMSim.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/PWMSim.cpp
@@ -10,12 +10,16 @@
 #include <hal/simulation/PWMData.h>
 
 #include "frc/PWM.h"
+#include "frc/motorcontrol/PWMMotorController.h"
 
 using namespace frc;
 using namespace frc::sim;
 
 PWMSim::PWMSim(const PWM& pwm) : m_index{pwm.GetChannel()} {}
 
+PWMSim::PWMSim(const PWMMotorController& motorctrl)
+    : m_index{motorctrl.GetChannel()} {}
+
 PWMSim::PWMSim(int channel) : m_index{channel} {}
 
 std::unique_ptr<CallbackStore> PWMSim::RegisterInitializedCallback(
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/PneumaticsBaseSim.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/PneumaticsBaseSim.cpp
new file mode 100644
index 0000000..476d07a
--- /dev/null
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/PneumaticsBaseSim.cpp
@@ -0,0 +1,33 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/simulation/PneumaticsBaseSim.h"
+
+#include "frc/Errors.h"
+#include "frc/PneumaticsModuleType.h"
+#include "frc/simulation/CTREPCMSim.h"
+#include "frc/simulation/REVPHSim.h"
+
+using namespace frc;
+using namespace frc::sim;
+
+PneumaticsBaseSim::PneumaticsBaseSim(int module) : m_index{module} {}
+
+PneumaticsBaseSim::PneumaticsBaseSim(const PneumaticsBase& module)
+    : m_index{module.GetModuleNumber()} {}
+
+std::shared_ptr<PneumaticsBaseSim> PneumaticsBaseSim::GetForType(
+    int module, PneumaticsModuleType type) {
+  switch (type) {
+    case PneumaticsModuleType::REVPH:
+      return std::make_shared<REVPHSim>(module);
+
+    case PneumaticsModuleType::CTREPCM:
+      return std::make_shared<CTREPCMSim>(module);
+
+    default:
+      throw FRC_MakeError(err::InvalidParameter, "{}",
+                          static_cast<int>(module));
+  }
+}
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/REVPHSim.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/REVPHSim.cpp
index ca7384a..df7bc02 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/REVPHSim.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/REVPHSim.cpp
@@ -14,12 +14,12 @@
 using namespace frc;
 using namespace frc::sim;
 
-REVPHSim::REVPHSim() : m_index{SensorUtil::GetDefaultREVPHModule()} {}
+REVPHSim::REVPHSim() : PneumaticsBaseSim{SensorUtil::GetDefaultREVPHModule()} {}
 
-REVPHSim::REVPHSim(int module) : m_index{module} {}
+REVPHSim::REVPHSim(int module) : PneumaticsBaseSim{module} {}
 
 REVPHSim::REVPHSim(const PneumaticsBase& pneumatics)
-    : m_index{pneumatics.GetModuleNumber()} {}
+    : PneumaticsBaseSim{pneumatics} {}
 
 std::unique_ptr<CallbackStore> REVPHSim::RegisterInitializedCallback(
     NotifyCallback callback, bool initialNotify) {
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/RoboRioSim.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/RoboRioSim.cpp
index dc2b557..6d0f809 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/RoboRioSim.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/RoboRioSim.cpp
@@ -39,7 +39,7 @@
 }
 
 units::volt_t RoboRioSim::GetVInVoltage() {
-  return units::volt_t(HALSIM_GetRoboRioVInVoltage());
+  return units::volt_t{HALSIM_GetRoboRioVInVoltage()};
 }
 
 void RoboRioSim::SetVInVoltage(units::volt_t vInVoltage) {
@@ -56,7 +56,7 @@
 }
 
 units::ampere_t RoboRioSim::GetVInCurrent() {
-  return units::ampere_t(HALSIM_GetRoboRioVInCurrent());
+  return units::ampere_t{HALSIM_GetRoboRioVInCurrent()};
 }
 
 void RoboRioSim::SetVInCurrent(units::ampere_t vInCurrent) {
@@ -73,7 +73,7 @@
 }
 
 units::volt_t RoboRioSim::GetUserVoltage6V() {
-  return units::volt_t(HALSIM_GetRoboRioUserVoltage6V());
+  return units::volt_t{HALSIM_GetRoboRioUserVoltage6V()};
 }
 
 void RoboRioSim::SetUserVoltage6V(units::volt_t userVoltage6V) {
@@ -90,7 +90,7 @@
 }
 
 units::ampere_t RoboRioSim::GetUserCurrent6V() {
-  return units::ampere_t(HALSIM_GetRoboRioUserCurrent6V());
+  return units::ampere_t{HALSIM_GetRoboRioUserCurrent6V()};
 }
 
 void RoboRioSim::SetUserCurrent6V(units::ampere_t userCurrent6V) {
@@ -124,7 +124,7 @@
 }
 
 units::volt_t RoboRioSim::GetUserVoltage5V() {
-  return units::volt_t(HALSIM_GetRoboRioUserVoltage5V());
+  return units::volt_t{HALSIM_GetRoboRioUserVoltage5V()};
 }
 
 void RoboRioSim::SetUserVoltage5V(units::volt_t userVoltage5V) {
@@ -141,7 +141,7 @@
 }
 
 units::ampere_t RoboRioSim::GetUserCurrent5V() {
-  return units::ampere_t(HALSIM_GetRoboRioUserCurrent5V());
+  return units::ampere_t{HALSIM_GetRoboRioUserCurrent5V()};
 }
 
 void RoboRioSim::SetUserCurrent5V(units::ampere_t userCurrent5V) {
@@ -175,7 +175,7 @@
 }
 
 units::volt_t RoboRioSim::GetUserVoltage3V3() {
-  return units::volt_t(HALSIM_GetRoboRioUserVoltage3V3());
+  return units::volt_t{HALSIM_GetRoboRioUserVoltage3V3()};
 }
 
 void RoboRioSim::SetUserVoltage3V3(units::volt_t userVoltage3V3) {
@@ -192,7 +192,7 @@
 }
 
 units::ampere_t RoboRioSim::GetUserCurrent3V3() {
-  return units::ampere_t(HALSIM_GetRoboRioUserCurrent3V3());
+  return units::ampere_t{HALSIM_GetRoboRioUserCurrent3V3()};
 }
 
 void RoboRioSim::SetUserCurrent3V3(units::ampere_t userCurrent3V3) {
@@ -277,13 +277,33 @@
 }
 
 units::volt_t RoboRioSim::GetBrownoutVoltage() {
-  return units::volt_t(HALSIM_GetRoboRioBrownoutVoltage());
+  return units::volt_t{HALSIM_GetRoboRioBrownoutVoltage()};
 }
 
 void RoboRioSim::SetBrownoutVoltage(units::volt_t vInVoltage) {
   HALSIM_SetRoboRioBrownoutVoltage(vInVoltage.value());
 }
 
+std::string RoboRioSim::GetSerialNumber() {
+  char serialNum[9];
+  size_t len = HALSIM_GetRoboRioSerialNumber(serialNum, sizeof(serialNum));
+  return std::string(serialNum, len);
+}
+
+void RoboRioSim::SetSerialNumber(std::string_view serialNumber) {
+  HALSIM_SetRoboRioSerialNumber(serialNumber.data(), serialNumber.size());
+}
+
+std::string RoboRioSim::GetComments() {
+  char comments[65];
+  size_t len = HALSIM_GetRoboRioComments(comments, sizeof(comments));
+  return std::string(comments, len);
+}
+
+void RoboRioSim::SetComments(std::string_view comments) {
+  HALSIM_SetRoboRioComments(comments.data(), comments.size());
+}
+
 void RoboRioSim::ResetData() {
   HALSIM_ResetRoboRioData();
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/SingleJointedArmSim.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/SingleJointedArmSim.cpp
index db56434..88e45c6 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/SingleJointedArmSim.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/SingleJointedArmSim.cpp
@@ -18,13 +18,13 @@
 SingleJointedArmSim::SingleJointedArmSim(
     const LinearSystem<2, 1, 1>& system, const DCMotor& gearbox, double gearing,
     units::meter_t armLength, units::radian_t minAngle,
-    units::radian_t maxAngle, units::kilogram_t mass, bool simulateGravity,
+    units::radian_t maxAngle, units::kilogram_t armMass, bool simulateGravity,
     const std::array<double, 1>& measurementStdDevs)
     : LinearSystemSim<2, 1, 1>(system, measurementStdDevs),
       m_r(armLength),
       m_minAngle(minAngle),
       m_maxAngle(maxAngle),
-      m_mass(mass),
+      m_armMass(armMass),
       m_gearbox(gearbox),
       m_gearing(gearing),
       m_simulateGravity(simulateGravity) {}
@@ -32,27 +32,27 @@
 SingleJointedArmSim::SingleJointedArmSim(
     const DCMotor& gearbox, double gearing, units::kilogram_square_meter_t moi,
     units::meter_t armLength, units::radian_t minAngle,
-    units::radian_t maxAngle, units::kilogram_t mass, bool simulateGravity,
+    units::radian_t maxAngle, units::kilogram_t armMass, bool simulateGravity,
     const std::array<double, 1>& measurementStdDevs)
     : SingleJointedArmSim(
           LinearSystemId::SingleJointedArmSystem(gearbox, moi, gearing),
-          gearbox, gearing, armLength, minAngle, maxAngle, mass,
+          gearbox, gearing, armLength, minAngle, maxAngle, armMass,
           simulateGravity, measurementStdDevs) {}
 
 bool SingleJointedArmSim::WouldHitLowerLimit(units::radian_t armAngle) const {
-  return armAngle < m_minAngle;
+  return armAngle <= m_minAngle;
 }
 
 bool SingleJointedArmSim::WouldHitUpperLimit(units::radian_t armAngle) const {
-  return armAngle > m_maxAngle;
+  return armAngle >= m_maxAngle;
 }
 
 bool SingleJointedArmSim::HasHitLowerLimit() const {
-  return WouldHitLowerLimit(units::radian_t(m_y(0)));
+  return WouldHitLowerLimit(units::radian_t{m_y(0)});
 }
 
 bool SingleJointedArmSim::HasHitUpperLimit() const {
-  return WouldHitUpperLimit(units::radian_t(m_y(0)));
+  return WouldHitUpperLimit(units::radian_t{m_y(0)});
 }
 
 units::radian_t SingleJointedArmSim::GetAngle() const {
@@ -72,12 +72,12 @@
 }
 
 void SingleJointedArmSim::SetInputVoltage(units::volt_t voltage) {
-  SetInput(Eigen::Vector<double, 1>{voltage.value()});
+  SetInput(Vectord<1>{voltage.value()});
 }
 
-Eigen::Vector<double, 2> SingleJointedArmSim::UpdateX(
-    const Eigen::Vector<double, 2>& currentXhat,
-    const Eigen::Vector<double, 1>& u, units::second_t dt) {
+Vectord<2> SingleJointedArmSim::UpdateX(const Vectord<2>& currentXhat,
+                                        const Vectord<1>& u,
+                                        units::second_t dt) {
   // Horizontal case:
   // Torque = F * r = I * alpha
   // alpha = F * r / I
@@ -88,25 +88,24 @@
   // We therefore find that f(x, u) = Ax + Bu + [[0] [m * g * r / I *
   // std::cos(theta)]]
 
-  Eigen::Vector<double, 2> updatedXhat = RKDP(
-      [&](const auto& x, const auto& u) -> Eigen::Vector<double, 2> {
-        Eigen::Vector<double, 2> xdot = m_plant.A() * x + m_plant.B() * u;
+  Vectord<2> updatedXhat = RKDP(
+      [&](const auto& x, const auto& u) -> Vectord<2> {
+        Vectord<2> xdot = m_plant.A() * x + m_plant.B() * u;
 
         if (m_simulateGravity) {
-          xdot += Eigen::Vector<double, 2>{
-              0.0, (m_mass * m_r * -9.8 * 3.0 / (m_mass * m_r * m_r) *
-                    std::cos(x(0)))
-                       .value()};
+          xdot += Vectord<2>{0.0, (m_armMass * m_r * -9.8 * 3.0 /
+                                   (m_armMass * m_r * m_r) * std::cos(x(0)))
+                                      .value()};
         }
         return xdot;
       },
       currentXhat, u, dt);
 
   // Check for collisions.
-  if (WouldHitLowerLimit(units::radian_t(updatedXhat(0)))) {
-    return Eigen::Vector<double, 2>{m_minAngle.value(), 0.0};
-  } else if (WouldHitUpperLimit(units::radian_t(updatedXhat(0)))) {
-    return Eigen::Vector<double, 2>{m_maxAngle.value(), 0.0};
+  if (WouldHitLowerLimit(units::radian_t{updatedXhat(0)})) {
+    return Vectord<2>{m_minAngle.value(), 0.0};
+  } else if (WouldHitUpperLimit(units::radian_t{updatedXhat(0)})) {
+    return Vectord<2>{m_maxAngle.value(), 0.0};
   }
   return updatedXhat;
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/SolenoidSim.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/SolenoidSim.cpp
new file mode 100644
index 0000000..29d8207
--- /dev/null
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/SolenoidSim.cpp
@@ -0,0 +1,41 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/simulation/SolenoidSim.h"
+
+#include "frc/PneumaticsBase.h"
+
+using namespace frc;
+using namespace frc::sim;
+
+SolenoidSim::SolenoidSim(std::shared_ptr<PneumaticsBaseSim> moduleSim,
+                         int channel)
+    : m_module{std::move(moduleSim)}, m_channel{channel} {}
+
+SolenoidSim::SolenoidSim(int module, PneumaticsModuleType type, int channel)
+    : m_module{PneumaticsBaseSim::GetForType(module, type)},
+      m_channel{channel} {}
+
+SolenoidSim::SolenoidSim(PneumaticsModuleType type, int channel)
+    : m_module{PneumaticsBaseSim::GetForType(
+          PneumaticsBase::GetDefaultForType(type), type)},
+      m_channel{channel} {}
+
+bool SolenoidSim::GetOutput() const {
+  return m_module->GetSolenoidOutput(m_channel);
+}
+
+void SolenoidSim::SetOutput(bool output) {
+  m_module->SetSolenoidOutput(m_channel, output);
+}
+
+std::unique_ptr<CallbackStore> SolenoidSim::RegisterOutputCallback(
+    NotifyCallback callback, bool initialNotify) {
+  return m_module->RegisterSolenoidOutputCallback(m_channel, callback,
+                                                  initialNotify);
+}
+
+std::shared_ptr<PneumaticsBaseSim> SolenoidSim::GetModuleSim() const {
+  return m_module;
+}
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/XboxControllerSim.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/XboxControllerSim.cpp
index 393c41a..daf48b7 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/XboxControllerSim.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/simulation/XboxControllerSim.cpp
@@ -13,11 +13,13 @@
     : GenericHIDSim{joystick} {
   SetAxisCount(6);
   SetButtonCount(10);
+  SetPOVCount(1);
 }
 
 XboxControllerSim::XboxControllerSim(int port) : GenericHIDSim{port} {
   SetAxisCount(6);
   SetButtonCount(10);
+  SetPOVCount(1);
 }
 
 void XboxControllerSim::SetLeftX(double value) {
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/smartdashboard/Field2d.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/smartdashboard/Field2d.cpp
index 2915a12..ec52e9c 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/smartdashboard/Field2d.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/smartdashboard/Field2d.cpp
@@ -4,6 +4,7 @@
 
 #include "frc/smartdashboard/Field2d.h"
 
+#include <networktables/DoubleArrayTopic.h>
 #include <networktables/NTSendableBuilder.h>
 #include <wpi/sendable/SendableRegistry.h>
 
@@ -57,7 +58,7 @@
       std::make_unique<FieldObject2d>(name, FieldObject2d::private_init{}));
   auto obj = m_objects.back().get();
   if (m_table) {
-    obj->m_entry = m_table->GetEntry(obj->m_name);
+    obj->m_entry = m_table->GetDoubleArrayTopic(obj->m_name).GetEntry({});
   }
   return obj;
 }
@@ -74,7 +75,7 @@
   m_table = builder.GetTable();
   for (auto&& obj : m_objects) {
     std::scoped_lock lock2(obj->m_mutex);
-    obj->m_entry = m_table->GetEntry(obj->m_name);
+    obj->m_entry = m_table->GetDoubleArrayTopic(obj->m_name).GetEntry({});
     obj->UpdateEntry(true);
   }
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/smartdashboard/FieldObject2d.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/smartdashboard/FieldObject2d.cpp
index 93d6d7e..3895e87 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/smartdashboard/FieldObject2d.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/smartdashboard/FieldObject2d.cpp
@@ -6,9 +6,6 @@
 
 #include <vector>
 
-#include <wpi/Endian.h>
-#include <wpi/MathExtras.h>
-
 #include "frc/trajectory/Trajectory.h"
 
 using namespace frc;
@@ -45,7 +42,7 @@
   return m_poses[0];
 }
 
-void FieldObject2d::SetPoses(wpi::span<const Pose2d> poses) {
+void FieldObject2d::SetPoses(std::span<const Pose2d> poses) {
   std::scoped_lock lock(m_mutex);
   m_poses.assign(poses.begin(), poses.end());
   UpdateEntry();
@@ -71,7 +68,7 @@
   return std::vector<Pose2d>(m_poses.begin(), m_poses.end());
 }
 
-wpi::span<const Pose2d> FieldObject2d::GetPoses(
+std::span<const Pose2d> FieldObject2d::GetPoses(
     wpi::SmallVectorImpl<Pose2d>& out) const {
   std::scoped_lock lock(m_mutex);
   UpdateFromEntry();
@@ -83,41 +80,17 @@
   if (!m_entry) {
     return;
   }
-  if (m_poses.size() < (255 / 3)) {
-    wpi::SmallVector<double, 9> arr;
-    for (auto&& pose : m_poses) {
-      auto& translation = pose.Translation();
-      arr.push_back(translation.X().value());
-      arr.push_back(translation.Y().value());
-      arr.push_back(pose.Rotation().Degrees().value());
-    }
-    if (setDefault) {
-      m_entry.SetDefaultDoubleArray(arr);
-    } else {
-      m_entry.ForceSetDoubleArray(arr);
-    }
+  wpi::SmallVector<double, 9> arr;
+  for (auto&& pose : m_poses) {
+    auto& translation = pose.Translation();
+    arr.push_back(translation.X().value());
+    arr.push_back(translation.Y().value());
+    arr.push_back(pose.Rotation().Degrees().value());
+  }
+  if (setDefault) {
+    m_entry.SetDefault(arr);
   } else {
-    // send as raw array of doubles if too big for NT array
-    std::vector<char> arr;
-    arr.resize(m_poses.size() * 3 * 8);
-    char* p = arr.data();
-    for (auto&& pose : m_poses) {
-      auto& translation = pose.Translation();
-      wpi::support::endian::write64be(
-          p, wpi::DoubleToBits(translation.X().value()));
-      p += 8;
-      wpi::support::endian::write64be(
-          p, wpi::DoubleToBits(translation.Y().value()));
-      p += 8;
-      wpi::support::endian::write64be(
-          p, wpi::DoubleToBits(pose.Rotation().Degrees().value()));
-      p += 8;
-    }
-    if (setDefault) {
-      m_entry.SetDefaultRaw({arr.data(), arr.size()});
-    } else {
-      m_entry.ForceSetRaw({arr.data(), arr.size()});
-    }
+    m_entry.Set(arr);
   }
 }
 
@@ -125,46 +98,15 @@
   if (!m_entry) {
     return;
   }
-  auto val = m_entry.GetValue();
-  if (!val) {
+  auto arr = m_entry.Get();
+  auto size = arr.size();
+  if ((size % 3) != 0) {
     return;
   }
-
-  if (val->IsDoubleArray()) {
-    auto arr = val->GetDoubleArray();
-    auto size = arr.size();
-    if ((size % 3) != 0) {
-      return;
-    }
-    m_poses.resize(size / 3);
-    for (size_t i = 0; i < size / 3; ++i) {
-      m_poses[i] =
-          Pose2d{units::meter_t{arr[i * 3 + 0]}, units::meter_t{arr[i * 3 + 1]},
-                 Rotation2d{units::degree_t{arr[i * 3 + 2]}}};
-    }
-  } else if (val->IsRaw()) {
-    // treat it simply as an array of doubles
-    std::string_view data = val->GetRaw();
-
-    // must be triples of doubles
-    auto size = data.size();
-    if ((size % (3 * 8)) != 0) {
-      return;
-    }
-    m_poses.resize(size / (3 * 8));
-    const char* p = data.data();
-    for (size_t i = 0; i < size / (3 * 8); ++i) {
-      double x = wpi::BitsToDouble(
-          wpi::support::endian::readNext<uint64_t, wpi::support::big,
-                                         wpi::support::unaligned>(p));
-      double y = wpi::BitsToDouble(
-          wpi::support::endian::readNext<uint64_t, wpi::support::big,
-                                         wpi::support::unaligned>(p));
-      double rot = wpi::BitsToDouble(
-          wpi::support::endian::readNext<uint64_t, wpi::support::big,
-                                         wpi::support::unaligned>(p));
-      m_poses[i] = Pose2d{units::meter_t{x}, units::meter_t{y},
-                          Rotation2d{units::degree_t{rot}}};
-    }
+  m_poses.resize(size / 3);
+  for (size_t i = 0; i < size / 3; ++i) {
+    m_poses[i] =
+        Pose2d{units::meter_t{arr[i * 3 + 0]}, units::meter_t{arr[i * 3 + 1]},
+               units::degree_t{arr[i * 3 + 2]}};
   }
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/smartdashboard/Mechanism2d.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/smartdashboard/Mechanism2d.cpp
index bfa827a..355cbc6 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/smartdashboard/Mechanism2d.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/smartdashboard/Mechanism2d.cpp
@@ -5,13 +5,14 @@
 #include "frc/smartdashboard/Mechanism2d.h"
 
 #include <cstdio>
+#include <string_view>
 
 #include <networktables/NTSendableBuilder.h>
 
 using namespace frc;
 
-static constexpr char kBackgroundColor[] = "backgroundColor";
-static constexpr char kDims[] = "dims";
+static constexpr std::string_view kBackgroundColor = "backgroundColor";
+static constexpr std::string_view kDims = "dims";
 
 Mechanism2d::Mechanism2d(double width, double height,
                          const Color8Bit& backgroundColor)
@@ -34,10 +35,9 @@
 }
 
 void Mechanism2d::SetBackgroundColor(const Color8Bit& color) {
-  std::snprintf(m_color, sizeof(m_color), "#%02X%02X%02X", color.red,
-                color.green, color.blue);
-  if (m_table) {
-    m_table->GetEntry(kBackgroundColor).SetString(m_color);
+  m_color = color.HexString();
+  if (m_colorPub) {
+    m_colorPub.Set(m_color);
   }
 }
 
@@ -46,8 +46,10 @@
 
   std::scoped_lock lock(m_mutex);
   m_table = builder.GetTable();
-  m_table->GetEntry(kDims).SetDoubleArray({m_width, m_height});
-  m_table->GetEntry(kBackgroundColor).SetString(m_color);
+  m_dimsPub = m_table->GetDoubleArrayTopic(kDims).Publish();
+  m_dimsPub.Set({{m_width, m_height}});
+  m_colorPub = m_table->GetStringTopic(kBackgroundColor).Publish();
+  m_colorPub.Set(m_color);
   for (const auto& entry : m_roots) {
     const auto& root = entry.getValue().get();
     root->Update(m_table->GetSubTable(entry.getKey()));
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/smartdashboard/MechanismLigament2d.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/smartdashboard/MechanismLigament2d.cpp
index b49bc99..a43aa16 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/smartdashboard/MechanismLigament2d.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/smartdashboard/MechanismLigament2d.cpp
@@ -12,7 +12,7 @@
                                          units::degree_t angle,
                                          double lineWeight,
                                          const frc::Color8Bit& color)
-    : MechanismObject2d(name),
+    : MechanismObject2d{name},
       m_length{length},
       m_angle{angle.value()},
       m_weight{lineWeight} {
@@ -21,38 +21,48 @@
 
 void MechanismLigament2d::UpdateEntries(
     std::shared_ptr<nt::NetworkTable> table) {
-  table->GetEntry(".type").SetString("line");
+  m_typePub = table->GetStringTopic(".type").Publish();
+  m_typePub.Set("line");
 
-  m_colorEntry = table->GetEntry("color");
-  m_angleEntry = table->GetEntry("angle");
-  m_weightEntry = table->GetEntry("weight");
-  m_lengthEntry = table->GetEntry("length");
-  Flush();
+  m_colorEntry = table->GetStringTopic("color").GetEntry("");
+  m_colorEntry.Set(m_color);
+  m_angleEntry = table->GetDoubleTopic("angle").GetEntry(0.0);
+  m_angleEntry.Set(m_angle);
+  m_weightEntry = table->GetDoubleTopic("weight").GetEntry(0.0);
+  m_weightEntry.Set(m_weight);
+  m_lengthEntry = table->GetDoubleTopic("length").GetEntry(0.0);
+  m_lengthEntry.Set(m_length);
 }
 
 void MechanismLigament2d::SetColor(const Color8Bit& color) {
   std::scoped_lock lock(m_mutex);
   std::snprintf(m_color, sizeof(m_color), "#%02X%02X%02X", color.red,
                 color.green, color.blue);
-  Flush();
+  if (m_colorEntry) {
+    m_colorEntry.Set(m_color);
+  }
 }
 
 void MechanismLigament2d::SetAngle(units::degree_t angle) {
   std::scoped_lock lock(m_mutex);
   m_angle = angle.value();
-  Flush();
+  if (m_angleEntry) {
+    m_angleEntry.Set(m_angle);
+  }
 }
 
 void MechanismLigament2d::SetLineWeight(double lineWidth) {
   std::scoped_lock lock(m_mutex);
   m_weight = lineWidth;
-  Flush();
+  if (m_weightEntry) {
+    m_weightEntry.Set(m_weight);
+  }
 }
 
 Color8Bit MechanismLigament2d::GetColor() {
   std::scoped_lock lock(m_mutex);
   if (m_colorEntry) {
-    auto color = m_colorEntry.GetString("");
+    auto color = m_colorEntry.Get();
     std::strncpy(m_color, color.c_str(), sizeof(m_color));
     m_color[sizeof(m_color) - 1] = '\0';
   }
@@ -64,7 +74,7 @@
 double MechanismLigament2d::GetAngle() {
   std::scoped_lock lock(m_mutex);
   if (m_angleEntry) {
-    m_angle = m_angleEntry.GetDouble(0.0);
+    m_angle = m_angleEntry.Get();
   }
   return m_angle;
 }
@@ -72,7 +82,7 @@
 double MechanismLigament2d::GetLength() {
   std::scoped_lock lock(m_mutex);
   if (m_lengthEntry) {
-    m_length = m_lengthEntry.GetDouble(0.0);
+    m_length = m_lengthEntry.Get();
   }
   return m_length;
 }
@@ -80,7 +90,7 @@
 double MechanismLigament2d::GetLineWeight() {
   std::scoped_lock lock(m_mutex);
   if (m_weightEntry) {
-    m_weight = m_weightEntry.GetDouble(0.0);
+    m_weight = m_weightEntry.Get();
   }
   return m_weight;
 }
@@ -88,16 +98,7 @@
 void MechanismLigament2d::SetLength(double length) {
   std::scoped_lock lock(m_mutex);
   m_length = length;
-  Flush();
-}
-
-#define SAFE_WRITE(data, Type)           \
-  if (m_##data##Entry) {                 \
-    m_##data##Entry.Set##Type(m_##data); \
+  if (m_lengthEntry) {
+    m_lengthEntry.Set(length);
   }
-void MechanismLigament2d::Flush() {
-  SAFE_WRITE(color, String)
-  SAFE_WRITE(angle, Double)
-  SAFE_WRITE(length, Double)
-  SAFE_WRITE(weight, Double)
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/smartdashboard/MechanismRoot2d.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/smartdashboard/MechanismRoot2d.cpp
index 637b24b..a40f5ee 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/smartdashboard/MechanismRoot2d.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/smartdashboard/MechanismRoot2d.cpp
@@ -10,7 +10,7 @@
 
 MechanismRoot2d::MechanismRoot2d(std::string_view name, double x, double y,
                                  const private_init&)
-    : MechanismObject2d(name), m_x{x}, m_y{y} {}
+    : MechanismObject2d{name}, m_x{x}, m_y{y} {}
 
 void MechanismRoot2d::SetPosition(double x, double y) {
   std::scoped_lock lock(m_mutex);
@@ -20,16 +20,16 @@
 }
 
 void MechanismRoot2d::UpdateEntries(std::shared_ptr<nt::NetworkTable> table) {
-  m_xEntry = table->GetEntry("x");
-  m_yEntry = table->GetEntry("y");
+  m_xPub = table->GetDoubleTopic("x").Publish();
+  m_yPub = table->GetDoubleTopic("y").Publish();
   Flush();
 }
 
 inline void MechanismRoot2d::Flush() {
-  if (m_xEntry) {
-    m_xEntry.SetDouble(m_x);
+  if (m_xPub) {
+    m_xPub.Set(m_x);
   }
-  if (m_yEntry) {
-    m_yEntry.SetDouble(m_y);
+  if (m_yPub) {
+    m_yPub.Set(m_y);
   }
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/smartdashboard/SendableBuilderImpl.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/smartdashboard/SendableBuilderImpl.cpp
index 48af198..79b0e6e 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/smartdashboard/SendableBuilderImpl.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/smartdashboard/SendableBuilderImpl.cpp
@@ -4,16 +4,38 @@
 
 #include "frc/smartdashboard/SendableBuilderImpl.h"
 
+#include <networktables/BooleanArrayTopic.h>
+#include <networktables/BooleanTopic.h>
+#include <networktables/DoubleArrayTopic.h>
+#include <networktables/DoubleTopic.h>
+#include <networktables/FloatArrayTopic.h>
+#include <networktables/FloatTopic.h>
+#include <networktables/IntegerArrayTopic.h>
+#include <networktables/IntegerTopic.h>
+#include <networktables/RawTopic.h>
+#include <networktables/StringArrayTopic.h>
 #include <ntcore_cpp.h>
-#include <wpi/SmallString.h>
+#include <wpi/SmallVector.h>
 
 #include "frc/smartdashboard/SmartDashboard.h"
 
 using namespace frc;
 
+template <typename Topic>
+void SendableBuilderImpl::PropertyImpl<Topic>::Update(bool controllable,
+                                                      int64_t time) {
+  if (controllable && sub && updateLocal) {
+    updateLocal(sub);
+  }
+  if (pub && updateNetwork) {
+    updateNetwork(pub, time);
+  }
+}
+
 void SendableBuilderImpl::SetTable(std::shared_ptr<nt::NetworkTable> table) {
   m_table = table;
-  m_controllableEntry = table->GetEntry(".controllable");
+  m_controllablePublisher = table->GetBooleanTopic(".controllable").Publish();
+  m_controllablePublisher.SetDefault(false);
 }
 
 std::shared_ptr<nt::NetworkTable> SendableBuilderImpl::GetTable() {
@@ -31,9 +53,7 @@
 void SendableBuilderImpl::Update() {
   uint64_t time = nt::Now();
   for (auto& property : m_properties) {
-    if (property.update) {
-      property.update(property.entry, time);
-    }
+    property->Update(m_controllable, time);
   }
   for (auto& updateTable : m_updateTables) {
     updateTable();
@@ -41,20 +61,16 @@
 }
 
 void SendableBuilderImpl::StartListeners() {
-  for (auto& property : m_properties) {
-    property.StartListener();
-  }
-  if (m_controllableEntry) {
-    m_controllableEntry.SetBoolean(true);
+  m_controllable = true;
+  if (m_controllablePublisher) {
+    m_controllablePublisher.Set(true);
   }
 }
 
 void SendableBuilderImpl::StopListeners() {
-  for (auto& property : m_properties) {
-    property.StopListener();
-  }
-  if (m_controllableEntry) {
-    m_controllableEntry.SetBoolean(false);
+  m_controllable = false;
+  if (m_controllablePublisher) {
+    m_controllablePublisher.Set(false);
   }
 }
 
@@ -77,11 +93,17 @@
 }
 
 void SendableBuilderImpl::SetSmartDashboardType(std::string_view type) {
-  m_table->GetEntry(".type").SetString(type);
+  if (!m_typePublisher) {
+    m_typePublisher = m_table->GetStringTopic(".type").Publish();
+  }
+  m_typePublisher.Set(type);
 }
 
 void SendableBuilderImpl::SetActuator(bool value) {
-  m_table->GetEntry(".actuator").SetBoolean(value);
+  if (!m_actuatorPublisher) {
+    m_actuatorPublisher = m_table->GetBooleanTopic(".actuator").Publish();
+  }
+  m_actuatorPublisher.Set(value);
   m_actuator = value;
 }
 
@@ -89,357 +111,229 @@
   m_safeState = func;
 }
 
-void SendableBuilderImpl::SetUpdateTable(std::function<void()> func) {
+void SendableBuilderImpl::SetUpdateTable(wpi::unique_function<void()> func) {
   m_updateTables.emplace_back(std::move(func));
 }
 
-nt::NetworkTableEntry SendableBuilderImpl::GetEntry(std::string_view key) {
-  return m_table->GetEntry(key);
+nt::Topic SendableBuilderImpl::GetTopic(std::string_view key) {
+  return m_table->GetTopic(key);
+}
+
+template <typename Topic, typename Getter, typename Setter>
+void SendableBuilderImpl::AddPropertyImpl(Topic topic, Getter getter,
+                                          Setter setter) {
+  auto prop = std::make_unique<PropertyImpl<Topic>>();
+  if (getter) {
+    prop->pub = topic.Publish();
+    prop->updateNetwork = [=](auto& pub, int64_t time) {
+      pub.Set(getter(), time);
+    };
+  }
+  if (setter) {
+    prop->sub =
+        topic.Subscribe({}, {.excludePublisher = prop->pub.GetHandle()});
+    prop->updateLocal = [=](auto& sub) {
+      for (auto&& val : sub.ReadQueue()) {
+        setter(val.value);
+      }
+    };
+  }
+  m_properties.emplace_back(std::move(prop));
 }
 
 void SendableBuilderImpl::AddBooleanProperty(std::string_view key,
                                              std::function<bool()> getter,
                                              std::function<void(bool)> setter) {
-  m_properties.emplace_back(*m_table, key);
-  if (getter) {
-    m_properties.back().update = [=](nt::NetworkTableEntry entry,
-                                     uint64_t time) {
-      entry.SetValue(nt::Value::MakeBoolean(getter(), time));
-    };
-  }
-  if (setter) {
-    m_properties.back().createListener =
-        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
-      return entry.AddListener(
-          [=](const nt::EntryNotification& event) {
-            if (!event.value->IsBoolean()) {
-              return;
-            }
-            SmartDashboard::PostListenerTask(
-                [=] { setter(event.value->GetBoolean()); });
-          },
-          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
-    };
-  }
+  AddPropertyImpl(m_table->GetBooleanTopic(key), std::move(getter),
+                  std::move(setter));
+}
+
+void SendableBuilderImpl::AddIntegerProperty(
+    std::string_view key, std::function<int64_t()> getter,
+    std::function<void(int64_t)> setter) {
+  AddPropertyImpl(m_table->GetIntegerTopic(key), std::move(getter),
+                  std::move(setter));
+}
+
+void SendableBuilderImpl::AddFloatProperty(std::string_view key,
+                                           std::function<float()> getter,
+                                           std::function<void(float)> setter) {
+  AddPropertyImpl(m_table->GetFloatTopic(key), std::move(getter),
+                  std::move(setter));
 }
 
 void SendableBuilderImpl::AddDoubleProperty(
     std::string_view key, std::function<double()> getter,
     std::function<void(double)> setter) {
-  m_properties.emplace_back(*m_table, key);
-  if (getter) {
-    m_properties.back().update = [=](nt::NetworkTableEntry entry,
-                                     uint64_t time) {
-      entry.SetValue(nt::Value::MakeDouble(getter(), time));
-    };
-  }
-  if (setter) {
-    m_properties.back().createListener =
-        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
-      return entry.AddListener(
-          [=](const nt::EntryNotification& event) {
-            if (!event.value->IsDouble()) {
-              return;
-            }
-            SmartDashboard::PostListenerTask(
-                [=] { setter(event.value->GetDouble()); });
-          },
-          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
-    };
-  }
+  AddPropertyImpl(m_table->GetDoubleTopic(key), std::move(getter),
+                  std::move(setter));
 }
 
 void SendableBuilderImpl::AddStringProperty(
     std::string_view key, std::function<std::string()> getter,
     std::function<void(std::string_view)> setter) {
-  m_properties.emplace_back(*m_table, key);
-  if (getter) {
-    m_properties.back().update = [=](nt::NetworkTableEntry entry,
-                                     uint64_t time) {
-      entry.SetValue(nt::Value::MakeString(getter(), time));
-    };
-  }
-  if (setter) {
-    m_properties.back().createListener =
-        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
-      return entry.AddListener(
-          [=](const nt::EntryNotification& event) {
-            if (!event.value->IsString()) {
-              return;
-            }
-            SmartDashboard::PostListenerTask(
-                [=] { setter(event.value->GetString()); });
-          },
-          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
-    };
-  }
+  AddPropertyImpl(m_table->GetStringTopic(key), std::move(getter),
+                  std::move(setter));
 }
 
 void SendableBuilderImpl::AddBooleanArrayProperty(
     std::string_view key, std::function<std::vector<int>()> getter,
-    std::function<void(wpi::span<const int>)> setter) {
-  m_properties.emplace_back(*m_table, key);
-  if (getter) {
-    m_properties.back().update = [=](nt::NetworkTableEntry entry,
-                                     uint64_t time) {
-      entry.SetValue(nt::Value::MakeBooleanArray(getter(), time));
-    };
-  }
-  if (setter) {
-    m_properties.back().createListener =
-        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
-      return entry.AddListener(
-          [=](const nt::EntryNotification& event) {
-            if (!event.value->IsBooleanArray()) {
-              return;
-            }
-            SmartDashboard::PostListenerTask(
-                [=] { setter(event.value->GetBooleanArray()); });
-          },
-          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
-    };
-  }
+    std::function<void(std::span<const int>)> setter) {
+  AddPropertyImpl(m_table->GetBooleanArrayTopic(key), std::move(getter),
+                  std::move(setter));
+}
+
+void SendableBuilderImpl::AddIntegerArrayProperty(
+    std::string_view key, std::function<std::vector<int64_t>()> getter,
+    std::function<void(std::span<const int64_t>)> setter) {
+  AddPropertyImpl(m_table->GetIntegerArrayTopic(key), std::move(getter),
+                  std::move(setter));
+}
+
+void SendableBuilderImpl::AddFloatArrayProperty(
+    std::string_view key, std::function<std::vector<float>()> getter,
+    std::function<void(std::span<const float>)> setter) {
+  AddPropertyImpl(m_table->GetFloatArrayTopic(key), std::move(getter),
+                  std::move(setter));
 }
 
 void SendableBuilderImpl::AddDoubleArrayProperty(
     std::string_view key, std::function<std::vector<double>()> getter,
-    std::function<void(wpi::span<const double>)> setter) {
-  m_properties.emplace_back(*m_table, key);
-  if (getter) {
-    m_properties.back().update = [=](nt::NetworkTableEntry entry,
-                                     uint64_t time) {
-      entry.SetValue(nt::Value::MakeDoubleArray(getter(), time));
-    };
-  }
-  if (setter) {
-    m_properties.back().createListener =
-        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
-      return entry.AddListener(
-          [=](const nt::EntryNotification& event) {
-            if (!event.value->IsDoubleArray()) {
-              return;
-            }
-            SmartDashboard::PostListenerTask(
-                [=] { setter(event.value->GetDoubleArray()); });
-          },
-          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
-    };
-  }
+    std::function<void(std::span<const double>)> setter) {
+  AddPropertyImpl(m_table->GetDoubleArrayTopic(key), std::move(getter),
+                  std::move(setter));
 }
 
 void SendableBuilderImpl::AddStringArrayProperty(
     std::string_view key, std::function<std::vector<std::string>()> getter,
-    std::function<void(wpi::span<const std::string>)> setter) {
-  m_properties.emplace_back(*m_table, key);
-  if (getter) {
-    m_properties.back().update = [=](nt::NetworkTableEntry entry,
-                                     uint64_t time) {
-      entry.SetValue(nt::Value::MakeStringArray(getter(), time));
-    };
-  }
-  if (setter) {
-    m_properties.back().createListener =
-        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
-      return entry.AddListener(
-          [=](const nt::EntryNotification& event) {
-            if (!event.value->IsStringArray()) {
-              return;
-            }
-            SmartDashboard::PostListenerTask(
-                [=] { setter(event.value->GetStringArray()); });
-          },
-          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
-    };
-  }
+    std::function<void(std::span<const std::string>)> setter) {
+  AddPropertyImpl(m_table->GetStringArrayTopic(key), std::move(getter),
+                  std::move(setter));
 }
 
 void SendableBuilderImpl::AddRawProperty(
-    std::string_view key, std::function<std::string()> getter,
-    std::function<void(std::string_view)> setter) {
-  m_properties.emplace_back(*m_table, key);
+    std::string_view key, std::string_view typeString,
+    std::function<std::vector<uint8_t>()> getter,
+    std::function<void(std::span<const uint8_t>)> setter) {
+  auto topic = m_table->GetRawTopic(key);
+  auto prop = std::make_unique<PropertyImpl<nt::RawTopic>>();
   if (getter) {
-    m_properties.back().update = [=](nt::NetworkTableEntry entry,
-                                     uint64_t time) {
-      entry.SetValue(nt::Value::MakeRaw(getter(), time));
+    prop->pub = topic.Publish(typeString);
+    prop->updateNetwork = [=](auto& pub, int64_t time) {
+      pub.Set(getter(), time);
     };
   }
   if (setter) {
-    m_properties.back().createListener =
-        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
-      return entry.AddListener(
-          [=](const nt::EntryNotification& event) {
-            if (!event.value->IsRaw()) {
-              return;
-            }
-            SmartDashboard::PostListenerTask(
-                [=] { setter(event.value->GetRaw()); });
-          },
-          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
+    prop->sub = topic.Subscribe(typeString, {},
+                                {.excludePublisher = prop->pub.GetHandle()});
+    prop->updateLocal = [=](auto& sub) {
+      for (auto&& val : sub.ReadQueue()) {
+        setter(val.value);
+      }
     };
   }
+  m_properties.emplace_back(std::move(prop));
 }
 
-void SendableBuilderImpl::AddValueProperty(
-    std::string_view key, std::function<std::shared_ptr<nt::Value>()> getter,
-    std::function<void(std::shared_ptr<nt::Value>)> setter) {
-  m_properties.emplace_back(*m_table, key);
+template <typename T, size_t Size, typename Topic, typename Getter,
+          typename Setter>
+void SendableBuilderImpl::AddSmallPropertyImpl(Topic topic, Getter getter,
+                                               Setter setter) {
+  auto prop = std::make_unique<PropertyImpl<Topic>>();
   if (getter) {
-    m_properties.back().update = [=](nt::NetworkTableEntry entry,
-                                     uint64_t time) {
-      entry.SetValue(getter());
+    prop->pub = topic.Publish();
+    prop->updateNetwork = [=](auto& pub, int64_t time) {
+      wpi::SmallVector<T, Size> buf;
+      pub.Set(getter(buf), time);
     };
   }
   if (setter) {
-    m_properties.back().createListener =
-        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
-      return entry.AddListener(
-          [=](const nt::EntryNotification& event) {
-            SmartDashboard::PostListenerTask([=] { setter(event.value); });
-          },
-          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
+    prop->sub =
+        topic.Subscribe({}, {.excludePublisher = prop->pub.GetHandle()});
+    prop->updateLocal = [=](auto& sub) {
+      for (auto&& val : sub.ReadQueue()) {
+        setter(val.value);
+      }
     };
   }
+  m_properties.emplace_back(std::move(prop));
 }
 
 void SendableBuilderImpl::AddSmallStringProperty(
     std::string_view key,
     std::function<std::string_view(wpi::SmallVectorImpl<char>& buf)> getter,
     std::function<void(std::string_view)> setter) {
-  m_properties.emplace_back(*m_table, key);
-  if (getter) {
-    m_properties.back().update = [=](nt::NetworkTableEntry entry,
-                                     uint64_t time) {
-      wpi::SmallString<128> buf;
-      entry.SetValue(nt::Value::MakeString(getter(buf), time));
-    };
-  }
-  if (setter) {
-    m_properties.back().createListener =
-        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
-      return entry.AddListener(
-          [=](const nt::EntryNotification& event) {
-            if (!event.value->IsString()) {
-              return;
-            }
-            SmartDashboard::PostListenerTask(
-                [=] { setter(event.value->GetString()); });
-          },
-          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
-    };
-  }
+  AddSmallPropertyImpl<char, 128>(m_table->GetStringTopic(key),
+                                  std::move(getter), std::move(setter));
 }
 
 void SendableBuilderImpl::AddSmallBooleanArrayProperty(
     std::string_view key,
-    std::function<wpi::span<const int>(wpi::SmallVectorImpl<int>& buf)> getter,
-    std::function<void(wpi::span<const int>)> setter) {
-  m_properties.emplace_back(*m_table, key);
-  if (getter) {
-    m_properties.back().update = [=](nt::NetworkTableEntry entry,
-                                     uint64_t time) {
-      wpi::SmallVector<int, 16> buf;
-      entry.SetValue(nt::Value::MakeBooleanArray(getter(buf), time));
-    };
-  }
-  if (setter) {
-    m_properties.back().createListener =
-        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
-      return entry.AddListener(
-          [=](const nt::EntryNotification& event) {
-            if (!event.value->IsBooleanArray()) {
-              return;
-            }
-            SmartDashboard::PostListenerTask(
-                [=] { setter(event.value->GetBooleanArray()); });
-          },
-          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
-    };
-  }
+    std::function<std::span<const int>(wpi::SmallVectorImpl<int>& buf)> getter,
+    std::function<void(std::span<const int>)> setter) {
+  AddSmallPropertyImpl<int, 16>(m_table->GetBooleanArrayTopic(key),
+                                std::move(getter), std::move(setter));
+}
+
+void SendableBuilderImpl::AddSmallIntegerArrayProperty(
+    std::string_view key,
+    std::function<std::span<const int64_t>(wpi::SmallVectorImpl<int64_t>& buf)>
+        getter,
+    std::function<void(std::span<const int64_t>)> setter) {
+  AddSmallPropertyImpl<int64_t, 16>(m_table->GetIntegerArrayTopic(key),
+                                    std::move(getter), std::move(setter));
+}
+
+void SendableBuilderImpl::AddSmallFloatArrayProperty(
+    std::string_view key,
+    std::function<std::span<const float>(wpi::SmallVectorImpl<float>& buf)>
+        getter,
+    std::function<void(std::span<const float>)> setter) {
+  AddSmallPropertyImpl<float, 16>(m_table->GetFloatArrayTopic(key),
+                                  std::move(getter), std::move(setter));
 }
 
 void SendableBuilderImpl::AddSmallDoubleArrayProperty(
     std::string_view key,
-    std::function<wpi::span<const double>(wpi::SmallVectorImpl<double>& buf)>
+    std::function<std::span<const double>(wpi::SmallVectorImpl<double>& buf)>
         getter,
-    std::function<void(wpi::span<const double>)> setter) {
-  m_properties.emplace_back(*m_table, key);
-  if (getter) {
-    m_properties.back().update = [=](nt::NetworkTableEntry entry,
-                                     uint64_t time) {
-      wpi::SmallVector<double, 16> buf;
-      entry.SetValue(nt::Value::MakeDoubleArray(getter(buf), time));
-    };
-  }
-  if (setter) {
-    m_properties.back().createListener =
-        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
-      return entry.AddListener(
-          [=](const nt::EntryNotification& event) {
-            if (!event.value->IsDoubleArray()) {
-              return;
-            }
-            SmartDashboard::PostListenerTask(
-                [=] { setter(event.value->GetDoubleArray()); });
-          },
-          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
-    };
-  }
+    std::function<void(std::span<const double>)> setter) {
+  AddSmallPropertyImpl<double, 16>(m_table->GetDoubleArrayTopic(key),
+                                   std::move(getter), std::move(setter));
 }
 
 void SendableBuilderImpl::AddSmallStringArrayProperty(
     std::string_view key,
     std::function<
-        wpi::span<const std::string>(wpi::SmallVectorImpl<std::string>& buf)>
+        std::span<const std::string>(wpi::SmallVectorImpl<std::string>& buf)>
         getter,
-    std::function<void(wpi::span<const std::string>)> setter) {
-  m_properties.emplace_back(*m_table, key);
-  if (getter) {
-    m_properties.back().update = [=](nt::NetworkTableEntry entry,
-                                     uint64_t time) {
-      wpi::SmallVector<std::string, 16> buf;
-      entry.SetValue(nt::Value::MakeStringArray(getter(buf), time));
-    };
-  }
-  if (setter) {
-    m_properties.back().createListener =
-        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
-      return entry.AddListener(
-          [=](const nt::EntryNotification& event) {
-            if (!event.value->IsStringArray()) {
-              return;
-            }
-            SmartDashboard::PostListenerTask(
-                [=] { setter(event.value->GetStringArray()); });
-          },
-          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
-    };
-  }
+    std::function<void(std::span<const std::string>)> setter) {
+  AddSmallPropertyImpl<std::string, 16>(m_table->GetStringArrayTopic(key),
+                                        std::move(getter), std::move(setter));
 }
 
 void SendableBuilderImpl::AddSmallRawProperty(
-    std::string_view key,
-    std::function<std::string_view(wpi::SmallVectorImpl<char>& buf)> getter,
-    std::function<void(std::string_view)> setter) {
-  m_properties.emplace_back(*m_table, key);
+    std::string_view key, std::string_view typeString,
+    std::function<std::span<uint8_t>(wpi::SmallVectorImpl<uint8_t>& buf)>
+        getter,
+    std::function<void(std::span<const uint8_t>)> setter) {
+  auto topic = m_table->GetRawTopic(key);
+  auto prop = std::make_unique<PropertyImpl<nt::RawTopic>>();
   if (getter) {
-    m_properties.back().update = [=](nt::NetworkTableEntry entry,
-                                     uint64_t time) {
-      wpi::SmallVector<char, 128> buf;
-      entry.SetValue(nt::Value::MakeRaw(getter(buf), time));
+    prop->pub = topic.Publish(typeString);
+    prop->updateNetwork = [=](auto& pub, int64_t time) {
+      wpi::SmallVector<uint8_t, 128> buf;
+      pub.Set(getter(buf), time);
     };
   }
   if (setter) {
-    m_properties.back().createListener =
-        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
-      return entry.AddListener(
-          [=](const nt::EntryNotification& event) {
-            if (!event.value->IsRaw()) {
-              return;
-            }
-            SmartDashboard::PostListenerTask(
-                [=] { setter(event.value->GetRaw()); });
-          },
-          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
+    prop->sub = topic.Subscribe(typeString, {},
+                                {.excludePublisher = prop->pub.GetHandle()});
+    prop->updateLocal = [=](auto& sub) {
+      for (auto&& val : sub.ReadQueue()) {
+        setter(val.value);
+      }
     };
   }
+  m_properties.emplace_back(std::move(prop));
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/smartdashboard/SendableChooserBase.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/smartdashboard/SendableChooserBase.cpp
index 550d40c..9fa5b69 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/smartdashboard/SendableChooserBase.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/smartdashboard/SendableChooserBase.cpp
@@ -19,7 +19,8 @@
       m_defaultChoice(std::move(oth.m_defaultChoice)),
       m_selected(std::move(oth.m_selected)),
       m_haveSelected(std::move(oth.m_haveSelected)),
-      m_activeEntries(std::move(oth.m_activeEntries)),
+      m_instancePubs(std::move(oth.m_instancePubs)),
+      m_activePubs(std::move(oth.m_activePubs)),
       m_instance(std::move(oth.m_instance)) {}
 
 SendableChooserBase& SendableChooserBase::operator=(SendableChooserBase&& oth) {
@@ -28,7 +29,8 @@
   m_defaultChoice = std::move(oth.m_defaultChoice);
   m_selected = std::move(oth.m_selected);
   m_haveSelected = std::move(oth.m_haveSelected);
-  m_activeEntries = std::move(oth.m_activeEntries);
+  m_instancePubs = std::move(oth.m_instancePubs);
+  m_activePubs = std::move(oth.m_activePubs);
   m_instance = std::move(oth.m_instance);
   return *this;
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/smartdashboard/SmartDashboard.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/smartdashboard/SmartDashboard.cpp
index 5088394..e6991d4 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cpp/smartdashboard/SmartDashboard.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/smartdashboard/SmartDashboard.cpp
@@ -70,29 +70,13 @@
   return GetInstance().table->GetEntry(key).IsPersistent();
 }
 
-void SmartDashboard::SetFlags(std::string_view key, unsigned int flags) {
-  GetInstance().table->GetEntry(key).SetFlags(flags);
-}
-
-void SmartDashboard::ClearFlags(std::string_view key, unsigned int flags) {
-  GetInstance().table->GetEntry(key).ClearFlags(flags);
-}
-
-unsigned int SmartDashboard::GetFlags(std::string_view key) {
-  return GetInstance().table->GetEntry(key).GetFlags();
-}
-
-void SmartDashboard::Delete(std::string_view key) {
-  GetInstance().table->Delete(key);
-}
-
 nt::NetworkTableEntry SmartDashboard::GetEntry(std::string_view key) {
   return GetInstance().table->GetEntry(key);
 }
 
 void SmartDashboard::PutData(std::string_view key, wpi::Sendable* data) {
   if (!data) {
-    throw FRC_MakeError(err::NullParameter, "{}", "value");
+    throw FRC_MakeError(err::NullParameter, "value");
   }
   auto& inst = GetInstance();
   std::scoped_lock lock(inst.tablesToDataMutex);
@@ -112,7 +96,7 @@
 
 void SmartDashboard::PutData(wpi::Sendable* value) {
   if (!value) {
-    throw FRC_MakeError(err::NullParameter, "{}", "value");
+    throw FRC_MakeError(err::NullParameter, "value");
   }
   auto name = wpi::SendableRegistry::GetName(value);
   if (!name.empty()) {
@@ -173,76 +157,77 @@
 }
 
 bool SmartDashboard::PutBooleanArray(std::string_view key,
-                                     wpi::span<const int> value) {
+                                     std::span<const int> value) {
   return GetInstance().table->GetEntry(key).SetBooleanArray(value);
 }
 
 bool SmartDashboard::SetDefaultBooleanArray(std::string_view key,
-                                            wpi::span<const int> defaultValue) {
+                                            std::span<const int> defaultValue) {
   return GetInstance().table->GetEntry(key).SetDefaultBooleanArray(
       defaultValue);
 }
 
 std::vector<int> SmartDashboard::GetBooleanArray(
-    std::string_view key, wpi::span<const int> defaultValue) {
+    std::string_view key, std::span<const int> defaultValue) {
   return GetInstance().table->GetEntry(key).GetBooleanArray(defaultValue);
 }
 
 bool SmartDashboard::PutNumberArray(std::string_view key,
-                                    wpi::span<const double> value) {
+                                    std::span<const double> value) {
   return GetInstance().table->GetEntry(key).SetDoubleArray(value);
 }
 
 bool SmartDashboard::SetDefaultNumberArray(
-    std::string_view key, wpi::span<const double> defaultValue) {
+    std::string_view key, std::span<const double> defaultValue) {
   return GetInstance().table->GetEntry(key).SetDefaultDoubleArray(defaultValue);
 }
 
 std::vector<double> SmartDashboard::GetNumberArray(
-    std::string_view key, wpi::span<const double> defaultValue) {
+    std::string_view key, std::span<const double> defaultValue) {
   return GetInstance().table->GetEntry(key).GetDoubleArray(defaultValue);
 }
 
 bool SmartDashboard::PutStringArray(std::string_view key,
-                                    wpi::span<const std::string> value) {
+                                    std::span<const std::string> value) {
   return GetInstance().table->GetEntry(key).SetStringArray(value);
 }
 
 bool SmartDashboard::SetDefaultStringArray(
-    std::string_view key, wpi::span<const std::string> defaultValue) {
+    std::string_view key, std::span<const std::string> defaultValue) {
   return GetInstance().table->GetEntry(key).SetDefaultStringArray(defaultValue);
 }
 
 std::vector<std::string> SmartDashboard::GetStringArray(
-    std::string_view key, wpi::span<const std::string> defaultValue) {
+    std::string_view key, std::span<const std::string> defaultValue) {
   return GetInstance().table->GetEntry(key).GetStringArray(defaultValue);
 }
 
-bool SmartDashboard::PutRaw(std::string_view key, std::string_view value) {
+bool SmartDashboard::PutRaw(std::string_view key,
+                            std::span<const uint8_t> value) {
   return GetInstance().table->GetEntry(key).SetRaw(value);
 }
 
 bool SmartDashboard::SetDefaultRaw(std::string_view key,
-                                   std::string_view defaultValue) {
+                                   std::span<const uint8_t> defaultValue) {
   return GetInstance().table->GetEntry(key).SetDefaultRaw(defaultValue);
 }
 
-std::string SmartDashboard::GetRaw(std::string_view key,
-                                   std::string_view defaultValue) {
+std::vector<uint8_t> SmartDashboard::GetRaw(
+    std::string_view key, std::span<const uint8_t> defaultValue) {
   return GetInstance().table->GetEntry(key).GetRaw(defaultValue);
 }
 
 bool SmartDashboard::PutValue(std::string_view keyName,
-                              std::shared_ptr<nt::Value> value) {
+                              const nt::Value& value) {
   return GetInstance().table->GetEntry(keyName).SetValue(value);
 }
 
 bool SmartDashboard::SetDefaultValue(std::string_view key,
-                                     std::shared_ptr<nt::Value> defaultValue) {
+                                     const nt::Value& defaultValue) {
   return GetInstance().table->GetEntry(key).SetDefaultValue(defaultValue);
 }
 
-std::shared_ptr<nt::Value> SmartDashboard::GetValue(std::string_view keyName) {
+nt::Value SmartDashboard::GetValue(std::string_view keyName) {
   return GetInstance().table->GetEntry(keyName).GetValue();
 }
 
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/util/Color.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/util/Color.cpp
new file mode 100644
index 0000000..e3adaf2
--- /dev/null
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/util/Color.cpp
@@ -0,0 +1,15 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/util/Color.h"
+
+#include <fmt/format.h>
+
+using namespace frc;
+
+std::string Color::HexString() const {
+  return fmt::format("#{:02X}{:02X}{:02X}", static_cast<int>(255.0 * red),
+                     static_cast<int>(255.0 * green),
+                     static_cast<int>(255.0 * blue));
+}
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cpp/util/Color8Bit.cpp b/third_party/allwpilib/wpilibc/src/main/native/cpp/util/Color8Bit.cpp
new file mode 100644
index 0000000..af200a2
--- /dev/null
+++ b/third_party/allwpilib/wpilibc/src/main/native/cpp/util/Color8Bit.cpp
@@ -0,0 +1,13 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/util/Color8Bit.h"
+
+#include <fmt/format.h>
+
+using namespace frc;
+
+std::string Color8Bit::HexString() const {
+  return fmt::format("#{:02X}{:02X}{:02X}", red, green, blue);
+}
diff --git a/third_party/allwpilib/wpilibc/src/main/native/cppcs/RobotBase.cpp b/third_party/allwpilib/wpilibc/src/main/native/cppcs/RobotBase.cpp
index 3433a02..535d20d 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/cppcs/RobotBase.cpp
+++ b/third_party/allwpilib/wpilibc/src/main/native/cppcs/RobotBase.cpp
@@ -45,7 +45,7 @@
              HALUsageReporting::kLanguage_CPlusPlus, 0, GetWPILibVersion());
 
   if (!frc::Notifier::SetHALThreadPriority(true, 40)) {
-    FRC_ReportError(warn::Warning, "{}",
+    FRC_ReportError(warn::Warning,
                     "Setting HAL Notifier RT priority to 40 failed\n");
   }
 
@@ -192,18 +192,10 @@
   return DriverStation::IsAutonomousEnabled();
 }
 
-bool RobotBase::IsOperatorControl() const {
-  return DriverStation::IsTeleop();
-}
-
 bool RobotBase::IsTeleop() const {
   return DriverStation::IsTeleop();
 }
 
-bool RobotBase::IsOperatorControlEnabled() const {
-  return DriverStation::IsTeleopEnabled();
-}
-
 bool RobotBase::IsTeleopEnabled() const {
   return DriverStation::IsTeleopEnabled();
 }
@@ -212,10 +204,6 @@
   return DriverStation::IsTest();
 }
 
-bool RobotBase::IsNewDataAvailable() const {
-  return DriverStation::IsNewControlData();
-}
-
 std::thread::id RobotBase::GetThreadId() {
   return m_threadId;
 }
@@ -231,13 +219,26 @@
   SetupMathShared();
 
   auto inst = nt::NetworkTableInstance::GetDefault();
-  inst.SetNetworkIdentity("Robot");
+  // subscribe to "" to force persistent values to progagate to local
+  nt::SubscribeMultiple(inst.GetHandle(), {{std::string_view{}}});
 #ifdef __FRC_ROBORIO__
-  inst.StartServer("/home/lvuser/networktables.ini");
+  inst.StartServer("/home/lvuser/networktables.json");
 #else
   inst.StartServer();
 #endif
 
+  // wait for the NT server to actually start
+  int count = 0;
+  while ((inst.GetNetworkMode() & NT_NET_MODE_STARTING) != 0) {
+    using namespace std::chrono_literals;
+    std::this_thread::sleep_for(10ms);
+    ++count;
+    if (count > 100) {
+      fmt::print(stderr, "timed out while waiting for NT server to start\n");
+      break;
+    }
+  }
+
   SmartDashboard::init();
 
   if (IsReal()) {
@@ -251,14 +252,9 @@
     }
   }
 
-  // Call DriverStation::InDisabled() to kick off DS thread
-  DriverStation::InDisabled(true);
+  // Call DriverStation::RefreshData() to kick things off
+  DriverStation::RefreshData();
 
   // First and one-time initialization
-  inst.GetTable("LiveWindow")
-      ->GetSubTable(".status")
-      ->GetEntry("LW Enabled")
-      .SetBoolean(false);
-
   LiveWindow::SetEnabled(false);
 }
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/ADIS16448_IMU.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/ADIS16448_IMU.h
index 0dbfa68..60d57a9 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/ADIS16448_IMU.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/ADIS16448_IMU.h
@@ -205,6 +205,8 @@
 
   int SetYawAxis(IMUAxis yaw_axis);
 
+  bool IsConnected() const;
+
   int ConfigDecRate(uint16_t DecimationRate);
 
   /**
@@ -285,6 +287,10 @@
     double gyro_rate_z = 0.0;
   };
 
+  /** @brief Internal Resources **/
+  DigitalInput* m_reset_in;
+  DigitalOutput* m_status_led;
+
   bool SwitchToStandardSPI();
 
   bool SwitchToAutoSPI();
@@ -357,10 +363,12 @@
   CalibrationTime m_calibration_time{0};
   SPI* m_spi = nullptr;
   DigitalInput* m_auto_interrupt = nullptr;
+  bool m_connected{false};
 
   std::thread m_acquire_task;
 
   hal::SimDevice m_simDevice;
+  hal::SimBoolean m_simConnected;
   hal::SimDouble m_simGyroAngleX;
   hal::SimDouble m_simGyroAngleY;
   hal::SimDouble m_simGyroAngleZ;
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/ADIS16470_IMU.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/ADIS16470_IMU.h
index e6f3ce7..4619819 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/ADIS16470_IMU.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/ADIS16470_IMU.h
@@ -93,7 +93,8 @@
                          CalibrationTime cal_time);
 
   /**
-   * @brief Destructor. Kills the acquisiton loop and closes the SPI peripheral.
+   * @brief Destructor. Kills the acquisition loop and closes the SPI
+   * peripheral.
    */
   ~ADIS16470_IMU() override;
 
@@ -159,6 +160,8 @@
 
   int SetYawAxis(IMUAxis yaw_axis);
 
+  bool IsConnected() const;
+
   // IMU yaw axis
   IMUAxis m_yaw_axis;
 
@@ -296,6 +299,10 @@
   static constexpr double deg_to_rad = 0.0174532;
   static constexpr double grav = 9.81;
 
+  /** @brief Resources **/
+  DigitalInput* m_reset_in;
+  DigitalOutput* m_status_led;
+
   /**
    * @brief Switches to standard SPI operation. Primarily used when exiting auto
    * SPI mode.
@@ -378,10 +385,12 @@
   SPI* m_spi = nullptr;
   DigitalInput* m_auto_interrupt = nullptr;
   double m_scaled_sample_rate = 2500.0;  // Default sample rate setting
+  bool m_connected{false};
 
   std::thread m_acquire_task;
 
   hal::SimDevice m_simDevice;
+  hal::SimBoolean m_simConnected;
   hal::SimDouble m_simGyroAngleX;
   hal::SimDouble m_simGyroAngleY;
   hal::SimDouble m_simGyroAngleZ;
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/ADXL345_I2C.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/ADXL345_I2C.h
index c997327..6b6b76c 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/ADXL345_I2C.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/ADXL345_I2C.h
@@ -19,6 +19,10 @@
  * This class allows access to a Analog Devices ADXL345 3-axis accelerometer on
  * an I2C bus. This class assumes the default (not alternate) sensor address of
  * 0x1D (7-bit address).
+ *
+ * The Onboard I2C port is subject to system lockups. See <a
+ * href="https://docs.wpilib.org/en/stable/docs/yearly-overview/known-issues.html#onboard-i2c-causing-system-lockups">
+ * WPILib Known Issues</a> page for details.
  */
 class ADXL345_I2C : public Accelerometer,
                     public nt::NTSendable,
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/ADXRS450_Gyro.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/ADXRS450_Gyro.h
index cb0dff8..55414d4 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/ADXRS450_Gyro.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/ADXRS450_Gyro.h
@@ -49,6 +49,8 @@
   ADXRS450_Gyro(ADXRS450_Gyro&&) = default;
   ADXRS450_Gyro& operator=(ADXRS450_Gyro&&) = default;
 
+  bool IsConnected() const;
+
   /**
    * Return the actual angle in degrees that the robot is currently facing.
    *
@@ -105,8 +107,10 @@
  private:
   SPI m_spi;
   SPI::Port m_port;
+  bool m_connected{false};
 
   hal::SimDevice m_simDevice;
+  hal::SimBoolean m_simConnected;
   hal::SimDouble m_simAngle;
   hal::SimDouble m_simRate;
 
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/AddressableLED.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/AddressableLED.h
index 561eb37..e6adfca 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/AddressableLED.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/AddressableLED.h
@@ -5,11 +5,11 @@
 #pragma once
 
 #include <initializer_list>
+#include <span>
 
 #include <hal/AddressableLEDTypes.h>
 #include <hal/Types.h>
 #include <units/time.h>
-#include <wpi/span.h>
 
 #include "util/Color.h"
 #include "util/Color8Bit.h"
@@ -107,7 +107,7 @@
    *
    * @param ledData the buffer to write
    */
-  void SetData(wpi::span<const LEDData> ledData);
+  void SetData(std::span<const LEDData> ledData);
 
   /**
    * Sets the led output data.
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/AnalogEncoder.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/AnalogEncoder.h
index 6f12cb8..1860273 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/AnalogEncoder.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/AnalogEncoder.h
@@ -72,9 +72,23 @@
   units::turn_t Get() const;
 
   /**
+   * Get the absolute position of the analog encoder.
+   *
+   * <p>GetAbsolutePosition() - GetPositionOffset() will give an encoder
+   * absolute position relative to the last reset. This could potentially be
+   * negative, which needs to be accounted for.
+   *
+   * <p>This will not account for rollovers, and will always be just the raw
+   * absolute position.
+   *
+   * @return the absolute position
+   */
+  double GetAbsolutePosition() const;
+
+  /**
    * Get the offset of position relative to the last reset.
    *
-   * GetPositionInRotation() - GetPositionOffset() will give an encoder absolute
+   * GetAbsolutePosition() - GetPositionOffset() will give an encoder absolute
    * position relative to the last reset. This could potentially be negative,
    * which needs to be accounted for.
    *
@@ -83,6 +97,15 @@
   double GetPositionOffset() const;
 
   /**
+   * Set the position offset.
+   *
+   * <p>This must be in the range of 0-1.
+   *
+   * @param offset the offset
+   */
+  void SetPositionOffset(double offset);
+
+  /**
    * Set the distance per rotation of the encoder. This sets the multiplier used
    * to determine the distance driven based on the rotation value from the
    * encoder. Set this value based on the how far the mechanism travels in 1
@@ -131,5 +154,6 @@
 
   hal::SimDevice m_simDevice;
   hal::SimDouble m_simPosition;
+  hal::SimDouble m_simAbsolutePosition;
 };
 }  // namespace frc
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/AsynchronousInterrupt.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/AsynchronousInterrupt.h
index 4531dfd..0dea5bc 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/AsynchronousInterrupt.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/AsynchronousInterrupt.h
@@ -82,7 +82,8 @@
    * @param source the DigitalSource the interrupts are triggered from
    * @param f the callback function to call when the interrupt is triggered
    * @param arg the first argument, interrupt was triggered on rising edge
-   * @param args the remaing arguments, interrupt was triggered on falling edge
+   * @param args the remaining arguments, interrupt was triggered on falling
+   * edge
    */
   template <typename Callable, typename Arg, typename... Args>
   AsynchronousInterrupt(DigitalSource& source, Callable&& f, Arg&& arg,
@@ -99,7 +100,8 @@
    * @param source the DigitalSource the interrupts are triggered from
    * @param f the callback function to call when the interrupt is triggered
    * @param arg the first argument, interrupt was triggered on rising edge
-   * @param args the remaing arguments, interrupt was triggered on falling edge
+   * @param args the remaining arguments, interrupt was triggered on falling
+   * edge
    */
   template <typename Callable, typename Arg, typename... Args>
   AsynchronousInterrupt(DigitalSource* source, Callable&& f, Arg&& arg,
@@ -116,7 +118,8 @@
    * @param source the DigitalSource the interrupts are triggered from
    * @param f the callback function to call when the interrupt is triggered
    * @param arg the first argument, interrupt was triggered on rising edge
-   * @param args the remaing arguments, interrupt was triggered on falling edge
+   * @param args the remaining arguments, interrupt was triggered on falling
+   * edge
    */
   template <typename Callable, typename Arg, typename... Args>
   AsynchronousInterrupt(std::shared_ptr<DigitalSource> source, Callable&& f,
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/Compressor.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/Compressor.h
index d8125ed..1329a3b 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/Compressor.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/Compressor.h
@@ -59,56 +59,59 @@
   Compressor& operator=(Compressor&&) = default;
 
   /**
-   * Starts closed-loop control. Note that closed loop control is enabled by
-   * default.
-   *
-   * @deprecated Use EnableDigital() instead.
-   */
-  WPI_DEPRECATED("Use EnableDigital() instead")
-  void Start();
-
-  /**
-   * Stops closed-loop control. Note that closed loop control is enabled by
-   * default.
-   *
-   * @deprecated Use Disable() instead.
-   */
-  WPI_DEPRECATED("Use Disable() instead")
-  void Stop();
-
-  /**
    * Check if compressor output is active.
+   * To (re)enable the compressor use EnableDigital() or EnableAnalog(...).
    *
-   * @return true if the compressor is on
+   * @return true if the compressor is on.
+   * @deprecated To avoid confusion in thinking this (re)enables the compressor
+   * use IsEnabled().
    */
+  WPI_DEPRECATED(
+      "To avoid confusion in thinking this (re)enables the compressor use "
+      "IsEnabled()")
   bool Enabled() const;
 
   /**
-   * Check if the pressure switch is triggered.
+   * Returns whether the compressor is active or not.
    *
-   * @return true if pressure is low
+   * @return true if the compressor is on - otherwise false.
+   */
+  bool IsEnabled() const;
+
+  /**
+   * Returns the state of the pressure switch.
+   *
+   * @return True if pressure switch indicates that the system is not full,
+   * otherwise false.
    */
   bool GetPressureSwitchValue() const;
 
   /**
-   * Query how much current the compressor is drawing.
+   * Get the current drawn by the compressor.
    *
-   * @return The current through the compressor, in amps
+   * @return Current drawn by the compressor.
    */
   units::ampere_t GetCurrent() const;
 
   /**
-   * Query the analog input voltage (on channel 0) (if supported).
+   * If supported by the device, returns the analog input voltage (on channel
+   * 0).
    *
-   * @return The analog input voltage, in volts
+   * This function is only supported by the REV PH. On CTRE PCM, this will
+   * return 0.
+   *
+   * @return The analog input voltage, in volts.
    */
   units::volt_t GetAnalogVoltage() const;
 
   /**
-   * Query the analog sensor pressure (on channel 0) (if supported). Note this
-   * is only for use with the REV Analog Pressure Sensor.
+   * If supported by the device, returns the pressure read by the analog
+   * pressure sensor (on channel 0).
    *
-   * @return The analog sensor pressure, in PSI
+   * This function is only supported by the REV PH with the REV Analog Pressure
+   * Sensor. On CTRE PCM, this will return 0.
+   *
+   * @return The pressure read by the analog pressure sensor.
    */
   units::pounds_per_square_inch_t GetPressure() const;
 
@@ -118,34 +121,68 @@
   void Disable();
 
   /**
-   * Enable compressor closed loop control using digital input.
+   * Enables the compressor in digital mode using the digital pressure switch.
+   * The compressor will turn on when the pressure switch indicates that the
+   * system is not full, and will turn off when the pressure switch indicates
+   * that the system is full.
    */
   void EnableDigital();
 
   /**
-   * Enable compressor closed loop control using analog input. Note this is only
-   * for use with the REV Analog Pressure Sensor.
+   * If supported by the device, enables the compressor in analog mode. This
+   * mode uses an analog pressure sensor connected to analog channel 0 to cycle
+   * the compressor. The compressor will turn on when the pressure drops below
+   * {@code minPressure} and will turn off when the pressure reaches {@code
+   * maxPressure}. This mode is only supported by the REV PH with the REV Analog
+   * Pressure Sensor connected to analog channel 0.
    *
-   * <p>On CTRE PCM, this will enable digital control.
+   * On CTRE PCM, this will enable digital control.
    *
-   * @param minPressure The minimum pressure in PSI to enable compressor
-   * @param maxPressure The maximum pressure in PSI to disable compressor
+   * @param minPressure The minimum pressure. The compressor will turn on when
+   * the pressure drops below this value.
+   * @param maxPressure The maximum pressure. The compressor will turn off when
+   * the pressure reaches this value.
    */
   void EnableAnalog(units::pounds_per_square_inch_t minPressure,
                     units::pounds_per_square_inch_t maxPressure);
 
   /**
-   * Enable compressor closed loop control using hybrid input. Note this is only
-   * for use with the REV Analog Pressure Sensor.
+   * If supported by the device, enables the compressor in hybrid mode. This
+   * mode uses both a digital pressure switch and an analog pressure sensor
+   * connected to analog channel 0 to cycle the compressor. This mode is only
+   * supported by the REV PH with the REV Analog Pressure Sensor connected to
+   * analog channel 0.
+   *
+   * The compressor will turn on when \a both:
+   *
+   * - The digital pressure switch indicates the system is not full AND
+   * - The analog pressure sensor indicates that the pressure in the system
+   * is below the specified minimum pressure.
+   *
+   * The compressor will turn off when \a either:
+   *
+   * - The digital pressure switch is disconnected or indicates that the system
+   * is full OR
+   * - The pressure detected by the analog sensor is greater than the specified
+   * maximum pressure.
    *
    * On CTRE PCM, this will enable digital control.
    *
-   * @param minPressure The minimum pressure in PSI to enable compressor
-   * @param maxPressure The maximum pressure in PSI to disable compressor
+   * @param minPressure The minimum pressure. The compressor will turn on
+   * when the pressure drops below this value and the pressure switch indicates
+   * that the system is not full.
+   * @param maxPressure The maximum pressure. The compressor will turn
+   * off when the pressure reaches this value or the pressure switch is
+   * disconnected or indicates that the system is full.
    */
   void EnableHybrid(units::pounds_per_square_inch_t minPressure,
                     units::pounds_per_square_inch_t maxPressure);
 
+  /**
+   * Returns the active compressor configuration.
+   *
+   * @return The active compressor configuration.
+   */
   CompressorConfigType GetConfigType() const;
 
   void InitSendable(wpi::SendableBuilder& builder) override;
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/Controller.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/Controller.h
deleted file mode 100644
index d750a0e..0000000
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/Controller.h
+++ /dev/null
@@ -1,41 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <wpi/deprecated.h>
-
-namespace frc {
-
-/**
- * Interface for Controllers.
- *
- * Common interface for controllers. Controllers run control loops, the most
- * common are PID controllers and their variants, but this includes anything
- * that is controlling an actuator in a separate thread.
- *
- * @deprecated Only used by the deprecated PIDController
- */
-class Controller {
- public:
-  WPI_DEPRECATED("Only used by the deprecated PIDController")
-  Controller() = default;
-  virtual ~Controller() = default;
-
-  Controller(Controller&&) = default;
-  Controller& operator=(Controller&&) = default;
-
-  /**
-   * Allows the control loop to run
-   */
-  virtual void Enable() = 0;
-
-  /**
-   * Stops the control loop from running until explicitly re-enabled by calling
-   * enable()
-   */
-  virtual void Disable() = 0;
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/DataLogManager.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/DataLogManager.h
new file mode 100644
index 0000000..fa7abba
--- /dev/null
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/DataLogManager.h
@@ -0,0 +1,85 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <string>
+#include <string_view>
+
+namespace wpi::log {
+class DataLog;
+}  // namespace wpi::log
+
+namespace frc {
+
+/**
+ * Centralized data log that provides automatic data log file management. It
+ * automatically cleans up old files when disk space is low and renames the file
+ * based either on current date/time or (if available) competition match number.
+ * The deta file will be saved to a USB flash drive if one is attached, or to
+ * /home/lvuser otherwise.
+ *
+ * Log files are initially named "FRC_TBD_{random}.wpilog" until the DS
+ * connects. After the DS connects, the log file is renamed to
+ * "FRC_yyyyMMdd_HHmmss.wpilog" (where the date/time is UTC). If the FMS is
+ * connected and provides a match number, the log file is renamed to
+ * "FRC_yyyyMMdd_HHmmss_{event}_{match}.wpilog".
+ *
+ * On startup, all existing FRC_TBD log files are deleted. If there is less than
+ * 50 MB of free space on the target storage, FRC_ log files are deleted (oldest
+ * to newest) until there is 50 MB free OR there are 10 files remaining.
+ *
+ * By default, all NetworkTables value changes are stored to the data log.
+ */
+class DataLogManager final {
+ public:
+  DataLogManager() = delete;
+
+  /**
+   * Start data log manager. The parameters have no effect if the data log
+   * manager was already started (e.g. by calling another static function).
+   *
+   * @param dir if not empty, directory to use for data log storage
+   * @param filename filename to use; if none provided, the filename is
+   *     automatically generated
+   * @param period time between automatic flushes to disk, in seconds;
+   *               this is a time/storage tradeoff
+   */
+  static void Start(std::string_view dir = "", std::string_view filename = "",
+                    double period = 0.25);
+
+  /**
+   * Log a message to the "messages" entry. The message is also printed to
+   * standard output (followed by a newline).
+   *
+   * @param message message
+   */
+  static void Log(std::string_view message);
+
+  /**
+   * Get the managed data log (for custom logging). Starts the data log manager
+   * if not already started.
+   *
+   * @return data log
+   */
+  static wpi::log::DataLog& GetLog();
+
+  /**
+   * Get the log directory.
+   *
+   * @return log directory
+   */
+  static std::string GetLogDir();
+
+  /**
+   * Enable or disable logging of NetworkTables data. Note that unlike the
+   * network interface for NetworkTables, this will capture every value change.
+   * Defaults to enabled.
+   *
+   * @param enabled true to enable, false to disable
+   */
+  static void LogNetworkTables(bool enabled);
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/DigitalOutput.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/DigitalOutput.h
index 0e124f1..d2981fa 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/DigitalOutput.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/DigitalOutput.h
@@ -5,6 +5,7 @@
 #pragma once
 
 #include <hal/Types.h>
+#include <units/time.h>
 #include <wpi/sendable/Sendable.h>
 #include <wpi/sendable/SendableHelper.h>
 
@@ -79,11 +80,11 @@
    * Output a single pulse on the digital output line.
    *
    * Send a single pulse on the digital output line where the pulse duration is
-   * specified in seconds. Maximum pulse length is 0.0016 seconds.
+   * specified in seconds. Maximum of 65535 microseconds.
    *
-   * @param length The pulse length in seconds
+   * @param pulseLength The pulse length in seconds
    */
-  void Pulse(double length);
+  void Pulse(units::second_t pulseLength);
 
   /**
    * Determine if the pulse is still going.
@@ -105,6 +106,19 @@
   void SetPWMRate(double rate);
 
   /**
+   * Enable a PWM PPS (Pulse Per Second) Output on this line.
+   *
+   * Allocate one of the 6 DO PWM generator resources from this module.
+   *
+   * Supply the duty-cycle to output.
+   *
+   * The resolution of the duty cycle is 8-bit.
+   *
+   * @param dutyCycle The duty-cycle to start generating. [0..1]
+   */
+  void EnablePPS(double dutyCycle);
+
+  /**
    * Enable a PWM Output on this line.
    *
    * Allocate one of the 6 DO PWM generator resources from this module.
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/DriverStation.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/DriverStation.h
index 30bf4fc..4cbf6da 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/DriverStation.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/DriverStation.h
@@ -7,7 +7,11 @@
 #include <string>
 
 #include <units/time.h>
-#include <wpi/deprecated.h>
+#include <wpi/Synchronization.h>
+
+namespace wpi::log {
+class DataLog;
+}  // namespace wpi::log
 
 namespace frc {
 
@@ -15,20 +19,11 @@
  * Provide access to the network communication data to / from the Driver
  * Station.
  */
-class DriverStation {
+class DriverStation final {
  public:
   enum Alliance { kRed, kBlue, kInvalid };
   enum MatchType { kNone, kPractice, kQualification, kElimination };
 
-  /**
-   * Return a reference to the singleton DriverStation.
-   *
-   * @return Reference to the DS instance
-   * @deprecated Use the static methods
-   */
-  WPI_DEPRECATED("Use static methods")
-  static DriverStation& GetInstance();
-
   static constexpr int kJoystickPorts = 6;
 
   /**
@@ -196,15 +191,6 @@
    * Check if the DS is commanding teleop mode.
    *
    * @return True if the robot is being commanded to be in teleop mode
-   * @deprecated Use IsTeleop() instead.
-   */
-  WPI_DEPRECATED("Use IsTeleop() instead")
-  static bool IsOperatorControl();
-
-  /**
-   * Check if the DS is commanding teleop mode.
-   *
-   * @return True if the robot is being commanded to be in teleop mode
    */
   static bool IsTeleop();
 
@@ -213,16 +199,6 @@
    *
    * @return True if the robot is being commanded to be in teleop mode and
    * enabled.
-   * @deprecated Use IsTeleopEnabled() instead.
-   */
-  WPI_DEPRECATED("Use IsTeleopEnabled() instead")
-  static bool IsOperatorControlEnabled();
-
-  /**
-   * Check if the DS is commanding teleop mode and if it has enabled the robot.
-   *
-   * @return True if the robot is being commanded to be in teleop mode and
-   * enabled.
    */
   static bool IsTeleopEnabled();
 
@@ -241,17 +217,6 @@
   static bool IsDSAttached();
 
   /**
-   * Has a new control packet from the driver station arrived since the last
-   * time this function was called?
-   *
-   * Warning: If you call this function from more than one place at the same
-   * time, you will not get the intended behavior.
-   *
-   * @return True if the control data has been updated since the last call.
-   */
-  static bool IsNewControlData();
-
-  /**
    * Is the driver station attached to a Field Management System?
    *
    * @return True if the robot is competing on a field being controlled by a
@@ -315,41 +280,6 @@
   static int GetLocation();
 
   /**
-   * Wait until a new packet comes from the driver station.
-   *
-   * This blocks on a semaphore, so the waiting is efficient.
-   *
-   * This is a good way to delay processing until there is new driver station
-   * data to act on.
-   *
-   * Checks if new control data has arrived since the last waitForData call
-   * on the current thread. If new data has not arrived, returns immediately.
-   */
-  static void WaitForData();
-
-  /**
-   * Wait until a new packet comes from the driver station, or wait for a
-   * timeout.
-   *
-   * Checks if new control data has arrived since the last waitForData call
-   * on the current thread. If new data has not arrived, returns immediately.
-   *
-   * If the timeout is less then or equal to 0, wait indefinitely.
-   *
-   * Timeout is in milliseconds
-   *
-   * This blocks on a semaphore, so the waiting is efficient.
-   *
-   * This is a good way to delay processing until there is new driver station
-   * data to act on.
-   *
-   * @param timeout Timeout
-   *
-   * @return true if new data, otherwise false
-   */
-  static bool WaitForData(units::second_t timeout);
-
-  /**
    * Return the approximate match time.
    *
    * The FMS does not send an official match time to the robots, but does send
@@ -373,56 +303,10 @@
    */
   static double GetBatteryVoltage();
 
-  /**
-   * Only to be used to tell the Driver Station what code you claim to be
-   * executing for diagnostic purposes only.
-   *
-   * @param entering If true, starting disabled code; if false, leaving disabled
-   *                 code.
-   */
-  static void InDisabled(bool entering);
+  static void RefreshData();
 
-  /**
-   * Only to be used to tell the Driver Station what code you claim to be
-   * executing for diagnostic purposes only.
-   *
-   * @param entering If true, starting autonomous code; if false, leaving
-   *                 autonomous code.
-   */
-  static void InAutonomous(bool entering);
-
-  /**
-   * Only to be used to tell the Driver Station what code you claim to be
-   * executing for diagnostic purposes only.
-   *
-   * @param entering If true, starting teleop code; if false, leaving teleop
-   *                 code.
-   * @deprecated Use InTeleop() instead.
-   */
-  WPI_DEPRECATED("Use InTeleop() instead")
-  static void InOperatorControl(bool entering);
-
-  /**
-   * Only to be used to tell the Driver Station what code you claim to be
-   * executing for diagnostic purposes only.
-   *
-   * @param entering If true, starting teleop code; if false, leaving teleop
-   *                 code.
-   */
-  static void InTeleop(bool entering);
-
-  /**
-   * Only to be used to tell the Driver Station what code you claim to be
-   * executing for diagnostic purposes only.
-   *
-   * @param entering If true, starting test code; if false, leaving test code.
-   */
-  static void InTest(bool entering);
-
-  /**
-   * Forces WaitForData() to return immediately.
-   */
-  static void WakeupWaitForData();
+  static void ProvideRefreshedDataEventHandle(WPI_EventHandle handle);
+  static void RemoveRefreshedDataEventHandle(WPI_EventHandle handle);
 
   /**
    * Allows the user to specify whether they want joystick connection warnings
@@ -441,6 +325,14 @@
    */
   static bool IsJoystickConnectionWarningSilenced();
 
+  /**
+   * Starts logging DriverStation data to data log. Repeated calls are ignored.
+   *
+   * @param log data log
+   * @param logJoysticks if true, log joystick data
+   */
+  static void StartDataLog(wpi::log::DataLog& log, bool logJoysticks = true);
+
  private:
   DriverStation() = default;
 };
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/DutyCycle.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/DutyCycle.h
index 7f45d06..e222045 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/DutyCycle.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/DutyCycle.h
@@ -7,6 +7,7 @@
 #include <memory>
 
 #include <hal/Types.h>
+#include <units/time.h>
 #include <wpi/sendable/Sendable.h>
 #include <wpi/sendable/SendableHelper.h>
 
@@ -83,21 +84,18 @@
   double GetOutput() const;
 
   /**
-   * Get the raw output ratio of the duty cycle signal.
+   * Get the raw high time of the duty cycle signal.
    *
-   * <p> 0 means always low, an output equal to
-   * GetOutputScaleFactor() means always high.
-   *
-   * @return output ratio in raw units
+   * @return high time of last pulse
    */
-  unsigned int GetOutputRaw() const;
+  units::second_t GetHighTime() const;
 
   /**
    * Get the scale factor of the output.
    *
    * <p> An output equal to this value is always high, and then linearly scales
-   * down to 0. Divide the result of getOutputRaw by this in order to get the
-   * percentage between 0 and 1.
+   * down to 0. Divide a raw result by this in order to get the
+   * percentage between 0 and 1. Used by DMA.
    *
    * @return the output scale factor
    */
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/DutyCycleEncoder.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/DutyCycleEncoder.h
index ab7ded9..5d04ada 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/DutyCycleEncoder.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/DutyCycleEncoder.h
@@ -122,6 +122,40 @@
   units::turn_t Get() const;
 
   /**
+   * Get the absolute position of the duty cycle encoder encoder.
+   *
+   * <p>GetAbsolutePosition() - GetPositionOffset() will give an encoder
+   * absolute position relative to the last reset. This could potentially be
+   * negative, which needs to be accounted for.
+   *
+   * <p>This will not account for rollovers, and will always be just the raw
+   * absolute position.
+   *
+   * @return the absolute position
+   */
+  double GetAbsolutePosition() const;
+
+  /**
+   * Get the offset of position relative to the last reset.
+   *
+   * GetAbsolutePosition() - GetPositionOffset() will give an encoder absolute
+   * position relative to the last reset. This could potentially be negative,
+   * which needs to be accounted for.
+   *
+   * @return the position offset
+   */
+  double GetPositionOffset() const;
+
+  /**
+   * Set the position offset.
+   *
+   * <p>This must be in the range of 0-1.
+   *
+   * @param offset the offset
+   */
+  void SetPositionOffset(double offset);
+
+  /**
    * Set the encoder duty cycle range. As the encoder needs to maintain a duty
    * cycle, the duty cycle cannot go all the way to 0% or all the way to 100%.
    * For example, an encoder with a 4096 us period might have a minimum duty
@@ -182,6 +216,7 @@
 
  private:
   void Init();
+  double MapSensorRange(double pos) const;
 
   std::shared_ptr<DutyCycle> m_dutyCycle;
   std::unique_ptr<AnalogTrigger> m_analogTrigger;
@@ -195,6 +230,7 @@
 
   hal::SimDevice m_simDevice;
   hal::SimDouble m_simPosition;
+  hal::SimDouble m_simAbsolutePosition;
   hal::SimDouble m_simDistancePerRotation;
   hal::SimBoolean m_simIsConnected;
 };
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/Encoder.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/Encoder.h
index f6753c2..deb36c0 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/Encoder.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/Encoder.h
@@ -166,7 +166,9 @@
    * scaled using the value from SetDistancePerPulse().
    *
    * @return Period in seconds of the most recent pulse.
+   * @deprecated Use getRate() in favor of this method.
    */
+  WPI_DEPRECATED("Use GetRate() in favor of this method")
   units::second_t GetPeriod() const override;
 
   /**
@@ -177,13 +179,12 @@
    * to determine if the wheels or other shaft has stopped rotating.
    * This method compensates for the decoding type.
    *
-   * @deprecated Use SetMinRate() in favor of this method.  This takes unscaled
-   *             periods and SetMinRate() scales using value from
-   *             SetDistancePerPulse().
-   *
    * @param maxPeriod The maximum time between rising and falling edges before
    *                  the FPGA will report the device stopped. This is expressed
    *                  in seconds.
+   * @deprecated Use SetMinRate() in favor of this method.  This takes unscaled
+   *             periods and SetMinRate() scales using value from
+   *             SetDistancePerPulse().
    */
   WPI_DEPRECATED(
       "Use SetMinRate() in favor of this method.  This takes unscaled periods "
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/Errors.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/Errors.h
index 84edc18..252a335 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/Errors.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/Errors.h
@@ -74,11 +74,12 @@
  * @param[in]  format error message format
  * @param[in]  args error message format args
  */
-template <typename S, typename... Args>
+template <typename... Args>
 inline void ReportError(int32_t status, const char* fileName, int lineNumber,
-                        const char* funcName, const S& format, Args&&... args) {
+                        const char* funcName, fmt::string_view format,
+                        Args&&... args) {
   ReportErrorV(status, fileName, lineNumber, funcName, format,
-               fmt::make_args_checked<Args...>(format, args...));
+               fmt::make_format_args(args...));
 }
 
 /**
@@ -99,14 +100,12 @@
                                       fmt::string_view format,
                                       fmt::format_args args);
 
-template <typename S, typename... Args>
-[[nodiscard]] inline RuntimeError MakeError(int32_t status,
-                                            const char* fileName,
-                                            int lineNumber,
-                                            const char* funcName,
-                                            const S& format, Args&&... args) {
+template <typename... Args>
+[[nodiscard]] inline RuntimeError MakeError(
+    int32_t status, const char* fileName, int lineNumber, const char* funcName,
+    fmt::string_view format, Args&&... args) {
   return MakeErrorV(status, fileName, lineNumber, funcName, format,
-                    fmt::make_args_checked<Args...>(format, args...));
+                    fmt::make_format_args(args...));
 }
 
 namespace err {
@@ -122,18 +121,24 @@
 }  // namespace warn
 }  // namespace frc
 
+// C++20 relaxed the number of arguments to variadics, but Apple Clang's
+// warnings haven't caught up yet: https://stackoverflow.com/a/67996331
+#ifdef __clang__
+#pragma clang diagnostic ignored "-Wgnu-zero-variadic-macro-arguments"
+#endif
+
 /**
  * Reports an error to the driver station (using HAL_SendError).
  *
  * @param[out] status error code
  * @param[in]  format error message format
  */
-#define FRC_ReportError(status, format, ...)                       \
-  do {                                                             \
-    if ((status) != 0) {                                           \
-      ::frc::ReportError(status, __FILE__, __LINE__, __FUNCTION__, \
-                         FMT_STRING(format), __VA_ARGS__);         \
-    }                                                              \
+#define FRC_ReportError(status, format, ...)                             \
+  do {                                                                   \
+    if ((status) != 0) {                                                 \
+      ::frc::ReportError(status, __FILE__, __LINE__, __FUNCTION__,       \
+                         FMT_STRING(format) __VA_OPT__(, ) __VA_ARGS__); \
+    }                                                                    \
   } while (0)
 
 /**
@@ -146,7 +151,7 @@
  */
 #define FRC_MakeError(status, format, ...)                   \
   ::frc::MakeError(status, __FILE__, __LINE__, __FUNCTION__, \
-                   FMT_STRING(format), __VA_ARGS__)
+                   FMT_STRING(format) __VA_OPT__(, ) __VA_ARGS__)
 
 /**
  * Checks a status code and depending on its value, either throws a
@@ -155,23 +160,24 @@
  * @param[out] status error code
  * @param[in]  format error message format
  */
-#define FRC_CheckErrorStatus(status, format, ...)                      \
-  do {                                                                 \
-    if ((status) < 0) {                                                \
-      throw ::frc::MakeError(status, __FILE__, __LINE__, __FUNCTION__, \
-                             FMT_STRING(format), __VA_ARGS__);         \
-    } else if ((status) > 0) {                                         \
-      ::frc::ReportError(status, __FILE__, __LINE__, __FUNCTION__,     \
-                         FMT_STRING(format), __VA_ARGS__);             \
-    }                                                                  \
+#define FRC_CheckErrorStatus(status, format, ...)                            \
+  do {                                                                       \
+    if ((status) < 0) {                                                      \
+      throw ::frc::MakeError(status, __FILE__, __LINE__, __FUNCTION__,       \
+                             FMT_STRING(format) __VA_OPT__(, ) __VA_ARGS__); \
+    } else if ((status) > 0) {                                               \
+      ::frc::ReportError(status, __FILE__, __LINE__, __FUNCTION__,           \
+                         FMT_STRING(format) __VA_OPT__(, ) __VA_ARGS__);     \
+    }                                                                        \
   } while (0)
 
 #define FRC_AssertMessage(condition, format, ...)                            \
   do {                                                                       \
     if (!(condition)) {                                                      \
       throw ::frc::MakeError(err::AssertionFailure, __FILE__, __LINE__,      \
-                             __FUNCTION__, FMT_STRING(format), __VA_ARGS__); \
+                             __FUNCTION__,                                   \
+                             FMT_STRING(format) __VA_OPT__(, ) __VA_ARGS__); \
     }                                                                        \
   } while (0)
 
-#define FRC_Assert(condition) FRC_AssertMessage(condition, "{}", #condition)
+#define FRC_Assert(condition) FRC_AssertMessage(condition, #condition)
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/GenericHID.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/GenericHID.h
index b6c18d3..f6db94c 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/GenericHID.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/GenericHID.h
@@ -10,7 +10,8 @@
 
 namespace frc {
 
-class DriverStation;
+class BooleanEvent;
+class EventLoop;
 
 /**
  * Handle input from standard HID devices connected to the Driver Station.
@@ -22,7 +23,7 @@
  */
 class GenericHID {
  public:
-  enum RumbleType { kLeftRumble, kRightRumble };
+  enum RumbleType { kLeftRumble, kRightRumble, kBothRumble };
 
   enum HIDType {
     kUnknown = -1,
@@ -92,6 +93,16 @@
   bool GetRawButtonReleased(int button);
 
   /**
+   * Constructs an event instance around this button's digital signal.
+   *
+   * @param button the button index
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the button's digital signal attached
+   * to the given loop.
+   */
+  BooleanEvent Button(int button, EventLoop* loop) const;
+
+  /**
    * Get the value of the axis.
    *
    * @param axis The axis to read, starting at 0.
@@ -111,6 +122,141 @@
   int GetPOV(int pov = 0) const;
 
   /**
+   * Constructs a BooleanEvent instance based around this angle of a POV on the
+   * HID.
+   *
+   * <p>The POV angles start at 0 in the up direction, and increase clockwise
+   * (eg right is 90, upper-left is 315).
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @param angle POV angle in degrees, or -1 for the center / not pressed.
+   * @return a BooleanEvent instance based around this angle of a POV on the
+   * HID.
+   */
+  BooleanEvent POV(int angle, EventLoop* loop) const;
+
+  /**
+   * Constructs a BooleanEvent instance based around this angle of a POV on the
+   * HID.
+   *
+   * <p>The POV angles start at 0 in the up direction, and increase clockwise
+   * (eg right is 90, upper-left is 315).
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @param pov   index of the POV to read (starting at 0). Defaults to 0.
+   * @param angle POV angle in degrees, or -1 for the center / not pressed.
+   * @return a BooleanEvent instance based around this angle of a POV on the
+   * HID.
+   */
+  BooleanEvent POV(int pov, int angle, EventLoop* loop) const;
+
+  /**
+   * Constructs a BooleanEvent instance based around the 0 degree angle (up) of
+   * the default (index 0) POV on the HID.
+   *
+   * @return a BooleanEvent instance based around the 0 degree angle of a POV on
+   * the HID.
+   */
+  BooleanEvent POVUp(EventLoop* loop) const;
+
+  /**
+   * Constructs a BooleanEvent instance based around the 45 degree angle (right
+   * up) of the default (index 0) POV on the HID.
+   *
+   * @return a BooleanEvent instance based around the 45 degree angle of a POV
+   * on the HID.
+   */
+  BooleanEvent POVUpRight(EventLoop* loop) const;
+
+  /**
+   * Constructs a BooleanEvent instance based around the 90 degree angle (right)
+   * of the default (index 0) POV on the HID.
+   *
+   * @return a BooleanEvent instance based around the 90 degree angle of a POV
+   * on the HID.
+   */
+  BooleanEvent POVRight(EventLoop* loop) const;
+
+  /**
+   * Constructs a BooleanEvent instance based around the 135 degree angle (right
+   * down) of the default (index 0) POV on the HID.
+   *
+   * @return a BooleanEvent instance based around the 135 degree angle of a POV
+   * on the HID.
+   */
+  BooleanEvent POVDownRight(EventLoop* loop) const;
+
+  /**
+   * Constructs a BooleanEvent instance based around the 180 degree angle (down)
+   * of the default (index 0) POV on the HID.
+   *
+   * @return a BooleanEvent instance based around the 180 degree angle of a POV
+   * on the HID.
+   */
+  BooleanEvent POVDown(EventLoop* loop) const;
+
+  /**
+   * Constructs a BooleanEvent instance based around the 225 degree angle (down
+   * left) of the default (index 0) POV on the HID.
+   *
+   * @return a BooleanEvent instance based around the 225 degree angle of a POV
+   * on the HID.
+   */
+  BooleanEvent POVDownLeft(EventLoop* loop) const;
+
+  /**
+   * Constructs a BooleanEvent instance based around the 270 degree angle (left)
+   * of the default (index 0) POV on the HID.
+   *
+   * @return a BooleanEvent instance based around the 270 degree angle of a POV
+   * on the HID.
+   */
+  BooleanEvent POVLeft(EventLoop* loop) const;
+
+  /**
+   * Constructs a BooleanEvent instance based around the 315 degree angle (left
+   * up) of the default (index 0) POV on the HID.
+   *
+   * @return a BooleanEvent instance based around the 315 degree angle of a POV
+   * on the HID.
+   */
+  BooleanEvent POVUpLeft(EventLoop* loop) const;
+
+  /**
+   * Constructs a BooleanEvent instance based around the center (not pressed) of
+   * the default (index 0) POV on the HID.
+   *
+   * @return a BooleanEvent instance based around the center of a POV on the
+   * HID.
+   */
+  BooleanEvent POVCenter(EventLoop* loop) const;
+
+  /**
+   * Constructs an event instance that is true when the axis value is less than
+   * threshold
+   *
+   * @param axis The axis to read, starting at 0.
+   * @param threshold The value below which this trigger should return true.
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance that is true when the axis value is less than the
+   * provided threshold.
+   */
+  BooleanEvent AxisLessThan(int axis, double threshold, EventLoop* loop) const;
+
+  /**
+   * Constructs an event instance that is true when the axis value is greater
+   * than threshold
+   *
+   * @param axis The axis to read, starting at 0.
+   * @param threshold The value above which this trigger should return true.
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance that is true when the axis value is greater than
+   * the provided threshold.
+   */
+  BooleanEvent AxisGreaterThan(int axis, double threshold,
+                               EventLoop* loop) const;
+
+  /**
    * Get the number of axes for the HID.
    *
    * @return the number of axis for the current HID
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/I2C.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/I2C.h
index d874a46..9489fcf 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/I2C.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/I2C.h
@@ -15,6 +15,10 @@
  *
  * This class is intended to be used by sensor (and other I2C device) drivers.
  * It probably should not be used directly.
+ *
+ * The Onboard I2C port is subject to system lockups. See <a
+ * href="https://docs.wpilib.org/en/stable/docs/yearly-overview/known-issues.html#onboard-i2c-causing-system-lockups">
+ * WPILib Known Issues</a> page for details.
  */
 class I2C {
  public:
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/IterativeRobotBase.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/IterativeRobotBase.h
index c4253ef..77ed197 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/IterativeRobotBase.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/IterativeRobotBase.h
@@ -5,7 +5,6 @@
 #pragma once
 
 #include <units/time.h>
-#include <wpi/deprecated.h>
 
 #include "frc/RobotBase.h"
 #include "frc/Watchdog.h"
@@ -196,13 +195,26 @@
 
   /**
    * Enables or disables flushing NetworkTables every loop iteration.
-   * By default, this is disabled.
+   * By default, this is enabled.
    *
    * @param enabled True to enable, false to disable
    */
   void SetNetworkTablesFlushEnabled(bool enabled);
 
   /**
+   * Sets whether LiveWindow operation is enabled during test mode.
+   *
+   * @param testLW True to enable, false to disable. Defaults to true.
+   * @throws if called in test mode.
+   */
+  void EnableLiveWindowInTest(bool testLW);
+
+  /**
+   * Whether LiveWindow operation is enabled during test mode.
+   */
+  bool IsLiveWindowEnabledInTest();
+
+  /**
    * Gets time period between calls to Periodic() functions.
    */
   units::second_t GetPeriod() const;
@@ -210,17 +222,6 @@
   /**
    * Constructor for IterativeRobotBase.
    *
-   * @param period Period in seconds.
-   *
-   * @deprecated Use IterativeRobotBase(units::second_t period) with unit-safety
-   * instead
-   */
-  WPI_DEPRECATED("Use constructor with unit-safety instead.")
-  explicit IterativeRobotBase(double period);
-
-  /**
-   * Constructor for IterativeRobotBase.
-   *
    * @param period Period.
    */
   explicit IterativeRobotBase(units::second_t period);
@@ -239,7 +240,8 @@
   Mode m_lastMode = Mode::kNone;
   units::second_t m_period;
   Watchdog m_watchdog;
-  bool m_ntFlushEnabled = false;
+  bool m_ntFlushEnabled = true;
+  bool m_lwEnabledInTest = true;
 
   void PrintLoopOverrunMessage();
 };
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/Joystick.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/Joystick.h
index 0d63e4e..fc0df35 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/Joystick.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/Joystick.h
@@ -173,6 +173,15 @@
   bool GetTriggerReleased();
 
   /**
+   * Constructs an event instance around the trigger button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the trigger button's digital signal
+   * attached to the given loop.
+   */
+  BooleanEvent Trigger(EventLoop* loop) const;
+
+  /**
    * Read the state of the top button on the joystick.
    *
    * Look up which button has been assigned to the top and read its state.
@@ -196,6 +205,15 @@
   bool GetTopReleased();
 
   /**
+   * Constructs an event instance around the top button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the top button's digital signal
+   * attached to the given loop.
+   */
+  BooleanEvent Top(EventLoop* loop) const;
+
+  /**
    * Get the magnitude of the direction vector formed by the joystick's
    * current position relative to its origin.
    *
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/MotorSafety.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/MotorSafety.h
index 1bfd34a..a17cdc0 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/MotorSafety.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/MotorSafety.h
@@ -14,8 +14,11 @@
 namespace frc {
 
 /**
- * This base class runs a watchdog timer and calls the subclass's StopMotor()
- * function if the timeout expires.
+ * The Motor Safety feature acts as a watchdog timer for an individual motor. It
+ * operates by maintaining a timer that tracks how long it has been since the
+ * feed() method has been called for that actuator. Code in the Driver Station
+ * class initiates a comparison of these timers to the timeout values for any
+ * actuator with safety enabled every 5 received packets (100ms nominal).
  *
  * The subclass should call Feed() whenever the motor value is updated.
  */
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/Notifier.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/Notifier.h
index 61b7fbb..bda685c 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/Notifier.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/Notifier.h
@@ -19,6 +19,13 @@
 
 namespace frc {
 
+/**
+ * Notifiers run a callback function on a separate thread at a specified period.
+ *
+ * If StartSingle() is used, the callback will run once. If StartPeriodic() is
+ * used, the callback will run repeatedly with the given period until stop() is
+ * called.
+ */
 class Notifier {
  public:
   /**
@@ -95,6 +102,9 @@
    * interrupt occurs, the event will be immediately requeued for the same time
    * interval.
    *
+   * The user-provided callback should be written in a nonblocking manner so the
+   * callback can be recalled at the next periodic event notification.
+   *
    * @param period Period to call the handler starting one period
    *               after the call to this method.
    */
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/PS4Controller.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/PS4Controller.h
index ee87501..9487634 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/PS4Controller.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/PS4Controller.h
@@ -99,6 +99,15 @@
   bool GetSquareButtonReleased();
 
   /**
+   * Constructs an event instance around the square button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the square button's digital signal
+   * attached to the given loop.
+   */
+  BooleanEvent Square(EventLoop* loop) const;
+
+  /**
    * Read the value of the Cross button on the controller.
    *
    * @return The state of the button.
@@ -120,6 +129,15 @@
   bool GetCrossButtonReleased();
 
   /**
+   * Constructs an event instance around the cross button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the cross button's digital signal
+   * attached to the given loop.
+   */
+  BooleanEvent Cross(EventLoop* loop) const;
+
+  /**
    * Read the value of the Circle button on the controller.
    *
    * @return The state of the button.
@@ -141,6 +159,15 @@
   bool GetCircleButtonReleased();
 
   /**
+   * Constructs an event instance around the circle button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the circle button's digital signal
+   * attached to the given loop.
+   */
+  BooleanEvent Circle(EventLoop* loop) const;
+
+  /**
    * Read the value of the Triangle button on the controller.
    *
    * @return The state of the button.
@@ -162,6 +189,15 @@
   bool GetTriangleButtonReleased();
 
   /**
+   * Constructs an event instance around the triangle button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the triangle button's digital signal
+   * attached to the given loop.
+   */
+  BooleanEvent Triangle(EventLoop* loop) const;
+
+  /**
    * Read the value of the L1 button on the controller.
    *
    * @return The state of the button.
@@ -183,6 +219,15 @@
   bool GetL1ButtonReleased();
 
   /**
+   * Constructs an event instance around the L1 button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the L1 button's digital signal
+   * attached to the given loop.
+   */
+  BooleanEvent L1(EventLoop* loop) const;
+
+  /**
    * Read the value of the R1 button on the controller.
    *
    * @return The state of the button.
@@ -204,6 +249,15 @@
   bool GetR1ButtonReleased();
 
   /**
+   * Constructs an event instance around the R1 button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the R1 button's digital signal
+   * attached to the given loop.
+   */
+  BooleanEvent R1(EventLoop* loop) const;
+
+  /**
    * Read the value of the L2 button on the controller.
    *
    * @return The state of the button.
@@ -225,6 +279,15 @@
   bool GetL2ButtonReleased();
 
   /**
+   * Constructs an event instance around the L2 button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the L2 button's digital signal
+   * attached to the given loop.
+   */
+  BooleanEvent L2(EventLoop* loop) const;
+
+  /**
    * Read the value of the R2 button on the controller.
    *
    * @return The state of the button.
@@ -246,6 +309,15 @@
   bool GetR2ButtonReleased();
 
   /**
+   * Constructs an event instance around the R2 button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the R2 button's digital signal
+   * attached to the given loop.
+   */
+  BooleanEvent R2(EventLoop* loop) const;
+
+  /**
    * Read the value of the Share button on the controller.
    *
    * @return The state of the button.
@@ -267,6 +339,15 @@
   bool GetShareButtonReleased();
 
   /**
+   * Constructs an event instance around the share button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the share button's digital signal
+   * attached to the given loop.
+   */
+  BooleanEvent Share(EventLoop* loop) const;
+
+  /**
    * Read the value of the Options button on the controller.
    *
    * @return The state of the button.
@@ -288,6 +369,15 @@
   bool GetOptionsButtonReleased();
 
   /**
+   * Constructs an event instance around the options button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the options button's digital signal
+   * attached to the given loop.
+   */
+  BooleanEvent Options(EventLoop* loop) const;
+
+  /**
    * Read the value of the L3 button (pressing the left analog stick) on the
    * controller.
    *
@@ -310,6 +400,15 @@
   bool GetL3ButtonReleased();
 
   /**
+   * Constructs an event instance around the L3 button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the L3 button's digital signal
+   * attached to the given loop.
+   */
+  BooleanEvent L3(EventLoop* loop) const;
+
+  /**
    * Read the value of the R3 button (pressing the right analog stick) on the
    * controller.
    *
@@ -332,6 +431,15 @@
   bool GetR3ButtonReleased();
 
   /**
+   * Constructs an event instance around the R3 button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the R3 button's digital signal
+   * attached to the given loop.
+   */
+  BooleanEvent R3(EventLoop* loop) const;
+
+  /**
    * Read the value of the PS button on the controller.
    *
    * @return The state of the button.
@@ -353,6 +461,15 @@
   bool GetPSButtonReleased();
 
   /**
+   * Constructs an event instance around the PS button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the PS button's digital signal
+   * attached to the given loop.
+   */
+  BooleanEvent PS(EventLoop* loop) const;
+
+  /**
    * Read the value of the touchpad button on the controller.
    *
    * @return The state of the button.
@@ -373,6 +490,15 @@
    */
   bool GetTouchpadReleased();
 
+  /**
+   * Constructs an event instance around the touchpad's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the touchpad's digital signal
+   * attached to the given loop.
+   */
+  BooleanEvent Touchpad(EventLoop* loop) const;
+
   struct Button {
     static constexpr int kSquare = 1;
     static constexpr int kCross = 2;
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/PWM.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/PWM.h
index efff540..e508915 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/PWM.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/PWM.h
@@ -166,7 +166,7 @@
   /**
    * Optionally eliminate the deadband from a motor controller.
    *
-   * @param eliminateDeadband If true, set the motor curve on the speed
+   * @param eliminateDeadband If true, set the motor curve on the motor
    *                          controller to eliminate the deadband in the middle
    *                          of the range. Otherwise, keep the full range
    *                          without modifying any values.
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/PneumaticHub.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/PneumaticHub.h
index d412bb6..f876b7a 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/PneumaticHub.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/PneumaticHub.h
@@ -13,23 +13,72 @@
 #include "PneumaticsBase.h"
 
 namespace frc {
+/** Module class for controlling a REV Robotics Pneumatic Hub. */
 class PneumaticHub : public PneumaticsBase {
  public:
+  /** Constructs a PneumaticHub with the default ID (1). */
   PneumaticHub();
+
+  /**
+   * Constructs a PneumaticHub.
+   *
+   * @param module module number to construct
+   */
   explicit PneumaticHub(int module);
 
   ~PneumaticHub() override = default;
 
   bool GetCompressor() const override;
 
+  /**
+   * Disables the compressor. The compressor will not turn on until
+   * EnableCompressorDigital(), EnableCompressorAnalog(), or
+   * EnableCompressorHybrid() are called.
+   */
   void DisableCompressor() override;
 
   void EnableCompressorDigital() override;
 
+  /**
+   * Enables the compressor in analog mode. This mode uses an analog pressure
+   * sensor connected to analog channel 0 to cycle the compressor. The
+   * compressor will turn on when the pressure drops below {@code minPressure}
+   * and will turn off when the pressure reaches {@code maxPressure}.
+   *
+   * @param minPressure The minimum pressure. The compressor will turn on when
+   * the pressure drops below this value.
+   * @param maxPressure The maximum pressure. The compressor will turn off when
+   * the pressure reaches this value.
+   */
   void EnableCompressorAnalog(
       units::pounds_per_square_inch_t minPressure,
       units::pounds_per_square_inch_t maxPressure) override;
 
+  /**
+   * Enables the compressor in hybrid mode. This mode uses both a digital
+   * pressure switch and an analog pressure sensor connected to analog channel 0
+   * to cycle the compressor.
+   *
+   * The compressor will turn on when \a both:
+   *
+   * - The digital pressure switch indicates the system is not full AND
+   * - The analog pressure sensor indicates that the pressure in the system is
+   * below the specified minimum pressure.
+   *
+   * The compressor will turn off when \a either:
+   *
+   * - The digital pressure switch is disconnected or indicates that the system
+   * is full OR
+   * - The pressure detected by the analog sensor is greater than the specified
+   * maximum pressure.
+   *
+   * @param minPressure The minimum pressure. The compressor will turn on when
+   * the pressure drops below this value and the pressure switch indicates that
+   * the system is not full.
+   * @param maxPressure The maximum pressure. The compressor will turn off when
+   * the pressure reaches this value or the pressure switch is disconnected or
+   * indicates that the system is full.
+   */
   void EnableCompressorHybrid(
       units::pounds_per_square_inch_t minPressure,
       units::pounds_per_square_inch_t maxPressure) override;
@@ -76,6 +125,11 @@
     uint32_t UniqueId;
   };
 
+  /**
+   * Returns the hardware and firmware versions of this device.
+   *
+   * @return The hardware and firmware versions.
+   */
   Version GetVersion() const;
 
   struct Faults {
@@ -103,6 +157,11 @@
     uint32_t HardwareFault : 1;
   };
 
+  /**
+   * Returns the faults currently active on this device.
+   *
+   * @return The faults.
+   */
   Faults GetFaults() const;
 
   struct StickyFaults {
@@ -115,20 +174,60 @@
     uint32_t HasReset : 1;
   };
 
+  /**
+   * Returns the sticky faults currently active on this device.
+   *
+   * @return The sticky faults.
+   */
   StickyFaults GetStickyFaults() const;
 
+  /** Clears the sticky faults. */
   void ClearStickyFaults();
 
+  /**
+   * Returns the current input voltage for this device.
+   *
+   * @return The input voltage.
+   */
   units::volt_t GetInputVoltage() const;
 
+  /**
+   * Returns the current voltage of the regulated 5v supply.
+   *
+   * @return The current voltage of the 5v supply.
+   */
   units::volt_t Get5VRegulatedVoltage() const;
 
+  /**
+   * Returns the total current drawn by all solenoids.
+   *
+   * @return Total current drawn by all solenoids.
+   */
   units::ampere_t GetSolenoidsTotalCurrent() const;
 
+  /**
+   * Returns the current voltage of the solenoid power supply.
+   *
+   * @return The current voltage of the solenoid power supply.
+   */
   units::volt_t GetSolenoidsVoltage() const;
 
+  /**
+   * Returns the raw voltage of the specified analog input channel.
+   *
+   * @param channel The analog input channel to read voltage from.
+   * @return The voltage of the specified analog input channel.
+   */
   units::volt_t GetAnalogVoltage(int channel) const override;
 
+  /**
+   * Returns the pressure read by an analog pressure sensor on the specified
+   * analog input channel.
+   *
+   * @param channel The analog input channel to read pressure from.
+   * @return The pressure read by an analog pressure sensor on the specified
+   * analog input channel.
+   */
   units::pounds_per_square_inch_t GetPressure(int channel) const override;
 
  private:
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/PneumaticsBase.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/PneumaticsBase.h
index 50ceb87..b455dc6 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/PneumaticsBase.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/PneumaticsBase.h
@@ -22,50 +22,194 @@
  public:
   virtual ~PneumaticsBase() = default;
 
+  /**
+   * Returns whether the compressor is active or not.
+   *
+   * @return True if the compressor is on - otherwise false.
+   */
   virtual bool GetCompressor() const = 0;
 
+  /**
+   * Returns the state of the pressure switch.
+   *
+   * @return True if pressure switch indicates that the system is full,
+   * otherwise false.
+   */
   virtual bool GetPressureSwitch() const = 0;
 
+  /**
+   * Returns the current drawn by the compressor.
+   *
+   * @return The current drawn by the compressor.
+   */
   virtual units::ampere_t GetCompressorCurrent() const = 0;
 
+  /** Disables the compressor. */
   virtual void DisableCompressor() = 0;
 
+  /**
+   * Enables the compressor in digital mode using the digital pressure switch.
+   * The compressor will turn on when the pressure switch indicates that the
+   * system is not full, and will turn off when the pressure switch indicates
+   * that the system is full.
+   */
   virtual void EnableCompressorDigital() = 0;
 
+  /**
+   * If supported by the device, enables the compressor in analog mode. This
+   * mode uses an analog pressure sensor connected to analog channel 0 to cycle
+   * the compressor. The compressor will turn on when the pressure drops below
+   * {@code minPressure} and will turn off when the pressure reaches {@code
+   * maxPressure}. This mode is only supported by the REV PH with the REV Analog
+   * Pressure Sensor connected to analog channel 0.
+   *
+   * On CTRE PCM, this will enable digital control.
+   *
+   * @param minPressure The minimum pressure. The compressor will turn on
+   * when the pressure drops below this value.
+   * @param maxPressure The maximum pressure. The compressor will turn
+   * off when the pressure reaches this value.
+   */
   virtual void EnableCompressorAnalog(
       units::pounds_per_square_inch_t minPressure,
       units::pounds_per_square_inch_t maxPressure) = 0;
 
+  /**
+   * If supported by the device, enables the compressor in hybrid mode. This
+   * mode uses both a digital pressure switch and an analog pressure sensor
+   * connected to analog channel 0 to cycle the compressor. This mode is only
+   * supported by the REV PH with the REV Analog Pressure Sensor connected to
+   * analog channel 0.
+   *
+   * The compressor will turn on when \a both:
+   *
+   * - The digital pressure switch indicates the system is not full AND
+   * - The analog pressure sensor indicates that the pressure in the system
+   * is below the specified minimum pressure.
+   *
+   * The compressor will turn off when \a either:
+   *
+   * - The digital pressure switch is disconnected or indicates that the system
+   * is full OR
+   * - The pressure detected by the analog sensor is greater than the specified
+   * maximum pressure.
+   *
+   * On CTRE PCM, this will enable digital control.
+   *
+   * @param minPressure The minimum pressure. The compressor will turn on
+   * when the pressure drops below this value and the pressure switch indicates
+   * that the system is not full.
+   * @param maxPressure The maximum pressure. The compressor will turn
+   * off when the pressure reaches this value or the pressure switch is
+   * disconnected or indicates that the system is full.
+   */
   virtual void EnableCompressorHybrid(
       units::pounds_per_square_inch_t minPressure,
       units::pounds_per_square_inch_t maxPressure) = 0;
 
+  /**
+   * Returns the active compressor configuration.
+   *
+   * @return The active compressor configuration.
+   */
   virtual CompressorConfigType GetCompressorConfigType() const = 0;
 
+  /**
+   * Sets solenoids on a pneumatics module.
+   *
+   * @param mask mask
+   * @param values values
+   */
   virtual void SetSolenoids(int mask, int values) = 0;
 
+  /**
+   * Gets a bitmask of solenoid values.
+   *
+   * @return values
+   */
   virtual int GetSolenoids() const = 0;
 
+  /**
+   * Get module number for this module.
+   *
+   * @return module number
+   */
   virtual int GetModuleNumber() const = 0;
 
+  /**
+   * Get a bitmask of disabled solenoids.
+   *
+   * @return bitmask of disabled solenoids
+   */
   virtual int GetSolenoidDisabledList() const = 0;
 
+  /**
+   * Fire a single solenoid shot.
+   *
+   * @param index solenoid index
+   */
   virtual void FireOneShot(int index) = 0;
 
+  /**
+   * Set the duration for a single solenoid shot.
+   *
+   * @param index solenoid index
+   * @param duration shot duration
+   */
   virtual void SetOneShotDuration(int index, units::second_t duration) = 0;
 
+  /**
+   * Check if a solenoid channel is valid.
+   *
+   * @param channel Channel to check
+   * @return True if channel exists
+   */
   virtual bool CheckSolenoidChannel(int channel) const = 0;
 
+  /**
+   * Check to see if the masked solenoids can be reserved, and if not reserve
+   * them.
+   *
+   * @param mask The bitmask of solenoids to reserve
+   * @return 0 if successful; mask of solenoids that couldn't be allocated
+   * otherwise
+   */
   virtual int CheckAndReserveSolenoids(int mask) = 0;
 
+  /**
+   * Unreserve the masked solenoids.
+   *
+   * @param mask The bitmask of solenoids to unreserve
+   */
   virtual void UnreserveSolenoids(int mask) = 0;
 
   virtual bool ReserveCompressor() = 0;
 
   virtual void UnreserveCompressor() = 0;
 
+  /**
+   * If supported by the device, returns the raw voltage of the specified analog
+   * input channel.
+   *
+   * This function is only supported by the REV PH. On CTRE PCM, this will
+   * return 0.
+   *
+   * @param channel The analog input channel to read voltage from.
+   * @return The voltage of the specified analog input channel.
+   */
   virtual units::volt_t GetAnalogVoltage(int channel) const = 0;
 
+  /**
+   * If supported by the device, returns the pressure read by an analog
+   * pressure sensor on the specified analog input channel.
+   *
+   * This function is only supported by the REV PH. On CTRE PCM, this will
+   * return 0.
+   *
+   * @param channel The analog input channel to read pressure from.
+   * @return The pressure read by an analog pressure sensor on the
+   * specified analog input channel.
+   */
   virtual units::pounds_per_square_inch_t GetPressure(int channel) const = 0;
 
   virtual Solenoid MakeSolenoid(int channel) = 0;
@@ -73,8 +217,22 @@
                                             int reverseChannel) = 0;
   virtual Compressor MakeCompressor() = 0;
 
+  /**
+   * For internal use to get a module for a specific type.
+   *
+   * @param module module number
+   * @param moduleType module type
+   * @return module
+   */
   static std::shared_ptr<PneumaticsBase> GetForType(
       int module, PneumaticsModuleType moduleType);
+
+  /**
+   * For internal use to get the default for a specific type.
+   *
+   * @param moduleType module type
+   * @return module default
+   */
   static int GetDefaultForType(PneumaticsModuleType moduleType);
 };
 }  // namespace frc
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/PneumaticsControlModule.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/PneumaticsControlModule.h
index ea4517b..acad5a1 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/PneumaticsControlModule.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/PneumaticsControlModule.h
@@ -13,23 +13,52 @@
 #include "PneumaticsBase.h"
 
 namespace frc {
+/** Module class for controlling a Cross The Road Electronics Pneumatics Control
+ * Module. */
 class PneumaticsControlModule : public PneumaticsBase {
  public:
+  /** Constructs a PneumaticsControlModule with the default ID (0). */
   PneumaticsControlModule();
+
+  /**
+   * Constructs a PneumaticsControlModule.
+   *
+   * @param module module number to construct
+   */
   explicit PneumaticsControlModule(int module);
 
   ~PneumaticsControlModule() override = default;
 
   bool GetCompressor() const override;
 
+  /**
+   * Disables the compressor. The compressor will not turn on until
+   * EnableCompressorDigital() is called.
+   */
   void DisableCompressor() override;
 
   void EnableCompressorDigital() override;
 
+  /**
+   * Enables the compressor in digital mode. Analog mode is unsupported by the
+   * CTRE PCM.
+   *
+   * @param minPressure Unsupported.
+   * @param maxPressure Unsupported.
+   * @see EnableCompressorDigital()
+   */
   void EnableCompressorAnalog(
       units::pounds_per_square_inch_t minPressure,
       units::pounds_per_square_inch_t maxPressure) override;
 
+  /**
+   * Enables the compressor in digital mode. Hybrid mode is unsupported by the
+   * CTRE PCM.
+   *
+   * @param minPressure Unsupported.
+   * @param maxPressure Unsupported.
+   * @see EnableCompressorDigital()
+   */
   void EnableCompressorHybrid(
       units::pounds_per_square_inch_t minPressure,
       units::pounds_per_square_inch_t maxPressure) override;
@@ -40,16 +69,67 @@
 
   units::ampere_t GetCompressorCurrent() const override;
 
+  /**
+   * Return whether the compressor current is currently too high.
+   *
+   * @return True if the compressor current is too high, otherwise false.
+   * @see GetCompressorCurrentTooHighStickyFault()
+   */
   bool GetCompressorCurrentTooHighFault() const;
+
+  /**
+   * Returns whether the compressor current has been too high since sticky
+   * faults were last cleared. This fault is persistent and can be cleared by
+   * ClearAllStickyFaults()
+   *
+   * @return True if the compressor current has been too high since sticky
+   * faults were last cleared.
+   * @see GetCompressorCurrentTooHighFault()
+   */
   bool GetCompressorCurrentTooHighStickyFault() const;
+
+  /**
+   * Returns whether the compressor is currently shorted.
+   *
+   * @return True if the compressor is currently shorted, otherwise false.
+   * @see GetCompressorShortedStickyFault()
+   */
   bool GetCompressorShortedFault() const;
+
+  /**
+   * Returns whether the compressor has been shorted since sticky faults were
+   * last cleared. This fault is persistent and can be cleared by
+   * ClearAllStickyFaults()
+   *
+   * @return True if the compressor has been shorted since sticky faults were
+   * last cleared, otherwise false.
+   * @see GetCompressorShortedFault()
+   */
   bool GetCompressorShortedStickyFault() const;
+
+  /**
+   * Returns whether the compressor is currently disconnected.
+   *
+   * @return True if compressor is currently disconnected, otherwise false.
+   * @see GetCompressorNotConnectedStickyFault()
+   */
   bool GetCompressorNotConnectedFault() const;
+
+  /**
+   * Returns whether the compressor has been disconnected since sticky faults
+   * were last cleared. This fault is persistent and can be cleared by
+   * ClearAllStickyFaults()}
+   *
+   * @return True if the compressor has been disconnected since sticky faults
+   * were last cleared, otherwise false.
+   * @see GetCompressorNotConnectedFault()
+   */
   bool GetCompressorNotConnectedStickyFault() const;
 
   bool GetSolenoidVoltageFault() const;
   bool GetSolenoidVoltageStickyFault() const;
 
+  /** Clears all sticky faults on this device. */
   void ClearAllStickyFaults();
 
   void SetSolenoids(int mask, int values) override;
@@ -74,8 +154,20 @@
 
   void UnreserveCompressor() override;
 
+  /**
+   * Unsupported by the CTRE PCM.
+   *
+   * @param channel Unsupported.
+   * @return 0
+   */
   units::volt_t GetAnalogVoltage(int channel) const override;
 
+  /**
+   * Unsupported by the CTRE PCM.
+   *
+   * @param channel Unsupported.
+   * @return 0
+   */
   units::pounds_per_square_inch_t GetPressure(int channel) const override;
 
   Solenoid MakeSolenoid(int channel) override;
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/Preferences.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/Preferences.h
index b939d9e..0094ad0 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/Preferences.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/Preferences.h
@@ -10,8 +10,6 @@
 #include <string_view>
 #include <vector>
 
-#include <wpi/deprecated.h>
-
 namespace frc {
 
 /**
@@ -31,15 +29,6 @@
 class Preferences {
  public:
   /**
-   * Get the one and only {@link Preferences} object.
-   *
-   * @return pointer to the {@link Preferences}
-   * @deprecated Use the static methods
-   */
-  WPI_DEPRECATED("Use static methods")
-  static Preferences* GetInstance();
-
-  /**
    * Returns a vector of all the keys.
    *
    * @return a vector of the keys
@@ -120,18 +109,6 @@
   static void SetString(std::string_view key, std::string_view value);
 
   /**
-   * Puts the given string into the preferences table.
-   *
-   * The value may not have quotation marks, nor may the key have any whitespace
-   * nor an equals sign.
-   *
-   * @param key   the key
-   * @param value the value
-   */
-  WPI_DEPRECATED("Use SetString instead.")
-  static void PutString(std::string_view key, std::string_view value);
-
-  /**
    * Puts the given string into the preferences table if it doesn't
    * already exist.
    */
@@ -148,17 +125,6 @@
   static void SetInt(std::string_view key, int value);
 
   /**
-   * Puts the given int into the preferences table.
-   *
-   * The key may not have any whitespace nor an equals sign.
-   *
-   * @param key   the key
-   * @param value the value
-   */
-  WPI_DEPRECATED("Use SetInt instead.")
-  static void PutInt(std::string_view key, int value);
-
-  /**
    * Puts the given int into the preferences table if it doesn't
    * already exist.
    */
@@ -175,17 +141,6 @@
   static void SetDouble(std::string_view key, double value);
 
   /**
-   * Puts the given double into the preferences table.
-   *
-   * The key may not have any whitespace nor an equals sign.
-   *
-   * @param key   the key
-   * @param value the value
-   */
-  WPI_DEPRECATED("Use SetDouble instead.")
-  static void PutDouble(std::string_view key, double value);
-
-  /**
    * Puts the given double into the preferences table if it doesn't
    * already exist.
    */
@@ -202,17 +157,6 @@
   static void SetFloat(std::string_view key, float value);
 
   /**
-   * Puts the given float into the preferences table.
-   *
-   * The key may not have any whitespace nor an equals sign.
-   *
-   * @param key   the key
-   * @param value the value
-   */
-  WPI_DEPRECATED("Use SetFloat instead.")
-  static void PutFloat(std::string_view key, float value);
-
-  /**
    * Puts the given float into the preferences table if it doesn't
    * already exist.
    */
@@ -229,17 +173,6 @@
   static void SetBoolean(std::string_view key, bool value);
 
   /**
-   * Puts the given boolean into the preferences table.
-   *
-   * The key may not have any whitespace nor an equals sign.
-   *
-   * @param key   the key
-   * @param value the value
-   */
-  WPI_DEPRECATED("Use SetBoolean instead.")
-  static void PutBoolean(std::string_view key, bool value);
-
-  /**
    * Puts the given boolean into the preferences table if it doesn't
    * already exist.
    */
@@ -256,17 +189,6 @@
   static void SetLong(std::string_view key, int64_t value);
 
   /**
-   * Puts the given long (int64_t) into the preferences table.
-   *
-   * The key may not have any whitespace nor an equals sign.
-   *
-   * @param key   the key
-   * @param value the value
-   */
-  WPI_DEPRECATED("Use SetLong instead.")
-  static void PutLong(std::string_view key, int64_t value);
-
-  /**
    * Puts the given long into the preferences table if it doesn't
    * already exist.
    */
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/RobotBase.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/RobotBase.h
index 70c6093..3ff4617 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/RobotBase.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/RobotBase.h
@@ -11,7 +11,6 @@
 #include <hal/HALBase.h>
 #include <hal/Main.h>
 #include <wpi/condition_variable.h>
-#include <wpi/deprecated.h>
 #include <wpi/mutex.h>
 
 #include "frc/Errors.h"
@@ -22,6 +21,9 @@
 int RunHALInitialization();
 
 namespace impl {
+#ifndef __FRC_ROBORIO__
+void ResetMotorSafety();
+#endif
 
 template <class Robot>
 void RunRobot(wpi::mutex& m, Robot** robot) {
@@ -35,7 +37,7 @@
   } catch (const frc::RuntimeError& e) {
     e.Report();
     FRC_ReportError(
-        err::Error, "{}",
+        err::Error,
         "The robot program quit unexpectedly."
         " This is usually due to a code error.\n"
         "  The above stacktrace can help determine where the error occurred.\n"
@@ -104,6 +106,9 @@
     impl::RunRobot<Robot>(m, &robot);
   }
 
+#ifndef __FRC_ROBORIO__
+  frc::impl::ResetMotorSafety();
+#endif
   HAL_Shutdown();
 
   return 0;
@@ -156,16 +161,6 @@
    *
    * @return True if the robot is currently operating in Tele-Op mode as
    *         determined by the field controls.
-   * @deprecated Use IsTeleop() instead.
-   */
-  WPI_DEPRECATED("Use IsTeleop() instead")
-  bool IsOperatorControl() const;
-
-  /**
-   * Determine if the robot is currently in Operator Control mode.
-   *
-   * @return True if the robot is currently operating in Tele-Op mode as
-   *         determined by the field controls.
    */
   bool IsTeleop() const;
 
@@ -173,16 +168,6 @@
    * Determine if the robot is current in Operator Control mode and enabled.
    *
    * @return True if the robot is currently operating in Tele-Op mode while
-   *         enabled as determined by the field-controls.
-   * @deprecated Use IsTeleopEnabled() instead.
-   */
-  WPI_DEPRECATED("Use IsTeleopEnabled() instead")
-  bool IsOperatorControlEnabled() const;
-
-  /**
-   * Determine if the robot is current in Operator Control mode and enabled.
-   *
-   * @return True if the robot is currently operating in Tele-Op mode while
    * wnabled as determined by the field-controls.
    */
   bool IsTeleopEnabled() const;
@@ -196,14 +181,6 @@
   bool IsTest() const;
 
   /**
-   * Indicates if new data is available from the driver station.
-   *
-   * @return Has new data arrived over the network since the last time this
-   *         function was called?
-   */
-  bool IsNewDataAvailable() const;
-
-  /**
    * Gets the ID of the main robot thread.
    */
   static std::thread::id GetThreadId();
@@ -237,7 +214,9 @@
    *
    * @return If the robot is running in simulation.
    */
-  static constexpr bool IsSimulation() { return !IsReal(); }
+  static constexpr bool IsSimulation() {
+    return !IsReal();
+  }
 
   /**
    * Constructor for a generic robot program.
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/RobotController.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/RobotController.h
index e9750f0..c020d34 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/RobotController.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/RobotController.h
@@ -6,6 +6,8 @@
 
 #include <stdint.h>
 
+#include <string>
+
 #include <units/voltage.h>
 
 namespace frc {
@@ -43,6 +45,24 @@
   static int64_t GetFPGARevision();
 
   /**
+   * Return the serial number of the roboRIO.
+   *
+   * @return The serial number of the roboRIO.
+   */
+  static std::string GetSerialNumber();
+
+  /**
+   * Return the comments from the roboRIO web interface.
+   *
+   * The comments string is cached after the first call to this function on the
+   * RoboRIO - restart the robot code to reload the comments string after
+   * changing it in the web interface.
+   *
+   * @return The comments from the roboRIO web interface.
+   */
+  static std::string GetComments();
+
+  /**
    * Read the microsecond-resolution timer on the FPGA.
    *
    * @return The current time in microseconds according to the FPGA (since FPGA
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/RobotState.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/RobotState.h
index cb97b13..0489b9b 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/RobotState.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/RobotState.h
@@ -4,8 +4,6 @@
 
 #pragma once
 
-#include <wpi/deprecated.h>
-
 namespace frc {
 
 class RobotState {
@@ -15,8 +13,6 @@
   static bool IsDisabled();
   static bool IsEnabled();
   static bool IsEStopped();
-  WPI_DEPRECATED("Use IsTeleop() instead")
-  static bool IsOperatorControl();
   static bool IsTeleop();
   static bool IsAutonomous();
   static bool IsTest();
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/SPI.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/SPI.h
index 38b5e04..4063550 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/SPI.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/SPI.h
@@ -7,11 +7,11 @@
 #include <stdint.h>
 
 #include <memory>
+#include <span>
 
 #include <hal/SPITypes.h>
 #include <units/time.h>
 #include <wpi/deprecated.h>
-#include <wpi/span.h>
 
 namespace frc {
 
@@ -27,6 +27,12 @@
 class SPI {
  public:
   enum Port { kOnboardCS0 = 0, kOnboardCS1, kOnboardCS2, kOnboardCS3, kMXP };
+  enum Mode {
+    kMode0 = HAL_SPI_kMode0,
+    kMode1 = HAL_SPI_kMode1,
+    kMode2 = HAL_SPI_kMode2,
+    kMode3 = HAL_SPI_kMode3
+  };
 
   /**
    * Constructor
@@ -55,60 +61,73 @@
   /**
    * Configure the order that bits are sent and received on the wire
    * to be most significant bit first.
+   *
+   * @deprecated Does not work, will be removed.
    */
+  WPI_DEPRECATED("Not supported by roboRIO.")
   void SetMSBFirst();
 
   /**
    * Configure the order that bits are sent and received on the wire
    * to be least significant bit first.
+   *
+   * @deprecated Does not work, will be removed.
    */
+  WPI_DEPRECATED("Not supported by roboRIO.")
   void SetLSBFirst();
 
   /**
    * Configure that the data is stable on the leading edge and the data
    * changes on the trailing edge.
+   *
+   * @deprecated Use SetMode() instead.
    */
+  WPI_DEPRECATED("Use SetMode() instead")
   void SetSampleDataOnLeadingEdge();
 
   /**
    * Configure that the data is stable on the trailing edge and the data
    * changes on the leading edge.
+   *
+   * @deprecated Use SetMode() instead.
    */
+  WPI_DEPRECATED("Use SetMode() instead")
   void SetSampleDataOnTrailingEdge();
 
   /**
-   * Configure that the data is stable on the falling edge and the data
-   * changes on the rising edge.
-   *
-   * @deprecated Use SetSampleDataOnTrailingEdge() instead.
-   *
-   */
-  WPI_DEPRECATED("Use SetSampleDataOnTrailingEdge instead.")
-  void SetSampleDataOnFalling();
-
-  /**
-   * Configure that the data is stable on the rising edge and the data
-   * changes on the falling edge.
-   *
-   * @deprecated Use SetSampleDataOnLeadingEdge() instead.
-   *
-   */
-  WPI_DEPRECATED("Use SetSampleDataOnLeadingEdge instead")
-  void SetSampleDataOnRising();
-
-  /**
    * Configure the clock output line to be active low.
    * This is sometimes called clock polarity high or clock idle high.
+   *
+   * @deprecated Use SetMode() instead.
    */
+  WPI_DEPRECATED("Use SetMode() instead")
   void SetClockActiveLow();
 
   /**
    * Configure the clock output line to be active high.
    * This is sometimes called clock polarity low or clock idle low.
+   *
+   * @deprecated Use SetMode() instead.
    */
+  WPI_DEPRECATED("Use SetMode() instead")
   void SetClockActiveHigh();
 
   /**
+   * Sets the mode for the SPI device.
+   *
+   * <p>Mode 0 is Clock idle low, data sampled on rising edge
+   *
+   * <p>Mode 1 is Clock idle low, data sampled on falling edge
+   *
+   * <p>Mode 2 is Clock idle high, data sampled on falling edge
+   *
+   * <p>Mode 3 is Clock idle high, data sampled on rising edge
+   *
+   * @param mode The mode to set.
+   */
+  void SetMode(Mode mode);
+
+  /**
    * Configure the chip select line to be active high.
    */
   void SetChipSelectActiveHigh();
@@ -177,7 +196,7 @@
    * @param dataToSend data to send (maximum 23 bytes)
    * @param zeroSize number of zeros to send after the data
    */
-  void SetAutoTransmitData(wpi::span<const uint8_t> dataToSend, int zeroSize);
+  void SetAutoTransmitData(std::span<const uint8_t> dataToSend, int zeroSize);
 
   /**
    * Start running the automatic SPI transfer engine at a periodic rate.
@@ -190,19 +209,6 @@
   void StartAutoRate(units::second_t period);
 
   /**
-   * Start running the automatic SPI transfer engine at a periodic rate.
-   *
-   * InitAuto() and SetAutoTransmitData() must be called before calling this
-   * function.
-   *
-   * @deprecated use unit-safe StartAutoRate(units::second_t period) instead.
-   *
-   * @param period period between transfers, in seconds (us resolution)
-   */
-  WPI_DEPRECATED("Use StartAutoRate with unit-safety instead")
-  void StartAutoRate(double period);
-
-  /**
    * Start running the automatic SPI transfer engine when a trigger occurs.
    *
    * InitAuto() and SetAutoTransmitData() must be called before calling this
@@ -287,31 +293,6 @@
                        int dataSize, bool isSigned, bool bigEndian);
 
   /**
-   * Initialize the accumulator.
-   *
-   * @deprecated Use unit-safe version instead.
-   *             InitAccumulator(units::second_t period, int cmd, int <!--
-   * -->         xferSize, int validMask, int validValue, int dataShift, <!--
-   * -->         int dataSize, bool isSigned, bool bigEndian)
-   *
-   * @param period     Time between reads
-   * @param cmd        SPI command to send to request data
-   * @param xferSize   SPI transfer size, in bytes
-   * @param validMask  Mask to apply to received data for validity checking
-   * @param validValue After valid_mask is applied, required matching value for
-   *                   validity checking
-   * @param dataShift  Bit shift to apply to received data to get actual data
-   *                   value
-   * @param dataSize   Size (in bits) of data field
-   * @param isSigned   Is data field signed?
-   * @param bigEndian  Is device big endian?
-   */
-  WPI_DEPRECATED("Use InitAccumulator with unit-safety instead")
-  void InitAccumulator(double period, int cmd, int xferSize, int validMask,
-                       int validValue, int dataShift, int dataSize,
-                       bool isSigned, bool bigEndian);
-
-  /**
    * Frees the accumulator.
    */
   void FreeAccumulator();
@@ -404,9 +385,7 @@
 
  protected:
   hal::SPIPort m_port;
-  bool m_msbFirst = false;          // Default little-endian
-  bool m_sampleOnTrailing = false;  // Default data updated on falling edge
-  bool m_clockIdleHigh = false;     // Default clock active high
+  HAL_SPIMode m_mode = HAL_SPIMode::HAL_SPI_kMode0;
 
  private:
   void Init();
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/SpeedController.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/SpeedController.h
deleted file mode 100644
index 8473015..0000000
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/SpeedController.h
+++ /dev/null
@@ -1,74 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <units/voltage.h>
-#include <wpi/deprecated.h>
-
-namespace frc {
-
-/**
- * Interface for speed controlling devices.
- *
- * @deprecated Use MotorController.
- */
-class WPI_DEPRECATED("use MotorController") SpeedController {
- public:
-  virtual ~SpeedController() = default;
-
-  /**
-   * Common interface for setting the speed of a speed controller.
-   *
-   * @param speed The speed to set.  Value should be between -1.0 and 1.0.
-   */
-  virtual void Set(double speed) = 0;
-
-  /**
-   * Sets the voltage output of the SpeedController.  Compensates for
-   * the current bus voltage to ensure that the desired voltage is output even
-   * if the battery voltage is below 12V - highly useful when the voltage
-   * outputs are "meaningful" (e.g. they come from a feedforward calculation).
-   *
-   * <p>NOTE: This function *must* be called regularly in order for voltage
-   * compensation to work properly - unlike the ordinary set function, it is not
-   * "set it and forget it."
-   *
-   * @param output The voltage to output.
-   */
-  virtual void SetVoltage(units::volt_t output);
-
-  /**
-   * Common interface for getting the current set speed of a speed controller.
-   *
-   * @return The current set speed.  Value is between -1.0 and 1.0.
-   */
-  virtual double Get() const = 0;
-
-  /**
-   * Common interface for inverting direction of a speed controller.
-   *
-   * @param isInverted The state of inversion, true is inverted.
-   */
-  virtual void SetInverted(bool isInverted) = 0;
-
-  /**
-   * Common interface for returning the inversion state of a speed controller.
-   *
-   * @return isInverted The state of inversion, true is inverted.
-   */
-  virtual bool GetInverted() const = 0;
-
-  /**
-   * Common interface for disabling a motor.
-   */
-  virtual void Disable() = 0;
-
-  /**
-   * Common interface to stop the motor until Set is called again.
-   */
-  virtual void StopMotor() = 0;
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/SpeedControllerGroup.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/SpeedControllerGroup.h
deleted file mode 100644
index 5a097b5..0000000
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/SpeedControllerGroup.h
+++ /dev/null
@@ -1,55 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <functional>
-#include <vector>
-
-#include <wpi/deprecated.h>
-#include <wpi/sendable/Sendable.h>
-#include <wpi/sendable/SendableHelper.h>
-
-#include "frc/motorcontrol/MotorController.h"
-
-namespace frc {
-
-/**
- * Allows multiple SpeedController objects to be linked together.
- *
- * @deprecated Use MotorControllerGroup.
- */
-class WPI_DEPRECATED("use MotorControllerGroup") SpeedControllerGroup
-    : public wpi::Sendable,
-      public MotorController,
-      public wpi::SendableHelper<SpeedControllerGroup> {
- public:
-  template <class... SpeedControllers>
-  explicit SpeedControllerGroup(SpeedController& speedController,
-                                SpeedControllers&... speedControllers);
-  explicit SpeedControllerGroup(
-      std::vector<std::reference_wrapper<SpeedController>>&& speedControllers);
-
-  SpeedControllerGroup(SpeedControllerGroup&&) = default;
-  SpeedControllerGroup& operator=(SpeedControllerGroup&&) = default;
-
-  void Set(double speed) override;
-  double Get() const override;
-  void SetInverted(bool isInverted) override;
-  bool GetInverted() const override;
-  void Disable() override;
-  void StopMotor() override;
-
-  void InitSendable(wpi::SendableBuilder& builder) override;
-
- private:
-  bool m_isInverted = false;
-  std::vector<std::reference_wrapper<SpeedController>> m_speedControllers;
-
-  void Initialize();
-};
-
-}  // namespace frc
-
-#include "frc/SpeedControllerGroup.inc"
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/SpeedControllerGroup.inc b/third_party/allwpilib/wpilibc/src/main/native/include/frc/SpeedControllerGroup.inc
deleted file mode 100644
index d5f17b4..0000000
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/SpeedControllerGroup.inc
+++ /dev/null
@@ -1,22 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <functional>
-#include <vector>
-
-#include "frc/SpeedControllerGroup.h"
-
-namespace frc {
-
-template <class... SpeedControllers>
-SpeedControllerGroup::SpeedControllerGroup(
-    SpeedController& speedController, SpeedControllers&... speedControllers)
-    : m_speedControllers(std::vector<std::reference_wrapper<SpeedController>>{
-          speedController, speedControllers...}) {
-  Initialize();
-}
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/SynchronousInterrupt.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/SynchronousInterrupt.h
index 03cc4f8..fbe0fca 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/SynchronousInterrupt.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/SynchronousInterrupt.h
@@ -21,6 +21,9 @@
  */
 class SynchronousInterrupt {
  public:
+  /**
+   * Event trigger combinations for a synchronous interrupt.
+   */
   enum WaitResult {
     kTimeout = 0x0,
     kRisingEdge = 0x1,
@@ -62,7 +65,7 @@
    *
    * @param timeout The timeout to wait for. 0s or less will return immediately.
    * @param ignorePrevious True to ignore any previous interrupts, false to
-   * return interrupt value if an interrupt has occured since last call.
+   * return interrupt value if an interrupt has occurred since last call.
    * @return The edge(s) that were triggered, or timeout.
    */
   WaitResult WaitForInterrupt(units::second_t timeout,
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/TimedRobot.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/TimedRobot.h
index cc64c03..f32e748 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/TimedRobot.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/TimedRobot.h
@@ -11,7 +11,6 @@
 #include <hal/Types.h>
 #include <units/math.h>
 #include <units/time.h>
-#include <wpi/deprecated.h>
 #include <wpi/priority_queue.h>
 
 #include "frc/IterativeRobotBase.h"
@@ -45,17 +44,6 @@
   /**
    * Constructor for TimedRobot.
    *
-   * @deprecated use unit safe constructor instead.
-   * TimedRobot(units::second_t period = kDefaultPeriod)
-   *
-   * @param period Period in seconds.
-   */
-  WPI_DEPRECATED("Use constructor with unit-safety instead.")
-  explicit TimedRobot(double period);
-
-  /**
-   * Constructor for TimedRobot.
-   *
    * @param period Period.
    */
   explicit TimedRobot(units::second_t period = kDefaultPeriod);
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/Timer.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/Timer.h
index 0aed658..14674ee 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/Timer.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/Timer.h
@@ -5,7 +5,6 @@
 #pragma once
 
 #include <units/time.h>
-#include <wpi/deprecated.h>
 
 namespace frc {
 
@@ -101,18 +100,6 @@
    *
    * @param period The period to check for.
    * @return       True if the period has passed.
-   * @deprecated Use AdvanceIfElapsed() instead.
-   */
-  WPI_DEPRECATED("Use AdvanceIfElapsed() instead.")
-  bool HasPeriodPassed(units::second_t period);
-
-  /**
-   * Check if the period specified has passed and if it has, advance the start
-   * time by that period. This is useful to decide if it's time to do periodic
-   * work without drifting later by the time it took to get around to checking.
-   *
-   * @param period The period to check for.
-   * @return       True if the period has passed.
    */
   bool AdvanceIfElapsed(units::second_t period);
 
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/Ultrasonic.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/Ultrasonic.h
index 253192f..137a5b7 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/Ultrasonic.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/Ultrasonic.h
@@ -164,11 +164,8 @@
    */
   static void UltrasonicChecker();
 
-  // Time (sec) for the ping trigger pulse.
-  static constexpr double kPingTime = 10 * 1e-6;
-
-  // Priority that the ultrasonic round robin task runs.
-  static constexpr int kPriority = 64;
+  // Time (usec) for the ping trigger pulse.
+  static constexpr auto kPingTime = 10_us;
 
   // Max time (ms) between readings.
   static constexpr auto kMaxUltrasonicTime = 0.1_s;
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/XboxController.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/XboxController.h
index cbdc7d7..370e46e 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/XboxController.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/XboxController.h
@@ -97,6 +97,24 @@
   bool GetRightBumperReleased();
 
   /**
+   * Constructs an event instance around the left bumper's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the left bumper's digital signal
+   * attached to the given loop.
+   */
+  BooleanEvent LeftBumper(EventLoop* loop) const;
+
+  /**
+   * Constructs an event instance around the right bumper's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the right bumper's digital signal
+   * attached to the given loop.
+   */
+  BooleanEvent RightBumper(EventLoop* loop) const;
+
+  /**
    * Read the value of the left stick button (LSB) on the controller.
    */
   bool GetLeftStickButton() const;
@@ -127,6 +145,24 @@
   bool GetRightStickButtonReleased();
 
   /**
+   * Constructs an event instance around the left stick's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the left stick's digital signal
+   * attached to the given loop.
+   */
+  BooleanEvent LeftStick(EventLoop* loop) const;
+
+  /**
+   * Constructs an event instance around the right stick's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the right stick's digital signal
+   * attached to the given loop.
+   */
+  BooleanEvent RightStick(EventLoop* loop) const;
+
+  /**
    * Read the value of the A button on the controller.
    *
    * @return The state of the button.
@@ -148,6 +184,15 @@
   bool GetAButtonReleased();
 
   /**
+   * Constructs an event instance around the A button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the A button's digital signal
+   * attached to the given loop.
+   */
+  BooleanEvent A(EventLoop* loop) const;
+
+  /**
    * Read the value of the B button on the controller.
    *
    * @return The state of the button.
@@ -169,6 +214,15 @@
   bool GetBButtonReleased();
 
   /**
+   * Constructs an event instance around the B button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the B button's digital signal
+   * attached to the given loop.
+   */
+  BooleanEvent B(EventLoop* loop) const;
+
+  /**
    * Read the value of the X button on the controller.
    *
    * @return The state of the button.
@@ -190,6 +244,15 @@
   bool GetXButtonReleased();
 
   /**
+   * Constructs an event instance around the X button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the X button's digital signal
+   * attached to the given loop.
+   */
+  BooleanEvent X(EventLoop* loop) const;
+
+  /**
    * Read the value of the Y button on the controller.
    *
    * @return The state of the button.
@@ -211,6 +274,15 @@
   bool GetYButtonReleased();
 
   /**
+   * Constructs an event instance around the Y button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the Y button's digital signal
+   * attached to the given loop.
+   */
+  BooleanEvent Y(EventLoop* loop) const;
+
+  /**
    * Whether the Y button was released since the last check.
    *
    * @return Whether the button was released since the last check.
@@ -232,6 +304,15 @@
   bool GetBackButtonReleased();
 
   /**
+   * Constructs an event instance around the back button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the back button's digital signal
+   * attached to the given loop.
+   */
+  BooleanEvent Back(EventLoop* loop) const;
+
+  /**
    * Read the value of the start button on the controller.
    *
    * @return The state of the button.
@@ -252,6 +333,59 @@
    */
   bool GetStartButtonReleased();
 
+  /**
+   * Constructs an event instance around the start button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the start button's digital signal
+   * attached to the given loop.
+   */
+  BooleanEvent Start(EventLoop* loop) const;
+
+  /**
+   * Constructs an event instance around the axis value of the left trigger. The
+   * returned trigger will be true when the axis value is greater than {@code
+   * threshold}.
+   * @param threshold the minimum axis value for the returned event to be true.
+   * This value should be in the range [0, 1] where 0 is the unpressed state of
+   * the axis.
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance that is true when the left trigger's axis exceeds
+   * the provided threshold, attached to the given event loop
+   */
+  BooleanEvent LeftTrigger(double threshold, EventLoop* loop) const;
+
+  /**
+   * Constructs an event instance around the axis value of the left trigger.
+   * The returned trigger will be true when the axis value is greater than 0.5.
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance that is true when the right trigger's axis
+   * exceeds 0.5, attached to the given event loop
+   */
+  BooleanEvent LeftTrigger(EventLoop* loop) const;
+
+  /**
+   * Constructs an event instance around the axis value of the right trigger.
+   * The returned trigger will be true when the axis value is greater than
+   * {@code threshold}.
+   * @param threshold the minimum axis value for the returned event to be true.
+   * This value should be in the range [0, 1] where 0 is the unpressed state of
+   * the axis.
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance that is true when the right trigger's axis
+   * exceeds the provided threshold, attached to the given event loop
+   */
+  BooleanEvent RightTrigger(double threshold, EventLoop* loop) const;
+
+  /**
+   * Constructs an event instance around the axis value of the right trigger.
+   * The returned trigger will be true when the axis value is greater than 0.5.
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance that is true when the right trigger's axis
+   * exceeds 0.5, attached to the given event loop
+   */
+  BooleanEvent RightTrigger(EventLoop* loop) const;
+
   struct Button {
     static constexpr int kLeftBumper = 5;
     static constexpr int kRightBumper = 6;
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h
index 7009eb9..2e701a3 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h
@@ -13,18 +13,7 @@
 
 namespace frc {
 
-#if defined(_MSC_VER)
-#pragma warning(push)
-#pragma warning(disable : 4996)  // was declared deprecated
-#elif defined(__clang__)
-#pragma clang diagnostic push
-#pragma clang diagnostic ignored "-Wdeprecated-declarations"
-#elif defined(__GNUC__)
-#pragma GCC diagnostic push
-#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
-#endif
-
-class SpeedController;
+class MotorController;
 
 /**
  * A class for driving differential drive/skid-steer drive platforms such as
@@ -81,21 +70,22 @@
  * |       |
  * </pre>
  *
- * Each Drive() function provides different inverse kinematic relations for a
- * differential drive robot. Motor outputs for the right side are negated, so
- * motor direction inversion by the user is usually unnecessary.
+ * Each drive function provides different inverse kinematic relations for a
+ * differential drive robot.
  *
- * This library uses the NED axes convention (North-East-Down as external
- * reference in the world frame):
- * http://www.nuclearprojects.com/ins/images/axis_big.png.
- *
- * The positive X axis points ahead, the positive Y axis points to the right,
- * and the positive Z axis points down. Rotations follow the right-hand rule, so
- * clockwise rotation around the Z axis is positive.
+ * This library uses the NWU axes convention (North-West-Up as external
+ * reference in the world frame). The positive X axis points ahead, the positive
+ * Y axis points to the left, and the positive Z axis points up. Rotations
+ * follow the right-hand rule, so counterclockwise rotation around the Z axis is
+ * positive.
  *
  * Inputs smaller then 0.02 will be set to 0, and larger values will be scaled
  * so that the full range is still used. This deadband value can be changed
  * with SetDeadband().
+ *
+ * MotorSafety is enabled by default. The tankDrive, arcadeDrive,
+ * or curvatureDrive methods should be called periodically to avoid Motor
+ * Safety timeouts.
  */
 class DifferentialDrive : public RobotDriveBase,
                           public wpi::Sendable,
@@ -117,7 +107,7 @@
    * To pass multiple motors per side, use a MotorControllerGroup. If a motor
    * needs to be inverted, do so before passing it in.
    */
-  DifferentialDrive(SpeedController& leftMotor, SpeedController& rightMotor);
+  DifferentialDrive(MotorController& leftMotor, MotorController& rightMotor);
 
   ~DifferentialDrive() override = default;
 
@@ -133,7 +123,7 @@
    * @param xSpeed        The speed at which the robot should drive along the X
    *                      axis [-1.0..1.0]. Forward is positive.
    * @param zRotation     The rotation rate of the robot around the Z axis
-   *                      [-1.0..1.0]. Clockwise is positive.
+   *                      [-1.0..1.0]. Counterclockwise is positive.
    * @param squareInputs If set, decreases the input sensitivity at low speeds.
    */
   void ArcadeDrive(double xSpeed, double zRotation, bool squareInputs = true);
@@ -147,8 +137,8 @@
    *
    * @param xSpeed           The robot's speed along the X axis [-1.0..1.0].
    *                         Forward is positive.
-   * @param zRotation        The normalized curvature [-1.0..1.0]. Clockwise is
-   *                         positive.
+   * @param zRotation        The normalized curvature [-1.0..1.0].
+   *                         Counterclockwise is positive.
    * @param allowTurnInPlace If set, overrides constant-curvature turning for
    *                         turn-in-place maneuvers. zRotation will control
    *                         turning rate instead of curvature.
@@ -220,16 +210,8 @@
   void InitSendable(wpi::SendableBuilder& builder) override;
 
  private:
-  SpeedController* m_leftMotor;
-  SpeedController* m_rightMotor;
+  MotorController* m_leftMotor;
+  MotorController* m_rightMotor;
 };
 
-#if defined(_MSC_VER)
-#pragma warning(pop)
-#elif defined(__clang__)
-#pragma clang diagnostic pop
-#elif defined(__GNUC__)
-#pragma GCC diagnostic pop
-#endif
-
 }  // namespace frc
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/drive/KilloughDrive.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/drive/KilloughDrive.h
deleted file mode 100644
index d4c5c5c..0000000
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/drive/KilloughDrive.h
+++ /dev/null
@@ -1,192 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <memory>
-#include <string>
-
-#include <wpi/sendable/Sendable.h>
-#include <wpi/sendable/SendableHelper.h>
-
-#include "frc/drive/RobotDriveBase.h"
-#include "frc/drive/Vector2d.h"
-
-namespace frc {
-
-#if defined(_MSC_VER)
-#pragma warning(push)
-#pragma warning(disable : 4996)  // was declared deprecated
-#elif defined(__clang__)
-#pragma clang diagnostic push
-#pragma clang diagnostic ignored "-Wdeprecated-declarations"
-#elif defined(__GNUC__)
-#pragma GCC diagnostic push
-#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
-#endif
-
-class SpeedController;
-
-/**
- * A class for driving Killough drive platforms.
- *
- * Killough drives are triangular with one omni wheel on each corner.
- *
- * Drive base diagram:
- * <pre>
- *  /_____\
- * / \   / \
- *    \ /
- *    ---
- * </pre>
- *
- * Each Drive() function provides different inverse kinematic relations for a
- * Killough drive. The default wheel vectors are parallel to their respective
- * opposite sides, but can be overridden. See the constructor for more
- * information.
- *
- * This library uses the NED axes convention (North-East-Down as external
- * reference in the world frame):
- * http://www.nuclearprojects.com/ins/images/axis_big.png.
- *
- * The positive X axis points ahead, the positive Y axis points right, and the
- * and the positive Z axis points down. Rotations follow the right-hand rule, so
- * clockwise rotation around the Z axis is positive.
- */
-class KilloughDrive : public RobotDriveBase,
-                      public wpi::Sendable,
-                      public wpi::SendableHelper<KilloughDrive> {
- public:
-  static constexpr double kDefaultLeftMotorAngle = 60.0;
-  static constexpr double kDefaultRightMotorAngle = 120.0;
-  static constexpr double kDefaultBackMotorAngle = 270.0;
-
-  /**
-   * Wheel speeds for a Killough drive.
-   *
-   * Uses normalized voltage [-1.0..1.0].
-   */
-  struct WheelSpeeds {
-    double left = 0.0;
-    double right = 0.0;
-    double back = 0.0;
-  };
-
-  /**
-   * Construct a Killough drive with the given motors and default motor angles.
-   *
-   * The default motor angles make the wheels on each corner parallel to their
-   * respective opposite sides.
-   *
-   * If a motor needs to be inverted, do so before passing it in.
-   *
-   * @param leftMotor  The motor on the left corner.
-   * @param rightMotor The motor on the right corner.
-   * @param backMotor  The motor on the back corner.
-   */
-  KilloughDrive(SpeedController& leftMotor, SpeedController& rightMotor,
-                SpeedController& backMotor);
-
-  /**
-   * Construct a Killough drive with the given motors.
-   *
-   * Angles are measured in degrees clockwise from the positive X axis.
-   *
-   * @param leftMotor       The motor on the left corner.
-   * @param rightMotor      The motor on the right corner.
-   * @param backMotor       The motor on the back corner.
-   * @param leftMotorAngle  The angle of the left wheel's forward direction of
-   *                        travel.
-   * @param rightMotorAngle The angle of the right wheel's forward direction of
-   *                        travel.
-   * @param backMotorAngle  The angle of the back wheel's forward direction of
-   *                        travel.
-   */
-  KilloughDrive(SpeedController& leftMotor, SpeedController& rightMotor,
-                SpeedController& backMotor, double leftMotorAngle,
-                double rightMotorAngle, double backMotorAngle);
-
-  ~KilloughDrive() override = default;
-
-  KilloughDrive(KilloughDrive&&) = default;
-  KilloughDrive& operator=(KilloughDrive&&) = default;
-
-  /**
-   * Drive method for Killough platform.
-   *
-   * Angles are measured clockwise from the positive X axis. The robot's speed
-   * is independent from its angle or rotation rate.
-   *
-   * @param ySpeed    The robot's speed along the Y axis [-1.0..1.0]. Right is
-   *                  positive.
-   * @param xSpeed    The robot's speed along the X axis [-1.0..1.0]. Forward is
-   *                  positive.
-   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0].
-   *                  Clockwise is positive.
-   * @param gyroAngle The current angle reading from the gyro in degrees around
-   *                  the Z axis. Use this to implement field-oriented controls.
-   */
-  void DriveCartesian(double ySpeed, double xSpeed, double zRotation,
-                      double gyroAngle = 0.0);
-
-  /**
-   * Drive method for Killough platform.
-   *
-   * Angles are measured clockwise from the positive X axis. The robot's speed
-   * is independent from its angle or rotation rate.
-   *
-   * @param magnitude The robot's speed at a given angle [-1.0..1.0]. Forward is
-   *                  positive.
-   * @param angle     The angle around the Z axis at which the robot drives in
-   *                  degrees [-180..180].
-   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0].
-   *                  Clockwise is positive.
-   */
-  void DrivePolar(double magnitude, double angle, double zRotation);
-
-  /**
-   * Cartesian inverse kinematics for Killough platform.
-   *
-   * Angles are measured clockwise from the positive X axis. The robot's speed
-   * is independent from its angle or rotation rate.
-   *
-   * @param ySpeed    The robot's speed along the Y axis [-1.0..1.0]. Right is
-   *                  positive.
-   * @param xSpeed    The robot's speed along the X axis [-1.0..1.0]. Forward is
-   *                  positive.
-   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0].
-   *                  Clockwise is positive.
-   * @param gyroAngle The current angle reading from the gyro in degrees around
-   *                  the Z axis. Use this to implement field-oriented controls.
-   * @return Wheel speeds [-1.0..1.0].
-   */
-  WheelSpeeds DriveCartesianIK(double ySpeed, double xSpeed, double zRotation,
-                               double gyroAngle = 0.0);
-
-  void StopMotor() override;
-  std::string GetDescription() const override;
-
-  void InitSendable(wpi::SendableBuilder& builder) override;
-
- private:
-  SpeedController* m_leftMotor;
-  SpeedController* m_rightMotor;
-  SpeedController* m_backMotor;
-
-  Vector2d m_leftVec;
-  Vector2d m_rightVec;
-  Vector2d m_backVec;
-
-  bool reported = false;
-};
-
-#if defined(_MSC_VER)
-#pragma warning(pop)
-#elif defined(__clang__)
-#pragma clang diagnostic pop
-#elif defined(__GNUC__)
-#pragma GCC diagnostic pop
-#endif
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/drive/MecanumDrive.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/drive/MecanumDrive.h
index 757ae67..f4c28f4 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/drive/MecanumDrive.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/drive/MecanumDrive.h
@@ -7,25 +7,16 @@
 #include <memory>
 #include <string>
 
+#include <units/angle.h>
 #include <wpi/sendable/Sendable.h>
 #include <wpi/sendable/SendableHelper.h>
 
 #include "frc/drive/RobotDriveBase.h"
+#include "frc/geometry/Rotation2d.h"
 
 namespace frc {
 
-#if defined(_MSC_VER)
-#pragma warning(push)
-#pragma warning(disable : 4996)  // was declared deprecated
-#elif defined(__clang__)
-#pragma clang diagnostic push
-#pragma clang diagnostic ignored "-Wdeprecated-declarations"
-#elif defined(__GNUC__)
-#pragma GCC diagnostic push
-#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
-#endif
-
-class SpeedController;
+class MotorController;
 
 /**
  * A class for driving Mecanum drive platforms.
@@ -46,9 +37,11 @@
  * Each Drive() function provides different inverse kinematic relations for a
  * Mecanum drive robot.
  *
- * The positive Y axis points ahead, the positive X axis points to the right,
- * and the positive Z axis points down. Rotations follow the right-hand rule, so
- * clockwise rotation around the Z axis is positive.
+ * This library uses the NWU axes convention (North-West-Up as external
+ * reference in the world frame). The positive X axis points ahead, the positive
+ * Y axis points to the left, and the positive Z axis points up. Rotations
+ * follow the right-hand rule, so counterclockwise rotation around the Z axis is
+ * positive.
  *
  * Note: the axis conventions used in this class differ from DifferentialDrive.
  * This may change in a future year's WPILib release.
@@ -57,15 +50,8 @@
  * so that the full range is still used. This deadband value can be changed
  * with SetDeadband().
  *
- * RobotDrive porting guide:
- * <br>DriveCartesian(double, double, double, double) is equivalent to
- * RobotDrive's MecanumDrive_Cartesian(double, double, double, double)
- * if a deadband of 0 is used, and the ySpeed and gyroAngle values are inverted
- * compared to RobotDrive (eg DriveCartesian(xSpeed, -ySpeed, zRotation,
- * -gyroAngle).
- * <br>DrivePolar(double, double, double) is equivalent to
- * RobotDrive's MecanumDrive_Polar(double, double, double) if a
- * deadband of 0 is used.
+ * MotorSafety is enabled by default. The DriveCartesian or DrivePolar
+ * methods should be called periodically to avoid Motor Safety timeouts.
  */
 class MecanumDrive : public RobotDriveBase,
                      public wpi::Sendable,
@@ -88,9 +74,9 @@
    *
    * If a motor needs to be inverted, do so before passing it in.
    */
-  MecanumDrive(SpeedController& frontLeftMotor, SpeedController& rearLeftMotor,
-               SpeedController& frontRightMotor,
-               SpeedController& rearRightMotor);
+  MecanumDrive(MotorController& frontLeftMotor, MotorController& rearLeftMotor,
+               MotorController& frontRightMotor,
+               MotorController& rearRightMotor);
 
   ~MecanumDrive() override = default;
 
@@ -100,54 +86,54 @@
   /**
    * Drive method for Mecanum platform.
    *
-   * Angles are measured clockwise from the positive X axis. The robot's speed
-   * is independent from its angle or rotation rate.
+   * Angles are measured counterclockwise from the positive X axis. The robot's
+   * speed is independent from its angle or rotation rate.
    *
-   * @param ySpeed    The robot's speed along the Y axis [-1.0..1.0]. Forward is
+   * @param xSpeed    The robot's speed along the X axis [-1.0..1.0]. Forward is
    *                  positive.
-   * @param xSpeed    The robot's speed along the X axis [-1.0..1.0]. Right is
+   * @param ySpeed    The robot's speed along the Y axis [-1.0..1.0]. Left is
    *                  positive.
    * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0].
-   *                  Clockwise is positive.
-   * @param gyroAngle The current angle reading from the gyro in degrees around
-   *                  the Z axis. Use this to implement field-oriented controls.
+   *                  Counterclockwise is positive.
+   * @param gyroAngle The gyro heading around the Z axis. Use this to implement
+   *                  field-oriented controls.
    */
-  void DriveCartesian(double ySpeed, double xSpeed, double zRotation,
-                      double gyroAngle = 0.0);
+  void DriveCartesian(double xSpeed, double ySpeed, double zRotation,
+                      Rotation2d gyroAngle = 0_rad);
 
   /**
    * Drive method for Mecanum platform.
    *
-   * Angles are measured clockwise from the positive X axis. The robot's speed
-   * is independent from its angle or rotation rate.
+   * Angles are measured counterclockwise from the positive X axis. The robot's
+   * speed is independent from its angle or rotation rate.
    *
    * @param magnitude The robot's speed at a given angle [-1.0..1.0]. Forward is
    *                  positive.
-   * @param angle     The angle around the Z axis at which the robot drives in
-   *                  degrees [-180..180].
+   * @param angle     The angle around the Z axis at which the robot drives.
    * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0].
-   *                  Clockwise is positive.
+   *                  Counterclockwise is positive.
    */
-  void DrivePolar(double magnitude, double angle, double zRotation);
+  void DrivePolar(double magnitude, Rotation2d angle, double zRotation);
 
   /**
    * Cartesian inverse kinematics for Mecanum platform.
    *
-   * Angles are measured clockwise from the positive X axis. The robot's speed
-   * is independent from its angle or rotation rate.
+   * Angles are measured counterclockwise from the positive X axis. The robot's
+   * speed is independent from its angle or rotation rate.
    *
-   * @param ySpeed    The robot's speed along the Y axis [-1.0..1.0]. Forward is
+   * @param xSpeed    The robot's speed along the X axis [-1.0..1.0]. Forward is
    *                  positive.
-   * @param xSpeed    The robot's speed along the X axis [-1.0..1.0]. Right is
+   * @param ySpeed    The robot's speed along the Y axis [-1.0..1.0]. Left is
    *                  positive.
    * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0].
-   *                  Clockwise is positive.
-   * @param gyroAngle The current angle reading from the gyro in degrees around
-   *                  the Z axis. Use this to implement field-oriented controls.
+   *                  Counterclockwise is positive.
+   * @param gyroAngle The gyro heading around the Z axis. Use this to implement
+   *                  field-oriented controls.
    * @return Wheel speeds [-1.0..1.0].
    */
-  static WheelSpeeds DriveCartesianIK(double ySpeed, double xSpeed,
-                                      double zRotation, double gyroAngle = 0.0);
+  static WheelSpeeds DriveCartesianIK(double xSpeed, double ySpeed,
+                                      double zRotation,
+                                      Rotation2d gyroAngle = 0_rad);
 
   void StopMotor() override;
   std::string GetDescription() const override;
@@ -155,20 +141,12 @@
   void InitSendable(wpi::SendableBuilder& builder) override;
 
  private:
-  SpeedController* m_frontLeftMotor;
-  SpeedController* m_rearLeftMotor;
-  SpeedController* m_frontRightMotor;
-  SpeedController* m_rearRightMotor;
+  MotorController* m_frontLeftMotor;
+  MotorController* m_rearLeftMotor;
+  MotorController* m_frontRightMotor;
+  MotorController* m_rearRightMotor;
 
   bool reported = false;
 };
 
-#if defined(_MSC_VER)
-#pragma warning(pop)
-#elif defined(__clang__)
-#pragma clang diagnostic pop
-#elif defined(__GNUC__)
-#pragma GCC diagnostic pop
-#endif
-
 }  // namespace frc
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/drive/RobotDriveBase.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/drive/RobotDriveBase.h
index 8ce5636..b3fb56b 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/drive/RobotDriveBase.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/drive/RobotDriveBase.h
@@ -5,17 +5,17 @@
 #pragma once
 
 #include <memory>
+#include <span>
 #include <string>
 
-#include <wpi/deprecated.h>
-#include <wpi/span.h>
-
 #include "frc/MotorSafety.h"
 
 namespace frc {
 
 /**
  * Common base class for drive platforms.
+ *
+ * MotorSafety is enabled by default.
  */
 class RobotDriveBase : public MotorSafety {
  public:
@@ -71,21 +71,10 @@
 
  protected:
   /**
-   * Returns 0.0 if the given value is within the specified range around zero.
-   * The remaining range between the deadband and 1.0 is scaled from 0.0 to 1.0.
-   *
-   * @param value    value to clip
-   * @param deadband range around zero
-   * @deprecated Use ApplyDeadband() in frc/MathUtil.h.
-   */
-  WPI_DEPRECATED("Use ApplyDeadband() in frc/MathUtil.h")
-  static double ApplyDeadband(double value, double deadband);
-
-  /**
    * Renormalize all wheel speeds if the magnitude of any wheel is greater than
    * 1.0.
    */
-  static void Desaturate(wpi::span<double> wheelSpeeds);
+  static void Desaturate(std::span<double> wheelSpeeds);
 
   double m_deadband = 0.02;
   double m_maxOutput = 1.0;
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/drive/Vector2d.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/drive/Vector2d.h
deleted file mode 100644
index 92a3de6..0000000
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/drive/Vector2d.h
+++ /dev/null
@@ -1,46 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-namespace frc {
-
-/**
- * This is a 2D vector struct that supports basic vector operations.
- */
-struct Vector2d {
-  Vector2d() = default;
-  Vector2d(double x, double y);
-
-  /**
-   * Rotate a vector in Cartesian space.
-   *
-   * @param angle angle in degrees by which to rotate vector counter-clockwise.
-   */
-  void Rotate(double angle);
-
-  /**
-   * Returns dot product of this vector with argument.
-   *
-   * @param vec Vector with which to perform dot product.
-   */
-  double Dot(const Vector2d& vec) const;
-
-  /**
-   * Returns magnitude of vector.
-   */
-  double Magnitude() const;
-
-  /**
-   * Returns scalar projection of this vector onto argument.
-   *
-   * @param vec Vector onto which to project this vector.
-   */
-  double ScalarProject(const Vector2d& vec) const;
-
-  double x = 0.0;
-  double y = 0.0;
-};
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/event/BooleanEvent.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/event/BooleanEvent.h
new file mode 100644
index 0000000..745a53c
--- /dev/null
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/event/BooleanEvent.h
@@ -0,0 +1,135 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <frc/filter/Debouncer.h>
+
+#include <functional>
+#include <memory>
+
+#include <units/time.h>
+#include <wpi/FunctionExtras.h>
+
+#include "EventLoop.h"
+
+namespace frc {
+
+/**
+ * This class provides an easy way to link actions to inputs. Each object
+ * represents a boolean condition to which callback actions can be bound using
+ * {@link #IfHigh(std::function<void()>)}.
+ *
+ * <p>These events can easily be composed using factories such as {@link
+ * #operator!},
+ * {@link #operator||}, {@link #operator&&} etc.
+ *
+ * <p>To get an event that activates only when this one changes, see {@link
+ * #Falling()} and {@link #Rising()}.
+ */
+class BooleanEvent {
+ public:
+  /**
+   * Creates a new event with the given condition determining whether it is
+   * active.
+   *
+   * @param loop the loop that polls this event
+   * @param condition returns whether or not the event should be active
+   */
+  BooleanEvent(EventLoop* loop, std::function<bool()> condition);
+
+  /**
+   * Check whether this event is active or not.
+   *
+   * @return true if active.
+   */
+  bool GetAsBoolean() const;
+
+  /**
+   * Bind an action to this event.
+   *
+   * @param action the action to run if this event is active.
+   */
+  void IfHigh(std::function<void()> action);
+
+  operator std::function<bool()>();  // NOLINT
+
+  /**
+   * A method to "downcast" a BooleanEvent instance to a subclass (for example,
+   * to a command-based version of this class).
+   *
+   * @param ctor a method reference to the constructor of the subclass that
+   * accepts the loop as the first parameter and the condition/signal as the
+   * second.
+   * @return an instance of the subclass.
+   */
+  template <class T>
+  T CastTo(std::function<T(EventLoop*, std::function<bool()>)> ctor =
+               [](EventLoop* loop, std::function<bool()> condition) {
+                 return T(loop, condition);
+               }) {
+    return ctor(m_loop, m_condition);
+  }
+
+  /**
+   * Creates a new event that is active when this event is inactive, i.e. that
+   * acts as the negation of this event.
+   *
+   * @return the negated event
+   */
+  BooleanEvent operator!();
+
+  /**
+   * Composes this event with another event, returning a new event that is
+   * active when both events are active.
+   *
+   * <p>The new event will use this event's polling loop.
+   *
+   * @param rhs the event to compose with
+   * @return the event that is active when both events are active
+   */
+  BooleanEvent operator&&(std::function<bool()> rhs);
+
+  /**
+   * Composes this event with another event, returning a new event that is
+   * active when either event is active.
+   *
+   * <p>The new event will use this event's polling loop.
+   *
+   * @param rhs the event to compose with
+   * @return the event that is active when either event is active
+   */
+  BooleanEvent operator||(std::function<bool()> rhs);
+
+  /**
+   * Get a new event that events only when this one newly changes to true.
+   *
+   * @return a new event representing when this one newly changes to true.
+   */
+  BooleanEvent Rising();
+
+  /**
+   * Get a new event that triggers only when this one newly changes to false.
+   *
+   * @return a new event representing when this one newly changes to false.
+   */
+  BooleanEvent Falling();
+
+  /**
+   * Creates a new debounced event from this event - it will become active when
+   * this event has been active for longer than the specified period.
+   *
+   * @param debounceTime The debounce period.
+   * @param type The debounce type.
+   * @return The debounced event.
+   */
+  BooleanEvent Debounce(units::second_t debounceTime,
+                        frc::Debouncer::DebounceType type =
+                            frc::Debouncer::DebounceType::kRising);
+
+ private:
+  EventLoop* m_loop;
+  std::function<bool()> m_condition;
+};
+}  // namespace frc
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/event/EventLoop.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/event/EventLoop.h
new file mode 100644
index 0000000..d18fac3
--- /dev/null
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/event/EventLoop.h
@@ -0,0 +1,42 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <functional>
+#include <vector>
+
+#include <wpi/FunctionExtras.h>
+
+namespace frc {
+/** The loop polling BooleanEvent objects and executing the actions bound to
+ * them. */
+class EventLoop {
+ public:
+  EventLoop();
+
+  EventLoop(const EventLoop&) = delete;
+  EventLoop& operator=(const EventLoop&) = delete;
+
+  /**
+   * Bind a new action to run.
+   *
+   * @param action the action to run.
+   */
+  void Bind(wpi::unique_function<void()> action);
+
+  /**
+   * Poll all bindings.
+   */
+  void Poll();
+
+  /**
+   * Clear all bindings.
+   */
+  void Clear();
+
+ private:
+  std::vector<wpi::unique_function<void()>> m_bindings;
+};
+}  // namespace frc
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/event/NetworkBooleanEvent.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/event/NetworkBooleanEvent.h
new file mode 100644
index 0000000..85f7039
--- /dev/null
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/event/NetworkBooleanEvent.h
@@ -0,0 +1,79 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <memory>
+#include <string_view>
+
+#include "BooleanEvent.h"
+
+namespace nt {
+class BooleanSubscriber;
+class BooleanTopic;
+class NetworkTable;
+class NetworkTableInstance;
+}  // namespace nt
+
+namespace frc {
+/**
+ * A Button that uses a NetworkTable boolean field.
+ *
+ * This class is provided by the NewCommands VendorDep
+ */
+class NetworkBooleanEvent : public BooleanEvent {
+ public:
+  /**
+   * Creates a new event with the given boolean topic determining whether it is
+   * active.
+   *
+   * @param loop the loop that polls this event
+   * @param topic The boolean topic that contains the value
+   */
+  NetworkBooleanEvent(EventLoop* loop, nt::BooleanTopic topic);
+
+  /**
+   * Creates a new event with the given boolean subscriber determining whether
+   * it is active.
+   *
+   * @param loop the loop that polls this event
+   * @param sub The boolean subscriber that provides the value
+   */
+  NetworkBooleanEvent(EventLoop* loop, nt::BooleanSubscriber sub);
+
+  /**
+   * Creates a new event with the given boolean topic determining whether it is
+   * active.
+   *
+   * @param loop the loop that polls this event
+   * @param table The NetworkTable that contains the topic
+   * @param topicName The topic name within the table that contains the value
+   */
+  NetworkBooleanEvent(EventLoop* loop, std::shared_ptr<nt::NetworkTable> table,
+                      std::string_view topicName);
+
+  /**
+   * Creates a new event with the given boolean topic determining whether it is
+   * active.
+   *
+   * @param loop the loop that polls this event
+   * @param tableName The NetworkTable name that contains the topic
+   * @param topicName The topic name within the table that contains the value
+   */
+  NetworkBooleanEvent(EventLoop* loop, std::string_view tableName,
+                      std::string_view topicName);
+
+  /**
+   * Creates a new event with the given boolean topic determining whether it is
+   * active.
+   *
+   * @param loop the loop that polls this event
+   * @param inst The NetworkTable instance to use
+   * @param tableName The NetworkTable that contains the topic
+   * @param topicName The topic name within the table that contains the value
+   */
+  NetworkBooleanEvent(EventLoop* loop, nt::NetworkTableInstance inst,
+                      std::string_view tableName, std::string_view topicName);
+};
+}  // namespace frc
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/interfaces/Gyro.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/interfaces/Gyro.h
index 50417ea..b74a3cf 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/interfaces/Gyro.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/interfaces/Gyro.h
@@ -77,7 +77,7 @@
    *         based on integration of the returned rate from the gyro.
    */
   virtual Rotation2d GetRotation2d() const {
-    return Rotation2d{units::degree_t{-GetAngle()}};
+    return units::degree_t{-GetAngle()};
   }
 };
 
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/internal/DriverStationModeThread.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/internal/DriverStationModeThread.h
new file mode 100644
index 0000000..f4fd11c
--- /dev/null
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/internal/DriverStationModeThread.h
@@ -0,0 +1,36 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <atomic>
+#include <thread>
+
+namespace frc::internal {
+class DriverStationModeThread {
+ public:
+  DriverStationModeThread();
+  ~DriverStationModeThread();
+
+  DriverStationModeThread(const DriverStationModeThread& other) = delete;
+  DriverStationModeThread(DriverStationModeThread&& other) = delete;
+  DriverStationModeThread& operator=(const DriverStationModeThread& other) =
+      delete;
+  DriverStationModeThread& operator=(DriverStationModeThread&& other) = delete;
+
+  void InAutonomous(bool entering);
+  void InDisabled(bool entering);
+  void InTeleop(bool entering);
+  void InTest(bool entering);
+
+ private:
+  std::atomic_bool m_keepAlive{false};
+  std::thread m_thread;
+  void Run();
+  bool m_userInDisabled{false};
+  bool m_userInAutonomous{false};
+  bool m_userInTeleop{false};
+  bool m_userInTest{false};
+};
+}  // namespace frc::internal
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/livewindow/LiveWindow.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/livewindow/LiveWindow.h
index 6851cde..3714146 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/livewindow/LiveWindow.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/livewindow/LiveWindow.h
@@ -6,8 +6,6 @@
 
 #include <functional>
 
-#include <wpi/deprecated.h>
-
 namespace wpi {
 class Sendable;
 }  // namespace wpi
@@ -18,20 +16,9 @@
  * The LiveWindow class is the public interface for putting sensors and
  * actuators on the LiveWindow.
  */
-class LiveWindow {
+class LiveWindow final {
  public:
   /**
-   * Get an instance of the LiveWindow main class.
-   *
-   * This is a singleton to guarantee that there is only a single instance
-   * regardless of how many times GetInstance is called.
-   * @deprecated Use the static methods unless guaranteeing LiveWindow is
-   * instantiated
-   */
-  WPI_DEPRECATED("Use static methods")
-  static LiveWindow* GetInstance();
-
-  /**
    * Set function to be called when LiveWindow is enabled.
    *
    * @param func function (or nullptr for none)
@@ -64,6 +51,11 @@
    */
   static void DisableAllTelemetry();
 
+  /**
+   * Enable ALL telemetry.
+   */
+  static void EnableAllTelemetry();
+
   static bool IsEnabled();
 
   /**
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/motorcontrol/MotorController.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/motorcontrol/MotorController.h
index 8ed19bc..24e1b17 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/motorcontrol/MotorController.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/motorcontrol/MotorController.h
@@ -6,32 +6,66 @@
 
 #include <units/voltage.h>
 
-#include "frc/SpeedController.h"
-
 namespace frc {
 
-#if defined(_MSC_VER)
-#pragma warning(push)
-#pragma warning(disable : 4996)  // was declared deprecated
-#elif defined(__clang__)
-#pragma clang diagnostic push
-#pragma clang diagnostic ignored "-Wdeprecated-declarations"
-#elif defined(__GNUC__)
-#pragma GCC diagnostic push
-#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
-#endif
-
 /**
  * Interface for motor controlling devices.
  */
-class MotorController : public SpeedController {};
+class MotorController {
+ public:
+  virtual ~MotorController() = default;
 
-#if defined(_MSC_VER)
-#pragma warning(pop)
-#elif defined(__clang__)
-#pragma clang diagnostic pop
-#elif defined(__GNUC__)
-#pragma GCC diagnostic pop
-#endif
+  /**
+   * Common interface for setting the speed of a motor controller.
+   *
+   * @param speed The speed to set.  Value should be between -1.0 and 1.0.
+   */
+  virtual void Set(double speed) = 0;
+
+  /**
+   * Sets the voltage output of the MotorController.  Compensates for
+   * the current bus voltage to ensure that the desired voltage is output even
+   * if the battery voltage is below 12V - highly useful when the voltage
+   * outputs are "meaningful" (e.g. they come from a feedforward calculation).
+   *
+   * <p>NOTE: This function *must* be called regularly in order for voltage
+   * compensation to work properly - unlike the ordinary set function, it is not
+   * "set it and forget it."
+   *
+   * @param output The voltage to output.
+   */
+  virtual void SetVoltage(units::volt_t output);
+
+  /**
+   * Common interface for getting the current set speed of a motor controller.
+   *
+   * @return The current set speed.  Value is between -1.0 and 1.0.
+   */
+  virtual double Get() const = 0;
+
+  /**
+   * Common interface for inverting direction of a motor controller.
+   *
+   * @param isInverted The state of inversion, true is inverted.
+   */
+  virtual void SetInverted(bool isInverted) = 0;
+
+  /**
+   * Common interface for returning the inversion state of a motor controller.
+   *
+   * @return isInverted The state of inversion, true is inverted.
+   */
+  virtual bool GetInverted() const = 0;
+
+  /**
+   * Common interface for disabling a motor.
+   */
+  virtual void Disable() = 0;
+
+  /**
+   * Common interface to stop the motor until Set is called again.
+   */
+  virtual void StopMotor() = 0;
+};
 
 }  // namespace frc
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/motorcontrol/MotorControllerGroup.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/motorcontrol/MotorControllerGroup.h
index 6f47bf9..99a9e4e 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/motorcontrol/MotorControllerGroup.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/motorcontrol/MotorControllerGroup.h
@@ -31,6 +31,7 @@
   MotorControllerGroup& operator=(MotorControllerGroup&&) = default;
 
   void Set(double speed) override;
+  void SetVoltage(units::volt_t output) override;
   double Get() const override;
   void SetInverted(bool isInverted) override;
   bool GetInverted() const override;
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/motorcontrol/PWMMotorController.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/motorcontrol/PWMMotorController.h
index 7bb63fb..bca5d7f 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/motorcontrol/PWMMotorController.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/motorcontrol/PWMMotorController.h
@@ -64,7 +64,7 @@
   /**
    * Optionally eliminate the deadband from a motor controller.
    *
-   * @param eliminateDeadband If true, set the motor curve on the speed
+   * @param eliminateDeadband If true, set the motor curve on the motor
    *                          controller to eliminate the deadband in the middle
    *                          of the range. Otherwise, keep the full range
    *                          without modifying any values.
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/shuffleboard/ComplexWidget.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/shuffleboard/ComplexWidget.h
index dc49d64..a96f879 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/shuffleboard/ComplexWidget.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/shuffleboard/ComplexWidget.h
@@ -21,7 +21,7 @@
 class ShuffleboardContainer;
 
 /**
- * A Shuffleboard widget that handles a Sendable object such as a speed
+ * A Shuffleboard widget that handles a Sendable object such as a motor
  * controller or sensor.
  */
 class ComplexWidget final : public ShuffleboardWidget<ComplexWidget> {
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/shuffleboard/RecordingController.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/shuffleboard/RecordingController.h
index 83b23a4..3ef5120 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/shuffleboard/RecordingController.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/shuffleboard/RecordingController.h
@@ -8,8 +8,10 @@
 #include <string>
 #include <string_view>
 
+#include <networktables/BooleanTopic.h>
 #include <networktables/NetworkTable.h>
 #include <networktables/NetworkTableInstance.h>
+#include <networktables/StringTopic.h>
 #include <wpi/SmallVector.h>
 
 #include "frc/shuffleboard/ShuffleboardEventImportance.h"
@@ -30,8 +32,8 @@
                       ShuffleboardEventImportance importance);
 
  private:
-  nt::NetworkTableEntry m_recordingControlEntry;
-  nt::NetworkTableEntry m_recordingFileNameFormatEntry;
+  nt::BooleanPublisher m_recordingControlEntry;
+  nt::StringPublisher m_recordingFileNameFormatEntry;
   std::shared_ptr<nt::NetworkTable> m_eventsTable;
 };
 
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/shuffleboard/SendableCameraWrapper.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/shuffleboard/SendableCameraWrapper.h
index 4792ce3..7951cf9 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/shuffleboard/SendableCameraWrapper.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/shuffleboard/SendableCameraWrapper.h
@@ -6,6 +6,7 @@
 
 #include <functional>
 #include <memory>
+#include <span>
 #include <string>
 #include <string_view>
 
@@ -22,9 +23,9 @@
 using CS_Source = CS_Handle;  // NOLINT
 #endif
 
+#include <networktables/StringArrayTopic.h>
 #include <wpi/sendable/Sendable.h>
 #include <wpi/sendable/SendableHelper.h>
-#include <wpi/span.h>
 
 namespace frc {
 
@@ -56,6 +57,17 @@
   SendableCameraWrapper(std::string_view cameraName, const private_init&);
 
   /**
+   * Creates a new sendable wrapper. Private constructor to avoid direct
+   * instantiation with multiple wrappers floating around for the same camera.
+   *
+   * @param cameraName the name of the camera to wrap
+   * @param cameraUrls camera URLs
+   */
+  SendableCameraWrapper(std::string_view cameraName,
+                        std::span<const std::string> cameraUrls,
+                        const private_init&);
+
+  /**
    * Gets a sendable wrapper object for the given video source, creating the
    * wrapper if one does not already exist for the source.
    *
@@ -67,12 +79,13 @@
   static SendableCameraWrapper& Wrap(CS_Source source);
 
   static SendableCameraWrapper& Wrap(std::string_view cameraName,
-                                     wpi::span<const std::string> cameraUrls);
+                                     std::span<const std::string> cameraUrls);
 
   void InitSendable(wpi::SendableBuilder& builder) override;
 
  private:
   std::string m_uri;
+  nt::StringArrayPublisher m_streams;
 };
 
 #ifndef DYNAMIC_CAMERA_SERVER
@@ -83,6 +96,17 @@
   m_uri += name;
 }
 
+inline SendableCameraWrapper::SendableCameraWrapper(
+    std::string_view cameraName, std::span<const std::string> cameraUrls,
+    const private_init&)
+    : SendableCameraWrapper(cameraName, private_init{}) {
+  m_streams = nt::NetworkTableInstance::GetDefault()
+                  .GetStringArrayTopic(
+                      fmt::format("/CameraPublisher/{}/streams", cameraName))
+                  .Publish();
+  m_streams.Set(cameraUrls);
+}
+
 inline SendableCameraWrapper& SendableCameraWrapper::Wrap(
     const cs::VideoSource& source) {
   return Wrap(source.GetHandle());
@@ -99,15 +123,12 @@
 }
 
 inline SendableCameraWrapper& SendableCameraWrapper::Wrap(
-    std::string_view cameraName, wpi::span<const std::string> cameraUrls) {
+    std::string_view cameraName, std::span<const std::string> cameraUrls) {
   auto& wrapper = detail::GetSendableCameraWrapper(cameraName);
   if (!wrapper) {
-    wrapper =
-        std::make_shared<SendableCameraWrapper>(cameraName, private_init{});
+    wrapper = std::make_shared<SendableCameraWrapper>(cameraName, cameraUrls,
+                                                      private_init{});
   }
-  auto streams = fmt::format("/CameraPublisher/{}/streams", cameraName);
-  nt::NetworkTableInstance::GetDefault().GetEntry(streams).SetStringArray(
-      cameraUrls);
   return *wrapper;
 }
 #endif
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardComponent.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardComponent.h
index 24f65a3..fc15948 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardComponent.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardComponent.h
@@ -37,8 +37,7 @@
    * @param properties the properties for this component
    * @return this component
    */
-  Derived& WithProperties(
-      const wpi::StringMap<std::shared_ptr<nt::Value>>& properties);
+  Derived& WithProperties(const wpi::StringMap<nt::Value>& properties);
 
   /**
    * Sets the position of this component in the tab. This has no effect if this
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardComponent.inc b/third_party/allwpilib/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardComponent.inc
index 9750d4a..63a4933 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardComponent.inc
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardComponent.inc
@@ -21,7 +21,7 @@
 
 template <typename Derived>
 Derived& ShuffleboardComponent<Derived>::WithProperties(
-    const wpi::StringMap<std::shared_ptr<nt::Value>>& properties) {
+    const wpi::StringMap<nt::Value>& properties) {
   m_properties = properties;
   m_metadataDirty = true;
   return *static_cast<Derived*>(this);
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardComponentBase.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardComponentBase.h
index d33a234..de27b35 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardComponentBase.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardComponentBase.h
@@ -35,7 +35,7 @@
   const std::string& GetType() const;
 
  protected:
-  wpi::StringMap<std::shared_ptr<nt::Value>> m_properties;
+  wpi::StringMap<nt::Value> m_properties;
   bool m_metadataDirty = true;
   int m_column = -1;
   int m_row = -1;
@@ -49,7 +49,7 @@
   /**
    * Gets the custom properties for this component. May be null.
    */
-  const wpi::StringMap<std::shared_ptr<nt::Value>>& GetProperties() const;
+  const wpi::StringMap<nt::Value>& GetProperties() const;
 };
 
 }  // namespace frc
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardContainer.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardContainer.h
index 13a5cee..5d20783 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardContainer.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardContainer.h
@@ -6,6 +6,7 @@
 
 #include <functional>
 #include <memory>
+#include <span>
 #include <string>
 #include <string_view>
 #include <vector>
@@ -14,7 +15,6 @@
 #include <networktables/NetworkTableValue.h>
 #include <wpi/SmallSet.h>
 #include <wpi/StringMap.h>
-#include <wpi/span.h>
 
 #include "frc/shuffleboard/BuiltInLayouts.h"
 #include "frc/shuffleboard/LayoutType.h"
@@ -137,7 +137,7 @@
    * @return a widget to display the camera stream
    */
   ComplexWidget& AddCamera(std::string_view title, std::string_view cameraName,
-                           wpi::span<const std::string> cameraUrls);
+                           std::span<const std::string> cameraUrls);
 
   /**
    * Adds a widget to this container to display the given sendable.
@@ -171,8 +171,7 @@
    * @see AddPersistent(std::string_view, std::shared_ptr<nt::Value>)
    *      Add(std::string_view title, std::shared_ptr<nt::Value> defaultValue)
    */
-  SimpleWidget& Add(std::string_view title,
-                    std::shared_ptr<nt::Value> defaultValue);
+  SimpleWidget& Add(std::string_view title, const nt::Value& defaultValue);
 
   /**
    * Adds a widget to this container to display the given data.
@@ -208,6 +207,19 @@
    * @return a widget to display the sendable data
    * @throws IllegalArgumentException if a widget already exists in this
    *         container with the given title
+   * @see AddPersistent(std::string_view, double)
+   *      Add(std::string_view title, double defaultValue)
+   */
+  SimpleWidget& Add(std::string_view title, float defaultValue);
+
+  /**
+   * Adds a widget to this container to display the given data.
+   *
+   * @param title the title of the widget
+   * @param defaultValue  the default value of the widget
+   * @return a widget to display the sendable data
+   * @throws IllegalArgumentException if a widget already exists in this
+   *         container with the given title
    * @see AddPersistent(std::string_view, int)
    *      Add(std::string_view title, int defaultValue)
    */
@@ -247,10 +259,10 @@
    * @return a widget to display the sendable data
    * @throws IllegalArgumentException if a widget already exists in this
    *         container with the given title
-   * @see AddPersistent(std::string_view, wpi::span<const bool>)
-   *      Add(std::string_view title, wpi::span<const bool> defaultValue)
+   * @see AddPersistent(std::string_view, std::span<const bool>)
+   *      Add(std::string_view title, std::span<const bool> defaultValue)
    */
-  SimpleWidget& Add(std::string_view title, wpi::span<const bool> defaultValue);
+  SimpleWidget& Add(std::string_view title, std::span<const bool> defaultValue);
 
   /**
    * Adds a widget to this container to display the given data.
@@ -260,11 +272,11 @@
    * @return a widget to display the sendable data
    * @throws IllegalArgumentException if a widget already exists in this
    *         container with the given title
-   * @see AddPersistent(std::string_view, wpi::span<const double>)
-   *      Add(std::string_view title, wpi::span<const double> defaultValue)
+   * @see AddPersistent(std::string_view, std::span<const double>)
+   *      Add(std::string_view title, std::span<const double> defaultValue)
    */
   SimpleWidget& Add(std::string_view title,
-                    wpi::span<const double> defaultValue);
+                    std::span<const double> defaultValue);
 
   /**
    * Adds a widget to this container to display the given data.
@@ -274,11 +286,39 @@
    * @return a widget to display the sendable data
    * @throws IllegalArgumentException if a widget already exists in this
    *         container with the given title
-   * @see AddPersistent(std::string_view, wpi::span<const std::string>)
-   *      Add(std::string_view title, wpi::span<const std::string> defaultValue)
+   * @see AddPersistent(std::string_view, std::span<const double>)
+   *      Add(std::string_view title, std::span<const double> defaultValue)
    */
   SimpleWidget& Add(std::string_view title,
-                    wpi::span<const std::string> defaultValue);
+                    std::span<const float> defaultValue);
+
+  /**
+   * Adds a widget to this container to display the given data.
+   *
+   * @param title the title of the widget
+   * @param defaultValue  the default value of the widget
+   * @return a widget to display the sendable data
+   * @throws IllegalArgumentException if a widget already exists in this
+   *         container with the given title
+   * @see AddPersistent(std::string_view, std::span<const double>)
+   *      Add(std::string_view title, std::span<const double> defaultValue)
+   */
+  SimpleWidget& Add(std::string_view title,
+                    std::span<const int64_t> defaultValue);
+
+  /**
+   * Adds a widget to this container to display the given data.
+   *
+   * @param title the title of the widget
+   * @param defaultValue  the default value of the widget
+   * @return a widget to display the sendable data
+   * @throws IllegalArgumentException if a widget already exists in this
+   *         container with the given title
+   * @see AddPersistent(std::string_view, std::span<const std::string>)
+   *      Add(std::string_view title, std::span<const std::string> defaultValue)
+   */
+  SimpleWidget& Add(std::string_view title,
+                    std::span<const std::string> defaultValue);
 
   /**
    * Adds a widget to this container. The widget will display the data provided
@@ -316,6 +356,45 @@
    * @param supplier the supplier for values
    * @return a widget to display data
    */
+  SuppliedValueWidget<double>& AddDouble(std::string_view title,
+                                         std::function<double()> supplier);
+
+  /**
+   * Adds a widget to this container. The widget will display the data provided
+   * by the value supplier. Changes made on the dashboard will not propagate to
+   * the widget object, and will be overridden by values from the value
+   * supplier.
+   *
+   * @param title the title of the widget
+   * @param supplier the supplier for values
+   * @return a widget to display data
+   */
+  SuppliedValueWidget<float>& AddFloat(std::string_view title,
+                                       std::function<float()> supplier);
+
+  /**
+   * Adds a widget to this container. The widget will display the data provided
+   * by the value supplier. Changes made on the dashboard will not propagate to
+   * the widget object, and will be overridden by values from the value
+   * supplier.
+   *
+   * @param title the title of the widget
+   * @param supplier the supplier for values
+   * @return a widget to display data
+   */
+  SuppliedValueWidget<int64_t>& AddInteger(std::string_view title,
+                                           std::function<int64_t()> supplier);
+
+  /**
+   * Adds a widget to this container. The widget will display the data provided
+   * by the value supplier. Changes made on the dashboard will not propagate to
+   * the widget object, and will be overridden by values from the value
+   * supplier.
+   *
+   * @param title the title of the widget
+   * @param supplier the supplier for values
+   * @return a widget to display data
+   */
   SuppliedValueWidget<bool>& AddBoolean(std::string_view title,
                                         std::function<bool()> supplier);
 
@@ -356,6 +435,45 @@
    * @param supplier the supplier for values
    * @return a widget to display data
    */
+  SuppliedValueWidget<std::vector<double>>& AddDoubleArray(
+      std::string_view title, std::function<std::vector<double>()> supplier);
+
+  /**
+   * Adds a widget to this container. The widget will display the data provided
+   * by the value supplier. Changes made on the dashboard will not propagate to
+   * the widget object, and will be overridden by values from the value
+   * supplier.
+   *
+   * @param title the title of the widget
+   * @param supplier the supplier for values
+   * @return a widget to display data
+   */
+  SuppliedValueWidget<std::vector<float>>& AddFloatArray(
+      std::string_view title, std::function<std::vector<float>()> supplier);
+
+  /**
+   * Adds a widget to this container. The widget will display the data provided
+   * by the value supplier. Changes made on the dashboard will not propagate to
+   * the widget object, and will be overridden by values from the value
+   * supplier.
+   *
+   * @param title the title of the widget
+   * @param supplier the supplier for values
+   * @return a widget to display data
+   */
+  SuppliedValueWidget<std::vector<int64_t>>& AddIntegerArray(
+      std::string_view title, std::function<std::vector<int64_t>()> supplier);
+
+  /**
+   * Adds a widget to this container. The widget will display the data provided
+   * by the value supplier. Changes made on the dashboard will not propagate to
+   * the widget object, and will be overridden by values from the value
+   * supplier.
+   *
+   * @param title the title of the widget
+   * @param supplier the supplier for values
+   * @return a widget to display data
+   */
   SuppliedValueWidget<std::vector<int>>& AddBooleanArray(
       std::string_view title, std::function<std::vector<int>()> supplier);
 
@@ -369,8 +487,23 @@
    * @param supplier the supplier for values
    * @return a widget to display data
    */
-  SuppliedValueWidget<std::string_view>& AddRaw(
-      std::string_view title, std::function<std::string_view()> supplier);
+  SuppliedValueWidget<std::vector<uint8_t>>& AddRaw(
+      std::string_view title, std::function<std::vector<uint8_t>()> supplier);
+
+  /**
+   * Adds a widget to this container. The widget will display the data provided
+   * by the value supplier. Changes made on the dashboard will not propagate to
+   * the widget object, and will be overridden by values from the value
+   * supplier.
+   *
+   * @param title the title of the widget
+   * @param typeString the NT type string
+   * @param supplier the supplier for values
+   * @return a widget to display data
+   */
+  SuppliedValueWidget<std::vector<uint8_t>>& AddRaw(
+      std::string_view title, std::string_view typeString,
+      std::function<std::vector<uint8_t>()> supplier);
 
   /**
    * Adds a widget to this container to display a simple piece of data.
@@ -386,7 +519,7 @@
    *      Add(std::string_view title, std::shared_ptr<nt::Value> defaultValue)
    */
   SimpleWidget& AddPersistent(std::string_view title,
-                              std::shared_ptr<nt::Value> defaultValue);
+                              const nt::Value& defaultValue);
 
   /**
    * Adds a widget to this container to display a simple piece of data.
@@ -421,15 +554,30 @@
   /**
    * Adds a widget to this container to display a simple piece of data.
    *
-   * Unlike Add(std::string_view, int), the value in the widget will be saved on
-   * the robot and will be used when the robot program next starts rather than
-   * {@code defaultValue}.
+   * Unlike Add(std::string_view, float), the value in the widget will be saved
+   * on the robot and will be used when the robot program next starts rather
+   * than {@code defaultValue}.
    *
    * @param title the title of the widget
    * @param defaultValue the default value of the widget
    * @return a widget to display the sendable data
-   * @see Add(std:string_view, int)
-   *      Add(std::string_view title, int defaultValue)
+   * @see Add(std::string_view, float)
+   *      Add(std::string_view title, float defaultValue)
+   */
+  SimpleWidget& AddPersistent(std::string_view title, float defaultValue);
+
+  /**
+   * Adds a widget to this container to display a simple piece of data.
+   *
+   * Unlike Add(std::string_view, int64_t), the value in the widget will be
+   * saved on the robot and will be used when the robot program next starts
+   * rather than {@code defaultValue}.
+   *
+   * @param title the title of the widget
+   * @param defaultValue the default value of the widget
+   * @return a widget to display the sendable data
+   * @see Add(std:string_view, int64_t)
+   *      Add(std::string_view title, int64_t defaultValue)
    */
   SimpleWidget& AddPersistent(std::string_view title, int defaultValue);
 
@@ -452,50 +600,82 @@
   /**
    * Adds a widget to this container to display a simple piece of data.
    *
-   * Unlike Add(std::string_view, wpi::span<const bool>), the value in the
+   * Unlike Add(std::string_view, std::span<const bool>), the value in the
    * widget will be saved on the robot and will be used when the robot program
    * next starts rather than {@code defaultValue}.
    *
    * @param title the title of the widget
    * @param defaultValue the default value of the widget
    * @return a widget to display the sendable data
-   * @see Add(std::string_view, wpi::span<const bool>)
-   *      Add(std::string_view title, wpi::span<const bool> defaultValue)
+   * @see Add(std::string_view, std::span<const bool>)
+   *      Add(std::string_view title, std::span<const bool> defaultValue)
    */
   SimpleWidget& AddPersistent(std::string_view title,
-                              wpi::span<const bool> defaultValue);
+                              std::span<const bool> defaultValue);
 
   /**
    * Adds a widget to this container to display a simple piece of data.
    *
-   * Unlike Add(std::string_view, wpi::span<const double>), the value in the
+   * Unlike Add(std::string_view, std::span<const double>), the value in the
    * widget will be saved on the robot and will be used when the robot program
    * next starts rather than {@code defaultValue}.
    *
    * @param title the title of the widget
    * @param defaultValue the default value of the widget
    * @return a widget to display the sendable data
-   * @see Add(std::string_view, wpi::span<const double>)
-   *      Add(std::string_view title, wpi::span<const double> defaultValue)
+   * @see Add(std::string_view, std::span<const double>)
+   *      Add(std::string_view title, std::span<const double> defaultValue)
    */
   SimpleWidget& AddPersistent(std::string_view title,
-                              wpi::span<const double> defaultValue);
+                              std::span<const double> defaultValue);
 
   /**
    * Adds a widget to this container to display a simple piece of data.
    *
-   * Unlike Add(std::string_view, wpi::span<const std::string>), the value in
+   * Unlike Add(std::string_view, std::span<const float>), the value in the
+   * widget will be saved on the robot and will be used when the robot program
+   * next starts rather than {@code defaultValue}.
+   *
+   * @param title the title of the widget
+   * @param defaultValue the default value of the widget
+   * @return a widget to display the sendable data
+   * @see Add(std::string_view, std::span<const float>)
+   *      Add(std::string_view title, std::span<const float> defaultValue)
+   */
+  SimpleWidget& AddPersistent(std::string_view title,
+                              std::span<const float> defaultValue);
+
+  /**
+   * Adds a widget to this container to display a simple piece of data.
+   *
+   * Unlike Add(std::string_view, std::span<const int64_t>), the value in the
+   * widget will be saved on the robot and will be used when the robot program
+   * next starts rather than {@code defaultValue}.
+   *
+   * @param title the title of the widget
+   * @param defaultValue the default value of the widget
+   * @return a widget to display the sendable data
+   * @see Add(std::string_view, std::span<const int64_t>)
+   *      Add(std::string_view title, std::span<const int64_t> defaultValue)
+   */
+  SimpleWidget& AddPersistent(std::string_view title,
+                              std::span<const int64_t> defaultValue);
+
+  /**
+   * Adds a widget to this container to display a simple piece of data.
+   *
+   * Unlike Add(std::string_view, std::span<const std::string>), the value in
    * the widget will be saved on the robot and will be used when the robot
    * program next starts rather than {@code defaultValue}.
    *
    * @param title the title of the widget
    * @param defaultValue the default value of the widget
    * @return a widget to display the sendable data
-   * @see Add(std::string_view, wpi::span<const std::string>)
-   *      Add(std::string_view title, wpi::span<const std::string> defaultValue)
+   * @see Add(std::string_view, std::span<const std::string>)
+   *      Add(std::string_view title, std::span<const std::string> defaultValue)
    */
   SimpleWidget& AddPersistent(std::string_view title,
-                              wpi::span<const std::string> defaultValue);
+                              std::span<const std::string> defaultValue);
 
   void EnableIfActuator() override;
 
@@ -541,7 +721,7 @@
 
 inline frc::ComplexWidget& frc::ShuffleboardContainer::AddCamera(
     std::string_view title, std::string_view cameraName,
-    wpi::span<const std::string> cameraUrls) {
+    std::span<const std::string> cameraUrls) {
   return Add(title, frc::SendableCameraWrapper::Wrap(cameraName, cameraUrls));
 }
 #endif
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/shuffleboard/SimpleWidget.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/shuffleboard/SimpleWidget.h
index 746b7d6..97502be 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/shuffleboard/SimpleWidget.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/shuffleboard/SimpleWidget.h
@@ -5,10 +5,11 @@
 #pragma once
 
 #include <memory>
+#include <string>
 #include <string_view>
 
+#include <networktables/GenericEntry.h>
 #include <networktables/NetworkTable.h>
-#include <networktables/NetworkTableEntry.h>
 
 #include "frc/shuffleboard/ShuffleboardWidget.h"
 
@@ -26,14 +27,26 @@
 
   /**
    * Gets the NetworkTable entry that contains the data for this widget.
+   * The widget owns the entry; the returned pointer's lifetime is the same as
+   * that of the widget.
    */
-  nt::NetworkTableEntry GetEntry();
+  nt::GenericEntry* GetEntry();
+
+  /**
+   * Gets the NetworkTable entry that contains the data for this widget.
+   * The widget owns the entry; the returned pointer's lifetime is the same as
+   * that of the widget.
+   *
+   * @param typeString NT type string
+   */
+  nt::GenericEntry* GetEntry(std::string_view typeString);
 
   void BuildInto(std::shared_ptr<nt::NetworkTable> parentTable,
                  std::shared_ptr<nt::NetworkTable> metaTable) override;
 
  private:
-  nt::NetworkTableEntry m_entry;
+  nt::GenericEntry m_entry;
+  std::string m_typeString;
 
   void ForceGenerate();
 };
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/shuffleboard/SuppliedValueWidget.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/shuffleboard/SuppliedValueWidget.h
index a2b042e..4f82dc6 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/shuffleboard/SuppliedValueWidget.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/shuffleboard/SuppliedValueWidget.h
@@ -6,10 +6,12 @@
 
 #include <functional>
 #include <memory>
+#include <string>
 #include <string_view>
 
+#include <networktables/BooleanTopic.h>
+#include <networktables/GenericEntry.h>
 #include <networktables/NetworkTable.h>
-#include <networktables/NetworkTableEntry.h>
 
 #include "frc/shuffleboard/ShuffleboardComponent.h"
 #include "frc/shuffleboard/ShuffleboardComponent.inc"
@@ -23,24 +25,35 @@
 class SuppliedValueWidget : public ShuffleboardWidget<SuppliedValueWidget<T>> {
  public:
   SuppliedValueWidget(ShuffleboardContainer& parent, std::string_view title,
-                      std::function<T()> supplier,
-                      std::function<void(nt::NetworkTableEntry, T)> setter)
+                      std::string_view typeString, std::function<T()> supplier,
+                      std::function<void(nt::GenericPublisher&, T)> setter)
       : ShuffleboardValue(title),
         ShuffleboardWidget<SuppliedValueWidget<T>>(parent, title),
+        m_typeString(typeString),
         m_supplier(supplier),
         m_setter(setter) {}
 
   void BuildInto(std::shared_ptr<nt::NetworkTable> parentTable,
                  std::shared_ptr<nt::NetworkTable> metaTable) override {
     this->BuildMetadata(metaTable);
-    metaTable->GetEntry("Controllable").SetBoolean(false);
+    if (!m_controllablePub) {
+      m_controllablePub =
+          nt::BooleanTopic{metaTable->GetTopic("Controllable")}.Publish();
+      m_controllablePub.Set(false);
+    }
 
-    auto entry = parentTable->GetEntry(this->GetTitle());
-    m_setter(entry, m_supplier());
+    if (!m_entry) {
+      m_entry =
+          parentTable->GetTopic(this->GetTitle()).GenericPublish(m_typeString);
+    }
+    m_setter(m_entry, m_supplier());
   }
 
  private:
+  std::string m_typeString;
   std::function<T()> m_supplier;
-  std::function<void(nt::NetworkTableEntry, T)> m_setter;
+  std::function<void(nt::GenericPublisher&, T)> m_setter;
+  nt::BooleanPublisher m_controllablePub;
+  nt::GenericPublisher m_entry;
 };
 }  // namespace frc
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/BatterySim.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/BatterySim.h
index 4a350cf..ab79844 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/BatterySim.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/BatterySim.h
@@ -5,6 +5,7 @@
 #pragma once
 
 #include <numeric>
+#include <span>
 
 #include <units/current.h>
 #include <units/impedance.h>
@@ -29,6 +30,25 @@
    * @param currents       The currents drawn from the battery.
    * @return The battery's voltage under load.
    */
+  static units::volt_t Calculate(units::volt_t nominalVoltage,
+                                 units::ohm_t resistance,
+                                 std::span<const units::ampere_t> currents) {
+    return nominalVoltage -
+           std::accumulate(currents.begin(), currents.end(), 0_A) * resistance;
+  }
+
+  /**
+   * Calculate the loaded battery voltage. Use this with
+   * RoboRioSim::SetVInVoltage(double) to set the simulated battery voltage,
+   * which can then be retrieved with the RobotController::GetBatteryVoltage()
+   * method.
+   *
+   * @param nominalVoltage The nominal battery voltage. Usually 12v.
+   * @param resistance     The forward resistance of the battery. Most batteries
+   *                       are at or below 20 milliohms.
+   * @param currents       The currents drawn from the battery.
+   * @return The battery's voltage under load.
+   */
   static units::volt_t Calculate(
       units::volt_t nominalVoltage, units::ohm_t resistance,
       std::initializer_list<units::ampere_t> currents) {
@@ -46,6 +66,20 @@
    * @param currents The currents drawn from the battery.
    * @return The battery's voltage under load.
    */
+  static units::volt_t Calculate(std::span<const units::ampere_t> currents) {
+    return Calculate(12_V, 0.02_Ohm, currents);
+  }
+
+  /**
+   * Calculate the loaded battery voltage. Use this with
+   * RoboRioSimSetVInVoltage(double) to set the simulated battery voltage, which
+   * can then be retrieved with the RobotController::GetBatteryVoltage() method.
+   * This function assumes a nominal voltage of 12V and a resistance of 20
+   * milliohms (0.020 ohms).
+   *
+   * @param currents The currents drawn from the battery.
+   * @return The battery's voltage under load.
+   */
   static units::volt_t Calculate(
       std::initializer_list<units::ampere_t> currents) {
     return Calculate(12_V, 0.02_Ohm, currents);
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/CTREPCMSim.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/CTREPCMSim.h
index 0929308..96959ed 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/CTREPCMSim.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/CTREPCMSim.h
@@ -8,17 +8,14 @@
 
 #include "frc/PneumaticsBase.h"
 #include "frc/simulation/CallbackStore.h"
+#include "frc/simulation/PneumaticsBaseSim.h"
 
-namespace frc {
-
-class Compressor;
-
-namespace sim {
+namespace frc::sim {
 
 /**
  * Class to control a simulated Pneumatic Control Module (PCM).
  */
-class CTREPCMSim {
+class CTREPCMSim : public PneumaticsBaseSim {
  public:
   /**
    * Constructs with the default PCM module number (CAN ID).
@@ -34,81 +31,28 @@
 
   explicit CTREPCMSim(const PneumaticsBase& pneumatics);
 
-  /**
-   * Register a callback to be run when a solenoid is initialized on a channel.
-   *
-   * @param callback the callback
-   * @param initialNotify should the callback be run with the initial state
-   * @return the CallbackStore object associated with this callback
-   */
+  ~CTREPCMSim() override = default;
+
   [[nodiscard]] std::unique_ptr<CallbackStore> RegisterInitializedCallback(
-      NotifyCallback callback, bool initialNotify);
+      NotifyCallback callback, bool initialNotify) override;
 
-  /**
-   * Check if a solenoid has been initialized on a specific channel.
-   *
-   * @return true if initialized
-   */
-  bool GetInitialized() const;
+  bool GetInitialized() const override;
 
-  /**
-   * Define whether a solenoid has been initialized on a specific channel.
-   *
-   * @param solenoidInitialized is there a solenoid initialized on that channel
-   */
-  void SetInitialized(bool solenoidInitialized);
+  void SetInitialized(bool initialized) override;
 
-  /**
-   * Register a callback to be run when the solenoid output on a channel
-   * changes.
-   *
-   * @param channel the channel to monitor
-   * @param callback the callback
-   * @param initialNotify should the callback be run with the initial value
-   * @return the CallbackStore object associated with this callback
-   */
   [[nodiscard]] std::unique_ptr<CallbackStore> RegisterSolenoidOutputCallback(
-      int channel, NotifyCallback callback, bool initialNotify);
+      int channel, NotifyCallback callback, bool initialNotify) override;
 
-  /**
-   * Check the solenoid output on a specific channel.
-   *
-   * @param channel the channel to check
-   * @return the solenoid output
-   */
-  bool GetSolenoidOutput(int channel) const;
+  bool GetSolenoidOutput(int channel) const override;
 
-  /**
-   * Change the solenoid output on a specific channel.
-   *
-   * @param channel the channel to check
-   * @param solenoidOutput the new solenoid output
-   */
-  void SetSolenoidOutput(int channel, bool solenoidOutput);
+  void SetSolenoidOutput(int channel, bool solenoidOutput) override;
 
-  /**
-   * Register a callback to be run when the compressor activates.
-   *
-   * @param callback the callback
-   * @param initialNotify whether to run the callback with the initial state
-   * @return the CallbackStore object associated with this callback
-   */
   [[nodiscard]] std::unique_ptr<CallbackStore> RegisterCompressorOnCallback(
-      NotifyCallback callback, bool initialNotify);
+      NotifyCallback callback, bool initialNotify) override;
 
-  /**
-   * Check if the compressor is on.
-   *
-   * @return true if the compressor is active
-   */
-  bool GetCompressorOn() const;
+  bool GetCompressorOn() const override;
 
-  /**
-   * Set whether the compressor is active.
-   *
-   * @param compressorOn the new value
-   */
-  void SetCompressorOn(bool compressorOn);
+  void SetCompressorOn(bool compressorOn) override;
 
   /**
    * Register a callback to be run whenever the closed loop state changes.
@@ -145,21 +89,21 @@
    * @return the CallbackStore object associated with this callback
    */
   [[nodiscard]] std::unique_ptr<CallbackStore> RegisterPressureSwitchCallback(
-      NotifyCallback callback, bool initialNotify);
+      NotifyCallback callback, bool initialNotify) override;
 
   /**
    * Check the value of the pressure switch.
    *
    * @return the pressure switch value
    */
-  bool GetPressureSwitch() const;
+  bool GetPressureSwitch() const override;
 
   /**
    * Set the value of the pressure switch.
    *
    * @param pressureSwitch the new value
    */
-  void SetPressureSwitch(bool pressureSwitch);
+  void SetPressureSwitch(bool pressureSwitch) override;
 
   /**
    * Register a callback to be run whenever the compressor current changes.
@@ -170,43 +114,26 @@
    */
   [[nodiscard]] std::unique_ptr<CallbackStore>
   RegisterCompressorCurrentCallback(NotifyCallback callback,
-                                    bool initialNotify);
+                                    bool initialNotify) override;
 
   /**
    * Read the compressor current.
    *
    * @return the current of the compressor connected to this module
    */
-  double GetCompressorCurrent() const;
+  double GetCompressorCurrent() const override;
 
   /**
    * Set the compressor current.
    *
    * @param compressorCurrent the new compressor current
    */
-  void SetCompressorCurrent(double compressorCurrent);
+  void SetCompressorCurrent(double compressorCurrent) override;
 
-  /**
-   * Get the current value of all solenoid outputs.
-   *
-   * @return the solenoid outputs (1 bit per output)
-   */
-  uint8_t GetAllSolenoidOutputs() const;
+  uint8_t GetAllSolenoidOutputs() const override;
 
-  /**
-   * Change all of the solenoid outputs.
-   *
-   * @param outputs the new solenoid outputs (1 bit per output)
-   */
-  void SetAllSolenoidOutputs(uint8_t outputs);
+  void SetAllSolenoidOutputs(uint8_t outputs) override;
 
-  /**
-   * Reset all simulation data for this object.
-   */
-  void ResetData();
-
- private:
-  int m_index;
+  void ResetData() override;
 };
-}  // namespace sim
-}  // namespace frc
+}  // namespace frc::sim
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/DifferentialDrivetrainSim.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/DifferentialDrivetrainSim.h
index 7c53eb7..c1cc1d7 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/DifferentialDrivetrainSim.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/DifferentialDrivetrainSim.h
@@ -4,11 +4,11 @@
 
 #pragma once
 
+#include <frc/EigenCore.h>
 #include <frc/kinematics/DifferentialDriveKinematics.h>
 #include <frc/system/LinearSystem.h>
 #include <frc/system/plant/DCMotor.h>
 
-#include <Eigen/Core>
 #include <units/length.h>
 #include <units/moment_of_inertia.h>
 #include <units/time.h>
@@ -80,7 +80,7 @@
    * @param u The input vector.
    * @return The normalized input.
    */
-  Eigen::Vector<double, 2> ClampInput(const Eigen::Vector<double, 2>& u);
+  Vectord<2> ClampInput(const Vectord<2>& u);
 
   /**
    * Sets the applied voltage to the drivetrain. Note that positive voltage must
@@ -178,7 +178,7 @@
    *
    * @param state The state.
    */
-  void SetState(const Eigen::Vector<double, 7>& state);
+  void SetState(const Vectord<7>& state);
 
   /**
    * Sets the system pose.
@@ -187,8 +187,7 @@
    */
   void SetPose(const frc::Pose2d& pose);
 
-  Eigen::Vector<double, 7> Dynamics(const Eigen::Vector<double, 7>& x,
-                                    const Eigen::Vector<double, 2>& u);
+  Vectord<7> Dynamics(const Vectord<7>& x, const Vectord<2>& u);
 
   class State {
    public:
@@ -256,7 +255,7 @@
   static DifferentialDrivetrainSim CreateKitbotSim(
       frc::DCMotor motor, double gearing, units::meter_t wheelSize,
       const std::array<double, 7>& measurementStdDevs = {}) {
-    // MOI estimation -- note that I = m r^2 for point masses
+    // MOI estimation -- note that I = mr² for point masses
     units::kilogram_square_meter_t batteryMoi = 12.5_lb * 10_in * 10_in;
     units::kilogram_square_meter_t gearboxMoi = (2.8_lb + 2.0_lb) *
                                                 2  // CIM plus toughbox per side
@@ -301,7 +300,7 @@
   /**
    * Returns the current output vector y.
    */
-  Eigen::Vector<double, 7> GetOutput() const;
+  Vectord<7> GetOutput() const;
 
   /**
    * Returns an element of the state vector. Note that this will not include
@@ -314,7 +313,7 @@
   /**
    * Returns the current state vector x. Note that this will not include noise!
    */
-  Eigen::Vector<double, 7> GetState() const;
+  Vectord<7> GetState() const;
 
   LinearSystem<2, 2, 2> m_plant;
   units::meter_t m_rb;
@@ -325,9 +324,9 @@
   double m_originalGearing;
   double m_currentGearing;
 
-  Eigen::Vector<double, 7> m_x;
-  Eigen::Vector<double, 2> m_u;
-  Eigen::Vector<double, 7> m_y;
+  Vectord<7> m_x;
+  Vectord<2> m_u;
+  Vectord<7> m_y;
   std::array<double, 7> m_measurementStdDevs;
 };
 }  // namespace frc::sim
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/DoubleSolenoidSim.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/DoubleSolenoidSim.h
new file mode 100644
index 0000000..eaa697f
--- /dev/null
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/DoubleSolenoidSim.h
@@ -0,0 +1,33 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <memory>
+
+#include "frc/DoubleSolenoid.h"
+#include "frc/PneumaticsModuleType.h"
+#include "frc/simulation/PneumaticsBaseSim.h"
+
+namespace frc::sim {
+
+class DoubleSolenoidSim {
+ public:
+  DoubleSolenoidSim(std::shared_ptr<PneumaticsBaseSim> moduleSim, int fwd,
+                    int rev);
+  DoubleSolenoidSim(int module, PneumaticsModuleType type, int fwd, int rev);
+  DoubleSolenoidSim(PneumaticsModuleType type, int fwd, int rev);
+
+  DoubleSolenoid::Value Get() const;
+  void Set(DoubleSolenoid::Value output);
+
+  std::shared_ptr<PneumaticsBaseSim> GetModuleSim() const;
+
+ private:
+  std::shared_ptr<PneumaticsBaseSim> m_module;
+  int m_fwd;
+  int m_rev;
+};
+
+}  // namespace frc::sim
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/DriverStationSim.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/DriverStationSim.h
index 412a921..232c123 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/DriverStationSim.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/DriverStationSim.h
@@ -337,7 +337,7 @@
    * @param stick The joystick number
    * @param name The value of name
    */
-  static void SetJoystickName(int stick, const char* name);
+  static void SetJoystickName(int stick, std::string_view name);
 
   /**
    * Sets the types of Axes for a joystick.
@@ -353,14 +353,14 @@
    *
    * @param message the game specific message
    */
-  static void SetGameSpecificMessage(const char* message);
+  static void SetGameSpecificMessage(std::string_view message);
 
   /**
    * Sets the event name.
    *
    * @param name the event name
    */
-  static void SetEventName(const char* name);
+  static void SetEventName(std::string_view name);
 
   /**
    * Sets the match type.
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/ElevatorSim.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/ElevatorSim.h
index 14b6d2d..cf40810 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/ElevatorSim.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/ElevatorSim.h
@@ -31,11 +31,13 @@
    *                           wrapped around.
    * @param minHeight          The minimum allowed height of the elevator.
    * @param maxHeight          The maximum allowed height of the elevator.
+   * @param simulateGravity    Whether gravity should be simulated or not.
    * @param measurementStdDevs The standard deviation of the measurements.
    */
   ElevatorSim(const LinearSystem<2, 1, 1>& plant, const DCMotor& gearbox,
               double gearing, units::meter_t drumRadius,
               units::meter_t minHeight, units::meter_t maxHeight,
+              bool simulateGravity,
               const std::array<double, 1>& measurementStdDevs = {0.0});
 
   /**
@@ -50,11 +52,13 @@
    *                           wrapped around.
    * @param minHeight          The minimum allowed height of the elevator.
    * @param maxHeight          The maximum allowed height of the elevator.
+   * @param simulateGravity    Whether gravity should be simulated or not.
    * @param measurementStdDevs The standard deviation of the measurements.
    */
   ElevatorSim(const DCMotor& gearbox, double gearing,
               units::kilogram_t carriageMass, units::meter_t drumRadius,
               units::meter_t minHeight, units::meter_t maxHeight,
+              bool simulateGravity,
               const std::array<double, 1>& measurementStdDevs = {0.0});
 
   /**
@@ -123,9 +127,8 @@
    * @param u           The system inputs (voltage).
    * @param dt          The time difference between controller updates.
    */
-  Eigen::Vector<double, 2> UpdateX(const Eigen::Vector<double, 2>& currentXhat,
-                                   const Eigen::Vector<double, 1>& u,
-                                   units::second_t dt) override;
+  Vectord<2> UpdateX(const Vectord<2>& currentXhat, const Vectord<1>& u,
+                     units::second_t dt) override;
 
  private:
   DCMotor m_gearbox;
@@ -133,5 +136,6 @@
   units::meter_t m_minHeight;
   units::meter_t m_maxHeight;
   double m_gearing;
+  bool m_simulateGravity;
 };
 }  // namespace frc::sim
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/LinearSystemSim.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/LinearSystemSim.h
index 731fad3..cfc87b2 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/LinearSystemSim.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/LinearSystemSim.h
@@ -6,10 +6,10 @@
 
 #include <array>
 
-#include <Eigen/Core>
 #include <units/current.h>
 #include <units/time.h>
 
+#include "frc/EigenCore.h"
 #include "frc/RobotController.h"
 #include "frc/StateSpaceUtil.h"
 #include "frc/system/LinearSystem.h"
@@ -40,9 +40,9 @@
       const LinearSystem<States, Inputs, Outputs>& system,
       const std::array<double, Outputs>& measurementStdDevs = {})
       : m_plant(system), m_measurementStdDevs(measurementStdDevs) {
-    m_x = Eigen::Vector<double, States>::Zero();
-    m_y = Eigen::Vector<double, Outputs>::Zero();
-    m_u = Eigen::Vector<double, Inputs>::Zero();
+    m_x = Vectord<States>::Zero();
+    m_y = Vectord<Outputs>::Zero();
+    m_u = Vectord<Inputs>::Zero();
   }
 
   virtual ~LinearSystemSim() = default;
@@ -71,7 +71,7 @@
    *
    * @return The current output of the plant.
    */
-  const Eigen::Vector<double, Outputs>& GetOutput() const { return m_y; }
+  const Vectord<Outputs>& GetOutput() const { return m_y; }
 
   /**
    * Returns an element of the current output of the plant.
@@ -86,7 +86,7 @@
    *
    * @param u The system inputs.
    */
-  void SetInput(const Eigen::Vector<double, Inputs>& u) { m_u = ClampInput(u); }
+  void SetInput(const Vectord<Inputs>& u) { m_u = ClampInput(u); }
 
   /*
    * Sets the system inputs.
@@ -104,7 +104,7 @@
    *
    * @param state The new state.
    */
-  void SetState(const Eigen::Vector<double, States>& state) { m_x = state; }
+  void SetState(const Vectord<States>& state) { m_x = state; }
 
   /**
    * Returns the current drawn by this simulated system. Override this method to
@@ -112,9 +112,7 @@
    *
    * @return The current drawn by this simulated mechanism.
    */
-  virtual units::ampere_t GetCurrentDraw() const {
-    return units::ampere_t(0.0);
-  }
+  virtual units::ampere_t GetCurrentDraw() const { return 0_A; }
 
  protected:
   /**
@@ -124,9 +122,9 @@
    * @param u           The system inputs (usually voltage).
    * @param dt          The time difference between controller updates.
    */
-  virtual Eigen::Vector<double, States> UpdateX(
-      const Eigen::Vector<double, States>& currentXhat,
-      const Eigen::Vector<double, Inputs>& u, units::second_t dt) {
+  virtual Vectord<States> UpdateX(const Vectord<States>& currentXhat,
+                                  const Vectord<Inputs>& u,
+                                  units::second_t dt) {
     return m_plant.CalculateX(currentXhat, u, dt);
   }
 
@@ -137,16 +135,16 @@
    * @param u          The input vector.
    * @return The normalized input.
    */
-  Eigen::Vector<double, Inputs> ClampInput(Eigen::Vector<double, Inputs> u) {
+  Vectord<Inputs> ClampInput(Vectord<Inputs> u) {
     return frc::DesaturateInputVector<Inputs>(
         u, frc::RobotController::GetInputVoltage());
   }
 
   LinearSystem<States, Inputs, Outputs> m_plant;
 
-  Eigen::Vector<double, States> m_x;
-  Eigen::Vector<double, Outputs> m_y;
-  Eigen::Vector<double, Inputs> m_u;
+  Vectord<States> m_x;
+  Vectord<Outputs> m_y;
+  Vectord<Inputs> m_u;
   std::array<double, Outputs> m_measurementStdDevs;
 };
 }  // namespace frc::sim
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/PWMSim.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/PWMSim.h
index 97e9b1f..8b4156e 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/PWMSim.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/PWMSim.h
@@ -11,6 +11,7 @@
 namespace frc {
 
 class PWM;
+class PWMMotorController;
 
 namespace sim {
 
@@ -27,6 +28,13 @@
   explicit PWMSim(const PWM& pwm);
 
   /**
+   * Constructs from a PWMMotorController object.
+   *
+   * @param motorctrl PWMMotorController to simulate
+   */
+  explicit PWMSim(const PWMMotorController& motorctrl);
+
+  /**
    * Constructs from a PWM channel number.
    *
    * @param channel Channel number
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/PneumaticsBaseSim.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/PneumaticsBaseSim.h
new file mode 100644
index 0000000..11110e3
--- /dev/null
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/PneumaticsBaseSim.h
@@ -0,0 +1,183 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <memory>
+
+#include "frc/PneumaticsBase.h"
+#include "frc/PneumaticsModuleType.h"
+#include "frc/simulation/CallbackStore.h"
+
+namespace frc::sim {
+
+class PneumaticsBaseSim {
+ public:
+  virtual ~PneumaticsBaseSim() = default;
+
+  static std::shared_ptr<PneumaticsBaseSim> GetForType(
+      int module, PneumaticsModuleType type);
+
+  /**
+   * Check whether the PCM/PH has been initialized.
+   *
+   * @return true if initialized
+   */
+  virtual bool GetInitialized() const = 0;
+
+  /**
+   * Define whether the PCM/PH has been initialized.
+   *
+   * @param initialized true for initialized
+   */
+  virtual void SetInitialized(bool initialized) = 0;
+
+  /**
+   * Register a callback to be run when the PCM/PH is initialized.
+   *
+   * @param callback the callback
+   * @param initialNotify whether to run the callback with the initial state
+   * @return the {@link CallbackStore} object associated with this callback.
+   * Save a reference to this object; it being deconstructed cancels the
+   * callback.
+   */
+  [[nodiscard]] virtual std::unique_ptr<CallbackStore>
+  RegisterInitializedCallback(NotifyCallback callback, bool initialNotify) = 0;
+
+  /**
+   * Check if the compressor is on.
+   *
+   * @return true if the compressor is active
+   */
+  virtual bool GetCompressorOn() const = 0;
+
+  /**
+   * Set whether the compressor is active.
+   *
+   * @param compressorOn the new value
+   */
+  virtual void SetCompressorOn(bool compressorOn) = 0;
+
+  /**
+   * Register a callback to be run when the compressor activates.
+   *
+   * @param callback the callback
+   * @param initialNotify whether to run the callback with the initial state
+   * @return the {@link CallbackStore} object associated with this callback.
+   * Save a reference to this object; it being deconstructed cancels the
+   * callback.
+   */
+  [[nodiscard]] virtual std::unique_ptr<CallbackStore>
+  RegisterCompressorOnCallback(NotifyCallback callback, bool initialNotify) = 0;
+
+  /**
+   * Check the solenoid output on a specific channel.
+   *
+   * @param channel the channel to check
+   * @return the solenoid output
+   */
+  virtual bool GetSolenoidOutput(int channel) const = 0;
+
+  /**
+   * Change the solenoid output on a specific channel.
+   *
+   * @param channel the channel to check
+   * @param solenoidOutput the new solenoid output
+   */
+  virtual void SetSolenoidOutput(int channel, bool solenoidOutput) = 0;
+
+  /**
+   * Register a callback to be run when the solenoid output on a channel
+   * changes.
+   *
+   * @param channel the channel to monitor
+   * @param callback the callback
+   * @param initialNotify should the callback be run with the initial value
+   * @return the {@link CallbackStore} object associated with this callback.
+   * Save a reference to this object; it being deconstructed cancels the
+   * callback.
+   */
+  [[nodiscard]] virtual std::unique_ptr<CallbackStore>
+  RegisterSolenoidOutputCallback(int channel, NotifyCallback callback,
+                                 bool initialNotify) = 0;
+
+  /**
+   * Check the value of the pressure switch.
+   *
+   * @return the pressure switch value
+   */
+  virtual bool GetPressureSwitch() const = 0;
+
+  /**
+   * Set the value of the pressure switch.
+   *
+   * @param pressureSwitch the new value
+   */
+  virtual void SetPressureSwitch(bool pressureSwitch) = 0;
+
+  /**
+   * Register a callback to be run whenever the pressure switch value changes.
+   *
+   * @param callback the callback
+   * @param initialNotify whether the callback should be called with the initial
+   * value
+   * @return the {@link CallbackStore} object associated with this callback.
+   * Save a reference to this object; it being deconstructed cancels the
+   * callback.
+   */
+  [[nodiscard]] virtual std::unique_ptr<CallbackStore>
+  RegisterPressureSwitchCallback(NotifyCallback callback,
+                                 bool initialNotify) = 0;
+
+  /**
+   * Read the compressor current.
+   *
+   * @return the current of the compressor connected to this module
+   */
+  virtual double GetCompressorCurrent() const = 0;
+
+  /**
+   * Set the compressor current.
+   *
+   * @param compressorCurrent the new compressor current
+   */
+  virtual void SetCompressorCurrent(double compressorCurrent) = 0;
+
+  /**
+   * Register a callback to be run whenever the compressor current changes.
+   *
+   * @param callback the callback
+   * @param initialNotify whether to call the callback with the initial state
+   * @return the {@link CallbackStore} object associated with this callback.
+   * Save a reference to this object; it being deconstructed cancels the
+   * callback.
+   */
+  [[nodiscard]] virtual std::unique_ptr<CallbackStore>
+  RegisterCompressorCurrentCallback(NotifyCallback callback,
+                                    bool initialNotify) = 0;
+
+  /**
+   * Get the current value of all solenoid outputs.
+   *
+   * @return the solenoid outputs (1 bit per output)
+   */
+  virtual uint8_t GetAllSolenoidOutputs() const = 0;
+
+  /**
+   * Change all of the solenoid outputs.
+   *
+   * @param outputs the new solenoid outputs (1 bit per output)
+   */
+  virtual void SetAllSolenoidOutputs(uint8_t outputs) = 0;
+
+  /** Reset all simulation data for this object. */
+  virtual void ResetData() = 0;
+
+ protected:
+  const int m_index;
+  explicit PneumaticsBaseSim(const PneumaticsBase& module);
+  explicit PneumaticsBaseSim(const int index);
+};
+
+}  // namespace frc::sim
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/REVPHSim.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/REVPHSim.h
index e5f4efe..fe305ba 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/REVPHSim.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/REVPHSim.h
@@ -8,6 +8,7 @@
 
 #include "frc/PneumaticsBase.h"
 #include "frc/simulation/CallbackStore.h"
+#include "frc/simulation/PneumaticsBaseSim.h"
 
 namespace frc {
 
@@ -18,7 +19,7 @@
 /**
  * Class to control a simulated Pneumatic Control Module (PCM).
  */
-class REVPHSim {
+class REVPHSim : public PneumaticsBaseSim {
  public:
   /**
    * Constructs with the default PCM module number (CAN ID).
@@ -34,81 +35,38 @@
 
   explicit REVPHSim(const PneumaticsBase& pneumatics);
 
-  /**
-   * Register a callback to be run when a solenoid is initialized on a channel.
-   *
-   * @param callback the callback
-   * @param initialNotify should the callback be run with the initial state
-   * @return the CallbackStore object associated with this callback
-   */
+  ~REVPHSim() override = default;
+
   [[nodiscard]] std::unique_ptr<CallbackStore> RegisterInitializedCallback(
-      NotifyCallback callback, bool initialNotify);
+      NotifyCallback callback, bool initialNotify) override;
 
-  /**
-   * Check if a solenoid has been initialized on a specific channel.
-   *
-   * @return true if initialized
-   */
-  bool GetInitialized() const;
+  bool GetInitialized() const override;
 
-  /**
-   * Define whether a solenoid has been initialized on a specific channel.
-   *
-   * @param solenoidInitialized is there a solenoid initialized on that channel
-   */
-  void SetInitialized(bool solenoidInitialized);
+  void SetInitialized(bool solenoidInitialized) override;
 
-  /**
-   * Register a callback to be run when the solenoid output on a channel
-   * changes.
-   *
-   * @param channel the channel to monitor
-   * @param callback the callback
-   * @param initialNotify should the callback be run with the initial value
-   * @return the CallbackStore object associated with this callback
-   */
   [[nodiscard]] std::unique_ptr<CallbackStore> RegisterSolenoidOutputCallback(
-      int channel, NotifyCallback callback, bool initialNotify);
+      int channel, NotifyCallback callback, bool initialNotify) override;
 
-  /**
-   * Check the solenoid output on a specific channel.
-   *
-   * @param channel the channel to check
-   * @return the solenoid output
-   */
-  bool GetSolenoidOutput(int channel) const;
+  bool GetSolenoidOutput(int channel) const override;
 
-  /**
-   * Change the solenoid output on a specific channel.
-   *
-   * @param channel the channel to check
-   * @param solenoidOutput the new solenoid output
-   */
-  void SetSolenoidOutput(int channel, bool solenoidOutput);
+  void SetSolenoidOutput(int channel, bool solenoidOutput) override;
 
-  /**
-   * Register a callback to be run when the compressor activates.
-   *
-   * @param callback the callback
-   * @param initialNotify whether to run the callback with the initial state
-   * @return the CallbackStore object associated with this callback
-   */
   [[nodiscard]] std::unique_ptr<CallbackStore> RegisterCompressorOnCallback(
-      NotifyCallback callback, bool initialNotify);
+      NotifyCallback callback, bool initialNotify) override;
 
   /**
    * Check if the compressor is on.
    *
    * @return true if the compressor is active
    */
-  bool GetCompressorOn() const;
+  bool GetCompressorOn() const override;
 
   /**
    * Set whether the compressor is active.
    *
    * @param compressorOn the new value
    */
-  void SetCompressorOn(bool compressorOn);
+  void SetCompressorOn(bool compressorOn) override;
 
   /**
    * Register a callback to be run whenever the closed loop state changes.
@@ -136,77 +94,26 @@
    */
   void SetCompressorConfigType(int compressorConfigType);
 
-  /**
-   * Register a callback to be run whenever the pressure switch value changes.
-   *
-   * @param callback the callback
-   * @param initialNotify whether the callback should be called with the
-   *                      initial value
-   * @return the CallbackStore object associated with this callback
-   */
   [[nodiscard]] std::unique_ptr<CallbackStore> RegisterPressureSwitchCallback(
-      NotifyCallback callback, bool initialNotify);
+      NotifyCallback callback, bool initialNotify) override;
 
-  /**
-   * Check the value of the pressure switch.
-   *
-   * @return the pressure switch value
-   */
-  bool GetPressureSwitch() const;
+  bool GetPressureSwitch() const override;
 
-  /**
-   * Set the value of the pressure switch.
-   *
-   * @param pressureSwitch the new value
-   */
-  void SetPressureSwitch(bool pressureSwitch);
+  void SetPressureSwitch(bool pressureSwitch) override;
 
-  /**
-   * Register a callback to be run whenever the compressor current changes.
-   *
-   * @param callback the callback
-   * @param initialNotify whether to call the callback with the initial state
-   * @return the CallbackStore object associated with this callback
-   */
   [[nodiscard]] std::unique_ptr<CallbackStore>
   RegisterCompressorCurrentCallback(NotifyCallback callback,
-                                    bool initialNotify);
+                                    bool initialNotify) override;
 
-  /**
-   * Read the compressor current.
-   *
-   * @return the current of the compressor connected to this module
-   */
-  double GetCompressorCurrent() const;
+  double GetCompressorCurrent() const override;
 
-  /**
-   * Set the compressor current.
-   *
-   * @param compressorCurrent the new compressor current
-   */
-  void SetCompressorCurrent(double compressorCurrent);
+  void SetCompressorCurrent(double compressorCurrent) override;
 
-  /**
-   * Get the current value of all solenoid outputs.
-   *
-   * @return the solenoid outputs (1 bit per output)
-   */
-  uint8_t GetAllSolenoidOutputs() const;
+  uint8_t GetAllSolenoidOutputs() const override;
 
-  /**
-   * Change all of the solenoid outputs.
-   *
-   * @param outputs the new solenoid outputs (1 bit per output)
-   */
-  void SetAllSolenoidOutputs(uint8_t outputs);
+  void SetAllSolenoidOutputs(uint8_t outputs) override;
 
-  /**
-   * Reset all simulation data for this object.
-   */
-  void ResetData();
-
- private:
-  int m_index;
+  void ResetData() override;
 };
 }  // namespace sim
 }  // namespace frc
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/RoboRioSim.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/RoboRioSim.h
index 1095106..ee959b66 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/RoboRioSim.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/RoboRioSim.h
@@ -5,6 +5,7 @@
 #pragma once
 
 #include <memory>
+#include <string>
 
 #include <units/current.h>
 #include <units/voltage.h>
@@ -419,6 +420,34 @@
   static void SetBrownoutVoltage(units::volt_t brownoutVoltage);
 
   /**
+   * Get the serial number.
+   *
+   * @return The serial number.
+   */
+  static std::string GetSerialNumber();
+
+  /**
+   * Set the serial number.
+   *
+   * @param serialNumber The serial number.
+   */
+  static void SetSerialNumber(std::string_view serialNumber);
+
+  /**
+   * Get the comments.
+   *
+   * @return The comments.
+   */
+  static std::string GetComments();
+
+  /**
+   * Set the comments.
+   *
+   * @param comments The comments.
+   */
+  static void SetComments(std::string_view comments);
+
+  /**
    * Reset all simulation data.
    */
   static void ResetData();
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/SingleJointedArmSim.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/SingleJointedArmSim.h
index 4ff29cc..57ad6b1 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/SingleJointedArmSim.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/SingleJointedArmSim.h
@@ -30,14 +30,14 @@
    * @param armLength          The length of the arm.
    * @param minAngle           The minimum angle that the arm is capable of.
    * @param maxAngle           The maximum angle that the arm is capable of.
-   * @param mass               The mass of the arm.
-   * @param measurementStdDevs The standard deviations of the measurements.
+   * @param armMass            The mass of the arm.
    * @param simulateGravity    Whether gravity should be simulated or not.
+   * @param measurementStdDevs The standard deviations of the measurements.
    */
   SingleJointedArmSim(const LinearSystem<2, 1, 1>& system,
                       const DCMotor& gearbox, double gearing,
                       units::meter_t armLength, units::radian_t minAngle,
-                      units::radian_t maxAngle, units::kilogram_t mass,
+                      units::radian_t maxAngle, units::kilogram_t armMass,
                       bool simulateGravity,
                       const std::array<double, 1>& measurementStdDevs = {0.0});
   /**
@@ -52,8 +52,8 @@
    * @param minAngle           The minimum angle that the arm is capable of.
    * @param maxAngle           The maximum angle that the arm is capable of.
    * @param mass               The mass of the arm.
-   * @param measurementStdDevs The standard deviation of the measurement noise.
    * @param simulateGravity    Whether gravity should be simulated or not.
+   * @param measurementStdDevs The standard deviation of the measurement noise.
    */
   SingleJointedArmSim(const DCMotor& gearbox, double gearing,
                       units::kilogram_square_meter_t moi,
@@ -142,15 +142,14 @@
    * @param u           The system inputs (voltage).
    * @param dt          The time difference between controller updates.
    */
-  Eigen::Vector<double, 2> UpdateX(const Eigen::Vector<double, 2>& currentXhat,
-                                   const Eigen::Vector<double, 1>& u,
-                                   units::second_t dt) override;
+  Vectord<2> UpdateX(const Vectord<2>& currentXhat, const Vectord<1>& u,
+                     units::second_t dt) override;
 
  private:
   units::meter_t m_r;
   units::radian_t m_minAngle;
   units::radian_t m_maxAngle;
-  units::kilogram_t m_mass;
+  units::kilogram_t m_armMass;
   const DCMotor m_gearbox;
   double m_gearing;
   bool m_simulateGravity;
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/SolenoidSim.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/SolenoidSim.h
new file mode 100644
index 0000000..66e3589
--- /dev/null
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/simulation/SolenoidSim.h
@@ -0,0 +1,42 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <memory>
+
+#include "frc/PneumaticsModuleType.h"
+#include "frc/simulation/PneumaticsBaseSim.h"
+
+namespace frc::sim {
+
+class SolenoidSim {
+ public:
+  SolenoidSim(std::shared_ptr<PneumaticsBaseSim> moduleSim, int channel);
+  SolenoidSim(int module, PneumaticsModuleType type, int channel);
+  SolenoidSim(PneumaticsModuleType type, int channel);
+
+  bool GetOutput() const;
+  void SetOutput(bool output);
+
+  /**
+   * Register a callback to be run when the output of this solenoid has changed.
+   *
+   * @param callback the callback
+   * @param initialNotify whether to run the callback with the initial state
+   * @return the {@link CallbackStore} object associated with this callback.
+   * Save a reference to this object; it being deconstructed cancels the
+   * callback.
+   */
+  [[nodiscard]] virtual std::unique_ptr<CallbackStore> RegisterOutputCallback(
+      NotifyCallback callback, bool initialNotify);
+
+  std::shared_ptr<PneumaticsBaseSim> GetModuleSim() const;
+
+ private:
+  std::shared_ptr<PneumaticsBaseSim> m_module;
+  int m_channel;
+};
+
+}  // namespace frc::sim
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/smartdashboard/FieldObject2d.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/smartdashboard/FieldObject2d.h
index 2e41d84..f55938e 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/smartdashboard/FieldObject2d.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/smartdashboard/FieldObject2d.h
@@ -5,16 +5,16 @@
 #pragma once
 
 #include <initializer_list>
+#include <span>
 #include <string>
 #include <string_view>
 #include <utility>
 #include <vector>
 
-#include <networktables/NetworkTableEntry.h>
+#include <networktables/DoubleArrayTopic.h>
 #include <units/length.h>
 #include <wpi/SmallVector.h>
 #include <wpi/mutex.h>
-#include <wpi/span.h>
 
 #include "frc/geometry/Pose2d.h"
 #include "frc/geometry/Rotation2d.h"
@@ -66,7 +66,7 @@
    *
    * @param poses array of 2D poses
    */
-  void SetPoses(wpi::span<const Pose2d> poses);
+  void SetPoses(std::span<const Pose2d> poses);
 
   /**
    * Set multiple poses from an array of Pose objects.
@@ -97,7 +97,7 @@
    * @param out output SmallVector to hold 2D poses
    * @return span referring to output SmallVector
    */
-  wpi::span<const Pose2d> GetPoses(wpi::SmallVectorImpl<Pose2d>& out) const;
+  std::span<const Pose2d> GetPoses(wpi::SmallVectorImpl<Pose2d>& out) const;
 
  private:
   void UpdateEntry(bool setDefault = false);
@@ -105,7 +105,7 @@
 
   mutable wpi::mutex m_mutex;
   std::string m_name;
-  nt::NetworkTableEntry m_entry;
+  nt::DoubleArrayEntry m_entry;
   mutable wpi::SmallVector<Pose2d, 1> m_poses;
 };
 
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/smartdashboard/Mechanism2d.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/smartdashboard/Mechanism2d.h
index cbe25be..c71bcaf 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/smartdashboard/Mechanism2d.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/smartdashboard/Mechanism2d.h
@@ -7,8 +7,10 @@
 #include <memory>
 #include <string>
 
+#include <networktables/DoubleArrayTopic.h>
 #include <networktables/NTSendable.h>
-#include <networktables/NetworkTableEntry.h>
+#include <networktables/NetworkTable.h>
+#include <networktables/StringTopic.h>
 #include <wpi/StringMap.h>
 #include <wpi/mutex.h>
 #include <wpi/sendable/SendableHelper.h>
@@ -79,9 +81,11 @@
  private:
   double m_width;
   double m_height;
-  char m_color[10];
+  std::string m_color;
   mutable wpi::mutex m_mutex;
   std::shared_ptr<nt::NetworkTable> m_table;
   wpi::StringMap<std::unique_ptr<MechanismRoot2d>> m_roots;
+  nt::DoubleArrayPublisher m_dimsPub;
+  nt::StringPublisher m_colorPub;
 };
 }  // namespace frc
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/smartdashboard/MechanismLigament2d.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/smartdashboard/MechanismLigament2d.h
index f1bebb9..f9c86fc 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/smartdashboard/MechanismLigament2d.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/smartdashboard/MechanismLigament2d.h
@@ -7,7 +7,8 @@
 #include <memory>
 #include <string_view>
 
-#include <networktables/NetworkTableEntry.h>
+#include <networktables/DoubleTopic.h>
+#include <networktables/StringTopic.h>
 #include <units/angle.h>
 
 #include "frc/smartdashboard/MechanismObject2d.h"
@@ -89,14 +90,14 @@
   void UpdateEntries(std::shared_ptr<nt::NetworkTable> table) override;
 
  private:
-  void Flush();
+  nt::StringPublisher m_typePub;
   double m_length;
-  nt::NetworkTableEntry m_lengthEntry;
+  nt::DoubleEntry m_lengthEntry;
   double m_angle;
-  nt::NetworkTableEntry m_angleEntry;
+  nt::DoubleEntry m_angleEntry;
   double m_weight;
-  nt::NetworkTableEntry m_weightEntry;
+  nt::DoubleEntry m_weightEntry;
   char m_color[10];
-  nt::NetworkTableEntry m_colorEntry;
+  nt::StringEntry m_colorEntry;
 };
 }  // namespace frc
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/smartdashboard/MechanismRoot2d.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/smartdashboard/MechanismRoot2d.h
index 5072547..37e0f7b 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/smartdashboard/MechanismRoot2d.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/smartdashboard/MechanismRoot2d.h
@@ -7,7 +7,7 @@
 #include <memory>
 #include <string_view>
 
-#include <networktables/NetworkTableEntry.h>
+#include <networktables/DoubleTopic.h>
 
 #include "MechanismObject2d.h"
 
@@ -48,7 +48,7 @@
   inline void Flush();
   double m_x;
   double m_y;
-  nt::NetworkTableEntry m_xEntry;
-  nt::NetworkTableEntry m_yEntry;
+  nt::DoublePublisher m_xPub;
+  nt::DoublePublisher m_yPub;
 };
 }  // namespace frc
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/smartdashboard/SendableBuilderImpl.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/smartdashboard/SendableBuilderImpl.h
index 36830f6..4bd4289 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/smartdashboard/SendableBuilderImpl.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/smartdashboard/SendableBuilderImpl.h
@@ -6,17 +6,18 @@
 
 #include <functional>
 #include <memory>
+#include <span>
 #include <string>
 #include <string_view>
 #include <utility>
 #include <vector>
 
+#include <networktables/BooleanTopic.h>
 #include <networktables/NTSendableBuilder.h>
 #include <networktables/NetworkTable.h>
-#include <networktables/NetworkTableEntry.h>
-#include <networktables/NetworkTableValue.h>
+#include <networktables/StringTopic.h>
+#include <wpi/FunctionExtras.h>
 #include <wpi/SmallVector.h>
-#include <wpi/span.h>
 
 namespace frc {
 
@@ -54,7 +55,8 @@
   bool IsActuator() const;
 
   /**
-   * Update the network table values by calling the getters for all properties.
+   * Synchronize with network table values by calling the getters for all
+   * properties and setters when the network table value has changed.
    */
   void Update() override;
 
@@ -88,12 +90,18 @@
   void SetSmartDashboardType(std::string_view type) override;
   void SetActuator(bool value) override;
   void SetSafeState(std::function<void()> func) override;
-  void SetUpdateTable(std::function<void()> func) override;
-  nt::NetworkTableEntry GetEntry(std::string_view key) override;
+  void SetUpdateTable(wpi::unique_function<void()> func) override;
+  nt::Topic GetTopic(std::string_view key) override;
 
   void AddBooleanProperty(std::string_view key, std::function<bool()> getter,
                           std::function<void(bool)> setter) override;
 
+  void AddIntegerProperty(std::string_view key, std::function<int64_t()> getter,
+                          std::function<void(int64_t)> setter) override;
+
+  void AddFloatProperty(std::string_view key, std::function<float()> getter,
+                        std::function<void(float)> setter) override;
+
   void AddDoubleProperty(std::string_view key, std::function<double()> getter,
                          std::function<void(double)> setter) override;
 
@@ -103,22 +111,28 @@
 
   void AddBooleanArrayProperty(
       std::string_view key, std::function<std::vector<int>()> getter,
-      std::function<void(wpi::span<const int>)> setter) override;
+      std::function<void(std::span<const int>)> setter) override;
+
+  void AddIntegerArrayProperty(
+      std::string_view key, std::function<std::vector<int64_t>()> getter,
+      std::function<void(std::span<const int64_t>)> setter) override;
+
+  void AddFloatArrayProperty(
+      std::string_view key, std::function<std::vector<float>()> getter,
+      std::function<void(std::span<const float>)> setter) override;
 
   void AddDoubleArrayProperty(
       std::string_view key, std::function<std::vector<double>()> getter,
-      std::function<void(wpi::span<const double>)> setter) override;
+      std::function<void(std::span<const double>)> setter) override;
 
   void AddStringArrayProperty(
       std::string_view key, std::function<std::vector<std::string>()> getter,
-      std::function<void(wpi::span<const std::string>)> setter) override;
+      std::function<void(std::span<const std::string>)> setter) override;
 
-  void AddRawProperty(std::string_view key, std::function<std::string()> getter,
-                      std::function<void(std::string_view)> setter) override;
-
-  void AddValueProperty(
-      std::string_view key, std::function<std::shared_ptr<nt::Value>()> getter,
-      std::function<void(std::shared_ptr<nt::Value>)> setter) override;
+  void AddRawProperty(
+      std::string_view key, std::string_view typeString,
+      std::function<std::vector<uint8_t>()> getter,
+      std::function<void(std::span<const uint8_t>)> setter) override;
 
   void AddSmallStringProperty(
       std::string_view key,
@@ -127,82 +141,77 @@
 
   void AddSmallBooleanArrayProperty(
       std::string_view key,
-      std::function<wpi::span<const int>(wpi::SmallVectorImpl<int>& buf)>
+      std::function<std::span<const int>(wpi::SmallVectorImpl<int>& buf)>
           getter,
-      std::function<void(wpi::span<const int>)> setter) override;
+      std::function<void(std::span<const int>)> setter) override;
+
+  void AddSmallIntegerArrayProperty(
+      std::string_view key,
+      std::function<
+          std::span<const int64_t>(wpi::SmallVectorImpl<int64_t>& buf)>
+          getter,
+      std::function<void(std::span<const int64_t>)> setter) override;
+
+  void AddSmallFloatArrayProperty(
+      std::string_view key,
+      std::function<std::span<const float>(wpi::SmallVectorImpl<float>& buf)>
+          getter,
+      std::function<void(std::span<const float>)> setter) override;
 
   void AddSmallDoubleArrayProperty(
       std::string_view key,
-      std::function<wpi::span<const double>(wpi::SmallVectorImpl<double>& buf)>
+      std::function<std::span<const double>(wpi::SmallVectorImpl<double>& buf)>
           getter,
-      std::function<void(wpi::span<const double>)> setter) override;
+      std::function<void(std::span<const double>)> setter) override;
 
   void AddSmallStringArrayProperty(
       std::string_view key,
       std::function<
-          wpi::span<const std::string>(wpi::SmallVectorImpl<std::string>& buf)>
+          std::span<const std::string>(wpi::SmallVectorImpl<std::string>& buf)>
           getter,
-      std::function<void(wpi::span<const std::string>)> setter) override;
+      std::function<void(std::span<const std::string>)> setter) override;
 
   void AddSmallRawProperty(
-      std::string_view key,
-      std::function<std::string_view(wpi::SmallVectorImpl<char>& buf)> getter,
-      std::function<void(std::string_view)> setter) override;
+      std::string_view key, std::string_view typeString,
+      std::function<std::span<uint8_t>(wpi::SmallVectorImpl<uint8_t>& buf)>
+          getter,
+      std::function<void(std::span<const uint8_t>)> setter) override;
 
  private:
   struct Property {
-    Property(nt::NetworkTable& table, std::string_view key)
-        : entry(table.GetEntry(key)) {}
-
-    Property(const Property&) = delete;
-    Property& operator=(const Property&) = delete;
-
-    Property(Property&& other) noexcept
-        : entry(other.entry),
-          listener(other.listener),
-          update(std::move(other.update)),
-          createListener(std::move(other.createListener)) {
-      other.entry = nt::NetworkTableEntry();
-      other.listener = 0;
-    }
-
-    Property& operator=(Property&& other) noexcept {
-      entry = other.entry;
-      listener = other.listener;
-      other.entry = nt::NetworkTableEntry();
-      other.listener = 0;
-      update = std::move(other.update);
-      createListener = std::move(other.createListener);
-      return *this;
-    }
-
-    ~Property() { StopListener(); }
-
-    void StartListener() {
-      if (entry && listener == 0 && createListener) {
-        listener = createListener(entry);
-      }
-    }
-
-    void StopListener() {
-      if (entry && listener != 0) {
-        entry.RemoveListener(listener);
-        listener = 0;
-      }
-    }
-
-    nt::NetworkTableEntry entry;
-    NT_EntryListener listener = 0;
-    std::function<void(nt::NetworkTableEntry entry, uint64_t time)> update;
-    std::function<NT_EntryListener(nt::NetworkTableEntry entry)> createListener;
+    virtual ~Property() = default;
+    virtual void Update(bool controllable, int64_t time) = 0;
   };
 
-  std::vector<Property> m_properties;
+  template <typename Topic>
+  struct PropertyImpl : public Property {
+    void Update(bool controllable, int64_t time) override;
+
+    using Publisher = typename Topic::PublisherType;
+    using Subscriber = typename Topic::SubscriberType;
+    Publisher pub;
+    Subscriber sub;
+    std::function<void(Publisher& pub, int64_t time)> updateNetwork;
+    std::function<void(Subscriber& sub)> updateLocal;
+  };
+
+  template <typename Topic, typename Getter, typename Setter>
+  void AddPropertyImpl(Topic topic, Getter getter, Setter setter);
+
+  template <typename T, size_t Size, typename Topic, typename Getter,
+            typename Setter>
+  void AddSmallPropertyImpl(Topic topic, Getter getter, Setter setter);
+
+  std::vector<std::unique_ptr<Property>> m_properties;
   std::function<void()> m_safeState;
-  std::vector<std::function<void()>> m_updateTables;
+  std::vector<wpi::unique_function<void()>> m_updateTables;
   std::shared_ptr<nt::NetworkTable> m_table;
-  nt::NetworkTableEntry m_controllableEntry;
+  bool m_controllable = false;
   bool m_actuator = false;
+
+  nt::BooleanPublisher m_controllablePublisher;
+  nt::StringPublisher m_typePublisher;
+  nt::BooleanPublisher m_actuatorPublisher;
 };
 
 }  // namespace frc
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooser.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooser.h
index b693762..7fe0b59 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooser.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooser.h
@@ -8,7 +8,6 @@
 #include <string_view>
 
 #include <wpi/StringMap.h>
-#include <wpi/deprecated.h>
 
 #include "frc/smartdashboard/SendableChooserBase.h"
 
@@ -69,36 +68,6 @@
   void SetDefaultOption(std::string_view name, T object);
 
   /**
-   * Adds the given object to the list of options.
-   *
-   * On the SmartDashboard on the desktop, the object will appear as the given
-   * name.
-   *
-   * @deprecated use AddOption(std::string_view name, T object) instead.
-   *
-   * @param name   the name of the option
-   * @param object the option
-   */
-  WPI_DEPRECATED("use AddOption() instead")
-  void AddObject(std::string_view name, T object) { AddOption(name, object); }
-
-  /**
-   * Add the given object to the list of options and marks it as the default.
-   *
-   * Functionally, this is very close to AddOption() except that it will use
-   * this as the default option if none other is explicitly selected.
-   *
-   * @deprecated use SetDefaultOption(std::string_view name, T object) instead.
-   *
-   * @param name   the name of the option
-   * @param object the option
-   */
-  WPI_DEPRECATED("use SetDefaultOption() instead")
-  void AddDefault(std::string_view name, T object) {
-    SetDefaultOption(name, object);
-  }
-
-  /**
    * Returns a copy of the selected option (a raw pointer U* if T =
    * std::unique_ptr<U> or a std::weak_ptr<U> if T = std::shared_ptr<U>).
    *
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooser.inc b/third_party/allwpilib/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooser.inc
index 25e2551..e90542b 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooser.inc
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooser.inc
@@ -48,10 +48,17 @@
 template <class T>
 void SendableChooser<T>::InitSendable(nt::NTSendableBuilder& builder) {
   builder.SetSmartDashboardType("String Chooser");
-  builder.GetEntry(kInstance).SetDouble(m_instance);
+  {
+    std::scoped_lock lock(m_mutex);
+    m_instancePubs.emplace_back(
+        nt::IntegerTopic{builder.GetTopic(kInstance)}.Publish());
+    m_instancePubs.back().Set(m_instance);
+    m_activePubs.emplace_back(
+        nt::StringTopic{builder.GetTopic(kActive)}.Publish());
+  }
   builder.AddStringArrayProperty(
       kOptions,
-      [=] {
+      [=, this] {
         std::vector<std::string> keys;
         for (const auto& choice : m_choices) {
           keys.emplace_back(choice.first());
@@ -66,13 +73,13 @@
       nullptr);
   builder.AddSmallStringProperty(
       kDefault,
-      [=](wpi::SmallVectorImpl<char>&) -> std::string_view {
+      [=, this](wpi::SmallVectorImpl<char>&) -> std::string_view {
         return m_defaultChoice;
       },
       nullptr);
   builder.AddSmallStringProperty(
       kActive,
-      [=](wpi::SmallVectorImpl<char>& buf) -> std::string_view {
+      [=, this](wpi::SmallVectorImpl<char>& buf) -> std::string_view {
         std::scoped_lock lock(m_mutex);
         if (m_haveSelected) {
           buf.assign(m_selected.begin(), m_selected.end());
@@ -82,18 +89,15 @@
         }
       },
       nullptr);
-  {
-    std::scoped_lock lock(m_mutex);
-    m_activeEntries.emplace_back(builder.GetEntry(kActive));
-  }
-  builder.AddStringProperty(kSelected, nullptr, [=](std::string_view val) {
-    std::scoped_lock lock(m_mutex);
-    m_haveSelected = true;
-    m_selected = val;
-    for (auto& entry : m_activeEntries) {
-      entry.SetString(val);
-    }
-  });
+  builder.AddStringProperty(kSelected, nullptr,
+                            [=, this](std::string_view val) {
+                              std::scoped_lock lock(m_mutex);
+                              m_haveSelected = true;
+                              m_selected = val;
+                              for (auto& pub : m_activePubs) {
+                                pub.Set(val);
+                              }
+                            });
 }
 
 template <class T>
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooserBase.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooserBase.h
index 78f891a..b5df73c 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooserBase.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooserBase.h
@@ -7,8 +7,9 @@
 #include <atomic>
 #include <string>
 
+#include <networktables/IntegerTopic.h>
 #include <networktables/NTSendable.h>
-#include <networktables/NetworkTableEntry.h>
+#include <networktables/StringTopic.h>
 #include <wpi/SmallVector.h>
 #include <wpi/mutex.h>
 #include <wpi/sendable/SendableHelper.h>
@@ -40,7 +41,8 @@
   std::string m_defaultChoice;
   std::string m_selected;
   bool m_haveSelected = false;
-  wpi::SmallVector<nt::NetworkTableEntry, 2> m_activeEntries;
+  wpi::SmallVector<nt::IntegerPublisher, 2> m_instancePubs;
+  wpi::SmallVector<nt::StringPublisher, 2> m_activePubs;
   wpi::mutex m_mutex;
   int m_instance;
   static std::atomic_int s_instances;
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/smartdashboard/SmartDashboard.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/smartdashboard/SmartDashboard.h
index 47c4a28..aeb4947 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/smartdashboard/SmartDashboard.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/smartdashboard/SmartDashboard.h
@@ -5,13 +5,13 @@
 #pragma once
 
 #include <memory>
+#include <span>
 #include <string>
 #include <string_view>
 #include <vector>
 
 #include <networktables/NetworkTableEntry.h>
 #include <networktables/NetworkTableValue.h>
-#include <wpi/span.h>
 
 namespace wpi {
 class Sendable;
@@ -63,39 +63,6 @@
   static bool IsPersistent(std::string_view key);
 
   /**
-   * Sets flags on the specified key in this table. The key can
-   * not be null.
-   *
-   * @param key the key name
-   * @param flags the flags to set (bitmask)
-   */
-  static void SetFlags(std::string_view key, unsigned int flags);
-
-  /**
-   * Clears flags on the specified key in this table. The key can
-   * not be null.
-   *
-   * @param key the key name
-   * @param flags the flags to clear (bitmask)
-   */
-  static void ClearFlags(std::string_view key, unsigned int flags);
-
-  /**
-   * Returns the flags for the specified key.
-   *
-   * @param key the key name
-   * @return the flags, or 0 if the key is not defined
-   */
-  static unsigned int GetFlags(std::string_view key);
-
-  /**
-   * Deletes the specified key in this table.
-   *
-   * @param key the key name
-   */
-  static void Delete(std::string_view key);
-
-  /**
    * Returns an NT Entry mapping to the specified key
    *
    * This is useful if an entry is used often, or is read and then modified.
@@ -249,7 +216,7 @@
    *       std::vector<bool> is special-cased in C++. 0 is false, any
    *       non-zero value is true.
    */
-  static bool PutBooleanArray(std::string_view key, wpi::span<const int> value);
+  static bool PutBooleanArray(std::string_view key, std::span<const int> value);
 
   /**
    * Gets the current value in the table, setting it if it does not exist.
@@ -259,7 +226,7 @@
    * @returns False if the table key exists with a different type
    */
   static bool SetDefaultBooleanArray(std::string_view key,
-                                     wpi::span<const int> defaultValue);
+                                     std::span<const int> defaultValue);
 
   /**
    * Returns the boolean array the key maps to.
@@ -280,7 +247,7 @@
    *       non-zero value is true.
    */
   static std::vector<int> GetBooleanArray(std::string_view key,
-                                          wpi::span<const int> defaultValue);
+                                          std::span<const int> defaultValue);
 
   /**
    * Put a number array in the table.
@@ -290,7 +257,7 @@
    * @return False if the table key already exists with a different type
    */
   static bool PutNumberArray(std::string_view key,
-                             wpi::span<const double> value);
+                             std::span<const double> value);
 
   /**
    * Gets the current value in the table, setting it if it does not exist.
@@ -300,7 +267,7 @@
    * @returns False if the table key exists with a different type
    */
   static bool SetDefaultNumberArray(std::string_view key,
-                                    wpi::span<const double> defaultValue);
+                                    std::span<const double> defaultValue);
 
   /**
    * Returns the number array the key maps to.
@@ -317,7 +284,7 @@
    *       use GetValue() instead.
    */
   static std::vector<double> GetNumberArray(
-      std::string_view key, wpi::span<const double> defaultValue);
+      std::string_view key, std::span<const double> defaultValue);
 
   /**
    * Put a string array in the table.
@@ -327,7 +294,7 @@
    * @return False if the table key already exists with a different type
    */
   static bool PutStringArray(std::string_view key,
-                             wpi::span<const std::string> value);
+                             std::span<const std::string> value);
 
   /**
    * Gets the current value in the table, setting it if it does not exist.
@@ -337,7 +304,7 @@
    * @returns False if the table key exists with a different type
    */
   static bool SetDefaultStringArray(std::string_view key,
-                                    wpi::span<const std::string> defaultValue);
+                                    std::span<const std::string> defaultValue);
 
   /**
    * Returns the string array the key maps to.
@@ -354,7 +321,7 @@
    *       use GetValue() instead.
    */
   static std::vector<std::string> GetStringArray(
-      std::string_view key, wpi::span<const std::string> defaultValue);
+      std::string_view key, std::span<const std::string> defaultValue);
 
   /**
    * Put a raw value (byte array) in the table.
@@ -363,7 +330,7 @@
    * @param value The value that will be assigned.
    * @return False if the table key already exists with a different type
    */
-  static bool PutRaw(std::string_view key, std::string_view value);
+  static bool PutRaw(std::string_view key, std::span<const uint8_t> value);
 
   /**
    * Gets the current value in the table, setting it if it does not exist.
@@ -373,7 +340,7 @@
    * @returns False if the table key exists with a different type
    */
   static bool SetDefaultRaw(std::string_view key,
-                            std::string_view defaultValue);
+                            std::span<const uint8_t> defaultValue);
 
   /**
    * Returns the raw value (byte array) the key maps to.
@@ -389,8 +356,8 @@
    * @note This makes a copy of the raw contents. If the overhead of this is a
    *       concern, use GetValue() instead.
    */
-  static std::string GetRaw(std::string_view key,
-                            std::string_view defaultValue);
+  static std::vector<uint8_t> GetRaw(std::string_view key,
+                                     std::span<const uint8_t> defaultValue);
 
   /**
    * Maps the specified key to the specified complex value (such as an array) in
@@ -403,8 +370,7 @@
    * @param value   the value
    * @return        False if the table key already exists with a different type
    */
-  static bool PutValue(std::string_view keyName,
-                       std::shared_ptr<nt::Value> value);
+  static bool PutValue(std::string_view keyName, const nt::Value& value);
 
   /**
    * Gets the current value in the table, setting it if it does not exist.
@@ -414,7 +380,7 @@
    * @returns False if the table key exists with a different type
    */
   static bool SetDefaultValue(std::string_view key,
-                              std::shared_ptr<nt::Value> defaultValue);
+                              const nt::Value& defaultValue);
 
   /**
    * Retrieves the complex value (such as an array) in this table into the
@@ -422,7 +388,7 @@
    *
    * @param keyName the key
    */
-  static std::shared_ptr<nt::Value> GetValue(std::string_view keyName);
+  static nt::Value GetValue(std::string_view keyName);
 
   /**
    * Posts a task from a listener to the ListenerExecutor, so that it can be run
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/util/Color.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/util/Color.h
index 00bc4af..87d8c12 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/util/Color.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/util/Color.h
@@ -5,6 +5,7 @@
 #pragma once
 
 #include <algorithm>
+#include <string>
 
 namespace frc {
 
@@ -741,7 +742,7 @@
   constexpr Color() = default;
 
   /**
-   * Constructs a Color.
+   * Constructs a Color from doubles (0-1).
    *
    * @param r Red value (0-1)
    * @param g Green value (0-1)
@@ -753,41 +754,70 @@
         blue(roundAndClamp(b)) {}
 
   /**
+   * Constructs a Color from ints (0-255).
+   *
+   * @param r Red value (0-255)
+   * @param g Green value (0-255)
+   * @param b Blue value (0-255)
+   */
+  constexpr Color(int r, int g, int b)
+      : Color(r / 255.0, g / 255.0, b / 255.0) {}
+
+  constexpr bool operator==(const Color&) const = default;
+
+  /**
    * Creates a Color from HSV values.
    *
-   * @param h The h value [0-180]
+   * @param h The h value [0-180)
    * @param s The s value [0-255]
    * @param v The v value [0-255]
    * @return The color
    */
   static constexpr Color FromHSV(int h, int s, int v) {
-    if (s == 0) {
-      return {v / 255.0, v / 255.0, v / 255.0};
-    }
+    // Loosely based on
+    // https://en.wikipedia.org/wiki/HSL_and_HSV#HSV_to_RGB
+    // The hue range is split into 60 degree regions where in each region there
+    // is one rgb component at a low value (m), one at a high value (v) and one
+    // that changes (X) from low to high (X+m) or high to low (v-X)
 
-    int region = h / 30;
-    int remainder = (h - (region * 30)) * 6;
+    // Difference between highest and lowest value of any rgb component
+    int chroma = (s * v) >> 8;
 
-    int p = (v * (255 - s)) >> 8;
-    int q = (v * (255 - ((s * remainder) >> 8))) >> 8;
-    int t = (v * (255 - ((s * (255 - remainder)) >> 8))) >> 8;
+    // Because hue is 0-180 rather than 0-360 use 30 not 60
+    int region = (h / 30) % 6;
+
+    // Remainder converted from 0-30 to 0-255
+    int remainder = static_cast<int>((h % 30) * (255 / 30.0));
+
+    // Value of the lowest rgb component
+    int m = v - chroma;
+
+    // Goes from 0 to chroma as hue increases
+    int X = (chroma * remainder) >> 8;
 
     switch (region) {
       case 0:
-        return Color(v / 255.0, t / 255.0, p / 255.0);
+        return Color(v, X + m, m);
       case 1:
-        return Color(q / 255.0, v / 255.0, p / 255.0);
+        return Color(v - X, v, m);
       case 2:
-        return Color(p / 255.0, v / 255.0, t / 255.0);
+        return Color(m, v, X + m);
       case 3:
-        return Color(p / 255.0, q / 255.0, v / 255.0);
+        return Color(m, v - X, v);
       case 4:
-        return Color(t / 255.0, p / 255.0, v / 255.0);
+        return Color(X + m, m, v);
       default:
-        return Color(v / 255.0, p / 255.0, q / 255.0);
+        return Color(v, m, v - X);
     }
   }
 
+  /**
+   * Return this color represented as a hex string.
+   *
+   * @return a string of the format <tt>\#RRGGBB</tt>
+   */
+  std::string HexString() const;
+
   double red = 0.0;
   double green = 0.0;
   double blue = 0.0;
@@ -802,14 +832,6 @@
   }
 };
 
-inline bool operator==(const Color& c1, const Color& c2) {
-  return c1.red == c2.red && c1.green == c2.green && c1.blue == c2.blue;
-}
-
-inline bool operator!=(const Color& c1, const Color& c2) {
-  return !(c1 == c2);
-}
-
 /*
  * FIRST Colors
  */
diff --git a/third_party/allwpilib/wpilibc/src/main/native/include/frc/util/Color8Bit.h b/third_party/allwpilib/wpilibc/src/main/native/include/frc/util/Color8Bit.h
index 62cbde9..10afead 100644
--- a/third_party/allwpilib/wpilibc/src/main/native/include/frc/util/Color8Bit.h
+++ b/third_party/allwpilib/wpilibc/src/main/native/include/frc/util/Color8Bit.h
@@ -5,6 +5,7 @@
 #pragma once
 
 #include <algorithm>
+#include <string>
 
 #include "Color.h"
 
@@ -43,13 +44,18 @@
     return Color(red / 255.0, green / 255.0, blue / 255.0);
   }
 
+  constexpr bool operator==(const Color8Bit&) const = default;
+
+  /**
+   * Return this color represented as a hex string.
+   *
+   * @return a string of the format <tt>\#RRGGBB</tt>
+   */
+  std::string HexString() const;
+
   int red = 0;
   int green = 0;
   int blue = 0;
 };
 
-inline bool operator==(const Color8Bit& c1, const Color8Bit& c2) {
-  return c1.red == c2.red && c1.green == c2.green && c1.blue == c2.blue;
-}
-
 }  // namespace frc
diff --git a/third_party/allwpilib/wpilibc/src/test/native/cpp/MockMotorController.cpp b/third_party/allwpilib/wpilibc/src/test/native/cpp/MockMotorController.cpp
deleted file mode 100644
index 62fd54a..0000000
--- a/third_party/allwpilib/wpilibc/src/test/native/cpp/MockMotorController.cpp
+++ /dev/null
@@ -1,31 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "MockMotorController.h"
-
-using namespace frc;
-
-void MockMotorController::Set(double speed) {
-  m_speed = m_isInverted ? -speed : speed;
-}
-
-double MockMotorController::Get() const {
-  return m_speed;
-}
-
-void MockMotorController::SetInverted(bool isInverted) {
-  m_isInverted = isInverted;
-}
-
-bool MockMotorController::GetInverted() const {
-  return m_isInverted;
-}
-
-void MockMotorController::Disable() {
-  m_speed = 0;
-}
-
-void MockMotorController::StopMotor() {
-  Disable();
-}
diff --git a/third_party/allwpilib/wpilibc/src/test/native/cpp/SpeedControllerGroupTest.cpp b/third_party/allwpilib/wpilibc/src/test/native/cpp/SpeedControllerGroupTest.cpp
deleted file mode 100644
index 38e1592..0000000
--- a/third_party/allwpilib/wpilibc/src/test/native/cpp/SpeedControllerGroupTest.cpp
+++ /dev/null
@@ -1,125 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/motorcontrol/MotorControllerGroup.h"  // NOLINT(build/include_order)
-
-#include <memory>
-#include <vector>
-
-#include "MockMotorController.h"
-#include "gtest/gtest.h"
-
-using namespace frc;
-
-enum MotorControllerGroupTestType { TEST_ONE, TEST_TWO, TEST_THREE };
-
-std::ostream& operator<<(std::ostream& os,
-                         const MotorControllerGroupTestType& type) {
-  switch (type) {
-    case TEST_ONE:
-      os << "MotorControllerGroup with one speed controller";
-      break;
-    case TEST_TWO:
-      os << "MotorControllerGroup with two speed controllers";
-      break;
-    case TEST_THREE:
-      os << "MotorControllerGroup with three speed controllers";
-      break;
-  }
-
-  return os;
-}
-
-/**
- * A fixture used for MotorControllerGroup testing.
- */
-class MotorControllerGroupTest
-    : public testing::TestWithParam<MotorControllerGroupTestType> {
- protected:
-  std::vector<MockMotorController> m_speedControllers;
-  std::unique_ptr<MotorControllerGroup> m_group;
-
-  void SetUp() override {
-    switch (GetParam()) {
-      case TEST_ONE: {
-        m_speedControllers.emplace_back();
-        m_group = std::make_unique<MotorControllerGroup>(m_speedControllers[0]);
-        break;
-      }
-
-      case TEST_TWO: {
-        m_speedControllers.emplace_back();
-        m_speedControllers.emplace_back();
-        m_group = std::make_unique<MotorControllerGroup>(m_speedControllers[0],
-                                                         m_speedControllers[1]);
-        break;
-      }
-
-      case TEST_THREE: {
-        m_speedControllers.emplace_back();
-        m_speedControllers.emplace_back();
-        m_speedControllers.emplace_back();
-        m_group = std::make_unique<MotorControllerGroup>(m_speedControllers[0],
-                                                         m_speedControllers[1],
-                                                         m_speedControllers[2]);
-        break;
-      }
-    }
-  }
-};
-
-TEST_P(MotorControllerGroupTest, Set) {
-  m_group->Set(1.0);
-
-  for (auto& speedController : m_speedControllers) {
-    EXPECT_FLOAT_EQ(speedController.Get(), 1.0);
-  }
-}
-
-TEST_P(MotorControllerGroupTest, GetInverted) {
-  m_group->SetInverted(true);
-
-  EXPECT_TRUE(m_group->GetInverted());
-}
-
-TEST_P(MotorControllerGroupTest, SetInvertedDoesNotModifyMotorControllers) {
-  for (auto& speedController : m_speedControllers) {
-    speedController.SetInverted(false);
-  }
-  m_group->SetInverted(true);
-
-  for (auto& speedController : m_speedControllers) {
-    EXPECT_EQ(speedController.GetInverted(), false);
-  }
-}
-
-TEST_P(MotorControllerGroupTest, SetInvertedDoesInvert) {
-  m_group->SetInverted(true);
-  m_group->Set(1.0);
-
-  for (auto& speedController : m_speedControllers) {
-    EXPECT_FLOAT_EQ(speedController.Get(), -1.0);
-  }
-}
-
-TEST_P(MotorControllerGroupTest, Disable) {
-  m_group->Set(1.0);
-  m_group->Disable();
-
-  for (auto& speedController : m_speedControllers) {
-    EXPECT_FLOAT_EQ(speedController.Get(), 0.0);
-  }
-}
-
-TEST_P(MotorControllerGroupTest, StopMotor) {
-  m_group->Set(1.0);
-  m_group->StopMotor();
-
-  for (auto& speedController : m_speedControllers) {
-    EXPECT_FLOAT_EQ(speedController.Get(), 0.0);
-  }
-}
-
-INSTANTIATE_TEST_SUITE_P(Tests, MotorControllerGroupTest,
-                         testing::Values(TEST_ONE, TEST_TWO, TEST_THREE));
diff --git a/third_party/allwpilib/wpilibc/src/test/native/cpp/TestCallbackHelpers.cpp b/third_party/allwpilib/wpilibc/src/test/native/cpp/TestCallbackHelpers.cpp
index 12ae5d2..99bd0fd 100644
--- a/third_party/allwpilib/wpilibc/src/test/native/cpp/TestCallbackHelpers.cpp
+++ b/third_party/allwpilib/wpilibc/src/test/native/cpp/TestCallbackHelpers.cpp
@@ -14,8 +14,9 @@
     throw std::invalid_argument("Null value");
   }
   if (value->type != HAL_BOOLEAN) {
-    throw std::invalid_argument(
-        fmt::format("Wrong type '{}' for boolean", value->type).c_str());
+    throw std::invalid_argument(fmt::format("Wrong type '{}' for boolean",
+                                            static_cast<int>(value->type))
+                                    .c_str());
   }
   m_wasTriggered = true;
   m_lastValue = value->data.v_boolean;
@@ -28,7 +29,8 @@
   }
   if (value->type != HAL_ENUM) {
     throw std::invalid_argument(
-        fmt::format("Wrong type '{}' for enum", value->type).c_str());
+        fmt::format("Wrong type '{}' for enum", static_cast<int>(value->type))
+            .c_str());
   }
 
   m_wasTriggered = true;
@@ -41,8 +43,9 @@
     throw std::invalid_argument("Null value");
   }
   if (value->type != HAL_INT) {
-    throw std::invalid_argument(
-        fmt::format("Wrong type '{}' for integer", value->type).c_str());
+    throw std::invalid_argument(fmt::format("Wrong type '{}' for integer",
+                                            static_cast<int>(value->type))
+                                    .c_str());
   }
 
   m_wasTriggered = true;
@@ -56,7 +59,8 @@
   }
   if (value->type != HAL_LONG) {
     throw std::invalid_argument(
-        fmt::format("Wrong type '{}' for long", value->type).c_str());
+        fmt::format("Wrong type '{}' for long", static_cast<int>(value->type))
+            .c_str());
   }
 
   m_wasTriggered = true;
@@ -70,7 +74,8 @@
   }
   if (value->type != HAL_DOUBLE) {
     throw std::invalid_argument(
-        fmt::format("Wrong type '{}' for double", value->type).c_str());
+        fmt::format("Wrong type '{}' for double", static_cast<int>(value->type))
+            .c_str());
   }
 
   m_wasTriggered = true;
diff --git a/third_party/allwpilib/wpilibc/src/test/native/cpp/TimedRobotTest.cpp b/third_party/allwpilib/wpilibc/src/test/native/cpp/TimedRobotTest.cpp
index ea9656b..08c262b 100644
--- a/third_party/allwpilib/wpilibc/src/test/native/cpp/TimedRobotTest.cpp
+++ b/third_party/allwpilib/wpilibc/src/test/native/cpp/TimedRobotTest.cpp
@@ -9,6 +9,7 @@
 #include <atomic>
 #include <thread>
 
+#include "frc/livewindow/LiveWindow.h"
 #include "frc/simulation/DriverStationSim.h"
 #include "frc/simulation/SimHooks.h"
 #include "gtest/gtest.h"
@@ -16,7 +17,7 @@
 using namespace frc;
 
 namespace {
-class TimedRobotTest : public ::testing::Test {
+class TimedRobotTest : public ::testing::TestWithParam<bool> {
  protected:
   void SetUp() override { frc::sim::PauseTiming(); }
 
@@ -304,8 +305,11 @@
   robotThread.join();
 }
 
-TEST_F(TimedRobotTest, TestMode) {
+TEST_P(TimedRobotTest, TestMode) {
+  bool isTestLW = GetParam();
+
   MockRobot robot;
+  robot.EnableLiveWindowInTest(isTestLW);
 
   std::thread robotThread{[&] { robot.StartCompetition(); }};
 
@@ -321,6 +325,7 @@
   EXPECT_EQ(0u, robot.m_autonomousInitCount);
   EXPECT_EQ(0u, robot.m_teleopInitCount);
   EXPECT_EQ(0u, robot.m_testInitCount);
+  EXPECT_FALSE(frc::LiveWindow::IsEnabled());
 
   EXPECT_EQ(0u, robot.m_robotPeriodicCount);
   EXPECT_EQ(0u, robot.m_simulationPeriodicCount);
@@ -342,6 +347,9 @@
   EXPECT_EQ(0u, robot.m_autonomousInitCount);
   EXPECT_EQ(0u, robot.m_teleopInitCount);
   EXPECT_EQ(1u, robot.m_testInitCount);
+  EXPECT_EQ(isTestLW, frc::LiveWindow::IsEnabled());
+
+  EXPECT_THROW(robot.EnableLiveWindowInTest(isTestLW), std::runtime_error);
 
   EXPECT_EQ(1u, robot.m_robotPeriodicCount);
   EXPECT_EQ(1u, robot.m_simulationPeriodicCount);
@@ -376,6 +384,32 @@
   EXPECT_EQ(0u, robot.m_teleopExitCount);
   EXPECT_EQ(0u, robot.m_testExitCount);
 
+  frc::sim::DriverStationSim::SetEnabled(false);
+  frc::sim::DriverStationSim::SetAutonomous(false);
+  frc::sim::DriverStationSim::SetTest(false);
+  frc::sim::DriverStationSim::NotifyNewData();
+  frc::sim::StepTiming(20_ms);  // Wait for Notifiers
+
+  EXPECT_EQ(1u, robot.m_robotInitCount);
+  EXPECT_EQ(1u, robot.m_simulationInitCount);
+  EXPECT_EQ(1u, robot.m_disabledInitCount);
+  EXPECT_EQ(0u, robot.m_autonomousInitCount);
+  EXPECT_EQ(0u, robot.m_teleopInitCount);
+  EXPECT_EQ(1u, robot.m_testInitCount);
+  EXPECT_FALSE(frc::LiveWindow::IsEnabled());
+
+  EXPECT_EQ(3u, robot.m_robotPeriodicCount);
+  EXPECT_EQ(3u, robot.m_simulationPeriodicCount);
+  EXPECT_EQ(1u, robot.m_disabledPeriodicCount);
+  EXPECT_EQ(0u, robot.m_autonomousPeriodicCount);
+  EXPECT_EQ(0u, robot.m_teleopPeriodicCount);
+  EXPECT_EQ(2u, robot.m_testPeriodicCount);
+
+  EXPECT_EQ(0u, robot.m_disabledExitCount);
+  EXPECT_EQ(0u, robot.m_autonomousExitCount);
+  EXPECT_EQ(0u, robot.m_teleopExitCount);
+  EXPECT_EQ(1u, robot.m_testExitCount);
+
   robot.EndCompetition();
   robotThread.join();
 }
@@ -418,6 +452,7 @@
   frc::sim::DriverStationSim::SetEnabled(true);
   frc::sim::DriverStationSim::SetAutonomous(true);
   frc::sim::DriverStationSim::SetTest(false);
+  frc::sim::DriverStationSim::NotifyNewData();
 
   frc::sim::StepTiming(20_ms);
 
@@ -435,6 +470,7 @@
   frc::sim::DriverStationSim::SetEnabled(true);
   frc::sim::DriverStationSim::SetAutonomous(false);
   frc::sim::DriverStationSim::SetTest(false);
+  frc::sim::DriverStationSim::NotifyNewData();
 
   frc::sim::StepTiming(20_ms);
 
@@ -452,6 +488,7 @@
   frc::sim::DriverStationSim::SetEnabled(true);
   frc::sim::DriverStationSim::SetAutonomous(false);
   frc::sim::DriverStationSim::SetTest(true);
+  frc::sim::DriverStationSim::NotifyNewData();
 
   frc::sim::StepTiming(20_ms);
 
@@ -469,6 +506,7 @@
   frc::sim::DriverStationSim::SetEnabled(false);
   frc::sim::DriverStationSim::SetAutonomous(false);
   frc::sim::DriverStationSim::SetTest(false);
+  frc::sim::DriverStationSim::NotifyNewData();
 
   frc::sim::StepTiming(20_ms);
 
@@ -568,3 +606,5 @@
   robot.EndCompetition();
   robotThread.join();
 }
+
+INSTANTIATE_TEST_SUITE_P(TimedRobotTests, TimedRobotTest, testing::Bool());
diff --git a/third_party/allwpilib/wpilibc/src/test/native/cpp/UnitNetworkTablesTest.cpp b/third_party/allwpilib/wpilibc/src/test/native/cpp/UnitNetworkTablesTest.cpp
new file mode 100644
index 0000000..505f906
--- /dev/null
+++ b/third_party/allwpilib/wpilibc/src/test/native/cpp/UnitNetworkTablesTest.cpp
@@ -0,0 +1,45 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <networktables/DoubleTopic.h>
+#include <networktables/NetworkTableInstance.h>
+#include <networktables/UnitTopic.h>
+#include <units/length.h>
+
+#include "gtest/gtest.h"
+
+class UnitNetworkTablesTest : public ::testing::Test {
+ public:
+  UnitNetworkTablesTest() : inst{nt::NetworkTableInstance::Create()} {}
+  ~UnitNetworkTablesTest() override { nt::NetworkTableInstance::Destroy(inst); }
+  nt::NetworkTableInstance inst;
+};
+
+TEST_F(UnitNetworkTablesTest, Publish) {
+  auto topic = nt::UnitTopic<units::meter_t>{inst.GetTopic("meterTest")};
+  auto pub = topic.Publish();
+  pub.Set(2_m);
+  ASSERT_EQ(topic.GetProperty("unit"), "meter");
+  ASSERT_TRUE(topic.IsMatchingUnit());
+}
+
+TEST_F(UnitNetworkTablesTest, SubscribeDouble) {
+  auto topic = nt::UnitTopic<units::meter_t>{inst.GetTopic("meterTest")};
+  auto pub = topic.Publish();
+  auto sub = inst.GetDoubleTopic("meterTest").Subscribe(0);
+  ASSERT_EQ(sub.Get(), 0);
+  ASSERT_EQ(sub.Get(3), 3);
+  pub.Set(2_m);
+  ASSERT_EQ(sub.Get(), 2);
+}
+
+TEST_F(UnitNetworkTablesTest, SubscribeUnit) {
+  auto topic = nt::UnitTopic<units::meter_t>{inst.GetTopic("meterTest")};
+  auto pub = topic.Publish();
+  auto sub = topic.Subscribe(0_m);
+  ASSERT_EQ(sub.Get(), 0_m);
+  ASSERT_EQ(sub.Get(3_m), 3_m);
+  pub.Set(2_m);
+  ASSERT_EQ(sub.Get(), 2_m);
+}
diff --git a/third_party/allwpilib/wpilibc/src/test/native/cpp/drive/DifferentialDriveTest.cpp b/third_party/allwpilib/wpilibc/src/test/native/cpp/drive/DifferentialDriveTest.cpp
index b930346..1f542be 100644
--- a/third_party/allwpilib/wpilibc/src/test/native/cpp/drive/DifferentialDriveTest.cpp
+++ b/third_party/allwpilib/wpilibc/src/test/native/cpp/drive/DifferentialDriveTest.cpp
@@ -2,9 +2,9 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
-#include "MockMotorController.h"
 #include "frc/drive/DifferentialDrive.h"
 #include "gtest/gtest.h"
+#include "motorcontrol/MockMotorController.h"
 
 TEST(DifferentialDriveTest, ArcadeDriveIK) {
   // Forward
@@ -13,12 +13,12 @@
   EXPECT_DOUBLE_EQ(1.0, speeds.right);
 
   // Forward left turn
-  speeds = frc::DifferentialDrive::ArcadeDriveIK(0.5, -0.5, false);
+  speeds = frc::DifferentialDrive::ArcadeDriveIK(0.5, 0.5, false);
   EXPECT_DOUBLE_EQ(0.0, speeds.left);
   EXPECT_DOUBLE_EQ(0.5, speeds.right);
 
   // Forward right turn
-  speeds = frc::DifferentialDrive::ArcadeDriveIK(0.5, 0.5, false);
+  speeds = frc::DifferentialDrive::ArcadeDriveIK(0.5, -0.5, false);
   EXPECT_DOUBLE_EQ(0.5, speeds.left);
   EXPECT_DOUBLE_EQ(0.0, speeds.right);
 
@@ -28,32 +28,32 @@
   EXPECT_DOUBLE_EQ(-1.0, speeds.right);
 
   // Backward left turn
-  speeds = frc::DifferentialDrive::ArcadeDriveIK(-0.5, -0.5, false);
+  speeds = frc::DifferentialDrive::ArcadeDriveIK(-0.5, 0.5, false);
   EXPECT_DOUBLE_EQ(-0.5, speeds.left);
   EXPECT_DOUBLE_EQ(0.0, speeds.right);
 
   // Backward right turn
-  speeds = frc::DifferentialDrive::ArcadeDriveIK(-0.5, 0.5, false);
+  speeds = frc::DifferentialDrive::ArcadeDriveIK(-0.5, -0.5, false);
   EXPECT_DOUBLE_EQ(0.0, speeds.left);
   EXPECT_DOUBLE_EQ(-0.5, speeds.right);
 
   // Left turn (xSpeed with negative sign)
-  speeds = frc::DifferentialDrive::ArcadeDriveIK(-0.0, -1.0, false);
+  speeds = frc::DifferentialDrive::ArcadeDriveIK(-0.0, 1.0, false);
   EXPECT_DOUBLE_EQ(-1.0, speeds.left);
   EXPECT_DOUBLE_EQ(1.0, speeds.right);
 
   // Left turn (xSpeed with positive sign)
-  speeds = frc::DifferentialDrive::ArcadeDriveIK(0.0, -1.0, false);
+  speeds = frc::DifferentialDrive::ArcadeDriveIK(0.0, 1.0, false);
   EXPECT_DOUBLE_EQ(-1.0, speeds.left);
   EXPECT_DOUBLE_EQ(1.0, speeds.right);
 
   // Right turn (xSpeed with negative sign)
-  speeds = frc::DifferentialDrive::ArcadeDriveIK(-0.0, 1.0, false);
+  speeds = frc::DifferentialDrive::ArcadeDriveIK(-0.0, -1.0, false);
   EXPECT_DOUBLE_EQ(1.0, speeds.left);
   EXPECT_DOUBLE_EQ(-1.0, speeds.right);
 
   // Right turn (xSpeed with positive sign)
-  speeds = frc::DifferentialDrive::ArcadeDriveIK(0.0, 1.0, false);
+  speeds = frc::DifferentialDrive::ArcadeDriveIK(0.0, -1.0, false);
   EXPECT_DOUBLE_EQ(1.0, speeds.left);
   EXPECT_DOUBLE_EQ(-1.0, speeds.right);
 }
@@ -65,12 +65,12 @@
   EXPECT_DOUBLE_EQ(1.0, speeds.right);
 
   // Forward left turn
-  speeds = frc::DifferentialDrive::ArcadeDriveIK(0.5, -0.5, true);
+  speeds = frc::DifferentialDrive::ArcadeDriveIK(0.5, 0.5, true);
   EXPECT_DOUBLE_EQ(0.0, speeds.left);
   EXPECT_DOUBLE_EQ(0.25, speeds.right);
 
   // Forward right turn
-  speeds = frc::DifferentialDrive::ArcadeDriveIK(0.5, 0.5, true);
+  speeds = frc::DifferentialDrive::ArcadeDriveIK(0.5, -0.5, true);
   EXPECT_DOUBLE_EQ(0.25, speeds.left);
   EXPECT_DOUBLE_EQ(0.0, speeds.right);
 
@@ -80,32 +80,32 @@
   EXPECT_DOUBLE_EQ(-1.0, speeds.right);
 
   // Backward left turn
-  speeds = frc::DifferentialDrive::ArcadeDriveIK(-0.5, -0.5, true);
+  speeds = frc::DifferentialDrive::ArcadeDriveIK(-0.5, 0.5, true);
   EXPECT_DOUBLE_EQ(-0.25, speeds.left);
   EXPECT_DOUBLE_EQ(0.0, speeds.right);
 
   // Backward right turn
-  speeds = frc::DifferentialDrive::ArcadeDriveIK(-0.5, 0.5, true);
+  speeds = frc::DifferentialDrive::ArcadeDriveIK(-0.5, -0.5, true);
   EXPECT_DOUBLE_EQ(0.0, speeds.left);
   EXPECT_DOUBLE_EQ(-0.25, speeds.right);
 
   // Left turn (xSpeed with negative sign)
-  speeds = frc::DifferentialDrive::ArcadeDriveIK(-0.0, -1.0, false);
+  speeds = frc::DifferentialDrive::ArcadeDriveIK(-0.0, 1.0, false);
   EXPECT_DOUBLE_EQ(-1.0, speeds.left);
   EXPECT_DOUBLE_EQ(1.0, speeds.right);
 
   // Left turn (xSpeed with positive sign)
-  speeds = frc::DifferentialDrive::ArcadeDriveIK(0.0, -1.0, false);
+  speeds = frc::DifferentialDrive::ArcadeDriveIK(0.0, 1.0, false);
   EXPECT_DOUBLE_EQ(-1.0, speeds.left);
   EXPECT_DOUBLE_EQ(1.0, speeds.right);
 
   // Right turn (xSpeed with negative sign)
-  speeds = frc::DifferentialDrive::ArcadeDriveIK(-0.0, 1.0, false);
+  speeds = frc::DifferentialDrive::ArcadeDriveIK(-0.0, -1.0, false);
   EXPECT_DOUBLE_EQ(1.0, speeds.left);
   EXPECT_DOUBLE_EQ(-1.0, speeds.right);
 
   // Right turn (xSpeed with positive sign)
-  speeds = frc::DifferentialDrive::ArcadeDriveIK(0.0, 1.0, false);
+  speeds = frc::DifferentialDrive::ArcadeDriveIK(0.0, -1.0, false);
   EXPECT_DOUBLE_EQ(1.0, speeds.left);
   EXPECT_DOUBLE_EQ(-1.0, speeds.right);
 }
@@ -117,12 +117,12 @@
   EXPECT_DOUBLE_EQ(1.0, speeds.right);
 
   // Forward left turn
-  speeds = frc::DifferentialDrive::CurvatureDriveIK(0.5, -0.5, false);
+  speeds = frc::DifferentialDrive::CurvatureDriveIK(0.5, 0.5, false);
   EXPECT_DOUBLE_EQ(0.25, speeds.left);
   EXPECT_DOUBLE_EQ(0.75, speeds.right);
 
   // Forward right turn
-  speeds = frc::DifferentialDrive::CurvatureDriveIK(0.5, 0.5, false);
+  speeds = frc::DifferentialDrive::CurvatureDriveIK(0.5, -0.5, false);
   EXPECT_DOUBLE_EQ(0.75, speeds.left);
   EXPECT_DOUBLE_EQ(0.25, speeds.right);
 
@@ -132,12 +132,12 @@
   EXPECT_DOUBLE_EQ(-1.0, speeds.right);
 
   // Backward left turn
-  speeds = frc::DifferentialDrive::CurvatureDriveIK(-0.5, -0.5, false);
+  speeds = frc::DifferentialDrive::CurvatureDriveIK(-0.5, 0.5, false);
   EXPECT_DOUBLE_EQ(-0.75, speeds.left);
   EXPECT_DOUBLE_EQ(-0.25, speeds.right);
 
   // Backward right turn
-  speeds = frc::DifferentialDrive::CurvatureDriveIK(-0.5, 0.5, false);
+  speeds = frc::DifferentialDrive::CurvatureDriveIK(-0.5, -0.5, false);
   EXPECT_DOUBLE_EQ(-0.25, speeds.left);
   EXPECT_DOUBLE_EQ(-0.75, speeds.right);
 }
@@ -149,12 +149,12 @@
   EXPECT_DOUBLE_EQ(1.0, speeds.right);
 
   // Forward left turn
-  speeds = frc::DifferentialDrive::CurvatureDriveIK(0.5, -0.5, true);
+  speeds = frc::DifferentialDrive::CurvatureDriveIK(0.5, 0.5, true);
   EXPECT_DOUBLE_EQ(0.0, speeds.left);
   EXPECT_DOUBLE_EQ(1.0, speeds.right);
 
   // Forward right turn
-  speeds = frc::DifferentialDrive::CurvatureDriveIK(0.5, 0.5, true);
+  speeds = frc::DifferentialDrive::CurvatureDriveIK(0.5, -0.5, true);
   EXPECT_DOUBLE_EQ(1.0, speeds.left);
   EXPECT_DOUBLE_EQ(0.0, speeds.right);
 
@@ -164,12 +164,12 @@
   EXPECT_DOUBLE_EQ(-1.0, speeds.right);
 
   // Backward left turn
-  speeds = frc::DifferentialDrive::CurvatureDriveIK(-0.5, -0.5, true);
+  speeds = frc::DifferentialDrive::CurvatureDriveIK(-0.5, 0.5, true);
   EXPECT_DOUBLE_EQ(-1.0, speeds.left);
   EXPECT_DOUBLE_EQ(0.0, speeds.right);
 
   // Backward right turn
-  speeds = frc::DifferentialDrive::CurvatureDriveIK(-0.5, 0.5, true);
+  speeds = frc::DifferentialDrive::CurvatureDriveIK(-0.5, -0.5, true);
   EXPECT_DOUBLE_EQ(0.0, speeds.left);
   EXPECT_DOUBLE_EQ(-1.0, speeds.right);
 }
@@ -250,12 +250,12 @@
   EXPECT_DOUBLE_EQ(1.0, right.Get());
 
   // Forward left turn
-  drive.ArcadeDrive(0.5, -0.5, false);
+  drive.ArcadeDrive(0.5, 0.5, false);
   EXPECT_DOUBLE_EQ(0.0, left.Get());
   EXPECT_DOUBLE_EQ(0.5, right.Get());
 
   // Forward right turn
-  drive.ArcadeDrive(0.5, 0.5, false);
+  drive.ArcadeDrive(0.5, -0.5, false);
   EXPECT_DOUBLE_EQ(0.5, left.Get());
   EXPECT_DOUBLE_EQ(0.0, right.Get());
 
@@ -265,12 +265,12 @@
   EXPECT_DOUBLE_EQ(-1.0, right.Get());
 
   // Backward left turn
-  drive.ArcadeDrive(-0.5, -0.5, false);
+  drive.ArcadeDrive(-0.5, 0.5, false);
   EXPECT_DOUBLE_EQ(-0.5, left.Get());
   EXPECT_DOUBLE_EQ(0.0, right.Get());
 
   // Backward right turn
-  drive.ArcadeDrive(-0.5, 0.5, false);
+  drive.ArcadeDrive(-0.5, -0.5, false);
   EXPECT_DOUBLE_EQ(0.0, left.Get());
   EXPECT_DOUBLE_EQ(-0.5, right.Get());
 }
@@ -287,12 +287,12 @@
   EXPECT_DOUBLE_EQ(1.0, right.Get());
 
   // Forward left turn
-  drive.ArcadeDrive(0.5, -0.5, true);
+  drive.ArcadeDrive(0.5, 0.5, true);
   EXPECT_DOUBLE_EQ(0.0, left.Get());
   EXPECT_DOUBLE_EQ(0.25, right.Get());
 
   // Forward right turn
-  drive.ArcadeDrive(0.5, 0.5, true);
+  drive.ArcadeDrive(0.5, -0.5, true);
   EXPECT_DOUBLE_EQ(0.25, left.Get());
   EXPECT_DOUBLE_EQ(0.0, right.Get());
 
@@ -302,12 +302,12 @@
   EXPECT_DOUBLE_EQ(-1.0, right.Get());
 
   // Backward left turn
-  drive.ArcadeDrive(-0.5, -0.5, true);
+  drive.ArcadeDrive(-0.5, 0.5, true);
   EXPECT_DOUBLE_EQ(-0.25, left.Get());
   EXPECT_DOUBLE_EQ(0.0, right.Get());
 
   // Backward right turn
-  drive.ArcadeDrive(-0.5, 0.5, true);
+  drive.ArcadeDrive(-0.5, -0.5, true);
   EXPECT_DOUBLE_EQ(0.0, left.Get());
   EXPECT_DOUBLE_EQ(-0.25, right.Get());
 }
@@ -324,12 +324,12 @@
   EXPECT_DOUBLE_EQ(1.0, right.Get());
 
   // Forward left turn
-  drive.CurvatureDrive(0.5, -0.5, false);
+  drive.CurvatureDrive(0.5, 0.5, false);
   EXPECT_DOUBLE_EQ(0.25, left.Get());
   EXPECT_DOUBLE_EQ(0.75, right.Get());
 
   // Forward right turn
-  drive.CurvatureDrive(0.5, 0.5, false);
+  drive.CurvatureDrive(0.5, -0.5, false);
   EXPECT_DOUBLE_EQ(0.75, left.Get());
   EXPECT_DOUBLE_EQ(0.25, right.Get());
 
@@ -339,12 +339,12 @@
   EXPECT_DOUBLE_EQ(-1.0, right.Get());
 
   // Backward left turn
-  drive.CurvatureDrive(-0.5, -0.5, false);
+  drive.CurvatureDrive(-0.5, 0.5, false);
   EXPECT_DOUBLE_EQ(-0.75, left.Get());
   EXPECT_DOUBLE_EQ(-0.25, right.Get());
 
   // Backward right turn
-  drive.CurvatureDrive(-0.5, 0.5, false);
+  drive.CurvatureDrive(-0.5, -0.5, false);
   EXPECT_DOUBLE_EQ(-0.25, left.Get());
   EXPECT_DOUBLE_EQ(-0.75, right.Get());
 }
@@ -361,12 +361,12 @@
   EXPECT_DOUBLE_EQ(1.0, right.Get());
 
   // Forward left turn
-  drive.CurvatureDrive(0.5, -0.5, true);
+  drive.CurvatureDrive(0.5, 0.5, true);
   EXPECT_DOUBLE_EQ(0.0, left.Get());
   EXPECT_DOUBLE_EQ(1.0, right.Get());
 
   // Forward right turn
-  drive.CurvatureDrive(0.5, 0.5, true);
+  drive.CurvatureDrive(0.5, -0.5, true);
   EXPECT_DOUBLE_EQ(1.0, left.Get());
   EXPECT_DOUBLE_EQ(0.0, right.Get());
 
@@ -376,12 +376,12 @@
   EXPECT_DOUBLE_EQ(-1.0, right.Get());
 
   // Backward left turn
-  drive.CurvatureDrive(-0.5, -0.5, true);
+  drive.CurvatureDrive(-0.5, 0.5, true);
   EXPECT_DOUBLE_EQ(-1.0, left.Get());
   EXPECT_DOUBLE_EQ(0.0, right.Get());
 
   // Backward right turn
-  drive.CurvatureDrive(-0.5, 0.5, true);
+  drive.CurvatureDrive(-0.5, -0.5, true);
   EXPECT_DOUBLE_EQ(0.0, left.Get());
   EXPECT_DOUBLE_EQ(-1.0, right.Get());
 }
diff --git a/third_party/allwpilib/wpilibc/src/test/native/cpp/drive/KilloughDriveTest.cpp b/third_party/allwpilib/wpilibc/src/test/native/cpp/drive/KilloughDriveTest.cpp
deleted file mode 100644
index c23c7b0..0000000
--- a/third_party/allwpilib/wpilibc/src/test/native/cpp/drive/KilloughDriveTest.cpp
+++ /dev/null
@@ -1,197 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include <cmath>
-
-#include "MockMotorController.h"
-#include "frc/drive/KilloughDrive.h"
-#include "gtest/gtest.h"
-
-TEST(KilloughDriveTest, CartesianIK) {
-  frc::MockMotorController left;
-  frc::MockMotorController right;
-  frc::MockMotorController back;
-  frc::KilloughDrive drive{left, right, back};
-
-  // Forward
-  auto speeds = drive.DriveCartesianIK(1.0, 0.0, 0.0);
-  EXPECT_DOUBLE_EQ(0.5, speeds.left);
-  EXPECT_DOUBLE_EQ(-0.5, speeds.right);
-  EXPECT_NEAR(0.0, speeds.back, 1e-9);
-
-  // Left
-  speeds = drive.DriveCartesianIK(0.0, -1.0, 0.0);
-  EXPECT_DOUBLE_EQ(-std::sqrt(3) / 2, speeds.left);
-  EXPECT_DOUBLE_EQ(-std::sqrt(3) / 2, speeds.right);
-  EXPECT_DOUBLE_EQ(1.0, speeds.back);
-
-  // Right
-  speeds = drive.DriveCartesianIK(0.0, 1.0, 0.0);
-  EXPECT_DOUBLE_EQ(std::sqrt(3) / 2, speeds.left);
-  EXPECT_DOUBLE_EQ(std::sqrt(3) / 2, speeds.right);
-  EXPECT_DOUBLE_EQ(-1.0, speeds.back);
-
-  // Rotate CCW
-  speeds = drive.DriveCartesianIK(0.0, 0.0, -1.0);
-  EXPECT_DOUBLE_EQ(-1.0, speeds.left);
-  EXPECT_DOUBLE_EQ(-1.0, speeds.right);
-  EXPECT_DOUBLE_EQ(-1.0, speeds.back);
-
-  // Rotate CW
-  speeds = drive.DriveCartesianIK(0.0, 0.0, 1.0);
-  EXPECT_DOUBLE_EQ(1.0, speeds.left);
-  EXPECT_DOUBLE_EQ(1.0, speeds.right);
-  EXPECT_DOUBLE_EQ(1.0, speeds.back);
-}
-
-TEST(KilloughDriveTest, CartesianIKGyro90CW) {
-  frc::MockMotorController left;
-  frc::MockMotorController right;
-  frc::MockMotorController back;
-  frc::KilloughDrive drive{left, right, back};
-
-  // Forward in global frame; left in robot frame
-  auto speeds = drive.DriveCartesianIK(1.0, 0.0, 0.0, 90.0);
-  EXPECT_DOUBLE_EQ(-std::sqrt(3) / 2, speeds.left);
-  EXPECT_DOUBLE_EQ(-std::sqrt(3) / 2, speeds.right);
-  EXPECT_DOUBLE_EQ(1.0, speeds.back);
-
-  // Left in global frame; backward in robot frame
-  speeds = drive.DriveCartesianIK(0.0, -1.0, 0.0, 90.0);
-  EXPECT_DOUBLE_EQ(-0.5, speeds.left);
-  EXPECT_NEAR(0.5, speeds.right, 1e-9);
-  EXPECT_NEAR(0.0, speeds.back, 1e-9);
-
-  // Right in global frame; forward in robot frame
-  speeds = drive.DriveCartesianIK(0.0, 1.0, 0.0, 90.0);
-  EXPECT_DOUBLE_EQ(0.5, speeds.left);
-  EXPECT_NEAR(-0.5, speeds.right, 1e-9);
-  EXPECT_NEAR(0.0, speeds.back, 1e-9);
-
-  // Rotate CCW
-  speeds = drive.DriveCartesianIK(0.0, 0.0, -1.0, 90.0);
-  EXPECT_DOUBLE_EQ(-1.0, speeds.left);
-  EXPECT_DOUBLE_EQ(-1.0, speeds.right);
-  EXPECT_DOUBLE_EQ(-1.0, speeds.back);
-
-  // Rotate CW
-  speeds = drive.DriveCartesianIK(0.0, 0.0, 1.0, 90.0);
-  EXPECT_DOUBLE_EQ(1.0, speeds.left);
-  EXPECT_DOUBLE_EQ(1.0, speeds.right);
-  EXPECT_DOUBLE_EQ(1.0, speeds.back);
-}
-
-TEST(KilloughDriveTest, Cartesian) {
-  frc::MockMotorController left;
-  frc::MockMotorController right;
-  frc::MockMotorController back;
-  frc::KilloughDrive drive{left, right, back};
-  drive.SetDeadband(0.0);
-
-  // Forward
-  drive.DriveCartesian(1.0, 0.0, 0.0);
-  EXPECT_DOUBLE_EQ(0.5, left.Get());
-  EXPECT_DOUBLE_EQ(-0.5, right.Get());
-  EXPECT_NEAR(0.0, back.Get(), 1e-9);
-
-  // Left
-  drive.DriveCartesian(0.0, -1.0, 0.0);
-  EXPECT_DOUBLE_EQ(-std::sqrt(3) / 2, left.Get());
-  EXPECT_DOUBLE_EQ(-std::sqrt(3) / 2, right.Get());
-  EXPECT_DOUBLE_EQ(1.0, back.Get());
-
-  // Right
-  drive.DriveCartesian(0.0, 1.0, 0.0);
-  EXPECT_DOUBLE_EQ(std::sqrt(3) / 2, left.Get());
-  EXPECT_DOUBLE_EQ(std::sqrt(3) / 2, right.Get());
-  EXPECT_DOUBLE_EQ(-1.0, back.Get());
-
-  // Rotate CCW
-  drive.DriveCartesian(0.0, 0.0, -1.0);
-  EXPECT_DOUBLE_EQ(-1.0, left.Get());
-  EXPECT_DOUBLE_EQ(-1.0, right.Get());
-  EXPECT_DOUBLE_EQ(-1.0, back.Get());
-
-  // Rotate CW
-  drive.DriveCartesian(0.0, 0.0, 1.0);
-  EXPECT_DOUBLE_EQ(1.0, left.Get());
-  EXPECT_DOUBLE_EQ(1.0, right.Get());
-  EXPECT_DOUBLE_EQ(1.0, back.Get());
-}
-
-TEST(KilloughDriveTest, CartesianGyro90CW) {
-  frc::MockMotorController left;
-  frc::MockMotorController right;
-  frc::MockMotorController back;
-  frc::KilloughDrive drive{left, right, back};
-  drive.SetDeadband(0.0);
-
-  // Forward in global frame; left in robot frame
-  drive.DriveCartesian(1.0, 0.0, 0.0, 90.0);
-  EXPECT_DOUBLE_EQ(-std::sqrt(3) / 2, left.Get());
-  EXPECT_DOUBLE_EQ(-std::sqrt(3) / 2, right.Get());
-  EXPECT_DOUBLE_EQ(1.0, back.Get());
-
-  // Left in global frame; backward in robot frame
-  drive.DriveCartesian(0.0, -1.0, 0.0, 90.0);
-  EXPECT_DOUBLE_EQ(-0.5, left.Get());
-  EXPECT_NEAR(0.5, right.Get(), 1e-9);
-  EXPECT_NEAR(0.0, back.Get(), 1e-9);
-
-  // Right in global frame; forward in robot frame
-  drive.DriveCartesian(0.0, 1.0, 0.0, 90.0);
-  EXPECT_DOUBLE_EQ(0.5, left.Get());
-  EXPECT_NEAR(-0.5, right.Get(), 1e-9);
-  EXPECT_NEAR(0.0, back.Get(), 1e-9);
-
-  // Rotate CCW
-  drive.DriveCartesian(0.0, 0.0, -1.0, 90.0);
-  EXPECT_DOUBLE_EQ(-1.0, left.Get());
-  EXPECT_DOUBLE_EQ(-1.0, right.Get());
-  EXPECT_DOUBLE_EQ(-1.0, back.Get());
-
-  // Rotate CW
-  drive.DriveCartesian(0.0, 0.0, 1.0, 90.0);
-  EXPECT_DOUBLE_EQ(1.0, left.Get());
-  EXPECT_DOUBLE_EQ(1.0, right.Get());
-  EXPECT_DOUBLE_EQ(1.0, back.Get());
-}
-
-TEST(KilloughDriveTest, Polar) {
-  frc::MockMotorController left;
-  frc::MockMotorController right;
-  frc::MockMotorController back;
-  frc::KilloughDrive drive{left, right, back};
-  drive.SetDeadband(0.0);
-
-  // Forward
-  drive.DrivePolar(1.0, 0.0, 0.0);
-  EXPECT_DOUBLE_EQ(std::sqrt(3) / 2, left.Get());
-  EXPECT_DOUBLE_EQ(std::sqrt(3) / 2, right.Get());
-  EXPECT_DOUBLE_EQ(-1.0, back.Get());
-
-  // Left
-  drive.DrivePolar(1.0, -90.0, 0.0);
-  EXPECT_DOUBLE_EQ(-0.5, left.Get());
-  EXPECT_DOUBLE_EQ(0.5, right.Get());
-  EXPECT_NEAR(0.0, back.Get(), 1e-9);
-
-  // Right
-  drive.DrivePolar(1.0, 90.0, 0.0);
-  EXPECT_DOUBLE_EQ(0.5, left.Get());
-  EXPECT_NEAR(-0.5, right.Get(), 1e-9);
-  EXPECT_NEAR(0.0, back.Get(), 1e-9);
-
-  // Rotate CCW
-  drive.DrivePolar(0.0, 0.0, -1.0);
-  EXPECT_DOUBLE_EQ(-1.0, left.Get());
-  EXPECT_DOUBLE_EQ(-1.0, right.Get());
-  EXPECT_DOUBLE_EQ(-1.0, back.Get());
-
-  // Rotate CW
-  drive.DrivePolar(0.0, 0.0, 1.0);
-  EXPECT_DOUBLE_EQ(1.0, left.Get());
-  EXPECT_DOUBLE_EQ(1.0, right.Get());
-  EXPECT_DOUBLE_EQ(1.0, back.Get());
-}
diff --git a/third_party/allwpilib/wpilibc/src/test/native/cpp/drive/MecanumDriveTest.cpp b/third_party/allwpilib/wpilibc/src/test/native/cpp/drive/MecanumDriveTest.cpp
index 2990848..de55462 100644
--- a/third_party/allwpilib/wpilibc/src/test/native/cpp/drive/MecanumDriveTest.cpp
+++ b/third_party/allwpilib/wpilibc/src/test/native/cpp/drive/MecanumDriveTest.cpp
@@ -2,9 +2,9 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
-#include "MockMotorController.h"
 #include "frc/drive/MecanumDrive.h"
 #include "gtest/gtest.h"
+#include "motorcontrol/MockMotorController.h"
 
 TEST(MecanumDriveTest, CartesianIK) {
   // Forward
@@ -45,35 +45,35 @@
 
 TEST(MecanumDriveTest, CartesianIKGyro90CW) {
   // Forward in global frame; left in robot frame
-  auto speeds = frc::MecanumDrive::DriveCartesianIK(1.0, 0.0, 0.0, 90.0);
+  auto speeds = frc::MecanumDrive::DriveCartesianIK(1.0, 0.0, 0.0, 90_deg);
   EXPECT_DOUBLE_EQ(-1.0, speeds.frontLeft);
   EXPECT_DOUBLE_EQ(1.0, speeds.frontRight);
   EXPECT_DOUBLE_EQ(1.0, speeds.rearLeft);
   EXPECT_DOUBLE_EQ(-1.0, speeds.rearRight);
 
   // Left in global frame; backward in robot frame
-  speeds = frc::MecanumDrive::DriveCartesianIK(0.0, -1.0, 0.0, 90.0);
+  speeds = frc::MecanumDrive::DriveCartesianIK(0.0, -1.0, 0.0, 90_deg);
   EXPECT_DOUBLE_EQ(-1.0, speeds.frontLeft);
   EXPECT_DOUBLE_EQ(-1.0, speeds.frontRight);
   EXPECT_DOUBLE_EQ(-1.0, speeds.rearLeft);
   EXPECT_DOUBLE_EQ(-1.0, speeds.rearRight);
 
   // Right in global frame; forward in robot frame
-  speeds = frc::MecanumDrive::DriveCartesianIK(0.0, 1.0, 0.0, 90.0);
+  speeds = frc::MecanumDrive::DriveCartesianIK(0.0, 1.0, 0.0, 90_deg);
   EXPECT_DOUBLE_EQ(1.0, speeds.frontLeft);
   EXPECT_DOUBLE_EQ(1.0, speeds.frontRight);
   EXPECT_DOUBLE_EQ(1.0, speeds.rearLeft);
   EXPECT_DOUBLE_EQ(1.0, speeds.rearRight);
 
   // Rotate CCW
-  speeds = frc::MecanumDrive::DriveCartesianIK(0.0, 0.0, -1.0, 90.0);
+  speeds = frc::MecanumDrive::DriveCartesianIK(0.0, 0.0, -1.0, 90_deg);
   EXPECT_DOUBLE_EQ(-1.0, speeds.frontLeft);
   EXPECT_DOUBLE_EQ(1.0, speeds.frontRight);
   EXPECT_DOUBLE_EQ(-1.0, speeds.rearLeft);
   EXPECT_DOUBLE_EQ(1.0, speeds.rearRight);
 
   // Rotate CW
-  speeds = frc::MecanumDrive::DriveCartesianIK(0.0, 0.0, 1.0, 90.0);
+  speeds = frc::MecanumDrive::DriveCartesianIK(0.0, 0.0, 1.0, 90_deg);
   EXPECT_DOUBLE_EQ(1.0, speeds.frontLeft);
   EXPECT_DOUBLE_EQ(-1.0, speeds.frontRight);
   EXPECT_DOUBLE_EQ(1.0, speeds.rearLeft);
@@ -133,35 +133,35 @@
   drive.SetDeadband(0.0);
 
   // Forward in global frame; left in robot frame
-  drive.DriveCartesian(1.0, 0.0, 0.0, 90.0);
+  drive.DriveCartesian(1.0, 0.0, 0.0, 90_deg);
   EXPECT_DOUBLE_EQ(-1.0, fl.Get());
   EXPECT_DOUBLE_EQ(1.0, fr.Get());
   EXPECT_DOUBLE_EQ(1.0, rl.Get());
   EXPECT_DOUBLE_EQ(-1.0, rr.Get());
 
   // Left in global frame; backward in robot frame
-  drive.DriveCartesian(0.0, -1.0, 0.0, 90.0);
+  drive.DriveCartesian(0.0, -1.0, 0.0, 90_deg);
   EXPECT_DOUBLE_EQ(-1.0, fl.Get());
   EXPECT_DOUBLE_EQ(-1.0, fr.Get());
   EXPECT_DOUBLE_EQ(-1.0, rl.Get());
   EXPECT_DOUBLE_EQ(-1.0, rr.Get());
 
   // Right in global frame; forward in robot frame
-  drive.DriveCartesian(0.0, 1.0, 0.0, 90.0);
+  drive.DriveCartesian(0.0, 1.0, 0.0, 90_deg);
   EXPECT_DOUBLE_EQ(1.0, fl.Get());
   EXPECT_DOUBLE_EQ(1.0, fr.Get());
   EXPECT_DOUBLE_EQ(1.0, rl.Get());
   EXPECT_DOUBLE_EQ(1.0, rr.Get());
 
   // Rotate CCW
-  drive.DriveCartesian(0.0, 0.0, -1.0, 90.0);
+  drive.DriveCartesian(0.0, 0.0, -1.0, 90_deg);
   EXPECT_DOUBLE_EQ(-1.0, fl.Get());
   EXPECT_DOUBLE_EQ(1.0, fr.Get());
   EXPECT_DOUBLE_EQ(-1.0, rl.Get());
   EXPECT_DOUBLE_EQ(1.0, rr.Get());
 
   // Rotate CW
-  drive.DriveCartesian(0.0, 0.0, 1.0, 90.0);
+  drive.DriveCartesian(0.0, 0.0, 1.0, 90_deg);
   EXPECT_DOUBLE_EQ(1.0, fl.Get());
   EXPECT_DOUBLE_EQ(-1.0, fr.Get());
   EXPECT_DOUBLE_EQ(1.0, rl.Get());
@@ -177,35 +177,35 @@
   drive.SetDeadband(0.0);
 
   // Forward
-  drive.DrivePolar(1.0, 0.0, 0.0);
+  drive.DrivePolar(1.0, 0_deg, 0.0);
   EXPECT_DOUBLE_EQ(1.0, fl.Get());
   EXPECT_DOUBLE_EQ(1.0, fr.Get());
   EXPECT_DOUBLE_EQ(1.0, rl.Get());
   EXPECT_DOUBLE_EQ(1.0, rr.Get());
 
   // Left
-  drive.DrivePolar(1.0, -90.0, 0.0);
+  drive.DrivePolar(1.0, -90_deg, 0.0);
   EXPECT_DOUBLE_EQ(-1.0, fl.Get());
   EXPECT_DOUBLE_EQ(1.0, fr.Get());
   EXPECT_DOUBLE_EQ(1.0, rl.Get());
   EXPECT_DOUBLE_EQ(-1.0, rr.Get());
 
   // Right
-  drive.DrivePolar(1.0, 90.0, 0.0);
+  drive.DrivePolar(1.0, 90_deg, 0.0);
   EXPECT_DOUBLE_EQ(1.0, fl.Get());
   EXPECT_DOUBLE_EQ(-1.0, fr.Get());
   EXPECT_DOUBLE_EQ(-1.0, rl.Get());
   EXPECT_DOUBLE_EQ(1.0, rr.Get());
 
   // Rotate CCW
-  drive.DrivePolar(0.0, 0.0, -1.0);
+  drive.DrivePolar(0.0, 0_deg, -1.0);
   EXPECT_DOUBLE_EQ(-1.0, fl.Get());
   EXPECT_DOUBLE_EQ(1.0, fr.Get());
   EXPECT_DOUBLE_EQ(-1.0, rl.Get());
   EXPECT_DOUBLE_EQ(1.0, rr.Get());
 
   // Rotate CW
-  drive.DrivePolar(0.0, 0.0, 1.0);
+  drive.DrivePolar(0.0, 0_deg, 1.0);
   EXPECT_DOUBLE_EQ(1.0, fl.Get());
   EXPECT_DOUBLE_EQ(-1.0, fr.Get());
   EXPECT_DOUBLE_EQ(1.0, rl.Get());
diff --git a/third_party/allwpilib/wpilibc/src/test/native/cpp/event/NetworkBooleanEventTest.cpp b/third_party/allwpilib/wpilibc/src/test/native/cpp/event/NetworkBooleanEventTest.cpp
new file mode 100644
index 0000000..d2ac7c4
--- /dev/null
+++ b/third_party/allwpilib/wpilibc/src/test/native/cpp/event/NetworkBooleanEventTest.cpp
@@ -0,0 +1,46 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <networktables/BooleanTopic.h>
+#include <networktables/NetworkTableInstance.h>
+
+#include "frc/event/EventLoop.h"
+#include "frc/event/NetworkBooleanEvent.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+class NetworkBooleanEventTest : public ::testing::Test {
+ public:
+  NetworkBooleanEventTest() {
+    m_inst = nt::NetworkTableInstance::Create();
+    m_inst.StartLocal();
+  }
+
+  ~NetworkBooleanEventTest() override {
+    nt::NetworkTableInstance::Destroy(m_inst);
+  }
+
+  nt::NetworkTableInstance m_inst;
+};
+
+TEST_F(NetworkBooleanEventTest, Set) {
+  EventLoop loop;
+  int counter = 0;
+
+  auto pub = m_inst.GetTable("TestTable")->GetBooleanTopic("Test").Publish();
+
+  NetworkBooleanEvent(&loop, m_inst, "TestTable", "Test").IfHigh([&] {
+    ++counter;
+  });
+  pub.Set(false);
+  loop.Poll();
+  EXPECT_EQ(0, counter);
+  pub.Set(true);
+  loop.Poll();
+  EXPECT_EQ(1, counter);
+  pub.Set(false);
+  loop.Poll();
+  EXPECT_EQ(1, counter);
+}
diff --git a/third_party/allwpilib/wpilibc/src/test/native/cpp/main.cpp b/third_party/allwpilib/wpilibc/src/test/native/cpp/main.cpp
index 6aea19a..ba29975 100644
--- a/third_party/allwpilib/wpilibc/src/test/native/cpp/main.cpp
+++ b/third_party/allwpilib/wpilibc/src/test/native/cpp/main.cpp
@@ -6,9 +6,18 @@
 
 #include "gtest/gtest.h"
 
+#ifndef __FRC_ROBORIO__
+namespace frc::impl {
+void ResetMotorSafety();
+}
+#endif
+
 int main(int argc, char** argv) {
   HAL_Initialize(500, 0);
   ::testing::InitGoogleTest(&argc, argv);
   int ret = RUN_ALL_TESTS();
+#ifndef __FRC_ROBORIO__
+  frc::impl::ResetMotorSafety();
+#endif
   return ret;
 }
diff --git a/third_party/allwpilib/wpilibc/src/test/native/cpp/motorcontrol/MockMotorController.cpp b/third_party/allwpilib/wpilibc/src/test/native/cpp/motorcontrol/MockMotorController.cpp
new file mode 100644
index 0000000..e0c9ee9
--- /dev/null
+++ b/third_party/allwpilib/wpilibc/src/test/native/cpp/motorcontrol/MockMotorController.cpp
@@ -0,0 +1,31 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "motorcontrol/MockMotorController.h"
+
+using namespace frc;
+
+void MockMotorController::Set(double speed) {
+  m_speed = m_isInverted ? -speed : speed;
+}
+
+double MockMotorController::Get() const {
+  return m_speed;
+}
+
+void MockMotorController::SetInverted(bool isInverted) {
+  m_isInverted = isInverted;
+}
+
+bool MockMotorController::GetInverted() const {
+  return m_isInverted;
+}
+
+void MockMotorController::Disable() {
+  m_speed = 0;
+}
+
+void MockMotorController::StopMotor() {
+  Disable();
+}
diff --git a/third_party/allwpilib/wpilibc/src/test/native/cpp/motorcontrol/MotorControllerGroupTest.cpp b/third_party/allwpilib/wpilibc/src/test/native/cpp/motorcontrol/MotorControllerGroupTest.cpp
new file mode 100644
index 0000000..48cf700
--- /dev/null
+++ b/third_party/allwpilib/wpilibc/src/test/native/cpp/motorcontrol/MotorControllerGroupTest.cpp
@@ -0,0 +1,125 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/motorcontrol/MotorControllerGroup.h"  // NOLINT(build/include_order)
+
+#include <memory>
+#include <vector>
+
+#include "gtest/gtest.h"
+#include "motorcontrol/MockMotorController.h"
+
+using namespace frc;
+
+enum MotorControllerGroupTestType { TEST_ONE, TEST_TWO, TEST_THREE };
+
+std::ostream& operator<<(std::ostream& os,
+                         const MotorControllerGroupTestType& type) {
+  switch (type) {
+    case TEST_ONE:
+      os << "MotorControllerGroup with one motor controller";
+      break;
+    case TEST_TWO:
+      os << "MotorControllerGroup with two motor controllers";
+      break;
+    case TEST_THREE:
+      os << "MotorControllerGroup with three motor controllers";
+      break;
+  }
+
+  return os;
+}
+
+/**
+ * A fixture used for MotorControllerGroup testing.
+ */
+class MotorControllerGroupTest
+    : public testing::TestWithParam<MotorControllerGroupTestType> {
+ protected:
+  std::vector<MockMotorController> m_motorControllers;
+  std::unique_ptr<MotorControllerGroup> m_group;
+
+  void SetUp() override {
+    switch (GetParam()) {
+      case TEST_ONE: {
+        m_motorControllers.emplace_back();
+        m_group = std::make_unique<MotorControllerGroup>(m_motorControllers[0]);
+        break;
+      }
+
+      case TEST_TWO: {
+        m_motorControllers.emplace_back();
+        m_motorControllers.emplace_back();
+        m_group = std::make_unique<MotorControllerGroup>(m_motorControllers[0],
+                                                         m_motorControllers[1]);
+        break;
+      }
+
+      case TEST_THREE: {
+        m_motorControllers.emplace_back();
+        m_motorControllers.emplace_back();
+        m_motorControllers.emplace_back();
+        m_group = std::make_unique<MotorControllerGroup>(m_motorControllers[0],
+                                                         m_motorControllers[1],
+                                                         m_motorControllers[2]);
+        break;
+      }
+    }
+  }
+};
+
+TEST_P(MotorControllerGroupTest, Set) {
+  m_group->Set(1.0);
+
+  for (auto& motorController : m_motorControllers) {
+    EXPECT_FLOAT_EQ(motorController.Get(), 1.0);
+  }
+}
+
+TEST_P(MotorControllerGroupTest, GetInverted) {
+  m_group->SetInverted(true);
+
+  EXPECT_TRUE(m_group->GetInverted());
+}
+
+TEST_P(MotorControllerGroupTest, SetInvertedDoesNotModifyMotorControllers) {
+  for (auto& motorController : m_motorControllers) {
+    motorController.SetInverted(false);
+  }
+  m_group->SetInverted(true);
+
+  for (auto& motorController : m_motorControllers) {
+    EXPECT_EQ(motorController.GetInverted(), false);
+  }
+}
+
+TEST_P(MotorControllerGroupTest, SetInvertedDoesInvert) {
+  m_group->SetInverted(true);
+  m_group->Set(1.0);
+
+  for (auto& motorController : m_motorControllers) {
+    EXPECT_FLOAT_EQ(motorController.Get(), -1.0);
+  }
+}
+
+TEST_P(MotorControllerGroupTest, Disable) {
+  m_group->Set(1.0);
+  m_group->Disable();
+
+  for (auto& motorController : m_motorControllers) {
+    EXPECT_FLOAT_EQ(motorController.Get(), 0.0);
+  }
+}
+
+TEST_P(MotorControllerGroupTest, StopMotor) {
+  m_group->Set(1.0);
+  m_group->StopMotor();
+
+  for (auto& motorController : m_motorControllers) {
+    EXPECT_FLOAT_EQ(motorController.Get(), 0.0);
+  }
+}
+
+INSTANTIATE_TEST_SUITE_P(Tests, MotorControllerGroupTest,
+                         testing::Values(TEST_ONE, TEST_TWO, TEST_THREE));
diff --git a/third_party/allwpilib/wpilibc/src/test/native/cpp/shuffleboard/ShuffleboardInstanceTest.cpp b/third_party/allwpilib/wpilibc/src/test/native/cpp/shuffleboard/ShuffleboardInstanceTest.cpp
index d370a2d..0b0c8df 100644
--- a/third_party/allwpilib/wpilibc/src/test/native/cpp/shuffleboard/ShuffleboardInstanceTest.cpp
+++ b/third_party/allwpilib/wpilibc/src/test/native/cpp/shuffleboard/ShuffleboardInstanceTest.cpp
@@ -31,8 +31,8 @@
                    .WithWidget("Text View")
                    .GetEntry();
 
-  EXPECT_EQ("string", entry.GetString("")) << "Wrong entry value";
-  EXPECT_EQ("/Shuffleboard/Tab Title/List/Data", entry.GetName())
+  EXPECT_EQ("string", entry->GetString("")) << "Wrong entry value";
+  EXPECT_EQ("/Shuffleboard/Tab Title/List/Data", entry->GetTopic().GetName())
       << "Entry path generated incorrectly";
 }
 
@@ -48,9 +48,9 @@
                    .Add("Value", "string")
                    .GetEntry();
 
-  EXPECT_EQ("string", entry.GetString("")) << "Wrong entry value";
+  EXPECT_EQ("string", entry->GetString("")) << "Wrong entry value";
   EXPECT_EQ("/Shuffleboard/Tab/First/Second/Third/Fourth/Value",
-            entry.GetName())
+            entry->GetTopic().GetName())
       << "Entry path generated incorrectly";
 }
 
@@ -66,9 +66,9 @@
   frc::SimpleWidget& widget = fourth.Add("Value", "string");
   auto entry = widget.GetEntry();
 
-  EXPECT_EQ("string", entry.GetString("")) << "Wrong entry value";
+  EXPECT_EQ("string", entry->GetString("")) << "Wrong entry value";
   EXPECT_EQ("/Shuffleboard/Tab/First/Second/Third/Fourth/Value",
-            entry.GetName())
+            entry->GetTopic().GetName())
       << "Entry path generated incorrectly";
 }
 
@@ -97,12 +97,12 @@
   // Note: we use the unsafe `GetBoolean()` method because if the value is NOT
   // a boolean, or if it is not present, then something has clearly gone very,
   // very wrong
-  bool controllable = controllableEntry.GetValue()->GetBoolean();
+  bool controllable = controllableEntry.GetValue().GetBoolean();
   // Sanity check
   EXPECT_TRUE(controllable)
       << "The nested actuator widget should be enabled by default";
   shuffleboardInst.DisableActuatorWidgets();
-  controllable = controllableEntry.GetValue()->GetBoolean();
+  controllable = controllableEntry.GetValue().GetBoolean();
   EXPECT_FALSE(controllable)
       << "The nested actuator widget should have been disabled";
 }
diff --git a/third_party/allwpilib/wpilibc/src/test/native/cpp/shuffleboard/SuppliedValueWidgetTest.cpp b/third_party/allwpilib/wpilibc/src/test/native/cpp/shuffleboard/SuppliedValueWidgetTest.cpp
index c8449e5..d964639 100644
--- a/third_party/allwpilib/wpilibc/src/test/native/cpp/shuffleboard/SuppliedValueWidgetTest.cpp
+++ b/third_party/allwpilib/wpilibc/src/test/native/cpp/shuffleboard/SuppliedValueWidgetTest.cpp
@@ -33,7 +33,7 @@
   auto entry = m_ntInst.inst.GetEntry("/Shuffleboard/Tab/String");
 
   m_shuffleboardInst.Update();
-  EXPECT_EQ("foo", entry.GetValue()->GetString());
+  EXPECT_EQ("foo", entry.GetValue().GetString());
 }
 
 TEST_F(SuppliedValueWidgetTest, AddNumber) {
@@ -42,7 +42,7 @@
   auto entry = m_ntInst.inst.GetEntry("/Shuffleboard/Tab/Num");
 
   m_shuffleboardInst.Update();
-  EXPECT_FLOAT_EQ(1.0, entry.GetValue()->GetDouble());
+  EXPECT_FLOAT_EQ(1.0, entry.GetValue().GetDouble());
 }
 
 TEST_F(SuppliedValueWidgetTest, AddBoolean) {
@@ -51,7 +51,7 @@
   auto entry = m_ntInst.inst.GetEntry("/Shuffleboard/Tab/Bool");
 
   m_shuffleboardInst.Update();
-  EXPECT_EQ(true, entry.GetValue()->GetBoolean());
+  EXPECT_EQ(true, entry.GetValue().GetBoolean());
 }
 
 TEST_F(SuppliedValueWidgetTest, AddStringArray) {
@@ -60,7 +60,7 @@
   auto entry = m_ntInst.inst.GetEntry("/Shuffleboard/Tab/Strings");
 
   m_shuffleboardInst.Update();
-  auto actual = entry.GetValue()->GetStringArray();
+  auto actual = entry.GetValue().GetStringArray();
 
   EXPECT_EQ(strings.size(), actual.size());
   for (size_t i = 0; i < strings.size(); i++) {
@@ -74,7 +74,7 @@
   auto entry = m_ntInst.inst.GetEntry("/Shuffleboard/Tab/Numbers");
 
   m_shuffleboardInst.Update();
-  auto actual = entry.GetValue()->GetDoubleArray();
+  auto actual = entry.GetValue().GetDoubleArray();
 
   EXPECT_EQ(nums.size(), actual.size());
   for (size_t i = 0; i < nums.size(); i++) {
@@ -88,7 +88,7 @@
   auto entry = m_ntInst.inst.GetEntry("/Shuffleboard/Tab/Booleans");
 
   m_shuffleboardInst.Update();
-  auto actual = entry.GetValue()->GetBooleanArray();
+  auto actual = entry.GetValue().GetBooleanArray();
 
   EXPECT_EQ(bools.size(), actual.size());
   for (size_t i = 0; i < bools.size(); i++) {
@@ -97,11 +97,11 @@
 }
 
 TEST_F(SuppliedValueWidgetTest, AddRaw) {
-  std::string_view bytes = "\1\2\3";
+  std::vector<uint8_t> bytes = {1, 2, 3};
   m_tab->AddRaw("Raw", [&bytes]() { return bytes; });
   auto entry = m_ntInst.inst.GetEntry("/Shuffleboard/Tab/Raw");
 
   m_shuffleboardInst.Update();
-  auto actual = entry.GetValue()->GetRaw();
-  EXPECT_EQ(bytes, actual);
+  auto actual = entry.GetValue().GetRaw();
+  EXPECT_EQ(bytes, std::vector<uint8_t>(actual.begin(), actual.end()));
 }
diff --git a/third_party/allwpilib/wpilibc/src/test/native/cpp/simulation/AddressableLEDSimTest.cpp b/third_party/allwpilib/wpilibc/src/test/native/cpp/simulation/AddressableLEDSimTest.cpp
index ad4452e..e450477 100644
--- a/third_party/allwpilib/wpilibc/src/test/native/cpp/simulation/AddressableLEDSimTest.cpp
+++ b/third_party/allwpilib/wpilibc/src/test/native/cpp/simulation/AddressableLEDSimTest.cpp
@@ -4,6 +4,8 @@
 
 #include "frc/simulation/AddressableLEDSim.h"  // NOLINT(build/include_order)
 
+#include <array>
+
 #include <hal/HAL.h>
 
 #include "callback_helpers/TestCallbackHelpers.h"
diff --git a/third_party/allwpilib/wpilibc/src/test/native/cpp/simulation/AnalogEncoderSimTest.cpp b/third_party/allwpilib/wpilibc/src/test/native/cpp/simulation/AnalogEncoderSimTest.cpp
index 375e21a..0a1b687 100644
--- a/third_party/allwpilib/wpilibc/src/test/native/cpp/simulation/AnalogEncoderSimTest.cpp
+++ b/third_party/allwpilib/wpilibc/src/test/native/cpp/simulation/AnalogEncoderSimTest.cpp
@@ -2,9 +2,10 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
+#include <numbers>
+
 #include <hal/HAL.h>
 #include <units/math.h>
-#include <wpi/numbers>
 
 #include "frc/AnalogEncoder.h"
 #include "frc/AnalogInput.h"
@@ -22,6 +23,6 @@
   encoderSim.SetPosition(180_deg);
   EXPECT_NEAR(encoder.Get().value(), 0.5, 1E-8);
   EXPECT_NEAR(encoderSim.GetTurns().value(), 0.5, 1E-8);
-  EXPECT_NEAR(encoderSim.GetPosition().Radians().value(), wpi::numbers::pi,
+  EXPECT_NEAR(encoderSim.GetPosition().Radians().value(), std::numbers::pi,
               1E-8);
 }
diff --git a/third_party/allwpilib/wpilibc/src/test/native/cpp/simulation/DifferentialDrivetrainSimTest.cpp b/third_party/allwpilib/wpilibc/src/test/native/cpp/simulation/DifferentialDrivetrainSimTest.cpp
index 8ccfcd6..6edfde0 100644
--- a/third_party/allwpilib/wpilibc/src/test/native/cpp/simulation/DifferentialDrivetrainSimTest.cpp
+++ b/third_party/allwpilib/wpilibc/src/test/native/cpp/simulation/DifferentialDrivetrainSimTest.cpp
@@ -30,17 +30,17 @@
   frc::LinearPlantInversionFeedforward feedforward{plant, 20_ms};
   frc::RamseteController ramsete;
 
-  feedforward.Reset(Eigen::Vector<double, 2>{0.0, 0.0});
+  feedforward.Reset(frc::Vectord<2>{0.0, 0.0});
 
   // Ground truth.
-  Eigen::Vector<double, 7> groundTruthX = Eigen::Vector<double, 7>::Zero();
+  frc::Vectord<7> groundTruthX = frc::Vectord<7>::Zero();
 
   frc::TrajectoryConfig config{1_mps, 1_mps_sq};
   config.AddConstraint(
       frc::DifferentialDriveKinematicsConstraint(kinematics, 1_mps));
 
   auto trajectory = frc::TrajectoryGenerator::GenerateTrajectory(
-      frc::Pose2d(), {}, frc::Pose2d(2_m, 2_m, 0_rad), config);
+      frc::Pose2d{}, {}, frc::Pose2d{2_m, 2_m, 0_rad}, config);
 
   for (auto t = 0_s; t < trajectory.TotalTime(); t += 20_ms) {
     auto state = trajectory.Sample(t);
@@ -48,15 +48,15 @@
 
     auto [l, r] = kinematics.ToWheelSpeeds(ramseteOut);
     auto voltages =
-        feedforward.Calculate(Eigen::Vector<double, 2>{l.value(), r.value()});
+        feedforward.Calculate(frc::Vectord<2>{l.value(), r.value()});
 
     // Sim periodic code.
-    sim.SetInputs(units::volt_t(voltages(0, 0)), units::volt_t(voltages(1, 0)));
+    sim.SetInputs(units::volt_t{voltages(0, 0)}, units::volt_t{voltages(1, 0)});
     sim.Update(20_ms);
 
     // Update ground truth.
     groundTruthX = frc::RK4(
-        [&sim](const auto& x, const auto& u) -> Eigen::Vector<double, 7> {
+        [&sim](const auto& x, const auto& u) -> frc::Vectord<7> {
           return sim.Dynamics(x, u);
         },
         groundTruthX, voltages, 20_ms);
diff --git a/third_party/allwpilib/wpilibc/src/test/native/cpp/simulation/DriverStationSimTest.cpp b/third_party/allwpilib/wpilibc/src/test/native/cpp/simulation/DriverStationSimTest.cpp
index d01ca27..6aa31c6 100644
--- a/third_party/allwpilib/wpilibc/src/test/native/cpp/simulation/DriverStationSimTest.cpp
+++ b/third_party/allwpilib/wpilibc/src/test/native/cpp/simulation/DriverStationSimTest.cpp
@@ -132,6 +132,7 @@
   // B1
   allianceStation = HAL_AllianceStationID_kBlue1;
   DriverStationSim::SetAllianceStationId(allianceStation);
+  frc::sim::DriverStationSim::NotifyNewData();
   EXPECT_EQ(allianceStation, DriverStationSim::GetAllianceStationId());
   EXPECT_EQ(DriverStation::kBlue, DriverStation::GetAlliance());
   EXPECT_EQ(1, DriverStation::GetLocation());
@@ -141,6 +142,7 @@
   // B2
   allianceStation = HAL_AllianceStationID_kBlue2;
   DriverStationSim::SetAllianceStationId(allianceStation);
+  frc::sim::DriverStationSim::NotifyNewData();
   EXPECT_EQ(allianceStation, DriverStationSim::GetAllianceStationId());
   EXPECT_EQ(DriverStation::kBlue, DriverStation::GetAlliance());
   EXPECT_EQ(2, DriverStation::GetLocation());
@@ -150,6 +152,7 @@
   // B3
   allianceStation = HAL_AllianceStationID_kBlue3;
   DriverStationSim::SetAllianceStationId(allianceStation);
+  frc::sim::DriverStationSim::NotifyNewData();
   EXPECT_EQ(allianceStation, DriverStationSim::GetAllianceStationId());
   EXPECT_EQ(DriverStation::kBlue, DriverStation::GetAlliance());
   EXPECT_EQ(3, DriverStation::GetLocation());
@@ -159,6 +162,7 @@
   // R1
   allianceStation = HAL_AllianceStationID_kRed1;
   DriverStationSim::SetAllianceStationId(allianceStation);
+  frc::sim::DriverStationSim::NotifyNewData();
   EXPECT_EQ(allianceStation, DriverStationSim::GetAllianceStationId());
   EXPECT_EQ(DriverStation::kRed, DriverStation::GetAlliance());
   EXPECT_EQ(1, DriverStation::GetLocation());
@@ -168,6 +172,7 @@
   // R2
   allianceStation = HAL_AllianceStationID_kRed2;
   DriverStationSim::SetAllianceStationId(allianceStation);
+  frc::sim::DriverStationSim::NotifyNewData();
   EXPECT_EQ(allianceStation, DriverStationSim::GetAllianceStationId());
   EXPECT_EQ(DriverStation::kRed, DriverStation::GetAlliance());
   EXPECT_EQ(2, DriverStation::GetLocation());
@@ -177,6 +182,7 @@
   // R3
   allianceStation = HAL_AllianceStationID_kRed3;
   DriverStationSim::SetAllianceStationId(allianceStation);
+  frc::sim::DriverStationSim::NotifyNewData();
   EXPECT_EQ(allianceStation, DriverStationSim::GetAllianceStationId());
   EXPECT_EQ(DriverStation::kRed, DriverStation::GetAlliance());
   EXPECT_EQ(3, DriverStation::GetLocation());
@@ -211,6 +217,7 @@
                                                         false);
   constexpr double kTestTime = 19.174;
   DriverStationSim::SetMatchTime(kTestTime);
+  frc::sim::DriverStationSim::NotifyNewData();
   EXPECT_EQ(kTestTime, DriverStationSim::GetMatchTime());
   EXPECT_EQ(kTestTime, DriverStation::GetMatchTime());
   EXPECT_TRUE(callback.WasTriggered());
diff --git a/third_party/allwpilib/wpilibc/src/test/native/cpp/simulation/ElevatorSimTest.cpp b/third_party/allwpilib/wpilibc/src/test/native/cpp/simulation/ElevatorSimTest.cpp
index 03022ab..3c647e6 100644
--- a/third_party/allwpilib/wpilibc/src/test/native/cpp/simulation/ElevatorSimTest.cpp
+++ b/third_party/allwpilib/wpilibc/src/test/native/cpp/simulation/ElevatorSimTest.cpp
@@ -2,6 +2,7 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
+#include <units/math.h>
 #include <units/time.h>
 
 #include "frc/Encoder.h"
@@ -15,10 +16,12 @@
 #include "frc/system/plant/LinearSystemId.h"
 #include "gtest/gtest.h"
 
+#define EXPECT_NEAR_UNITS(val1, val2, eps) \
+  EXPECT_LE(units::math::abs(val1 - val2), eps)
+
 TEST(ElevatorSimTest, StateSpaceSim) {
-  frc::sim::ElevatorSim sim(frc::DCMotor::Vex775Pro(4), 14.67, 8_kg,
-                            units::meter_t(0.75 * 25.4 / 1000.0), 0_m, 3_m,
-                            {0.01});
+  frc::sim::ElevatorSim sim(frc::DCMotor::Vex775Pro(4), 14.67, 8_kg, 0.75_in,
+                            0_m, 3_m, true, {0.01});
   frc2::PIDController controller(10, 0.0, 0.0);
 
   frc::PWMVictorSPX motor(0);
@@ -30,8 +33,7 @@
     auto nextVoltage = controller.Calculate(encoderSim.GetDistance());
     motor.Set(nextVoltage / frc::RobotController::GetInputVoltage());
 
-    Eigen::Vector<double, 1> u{motor.Get() *
-                               frc::RobotController::GetInputVoltage()};
+    frc::Vectord<1> u{motor.Get() * frc::RobotController::GetInputVoltage()};
     sim.SetInput(u);
     sim.Update(20_ms);
 
@@ -43,11 +45,10 @@
 }
 
 TEST(ElevatorSimTest, MinMax) {
-  frc::sim::ElevatorSim sim(frc::DCMotor::Vex775Pro(4), 14.67, 8_kg,
-                            units::meter_t(0.75 * 25.4 / 1000.0), 0_m, 1_m,
-                            {0.01});
+  frc::sim::ElevatorSim sim(frc::DCMotor::Vex775Pro(4), 14.67, 8_kg, 0.75_in,
+                            0_m, 1_m, true, {0.01});
   for (size_t i = 0; i < 100; ++i) {
-    sim.SetInput(Eigen::Vector<double, 1>{0.0});
+    sim.SetInput(frc::Vectord<1>{0.0});
     sim.Update(20_ms);
 
     auto height = sim.GetPosition();
@@ -55,7 +56,7 @@
   }
 
   for (size_t i = 0; i < 100; ++i) {
-    sim.SetInput(Eigen::Vector<double, 1>{12.0});
+    sim.SetInput(frc::Vectord<1>{12.0});
     sim.Update(20_ms);
 
     auto height = sim.GetPosition();
@@ -64,26 +65,19 @@
 }
 
 TEST(ElevatorSimTest, Stability) {
-  static constexpr double kElevatorGearing = 100.0;
-  static constexpr units::meter_t kElevatorDrumRadius = 0.5_in;
-  static constexpr units::kilogram_t kCarriageMass = 4.0_kg;
-  frc::DCMotor m_elevatorGearbox = frc::DCMotor::Vex775Pro(4);
+  frc::sim::ElevatorSim sim{
+      frc::DCMotor::Vex775Pro(4), 100, 4_kg, 0.5_in, 0_m, 10_m, true};
 
-  frc::LinearSystem<2, 1, 1> system = frc::LinearSystemId::ElevatorSystem(
-      m_elevatorGearbox, kCarriageMass, kElevatorDrumRadius, kElevatorGearing);
-
-  Eigen::Vector<double, 2> x0{0.0, 0.0};
-  Eigen::Vector<double, 1> u0{12.0};
-
-  Eigen::Vector<double, 2> x1{0.0, 0.0};
-  for (size_t i = 0; i < 50; i++) {
-    x1 = frc::RKDP(
-        [&](const Eigen::Vector<double, 2>& x,
-            const Eigen::Vector<double, 1>& u) -> Eigen::Vector<double, 2> {
-          return system.A() * x + system.B() * u;
-        },
-        x1, u0, 0.020_s);
+  sim.SetState(frc::Vectord<2>{0.0, 0.0});
+  sim.SetInput(frc::Vectord<1>{12.0});
+  for (int i = 0; i < 50; ++i) {
+    sim.Update(20_ms);
   }
 
-  EXPECT_NEAR(x1(0), system.CalculateX(x0, u0, 1_s)(0), 0.1);
+  frc::LinearSystem<2, 1, 1> system = frc::LinearSystemId::ElevatorSystem(
+      frc::DCMotor::Vex775Pro(4), 4_kg, 0.5_in, 100);
+  EXPECT_NEAR_UNITS(
+      units::meter_t{system.CalculateX(frc::Vectord<2>{0.0, 0.0},
+                                       frc::Vectord<1>{12.0}, 20_ms * 50)(0)},
+      sim.GetPosition(), 1_cm);
 }
diff --git a/third_party/allwpilib/wpilibc/src/test/native/cpp/simulation/EncoderSimTest.cpp b/third_party/allwpilib/wpilibc/src/test/native/cpp/simulation/EncoderSimTest.cpp
index be13ca5..7722ccc 100644
--- a/third_party/allwpilib/wpilibc/src/test/native/cpp/simulation/EncoderSimTest.cpp
+++ b/third_party/allwpilib/wpilibc/src/test/native/cpp/simulation/EncoderSimTest.cpp
@@ -91,7 +91,9 @@
   auto cb = sim.RegisterPeriodCallback(callback.GetCallback(), false);
   sim.SetPeriod(123.456);
   EXPECT_EQ(123.456, sim.GetPeriod());
+  WPI_IGNORE_DEPRECATED
   EXPECT_EQ(123.456, encoder.GetPeriod().value());
+  WPI_UNIGNORE_DEPRECATED
   EXPECT_EQ(kDefaultDistancePerPulse / 123.456, encoder.GetRate());
 
   EXPECT_TRUE(callback.WasTriggered());
@@ -110,7 +112,9 @@
   DoubleCallback callback;
   auto cb = sim.RegisterMaxPeriodCallback(callback.GetCallback(), false);
 
+  WPI_IGNORE_DEPRECATED
   encoder.SetMaxPeriod(units::second_t{123.456});
+  WPI_UNIGNORE_DEPRECATED
   EXPECT_EQ(123.456, sim.GetMaxPeriod());
 
   EXPECT_TRUE(callback.WasTriggered());
diff --git a/third_party/allwpilib/wpilibc/src/test/native/cpp/simulation/RoboRioSimTest.cpp b/third_party/allwpilib/wpilibc/src/test/native/cpp/simulation/RoboRioSimTest.cpp
index c6e93d4..98d4620 100644
--- a/third_party/allwpilib/wpilibc/src/test/native/cpp/simulation/RoboRioSimTest.cpp
+++ b/third_party/allwpilib/wpilibc/src/test/native/cpp/simulation/RoboRioSimTest.cpp
@@ -207,4 +207,41 @@
   EXPECT_EQ(kTestFaults, RobotController::GetFaultCount3V3());
 }
 
+TEST(RoboRioSimTest, SetSerialNumber) {
+  const std::string kSerialNum = "Hello";
+
+  RoboRioSim::ResetData();
+
+  RoboRioSim::SetSerialNumber(kSerialNum);
+  EXPECT_EQ(kSerialNum, RoboRioSim::GetSerialNumber());
+  EXPECT_EQ(kSerialNum, RobotController::GetSerialNumber());
+
+  const std::string kSerialNumberOverflow = "SerialNumber";
+  const std::string kSerialNumberTruncated = kSerialNumberOverflow.substr(0, 8);
+
+  RoboRioSim::SetSerialNumber(kSerialNumberOverflow);
+  EXPECT_EQ(kSerialNumberTruncated, RoboRioSim::GetSerialNumber());
+  EXPECT_EQ(kSerialNumberTruncated, RobotController::GetSerialNumber());
+}
+
+TEST(RoboRioSimTest, SetComments) {
+  const std::string kComments =
+      "Hello! These are comments in the roboRIO web interface!";
+
+  RoboRioSim::ResetData();
+
+  RoboRioSim::SetComments(kComments);
+  EXPECT_EQ(kComments, RoboRioSim::GetComments());
+  EXPECT_EQ(kComments, RobotController::GetComments());
+
+  const std::string kCommentsOverflow =
+      "Hello! These are comments in the roboRIO web interface! This comment "
+      "exceeds 64 characters!";
+  const std::string kCommentsTruncated = kCommentsOverflow.substr(0, 64);
+
+  RoboRioSim::SetComments(kCommentsOverflow);
+  EXPECT_EQ(kCommentsTruncated, RoboRioSim::GetComments());
+  EXPECT_EQ(kCommentsTruncated, RobotController::GetComments());
+}
+
 }  // namespace frc::sim
diff --git a/third_party/allwpilib/wpilibc/src/test/native/cpp/simulation/SingleJointedArmSimTest.cpp b/third_party/allwpilib/wpilibc/src/test/native/cpp/simulation/SingleJointedArmSimTest.cpp
index 03df12b..2e4c793 100644
--- a/third_party/allwpilib/wpilibc/src/test/native/cpp/simulation/SingleJointedArmSimTest.cpp
+++ b/third_party/allwpilib/wpilibc/src/test/native/cpp/simulation/SingleJointedArmSimTest.cpp
@@ -2,7 +2,7 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
-#include <wpi/numbers>
+#include <numbers>
 
 #include "frc/simulation/SingleJointedArmSim.h"
 #include "gtest/gtest.h"
@@ -10,13 +10,13 @@
 TEST(SingleJointedArmTest, Disabled) {
   frc::sim::SingleJointedArmSim sim(frc::DCMotor::Vex775Pro(2), 100, 3_kg_sq_m,
                                     9.5_in, -180_deg, 0_deg, 10_lb, true);
-  sim.SetState(Eigen::Vector<double, 2>{0.0, 0.0});
+  sim.SetState(frc::Vectord<2>{0.0, 0.0});
 
   for (size_t i = 0; i < 12 / 0.02; ++i) {
-    sim.SetInput(Eigen::Vector<double, 1>{0.0});
+    sim.SetInput(frc::Vectord<1>{0.0});
     sim.Update(20_ms);
   }
 
   // The arm should swing down.
-  EXPECT_NEAR(sim.GetAngle().value(), -wpi::numbers::pi / 2, 0.01);
+  EXPECT_NEAR(sim.GetAngle().value(), -std::numbers::pi / 2, 0.01);
 }
diff --git a/third_party/allwpilib/wpilibc/src/test/native/cpp/simulation/StateSpaceSimTest.cpp b/third_party/allwpilib/wpilibc/src/test/native/cpp/simulation/StateSpaceSimTest.cpp
index 23af83d..7456adb 100644
--- a/third_party/allwpilib/wpilibc/src/test/native/cpp/simulation/StateSpaceSimTest.cpp
+++ b/third_party/allwpilib/wpilibc/src/test/native/cpp/simulation/StateSpaceSimTest.cpp
@@ -40,14 +40,14 @@
   for (int i = 0; i < 100; i++) {
     // RobotPeriodic runs first
     auto voltageOut = controller.Calculate(encoder.GetRate(), 200.0);
-    motor.SetVoltage(units::volt_t(voltageOut) +
+    motor.SetVoltage(units::volt_t{voltageOut} +
                      feedforward.Calculate(200_rad_per_s));
 
     // Then, SimulationPeriodic runs
     frc::sim::RoboRioSim::SetVInVoltage(
         frc::sim::BatterySim::Calculate({sim.GetCurrentDraw()}));
-    sim.SetInput(Eigen::Vector<double, 1>{
-        motor.Get() * frc::RobotController::GetInputVoltage()});
+    sim.SetInput(
+        frc::Vectord<1>{motor.Get() * frc::RobotController::GetInputVoltage()});
     sim.Update(20_ms);
     encoderSim.SetRate(sim.GetAngularVelocity().value());
   }
diff --git a/third_party/allwpilib/wpilibc/src/test/native/include/MockMotorController.h b/third_party/allwpilib/wpilibc/src/test/native/include/motorcontrol/MockMotorController.h
similarity index 100%
rename from third_party/allwpilib/wpilibc/src/test/native/include/MockMotorController.h
rename to third_party/allwpilib/wpilibc/src/test/native/include/motorcontrol/MockMotorController.h
diff --git a/third_party/allwpilib/wpilibcExamples/CMakeLists.txt b/third_party/allwpilib/wpilibcExamples/CMakeLists.txt
index 27cff6b..3b2413d 100644
--- a/third_party/allwpilib/wpilibcExamples/CMakeLists.txt
+++ b/third_party/allwpilib/wpilibcExamples/CMakeLists.txt
@@ -10,13 +10,16 @@
   file(GLOB_RECURSE sources src/main/cpp/examples/${example}/cpp/*.cpp
                             src/main/cpp/examples/${example}/c/*.c)
   add_executable(${example} ${sources})
+  wpilib_target_warnings(${example})
   target_include_directories(${example} PUBLIC src/main/cpp/examples/${example}/include)
-  target_link_libraries(${example} wpilibc wpilibNewCommands wpilibOldCommands)
+  target_link_libraries(${example} wpilibc wpilibNewCommands)
 
   if (WITH_TESTS AND EXISTS ${CMAKE_SOURCE_DIR}/wpilibcExamples/src/test/cpp/examples/${example})
     wpilib_add_test(${example} src/test/cpp/examples/${example}/cpp)
     target_sources(${example}_test PRIVATE ${sources})
-    target_include_directories(${example}_test PRIVATE src/test/cpp/examples/${example}/include)
+    target_include_directories(${example}_test PRIVATE
+                               src/main/cpp/examples/${example}/include
+                               src/test/cpp/examples/${example}/include)
     target_compile_definitions(${example}_test PUBLIC RUNNING_FRC_TESTS)
     target_link_libraries(${example}_test wpilibc wpilibNewCommands gmock_main)
   endif()
@@ -26,6 +29,7 @@
   file(GLOB_RECURSE sources src/main/cpp/templates/${template}/cpp/*.cpp
                             src/main/cpp/templates/${template}/c/*.c)
   add_executable(${template} ${sources})
+  wpilib_target_warnings(${template})
   target_include_directories(${template} PUBLIC src/main/cpp/templates/${template}/include)
   target_link_libraries(${template} wpilibc wpilibNewCommands)
 endforeach()
diff --git a/third_party/allwpilib/wpilibcExamples/build.gradle b/third_party/allwpilib/wpilibcExamples/build.gradle
index 7561ed5..2ca6038 100644
--- a/third_party/allwpilib/wpilibcExamples/build.gradle
+++ b/third_party/allwpilib/wpilibcExamples/build.gradle
@@ -34,11 +34,6 @@
             templatesMap.put(it, [])
         }
 
-nativeUtils.platformConfigs.named(nativeUtils.wpi.platforms.roborio).configure {
-    cppCompiler.args.remove('-Wno-error=deprecated-declarations')
-    cppCompiler.args.add('-Werror=deprecated-declarations')
-}
-
 nativeUtils.platformConfigs.named(nativeUtils.wpi.platforms.windowsx64).configure {
     linker.args.remove('/DEBUG:FULL')
     cppCompiler.debugArgs.remove('/Zi')
@@ -64,14 +59,15 @@
                     binary.buildable = false
                     return
                 }
-                lib project: ':wpilibOldCommands', library: 'wpilibOldCommands', linkage: 'shared'
                 lib project: ':wpilibNewCommands', library: 'wpilibNewCommands', linkage: 'shared'
+                lib project: ':apriltag', library: 'apriltag', linkage: 'shared'
                 lib project: ':wpilibc', library: 'wpilibc', linkage: 'shared'
                 lib project: ':wpimath', library: 'wpimath', linkage: 'shared'
-                lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
+                project(':ntcore').addNtcoreDependency(binary, 'shared')
                 lib project: ':cscore', library: 'cscore', linkage: 'shared'
                 project(':hal').addHalDependency(binary, 'shared')
                 lib project: ':cameraserver', library: 'cameraserver', linkage: 'shared'
+                lib project: ':wpinet', library: 'wpinet', linkage: 'shared'
                 lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
             }
             sources {
@@ -94,11 +90,13 @@
                 binaries.all { binary ->
                     lib project: ':wpilibNewCommands', library: 'wpilibNewCommands', linkage: 'shared'
                     lib project: ':wpilibc', library: 'wpilibc', linkage: 'shared'
+                    lib project: ':apriltag', library: 'apriltag', linkage: 'shared'
                     lib project: ':wpimath', library: 'wpimath', linkage: 'shared'
-                    lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
+                    project(':ntcore').addNtcoreDependency(binary, 'shared')
                     lib project: ':cscore', library: 'cscore', linkage: 'shared'
                     project(':hal').addHalDependency(binary, 'shared')
                     lib project: ':cameraserver', library: 'cameraserver', linkage: 'shared'
+                    lib project: ':wpinet', library: 'wpinet', linkage: 'shared'
                     lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
                     if (binary.targetPlatform.name == nativeUtils.wpi.platforms.roborio) {
                         nativeUtils.useRequiredLibrary(binary, 'ni_link_libraries', 'ni_runtime_libraries')
@@ -141,19 +139,14 @@
                 binaries.all { binary ->
                     lib project: ':wpilibNewCommands', library: 'wpilibNewCommands', linkage: 'shared'
                     lib project: ':wpilibc', library: 'wpilibc', linkage: 'shared'
+                    lib project: ':apriltag', library: 'apriltag', linkage: 'shared'
                     lib project: ':wpimath', library: 'wpimath', linkage: 'shared'
-                    lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
+                    project(':ntcore').addNtcoreDependency(binary, 'shared')
                     lib project: ':cscore', library: 'cscore', linkage: 'shared'
                     project(':hal').addHalDependency(binary, 'shared')
                     lib project: ':cameraserver', library: 'cameraserver', linkage: 'shared'
+                    lib project: ':wpinet', library: 'wpinet', linkage: 'shared'
                     lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
-                    binary.tasks.withType(CppCompile) {
-                        if (!(binary.toolChain in VisualCpp)) {
-                            cppCompiler.args "-Wno-error=deprecated-declarations"
-                        } else {
-                            cppCompiler.args "/wd4996"
-                        }
-                    }
                     if (binary.targetPlatform.name == nativeUtils.wpi.platforms.roborio) {
                         nativeUtils.useRequiredLibrary(binary, 'ni_link_libraries', 'ni_runtime_libraries')
                     }
@@ -212,11 +205,13 @@
         withType(GoogleTestTestSuiteBinarySpec) {
             lib project: ':wpilibNewCommands', library: 'wpilibNewCommands', linkage: 'shared'
             lib project: ':wpilibc', library: 'wpilibc', linkage: 'shared'
+            lib project: ':apriltag', library: 'apriltag', linkage: 'shared'
             lib project: ':wpimath', library: 'wpimath', linkage: 'shared'
-            lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
+            project(':ntcore').addNtcoreDependency(it, 'shared')
             lib project: ':cscore', library: 'cscore', linkage: 'shared'
             project(':hal').addHalDependency(it, 'shared')
             lib project: ':cameraserver', library: 'cameraserver', linkage: 'shared'
+            lib project: ':wpinet', library: 'wpinet', linkage: 'shared'
             lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
             if (it.targetPlatform.name == nativeUtils.wpi.platforms.roborio) {
                 nativeUtils.useRequiredLibrary(it, 'ni_link_libraries', 'ni_runtime_libraries')
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/command/ReplaceMeCommand.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/command/ReplaceMeCommand.cpp
deleted file mode 100644
index 24726b0..0000000
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/command/ReplaceMeCommand.cpp
+++ /dev/null
@@ -1,28 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "ReplaceMeCommand.h"
-
-ReplaceMeCommand::ReplaceMeCommand() {
-  // Use Requires() here to declare subsystem dependencies
-  // eg. Requires(Robot::chassis.get());
-}
-
-// Called just before this Command runs the first time
-void ReplaceMeCommand::Initialize() {}
-
-// Called repeatedly when this Command is scheduled to run
-void ReplaceMeCommand::Execute() {}
-
-// Make this return true when this Command no longer needs to run execute()
-bool ReplaceMeCommand::IsFinished() {
-  return false;
-}
-
-// Called once after isFinished returns true
-void ReplaceMeCommand::End() {}
-
-// Called when another command which requires one or more of the same
-// subsystems is scheduled to run
-void ReplaceMeCommand::Interrupted() {}
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/command/ReplaceMeCommand.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/command/ReplaceMeCommand.h
deleted file mode 100644
index 64fcd26..0000000
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/command/ReplaceMeCommand.h
+++ /dev/null
@@ -1,17 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <frc/commands/Command.h>
-
-class ReplaceMeCommand : public frc::Command {
- public:
-  ReplaceMeCommand();
-  void Initialize() override;
-  void Execute() override;
-  bool IsFinished() override;
-  void End() override;
-  void Interrupted() override;
-};
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/commandgroup/ReplaceMeCommandGroup.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/commandgroup/ReplaceMeCommandGroup.cpp
deleted file mode 100644
index ced938d..0000000
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/commandgroup/ReplaceMeCommandGroup.cpp
+++ /dev/null
@@ -1,24 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "ReplaceMeCommandGroup.h"
-
-ReplaceMeCommandGroup::ReplaceMeCommandGroup() {
-  // Add Commands here:
-  // e.g. AddSequential(new Command1());
-  //      AddSequential(new Command2());
-  // these will run in order.
-
-  // To run multiple commands at the same time,
-  // use AddParallel()
-  // e.g. AddParallel(new Command1());
-  //      AddSequential(new Command2());
-  // Command1 and Command2 will run in parallel.
-
-  // A command group will require all of the subsystems that each member
-  // would require.
-  // e.g. if Command1 requires chassis, and Command2 requires arm,
-  // a CommandGroup containing them would require both the chassis and the
-  // arm.
-}
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/commandgroup/ReplaceMeCommandGroup.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/commandgroup/ReplaceMeCommandGroup.h
deleted file mode 100644
index c51a964..0000000
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/commandgroup/ReplaceMeCommandGroup.h
+++ /dev/null
@@ -1,12 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <frc/commands/CommandGroup.h>
-
-class ReplaceMeCommandGroup : public frc::CommandGroup {
- public:
-  ReplaceMeCommandGroup();
-};
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/commands.json b/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/commands.json
index 6b5bf1e..7f0c8f9 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/commands.json
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/commands.json
@@ -16,120 +16,7 @@
     "commandversion": 0
   },
   {
-    "name": "Command (Old)",
-    "description": "Create a base command",
-    "tags": [
-      "command"
-    ],
-    "foldername": "command",
-    "headers": [
-      "ReplaceMeCommand.h"
-    ],
-    "source": [
-      "ReplaceMeCommand.cpp"
-    ],
-    "replacename": "ReplaceMeCommand",
-    "commandversion": 1
-  },
-  {
-    "name": "Command Group (Old)",
-    "description": "Create a command group",
-    "tags": [
-      "commandgroup"
-    ],
-    "foldername": "commandgroup",
-    "headers": [
-      "ReplaceMeCommandGroup.h"
-    ],
-    "source": [
-      "ReplaceMeCommandGroup.cpp"
-    ],
-    "replacename": "ReplaceMeCommandGroup",
-    "commandversion": 1
-  },
-  {
-    "name": "Instant Command (Old)",
-    "description": "A command that runs immediately",
-    "tags": [
-      "instantcommand"
-    ],
-    "foldername": "instant",
-    "headers": [
-      "ReplaceMeInstantCommand.h"
-    ],
-    "source": [
-      "ReplaceMeInstantCommand.cpp"
-    ],
-    "replacename": "ReplaceMeInstantCommand",
-    "commandversion": 1
-  },
-  {
-    "name": "Subsystem (Old)",
-    "description": "A subsystem",
-    "tags": [
-      "subsystem"
-    ],
-    "foldername": "subsystem",
-    "headers": [
-      "ReplaceMeSubsystem.h"
-    ],
-    "source": [
-      "ReplaceMeSubsystem.cpp"
-    ],
-    "replacename": "ReplaceMeSubsystem",
-    "commandversion": 1
-  },
-  {
-    "name": "PID Subsystem (Old)",
-    "description": "A subsystem that runs a PID loop",
-    "tags": [
-      "pidsubsystem",
-      "pid"
-    ],
-    "foldername": "pidsubsystem",
-    "headers": [
-      "ReplaceMePIDSubsystem.h"
-    ],
-    "source": [
-      "ReplaceMePIDSubsystem.cpp"
-    ],
-    "replacename": "ReplaceMePIDSubsystem",
-    "commandversion": 1
-  },
-  {
-    "name": "Timed Command (Old)",
-    "description": "A command that runs for a specified time",
-    "tags": [
-      "timedcommand"
-    ],
-    "foldername": "timed",
-    "headers": [
-      "ReplaceMeTimedCommand.h"
-    ],
-    "source": [
-      "ReplaceMeTimedCommand.cpp"
-    ],
-    "replacename": "ReplaceMeTimedCommand",
-    "commandversion": 1
-  },
-  {
-    "name": "Trigger (Old)",
-    "description": "A command that runs off of a trigger",
-    "tags": [
-      "trigger"
-    ],
-    "foldername": "trigger",
-    "headers": [
-      "ReplaceMeTrigger.h"
-    ],
-    "source": [
-      "ReplaceMeTrigger.cpp"
-    ],
-    "replacename": "ReplaceMeTrigger",
-    "commandversion": 1
-  },
-  {
-    "name": "Command (New)",
+    "name": "Command",
     "description": "A command.",
     "tags": [
       "command"
@@ -145,7 +32,7 @@
     "commandversion": 2
   },
   {
-    "name": "InstantCommand (New)",
+    "name": "InstantCommand",
     "description": "A command that finishes instantly.",
     "tags": [
       "instantcommand"
@@ -161,7 +48,7 @@
     "commandversion": 2
   },
   {
-    "name": "ParallelCommandGroup (New)",
+    "name": "ParallelCommandGroup",
     "description": "A command group that runs commands in parallel, ending when all commands have finished.",
     "tags": [
       "parallelcommandgroup"
@@ -177,7 +64,7 @@
     "commandversion": 2
   },
   {
-    "name": "ParallelDeadlineGroup (New)",
+    "name": "ParallelDeadlineGroup",
     "description": "A command group that runs commands in parallel, ending when a specific command has finished.",
     "tags": [
       "paralleldeadlinegroup"
@@ -193,7 +80,7 @@
     "commandversion": 2
   },
   {
-    "name": "ParallelRaceGroup (New)",
+    "name": "ParallelRaceGroup",
     "description": "A command that runs commands in parallel, ending as soon as any command has finished.",
     "tags": [
       "parallelracegroup"
@@ -209,7 +96,7 @@
     "commandversion": 2
   },
   {
-    "name": "PIDCommand (New)",
+    "name": "PIDCommand",
     "description": "A command that runs a PIDController.",
     "tags": [
       "pidcommand"
@@ -225,7 +112,7 @@
     "commandversion": 2
   },
   {
-    "name": "PIDSubsystem (New)",
+    "name": "PIDSubsystem",
     "description": "A subsystem that runs a PIDController.",
     "tags": [
       "pidsubsystem"
@@ -241,7 +128,7 @@
     "commandversion": 2
   },
   {
-    "name": "ProfiledPIDCommand (New)",
+    "name": "ProfiledPIDCommand",
     "description": "A command that runs a ProfiledPIDController.",
     "tags": [
       "profiledpidcommand"
@@ -257,7 +144,7 @@
     "commandversion": 2
   },
   {
-    "name": "ProfiledPIDSubsystem (New)",
+    "name": "ProfiledPIDSubsystem",
     "description": "A subsystem that runs a ProfiledPIDController.",
     "tags": [
       "profiledpidsubsystem"
@@ -273,7 +160,7 @@
     "commandversion": 2
   },
   {
-    "name": "SequentialCommandGroup (New)",
+    "name": "SequentialCommandGroup",
     "description": "A command group that runs commands in sequence.",
     "tags": [
       "sequentialcommandgroup"
@@ -289,7 +176,7 @@
     "commandversion": 2
   },
   {
-    "name": "Subsystem (New)",
+    "name": "Subsystem",
     "description": "A robot subsystem.",
     "tags": [
       "subsystem"
@@ -305,7 +192,7 @@
     "commandversion": 2
   },
   {
-    "name": "TrapezoidProfileCommand (New)",
+    "name": "TrapezoidProfileCommand",
     "description": "A command that executes a trapezoidal motion profile.",
     "tags": [
       "trapezoidprofilecommand"
@@ -321,7 +208,7 @@
     "commandversion": 2
   },
   {
-    "name": "TrapezoidProfileSubsystem (New)",
+    "name": "TrapezoidProfileSubsystem",
     "description": "A subsystem that executes a trapezoidal motion profile.",
     "tags": [
       "trapezoidprofilesubsystem"
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/instant/ReplaceMeInstantCommand.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/instant/ReplaceMeInstantCommand.cpp
deleted file mode 100644
index 1a80288..0000000
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/instant/ReplaceMeInstantCommand.cpp
+++ /dev/null
@@ -1,13 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "ReplaceMeInstantCommand.h"
-
-ReplaceMeInstantCommand::ReplaceMeInstantCommand() {
-  // Use Requires() here to declare subsystem dependencies
-  // eg. Requires(Robot::chassis.get());
-}
-
-// Called once when the command executes
-void ReplaceMeInstantCommand::Initialize() {}
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/instant/ReplaceMeInstantCommand.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/instant/ReplaceMeInstantCommand.h
deleted file mode 100644
index c73cbcf..0000000
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/instant/ReplaceMeInstantCommand.h
+++ /dev/null
@@ -1,13 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <frc/commands/InstantCommand.h>
-
-class ReplaceMeInstantCommand : public frc::InstantCommand {
- public:
-  ReplaceMeInstantCommand();
-  void Initialize() override;
-};
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/parallelcommandgroup/ReplaceMeParallelCommandGroup.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/parallelcommandgroup/ReplaceMeParallelCommandGroup.cpp
index e814a09..3a387ff 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/parallelcommandgroup/ReplaceMeParallelCommandGroup.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/parallelcommandgroup/ReplaceMeParallelCommandGroup.cpp
@@ -9,5 +9,5 @@
 // https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
 ReplaceMeParallelCommandGroup::ReplaceMeParallelCommandGroup() {
   // Add your commands here, e.g.
-  // AddCommands(FooCommand(), BarCommand());
+  // AddCommands(FooCommand{}, BarCommand{});
 }
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/paralleldeadlinegroup/ReplaceMeParallelDeadlineGroup.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/paralleldeadlinegroup/ReplaceMeParallelDeadlineGroup.cpp
index 67c12a3..f664e55 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/paralleldeadlinegroup/ReplaceMeParallelDeadlineGroup.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/paralleldeadlinegroup/ReplaceMeParallelDeadlineGroup.cpp
@@ -10,9 +10,8 @@
 // For more information, see:
 // https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
 ReplaceMeParallelDeadlineGroup::ReplaceMeParallelDeadlineGroup()
-    : CommandHelper(
-          // The deadline command
-          frc2::InstantCommand([] {})) {
+    // The deadline command
+    : CommandHelper{frc2::InstantCommand{[] {}}} {
   // Add your commands here, e.g.
-  // AddCommands(FooCommand(), BarCommand());
+  // AddCommands(FooCommand{}, BarCommand{});
 }
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/parallelracegroup/ReplaceMeParallelRaceGroup.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/parallelracegroup/ReplaceMeParallelRaceGroup.cpp
index 9cc3784..f51433c 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/parallelracegroup/ReplaceMeParallelRaceGroup.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/parallelracegroup/ReplaceMeParallelRaceGroup.cpp
@@ -9,5 +9,5 @@
 // https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
 ReplaceMeParallelRaceGroup::ReplaceMeParallelRaceGroup() {
   // Add your commands here, e.g.
-  // AddCommands(FooCommand(), BarCommand());
+  // AddCommands(FooCommand{}, BarCommand{});
 }
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/pidcommand/ReplaceMePIDCommand.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/pidcommand/ReplaceMePIDCommand.cpp
index 1bcc830..4a7d0e1 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/pidcommand/ReplaceMePIDCommand.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/pidcommand/ReplaceMePIDCommand.cpp
@@ -8,16 +8,15 @@
 // For more information, see:
 // https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
 ReplaceMePIDCommand::ReplaceMePIDCommand()
-    : CommandHelper(
-          frc2::PIDController(0, 0, 0),
-          // This should return the measurement
-          [] { return 0; },
-          // This should return the setpoint (can also be a constant)
-          [] { return 0; },
-          // This uses the output
-          [](double output) {
-            // Use the output here
-          }) {}
+    : CommandHelper{frc2::PIDController{0, 0, 0},
+                    // This should return the measurement
+                    [] { return 0; },
+                    // This should return the setpoint (can also be a constant)
+                    [] { return 0; },
+                    // This uses the output
+                    [](double output) {
+                      // Use the output here
+                    }} {}
 
 // Returns true when the command should end.
 bool ReplaceMePIDCommand::IsFinished() {
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/pidsubsystem/ReplaceMePIDSubsystem.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/pidsubsystem/ReplaceMePIDSubsystem.cpp
deleted file mode 100644
index 7b44893..0000000
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/pidsubsystem/ReplaceMePIDSubsystem.cpp
+++ /dev/null
@@ -1,33 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "ReplaceMePIDSubsystem.h"
-
-#include <frc/livewindow/LiveWindow.h>
-#include <frc/smartdashboard/SmartDashboard.h>
-
-ReplaceMePIDSubsystem::ReplaceMePIDSubsystem()
-    : PIDSubsystem("ReplaceMePIDSubsystem", 1.0, 0.0, 0.0) {
-  // Use these to get going:
-  // SetSetpoint() -  Sets where the PID controller should move the system
-  //                  to
-  // Enable() - Enables the PID controller.
-}
-
-double ReplaceMePIDSubsystem::ReturnPIDInput() {
-  // Return your input value for the PID loop
-  // e.g. a sensor, like a potentiometer:
-  // yourPot->SetAverageVoltage() / kYourMaxVoltage;
-  return 0;
-}
-
-void ReplaceMePIDSubsystem::UsePIDOutput(double output) {
-  // Use output to drive your system, like a motor
-  // e.g. yourMotor->Set(output);
-}
-
-void ReplaceMePIDSubsystem::InitDefaultCommand() {
-  // Set the default command for a subsystem here.
-  // SetDefaultCommand(new MySpecialCommand());
-}
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/pidsubsystem/ReplaceMePIDSubsystem.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/pidsubsystem/ReplaceMePIDSubsystem.h
deleted file mode 100644
index f9aabc9..0000000
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/pidsubsystem/ReplaceMePIDSubsystem.h
+++ /dev/null
@@ -1,15 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <frc/commands/PIDSubsystem.h>
-
-class ReplaceMePIDSubsystem : public frc::PIDSubsystem {
- public:
-  ReplaceMePIDSubsystem();
-  double ReturnPIDInput() override;
-  void UsePIDOutput(double output) override;
-  void InitDefaultCommand() override;
-};
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/pidsubsystem2/ReplaceMePIDSubsystem2.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/pidsubsystem2/ReplaceMePIDSubsystem2.cpp
index 2cdce1b..749b106 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/pidsubsystem2/ReplaceMePIDSubsystem2.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/pidsubsystem2/ReplaceMePIDSubsystem2.cpp
@@ -5,9 +5,8 @@
 #include "ReplaceMePIDSubsystem2.h"
 
 ReplaceMePIDSubsystem2::ReplaceMePIDSubsystem2()
-    : PIDSubsystem(
-          // The PIDController used by the subsystem
-          frc2::PIDController(0, 0, 0)) {}
+    // The PIDController used by the subsystem
+    : PIDSubsystem{frc2::PIDController{0, 0, 0}} {}
 
 void ReplaceMePIDSubsystem2::UseOutput(double output, double setpoint) {
   // Use the output here
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/profiledpidcommand/ReplaceMeProfiledPIDCommand.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/profiledpidcommand/ReplaceMeProfiledPIDCommand.cpp
index 880a222..f3fd26a 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/profiledpidcommand/ReplaceMeProfiledPIDCommand.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/profiledpidcommand/ReplaceMeProfiledPIDCommand.cpp
@@ -11,13 +11,15 @@
 // For more information, see:
 // https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
 ReplaceMeProfiledPIDCommand::ReplaceMeProfiledPIDCommand()
-    : CommandHelper(
+    : CommandHelper{
           // The ProfiledPIDController that the command will use
-          frc::ProfiledPIDController<units::meters>(
+          frc::ProfiledPIDController<units::meters>{
               // The PID gains
-              0, 0, 0,
+              0,
+              0,
+              0,
               // The motion profile constraints
-              {0_mps, 0_mps_sq}),
+              {0_mps, 0_mps_sq}},
           // This should return the measurement
           [] { return 0_m; },
           // This should return the goal state (can also be a constant)
@@ -28,7 +30,7 @@
           [](double output,
              frc::TrapezoidProfile<units::meters>::State setpoint) {
             // Use the output and setpoint here
-          }) {}
+          }} {}
 
 // Returns true when the command should end.
 bool ReplaceMeProfiledPIDCommand::IsFinished() {
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/profiledpidsubsystem/ReplaceMeProfiledPIDSubsystem.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/profiledpidsubsystem/ReplaceMeProfiledPIDSubsystem.cpp
index d65a867..2ee899c 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/profiledpidsubsystem/ReplaceMeProfiledPIDSubsystem.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/profiledpidsubsystem/ReplaceMeProfiledPIDSubsystem.cpp
@@ -8,13 +8,14 @@
 #include <units/velocity.h>
 
 ReplaceMeProfiledPIDSubsystem::ReplaceMeProfiledPIDSubsystem()
-    : ProfiledPIDSubsystem(
-          // The ProfiledPIDController used by the subsystem
-          frc::ProfiledPIDController<units::meters>(
-              // The PID gains
-              0, 0, 0,
-              // The constraints for the motion profiles
-              {0_mps, 0_mps_sq})) {}
+    // The ProfiledPIDController used by the subsystem
+    : ProfiledPIDSubsystem{frc::ProfiledPIDController<units::meters>{
+          // The PID gains
+          0,
+          0,
+          0,
+          // The constraints for the motion profiles
+          {0_mps, 0_mps_sq}}} {}
 
 void ReplaceMeProfiledPIDSubsystem::UseOutput(
     double output, frc::TrapezoidProfile<units::meters>::State setpoint) {
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/sequentialcommandgroup/ReplaceMeSequentialCommandGroup.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/sequentialcommandgroup/ReplaceMeSequentialCommandGroup.cpp
index c83a99d..cc2504c 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/sequentialcommandgroup/ReplaceMeSequentialCommandGroup.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/sequentialcommandgroup/ReplaceMeSequentialCommandGroup.cpp
@@ -9,5 +9,5 @@
 // https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
 ReplaceMeSequentialCommandGroup::ReplaceMeSequentialCommandGroup() {
   // Add your commands here, e.g.
-  // AddCommands(FooCommand(), BarCommand());
+  // AddCommands(FooCommand{}, BarCommand{});
 }
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/subsystem/ReplaceMeSubsystem.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/subsystem/ReplaceMeSubsystem.cpp
deleted file mode 100644
index ca589f1..0000000
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/subsystem/ReplaceMeSubsystem.cpp
+++ /dev/null
@@ -1,15 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "ReplaceMeSubsystem.h"
-
-ReplaceMeSubsystem::ReplaceMeSubsystem() : Subsystem("ExampleSubsystem") {}
-
-void ReplaceMeSubsystem::InitDefaultCommand() {
-  // Set the default command for a subsystem here.
-  // SetDefaultCommand(new MySpecialCommand());
-}
-
-// Put methods for controlling this subsystem
-// here. Call these from Commands.
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/subsystem/ReplaceMeSubsystem.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/subsystem/ReplaceMeSubsystem.h
deleted file mode 100644
index 3de6031..0000000
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/subsystem/ReplaceMeSubsystem.h
+++ /dev/null
@@ -1,17 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <frc/commands/Subsystem.h>
-
-class ReplaceMeSubsystem : public frc::Subsystem {
- private:
-  // It's desirable that everything possible under private except
-  // for methods that implement subsystem capabilities
-
- public:
-  ReplaceMeSubsystem();
-  void InitDefaultCommand() override;
-};
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/timed/ReplaceMeTimedCommand.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/timed/ReplaceMeTimedCommand.cpp
deleted file mode 100644
index c6793e0..0000000
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/timed/ReplaceMeTimedCommand.cpp
+++ /dev/null
@@ -1,24 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "ReplaceMeTimedCommand.h"
-
-ReplaceMeTimedCommand::ReplaceMeTimedCommand(units::second_t timeout)
-    : TimedCommand(timeout) {
-  // Use Requires() here to declare subsystem dependencies
-  // eg. Requires(Robot::chassis.get());
-}
-
-// Called just before this Command runs the first time
-void ReplaceMeTimedCommand::Initialize() {}
-
-// Called repeatedly when this Command is scheduled to run
-void ReplaceMeTimedCommand::Execute() {}
-
-// Called once after command times out
-void ReplaceMeTimedCommand::End() {}
-
-// Called when another command which requires one or more of the same
-// subsystems is scheduled to run
-void ReplaceMeTimedCommand::Interrupted() {}
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/timed/ReplaceMeTimedCommand.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/timed/ReplaceMeTimedCommand.h
deleted file mode 100644
index 48cfa2d..0000000
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/timed/ReplaceMeTimedCommand.h
+++ /dev/null
@@ -1,17 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <frc/commands/TimedCommand.h>
-#include <units/time.h>
-
-class ReplaceMeTimedCommand : public frc::TimedCommand {
- public:
-  explicit ReplaceMeTimedCommand(units::second_t timeout);
-  void Initialize() override;
-  void Execute() override;
-  void End() override;
-  void Interrupted() override;
-};
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/trigger/ReplaceMeTrigger.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/trigger/ReplaceMeTrigger.cpp
deleted file mode 100644
index 3c563ff..0000000
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/trigger/ReplaceMeTrigger.cpp
+++ /dev/null
@@ -1,11 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "ReplaceMeTrigger.h"
-
-ReplaceMeTrigger::ReplaceMeTrigger() = default;
-
-bool ReplaceMeTrigger::Get() {
-  return false;
-}
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/trigger/ReplaceMeTrigger.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/trigger/ReplaceMeTrigger.h
deleted file mode 100644
index a76dcd9..0000000
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/commands/trigger/ReplaceMeTrigger.h
+++ /dev/null
@@ -1,13 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <frc/buttons/Trigger.h>
-
-class ReplaceMeTrigger : public frc::Trigger {
- public:
-  ReplaceMeTrigger();
-  bool Get() override;
-};
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/AddressableLED/cpp/Robot.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/AddressableLED/cpp/Robot.cpp
index d59b370..d3356c6 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/AddressableLED/cpp/Robot.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/AddressableLED/cpp/Robot.cpp
@@ -2,54 +2,37 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
-#include <array>
+#include "Robot.h"
 
-#include <frc/AddressableLED.h>
-#include <frc/TimedRobot.h>
-#include <frc/smartdashboard/SmartDashboard.h>
+void Robot::RobotInit() {
+  // Default to a length of 60, start empty output
+  // Length is expensive to set, so only set it once, then just update data
+  m_led.SetLength(kLength);
+  m_led.SetData(m_ledBuffer);
+  m_led.Start();
+}
 
-class Robot : public frc::TimedRobot {
-  static constexpr int kLength = 60;
+void Robot::RobotPeriodic() {
+  // Fill the buffer with a rainbow
+  Rainbow();
+  // Set the LEDs
+  m_led.SetData(m_ledBuffer);
+}
 
-  // PWM port 9
-  // Must be a PWM header, not MXP or DIO
-  frc::AddressableLED m_led{9};
-  std::array<frc::AddressableLED::LEDData, kLength>
-      m_ledBuffer;  // Reuse the buffer
-  // Store what the last hue of the first pixel is
-  int firstPixelHue = 0;
-
- public:
-  void Rainbow() {
-    // For every pixel
-    for (int i = 0; i < kLength; i++) {
-      // Calculate the hue - hue is easier for rainbows because the color
-      // shape is a circle so only one value needs to precess
-      const auto pixelHue = (firstPixelHue + (i * 180 / kLength)) % 180;
-      // Set the value
-      m_ledBuffer[i].SetHSV(pixelHue, 255, 128);
-    }
-    // Increase by to make the rainbow "move"
-    firstPixelHue += 3;
-    // Check bounds
-    firstPixelHue %= 180;
+void Robot::Rainbow() {
+  // For every pixel
+  for (int i = 0; i < kLength; i++) {
+    // Calculate the hue - hue is easier for rainbows because the color
+    // shape is a circle so only one value needs to precess
+    const auto pixelHue = (firstPixelHue + (i * 180 / kLength)) % 180;
+    // Set the value
+    m_ledBuffer[i].SetHSV(pixelHue, 255, 128);
   }
-
-  void RobotInit() override {
-    // Default to a length of 60, start empty output
-    // Length is expensive to set, so only set it once, then just update data
-    m_led.SetLength(kLength);
-    m_led.SetData(m_ledBuffer);
-    m_led.Start();
-  }
-
-  void RobotPeriodic() override {
-    // Fill the buffer with a rainbow
-    Rainbow();
-    // Set the LEDs
-    m_led.SetData(m_ledBuffer);
-  }
-};
+  // Increase by to make the rainbow "move"
+  firstPixelHue += 3;
+  // Check bounds
+  firstPixelHue %= 180;
+}
 
 #ifndef RUNNING_FRC_TESTS
 int main() {
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/AddressableLED/include/Robot.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/AddressableLED/include/Robot.h
new file mode 100644
index 0000000..77090b6
--- /dev/null
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/AddressableLED/include/Robot.h
@@ -0,0 +1,28 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <array>
+
+#include <frc/AddressableLED.h>
+#include <frc/TimedRobot.h>
+
+class Robot : public frc::TimedRobot {
+ public:
+  void Rainbow();
+  void RobotInit() override;
+  void RobotPeriodic() override;
+
+ private:
+  static constexpr int kLength = 60;
+
+  // PWM port 9
+  // Must be a PWM header, not MXP or DIO
+  frc::AddressableLED m_led{9};
+  std::array<frc::AddressableLED::LEDData, kLength>
+      m_ledBuffer;  // Reuse the buffer
+  // Store what the last hue of the first pixel is
+  int firstPixelHue = 0;
+};
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp
index e346e41..b636b44 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp
@@ -27,7 +27,7 @@
 
   void TeleopPeriodic() override {
     // Drive with arcade style
-    m_robotDrive.ArcadeDrive(-m_stick.GetY(), m_stick.GetX());
+    m_robotDrive.ArcadeDrive(-m_stick.GetY(), -m_stick.GetX());
   }
 };
 
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArcadeDriveXboxController/cpp/Robot.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArcadeDriveXboxController/cpp/Robot.cpp
index 7f497b3..23c9a56 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArcadeDriveXboxController/cpp/Robot.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArcadeDriveXboxController/cpp/Robot.cpp
@@ -30,7 +30,7 @@
     // That means that the Y axis of the left stick moves forward
     // and backward, and the X of the right stick turns left and right.
     m_robotDrive.ArcadeDrive(-m_driverController.GetLeftY(),
-                             m_driverController.GetRightX());
+                             -m_driverController.GetRightX());
   }
 };
 
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/RobotContainer.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/RobotContainer.cpp
index 158945e..90aa789 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/RobotContainer.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/RobotContainer.cpp
@@ -5,9 +5,13 @@
 #include "RobotContainer.h"
 
 #include <frc/shuffleboard/Shuffleboard.h>
+#include <frc2/command/Commands.h>
+#include <frc2/command/InstantCommand.h>
 #include <frc2/command/button/JoystickButton.h>
 #include <units/angle.h>
 
+namespace ac = AutoConstants;
+
 RobotContainer::RobotContainer() {
   // Initialize all of your commands and subsystems here
 
@@ -15,10 +19,10 @@
   ConfigureButtonBindings();
 
   // Set up default drive command
-  m_drive.SetDefaultCommand(frc2::RunCommand(
+  m_drive.SetDefaultCommand(frc2::cmd::Run(
       [this] {
         m_drive.ArcadeDrive(-m_driverController.GetLeftY(),
-                            m_driverController.GetRightX());
+                            -m_driverController.GetRightX());
       },
       {&m_drive}));
 }
@@ -27,32 +31,29 @@
   // Configure your button bindings here
 
   // Move the arm to 2 radians above horizontal when the 'A' button is pressed.
-  frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kA)
-      .WhenPressed(
-          [this] {
-            m_arm.SetGoal(2_rad);
-            m_arm.Enable();
-          },
-          {&m_arm});
+  m_driverController.A().OnTrue(frc2::cmd::RunOnce(
+      [this] {
+        m_arm.SetGoal(2_rad);
+        m_arm.Enable();
+      },
+      {&m_arm}));
 
   // Move the arm to neutral position when the 'B' button is pressed.
-  frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kB)
-      .WhenPressed(
-          [this] {
-            m_arm.SetGoal(ArmConstants::kArmOffset);
-            m_arm.Enable();
-          },
-          {&m_arm});
+  m_driverController.B().OnTrue(frc2::cmd::RunOnce(
+      [this] {
+        m_arm.SetGoal(ArmConstants::kArmOffset);
+        m_arm.Enable();
+      },
+      {&m_arm}));
 
   // Disable the arm controller when Y is pressed.
-  frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kY)
-      .WhenPressed([this] { m_arm.Disable(); }, {&m_arm});
+  m_driverController.Y().OnTrue(
+      frc2::cmd::RunOnce([this] { m_arm.Disable(); }, {&m_arm}));
 
   // While holding the shoulder button, drive at half speed
-  frc2::JoystickButton(&m_driverController,
-                       frc::XboxController::Button::kRightBumper)
-      .WhenPressed([this] { m_drive.SetMaxOutput(0.5); })
-      .WhenReleased([this] { m_drive.SetMaxOutput(1); });
+  m_driverController.RightBumper()
+      .OnTrue(frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(0.5); }))
+      .OnFalse(frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(1.0); }));
 }
 
 void RobotContainer::DisablePIDSubsystems() {
@@ -60,6 +61,5 @@
 }
 
 frc2::Command* RobotContainer::GetAutonomousCommand() {
-  // Runs the chosen command in autonomous
-  return new frc2::InstantCommand([] {});
+  return nullptr;
 }
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/subsystems/ArmSubsystem.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/subsystems/ArmSubsystem.cpp
index c5fb3b2..6d5eab6 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/subsystems/ArmSubsystem.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/subsystems/ArmSubsystem.cpp
@@ -26,9 +26,9 @@
   units::volt_t feedforward =
       m_feedforward.Calculate(setpoint.position, setpoint.velocity);
   // Add the feedforward to the PID output to get the motor output
-  m_motor.SetVoltage(units::volt_t(output) + feedforward);
+  m_motor.SetVoltage(units::volt_t{output} + feedforward);
 }
 
 units::radian_t ArmSubsystem::GetMeasurement() {
-  return units::radian_t(m_encoder.GetDistance()) + kArmOffset;
+  return units::radian_t{m_encoder.GetDistance()} + kArmOffset;
 }
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBot/include/Constants.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBot/include/Constants.h
index bd432ee..cff3932 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBot/include/Constants.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBot/include/Constants.h
@@ -4,11 +4,12 @@
 
 #pragma once
 
+#include <numbers>
+
 #include <units/angle.h>
 #include <units/angular_velocity.h>
 #include <units/time.h>
 #include <units/voltage.h>
-#include <wpi/numbers>
 
 /**
  * The Constants header provides a convenient place for teams to hold robot-wide
@@ -34,7 +35,7 @@
 constexpr double kWheelDiameterInches = 6;
 constexpr double kEncoderDistancePerPulse =
     // Assumes the encoders are directly mounted on the wheel shafts
-    (kWheelDiameterInches * wpi::numbers::pi) /
+    (kWheelDiameterInches * std::numbers::pi) /
     static_cast<double>(kEncoderCPR);
 }  // namespace DriveConstants
 
@@ -56,7 +57,7 @@
 constexpr int kEncoderPorts[]{4, 5};
 constexpr int kEncoderPPR = 256;
 constexpr auto kEncoderDistancePerPulse =
-    2.0_rad * wpi::numbers::pi / kEncoderPPR;
+    2.0_rad * std::numbers::pi / kEncoderPPR;
 
 // The offset of the arm from the horizontal in its neutral position,
 // measured from the horizontal
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBot/include/RobotContainer.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBot/include/RobotContainer.h
index 782207b..67d194c 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBot/include/RobotContainer.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBot/include/RobotContainer.h
@@ -4,23 +4,13 @@
 
 #pragma once
 
-#include <frc/XboxController.h>
-#include <frc/smartdashboard/SendableChooser.h>
 #include <frc2/command/Command.h>
-#include <frc2/command/ConditionalCommand.h>
-#include <frc2/command/InstantCommand.h>
-#include <frc2/command/ParallelRaceGroup.h>
-#include <frc2/command/RunCommand.h>
-#include <frc2/command/SequentialCommandGroup.h>
-#include <frc2/command/WaitCommand.h>
-#include <frc2/command/WaitUntilCommand.h>
+#include <frc2/command/button/CommandXboxController.h>
 
 #include "Constants.h"
 #include "subsystems/ArmSubsystem.h"
 #include "subsystems/DriveSubsystem.h"
 
-namespace ac = AutoConstants;
-
 /**
  * This class is where the bulk of the robot should be declared.  Since
  * Command-based is a "declarative" paradigm, very little robot logic should
@@ -42,7 +32,8 @@
 
  private:
   // The driver's controller
-  frc::XboxController m_driverController{OIConstants::kDriverControllerPort};
+  frc2::CommandXboxController m_driverController{
+      OIConstants::kDriverControllerPort};
 
   // The robot's subsystems and commands are defined here...
 
@@ -50,7 +41,5 @@
   DriveSubsystem m_drive;
   ArmSubsystem m_arm;
 
-  // The chooser for the autonomous routines
-
   void ConfigureButtonBindings();
 };
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/RobotContainer.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/RobotContainer.cpp
index 1f6a138..dce4b95 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/RobotContainer.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/RobotContainer.cpp
@@ -4,8 +4,6 @@
 
 #include "RobotContainer.h"
 
-#include <frc/shuffleboard/Shuffleboard.h>
-#include <frc2/command/button/JoystickButton.h>
 #include <units/angle.h>
 
 RobotContainer::RobotContainer() {
@@ -15,34 +13,27 @@
   ConfigureButtonBindings();
 
   // Set up default drive command
-  m_drive.SetDefaultCommand(frc2::RunCommand(
-      [this] {
-        m_drive.ArcadeDrive(-m_driverController.GetLeftY(),
-                            m_driverController.GetRightX());
-      },
-      {&m_drive}));
+  m_drive.SetDefaultCommand(m_drive.ArcadeDriveCommand(
+      [this] { return -m_driverController.GetLeftY(); },
+      [this] { return -m_driverController.GetRightX(); }));
 }
 
 void RobotContainer::ConfigureButtonBindings() {
   // Configure your button bindings here
 
   // Move the arm to 2 radians above horizontal when the 'A' button is pressed.
-  frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kA)
-      .WhenPressed([this] { m_arm.SetGoal(2_rad); }, {&m_arm});
+  m_driverController.A().OnTrue(m_arm.SetArmGoalCommand(2_rad));
 
   // Move the arm to neutral position when the 'B' button is pressed.
-  frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kB)
-      .WhenPressed([this] { m_arm.SetGoal(ArmConstants::kArmOffset); },
-                   {&m_arm});
+  m_driverController.B().OnTrue(
+      m_arm.SetArmGoalCommand(ArmConstants::kArmOffset));
 
   // While holding the shoulder button, drive at half speed
-  frc2::JoystickButton(&m_driverController,
-                       frc::XboxController::Button::kRightBumper)
-      .WhenPressed([this] { m_drive.SetMaxOutput(0.5); })
-      .WhenReleased([this] { m_drive.SetMaxOutput(1); });
+  m_driverController.RightBumper()
+      .OnTrue(m_drive.SetMaxOutputCommand(0.5))
+      .OnFalse(m_drive.SetMaxOutputCommand(1.0));
 }
 
 frc2::Command* RobotContainer::GetAutonomousCommand() {
-  // Runs the chosen command in autonomous
-  return new frc2::InstantCommand([] {});
+  return nullptr;
 }
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/subsystems/ArmSubsystem.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/subsystems/ArmSubsystem.cpp
index 7557b5a..5603c68 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/subsystems/ArmSubsystem.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/subsystems/ArmSubsystem.cpp
@@ -25,3 +25,7 @@
   m_motor.SetSetpoint(ExampleSmartMotorController::PIDMode::kPosition,
                       setpoint.position.value(), feedforward / 12_V);
 }
+
+frc2::CommandPtr ArmSubsystem::SetArmGoalCommand(units::radian_t goal) {
+  return frc2::cmd::RunOnce([this, goal] { this->SetGoal(goal); }, {this});
+}
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/subsystems/DriveSubsystem.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/subsystems/DriveSubsystem.cpp
index fac0df9..16409ad 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/subsystems/DriveSubsystem.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/subsystems/DriveSubsystem.cpp
@@ -26,10 +26,6 @@
   // Implementation of subsystem periodic method goes here.
 }
 
-void DriveSubsystem::ArcadeDrive(double fwd, double rot) {
-  m_drive.ArcadeDrive(fwd, rot);
-}
-
 void DriveSubsystem::ResetEncoders() {
   m_leftEncoder.Reset();
   m_rightEncoder.Reset();
@@ -47,6 +43,16 @@
   return m_rightEncoder;
 }
 
-void DriveSubsystem::SetMaxOutput(double maxOutput) {
-  m_drive.SetMaxOutput(maxOutput);
+frc2::CommandPtr DriveSubsystem::SetMaxOutputCommand(double maxOutput) {
+  return frc2::cmd::RunOnce(
+      [this, maxOutput] { m_drive.SetMaxOutput(maxOutput); });
+}
+
+frc2::CommandPtr DriveSubsystem::ArcadeDriveCommand(
+    std::function<double()> fwd, std::function<double()> rot) {
+  return frc2::cmd::Run(
+      [this, fwd = std::move(fwd), rot = std::move(rot)] {
+        m_drive.ArcadeDrive(fwd(), rot());
+      },
+      {this});
 }
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/Constants.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/Constants.h
index bd432ee..cff3932 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/Constants.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/Constants.h
@@ -4,11 +4,12 @@
 
 #pragma once
 
+#include <numbers>
+
 #include <units/angle.h>
 #include <units/angular_velocity.h>
 #include <units/time.h>
 #include <units/voltage.h>
-#include <wpi/numbers>
 
 /**
  * The Constants header provides a convenient place for teams to hold robot-wide
@@ -34,7 +35,7 @@
 constexpr double kWheelDiameterInches = 6;
 constexpr double kEncoderDistancePerPulse =
     // Assumes the encoders are directly mounted on the wheel shafts
-    (kWheelDiameterInches * wpi::numbers::pi) /
+    (kWheelDiameterInches * std::numbers::pi) /
     static_cast<double>(kEncoderCPR);
 }  // namespace DriveConstants
 
@@ -56,7 +57,7 @@
 constexpr int kEncoderPorts[]{4, 5};
 constexpr int kEncoderPPR = 256;
 constexpr auto kEncoderDistancePerPulse =
-    2.0_rad * wpi::numbers::pi / kEncoderPPR;
+    2.0_rad * std::numbers::pi / kEncoderPPR;
 
 // The offset of the arm from the horizontal in its neutral position,
 // measured from the horizontal
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/RobotContainer.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/RobotContainer.h
index 5aba470..08a4dbe 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/RobotContainer.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/RobotContainer.h
@@ -4,16 +4,8 @@
 
 #pragma once
 
-#include <frc/XboxController.h>
-#include <frc/smartdashboard/SendableChooser.h>
 #include <frc2/command/Command.h>
-#include <frc2/command/ConditionalCommand.h>
-#include <frc2/command/InstantCommand.h>
-#include <frc2/command/ParallelRaceGroup.h>
-#include <frc2/command/RunCommand.h>
-#include <frc2/command/SequentialCommandGroup.h>
-#include <frc2/command/WaitCommand.h>
-#include <frc2/command/WaitUntilCommand.h>
+#include <frc2/command/button/CommandXboxController.h>
 
 #include "Constants.h"
 #include "subsystems/ArmSubsystem.h"
@@ -36,7 +28,8 @@
 
  private:
   // The driver's controller
-  frc::XboxController m_driverController{OIConstants::kDriverControllerPort};
+  frc2::CommandXboxController m_driverController{
+      OIConstants::kDriverControllerPort};
 
   // The robot's subsystems and commands are defined here...
 
@@ -44,7 +37,5 @@
   DriveSubsystem m_drive;
   ArmSubsystem m_arm;
 
-  // The chooser for the autonomous routines
-
   void ConfigureButtonBindings();
 };
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/subsystems/ArmSubsystem.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/subsystems/ArmSubsystem.h
index 1fb5b87..ea2dc64 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/subsystems/ArmSubsystem.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/subsystems/ArmSubsystem.h
@@ -5,6 +5,7 @@
 #pragma once
 
 #include <frc/controller/ArmFeedforward.h>
+#include <frc2/command/Commands.h>
 #include <frc2/command/TrapezoidProfileSubsystem.h>
 #include <units/angle.h>
 
@@ -21,6 +22,8 @@
 
   void UseState(State setpoint) override;
 
+  frc2::CommandPtr SetArmGoalCommand(units::radian_t goal);
+
  private:
   ExampleSmartMotorController m_motor;
   frc::ArmFeedforward m_feedforward;
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/subsystems/DriveSubsystem.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/subsystems/DriveSubsystem.h
index 47bf28e..6830b96 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/subsystems/DriveSubsystem.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/subsystems/DriveSubsystem.h
@@ -4,10 +4,13 @@
 
 #pragma once
 
+#include <functional>
+
 #include <frc/Encoder.h>
 #include <frc/drive/DifferentialDrive.h>
 #include <frc/motorcontrol/MotorControllerGroup.h>
 #include <frc/motorcontrol/PWMSparkMax.h>
+#include <frc2/command/Commands.h>
 #include <frc2/command/SubsystemBase.h>
 
 #include "Constants.h"
@@ -24,14 +27,6 @@
   // Subsystem methods go here.
 
   /**
-   * Drives the robot using arcade controls.
-   *
-   * @param fwd the commanded forward movement
-   * @param rot the commanded rotation
-   */
-  void ArcadeDrive(double fwd, double rot);
-
-  /**
    * Resets the drive encoders to currently read a position of 0.
    */
   void ResetEncoders();
@@ -63,7 +58,10 @@
    *
    * @param maxOutput the maximum output to which the drive will be constrained
    */
-  void SetMaxOutput(double maxOutput);
+  frc2::CommandPtr SetMaxOutputCommand(double maxOutput);
+
+  frc2::CommandPtr ArcadeDriveCommand(std::function<double()> fwd,
+                                      std::function<double()> rot);
 
  private:
   // Components (e.g. motor controllers and sensors) should generally be
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmSimulation/cpp/Robot.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmSimulation/cpp/Robot.cpp
index 330ddc4..2027d25 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmSimulation/cpp/Robot.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ArmSimulation/cpp/Robot.cpp
@@ -2,6 +2,8 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
+#include <numbers>
+
 #include <frc/Encoder.h>
 #include <frc/Joystick.h>
 #include <frc/Preferences.h>
@@ -22,7 +24,6 @@
 #include <frc/util/Color8Bit.h>
 #include <units/angle.h>
 #include <units/moment_of_inertia.h>
-#include <wpi/numbers>
 
 /**
  * This is a sample program to demonstrate how to use a state-space controller
@@ -45,7 +46,7 @@
   // distance per pulse = (angle per revolution) / (pulses per revolution)
   //  = (2 * PI rads) / (4096 pulses)
   static constexpr double kArmEncoderDistPerPulse =
-      2.0 * wpi::numbers::pi / 4096.0;
+      2.0 * std::numbers::pi / 4096.0;
 
   // The arm gearbox represents a gearbox containing two Vex 775pro motors.
   frc::DCMotor m_armGearbox = frc::DCMotor::Vex775Pro(2);
@@ -101,8 +102,8 @@
   void SimulationPeriodic() override {
     // In this method, we update our simulation of what our arm is doing
     // First, we set our "inputs" (voltages)
-    m_armSim.SetInput(Eigen::Vector<double, 1>{
-        m_motor.Get() * frc::RobotController::GetInputVoltage()});
+    m_armSim.SetInput(frc::Vectord<1>{m_motor.Get() *
+                                      frc::RobotController::GetInputVoltage()});
 
     // Next, we update it. The standard loop time is 20ms.
     m_armSim.Update(20_ms);
@@ -120,8 +121,8 @@
 
   void TeleopInit() override {
     // Read Preferences for Arm setpoint and kP on entering Teleop
-    armPosition = units::degree_t(
-        frc::Preferences::GetDouble(kArmPositionKey, armPosition.value()));
+    armPosition = units::degree_t{
+        frc::Preferences::GetDouble(kArmPositionKey, armPosition.value())};
     if (kArmKp != frc::Preferences::GetDouble(kArmPKey, kArmKp)) {
       kArmKp = frc::Preferences::GetDouble(kArmPKey, kArmKp);
       m_controller.SetP(kArmKp);
@@ -133,8 +134,8 @@
       // Here, we run PID control like normal, with a setpoint read from
       // preferences in degrees.
       double pidOutput = m_controller.Calculate(
-          m_encoder.GetDistance(), (units::radian_t(armPosition).value()));
-      m_motor.SetVoltage(units::volt_t(pidOutput));
+          m_encoder.GetDistance(), (units::radian_t{armPosition}.value()));
+      m_motor.SetVoltage(units::volt_t{pidOutput});
     } else {
       // Otherwise, we disable the motor.
       m_motor.Set(0.0);
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/CANPDP/cpp/Robot.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/CANPDP/cpp/Robot.cpp
index aed898f..95a9a0d 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/CANPDP/cpp/Robot.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/CANPDP/cpp/Robot.cpp
@@ -13,20 +13,40 @@
  */
 class Robot : public frc::TimedRobot {
  public:
-  void TeleopPeriodic() override {
-    /* Get the current going through channel 7, in Amperes. The PDP returns the
-     * current in increments of 0.125A. At low currents the current readings
-     * tend to be less accurate.
-     */
-    frc::SmartDashboard::PutNumber("Current Channel 7", m_pdp.GetCurrent(7));
+  void RobotInit() override {
+    // Put the PDP itself to the dashboard
+    frc::SmartDashboard::PutData("PDP", &m_pdp);
+  }
 
-    /* Get the voltage going into the PDP, in Volts. The PDP returns the voltage
-     * in increments of 0.05 Volts.
-     */
-    frc::SmartDashboard::PutNumber("Voltage", m_pdp.GetVoltage());
+  void RobotPeriodic() override {
+    // Get the current going through channel 7, in Amperes.
+    // The PDP returns the current in increments of 0.125A.
+    // At low currents the current readings tend to be less accurate.
+    double current7 = m_pdp.GetCurrent(7);
+    frc::SmartDashboard::PutNumber("Current Channel 7", current7);
+
+    // Get the voltage going into the PDP, in Volts.
+    // The PDP returns the voltage in increments of 0.05 Volts.
+    double voltage = m_pdp.GetVoltage();
+    frc::SmartDashboard::PutNumber("Voltage", voltage);
 
     // Retrieves the temperature of the PDP, in degrees Celsius.
-    frc::SmartDashboard::PutNumber("Temperature", m_pdp.GetTemperature());
+    double temperatureCelsius = m_pdp.GetTemperature();
+    frc::SmartDashboard::PutNumber("Temperature", temperatureCelsius);
+
+    // Get the total current of all channels.
+    double totalCurrent = m_pdp.GetTotalCurrent();
+    frc::SmartDashboard::PutNumber("Total Current", totalCurrent);
+
+    // Get the total power of all channels.
+    // Power is the bus voltage multiplied by the current with the units Watts.
+    double totalPower = m_pdp.GetTotalPower();
+    frc::SmartDashboard::PutNumber("Total Power", totalPower);
+
+    // Get the total energy of all channels.
+    // Energy is the power summed over time with units Joules.
+    double totalEnergy = m_pdp.GetTotalEnergy();
+    frc::SmartDashboard::PutNumber("Total Energy", totalEnergy);
   }
 
  private:
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/cpp/Drivetrain.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/cpp/Drivetrain.cpp
index da638d5..cc7db7b 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/cpp/Drivetrain.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/cpp/Drivetrain.cpp
@@ -23,6 +23,6 @@
 
 void Drivetrain::UpdateOdometry() {
   m_odometry.Update(m_gyro.GetRotation2d(),
-                    units::meter_t(m_leftEncoder.GetDistance()),
-                    units::meter_t(m_rightEncoder.GetDistance()));
+                    units::meter_t{m_leftEncoder.GetDistance()},
+                    units::meter_t{m_rightEncoder.GetDistance()});
 }
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/include/Drivetrain.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/include/Drivetrain.h
index 81d0a71..b4ad1db 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/include/Drivetrain.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/include/Drivetrain.h
@@ -4,6 +4,8 @@
 
 #pragma once
 
+#include <numbers>
+
 #include <frc/AnalogGyro.h>
 #include <frc/Encoder.h>
 #include <frc/controller/PIDController.h>
@@ -16,7 +18,6 @@
 #include <units/angular_velocity.h>
 #include <units/length.h>
 #include <units/velocity.h>
-#include <wpi/numbers>
 
 /**
  * Represents a differential drive style drivetrain.
@@ -33,9 +34,9 @@
     // Set the distance per pulse for the drive encoders. We can simply use the
     // distance traveled for one rotation of the wheel divided by the encoder
     // resolution.
-    m_leftEncoder.SetDistancePerPulse(2 * wpi::numbers::pi * kWheelRadius /
+    m_leftEncoder.SetDistancePerPulse(2 * std::numbers::pi * kWheelRadius /
                                       kEncoderResolution);
-    m_rightEncoder.SetDistancePerPulse(2 * wpi::numbers::pi * kWheelRadius /
+    m_rightEncoder.SetDistancePerPulse(2 * std::numbers::pi * kWheelRadius /
                                        kEncoderResolution);
 
     m_leftEncoder.Reset();
@@ -45,7 +46,7 @@
   static constexpr units::meters_per_second_t kMaxSpeed =
       3.0_mps;  // 3 meters per second
   static constexpr units::radians_per_second_t kMaxAngularSpeed{
-      wpi::numbers::pi};  // 1/2 rotation per second
+      std::numbers::pi};  // 1/2 rotation per second
 
   void SetSpeeds(const frc::DifferentialDriveWheelSpeeds& speeds);
   void Drive(units::meters_per_second_t xSpeed,
@@ -74,7 +75,9 @@
   frc::AnalogGyro m_gyro{0};
 
   frc::DifferentialDriveKinematics m_kinematics{kTrackWidth};
-  frc::DifferentialDriveOdometry m_odometry{m_gyro.GetRotation2d()};
+  frc::DifferentialDriveOdometry m_odometry{
+      m_gyro.GetRotation2d(), units::meter_t{m_leftEncoder.GetDistance()},
+      units::meter_t{m_rightEncoder.GetDistance()}};
 
   // Gains are for example purposes only - must be determined for your own
   // robot!
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/cpp/Drivetrain.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/cpp/Drivetrain.cpp
index 1ed0e46..866d62d 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/cpp/Drivetrain.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/cpp/Drivetrain.cpp
@@ -27,10 +27,8 @@
 
 void Drivetrain::UpdateOdometry() {
   m_poseEstimator.Update(m_gyro.GetRotation2d(),
-                         {units::meters_per_second_t(m_leftEncoder.GetRate()),
-                          units::meters_per_second_t(m_rightEncoder.GetRate())},
-                         units::meter_t(m_leftEncoder.GetDistance()),
-                         units::meter_t(m_rightEncoder.GetDistance()));
+                         units::meter_t{m_leftEncoder.GetDistance()},
+                         units::meter_t{m_rightEncoder.GetDistance()});
 
   // Also apply vision measurements. We use 0.3 seconds in the past as an
   // example -- on a real robot, this must be calculated based either on latency
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/Drivetrain.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/Drivetrain.h
index dfb57a6..3001763 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/Drivetrain.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/Drivetrain.h
@@ -4,6 +4,8 @@
 
 #pragma once
 
+#include <numbers>
+
 #include <frc/AnalogGyro.h>
 #include <frc/Encoder.h>
 #include <frc/controller/PIDController.h>
@@ -16,7 +18,6 @@
 #include <units/angular_velocity.h>
 #include <units/length.h>
 #include <units/velocity.h>
-#include <wpi/numbers>
 
 /**
  * Represents a differential drive style drivetrain.
@@ -34,9 +35,9 @@
     // distance traveled for one rotation of the wheel divided by the encoder
     // resolution.
     m_leftEncoder.SetDistancePerPulse(
-        2 * wpi::numbers::pi * kWheelRadius.value() / kEncoderResolution);
+        2 * std::numbers::pi * kWheelRadius.value() / kEncoderResolution);
     m_rightEncoder.SetDistancePerPulse(
-        2 * wpi::numbers::pi * kWheelRadius.value() / kEncoderResolution);
+        2 * std::numbers::pi * kWheelRadius.value() / kEncoderResolution);
 
     m_leftEncoder.Reset();
     m_rightEncoder.Reset();
@@ -45,7 +46,7 @@
   static constexpr units::meters_per_second_t kMaxSpeed =
       3.0_mps;  // 3 meters per second
   static constexpr units::radians_per_second_t kMaxAngularSpeed{
-      wpi::numbers::pi};  // 1/2 rotation per second
+      std::numbers::pi};  // 1/2 rotation per second
 
   void SetSpeeds(const frc::DifferentialDriveWheelSpeeds& speeds);
   void Drive(units::meters_per_second_t xSpeed,
@@ -78,10 +79,12 @@
   // Gains are for example purposes only - must be determined for your own
   // robot!
   frc::DifferentialDrivePoseEstimator m_poseEstimator{
-      frc::Rotation2d(),
-      frc::Pose2d(),
-      {0.01, 0.01, 0.01, 0.01, 0.01},
-      {0.1, 0.1, 0.1},
+      m_kinematics,
+      m_gyro.GetRotation2d(),
+      units::meter_t{m_leftEncoder.GetDistance()},
+      units::meter_t{m_rightEncoder.GetDistance()},
+      frc::Pose2d{},
+      {0.01, 0.01, 0.01},
       {0.1, 0.1, 0.1}};
 
   // Gains are for example purposes only - must be determined for your own
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/ExampleGlobalMeasurementSensor.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/ExampleGlobalMeasurementSensor.h
index 4697938..b9e2ba4 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/ExampleGlobalMeasurementSensor.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/ExampleGlobalMeasurementSensor.h
@@ -16,9 +16,9 @@
   static frc::Pose2d GetEstimatedGlobalPose(
       const frc::Pose2d& estimatedRobotPose) {
     auto randVec = frc::MakeWhiteNoiseVector(0.1, 0.1, 0.1);
-    return frc::Pose2d(estimatedRobotPose.X() + units::meter_t(randVec(0)),
-                       estimatedRobotPose.Y() + units::meter_t(randVec(1)),
+    return frc::Pose2d{estimatedRobotPose.X() + units::meter_t{randVec(0)},
+                       estimatedRobotPose.Y() + units::meter_t{randVec(1)},
                        estimatedRobotPose.Rotation() +
-                           frc::Rotation2d(units::radian_t(randVec(2))));
+                           frc::Rotation2d{units::radian_t{randVec(2)}}};
   }
 };
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/RobotContainer.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/RobotContainer.cpp
index bc940cd..8c2423b 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/RobotContainer.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/RobotContainer.cpp
@@ -4,9 +4,6 @@
 
 #include "RobotContainer.h"
 
-#include <frc/shuffleboard/Shuffleboard.h>
-#include <frc2/command/button/JoystickButton.h>
-
 #include "commands/DriveDistanceProfiled.h"
 
 RobotContainer::RobotContainer() {
@@ -16,10 +13,10 @@
   ConfigureButtonBindings();
 
   // Set up default drive command
-  m_drive.SetDefaultCommand(frc2::RunCommand(
+  m_drive.SetDefaultCommand(frc2::cmd::Run(
       [this] {
         m_drive.ArcadeDrive(-m_driverController.GetLeftY(),
-                            m_driverController.GetRightX());
+                            -m_driverController.GetRightX());
       },
       {&m_drive}));
 }
@@ -28,37 +25,38 @@
   // Configure your button bindings here
 
   // While holding the shoulder button, drive at half speed
-  frc2::JoystickButton(&m_driverController,
-                       frc::XboxController::Button::kRightBumper)
-      .WhenPressed(&m_driveHalfSpeed)
-      .WhenReleased(&m_driveFullSpeed);
+  m_driverController.RightBumper()
+      .OnTrue(m_driveHalfSpeed.get())
+      .OnFalse(m_driveFullSpeed.get());
 
   // Drive forward by 3 meters when the 'A' button is pressed, with a timeout of
   // 10 seconds
-  frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kA)
-      .WhenPressed(DriveDistanceProfiled(3_m, &m_drive).WithTimeout(10_s));
+  m_driverController.A().OnTrue(
+      DriveDistanceProfiled(3_m, &m_drive).WithTimeout(10_s));
 
   // Do the same thing as above when the 'B' button is pressed, but defined
   // inline
-  frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kB)
-      .WhenPressed(
-          frc2::TrapezoidProfileCommand<units::meters>(
-              frc::TrapezoidProfile<units::meters>(
-                  // Limit the max acceleration and velocity
-                  {DriveConstants::kMaxSpeed, DriveConstants::kMaxAcceleration},
-                  // End at desired position in meters; implicitly starts at 0
-                  {3_m, 0_mps}),
-              // Pipe the profile state to the drive
-              [this](auto setpointState) {
-                m_drive.SetDriveStates(setpointState, setpointState);
-              },
-              // Require the drive
-              {&m_drive})
-              .BeforeStarting([this]() { m_drive.ResetEncoders(); })
-              .WithTimeout(10_s));
+  m_driverController.B().OnTrue(
+      frc2::TrapezoidProfileCommand<units::meters>(
+          frc::TrapezoidProfile<units::meters>(
+              // Limit the max acceleration and velocity
+              {DriveConstants::kMaxSpeed, DriveConstants::kMaxAcceleration},
+              // End at desired position in meters; implicitly starts at 0
+              {3_m, 0_mps}),
+          // Pipe the profile state to the drive
+          [this](auto setpointState) {
+            m_drive.SetDriveStates(setpointState, setpointState);
+          },
+          // Require the drive
+          {&m_drive})
+          // Convert to CommandPtr
+          .ToPtr()
+          .BeforeStarting(
+              frc2::cmd::RunOnce([this]() { m_drive.ResetEncoders(); }, {}))
+          .WithTimeout(10_s));
 }
 
 frc2::Command* RobotContainer::GetAutonomousCommand() {
   // Runs the chosen command in autonomous
-  return new frc2::InstantCommand([] {});
+  return nullptr;
 }
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/commands/DriveDistanceProfiled.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/commands/DriveDistanceProfiled.cpp
index cecb9d6..6780c33 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/commands/DriveDistanceProfiled.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/commands/DriveDistanceProfiled.cpp
@@ -10,18 +10,18 @@
 
 DriveDistanceProfiled::DriveDistanceProfiled(units::meter_t distance,
                                              DriveSubsystem* drive)
-    : CommandHelper(
-          frc::TrapezoidProfile<units::meters>(
+    : CommandHelper{
+          frc::TrapezoidProfile<units::meters>{
               // Limit the max acceleration and velocity
               {kMaxSpeed, kMaxAcceleration},
               // End at desired position in meters; implicitly starts at 0
-              {distance, 0_mps}),
+              {distance, 0_mps}},
           // Pipe the profile state to the drive
           [drive](auto setpointState) {
             drive->SetDriveStates(setpointState, setpointState);
           },
           // Require the drive
-          {drive}) {
+          {drive}} {
   // Reset drive encoders since we're starting at 0
   drive->ResetEncoders();
 }
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/subsystems/DriveSubsystem.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/subsystems/DriveSubsystem.cpp
index 270124b..db8ba70 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/subsystems/DriveSubsystem.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/subsystems/DriveSubsystem.cpp
@@ -54,11 +54,11 @@
 }
 
 units::meter_t DriveSubsystem::GetLeftEncoderDistance() {
-  return units::meter_t(m_leftLeader.GetEncoderDistance());
+  return units::meter_t{m_leftLeader.GetEncoderDistance()};
 }
 
 units::meter_t DriveSubsystem::GetRightEncoderDistance() {
-  return units::meter_t(m_rightLeader.GetEncoderDistance());
+  return units::meter_t{m_rightLeader.GetEncoderDistance()};
 }
 
 void DriveSubsystem::SetMaxOutput(double maxOutput) {
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/Constants.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/Constants.h
index 6644c08..7b7de40 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/Constants.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/Constants.h
@@ -4,12 +4,13 @@
 
 #pragma once
 
+#include <numbers>
+
 #include <units/acceleration.h>
 #include <units/length.h>
 #include <units/time.h>
 #include <units/velocity.h>
 #include <units/voltage.h>
-#include <wpi/numbers>
 
 /**
  * The Constants header provides a convenient place for teams to hold robot-wide
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/RobotContainer.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/RobotContainer.h
index aced9e0..4700a70 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/RobotContainer.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/RobotContainer.h
@@ -4,14 +4,10 @@
 
 #pragma once
 
-#include <frc/XboxController.h>
-#include <frc/smartdashboard/SendableChooser.h>
 #include <frc2/command/Command.h>
-#include <frc2/command/InstantCommand.h>
-#include <frc2/command/ParallelRaceGroup.h>
-#include <frc2/command/RunCommand.h>
-#include <frc2/command/SequentialCommandGroup.h>
-#include <frc2/command/StartEndCommand.h>
+#include <frc2/command/CommandPtr.h>
+#include <frc2/command/Commands.h>
+#include <frc2/command/button/CommandXboxController.h>
 
 #include "Constants.h"
 #include "subsystems/DriveSubsystem.h"
@@ -31,17 +27,19 @@
 
  private:
   // The driver's controller
-  frc::XboxController m_driverController{OIConstants::kDriverControllerPort};
+  frc2::CommandXboxController m_driverController{
+      OIConstants::kDriverControllerPort};
 
   // The robot's subsystems and commands are defined here...
 
   // The robot's subsystems
   DriveSubsystem m_drive;
 
-  frc2::InstantCommand m_driveHalfSpeed{[this] { m_drive.SetMaxOutput(0.5); },
-                                        {}};
-  frc2::InstantCommand m_driveFullSpeed{[this] { m_drive.SetMaxOutput(1); },
-                                        {}};
+  // RobotContainer-owned commands
+  frc2::CommandPtr m_driveHalfSpeed =
+      frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(0.5); }, {});
+  frc2::CommandPtr m_driveFullSpeed =
+      frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(1); }, {});
 
   void ConfigureButtonBindings();
 };
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ElevatorProfiledPID/cpp/Robot.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ElevatorProfiledPID/cpp/Robot.cpp
index ebafa75..518114a 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ElevatorProfiledPID/cpp/Robot.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ElevatorProfiledPID/cpp/Robot.cpp
@@ -2,6 +2,8 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
+#include <numbers>
+
 #include <frc/Encoder.h>
 #include <frc/Joystick.h>
 #include <frc/TimedRobot.h>
@@ -12,14 +14,13 @@
 #include <units/length.h>
 #include <units/time.h>
 #include <units/velocity.h>
-#include <wpi/numbers>
 
 class Robot : public frc::TimedRobot {
  public:
   static constexpr units::second_t kDt = 20_ms;
 
   Robot() {
-    m_encoder.SetDistancePerPulse(1.0 / 360.0 * 2.0 * wpi::numbers::pi * 1.5);
+    m_encoder.SetDistancePerPulse(1.0 / 360.0 * 2.0 * std::numbers::pi * 1.5);
   }
 
   void TeleopPeriodic() override {
@@ -31,7 +32,7 @@
 
     // Run controller and update motor output
     m_motor.Set(
-        m_controller.Calculate(units::meter_t(m_encoder.GetDistance())));
+        m_controller.Calculate(units::meter_t{m_encoder.GetDistance()}));
   }
 
  private:
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/cpp/Robot.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/cpp/Robot.cpp
index 4b2891d..039a499 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/cpp/Robot.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/cpp/Robot.cpp
@@ -2,6 +2,8 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
+#include <numbers>
+
 #include <frc/Encoder.h>
 #include <frc/Joystick.h>
 #include <frc/RobotController.h>
@@ -23,7 +25,6 @@
 #include <units/angle.h>
 #include <units/length.h>
 #include <units/moment_of_inertia.h>
-#include <wpi/numbers>
 
 /**
  * This is a sample program to demonstrate how to use a state-space controller
@@ -46,7 +47,7 @@
   // distance per pulse = (distance per revolution) / (pulses per revolution)
   //  = (Pi * D) / ppr
   static constexpr double kArmEncoderDistPerPulse =
-      2.0 * wpi::numbers::pi * kElevatorDrumRadius.value() / 4096.0;
+      2.0 * std::numbers::pi * kElevatorDrumRadius.value() / 4096.0;
 
   // This gearbox represents a gearbox containing 4 Vex 775pro motors.
   frc::DCMotor m_elevatorGearbox = frc::DCMotor::Vex775Pro(4);
@@ -64,6 +65,7 @@
                                       kElevatorDrumRadius,
                                       kMinElevatorHeight,
                                       kMaxElevatorHeight,
+                                      true,
                                       {0.01}};
   frc::sim::EncoderSim m_encoderSim{m_encoder};
 
@@ -73,7 +75,7 @@
       m_mech2d.GetRoot("Elevator Root", 10, 0);
   frc::MechanismLigament2d* m_elevatorMech2d =
       m_elevatorRoot->Append<frc::MechanismLigament2d>(
-          "Elevator", units::inch_t(m_elevatorSim.GetPosition()).value(),
+          "Elevator", units::inch_t{m_elevatorSim.GetPosition()}.value(),
           90_deg);
 
  public:
@@ -81,13 +83,15 @@
     m_encoder.SetDistancePerPulse(kArmEncoderDistPerPulse);
 
     // Put Mechanism 2d to SmartDashboard
+    // To view the Elevator Sim in the simulator, select Network Tables ->
+    // SmartDashboard -> Elevator Sim
     frc::SmartDashboard::PutData("Elevator Sim", &m_mech2d);
   }
 
   void SimulationPeriodic() override {
     // In this method, we update our simulation of what our elevator is doing
     // First, we set our "inputs" (voltages)
-    m_elevatorSim.SetInput(Eigen::Vector<double, 1>{
+    m_elevatorSim.SetInput(frc::Vectord<1>{
         m_motor.Get() * frc::RobotController::GetInputVoltage()});
 
     // Next, we update it. The standard loop time is 20ms.
@@ -102,15 +106,15 @@
 
     // Update the Elevator length based on the simulated elevator height
     m_elevatorMech2d->SetLength(
-        units::inch_t(m_elevatorSim.GetPosition()).value());
+        units::inch_t{m_elevatorSim.GetPosition()}.value());
   }
 
   void TeleopPeriodic() override {
     if (m_joystick.GetTrigger()) {
       // Here, we run PID control like normal, with a constant setpoint of 30in.
       double pidOutput = m_controller.Calculate(m_encoder.GetDistance(),
-                                                units::meter_t(30_in).value());
-      m_motor.SetVoltage(units::volt_t(pidOutput));
+                                                units::meter_t{30_in}.value());
+      m_motor.SetVoltage(units::volt_t{pidOutput});
     } else {
       // Otherwise, we disable the motor.
       m_motor.Set(0.0);
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ElevatorTrapezoidProfile/cpp/Robot.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ElevatorTrapezoidProfile/cpp/Robot.cpp
index d629185..f708143 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ElevatorTrapezoidProfile/cpp/Robot.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ElevatorTrapezoidProfile/cpp/Robot.cpp
@@ -2,6 +2,8 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
+#include <numbers>
+
 #include <frc/Joystick.h>
 #include <frc/TimedRobot.h>
 #include <frc/controller/SimpleMotorFeedforward.h>
@@ -11,7 +13,6 @@
 #include <units/time.h>
 #include <units/velocity.h>
 #include <units/voltage.h>
-#include <wpi/numbers>
 
 #include "ExampleSmartMotorController.h"
 
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/Encoder/cpp/Robot.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/Encoder/cpp/Robot.cpp
index 7db2c83..255cc4f 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/Encoder/cpp/Robot.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/Encoder/cpp/Robot.cpp
@@ -2,10 +2,11 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
+#include <numbers>
+
 #include <frc/Encoder.h>
 #include <frc/TimedRobot.h>
 #include <frc/smartdashboard/SmartDashboard.h>
-#include <wpi/numbers>
 
 /**
  * Sample program displaying the value of a quadrature encoder on the
@@ -40,7 +41,7 @@
      * inch diameter (1.5inch radius) wheel, and that we want to measure
      * distance in inches.
      */
-    m_encoder.SetDistancePerPulse(1.0 / 360.0 * 2.0 * wpi::numbers::pi * 1.5);
+    m_encoder.SetDistancePerPulse(1.0 / 360.0 * 2.0 * std::numbers::pi * 1.5);
 
     /* Defines the lowest rate at which the encoder will not be considered
      * stopped, for the purposes of the GetStopped() method. Units are in
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/EventLoop/cpp/Robot.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/EventLoop/cpp/Robot.cpp
new file mode 100644
index 0000000..c8e84fb
--- /dev/null
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/EventLoop/cpp/Robot.cpp
@@ -0,0 +1,102 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <frc/Encoder.h>
+#include <frc/Joystick.h>
+#include <frc/TimedRobot.h>
+#include <frc/Ultrasonic.h>
+#include <frc/controller/PIDController.h>
+#include <frc/controller/SimpleMotorFeedforward.h>
+#include <frc/event/BooleanEvent.h>
+#include <frc/event/EventLoop.h>
+#include <frc/motorcontrol/PWMSparkMax.h>
+#include <units/angular_velocity.h>
+#include <units/length.h>
+#include <units/time.h>
+#include <units/voltage.h>
+
+static const auto SHOT_VELOCITY = 200_rpm;
+static const auto TOLERANCE = 8_rpm;
+static const auto KICKER_THRESHOLD = 15_mm;
+
+class Robot : public frc::TimedRobot {
+ public:
+  void RobotInit() override {
+    m_controller.SetTolerance(TOLERANCE.value());
+
+    frc::BooleanEvent isBallAtKicker{&m_loop, [&kickerSensor = m_kickerSensor] {
+                                       return kickerSensor.GetRange() <
+                                              KICKER_THRESHOLD;
+                                     }};
+    frc::BooleanEvent intakeButton{
+        &m_loop, [&joystick = m_joystick] { return joystick.GetRawButton(2); }};
+
+    // if the thumb button is held
+    (intakeButton
+     // and there is not a ball at the kicker
+     && !isBallAtKicker)
+        // activate the intake
+        .IfHigh([&intake = m_intake] { intake.Set(0.5); });
+
+    // if the thumb button is not held
+    (!intakeButton
+     // or there is a ball in the kicker
+     || isBallAtKicker)
+        // stop the intake
+        .IfHigh([&intake = m_intake] { intake.Set(0.0); });
+
+    frc::BooleanEvent shootTrigger{
+        &m_loop, [&joystick = m_joystick] { return joystick.GetTrigger(); }};
+
+    // if the trigger is held
+    shootTrigger
+        // accelerate the shooter wheel
+        .IfHigh([&shooter = m_shooter, &controller = m_controller, &ff = m_ff,
+                 &encoder = m_shooterEncoder] {
+          shooter.SetVoltage(units::volt_t{controller.Calculate(
+                                 encoder.GetRate(), SHOT_VELOCITY.value())} +
+                             ff.Calculate(SHOT_VELOCITY));
+        });
+    // if not, stop
+    (!shootTrigger).IfHigh([&shooter = m_shooter] { shooter.Set(0.0); });
+
+    frc::BooleanEvent atTargetVelocity =
+        frc::BooleanEvent(
+            &m_loop,
+            [&controller = m_controller] { return controller.AtSetpoint(); })
+            // debounce for more stability
+            .Debounce(0.2_s);
+
+    // if we're at the target velocity, kick the ball into the shooter wheel
+    atTargetVelocity.IfHigh([&kicker = m_kicker] { kicker.Set(0.7); });
+
+    // when we stop being at the target velocity, it means the ball was shot
+    atTargetVelocity
+        .Falling()
+        // so stop the kicker
+        .IfHigh([&kicker = m_kicker] { kicker.Set(0.0); });
+  }
+
+  void RobotPeriodic() override { m_loop.Poll(); }
+
+ private:
+  frc::PWMSparkMax m_shooter{0};
+  frc::Encoder m_shooterEncoder{0, 1};
+  frc::PIDController m_controller{0.3, 0, 0};
+  frc::SimpleMotorFeedforward<units::radians> m_ff{0.1_V, 0.065_V / 1_rpm};
+
+  frc::PWMSparkMax m_kicker{1};
+  frc::Ultrasonic m_kickerSensor{2, 3};
+
+  frc::PWMSparkMax m_intake{3};
+
+  frc::EventLoop m_loop{};
+  frc::Joystick m_joystick{0};
+};
+
+#ifndef RUNNING_FRC_TESTS
+int main() {
+  return frc::StartRobot<Robot>();
+}
+#endif
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/RobotContainer.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/RobotContainer.cpp
index c459739..3841118 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/RobotContainer.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/RobotContainer.cpp
@@ -4,9 +4,6 @@
 
 #include "RobotContainer.h"
 
-#include <frc/shuffleboard/Shuffleboard.h>
-#include <frc2/command/button/JoystickButton.h>
-
 RobotContainer::RobotContainer() {
   // Initialize all of your commands and subsystems here
 
@@ -14,10 +11,10 @@
   ConfigureButtonBindings();
 
   // Set up default drive command
-  m_drive.SetDefaultCommand(frc2::RunCommand(
+  m_drive.SetDefaultCommand(frc2::cmd::Run(
       [this] {
         m_drive.ArcadeDrive(-m_driverController.GetLeftY(),
-                            m_driverController.GetRightX());
+                            -m_driverController.GetRightX());
       },
       {&m_drive}));
 }
@@ -25,27 +22,45 @@
 void RobotContainer::ConfigureButtonBindings() {
   // Configure your button bindings here
 
+  // We can bind commands while keeping their ownership in RobotContainer
+
   // Spin up the shooter when the 'A' button is pressed
-  frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kA)
-      .WhenPressed(&m_spinUpShooter);
+  m_driverController.A().OnTrue(m_spinUpShooter.get());
 
   // Turn off the shooter when the 'B' button is pressed
-  frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kB)
-      .WhenPressed(&m_stopShooter);
+  m_driverController.B().OnTrue(m_stopShooter.get());
 
-  // Shoot when the 'X' button is held
-  frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kX)
-      .WhenPressed(&m_shoot)
-      .WhenReleased(&m_stopFeeder);
+  // We can also *move* command ownership to the scheduler
+  // Note that we won't be able to access these commands after moving them!
+
+  // Shoots if the shooter wheel has reached the target speed
+  frc2::CommandPtr shoot = frc2::cmd::Either(
+      // Run the feeder
+      frc2::cmd::RunOnce([this] { m_shooter.RunFeeder(); }, {&m_shooter}),
+      // Do nothing
+      frc2::cmd::None(),
+      // Determine which of the above to do based on whether the shooter has
+      // reached the desired speed
+      [this] { return m_shooter.AtSetpoint(); });
+
+  frc2::CommandPtr stopFeeder =
+      frc2::cmd::RunOnce([this] { m_shooter.StopFeeder(); }, {&m_shooter});
+
+  // Shoot when the 'X' button is pressed
+  m_driverController.X()
+      .OnTrue(std::move(shoot))
+      .OnFalse(std::move(stopFeeder));
+
+  // We can also define commands inline at the binding!
+  // (ownership will be passed to the scheduler)
 
   // While holding the shoulder button, drive at half speed
-  frc2::JoystickButton(&m_driverController,
-                       frc::XboxController::Button::kRightBumper)
-      .WhenPressed(&m_driveHalfSpeed)
-      .WhenReleased(&m_driveFullSpeed);
+  m_driverController.RightBumper()
+      .OnTrue(frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(0.5); }, {}))
+      .OnFalse(frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(1); }, {}));
 }
 
 frc2::Command* RobotContainer::GetAutonomousCommand() {
   // Runs the chosen command in autonomous
-  return &m_autonomousCommand;
+  return m_autonomousCommand.get();
 }
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/subsystems/ShooterSubsystem.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/subsystems/ShooterSubsystem.cpp
index c386ee7..aec84f1 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/subsystems/ShooterSubsystem.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/subsystems/ShooterSubsystem.cpp
@@ -11,7 +11,7 @@
 using namespace ShooterConstants;
 
 ShooterSubsystem::ShooterSubsystem()
-    : PIDSubsystem(frc2::PIDController(kP, kI, kD)),
+    : PIDSubsystem{frc2::PIDController{kP, kI, kD}},
       m_shooterMotor(kShooterMotorPort),
       m_feederMotor(kFeederMotorPort),
       m_shooterEncoder(kEncoderPorts[0], kEncoderPorts[1]),
@@ -22,7 +22,7 @@
 }
 
 void ShooterSubsystem::UseOutput(double output, double setpoint) {
-  m_shooterMotor.SetVoltage(units::volt_t(output) +
+  m_shooterMotor.SetVoltage(units::volt_t{output} +
                             m_shooterFeedforward.Calculate(kShooterTargetRPS));
 }
 
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/Frisbeebot/include/Constants.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/Frisbeebot/include/Constants.h
index 8ac7b0e..855603a 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/Frisbeebot/include/Constants.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/Frisbeebot/include/Constants.h
@@ -4,10 +4,11 @@
 
 #pragma once
 
+#include <numbers>
+
 #include <units/angle.h>
 #include <units/time.h>
 #include <units/voltage.h>
-#include <wpi/numbers>
 
 /**
  * The Constants header provides a convenient place for teams to hold robot-wide
@@ -33,7 +34,7 @@
 constexpr double kWheelDiameterInches = 6;
 constexpr double kEncoderDistancePerPulse =
     // Assumes the encoders are directly mounted on the wheel shafts
-    (kWheelDiameterInches * wpi::numbers::pi) /
+    (kWheelDiameterInches * std::numbers::pi) /
     static_cast<double>(kEncoderCPR);
 }  // namespace DriveConstants
 
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/Frisbeebot/include/RobotContainer.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/Frisbeebot/include/RobotContainer.h
index 26714fe..40091f1 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/Frisbeebot/include/RobotContainer.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/Frisbeebot/include/RobotContainer.h
@@ -4,16 +4,10 @@
 
 #pragma once
 
-#include <frc/XboxController.h>
-#include <frc/smartdashboard/SendableChooser.h>
 #include <frc2/command/Command.h>
-#include <frc2/command/ConditionalCommand.h>
-#include <frc2/command/InstantCommand.h>
-#include <frc2/command/ParallelRaceGroup.h>
-#include <frc2/command/RunCommand.h>
-#include <frc2/command/SequentialCommandGroup.h>
-#include <frc2/command/WaitCommand.h>
-#include <frc2/command/WaitUntilCommand.h>
+#include <frc2/command/CommandPtr.h>
+#include <frc2/command/Commands.h>
+#include <frc2/command/button/CommandXboxController.h>
 
 #include "Constants.h"
 #include "subsystems/DriveSubsystem.h"
@@ -32,65 +26,47 @@
  public:
   RobotContainer();
 
+  // The chooser for the autonomous routines
   frc2::Command* GetAutonomousCommand();
 
  private:
   // The driver's controller
-  frc::XboxController m_driverController{OIConstants::kDriverControllerPort};
-
-  // The robot's subsystems and commands are defined here...
+  frc2::CommandXboxController m_driverController{
+      OIConstants::kDriverControllerPort};
 
   // The robot's subsystems
   DriveSubsystem m_drive;
   ShooterSubsystem m_shooter;
 
-  // A simple autonomous routine that shoots the loaded frisbees
-  frc2::SequentialCommandGroup m_autonomousCommand =
-      frc2::SequentialCommandGroup{
+  // RobotContainer-owned commands
+  // (These variables will still be valid after binding, because we don't move
+  // ownership)
+
+  frc2::CommandPtr m_spinUpShooter =
+      frc2::cmd::RunOnce([this] { m_shooter.Enable(); }, {&m_shooter});
+
+  frc2::CommandPtr m_stopShooter =
+      frc2::cmd::RunOnce([this] { m_shooter.Disable(); }, {&m_shooter});
+
+  // An autonomous routine that shoots the loaded frisbees
+  frc2::CommandPtr m_autonomousCommand =
+      frc2::cmd::Sequence(
           // Start the command by spinning up the shooter...
-          frc2::InstantCommand([this] { m_shooter.Enable(); }, {&m_shooter}),
+          frc2::cmd::RunOnce([this] { m_shooter.Enable(); }, {&m_shooter}),
           // Wait until the shooter is at speed before feeding the frisbees
-          frc2::WaitUntilCommand([this] { return m_shooter.AtSetpoint(); }),
+          frc2::cmd::WaitUntil([this] { return m_shooter.AtSetpoint(); }),
           // Start running the feeder
-          frc2::InstantCommand([this] { m_shooter.RunFeeder(); }, {&m_shooter}),
+          frc2::cmd::RunOnce([this] { m_shooter.RunFeeder(); }, {&m_shooter}),
           // Shoot for the specified time
-          frc2::WaitCommand(ac::kAutoShootTimeSeconds)}
+          frc2::cmd::Wait(ac::kAutoShootTimeSeconds))
           // Add a timeout (will end the command if, for instance, the shooter
           // never gets up to speed)
           .WithTimeout(ac::kAutoTimeoutSeconds)
           // When the command ends, turn off the shooter and the feeder
-          .AndThen([this] {
+          .AndThen(frc2::cmd::RunOnce([this] {
             m_shooter.Disable();
             m_shooter.StopFeeder();
-          });
-
-  // Assorted commands to be bound to buttons
-
-  frc2::InstantCommand m_spinUpShooter{[this] { m_shooter.Enable(); },
-                                       {&m_shooter}};
-
-  frc2::InstantCommand m_stopShooter{[this] { m_shooter.Disable(); },
-                                     {&m_shooter}};
-
-  // Shoots if the shooter wheel has reached the target speed
-  frc2::ConditionalCommand m_shoot{
-      // Run the feeder
-      frc2::InstantCommand{[this] { m_shooter.RunFeeder(); }, {&m_shooter}},
-      // Do nothing
-      frc2::InstantCommand(),
-      // Determine which of the above to do based on whether the shooter has
-      // reached the desired speed
-      [this] { return m_shooter.AtSetpoint(); }};
-
-  frc2::InstantCommand m_stopFeeder{[this] { m_shooter.StopFeeder(); },
-                                    {&m_shooter}};
-
-  frc2::InstantCommand m_driveHalfSpeed{[this] { m_drive.SetMaxOutput(0.5); },
-                                        {}};
-  frc2::InstantCommand m_driveFullSpeed{[this] { m_drive.SetMaxOutput(1); },
-                                        {}};
-
-  // The chooser for the autonomous routines
+          }));
 
   void ConfigureButtonBindings();
 };
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/RobotContainer.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/RobotContainer.cpp
index 37eb460..c08faee 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/RobotContainer.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/RobotContainer.cpp
@@ -22,9 +22,9 @@
   frc::SmartDashboard::PutData(&m_wrist);
   frc::SmartDashboard::PutData(&m_claw);
 
-  m_drivetrain.SetDefaultCommand(TankDrive([this] { return m_joy.GetLeftY(); },
-                                           [this] { return m_joy.GetRightY(); },
-                                           m_drivetrain));
+  m_drivetrain.SetDefaultCommand(
+      TankDrive([this] { return -m_joy.GetLeftY(); },
+                [this] { return -m_joy.GetRightY(); }, m_drivetrain));
 
   // Configure the button bindings
   ConfigureButtonBindings();
@@ -32,20 +32,20 @@
 
 void RobotContainer::ConfigureButtonBindings() {
   // Configure your button bindings here
-  frc2::JoystickButton(&m_joy, 5).WhenPressed(
-      SetElevatorSetpoint(0.25, m_elevator));
-  frc2::JoystickButton(&m_joy, 6).WhenPressed(CloseClaw(m_claw));
-  frc2::JoystickButton(&m_joy, 7).WhenPressed(
-      SetElevatorSetpoint(0.0, m_elevator));
-  frc2::JoystickButton(&m_joy, 8).WhenPressed(OpenClaw(m_claw));
-  frc2::JoystickButton(&m_joy, 9).WhenPressed(
-      Autonomous(m_claw, m_wrist, m_elevator, m_drivetrain));
+  frc2::JoystickButton(&m_joy, 5).OnTrue(
+      SetElevatorSetpoint(0.25, m_elevator).ToPtr());
+  frc2::JoystickButton(&m_joy, 6).OnTrue(CloseClaw(m_claw).ToPtr());
+  frc2::JoystickButton(&m_joy, 7).OnTrue(
+      SetElevatorSetpoint(0.0, m_elevator).ToPtr());
+  frc2::JoystickButton(&m_joy, 8).OnTrue(OpenClaw(m_claw).ToPtr());
+  frc2::JoystickButton(&m_joy, 9).OnTrue(
+      Autonomous(m_claw, m_wrist, m_elevator, m_drivetrain).ToPtr());
   frc2::JoystickButton(&m_joy, 10)
-      .WhenPressed(Pickup(m_claw, m_wrist, m_elevator));
+      .OnTrue(Pickup(m_claw, m_wrist, m_elevator).ToPtr());
   frc2::JoystickButton(&m_joy, 11)
-      .WhenPressed(Place(m_claw, m_wrist, m_elevator));
+      .OnTrue(Place(m_claw, m_wrist, m_elevator).ToPtr());
   frc2::JoystickButton(&m_joy, 12)
-      .WhenPressed(PrepareToPickup(m_claw, m_wrist, m_elevator));
+      .OnTrue(PrepareToPickup(m_claw, m_wrist, m_elevator).ToPtr());
 }
 
 frc2::Command* RobotContainer::GetAutonomousCommand() {
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/DriveStraight.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/DriveStraight.cpp
index d3e85bd..c1f5d88 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/DriveStraight.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/DriveStraight.cpp
@@ -9,12 +9,13 @@
 #include "Robot.h"
 
 DriveStraight::DriveStraight(double distance, Drivetrain& drivetrain)
-    : frc2::CommandHelper<frc2::PIDCommand, DriveStraight>(
-          frc2::PIDController(4, 0, 0),
-          [&drivetrain] { return drivetrain.GetDistance(); }, distance,
+    : frc2::CommandHelper<frc2::PIDCommand, DriveStraight>{
+          frc2::PIDController{4, 0, 0},
+          [&drivetrain] { return drivetrain.GetDistance(); },
+          distance,
           [&drivetrain](double output) { drivetrain.Drive(output, output); },
-          {&drivetrain}),
-      m_drivetrain(&drivetrain) {
+          {&drivetrain}},
+      m_drivetrain{&drivetrain} {
   m_controller.SetTolerance(0.01);
 }
 
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/SetDistanceToBox.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/SetDistanceToBox.cpp
index 84bf237..de8f1e7 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/SetDistanceToBox.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/SetDistanceToBox.cpp
@@ -9,13 +9,13 @@
 #include "Robot.h"
 
 SetDistanceToBox::SetDistanceToBox(double distance, Drivetrain& drivetrain)
-    : frc2::CommandHelper<frc2::PIDCommand, SetDistanceToBox>(
-          frc2::PIDController(-2, 0, 0),
+    : frc2::CommandHelper<frc2::PIDCommand, SetDistanceToBox>{
+          frc2::PIDController{-2, 0, 0},
           [&drivetrain] { return drivetrain.GetDistanceToObstacle(); },
           distance,
           [&drivetrain](double output) { drivetrain.Drive(output, output); },
-          {&drivetrain}),
-      m_drivetrain(&drivetrain) {
+          {&drivetrain}},
+      m_drivetrain{&drivetrain} {
   m_controller.SetTolerance(0.01);
 }
 
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Drivetrain.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Drivetrain.cpp
index 16d6e46..2bfd391 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Drivetrain.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Drivetrain.cpp
@@ -4,10 +4,11 @@
 
 #include "subsystems/Drivetrain.h"
 
+#include <numbers>
+
 #include <frc/Joystick.h>
 #include <frc/smartdashboard/SmartDashboard.h>
 #include <units/length.h>
-#include <wpi/numbers>
 
 Drivetrain::Drivetrain() {
   // We need to invert one side of the drivetrain so that positive voltages
@@ -26,9 +27,9 @@
 #else
   // Circumference = diameter * pi. 360 tick simulated encoders.
   m_leftEncoder.SetDistancePerPulse(units::foot_t{4_in}.value() *
-                                    wpi::numbers::pi / 360.0);
+                                    std::numbers::pi / 360.0);
   m_rightEncoder.SetDistancePerPulse(units::foot_t{4_in}.value() *
-                                     wpi::numbers::pi / 360.0);
+                                     std::numbers::pi / 360.0);
 #endif
   SetName("Drivetrain");
   // Let's show everything on the LiveWindow
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Elevator.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Elevator.cpp
index 0c195e3..c75c7bc 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Elevator.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Elevator.cpp
@@ -9,7 +9,7 @@
 #include <frc/smartdashboard/SmartDashboard.h>
 
 Elevator::Elevator()
-    : frc2::PIDSubsystem(frc2::PIDController(kP_real, kI_real, 0)) {
+    : frc2::PIDSubsystem{frc2::PIDController{kP_real, kI_real, 0}} {
 #ifdef SIMULATION  // Check for simulation and update PID values
   GetPIDController()->SetPID(kP_simulation, kI_simulation, 0, 0);
 #endif
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Wrist.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Wrist.cpp
index 339ccd0..8b24a7b 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Wrist.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Wrist.cpp
@@ -7,7 +7,7 @@
 #include <frc/controller/PIDController.h>
 #include <frc/smartdashboard/SmartDashboard.h>
 
-Wrist::Wrist() : frc2::PIDSubsystem(frc2::PIDController(kP, 0, 0)) {
+Wrist::Wrist() : frc2::PIDSubsystem{frc2::PIDController{kP, 0, 0}} {
   m_controller.SetTolerance(2.5);
 
   SetName("Wrist");
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp
index 003a08a..a49d4f6 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp
@@ -2,20 +2,20 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
-#include <frc/Joystick.h>
 #include <frc/TimedRobot.h>
 #include <frc/Timer.h>
+#include <frc/XboxController.h>
 #include <frc/drive/DifferentialDrive.h>
 #include <frc/motorcontrol/PWMSparkMax.h>
 
 class Robot : public frc::TimedRobot {
  public:
   Robot() {
-    m_right.SetInverted(true);
-    m_robotDrive.SetExpiration(100_ms);
     // We need to invert one side of the drivetrain so that positive voltages
     // result in both sides moving forward. Depending on how your robot's
     // gearbox is constructed, you might have to invert the left side instead.
+    m_right.SetInverted(true);
+    m_robotDrive.SetExpiration(100_ms);
     m_timer.Start();
   }
 
@@ -27,19 +27,20 @@
   void AutonomousPeriodic() override {
     // Drive for 2 seconds
     if (m_timer.Get() < 2_s) {
-      // Drive forwards half speed
-      m_robotDrive.ArcadeDrive(0.5, 0.0);
+      // Drive forwards half speed, make sure to turn input squaring off
+      m_robotDrive.ArcadeDrive(0.5, 0.0, false);
     } else {
       // Stop robot
-      m_robotDrive.ArcadeDrive(0.0, 0.0);
+      m_robotDrive.ArcadeDrive(0.0, 0.0, false);
     }
   }
 
   void TeleopInit() override {}
 
   void TeleopPeriodic() override {
-    // Drive with arcade style (use right stick)
-    m_robotDrive.ArcadeDrive(-m_stick.GetY(), m_stick.GetX());
+    // Drive with arcade style (use right stick to steer)
+    m_robotDrive.ArcadeDrive(-m_controller.GetLeftY(),
+                             m_controller.GetRightX());
   }
 
   void TestInit() override {}
@@ -52,7 +53,7 @@
   frc::PWMSparkMax m_right{1};
   frc::DifferentialDrive m_robotDrive{m_left, m_right};
 
-  frc::Joystick m_stick{0};
+  frc::XboxController m_controller{0};
   frc::Timer m_timer;
 };
 
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp
index 0e1410e..5230c7c 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp
@@ -32,9 +32,7 @@
    */
   void TeleopPeriodic() override {
     double turningValue = (kAngleSetpoint - m_gyro.GetAngle()) * kP;
-    // Invert the direction of the turn if we are going backwards
-    turningValue = std::copysign(turningValue, m_joystick.GetY());
-    m_robotDrive.ArcadeDrive(-m_joystick.GetY(), turningValue);
+    m_drive.ArcadeDrive(-m_joystick.GetY(), -turningValue);
   }
 
  private:
@@ -52,7 +50,7 @@
 
   frc::PWMSparkMax m_left{kLeftMotorPort};
   frc::PWMSparkMax m_right{kRightMotorPort};
-  frc::DifferentialDrive m_robotDrive{m_left, m_right};
+  frc::DifferentialDrive m_drive{m_left, m_right};
 
   frc::AnalogGyro m_gyro{kGyroPort};
   frc::Joystick m_joystick{kJoystickPort};
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/RobotContainer.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/RobotContainer.cpp
index 6f5911e..3404b77 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/RobotContainer.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/RobotContainer.cpp
@@ -5,6 +5,7 @@
 #include "RobotContainer.h"
 
 #include <frc/shuffleboard/Shuffleboard.h>
+#include <frc2/command/Commands.h>
 #include <frc2/command/PIDCommand.h>
 #include <frc2/command/ParallelRaceGroup.h>
 #include <frc2/command/RunCommand.h>
@@ -20,7 +21,7 @@
   m_drive.SetDefaultCommand(frc2::RunCommand(
       [this] {
         m_drive.ArcadeDrive(-m_driverController.GetLeftY(),
-                            m_driverController.GetRightX());
+                            -m_driverController.GetRightX());
       },
       {&m_drive}));
 }
@@ -32,33 +33,35 @@
 
   // Stabilize robot to drive straight with gyro when L1 is held
   frc2::JoystickButton(&m_driverController, frc::PS4Controller::Button::kL1)
-      .WhenHeld(frc2::PIDCommand{
-          frc2::PIDController{dc::kStabilizationP, dc::kStabilizationI,
-                              dc::kStabilizationD},
-          // Close the loop on the turn rate
-          [this] { return m_drive.GetTurnRate(); },
-          // Setpoint is 0
-          0,
-          // Pipe the output to the turning controls
-          [this](double output) {
-            m_drive.ArcadeDrive(m_driverController.GetLeftY(), output);
-          },
-          // Require the robot drive
-          {&m_drive}});
+      .WhileTrue(
+          frc2::PIDCommand(
+              frc2::PIDController{dc::kStabilizationP, dc::kStabilizationI,
+                                  dc::kStabilizationD},
+              // Close the loop on the turn rate
+              [this] { return m_drive.GetTurnRate(); },
+              // Setpoint is 0
+              0,
+              // Pipe the output to the turning controls
+              [this](double output) {
+                m_drive.ArcadeDrive(m_driverController.GetLeftY(), output);
+              },
+              // Require the robot drive
+              {&m_drive})
+              .ToPtr());
 
   // Turn to 90 degrees when the 'Cross' button is pressed
   frc2::JoystickButton(&m_driverController, frc::PS4Controller::Button::kCross)
-      .WhenPressed(TurnToAngle{90_deg, &m_drive}.WithTimeout(5_s));
+      .OnTrue(TurnToAngle{90_deg, &m_drive}.WithTimeout(5_s));
 
   // Turn to -90 degrees with a profile when the 'Square' button is pressed,
   // with a 5 second timeout
   frc2::JoystickButton(&m_driverController, frc::PS4Controller::Button::kSquare)
-      .WhenPressed(TurnToAngle{90_deg, &m_drive}.WithTimeout(5_s));
+      .OnTrue(TurnToAngle{90_deg, &m_drive}.WithTimeout(5_s));
 
   // While holding R1, drive at half speed
   frc2::JoystickButton(&m_driverController, frc::PS4Controller::Button::kR1)
-      .WhenPressed(frc2::InstantCommand{[this] { m_drive.SetMaxOutput(0.5); }})
-      .WhenReleased(frc2::InstantCommand{[this] { m_drive.SetMaxOutput(1); }});
+      .OnTrue(frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(0.5); }, {}))
+      .OnFalse(frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(1); }, {}));
 }
 
 frc2::Command* RobotContainer::GetAutonomousCommand() {
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/commands/TurnToAngle.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/commands/TurnToAngle.cpp
index 681bb39..3038f79 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/commands/TurnToAngle.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/commands/TurnToAngle.cpp
@@ -9,16 +9,15 @@
 using namespace DriveConstants;
 
 TurnToAngle::TurnToAngle(units::degree_t target, DriveSubsystem* drive)
-    : CommandHelper(
-          frc2::PIDController(kTurnP, kTurnI, kTurnD),
-          // Close loop on heading
-          [drive] { return drive->GetHeading().value(); },
-          // Set reference to target
-          target.value(),
-          // Pipe output to turn robot
-          [drive](double output) { drive->ArcadeDrive(0, output); },
-          // Require the drive
-          {drive}) {
+    : CommandHelper{frc2::PIDController{kTurnP, kTurnI, kTurnD},
+                    // Close loop on heading
+                    [drive] { return drive->GetHeading().value(); },
+                    // Set reference to target
+                    target.value(),
+                    // Pipe output to turn robot
+                    [drive](double output) { drive->ArcadeDrive(0, output); },
+                    // Require the drive
+                    {drive}} {
   // Set the controller to be continuous (because it is an angle controller)
   m_controller.EnableContinuousInput(-180, 180);
   // Set the controller tolerance - the delta tolerance ensures the robot is
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/commands/TurnToAngleProfiled.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/commands/TurnToAngleProfiled.cpp
index a359625..df4e355 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/commands/TurnToAngleProfiled.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/commands/TurnToAngleProfiled.cpp
@@ -10,9 +10,9 @@
 
 TurnToAngleProfiled::TurnToAngleProfiled(units::degree_t target,
                                          DriveSubsystem* drive)
-    : CommandHelper(
-          frc::ProfiledPIDController<units::radians>(
-              kTurnP, kTurnI, kTurnD, {kMaxTurnRate, kMaxTurnAcceleration}),
+    : CommandHelper{
+          frc::ProfiledPIDController<units::radians>{
+              kTurnP, kTurnI, kTurnD, {kMaxTurnRate, kMaxTurnAcceleration}},
           // Close loop on heading
           [drive] { return drive->GetHeading(); },
           // Set reference to target
@@ -22,7 +22,7 @@
             drive->ArcadeDrive(0, output);
           },
           // Require the drive
-          {drive}) {
+          {drive}} {
   // Set the controller to be continuous (because it is an angle controller)
   GetController().EnableContinuousInput(-180_deg, 180_deg);
   // Set the controller tolerance - the delta tolerance ensures the robot is
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/subsystems/DriveSubsystem.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/subsystems/DriveSubsystem.cpp
index baa78de..0cbd0e5 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/subsystems/DriveSubsystem.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/subsystems/DriveSubsystem.cpp
@@ -53,8 +53,8 @@
 }
 
 units::degree_t DriveSubsystem::GetHeading() {
-  return units::degree_t(std::remainder(m_gyro.GetAngle(), 360) *
-                         (kGyroReversed ? -1.0 : 1.0));
+  return units::degree_t{std::remainder(m_gyro.GetAngle(), 360) *
+                         (kGyroReversed ? -1.0 : 1.0)};
 }
 
 double DriveSubsystem::GetTurnRate() {
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/Constants.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/Constants.h
index 210f82d..77673c9 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/Constants.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/Constants.h
@@ -4,9 +4,10 @@
 
 #pragma once
 
+#include <numbers>
+
 #include <units/angle.h>
 #include <units/angular_velocity.h>
-#include <wpi/numbers>
 
 /**
  * The Constants header provides a convenient place for teams to hold robot-wide
@@ -32,7 +33,7 @@
 constexpr double kWheelDiameterInches = 6;
 constexpr double kEncoderDistancePerPulse =
     // Assumes the encoders are directly mounted on the wheel shafts
-    (kWheelDiameterInches * wpi::numbers::pi) /
+    (kWheelDiameterInches * std::numbers::pi) /
     static_cast<double>(kEncoderCPR);
 
 constexpr bool kGyroReversed = true;
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp
index a4e0457..2207f79 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp
@@ -28,8 +28,8 @@
    * Mecanum drive is used with the gyro angle as an input.
    */
   void TeleopPeriodic() override {
-    m_robotDrive.DriveCartesian(-m_joystick.GetY(), m_joystick.GetX(),
-                                m_joystick.GetZ(), m_gyro.GetAngle());
+    m_robotDrive.DriveCartesian(-m_joystick.GetY(), -m_joystick.GetX(),
+                                -m_joystick.GetZ(), m_gyro.GetRotation2d());
   }
 
  private:
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HAL/c/Robot.c b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HAL/c/Robot.c
index 0db402b..b0905f9 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HAL/c/Robot.c
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HAL/c/Robot.c
@@ -87,13 +87,18 @@
     return 1;
   }
 
+  WPI_EventHandle eventHandle = WPI_CreateEvent(1, 0);
+  HAL_ProvideNewDataEventHandle(eventHandle);
+
   while (1) {
     // Wait for DS data, with a timeout
-    HAL_Bool validData = HAL_WaitForDSDataTimeout(1.0);
-    if (!validData) {
+    int timed_out = 0;
+    int signaled = WPI_WaitForObjectTimeout(eventHandle, 1.0, &timed_out);
+    if (!signaled) {
       // Do something here on no packet
       continue;
     }
+
     enum DriverStationMode dsMode = getDSMode();
     switch (dsMode) {
       case DisabledMode:
@@ -116,6 +121,9 @@
   }
 
   // Clean up resources
+  HAL_RemoveNewDataEventHandle(eventHandle);
+  WPI_DestroyEvent(eventHandle);
+
   status = 0;
   HAL_FreeDIOPort(dio);
   HAL_FreePWMPort(pwmPort, &status);
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/RobotContainer.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/RobotContainer.cpp
index 8fae7d2..5a0cdad 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/RobotContainer.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/RobotContainer.cpp
@@ -5,14 +5,14 @@
 #include "RobotContainer.h"
 
 #include <frc/shuffleboard/Shuffleboard.h>
-#include <frc2/command/button/JoystickButton.h>
 
 RobotContainer::RobotContainer() {
   // Initialize all of your commands and subsystems here
 
   // Add commands to the autonomous command chooser
-  m_chooser.SetDefaultOption("Simple Auto", &m_simpleAuto);
-  m_chooser.AddOption("Complex Auto", &m_complexAuto);
+  // Note that we do *not* move ownership into the chooser
+  m_chooser.SetDefaultOption("Simple Auto", m_simpleAuto.get());
+  m_chooser.AddOption("Complex Auto", m_complexAuto.get());
 
   // Put the chooser on the dashboard
   frc::Shuffleboard::GetTab("Autonomous").Add(m_chooser);
@@ -21,10 +21,10 @@
   ConfigureButtonBindings();
 
   // Set up default drive command
-  m_drive.SetDefaultCommand(frc2::RunCommand(
+  m_drive.SetDefaultCommand(frc2::cmd::Run(
       [this] {
         m_drive.ArcadeDrive(-m_driverController.GetLeftY(),
-                            m_driverController.GetRightX());
+                            -m_driverController.GetRightX());
       },
       {&m_drive}));
 }
@@ -33,15 +33,13 @@
   // Configure your button bindings here
 
   // Grab the hatch when the 'Circle' button is pressed.
-  frc2::JoystickButton(&m_driverController, frc::PS4Controller::Button::kCircle)
-      .WhenPressed(&m_grabHatch);
+  m_driverController.Circle().OnTrue(m_hatch.GrabHatchCommand());
   // Release the hatch when the 'Square' button is pressed.
-  frc2::JoystickButton(&m_driverController, frc::PS4Controller::Button::kSquare)
-      .WhenPressed(&m_releaseHatch);
+  m_driverController.Square().OnTrue(m_hatch.ReleaseHatchCommand());
   // While holding R1, drive at half speed
-  frc2::JoystickButton(&m_driverController, frc::PS4Controller::Button::kR1)
-      .WhenPressed(&m_driveHalfSpeed)
-      .WhenReleased(&m_driveFullSpeed);
+  m_driverController.R1()
+      .OnTrue(frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(0.5); }, {}))
+      .OnFalse(frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(1.0); }, {}));
 }
 
 frc2::Command* RobotContainer::GetAutonomousCommand() {
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/commands/Autos.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/commands/Autos.cpp
new file mode 100644
index 0000000..73e60ed
--- /dev/null
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/commands/Autos.cpp
@@ -0,0 +1,73 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "commands/Autos.h"
+
+#include <frc2/command/Commands.h>
+#include <frc2/command/FunctionalCommand.h>
+
+#include "Constants.h"
+
+using namespace AutoConstants;
+
+frc2::CommandPtr autos::SimpleAuto(DriveSubsystem* drive) {
+  return frc2::FunctionalCommand(
+             // Reset encoders on command start
+             [drive] { drive->ResetEncoders(); },
+             // Drive forward while the command is executing
+             [drive] { drive->ArcadeDrive(AutoConstants::kAutoDriveSpeed, 0); },
+             // Stop driving at the end of the command
+             [drive](bool interrupted) { drive->ArcadeDrive(0, 0); },
+             // End the command when the robot's driven distance exceeds the
+             // desired value
+             [drive] {
+               return drive->GetAverageEncoderDistance() >=
+                      AutoConstants::kAutoDriveDistanceInches;
+             },
+             // Requires the drive subsystem
+             {drive})
+      .ToPtr();
+}
+
+frc2::CommandPtr autos::ComplexAuto(DriveSubsystem* drive,
+                                    HatchSubsystem* hatch) {
+  return frc2::cmd::Sequence(
+      // Drive forward the specified distance
+      frc2::FunctionalCommand(
+          // Reset encoders on command start
+          [drive] { drive->ResetEncoders(); },
+          // Drive forward while the command is executing
+          [drive] { drive->ArcadeDrive(kAutoDriveSpeed, 0); },
+          // Stop driving at the end of the command
+          [drive](bool interrupted) { drive->ArcadeDrive(0, 0); },
+          // End the command when the robot's driven distance exceeds the
+          // desired value
+          [drive] {
+            return drive->GetAverageEncoderDistance() >=
+                   kAutoDriveDistanceInches;
+          },
+          // Requires the drive subsystem
+          {drive})
+          .ToPtr(),
+      // Release the hatch
+      hatch->ReleaseHatchCommand(),
+      // Drive backward the specified distance
+      // Drive forward the specified distance
+      frc2::FunctionalCommand(
+          // Reset encoders on command start
+          [drive] { drive->ResetEncoders(); },
+          // Drive backward while the command is executing
+          [drive] { drive->ArcadeDrive(-kAutoDriveSpeed, 0); },
+          // Stop driving at the end of the command
+          [drive](bool interrupted) { drive->ArcadeDrive(0, 0); },
+          // End the command when the robot's driven distance exceeds the
+          // desired value
+          [drive] {
+            return drive->GetAverageEncoderDistance() <=
+                   kAutoBackupDistanceInches;
+          },
+          // Requires the drive subsystem
+          {drive})
+          .ToPtr());
+}
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/commands/ComplexAuto.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/commands/ComplexAuto.cpp
deleted file mode 100644
index f88850e..0000000
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/commands/ComplexAuto.cpp
+++ /dev/null
@@ -1,50 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "commands/ComplexAuto.h"
-
-#include <frc2/command/FunctionalCommand.h>
-#include <frc2/command/InstantCommand.h>
-#include <frc2/command/ParallelRaceGroup.h>
-
-using namespace AutoConstants;
-
-ComplexAuto::ComplexAuto(DriveSubsystem* drive, HatchSubsystem* hatch) {
-  AddCommands(
-      // Drive forward the specified distance
-      frc2::FunctionalCommand(
-          // Reset encoders on command start
-          [&] { drive->ResetEncoders(); },
-          // Drive forward while the command is executing
-          [&] { drive->ArcadeDrive(kAutoDriveSpeed, 0); },
-          // Stop driving at the end of the command
-          [&](bool interrupted) { drive->ArcadeDrive(0, 0); },
-          // End the command when the robot's driven distance exceeds the
-          // desired value
-          [&] {
-            return drive->GetAverageEncoderDistance() >=
-                   kAutoDriveDistanceInches;
-          },
-          // Requires the drive subsystem
-          {drive}),
-      // Release the hatch
-      frc2::InstantCommand([hatch] { hatch->ReleaseHatch(); }, {hatch}),
-      // Drive backward the specified distance
-      // Drive forward the specified distance
-      frc2::FunctionalCommand(
-          // Reset encoders on command start
-          [&] { drive->ResetEncoders(); },
-          // Drive backward while the command is executing
-          [&] { drive->ArcadeDrive(-kAutoDriveSpeed, 0); },
-          // Stop driving at the end of the command
-          [&](bool interrupted) { drive->ArcadeDrive(0, 0); },
-          // End the command when the robot's driven distance exceeds the
-          // desired value
-          [&] {
-            return drive->GetAverageEncoderDistance() <=
-                   kAutoBackupDistanceInches;
-          },
-          // Requires the drive subsystem
-          {drive}));
-}
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/HatchSubsystem.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/HatchSubsystem.cpp
index ba1c0dd..e766d43 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/HatchSubsystem.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/HatchSubsystem.cpp
@@ -10,10 +10,14 @@
     : m_hatchSolenoid{frc::PneumaticsModuleType::CTREPCM,
                       kHatchSolenoidPorts[0], kHatchSolenoidPorts[1]} {}
 
-void HatchSubsystem::GrabHatch() {
-  m_hatchSolenoid.Set(frc::DoubleSolenoid::kForward);
+frc2::CommandPtr HatchSubsystem::GrabHatchCommand() {
+  // implicitly require `this`
+  return this->RunOnce(
+      [this] { m_hatchSolenoid.Set(frc::DoubleSolenoid::kForward); });
 }
 
-void HatchSubsystem::ReleaseHatch() {
-  m_hatchSolenoid.Set(frc::DoubleSolenoid::kReverse);
+frc2::CommandPtr HatchSubsystem::ReleaseHatchCommand() {
+  // implicitly require `this`
+  return this->RunOnce(
+      [this] { m_hatchSolenoid.Set(frc::DoubleSolenoid::kReverse); });
 }
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/Constants.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/Constants.h
index e9fbfdc..7a2bdae 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/Constants.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/Constants.h
@@ -4,7 +4,7 @@
 
 #pragma once
 
-#include <wpi/numbers>
+#include <numbers>
 
 /**
  * The Constants header provides a convenient place for teams to hold robot-wide
@@ -30,7 +30,7 @@
 constexpr double kWheelDiameterInches = 6;
 constexpr double kEncoderDistancePerPulse =
     // Assumes the encoders are directly mounted on the wheel shafts
-    (kWheelDiameterInches * wpi::numbers::pi) /
+    (kWheelDiameterInches * std::numbers::pi) /
     static_cast<double>(kEncoderCPR);
 }  // namespace DriveConstants
 
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/RobotContainer.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/RobotContainer.h
index b17c55d..002a8a6 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/RobotContainer.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/RobotContainer.h
@@ -4,17 +4,13 @@
 
 #pragma once
 
-#include <frc/PS4Controller.h>
 #include <frc/smartdashboard/SendableChooser.h>
 #include <frc2/command/Command.h>
-#include <frc2/command/FunctionalCommand.h>
-#include <frc2/command/InstantCommand.h>
-#include <frc2/command/ParallelRaceGroup.h>
-#include <frc2/command/RunCommand.h>
-#include <frc2/command/SequentialCommandGroup.h>
+#include <frc2/command/Commands.h>
+#include <frc2/command/button/CommandPS4Controller.h>
 
 #include "Constants.h"
-#include "commands/ComplexAuto.h"
+#include "commands/Autos.h"
 #include "subsystems/DriveSubsystem.h"
 #include "subsystems/HatchSubsystem.h"
 
@@ -35,7 +31,8 @@
 
  private:
   // The driver's controller
-  frc::PS4Controller m_driverController{OIConstants::kDriverControllerPort};
+  frc2::CommandPS4Controller m_driverController{
+      OIConstants::kDriverControllerPort};
 
   // The robot's subsystems and commands are defined here...
 
@@ -43,33 +40,11 @@
   DriveSubsystem m_drive;
   HatchSubsystem m_hatch;
 
+  // Commands owned by RobotContainer
+
   // The autonomous routines
-  frc2::FunctionalCommand m_simpleAuto = frc2::FunctionalCommand(
-      // Reset encoders on command start
-      [this] { m_drive.ResetEncoders(); },
-      // Drive forward while the command is executing
-      [this] { m_drive.ArcadeDrive(AutoConstants::kAutoDriveSpeed, 0); },
-      // Stop driving at the end of the command
-      [this](bool interrupted) { m_drive.ArcadeDrive(0, 0); },
-      // End the command when the robot's driven distance exceeds the desired
-      // value
-      [this] {
-        return m_drive.GetAverageEncoderDistance() >=
-               AutoConstants::kAutoDriveDistanceInches;
-      },
-      // Requires the drive subsystem
-      {&m_drive});
-  ComplexAuto m_complexAuto{&m_drive, &m_hatch};
-
-  // Assorted commands to be bound to buttons
-
-  frc2::InstantCommand m_grabHatch{[this] { m_hatch.GrabHatch(); }, {&m_hatch}};
-  frc2::InstantCommand m_releaseHatch{[this] { m_hatch.ReleaseHatch(); },
-                                      {&m_hatch}};
-  frc2::InstantCommand m_driveHalfSpeed{[this] { m_drive.SetMaxOutput(0.5); },
-                                        {}};
-  frc2::InstantCommand m_driveFullSpeed{[this] { m_drive.SetMaxOutput(1); },
-                                        {}};
+  frc2::CommandPtr m_simpleAuto = autos::SimpleAuto(&m_drive);
+  frc2::CommandPtr m_complexAuto = autos::ComplexAuto(&m_drive, &m_hatch);
 
   // The chooser for the autonomous routines
   frc::SendableChooser<frc2::Command*> m_chooser;
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/commands/Autos.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/commands/Autos.h
new file mode 100644
index 0000000..8adbdf8
--- /dev/null
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/commands/Autos.h
@@ -0,0 +1,26 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <frc2/command/CommandPtr.h>
+
+#include "subsystems/DriveSubsystem.h"
+#include "subsystems/HatchSubsystem.h"
+
+/** Container for auto command factories. */
+namespace autos {
+
+/**
+ * A simple auto that drives forward, then stops.
+ */
+frc2::CommandPtr SimpleAuto(DriveSubsystem* drive);
+
+/**
+ * A complex auto command that drives forward, releases a hatch, and then drives
+ * backward.
+ */
+frc2::CommandPtr ComplexAuto(DriveSubsystem* drive, HatchSubsystem* hatch);
+
+}  // namespace autos
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/commands/ComplexAuto.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/commands/ComplexAuto.h
deleted file mode 100644
index e746d8a..0000000
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/commands/ComplexAuto.h
+++ /dev/null
@@ -1,28 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <frc2/command/CommandHelper.h>
-#include <frc2/command/SequentialCommandGroup.h>
-
-#include "Constants.h"
-#include "subsystems/DriveSubsystem.h"
-#include "subsystems/HatchSubsystem.h"
-
-/**
- * A complex auto command that drives forward, releases a hatch, and then drives
- * backward.
- */
-class ComplexAuto
-    : public frc2::CommandHelper<frc2::SequentialCommandGroup, ComplexAuto> {
- public:
-  /**
-   * Creates a new ComplexAuto.
-   *
-   * @param drive The drive subsystem this command will run on
-   * @param hatch The hatch subsystem this command will run on
-   */
-  ComplexAuto(DriveSubsystem* drive, HatchSubsystem* hatch);
-};
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/subsystems/HatchSubsystem.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/subsystems/HatchSubsystem.h
index bb06100..b21bb56 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/subsystems/HatchSubsystem.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/subsystems/HatchSubsystem.h
@@ -6,6 +6,7 @@
 
 #include <frc/DoubleSolenoid.h>
 #include <frc/PneumaticsControlModule.h>
+#include <frc2/command/CommandPtr.h>
 #include <frc2/command/SubsystemBase.h>
 
 #include "Constants.h"
@@ -19,12 +20,12 @@
   /**
    * Grabs the hatch.
    */
-  void GrabHatch();
+  frc2::CommandPtr GrabHatchCommand();
 
   /**
    * Releases the hatch.
    */
-  void ReleaseHatch();
+  frc2::CommandPtr ReleaseHatchCommand();
 
  private:
   // Components (e.g. motor controllers and sensors) should generally be
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/RobotContainer.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/RobotContainer.cpp
index 6f8c5a6..876a984 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/RobotContainer.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/RobotContainer.cpp
@@ -28,27 +28,25 @@
   // Set up default drive command
   m_drive.SetDefaultCommand(DefaultDrive(
       &m_drive, [this] { return -m_driverController.GetLeftY(); },
-      [this] { return m_driverController.GetRightX(); }));
+      [this] { return -m_driverController.GetRightX(); }));
 }
 
 void RobotContainer::ConfigureButtonBindings() {
   // Configure your button bindings here
 
-  // NOTE: Using `new` here will leak these commands if they are ever no longer
-  // needed. This is usually a non-issue as button-bindings tend to be permanent
-  // - however, if you wish to avoid this, the commands should be
-  // stack-allocated and declared as members of RobotContainer.
+  // NOTE: since we're binding a CommandPtr, command ownership here is moved to
+  // the scheduler thus, no memory leaks!
 
   // Grab the hatch when the 'A' button is pressed.
   frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kA)
-      .WhenPressed(new GrabHatch(&m_hatch));
+      .OnTrue(GrabHatch(&m_hatch).ToPtr());
   // Release the hatch when the 'B' button is pressed.
   frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kB)
-      .WhenPressed(new ReleaseHatch(&m_hatch));
+      .OnTrue(ReleaseHatch(&m_hatch).ToPtr());
   // While holding the shoulder button, drive at half speed
   frc2::JoystickButton(&m_driverController,
                        frc::XboxController::Button::kRightBumper)
-      .WhenHeld(new HalveDriveSpeed(&m_drive));
+      .WhileTrue(HalveDriveSpeed(&m_drive).ToPtr());
 }
 
 frc2::Command* RobotContainer::GetAutonomousCommand() {
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/Constants.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/Constants.h
index e9fbfdc..7a2bdae 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/Constants.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/Constants.h
@@ -4,7 +4,7 @@
 
 #pragma once
 
-#include <wpi/numbers>
+#include <numbers>
 
 /**
  * The Constants header provides a convenient place for teams to hold robot-wide
@@ -30,7 +30,7 @@
 constexpr double kWheelDiameterInches = 6;
 constexpr double kEncoderDistancePerPulse =
     // Assumes the encoders are directly mounted on the wheel shafts
-    (kWheelDiameterInches * wpi::numbers::pi) /
+    (kWheelDiameterInches * std::numbers::pi) /
     static_cast<double>(kEncoderCPR);
 }  // namespace DriveConstants
 
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumBot/cpp/Drivetrain.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumBot/cpp/Drivetrain.cpp
index 4d3aac2..a59b758 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumBot/cpp/Drivetrain.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumBot/cpp/Drivetrain.cpp
@@ -5,10 +5,17 @@
 #include "Drivetrain.h"
 
 frc::MecanumDriveWheelSpeeds Drivetrain::GetCurrentState() const {
-  return {units::meters_per_second_t(m_frontLeftEncoder.GetRate()),
-          units::meters_per_second_t(m_frontRightEncoder.GetRate()),
-          units::meters_per_second_t(m_backLeftEncoder.GetRate()),
-          units::meters_per_second_t(m_backRightEncoder.GetRate())};
+  return {units::meters_per_second_t{m_frontLeftEncoder.GetRate()},
+          units::meters_per_second_t{m_frontRightEncoder.GetRate()},
+          units::meters_per_second_t{m_backLeftEncoder.GetRate()},
+          units::meters_per_second_t{m_backRightEncoder.GetRate()}};
+}
+
+frc::MecanumDriveWheelPositions Drivetrain::GetCurrentWheelDistances() const {
+  return {units::meter_t{m_frontLeftEncoder.GetDistance()},
+          units::meter_t{m_frontRightEncoder.GetDistance()},
+          units::meter_t{m_backLeftEncoder.GetDistance()},
+          units::meter_t{m_backRightEncoder.GetDistance()}};
 }
 
 void Drivetrain::SetSpeeds(const frc::MecanumDriveWheelSpeeds& wheelSpeeds) {
@@ -52,5 +59,5 @@
 }
 
 void Drivetrain::UpdateOdometry() {
-  m_odometry.Update(m_gyro.GetRotation2d(), GetCurrentState());
+  m_odometry.Update(m_gyro.GetRotation2d(), GetCurrentWheelDistances());
 }
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumBot/include/Drivetrain.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumBot/include/Drivetrain.h
index 9ec5fc5..fd4ae7a 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumBot/include/Drivetrain.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumBot/include/Drivetrain.h
@@ -4,6 +4,8 @@
 
 #pragma once
 
+#include <numbers>
+
 #include <frc/AnalogGyro.h>
 #include <frc/Encoder.h>
 #include <frc/controller/PIDController.h>
@@ -13,7 +15,6 @@
 #include <frc/kinematics/MecanumDriveOdometry.h>
 #include <frc/kinematics/MecanumDriveWheelSpeeds.h>
 #include <frc/motorcontrol/PWMSparkMax.h>
-#include <wpi/numbers>
 
 /**
  * Represents a mecanum drive style drivetrain.
@@ -30,6 +31,7 @@
   }
 
   frc::MecanumDriveWheelSpeeds GetCurrentState() const;
+  frc::MecanumDriveWheelPositions GetCurrentWheelDistances() const;
   void SetSpeeds(const frc::MecanumDriveWheelSpeeds& wheelSpeeds);
   void Drive(units::meters_per_second_t xSpeed,
              units::meters_per_second_t ySpeed, units::radians_per_second_t rot,
@@ -39,7 +41,7 @@
   static constexpr units::meters_per_second_t kMaxSpeed =
       3.0_mps;  // 3 meters per second
   static constexpr units::radians_per_second_t kMaxAngularSpeed{
-      wpi::numbers::pi};  // 1/2 rotation per second
+      std::numbers::pi};  // 1/2 rotation per second
 
  private:
   frc::PWMSparkMax m_frontLeftMotor{1};
@@ -68,7 +70,8 @@
       m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation,
       m_backRightLocation};
 
-  frc::MecanumDriveOdometry m_odometry{m_kinematics, m_gyro.GetRotation2d()};
+  frc::MecanumDriveOdometry m_odometry{m_kinematics, m_gyro.GetRotation2d(),
+                                       GetCurrentWheelDistances()};
 
   // Gains are for example purposes only - must be determined for your own
   // robot!
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/Constants.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/Constants.cpp
index 36912b5..99aed4e 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/Constants.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/Constants.cpp
@@ -7,10 +7,10 @@
 namespace DriveConstants {
 
 const frc::MecanumDriveKinematics kDriveKinematics{
-    frc::Translation2d(kWheelBase / 2, kTrackWidth / 2),
-    frc::Translation2d(kWheelBase / 2, -kTrackWidth / 2),
-    frc::Translation2d(-kWheelBase / 2, kTrackWidth / 2),
-    frc::Translation2d(-kWheelBase / 2, -kTrackWidth / 2)};
+    frc::Translation2d{kWheelBase / 2, kTrackWidth / 2},
+    frc::Translation2d{kWheelBase / 2, -kTrackWidth / 2},
+    frc::Translation2d{-kWheelBase / 2, kTrackWidth / 2},
+    frc::Translation2d{-kWheelBase / 2, -kTrackWidth / 2}};
 
 }  // namespace DriveConstants
 
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/RobotContainer.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/RobotContainer.cpp
index 3e2c6bf..1e9a9ae 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/RobotContainer.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/RobotContainer.cpp
@@ -30,9 +30,9 @@
   // Set up default drive command
   m_drive.SetDefaultCommand(frc2::RunCommand(
       [this] {
-        m_drive.Drive(m_driverController.GetLeftY(),
-                      m_driverController.GetRightX(),
-                      m_driverController.GetLeftX(), false);
+        m_drive.Drive(-m_driverController.GetLeftY(),
+                      -m_driverController.GetRightX(),
+                      -m_driverController.GetLeftX(), false);
       },
       {&m_drive}));
 }
@@ -43,8 +43,8 @@
   // While holding the shoulder button, drive at half speed
   frc2::JoystickButton(&m_driverController,
                        frc::XboxController::Button::kRightBumper)
-      .WhenPressed(&m_driveHalfSpeed)
-      .WhenReleased(&m_driveFullSpeed);
+      .OnTrue(&m_driveHalfSpeed)
+      .OnFalse(&m_driveFullSpeed);
 }
 
 frc2::Command* RobotContainer::GetAutonomousCommand() {
@@ -57,11 +57,11 @@
   // An example trajectory to follow.  All units in meters.
   auto exampleTrajectory = frc::TrajectoryGenerator::GenerateTrajectory(
       // Start at the origin facing the +X direction
-      frc::Pose2d(0_m, 0_m, frc::Rotation2d(0_deg)),
+      frc::Pose2d{0_m, 0_m, 0_deg},
       // Pass through these two interior waypoints, making an 's' curve path
-      {frc::Translation2d(1_m, 1_m), frc::Translation2d(2_m, -1_m)},
+      {frc::Translation2d{1_m, 1_m}, frc::Translation2d{2_m, -1_m}},
       // End 3 meters straight ahead of where we started, facing forward
-      frc::Pose2d(3_m, 0_m, frc::Rotation2d(0_deg)),
+      frc::Pose2d{3_m, 0_m, 0_deg},
       // Pass the config
       config);
 
@@ -71,8 +71,8 @@
       frc::SimpleMotorFeedforward<units::meters>(ks, kv, ka),
       DriveConstants::kDriveKinematics,
 
-      frc2::PIDController(AutoConstants::kPXController, 0, 0),
-      frc2::PIDController(AutoConstants::kPYController, 0, 0),
+      frc2::PIDController{AutoConstants::kPXController, 0, 0},
+      frc2::PIDController{AutoConstants::kPYController, 0, 0},
       frc::ProfiledPIDController<units::radians>(
           AutoConstants::kPThetaController, 0, 0,
           AutoConstants::kThetaControllerConstraints),
@@ -81,18 +81,18 @@
 
       [this]() {
         return frc::MecanumDriveWheelSpeeds{
-            units::meters_per_second_t(m_drive.GetFrontLeftEncoder().GetRate()),
-            units::meters_per_second_t(
-                m_drive.GetFrontRightEncoder().GetRate()),
-            units::meters_per_second_t(m_drive.GetRearLeftEncoder().GetRate()),
-            units::meters_per_second_t(
-                m_drive.GetRearRightEncoder().GetRate())};
+            units::meters_per_second_t{m_drive.GetFrontLeftEncoder().GetRate()},
+            units::meters_per_second_t{
+                m_drive.GetFrontRightEncoder().GetRate()},
+            units::meters_per_second_t{m_drive.GetRearLeftEncoder().GetRate()},
+            units::meters_per_second_t{
+                m_drive.GetRearRightEncoder().GetRate()}};
       },
 
-      frc2::PIDController(DriveConstants::kPFrontLeftVel, 0, 0),
-      frc2::PIDController(DriveConstants::kPRearLeftVel, 0, 0),
-      frc2::PIDController(DriveConstants::kPFrontRightVel, 0, 0),
-      frc2::PIDController(DriveConstants::kPRearRightVel, 0, 0),
+      frc2::PIDController{DriveConstants::kPFrontLeftVel, 0, 0},
+      frc2::PIDController{DriveConstants::kPRearLeftVel, 0, 0},
+      frc2::PIDController{DriveConstants::kPFrontRightVel, 0, 0},
+      frc2::PIDController{DriveConstants::kPRearRightVel, 0, 0},
 
       [this](units::volt_t frontLeft, units::volt_t rearLeft,
              units::volt_t frontRight, units::volt_t rearRight) {
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/subsystems/DriveSubsystem.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/subsystems/DriveSubsystem.cpp
index 9e06068..9120fa6 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/subsystems/DriveSubsystem.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/subsystems/DriveSubsystem.cpp
@@ -28,7 +28,8 @@
       m_rearRightEncoder{kRearRightEncoderPorts[0], kRearRightEncoderPorts[1],
                          kRearRightEncoderReversed},
 
-      m_odometry{kDriveKinematics, m_gyro.GetRotation2d(), frc::Pose2d()} {
+      m_odometry{kDriveKinematics, m_gyro.GetRotation2d(),
+                 getCurrentWheelDistances(), frc::Pose2d{}} {
   // Set the distance per pulse for the encoders
   m_frontLeftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
   m_rearLeftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
@@ -43,19 +44,13 @@
 
 void DriveSubsystem::Periodic() {
   // Implementation of subsystem periodic method goes here.
-  m_odometry.Update(
-      m_gyro.GetRotation2d(),
-      frc::MecanumDriveWheelSpeeds{
-          units::meters_per_second_t(m_frontLeftEncoder.GetRate()),
-          units::meters_per_second_t(m_rearLeftEncoder.GetRate()),
-          units::meters_per_second_t(m_frontRightEncoder.GetRate()),
-          units::meters_per_second_t(m_rearRightEncoder.GetRate())});
+  m_odometry.Update(m_gyro.GetRotation2d(), getCurrentWheelDistances());
 }
 
 void DriveSubsystem::Drive(double xSpeed, double ySpeed, double rot,
                            bool fieldRelative) {
   if (fieldRelative) {
-    m_drive.DriveCartesian(ySpeed, xSpeed, rot, -m_gyro.GetAngle());
+    m_drive.DriveCartesian(ySpeed, xSpeed, rot, m_gyro.GetRotation2d());
   } else {
     m_drive.DriveCartesian(ySpeed, xSpeed, rot);
   }
@@ -96,10 +91,18 @@
 
 frc::MecanumDriveWheelSpeeds DriveSubsystem::getCurrentWheelSpeeds() {
   return (frc::MecanumDriveWheelSpeeds{
-      units::meters_per_second_t(m_frontLeftEncoder.GetRate()),
-      units::meters_per_second_t(m_rearLeftEncoder.GetRate()),
-      units::meters_per_second_t(m_frontRightEncoder.GetRate()),
-      units::meters_per_second_t(m_rearRightEncoder.GetRate())});
+      units::meters_per_second_t{m_frontLeftEncoder.GetRate()},
+      units::meters_per_second_t{m_rearLeftEncoder.GetRate()},
+      units::meters_per_second_t{m_frontRightEncoder.GetRate()},
+      units::meters_per_second_t{m_rearRightEncoder.GetRate()}});
+}
+
+frc::MecanumDriveWheelPositions DriveSubsystem::getCurrentWheelDistances() {
+  return (frc::MecanumDriveWheelPositions{
+      units::meter_t{m_frontLeftEncoder.GetDistance()},
+      units::meter_t{m_rearLeftEncoder.GetDistance()},
+      units::meter_t{m_frontRightEncoder.GetDistance()},
+      units::meter_t{m_rearRightEncoder.GetDistance()}});
 }
 
 void DriveSubsystem::SetMaxOutput(double maxOutput) {
@@ -123,5 +126,6 @@
 }
 
 void DriveSubsystem::ResetOdometry(frc::Pose2d pose) {
-  m_odometry.ResetPosition(pose, m_gyro.GetRotation2d());
+  m_odometry.ResetPosition(m_gyro.GetRotation2d(), getCurrentWheelDistances(),
+                           pose);
 }
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/Constants.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/Constants.h
index 8d59a2c..527504a 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/Constants.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/Constants.h
@@ -2,17 +2,19 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
+#include <numbers>
+
 #include <frc/geometry/Translation2d.h>
 #include <frc/kinematics/MecanumDriveKinematics.h>
 #include <frc/trajectory/TrapezoidProfile.h>
 #include <units/acceleration.h>
 #include <units/angle.h>
+#include <units/angular_acceleration.h>
 #include <units/angular_velocity.h>
 #include <units/length.h>
 #include <units/time.h>
 #include <units/velocity.h>
 #include <units/voltage.h>
-#include <wpi/numbers>
 
 #pragma once
 
@@ -51,7 +53,7 @@
 constexpr double kWheelDiameterMeters = 0.15;
 constexpr double kEncoderDistancePerPulse =
     // Assumes the encoders are directly mounted on the wheel shafts
-    (kWheelDiameterMeters * wpi::numbers::pi) /
+    (kWheelDiameterMeters * std::numbers::pi) /
     static_cast<double>(kEncoderCPR);
 
 // These are example values only - DO NOT USE THESE FOR YOUR OWN ROBOT!
@@ -70,15 +72,10 @@
 }  // namespace DriveConstants
 
 namespace AutoConstants {
-using radians_per_second_squared_t =
-    units::compound_unit<units::radians,
-                         units::inverse<units::squared<units::second>>>;
-
-constexpr auto kMaxSpeed = units::meters_per_second_t(3);
-constexpr auto kMaxAcceleration = units::meters_per_second_squared_t(3);
-constexpr auto kMaxAngularSpeed = units::radians_per_second_t(3);
-constexpr auto kMaxAngularAcceleration =
-    units::unit_t<radians_per_second_squared_t>(3);
+constexpr auto kMaxSpeed = 3_mps;
+constexpr auto kMaxAcceleration = 3_mps_sq;
+constexpr auto kMaxAngularSpeed = 3_rad_per_s;
+constexpr auto kMaxAngularAcceleration = 3_rad_per_s_sq;
 
 constexpr double kPXController = 0.5;
 constexpr double kPYController = 0.5;
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/subsystems/DriveSubsystem.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/subsystems/DriveSubsystem.h
index 95b08b6..579a395 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/subsystems/DriveSubsystem.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/subsystems/DriveSubsystem.h
@@ -82,6 +82,13 @@
   frc::MecanumDriveWheelSpeeds getCurrentWheelSpeeds();
 
   /**
+   * Gets the distances travelled by each wheel.
+   *
+   * @return the distances travelled by each wheel.
+   */
+  frc::MecanumDriveWheelPositions getCurrentWheelDistances();
+
+  /**
    * Sets the drive MotorControllers to a desired voltage.
    */
   void SetMotorControllersVolts(units::volt_t frontLeftPower,
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp
index f8d95ac..2b57f3c 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp
@@ -21,11 +21,11 @@
   }
 
   void TeleopPeriodic() override {
-    /* Use the joystick X axis for lateral movement, Y axis for forward
+    /* Use the joystick X axis for forward movement, Y axis for lateral
      * movement, and Z axis for rotation.
      */
-    m_robotDrive.DriveCartesian(-m_stick.GetY(), m_stick.GetX(),
-                                m_stick.GetZ());
+    m_robotDrive.DriveCartesian(-m_stick.GetY(), -m_stick.GetX(),
+                                -m_stick.GetZ());
   }
 
  private:
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/cpp/Drivetrain.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/cpp/Drivetrain.cpp
index daa4b42..c1046dd 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/cpp/Drivetrain.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/cpp/Drivetrain.cpp
@@ -9,10 +9,17 @@
 #include "ExampleGlobalMeasurementSensor.h"
 
 frc::MecanumDriveWheelSpeeds Drivetrain::GetCurrentState() const {
-  return {units::meters_per_second_t(m_frontLeftEncoder.GetRate()),
-          units::meters_per_second_t(m_frontRightEncoder.GetRate()),
-          units::meters_per_second_t(m_backLeftEncoder.GetRate()),
-          units::meters_per_second_t(m_backRightEncoder.GetRate())};
+  return {units::meters_per_second_t{m_frontLeftEncoder.GetRate()},
+          units::meters_per_second_t{m_frontRightEncoder.GetRate()},
+          units::meters_per_second_t{m_backLeftEncoder.GetRate()},
+          units::meters_per_second_t{m_backRightEncoder.GetRate()}};
+}
+
+frc::MecanumDriveWheelPositions Drivetrain::GetCurrentDistances() const {
+  return {units::meter_t{m_frontLeftEncoder.GetDistance()},
+          units::meter_t{m_frontRightEncoder.GetDistance()},
+          units::meter_t{m_backLeftEncoder.GetDistance()},
+          units::meter_t{m_backRightEncoder.GetDistance()}};
 }
 
 void Drivetrain::SetSpeeds(const frc::MecanumDriveWheelSpeeds& wheelSpeeds) {
@@ -49,7 +56,7 @@
 }
 
 void Drivetrain::UpdateOdometry() {
-  m_poseEstimator.Update(m_gyro.GetRotation2d(), GetCurrentState());
+  m_poseEstimator.Update(m_gyro.GetRotation2d(), GetCurrentDistances());
 
   // Also apply vision measurements. We use 0.3 seconds in the past as an
   // example -- on a real robot, this must be calculated based either on latency
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/include/Drivetrain.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/include/Drivetrain.h
index 3eea4a2..eeaf7af 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/include/Drivetrain.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/include/Drivetrain.h
@@ -4,6 +4,8 @@
 
 #pragma once
 
+#include <numbers>
+
 #include <frc/AnalogGyro.h>
 #include <frc/Encoder.h>
 #include <frc/controller/PIDController.h>
@@ -14,7 +16,6 @@
 #include <frc/kinematics/MecanumDriveOdometry.h>
 #include <frc/kinematics/MecanumDriveWheelSpeeds.h>
 #include <frc/motorcontrol/PWMSparkMax.h>
-#include <wpi/numbers>
 
 /**
  * Represents a mecanum drive style drivetrain.
@@ -31,6 +32,7 @@
   }
 
   frc::MecanumDriveWheelSpeeds GetCurrentState() const;
+  frc::MecanumDriveWheelPositions GetCurrentDistances() const;
   void SetSpeeds(const frc::MecanumDriveWheelSpeeds& wheelSpeeds);
   void Drive(units::meters_per_second_t xSpeed,
              units::meters_per_second_t ySpeed, units::radians_per_second_t rot,
@@ -39,7 +41,7 @@
 
   static constexpr auto kMaxSpeed = 3.0_mps;  // 3 meters per second
   static constexpr units::radians_per_second_t kMaxAngularSpeed{
-      wpi::numbers::pi};  // 1/2 rotation per second
+      std::numbers::pi};  // 1/2 rotation per second
 
  private:
   frc::PWMSparkMax m_frontLeftMotor{1};
@@ -75,6 +77,6 @@
   // Gains are for example purposes only - must be determined for your own
   // robot!
   frc::MecanumDrivePoseEstimator m_poseEstimator{
-      frc::Rotation2d(), frc::Pose2d(), m_kinematics,
-      {0.1, 0.1, 0.1},   {0.05},        {0.1, 0.1, 0.1}};
+      m_kinematics,  m_gyro.GetRotation2d(), GetCurrentDistances(),
+      frc::Pose2d{}, {0.1, 0.1, 0.1},        {0.1, 0.1, 0.1}};
 };
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/include/ExampleGlobalMeasurementSensor.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/include/ExampleGlobalMeasurementSensor.h
index a4caff4..b9e2ba4 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/include/ExampleGlobalMeasurementSensor.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/include/ExampleGlobalMeasurementSensor.h
@@ -16,9 +16,9 @@
   static frc::Pose2d GetEstimatedGlobalPose(
       const frc::Pose2d& estimatedRobotPose) {
     auto randVec = frc::MakeWhiteNoiseVector(0.1, 0.1, 0.1);
-    return frc::Pose2d(estimatedRobotPose.X() + units::meter_t(randVec(0)),
-                       estimatedRobotPose.Y() + units::meter_t(randVec(1)),
+    return frc::Pose2d{estimatedRobotPose.X() + units::meter_t{randVec(0)},
+                       estimatedRobotPose.Y() + units::meter_t{randVec(1)},
                        estimatedRobotPose.Rotation() +
-                           frc::Rotation2d(units::radian_t(randVec(3))));
+                           frc::Rotation2d{units::radian_t{randVec(2)}}};
   }
 };
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/Mechanism2d/cpp/Robot.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/Mechanism2d/cpp/Robot.cpp
index 551dc78..6d1967f 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/Mechanism2d/cpp/Robot.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/Mechanism2d/cpp/Robot.cpp
@@ -41,7 +41,7 @@
     // update the dashboard mechanism's state
     m_elevator->SetLength(kElevatorMinimumLength +
                           m_elevatorEncoder.GetDistance());
-    m_wrist->SetAngle(units::degree_t(m_wristPotentiometer.Get()));
+    m_wrist->SetAngle(units::degree_t{m_wristPotentiometer.Get()});
   }
 
   void TeleopPeriodic() override {
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MotorControl/cpp/Robot.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MotorControl/cpp/Robot.cpp
index 0092ec3..7a4325f 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MotorControl/cpp/Robot.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MotorControl/cpp/Robot.cpp
@@ -2,25 +2,47 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
+#include <numbers>
+
+#include <frc/Encoder.h>
 #include <frc/Joystick.h>
 #include <frc/TimedRobot.h>
 #include <frc/motorcontrol/PWMSparkMax.h>
+#include <frc/smartdashboard/SmartDashboard.h>
 
 /**
  * This sample program shows how to control a motor using a joystick. In the
  * operator control part of the program, the joystick is read and the value is
  * written to the motor.
  *
- * Joystick analog values range from -1 to 1 and speed controller inputs as
+ * Joystick analog values range from -1 to 1 and motor controller inputs as
  * range from -1 to 1 making it easy to work together.
+ *
+ * In addition, the encoder value of an encoder connected to ports 0 and 1 is
+ * consistently sent to the Dashboard.
  */
 class Robot : public frc::TimedRobot {
  public:
   void TeleopPeriodic() override { m_motor.Set(m_stick.GetY()); }
 
+  /*
+   * The RobotPeriodic function is called every control packet no matter the
+   * robot mode.
+   */
+  void RobotPeriodic() override {
+    frc::SmartDashboard::PutNumber("Encoder", m_encoder.GetDistance());
+  }
+
+  void RobotInit() override {
+    // Use SetDistancePerPulse to set the multiplier for GetDistance
+    // This is set up assuming a 6 inch wheel with a 360 CPR encoder.
+    m_encoder.SetDistancePerPulse((std::numbers::pi * 6) / 360.0);
+  }
+
  private:
   frc::Joystick m_stick{0};
   frc::PWMSparkMax m_motor{0};
+  frc::Encoder m_encoder{0, 1};
 };
 
 #ifndef RUNNING_FRC_TESTS
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MotorControlEncoder/cpp/Robot.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MotorControlEncoder/cpp/Robot.cpp
deleted file mode 100644
index 7d0e9ba..0000000
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/MotorControlEncoder/cpp/Robot.cpp
+++ /dev/null
@@ -1,51 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include <frc/Encoder.h>
-#include <frc/Joystick.h>
-#include <frc/TimedRobot.h>
-#include <frc/motorcontrol/PWMSparkMax.h>
-#include <frc/smartdashboard/SmartDashboard.h>
-#include <wpi/numbers>
-
-/**
- * This sample program shows how to control a motor using a joystick. In the
- * operator control part of the program, the joystick is read and the value is
- * written to the motor.
- *
- * Joystick analog values range from -1 to 1 and speed controller inputs as
- * range from -1 to 1 making it easy to work together.
- *
- * In addition, the encoder value of an encoder connected to ports 0 and 1 is
- * consistently sent to the Dashboard.
- */
-class Robot : public frc::TimedRobot {
- public:
-  void TeleopPeriodic() override { m_motor.Set(m_stick.GetY()); }
-
-  /*
-   * The RobotPeriodic function is called every control packet no matter the
-   * robot mode.
-   */
-  void RobotPeriodic() override {
-    frc::SmartDashboard::PutNumber("Encoder", m_encoder.GetDistance());
-  }
-
-  void RobotInit() override {
-    // Use SetDistancePerPulse to set the multiplier for GetDistance
-    // This is set up assuming a 6 inch wheel with a 360 CPR encoder.
-    m_encoder.SetDistancePerPulse((wpi::numbers::pi * 6) / 360.0);
-  }
-
- private:
-  frc::Joystick m_stick{0};
-  frc::PWMSparkMax m_motor{0};
-  frc::Encoder m_encoder{0, 1};
-};
-
-#ifndef RUNNING_FRC_TESTS
-int main() {
-  return frc::StartRobot<Robot>();
-}
-#endif
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/RobotContainer.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/RobotContainer.cpp
index 49ee31b..a72b129 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/RobotContainer.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/RobotContainer.cpp
@@ -28,8 +28,8 @@
   // Set up default drive command
   m_drive.SetDefaultCommand(frc2::RunCommand(
       [this] {
-        m_drive.ArcadeDrive(m_driverController.GetLeftY(),
-                            m_driverController.GetRightX());
+        m_drive.ArcadeDrive(-m_driverController.GetLeftY(),
+                            -m_driverController.GetRightX());
       },
       {&m_drive}));
 }
@@ -38,21 +38,21 @@
   // Configure your button bindings here
 
   // While holding the shoulder button, drive at half speed
-  frc2::JoystickButton(&m_driverController, 6)
-      .WhenPressed(&m_driveHalfSpeed)
-      .WhenReleased(&m_driveFullSpeed);
+  frc2::JoystickButton{&m_driverController, 6}
+      .OnTrue(&m_driveHalfSpeed)
+      .OnFalse(&m_driveFullSpeed);
 }
 
 frc2::Command* RobotContainer::GetAutonomousCommand() {
   // Create a voltage constraint to ensure we don't accelerate too fast
-  frc::DifferentialDriveVoltageConstraint autoVoltageConstraint(
-      frc::SimpleMotorFeedforward<units::meters>(
-          DriveConstants::ks, DriveConstants::kv, DriveConstants::ka),
-      DriveConstants::kDriveKinematics, 10_V);
+  frc::DifferentialDriveVoltageConstraint autoVoltageConstraint{
+      frc::SimpleMotorFeedforward<units::meters>{
+          DriveConstants::ks, DriveConstants::kv, DriveConstants::ka},
+      DriveConstants::kDriveKinematics, 10_V};
 
   // Set up config for trajectory
-  frc::TrajectoryConfig config(AutoConstants::kMaxSpeed,
-                               AutoConstants::kMaxAcceleration);
+  frc::TrajectoryConfig config{AutoConstants::kMaxSpeed,
+                               AutoConstants::kMaxAcceleration};
   // Add kinematics to ensure max speed is actually obeyed
   config.SetKinematics(DriveConstants::kDriveKinematics);
   // Apply the voltage constraint
@@ -61,26 +61,27 @@
   // An example trajectory to follow.  All units in meters.
   auto exampleTrajectory = frc::TrajectoryGenerator::GenerateTrajectory(
       // Start at the origin facing the +X direction
-      frc::Pose2d(0_m, 0_m, frc::Rotation2d(0_deg)),
+      frc::Pose2d{0_m, 0_m, 0_deg},
       // Pass through these two interior waypoints, making an 's' curve path
-      {frc::Translation2d(1_m, 1_m), frc::Translation2d(2_m, -1_m)},
+      {frc::Translation2d{1_m, 1_m}, frc::Translation2d{2_m, -1_m}},
       // End 3 meters straight ahead of where we started, facing forward
-      frc::Pose2d(3_m, 0_m, frc::Rotation2d(0_deg)),
+      frc::Pose2d{3_m, 0_m, 0_deg},
       // Pass the config
       config);
 
-  frc2::RamseteCommand ramseteCommand(
-      exampleTrajectory, [this]() { return m_drive.GetPose(); },
-      frc::RamseteController(AutoConstants::kRamseteB,
-                             AutoConstants::kRamseteZeta),
-      frc::SimpleMotorFeedforward<units::meters>(
-          DriveConstants::ks, DriveConstants::kv, DriveConstants::ka),
+  frc2::RamseteCommand ramseteCommand{
+      exampleTrajectory,
+      [this]() { return m_drive.GetPose(); },
+      frc::RamseteController{AutoConstants::kRamseteB,
+                             AutoConstants::kRamseteZeta},
+      frc::SimpleMotorFeedforward<units::meters>{
+          DriveConstants::ks, DriveConstants::kv, DriveConstants::ka},
       DriveConstants::kDriveKinematics,
       [this] { return m_drive.GetWheelSpeeds(); },
-      frc2::PIDController(DriveConstants::kPDriveVel, 0, 0),
-      frc2::PIDController(DriveConstants::kPDriveVel, 0, 0),
+      frc2::PIDController{DriveConstants::kPDriveVel, 0, 0},
+      frc2::PIDController{DriveConstants::kPDriveVel, 0, 0},
       [this](auto left, auto right) { m_drive.TankDriveVolts(left, right); },
-      {&m_drive});
+      {&m_drive}};
 
   // Reset odometry to the starting pose of the trajectory.
   m_drive.ResetOdometry(exampleTrajectory.InitialPose());
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/subsystems/DriveSubsystem.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/subsystems/DriveSubsystem.cpp
index a5b853e..f8ec1db 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/subsystems/DriveSubsystem.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/subsystems/DriveSubsystem.cpp
@@ -16,7 +16,7 @@
       m_right2{kRightMotor2Port},
       m_leftEncoder{kLeftEncoderPorts[0], kLeftEncoderPorts[1]},
       m_rightEncoder{kRightEncoderPorts[0], kRightEncoderPorts[1]},
-      m_odometry{m_gyro.GetRotation2d()} {
+      m_odometry{m_gyro.GetRotation2d(), units::meter_t{0}, units::meter_t{0}} {
   // We need to invert one side of the drivetrain so that positive voltages
   // result in both sides moving forward. Depending on how your robot's
   // gearbox is constructed, you might have to invert the left side instead.
@@ -32,8 +32,8 @@
 void DriveSubsystem::Periodic() {
   // Implementation of subsystem periodic method goes here.
   m_odometry.Update(m_gyro.GetRotation2d(),
-                    units::meter_t(m_leftEncoder.GetDistance()),
-                    units::meter_t(m_rightEncoder.GetDistance()));
+                    units::meter_t{m_leftEncoder.GetDistance()},
+                    units::meter_t{m_rightEncoder.GetDistance()});
 }
 
 void DriveSubsystem::ArcadeDrive(double fwd, double rot) {
@@ -80,11 +80,13 @@
 }
 
 frc::DifferentialDriveWheelSpeeds DriveSubsystem::GetWheelSpeeds() {
-  return {units::meters_per_second_t(m_leftEncoder.GetRate()),
-          units::meters_per_second_t(m_rightEncoder.GetRate())};
+  return {units::meters_per_second_t{m_leftEncoder.GetRate()},
+          units::meters_per_second_t{m_rightEncoder.GetRate()}};
 }
 
 void DriveSubsystem::ResetOdometry(frc::Pose2d pose) {
   ResetEncoders();
-  m_odometry.ResetPosition(pose, m_gyro.GetRotation2d());
+  m_odometry.ResetPosition(m_gyro.GetRotation2d(),
+                           units::meter_t{m_leftEncoder.GetDistance()},
+                           units::meter_t{m_rightEncoder.GetDistance()}, pose);
 }
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/Constants.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/Constants.h
index 174a028..18747d4 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/Constants.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/Constants.h
@@ -2,6 +2,8 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
+#include <numbers>
+
 #include <frc/kinematics/DifferentialDriveKinematics.h>
 #include <frc/trajectory/constraint/DifferentialDriveKinematicsConstraint.h>
 #include <units/acceleration.h>
@@ -10,7 +12,6 @@
 #include <units/time.h>
 #include <units/velocity.h>
 #include <units/voltage.h>
-#include <wpi/numbers>
 
 #pragma once
 
@@ -41,7 +42,7 @@
 constexpr double kWheelDiameterInches = 6;
 constexpr double kEncoderDistancePerPulse =
     // Assumes the encoders are directly mounted on the wheel shafts
-    (kWheelDiameterInches * wpi::numbers::pi) /
+    (kWheelDiameterInches * std::numbers::pi) /
     static_cast<double>(kEncoderCPR);
 
 // These are example values only - DO NOT USE THESE FOR YOUR OWN ROBOT!
@@ -59,7 +60,7 @@
 
 namespace AutoConstants {
 constexpr auto kMaxSpeed = 3_mps;
-constexpr auto kMaxAcceleration = 3_mps_sq;
+constexpr auto kMaxAcceleration = 1_mps_sq;
 
 // Reasonable baseline values for a RAMSETE follower in units of meters and
 // seconds
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RamseteController/cpp/Drivetrain.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RamseteController/cpp/Drivetrain.cpp
index 1871688..8c1e632 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RamseteController/cpp/Drivetrain.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RamseteController/cpp/Drivetrain.cpp
@@ -23,12 +23,14 @@
 
 void Drivetrain::UpdateOdometry() {
   m_odometry.Update(m_gyro.GetRotation2d(),
-                    units::meter_t(m_leftEncoder.GetDistance()),
-                    units::meter_t(m_rightEncoder.GetDistance()));
+                    units::meter_t{m_leftEncoder.GetDistance()},
+                    units::meter_t{m_rightEncoder.GetDistance()});
 }
 
 void Drivetrain::ResetOdometry(const frc::Pose2d& pose) {
-  m_odometry.ResetPosition(pose, m_gyro.GetRotation2d());
+  m_odometry.ResetPosition(m_gyro.GetRotation2d(),
+                           units::meter_t{m_leftEncoder.GetDistance()},
+                           units::meter_t{m_rightEncoder.GetDistance()}, pose);
 }
 
 frc::Pose2d Drivetrain::GetPose() const {
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RamseteController/cpp/Robot.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RamseteController/cpp/Robot.cpp
index f47da51..d7902f1 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RamseteController/cpp/Robot.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RamseteController/cpp/Robot.cpp
@@ -79,9 +79,9 @@
 
   // An example trajectory to follow.
   frc::Trajectory m_trajectory = frc::TrajectoryGenerator::GenerateTrajectory(
-      frc::Pose2d(0_m, 0_m, 0_rad),
-      {frc::Translation2d(1_m, 1_m), frc::Translation2d(2_m, -1_m)},
-      frc::Pose2d(3_m, 0_m, 0_rad), frc::TrajectoryConfig(3_fps, 3_fps_sq));
+      frc::Pose2d{0_m, 0_m, 0_rad},
+      {frc::Translation2d{1_m, 1_m}, frc::Translation2d{2_m, -1_m}},
+      frc::Pose2d{3_m, 0_m, 0_rad}, frc::TrajectoryConfig(3_fps, 3_fps_sq));
 
   // The Ramsete Controller to follow the trajectory.
   frc::RamseteController m_ramseteController;
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RamseteController/include/Drivetrain.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RamseteController/include/Drivetrain.h
index 11fa523..40cc715 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RamseteController/include/Drivetrain.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RamseteController/include/Drivetrain.h
@@ -4,6 +4,8 @@
 
 #pragma once
 
+#include <numbers>
+
 #include <frc/AnalogGyro.h>
 #include <frc/Encoder.h>
 #include <frc/controller/PIDController.h>
@@ -14,7 +16,6 @@
 #include <frc/motorcontrol/PWMSparkMax.h>
 #include <units/angular_velocity.h>
 #include <units/length.h>
-#include <wpi/numbers>
 
 /**
  * Represents a differential drive style drivetrain.
@@ -32,9 +33,9 @@
     // Set the distance per pulse for the drive encoders. We can simply use the
     // distance traveled for one rotation of the wheel divided by the encoder
     // resolution.
-    m_leftEncoder.SetDistancePerPulse(2 * wpi::numbers::pi * kWheelRadius /
+    m_leftEncoder.SetDistancePerPulse(2 * std::numbers::pi * kWheelRadius /
                                       kEncoderResolution);
-    m_rightEncoder.SetDistancePerPulse(2 * wpi::numbers::pi * kWheelRadius /
+    m_rightEncoder.SetDistancePerPulse(2 * std::numbers::pi * kWheelRadius /
                                        kEncoderResolution);
 
     m_leftEncoder.Reset();
@@ -44,7 +45,7 @@
   static constexpr units::meters_per_second_t kMaxSpeed =
       3.0_mps;  // 3 meters per second
   static constexpr units::radians_per_second_t kMaxAngularSpeed{
-      wpi::numbers::pi};  // 1/2 rotation per second
+      std::numbers::pi};  // 1/2 rotation per second
 
   void SetSpeeds(const frc::DifferentialDriveWheelSpeeds& speeds);
   void Drive(units::meters_per_second_t xSpeed,
@@ -75,7 +76,9 @@
   frc::AnalogGyro m_gyro{0};
 
   frc::DifferentialDriveKinematics m_kinematics{kTrackWidth};
-  frc::DifferentialDriveOdometry m_odometry{m_gyro.GetRotation2d()};
+  frc::DifferentialDriveOdometry m_odometry{
+      m_gyro.GetRotation2d(), units::meter_t{m_leftEncoder.GetDistance()},
+      units::meter_t{m_rightEncoder.GetDistance()}};
 
   // Gains are for example purposes only - must be determined for your own
   // robot!
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/RapidReactCommandBot.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/RapidReactCommandBot.cpp
new file mode 100644
index 0000000..c25f0e8
--- /dev/null
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/RapidReactCommandBot.cpp
@@ -0,0 +1,50 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "RapidReactCommandBot.h"
+
+#include <frc2/command/Command.h>
+#include <frc2/command/Commands.h>
+#include <frc2/command/button/Trigger.h>
+
+#include "Constants.h"
+
+void RapidReactCommandBot::ConfigureBindings() {
+  // Automatically run the storage motor whenever the ball storage is not full,
+  // and turn it off whenever it fills.
+  frc2::Trigger([this] {
+    return m_storage.IsFull();
+  }).WhileFalse(m_storage.RunCommand());
+
+  // Automatically disable and retract the intake whenever the ball storage is
+  // full.
+  frc2::Trigger([this] {
+    return m_storage.IsFull();
+  }).OnTrue(m_intake.RetractCommand());
+
+  // Control the drive with split-stick arcade controls
+  m_drive.SetDefaultCommand(m_drive.ArcadeDriveCommand(
+      [this] { return -m_driverController.GetLeftY(); },
+      [this] { return -m_driverController.GetRightX(); }));
+
+  // Deploy the intake with the X button
+  m_driverController.X().OnTrue(m_intake.IntakeCommand());
+  // Retract the intake with the Y button
+  m_driverController.Y().OnTrue(m_intake.RetractCommand());
+
+  // Fire the shooter with the A button
+  m_driverController.A().OnTrue(
+      frc2::cmd::Parallel(
+          m_shooter.ShootCommand(ShooterConstants::kShooterTarget),
+          m_storage.RunCommand())
+          // Since we composed this inline we should give it a name
+          .WithName("Shoot"));
+}
+
+frc2::CommandPtr RapidReactCommandBot::GetAutonomousCommand() {
+  return m_drive
+      .DriveDistanceCommand(AutoConstants::kDriveDistance,
+                            AutoConstants::kDriveSpeed)
+      .WithTimeout(AutoConstants::kTimeout);
+}
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/Robot.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/Robot.cpp
new file mode 100644
index 0000000..06bbe40
--- /dev/null
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/Robot.cpp
@@ -0,0 +1,58 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "Robot.h"
+
+void Robot::RobotInit() {
+  // Configure default commands and condition bindings on robot startup
+  m_robot.ConfigureBindings();
+}
+
+void Robot::RobotPeriodic() {
+  // Runs the Scheduler.  This is responsible for polling buttons, adding
+  // newly-scheduled commands, running already-scheduled commands, removing
+  // finished or interrupted commands, and running subsystem Periodic() methods.
+  // This must be called from the robot's periodic block in order for anything
+  // in the Command-based framework to work.
+  frc2::CommandScheduler::GetInstance().Run();
+}
+
+void Robot::DisabledInit() {}
+
+void Robot::DisabledPeriodic() {}
+
+void Robot::AutonomousInit() {
+  m_autonomousCommand = m_robot.GetAutonomousCommand();
+
+  if (m_autonomousCommand) {
+    m_autonomousCommand->Schedule();
+  }
+}
+
+void Robot::AutonomousPeriodic() {}
+
+void Robot::TeleopInit() {
+  // This makes sure that the autonomous stops running when
+  // teleop starts running. If you want the autonomous to
+  // continue until interrupted by another command, remove
+  // this line or comment it out.
+  if (m_autonomousCommand) {
+    m_autonomousCommand->Cancel();
+  }
+}
+
+void Robot::TeleopPeriodic() {}
+
+void Robot::TestInit() {
+  // Cancels all running commands at the start of test mode.
+  frc2::CommandScheduler::GetInstance().CancelAll();
+}
+
+void Robot::TestPeriodic() {}
+
+#ifndef RUNNING_FRC_TESTS
+int main() {
+  return frc::StartRobot<Robot>();
+}
+#endif
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Drive.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Drive.cpp
new file mode 100644
index 0000000..98ff0ca
--- /dev/null
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Drive.cpp
@@ -0,0 +1,46 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "subsystems/Drive.h"
+
+#include <utility>
+
+#include <frc2/command/Commands.h>
+
+Drive::Drive() {
+  // We need to invert one side of the drivetrain so that positive voltages
+  // result in both sides moving forward. Depending on how your robot's
+  // gearbox is constructed, you might have to invert the left side instead.
+  m_rightMotors.SetInverted(true);
+
+  // Sets the distance per pulse for the encoders
+  m_leftEncoder.SetDistancePerPulse(DriveConstants::kEncoderDistancePerPulse);
+  m_rightEncoder.SetDistancePerPulse(DriveConstants::kEncoderDistancePerPulse);
+}
+
+frc2::CommandPtr Drive::ArcadeDriveCommand(std::function<double()> fwd,
+                                           std::function<double()> rot) {
+  return Run([this, fwd = std::move(fwd), rot = std::move(rot)] {
+           m_drive.ArcadeDrive(fwd(), rot());
+         })
+      .WithName("ArcadeDrive");
+}
+
+frc2::CommandPtr Drive::DriveDistanceCommand(units::meter_t distance,
+                                             double speed) {
+  return RunOnce([this] {
+           // Reset encoders at the start of the command
+           m_leftEncoder.Reset();
+           m_rightEncoder.Reset();
+         })
+      // Drive forward at specified speed
+      .AndThen(Run([this, speed] { m_drive.ArcadeDrive(speed, 0.0); }))
+      .Until([this, distance] {
+        return units::math::max(units::meter_t(m_leftEncoder.GetDistance()),
+                                units::meter_t(m_rightEncoder.GetDistance())) >=
+               distance;
+      })
+      // Stop the drive when the command ends
+      .FinallyDo([this](bool interrupted) { m_drive.StopMotor(); });
+}
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Intake.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Intake.cpp
new file mode 100644
index 0000000..2069185
--- /dev/null
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Intake.cpp
@@ -0,0 +1,19 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "subsystems/Intake.h"
+
+frc2::CommandPtr Intake::IntakeCommand() {
+  return RunOnce([this] { m_piston.Set(frc::DoubleSolenoid::kForward); })
+      .AndThen(Run([this] { m_motor.Set(1.0); }))
+      .WithName("Intake");
+}
+
+frc2::CommandPtr Intake::RetractCommand() {
+  return RunOnce([this] {
+           m_motor.Disable();
+           m_piston.Set(frc::DoubleSolenoid::kReverse);
+         })
+      .WithName("Retract");
+}
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Shooter.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Shooter.cpp
new file mode 100644
index 0000000..e8950ee
--- /dev/null
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Shooter.cpp
@@ -0,0 +1,38 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "subsystems/Shooter.h"
+
+#include <frc2/command/Commands.h>
+
+Shooter::Shooter() {
+  m_shooterFeedback.SetTolerance(ShooterConstants::kShooterTolerance.value());
+  m_shooterEncoder.SetDistancePerPulse(
+      ShooterConstants::kEncoderDistancePerPulse);
+
+  SetDefaultCommand(RunOnce([this] {
+                      m_shooterMotor.Disable();
+                      m_feederMotor.Disable();
+                    })
+                        .AndThen(Run([] {}))
+                        .WithName("Idle"));
+}
+
+frc2::CommandPtr Shooter::ShootCommand(units::turns_per_second_t setpoint) {
+  return frc2::cmd::Parallel(
+             // Run the shooter flywheel at the desired setpoint using
+             // feedforward and feedback
+             Run([this, setpoint] {
+               m_shooterMotor.SetVoltage(
+                   m_shooterFeedforward.Calculate(setpoint) +
+                   units::volt_t(m_shooterFeedback.Calculate(
+                       m_shooterEncoder.GetRate(), setpoint.value())));
+             }),
+             // Wait until the shooter has reached the setpoint, and then
+             // run the feeder
+             frc2::cmd::WaitUntil([this] {
+               return m_shooterFeedback.AtSetpoint();
+             }).AndThen([this] { m_feederMotor.Set(1.0); }))
+      .WithName("Shoot");
+}
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Storage.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Storage.cpp
new file mode 100644
index 0000000..3e9dc62
--- /dev/null
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Storage.cpp
@@ -0,0 +1,18 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "subsystems/Storage.h"
+
+Storage::Storage() {
+  SetDefaultCommand(
+      RunOnce([this] { m_motor.Disable(); }).AndThen([] {}).WithName("Idle"));
+}
+
+frc2::CommandPtr Storage::RunCommand() {
+  return Run([this] { m_motor.Set(1.0); }).WithName("Run");
+}
+
+bool Storage::IsFull() const {
+  return m_ballSensor.Get();
+}
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/Constants.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/Constants.h
new file mode 100644
index 0000000..330eeba
--- /dev/null
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/Constants.h
@@ -0,0 +1,79 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <numbers>
+
+#include <units/angle.h>
+#include <units/angular_velocity.h>
+#include <units/length.h>
+#include <units/time.h>
+#include <units/voltage.h>
+
+namespace DriveConstants {
+constexpr int kLeftMotor1Port = 0;
+constexpr int kLeftMotor2Port = 1;
+constexpr int kRightMotor1Port = 2;
+constexpr int kRightMotor2Port = 3;
+
+constexpr int kLeftEncoderPorts[]{0, 1};
+constexpr int kRightEncoderPorts[]{2, 3};
+constexpr bool kLeftEncoderReversed = false;
+constexpr bool kRightEncoderReversed = true;
+
+constexpr double kEncoderCPR = 1024;
+constexpr units::meter_t kWheelDiameter = 6.0_in;
+constexpr double kEncoderDistancePerPulse =
+    // Assumes the encoders are directly mounted on the wheel shafts
+    ((kWheelDiameter * std::numbers::pi) / kEncoderCPR).value();
+
+}  // namespace DriveConstants
+
+namespace IntakeConstants {
+constexpr int kMotorPort = 6;
+constexpr int kSolenoidPorts[]{0, 1};
+}  // namespace IntakeConstants
+
+namespace StorageConstants {
+constexpr int kMotorPort = 7;
+constexpr int kBallSensorPort = 6;
+}  // namespace StorageConstants
+
+namespace ShooterConstants {
+constexpr int kEncoderPorts[]{4, 5};
+constexpr bool kEncoderReversed = false;
+constexpr double kEncoderCPR = 1024;
+constexpr double kEncoderDistancePerPulse =
+    // Distance units will be rotations
+    1.0 / kEncoderCPR;
+
+constexpr int kShooterMotorPort = 4;
+constexpr int kFeederMotorPort = 5;
+
+constexpr auto kShooterFree = 5300_tps;
+constexpr auto kShooterTarget = 4000_tps;
+constexpr auto kShooterTolerance = 50_tps;
+
+// These are not real PID gains, and will have to be tuned for your specific
+// robot.
+constexpr double kP = 1;
+
+constexpr units::volt_t kS = 0.05_V;
+constexpr auto kV =
+    // Should have value 12V at free speed...
+    12.0_V / kShooterFree;
+
+constexpr double kFeederSpeed = 0.5;
+}  // namespace ShooterConstants
+
+namespace OIConstants {
+constexpr int kDriverControllerPort = 0;
+}  // namespace OIConstants
+
+namespace AutoConstants {
+constexpr units::second_t kTimeout = 3.0_s;
+constexpr units::meter_t kDriveDistance = 2.0_m;
+constexpr double kDriveSpeed = 0.5;
+}  // namespace AutoConstants
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/RapidReactCommandBot.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/RapidReactCommandBot.h
new file mode 100644
index 0000000..4f733b7
--- /dev/null
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/RapidReactCommandBot.h
@@ -0,0 +1,52 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <frc2/command/CommandPtr.h>
+#include <frc2/command/button/CommandXboxController.h>
+
+#include "Constants.h"
+#include "subsystems/Drive.h"
+#include "subsystems/Intake.h"
+#include "subsystems/Shooter.h"
+#include "subsystems/Storage.h"
+
+/**
+ * This class is where the bulk of the robot should be declared. Since
+ * Command-based is a "declarative" paradigm, very little robot logic should
+ * actually be handled in the {@link Robot} periodic methods (other than the
+ * scheduler calls). Instead, the structure of the robot (including subsystems,
+ * commands, and button mappings) should be declared here.
+ */
+class RapidReactCommandBot {
+ public:
+  /**
+   * Use this method to define bindings between conditions and commands. These
+   * are useful for automating robot behaviors based on button and sensor input.
+   *
+   * <p>Should be called during Robot::RobotInit().
+   *
+   * <p>Event binding methods are available on the frc2::Trigger class.
+   */
+  void ConfigureBindings();
+
+  /**
+   * Use this to define the command that runs during autonomous.
+   *
+   * <p>Scheduled during Robot::AutonomousInit().
+   */
+  frc2::CommandPtr GetAutonomousCommand();
+
+ private:
+  // The robot's subsystems
+  Drive m_drive;
+  Intake m_intake;
+  Shooter m_shooter;
+  Storage m_storage;
+
+  // The driver's controller
+  frc2::CommandXboxController m_driverController{
+      OIConstants::kDriverControllerPort};
+};
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/Robot.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/Robot.h
new file mode 100644
index 0000000..bab80f7
--- /dev/null
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/Robot.h
@@ -0,0 +1,30 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <optional>
+
+#include <frc/TimedRobot.h>
+#include <frc2/command/CommandPtr.h>
+
+#include "RapidReactCommandBot.h"
+
+class Robot : public frc::TimedRobot {
+ public:
+  void RobotInit() override;
+  void RobotPeriodic() override;
+  void DisabledInit() override;
+  void DisabledPeriodic() override;
+  void AutonomousInit() override;
+  void AutonomousPeriodic() override;
+  void TeleopInit() override;
+  void TeleopPeriodic() override;
+  void TestInit() override;
+  void TestPeriodic() override;
+
+ private:
+  RapidReactCommandBot m_robot;
+  std::optional<frc2::CommandPtr> m_autonomousCommand;
+};
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Drive.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Drive.h
new file mode 100644
index 0000000..9a39a14
--- /dev/null
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Drive.h
@@ -0,0 +1,58 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <functional>
+
+#include <frc/Encoder.h>
+#include <frc/drive/DifferentialDrive.h>
+#include <frc/motorcontrol/MotorControllerGroup.h>
+#include <frc/motorcontrol/PWMSparkMax.h>
+#include <frc2/command/CommandPtr.h>
+#include <frc2/command/SubsystemBase.h>
+#include <units/length.h>
+
+#include "Constants.h"
+
+class Drive : public frc2::SubsystemBase {
+ public:
+  Drive();
+  /**
+   * Returns a command that drives the robot with arcade controls.
+   *
+   * @param fwd the commanded forward movement
+   * @param rot the commanded rotation
+   */
+  [[nodiscard]] frc2::CommandPtr ArcadeDriveCommand(
+      std::function<double()> fwd, std::function<double()> rot);
+
+  /**
+   * Returns a command that drives the robot forward a specified distance at a
+   * specified speed.
+   *
+   * @param distance The distance to drive forward in meters
+   * @param speed The fraction of max speed at which to drive
+   */
+  [[nodiscard]] frc2::CommandPtr DriveDistanceCommand(units::meter_t distance,
+                                                      double speed);
+
+ private:
+  frc::PWMSparkMax m_leftLeader{DriveConstants::kLeftMotor1Port};
+  frc::PWMSparkMax m_leftFollower{DriveConstants::kLeftMotor2Port};
+  frc::PWMSparkMax m_rightLeader{DriveConstants::kRightMotor1Port};
+  frc::PWMSparkMax m_rightFollower{DriveConstants::kRightMotor2Port};
+
+  frc::MotorControllerGroup m_leftMotors{m_leftLeader, m_leftFollower};
+  frc::MotorControllerGroup m_rightMotors{m_rightLeader, m_rightFollower};
+
+  frc::DifferentialDrive m_drive{m_leftMotors, m_rightMotors};
+
+  frc::Encoder m_leftEncoder{DriveConstants::kLeftEncoderPorts[0],
+                             DriveConstants::kLeftEncoderPorts[1],
+                             DriveConstants::kLeftEncoderReversed};
+  frc::Encoder m_rightEncoder{DriveConstants::kRightEncoderPorts[0],
+                              DriveConstants::kRightEncoderPorts[1],
+                              DriveConstants::kRightEncoderReversed};
+};
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Intake.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Intake.h
new file mode 100644
index 0000000..af8d39a
--- /dev/null
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Intake.h
@@ -0,0 +1,32 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <functional>
+
+#include <frc/DoubleSolenoid.h>
+#include <frc/motorcontrol/PWMSparkMax.h>
+#include <frc2/command/CommandPtr.h>
+#include <frc2/command/SubsystemBase.h>
+
+#include "Constants.h"
+
+class Intake : public frc2::SubsystemBase {
+ public:
+  Intake() = default;
+
+  /** Returns a command that deploys the intake, and then runs the intake motor
+   * indefinitely. */
+  [[nodiscard]] frc2::CommandPtr IntakeCommand();
+
+  /** Returns a command that turns off and retracts the intake. */
+  [[nodiscard]] frc2::CommandPtr RetractCommand();
+
+ private:
+  frc::PWMSparkMax m_motor{IntakeConstants::kMotorPort};
+  frc::DoubleSolenoid m_piston{frc::PneumaticsModuleType::REVPH,
+                               IntakeConstants::kSolenoidPorts[0],
+                               IntakeConstants::kSolenoidPorts[1]};
+};
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Shooter.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Shooter.h
new file mode 100644
index 0000000..5ab2a63
--- /dev/null
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Shooter.h
@@ -0,0 +1,44 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <functional>
+
+#include <frc/Encoder.h>
+#include <frc/controller/PIDController.h>
+#include <frc/controller/SimpleMotorFeedforward.h>
+#include <frc/motorcontrol/PWMSparkMax.h>
+#include <frc2/command/CommandPtr.h>
+#include <frc2/command/SubsystemBase.h>
+#include <units/angle.h>
+#include <units/angular_velocity.h>
+
+#include "Constants.h"
+
+class Shooter : public frc2::SubsystemBase {
+ public:
+  Shooter();
+
+  /**
+   * Returns a command to shoot the balls currently stored in the robot. Spins
+   * the shooter flywheel up to the specified setpoint, and then runs the feeder
+   * motor.
+   *
+   * @param setpointRotationsPerSecond The desired shooter velocity
+   */
+  [[nodiscard]] frc2::CommandPtr ShootCommand(
+      units::turns_per_second_t setpoint);
+
+ private:
+  frc::PWMSparkMax m_shooterMotor{ShooterConstants::kShooterMotorPort};
+  frc::PWMSparkMax m_feederMotor{ShooterConstants::kFeederMotorPort};
+
+  frc::Encoder m_shooterEncoder{ShooterConstants::kEncoderPorts[0],
+                                ShooterConstants::kEncoderPorts[1],
+                                ShooterConstants::kEncoderReversed};
+  frc::SimpleMotorFeedforward<units::turns> m_shooterFeedforward{
+      ShooterConstants::kS, ShooterConstants::kV};
+  frc::PIDController m_shooterFeedback{ShooterConstants::kP, 0.0, 0.0};
+};
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Storage.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Storage.h
new file mode 100644
index 0000000..eab6da4
--- /dev/null
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Storage.h
@@ -0,0 +1,26 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <frc/DigitalInput.h>
+#include <frc/motorcontrol/PWMSparkMax.h>
+#include <frc2/command/CommandPtr.h>
+#include <frc2/command/SubsystemBase.h>
+
+#include "Constants.h"
+
+class Storage : frc2::SubsystemBase {
+ public:
+  Storage();
+  /** Returns a command that runs the storage motor indefinitely. */
+  [[nodiscard]] frc2::CommandPtr RunCommand();
+
+  /** Whether the ball storage is full. */
+  bool IsFull() const;
+
+ private:
+  frc::PWMSparkMax m_motor{StorageConstants::kMotorPort};
+  frc::DigitalInput m_ballSensor{StorageConstants::kBallSensorPort};
+};
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/RobotContainer.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/RobotContainer.cpp
index 3cbad01..f6e1fa4 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/RobotContainer.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/RobotContainer.cpp
@@ -5,7 +5,7 @@
 #include "RobotContainer.h"
 
 #include <frc/smartdashboard/SmartDashboard.h>
-#include <frc2/command/PrintCommand.h>
+#include <frc2/command/Commands.h>
 #include <frc2/command/button/Button.h>
 
 #include "commands/TeleopArcadeDrive.h"
@@ -19,11 +19,11 @@
   // Also set default commands here
   m_drive.SetDefaultCommand(TeleopArcadeDrive(
       &m_drive, [this] { return -m_controller.GetRawAxis(1); },
-      [this] { return m_controller.GetRawAxis(2); }));
+      [this] { return -m_controller.GetRawAxis(2); }));
 
   // Example of how to use the onboard IO
-  m_onboardButtonA.WhenPressed(frc2::PrintCommand("Button A Pressed"))
-      .WhenReleased(frc2::PrintCommand("Button A Released"));
+  m_onboardButtonA.OnTrue(frc2::cmd::Print("Button A Pressed"))
+      .OnFalse(frc2::cmd::Print("Button A Released"));
 
   // Setup SmartDashboard options.
   m_chooser.SetDefaultOption("Auto Routine Distance", &m_autoDistance);
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/commands/TurnDegrees.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/commands/TurnDegrees.cpp
index 2d6c148..8c1f29e 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/commands/TurnDegrees.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/commands/TurnDegrees.cpp
@@ -4,8 +4,9 @@
 
 #include "commands/TurnDegrees.h"
 
+#include <numbers>
+
 #include <units/math.h>
-#include <wpi/numbers>
 
 void TurnDegrees::Initialize() {
   // Set motors to stop, read encoder values for starting point
@@ -26,7 +27,7 @@
   // found here https://www.pololu.com/category/203/romi-chassis-kits, has a
   // wheel placement diameter (149 mm) - width of the wheel (8 mm) = 141 mm
   // or 5.551 inches. We then take into consideration the width of the tires.
-  static auto inchPerDegree = (5.551_in * wpi::numbers::pi) / 360_deg;
+  static auto inchPerDegree = (5.551_in * std::numbers::pi) / 360_deg;
 
   // Compare distance traveled from start to distance based on degree turn.
   return GetAverageTurningDistance() >= inchPerDegree * m_angle;
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/subsystems/Drivetrain.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/subsystems/Drivetrain.cpp
index 13ec2d8..979f8a0 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/subsystems/Drivetrain.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/subsystems/Drivetrain.cpp
@@ -4,7 +4,7 @@
 
 #include "subsystems/Drivetrain.h"
 
-#include <wpi/numbers>
+#include <numbers>
 
 #include "Constants.h"
 
@@ -20,9 +20,9 @@
   // gearbox is constructed, you might have to invert the left side instead.
   m_rightMotor.SetInverted(true);
 
-  m_leftEncoder.SetDistancePerPulse(wpi::numbers::pi * kWheelDiameter.value() /
+  m_leftEncoder.SetDistancePerPulse(std::numbers::pi * kWheelDiameter.value() /
                                     kCountsPerRevolution);
-  m_rightEncoder.SetDistancePerPulse(wpi::numbers::pi * kWheelDiameter.value() /
+  m_rightEncoder.SetDistancePerPulse(std::numbers::pi * kWheelDiameter.value() /
                                      kCountsPerRevolution);
   ResetEncoders();
 }
@@ -49,11 +49,11 @@
 }
 
 units::meter_t Drivetrain::GetLeftDistance() {
-  return units::meter_t(m_leftEncoder.GetDistance());
+  return units::meter_t{m_leftEncoder.GetDistance()};
 }
 
 units::meter_t Drivetrain::GetRightDistance() {
-  return units::meter_t(m_rightEncoder.GetDistance());
+  return units::meter_t{m_rightEncoder.GetDistance()};
 }
 
 units::meter_t Drivetrain::GetAverageDistance() {
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RomiReference/include/RobotContainer.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RomiReference/include/RobotContainer.h
index 821542c..ab88b15 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RomiReference/include/RobotContainer.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/RomiReference/include/RobotContainer.h
@@ -7,6 +7,7 @@
 #include <frc/Joystick.h>
 #include <frc/smartdashboard/SendableChooser.h>
 #include <frc2/command/Command.h>
+#include <frc2/command/CommandPtr.h>
 #include <frc2/command/button/Button.h>
 
 #include "Constants.h"
@@ -50,7 +51,7 @@
                         OnBoardIO::ChannelMode::INPUT};
 
   // Example button
-  frc2::Button m_onboardButtonA{
+  frc2::Trigger m_onboardButtonA{
       [this] { return m_onboardIO.GetButtonAPressed(); }};
 
   // Autonomous commands.
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SchedulerEventLogging/cpp/RobotContainer.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SchedulerEventLogging/cpp/RobotContainer.cpp
index 0c2e79c..e54c42f 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SchedulerEventLogging/cpp/RobotContainer.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SchedulerEventLogging/cpp/RobotContainer.cpp
@@ -46,14 +46,14 @@
 
   // Run instant command 1 when the 'A' button is pressed
   frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kA)
-      .WhenPressed(&m_instantCommand1);
+      .OnTrue(&m_instantCommand1);
   // Run instant command 2 when the 'X' button is pressed
   frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kX)
-      .WhenPressed(&m_instantCommand2);
+      .OnTrue(&m_instantCommand2);
   // Run instant command 3 when the 'Y' button is held; release early to
   // interrupt
   frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kY)
-      .WhenHeld(&m_waitCommand);
+      .OnTrue(&m_waitCommand);
 }
 
 frc2::Command* RobotContainer::GetAutonomousCommand() {
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ShuffleBoard/cpp/Robot.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ShuffleBoard/cpp/Robot.cpp
index a114b92..1417801 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ShuffleBoard/cpp/Robot.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/ShuffleBoard/cpp/Robot.cpp
@@ -11,7 +11,7 @@
 #include <frc/shuffleboard/Shuffleboard.h>
 #include <frc/shuffleboard/ShuffleboardLayout.h>
 #include <frc/shuffleboard/ShuffleboardTab.h>
-#include <networktables/NetworkTableEntry.h>
+#include <networktables/GenericEntry.h>
 #include <networktables/NetworkTableInstance.h>
 
 /**
@@ -57,7 +57,7 @@
 
   void AutonomousInit() override {
     // Update the Max Output for the drivetrain.
-    m_robotDrive.SetMaxOutput(m_maxSpeed.GetDouble(1.0));
+    m_robotDrive.SetMaxOutput(m_maxSpeed->GetDouble(1.0));
   }
 
  private:
@@ -73,7 +73,7 @@
   frc::Encoder m_rightEncoder{2, 3};
   frc::AnalogPotentiometer m_ElevatorPot{0};
 
-  nt::NetworkTableEntry m_maxSpeed;
+  nt::GenericEntry* m_maxSpeed;
 };
 
 #ifndef RUNNING_FRC_TESTS
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Drivetrain.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Drivetrain.cpp
index 098b997..93d0889 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Drivetrain.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Drivetrain.cpp
@@ -25,15 +25,17 @@
 
 void Drivetrain::UpdateOdometry() {
   m_odometry.Update(m_gyro.GetRotation2d(),
-                    units::meter_t(m_leftEncoder.GetDistance()),
-                    units::meter_t(m_rightEncoder.GetDistance()));
+                    units::meter_t{m_leftEncoder.GetDistance()},
+                    units::meter_t{m_rightEncoder.GetDistance()});
 }
 
 void Drivetrain::ResetOdometry(const frc::Pose2d& pose) {
   m_leftEncoder.Reset();
   m_rightEncoder.Reset();
   m_drivetrainSimulator.SetPose(pose);
-  m_odometry.ResetPosition(pose, m_gyro.GetRotation2d());
+  m_odometry.ResetPosition(m_gyro.GetRotation2d(),
+                           units::meter_t{m_leftEncoder.GetDistance()},
+                           units::meter_t{m_rightEncoder.GetDistance()}, pose);
 }
 
 void Drivetrain::SimulationPeriodic() {
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Robot.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Robot.cpp
index a6eeef4..7ea7b09 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Robot.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Robot.cpp
@@ -14,12 +14,8 @@
 class Robot : public frc::TimedRobot {
  public:
   void RobotInit() override {
-    // Flush NetworkTables every loop. This ensures that robot pose and other
-    // values are sent during every iteration.
-    SetNetworkTablesFlushEnabled(true);
-
     m_trajectory = frc::TrajectoryGenerator::GenerateTrajectory(
-        frc::Pose2d(2_m, 2_m, 0_rad), {}, frc::Pose2d(6_m, 4_m, 0_rad),
+        frc::Pose2d{2_m, 2_m, 0_rad}, {}, frc::Pose2d{6_m, 4_m, 0_rad},
         frc::TrajectoryConfig(2_mps, 2_mps_sq));
   }
 
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/include/Drivetrain.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/include/Drivetrain.h
index d8c58c2..80363b5 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/include/Drivetrain.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/include/Drivetrain.h
@@ -4,6 +4,8 @@
 
 #pragma once
 
+#include <numbers>
+
 #include <frc/AnalogGyro.h>
 #include <frc/Encoder.h>
 #include <frc/controller/PIDController.h>
@@ -22,7 +24,6 @@
 #include <units/angular_velocity.h>
 #include <units/length.h>
 #include <units/velocity.h>
-#include <wpi/numbers>
 
 /**
  * Represents a differential drive style drivetrain.
@@ -40,9 +41,9 @@
     // Set the distance per pulse for the drive encoders. We can simply use the
     // distance traveled for one rotation of the wheel divided by the encoder
     // resolution.
-    m_leftEncoder.SetDistancePerPulse(2 * wpi::numbers::pi * kWheelRadius /
+    m_leftEncoder.SetDistancePerPulse(2 * std::numbers::pi * kWheelRadius /
                                       kEncoderResolution);
-    m_rightEncoder.SetDistancePerPulse(2 * wpi::numbers::pi * kWheelRadius /
+    m_rightEncoder.SetDistancePerPulse(2 * std::numbers::pi * kWheelRadius /
                                        kEncoderResolution);
 
     m_leftEncoder.Reset();
@@ -56,7 +57,7 @@
   static constexpr units::meters_per_second_t kMaxSpeed =
       3.0_mps;  // 3 meters per second
   static constexpr units::radians_per_second_t kMaxAngularSpeed{
-      wpi::numbers::pi};  // 1/2 rotation per second
+      std::numbers::pi};  // 1/2 rotation per second
 
   void SetSpeeds(const frc::DifferentialDriveWheelSpeeds& speeds);
   void Drive(units::meters_per_second_t xSpeed,
@@ -91,7 +92,9 @@
   frc::AnalogGyro m_gyro{0};
 
   frc::DifferentialDriveKinematics m_kinematics{kTrackWidth};
-  frc::DifferentialDriveOdometry m_odometry{m_gyro.GetRotation2d()};
+  frc::DifferentialDriveOdometry m_odometry{
+      m_gyro.GetRotation2d(), units::meter_t{m_leftEncoder.GetDistance()},
+      units::meter_t{m_rightEncoder.GetDistance()}};
 
   // Gains are for example purposes only - must be determined for your own
   // robot!
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/StateSpaceArm/cpp/Robot.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/StateSpaceArm/cpp/Robot.cpp
index 0f03d37..aec9738 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/StateSpaceArm/cpp/Robot.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/StateSpaceArm/cpp/Robot.cpp
@@ -2,10 +2,11 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
+#include <numbers>
+
 #include <frc/Encoder.h>
 #include <frc/TimedRobot.h>
 #include <frc/XboxController.h>
-#include <frc/controller/LinearPlantInversionFeedforward.h>
 #include <frc/controller/LinearQuadraticRegulator.h>
 #include <frc/drive/DifferentialDrive.h>
 #include <frc/estimator/KalmanFilter.h>
@@ -16,7 +17,6 @@
 #include <frc/trajectory/TrapezoidProfile.h>
 #include <units/angle.h>
 #include <units/moment_of_inertia.h>
-#include <wpi/numbers>
 
 /**
  * This is a sample program to demonstrate how to use a state-space controller
@@ -64,8 +64,8 @@
       // qelms. Velocity error tolerance, in radians and radians per second.
       // Decrease this to more heavily penalize state excursion, or make the
       // controller behave more aggressively.
-      {1.0 * 2.0 * wpi::numbers::pi / 360.0,
-       10.0 * 2.0 * wpi::numbers::pi / 360.0},
+      {1.0 * 2.0 * std::numbers::pi / 360.0,
+       10.0 * 2.0 * std::numbers::pi / 360.0},
       // relms. Control effort (voltage) tolerance. Decrease this to more
       // heavily penalize control effort, or make the controller less
       // aggressive. 12 is a good starting point because that is the
@@ -94,16 +94,15 @@
  public:
   void RobotInit() override {
     // We go 2 pi radians per 4096 clicks.
-    m_encoder.SetDistancePerPulse(2.0 * wpi::numbers::pi / 4096.0);
+    m_encoder.SetDistancePerPulse(2.0 * std::numbers::pi / 4096.0);
   }
 
   void TeleopInit() override {
-    m_loop.Reset(
-        Eigen::Vector<double, 2>{m_encoder.GetDistance(), m_encoder.GetRate()});
+    m_loop.Reset(frc::Vectord<2>{m_encoder.GetDistance(), m_encoder.GetRate()});
 
     m_lastProfiledReference = {
-        units::radian_t(m_encoder.GetDistance()),
-        units::radians_per_second_t(m_encoder.GetRate())};
+        units::radian_t{m_encoder.GetDistance()},
+        units::radians_per_second_t{m_encoder.GetRate()}};
   }
 
   void TeleopPeriodic() override {
@@ -122,12 +121,11 @@
                                                m_lastProfiledReference))
             .Calculate(20_ms);
 
-    m_loop.SetNextR(
-        Eigen::Vector<double, 2>{m_lastProfiledReference.position.value(),
-                                 m_lastProfiledReference.velocity.value()});
+    m_loop.SetNextR(frc::Vectord<2>{m_lastProfiledReference.position.value(),
+                                    m_lastProfiledReference.velocity.value()});
 
     // Correct our Kalman filter's state vector estimate with encoder data.
-    m_loop.Correct(Eigen::Vector<double, 1>{m_encoder.GetDistance()});
+    m_loop.Correct(frc::Vectord<1>{m_encoder.GetDistance()});
 
     // Update our LQR to generate new voltage commands and use the voltages to
     // predict the next state with out Kalman filter.
@@ -136,7 +134,7 @@
     // Send the new calculated voltage to the motors.
     // voltage = duty cycle * battery voltage, so
     // duty cycle = voltage / battery voltage
-    m_motor.SetVoltage(units::volt_t(m_loop.U(0)));
+    m_motor.SetVoltage(units::volt_t{m_loop.U(0)});
   }
 };
 
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/Robot.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/Robot.cpp
index 318dc61..fce5aec 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/Robot.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/Robot.cpp
@@ -9,11 +9,7 @@
 #include <frc/smartdashboard/SmartDashboard.h>
 #include <frc2/command/CommandScheduler.h>
 
-void Robot::RobotInit() {
-  // Flush NetworkTables every loop. This ensures that robot pose and other
-  // values are sent during every iteration.
-  SetNetworkTablesFlushEnabled(true);
-}
+void Robot::RobotInit() {}
 
 /**
  * This function is called every 20 ms, no matter the mode. Use
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/RobotContainer.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/RobotContainer.cpp
index a4245d6..fec6de3 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/RobotContainer.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/RobotContainer.cpp
@@ -26,10 +26,15 @@
   ConfigureButtonBindings();
 
   // Set up default drive command
+  // A split-stick arcade command, with forward/backward controlled by the left
+  // hand, and turning controlled by the right.
+  // If you are using the keyboard as a joystick, it is recommended that you go
+  // to the following link to read about editing the keyboard settings.
+  // https://docs.wpilib.org/en/stable/docs/software/wpilib-tools/robot-simulation/simulation-gui.html#using-the-keyboard-as-a-joystick
   m_drive.SetDefaultCommand(frc2::RunCommand(
       [this] {
         m_drive.ArcadeDrive(-m_driverController.GetLeftY(),
-                            m_driverController.GetRightX());
+                            -m_driverController.GetLeftX());
       },
       {&m_drive}));
 }
@@ -48,8 +53,8 @@
   // While holding the shoulder button, drive at half speed
   frc2::JoystickButton(&m_driverController,
                        frc::XboxController::Button::kRightBumper)
-      .WhenPressed(&m_driveHalfSpeed)
-      .WhenReleased(&m_driveFullSpeed);
+      .OnTrue(&m_driveHalfSpeed)
+      .OnFalse(&m_driveFullSpeed);
 }
 
 frc2::Command* RobotContainer::GetAutonomousCommand() {
@@ -70,24 +75,24 @@
   // An example trajectory to follow.  All units in meters.
   auto exampleTrajectory = frc::TrajectoryGenerator::GenerateTrajectory(
       // Start at (1, 2) facing the +X direction
-      frc::Pose2d(1_m, 2_m, 0_deg),
+      frc::Pose2d{1_m, 2_m, 0_deg},
       // Pass through these two interior waypoints, making an 's' curve path
-      {frc::Translation2d(2_m, 3_m), frc::Translation2d(3_m, 1_m)},
+      {frc::Translation2d{2_m, 3_m}, frc::Translation2d{3_m, 1_m}},
       // End 3 meters straight ahead of where we started, facing forward
-      frc::Pose2d(4_m, 2_m, 0_deg),
+      frc::Pose2d{4_m, 2_m, 0_deg},
       // Pass the config
       config);
 
   frc2::RamseteCommand ramseteCommand(
       exampleTrajectory, [this] { return m_drive.GetPose(); },
-      frc::RamseteController(AutoConstants::kRamseteB,
-                             AutoConstants::kRamseteZeta),
+      frc::RamseteController{AutoConstants::kRamseteB,
+                             AutoConstants::kRamseteZeta},
       frc::SimpleMotorFeedforward<units::meters>(
           DriveConstants::ks, DriveConstants::kv, DriveConstants::ka),
       DriveConstants::kDriveKinematics,
       [this] { return m_drive.GetWheelSpeeds(); },
-      frc2::PIDController(DriveConstants::kPDriveVel, 0, 0),
-      frc2::PIDController(DriveConstants::kPDriveVel, 0, 0),
+      frc2::PIDController{DriveConstants::kPDriveVel, 0, 0},
+      frc2::PIDController{DriveConstants::kPDriveVel, 0, 0},
       [this](auto left, auto right) { m_drive.TankDriveVolts(left, right); },
       {&m_drive});
 
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/subsystems/DriveSubsystem.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/subsystems/DriveSubsystem.cpp
index 0971549..15d8596 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/subsystems/DriveSubsystem.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/subsystems/DriveSubsystem.cpp
@@ -30,8 +30,8 @@
 void DriveSubsystem::Periodic() {
   // Implementation of subsystem periodic method goes here.
   m_odometry.Update(m_gyro.GetRotation2d(),
-                    units::meter_t(m_leftEncoder.GetDistance()),
-                    units::meter_t(m_rightEncoder.GetDistance()));
+                    units::meter_t{m_leftEncoder.GetDistance()},
+                    units::meter_t{m_rightEncoder.GetDistance()});
   m_fieldSim.SetRobotPose(m_odometry.GetPose());
 }
 
@@ -102,12 +102,14 @@
 }
 
 frc::DifferentialDriveWheelSpeeds DriveSubsystem::GetWheelSpeeds() {
-  return {units::meters_per_second_t(m_leftEncoder.GetRate()),
-          units::meters_per_second_t(m_rightEncoder.GetRate())};
+  return {units::meters_per_second_t{m_leftEncoder.GetRate()},
+          units::meters_per_second_t{m_rightEncoder.GetRate()}};
 }
 
 void DriveSubsystem::ResetOdometry(frc::Pose2d pose) {
   ResetEncoders();
   m_drivetrainSimulator.SetPose(pose);
-  m_odometry.ResetPosition(pose, m_gyro.GetRotation2d());
+  m_odometry.ResetPosition(m_gyro.GetRotation2d(),
+                           units::meter_t{m_leftEncoder.GetDistance()},
+                           units::meter_t{m_rightEncoder.GetDistance()}, pose);
 }
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/include/Constants.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/include/Constants.h
index b12eef1..d8080ca 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/include/Constants.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/include/Constants.h
@@ -2,6 +2,8 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
+#include <numbers>
+
 #include <frc/kinematics/DifferentialDriveKinematics.h>
 #include <frc/system/plant/DCMotor.h>
 #include <frc/system/plant/LinearSystemId.h>
@@ -12,7 +14,6 @@
 #include <units/time.h>
 #include <units/velocity.h>
 #include <units/voltage.h>
-#include <wpi/numbers>
 
 #pragma once
 
@@ -43,7 +44,7 @@
 constexpr auto kWheelDiameter = 6_in;
 constexpr double kEncoderDistancePerPulse =
     // Assumes the encoders are directly mounted on the wheel shafts
-    (kWheelDiameter.value() * wpi::numbers::pi) /
+    (kWheelDiameter.value() * std::numbers::pi) /
     static_cast<double>(kEncoderCPR);
 
 // These are example values only - DO NOT USE THESE FOR YOUR OWN ROBOT!
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/include/subsystems/DriveSubsystem.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/include/subsystems/DriveSubsystem.h
index 395133c..57392c7 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/include/subsystems/DriveSubsystem.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/include/subsystems/DriveSubsystem.h
@@ -144,17 +144,21 @@
 
   // The left-side drive encoder
   frc::Encoder m_leftEncoder{DriveConstants::kLeftEncoderPorts[0],
-                             DriveConstants::kLeftEncoderPorts[1]};
+                             DriveConstants::kLeftEncoderPorts[1],
+                             DriveConstants::kLeftEncoderReversed};
 
   // The right-side drive encoder
   frc::Encoder m_rightEncoder{DriveConstants::kRightEncoderPorts[0],
-                              DriveConstants::kRightEncoderPorts[1]};
+                              DriveConstants::kRightEncoderPorts[1],
+                              DriveConstants::kRightEncoderReversed};
 
   // The gyro sensor
   frc::ADXRS450_Gyro m_gyro;
 
   // Odometry class for tracking robot pose
-  frc::DifferentialDriveOdometry m_odometry{m_gyro.GetRotation2d()};
+  frc::DifferentialDriveOdometry m_odometry{
+      m_gyro.GetRotation2d(), units::meter_t{m_leftEncoder.GetDistance()},
+      units::meter_t{m_rightEncoder.GetDistance()}};
 
   // These classes help simulate our drivetrain.
   frc::sim::DifferentialDrivetrainSim m_drivetrainSimulator{
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/StateSpaceElevator/cpp/Robot.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/StateSpaceElevator/cpp/Robot.cpp
index 4c9d65e..7decddd 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/StateSpaceElevator/cpp/Robot.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/StateSpaceElevator/cpp/Robot.cpp
@@ -2,6 +2,8 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
+#include <numbers>
+
 #include <frc/Encoder.h>
 #include <frc/TimedRobot.h>
 #include <frc/XboxController.h>
@@ -17,7 +19,6 @@
 #include <units/length.h>
 #include <units/mass.h>
 #include <units/velocity.h>
-#include <wpi/numbers>
 
 /**
  * This is a sample program to demonstrate how to use a state-space controller
@@ -90,17 +91,16 @@
  public:
   void RobotInit() override {
     // Circumference = pi * d, so distance per click = pi * d / counts
-    m_encoder.SetDistancePerPulse(2.0 * wpi::numbers::pi * kDrumRadius.value() /
+    m_encoder.SetDistancePerPulse(2.0 * std::numbers::pi * kDrumRadius.value() /
                                   4096.0);
   }
 
   void TeleopInit() override {
     // Reset our loop to make sure it's in a known state.
-    m_loop.Reset(
-        Eigen::Vector<double, 2>{m_encoder.GetDistance(), m_encoder.GetRate()});
+    m_loop.Reset(frc::Vectord<2>{m_encoder.GetDistance(), m_encoder.GetRate()});
 
-    m_lastProfiledReference = {units::meter_t(m_encoder.GetDistance()),
-                               units::meters_per_second_t(m_encoder.GetRate())};
+    m_lastProfiledReference = {units::meter_t{m_encoder.GetDistance()},
+                               units::meters_per_second_t{m_encoder.GetRate()}};
   }
 
   void TeleopPeriodic() override {
@@ -119,12 +119,11 @@
                                               m_lastProfiledReference))
             .Calculate(20_ms);
 
-    m_loop.SetNextR(
-        Eigen::Vector<double, 2>{m_lastProfiledReference.position.value(),
-                                 m_lastProfiledReference.velocity.value()});
+    m_loop.SetNextR(frc::Vectord<2>{m_lastProfiledReference.position.value(),
+                                    m_lastProfiledReference.velocity.value()});
 
     // Correct our Kalman filter's state vector estimate with encoder data.
-    m_loop.Correct(Eigen::Vector<double, 1>{m_encoder.GetDistance()});
+    m_loop.Correct(frc::Vectord<1>{m_encoder.GetDistance()});
 
     // Update our LQR to generate new voltage commands and use the voltages to
     // predict the next state with out Kalman filter.
@@ -133,7 +132,7 @@
     // Send the new calculated voltage to the motors.
     // voltage = duty cycle * battery voltage, so
     // duty cycle = voltage / battery voltage
-    m_motor.SetVoltage(units::volt_t(m_loop.U(0)));
+    m_motor.SetVoltage(units::volt_t{m_loop.U(0)});
   }
 };
 
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheel/cpp/Robot.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheel/cpp/Robot.cpp
index 636916f..5d413ab 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheel/cpp/Robot.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheel/cpp/Robot.cpp
@@ -2,6 +2,8 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
+#include <numbers>
+
 #include <frc/DriverStation.h>
 #include <frc/Encoder.h>
 #include <frc/TimedRobot.h>
@@ -14,7 +16,6 @@
 #include <frc/system/plant/DCMotor.h>
 #include <frc/system/plant/LinearSystemId.h>
 #include <units/angular_velocity.h>
-#include <wpi/numbers>
 
 /**
  * This is a sample program to demonstrate how to use a state-space controller
@@ -81,11 +82,11 @@
  public:
   void RobotInit() override {
     // We go 2 pi radians per 4096 clicks.
-    m_encoder.SetDistancePerPulse(2.0 * wpi::numbers::pi / 4096.0);
+    m_encoder.SetDistancePerPulse(2.0 * std::numbers::pi / 4096.0);
   }
 
   void TeleopInit() override {
-    m_loop.Reset(Eigen::Vector<double, 1>{m_encoder.GetRate()});
+    m_loop.Reset(frc::Vectord<1>{m_encoder.GetRate()});
   }
 
   void TeleopPeriodic() override {
@@ -93,14 +94,14 @@
     // setpoint of a PID controller.
     if (m_joystick.GetRightBumper()) {
       // We pressed the bumper, so let's set our next reference
-      m_loop.SetNextR(Eigen::Vector<double, 1>{kSpinup.value()});
+      m_loop.SetNextR(frc::Vectord<1>{kSpinup.value()});
     } else {
       // We released the bumper, so let's spin down
-      m_loop.SetNextR(Eigen::Vector<double, 1>{0.0});
+      m_loop.SetNextR(frc::Vectord<1>{0.0});
     }
 
     // Correct our Kalman filter's state vector estimate with encoder data.
-    m_loop.Correct(Eigen::Vector<double, 1>{m_encoder.GetRate()});
+    m_loop.Correct(frc::Vectord<1>{m_encoder.GetRate()});
 
     // Update our LQR to generate new voltage commands and use the voltages to
     // predict the next state with out Kalman filter.
@@ -109,7 +110,7 @@
     // Send the new calculated voltage to the motors.
     // voltage = duty cycle * battery voltage, so
     // duty cycle = voltage / battery voltage
-    m_motor.SetVoltage(units::volt_t(m_loop.U(0)));
+    m_motor.SetVoltage(units::volt_t{m_loop.U(0)});
   }
 };
 
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheelSysId/cpp/Robot.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheelSysId/cpp/Robot.cpp
index 69d1953..d3bab6e 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheelSysId/cpp/Robot.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheelSysId/cpp/Robot.cpp
@@ -2,11 +2,12 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
+#include <numbers>
+
 #include <frc/DriverStation.h>
 #include <frc/Encoder.h>
 #include <frc/TimedRobot.h>
 #include <frc/XboxController.h>
-#include <frc/controller/LinearPlantInversionFeedforward.h>
 #include <frc/controller/LinearQuadraticRegulator.h>
 #include <frc/drive/DifferentialDrive.h>
 #include <frc/estimator/KalmanFilter.h>
@@ -14,7 +15,6 @@
 #include <frc/system/LinearSystemLoop.h>
 #include <frc/system/plant/DCMotor.h>
 #include <frc/system/plant/LinearSystemId.h>
-#include <wpi/numbers>
 
 /**
  * This is a sample program to demonstrate how to use a state-space controller
@@ -82,11 +82,11 @@
  public:
   void RobotInit() override {
     // We go 2 pi radians per 4096 clicks.
-    m_encoder.SetDistancePerPulse(2.0 * wpi::numbers::pi / 4096.0);
+    m_encoder.SetDistancePerPulse(2.0 * std::numbers::pi / 4096.0);
   }
 
   void TeleopInit() override {
-    m_loop.Reset(Eigen::Vector<double, 1>{m_encoder.GetRate()});
+    m_loop.Reset(frc::Vectord<1>{m_encoder.GetRate()});
   }
 
   void TeleopPeriodic() override {
@@ -94,14 +94,14 @@
     // setpoint of a PID controller.
     if (m_joystick.GetRightBumper()) {
       // We pressed the bumper, so let's set our next reference
-      m_loop.SetNextR(Eigen::Vector<double, 1>{kSpinup.value()});
+      m_loop.SetNextR(frc::Vectord<1>{kSpinup.value()});
     } else {
       // We released the bumper, so let's spin down
-      m_loop.SetNextR(Eigen::Vector<double, 1>{0.0});
+      m_loop.SetNextR(frc::Vectord<1>{0.0});
     }
 
     // Correct our Kalman filter's state vector estimate with encoder data.
-    m_loop.Correct(Eigen::Vector<double, 1>{m_encoder.GetRate()});
+    m_loop.Correct(frc::Vectord<1>{m_encoder.GetRate()});
 
     // Update our LQR to generate new voltage commands and use the voltages to
     // predict the next state with out Kalman filter.
@@ -110,7 +110,7 @@
     // Send the new calculated voltage to the motors.
     // voltage = duty cycle * battery voltage, so
     // duty cycle = voltage / battery voltage
-    m_motor.SetVoltage(units::volt_t(m_loop.U(0)));
+    m_motor.SetVoltage(units::volt_t{m_loop.U(0)});
   }
 };
 
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveBot/cpp/Drivetrain.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveBot/cpp/Drivetrain.cpp
index 709f403..537da53 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveBot/cpp/Drivetrain.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveBot/cpp/Drivetrain.cpp
@@ -23,7 +23,7 @@
 }
 
 void Drivetrain::UpdateOdometry() {
-  m_odometry.Update(m_gyro.GetRotation2d(), m_frontLeft.GetState(),
-                    m_frontRight.GetState(), m_backLeft.GetState(),
-                    m_backRight.GetState());
+  m_odometry.Update(m_gyro.GetRotation2d(),
+                    {m_frontLeft.GetPosition(), m_frontRight.GetPosition(),
+                     m_backLeft.GetPosition(), m_backRight.GetPosition()});
 }
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveBot/cpp/SwerveModule.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveBot/cpp/SwerveModule.cpp
index 24a6527..0f9e27e 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveBot/cpp/SwerveModule.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveBot/cpp/SwerveModule.cpp
@@ -4,8 +4,9 @@
 
 #include "SwerveModule.h"
 
+#include <numbers>
+
 #include <frc/geometry/Rotation2d.h>
-#include <wpi/numbers>
 
 SwerveModule::SwerveModule(const int driveMotorChannel,
                            const int turningMotorChannel,
@@ -20,31 +21,36 @@
   // Set the distance per pulse for the drive encoder. We can simply use the
   // distance traveled for one rotation of the wheel divided by the encoder
   // resolution.
-  m_driveEncoder.SetDistancePerPulse(2 * wpi::numbers::pi * kWheelRadius /
+  m_driveEncoder.SetDistancePerPulse(2 * std::numbers::pi * kWheelRadius /
                                      kEncoderResolution);
 
   // Set the distance (in this case, angle) per pulse for the turning encoder.
-  // This is the the angle through an entire rotation (2 * wpi::numbers::pi)
+  // This is the the angle through an entire rotation (2 * std::numbers::pi)
   // divided by the encoder resolution.
-  m_turningEncoder.SetDistancePerPulse(2 * wpi::numbers::pi /
+  m_turningEncoder.SetDistancePerPulse(2 * std::numbers::pi /
                                        kEncoderResolution);
 
   // Limit the PID Controller's input range between -pi and pi and set the input
   // to be continuous.
   m_turningPIDController.EnableContinuousInput(
-      -units::radian_t(wpi::numbers::pi), units::radian_t(wpi::numbers::pi));
+      -units::radian_t{std::numbers::pi}, units::radian_t{std::numbers::pi});
 }
 
 frc::SwerveModuleState SwerveModule::GetState() const {
   return {units::meters_per_second_t{m_driveEncoder.GetRate()},
-          frc::Rotation2d(units::radian_t(m_turningEncoder.Get()))};
+          units::radian_t{m_turningEncoder.GetDistance()}};
+}
+
+frc::SwerveModulePosition SwerveModule::GetPosition() const {
+  return {units::meter_t{m_driveEncoder.GetDistance()},
+          units::radian_t{m_turningEncoder.GetDistance()}};
 }
 
 void SwerveModule::SetDesiredState(
     const frc::SwerveModuleState& referenceState) {
   // Optimize the reference state to avoid spinning further than 90 degrees
   const auto state = frc::SwerveModuleState::Optimize(
-      referenceState, units::radian_t(m_turningEncoder.Get()));
+      referenceState, units::radian_t{m_turningEncoder.GetDistance()});
 
   // Calculate the drive output from the drive PID controller.
   const auto driveOutput = m_drivePIDController.Calculate(
@@ -54,7 +60,7 @@
 
   // Calculate the turning motor output from the turning PID controller.
   const auto turnOutput = m_turningPIDController.Calculate(
-      units::radian_t(m_turningEncoder.Get()), state.angle.Radians());
+      units::radian_t{m_turningEncoder.GetDistance()}, state.angle.Radians());
 
   const auto turnFeedforward = m_turnFeedforward.Calculate(
       m_turningPIDController.GetSetpoint().velocity);
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveBot/include/Drivetrain.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveBot/include/Drivetrain.h
index 2b3cc0e..87233d2 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveBot/include/Drivetrain.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveBot/include/Drivetrain.h
@@ -4,11 +4,12 @@
 
 #pragma once
 
+#include <numbers>
+
 #include <frc/AnalogGyro.h>
 #include <frc/geometry/Translation2d.h>
 #include <frc/kinematics/SwerveDriveKinematics.h>
 #include <frc/kinematics/SwerveDriveOdometry.h>
-#include <wpi/numbers>
 
 #include "SwerveModule.h"
 
@@ -27,7 +28,7 @@
   static constexpr units::meters_per_second_t kMaxSpeed =
       3.0_mps;  // 3 meters per second
   static constexpr units::radians_per_second_t kMaxAngularSpeed{
-      wpi::numbers::pi};  // 1/2 rotation per second
+      std::numbers::pi};  // 1/2 rotation per second
 
  private:
   frc::Translation2d m_frontLeftLocation{+0.381_m, +0.381_m};
@@ -46,5 +47,9 @@
       m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation,
       m_backRightLocation};
 
-  frc::SwerveDriveOdometry<4> m_odometry{m_kinematics, m_gyro.GetRotation2d()};
+  frc::SwerveDriveOdometry<4> m_odometry{
+      m_kinematics,
+      m_gyro.GetRotation2d(),
+      {m_frontLeft.GetPosition(), m_frontRight.GetPosition(),
+       m_backLeft.GetPosition(), m_backRight.GetPosition()}};
 };
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveBot/include/SwerveModule.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveBot/include/SwerveModule.h
index 00a938b..1861498 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveBot/include/SwerveModule.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveBot/include/SwerveModule.h
@@ -4,17 +4,19 @@
 
 #pragma once
 
+#include <numbers>
+
 #include <frc/Encoder.h>
 #include <frc/controller/PIDController.h>
 #include <frc/controller/ProfiledPIDController.h>
 #include <frc/controller/SimpleMotorFeedforward.h>
+#include <frc/kinematics/SwerveModulePosition.h>
 #include <frc/kinematics/SwerveModuleState.h>
 #include <frc/motorcontrol/PWMSparkMax.h>
 #include <units/angular_velocity.h>
 #include <units/time.h>
 #include <units/velocity.h>
 #include <units/voltage.h>
-#include <wpi/numbers>
 
 class SwerveModule {
  public:
@@ -22,6 +24,7 @@
                int driveEncoderChannelA, int driveEncoderChannelB,
                int turningEncoderChannelA, int turningEncoderChannelB);
   frc::SwerveModuleState GetState() const;
+  frc::SwerveModulePosition GetPosition() const;
   void SetDesiredState(const frc::SwerveModuleState& state);
 
  private:
@@ -29,9 +32,9 @@
   static constexpr int kEncoderResolution = 4096;
 
   static constexpr auto kModuleMaxAngularVelocity =
-      wpi::numbers::pi * 1_rad_per_s;  // radians per second
+      std::numbers::pi * 1_rad_per_s;  // radians per second
   static constexpr auto kModuleMaxAngularAcceleration =
-      wpi::numbers::pi * 2_rad_per_s / 1_s;  // radians per second^2
+      std::numbers::pi * 2_rad_per_s / 1_s;  // radians per second^2
 
   frc::PWMSparkMax m_driveMotor;
   frc::PWMSparkMax m_turningMotor;
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/RobotContainer.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/RobotContainer.cpp
index a35314e..52b25b9 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/RobotContainer.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/RobotContainer.cpp
@@ -35,9 +35,9 @@
   m_drive.SetDefaultCommand(frc2::RunCommand(
       [this] {
         m_drive.Drive(
-            units::meters_per_second_t(m_driverController.GetLeftY()),
-            units::meters_per_second_t(m_driverController.GetLeftX()),
-            units::radians_per_second_t(m_driverController.GetRightX()), false);
+            units::meters_per_second_t{m_driverController.GetLeftY()},
+            units::meters_per_second_t{m_driverController.GetLeftX()},
+            units::radians_per_second_t{m_driverController.GetRightX()}, false);
       },
       {&m_drive}));
 }
@@ -54,11 +54,11 @@
   // An example trajectory to follow.  All units in meters.
   auto exampleTrajectory = frc::TrajectoryGenerator::GenerateTrajectory(
       // Start at the origin facing the +X direction
-      frc::Pose2d(0_m, 0_m, frc::Rotation2d(0_deg)),
+      frc::Pose2d{0_m, 0_m, 0_deg},
       // Pass through these two interior waypoints, making an 's' curve path
-      {frc::Translation2d(1_m, 1_m), frc::Translation2d(2_m, -1_m)},
+      {frc::Translation2d{1_m, 1_m}, frc::Translation2d{2_m, -1_m}},
       // End 3 meters straight ahead of where we started, facing forward
-      frc::Pose2d(3_m, 0_m, frc::Rotation2d(0_deg)),
+      frc::Pose2d{3_m, 0_m, 0_deg},
       // Pass the config
       config);
 
@@ -66,16 +66,16 @@
       AutoConstants::kPThetaController, 0, 0,
       AutoConstants::kThetaControllerConstraints};
 
-  thetaController.EnableContinuousInput(units::radian_t(-wpi::numbers::pi),
-                                        units::radian_t(wpi::numbers::pi));
+  thetaController.EnableContinuousInput(units::radian_t{-std::numbers::pi},
+                                        units::radian_t{std::numbers::pi});
 
   frc2::SwerveControllerCommand<4> swerveControllerCommand(
       exampleTrajectory, [this]() { return m_drive.GetPose(); },
 
       m_drive.kDriveKinematics,
 
-      frc2::PIDController(AutoConstants::kPXController, 0, 0),
-      frc2::PIDController(AutoConstants::kPYController, 0, 0), thetaController,
+      frc2::PIDController{AutoConstants::kPXController, 0, 0},
+      frc2::PIDController{AutoConstants::kPYController, 0, 0}, thetaController,
 
       [this](auto moduleStates) { m_drive.SetModuleStates(moduleStates); },
 
@@ -88,10 +88,5 @@
   return new frc2::SequentialCommandGroup(
       std::move(swerveControllerCommand),
       frc2::InstantCommand(
-          [this]() {
-            m_drive.Drive(units::meters_per_second_t(0),
-                          units::meters_per_second_t(0),
-                          units::radians_per_second_t(0), false);
-          },
-          {}));
+          [this]() { m_drive.Drive(0_mps, 0_mps, 0_rad_per_s, false); }, {}));
 }
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/subsystems/DriveSubsystem.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/subsystems/DriveSubsystem.cpp
index fd15100..4b60372 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/subsystems/DriveSubsystem.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/subsystems/DriveSubsystem.cpp
@@ -36,13 +36,17 @@
           kRearRightDriveEncoderPorts,    kRearRightTurningEncoderPorts,
           kRearRightDriveEncoderReversed, kRearRightTurningEncoderReversed},
 
-      m_odometry{kDriveKinematics, m_gyro.GetRotation2d(), frc::Pose2d()} {}
+      m_odometry{kDriveKinematics,
+                 m_gyro.GetRotation2d(),
+                 {m_frontLeft.GetPosition(), m_frontRight.GetPosition(),
+                  m_rearLeft.GetPosition(), m_rearRight.GetPosition()},
+                 frc::Pose2d{}} {}
 
 void DriveSubsystem::Periodic() {
   // Implementation of subsystem periodic method goes here.
-  m_odometry.Update(m_gyro.GetRotation2d(), m_frontLeft.GetState(),
-                    m_rearLeft.GetState(), m_frontRight.GetState(),
-                    m_rearRight.GetState());
+  m_odometry.Update(m_gyro.GetRotation2d(),
+                    {m_frontLeft.GetPosition(), m_rearLeft.GetPosition(),
+                     m_frontRight.GetPosition(), m_rearRight.GetPosition()});
 }
 
 void DriveSubsystem::Drive(units::meters_per_second_t xSpeed,
@@ -98,6 +102,9 @@
 }
 
 void DriveSubsystem::ResetOdometry(frc::Pose2d pose) {
-  m_odometry.ResetPosition(pose,
-                           frc::Rotation2d(units::degree_t(GetHeading())));
+  m_odometry.ResetPosition(
+      GetHeading(),
+      {m_frontLeft.GetPosition(), m_frontRight.GetPosition(),
+       m_rearLeft.GetPosition(), m_rearRight.GetPosition()},
+      pose);
 }
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/subsystems/SwerveModule.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/subsystems/SwerveModule.cpp
index 4d20ec8..bb0362e 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/subsystems/SwerveModule.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/subsystems/SwerveModule.cpp
@@ -4,8 +4,9 @@
 
 #include "subsystems/SwerveModule.h"
 
+#include <numbers>
+
 #include <frc/geometry/Rotation2d.h>
-#include <wpi/numbers>
 
 #include "Constants.h"
 
@@ -27,7 +28,7 @@
       ModuleConstants::kDriveEncoderDistancePerPulse);
 
   // Set the distance (in this case, angle) per pulse for the turning encoder.
-  // This is the the angle through an entire rotation (2 * wpi::numbers::pi)
+  // This is the the angle through an entire rotation (2 * std::numbers::pi)
   // divided by the encoder resolution.
   m_turningEncoder.SetDistancePerPulse(
       ModuleConstants::kTurningEncoderDistancePerPulse);
@@ -35,19 +36,24 @@
   // Limit the PID Controller's input range between -pi and pi and set the input
   // to be continuous.
   m_turningPIDController.EnableContinuousInput(
-      units::radian_t(-wpi::numbers::pi), units::radian_t(wpi::numbers::pi));
+      units::radian_t{-std::numbers::pi}, units::radian_t{std::numbers::pi});
 }
 
 frc::SwerveModuleState SwerveModule::GetState() {
   return {units::meters_per_second_t{m_driveEncoder.GetRate()},
-          frc::Rotation2d(units::radian_t(m_turningEncoder.Get()))};
+          units::radian_t{m_turningEncoder.GetDistance()}};
+}
+
+frc::SwerveModulePosition SwerveModule::GetPosition() {
+  return {units::meter_t{m_driveEncoder.GetDistance()},
+          units::radian_t{m_turningEncoder.GetDistance()}};
 }
 
 void SwerveModule::SetDesiredState(
     const frc::SwerveModuleState& referenceState) {
   // Optimize the reference state to avoid spinning further than 90 degrees
   const auto state = frc::SwerveModuleState::Optimize(
-      referenceState, units::radian_t(m_turningEncoder.Get()));
+      referenceState, units::radian_t{m_turningEncoder.GetDistance()});
 
   // Calculate the drive output from the drive PID controller.
   const auto driveOutput = m_drivePIDController.Calculate(
@@ -55,7 +61,7 @@
 
   // Calculate the turning motor output from the turning PID controller.
   auto turnOutput = m_turningPIDController.Calculate(
-      units::radian_t(m_turningEncoder.Get()), state.angle.Radians());
+      units::radian_t{m_turningEncoder.GetDistance()}, state.angle.Radians());
 
   // Set the motor outputs.
   m_driveMotor.Set(driveOutput);
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/Constants.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/Constants.h
index e6fa136..cacab87 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/Constants.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/Constants.h
@@ -2,17 +2,19 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
+#include <numbers>
+
 #include <frc/geometry/Translation2d.h>
 #include <frc/kinematics/SwerveDriveKinematics.h>
 #include <frc/trajectory/TrapezoidProfile.h>
 #include <units/acceleration.h>
 #include <units/angle.h>
+#include <units/angular_acceleration.h>
 #include <units/angular_velocity.h>
 #include <units/length.h>
 #include <units/time.h>
 #include <units/velocity.h>
 #include <units/voltage.h>
-#include <wpi/numbers>
 
 #pragma once
 
@@ -76,27 +78,22 @@
 constexpr double kWheelDiameterMeters = 0.15;
 constexpr double kDriveEncoderDistancePerPulse =
     // Assumes the encoders are directly mounted on the wheel shafts
-    (kWheelDiameterMeters * wpi::numbers::pi) /
+    (kWheelDiameterMeters * std::numbers::pi) /
     static_cast<double>(kEncoderCPR);
 
 constexpr double kTurningEncoderDistancePerPulse =
     // Assumes the encoders are directly mounted on the wheel shafts
-    (wpi::numbers::pi * 2) / static_cast<double>(kEncoderCPR);
+    (std::numbers::pi * 2) / static_cast<double>(kEncoderCPR);
 
 constexpr double kPModuleTurningController = 1;
 constexpr double kPModuleDriveController = 1;
 }  // namespace ModuleConstants
 
 namespace AutoConstants {
-using radians_per_second_squared_t =
-    units::compound_unit<units::radians,
-                         units::inverse<units::squared<units::second>>>;
-
-constexpr auto kMaxSpeed = units::meters_per_second_t(3);
-constexpr auto kMaxAcceleration = units::meters_per_second_squared_t(3);
-constexpr auto kMaxAngularSpeed = units::radians_per_second_t(3.142);
-constexpr auto kMaxAngularAcceleration =
-    units::unit_t<radians_per_second_squared_t>(3.142);
+constexpr auto kMaxSpeed = 3_mps;
+constexpr auto kMaxAcceleration = 3_mps_sq;
+constexpr auto kMaxAngularSpeed = 3.142_rad_per_s;
+constexpr auto kMaxAngularAcceleration = 3.142_rad_per_s_sq;
 
 constexpr double kPXController = 0.5;
 constexpr double kPYController = 0.5;
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/subsystems/DriveSubsystem.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/subsystems/DriveSubsystem.h
index 5233f3f..e9ed17b 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/subsystems/DriveSubsystem.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/subsystems/DriveSubsystem.h
@@ -94,10 +94,10 @@
       0.7_m;  // Distance between centers of front and back wheels on robot
 
   frc::SwerveDriveKinematics<4> kDriveKinematics{
-      frc::Translation2d(kWheelBase / 2, kTrackWidth / 2),
-      frc::Translation2d(kWheelBase / 2, -kTrackWidth / 2),
-      frc::Translation2d(-kWheelBase / 2, kTrackWidth / 2),
-      frc::Translation2d(-kWheelBase / 2, -kTrackWidth / 2)};
+      frc::Translation2d{kWheelBase / 2, kTrackWidth / 2},
+      frc::Translation2d{kWheelBase / 2, -kTrackWidth / 2},
+      frc::Translation2d{-kWheelBase / 2, kTrackWidth / 2},
+      frc::Translation2d{-kWheelBase / 2, -kTrackWidth / 2}};
 
  private:
   // Components (e.g. motor controllers and sensors) should generally be
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/subsystems/SwerveModule.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/subsystems/SwerveModule.h
index 4208b35..f0d5ede 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/subsystems/SwerveModule.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/subsystems/SwerveModule.h
@@ -4,22 +4,20 @@
 
 #pragma once
 
+#include <numbers>
+
 #include <frc/Encoder.h>
 #include <frc/controller/PIDController.h>
 #include <frc/controller/ProfiledPIDController.h>
 #include <frc/geometry/Rotation2d.h>
+#include <frc/kinematics/SwerveModulePosition.h>
 #include <frc/kinematics/SwerveModuleState.h>
 #include <frc/motorcontrol/Spark.h>
 #include <frc/trajectory/TrapezoidProfile.h>
-#include <wpi/numbers>
 
 #include "Constants.h"
 
 class SwerveModule {
-  using radians_per_second_squared_t =
-      units::compound_unit<units::radians,
-                           units::inverse<units::squared<units::second>>>;
-
  public:
   SwerveModule(int driveMotorChannel, int turningMotorChannel,
                const int driveEncoderPorts[2], const int turningEncoderPorts[2],
@@ -27,6 +25,8 @@
 
   frc::SwerveModuleState GetState();
 
+  frc::SwerveModulePosition GetPosition();
+
   void SetDesiredState(const frc::SwerveModuleState& state);
 
   void ResetEncoders();
@@ -36,12 +36,10 @@
   // ProfiledPIDController's constraints only take in meters per second and
   // meters per second squared.
 
-  static constexpr units::radians_per_second_t kModuleMaxAngularVelocity =
-      units::radians_per_second_t(wpi::numbers::pi);  // radians per second
-  static constexpr units::unit_t<radians_per_second_squared_t>
-      kModuleMaxAngularAcceleration =
-          units::unit_t<radians_per_second_squared_t>(
-              wpi::numbers::pi * 2.0);  // radians per second squared
+  static constexpr auto kModuleMaxAngularVelocity =
+      units::radians_per_second_t{std::numbers::pi};
+  static constexpr auto kModuleMaxAngularAcceleration =
+      units::radians_per_second_squared_t{std::numbers::pi * 2.0};
 
   frc::Spark m_driveMotor;
   frc::Spark m_turningMotor;
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/cpp/Drivetrain.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/cpp/Drivetrain.cpp
index 33a3233..5402e87 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/cpp/Drivetrain.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/cpp/Drivetrain.cpp
@@ -27,9 +27,9 @@
 }
 
 void Drivetrain::UpdateOdometry() {
-  m_poseEstimator.Update(m_gyro.GetRotation2d(), m_frontLeft.GetState(),
-                         m_frontRight.GetState(), m_backLeft.GetState(),
-                         m_backRight.GetState());
+  m_poseEstimator.Update(m_gyro.GetRotation2d(),
+                         {m_frontLeft.GetPosition(), m_frontRight.GetPosition(),
+                          m_backLeft.GetPosition(), m_backRight.GetPosition()});
 
   // Also apply vision measurements. We use 0.3 seconds in the past as an
   // example -- on a real robot, this must be calculated based either on latency
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/cpp/SwerveModule.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/cpp/SwerveModule.cpp
index 968ccad..c5a0839 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/cpp/SwerveModule.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/cpp/SwerveModule.cpp
@@ -4,8 +4,9 @@
 
 #include "SwerveModule.h"
 
+#include <numbers>
+
 #include <frc/geometry/Rotation2d.h>
-#include <wpi/numbers>
 
 SwerveModule::SwerveModule(const int driveMotorChannel,
                            const int turningMotorChannel,
@@ -20,31 +21,36 @@
   // Set the distance per pulse for the drive encoder. We can simply use the
   // distance traveled for one rotation of the wheel divided by the encoder
   // resolution.
-  m_driveEncoder.SetDistancePerPulse(2 * wpi::numbers::pi *
+  m_driveEncoder.SetDistancePerPulse(2 * std::numbers::pi *
                                      kWheelRadius.value() / kEncoderResolution);
 
   // Set the distance (in this case, angle) per pulse for the turning encoder.
-  // This is the the angle through an entire rotation (2 * wpi::numbers::pi)
+  // This is the the angle through an entire rotation (2 * std::numbers::pi)
   // divided by the encoder resolution.
-  m_turningEncoder.SetDistancePerPulse(2 * wpi::numbers::pi /
+  m_turningEncoder.SetDistancePerPulse(2 * std::numbers::pi /
                                        kEncoderResolution);
 
   // Limit the PID Controller's input range between -pi and pi and set the input
   // to be continuous.
   m_turningPIDController.EnableContinuousInput(
-      -units::radian_t(wpi::numbers::pi), units::radian_t(wpi::numbers::pi));
+      -units::radian_t{std::numbers::pi}, units::radian_t{std::numbers::pi});
 }
 
 frc::SwerveModuleState SwerveModule::GetState() const {
   return {units::meters_per_second_t{m_driveEncoder.GetRate()},
-          frc::Rotation2d(units::radian_t(m_turningEncoder.Get()))};
+          units::radian_t{m_turningEncoder.GetDistance()}};
+}
+
+frc::SwerveModulePosition SwerveModule::GetPosition() const {
+  return {units::meter_t{m_driveEncoder.GetDistance()},
+          units::radian_t{m_turningEncoder.GetDistance()}};
 }
 
 void SwerveModule::SetDesiredState(
     const frc::SwerveModuleState& referenceState) {
   // Optimize the reference state to avoid spinning further than 90 degrees
   const auto state = frc::SwerveModuleState::Optimize(
-      referenceState, units::radian_t(m_turningEncoder.Get()));
+      referenceState, units::radian_t{m_turningEncoder.GetDistance()});
 
   // Calculate the drive output from the drive PID controller.
   const auto driveOutput = m_drivePIDController.Calculate(
@@ -54,7 +60,7 @@
 
   // Calculate the turning motor output from the turning PID controller.
   const auto turnOutput = m_turningPIDController.Calculate(
-      units::radian_t(m_turningEncoder.Get()), state.angle.Radians());
+      units::radian_t{m_turningEncoder.GetDistance()}, state.angle.Radians());
 
   const auto turnFeedforward = m_turnFeedforward.Calculate(
       m_turningPIDController.GetSetpoint().velocity);
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/include/Drivetrain.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/include/Drivetrain.h
index f525729..e042291 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/include/Drivetrain.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/include/Drivetrain.h
@@ -4,12 +4,13 @@
 
 #pragma once
 
+#include <numbers>
+
 #include <frc/AnalogGyro.h>
 #include <frc/estimator/SwerveDrivePoseEstimator.h>
 #include <frc/geometry/Translation2d.h>
 #include <frc/kinematics/SwerveDriveKinematics.h>
 #include <frc/kinematics/SwerveDriveOdometry.h>
-#include <wpi/numbers>
 
 #include "SwerveModule.h"
 
@@ -27,7 +28,7 @@
 
   static constexpr auto kMaxSpeed = 3.0_mps;  // 3 meters per second
   static constexpr units::radians_per_second_t kMaxAngularSpeed{
-      wpi::numbers::pi};  // 1/2 rotation per second
+      std::numbers::pi};  // 1/2 rotation per second
 
  private:
   frc::Translation2d m_frontLeftLocation{+0.381_m, +0.381_m};
@@ -49,6 +50,11 @@
   // Gains are for example purposes only - must be determined for your own
   // robot!
   frc::SwerveDrivePoseEstimator<4> m_poseEstimator{
-      frc::Rotation2d(), frc::Pose2d(), m_kinematics,
-      {0.1, 0.1, 0.1},   {0.05},        {0.1, 0.1, 0.1}};
+      m_kinematics,
+      frc::Rotation2d{},
+      {m_frontLeft.GetPosition(), m_frontRight.GetPosition(),
+       m_backLeft.GetPosition(), m_backRight.GetPosition()},
+      frc::Pose2d{},
+      {0.1, 0.1, 0.1},
+      {0.1, 0.1, 0.1}};
 };
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/include/ExampleGlobalMeasurementSensor.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/include/ExampleGlobalMeasurementSensor.h
index a4caff4..b9e2ba4 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/include/ExampleGlobalMeasurementSensor.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/include/ExampleGlobalMeasurementSensor.h
@@ -16,9 +16,9 @@
   static frc::Pose2d GetEstimatedGlobalPose(
       const frc::Pose2d& estimatedRobotPose) {
     auto randVec = frc::MakeWhiteNoiseVector(0.1, 0.1, 0.1);
-    return frc::Pose2d(estimatedRobotPose.X() + units::meter_t(randVec(0)),
-                       estimatedRobotPose.Y() + units::meter_t(randVec(1)),
+    return frc::Pose2d{estimatedRobotPose.X() + units::meter_t{randVec(0)},
+                       estimatedRobotPose.Y() + units::meter_t{randVec(1)},
                        estimatedRobotPose.Rotation() +
-                           frc::Rotation2d(units::radian_t(randVec(3))));
+                           frc::Rotation2d{units::radian_t{randVec(2)}}};
   }
 };
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/include/SwerveModule.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/include/SwerveModule.h
index 7456584..049d507 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/include/SwerveModule.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/include/SwerveModule.h
@@ -4,17 +4,19 @@
 
 #pragma once
 
+#include <numbers>
+
 #include <frc/Encoder.h>
 #include <frc/controller/PIDController.h>
 #include <frc/controller/ProfiledPIDController.h>
 #include <frc/controller/SimpleMotorFeedforward.h>
+#include <frc/kinematics/SwerveModulePosition.h>
 #include <frc/kinematics/SwerveModuleState.h>
 #include <frc/motorcontrol/PWMSparkMax.h>
 #include <units/angular_velocity.h>
 #include <units/time.h>
 #include <units/velocity.h>
 #include <units/voltage.h>
-#include <wpi/numbers>
 
 class SwerveModule {
  public:
@@ -22,6 +24,7 @@
                int driveEncoderChannelA, int driveEncoderChannelB,
                int turningEncoderChannelA, int turningEncoderChannelB);
   frc::SwerveModuleState GetState() const;
+  frc::SwerveModulePosition GetPosition() const;
   void SetDesiredState(const frc::SwerveModuleState& state);
 
  private:
@@ -29,9 +32,9 @@
   static constexpr int kEncoderResolution = 4096;
 
   static constexpr auto kModuleMaxAngularVelocity =
-      wpi::numbers::pi * 1_rad_per_s;  // radians per second
+      std::numbers::pi * 1_rad_per_s;  // radians per second
   static constexpr auto kModuleMaxAngularAcceleration =
-      wpi::numbers::pi * 2_rad_per_s / 1_s;  // radians per second^2
+      std::numbers::pi * 2_rad_per_s / 1_s;  // radians per second^2
 
   frc::PWMSparkMax m_driveMotor;
   frc::PWMSparkMax m_turningMotor;
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/TankDrive/cpp/Robot.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/TankDrive/cpp/Robot.cpp
index c003762..4e48d47 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/TankDrive/cpp/Robot.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/TankDrive/cpp/Robot.cpp
@@ -28,7 +28,7 @@
 
   void TeleopPeriodic() override {
     // Drive with tank style
-    m_robotDrive.TankDrive(m_leftStick.GetY(), m_rightStick.GetY());
+    m_robotDrive.TankDrive(-m_leftStick.GetY(), -m_rightStick.GetY());
   }
 };
 
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/UnitTest/cpp/Robot.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/UnitTest/cpp/Robot.cpp
new file mode 100644
index 0000000..9434b46
--- /dev/null
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/UnitTest/cpp/Robot.cpp
@@ -0,0 +1,32 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "Robot.h"
+
+/**
+ * This function is called periodically during operator control.
+ */
+void Robot::TeleopPeriodic() {
+  // Activate the intake while the trigger is held
+  if (m_joystick.GetTrigger()) {
+    m_intake.Activate(IntakeConstants::kIntakeSpeed);
+  } else {
+    m_intake.Activate(0);
+  }
+
+  // Toggle deploying the intake when the top button is pressed
+  if (m_joystick.GetTop()) {
+    if (m_intake.IsDeployed()) {
+      m_intake.Retract();
+    } else {
+      m_intake.Deploy();
+    }
+  }
+}
+
+#ifndef RUNNING_FRC_TESTS
+int main() {
+  return frc::StartRobot<Robot>();
+}
+#endif
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/UnitTest/cpp/subsystems/Intake.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/UnitTest/cpp/subsystems/Intake.cpp
new file mode 100644
index 0000000..5a878e7
--- /dev/null
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/UnitTest/cpp/subsystems/Intake.cpp
@@ -0,0 +1,26 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "subsystems/Intake.h"
+
+void Intake::Deploy() {
+  m_piston.Set(frc::DoubleSolenoid::Value::kForward);
+}
+
+void Intake::Retract() {
+  m_piston.Set(frc::DoubleSolenoid::Value::kReverse);
+  m_motor.Set(0);  // turn off the motor
+}
+
+void Intake::Activate(double speed) {
+  if (IsDeployed()) {
+    m_motor.Set(speed);
+  } else {  // if piston isn't open, do nothing
+    m_motor.Set(0);
+  }
+}
+
+bool Intake::IsDeployed() const {
+  return m_piston.Get() == frc::DoubleSolenoid::Value::kForward;
+}
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/UnitTest/include/Constants.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/UnitTest/include/Constants.h
new file mode 100644
index 0000000..2ad9b07
--- /dev/null
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/UnitTest/include/Constants.h
@@ -0,0 +1,26 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+/**
+ * The Constants header provides a convenient place for teams to hold robot-wide
+ * numerical or bool constants.  This should not be used for any other purpose.
+ *
+ * It is generally a good idea to place constants into subsystem- or
+ * command-specific namespaces within this header, which can then be used where
+ * they are needed.
+ */
+
+namespace IntakeConstants {
+constexpr int kMotorPort = 1;
+
+constexpr int kPistonFwdChannel = 0;
+constexpr int kPistonRevChannel = 1;
+constexpr double kIntakeSpeed = 0.5;
+}  // namespace IntakeConstants
+
+namespace OperatorConstants {
+constexpr int kJoystickIndex = 0;
+}  // namespace OperatorConstants
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/UnitTest/include/Robot.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/UnitTest/include/Robot.h
new file mode 100644
index 0000000..492dded
--- /dev/null
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/UnitTest/include/Robot.h
@@ -0,0 +1,20 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <frc/Joystick.h>
+#include <frc/TimedRobot.h>
+
+#include "Constants.h"
+#include "subsystems/Intake.h"
+
+class Robot : public frc::TimedRobot {
+ public:
+  void TeleopPeriodic() override;
+
+ private:
+  Intake m_intake;
+  frc::Joystick m_joystick{OperatorConstants::kJoystickIndex};
+};
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/UnitTest/include/subsystems/Intake.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/UnitTest/include/subsystems/Intake.h
new file mode 100644
index 0000000..20cf1b6
--- /dev/null
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/UnitTest/include/subsystems/Intake.h
@@ -0,0 +1,24 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <frc/DoubleSolenoid.h>
+#include <frc/motorcontrol/PWMSparkMax.h>
+
+#include "Constants.h"
+
+class Intake {
+ public:
+  void Deploy();
+  void Retract();
+  void Activate(double speed);
+  bool IsDeployed() const;
+
+ private:
+  frc::PWMSparkMax m_motor{IntakeConstants::kMotorPort};
+  frc::DoubleSolenoid m_piston{frc::PneumaticsModuleType::CTREPCM,
+                               IntakeConstants::kPistonFwdChannel,
+                               IntakeConstants::kPistonRevChannel};
+};
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/examples.json b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/examples.json
index 9eb5b6b..aaec45d 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/examples.json
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/examples/examples.json
@@ -1,19 +1,6 @@
 [
   {
-    "name": "Motor Controller",
-    "description": "Demonstrate controlling a single motor with a Joystick.",
-    "tags": [
-      "Robot and Motor",
-      "Actuators",
-      "Joystick",
-      "Complete List"
-    ],
-    "foldername": "MotorControl",
-    "gradlebase": "cpp",
-    "commandversion": 2
-  },
-  {
-    "name": "Motor Control With Encoder",
+    "name": "Motor Control",
     "description": "Demonstrate controlling a single motor with a Joystick and displaying the net movement of the motor using an encoder.",
     "tags": [
       "Robot and Motor",
@@ -23,7 +10,7 @@
       "Joystick",
       "Complete List"
     ],
-    "foldername": "MotorControlEncoder",
+    "foldername": "MotorControl",
     "gradlebase": "cpp",
     "commandversion": 2
   },
@@ -85,6 +72,16 @@
     "commandversion": 2
   },
   {
+    "name": "EventLoop",
+    "description": "Demonstrate managing a ball system using EventLoop and BooleanEvent.",
+    "tags": [
+      "EventLoop"
+    ],
+    "foldername": "EventLoop",
+    "gradlebase": "cpp",
+    "commandversion": 2
+  },
+  {
     "name": "Arcade Drive",
     "description": "An example program which demonstrates the use of Arcade Drive with the DifferentialDrive class",
     "tags": [
@@ -347,6 +344,18 @@
     "commandversion": 2
   },
   {
+    "name": "Rapid React Command Bot",
+    "description": "A fully-functional command-based fender bot for the 2022 game using the new command framework.",
+    "tags": [
+      "Complete robot",
+      "Command-based",
+      "Lambdas"
+    ],
+    "foldername": "RapidReactCommandBot",
+    "gradlebase": "cpp",
+    "commandversion": 2
+  },
+  {
     "name": "Select Command Example",
     "description": "An example showing how to use the SelectCommand class from the new command framework.",
     "tags": [
@@ -600,7 +609,6 @@
     ],
     "foldername": "StateSpaceFlywheel",
     "gradlebase": "cpp",
-    "mainclass": "Main",
     "commandversion": 2
   },
   {
@@ -619,7 +627,6 @@
     ],
     "foldername": "StateSpaceFlywheelSysId",
     "gradlebase": "cpp",
-    "mainclass": "Main",
     "commandversion": 2
   },
   {
@@ -635,7 +642,6 @@
     ],
     "foldername": "StateSpaceElevator",
     "gradlebase": "cpp",
-    "mainclass": "Main",
     "commandversion": 2
   },
   {
@@ -651,7 +657,6 @@
     ],
     "foldername": "StateSpaceArm",
     "gradlebase": "cpp",
-    "mainclass": "Main",
     "commandversion": 2
   },
   {
@@ -668,7 +673,6 @@
     ],
     "foldername": "ElevatorSimulation",
     "gradlebase": "cpp",
-    "mainclass": "Main",
     "commandversion": 2
   },
   {
@@ -684,7 +688,6 @@
     ],
     "foldername": "DifferentialDrivePoseEstimator",
     "gradlebase": "cpp",
-    "mainclass": "Main",
     "commandversion": 2
   },
   {
@@ -700,7 +703,6 @@
     ],
     "foldername": "MecanumDrivePoseEstimator",
     "gradlebase": "cpp",
-    "mainclass": "Main",
     "commandversion": 2
   },
   {
@@ -718,7 +720,16 @@
     ],
     "foldername": "ArmSimulation",
     "gradlebase": "cpp",
-    "mainclass": "Main",
+    "commandversion": 2
+  },
+  {
+    "name": "UnitTesting",
+    "description": "Demonstrates basic unit testing for a robot project.",
+    "tags": [
+      "Testing"
+    ],
+    "foldername": "UnitTest",
+    "gradlebase": "cpp",
     "commandversion": 2
   },
   {
@@ -736,7 +747,6 @@
     ],
     "foldername": "SimpleDifferentialDriveSimulation",
     "gradlebase": "cpp",
-    "mainclass": "Main",
     "commandversion": 2
   },
   {
@@ -754,7 +764,6 @@
     ],
     "foldername": "StateSpaceDifferentialDriveSimulation",
     "gradlebase": "cpp",
-    "mainclass": "Main",
     "commandversion": 2
   },
   {
@@ -771,7 +780,6 @@
     ],
     "foldername": "SwerveDrivePoseEstimator",
     "gradlebase": "cpp",
-    "mainclass": "Main",
     "commandversion": 2
   }
 ]
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/Robot.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/Robot.cpp
index 426b989..c1c1ae6 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/Robot.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/Robot.cpp
@@ -4,7 +4,6 @@
 
 #include "Robot.h"
 
-#include <frc/smartdashboard/SmartDashboard.h>
 #include <frc2/command/CommandScheduler.h>
 
 void Robot::RobotInit() {}
@@ -37,7 +36,7 @@
 void Robot::AutonomousInit() {
   m_autonomousCommand = m_container.GetAutonomousCommand();
 
-  if (m_autonomousCommand != nullptr) {
+  if (m_autonomousCommand) {
     m_autonomousCommand->Schedule();
   }
 }
@@ -49,9 +48,8 @@
   // teleop starts running. If you want the autonomous to
   // continue until interrupted by another command, remove
   // this line or comment it out.
-  if (m_autonomousCommand != nullptr) {
+  if (m_autonomousCommand) {
     m_autonomousCommand->Cancel();
-    m_autonomousCommand = nullptr;
   }
 }
 
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/RobotContainer.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/RobotContainer.cpp
index 8ba2094..4300501 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/RobotContainer.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/RobotContainer.cpp
@@ -4,18 +4,32 @@
 
 #include "RobotContainer.h"
 
-RobotContainer::RobotContainer() : m_autonomousCommand(&m_subsystem) {
+#include <frc2/command/button/Trigger.h>
+
+#include "commands/Autos.h"
+#include "commands/ExampleCommand.h"
+
+RobotContainer::RobotContainer() {
   // Initialize all of your commands and subsystems here
 
   // Configure the button bindings
-  ConfigureButtonBindings();
+  ConfigureBindings();
 }
 
-void RobotContainer::ConfigureButtonBindings() {
-  // Configure your button bindings here
+void RobotContainer::ConfigureBindings() {
+  // Configure your trigger bindings here
+
+  // Schedule `ExampleCommand` when `exampleCondition` changes to `true`
+  frc2::Trigger([this] {
+    return m_subsystem.ExampleCondition();
+  }).OnTrue(ExampleCommand(&m_subsystem).ToPtr());
+
+  // Schedule `ExampleMethodCommand` when the Xbox controller's B button is
+  // pressed, cancelling on release.
+  m_driverController.B().WhileTrue(m_subsystem.ExampleMethodCommand());
 }
 
-frc2::Command* RobotContainer::GetAutonomousCommand() {
+frc2::CommandPtr RobotContainer::GetAutonomousCommand() {
   // An example command will be run in autonomous
-  return &m_autonomousCommand;
+  return autos::ExampleAuto(&m_subsystem);
 }
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/commands/Autos.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/commands/Autos.cpp
new file mode 100644
index 0000000..3eb0958
--- /dev/null
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/commands/Autos.cpp
@@ -0,0 +1,14 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "commands/Autos.h"
+
+#include <frc2/command/Commands.h>
+
+#include "commands/ExampleCommand.h"
+
+frc2::CommandPtr autos::ExampleAuto(ExampleSubsystem* subsystem) {
+  return frc2::cmd::Sequence(subsystem->ExampleMethodCommand(),
+                             ExampleCommand(subsystem).ToPtr());
+}
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/commands/ExampleCommand.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/commands/ExampleCommand.cpp
index e551aa1..f7ab3e2 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/commands/ExampleCommand.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/commands/ExampleCommand.cpp
@@ -5,4 +5,7 @@
 #include "commands/ExampleCommand.h"
 
 ExampleCommand::ExampleCommand(ExampleSubsystem* subsystem)
-    : m_subsystem{subsystem} {}
+    : m_subsystem{subsystem} {
+  // Register that this command requires the subsystem.
+  AddRequirements(m_subsystem);
+}
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/subsystems/ExampleSubsystem.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/subsystems/ExampleSubsystem.cpp
index 4a31aee..1660de7 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/subsystems/ExampleSubsystem.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/subsystems/ExampleSubsystem.cpp
@@ -8,6 +8,17 @@
   // Implementation of subsystem constructor goes here.
 }
 
+frc2::CommandPtr ExampleSubsystem::ExampleMethodCommand() {
+  // Inline construction of command goes here.
+  // Subsystem::RunOnce implicitly requires `this` subsystem.
+  return RunOnce([/* this */] { /* one-time action goes here */ });
+}
+
+bool ExampleSubsystem::ExampleCondition() {
+  // Query some boolean state, such as a digital sensor.
+  return false;
+}
+
 void ExampleSubsystem::Periodic() {
   // Implementation of subsystem periodic method goes here.
 }
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbased/include/Constants.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbased/include/Constants.h
index 20cc88a..963b31c 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbased/include/Constants.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbased/include/Constants.h
@@ -13,3 +13,9 @@
  * command-specific namespaces within this header, which can then be used where
  * they are needed.
  */
+
+namespace OperatorConstants {
+
+constexpr int kDriverControllerPort = 0;
+
+}  // namespace OperatorConstants
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbased/include/Robot.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbased/include/Robot.h
index 25e3229..e9d45e7 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbased/include/Robot.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbased/include/Robot.h
@@ -4,8 +4,10 @@
 
 #pragma once
 
+#include <optional>
+
 #include <frc/TimedRobot.h>
-#include <frc2/command/Command.h>
+#include <frc2/command/CommandPtr.h>
 
 #include "RobotContainer.h"
 
@@ -24,9 +26,9 @@
   void SimulationPeriodic() override;
 
  private:
-  // Have it null by default so that if testing teleop it
+  // Have it empty by default so that if testing teleop it
   // doesn't have undefined behavior and potentially crash.
-  frc2::Command* m_autonomousCommand = nullptr;
+  std::optional<frc2::CommandPtr> m_autonomousCommand;
 
   RobotContainer m_container;
 };
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbased/include/RobotContainer.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbased/include/RobotContainer.h
index 2988968..697b9a2 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbased/include/RobotContainer.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbased/include/RobotContainer.h
@@ -4,9 +4,10 @@
 
 #pragma once
 
-#include <frc2/command/Command.h>
+#include <frc2/command/CommandPtr.h>
+#include <frc2/command/button/CommandXboxController.h>
 
-#include "commands/ExampleCommand.h"
+#include "Constants.h"
 #include "subsystems/ExampleSubsystem.h"
 
 /**
@@ -14,18 +15,21 @@
  * Command-based is a "declarative" paradigm, very little robot logic should
  * actually be handled in the {@link Robot} periodic methods (other than the
  * scheduler calls).  Instead, the structure of the robot (including subsystems,
- * commands, and button mappings) should be declared here.
+ * commands, and trigger mappings) should be declared here.
  */
 class RobotContainer {
  public:
   RobotContainer();
 
-  frc2::Command* GetAutonomousCommand();
+  frc2::CommandPtr GetAutonomousCommand();
 
  private:
-  // The robot's subsystems and commands are defined here...
-  ExampleSubsystem m_subsystem;
-  ExampleCommand m_autonomousCommand;
+  // Replace with CommandPS4Controller or CommandJoystick if needed
+  frc2::CommandXboxController m_driverController{
+      OperatorConstants::kDriverControllerPort};
 
-  void ConfigureButtonBindings();
+  // The robot's subsystems are defined here...
+  ExampleSubsystem m_subsystem;
+
+  void ConfigureBindings();
 };
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbased/include/commands/Autos.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbased/include/commands/Autos.h
new file mode 100644
index 0000000..62e2b56
--- /dev/null
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbased/include/commands/Autos.h
@@ -0,0 +1,16 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <frc2/command/CommandPtr.h>
+
+#include "subsystems/ExampleSubsystem.h"
+
+namespace autos {
+/**
+ * Example static factory for an autonomous command.
+ */
+frc2::CommandPtr ExampleAuto(ExampleSubsystem* subsystem);
+}  // namespace autos
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbased/include/subsystems/ExampleSubsystem.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbased/include/subsystems/ExampleSubsystem.h
index a805151..669f2ed 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbased/include/subsystems/ExampleSubsystem.h
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbased/include/subsystems/ExampleSubsystem.h
@@ -4,6 +4,7 @@
 
 #pragma once
 
+#include <frc2/command/CommandPtr.h>
 #include <frc2/command/SubsystemBase.h>
 
 class ExampleSubsystem : public frc2::SubsystemBase {
@@ -11,6 +12,19 @@
   ExampleSubsystem();
 
   /**
+   * Example command factory method.
+   */
+  frc2::CommandPtr ExampleMethodCommand();
+
+  /**
+   * An example method querying a boolean state of the subsystem (for example, a
+   * digital sensor).
+   *
+   * @return value of some boolean subsystem state, such as a digital sensor.
+   */
+  bool ExampleCondition();
+
+  /**
    * Will be called periodically whenever the CommandScheduler runs.
    */
   void Periodic() override;
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/cpp/Robot.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/cpp/Robot.cpp
new file mode 100644
index 0000000..32782b2
--- /dev/null
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/cpp/Robot.cpp
@@ -0,0 +1,55 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "Robot.h"
+
+#include <frc2/command/CommandScheduler.h>
+
+void Robot::RobotInit() {}
+
+void Robot::RobotPeriodic() {
+  frc2::CommandScheduler::GetInstance().Run();
+}
+
+void Robot::DisabledInit() {}
+
+void Robot::DisabledPeriodic() {}
+
+void Robot::DisabledExit() {}
+
+void Robot::AutonomousInit() {
+  m_autonomousCommand = m_container.GetAutonomousCommand();
+
+  if (m_autonomousCommand) {
+    m_autonomousCommand->Schedule();
+  }
+}
+
+void Robot::AutonomousPeriodic() {}
+
+void Robot::AutonomousExit() {}
+
+void Robot::TeleopInit() {
+  if (m_autonomousCommand) {
+    m_autonomousCommand->Cancel();
+  }
+}
+
+void Robot::TeleopPeriodic() {}
+
+void Robot::TeleopExit() {}
+
+void Robot::TestInit() {
+  frc2::CommandScheduler::GetInstance().CancelAll();
+}
+
+void Robot::TestPeriodic() {}
+
+void Robot::TestExit() {}
+
+#ifndef RUNNING_FRC_TESTS
+int main() {
+  return frc::StartRobot<Robot>();
+}
+#endif
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/cpp/RobotContainer.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/cpp/RobotContainer.cpp
new file mode 100644
index 0000000..e63532a
--- /dev/null
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/cpp/RobotContainer.cpp
@@ -0,0 +1,17 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "RobotContainer.h"
+
+#include <frc2/command/Commands.h>
+
+RobotContainer::RobotContainer() {
+  ConfigureBindings();
+}
+
+void RobotContainer::ConfigureBindings() {}
+
+frc2::CommandPtr RobotContainer::GetAutonomousCommand() {
+  return frc2::cmd::Print("No autonomous command configured");
+}
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/include/Robot.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/include/Robot.h
new file mode 100644
index 0000000..6bdb217
--- /dev/null
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/include/Robot.h
@@ -0,0 +1,35 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <optional>
+
+#include <frc/TimedRobot.h>
+#include <frc2/command/CommandPtr.h>
+
+#include "RobotContainer.h"
+
+class Robot : public frc::TimedRobot {
+ public:
+  void RobotInit() override;
+  void RobotPeriodic() override;
+  void DisabledInit() override;
+  void DisabledPeriodic() override;
+  void DisabledExit() override;
+  void AutonomousInit() override;
+  void AutonomousPeriodic() override;
+  void AutonomousExit() override;
+  void TeleopInit() override;
+  void TeleopPeriodic() override;
+  void TeleopExit() override;
+  void TestInit() override;
+  void TestPeriodic() override;
+  void TestExit() override;
+
+ private:
+  std::optional<frc2::CommandPtr> m_autonomousCommand;
+
+  RobotContainer m_container;
+};
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/include/RobotContainer.h b/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/include/RobotContainer.h
new file mode 100644
index 0000000..a66653c
--- /dev/null
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/include/RobotContainer.h
@@ -0,0 +1,17 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <frc2/command/CommandPtr.h>
+
+class RobotContainer {
+ public:
+  RobotContainer();
+
+  frc2::CommandPtr GetAutonomousCommand();
+
+ private:
+  void ConfigureBindings();
+};
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/robotbaseskeleton/cpp/Robot.cpp b/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/robotbaseskeleton/cpp/Robot.cpp
index 29bae0b..0c67d6d 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/robotbaseskeleton/cpp/Robot.cpp
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/robotbaseskeleton/cpp/Robot.cpp
@@ -5,6 +5,7 @@
 #include "Robot.h"
 
 #include <frc/DriverStation.h>
+#include <frc/internal/DriverStationModeThread.h>
 #include <frc/livewindow/LiveWindow.h>
 #include <frc/shuffleboard/Shuffleboard.h>
 #include <hal/DriverStation.h>
@@ -23,41 +24,46 @@
 void Robot::StartCompetition() {
   RobotInit();
 
+  frc::internal::DriverStationModeThread modeThread;
+
+  wpi::Event event{false, false};
+  frc::DriverStation::ProvideRefreshedDataEventHandle(event.GetHandle());
+
   // Tell the DS that the robot is ready to be enabled
   HAL_ObserveUserProgramStarting();
 
   while (!m_exit) {
     if (IsDisabled()) {
-      frc::DriverStation::InDisabled(true);
+      modeThread.InDisabled(true);
       Disabled();
-      frc::DriverStation::InDisabled(false);
+      modeThread.InDisabled(false);
       while (IsDisabled()) {
-        frc::DriverStation::WaitForData();
+        wpi::WaitForObject(event.GetHandle());
       }
     } else if (IsAutonomous()) {
-      frc::DriverStation::InAutonomous(true);
+      modeThread.InAutonomous(true);
       Autonomous();
-      frc::DriverStation::InAutonomous(false);
+      modeThread.InAutonomous(false);
       while (IsAutonomousEnabled()) {
-        frc::DriverStation::WaitForData();
+        wpi::WaitForObject(event.GetHandle());
       }
     } else if (IsTest()) {
       frc::LiveWindow::SetEnabled(true);
       frc::Shuffleboard::EnableActuatorWidgets();
-      frc::DriverStation::InTest(true);
+      modeThread.InTest(true);
       Test();
-      frc::DriverStation::InTest(false);
+      modeThread.InTest(false);
       while (IsTest() && IsEnabled()) {
-        frc::DriverStation::WaitForData();
+        wpi::WaitForObject(event.GetHandle());
       }
       frc::LiveWindow::SetEnabled(false);
       frc::Shuffleboard::DisableActuatorWidgets();
     } else {
-      frc::DriverStation::InTeleop(true);
+      modeThread.InTeleop(true);
       Teleop();
-      frc::DriverStation::InTeleop(false);
+      modeThread.InTeleop(false);
       while (IsTeleopEnabled()) {
-        frc::DriverStation::WaitForData();
+        wpi::WaitForObject(event.GetHandle());
       }
     }
   }
diff --git a/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/templates.json b/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/templates.json
index 83260a0..67e4438 100644
--- a/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/templates.json
+++ b/third_party/allwpilib/wpilibcExamples/src/main/cpp/templates/templates.json
@@ -10,6 +10,16 @@
     "commandversion": 2
   },
   {
+    "name": "Command Robot Skeleton (Advanced)",
+    "description": "Skeleton (stub) code for Command Robot",
+    "tags": [
+      "Command", "Skeleton"
+    ],
+    "foldername": "commandbasedskeleton",
+    "gradlebase": "cpp",
+    "commandversion": 2
+  },
+  {
     "name": "Timed Robot",
     "description": "Timed style",
     "tags": [
diff --git a/third_party/allwpilib/wpilibcExamples/src/test/cpp/examples/AddressableLED/cpp/RainbowTest.cpp b/third_party/allwpilib/wpilibcExamples/src/test/cpp/examples/AddressableLED/cpp/RainbowTest.cpp
new file mode 100644
index 0000000..553a2bb
--- /dev/null
+++ b/third_party/allwpilib/wpilibcExamples/src/test/cpp/examples/AddressableLED/cpp/RainbowTest.cpp
@@ -0,0 +1,53 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <fmt/format.h>
+#include <gtest/gtest.h>
+
+#include <array>
+
+#include <frc/AddressableLED.h>
+#include <frc/simulation/AddressableLEDSim.h>
+#include <frc/util/Color.h>
+#include <frc/util/Color8Bit.h>
+#include <hal/AddressableLEDTypes.h>
+
+#include "Robot.h"
+
+void AssertIndexColor(std::array<frc::AddressableLED::LEDData, 60> data,
+                      int index, int hue, int saturation, int value);
+
+TEST(RainbowTest, RainbowPattern) {
+  Robot robot;
+  robot.RobotInit();
+  frc::sim::AddressableLEDSim ledSim =
+      frc::sim::AddressableLEDSim::CreateForChannel(9);
+  EXPECT_TRUE(ledSim.GetRunning());
+  EXPECT_EQ(60, ledSim.GetLength());
+
+  auto rainbowFirstPixelHue = 0;
+  std::array<frc::AddressableLED::LEDData, 60> data;
+  for (int iteration = 0; iteration < 100; iteration++) {
+    SCOPED_TRACE(fmt::format("Iteration {} of 100", iteration));
+    robot.RobotPeriodic();
+    ledSim.GetData(data.data());
+    for (int i = 0; i < 60; i++) {
+      SCOPED_TRACE(fmt::format("LED {} of 60", i));
+      auto hue = (rainbowFirstPixelHue + (i * 180 / 60)) % 180;
+      AssertIndexColor(data, i, hue, 255, 128);
+    }
+    rainbowFirstPixelHue += 3;
+    rainbowFirstPixelHue %= 180;
+  }
+}
+
+void AssertIndexColor(std::array<frc::AddressableLED::LEDData, 60> data,
+                      int index, int hue, int saturation, int value) {
+  frc::Color8Bit color{frc::Color::FromHSV(hue, saturation, value)};
+
+  EXPECT_EQ(0, data[index].padding);
+  EXPECT_EQ(color.red, data[index].r & 0xFF);
+  EXPECT_EQ(color.green, data[index].g & 0xFF);
+  EXPECT_EQ(color.blue, data[index].b & 0xFF);
+}
diff --git a/third_party/allwpilib/wpilibcExamples/src/test/cpp/examples/AddressableLED/cpp/main.cpp b/third_party/allwpilib/wpilibcExamples/src/test/cpp/examples/AddressableLED/cpp/main.cpp
new file mode 100644
index 0000000..285c1d5
--- /dev/null
+++ b/third_party/allwpilib/wpilibcExamples/src/test/cpp/examples/AddressableLED/cpp/main.cpp
@@ -0,0 +1,17 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <hal/HALBase.h>
+
+#include "gtest/gtest.h"
+
+/**
+ * Runs all unit tests.
+ */
+int main(int argc, char** argv) {
+  HAL_Initialize(500, 0);
+  ::testing::InitGoogleTest(&argc, argv);
+  int ret = RUN_ALL_TESTS();
+  return ret;
+}
diff --git a/third_party/allwpilib/wpilibcExamples/src/test/cpp/examples/UnitTest/cpp/main.cpp b/third_party/allwpilib/wpilibcExamples/src/test/cpp/examples/UnitTest/cpp/main.cpp
new file mode 100644
index 0000000..285c1d5
--- /dev/null
+++ b/third_party/allwpilib/wpilibcExamples/src/test/cpp/examples/UnitTest/cpp/main.cpp
@@ -0,0 +1,17 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <hal/HALBase.h>
+
+#include "gtest/gtest.h"
+
+/**
+ * Runs all unit tests.
+ */
+int main(int argc, char** argv) {
+  HAL_Initialize(500, 0);
+  ::testing::InitGoogleTest(&argc, argv);
+  int ret = RUN_ALL_TESTS();
+  return ret;
+}
diff --git a/third_party/allwpilib/wpilibcExamples/src/test/cpp/examples/UnitTest/cpp/subsystems/IntakeTest.cpp b/third_party/allwpilib/wpilibcExamples/src/test/cpp/examples/UnitTest/cpp/subsystems/IntakeTest.cpp
new file mode 100644
index 0000000..ae1d786
--- /dev/null
+++ b/third_party/allwpilib/wpilibcExamples/src/test/cpp/examples/UnitTest/cpp/subsystems/IntakeTest.cpp
@@ -0,0 +1,46 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <gtest/gtest.h>
+
+#include <frc/DoubleSolenoid.h>
+#include <frc/simulation/DoubleSolenoidSim.h>
+#include <frc/simulation/PWMSim.h>
+
+#include "Constants.h"
+#include "subsystems/Intake.h"
+
+class IntakeTest : public testing::Test {
+ protected:
+  Intake intake;  // create our intake
+  frc::sim::PWMSim simMotor{
+      IntakeConstants::kMotorPort};  // create our simulation PWM
+  frc::sim::DoubleSolenoidSim simPiston{
+      frc::PneumaticsModuleType::CTREPCM, IntakeConstants::kPistonFwdChannel,
+      IntakeConstants::kPistonRevChannel};  // create our simulation solenoid
+};
+
+TEST_F(IntakeTest, DoesntWorkWhenClosed) {
+  intake.Retract();      // close the intake
+  intake.Activate(0.5);  // try to activate the motor
+  EXPECT_DOUBLE_EQ(
+      0.0,
+      simMotor.GetSpeed());  // make sure that the value set to the motor is 0
+}
+
+TEST_F(IntakeTest, WorksWhenOpen) {
+  intake.Deploy();
+  intake.Activate(0.5);
+  EXPECT_DOUBLE_EQ(0.5, simMotor.GetSpeed());
+}
+
+TEST_F(IntakeTest, Retract) {
+  intake.Retract();
+  EXPECT_EQ(frc::DoubleSolenoid::Value::kReverse, simPiston.Get());
+}
+
+TEST_F(IntakeTest, Deploy) {
+  intake.Deploy();
+  EXPECT_EQ(frc::DoubleSolenoid::Value::kForward, simPiston.Get());
+}
diff --git a/third_party/allwpilib/wpilibcIntegrationTests/build.gradle b/third_party/allwpilib/wpilibcIntegrationTests/build.gradle
index 4d66667..38fbe82 100644
--- a/third_party/allwpilib/wpilibcIntegrationTests/build.gradle
+++ b/third_party/allwpilib/wpilibcIntegrationTests/build.gradle
@@ -39,21 +39,19 @@
                             }
                         }
                     }
-                    binary.tasks.withType(CppCompile) {
-                        cppCompiler.args "-Wno-missing-field-initializers"
-                        cppCompiler.args "-Wno-unused-variable"
-                        cppCompiler.args "-Wno-error=deprecated-declarations"
-                    }
-                    lib project: ':wpilibOldCommands', library: 'wpilibOldCommands', linkage: 'shared'
                     lib project: ':wpilibc', library: 'wpilibc', linkage: 'shared'
                     lib project: ':wpimath', library: 'wpimath', linkage: 'shared'
-                    lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
+                    project(':ntcore').addNtcoreDependency(binary, 'shared')
+                    project(':ntcore').addNtcoreJniDependency(binary)
                     lib project: ':cscore', library: 'cscore', linkage: 'shared'
-                    lib project: ':ntcore', library: 'ntcoreJNIShared', linkage: 'shared'
                     lib project: ':cscore', library: 'cscoreJNIShared', linkage: 'shared'
                     project(':hal').addHalDependency(binary, 'shared')
                     project(':hal').addHalJniDependency(binary)
                     lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+                    lib project: ':wpimath', library: 'wpimathJNIShared', linkage: 'shared'
+                    lib project: ':wpinet', library: 'wpinetJNIShared', linkage: 'shared'
+                    lib project: ':wpiutil', library: 'wpiutilJNIShared', linkage: 'shared'
+                    lib project: ':wpinet', library: 'wpinet', linkage: 'shared'
                     lib project: ':cameraserver', library: 'cameraserver', linkage: 'shared'
                     if (binary.targetPlatform.name == nativeUtils.wpi.platforms.roborio) {
                         nativeUtils.useRequiredLibrary(binary, 'ni_link_libraries', 'ni_runtime_libraries')
@@ -87,6 +85,9 @@
                         into '/cpp'
                     }
                     installTask.libs.each {
+                        if (it.absolutePath.endsWith('.debug')) {
+                            return
+                        }
                         task.from(it) {
                             into '/libs'
                         }
diff --git a/third_party/allwpilib/wpilibcIntegrationTests/src/main/native/cpp/DriverStationTest.cpp b/third_party/allwpilib/wpilibcIntegrationTests/src/main/native/cpp/DriverStationTest.cpp
index e4a2721..0369717 100644
--- a/third_party/allwpilib/wpilibcIntegrationTests/src/main/native/cpp/DriverStationTest.cpp
+++ b/third_party/allwpilib/wpilibcIntegrationTests/src/main/native/cpp/DriverStationTest.cpp
@@ -4,6 +4,7 @@
 
 #include "frc/DriverStation.h"  // NOLINT(build/include_order)
 
+#include <hal/DriverStation.h>
 #include <units/math.h>
 #include <units/time.h>
 
@@ -20,11 +21,16 @@
 TEST(DriverStationTest, WaitForData) {
   units::microsecond_t initialTime(frc::RobotController::GetFPGATime());
 
+  wpi::Event waitEvent{true};
+  HAL_ProvideNewDataEventHandle(waitEvent.GetHandle());
+
   // 20ms waiting intervals * 50 = 1s
   for (int i = 0; i < 50; i++) {
-    frc::DriverStation::WaitForData();
+    wpi::WaitForObject(waitEvent.GetHandle());
   }
 
+  HAL_RemoveNewDataEventHandle(waitEvent.GetHandle());
+
   units::microsecond_t finalTime(frc::RobotController::GetFPGATime());
 
   EXPECT_NEAR_UNITS(1_s, finalTime - initialTime, 200_ms);
diff --git a/third_party/allwpilib/wpilibcIntegrationTests/src/main/native/cpp/PreferencesTest.cpp b/third_party/allwpilib/wpilibcIntegrationTests/src/main/native/cpp/PreferencesTest.cpp
index 5e79f27..78d9c43 100644
--- a/third_party/allwpilib/wpilibcIntegrationTests/src/main/native/cpp/PreferencesTest.cpp
+++ b/third_party/allwpilib/wpilibcIntegrationTests/src/main/native/cpp/PreferencesTest.cpp
@@ -7,6 +7,7 @@
 #include <cstdio>
 #include <fstream>
 
+#include <networktables/MultiSubscriber.h>
 #include <networktables/NetworkTableInstance.h>
 #include <ntcore.h>
 #include <units/time.h>
@@ -14,7 +15,7 @@
 #include "frc/Timer.h"
 #include "gtest/gtest.h"
 
-static const char* kFileName = "networktables.ini";
+static const char* kFileName = "networktables.json";
 static constexpr auto kSaveTime = 1.2_s;
 
 /**
@@ -27,47 +28,71 @@
 
   std::remove(kFileName);
   std::ofstream preferencesFile(kFileName);
-  preferencesFile << "[NetworkTables Storage 3.0]" << std::endl;
-  preferencesFile
-      << "string \"/Preferences/testFileGetString\"=\"Hello, preferences file\""
-      << std::endl;
-  preferencesFile << "double \"/Preferences/testFileGetInt\"=1" << std::endl;
-  preferencesFile << "double \"/Preferences/testFileGetDouble\"=0.5"
-                  << std::endl;
-  preferencesFile << "double \"/Preferences/testFileGetFloat\"=0.25"
-                  << std::endl;
-  preferencesFile << "boolean \"/Preferences/testFileGetBoolean\"=true"
-                  << std::endl;
-  preferencesFile
-      << "double \"/Preferences/testFileGetLong\"=1000000000000000000"
-      << std::endl;
+  preferencesFile << "[" << std::endl;
+  preferencesFile << "{\"type\":\"string\","
+                  << "\"name\":\"/Preferences/testFileGetString\","
+                  << "\"value\":\"Hello, preferences file\","
+                  << "\"properties\":{\"persistent\":true}}," << std::endl;
+  preferencesFile << "{\"type\":\"int\","
+                  << "\"name\":\"/Preferences/testFileGetInt\","
+                  << "\"value\":1,"
+                  << "\"properties\":{\"persistent\":true}}," << std::endl;
+  preferencesFile << "{\"type\":\"double\","
+                  << "\"name\":\"/Preferences/testFileGetDouble\","
+                  << "\"value\":0.5,"
+                  << "\"properties\":{\"persistent\":true}}," << std::endl;
+  preferencesFile << "{\"type\":\"float\","
+                  << "\"name\":\"/Preferences/testFileGetFloat\","
+                  << "\"value\":0.25,"
+                  << "\"properties\":{\"persistent\":true}}," << std::endl;
+  preferencesFile << "{\"type\":\"boolean\","
+                  << "\"name\":\"/Preferences/testFileGetBoolean\","
+                  << "\"value\":true,"
+                  << "\"properties\":{\"persistent\":true}}]" << std::endl;
   preferencesFile.close();
 
+  nt::MultiSubscriber suball{inst, {{std::string_view{}}}};
   inst.StartServer();
 
+  int count = 0;
+  while ((inst.GetNetworkMode() & NT_NET_MODE_STARTING) != 0) {
+    frc::Wait(10_ms);
+    count++;
+    if (count > 30) {
+      FAIL() << "timed out waiting for server startup";
+    }
+  }
+
   EXPECT_EQ("Hello, preferences file",
             frc::Preferences::GetString("testFileGetString"));
   EXPECT_EQ(1, frc::Preferences::GetInt("testFileGetInt"));
   EXPECT_FLOAT_EQ(0.5, frc::Preferences::GetDouble("testFileGetDouble"));
   EXPECT_FLOAT_EQ(0.25f, frc::Preferences::GetFloat("testFileGetFloat"));
   EXPECT_TRUE(frc::Preferences::GetBoolean("testFileGetBoolean"));
-  EXPECT_EQ(1000000000000000000ll,
-            frc::Preferences::GetLong("testFileGetLong"));
 }
 
 /**
  * If we set some values using the Preferences class, test that they show up
- * in networktables.ini
+ * in networktables.json
  */
 TEST(PreferencesTest, WritePreferencesToFile) {
   auto inst = nt::NetworkTableInstance::GetDefault();
   inst.StartServer();
+
+  int count = 0;
+  while ((inst.GetNetworkMode() & NT_NET_MODE_STARTING) != 0) {
+    frc::Wait(10_ms);
+    count++;
+    if (count > 30) {
+      FAIL() << "timed out waiting for server startup";
+    }
+  }
+
   frc::Preferences::Remove("testFileGetString");
   frc::Preferences::Remove("testFileGetInt");
   frc::Preferences::Remove("testFileGetDouble");
   frc::Preferences::Remove("testFileGetFloat");
   frc::Preferences::Remove("testFileGetBoolean");
-  frc::Preferences::Remove("testFileGetLong");
 
   frc::Wait(kSaveTime);
 
@@ -76,19 +101,52 @@
   frc::Preferences::SetDouble("testFileSetDouble", 0.5);
   frc::Preferences::SetFloat("testFileSetFloat", 0.25f);
   frc::Preferences::SetBoolean("testFileSetBoolean", true);
-  frc::Preferences::SetLong("testFileSetLong", 1000000000000000000ll);
 
   frc::Wait(kSaveTime);
 
   static char const* kExpectedFileContents[] = {
-      "[NetworkTables Storage 3.0]",
-      "string \"/Preferences/.type\"=\"RobotPreferences\"",
-      "boolean \"/Preferences/testFileSetBoolean\"=true",
-      "double \"/Preferences/testFileSetDouble\"=0.5",
-      "double \"/Preferences/testFileSetFloat\"=0.25",
-      "double \"/Preferences/testFileSetInt\"=1",
-      "double \"/Preferences/testFileSetLong\"=1e+18",
-      "string \"/Preferences/testFileSetString\"=\"Hello, preferences file\""};
+      "[",
+      "  {",
+      "    \"name\": \"/Preferences/testFileSetString\",",
+      "    \"type\": \"string\",",
+      "    \"value\": \"Hello, preferences file\",",
+      "    \"properties\": {",
+      "      \"persistent\": true",
+      "    }",
+      "  },",
+      "  {",
+      "    \"name\": \"/Preferences/testFileSetInt\",",
+      "    \"type\": \"int\",",
+      "    \"value\": 1,",
+      "    \"properties\": {",
+      "      \"persistent\": true",
+      "    }",
+      "  },",
+      "  {",
+      "    \"name\": \"/Preferences/testFileSetDouble\",",
+      "    \"type\": \"double\",",
+      "    \"value\": 0.5,",
+      "    \"properties\": {",
+      "      \"persistent\": true",
+      "    }",
+      "  },",
+      "  {",
+      "    \"name\": \"/Preferences/testFileSetFloat\",",
+      "    \"type\": \"float\",",
+      "    \"value\": 0.25,",
+      "    \"properties\": {",
+      "      \"persistent\": true",
+      "    }",
+      "  },",
+      "  {",
+      "    \"name\": \"/Preferences/testFileSetBoolean\",",
+      "    \"type\": \"boolean\",",
+      "    \"value\": true,",
+      "    \"properties\": {",
+      "      \"persistent\": true",
+      "    }",
+      "  }",
+      "]"};
 
   std::ifstream preferencesFile(kFileName);
   for (auto& kExpectedFileContent : kExpectedFileContents) {
@@ -99,6 +157,6 @@
     std::getline(preferencesFile, line);
 
     ASSERT_EQ(kExpectedFileContent, line)
-        << "A line in networktables.ini was not correct";
+        << "A line in networktables.json was not correct";
   }
 }
diff --git a/third_party/allwpilib/wpilibcIntegrationTests/src/main/native/cpp/TestEnvironment.cpp b/third_party/allwpilib/wpilibcIntegrationTests/src/main/native/cpp/TestEnvironment.cpp
index 1f5e360..59a3a58 100644
--- a/third_party/allwpilib/wpilibcIntegrationTests/src/main/native/cpp/TestEnvironment.cpp
+++ b/third_party/allwpilib/wpilibcIntegrationTests/src/main/native/cpp/TestEnvironment.cpp
@@ -45,6 +45,7 @@
     fmt::print("Started coms\n");
 
     int enableCounter = 0;
+    frc::DriverStation::RefreshData();
     while (!frc::DriverStation::IsEnabled()) {
       if (enableCounter > 50) {
         // Robot did not enable properly after 5 seconds.
@@ -56,6 +57,7 @@
       std::this_thread::sleep_for(100ms);
 
       fmt::print("Waiting for enable: {}\n", enableCounter++);
+      frc::DriverStation::RefreshData();
     }
   }
 
diff --git a/third_party/allwpilib/wpilibcIntegrationTests/src/main/native/cpp/mockds/MockDS.cpp b/third_party/allwpilib/wpilibcIntegrationTests/src/main/native/cpp/mockds/MockDS.cpp
index b2e5c2d..2e53a9a 100644
--- a/third_party/allwpilib/wpilibcIntegrationTests/src/main/native/cpp/mockds/MockDS.cpp
+++ b/third_party/allwpilib/wpilibcIntegrationTests/src/main/native/cpp/mockds/MockDS.cpp
@@ -12,7 +12,7 @@
 #include <hal/cpp/fpga_clock.h>
 #include <wpi/Logger.h>
 #include <wpi/SmallVector.h>
-#include <wpi/UDPClient.h>
+#include <wpinet/UDPClient.h>
 
 static void LoggerFunc(unsigned int level, const char* file, unsigned int line,
                        const char* msg) {
diff --git a/third_party/allwpilib/wpilibj/build.gradle b/third_party/allwpilib/wpilibj/build.gradle
index 665560c..77eb349 100644
--- a/third_party/allwpilib/wpilibj/build.gradle
+++ b/third_party/allwpilib/wpilibj/build.gradle
@@ -56,12 +56,15 @@
 }
 
 repositories {
-    mavenCentral()
+    maven {
+        url = 'https://frcmaven.wpi.edu/artifactory/ex-mvn'
+    }
 }
 
 dependencies {
     implementation project(':hal')
     implementation project(':wpiutil')
+    implementation project(':wpinet')
     implementation project(':wpimath')
     implementation project(':ntcore')
     implementation project(':cscore')
@@ -69,6 +72,7 @@
     testImplementation 'org.mockito:mockito-core:4.1.0'
     devImplementation project(':hal')
     devImplementation project(':wpiutil')
+    devImplementation project(':wpinet')
     devImplementation project(':wpimath')
     devImplementation project(':ntcore')
     devImplementation project(':cscore')
@@ -108,12 +112,14 @@
                 }
             }
             binaries.all {
-                lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
+                project(':ntcore').addNtcoreDependency(it, 'shared')
+                project(':ntcore').addNtcoreJniDependency(it)
                 lib project: ':cscore', library: 'cscore', linkage: 'shared'
+                lib project: ':wpinet', library: 'wpinet', linkage: 'shared'
                 lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
                 lib project: ':wpimath', library: 'wpimath', linkage: 'shared'
-                lib project: ':ntcore', library: 'ntcoreJNIShared', linkage: 'shared'
                 lib project: ':cscore', library: 'cscoreJNIShared', linkage: 'shared'
+                lib project: ':wpinet', library: 'wpinetJNIShared', linkage: 'shared'
                 lib project: ':wpiutil', library: 'wpiutilJNIShared', linkage: 'shared'
                 lib project: ':wpimath', library: 'wpimathJNIShared', linkage: 'shared'
                 lib project: ':cameraserver', library: 'cameraserver', linkage: 'shared'
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADIS16448_IMU.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADIS16448_IMU.java
index 4ac4b4f..a005b73 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADIS16448_IMU.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADIS16448_IMU.java
@@ -15,6 +15,7 @@
 
 import edu.wpi.first.hal.FRCNetComm.tResourceType;
 import edu.wpi.first.hal.HAL;
+import edu.wpi.first.hal.SimBoolean;
 import edu.wpi.first.hal.SimDevice;
 import edu.wpi.first.hal.SimDouble;
 import edu.wpi.first.networktables.NTSendable;
@@ -183,8 +184,10 @@
   private DigitalInput m_reset_in;
   private DigitalOutput m_status_led;
   private Thread m_acquire_task;
+  private boolean m_connected;
 
   private SimDevice m_simDevice;
+  private SimBoolean m_simConnected;
   private SimDouble m_simGyroAngleX;
   private SimDouble m_simGyroAngleY;
   private SimDouble m_simGyroAngleZ;
@@ -262,6 +265,7 @@
 
     m_simDevice = SimDevice.create("Gyro:ADIS16448", port.value);
     if (m_simDevice != null) {
+      m_simConnected = m_simDevice.createBoolean("connected", SimDevice.Direction.kInput, true);
       m_simGyroAngleX = m_simDevice.createDouble("gyro_angle_x", SimDevice.Direction.kInput, 0.0);
       m_simGyroAngleY = m_simDevice.createDouble("gyro_angle_y", SimDevice.Direction.kInput, 0.0);
       m_simGyroAngleZ = m_simDevice.createDouble("gyro_angle_z", SimDevice.Direction.kInput, 0.0);
@@ -314,7 +318,7 @@
       calibrate();
       // Reset accumulated offsets
       reset();
-      // Tell the acquire loop that we're done starting up
+      // Indicate to the acquire loop that we're done starting up
       m_start_up_mode = false;
       // Let the user know the IMU was initiallized successfully
       DriverStation.reportWarning("ADIS16448 IMU Successfully Initialized!", false);
@@ -324,6 +328,14 @@
 
     // Report usage and post data to DS
     HAL.report(tResourceType.kResourceType_ADIS16448, 0);
+    m_connected = true;
+  }
+
+  public boolean isConnected() {
+    if (m_simConnected != null) {
+      return m_simConnected.get();
+    }
+    return m_connected;
   }
 
   /** */
@@ -351,8 +363,7 @@
 
   /** */
   private static int toInt(int... buf) {
-    return (int)
-        ((buf[0] & 0xFF) << 24 | (buf[1] & 0xFF) << 16 | (buf[2] & 0xFF) << 8 | (buf[3] & 0xFF));
+    return (buf[0] & 0xFF) << 24 | (buf[1] & 0xFF) << 16 | (buf[2] & 0xFF) << 8 | (buf[3] & 0xFF);
   }
 
   /** */
@@ -396,9 +407,7 @@
       System.out.println("Setting up a new SPI port.");
       m_spi = new SPI(m_spi_port);
       m_spi.setClockRate(1000000);
-      m_spi.setMSBFirst();
-      m_spi.setSampleDataOnTrailingEdge();
-      m_spi.setClockActiveLow();
+      m_spi.setMode(SPI.Mode.kMode3);
       m_spi.setChipSelectActiveLow();
       readRegister(PROD_ID); // Dummy read
 
@@ -482,12 +491,12 @@
     /* Check max */
     if (m_decRate > 9) {
       DriverStation.reportError(
-          "Attemted to write an invalid decimation value. Capping at 9", false);
+          "Attempted to write an invalid decimation value. Capping at 9", false);
       m_decRate = 9;
     }
     if (m_decRate < 0) {
       DriverStation.reportError(
-          "Attemted to write an invalid decimation value. Capping at 0", false);
+          "Attempted to write an invalid decimation value. Capping at 0", false);
       m_decRate = 0;
     }
 
@@ -541,7 +550,7 @@
       m_offset_data_gyro_rate_x = new double[size];
       m_offset_data_gyro_rate_y = new double[size];
       m_offset_data_gyro_rate_z = new double[size];
-      // Set acculumate count to 0
+      // Set accumulate count to 0
       m_accum_count = 0;
     }
   }
@@ -614,7 +623,6 @@
     m_spi.write(buf, 2);
   }
 
-  /** {@inheritDoc} */
   public void reset() {
     synchronized (this) {
       m_integ_gyro_angle_x = 0.0;
@@ -943,7 +951,9 @@
     return compAngle;
   }
 
-  /** @return Yaw axis angle in degrees (CCW positive) */
+  /**
+   * @return Yaw axis angle in degrees (CCW positive)
+   */
   public synchronized double getAngle() {
     switch (m_yaw_axis) {
       case kX:
@@ -957,7 +967,9 @@
     }
   }
 
-  /** @return Yaw axis angular rate in degrees per second (CCW positive) */
+  /**
+   * @return Yaw axis angular rate in degrees per second (CCW positive)
+   */
   public synchronized double getRate() {
     switch (m_yaw_axis) {
       case kX:
@@ -971,12 +983,16 @@
     }
   }
 
-  /** @return Yaw Axis */
+  /**
+   * @return Yaw Axis
+   */
   public IMUAxis getYawAxis() {
     return m_yaw_axis;
   }
 
-  /** @return accumulated gyro angle in the X axis in degrees */
+  /**
+   * @return accumulated gyro angle in the X axis in degrees
+   */
   public synchronized double getGyroAngleX() {
     if (m_simGyroAngleX != null) {
       return m_simGyroAngleX.get();
@@ -984,7 +1000,9 @@
     return m_integ_gyro_angle_x;
   }
 
-  /** @return accumulated gyro angle in the Y axis in degrees */
+  /**
+   * @return accumulated gyro angle in the Y axis in degrees
+   */
   public synchronized double getGyroAngleY() {
     if (m_simGyroAngleY != null) {
       return m_simGyroAngleY.get();
@@ -992,7 +1010,9 @@
     return m_integ_gyro_angle_y;
   }
 
-  /** @return accumulated gyro angle in the Z axis in degrees */
+  /**
+   * @return accumulated gyro angle in the Z axis in degrees
+   */
   public synchronized double getGyroAngleZ() {
     if (m_simGyroAngleZ != null) {
       return m_simGyroAngleZ.get();
@@ -1000,7 +1020,9 @@
     return m_integ_gyro_angle_z;
   }
 
-  /** @return gyro angular rate in the X axis in degrees per second */
+  /**
+   * @return gyro angular rate in the X axis in degrees per second
+   */
   public synchronized double getGyroRateX() {
     if (m_simGyroRateX != null) {
       return m_simGyroRateX.get();
@@ -1008,7 +1030,9 @@
     return m_gyro_rate_x;
   }
 
-  /** @return gyro angular rate in the Y axis in degrees per second */
+  /**
+   * @return gyro angular rate in the Y axis in degrees per second
+   */
   public synchronized double getGyroRateY() {
     if (m_simGyroRateY != null) {
       return m_simGyroRateY.get();
@@ -1016,7 +1040,9 @@
     return m_gyro_rate_y;
   }
 
-  /** @return gyro angular rate in the Z axis in degrees per second */
+  /**
+   * @return gyro angular rate in the Z axis in degrees per second
+   */
   public synchronized double getGyroRateZ() {
     if (m_simGyroRateZ != null) {
       return m_simGyroRateZ.get();
@@ -1024,7 +1050,9 @@
     return m_gyro_rate_z;
   }
 
-  /** @return urrent acceleration in the X axis in meters per second squared */
+  /**
+   * @return urrent acceleration in the X axis in meters per second squared
+   */
   public synchronized double getAccelX() {
     if (m_simAccelX != null) {
       return m_simAccelX.get();
@@ -1032,7 +1060,9 @@
     return m_accel_x * 9.81;
   }
 
-  /** @return current acceleration in the Y axis in meters per second squared */
+  /**
+   * @return current acceleration in the Y axis in meters per second squared
+   */
   public synchronized double getAccelY() {
     if (m_simAccelY != null) {
       return m_simAccelY.get();
@@ -1040,7 +1070,9 @@
     return m_accel_y * 9.81;
   }
 
-  /** @return current acceleration in the Z axis in meters per second squared */
+  /**
+   * @return current acceleration in the Z axis in meters per second squared
+   */
   public synchronized double getAccelZ() {
     if (m_simAccelZ != null) {
       return m_simAccelZ.get();
@@ -1048,51 +1080,69 @@
     return m_accel_z * 9.81;
   }
 
-  /** @return Magnetic field strength in the X axis in Tesla */
+  /**
+   * @return Magnetic field strength in the X axis in Tesla
+   */
   public synchronized double getMagneticFieldX() {
     // mG to T
     return m_mag_x * 1e-7;
   }
 
-  /** @return Magnetic field strength in the Y axis in Tesla */
+  /**
+   * @return Magnetic field strength in the Y axis in Tesla
+   */
   public synchronized double getMagneticFieldY() {
     // mG to T
     return m_mag_y * 1e-7;
   }
 
-  /** @return Magnetic field strength in the Z axis in Tesla */
+  /**
+   * @return Magnetic field strength in the Z axis in Tesla
+   */
   public synchronized double getMagneticFieldZ() {
     // mG to T
     return m_mag_z * 1e-7;
   }
 
-  /** @return X axis complementary angle in degrees */
+  /**
+   * @return X-axis complementary angle in degrees
+   */
   public synchronized double getXComplementaryAngle() {
     return m_compAngleX;
   }
 
-  /** @return Y axis complementary angle in degrees */
+  /**
+   * @return Y-axis complementary angle in degrees
+   */
   public synchronized double getYComplementaryAngle() {
     return m_compAngleY;
   }
 
-  /** @return X axis filtered acceleration angle in degrees */
+  /**
+   * @return X-axis filtered acceleration angle in degrees
+   */
   public synchronized double getXFilteredAccelAngle() {
     return m_accelAngleX;
   }
 
-  /** @return Y axis filtered acceleration angle in degrees */
+  /**
+   * @return Y-axis filtered acceleration angle in degrees
+   */
   public synchronized double getYFilteredAccelAngle() {
     return m_accelAngleY;
   }
 
-  /** @return Barometric Pressure in PSI */
+  /**
+   * @return Barometric Pressure in PSI
+   */
   public synchronized double getBarometricPressure() {
-    // mbar to PSI
+    // mbar to PSI conversion
     return m_baro * 0.0145;
   }
 
-  /** @return Temperature in degrees Celsius */
+  /**
+   * @return Temperature in degrees Celsius
+   */
   public synchronized double getTemperature() {
     return m_temp;
   }
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADIS16470_IMU.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADIS16470_IMU.java
index 8bafa1a..f287cab 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADIS16470_IMU.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADIS16470_IMU.java
@@ -14,6 +14,7 @@
 // import java.lang.FdLibm.Pow;
 import edu.wpi.first.hal.FRCNetComm.tResourceType;
 import edu.wpi.first.hal.HAL;
+import edu.wpi.first.hal.SimBoolean;
 import edu.wpi.first.hal.SimDevice;
 import edu.wpi.first.hal.SimDouble;
 import edu.wpi.first.networktables.NTSendable;
@@ -250,8 +251,10 @@
   private DigitalInput m_reset_in;
   private DigitalOutput m_status_led;
   private Thread m_acquire_task;
+  private boolean m_connected;
 
   private SimDevice m_simDevice;
+  private SimBoolean m_simConnected;
   private SimDouble m_simGyroAngleX;
   private SimDouble m_simGyroAngleY;
   private SimDouble m_simGyroAngleZ;
@@ -293,6 +296,7 @@
 
     m_simDevice = SimDevice.create("Gyro:ADIS16470", port.value);
     if (m_simDevice != null) {
+      m_simConnected = m_simDevice.createBoolean("connected", SimDevice.Direction.kInput, true);
       m_simGyroAngleX = m_simDevice.createDouble("gyro_angle_x", SimDevice.Direction.kInput, 0.0);
       m_simGyroAngleY = m_simDevice.createDouble("gyro_angle_y", SimDevice.Direction.kInput, 0.0);
       m_simGyroAngleZ = m_simDevice.createDouble("gyro_angle_z", SimDevice.Direction.kInput, 0.0);
@@ -361,6 +365,14 @@
 
     // Report usage and post data to DS
     HAL.report(tResourceType.kResourceType_ADIS16470, 0);
+    m_connected = true;
+  }
+
+  public boolean isConnected() {
+    if (m_simConnected != null) {
+      return m_simConnected.get();
+    }
+    return m_connected;
   }
 
   /**
@@ -392,8 +404,7 @@
    * @return
    */
   private static int toInt(int... buf) {
-    return (int)
-        ((buf[0] & 0xFF) << 24 | (buf[1] & 0xFF) << 16 | (buf[2] & 0xFF) << 8 | (buf[3] & 0xFF));
+    return (buf[0] & 0xFF) << 24 | (buf[1] & 0xFF) << 16 | (buf[2] & 0xFF) << 8 | (buf[3] & 0xFF);
   }
 
   /**
@@ -439,9 +450,7 @@
       System.out.println("Setting up a new SPI port.");
       m_spi = new SPI(m_spi_port);
       m_spi.setClockRate(2000000);
-      m_spi.setMSBFirst();
-      m_spi.setSampleDataOnTrailingEdge();
-      m_spi.setClockActiveLow();
+      m_spi.setMode(SPI.Mode.kMode3);
       m_spi.setChipSelectActiveLow();
       readRegister(PROD_ID); // Dummy read
 
@@ -466,7 +475,9 @@
     }
   }
 
-  /** @return */
+  /**
+   * @return
+   */
   boolean switchToAutoSPI() {
     // No SPI port has been set up. Go set one up first.
     if (m_spi == null) {
@@ -556,7 +567,7 @@
       return 2;
     }
     if (m_reg > 1999) {
-      DriverStation.reportError("Attemted to write an invalid deimation value.", false);
+      DriverStation.reportError("Attempted to write an invalid deimation value.", false);
       m_reg = 1999;
     }
     m_scaled_sample_rate = (((m_reg + 1.0) / 2000.0) * 1000000.0);
@@ -639,7 +650,6 @@
     m_spi.write(buf, 2);
   }
 
-  /** {@inheritDoc} */
   public void reset() {
     synchronized (this) {
       m_integ_angle = 0.0;
@@ -918,7 +928,9 @@
     return compAngle;
   }
 
-  /** @return Yaw axis angle in degrees (CCW positive) */
+  /**
+   * @return Yaw axis angle in degrees (CCW positive)
+   */
   public synchronized double getAngle() {
     switch (m_yaw_axis) {
       case kX:
@@ -940,7 +952,9 @@
     return m_integ_angle;
   }
 
-  /** @return Yaw axis angular rate in degrees per second (CCW positive) */
+  /**
+   * @return Yaw axis angular rate in degrees per second (CCW positive)
+   */
   public synchronized double getRate() {
     if (m_yaw_axis == IMUAxis.kX) {
       if (m_simGyroRateX != null) {
@@ -962,42 +976,58 @@
     }
   }
 
-  /** @return Yaw Axis */
+  /**
+   * @return Yaw Axis
+   */
   public IMUAxis getYawAxis() {
     return m_yaw_axis;
   }
 
-  /** @return current acceleration in the X axis */
+  /**
+   * @return current acceleration in the X axis
+   */
   public synchronized double getAccelX() {
     return m_accel_x * 9.81;
   }
 
-  /** @return current acceleration in the Y axis */
+  /**
+   * @return current acceleration in the Y axis
+   */
   public synchronized double getAccelY() {
     return m_accel_y * 9.81;
   }
 
-  /** @return current acceleration in the Z axis */
+  /**
+   * @return current acceleration in the Z axis
+   */
   public synchronized double getAccelZ() {
     return m_accel_z * 9.81;
   }
 
-  /** @return X axis complementary angle */
+  /**
+   * @return X-axis complementary angle
+   */
   public synchronized double getXComplementaryAngle() {
     return m_compAngleX;
   }
 
-  /** @return Y axis complementary angle */
+  /**
+   * @return Y-axis complementary angle
+   */
   public synchronized double getYComplementaryAngle() {
     return m_compAngleY;
   }
 
-  /** @return X axis filtered acceleration angle */
+  /**
+   * @return X-axis filtered acceleration angle
+   */
   public synchronized double getXFilteredAccelAngle() {
     return m_accelAngleX;
   }
 
-  /** @return Y axis filtered acceleration angle */
+  /**
+   * @return Y-axis filtered acceleration angle
+   */
   public synchronized double getYFilteredAccelAngle() {
     return m_accelAngleY;
   }
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_I2C.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_I2C.java
index 29d3930..fddc01d 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_I2C.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_I2C.java
@@ -10,15 +10,22 @@
 import edu.wpi.first.hal.SimDevice;
 import edu.wpi.first.hal.SimDouble;
 import edu.wpi.first.hal.SimEnum;
+import edu.wpi.first.networktables.DoublePublisher;
+import edu.wpi.first.networktables.DoubleTopic;
 import edu.wpi.first.networktables.NTSendable;
 import edu.wpi.first.networktables.NTSendableBuilder;
-import edu.wpi.first.networktables.NetworkTableEntry;
 import edu.wpi.first.util.sendable.SendableRegistry;
 import edu.wpi.first.wpilibj.interfaces.Accelerometer;
 import java.nio.ByteBuffer;
 import java.nio.ByteOrder;
 
-/** ADXL345 I2C Accelerometer. */
+/**
+ * ADXL345 I2C Accelerometer.
+ *
+ * <p>The Onboard I2C port is subject to system lockups. See <a
+ * href="https://docs.wpilib.org/en/stable/docs/yearly-overview/known-issues.html#onboard-i2c-causing-system-lockups">
+ * WPILib Known Issues</a> page for details.
+ */
 @SuppressWarnings({"TypeName", "PMD.UnusedPrivateField"})
 public class ADXL345_I2C implements Accelerometer, NTSendable, AutoCloseable {
   private static final byte kAddress = 0x1D;
@@ -43,7 +50,6 @@
     kZ((byte) 0x04);
 
     /** The integer value representing this enumeration. */
-    @SuppressWarnings("MemberName")
     public final byte value;
 
     Axes(byte value) {
@@ -226,15 +232,18 @@
   @Override
   public void initSendable(NTSendableBuilder builder) {
     builder.setSmartDashboardType("3AxisAccelerometer");
-    NetworkTableEntry entryX = builder.getEntry("X");
-    NetworkTableEntry entryY = builder.getEntry("Y");
-    NetworkTableEntry entryZ = builder.getEntry("Z");
+    DoublePublisher pubX = new DoubleTopic(builder.getTopic("X")).publish();
+    DoublePublisher pubY = new DoubleTopic(builder.getTopic("Y")).publish();
+    DoublePublisher pubZ = new DoubleTopic(builder.getTopic("Z")).publish();
+    builder.addCloseable(pubX);
+    builder.addCloseable(pubY);
+    builder.addCloseable(pubZ);
     builder.setUpdateTable(
         () -> {
           AllAxes data = getAccelerations();
-          entryX.setDouble(data.XAxis);
-          entryY.setDouble(data.YAxis);
-          entryZ.setDouble(data.ZAxis);
+          pubX.set(data.XAxis);
+          pubY.set(data.YAxis);
+          pubZ.set(data.ZAxis);
         });
   }
 }
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_SPI.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_SPI.java
index fa8b7d8..4806979 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_SPI.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_SPI.java
@@ -10,9 +10,10 @@
 import edu.wpi.first.hal.SimDevice;
 import edu.wpi.first.hal.SimDouble;
 import edu.wpi.first.hal.SimEnum;
+import edu.wpi.first.networktables.DoublePublisher;
+import edu.wpi.first.networktables.DoubleTopic;
 import edu.wpi.first.networktables.NTSendable;
 import edu.wpi.first.networktables.NTSendableBuilder;
-import edu.wpi.first.networktables.NetworkTableEntry;
 import edu.wpi.first.util.sendable.SendableRegistry;
 import edu.wpi.first.wpilibj.interfaces.Accelerometer;
 import java.nio.ByteBuffer;
@@ -118,9 +119,7 @@
    */
   private void init(Range range) {
     m_spi.setClockRate(500000);
-    m_spi.setMSBFirst();
-    m_spi.setSampleDataOnTrailingEdge();
-    m_spi.setClockActiveLow();
+    m_spi.setMode(SPI.Mode.kMode3);
     m_spi.setChipSelectActiveHigh();
 
     // Turn on the measurements
@@ -236,15 +235,18 @@
   @Override
   public void initSendable(NTSendableBuilder builder) {
     builder.setSmartDashboardType("3AxisAccelerometer");
-    NetworkTableEntry entryX = builder.getEntry("X");
-    NetworkTableEntry entryY = builder.getEntry("Y");
-    NetworkTableEntry entryZ = builder.getEntry("Z");
+    DoublePublisher pubX = new DoubleTopic(builder.getTopic("X")).publish();
+    DoublePublisher pubY = new DoubleTopic(builder.getTopic("Y")).publish();
+    DoublePublisher pubZ = new DoubleTopic(builder.getTopic("Z")).publish();
+    builder.addCloseable(pubX);
+    builder.addCloseable(pubY);
+    builder.addCloseable(pubZ);
     builder.setUpdateTable(
         () -> {
           AllAxes data = getAccelerations();
-          entryX.setDouble(data.XAxis);
-          entryY.setDouble(data.YAxis);
-          entryZ.setDouble(data.ZAxis);
+          pubX.set(data.XAxis);
+          pubY.set(data.YAxis);
+          pubZ.set(data.ZAxis);
         });
   }
 }
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL362.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL362.java
index 2a9c2fe..afd76d6 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL362.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL362.java
@@ -9,9 +9,10 @@
 import edu.wpi.first.hal.SimDevice;
 import edu.wpi.first.hal.SimDouble;
 import edu.wpi.first.hal.SimEnum;
+import edu.wpi.first.networktables.DoublePublisher;
+import edu.wpi.first.networktables.DoubleTopic;
 import edu.wpi.first.networktables.NTSendable;
 import edu.wpi.first.networktables.NTSendableBuilder;
-import edu.wpi.first.networktables.NetworkTableEntry;
 import edu.wpi.first.util.sendable.SendableRegistry;
 import edu.wpi.first.wpilibj.interfaces.Accelerometer;
 import java.nio.ByteBuffer;
@@ -106,9 +107,7 @@
     }
 
     m_spi.setClockRate(3000000);
-    m_spi.setMSBFirst();
-    m_spi.setSampleDataOnTrailingEdge();
-    m_spi.setClockActiveLow();
+    m_spi.setMode(SPI.Mode.kMode3);
     m_spi.setChipSelectActiveLow();
 
     ByteBuffer transferBuffer = ByteBuffer.allocate(3);
@@ -265,15 +264,18 @@
   @Override
   public void initSendable(NTSendableBuilder builder) {
     builder.setSmartDashboardType("3AxisAccelerometer");
-    NetworkTableEntry entryX = builder.getEntry("X");
-    NetworkTableEntry entryY = builder.getEntry("Y");
-    NetworkTableEntry entryZ = builder.getEntry("Z");
+    DoublePublisher pubX = new DoubleTopic(builder.getTopic("X")).publish();
+    DoublePublisher pubY = new DoubleTopic(builder.getTopic("Y")).publish();
+    DoublePublisher pubZ = new DoubleTopic(builder.getTopic("Z")).publish();
+    builder.addCloseable(pubX);
+    builder.addCloseable(pubY);
+    builder.addCloseable(pubZ);
     builder.setUpdateTable(
         () -> {
           AllAxes data = getAccelerations();
-          entryX.setDouble(data.XAxis);
-          entryY.setDouble(data.YAxis);
-          entryZ.setDouble(data.ZAxis);
+          pubX.set(data.XAxis);
+          pubY.set(data.YAxis);
+          pubZ.set(data.ZAxis);
         });
   }
 }
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXRS450_Gyro.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXRS450_Gyro.java
index 5a826de..145e6e2 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXRS450_Gyro.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXRS450_Gyro.java
@@ -26,7 +26,7 @@
  * <p>This class is for the digital ADXRS450 gyro sensor that connects via SPI. Only one instance of
  * an ADXRS Gyro is supported.
  */
-@SuppressWarnings({"TypeName", "AbbreviationAsWordInName", "PMD.UnusedPrivateField"})
+@SuppressWarnings({"TypeName", "PMD.UnusedPrivateField"})
 public class ADXRS450_Gyro implements Gyro, Sendable {
   private static final double kSamplePeriod = 0.0005;
   private static final double kCalibrationSampleTime = 5.0;
@@ -71,9 +71,7 @@
     }
 
     m_spi.setClockRate(3000000);
-    m_spi.setMSBFirst();
-    m_spi.setSampleDataOnLeadingEdge();
-    m_spi.setClockActiveHigh();
+    m_spi.setMode(SPI.Mode.kMode0);
     m_spi.setChipSelectActiveLow();
 
     if (m_simDevice == null) {
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AddressableLED.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AddressableLED.java
index f4b367a..2b1f54b 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AddressableLED.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AddressableLED.java
@@ -42,7 +42,7 @@
   /**
    * Sets the length of the LED strip.
    *
-   * <p>Calling this is an expensive call, so its best to call it once, then just update data.
+   * <p>Calling this is an expensive call, so it's best to call it once, then just update data.
    *
    * <p>The max length is 5460 LEDs.
    *
@@ -53,7 +53,7 @@
   }
 
   /**
-   * Sets the led output data.
+   * Sets the LED output data.
    *
    * <p>If the output is enabled, this will start writing the next data cycle. It is safe to call,
    * even while output is enabled.
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AddressableLEDBuffer.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AddressableLEDBuffer.java
index c9659a1..a19773e 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AddressableLEDBuffer.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AddressableLEDBuffer.java
@@ -28,7 +28,6 @@
    * @param g the g value [0-255]
    * @param b the b value [0-255]
    */
-  @SuppressWarnings("ParameterName")
   public void setRGB(int index, int r, int g, int b) {
     m_buffer[index * 4] = (byte) b;
     m_buffer[(index * 4) + 1] = (byte) g;
@@ -40,42 +39,58 @@
    * Sets a specific led in the buffer.
    *
    * @param index the index to write
-   * @param h the h value [0-180]
+   * @param h the h value [0-180)
    * @param s the s value [0-255]
    * @param v the v value [0-255]
    */
-  @SuppressWarnings("ParameterName")
   public void setHSV(final int index, final int h, final int s, final int v) {
     if (s == 0) {
       setRGB(index, v, v, v);
       return;
     }
 
-    final int region = h / 30;
-    final int remainder = (h - (region * 30)) * 6;
+    // The below algorithm is copied from Color.fromHSV and moved here for
+    // performance reasons.
 
-    final int p = (v * (255 - s)) >> 8;
-    final int q = (v * (255 - ((s * remainder) >> 8))) >> 8;
-    final int t = (v * (255 - ((s * (255 - remainder)) >> 8))) >> 8;
+    // Loosely based on
+    // https://en.wikipedia.org/wiki/HSL_and_HSV#HSV_to_RGB
+    // The hue range is split into 60 degree regions where in each region there
+    // is one rgb component at a low value (m), one at a high value (v) and one
+    // that changes (X) from low to high (X+m) or high to low (v-X)
+
+    // Difference between highest and lowest value of any rgb component
+    final int chroma = (s * v) / 255;
+
+    // Because hue is 0-180 rather than 0-360 use 30 not 60
+    final int region = (h / 30) % 6;
+
+    // Remainder converted from 0-30 to 0-255
+    final int remainder = (int) Math.round((h % 30) * (255 / 30.0));
+
+    // Value of the lowest rgb component
+    final int m = v - chroma;
+
+    // Goes from 0 to chroma as hue increases
+    final int X = (chroma * remainder) >> 8;
 
     switch (region) {
       case 0:
-        setRGB(index, v, t, p);
+        setRGB(index, v, X + m, m);
         break;
       case 1:
-        setRGB(index, q, v, p);
+        setRGB(index, v - X, v, m);
         break;
       case 2:
-        setRGB(index, p, v, t);
+        setRGB(index, m, v, X + m);
         break;
       case 3:
-        setRGB(index, p, q, v);
+        setRGB(index, m, v - X, v);
         break;
       case 4:
-        setRGB(index, t, p, v);
+        setRGB(index, X + m, m, v);
         break;
       default:
-        setRGB(index, v, p, q);
+        setRGB(index, v, m, v - X);
         break;
     }
   }
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogAccelerometer.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogAccelerometer.java
index a2405b8..3ea9ef7 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogAccelerometer.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogAccelerometer.java
@@ -4,7 +4,7 @@
 
 package edu.wpi.first.wpilibj;
 
-import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
 
 import edu.wpi.first.hal.FRCNetComm.tResourceType;
 import edu.wpi.first.hal.HAL;
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogEncoder.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogEncoder.java
index 24989dd..8e45869 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogEncoder.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogEncoder.java
@@ -7,6 +7,7 @@
 import edu.wpi.first.hal.SimDevice;
 import edu.wpi.first.hal.SimDevice.Direction;
 import edu.wpi.first.hal.SimDouble;
+import edu.wpi.first.math.MathUtil;
 import edu.wpi.first.util.sendable.Sendable;
 import edu.wpi.first.util.sendable.SendableBuilder;
 import edu.wpi.first.util.sendable.SendableRegistry;
@@ -23,6 +24,7 @@
 
   protected SimDevice m_simDevice;
   protected SimDouble m_simPosition;
+  protected SimDouble m_simAbsolutePosition;
 
   /**
    * Construct a new AnalogEncoder attached to a specific AnalogIn channel.
@@ -51,6 +53,7 @@
 
     if (m_simDevice != null) {
       m_simPosition = m_simDevice.createDouble("Position", Direction.kInput, 0.0);
+      m_simAbsolutePosition = m_simDevice.createDouble("absPosition", Direction.kInput, 0.0);
     }
 
     // Limits need to be 25% from each end
@@ -61,6 +64,11 @@
     SendableRegistry.addLW(this, "Analog Encoder", m_analogInput.getChannel());
   }
 
+  private boolean doubleEquals(double a, double b) {
+    double epsilon = 0.00001d;
+    return Math.abs(a - b) < epsilon;
+  }
+
   /**
    * Get the encoder value since the last reset.
    *
@@ -80,7 +88,8 @@
       double pos = m_analogInput.getVoltage();
       double counter2 = m_counter.get();
       double pos2 = m_analogInput.getVoltage();
-      if (counter == counter2 && pos == pos2) {
+      if (counter == counter2 && doubleEquals(pos, pos2)) {
+        pos = pos / RobotController.getVoltage5V();
         double position = counter + pos - m_positionOffset;
         m_lastPosition = position;
         return position;
@@ -93,11 +102,28 @@
   }
 
   /**
+   * Get the absolute position of the analog encoder.
+   *
+   * <p>getAbsolutePosition() - getPositionOffset() will give an encoder absolute position relative
+   * to the last reset. This could potentially be negative, which needs to be accounted for.
+   *
+   * <p>This will not account for rollovers, and will always be just the raw absolute position.
+   *
+   * @return the absolute position
+   */
+  public double getAbsolutePosition() {
+    if (m_simAbsolutePosition != null) {
+      return m_simAbsolutePosition.get();
+    }
+
+    return m_analogInput.getVoltage() / RobotController.getVoltage5V();
+  }
+
+  /**
    * Get the offset of position relative to the last reset.
    *
-   * <p>getPositionInRotation() - getPositionOffset() will give an encoder absolute position
-   * relative to the last reset. This could potentially be negative, which needs to be accounted
-   * for.
+   * <p>getAbsolutePosition() - getPositionOffset() will give an encoder absolute position relative
+   * to the last reset. This could potentially be negative, which needs to be accounted for.
    *
    * @return the position offset
    */
@@ -106,10 +132,21 @@
   }
 
   /**
+   * Set the position offset.
+   *
+   * <p>This must be in the range of 0-1.
+   *
+   * @param offset the offset
+   */
+  public void setPositionOffset(double offset) {
+    m_positionOffset = MathUtil.clamp(offset, 0.0, 1.0);
+  }
+
+  /**
    * Set the distance per rotation of the encoder. This sets the multiplier used to determine the
-   * distance driven based on the rotation value from the encoder. Set this value based on the how
-   * far the mechanism travels in 1 rotation of the encoder, and factor in gearing reductions
-   * following the encoder shaft. This distance can be in any units you like, linear or angular.
+   * distance driven based on the rotation value from the encoder. Set this value based on how far
+   * the mechanism travels in 1 rotation of the encoder, and factor in gearing reductions following
+   * the encoder shaft. This distance can be in any units you like, linear or angular.
    *
    * @param distancePerRotation the distance per rotation of the encoder
    */
@@ -148,7 +185,7 @@
   /** Reset the Encoder distance to zero. */
   public void reset() {
     m_counter.reset();
-    m_positionOffset = m_analogInput.getVoltage();
+    m_positionOffset = m_analogInput.getVoltage() / RobotController.getVoltage5V();
   }
 
   @Override
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogGyro.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogGyro.java
index c9b9126..06c7e46 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogGyro.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogGyro.java
@@ -4,7 +4,7 @@
 
 package edu.wpi.first.wpilibj;
 
-import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
 
 import edu.wpi.first.hal.AnalogGyroJNI;
 import edu.wpi.first.hal.FRCNetComm.tResourceType;
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogInput.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogInput.java
index e3bedcb..e90bfd2 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogInput.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogInput.java
@@ -107,8 +107,8 @@
   }
 
   /**
-   * Get the factory scaling least significant bit weight constant. The least significant bit weight
-   * constant for the channel that was calibrated in manufacturing and stored in an eeprom.
+   * Get the factory scaling the least significant bit weight constant. The least significant bit
+   * weight constant for the channel that was calibrated in manufacturing and stored in an eeprom.
    *
    * <p>Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9)
    *
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogPotentiometer.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogPotentiometer.java
index 4a5bd75..7d58585 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogPotentiometer.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogPotentiometer.java
@@ -23,8 +23,8 @@
    * AnalogPotentiometer constructor.
    *
    * <p>Use the fullRange and offset values so that the output produces meaningful values. I.E: you
-   * have a 270 degree potentiometer and you want the output to be degrees with the halfway point as
-   * 0 degrees. The fullRange value is 270.0(degrees) and the offset is -135.0 since the halfway
+   * have a 270 degree potentiometer, and you want the output to be degrees with the halfway point
+   * as 0 degrees. The fullRange value is 270.0(degrees) and the offset is -135.0 since the halfway
    * point after scaling is 135 degrees. This will calculate the result from the fullRange times the
    * fraction of the supply voltage, plus the offset.
    *
@@ -43,8 +43,8 @@
    * AnalogPotentiometer constructor.
    *
    * <p>Use the fullRange and offset values so that the output produces meaningful values. I.E: you
-   * have a 270 degree potentiometer and you want the output to be degrees with the halfway point as
-   * 0 degrees. The fullRange value is 270.0(degrees) and the offset is -135.0 since the halfway
+   * have a 270 degree potentiometer, and you want the output to be degrees with the halfway point
+   * as 0 degrees. The fullRange value is 270.0(degrees) and the offset is -135.0 since the halfway
    * point after scaling is 135 degrees. This will calculate the result from the fullRange times the
    * fraction of the supply voltage, plus the offset.
    *
@@ -66,7 +66,7 @@
    * AnalogPotentiometer constructor.
    *
    * <p>Use the scale value so that the output produces meaningful values. I.E: you have a 270
-   * degree potentiometer and you want the output to be degrees with the starting point as 0
+   * degree potentiometer, and you want the output to be degrees with the starting point as 0
    * degrees. The scale value is 270.0(degrees).
    *
    * @param channel The analog input channel this potentiometer is plugged into. 0-3 are on-board
@@ -81,7 +81,7 @@
    * AnalogPotentiometer constructor.
    *
    * <p>Use the fullRange and offset values so that the output produces meaningful values. I.E: you
-   * have a 270 degree potentiometer and you want the output to be degrees with the starting point
+   * have a 270 degree potentiometer, and you want the output to be degrees with the starting point
    * as 0 degrees. The scale value is 270.0(degrees).
    *
    * @param input The {@link AnalogInput} this potentiometer is plugged into.
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTrigger.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTrigger.java
index d5825c1..8baa508 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTrigger.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTrigger.java
@@ -16,7 +16,6 @@
 /** Class for creating and configuring Analog Triggers. */
 public class AnalogTrigger implements Sendable, AutoCloseable {
   /** Exceptions dealing with improper operation of the Analog trigger. */
-  @SuppressWarnings("serial")
   public static class AnalogTriggerException extends RuntimeException {
     /**
      * Create a new exception with the given message.
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTriggerOutput.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTriggerOutput.java
index 0f513b4..0f37edc 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTriggerOutput.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTriggerOutput.java
@@ -4,7 +4,7 @@
 
 package edu.wpi.first.wpilibj;
 
-import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
 
 import edu.wpi.first.hal.AnalogJNI;
 import edu.wpi.first.hal.FRCNetComm.tResourceType;
@@ -22,8 +22,8 @@
  * upper limit, then the output is true. If the analog value is in between, then the trigger output
  * state maintains its most recent value.
  *
- * <p>The InWindow output indicates whether or not the analog signal is inside the range defined by
- * the limits.
+ * <p>The InWindow output indicates whether the analog signal is inside the range defined by the
+ * limits.
  *
  * <p>The RisingPulse and FallingPulse outputs detect an instantaneous transition from above the
  * upper limit to below the lower limit, and vise versa. These pulses represent a rollover condition
@@ -40,7 +40,6 @@
  */
 public class AnalogTriggerOutput extends DigitalSource implements Sendable {
   /** Exceptions dealing with improper operation of the Analog trigger output. */
-  @SuppressWarnings("serial")
   public static class AnalogTriggerOutputException extends RuntimeException {
     /**
      * Create a new exception with the given message.
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AsynchronousInterrupt.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AsynchronousInterrupt.java
index 1981671..4cb3cb5 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AsynchronousInterrupt.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/AsynchronousInterrupt.java
@@ -4,7 +4,7 @@
 
 package edu.wpi.first.wpilibj;
 
-import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
 
 import java.util.concurrent.atomic.AtomicBoolean;
 import java.util.function.BiConsumer;
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/CAN.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/CAN.java
index 3dc6c1d..77ccb37 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/CAN.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/CAN.java
@@ -149,7 +149,7 @@
   }
 
   /**
-   * Read a CAN packet. The will continuously return the last packet received, without accounting
+   * Read a CAN packet. This will continuously return the last packet received, without accounting
    * for packet age.
    *
    * @param apiId The API ID to read.
@@ -161,7 +161,7 @@
   }
 
   /**
-   * Read a CAN packet. The will return the last packet received until the packet is older then the
+   * Read a CAN packet. This will return the last packet received until the packet is older than the
    * requested timeout. Then it will return false.
    *
    * @param apiId The API ID to read.
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Compressor.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Compressor.java
index a7d079b..e26bd62 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Compressor.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Compressor.java
@@ -63,74 +63,63 @@
   }
 
   /**
-   * Start the compressor running in closed loop control mode.
-   *
-   * <p>Use the method in cases where you would like to manually stop and start the compressor for
-   * applications such as conserving battery or making sure that the compressor motor doesn't start
-   * during critical operations.
-   *
-   * @deprecated Use enableDigital() instead.
-   */
-  @Deprecated(since = "2022", forRemoval = true)
-  public void start() {
-    enableDigital();
-  }
-
-  /**
-   * Stop the compressor from running in closed loop control mode.
-   *
-   * <p>Use the method in cases where you would like to manually stop and start the compressor for
-   * applications such as conserving battery or making sure that the compressor motor doesn't start
-   * during critical operations.
-   *
-   * @deprecated Use disable() instead.
-   */
-  @Deprecated(since = "2022", forRemoval = true)
-  public void stop() {
-    disable();
-  }
-
-  /**
-   * Get the status of the compressor.
+   * Get the status of the compressor. To (re)enable the compressor use enableDigital() or
+   * enableAnalog(...).
    *
    * @return true if the compressor is on
+   * @deprecated To avoid confusion in thinking this (re)enables the compressor use IsEnabled().
    */
+  @Deprecated(since = "2023", forRemoval = true)
   public boolean enabled() {
+    return isEnabled();
+  }
+
+  /**
+   * Returns whether the compressor is active or not.
+   *
+   * @return true if the compressor is on - otherwise false.
+   */
+  public boolean isEnabled() {
     return m_module.getCompressor();
   }
 
   /**
-   * Get the pressure switch value.
+   * Returns the state of the pressure switch.
    *
-   * @return true if the pressure is low
+   * @return True if pressure switch indicates that the system is not full, otherwise false.
    */
   public boolean getPressureSwitchValue() {
     return m_module.getPressureSwitch();
   }
 
   /**
-   * Get the current being used by the compressor.
+   * Get the current drawn by the compressor.
    *
-   * @return current consumed by the compressor in amps
+   * @return Current drawn by the compressor in amps.
    */
   public double getCurrent() {
     return m_module.getCompressorCurrent();
   }
 
   /**
-   * Query the analog input voltage (on channel 0) (if supported).
+   * If supported by the device, returns the analog input voltage (on channel 0).
    *
-   * @return The analog input voltage, in volts
+   * <p>This function is only supported by the REV PH. On CTRE PCM, this will return 0.
+   *
+   * @return The analog input voltage, in volts.
    */
   public double getAnalogVoltage() {
     return m_module.getAnalogVoltage(0);
   }
 
   /**
-   * Query the analog sensor pressure (on channel 0) (if supported). Note this is only for use with
-   * the REV Analog Pressure Sensor.
+   * If supported by the device, returns the pressure (in PSI) read by the analog pressure sensor
+   * (on channel 0).
    *
-   * @return The analog sensor pressure, in PSI
+   * <p>This function is only supported by the REV PH with the REV Analog Pressure Sensor. On CTRE
+   * PCM, this will return 0.
+   *
+   * @return The pressure (in PSI) read by the analog pressure sensor.
    */
   public double getPressure() {
     return m_module.getPressure(0);
@@ -141,41 +130,71 @@
     m_module.disableCompressor();
   }
 
-  /** Enable compressor closed loop control using digital input. */
+  /**
+   * Enables the compressor in digital mode using the digital pressure switch. The compressor will
+   * turn on when the pressure switch indicates that the system is not full, and will turn off when
+   * the pressure switch indicates that the system is full.
+   */
   public void enableDigital() {
     m_module.enableCompressorDigital();
   }
 
   /**
-   * Enable compressor closed loop control using analog input. Note this is only for use with the
-   * REV Analog Pressure Sensor.
+   * If supported by the device, enables the compressor in analog mode. This mode uses an analog
+   * pressure sensor connected to analog channel 0 to cycle the compressor. The compressor will turn
+   * on when the pressure drops below {@code minPressure} and will turn off when the pressure
+   * reaches {@code maxPressure}. This mode is only supported by the REV PH with the REV Analog
+   * Pressure Sensor connected to analog channel 0.
    *
    * <p>On CTRE PCM, this will enable digital control.
    *
-   * @param minPressure The minimum pressure in PSI to enable compressor
-   * @param maxPressure The maximum pressure in PSI to disable compressor
+   * @param minPressure The minimum pressure in PSI. The compressor will turn on when the pressure
+   *     drops below this value.
+   * @param maxPressure The maximum pressure in PSI. The compressor will turn off when the pressure
+   *     reaches this value.
    */
   public void enableAnalog(double minPressure, double maxPressure) {
     m_module.enableCompressorAnalog(minPressure, maxPressure);
   }
 
   /**
-   * Enable compressor closed loop control using hybrid input. Note this is only for use with the
-   * REV Analog Pressure Sensor.
+   * If supported by the device, enables the compressor in hybrid mode. This mode uses both a
+   * digital pressure switch and an analog pressure sensor connected to analog channel 0 to cycle
+   * the compressor. This mode is only supported by the REV PH with the REV Analog Pressure Sensor
+   * connected to analog channel 0.
+   *
+   * <p>The compressor will turn on when <i>both</i>:
+   *
+   * <ul>
+   *   <li>The digital pressure switch indicates the system is not full AND
+   *   <li>The analog pressure sensor indicates that the pressure in the system is below the
+   *       specified minimum pressure.
+   * </ul>
+   *
+   * <p>The compressor will turn off when <i>either</i>:
+   *
+   * <ul>
+   *   <li>The digital pressure switch is disconnected or indicates that the system is full OR
+   *   <li>The pressure detected by the analog sensor is greater than the specified maximum
+   *       pressure.
+   * </ul>
    *
    * <p>On CTRE PCM, this will enable digital control.
    *
-   * @param minPressure The minimum pressure in PSI to enable compressor
-   * @param maxPressure The maximum pressure in PSI to disable compressor
+   * @param minPressure The minimum pressure in PSI. The compressor will turn on when the pressure
+   *     drops below this value and the pressure switch indicates that the system is not full.
+   * @param maxPressure The maximum pressure in PSI. The compressor will turn off when the pressure
+   *     reaches this value or the pressure switch is disconnected or indicates that the system is
+   *     full.
    */
   public void enableHybrid(double minPressure, double maxPressure) {
     m_module.enableCompressorHybrid(minPressure, maxPressure);
   }
 
   /**
-   * Gets the current operating mode of the Compressor.
+   * Returns the active compressor configuration.
    *
-   * @return true if compressor is operating on closed-loop mode
+   * @return The active compressor configuration.
    */
   public CompressorConfigType getConfigType() {
     return m_module.getCompressorConfigType();
@@ -184,7 +203,7 @@
   @Override
   public void initSendable(SendableBuilder builder) {
     builder.setSmartDashboardType("Compressor");
-    builder.addBooleanProperty("Enabled", this::enabled, null);
+    builder.addBooleanProperty("Enabled", this::isEnabled, null);
     builder.addBooleanProperty("Pressure switch", this::getPressureSwitchValue, null);
   }
 }
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Controller.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Controller.java
deleted file mode 100644
index 886050b..0000000
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Controller.java
+++ /dev/null
@@ -1,23 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj;
-
-/**
- * An interface for controllers. Controllers run control loops, the most command are PID controllers
- * and there variants, but this includes anything that is controlling an actuator in a separate
- * thread.
- *
- * @deprecated None of the 2020 FRC controllers use this.
- */
-@Deprecated(since = "2020", forRemoval = true)
-public interface Controller {
-  /** Allows the control loop to run. */
-  void enable();
-
-  /**
-   * Stops the control loop from running until explicitly re-enabled by calling {@link #enable()}.
-   */
-  void disable();
-}
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Counter.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Counter.java
index d445e9f..01483ab 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Counter.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Counter.java
@@ -4,8 +4,7 @@
 
 package edu.wpi.first.wpilibj;
 
-import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
-import static java.util.Objects.requireNonNull;
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
 
 import edu.wpi.first.hal.CounterJNI;
 import edu.wpi.first.hal.FRCNetComm.tResourceType;
@@ -192,7 +191,6 @@
    *
    * @return the Counter's FPGA index
    */
-  @SuppressWarnings("AbbreviationAsWordInName")
   public int getFPGAIndex() {
     return m_index;
   }
@@ -280,7 +278,7 @@
    * @param source the digital source to count
    */
   public void setDownSource(DigitalSource source) {
-    requireNonNull(source, "The Digital Source given was null");
+    requireNonNullParam(source, "source", "setDownSource");
 
     if (m_downSource != null && m_allocatedDownSource) {
       m_downSource.close();
@@ -313,7 +311,9 @@
    * @param fallingEdge true to count the falling edge
    */
   public void setDownSourceEdge(boolean risingEdge, boolean fallingEdge) {
-    requireNonNull(m_downSource, "Down Source must be set before setting the edge!");
+    if (m_downSource == null) {
+      throw new IllegalStateException("Down Source must be set before setting the edge!");
+    }
 
     CounterJNI.setCounterDownSourceEdge(m_counter, risingEdge, fallingEdge);
   }
@@ -385,7 +385,7 @@
   }
 
   /**
-   * Reset the Counter to zero. Set the counter value to zero. This doesn't effect the running state
+   * Reset the Counter to zero. Set the counter value to zero. This doesn't affect the running state
    * of the counter, just sets the current value to zero.
    */
   @Override
@@ -425,7 +425,7 @@
   /**
    * Determine if the clock is stopped. Determine if the clocked input is stopped based on the
    * MaxPeriod value set using the SetMaxPeriod method. If the clock exceeds the MaxPeriod, then the
-   * device (and counter) are assumed to be stopped and it returns true.
+   * device (and counter) are assumed to be stopped and the method will return true.
    *
    * @return true if the most recent counter period exceeds the MaxPeriod value set by SetMaxPeriod.
    */
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/CounterBase.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/CounterBase.java
index 735b893..60d5690 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/CounterBase.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/CounterBase.java
@@ -6,14 +6,14 @@
 
 /**
  * Interface for counting the number of ticks on a digital input channel. Encoders, Gear tooth
- * sensors, and counters should all subclass this so it can be used to build more advanced classes
- * for control and driving.
+ * sensors, and counters should all subclass this in order to build more advanced classes for
+ * control and driving.
  *
  * <p>All counters will immediately start counting - reset() them if you need them to be zeroed
  * before use.
  */
 public interface CounterBase {
-  /** The number of edges for the counterbase to increment or decrement on. */
+  /** The number of edges for the CounterBase to increment or decrement on. */
   enum EncodingType {
     /** Count only the rising edge. */
     k1X(0),
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/DSControlWord.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/DSControlWord.java
index 37e046d..8837d41 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/DSControlWord.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/DSControlWord.java
@@ -16,12 +16,12 @@
    * <p>Upon construction, the current Driver Station control word is read and stored internally.
    */
   public DSControlWord() {
-    update();
+    refresh();
   }
 
   /** Update internal Driver Station control word. */
-  public void update() {
-    DriverStation.updateControlWordFromCache(m_controlWord);
+  public void refresh() {
+    DriverStation.refreshControlWordFromCache(m_controlWord);
   }
 
   /**
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/DataLogManager.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/DataLogManager.java
new file mode 100644
index 0000000..927c14d
--- /dev/null
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/DataLogManager.java
@@ -0,0 +1,384 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.networktables.NetworkTableInstance;
+import edu.wpi.first.util.WPIUtilJNI;
+import edu.wpi.first.util.concurrent.Event;
+import edu.wpi.first.util.datalog.DataLog;
+import edu.wpi.first.util.datalog.IntegerLogEntry;
+import edu.wpi.first.util.datalog.StringLogEntry;
+import java.io.File;
+import java.io.IOException;
+import java.nio.file.Files;
+import java.nio.file.Path;
+import java.nio.file.Paths;
+import java.time.LocalDateTime;
+import java.time.ZoneId;
+import java.time.format.DateTimeFormatter;
+import java.util.Arrays;
+import java.util.Comparator;
+import java.util.Random;
+
+/**
+ * Centralized data log that provides automatic data log file management. It automatically cleans up
+ * old files when disk space is low and renames the file based either on current date/time or (if
+ * available) competition match number. The deta file will be saved to a USB flash drive if one is
+ * attached, or to /home/lvuser otherwise.
+ *
+ * <p>Log files are initially named "FRC_TBD_{random}.wpilog" until the DS connects. After the DS
+ * connects, the log file is renamed to "FRC_yyyyMMdd_HHmmss.wpilog" (where the date/time is UTC).
+ * If the FMS is connected and provides a match number, the log file is renamed to
+ * "FRC_yyyyMMdd_HHmmss_{event}_{match}.wpilog".
+ *
+ * <p>On startup, all existing FRC_TBD log files are deleted. If there is less than 50 MB of free
+ * space on the target storage, FRC_ log files are deleted (oldest to newest) until there is 50 MB
+ * free OR there are 10 files remaining.
+ *
+ * <p>By default, all NetworkTables value changes are stored to the data log.
+ */
+public final class DataLogManager {
+  private static DataLog m_log;
+  private static String m_logDir;
+  private static boolean m_filenameOverride;
+  private static final Thread m_thread;
+  private static final ZoneId m_utc = ZoneId.of("UTC");
+  private static final DateTimeFormatter m_timeFormatter =
+      DateTimeFormatter.ofPattern("yyyyMMdd_HHmmss").withZone(m_utc);
+  private static boolean m_ntLoggerEnabled = true;
+  private static int m_ntEntryLogger;
+  private static int m_ntConnLogger;
+  private static StringLogEntry m_messageLog;
+
+  // if less than this much free space, delete log files until there is this much free space
+  // OR there are this many files remaining.
+  private static final long kFreeSpaceThreshold = 50000000L;
+  private static final int kFileCountThreshold = 10;
+
+  private DataLogManager() {}
+
+  static {
+    m_thread = new Thread(DataLogManager::logMain, "DataLogDS");
+    m_thread.setDaemon(true);
+  }
+
+  /** Start data log manager with default directory location. */
+  public static synchronized void start() {
+    start("", "", 0.25);
+  }
+
+  /**
+   * Start data log manager. The parameters have no effect if the data log manager was already
+   * started (e.g. by calling another static function).
+   *
+   * @param dir if not empty, directory to use for data log storage
+   */
+  public static synchronized void start(String dir) {
+    start(dir, "", 0.25);
+  }
+
+  /**
+   * Start data log manager. The parameters have no effect if the data log manager was already
+   * started (e.g. by calling another static function).
+   *
+   * @param dir if not empty, directory to use for data log storage
+   * @param filename filename to use; if none provided, the filename is automatically generated
+   */
+  public static synchronized void start(String dir, String filename) {
+    start(dir, filename, 0.25);
+  }
+
+  /**
+   * Start data log manager. The parameters have no effect if the data log manager was already
+   * started (e.g. by calling another static function).
+   *
+   * @param dir if not empty, directory to use for data log storage
+   * @param filename filename to use; if none provided, the filename is automatically generated
+   * @param period time between automatic flushes to disk, in seconds; this is a time/storage
+   *     tradeoff
+   */
+  public static synchronized void start(String dir, String filename, double period) {
+    if (m_log != null) {
+      return;
+    }
+    m_logDir = makeLogDir(dir);
+    m_filenameOverride = !filename.isEmpty();
+
+    // Delete all previously existing FRC_TBD_*.wpilog files. These only exist when the robot
+    // never connects to the DS, so they are very unlikely to have useful data and just clutter
+    // the filesystem.
+    File[] files =
+        new File(m_logDir)
+            .listFiles((d, name) -> name.startsWith("FRC_TBD_") && name.endsWith(".wpilog"));
+    if (files != null) {
+      for (File file : files) {
+        if (!file.delete()) {
+          System.err.println("DataLogManager: could not delete " + file);
+        }
+      }
+    }
+
+    m_log = new DataLog(m_logDir, makeLogFilename(filename), period);
+    m_messageLog = new StringLogEntry(m_log, "messages");
+    m_thread.start();
+
+    // Log all NT entries and connections
+    if (m_ntLoggerEnabled) {
+      startNtLog();
+    }
+  }
+
+  /**
+   * Log a message to the "messages" entry. The message is also printed to standard output (followed
+   * by a newline).
+   *
+   * @param message message
+   */
+  public static synchronized void log(String message) {
+    if (m_messageLog == null) {
+      start();
+    }
+    m_messageLog.append(message);
+    System.out.println(message);
+  }
+
+  /**
+   * Get the managed data log (for custom logging). Starts the data log manager if not already
+   * started.
+   *
+   * @return data log
+   */
+  public static synchronized DataLog getLog() {
+    if (m_log == null) {
+      start();
+    }
+    return m_log;
+  }
+
+  /**
+   * Get the log directory.
+   *
+   * @return log directory, or empty string if logging not yet started
+   */
+  public static synchronized String getLogDir() {
+    if (m_logDir == null) {
+      return "";
+    }
+    return m_logDir;
+  }
+
+  /**
+   * Enable or disable logging of NetworkTables data. Note that unlike the network interface for
+   * NetworkTables, this will capture every value change. Defaults to enabled.
+   *
+   * @param enabled true to enable, false to disable
+   */
+  public static synchronized void logNetworkTables(boolean enabled) {
+    boolean wasEnabled = m_ntLoggerEnabled;
+    m_ntLoggerEnabled = enabled;
+    if (m_log == null) {
+      start();
+      return;
+    }
+    if (enabled && !wasEnabled) {
+      startNtLog();
+    } else if (!enabled && wasEnabled) {
+      stopNtLog();
+    }
+  }
+
+  private static String makeLogDir(String dir) {
+    if (!dir.isEmpty()) {
+      return dir;
+    }
+
+    if (RobotBase.isReal()) {
+      try {
+        // prefer a mounted USB drive if one is accessible
+        Path usbDir = Paths.get("/u").toRealPath();
+        if (Files.isWritable(usbDir)) {
+          return usbDir.toString();
+        }
+      } catch (IOException ex) {
+        // ignored
+      }
+    }
+
+    return Filesystem.getOperatingDirectory().getAbsolutePath();
+  }
+
+  private static String makeLogFilename(String filenameOverride) {
+    if (!filenameOverride.isEmpty()) {
+      return filenameOverride;
+    }
+    Random rnd = new Random();
+    StringBuilder filename = new StringBuilder();
+    filename.append("FRC_TBD_");
+    for (int i = 0; i < 4; i++) {
+      filename.append(String.format("%04x", rnd.nextInt(0x10000)));
+    }
+    filename.append(".wpilog");
+    return filename.toString();
+  }
+
+  private static void startNtLog() {
+    NetworkTableInstance inst = NetworkTableInstance.getDefault();
+    m_ntEntryLogger = inst.startEntryDataLog(m_log, "", "NT:");
+    m_ntConnLogger = inst.startConnectionDataLog(m_log, "NTConnection");
+  }
+
+  private static void stopNtLog() {
+    NetworkTableInstance.stopEntryDataLog(m_ntEntryLogger);
+    NetworkTableInstance.stopConnectionDataLog(m_ntConnLogger);
+  }
+
+  private static void logMain() {
+    // based on free disk space, scan for "old" FRC_*.wpilog files and remove
+    {
+      File logDir = new File(m_logDir);
+      long freeSpace = logDir.getFreeSpace();
+      if (freeSpace < kFreeSpaceThreshold) {
+        // Delete oldest FRC_*.wpilog files (ignore FRC_TBD_*.wpilog as we just created one)
+        File[] files =
+            logDir.listFiles(
+                (dir, name) ->
+                    name.startsWith("FRC_")
+                        && name.endsWith(".wpilog")
+                        && !name.startsWith("FRC_TBD_"));
+        if (files != null) {
+          Arrays.sort(files, Comparator.comparingLong(File::lastModified));
+          int count = files.length;
+          for (File file : files) {
+            --count;
+            if (count < kFileCountThreshold) {
+              break;
+            }
+            long length = file.length();
+            if (file.delete()) {
+              freeSpace += length;
+              if (freeSpace >= kFreeSpaceThreshold) {
+                break;
+              }
+            } else {
+              System.err.println("DataLogManager: could not delete " + file);
+            }
+          }
+        }
+      }
+    }
+
+    int timeoutCount = 0;
+    boolean paused = false;
+    int dsAttachCount = 0;
+    int fmsAttachCount = 0;
+    boolean dsRenamed = m_filenameOverride;
+    boolean fmsRenamed = m_filenameOverride;
+    int sysTimeCount = 0;
+    IntegerLogEntry sysTimeEntry =
+        new IntegerLogEntry(
+            m_log, "systemTime", "{\"source\":\"DataLogManager\",\"format\":\"time_t_us\"}");
+
+    Event newDataEvent = new Event();
+    DriverStation.provideRefreshedDataEventHandle(newDataEvent.getHandle());
+    while (!Thread.interrupted()) {
+      boolean timedOut;
+      try {
+        timedOut = WPIUtilJNI.waitForObjectTimeout(newDataEvent.getHandle(), 0.25);
+      } catch (InterruptedException e) {
+        break;
+      }
+      if (Thread.interrupted()) {
+        break;
+      }
+      if (timedOut) {
+        timeoutCount++;
+        // pause logging after being disconnected for 10 seconds
+        if (timeoutCount > 40 && !paused) {
+          timeoutCount = 0;
+          paused = true;
+          m_log.pause();
+        }
+        continue;
+      }
+      // when we connect to the DS, resume logging
+      timeoutCount = 0;
+      if (paused) {
+        paused = false;
+        m_log.resume();
+      }
+
+      if (!dsRenamed) {
+        // track DS attach
+        if (DriverStation.isDSAttached()) {
+          dsAttachCount++;
+        } else {
+          dsAttachCount = 0;
+        }
+        if (dsAttachCount > 50) { // 1 second
+          LocalDateTime now = LocalDateTime.now(m_utc);
+          if (now.getYear() > 2000) {
+            // assume local clock is now synchronized to DS, so rename based on
+            // local time
+            m_log.setFilename("FRC_" + m_timeFormatter.format(now) + ".wpilog");
+            dsRenamed = true;
+          } else {
+            dsAttachCount = 0; // wait a bit and try again
+          }
+        }
+      }
+
+      if (!fmsRenamed) {
+        // track FMS attach
+        if (DriverStation.isFMSAttached()) {
+          fmsAttachCount++;
+        } else {
+          fmsAttachCount = 0;
+        }
+        if (fmsAttachCount > 100) { // 2 seconds
+          // match info comes through TCP, so we need to double-check we've
+          // actually received it
+          DriverStation.MatchType matchType = DriverStation.getMatchType();
+          if (matchType != DriverStation.MatchType.None) {
+            // rename per match info
+            char matchTypeChar;
+            switch (matchType) {
+              case Practice:
+                matchTypeChar = 'P';
+                break;
+              case Qualification:
+                matchTypeChar = 'Q';
+                break;
+              case Elimination:
+                matchTypeChar = 'E';
+                break;
+              default:
+                matchTypeChar = '_';
+                break;
+            }
+            m_log.setFilename(
+                "FRC_"
+                    + m_timeFormatter.format(LocalDateTime.now(m_utc))
+                    + "_"
+                    + DriverStation.getEventName()
+                    + "_"
+                    + matchTypeChar
+                    + DriverStation.getMatchNumber()
+                    + ".wpilog");
+            fmsRenamed = true;
+            dsRenamed = true; // don't override FMS rename
+          }
+        }
+      }
+
+      // Write system time every ~5 seconds
+      sysTimeCount++;
+      if (sysTimeCount >= 250) {
+        sysTimeCount = 0;
+        sysTimeEntry.append(WPIUtilJNI.getSystemTime(), WPIUtilJNI.now());
+      }
+    }
+    newDataEvent.close();
+  }
+}
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalGlitchFilter.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalGlitchFilter.java
index abcc67b..3422d34 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalGlitchFilter.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalGlitchFilter.java
@@ -15,7 +15,7 @@
 
 /**
  * Class to enable glitch filtering on a set of digital inputs. This class will manage adding and
- * removing digital inputs from a FPGA glitch filter. The filter lets the user configure the time
+ * removing digital inputs from an FPGA glitch filter. The filter lets the user configure the time
  * that an input must remain high or low before it is classified as high or low.
  */
 public class DigitalGlitchFilter implements Sendable, AutoCloseable {
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalOutput.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalOutput.java
index 2c87df5..78e8bed 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalOutput.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalOutput.java
@@ -80,12 +80,15 @@
   }
 
   /**
-   * Generate a single pulse. There can only be a single pulse going at any time.
+   * Output a single pulse on the digital output line.
    *
-   * @param pulseLength The length of the pulse.
+   * <p>Send a single pulse on the digital output line where the pulse duration is specified in
+   * seconds. Maximum of 65535 microseconds.
+   *
+   * @param pulseLengthSeconds The pulse length in seconds
    */
-  public void pulse(final double pulseLength) {
-    DIOJNI.pulse(m_handle, pulseLength);
+  public void pulse(final double pulseLengthSeconds) {
+    DIOJNI.pulse(m_handle, pulseLengthSeconds);
   }
 
   /**
@@ -111,11 +114,31 @@
   }
 
   /**
+   * Enable a PWM PPS (Pulse Per Second) Output on this line.
+   *
+   * <p>Allocate one of the 6 DO PWM generator resources.
+   *
+   * <p>Supply the duty-cycle to output.
+   *
+   * <p>The resolution of the duty cycle is 8-bit.
+   *
+   * @param dutyCycle The duty-cycle to start generating. [0..1]
+   */
+  public void enablePPS(double dutyCycle) {
+    if (m_pwmGenerator != invalidPwmGenerator) {
+      return;
+    }
+    m_pwmGenerator = DIOJNI.allocateDigitalPWM();
+    DIOJNI.setDigitalPWMPPS(m_pwmGenerator, dutyCycle);
+    DIOJNI.setDigitalPWMOutputChannel(m_pwmGenerator, m_channel);
+  }
+
+  /**
    * Enable a PWM Output on this line.
    *
    * <p>Allocate one of the 6 DO PWM generator resources.
    *
-   * <p>Supply the initial duty-cycle to output so as to avoid a glitch when first starting.
+   * <p>Supply the initial duty-cycle to output in order to avoid a glitch when first starting.
    *
    * <p>The resolution of the duty cycle is 8-bit for low frequencies (1kHz or less) but is reduced
    * the higher the frequency of the PWM signal is.
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/DriverStation.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/DriverStation.java
index 8eeb284..e9d593c 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/DriverStation.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/DriverStation.java
@@ -6,19 +6,26 @@
 
 import edu.wpi.first.hal.AllianceStationID;
 import edu.wpi.first.hal.ControlWord;
+import edu.wpi.first.hal.DriverStationJNI;
 import edu.wpi.first.hal.HAL;
 import edu.wpi.first.hal.MatchInfoData;
+import edu.wpi.first.networktables.BooleanPublisher;
+import edu.wpi.first.networktables.IntegerPublisher;
 import edu.wpi.first.networktables.NetworkTable;
-import edu.wpi.first.networktables.NetworkTableEntry;
 import edu.wpi.first.networktables.NetworkTableInstance;
+import edu.wpi.first.networktables.StringPublisher;
+import edu.wpi.first.util.EventVector;
+import edu.wpi.first.util.WPIUtilJNI;
+import edu.wpi.first.util.datalog.BooleanArrayLogEntry;
+import edu.wpi.first.util.datalog.BooleanLogEntry;
+import edu.wpi.first.util.datalog.DataLog;
+import edu.wpi.first.util.datalog.FloatArrayLogEntry;
+import edu.wpi.first.util.datalog.IntegerArrayLogEntry;
 import java.nio.ByteBuffer;
-import java.util.concurrent.TimeUnit;
-import java.util.concurrent.locks.Condition;
-import java.util.concurrent.locks.Lock;
 import java.util.concurrent.locks.ReentrantLock;
 
 /** Provide access to the network communication data to / from the Driver Station. */
-public class DriverStation {
+public final class DriverStation {
   /** Number of Joystick Ports. */
   public static final int kJoystickPorts = 6;
 
@@ -29,16 +36,25 @@
 
   private static class HALJoystickAxes {
     public float[] m_axes;
-    public short m_count;
+    public int m_count;
 
     HALJoystickAxes(int count) {
       m_axes = new float[count];
     }
   }
 
+  private static class HALJoystickAxesRaw {
+    public int[] m_axes;
+    public int m_count;
+
+    HALJoystickAxesRaw(int count) {
+      m_axes = new int[count];
+    }
+  }
+
   private static class HALJoystickPOVs {
     public short[] m_povs;
-    public short m_count;
+    public int m_count;
 
     HALJoystickPOVs(int count) {
       m_povs = new short[count];
@@ -65,94 +81,51 @@
   private static final double JOYSTICK_UNPLUGGED_MESSAGE_INTERVAL = 1.0;
   private static double m_nextMessageTime;
 
-  private static class DriverStationTask implements Runnable {
-    DriverStationTask() {}
-
-    @Override
-    public void run() {
-      DriverStation.run();
-    }
-  } /* DriverStationTask */
-
+  @SuppressWarnings("MemberName")
   private static class MatchDataSender {
-    @SuppressWarnings("MemberName")
     NetworkTable table;
-
-    @SuppressWarnings("MemberName")
-    NetworkTableEntry typeMetadata;
-
-    @SuppressWarnings("MemberName")
-    NetworkTableEntry gameSpecificMessage;
-
-    @SuppressWarnings("MemberName")
-    NetworkTableEntry eventName;
-
-    @SuppressWarnings("MemberName")
-    NetworkTableEntry matchNumber;
-
-    @SuppressWarnings("MemberName")
-    NetworkTableEntry replayNumber;
-
-    @SuppressWarnings("MemberName")
-    NetworkTableEntry matchType;
-
-    @SuppressWarnings("MemberName")
-    NetworkTableEntry alliance;
-
-    @SuppressWarnings("MemberName")
-    NetworkTableEntry station;
-
-    @SuppressWarnings("MemberName")
-    NetworkTableEntry controlWord;
-
-    @SuppressWarnings("MemberName")
+    StringPublisher typeMetadata;
+    StringPublisher gameSpecificMessage;
+    StringPublisher eventName;
+    IntegerPublisher matchNumber;
+    IntegerPublisher replayNumber;
+    IntegerPublisher matchType;
+    BooleanPublisher alliance;
+    IntegerPublisher station;
+    IntegerPublisher controlWord;
     boolean oldIsRedAlliance = true;
-
-    @SuppressWarnings("MemberName")
     int oldStationNumber = 1;
-
-    @SuppressWarnings("MemberName")
     String oldEventName = "";
-
-    @SuppressWarnings("MemberName")
     String oldGameSpecificMessage = "";
-
-    @SuppressWarnings("MemberName")
     int oldMatchNumber;
-
-    @SuppressWarnings("MemberName")
     int oldReplayNumber;
-
-    @SuppressWarnings("MemberName")
     int oldMatchType;
-
-    @SuppressWarnings("MemberName")
     int oldControlWord;
 
     MatchDataSender() {
       table = NetworkTableInstance.getDefault().getTable("FMSInfo");
-      typeMetadata = table.getEntry(".type");
-      typeMetadata.forceSetString("FMSInfo");
-      gameSpecificMessage = table.getEntry("GameSpecificMessage");
-      gameSpecificMessage.forceSetString("");
-      eventName = table.getEntry("EventName");
-      eventName.forceSetString("");
-      matchNumber = table.getEntry("MatchNumber");
-      matchNumber.forceSetDouble(0);
-      replayNumber = table.getEntry("ReplayNumber");
-      replayNumber.forceSetDouble(0);
-      matchType = table.getEntry("MatchType");
-      matchType.forceSetDouble(0);
-      alliance = table.getEntry("IsRedAlliance");
-      alliance.forceSetBoolean(true);
-      station = table.getEntry("StationNumber");
-      station.forceSetDouble(1);
-      controlWord = table.getEntry("FMSControlData");
-      controlWord.forceSetDouble(0);
+      typeMetadata = table.getStringTopic(".type").publish();
+      typeMetadata.set("FMSInfo");
+      gameSpecificMessage = table.getStringTopic("GameSpecificMessage").publish();
+      gameSpecificMessage.set("");
+      eventName = table.getStringTopic("EventName").publish();
+      eventName.set("");
+      matchNumber = table.getIntegerTopic("MatchNumber").publish();
+      matchNumber.set(0);
+      replayNumber = table.getIntegerTopic("ReplayNumber").publish();
+      replayNumber.set(0);
+      matchType = table.getIntegerTopic("MatchType").publish();
+      matchType.set(0);
+      alliance = table.getBooleanTopic("IsRedAlliance").publish();
+      alliance.set(true);
+      station = table.getIntegerTopic("StationNumber").publish();
+      station.set(1);
+      controlWord = table.getIntegerTopic("FMSControlData").publish();
+      controlWord.set(0);
     }
 
     private void sendMatchData() {
-      AllianceStationID allianceID = HAL.getAllianceStation();
+      AllianceStationID allianceID = DriverStationJNI.getAllianceStation();
       boolean isRedAlliance = false;
       int stationNumber = 1;
       switch (allianceID) {
@@ -198,57 +171,218 @@
       } finally {
         m_cacheDataMutex.unlock();
       }
-      currentControlWord = HAL.nativeGetControlWord();
+      currentControlWord = DriverStationJNI.nativeGetControlWord();
 
       if (oldIsRedAlliance != isRedAlliance) {
-        alliance.setBoolean(isRedAlliance);
+        alliance.set(isRedAlliance);
         oldIsRedAlliance = isRedAlliance;
       }
       if (oldStationNumber != stationNumber) {
-        station.setDouble(stationNumber);
+        station.set(stationNumber);
         oldStationNumber = stationNumber;
       }
       if (!oldEventName.equals(currentEventName)) {
-        eventName.setString(currentEventName);
+        eventName.set(currentEventName);
         oldEventName = currentEventName;
       }
       if (!oldGameSpecificMessage.equals(currentGameSpecificMessage)) {
-        gameSpecificMessage.setString(currentGameSpecificMessage);
+        gameSpecificMessage.set(currentGameSpecificMessage);
         oldGameSpecificMessage = currentGameSpecificMessage;
       }
       if (currentMatchNumber != oldMatchNumber) {
-        matchNumber.setDouble(currentMatchNumber);
+        matchNumber.set(currentMatchNumber);
         oldMatchNumber = currentMatchNumber;
       }
       if (currentReplayNumber != oldReplayNumber) {
-        replayNumber.setDouble(currentReplayNumber);
+        replayNumber.set(currentReplayNumber);
         oldReplayNumber = currentReplayNumber;
       }
       if (currentMatchType != oldMatchType) {
-        matchType.setDouble(currentMatchType);
+        matchType.set(currentMatchType);
         oldMatchType = currentMatchType;
       }
       if (currentControlWord != oldControlWord) {
-        controlWord.setDouble(currentControlWord);
+        controlWord.set(currentControlWord);
         oldControlWord = currentControlWord;
       }
     }
   }
 
-  private static DriverStation instance = new DriverStation();
+  private static class JoystickLogSender {
+    JoystickLogSender(DataLog log, int stick, long timestamp) {
+      m_stick = stick;
+
+      m_logButtons = new BooleanArrayLogEntry(log, "DS:joystick" + stick + "/buttons", timestamp);
+      m_logAxes = new FloatArrayLogEntry(log, "DS:joystick" + stick + "/axes", timestamp);
+      m_logPOVs = new IntegerArrayLogEntry(log, "DS:joystick" + stick + "/povs", timestamp);
+
+      appendButtons(timestamp);
+      appendAxes(timestamp);
+      appendPOVs(timestamp);
+    }
+
+    public void send(long timestamp) {
+      if (m_joystickButtonsCache[m_stick].m_count != m_joystickButtons[m_stick].m_count
+          || m_joystickButtonsCache[m_stick].m_buttons != m_joystickButtons[m_stick].m_buttons) {
+        appendButtons(timestamp);
+      }
+
+      if (m_joystickAxesCache[m_stick].m_count != m_joystickAxes[m_stick].m_count) {
+        appendAxes(timestamp);
+      } else {
+        int count = m_joystickAxesCache[m_stick].m_count;
+        for (int i = 0; i < count; i++) {
+          if (m_joystickAxesCache[m_stick].m_axes[i] != m_joystickAxes[m_stick].m_axes[i]) {
+            appendAxes(timestamp);
+            break;
+          }
+        }
+      }
+
+      if (m_joystickPOVsCache[m_stick].m_count != m_joystickPOVs[m_stick].m_count) {
+        appendPOVs(timestamp);
+      } else {
+        int count = m_joystickPOVsCache[m_stick].m_count;
+        for (int i = 0; i < count; i++) {
+          if (m_joystickPOVsCache[m_stick].m_povs[i] != m_joystickPOVs[m_stick].m_povs[i]) {
+            appendPOVs(timestamp);
+            break;
+          }
+        }
+      }
+    }
+
+    void appendButtons(long timestamp) {
+      int count = m_joystickButtonsCache[m_stick].m_count;
+      if (m_sizedButtons == null || m_sizedButtons.length != count) {
+        m_sizedButtons = new boolean[count];
+      }
+      int buttons = m_joystickButtonsCache[m_stick].m_buttons;
+      for (int i = 0; i < count; i++) {
+        m_sizedButtons[i] = (buttons & (1 << i)) != 0;
+      }
+      m_logButtons.append(m_sizedButtons, timestamp);
+    }
+
+    void appendAxes(long timestamp) {
+      int count = m_joystickAxesCache[m_stick].m_count;
+      if (m_sizedAxes == null || m_sizedAxes.length != count) {
+        m_sizedAxes = new float[count];
+      }
+      System.arraycopy(m_joystickAxesCache[m_stick].m_axes, 0, m_sizedAxes, 0, count);
+      m_logAxes.append(m_sizedAxes, timestamp);
+    }
+
+    void appendPOVs(long timestamp) {
+      int count = m_joystickPOVsCache[m_stick].m_count;
+      if (m_sizedPOVs == null || m_sizedPOVs.length != count) {
+        m_sizedPOVs = new long[count];
+      }
+      for (int i = 0; i < count; i++) {
+        m_sizedPOVs[i] = m_joystickPOVsCache[m_stick].m_povs[i];
+      }
+      m_logPOVs.append(m_sizedPOVs, timestamp);
+    }
+
+    final int m_stick;
+    boolean[] m_sizedButtons;
+    float[] m_sizedAxes;
+    long[] m_sizedPOVs;
+    final BooleanArrayLogEntry m_logButtons;
+    final FloatArrayLogEntry m_logAxes;
+    final IntegerArrayLogEntry m_logPOVs;
+  }
+
+  private static class DataLogSender {
+    DataLogSender(DataLog log, boolean logJoysticks, long timestamp) {
+      m_logEnabled = new BooleanLogEntry(log, "DS:enabled", timestamp);
+      m_logAutonomous = new BooleanLogEntry(log, "DS:autonomous", timestamp);
+      m_logTest = new BooleanLogEntry(log, "DS:test", timestamp);
+      m_logEstop = new BooleanLogEntry(log, "DS:estop", timestamp);
+
+      // append initial control word values
+      m_wasEnabled = m_controlWordCache.getEnabled();
+      m_wasAutonomous = m_controlWordCache.getAutonomous();
+      m_wasTest = m_controlWordCache.getTest();
+      m_wasEstop = m_controlWordCache.getEStop();
+
+      m_logEnabled.append(m_wasEnabled, timestamp);
+      m_logAutonomous.append(m_wasAutonomous, timestamp);
+      m_logTest.append(m_wasTest, timestamp);
+      m_logEstop.append(m_wasEstop, timestamp);
+
+      if (logJoysticks) {
+        m_joysticks = new JoystickLogSender[kJoystickPorts];
+        for (int i = 0; i < kJoystickPorts; i++) {
+          m_joysticks[i] = new JoystickLogSender(log, i, timestamp);
+        }
+      } else {
+        m_joysticks = new JoystickLogSender[0];
+      }
+    }
+
+    public void send(long timestamp) {
+      // append control word value changes
+      boolean enabled = m_controlWordCache.getEnabled();
+      if (enabled != m_wasEnabled) {
+        m_logEnabled.append(enabled, timestamp);
+      }
+      m_wasEnabled = enabled;
+
+      boolean autonomous = m_controlWordCache.getAutonomous();
+      if (autonomous != m_wasAutonomous) {
+        m_logAutonomous.append(autonomous, timestamp);
+      }
+      m_wasAutonomous = autonomous;
+
+      boolean test = m_controlWordCache.getTest();
+      if (test != m_wasTest) {
+        m_logTest.append(test, timestamp);
+      }
+      m_wasTest = test;
+
+      boolean estop = m_controlWordCache.getEStop();
+      if (estop != m_wasEstop) {
+        m_logEstop.append(estop, timestamp);
+      }
+      m_wasEstop = estop;
+
+      // append joystick value changes
+      for (JoystickLogSender joystick : m_joysticks) {
+        joystick.send(timestamp);
+      }
+    }
+
+    boolean m_wasEnabled;
+    boolean m_wasAutonomous;
+    boolean m_wasTest;
+    boolean m_wasEstop;
+    final BooleanLogEntry m_logEnabled;
+    final BooleanLogEntry m_logAutonomous;
+    final BooleanLogEntry m_logTest;
+    final BooleanLogEntry m_logEstop;
+
+    final JoystickLogSender[] m_joysticks;
+  }
 
   // Joystick User Data
   private static HALJoystickAxes[] m_joystickAxes = new HALJoystickAxes[kJoystickPorts];
+  private static HALJoystickAxesRaw[] m_joystickAxesRaw = new HALJoystickAxesRaw[kJoystickPorts];
   private static HALJoystickPOVs[] m_joystickPOVs = new HALJoystickPOVs[kJoystickPorts];
   private static HALJoystickButtons[] m_joystickButtons = new HALJoystickButtons[kJoystickPorts];
   private static MatchInfoData m_matchInfo = new MatchInfoData();
+  private static ControlWord m_controlWord = new ControlWord();
+  private static EventVector m_refreshEvents = new EventVector();
 
   // Joystick Cached Data
   private static HALJoystickAxes[] m_joystickAxesCache = new HALJoystickAxes[kJoystickPorts];
+  private static HALJoystickAxesRaw[] m_joystickAxesRawCache =
+      new HALJoystickAxesRaw[kJoystickPorts];
   private static HALJoystickPOVs[] m_joystickPOVsCache = new HALJoystickPOVs[kJoystickPorts];
   private static HALJoystickButtons[] m_joystickButtonsCache =
       new HALJoystickButtons[kJoystickPorts];
   private static MatchInfoData m_matchInfoCache = new MatchInfoData();
+  private static ControlWord m_controlWordCache = new ControlWord();
 
   // Joystick button rising/falling edge flags
   private static int[] m_joystickButtonsPressed = new int[kJoystickPorts];
@@ -258,43 +392,12 @@
   private static final ByteBuffer m_buttonCountBuffer = ByteBuffer.allocateDirect(1);
 
   private static final MatchDataSender m_matchDataSender;
-
-  // Internal Driver Station thread
-  private static Thread m_thread;
-
-  private static volatile boolean m_threadKeepAlive = true;
+  private static DataLogSender m_dataLogSender;
 
   private static final ReentrantLock m_cacheDataMutex = new ReentrantLock();
 
-  private static final Lock m_waitForDataMutex;
-  private static final Condition m_waitForDataCond;
-  private static int m_waitForDataCount;
-  private static final ThreadLocal<Integer> m_lastCount = ThreadLocal.withInitial(() -> 0);
-
   private static boolean m_silenceJoystickWarning;
 
-  // Robot state status variables
-  private static boolean m_userInDisabled;
-  private static boolean m_userInAutonomous;
-  private static boolean m_userInTeleop;
-  private static boolean m_userInTest;
-
-  // Control word variables
-  private static final ReentrantLock m_controlWordMutex = new ReentrantLock();
-  private static final ControlWord m_controlWordCache;
-  private static long m_lastControlWordUpdate;
-
-  /**
-   * Gets an instance of the DriverStation.
-   *
-   * @return The DriverStation.
-   * @deprecated Use the static methods
-   */
-  @Deprecated
-  public static DriverStation getInstance() {
-    return DriverStation.instance;
-  }
-
   /**
    * DriverStation constructor.
    *
@@ -305,42 +408,20 @@
 
   static {
     HAL.initialize(500, 0);
-    m_waitForDataCount = 0;
-    m_waitForDataMutex = new ReentrantLock();
-    m_waitForDataCond = m_waitForDataMutex.newCondition();
 
     for (int i = 0; i < kJoystickPorts; i++) {
       m_joystickButtons[i] = new HALJoystickButtons();
-      m_joystickAxes[i] = new HALJoystickAxes(HAL.kMaxJoystickAxes);
-      m_joystickPOVs[i] = new HALJoystickPOVs(HAL.kMaxJoystickPOVs);
+      m_joystickAxes[i] = new HALJoystickAxes(DriverStationJNI.kMaxJoystickAxes);
+      m_joystickAxesRaw[i] = new HALJoystickAxesRaw(DriverStationJNI.kMaxJoystickAxes);
+      m_joystickPOVs[i] = new HALJoystickPOVs(DriverStationJNI.kMaxJoystickPOVs);
 
       m_joystickButtonsCache[i] = new HALJoystickButtons();
-      m_joystickAxesCache[i] = new HALJoystickAxes(HAL.kMaxJoystickAxes);
-      m_joystickPOVsCache[i] = new HALJoystickPOVs(HAL.kMaxJoystickPOVs);
+      m_joystickAxesCache[i] = new HALJoystickAxes(DriverStationJNI.kMaxJoystickAxes);
+      m_joystickAxesRawCache[i] = new HALJoystickAxesRaw(DriverStationJNI.kMaxJoystickAxes);
+      m_joystickPOVsCache[i] = new HALJoystickPOVs(DriverStationJNI.kMaxJoystickPOVs);
     }
 
-    m_controlWordCache = new ControlWord();
-    m_lastControlWordUpdate = 0;
-
     m_matchDataSender = new MatchDataSender();
-
-    m_thread = new Thread(new DriverStationTask(), "FRCDriverStation");
-    m_thread.setPriority((Thread.NORM_PRIORITY + Thread.MAX_PRIORITY) / 2);
-
-    m_thread.start();
-  }
-
-  /** Kill the thread. */
-  public static synchronized void release() {
-    m_threadKeepAlive = false;
-    if (m_thread != null) {
-      try {
-        m_thread.join();
-      } catch (InterruptedException ex) {
-        Thread.currentThread().interrupt();
-      }
-      m_thread = null;
-    }
   }
 
   /**
@@ -418,7 +499,8 @@
         }
       }
     }
-    HAL.sendError(isError, code, false, error, locString, traceString.toString(), true);
+    DriverStationJNI.sendError(
+        isError, code, false, error, locString, traceString.toString(), true);
   }
 
   /**
@@ -547,7 +629,7 @@
     if (stick < 0 || stick >= kJoystickPorts) {
       throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
     }
-    if (axis < 0 || axis >= HAL.kMaxJoystickAxes) {
+    if (axis < 0 || axis >= DriverStationJNI.kMaxJoystickAxes) {
       throw new IllegalArgumentException("Joystick axis is out of range");
     }
 
@@ -580,7 +662,7 @@
     if (stick < 0 || stick >= kJoystickPorts) {
       throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
     }
-    if (pov < 0 || pov >= HAL.kMaxJoystickPOVs) {
+    if (pov < 0 || pov >= DriverStationJNI.kMaxJoystickPOVs) {
       throw new IllegalArgumentException("Joystick POV is out of range");
     }
 
@@ -641,10 +723,10 @@
   }
 
   /**
-   * Returns the number of POVs on a given joystick port.
+   * Returns the number of povs on a given joystick port.
    *
    * @param stick The joystick port number
-   * @return The number of POVs on the indicated joystick
+   * @return The number of povs on the indicated joystick
    */
   public static int getStickPOVCount(int stick) {
     if (stick < 0 || stick >= kJoystickPorts) {
@@ -689,7 +771,7 @@
       throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
     }
 
-    return HAL.getJoystickIsXbox((byte) stick) == 1;
+    return DriverStationJNI.getJoystickIsXbox((byte) stick) == 1;
   }
 
   /**
@@ -703,7 +785,7 @@
       throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
     }
 
-    return HAL.getJoystickType((byte) stick);
+    return DriverStationJNI.getJoystickType((byte) stick);
   }
 
   /**
@@ -717,7 +799,7 @@
       throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
     }
 
-    return HAL.getJoystickName((byte) stick);
+    return DriverStationJNI.getJoystickName((byte) stick);
   }
 
   /**
@@ -732,7 +814,7 @@
       throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
     }
 
-    return HAL.getJoystickAxisType((byte) stick, (byte) axis);
+    return DriverStationJNI.getJoystickAxisType((byte) stick, (byte) axis);
   }
 
   /**
@@ -756,12 +838,11 @@
    * @return True if the robot is enabled, false otherwise.
    */
   public static boolean isEnabled() {
-    m_controlWordMutex.lock();
+    m_cacheDataMutex.lock();
     try {
-      updateControlWord(false);
-      return m_controlWordCache.getEnabled() && m_controlWordCache.getDSAttached();
+      return m_controlWord.getEnabled() && m_controlWord.getDSAttached();
     } finally {
-      m_controlWordMutex.unlock();
+      m_cacheDataMutex.unlock();
     }
   }
 
@@ -780,12 +861,11 @@
    * @return True if the robot is e-stopped, false otherwise.
    */
   public static boolean isEStopped() {
-    m_controlWordMutex.lock();
+    m_cacheDataMutex.lock();
     try {
-      updateControlWord(false);
-      return m_controlWordCache.getEStop();
+      return m_controlWord.getEStop();
     } finally {
-      m_controlWordMutex.unlock();
+      m_cacheDataMutex.unlock();
     }
   }
 
@@ -796,12 +876,11 @@
    * @return True if autonomous mode should be enabled, false otherwise.
    */
   public static boolean isAutonomous() {
-    m_controlWordMutex.lock();
+    m_cacheDataMutex.lock();
     try {
-      updateControlWord(false);
-      return m_controlWordCache.getAutonomous();
+      return m_controlWord.getAutonomous();
     } finally {
-      m_controlWordMutex.unlock();
+      m_cacheDataMutex.unlock();
     }
   }
 
@@ -812,12 +891,11 @@
    * @return True if autonomous should be set and the robot should be enabled.
    */
   public static boolean isAutonomousEnabled() {
-    m_controlWordMutex.lock();
+    m_cacheDataMutex.lock();
     try {
-      updateControlWord(false);
-      return m_controlWordCache.getAutonomous() && m_controlWordCache.getEnabled();
+      return m_controlWord.getAutonomous() && m_controlWord.getEnabled();
     } finally {
-      m_controlWordMutex.unlock();
+      m_cacheDataMutex.unlock();
     }
   }
 
@@ -826,18 +904,6 @@
    * operator-controlled mode.
    *
    * @return True if operator-controlled mode should be enabled, false otherwise.
-   * @deprecated Use isTeleop() instead.
-   */
-  @Deprecated(since = "2022", forRemoval = true)
-  public static boolean isOperatorControl() {
-    return isTeleop();
-  }
-
-  /**
-   * Gets a value indicating whether the Driver Station requires the robot to be running in
-   * operator-controlled mode.
-   *
-   * @return True if operator-controlled mode should be enabled, false otherwise.
    */
   public static boolean isTeleop() {
     return !(isAutonomous() || isTest());
@@ -848,28 +914,15 @@
    * operator-controller mode and enabled.
    *
    * @return True if operator-controlled mode should be set and the robot should be enabled.
-   * @deprecated Use isTeleopEnabled() instead.
-   */
-  @Deprecated(since = "2022", forRemoval = true)
-  public static boolean isOperatorControlEnabled() {
-    return isTeleopEnabled();
-  }
-
-  /**
-   * Gets a value indicating whether the Driver Station requires the robot to be running in
-   * operator-controller mode and enabled.
-   *
-   * @return True if operator-controlled mode should be set and the robot should be enabled.
    */
   public static boolean isTeleopEnabled() {
-    m_controlWordMutex.lock();
+    m_cacheDataMutex.lock();
     try {
-      updateControlWord(false);
-      return !m_controlWordCache.getAutonomous()
-          && !m_controlWordCache.getTest()
-          && m_controlWordCache.getEnabled();
+      return !m_controlWord.getAutonomous()
+          && !m_controlWord.getTest()
+          && m_controlWord.getEnabled();
     } finally {
-      m_controlWordMutex.unlock();
+      m_cacheDataMutex.unlock();
     }
   }
 
@@ -880,12 +933,11 @@
    * @return True if test mode should be enabled, false otherwise.
    */
   public static boolean isTest() {
-    m_controlWordMutex.lock();
+    m_cacheDataMutex.lock();
     try {
-      updateControlWord(false);
-      return m_controlWordCache.getTest();
+      return m_controlWord.getTest();
     } finally {
-      m_controlWordMutex.unlock();
+      m_cacheDataMutex.unlock();
     }
   }
 
@@ -895,47 +947,25 @@
    * @return True if Driver Station is attached, false otherwise.
    */
   public static boolean isDSAttached() {
-    m_controlWordMutex.lock();
+    m_cacheDataMutex.lock();
     try {
-      updateControlWord(false);
-      return m_controlWordCache.getDSAttached();
+      return m_controlWord.getDSAttached();
     } finally {
-      m_controlWordMutex.unlock();
+      m_cacheDataMutex.unlock();
     }
   }
 
   /**
-   * Gets if a new control packet from the driver station arrived since the last time this function
-   * was called.
-   *
-   * @return True if the control data has been updated since the last call.
-   */
-  public static boolean isNewControlData() {
-    m_waitForDataMutex.lock();
-    try {
-      int currentCount = m_waitForDataCount;
-      if (m_lastCount.get() != currentCount) {
-        m_lastCount.set(currentCount);
-        return true;
-      }
-    } finally {
-      m_waitForDataMutex.unlock();
-    }
-    return false;
-  }
-
-  /**
    * Gets if the driver station attached to a Field Management System.
    *
    * @return true if the robot is competing on a field being controlled by a Field Management System
    */
   public static boolean isFMSAttached() {
-    m_controlWordMutex.lock();
+    m_cacheDataMutex.lock();
     try {
-      updateControlWord(false);
-      return m_controlWordCache.getFMSAttached();
+      return m_controlWord.getFMSAttached();
     } finally {
-      m_controlWordMutex.unlock();
+      m_cacheDataMutex.unlock();
     }
   }
 
@@ -1026,7 +1056,7 @@
    * @return the current alliance
    */
   public static Alliance getAlliance() {
-    AllianceStationID allianceStationID = HAL.getAllianceStation();
+    AllianceStationID allianceStationID = DriverStationJNI.getAllianceStation();
     if (allianceStationID == null) {
       return Alliance.Invalid;
     }
@@ -1053,7 +1083,7 @@
    * @return the location of the team's driver station controls: 1, 2, or 3
    */
   public static int getLocation() {
-    AllianceStationID allianceStationID = HAL.getAllianceStation();
+    AllianceStationID allianceStationID = DriverStationJNI.getAllianceStation();
     if (allianceStationID == null) {
       return 0;
     }
@@ -1076,68 +1106,6 @@
   }
 
   /**
-   * Wait for new data from the driver station.
-   *
-   * <p>Checks if new control data has arrived since the last waitForData call on the current
-   * thread. If new data has not arrived, returns immediately.
-   */
-  public static void waitForData() {
-    waitForData(0);
-  }
-
-  /**
-   * Wait for new data or for timeout, which ever comes first. If timeout is 0, wait for new data
-   * only.
-   *
-   * <p>Checks if new control data has arrived since the last waitForData call on the current
-   * thread. If new data has not arrived, returns immediately.
-   *
-   * @param timeoutSeconds The maximum time in seconds to wait.
-   * @return true if there is new data, otherwise false
-   */
-  public static boolean waitForData(double timeoutSeconds) {
-    long startTimeMicroS = RobotController.getFPGATime();
-    long timeoutMicroS = (long) (timeoutSeconds * 1e6);
-    m_waitForDataMutex.lock();
-    try {
-      int currentCount = m_waitForDataCount;
-      if (m_lastCount.get() != currentCount) {
-        m_lastCount.set(currentCount);
-        return true;
-      }
-      while (m_waitForDataCount == currentCount) {
-        if (timeoutMicroS > 0) {
-          long nowMicroS = RobotController.getFPGATime();
-          if (nowMicroS < startTimeMicroS + timeoutMicroS) {
-            // We still have time to wait
-            boolean signaled =
-                m_waitForDataCond.await(
-                    startTimeMicroS + timeoutMicroS - nowMicroS, TimeUnit.MICROSECONDS);
-            if (!signaled) {
-              // Return false if a timeout happened
-              return false;
-            }
-          } else {
-            // Time has elapsed.
-            return false;
-          }
-        } else {
-          m_waitForDataCond.await();
-        }
-      }
-      m_lastCount.set(m_waitForDataCount);
-      // Return true if we have received a proper signal
-      return true;
-    } catch (InterruptedException ex) {
-      // return false on a thread interrupt
-      Thread.currentThread().interrupt();
-      return false;
-    } finally {
-      m_waitForDataMutex.unlock();
-    }
-  }
-
-  /**
    * Return the approximate match time. The FMS does not send an official match time to the robots,
    * but does send an approximate match time. The value will count down the time remaining in the
    * current period (auto or teleop). Warning: This is not an official time (so it cannot be used to
@@ -1147,70 +1115,7 @@
    * @return Time remaining in current match period (auto or teleop) in seconds
    */
   public static double getMatchTime() {
-    return HAL.getMatchTime();
-  }
-
-  /**
-   * Only to be used to tell the Driver Station what code you claim to be executing for diagnostic
-   * purposes only.
-   *
-   * @param entering If true, starting disabled code; if false, leaving disabled code
-   */
-  public static void inDisabled(boolean entering) {
-    m_userInDisabled = entering;
-  }
-
-  /**
-   * Only to be used to tell the Driver Station what code you claim to be executing for diagnostic
-   * purposes only.
-   *
-   * @param entering If true, starting autonomous code; if false, leaving autonomous code
-   */
-  public static void inAutonomous(boolean entering) {
-    m_userInAutonomous = entering;
-  }
-
-  /**
-   * Only to be used to tell the Driver Station what code you claim to be executing for diagnostic
-   * purposes only.
-   *
-   * @param entering If true, starting teleop code; if false, leaving teleop code
-   * @deprecated Use {@link #inTeleop(boolean)} instead.
-   */
-  @Deprecated(since = "2022", forRemoval = true)
-  public static void inOperatorControl(boolean entering) {
-    m_userInTeleop = entering;
-  }
-
-  /**
-   * Only to be used to tell the Driver Station what code you claim to be executing for diagnostic
-   * purposes only.
-   *
-   * @param entering If true, starting teleop code; if false, leaving teleop code
-   */
-  public static void inTeleop(boolean entering) {
-    m_userInTeleop = entering;
-  }
-
-  /**
-   * Only to be used to tell the Driver Station what code you claim to be executing for diagnostic
-   * purposes only.
-   *
-   * @param entering If true, starting test code; if false, leaving test code
-   */
-  public static void inTest(boolean entering) {
-    m_userInTest = entering;
-  }
-
-  /** Forces waitForData() to return immediately. */
-  public static void wakeupWaitForData() {
-    m_waitForDataMutex.lock();
-    try {
-      m_waitForDataCount++;
-      m_waitForDataCond.signalAll();
-    } finally {
-      m_waitForDataMutex.unlock();
-    }
+    return DriverStationJNI.getMatchTime();
   }
 
   /**
@@ -1235,30 +1140,44 @@
   }
 
   /**
+   * Refresh the passed in control word to contain the current control word cache.
+   *
+   * @param word Word to refresh.
+   */
+  public static void refreshControlWordFromCache(ControlWord word) {
+    m_cacheDataMutex.lock();
+    try {
+      word.update(m_controlWord);
+    } finally {
+      m_cacheDataMutex.unlock();
+    }
+  }
+
+  /**
    * Copy data from the DS task for the user. If no new data exists, it will just be returned,
    * otherwise the data will be copied from the DS polling loop.
    */
-  protected static void getData() {
-    // Get the status of all of the joysticks
+  public static void refreshData() {
+    DriverStationJNI.refreshDSData();
+
+    // Get the status of all the joysticks
     for (byte stick = 0; stick < kJoystickPorts; stick++) {
       m_joystickAxesCache[stick].m_count =
-          HAL.getJoystickAxes(stick, m_joystickAxesCache[stick].m_axes);
+          DriverStationJNI.getJoystickAxes(stick, m_joystickAxesCache[stick].m_axes);
+      m_joystickAxesRawCache[stick].m_count =
+          DriverStationJNI.getJoystickAxesRaw(stick, m_joystickAxesRawCache[stick].m_axes);
       m_joystickPOVsCache[stick].m_count =
-          HAL.getJoystickPOVs(stick, m_joystickPOVsCache[stick].m_povs);
-      m_joystickButtonsCache[stick].m_buttons = HAL.getJoystickButtons(stick, m_buttonCountBuffer);
+          DriverStationJNI.getJoystickPOVs(stick, m_joystickPOVsCache[stick].m_povs);
+      m_joystickButtonsCache[stick].m_buttons =
+          DriverStationJNI.getJoystickButtons(stick, m_buttonCountBuffer);
       m_joystickButtonsCache[stick].m_count = m_buttonCountBuffer.get(0);
     }
 
-    HAL.getMatchInfo(m_matchInfoCache);
+    DriverStationJNI.getMatchInfo(m_matchInfoCache);
 
-    m_controlWordMutex.lock();
-    try {
-      // Force a control word update, to make sure the data is the newest.
-      updateControlWord(true);
-    } finally {
-      m_controlWordMutex.unlock();
-    }
+    DriverStationJNI.getControlWord(m_controlWordCache);
 
+    DataLogSender dataLogSender;
     // lock joystick mutex to swap cache data
     m_cacheDataMutex.lock();
     try {
@@ -1277,6 +1196,10 @@
       m_joystickAxes = m_joystickAxesCache;
       m_joystickAxesCache = currentAxes;
 
+      HALJoystickAxesRaw[] currentAxesRaw = m_joystickAxesRaw;
+      m_joystickAxesRaw = m_joystickAxesRawCache;
+      m_joystickAxesRawCache = currentAxesRaw;
+
       HALJoystickButtons[] currentButtons = m_joystickButtons;
       m_joystickButtons = m_joystickButtonsCache;
       m_joystickButtonsCache = currentButtons;
@@ -1288,12 +1211,30 @@
       MatchInfoData currentInfo = m_matchInfo;
       m_matchInfo = m_matchInfoCache;
       m_matchInfoCache = currentInfo;
+
+      ControlWord currentWord = m_controlWord;
+      m_controlWord = m_controlWordCache;
+      m_controlWordCache = currentWord;
+
+      dataLogSender = m_dataLogSender;
     } finally {
       m_cacheDataMutex.unlock();
     }
 
-    wakeupWaitForData();
+    m_refreshEvents.wakeup();
+
     m_matchDataSender.sendMatchData();
+    if (dataLogSender != null) {
+      dataLogSender.send(WPIUtilJNI.now());
+    }
+  }
+
+  public static void provideRefreshedDataEventHandle(int handle) {
+    m_refreshEvents.add(handle);
+  }
+
+  public static void removeRefreshedDataEventHandle(int handle) {
+    m_refreshEvents.remove(handle);
   }
 
   /**
@@ -1322,65 +1263,31 @@
     }
   }
 
-  /** Provides the service routine for the DS polling m_thread. */
-  private static void run() {
-    int safetyCounter = 0;
-    while (m_threadKeepAlive) {
-      HAL.waitForDSData();
-      getData();
-
-      if (isDisabled()) {
-        safetyCounter = 0;
-      }
-
-      safetyCounter++;
-      if (safetyCounter >= 4) {
-        MotorSafety.checkMotors();
-        safetyCounter = 0;
-      }
-      if (m_userInDisabled) {
-        HAL.observeUserProgramDisabled();
-      }
-      if (m_userInAutonomous) {
-        HAL.observeUserProgramAutonomous();
-      }
-      if (m_userInTeleop) {
-        HAL.observeUserProgramTeleop();
-      }
-      if (m_userInTest) {
-        HAL.observeUserProgramTest();
-      }
-    }
-  }
-
   /**
-   * Forces a control word cache update, and update the passed in control word.
+   * Starts logging DriverStation data to data log. Repeated calls are ignored.
    *
-   * @param word Word to update.
+   * @param log data log
+   * @param logJoysticks if true, log joystick data
    */
-  public static void updateControlWordFromCache(ControlWord word) {
-    m_controlWordMutex.lock();
+  @SuppressWarnings("PMD.NonThreadSafeSingleton")
+  public static void startDataLog(DataLog log, boolean logJoysticks) {
+    m_cacheDataMutex.lock();
     try {
-      updateControlWord(true);
-      word.update(m_controlWordCache);
+      if (m_dataLogSender == null) {
+        m_dataLogSender = new DataLogSender(log, logJoysticks, WPIUtilJNI.now());
+      }
     } finally {
-      m_controlWordMutex.unlock();
+      m_cacheDataMutex.unlock();
     }
   }
 
   /**
-   * Updates the data in the control word cache. Updates if the force parameter is set, or if 50ms
-   * have passed since the last update.
+   * Starts logging DriverStation data to data log, including joystick data. Repeated calls are
+   * ignored.
    *
-   * <p>Must be called with m_controlWordMutex lock held.
-   *
-   * @param force True to force an update to the cache, otherwise update if 50ms have passed.
+   * @param log data log
    */
-  private static void updateControlWord(boolean force) {
-    long now = System.currentTimeMillis();
-    if (now - m_lastControlWordUpdate > 50 || force) {
-      HAL.getControlWord(m_controlWordCache);
-      m_lastControlWordUpdate = now;
-    }
+  public static void startDataLog(DataLog log) {
+    startDataLog(log, true);
   }
 }
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/DutyCycle.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/DutyCycle.java
index c700bca..d500ba7 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/DutyCycle.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/DutyCycle.java
@@ -73,21 +73,19 @@
   }
 
   /**
-   * Get the raw output ratio of the duty cycle signal.
+   * Get the raw high time of the duty cycle signal.
    *
-   * <p>0 means always low, an output equal to getOutputScaleFactor() means always high.
-   *
-   * @return output ratio in raw units
+   * @return high time of last pulse in nanoseconds
    */
-  public int getOutputRaw() {
-    return DutyCycleJNI.getOutputRaw(m_handle);
+  public int getHighTimeNanoseconds() {
+    return DutyCycleJNI.getHighTime(m_handle);
   }
 
   /**
    * Get the scale factor of the output.
    *
-   * <p>An output equal to this value is always high, and then linearly scales down to 0. Divide the
-   * result of getOutputRaw by this in order to get the percentage between 0 and 1.
+   * <p>An output equal to this value is always high, and then linearly scales down to 0. Divide a
+   * raw result by this in order to get the percentage between 0 and 1. Used by DMA.
    *
    * @return the output scale factor
    */
@@ -100,7 +98,6 @@
    *
    * @return the FPGA index
    */
-  @SuppressWarnings("AbbreviationAsWordInName")
   public final int getFPGAIndex() {
     return DutyCycleJNI.getFPGAIndex(m_handle);
   }
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/DutyCycleEncoder.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/DutyCycleEncoder.java
index c8d5bc9..dd78860 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/DutyCycleEncoder.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/DutyCycleEncoder.java
@@ -32,6 +32,7 @@
 
   protected SimDevice m_simDevice;
   protected SimDouble m_simPosition;
+  protected SimDouble m_simAbsolutePosition;
   protected SimDouble m_simDistancePerRotation;
   protected SimBoolean m_simIsConnected;
 
@@ -75,6 +76,8 @@
       m_simPosition = m_simDevice.createDouble("position", SimDevice.Direction.kInput, 0.0);
       m_simDistancePerRotation =
           m_simDevice.createDouble("distance_per_rot", SimDevice.Direction.kOutput, 1.0);
+      m_simAbsolutePosition =
+          m_simDevice.createDouble("absPosition", SimDevice.Direction.kInput, 0.0);
       m_simIsConnected = m_simDevice.createBoolean("connected", SimDevice.Direction.kInput, true);
     } else {
       m_counter = new Counter();
@@ -87,6 +90,23 @@
     SendableRegistry.addLW(this, "DutyCycle Encoder", m_dutyCycle.getSourceChannel());
   }
 
+  private double mapSensorRange(double pos) {
+    // map sensor range
+    if (pos < m_sensorMin) {
+      pos = m_sensorMin;
+    }
+    if (pos > m_sensorMax) {
+      pos = m_sensorMax;
+    }
+    pos = (pos - m_sensorMin) / (m_sensorMax - m_sensorMin);
+    return pos;
+  }
+
+  private boolean doubleEquals(double a, double b) {
+    double epsilon = 0.00001d;
+    return Math.abs(a - b) < epsilon;
+  }
+
   /**
    * Get the encoder value since the last reset.
    *
@@ -107,15 +127,9 @@
       double pos = m_dutyCycle.getOutput();
       double counter2 = m_counter.get();
       double pos2 = m_dutyCycle.getOutput();
-      if (counter == counter2 && pos == pos2) {
+      if (counter == counter2 && doubleEquals(pos, pos2)) {
         // map sensor range
-        if (pos < m_sensorMin) {
-          pos = m_sensorMin;
-        }
-        if (pos > m_sensorMax) {
-          pos = m_sensorMax;
-        }
-        pos = (pos - m_sensorMin) / (m_sensorMax - m_sensorMin);
+        pos = mapSensorRange(pos);
         double position = counter + pos - m_positionOffset;
         m_lastPosition = position;
         return position;
@@ -128,11 +142,28 @@
   }
 
   /**
+   * Get the absolute position of the duty cycle encoder.
+   *
+   * <p>getAbsolutePosition() - getPositionOffset() will give an encoder absolute position relative
+   * to the last reset. This could potentially be negative, which needs to be accounted for.
+   *
+   * <p>This will not account for rollovers, and will always be just the raw absolute position.
+   *
+   * @return the absolute position
+   */
+  public double getAbsolutePosition() {
+    if (m_simAbsolutePosition != null) {
+      return m_simAbsolutePosition.get();
+    }
+
+    return mapSensorRange(m_dutyCycle.getOutput());
+  }
+
+  /**
    * Get the offset of position relative to the last reset.
    *
-   * <p>getPositionInRotation() - getPositionOffset() will give an encoder absolute position
-   * relative to the last reset. This could potentially be negative, which needs to be accounted
-   * for.
+   * <p>getAbsolutePosition() - getPositionOffset() will give an encoder absolute position relative
+   * to the last reset. This could potentially be negative, which needs to be accounted for.
    *
    * @return the position offset
    */
@@ -141,6 +172,17 @@
   }
 
   /**
+   * Set the position offset.
+   *
+   * <p>This must be in the range of 0-1.
+   *
+   * @param offset the offset
+   */
+  public void setPositionOffset(double offset) {
+    m_positionOffset = MathUtil.clamp(offset, 0.0, 1.0);
+  }
+
+  /**
    * Set the encoder duty cycle range. As the encoder needs to maintain a duty cycle, the duty cycle
    * cannot go all the way to 0% or all the way to 100%. For example, an encoder with a 4096 us
    * period might have a minimum duty cycle of 1 us / 4096 us and a maximum duty cycle of 4095 /
@@ -158,9 +200,9 @@
 
   /**
    * Set the distance per rotation of the encoder. This sets the multiplier used to determine the
-   * distance driven based on the rotation value from the encoder. Set this value based on the how
-   * far the mechanism travels in 1 rotation of the encoder, and factor in gearing reductions
-   * following the encoder shaft. This distance can be in any units you like, linear or angular.
+   * distance driven based on the rotation value from the encoder. Set this value based on how far
+   * the mechanism travels in 1 rotation of the encoder, and factor in gearing reductions following
+   * the encoder shaft. This distance can be in any units you like, linear or angular.
    *
    * @param distancePerRotation the distance per rotation of the encoder
    */
@@ -257,7 +299,6 @@
    *
    * @return the FPGA index
    */
-  @SuppressWarnings("AbbreviationAsWordInName")
   public int getFPGAIndex() {
     return m_dutyCycle.getFPGAIndex();
   }
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Encoder.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Encoder.java
index 200d713..2476272 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Encoder.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Encoder.java
@@ -4,7 +4,7 @@
 
 package edu.wpi.first.wpilibj;
 
-import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
 
 import edu.wpi.first.hal.EncoderJNI;
 import edu.wpi.first.hal.FRCNetComm.tResourceType;
@@ -42,9 +42,9 @@
     }
   }
 
-  /** The a source. */
+  /** The 'a' source. */
   protected DigitalSource m_aSource; // the A phase of the quad encoder
-  /** The b source. */
+  /** The 'b' source. */
   protected DigitalSource m_bSource; // the B phase of the quad encoder
   /** The index source. */
   protected DigitalSource m_indexSource; // Index on some encoders
@@ -84,8 +84,8 @@
    *
    * <p>The encoder will start counting immediately.
    *
-   * @param channelA The a channel DIO channel. 0-9 are on-board, 10-25 are on the MXP port
-   * @param channelB The b channel DIO channel. 0-9 are on-board, 10-25 are on the MXP port
+   * @param channelA The 'a' channel DIO channel. 0-9 are on-board, 10-25 are on the MXP port
+   * @param channelB The 'b' channel DIO channel. 0-9 are on-board, 10-25 are on the MXP port
    * @param reverseDirection represents the orientation of the encoder and inverts the output values
    *     if necessary so forward represents positive values.
    */
@@ -94,7 +94,7 @@
   }
 
   /**
-   * Encoder constructor. Construct a Encoder given a and b channels.
+   * Encoder constructor. Construct an Encoder given a and b channels.
    *
    * <p>The encoder will start counting immediately.
    *
@@ -106,7 +106,7 @@
   }
 
   /**
-   * Encoder constructor. Construct a Encoder given a and b channels.
+   * Encoder constructor. Construct an Encoder given a and b channels.
    *
    * <p>The encoder will start counting immediately.
    *
@@ -117,7 +117,7 @@
    * @param encodingType either k1X, k2X, or k4X to indicate 1X, 2X or 4X decoding. If 4X is
    *     selected, then an encoder FPGA object is used and the returned counts will be 4x the
    *     encoder spec'd value since all rising and falling edges are counted. If 1X or 2X are
-   *     selected then a m_counter object will be used and the returned value will either exactly
+   *     selected, then a counter object will be used and the returned value will either exactly
    *     match the spec'd count or be double (2x) the spec'd count.
    */
   public Encoder(
@@ -139,8 +139,8 @@
   }
 
   /**
-   * Encoder constructor. Construct a Encoder given a and b channels. Using an index pulse forces 4x
-   * encoding
+   * Encoder constructor. Construct an Encoder given a and b channels. Using an index pulse forces
+   * 4x encoding
    *
    * <p>The encoder will start counting immediately.
    *
@@ -160,8 +160,8 @@
   }
 
   /**
-   * Encoder constructor. Construct a Encoder given a and b channels. Using an index pulse forces 4x
-   * encoding
+   * Encoder constructor. Construct an Encoder given a and b channels. Using an index pulse forces
+   * 4x encoding
    *
    * <p>The encoder will start counting immediately.
    *
@@ -174,14 +174,14 @@
   }
 
   /**
-   * Encoder constructor. Construct a Encoder given a and b channels as digital inputs. This is used
-   * in the case where the digital inputs are shared. The Encoder class will not allocate the
+   * Encoder constructor. Construct an Encoder given a and b channels as digital inputs. This is
+   * used in the case where the digital inputs are shared. The Encoder class will not allocate the
    * digital inputs and assume that they already are counted.
    *
    * <p>The encoder will start counting immediately.
    *
-   * @param sourceA The source that should be used for the a channel.
-   * @param sourceB the source that should be used for the b channel.
+   * @param sourceA The source that should be used for the 'a' channel.
+   * @param sourceB the source that should be used for the 'b' channel.
    * @param reverseDirection represents the orientation of the encoder and inverts the output values
    *     if necessary so forward represents positive values.
    */
@@ -190,34 +190,34 @@
   }
 
   /**
-   * Encoder constructor. Construct a Encoder given a and b channels as digital inputs. This is used
-   * in the case where the digital inputs are shared. The Encoder class will not allocate the
+   * Encoder constructor. Construct an Encoder given a and b channels as digital inputs. This is
+   * used in the case where the digital inputs are shared. The Encoder class will not allocate the
    * digital inputs and assume that they already are counted.
    *
    * <p>The encoder will start counting immediately.
    *
-   * @param sourceA The source that should be used for the a channel.
-   * @param sourceB the source that should be used for the b channel.
+   * @param sourceA The source that should be used for the 'a' channel.
+   * @param sourceB the source that should be used for the 'b' channel.
    */
   public Encoder(DigitalSource sourceA, DigitalSource sourceB) {
     this(sourceA, sourceB, false);
   }
 
   /**
-   * Encoder constructor. Construct a Encoder given a and b channels as digital inputs. This is used
-   * in the case where the digital inputs are shared. The Encoder class will not allocate the
+   * Encoder constructor. Construct an Encoder given a and b channels as digital inputs. This is
+   * used in the case where the digital inputs are shared. The Encoder class will not allocate the
    * digital inputs and assume that they already are counted.
    *
    * <p>The encoder will start counting immediately.
    *
-   * @param sourceA The source that should be used for the a channel.
-   * @param sourceB the source that should be used for the b channel.
+   * @param sourceA The source that should be used for the 'a' channel.
+   * @param sourceB the source that should be used for the 'b' channel.
    * @param reverseDirection represents the orientation of the encoder and inverts the output values
    *     if necessary so forward represents positive values.
    * @param encodingType either k1X, k2X, or k4X to indicate 1X, 2X or 4X decoding. If 4X is
    *     selected, then an encoder FPGA object is used and the returned counts will be 4x the
    *     encoder spec'd value since all rising and falling edges are counted. If 1X or 2X are
-   *     selected then a m_counter object will be used and the returned value will either exactly
+   *     selected then a counter object will be used and the returned value will either exactly
    *     match the spec'd count or be double (2x) the spec'd count.
    */
   public Encoder(
@@ -239,14 +239,14 @@
   }
 
   /**
-   * Encoder constructor. Construct a Encoder given a, b and index channels as digital inputs. This
+   * Encoder constructor. Construct an Encoder given a, b and index channels as digital inputs. This
    * is used in the case where the digital inputs are shared. The Encoder class will not allocate
    * the digital inputs and assume that they already are counted.
    *
    * <p>The encoder will start counting immediately.
    *
-   * @param sourceA The source that should be used for the a channel.
-   * @param sourceB the source that should be used for the b channel.
+   * @param sourceA The source that should be used for the 'a' channel.
+   * @param sourceB the source that should be used for the 'b' channel.
    * @param indexSource the source that should be used for the index channel.
    * @param reverseDirection represents the orientation of the encoder and inverts the output values
    *     if necessary so forward represents positive values.
@@ -263,14 +263,14 @@
   }
 
   /**
-   * Encoder constructor. Construct a Encoder given a, b and index channels as digital inputs. This
+   * Encoder constructor. Construct an Encoder given a, b and index channels as digital inputs. This
    * is used in the case where the digital inputs are shared. The Encoder class will not allocate
    * the digital inputs and assume that they already are counted.
    *
    * <p>The encoder will start counting immediately.
    *
-   * @param sourceA The source that should be used for the a channel.
-   * @param sourceB the source that should be used for the b channel.
+   * @param sourceA The source that should be used for the 'a' channel.
+   * @param sourceB the source that should be used for the 'b' channel.
    * @param indexSource the source that should be used for the index channel.
    */
   public Encoder(DigitalSource sourceA, DigitalSource sourceB, DigitalSource indexSource) {
@@ -282,7 +282,6 @@
    *
    * @return The Encoder's FPGA index.
    */
-  @SuppressWarnings("AbbreviationAsWordInName")
   public int getFPGAIndex() {
     return EncoderJNI.getEncoderFPGAIndex(m_encoder);
   }
@@ -370,8 +369,11 @@
    *
    * @param maxPeriod The maximum time between rising and falling edges before the FPGA will report
    *     the device stopped. This is expressed in seconds.
+   * @deprecated Use setMinRate() in favor of this method. This takes unscaled periods and
+   *     setMinRate() scales using value from setDistancePerPulse().
    */
   @Override
+  @Deprecated
   public void setMaxPeriod(double maxPeriod) {
     EncoderJNI.setEncoderMaxPeriod(m_encoder, maxPeriod);
   }
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Filesystem.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Filesystem.java
index 98230db..125c1e2 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Filesystem.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Filesystem.java
@@ -41,12 +41,11 @@
   }
 
   /**
-   * Obtains the deploy directory of the program, which is the remote location src/main/deploy is
-   * deployed to by default. On the roboRIO, this is /home/lvuser/deploy. In simulation, it is where
-   * the simulation was launched from, in the subdirectory "src/main/deploy"
-   * (`pwd`/src/main/deploy).
+   * Obtains the 'deploy' directory of the program, located at src/main/deploy, which is deployed by
+   * default. On the roboRIO, this is /home/lvuser/deploy. In simulation, it is where the simulation
+   * was launched from, in the subdirectory "src/main/deploy" (`pwd`/src/main/deploy).
    *
-   * @return The deploy directory
+   * @return The 'deploy' directory
    */
   public static File getDeployDirectory() {
     if (RobotBase.isReal()) {
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/GenericHID.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/GenericHID.java
index 4903e00..58e55f0 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/GenericHID.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/GenericHID.java
@@ -4,7 +4,10 @@
 
 package edu.wpi.first.wpilibj;
 
-import edu.wpi.first.hal.HAL;
+import edu.wpi.first.hal.DriverStationJNI;
+import edu.wpi.first.math.MathUtil;
+import edu.wpi.first.wpilibj.event.BooleanEvent;
+import edu.wpi.first.wpilibj.event.EventLoop;
 import java.util.HashMap;
 import java.util.Map;
 
@@ -19,7 +22,8 @@
   /** Represents a rumble output on the JoyStick. */
   public enum RumbleType {
     kLeftRumble,
-    kRightRumble
+    kRightRumble,
+    kBothRumble
   }
 
   public enum HIDType {
@@ -120,6 +124,17 @@
   }
 
   /**
+   * Constructs an event instance around this button's digital signal.
+   *
+   * @param button the button index
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the button's digital signal attached to the given loop.
+   */
+  public BooleanEvent button(int button, EventLoop loop) {
+    return new BooleanEvent(loop, () -> getRawButton(button));
+  }
+
+  /**
    * Get the value of the axis.
    *
    * @param axis The axis to read, starting at 0.
@@ -132,7 +147,7 @@
   /**
    * Get the angle in degrees of a POV on the HID.
    *
-   * <p>The POV angles start at 0 in the up direction, and increase clockwise (eg right is 90,
+   * <p>The POV angles start at 0 in the up direction, and increase clockwise (e.g. right is 90,
    * upper-left is 315).
    *
    * @param pov The index of the POV to read (starting at 0). Defaults to 0.
@@ -145,7 +160,7 @@
   /**
    * Get the angle in degrees of the default POV (index 0) on the HID.
    *
-   * <p>The POV angles start at 0 in the up direction, and increase clockwise (eg right is 90,
+   * <p>The POV angles start at 0 in the up direction, and increase clockwise (e.g. right is 90,
    * upper-left is 315).
    *
    * @return the angle of the POV in degrees, or -1 if the POV is not pressed.
@@ -155,6 +170,161 @@
   }
 
   /**
+   * Constructs a BooleanEvent instance based around this angle of a POV on the HID.
+   *
+   * <p>The POV angles start at 0 in the up direction, and increase clockwise (eg right is 90,
+   * upper-left is 315).
+   *
+   * @param angle POV angle in degrees, or -1 for the center / not pressed.
+   * @param loop the event loop instance to attach the event to.
+   * @return a BooleanEvent instance based around this angle of a POV on the HID.
+   */
+  public BooleanEvent pov(int angle, EventLoop loop) {
+    return pov(0, angle, loop);
+  }
+
+  /**
+   * Constructs a BooleanEvent instance based around this angle of a POV on the HID.
+   *
+   * <p>The POV angles start at 0 in the up direction, and increase clockwise (e.g. right is 90,
+   * upper-left is 315).
+   *
+   * @param pov index of the POV to read (starting at 0). Defaults to 0.
+   * @param angle POV angle in degrees, or -1 for the center / not pressed.
+   * @param loop the event loop instance to attach the event to.
+   * @return a BooleanEvent instance based around this angle of a POV on the HID.
+   */
+  public BooleanEvent pov(int pov, int angle, EventLoop loop) {
+    return new BooleanEvent(loop, () -> getPOV(pov) == angle);
+  }
+
+  /**
+   * Constructs a BooleanEvent instance based around the 0 degree angle (up) of the default (index
+   * 0) POV on the HID.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return a BooleanEvent instance based around the 0 degree angle of a POV on the HID.
+   */
+  public BooleanEvent povUp(EventLoop loop) {
+    return pov(0, loop);
+  }
+
+  /**
+   * Constructs a BooleanEvent instance based around the 45 degree angle (right up) of the default
+   * (index 0) POV on the HID.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return a BooleanEvent instance based around the 45 degree angle of a POV on the HID.
+   */
+  public BooleanEvent povUpRight(EventLoop loop) {
+    return pov(45, loop);
+  }
+
+  /**
+   * Constructs a BooleanEvent instance based around the 90 degree angle (right) of the default
+   * (index 0) POV on the HID.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return a BooleanEvent instance based around the 90 degree angle of a POV on the HID.
+   */
+  public BooleanEvent povRight(EventLoop loop) {
+    return pov(90, loop);
+  }
+
+  /**
+   * Constructs a BooleanEvent instance based around the 135 degree angle (right down) of the
+   * default (index 0) POV on the HID.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return a BooleanEvent instance based around the 135 degree angle of a POV on the HID.
+   */
+  public BooleanEvent povDownRight(EventLoop loop) {
+    return pov(135, loop);
+  }
+
+  /**
+   * Constructs a BooleanEvent instance based around the 180 degree angle (down) of the default
+   * (index 0) POV on the HID.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return a BooleanEvent instance based around the 180 degree angle of a POV on the HID.
+   */
+  public BooleanEvent povDown(EventLoop loop) {
+    return pov(180, loop);
+  }
+
+  /**
+   * Constructs a BooleanEvent instance based around the 225 degree angle (down left) of the default
+   * (index 0) POV on the HID.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return a BooleanEvent instance based around the 225 degree angle of a POV on the HID.
+   */
+  public BooleanEvent povDownLeft(EventLoop loop) {
+    return pov(225, loop);
+  }
+
+  /**
+   * Constructs a BooleanEvent instance based around the 270 degree angle (left) of the default
+   * (index 0) POV on the HID.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return a BooleanEvent instance based around the 270 degree angle of a POV on the HID.
+   */
+  public BooleanEvent povLeft(EventLoop loop) {
+    return pov(270, loop);
+  }
+
+  /**
+   * Constructs a BooleanEvent instance based around the 315 degree angle (left up) of the default
+   * (index 0) POV on the HID.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return a BooleanEvent instance based around the 315 degree angle of a POV on the HID.
+   */
+  public BooleanEvent povUpLeft(EventLoop loop) {
+    return pov(315, loop);
+  }
+
+  /**
+   * Constructs a BooleanEvent instance based around the center (not pressed) of the default (index
+   * 0) POV on the HID.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return a BooleanEvent instance based around the center of a POV on the HID.
+   */
+  public BooleanEvent povCenter(EventLoop loop) {
+    return pov(-1, loop);
+  }
+
+  /**
+   * Constructs an event instance that is true when the axis value is less than {@code threshold},
+   * attached to the given loop.
+   *
+   * @param axis The axis to read, starting at 0
+   * @param threshold The value below which this event should return true.
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance that is true when the axis value is less than the provided threshold.
+   */
+  public BooleanEvent axisLessThan(int axis, double threshold, EventLoop loop) {
+    return new BooleanEvent(loop, () -> getRawAxis(axis) < threshold);
+  }
+
+  /**
+   * Constructs an event instance that is true when the axis value is greater than {@code
+   * threshold}, attached to the given loop.
+   *
+   * @param axis The axis to read, starting at 0
+   * @param threshold The value above which this event should return true.
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance that is true when the axis value is greater than the provided
+   *     threshold.
+   */
+  public BooleanEvent axisGreaterThan(int axis, double threshold, EventLoop loop) {
+    return new BooleanEvent(loop, () -> getRawAxis(axis) > threshold);
+  }
+
+  /**
    * Get the number of axes for the HID.
    *
    * @return the number of axis for the current HID
@@ -209,10 +379,10 @@
   }
 
   /**
-   * Get the axis type of a joystick axis.
+   * Get the axis type of the provided joystick axis.
    *
    * @param axis The axis to read, starting at 0.
-   * @return the axis type of a joystick axis.
+   * @return the axis type of the given joystick axis
    */
   public int getAxisType(int axis) {
     return DriverStation.getJoystickAxisType(m_port, axis);
@@ -235,7 +405,7 @@
    */
   public void setOutput(int outputNumber, boolean value) {
     m_outputs = (m_outputs & ~(1 << (outputNumber - 1))) | ((value ? 1 : 0) << (outputNumber - 1));
-    HAL.setJoystickOutputs((byte) m_port, m_outputs, m_leftRumble, m_rightRumble);
+    DriverStationJNI.setJoystickOutputs((byte) m_port, m_outputs, m_leftRumble, m_rightRumble);
   }
 
   /**
@@ -245,7 +415,7 @@
    */
   public void setOutputs(int value) {
     m_outputs = value;
-    HAL.setJoystickOutputs((byte) m_port, m_outputs, m_leftRumble, m_rightRumble);
+    DriverStationJNI.setJoystickOutputs((byte) m_port, m_outputs, m_leftRumble, m_rightRumble);
   }
 
   /**
@@ -256,16 +426,24 @@
    * @param value The normalized value (0 to 1) to set the rumble to
    */
   public void setRumble(RumbleType type, double value) {
-    if (value < 0) {
-      value = 0;
-    } else if (value > 1) {
-      value = 1;
+    value = MathUtil.clamp(value, 0, 1);
+    short rumbleValue = (short) (value * 65535);
+
+    switch (type) {
+      case kLeftRumble:
+        this.m_leftRumble = rumbleValue;
+        break;
+      case kRightRumble:
+        this.m_rightRumble = rumbleValue;
+        break;
+      case kBothRumble:
+      default:
+        this.m_leftRumble = rumbleValue;
+        this.m_rightRumble = rumbleValue;
+        break;
     }
-    if (type == RumbleType.kLeftRumble) {
-      m_leftRumble = (short) (value * 65535);
-    } else {
-      m_rightRumble = (short) (value * 65535);
-    }
-    HAL.setJoystickOutputs((byte) m_port, m_outputs, m_leftRumble, m_rightRumble);
+
+    DriverStationJNI.setJoystickOutputs(
+        (byte) this.m_port, this.m_outputs, this.m_leftRumble, this.m_rightRumble);
   }
 }
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/I2C.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/I2C.java
index 03a00cc..1c37ecf 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/I2C.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/I2C.java
@@ -4,7 +4,7 @@
 
 package edu.wpi.first.wpilibj;
 
-import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
 
 import edu.wpi.first.hal.FRCNetComm.tResourceType;
 import edu.wpi.first.hal.HAL;
@@ -17,6 +17,10 @@
  *
  * <p>This class is intended to be used by sensor (and other I2C device) drivers. It probably should
  * not be used directly.
+ *
+ * <p>The Onboard I2C port is subject to system lockups. See <a
+ * href="https://docs.wpilib.org/en/stable/docs/yearly-overview/known-issues.html#onboard-i2c-causing-system-lockups">
+ * WPILib Known Issues</a> page for details.
  */
 public class I2C implements AutoCloseable {
   public enum Port {
@@ -112,7 +116,6 @@
    * @param receiveSize Number of bytes to read from the device.
    * @return Transfer Aborted... false for success, true for aborted.
    */
-  @SuppressWarnings("ByteBufferBackingArray")
   public synchronized boolean transaction(
       ByteBuffer dataToSend, int sendSize, ByteBuffer dataReceived, int receiveSize) {
     if (dataToSend.hasArray() && dataReceived.hasArray()) {
@@ -207,7 +210,6 @@
    * @param size The number of data bytes to write.
    * @return Transfer Aborted... false for success, true for aborted.
    */
-  @SuppressWarnings("ByteBufferBackingArray")
   public synchronized boolean writeBulk(ByteBuffer data, int size) {
     if (data.hasArray()) {
       return writeBulk(data.array(), size);
@@ -262,7 +264,6 @@
    * @param buffer A buffer to store the data read from the device.
    * @return Transfer Aborted... false for success, true for aborted.
    */
-  @SuppressWarnings("ByteBufferBackingArray")
   public boolean read(int registerAddress, int count, ByteBuffer buffer) {
     if (count < 1) {
       throw new BoundaryException("Value must be at least 1, " + count + " given");
@@ -319,7 +320,6 @@
    * @param count The number of bytes to read in the transaction.
    * @return Transfer Aborted... false for success, true for aborted.
    */
-  @SuppressWarnings("ByteBufferBackingArray")
   public boolean readOnly(ByteBuffer buffer, int count) {
     if (count < 1) {
       throw new BoundaryException("Value must be at least 1, " + count + " given");
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/IterativeRobotBase.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/IterativeRobotBase.java
index a8c92a6..e0fe034 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/IterativeRobotBase.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/IterativeRobotBase.java
@@ -4,11 +4,13 @@
 
 package edu.wpi.first.wpilibj;
 
+import edu.wpi.first.hal.DriverStationJNI;
 import edu.wpi.first.hal.HAL;
 import edu.wpi.first.networktables.NetworkTableInstance;
 import edu.wpi.first.wpilibj.livewindow.LiveWindow;
 import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
 import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
+import java.util.ConcurrentModificationException;
 
 /**
  * IterativeRobotBase implements a specific type of robot program framework, extending the RobotBase
@@ -42,7 +44,7 @@
  *   <li>testPeriodic()
  * </ul>
  *
- * <p>final() functions -- each of the following functions is called once when the appropriate mode
+ * <p>exit() functions -- each of the following functions is called once when the appropriate mode
  * is exited:
  *
  * <ul>
@@ -65,7 +67,8 @@
   private Mode m_lastMode = Mode.kNone;
   private final double m_period;
   private final Watchdog m_watchdog;
-  private boolean m_ntFlushEnabled;
+  private boolean m_ntFlushEnabled = true;
+  private boolean m_lwEnabledInTest = true;
 
   /**
    * Constructor for IterativeRobotBase.
@@ -134,7 +137,6 @@
    * <p>Users should override this method for initialization code which will be called each time the
    * robot enters test mode.
    */
-  @SuppressWarnings("PMD.JUnit4TestShouldUseTestAnnotation")
   public void testInit() {}
 
   /* ----------- Overridable periodic code ----------------- */
@@ -196,7 +198,6 @@
   private boolean m_tmpFirstRun = true;
 
   /** Periodic code for test mode should go here. */
-  @SuppressWarnings("PMD.JUnit4TestShouldUseTestAnnotation")
   public void testPeriodic() {
     if (m_tmpFirstRun) {
       System.out.println("Default testPeriodic() method... Override me!");
@@ -234,11 +235,10 @@
    * <p>Users should override this method for code which will be called each time the robot exits
    * test mode.
    */
-  @SuppressWarnings("PMD.JUnit4TestShouldUseTestAnnotation")
   public void testExit() {}
 
   /**
-   * Enables or disables flushing NetworkTables every loop iteration. By default, this is disabled.
+   * Enables or disables flushing NetworkTables every loop iteration. By default, this is enabled.
    *
    * @param enabled True to enable, false to disable
    */
@@ -247,6 +247,28 @@
   }
 
   /**
+   * Sets whether LiveWindow operation is enabled during test mode. Calling
+   *
+   * @param testLW True to enable, false to disable. Defaults to true.
+   * @throws ConcurrentModificationException if this is called during test mode.
+   */
+  public void enableLiveWindowInTest(boolean testLW) {
+    if (isTest()) {
+      throw new ConcurrentModificationException("Can't configure test mode while in test mode!");
+    }
+    m_lwEnabledInTest = testLW;
+  }
+
+  /**
+   * Whether LiveWindow operation is enabled during test mode.
+   *
+   * @return whether LiveWindow should be enabled in test mode.
+   */
+  public boolean isLiveWindowEnabledInTest() {
+    return m_lwEnabledInTest;
+  }
+
+  /**
    * Gets time period between calls to Periodic() functions.
    *
    * @return The time period between calls to Periodic() functions.
@@ -256,10 +278,12 @@
   }
 
   protected void loopFunc() {
+    DriverStation.refreshData();
     m_watchdog.reset();
 
+    m_word.refresh();
+
     // Get current mode
-    m_word.update();
     Mode mode = Mode.kNone;
     if (m_word.isDisabled()) {
       mode = Mode.kDisabled;
@@ -281,8 +305,10 @@
       } else if (m_lastMode == Mode.kTeleop) {
         teleopExit();
       } else if (m_lastMode == Mode.kTest) {
-        LiveWindow.setEnabled(false);
-        Shuffleboard.disableActuatorWidgets();
+        if (m_lwEnabledInTest) {
+          LiveWindow.setEnabled(false);
+          Shuffleboard.disableActuatorWidgets();
+        }
         testExit();
       }
 
@@ -297,8 +323,10 @@
         teleopInit();
         m_watchdog.addEpoch("teleopInit()");
       } else if (mode == Mode.kTest) {
-        LiveWindow.setEnabled(true);
-        Shuffleboard.enableActuatorWidgets();
+        if (m_lwEnabledInTest) {
+          LiveWindow.setEnabled(true);
+          Shuffleboard.enableActuatorWidgets();
+        }
         testInit();
         m_watchdog.addEpoch("testInit()");
       }
@@ -308,19 +336,19 @@
 
     // Call the appropriate function depending upon the current robot mode
     if (mode == Mode.kDisabled) {
-      HAL.observeUserProgramDisabled();
+      DriverStationJNI.observeUserProgramDisabled();
       disabledPeriodic();
       m_watchdog.addEpoch("disabledPeriodic()");
     } else if (mode == Mode.kAutonomous) {
-      HAL.observeUserProgramAutonomous();
+      DriverStationJNI.observeUserProgramAutonomous();
       autonomousPeriodic();
       m_watchdog.addEpoch("autonomousPeriodic()");
     } else if (mode == Mode.kTeleop) {
-      HAL.observeUserProgramTeleop();
+      DriverStationJNI.observeUserProgramTeleop();
       teleopPeriodic();
       m_watchdog.addEpoch("teleopPeriodic()");
     } else {
-      HAL.observeUserProgramTest();
+      DriverStationJNI.observeUserProgramTest();
       testPeriodic();
       m_watchdog.addEpoch("testPeriodic()");
     }
@@ -346,7 +374,7 @@
 
     // Flush NetworkTables
     if (m_ntFlushEnabled) {
-      NetworkTableInstance.getDefault().flush();
+      NetworkTableInstance.getDefault().flushLocal();
     }
 
     // Warn on loop time overruns
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Joystick.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Joystick.java
index e9b09a9..d73b7bb 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Joystick.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Joystick.java
@@ -6,6 +6,8 @@
 
 import edu.wpi.first.hal.FRCNetComm.tResourceType;
 import edu.wpi.first.hal.HAL;
+import edu.wpi.first.wpilibj.event.BooleanEvent;
+import edu.wpi.first.wpilibj.event.EventLoop;
 
 /**
  * Handle input from Flight Joysticks connected to the Driver Station.
@@ -234,6 +236,17 @@
   }
 
   /**
+   * Constructs an event instance around the trigger button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the trigger button's digital signal attached to the
+   *     given loop.
+   */
+  public BooleanEvent trigger(EventLoop loop) {
+    return new BooleanEvent(loop, this::getTrigger);
+  }
+
+  /**
    * Read the state of the top button on the joystick.
    *
    * @return The state of the top button.
@@ -261,13 +274,24 @@
   }
 
   /**
+   * Constructs an event instance around the top button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the top button's digital signal attached to the given
+   *     loop.
+   */
+  public BooleanEvent top(EventLoop loop) {
+    return new BooleanEvent(loop, this::getTop);
+  }
+
+  /**
    * Get the magnitude of the direction vector formed by the joystick's current position relative to
    * its origin.
    *
    * @return The magnitude of the direction vector
    */
   public double getMagnitude() {
-    return Math.sqrt(Math.pow(getX(), 2) + Math.pow(getY(), 2));
+    return Math.hypot(getX(), getY());
   }
 
   /**
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/MotorSafety.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/MotorSafety.java
index 4e76936..c1bf04b 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/MotorSafety.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/MotorSafety.java
@@ -4,12 +4,17 @@
 
 package edu.wpi.first.wpilibj;
 
+import edu.wpi.first.hal.ControlWord;
+import edu.wpi.first.hal.DriverStationJNI;
+import edu.wpi.first.util.WPIUtilJNI;
 import java.util.LinkedHashSet;
 import java.util.Set;
 
 /**
- * This base class runs a watchdog timer and calls the subclass's StopMotor() function if the
- * timeout expires.
+ * The Motor Safety feature acts as a watchdog timer for an individual motor. It operates by
+ * maintaining a timer that tracks how long it has been since the feed() method has been called for
+ * that actuator. Code in the Driver Station class initiates a comparison of these timers to the
+ * timeout values for any actuator with safety enabled every 5 received packets (100ms nominal).
  *
  * <p>The subclass should call feed() whenever the motor value is updated.
  */
@@ -22,11 +27,49 @@
   private final Object m_thisMutex = new Object();
   private static final Set<MotorSafety> m_instanceList = new LinkedHashSet<>();
   private static final Object m_listMutex = new Object();
+  private static Thread m_safetyThread;
+
+  @SuppressWarnings("PMD.AssignmentInOperand")
+  private static void threadMain() {
+    int event = WPIUtilJNI.createEvent(false, false);
+    DriverStationJNI.provideNewDataEventHandle(event);
+    ControlWord controlWord = new ControlWord();
+
+    int safetyCounter = 0;
+    while (true) {
+      boolean timedOut;
+      try {
+        timedOut = WPIUtilJNI.waitForObjectTimeout(event, 0.1);
+      } catch (InterruptedException e) {
+        DriverStationJNI.removeNewDataEventHandle(event);
+        WPIUtilJNI.destroyEvent(event);
+        Thread.currentThread().interrupt();
+        return;
+      }
+      if (!timedOut) {
+        DriverStationJNI.getControlWord(controlWord);
+        if (!(controlWord.getEnabled() && controlWord.getDSAttached())) {
+          safetyCounter = 0;
+        }
+        if (++safetyCounter >= 4) {
+          checkMotors();
+          safetyCounter = 0;
+        }
+      } else {
+        safetyCounter = 0;
+      }
+    }
+  }
 
   /** MotorSafety constructor. */
   public MotorSafety() {
     synchronized (m_listMutex) {
       m_instanceList.add(this);
+      if (m_safetyThread == null) {
+        m_safetyThread = new Thread(() -> threadMain(), "MotorSafety Thread");
+        m_safetyThread.setDaemon(true);
+        m_safetyThread.start();
+      }
     }
   }
 
@@ -93,7 +136,10 @@
     }
 
     if (stopTime < Timer.getFPGATimestamp()) {
-      DriverStation.reportError(getDescription() + "... Output not updated often enough.", false);
+      DriverStation.reportError(
+          getDescription()
+              + "... Output not updated often enough. See https://docs.wpilib.org/motorsafety for more information.",
+          false);
 
       stopMotor();
     }
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Notifier.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Notifier.java
index 9355b4d..25657b3 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Notifier.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Notifier.java
@@ -4,12 +4,18 @@
 
 package edu.wpi.first.wpilibj;
 
-import static java.util.Objects.requireNonNull;
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
 
 import edu.wpi.first.hal.NotifierJNI;
 import java.util.concurrent.atomic.AtomicInteger;
 import java.util.concurrent.locks.ReentrantLock;
 
+/**
+ * Notifiers run a callback function on a separate thread at a specified period.
+ *
+ * <p>If startSingle() is used, the callback will run once. If startPeriodic() is used, the callback
+ * will run repeatedly with the given period until stop() is called.
+ */
 public class Notifier implements AutoCloseable {
   // The thread waiting on the HAL alarm.
   private Thread m_thread;
@@ -31,12 +37,6 @@
   private double m_periodSeconds;
 
   @Override
-  @SuppressWarnings("NoFinalizer")
-  protected void finalize() {
-    close();
-  }
-
-  @Override
   public void close() {
     int handle = m_notifier.getAndSet(0);
     if (handle == 0) {
@@ -81,7 +81,7 @@
    *     or StartPeriodic.
    */
   public Notifier(Runnable run) {
-    requireNonNull(run);
+    requireNonNullParam(run, "run", "Notifier");
 
     m_handler = run;
     m_notifier.set(NotifierJNI.initializeNotifier());
@@ -128,10 +128,12 @@
             error = cause;
           }
           DriverStation.reportError(
-              "Unhandled exception: " + error.toString(), error.getStackTrace());
+              "Unhandled exception in Notifier thread: " + error.toString(), error.getStackTrace());
           DriverStation.reportError(
-              "The loopFunc() method (or methods called by it) should have handled "
-                  + "the exception above.",
+              "The Runnable for this Notifier (or methods called by it) should have handled "
+                  + "the exception above.\n"
+                  + "  The above stacktrace can help determine where the error occurred.\n"
+                  + "  See https://wpilib.org/stacktrace for more information.",
               false);
         });
     m_thread.start();
@@ -184,6 +186,9 @@
    * notification. Each time the interrupt occurs, the event will be immediately requeued for the
    * same time interval.
    *
+   * <p>The user-provided callback should be written in a nonblocking manner so the callback can be
+   * recalled at the next periodic event notification.
+   *
    * @param periodSeconds Period in seconds to call the handler starting one period after the call
    *     to this method.
    */
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/PS4Controller.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/PS4Controller.java
index e3eb052..c418e54 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/PS4Controller.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/PS4Controller.java
@@ -6,6 +6,8 @@
 
 import edu.wpi.first.hal.FRCNetComm.tResourceType;
 import edu.wpi.first.hal.HAL;
+import edu.wpi.first.wpilibj.event.BooleanEvent;
+import edu.wpi.first.wpilibj.event.EventLoop;
 
 /**
  * Handle input from PS4 controllers connected to the Driver Station.
@@ -210,6 +212,30 @@
   }
 
   /**
+   * Constructs an event instance around the L2 button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the L2 button's digital signal attached to the given
+   *     loop.
+   */
+  @SuppressWarnings("MethodName")
+  public BooleanEvent L2(EventLoop loop) {
+    return new BooleanEvent(loop, this::getL2Button);
+  }
+
+  /**
+   * Constructs an event instance around the R2 button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the R2 button's digital signal attached to the given
+   *     loop.
+   */
+  @SuppressWarnings("MethodName")
+  public BooleanEvent R2(EventLoop loop) {
+    return new BooleanEvent(loop, this::getR2Button);
+  }
+
+  /**
    * Read the value of the L1 button on the controller.
    *
    * @return The state of the button.
@@ -264,6 +290,30 @@
   }
 
   /**
+   * Constructs an event instance around the L1 button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the L1 button's digital signal attached to the given
+   *     loop.
+   */
+  @SuppressWarnings("MethodName")
+  public BooleanEvent L1(EventLoop loop) {
+    return new BooleanEvent(loop, this::getL1Button);
+  }
+
+  /**
+   * Constructs an event instance around the R1 button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the R1 button's digital signal attached to the given
+   *     loop.
+   */
+  @SuppressWarnings("MethodName")
+  public BooleanEvent R1(EventLoop loop) {
+    return new BooleanEvent(loop, this::getR1Button);
+  }
+
+  /**
    * Read the value of the L3 button (pressing the left analog stick) on the controller.
    *
    * @return The state of the button.
@@ -318,6 +368,30 @@
   }
 
   /**
+   * Constructs an event instance around the L3 button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the L3 button's digital signal attached to the given
+   *     loop.
+   */
+  @SuppressWarnings("MethodName")
+  public BooleanEvent L3(EventLoop loop) {
+    return new BooleanEvent(loop, this::getL3Button);
+  }
+
+  /**
+   * Constructs an event instance around the R3 button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the R3 button's digital signal attached to the given
+   *     loop.
+   */
+  @SuppressWarnings("MethodName")
+  public BooleanEvent R3(EventLoop loop) {
+    return new BooleanEvent(loop, this::getR3Button);
+  }
+
+  /**
    * Read the value of the Square button on the controller.
    *
    * @return The state of the button.
@@ -345,6 +419,17 @@
   }
 
   /**
+   * Constructs an event instance around the square button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the square button's digital signal attached to the given
+   *     loop.
+   */
+  public BooleanEvent square(EventLoop loop) {
+    return new BooleanEvent(loop, this::getSquareButton);
+  }
+
+  /**
    * Read the value of the Cross button on the controller.
    *
    * @return The state of the button.
@@ -372,6 +457,17 @@
   }
 
   /**
+   * Constructs an event instance around the cross button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the cross button's digital signal attached to the given
+   *     loop.
+   */
+  public BooleanEvent cross(EventLoop loop) {
+    return new BooleanEvent(loop, this::getCrossButton);
+  }
+
+  /**
    * Read the value of the Triangle button on the controller.
    *
    * @return The state of the button.
@@ -399,6 +495,17 @@
   }
 
   /**
+   * Constructs an event instance around the triangle button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the triangle button's digital signal attached to the
+   *     given loop.
+   */
+  public BooleanEvent triangle(EventLoop loop) {
+    return new BooleanEvent(loop, this::getTriangleButton);
+  }
+
+  /**
    * Read the value of the Circle button on the controller.
    *
    * @return The state of the button.
@@ -426,6 +533,17 @@
   }
 
   /**
+   * Constructs an event instance around the circle button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the circle button's digital signal attached to the given
+   *     loop.
+   */
+  public BooleanEvent circle(EventLoop loop) {
+    return new BooleanEvent(loop, this::getCircleButton);
+  }
+
+  /**
    * Read the value of the share button on the controller.
    *
    * @return The state of the button.
@@ -453,6 +571,18 @@
   }
 
   /**
+   * Constructs an event instance around the share button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the share button's digital signal attached to the given
+   *     loop.
+   */
+  @SuppressWarnings("MethodName")
+  public BooleanEvent share(EventLoop loop) {
+    return new BooleanEvent(loop, this::getShareButton);
+  }
+
+  /**
    * Read the value of the PS button on the controller.
    *
    * @return The state of the button.
@@ -480,6 +610,18 @@
   }
 
   /**
+   * Constructs an event instance around the PS button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the PS button's digital signal attached to the given
+   *     loop.
+   */
+  @SuppressWarnings("MethodName")
+  public BooleanEvent PS(EventLoop loop) {
+    return new BooleanEvent(loop, this::getPSButton);
+  }
+
+  /**
    * Read the value of the options button on the controller.
    *
    * @return The state of the button.
@@ -507,6 +649,17 @@
   }
 
   /**
+   * Constructs an event instance around the options button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the options button's digital signal attached to the
+   *     given loop.
+   */
+  public BooleanEvent options(EventLoop loop) {
+    return new BooleanEvent(loop, this::getOptionsButton);
+  }
+
+  /**
    * Read the value of the touchpad on the controller.
    *
    * @return The state of the touchpad.
@@ -532,4 +685,15 @@
   public boolean getTouchpadReleased() {
     return getRawButtonReleased(Button.kTouchpad.value);
   }
+
+  /**
+   * Constructs an event instance around the touchpad's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the touchpad's digital signal attached to the given
+   *     loop.
+   */
+  public BooleanEvent touchpad(EventLoop loop) {
+    return new BooleanEvent(loop, this::getTouchpad);
+  }
 }
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWM.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWM.java
index 9d86ab8..e1f0a96 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWM.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWM.java
@@ -213,7 +213,7 @@
     return PWMJNI.getPWMRaw(m_handle);
   }
 
-  /** Temporarily disables the PWM output. The next set call will reenable the output. */
+  /** Temporarily disables the PWM output. The next set call will re-enable the output. */
   public void setDisabled() {
     PWMJNI.setPWMDisabled(m_handle);
   }
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/PneumaticHub.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/PneumaticHub.java
index 7b077a8..ff49b4a 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/PneumaticHub.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/PneumaticHub.java
@@ -128,7 +128,7 @@
   private final DataStore m_dataStore;
   private final int m_handle;
 
-  /** Constructs a PneumaticHub with the default id (1). */
+  /** Constructs a PneumaticHub with the default ID (1). */
   public PneumaticHub() {
     this(SensorUtil.getDefaultREVPHModule());
   }
@@ -256,6 +256,11 @@
     return raw & 0xFFFF;
   }
 
+  /**
+   * Disables the compressor. The compressor will not turn on until {@link
+   * #enableCompressorDigital()}, {@link #enableCompressorAnalog(double, double)}, or {@link
+   * #enableCompressorHybrid(double, double)} are called.
+   */
   @Override
   public void disableCompressor() {
     REVPHJNI.setClosedLoopControlDisabled(m_handle);
@@ -266,6 +271,16 @@
     REVPHJNI.setClosedLoopControlDigital(m_handle);
   }
 
+  /**
+   * Enables the compressor in analog mode. This mode uses an analog pressure sensor connected to
+   * analog channel 0 to cycle the compressor. The compressor will turn on when the pressure drops
+   * below {@code minPressure} and will turn off when the pressure reaches {@code maxPressure}.
+   *
+   * @param minPressure The minimum pressure in PSI. The compressor will turn on when the pressure
+   *     drops below this value.
+   * @param maxPressure The maximum pressure in PSI. The compressor will turn off when the pressure
+   *     reaches this value.
+   */
   @Override
   public void enableCompressorAnalog(double minPressure, double maxPressure) {
     if (minPressure >= maxPressure) {
@@ -284,6 +299,32 @@
     REVPHJNI.setClosedLoopControlAnalog(m_handle, minAnalogVoltage, maxAnalogVoltage);
   }
 
+  /**
+   * Enables the compressor in hybrid mode. This mode uses both a digital pressure switch and an
+   * analog pressure sensor connected to analog channel 0 to cycle the compressor.
+   *
+   * <p>The compressor will turn on when <i>both</i>:
+   *
+   * <ul>
+   *   <li>The digital pressure switch indicates the system is not full AND
+   *   <li>The analog pressure sensor indicates that the pressure in the system is below the
+   *       specified minimum pressure.
+   * </ul>
+   *
+   * <p>The compressor will turn off when <i>either</i>:
+   *
+   * <ul>
+   *   <li>The digital pressure switch is disconnected or indicates that the system is full OR
+   *   <li>The pressure detected by the analog sensor is greater than the specified maximum
+   *       pressure.
+   * </ul>
+   *
+   * @param minPressure The minimum pressure in PSI. The compressor will turn on when the pressure
+   *     drops below this value and the pressure switch indicates that the system is not full.
+   * @param maxPressure The maximum pressure in PSI. The compressor will turn off when the pressure
+   *     reaches this value or the pressure switch is disconnected or indicates that the system is
+   *     full.
+   */
   @Override
   public void enableCompressorHybrid(double minPressure, double maxPressure) {
     if (minPressure >= maxPressure) {
@@ -302,11 +343,23 @@
     REVPHJNI.setClosedLoopControlHybrid(m_handle, minAnalogVoltage, maxAnalogVoltage);
   }
 
+  /**
+   * Returns the raw voltage of the specified analog input channel.
+   *
+   * @param channel The analog input channel to read voltage from.
+   * @return The voltage of the specified analog input channel.
+   */
   @Override
   public double getAnalogVoltage(int channel) {
     return REVPHJNI.getAnalogVoltage(m_handle, channel);
   }
 
+  /**
+   * Returns the pressure read by an analog pressure sensor on the specified analog input channel.
+   *
+   * @param channel The analog input channel to read pressure from.
+   * @return The pressure read by an analog pressure sensor on the specified analog input channel.
+   */
   @Override
   public double getPressure(int channel) {
     double sensorVoltage = REVPHJNI.getAnalogVoltage(m_handle, channel);
@@ -314,34 +367,70 @@
     return voltsToPsi(sensorVoltage, supplyVoltage);
   }
 
+  /** Clears the sticky faults. */
   public void clearStickyFaults() {
     REVPHJNI.clearStickyFaults(m_handle);
   }
 
+  /**
+   * Returns the hardware and firmware versions of this device.
+   *
+   * @return The hardware and firmware versions.
+   */
   public REVPHVersion getVersion() {
     return REVPHJNI.getVersion(m_handle);
   }
 
+  /**
+   * Returns the faults currently active on this device.
+   *
+   * @return The faults.
+   */
   public REVPHFaults getFaults() {
     return REVPHJNI.getFaults(m_handle);
   }
 
+  /**
+   * Returns the sticky faults currently active on this device.
+   *
+   * @return The sticky faults.
+   */
   public REVPHStickyFaults getStickyFaults() {
     return REVPHJNI.getStickyFaults(m_handle);
   }
 
+  /**
+   * Returns the current input voltage for this device.
+   *
+   * @return The input voltage.
+   */
   public double getInputVoltage() {
     return REVPHJNI.getInputVoltage(m_handle);
   }
 
+  /**
+   * Returns the current voltage of the regulated 5v supply.
+   *
+   * @return The current voltage of the 5v supply.
+   */
   public double get5VRegulatedVoltage() {
     return REVPHJNI.get5VVoltage(m_handle);
   }
 
+  /**
+   * Returns the total current (in amps) drawn by all solenoids.
+   *
+   * @return Total current drawn by all solenoids in amps.
+   */
   public double getSolenoidsTotalCurrent() {
     return REVPHJNI.getSolenoidCurrent(m_handle);
   }
 
+  /**
+   * Returns the current voltage of the solenoid power supply.
+   *
+   * @return The current voltage of the solenoid power supply.
+   */
   public double getSolenoidsVoltage() {
     return REVPHJNI.getSolenoidVoltage(m_handle);
   }
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/PneumaticsBase.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/PneumaticsBase.java
index 1261eac..57dbfc6 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/PneumaticsBase.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/PneumaticsBase.java
@@ -45,7 +45,7 @@
   void setSolenoids(int mask, int values);
 
   /**
-   * Gets solenoid values.
+   * Gets a bitmask of solenoid values.
    *
    * @return values
    */
@@ -59,9 +59,9 @@
   int getModuleNumber();
 
   /**
-   * Get the disabled solenoids.
+   * Get a bitmask of disabled solenoids.
    *
-   * @return disabled list
+   * @return bitmask of disabled solenoids
    */
   int getSolenoidDisabledList();
 
@@ -80,24 +80,112 @@
    */
   void setOneShotDuration(int index, int durMs);
 
+  /**
+   * Returns whether the compressor is active or not.
+   *
+   * @return True if the compressor is on - otherwise false.
+   */
   boolean getCompressor();
 
+  /**
+   * Returns the state of the pressure switch.
+   *
+   * @return True if pressure switch indicates that the system is not full, otherwise false.
+   */
   boolean getPressureSwitch();
 
+  /**
+   * Returns the current drawn by the compressor in amps.
+   *
+   * @return The current drawn by the compressor.
+   */
   double getCompressorCurrent();
 
+  /** Disables the compressor. */
   void disableCompressor();
 
+  /**
+   * Enables the compressor in digital mode using the digital pressure switch. The compressor will
+   * turn on when the pressure switch indicates that the system is not full, and will turn off when
+   * the pressure switch indicates that the system is full.
+   */
   void enableCompressorDigital();
 
+  /**
+   * If supported by the device, enables the compressor in analog mode. This mode uses an analog
+   * pressure sensor connected to analog channel 0 to cycle the compressor. The compressor will turn
+   * on when the pressure drops below {@code minPressure} and will turn off when the pressure
+   * reaches {@code maxPressure}. This mode is only supported by the REV PH with the REV Analog
+   * Pressure Sensor connected to analog channel 0.
+   *
+   * <p>On CTRE PCM, this will enable digital control.
+   *
+   * @param minPressure The minimum pressure in PSI. The compressor will turn on when the pressure
+   *     drops below this value.
+   * @param maxPressure The maximum pressure in PSI. The compressor will turn off when the pressure
+   *     reaches this value.
+   */
   void enableCompressorAnalog(double minPressure, double maxPressure);
 
+  /**
+   * If supported by the device, enables the compressor in hybrid mode. This mode uses both a
+   * digital pressure switch and an analog pressure sensor connected to analog channel 0 to cycle
+   * the compressor. This mode is only supported by the REV PH with the REV Analog Pressure Sensor
+   * connected to analog channel 0.
+   *
+   * <p>The compressor will turn on when <i>both</i>:
+   *
+   * <ul>
+   *   <li>The digital pressure switch indicates the system is not full AND
+   *   <li>The analog pressure sensor indicates that the pressure in the system is below the
+   *       specified minimum pressure.
+   * </ul>
+   *
+   * <p>The compressor will turn off when <i>either</i>:
+   *
+   * <ul>
+   *   <li>The digital pressure switch is disconnected or indicates that the system is full OR
+   *   <li>The pressure detected by the analog sensor is greater than the specified maximum
+   *       pressure.
+   * </ul>
+   *
+   * <p>On CTRE PCM, this will enable digital control.
+   *
+   * @param minPressure The minimum pressure in PSI. The compressor will turn on when the pressure
+   *     drops below this value and the pressure switch indicates that the system is not full.
+   * @param maxPressure The maximum pressure in PSI. The compressor will turn off when the pressure
+   *     reaches this value or the pressure switch is disconnected or indicates that the system is
+   *     full.
+   */
   void enableCompressorHybrid(double minPressure, double maxPressure);
 
+  /**
+   * If supported by the device, returns the raw voltage of the specified analog input channel.
+   *
+   * <p>This function is only supported by the REV PH. On CTRE PCM, this will return 0.
+   *
+   * @param channel The analog input channel to read voltage from.
+   * @return The voltage of the specified analog input channel.
+   */
   double getAnalogVoltage(int channel);
 
+  /**
+   * If supported by the device, returns the pressure (in PSI) read by an analog pressure sensor on
+   * the specified analog input channel.
+   *
+   * <p>This function is only supported by the REV PH. On CTRE PCM, this will return 0.
+   *
+   * @param channel The analog input channel to read pressure from.
+   * @return The pressure (in PSI) read by an analog pressure sensor on the specified analog input
+   *     channel.
+   */
   double getPressure(int channel);
 
+  /**
+   * Returns the active compressor configuration.
+   *
+   * @return The active compressor configuration.
+   */
   CompressorConfigType getCompressorConfigType();
 
   /**
@@ -111,15 +199,15 @@
   /**
    * Check to see if the masked solenoids can be reserved, and if not reserve them.
    *
-   * @param mask The solenoid mask to reserve
-   * @return 0 if successful, mask of solenoids that couldn't be allocated otherwise
+   * @param mask The bitmask of solenoids to reserve
+   * @return 0 if successful; mask of solenoids that couldn't be allocated otherwise
    */
   int checkAndReserveSolenoids(int mask);
 
   /**
    * Unreserve the masked solenoids.
    *
-   * @param mask The solenoid mask to unreserve
+   * @param mask The bitmask of solenoids to unreserve
    */
   void unreserveSolenoids(int mask);
 
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/PneumaticsControlModule.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/PneumaticsControlModule.java
index 9ea6a3f..aac16a3 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/PneumaticsControlModule.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/PneumaticsControlModule.java
@@ -66,7 +66,7 @@
   private final DataStore m_dataStore;
   private final int m_handle;
 
-  /** Constructs a PneumaticsControlModule with the default id (0). */
+  /** Constructs a PneumaticsControlModule with the default ID (0). */
   public PneumaticsControlModule() {
     this(SensorUtil.getDefaultCTREPCMModule());
   }
@@ -101,26 +101,67 @@
     return CTREPCMJNI.getCompressorCurrent(m_handle);
   }
 
+  /**
+   * Return whether the compressor current is currently too high.
+   *
+   * @return True if the compressor current is too high, otherwise false.
+   * @see #getCompressorCurrentTooHighStickyFault()
+   */
   public boolean getCompressorCurrentTooHighFault() {
     return CTREPCMJNI.getCompressorCurrentTooHighFault(m_handle);
   }
 
+  /**
+   * Returns whether the compressor current has been too high since sticky faults were last cleared.
+   * This fault is persistent and can be cleared by {@link #clearAllStickyFaults()}
+   *
+   * @return True if the compressor current has been too high since sticky faults were last cleared.
+   * @see #getCompressorCurrentTooHighFault()
+   */
   public boolean getCompressorCurrentTooHighStickyFault() {
     return CTREPCMJNI.getCompressorCurrentTooHighStickyFault(m_handle);
   }
 
+  /**
+   * Returns whether the compressor is currently shorted.
+   *
+   * @return True if the compressor is currently shorted, otherwise false.
+   * @see #getCompressorShortedStickyFault()
+   */
   public boolean getCompressorShortedFault() {
     return CTREPCMJNI.getCompressorShortedFault(m_handle);
   }
 
+  /**
+   * Returns whether the compressor has been shorted since sticky faults were last cleared. This
+   * fault is persistent and can be cleared by {@link #clearAllStickyFaults()}
+   *
+   * @return True if the compressor has been shorted since sticky faults were last cleared,
+   *     otherwise false.
+   * @see #getCompressorShortedFault()
+   */
   public boolean getCompressorShortedStickyFault() {
     return CTREPCMJNI.getCompressorShortedStickyFault(m_handle);
   }
 
+  /**
+   * Returns whether the compressor is currently disconnected.
+   *
+   * @return True if compressor is currently disconnected, otherwise false.
+   * @see #getCompressorNotConnectedStickyFault()
+   */
   public boolean getCompressorNotConnectedFault() {
     return CTREPCMJNI.getCompressorNotConnectedFault(m_handle);
   }
 
+  /**
+   * Returns whether the compressor has been disconnected since sticky faults were last cleared.
+   * This fault is persistent and can be cleared by {@link #clearAllStickyFaults()}
+   *
+   * @return True if the compressor has been disconnected since sticky faults were last cleared,
+   *     otherwise false.
+   * @see #getCompressorNotConnectedFault()
+   */
   public boolean getCompressorNotConnectedStickyFault() {
     return CTREPCMJNI.getCompressorNotConnectedStickyFault(m_handle);
   }
@@ -153,6 +194,7 @@
     return CTREPCMJNI.getSolenoidVoltageStickyFault(m_handle);
   }
 
+  /** Clears all sticky faults on this device. */
   public void clearAllStickyFaults() {
     CTREPCMJNI.clearAllStickyFaults(m_handle);
   }
@@ -224,6 +266,10 @@
     }
   }
 
+  /**
+   * Disables the compressor. The compressor will not turn on until {@link
+   * #enableCompressorDigital()} is called.
+   */
   @Override
   public void disableCompressor() {
     CTREPCMJNI.setClosedLoopControl(m_handle, false);
@@ -234,11 +280,25 @@
     CTREPCMJNI.setClosedLoopControl(m_handle, true);
   }
 
+  /**
+   * Enables the compressor in digital mode. Analog mode is unsupported by the CTRE PCM.
+   *
+   * @param minPressure Unsupported.
+   * @param maxPressure Unsupported.
+   * @see #enableCompressorDigital()
+   */
   @Override
   public void enableCompressorAnalog(double minPressure, double maxPressure) {
     CTREPCMJNI.setClosedLoopControl(m_handle, false);
   }
 
+  /**
+   * Enables the compressor in digital mode. Hybrid mode is unsupported by the CTRE PCM.
+   *
+   * @param minPressure Unsupported.
+   * @param maxPressure Unsupported.
+   * @see #enableCompressorDigital()
+   */
   @Override
   public void enableCompressorHybrid(double minPressure, double maxPressure) {
     CTREPCMJNI.setClosedLoopControl(m_handle, false);
@@ -251,11 +311,23 @@
         : CompressorConfigType.Disabled;
   }
 
+  /**
+   * Unsupported by the CTRE PCM.
+   *
+   * @param channel Unsupported.
+   * @return 0
+   */
   @Override
   public double getAnalogVoltage(int channel) {
     return 0;
   }
 
+  /**
+   * Unsupported by the CTRE PCM.
+   *
+   * @param channel Unsupported.
+   * @return 0
+   */
   @Override
   public double getPressure(int channel) {
     return 0;
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Preferences.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Preferences.java
index cf7b9ec..a80fd45 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Preferences.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Preferences.java
@@ -4,15 +4,20 @@
 
 package edu.wpi.first.wpilibj;
 
-import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
 
 import edu.wpi.first.hal.FRCNetComm.tResourceType;
 import edu.wpi.first.hal.HAL;
-import edu.wpi.first.networktables.EntryListenerFlags;
+import edu.wpi.first.networktables.MultiSubscriber;
 import edu.wpi.first.networktables.NetworkTable;
 import edu.wpi.first.networktables.NetworkTableEntry;
+import edu.wpi.first.networktables.NetworkTableEvent;
 import edu.wpi.first.networktables.NetworkTableInstance;
+import edu.wpi.first.networktables.NetworkTableListener;
+import edu.wpi.first.networktables.StringPublisher;
+import edu.wpi.first.networktables.Topic;
 import java.util.Collection;
+import java.util.EnumSet;
 
 /**
  * The preferences class provides a relatively simple way to save important values to the roboRIO to
@@ -30,37 +35,58 @@
 public final class Preferences {
   /** The Preferences table name. */
   private static final String TABLE_NAME = "Preferences";
-  /** The singleton instance. */
-  private static Preferences instance;
   /** The network table. */
-  private static final NetworkTable m_table;
+  private static NetworkTable m_table;
 
-  /**
-   * Returns the preferences instance.
-   *
-   * @return the preferences instance
-   * @deprecated Use the static methods
-   */
-  @Deprecated
-  public static synchronized Preferences getInstance() {
-    if (instance == null) {
-      instance = new Preferences();
-    }
-    return instance;
-  }
+  private static StringPublisher m_typePublisher;
+  private static MultiSubscriber m_tableSubscriber;
+  private static NetworkTableListener m_listener;
 
   /** Creates a preference class. */
   private Preferences() {}
 
   static {
-    m_table = NetworkTableInstance.getDefault().getTable(TABLE_NAME);
-    m_table.getEntry(".type").setString("RobotPreferences");
+    setNetworkTableInstance(NetworkTableInstance.getDefault());
+    HAL.report(tResourceType.kResourceType_Preferences, 0);
+  }
+
+  /**
+   * Set the NetworkTable instance used for entries. For testing purposes; use with caution.
+   *
+   * @param inst NetworkTable instance
+   */
+  public static synchronized void setNetworkTableInstance(NetworkTableInstance inst) {
+    m_table = inst.getTable(TABLE_NAME);
+    if (m_typePublisher != null) {
+      m_typePublisher.close();
+    }
+    m_typePublisher = m_table.getStringTopic(".type").publish();
+    m_typePublisher.set("RobotPreferences");
+
+    // Subscribe to all Preferences; this ensures we get the latest values
+    // ahead of a getter call.
+    if (m_tableSubscriber != null) {
+      m_tableSubscriber.close();
+    }
+    m_tableSubscriber = new MultiSubscriber(inst, new String[] {m_table.getPath() + "/"});
+
     // Listener to set all Preferences values to persistent
     // (for backwards compatibility with old dashboards).
-    m_table.addEntryListener(
-        (table, key, entry, value, flags) -> entry.setPersistent(),
-        EntryListenerFlags.kImmediate | EntryListenerFlags.kNew);
-    HAL.report(tResourceType.kResourceType_Preferences, 0);
+    if (m_listener != null) {
+      m_listener.close();
+    }
+    m_listener =
+        NetworkTableListener.createListener(
+            m_tableSubscriber,
+            EnumSet.of(NetworkTableEvent.Kind.kImmediate, NetworkTableEvent.Kind.kPublish),
+            event -> {
+              if (event.topicInfo != null) {
+                Topic topic = event.topicInfo.getTopic();
+                if (!topic.equals(m_typePublisher.getTopic())) {
+                  event.topicInfo.getTopic().setPersistent(true);
+                }
+              }
+            });
   }
 
   /**
@@ -88,19 +114,6 @@
   }
 
   /**
-   * Puts the given string into the preferences table.
-   *
-   * @param key the key
-   * @param value the value
-   * @throws NullPointerException if value is null
-   * @deprecated Use {@link #setString(String, String)}
-   */
-  @Deprecated
-  public static void putString(String key, String value) {
-    setString(key, value);
-  }
-
-  /**
    * Puts the given string into the preferences table if it doesn't already exist.
    *
    * @param key The key
@@ -125,18 +138,6 @@
   }
 
   /**
-   * Puts the given int into the preferences table.
-   *
-   * @param key the key
-   * @param value the value
-   * @deprecated Use {@link #setInt(String, int)}
-   */
-  @Deprecated
-  public static void putInt(String key, int value) {
-    setInt(key, value);
-  }
-
-  /**
    * Puts the given int into the preferences table if it doesn't already exist.
    *
    * @param key The key
@@ -161,18 +162,6 @@
   }
 
   /**
-   * Puts the given double into the preferences table.
-   *
-   * @param key the key
-   * @param value the value
-   * @deprecated Use {@link #setDouble(String, double)}
-   */
-  @Deprecated
-  public static void putDouble(String key, double value) {
-    setDouble(key, value);
-  }
-
-  /**
    * Puts the given double into the preferences table if it doesn't already exist.
    *
    * @param key The key
@@ -197,18 +186,6 @@
   }
 
   /**
-   * Puts the given float into the preferences table.
-   *
-   * @param key the key
-   * @param value the value
-   * @deprecated Use {@link #setFloat(String, float)}
-   */
-  @Deprecated
-  public static void putFloat(String key, float value) {
-    setFloat(key, value);
-  }
-
-  /**
    * Puts the given float into the preferences table if it doesn't already exist.
    *
    * @param key The key
@@ -233,18 +210,6 @@
   }
 
   /**
-   * Puts the given boolean into the preferences table.
-   *
-   * @param key the key
-   * @param value the value
-   * @deprecated Use {@link #setBoolean(String, boolean)}
-   */
-  @Deprecated
-  public static void putBoolean(String key, boolean value) {
-    setBoolean(key, value);
-  }
-
-  /**
    * Puts the given boolean into the preferences table if it doesn't already exist.
    *
    * @param key The key
@@ -269,18 +234,6 @@
   }
 
   /**
-   * Puts the given long into the preferences table.
-   *
-   * @param key the key
-   * @param value the value
-   * @deprecated Use {@link #setLong(String, long)}
-   */
-  @Deprecated
-  public static void putLong(String key, long value) {
-    setLong(key, value);
-  }
-
-  /**
    * Puts the given long into the preferences table if it doesn't already exist.
    *
    * @param key The key
@@ -293,7 +246,7 @@
   }
 
   /**
-   * Returns whether or not there is a key with the given name.
+   * Returns whether there is a key with the given name.
    *
    * @param key the key
    * @return if there is a value at the given key
@@ -308,7 +261,9 @@
    * @param key the key
    */
   public static void remove(String key) {
-    m_table.delete(key);
+    NetworkTableEntry entry = m_table.getEntry(key);
+    entry.clearPersistent();
+    entry.unpublish();
   }
 
   /** Remove all preferences. */
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Relay.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Relay.java
index 05efebd..a2a58d3 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Relay.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Relay.java
@@ -4,7 +4,7 @@
 
 package edu.wpi.first.wpilibj;
 
-import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
 
 import edu.wpi.first.hal.FRCNetComm.tResourceType;
 import edu.wpi.first.hal.HAL;
@@ -31,7 +31,6 @@
    * This class represents errors in trying to set relay values contradictory to the direction to
    * which the relay is set.
    */
-  @SuppressWarnings("serial")
   public static class InvalidValueException extends RuntimeException {
     /**
      * Create a new exception with the given message.
@@ -160,7 +159,7 @@
    * <p>When set to kBothDirections, the relay can be set to any of the four states: 0v-0v, 12v-0v,
    * 0v-12v, 12v-12v
    *
-   * <p>When set to kForwardOnly or kReverseOnly, you can specify the constant for the direction or
+   * <p>When set to kForwardOnly or kReverseOnly, you can specify the constant for the direction, or
    * you can simply specify kOff and kOn. Using only kOff and kOn is recommended.
    *
    * @param value The state to set the relay.
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Resource.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Resource.java
index 09137d6..f4b0458 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Resource.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Resource.java
@@ -9,14 +9,14 @@
 
 /**
  * Track resources in the program. The Resource class is a convenient way of keeping track of
- * allocated arbitrary resources in the program. Resources are just indices that have an lower and
+ * allocated arbitrary resources in the program. Resources are just indices that have a lower and
  * upper bound that are tracked by this class. In the library they are used for tracking allocation
  * of hardware channels but this is purely arbitrary. The resource class does not do any actual
  * allocation, but simply tracks if a given index is currently in use.
  *
  * <p><b>WARNING:</b> this should only be statically allocated. When the program loads into memory
  * all the static constructors are called. At that time a linked list of all the "Resources" is
- * created. Then when the program actually starts - in the Robot constructor, all resources are
+ * created. Then, when the program actually starts - in the Robot constructor, all resources are
  * initialized. This ensures that the program is restartable in memory without having to
  * unload/reload.
  */
@@ -71,7 +71,7 @@
 
   /**
    * Allocate a specific resource value. The user requests a specific resource value, i.e. channel
-   * number and it is verified unallocated, then returned.
+   * number, and it is verified unallocated, then returned.
    *
    * @param index The resource to allocate
    * @return The index of the allocated block
@@ -90,8 +90,8 @@
 
   /**
    * Free an allocated resource. After a resource is no longer needed, for example a destructor is
-   * called for a channel assignment class, Free will release the resource value so it can be reused
-   * somewhere else in the program.
+   * called for a channel assignment class, this method will release the resource value, so it can
+   * be reused somewhere else in the program.
    *
    * @param index The index of the resource to free.
    */
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java
index 5480f9b..e4fb962 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java
@@ -14,6 +14,7 @@
 import edu.wpi.first.math.MathShared;
 import edu.wpi.first.math.MathSharedStore;
 import edu.wpi.first.math.MathUsageId;
+import edu.wpi.first.networktables.MultiSubscriber;
 import edu.wpi.first.networktables.NetworkTableInstance;
 import edu.wpi.first.wpilibj.livewindow.LiveWindow;
 import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
@@ -38,6 +39,8 @@
   // This is usually 1, but it is best to make sure
   private static long m_threadId = -1;
 
+  private final MultiSubscriber m_suball;
+
   private static void setupCameraServerShared() {
     CameraServerShared shared =
         new CameraServerShared() {
@@ -134,20 +137,34 @@
    * completion before Autonomous is entered.
    *
    * <p>This must be used to ensure that the communications code starts. In the future it would be
-   * nice to put this code into it's own task that loads on boot so ensure that it runs.
+   * nice to put this code into its own task that loads on boot so ensure that it runs.
    */
   protected RobotBase() {
     final NetworkTableInstance inst = NetworkTableInstance.getDefault();
     m_threadId = Thread.currentThread().getId();
     setupCameraServerShared();
     setupMathShared();
-    inst.setNetworkIdentity("Robot");
+    // subscribe to "" to force persistent values to propagate to local
+    m_suball = new MultiSubscriber(inst, new String[] {""});
     if (isReal()) {
-      inst.startServer("/home/lvuser/networktables.ini");
+      inst.startServer("/home/lvuser/networktables.json");
     } else {
       inst.startServer();
     }
-    inst.getTable("LiveWindow").getSubTable(".status").getEntry("LW Enabled").setBoolean(false);
+
+    // wait for the NT server to actually start
+    try {
+      int count = 0;
+      while (inst.getNetworkMode().contains(NetworkTableInstance.NetworkMode.kStarting)) {
+        Thread.sleep(10);
+        count++;
+        if (count > 100) {
+          throw new InterruptedException();
+        }
+      }
+    } catch (InterruptedException ex) {
+      System.err.println("timed out while waiting for NT server to start");
+    }
 
     LiveWindow.setEnabled(false);
     Shuffleboard.disableActuatorWidgets();
@@ -158,7 +175,9 @@
   }
 
   @Override
-  public void close() {}
+  public void close() {
+    m_suball.close();
+  }
 
   /**
    * Get the current runtime type.
@@ -239,18 +258,6 @@
    * controls.
    *
    * @return True if the robot is currently operating in Tele-Op mode.
-   * @deprecated Use isTeleop() instead.
-   */
-  @Deprecated(since = "2022", forRemoval = true)
-  public boolean isOperatorControl() {
-    return DriverStation.isTeleop();
-  }
-
-  /**
-   * Determine if the robot is currently in Operator Control mode as determined by the field
-   * controls.
-   *
-   * @return True if the robot is currently operating in Tele-Op mode.
    */
   public boolean isTeleop() {
     return DriverStation.isTeleop();
@@ -261,59 +268,22 @@
    * field controls.
    *
    * @return True if the robot is currently operating in Tele-Op mode while enabled.
-   * @deprecated Use isTeleopEnabled() instead.
-   */
-  @Deprecated(since = "2022", forRemoval = true)
-  public boolean isOperatorControlEnabled() {
-    return DriverStation.isTeleopEnabled();
-  }
-
-  /**
-   * Determine if the robot is current in Operator Control mode and enabled as determined by the
-   * field controls.
-   *
-   * @return True if the robot is currently operating in Tele-Op mode while enabled.
    */
   public boolean isTeleopEnabled() {
     return DriverStation.isTeleopEnabled();
   }
 
-  /**
-   * Indicates if new data is available from the driver station.
-   *
-   * @return Has new data arrived over the network since the last time this function was called?
-   */
-  public boolean isNewDataAvailable() {
-    return DriverStation.isNewControlData();
-  }
-
   /** Provide an alternate "main loop" via startCompetition(). */
   public abstract void startCompetition();
 
   /** Ends the main loop in startCompetition(). */
   public abstract void endCompetition();
 
-  @SuppressWarnings("MissingJavadocMethod")
-  public static boolean getBooleanProperty(String name, boolean defaultValue) {
-    String propVal = System.getProperty(name);
-    if (propVal == null) {
-      return defaultValue;
-    }
-    if ("false".equalsIgnoreCase(propVal)) {
-      return false;
-    } else if ("true".equalsIgnoreCase(propVal)) {
-      return true;
-    } else {
-      throw new IllegalStateException(propVal);
-    }
-  }
-
   private static final ReentrantLock m_runMutex = new ReentrantLock();
   private static RobotBase m_robotCopy;
   private static boolean m_suppressExitWarning;
 
   /** Run the robot main loop. */
-  @SuppressWarnings({"PMD.AvoidCatchingThrowable", "PMD.AvoidReassigningCatchVariables"})
   private static <T extends RobotBase> void runRobot(Supplier<T> robotSupplier) {
     System.out.println("********** Robot program starting **********");
 
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotController.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotController.java
index 8a7460e..8bf9268 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotController.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotController.java
@@ -21,7 +21,6 @@
    *
    * @return FPGA Version number.
    */
-  @SuppressWarnings("AbbreviationAsWordInName")
   public static int getFPGAVersion() {
     return HALUtil.getFPGAVersion();
   }
@@ -33,12 +32,32 @@
    *
    * @return FPGA Revision number.
    */
-  @SuppressWarnings("AbbreviationAsWordInName")
   public static long getFPGARevision() {
     return (long) HALUtil.getFPGARevision();
   }
 
   /**
+   * Return the serial number of the roboRIO.
+   *
+   * @return The serial number of the roboRIO.
+   */
+  public static String getSerialNumber() {
+    return HALUtil.getSerialNumber();
+  }
+
+  /**
+   * Return the comments from the roboRIO web interface.
+   *
+   * <p>The comments string is cached after the first call to this function on the RoboRIO - restart
+   * the robot code to reload the comments string after changing it in the web interface.
+   *
+   * @return the comments from the roboRIO web interface.
+   */
+  public static String getComments() {
+    return HALUtil.getComments();
+  }
+
+  /**
    * Read the microsecond timer from the FPGA.
    *
    * @return The current time in microseconds according to the FPGA.
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotState.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotState.java
index 462051a..44198df 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotState.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotState.java
@@ -4,33 +4,57 @@
 
 package edu.wpi.first.wpilibj;
 
-@SuppressWarnings("MissingJavadocMethod")
 public final class RobotState {
+  /**
+   * Returns true if the robot is disabled.
+   *
+   * @return True if the robot is disabled.
+   */
   public static boolean isDisabled() {
     return DriverStation.isDisabled();
   }
 
+  /**
+   * Returns true if the robot is enabled.
+   *
+   * @return True if the robot is enabled.
+   */
   public static boolean isEnabled() {
     return DriverStation.isEnabled();
   }
 
+  /**
+   * Returns true if the robot is E-stopped.
+   *
+   * @return True if the robot is E-stopped.
+   */
   public static boolean isEStopped() {
     return DriverStation.isEStopped();
   }
 
-  @Deprecated
-  public static boolean isOperatorControl() {
-    return isTeleop();
-  }
-
+  /**
+   * Returns true if the robot is in teleop mode.
+   *
+   * @return True if the robot is in teleop mode.
+   */
   public static boolean isTeleop() {
     return DriverStation.isTeleop();
   }
 
+  /**
+   * Returns true if the robot is in autonomous mode.
+   *
+   * @return True if the robot is in autonomous mode.
+   */
   public static boolean isAutonomous() {
     return DriverStation.isAutonomous();
   }
 
+  /**
+   * Returns true if the robot is in test mode.
+   *
+   * @return True if the robot is in test mode.
+   */
   public static boolean isTest() {
     return DriverStation.isTest();
   }
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/SPI.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/SPI.java
index 2243140..73a0b23 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/SPI.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/SPI.java
@@ -12,14 +12,14 @@
 import java.nio.ByteOrder;
 import java.nio.IntBuffer;
 
-/** Represents a SPI bus port. */
+/** Represents an SPI bus port. */
 public class SPI implements AutoCloseable {
   public enum Port {
-    kOnboardCS0(0),
-    kOnboardCS1(1),
-    kOnboardCS2(2),
-    kOnboardCS3(3),
-    kMXP(4);
+    kOnboardCS0(SPIJNI.ONBOARD_CS0_PORT),
+    kOnboardCS1(SPIJNI.ONBOARD_CS0_PORT),
+    kOnboardCS2(SPIJNI.ONBOARD_CS0_PORT),
+    kOnboardCS3(SPIJNI.ONBOARD_CS0_PORT),
+    kMXP(SPIJNI.MXP_PORT);
 
     public final int value;
 
@@ -28,10 +28,21 @@
     }
   }
 
+  public enum Mode {
+    kMode0(SPIJNI.SPI_MODE0),
+    kMode1(SPIJNI.SPI_MODE1),
+    kMode2(SPIJNI.SPI_MODE2),
+    kMode3(SPIJNI.SPI_MODE3);
+
+    public final int value;
+
+    Mode(int value) {
+      this.value = value;
+    }
+  }
+
   private int m_port;
-  private int m_msbFirst;
-  private int m_clockIdleHigh;
-  private int m_sampleOnTrailing;
+  private int m_mode;
 
   /**
    * Constructor.
@@ -39,10 +50,13 @@
    * @param port the physical SPI port
    */
   public SPI(Port port) {
-    m_port = (byte) port.value;
+    m_port = port.value;
 
     SPIJNI.spiInitialize(m_port);
 
+    m_mode = 0;
+    SPIJNI.spiSetMode(m_port, m_mode);
+
     HAL.report(tResourceType.kResourceType_SPI, port.value + 1);
   }
 
@@ -70,81 +84,91 @@
   }
 
   /**
-   * Configure the order that bits are sent and received on the wire to be most significant bit
+   * Configure the order that bits are sent and received on the wire to be the most significant bit
    * first.
+   *
+   * @deprecated Does not work, will be removed.
    */
+  @Deprecated(since = "2023", forRemoval = true)
   public final void setMSBFirst() {
-    m_msbFirst = 1;
-    SPIJNI.spiSetOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+    DriverStation.reportWarning("setMSBFirst not supported by roboRIO", false);
   }
 
   /**
-   * Configure the order that bits are sent and received on the wire to be least significant bit
+   * Configure the order that bits are sent and received on the wire to be the least significant bit
    * first.
+   *
+   * @deprecated Does not work, will be removed.
    */
+  @Deprecated(since = "2023", forRemoval = true)
   public final void setLSBFirst() {
-    m_msbFirst = 0;
-    SPIJNI.spiSetOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+    DriverStation.reportWarning("setLSBFirst not supported by roboRIO", false);
   }
 
   /**
    * Configure the clock output line to be active low. This is sometimes called clock polarity high
    * or clock idle high.
+   *
+   * @deprecated Use setMode() instead.
    */
+  @Deprecated(since = "2023", forRemoval = true)
   public final void setClockActiveLow() {
-    m_clockIdleHigh = 1;
-    SPIJNI.spiSetOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+    m_mode |= 1;
+    SPIJNI.spiSetMode(m_port, m_mode);
   }
 
   /**
    * Configure the clock output line to be active high. This is sometimes called clock polarity low
    * or clock idle low.
+   *
+   * @deprecated Use setMode() instead.
    */
+  @Deprecated(since = "2023", forRemoval = true)
   public final void setClockActiveHigh() {
-    m_clockIdleHigh = 0;
-    SPIJNI.spiSetOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+    m_mode &= 1;
+    SPIJNI.spiSetMode(m_port, m_mode);
   }
 
   /**
    * Configure that the data is stable on the leading edge and the data changes on the trailing
    * edge.
+   *
+   * @deprecated Use setMode() instead.
    */
+  @Deprecated(since = "2023", forRemoval = true)
   public final void setSampleDataOnLeadingEdge() {
-    m_sampleOnTrailing = 0;
-    SPIJNI.spiSetOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+    m_mode &= 2;
+    SPIJNI.spiSetMode(m_port, m_mode);
   }
 
   /**
    * Configure that the data is stable on the trailing edge and the data changes on the leading
    * edge.
+   *
+   * @deprecated Use setMode() instead.
    */
+  @Deprecated(since = "2023", forRemoval = true)
   public final void setSampleDataOnTrailingEdge() {
-    m_sampleOnTrailing = 1;
-    SPIJNI.spiSetOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+    m_mode |= 2;
+    SPIJNI.spiSetMode(m_port, m_mode);
   }
 
   /**
-   * Configure that the data is stable on the falling edge and the data changes on the rising edge.
-   * Note this gets reversed is setClockActiveLow is set.
+   * Sets the mode for the SPI device.
    *
-   * @deprecated use {@link #setSampleDataOnTrailingEdge()} in most cases.
-   */
-  @Deprecated
-  public final void setSampleDataOnFalling() {
-    m_sampleOnTrailing = 1;
-    SPIJNI.spiSetOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
-  }
-
-  /**
-   * Configure that the data is stable on the rising edge and the data changes on the falling edge.
-   * Note this gets reversed is setClockActiveLow is set.
+   * <p>Mode 0 is Clock idle low, data sampled on rising edge.
    *
-   * @deprecated use {@link #setSampleDataOnLeadingEdge()} in most cases.
+   * <p>Mode 1 is Clock idle low, data sampled on falling edge.
+   *
+   * <p>Mode 2 is Clock idle high, data sampled on falling edge.
+   *
+   * <p>Mode 3 is Clock idle high, data sampled on rising edge.
+   *
+   * @param mode The mode to set.
    */
-  @Deprecated
-  public final void setSampleDataOnRising() {
-    m_sampleOnTrailing = 0;
-    SPIJNI.spiSetOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+  public final void setMode(Mode mode) {
+    m_mode = mode.value & 0x3;
+    SPIJNI.spiSetMode(m_port, m_mode);
   }
 
   /** Configure the chip select line to be active high. */
@@ -184,7 +208,6 @@
    * @param size The number of bytes to send.
    * @return Number of bytes written or -1 on error.
    */
-  @SuppressWarnings("ByteBufferBackingArray")
   public int write(ByteBuffer dataToSend, int size) {
     if (dataToSend.hasArray()) {
       return write(dataToSend.array(), size);
@@ -233,7 +256,6 @@
    * @param size The length of the transaction, in bytes
    * @return Number of bytes read or -1 on error.
    */
-  @SuppressWarnings("ByteBufferBackingArray")
   public int read(boolean initiate, ByteBuffer dataReceived, int size) {
     if (dataReceived.hasArray()) {
       return read(initiate, dataReceived.array(), size);
@@ -273,7 +295,6 @@
    * @param size The length of the transaction, in bytes
    * @return TODO
    */
-  @SuppressWarnings("ByteBufferBackingArray")
   public int transaction(ByteBuffer dataToSend, ByteBuffer dataReceived, int size) {
     if (dataToSend.hasArray() && dataReceived.hasArray()) {
       return transaction(dataToSend.array(), dataReceived.array(), size);
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/SensorUtil.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/SensorUtil.java
index 0ac24de..bcedd81 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/SensorUtil.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/SensorUtil.java
@@ -141,7 +141,6 @@
    *
    * @return The number of the default solenoid module.
    */
-  @SuppressWarnings("AbbreviationAsWordInName")
   public static int getDefaultCTREPCMModule() {
     return 0;
   }
@@ -151,7 +150,6 @@
    *
    * @return The number of the default solenoid module.
    */
-  @SuppressWarnings("AbbreviationAsWordInName")
   public static int getDefaultREVPHModule() {
     return 1;
   }
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/SerialPort.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/SerialPort.java
index 331bbf1..1a05c8a 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/SerialPort.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/SerialPort.java
@@ -84,48 +84,6 @@
   /**
    * Create an instance of a Serial Port class.
    *
-   * <p>Prefer to use the constructor that doesn't take a port name, but in some cases the automatic
-   * detection might not work correctly.
-   *
-   * @param baudRate The baud rate to configure the serial port.
-   * @param port The Serial port to use
-   * @param portName The direct portName to use
-   * @param dataBits The number of data bits per transfer. Valid values are between 5 and 8 bits.
-   * @param parity Select the type of parity checking to use.
-   * @param stopBits The number of stop bits to use as defined by the enum StopBits.
-   * @deprecated Will be removed for 2019
-   */
-  @Deprecated
-  public SerialPort(
-      final int baudRate,
-      String portName,
-      Port port,
-      final int dataBits,
-      Parity parity,
-      StopBits stopBits) {
-    m_portHandle = SerialPortJNI.serialInitializePortDirect((byte) port.value, portName);
-    SerialPortJNI.serialSetBaudRate(m_portHandle, baudRate);
-    SerialPortJNI.serialSetDataBits(m_portHandle, (byte) dataBits);
-    SerialPortJNI.serialSetParity(m_portHandle, (byte) parity.value);
-    SerialPortJNI.serialSetStopBits(m_portHandle, (byte) stopBits.value);
-
-    // Set the default read buffer size to 1 to return bytes immediately
-    setReadBufferSize(1);
-
-    // Set the default timeout to 5 seconds.
-    setTimeout(5.0);
-
-    // Don't wait until the buffer is full to transmit.
-    setWriteBufferMode(WriteBufferMode.kFlushOnAccess);
-
-    disableTermination();
-
-    HAL.report(tResourceType.kResourceType_SerialPort, port.value + 1);
-  }
-
-  /**
-   * Create an instance of a Serial Port class.
-   *
    * @param baudRate The baud rate to configure the serial port.
    * @param port The Serial port to use
    * @param dataBits The number of data bits per transfer. Valid values are between 5 and 8 bits.
@@ -206,9 +164,8 @@
   /**
    * Enable termination and specify the termination character.
    *
-   * <p>Termination is currently only implemented for receive. When the the terminator is received,
-   * the read() or readString() will return fewer bytes than requested, stopping after the
-   * terminator.
+   * <p>Termination is currently only implemented for receive. When the terminator is received, the
+   * read() or readString() will return fewer bytes than requested, stopping after the terminator.
    *
    * @param terminator The character to use for termination.
    */
@@ -219,9 +176,8 @@
   /**
    * Enable termination with the default terminator '\n'
    *
-   * <p>Termination is currently only implemented for receive. When the the terminator is received,
-   * the read() or readString() will return fewer bytes than requested, stopping after the
-   * terminator.
+   * <p>Termination is currently only implemented for receive. When the terminator is received, the
+   * read() or readString() will return fewer bytes than requested, stopping after the terminator.
    *
    * <p>The default terminator is '\n'
    */
@@ -310,7 +266,7 @@
    * <p>This defines the timeout for transactions with the hardware. It will affect reads if less
    * bytes are available than the read buffer size (defaults to 1) and very large writes.
    *
-   * @param timeout The number of seconds to to wait for I/O.
+   * @param timeout The number of seconds to wait for I/O.
    */
   public void setTimeout(double timeout) {
     SerialPortJNI.serialSetTimeout(m_portHandle, timeout);
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/SpeedController.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/SpeedController.java
deleted file mode 100644
index 490455c..0000000
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/SpeedController.java
+++ /dev/null
@@ -1,65 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj;
-
-/**
- * Interface for motor controlling devices.
- *
- * @deprecated Use {@link edu.wpi.first.wpilibj.motorcontrol.MotorController}.
- */
-@Deprecated(since = "2022", forRemoval = true)
-public interface SpeedController {
-  /**
-   * Common interface for setting the speed of a motor controller.
-   *
-   * @param speed The speed to set. Value should be between -1.0 and 1.0.
-   */
-  void set(double speed);
-
-  /**
-   * Sets the voltage output of the MotorController. Compensates for the current bus voltage to
-   * ensure that the desired voltage is output even if the battery voltage is below 12V - highly
-   * useful when the voltage outputs are "meaningful" (e.g. they come from a feedforward
-   * calculation).
-   *
-   * <p>NOTE: This function *must* be called regularly in order for voltage compensation to work
-   * properly - unlike the ordinary set function, it is not "set it and forget it."
-   *
-   * @param outputVolts The voltage to output.
-   */
-  default void setVoltage(double outputVolts) {
-    set(outputVolts / RobotController.getBatteryVoltage());
-  }
-
-  /**
-   * Common interface for getting the current set speed of a motor controller.
-   *
-   * @return The current set speed. Value is between -1.0 and 1.0.
-   */
-  double get();
-
-  /**
-   * Common interface for inverting direction of a motor controller.
-   *
-   * @param isInverted The state of inversion true is inverted.
-   */
-  void setInverted(boolean isInverted);
-
-  /**
-   * Common interface for returning if a motor controller is in the inverted state or not.
-   *
-   * @return isInverted The state of the inversion true is inverted.
-   */
-  boolean getInverted();
-
-  /** Disable the motor controller. */
-  void disable();
-
-  /**
-   * Stops motor movement. Motor can be moved again by calling set without having to re-enable the
-   * motor.
-   */
-  void stopMotor();
-}
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/SpeedControllerGroup.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/SpeedControllerGroup.java
deleted file mode 100644
index d2217b7..0000000
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/SpeedControllerGroup.java
+++ /dev/null
@@ -1,103 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj;
-
-import edu.wpi.first.util.sendable.Sendable;
-import edu.wpi.first.util.sendable.SendableBuilder;
-import edu.wpi.first.util.sendable.SendableRegistry;
-import edu.wpi.first.wpilibj.motorcontrol.MotorController;
-import java.util.Arrays;
-
-/**
- * Allows multiple {@link SpeedController} objects to be linked together.
- *
- * @deprecated Use {@link edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup}.
- */
-@Deprecated(since = "2022", forRemoval = true)
-@SuppressWarnings("removal")
-public class SpeedControllerGroup implements MotorController, Sendable, AutoCloseable {
-  private boolean m_isInverted;
-  private final SpeedController[] m_speedControllers;
-  private static int instances;
-
-  /**
-   * Create a new SpeedControllerGroup with the provided SpeedControllers.
-   *
-   * @param speedController The first SpeedController to add.
-   * @param speedControllers The SpeedControllers to add
-   */
-  public SpeedControllerGroup(
-      SpeedController speedController, SpeedController... speedControllers) {
-    m_speedControllers = new SpeedController[speedControllers.length + 1];
-    m_speedControllers[0] = speedController;
-    System.arraycopy(speedControllers, 0, m_speedControllers, 1, speedControllers.length);
-    init();
-  }
-
-  public SpeedControllerGroup(SpeedController[] speedControllers) {
-    m_speedControllers = Arrays.copyOf(speedControllers, speedControllers.length);
-    init();
-  }
-
-  private void init() {
-    for (SpeedController controller : m_speedControllers) {
-      SendableRegistry.addChild(this, controller);
-    }
-    instances++;
-    SendableRegistry.addLW(this, "MotorControllerGroup", instances);
-  }
-
-  @Override
-  public void close() {
-    SendableRegistry.remove(this);
-  }
-
-  @Override
-  public void set(double speed) {
-    for (SpeedController speedController : m_speedControllers) {
-      speedController.set(m_isInverted ? -speed : speed);
-    }
-  }
-
-  @Override
-  public double get() {
-    if (m_speedControllers.length > 0) {
-      return m_speedControllers[0].get() * (m_isInverted ? -1 : 1);
-    }
-    return 0.0;
-  }
-
-  @Override
-  public void setInverted(boolean isInverted) {
-    m_isInverted = isInverted;
-  }
-
-  @Override
-  public boolean getInverted() {
-    return m_isInverted;
-  }
-
-  @Override
-  public void disable() {
-    for (SpeedController speedController : m_speedControllers) {
-      speedController.disable();
-    }
-  }
-
-  @Override
-  public void stopMotor() {
-    for (SpeedController speedController : m_speedControllers) {
-      speedController.stopMotor();
-    }
-  }
-
-  @Override
-  public void initSendable(SendableBuilder builder) {
-    builder.setSmartDashboardType("Motor Controller");
-    builder.setActuator(true);
-    builder.setSafeState(this::stopMotor);
-    builder.addDoubleProperty("Value", this::get, this::set);
-  }
-}
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/SynchronousInterrupt.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/SynchronousInterrupt.java
index 1e7a54d..705d6b1 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/SynchronousInterrupt.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/SynchronousInterrupt.java
@@ -4,7 +4,7 @@
 
 package edu.wpi.first.wpilibj;
 
-import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
 
 import edu.wpi.first.hal.InterruptJNI;
 
@@ -21,14 +21,13 @@
 
   private final int m_handle;
 
-  @SuppressWarnings("JavadocMethod")
+  /** Event trigger combinations for a synchronous interrupt. */
   public enum WaitResult {
     kTimeout(0x0),
     kRisingEdge(0x1),
     kFallingEdge(0x100),
     kBoth(0x101);
 
-    @SuppressWarnings("MemberName")
     public final int value;
 
     WaitResult(int value) {
@@ -91,7 +90,7 @@
    *     interrupt was read.
    * @return The raw hardware interrupt result
    */
-  int waitForInterruptRaw(double timeoutSeconds, boolean ignorePrevious) {
+  long waitForInterruptRaw(double timeoutSeconds, boolean ignorePrevious) {
     return InterruptJNI.waitForInterrupt(m_handle, timeoutSeconds, ignorePrevious);
   }
 
@@ -102,14 +101,14 @@
    * @param ignorePrevious True to ignore if a previous interrupt has occurred, and only wait for a
    *     new trigger. False will consider if an interrupt has occurred since the last time the
    *     interrupt was read.
-   * @return Result of which edges were triggered, or if an timeout occurred.
+   * @return Result of which edges were triggered, or if a timeout occurred.
    */
   public WaitResult waitForInterrupt(double timeoutSeconds, boolean ignorePrevious) {
-    int result = InterruptJNI.waitForInterrupt(m_handle, timeoutSeconds, ignorePrevious);
+    long result = InterruptJNI.waitForInterrupt(m_handle, timeoutSeconds, ignorePrevious);
 
     // Rising edge result is the interrupt bit set in the byte 0xFF
     // Falling edge result is the interrupt bit set in the byte 0xFF00
-    // Set any bit set to be true for that edge, and AND the 2 results
+    // Set any bit set to be true for that edge, and then conduct a logical AND on the 2 results
     // together to match the existing enum for all interrupts
     boolean rising = (result & 0xFF) != 0;
     boolean falling = (result & 0xFF00) != 0;
@@ -120,7 +119,7 @@
    * Wait for an interrupt, ignoring any previously occurring interrupts.
    *
    * @param timeoutSeconds The timeout in seconds. 0 or less will return immediately.
-   * @return Result of which edges were triggered, or if an timeout occurred.
+   * @return Result of which edges were triggered, or if a timeout occurred.
    */
   public WaitResult waitForInterrupt(double timeoutSeconds) {
     return waitForInterrupt(timeoutSeconds, true);
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java
index dda62d2..5a53b14 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java
@@ -4,6 +4,7 @@
 
 package edu.wpi.first.wpilibj;
 
+import edu.wpi.first.hal.DriverStationJNI;
 import edu.wpi.first.hal.FRCNetComm.tInstances;
 import edu.wpi.first.hal.FRCNetComm.tResourceType;
 import edu.wpi.first.hal.HAL;
@@ -94,15 +95,13 @@
   }
 
   @Override
-  @SuppressWarnings("NoFinalizer")
-  protected void finalize() {
+  public void close() {
     NotifierJNI.stopNotifier(m_notifier);
     NotifierJNI.cleanNotifier(m_notifier);
   }
 
   /** Provide an alternate "main loop" via startCompetition(). */
   @Override
-  @SuppressWarnings("UnsafeFinalization")
   public void startCompetition() {
     robotInit();
 
@@ -112,7 +111,7 @@
 
     // Tell the DS that the robot is ready to be enabled
     System.out.println("********** Robot program startup complete **********");
-    HAL.observeUserProgramStarting();
+    DriverStationJNI.observeUserProgramStarting();
 
     // Loop forever, calling the appropriate mode-dependent function
     while (true) {
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Timer.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Timer.java
index 939e255..6f9a361 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Timer.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Timer.java
@@ -17,7 +17,6 @@
    *
    * @return Robot running time in seconds.
    */
-  @SuppressWarnings("AbbreviationAsWordInName")
   public static double getFPGATimestamp() {
     return RobotController.getFPGATime() / 1000000.0;
   }
@@ -55,7 +54,7 @@
   private double m_accumulatedTime;
   private boolean m_running;
 
-  @SuppressWarnings("MissingJavadocMethod")
+  /** Timer constructor. */
   public Timer() {
     reset();
   }
@@ -126,20 +125,6 @@
    * This is useful to decide if it's time to do periodic work without drifting later by the time it
    * took to get around to checking.
    *
-   * @param period The period to check for (in seconds).
-   * @return Whether the period has passed.
-   * @deprecated Use advanceIfElapsed() instead.
-   */
-  @Deprecated(since = "2022", forRemoval = true)
-  public boolean hasPeriodPassed(double period) {
-    return advanceIfElapsed(period);
-  }
-
-  /**
-   * Check if the period specified has passed and if it has, advance the start time by that period.
-   * This is useful to decide if it's time to do periodic work without drifting later by the time it
-   * took to get around to checking.
-   *
    * @param seconds The period to check.
    * @return Whether the period has passed.
    */
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Tracer.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Tracer.java
index ea04192..2415079 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Tracer.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Tracer.java
@@ -22,7 +22,6 @@
   private long m_lastEpochsPrintTime; // microseconds
   private long m_startTime; // microseconds
 
-  @SuppressWarnings("PMD.UseConcurrentHashMap")
   private final Map<String, Long> m_epochs = new HashMap<>(); // microseconds
 
   /** Tracer constructor. */
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Ultrasonic.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Ultrasonic.java
index 2d3fb4e..d7b326a 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Ultrasonic.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Ultrasonic.java
@@ -4,7 +4,7 @@
 
 package edu.wpi.first.wpilibj;
 
-import static java.util.Objects.requireNonNull;
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
 
 import edu.wpi.first.hal.FRCNetComm.tResourceType;
 import edu.wpi.first.hal.HAL;
@@ -79,7 +79,7 @@
   /**
    * Initialize the Ultrasonic Sensor. This is the common code that initializes the ultrasonic
    * sensor given that there are two digital I/O channels allocated. If the system was running in
-   * automatic mode (round robin) when the new sensor is added, it is stopped, the sensor is added,
+   * automatic mode (round-robin) when the new sensor is added, it is stopped, the sensor is added,
    * then automatic mode is restored.
    */
   private synchronized void initialize() {
@@ -103,7 +103,7 @@
     m_counter.setMaxPeriod(1.0);
     m_counter.setSemiPeriodMode(true);
     m_counter.reset();
-    m_enabled = true; // make it available for round robin scheduling
+    m_enabled = true; // make it available for round-robin scheduling
     setAutomaticMode(originalMode);
 
     m_instances++;
@@ -116,7 +116,7 @@
   }
 
   /**
-   * Create an instance of the Ultrasonic Sensor. This is designed to supchannel the Daventech SRF04
+   * Create an instance of the Ultrasonic Sensor. This is designed to support the Daventech SRF04
    * and Vex ultrasonic sensors.
    *
    * @param pingChannel The digital output channel that sends the pulse to initiate the sensor
@@ -142,8 +142,8 @@
    * @param echoChannel The digital input object that times the return pulse to determine the range.
    */
   public Ultrasonic(DigitalOutput pingChannel, DigitalInput echoChannel) {
-    requireNonNull(pingChannel, "Provided ping channel was null");
-    requireNonNull(echoChannel, "Provided echo channel was null");
+    requireNonNullParam(pingChannel, "pingChannel", "Ultrasonic");
+    requireNonNullParam(echoChannel, "echoChannel", "Ultrasonic");
 
     m_allocatedChannels = false;
     m_pingChannel = pingChannel;
@@ -153,7 +153,7 @@
 
   /**
    * Destructor for the ultrasonic sensor. Delete the instance of the ultrasonic sensor by freeing
-   * the allocated digital channels. If the system was in automatic mode (round robin), then it is
+   * the allocated digital channels. If the system was in automatic mode (round-robin), then it is
    * stopped, then started again after this sensor is removed (provided this wasn't the last
    * sensor).
    */
@@ -194,10 +194,10 @@
   /**
    * Turn Automatic mode on/off for all sensors.
    *
-   * <p>When in Automatic mode, all sensors will fire in round robin, waiting a set time between
+   * <p>When in Automatic mode, all sensors will fire in round-robin, waiting a set time between
    * each sensor.
    *
-   * @param enabling Set to true if round robin scheduling should start for all the ultrasonic
+   * @param enabling Set to true if round-robin scheduling should start for all the ultrasonic
    *     sensors. This scheduling method assures that the sensors are non-interfering because no two
    *     sensors fire at the same time. If another scheduling algorithm is preferred, it can be
    *     implemented by pinging the sensors manually and waiting for the results to come back.
@@ -239,12 +239,12 @@
 
   /**
    * Single ping to ultrasonic sensor. Send out a single ping to the ultrasonic sensor. This only
-   * works if automatic (round robin) mode is disabled. A single ping is sent out, and the counter
+   * works if automatic (round-robin) mode is disabled. A single ping is sent out, and the counter
    * should count the semi-period when it comes in. The counter is reset to make the current value
    * invalid.
    */
   public void ping() {
-    setAutomaticMode(false); // turn off automatic round robin if pinging
+    setAutomaticMode(false); // turn off automatic round-robin if pinging
     // single sensor
     m_counter.reset(); // reset the counter to zero (invalid data now)
     // do the ping to start getting a single range
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Watchdog.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Watchdog.java
index 22581a5..f7bf85b 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Watchdog.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/Watchdog.java
@@ -208,7 +208,6 @@
     m_suppressTimeoutMessage = suppress;
   }
 
-  @SuppressWarnings("resource")
   private static void updateAlarm() {
     if (m_watchdogs.size() == 0) {
       NotifierJNI.cancelNotifierAlarm(m_notifier);
@@ -225,7 +224,6 @@
     return inst;
   }
 
-  @SuppressWarnings("PMD.AvoidDeeplyNestedIfStmts")
   private static void schedulerFunc() {
     while (!Thread.currentThread().isInterrupted()) {
       long curTime = NotifierJNI.waitForNotifierAlarm(m_notifier);
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/XboxController.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/XboxController.java
index 5de3503..47195eb 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/XboxController.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/XboxController.java
@@ -6,6 +6,8 @@
 
 import edu.wpi.first.hal.FRCNetComm.tResourceType;
 import edu.wpi.first.hal.HAL;
+import edu.wpi.first.wpilibj.event.BooleanEvent;
+import edu.wpi.first.wpilibj.event.EventLoop;
 
 /**
  * Handle input from Xbox 360 or Xbox One controllers connected to the Driver Station.
@@ -28,7 +30,6 @@
     kBack(7),
     kStart(8);
 
-    @SuppressWarnings("MemberName")
     public final int value;
 
     Button(int value) {
@@ -62,7 +63,6 @@
     kLeftTrigger(2),
     kRightTrigger(3);
 
-    @SuppressWarnings("MemberName")
     public final int value;
 
     Axis(int value) {
@@ -209,6 +209,28 @@
   }
 
   /**
+   * Constructs an event instance around the right bumper's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the right bumper's digital signal attached to the given
+   *     loop.
+   */
+  public BooleanEvent leftBumper(EventLoop loop) {
+    return new BooleanEvent(loop, this::getLeftBumper);
+  }
+
+  /**
+   * Constructs an event instance around the left bumper's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the left bumper's digital signal attached to the given
+   *     loop.
+   */
+  public BooleanEvent rightBumper(EventLoop loop) {
+    return new BooleanEvent(loop, this::getRightBumper);
+  }
+
+  /**
    * Read the value of the left stick button (LSB) on the controller.
    *
    * @return The state of the button.
@@ -263,6 +285,28 @@
   }
 
   /**
+   * Constructs an event instance around the left stick button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the left stick button's digital signal attached to the
+   *     given loop.
+   */
+  public BooleanEvent leftStick(EventLoop loop) {
+    return new BooleanEvent(loop, this::getLeftStickButton);
+  }
+
+  /**
+   * Constructs an event instance around the right stick button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the right stick button's digital signal attached to the
+   *     given loop.
+   */
+  public BooleanEvent rightStick(EventLoop loop) {
+    return new BooleanEvent(loop, this::getRightStickButton);
+  }
+
+  /**
    * Read the value of the A button on the controller.
    *
    * @return The state of the button.
@@ -290,6 +334,18 @@
   }
 
   /**
+   * Constructs an event instance around the A button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the A button's digital signal attached to the given
+   *     loop.
+   */
+  @SuppressWarnings("MethodName")
+  public BooleanEvent a(EventLoop loop) {
+    return new BooleanEvent(loop, this::getAButton);
+  }
+
+  /**
    * Read the value of the B button on the controller.
    *
    * @return The state of the button.
@@ -317,6 +373,18 @@
   }
 
   /**
+   * Constructs an event instance around the B button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the B button's digital signal attached to the given
+   *     loop.
+   */
+  @SuppressWarnings("MethodName")
+  public BooleanEvent b(EventLoop loop) {
+    return new BooleanEvent(loop, this::getBButton);
+  }
+
+  /**
    * Read the value of the X button on the controller.
    *
    * @return The state of the button.
@@ -344,6 +412,18 @@
   }
 
   /**
+   * Constructs an event instance around the X button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the X button's digital signal attached to the given
+   *     loop.
+   */
+  @SuppressWarnings("MethodName")
+  public BooleanEvent x(EventLoop loop) {
+    return new BooleanEvent(loop, this::getXButton);
+  }
+
+  /**
    * Read the value of the Y button on the controller.
    *
    * @return The state of the button.
@@ -371,6 +451,18 @@
   }
 
   /**
+   * Constructs an event instance around the Y button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the Y button's digital signal attached to the given
+   *     loop.
+   */
+  @SuppressWarnings("MethodName")
+  public BooleanEvent y(EventLoop loop) {
+    return new BooleanEvent(loop, this::getYButton);
+  }
+
+  /**
    * Read the value of the back button on the controller.
    *
    * @return The state of the button.
@@ -398,6 +490,17 @@
   }
 
   /**
+   * Constructs an event instance around the back button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the back button's digital signal attached to the given
+   *     loop.
+   */
+  public BooleanEvent back(EventLoop loop) {
+    return new BooleanEvent(loop, this::getBackButton);
+  }
+
+  /**
    * Read the value of the start button on the controller.
    *
    * @return The state of the button.
@@ -423,4 +526,67 @@
   public boolean getStartButtonReleased() {
     return getRawButtonReleased(Button.kStart.value);
   }
+
+  /**
+   * Constructs an event instance around the start button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the start button's digital signal attached to the given
+   *     loop.
+   */
+  public BooleanEvent start(EventLoop loop) {
+    return new BooleanEvent(loop, this::getStartButton);
+  }
+
+  /**
+   * Constructs an event instance around the axis value of the right trigger. The returned trigger
+   * will be true when the axis value is greater than {@code threshold}.
+   *
+   * @param threshold the minimum axis value for the returned {@link BooleanEvent} to be true. This
+   *     value should be in the range [0, 1] where 0 is the unpressed state of the axis.
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance that is true when the right trigger's axis exceeds the provided
+   *     threshold, attached to the given event loop
+   */
+  public BooleanEvent leftTrigger(double threshold, EventLoop loop) {
+    return new BooleanEvent(loop, () -> getLeftTriggerAxis() > threshold);
+  }
+
+  /**
+   * Constructs an event instance around the axis value of the right trigger. The returned trigger
+   * will be true when the axis value is greater than 0.5.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance that is true when the right trigger's axis exceeds the provided
+   *     threshold, attached to the given event loop
+   */
+  public BooleanEvent leftTrigger(EventLoop loop) {
+    return leftTrigger(0.5, loop);
+  }
+
+  /**
+   * Constructs an event instance around the axis value of the right trigger. The returned trigger
+   * will be true when the axis value is greater than {@code threshold}.
+   *
+   * @param threshold the minimum axis value for the returned {@link BooleanEvent} to be true. This
+   *     value should be in the range [0, 1] where 0 is the unpressed state of the axis.
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance that is true when the right trigger's axis exceeds the provided
+   *     threshold, attached to the given event loop
+   */
+  public BooleanEvent rightTrigger(double threshold, EventLoop loop) {
+    return new BooleanEvent(loop, () -> getRightTriggerAxis() > threshold);
+  }
+
+  /**
+   * Constructs an event instance around the axis value of the right trigger. The returned trigger
+   * will be true when the axis value is greater than 0.5.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance that is true when the right trigger's axis exceeds the provided
+   *     threshold, attached to the given event loop
+   */
+  public BooleanEvent rightTrigger(EventLoop loop) {
+    return rightTrigger(0.5, loop);
+  }
 }
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/ExternalDirectionCounter.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/ExternalDirectionCounter.java
index e10274b..6828b9a 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/ExternalDirectionCounter.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/ExternalDirectionCounter.java
@@ -4,7 +4,7 @@
 
 package edu.wpi.first.wpilibj.counter;
 
-import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
 
 import edu.wpi.first.hal.CounterJNI;
 import edu.wpi.first.hal.FRCNetComm.tResourceType;
@@ -72,7 +72,7 @@
   }
 
   /**
-   * Sets to revese the counter direction.
+   * Sets to reverse the counter direction.
    *
    * @param reverseDirection True to reverse counting direction.
    */
@@ -95,7 +95,7 @@
   }
 
   @Override
-  public void close() throws Exception {
+  public void close() {
     SendableRegistry.remove(this);
     CounterJNI.freeCounter(m_handle);
     CounterJNI.suppressUnused(m_countSource);
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/Tachometer.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/Tachometer.java
index f83b255..5bd8e7e 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/Tachometer.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/Tachometer.java
@@ -4,7 +4,7 @@
 
 package edu.wpi.first.wpilibj.counter;
 
-import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
 
 import edu.wpi.first.hal.CounterJNI;
 import edu.wpi.first.hal.FRCNetComm.tResourceType;
@@ -52,7 +52,7 @@
   }
 
   @Override
-  public void close() throws Exception {
+  public void close() {
     SendableRegistry.remove(this);
     CounterJNI.freeCounter(m_handle);
     CounterJNI.suppressUnused(m_source);
@@ -77,7 +77,7 @@
     if (period == 0) {
       return 0;
     }
-    return period;
+    return 1 / period;
   }
 
   /**
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/UpDownCounter.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/UpDownCounter.java
index 81d504e..c89c118 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/UpDownCounter.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/UpDownCounter.java
@@ -21,8 +21,8 @@
  * digital input and down on an edge from another digital input.
  */
 public class UpDownCounter implements Sendable, AutoCloseable {
-  private DigitalSource m_upSource;
-  private DigitalSource m_downSource;
+  private final DigitalSource m_upSource;
+  private final DigitalSource m_downSource;
 
   private final int m_handle;
 
@@ -43,6 +43,8 @@
       CounterJNI.setCounterUpSource(
           m_handle, upSource.getPortHandleForRouting(), upSource.getAnalogTriggerTypeForRouting());
       CounterJNI.setCounterUpSourceEdge(m_handle, true, false);
+    } else {
+      m_upSource = null;
     }
 
     if (downSource != null) {
@@ -52,6 +54,8 @@
           downSource.getPortHandleForRouting(),
           downSource.getAnalogTriggerTypeForRouting());
       CounterJNI.setCounterDownSourceEdge(m_handle, true, false);
+    } else {
+      m_downSource = null;
     }
 
     reset();
@@ -62,7 +66,7 @@
   }
 
   @Override
-  public void close() throws Exception {
+  public void close() {
     SendableRegistry.remove(this);
     CounterJNI.freeCounter(m_handle);
     CounterJNI.suppressUnused(m_upSource);
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/DifferentialDrive.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/DifferentialDrive.java
index 6b2d1ee..4b12682 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/DifferentialDrive.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/DifferentialDrive.java
@@ -4,7 +4,7 @@
 
 package edu.wpi.first.wpilibj.drive;
 
-import static java.util.Objects.requireNonNull;
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
 
 import edu.wpi.first.hal.FRCNetComm.tInstances;
 import edu.wpi.first.hal.FRCNetComm.tResourceType;
@@ -13,7 +13,7 @@
 import edu.wpi.first.util.sendable.Sendable;
 import edu.wpi.first.util.sendable.SendableBuilder;
 import edu.wpi.first.util.sendable.SendableRegistry;
-import edu.wpi.first.wpilibj.SpeedController;
+import edu.wpi.first.wpilibj.motorcontrol.MotorController;
 
 /**
  * A class for driving differential drive/skid-steer drive platforms such as the Kit of Parts drive
@@ -70,27 +70,26 @@
  * |       |
  * </pre>
  *
- * <p>Each drive() function provides different inverse kinematic relations for a differential drive
- * robot. Motor outputs for the right side are negated, so motor direction inversion by the user is
- * usually unnecessary.
+ * <p>Each drive function provides different inverse kinematic relations for a differential drive
+ * robot.
  *
- * <p>This library uses the NED axes convention (North-East-Down as external reference in the world
- * frame): http://www.nuclearprojects.com/ins/images/axis_big.png.
- *
- * <p>The positive X axis points ahead, the positive Y axis points right, and the positive Z axis
- * points down. Rotations follow the right-hand rule, so clockwise rotation around the Z axis is
- * positive.
+ * <p>This library uses the NWU axes convention (North-West-Up as external reference in the world
+ * frame). The positive X axis points ahead, the positive Y axis points to the left, and the
+ * positive Z axis points up. Rotations follow the right-hand rule, so counterclockwise rotation
+ * around the Z axis is positive.
  *
  * <p>Inputs smaller then {@value edu.wpi.first.wpilibj.drive.RobotDriveBase#kDefaultDeadband} will
  * be set to 0, and larger values will be scaled so that the full range is still used. This deadband
  * value can be changed with {@link #setDeadband}.
+ *
+ * <p>{@link edu.wpi.first.wpilibj.MotorSafety} is enabled by default. The tankDrive, arcadeDrive,
+ * or curvatureDrive methods should be called periodically to avoid Motor Safety timeouts.
  */
-@SuppressWarnings("removal")
 public class DifferentialDrive extends RobotDriveBase implements Sendable, AutoCloseable {
   private static int instances;
 
-  private final SpeedController m_leftMotor;
-  private final SpeedController m_rightMotor;
+  private final MotorController m_leftMotor;
+  private final MotorController m_rightMotor;
 
   private boolean m_reported;
 
@@ -129,9 +128,9 @@
    * @param leftMotor Left motor.
    * @param rightMotor Right motor.
    */
-  public DifferentialDrive(SpeedController leftMotor, SpeedController rightMotor) {
-    requireNonNull(leftMotor, "Left motor cannot be null");
-    requireNonNull(rightMotor, "Right motor cannot be null");
+  public DifferentialDrive(MotorController leftMotor, MotorController rightMotor) {
+    requireNonNullParam(leftMotor, "leftMotor", "DifferentialDrive");
+    requireNonNullParam(rightMotor, "rightMotor", "DifferentialDrive");
 
     m_leftMotor = leftMotor;
     m_rightMotor = rightMotor;
@@ -151,10 +150,9 @@
    * decrease sensitivity at low speeds.
    *
    * @param xSpeed The robot's speed along the X axis [-1.0..1.0]. Forward is positive.
-   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Clockwise is
+   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Counterclockwise is
    *     positive.
    */
-  @SuppressWarnings("ParameterName")
   public void arcadeDrive(double xSpeed, double zRotation) {
     arcadeDrive(xSpeed, zRotation, true);
   }
@@ -163,11 +161,10 @@
    * Arcade drive method for differential drive platform.
    *
    * @param xSpeed The robot's speed along the X axis [-1.0..1.0]. Forward is positive.
-   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Clockwise is
+   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Counterclockwise is
    *     positive.
    * @param squareInputs If set, decreases the input sensitivity at low speeds.
    */
-  @SuppressWarnings("ParameterName")
   public void arcadeDrive(double xSpeed, double zRotation, boolean squareInputs) {
     if (!m_reported) {
       HAL.report(
@@ -193,11 +190,10 @@
    * heading change. This makes the robot more controllable at high speeds.
    *
    * @param xSpeed The robot's speed along the X axis [-1.0..1.0]. Forward is positive.
-   * @param zRotation The normalized curvature [-1.0..1.0]. Clockwise is positive.
+   * @param zRotation The normalized curvature [-1.0..1.0]. Counterclockwise is positive.
    * @param allowTurnInPlace If set, overrides constant-curvature turning for turn-in-place
    *     maneuvers. zRotation will control turning rate instead of curvature.
    */
-  @SuppressWarnings("ParameterName")
   public void curvatureDrive(double xSpeed, double zRotation, boolean allowTurnInPlace) {
     if (!m_reported) {
       HAL.report(
@@ -258,12 +254,11 @@
    * Arcade drive inverse kinematics for differential drive platform.
    *
    * @param xSpeed The robot's speed along the X axis [-1.0..1.0]. Forward is positive.
-   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Clockwise is
+   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Counterclockwise is
    *     positive.
    * @param squareInputs If set, decreases the input sensitivity at low speeds.
    * @return Wheel speeds [-1.0..1.0].
    */
-  @SuppressWarnings("ParameterName")
   public static WheelSpeeds arcadeDriveIK(double xSpeed, double zRotation, boolean squareInputs) {
     xSpeed = MathUtil.clamp(xSpeed, -1.0, 1.0);
     zRotation = MathUtil.clamp(zRotation, -1.0, 1.0);
@@ -275,37 +270,19 @@
       zRotation = Math.copySign(zRotation * zRotation, zRotation);
     }
 
-    double leftSpeed;
-    double rightSpeed;
+    double leftSpeed = xSpeed - zRotation;
+    double rightSpeed = xSpeed + zRotation;
 
-    double maxInput = Math.copySign(Math.max(Math.abs(xSpeed), Math.abs(zRotation)), xSpeed);
-
-    if (Double.compare(xSpeed, 0.0) >= 0) {
-      // First quadrant, else second quadrant
-      if (Double.compare(zRotation, 0.0) >= 0) {
-        leftSpeed = maxInput;
-        rightSpeed = xSpeed - zRotation;
-      } else {
-        leftSpeed = xSpeed + zRotation;
-        rightSpeed = maxInput;
-      }
-    } else {
-      // Third quadrant, else fourth quadrant
-      if (Double.compare(zRotation, 0.0) >= 0) {
-        leftSpeed = xSpeed + zRotation;
-        rightSpeed = maxInput;
-      } else {
-        leftSpeed = maxInput;
-        rightSpeed = xSpeed - zRotation;
-      }
+    // Find the maximum possible value of (throttle + turn) along the vector
+    // that the joystick is pointing, then desaturate the wheel speeds
+    double greaterInput = Math.max(Math.abs(xSpeed), Math.abs(zRotation));
+    double lesserInput = Math.min(Math.abs(xSpeed), Math.abs(zRotation));
+    if (greaterInput == 0.0) {
+      return new WheelSpeeds(0.0, 0.0);
     }
-
-    // Normalize the wheel speeds
-    double maxMagnitude = Math.max(Math.abs(leftSpeed), Math.abs(rightSpeed));
-    if (maxMagnitude > 1.0) {
-      leftSpeed /= maxMagnitude;
-      rightSpeed /= maxMagnitude;
-    }
+    double saturatedInput = (greaterInput + lesserInput) / greaterInput;
+    leftSpeed /= saturatedInput;
+    rightSpeed /= saturatedInput;
 
     return new WheelSpeeds(leftSpeed, rightSpeed);
   }
@@ -317,12 +294,11 @@
    * heading change. This makes the robot more controllable at high speeds.
    *
    * @param xSpeed The robot's speed along the X axis [-1.0..1.0]. Forward is positive.
-   * @param zRotation The normalized curvature [-1.0..1.0]. Clockwise is positive.
+   * @param zRotation The normalized curvature [-1.0..1.0]. Counterclockwise is positive.
    * @param allowTurnInPlace If set, overrides constant-curvature turning for turn-in-place
    *     maneuvers. zRotation will control rotation rate around the Z axis instead of curvature.
    * @return Wheel speeds [-1.0..1.0].
    */
-  @SuppressWarnings("ParameterName")
   public static WheelSpeeds curvatureDriveIK(
       double xSpeed, double zRotation, boolean allowTurnInPlace) {
     xSpeed = MathUtil.clamp(xSpeed, -1.0, 1.0);
@@ -332,14 +308,14 @@
     double rightSpeed;
 
     if (allowTurnInPlace) {
-      leftSpeed = xSpeed + zRotation;
-      rightSpeed = xSpeed - zRotation;
+      leftSpeed = xSpeed - zRotation;
+      rightSpeed = xSpeed + zRotation;
     } else {
-      leftSpeed = xSpeed + Math.abs(xSpeed) * zRotation;
-      rightSpeed = xSpeed - Math.abs(xSpeed) * zRotation;
+      leftSpeed = xSpeed - Math.abs(xSpeed) * zRotation;
+      rightSpeed = xSpeed + Math.abs(xSpeed) * zRotation;
     }
 
-    // Normalize wheel speeds
+    // Desaturate wheel speeds
     double maxMagnitude = Math.max(Math.abs(leftSpeed), Math.abs(rightSpeed));
     if (maxMagnitude > 1.0) {
       leftSpeed /= maxMagnitude;
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/KilloughDrive.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/KilloughDrive.java
deleted file mode 100644
index 9915c87..0000000
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/KilloughDrive.java
+++ /dev/null
@@ -1,312 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.drive;
-
-import static java.util.Objects.requireNonNull;
-
-import edu.wpi.first.hal.FRCNetComm.tInstances;
-import edu.wpi.first.hal.FRCNetComm.tResourceType;
-import edu.wpi.first.hal.HAL;
-import edu.wpi.first.math.MathUtil;
-import edu.wpi.first.util.sendable.Sendable;
-import edu.wpi.first.util.sendable.SendableBuilder;
-import edu.wpi.first.util.sendable.SendableRegistry;
-import edu.wpi.first.wpilibj.SpeedController;
-
-/**
- * A class for driving Killough drive platforms.
- *
- * <p>Killough drives are triangular with one omni wheel on each corner.
- *
- * <p>Drive base diagram:
- *
- * <pre>
- *  /_____\
- * / \   / \
- *    \ /
- *    ---
- * </pre>
- *
- * <p>Each drive() function provides different inverse kinematic relations for a Killough drive. The
- * default wheel vectors are parallel to their respective opposite sides, but can be overridden. See
- * the constructor for more information.
- *
- * <p>This library uses the NED axes convention (North-East-Down as external reference in the world
- * frame): http://www.nuclearprojects.com/ins/images/axis_big.png.
- *
- * <p>The positive X axis points ahead, the positive Y axis points right, and the positive Z axis
- * points down. Rotations follow the right-hand rule, so clockwise rotation around the Z axis is
- * positive.
- */
-@SuppressWarnings("removal")
-public class KilloughDrive extends RobotDriveBase implements Sendable, AutoCloseable {
-  public static final double kDefaultLeftMotorAngle = 60.0;
-  public static final double kDefaultRightMotorAngle = 120.0;
-  public static final double kDefaultBackMotorAngle = 270.0;
-
-  private static int instances;
-
-  private SpeedController m_leftMotor;
-  private SpeedController m_rightMotor;
-  private SpeedController m_backMotor;
-
-  private Vector2d m_leftVec;
-  private Vector2d m_rightVec;
-  private Vector2d m_backVec;
-
-  private boolean m_reported;
-
-  /**
-   * Wheel speeds for a Killough drive.
-   *
-   * <p>Uses normalized voltage [-1.0..1.0].
-   */
-  @SuppressWarnings("MemberName")
-  public static class WheelSpeeds {
-    public double left;
-    public double right;
-    public double back;
-
-    /** Constructs a WheelSpeeds with zeroes for left, right, and back speeds. */
-    public WheelSpeeds() {}
-
-    /**
-     * Constructs a WheelSpeeds.
-     *
-     * @param left The left speed [-1.0..1.0].
-     * @param right The right speed [-1.0..1.0].
-     * @param back The back speed [-1.0..1.0].
-     */
-    public WheelSpeeds(double left, double right, double back) {
-      this.left = left;
-      this.right = right;
-      this.back = back;
-    }
-  }
-
-  /**
-   * Construct a Killough drive with the given motors and default motor angles.
-   *
-   * <p>The default motor angles make the wheels on each corner parallel to their respective
-   * opposite sides.
-   *
-   * <p>If a motor needs to be inverted, do so before passing it in.
-   *
-   * @param leftMotor The motor on the left corner.
-   * @param rightMotor The motor on the right corner.
-   * @param backMotor The motor on the back corner.
-   */
-  public KilloughDrive(
-      SpeedController leftMotor, SpeedController rightMotor, SpeedController backMotor) {
-    this(
-        leftMotor,
-        rightMotor,
-        backMotor,
-        kDefaultLeftMotorAngle,
-        kDefaultRightMotorAngle,
-        kDefaultBackMotorAngle);
-  }
-
-  /**
-   * Construct a Killough drive with the given motors.
-   *
-   * <p>Angles are measured in degrees clockwise from the positive X axis.
-   *
-   * @param leftMotor The motor on the left corner.
-   * @param rightMotor The motor on the right corner.
-   * @param backMotor The motor on the back corner.
-   * @param leftMotorAngle The angle of the left wheel's forward direction of travel.
-   * @param rightMotorAngle The angle of the right wheel's forward direction of travel.
-   * @param backMotorAngle The angle of the back wheel's forward direction of travel.
-   */
-  public KilloughDrive(
-      SpeedController leftMotor,
-      SpeedController rightMotor,
-      SpeedController backMotor,
-      double leftMotorAngle,
-      double rightMotorAngle,
-      double backMotorAngle) {
-    requireNonNull(leftMotor, "Left motor cannot be null");
-    requireNonNull(rightMotor, "Right motor cannot be null");
-    requireNonNull(backMotor, "Back motor cannot be null");
-
-    m_leftMotor = leftMotor;
-    m_rightMotor = rightMotor;
-    m_backMotor = backMotor;
-    m_leftVec =
-        new Vector2d(
-            Math.cos(leftMotorAngle * (Math.PI / 180.0)),
-            Math.sin(leftMotorAngle * (Math.PI / 180.0)));
-    m_rightVec =
-        new Vector2d(
-            Math.cos(rightMotorAngle * (Math.PI / 180.0)),
-            Math.sin(rightMotorAngle * (Math.PI / 180.0)));
-    m_backVec =
-        new Vector2d(
-            Math.cos(backMotorAngle * (Math.PI / 180.0)),
-            Math.sin(backMotorAngle * (Math.PI / 180.0)));
-    SendableRegistry.addChild(this, m_leftMotor);
-    SendableRegistry.addChild(this, m_rightMotor);
-    SendableRegistry.addChild(this, m_backMotor);
-    instances++;
-    SendableRegistry.addLW(this, "KilloughDrive", instances);
-  }
-
-  @Override
-  public void close() {
-    SendableRegistry.remove(this);
-  }
-
-  /**
-   * Drive method for Killough platform.
-   *
-   * <p>Angles are measured clockwise from the positive X axis. The robot's speed is independent
-   * from its angle or rotation rate.
-   *
-   * @param ySpeed The robot's speed along the Y axis [-1.0..1.0]. Right is positive.
-   * @param xSpeed The robot's speed along the X axis [-1.0..1.0]. Forward is positive.
-   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Clockwise is
-   *     positive.
-   */
-  @SuppressWarnings("ParameterName")
-  public void driveCartesian(double ySpeed, double xSpeed, double zRotation) {
-    driveCartesian(ySpeed, xSpeed, zRotation, 0.0);
-  }
-
-  /**
-   * Drive method for Killough platform.
-   *
-   * <p>Angles are measured clockwise from the positive X axis. The robot's speed is independent
-   * from its angle or rotation rate.
-   *
-   * @param ySpeed The robot's speed along the Y axis [-1.0..1.0]. Right is positive.
-   * @param xSpeed The robot's speed along the X axis [-1.0..1.0]. Forward is positive.
-   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Clockwise is
-   *     positive.
-   * @param gyroAngle The current angle reading from the gyro in degrees around the Z axis. Use this
-   *     to implement field-oriented controls.
-   */
-  @SuppressWarnings("ParameterName")
-  public void driveCartesian(double ySpeed, double xSpeed, double zRotation, double gyroAngle) {
-    if (!m_reported) {
-      HAL.report(
-          tResourceType.kResourceType_RobotDrive, tInstances.kRobotDrive2_KilloughCartesian, 3);
-      m_reported = true;
-    }
-
-    ySpeed = MathUtil.applyDeadband(ySpeed, m_deadband);
-    xSpeed = MathUtil.applyDeadband(xSpeed, m_deadband);
-
-    var speeds = driveCartesianIK(ySpeed, xSpeed, zRotation, gyroAngle);
-
-    m_leftMotor.set(speeds.left * m_maxOutput);
-    m_rightMotor.set(speeds.right * m_maxOutput);
-    m_backMotor.set(speeds.back * m_maxOutput);
-
-    feed();
-  }
-
-  /**
-   * Drive method for Killough platform.
-   *
-   * <p>Angles are measured counter-clockwise from straight ahead. The speed at which the robot
-   * drives (translation) is independent from its angle or rotation rate.
-   *
-   * @param magnitude The robot's speed at a given angle [-1.0..1.0]. Forward is positive.
-   * @param angle The angle around the Z axis at which the robot drives in degrees [-180..180].
-   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Clockwise is
-   *     positive.
-   */
-  @SuppressWarnings("ParameterName")
-  public void drivePolar(double magnitude, double angle, double zRotation) {
-    if (!m_reported) {
-      HAL.report(tResourceType.kResourceType_RobotDrive, tInstances.kRobotDrive2_KilloughPolar, 3);
-      m_reported = true;
-    }
-
-    driveCartesian(
-        magnitude * Math.sin(angle * (Math.PI / 180.0)),
-        magnitude * Math.cos(angle * (Math.PI / 180.0)),
-        zRotation,
-        0.0);
-  }
-
-  /**
-   * Cartesian inverse kinematics for Killough platform.
-   *
-   * <p>Angles are measured clockwise from the positive X axis. The robot's speed is independent
-   * from its angle or rotation rate.
-   *
-   * @param ySpeed The robot's speed along the Y axis [-1.0..1.0]. Right is positive.
-   * @param xSpeed The robot's speed along the X axis [-1.0..1.0]. Forward is positive.
-   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Clockwise is
-   *     positive.
-   * @return Wheel speeds [-1.0..1.0].
-   */
-  @SuppressWarnings("ParameterName")
-  public WheelSpeeds driveCartesianIK(double ySpeed, double xSpeed, double zRotation) {
-    return driveCartesianIK(ySpeed, xSpeed, zRotation, 0.0);
-  }
-
-  /**
-   * Cartesian inverse kinematics for Killough platform.
-   *
-   * <p>Angles are measured clockwise from the positive X axis. The robot's speed is independent
-   * from its angle or rotation rate.
-   *
-   * @param ySpeed The robot's speed along the Y axis [-1.0..1.0]. Right is positive.
-   * @param xSpeed The robot's speed along the X axis [-1.0..1.0]. Forward is positive.
-   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Clockwise is
-   *     positive.
-   * @param gyroAngle The current angle reading from the gyro in degrees around the Z axis. Use this
-   *     to implement field-oriented controls.
-   * @return Wheel speeds [-1.0..1.0].
-   */
-  @SuppressWarnings("ParameterName")
-  public WheelSpeeds driveCartesianIK(
-      double ySpeed, double xSpeed, double zRotation, double gyroAngle) {
-    ySpeed = MathUtil.clamp(ySpeed, -1.0, 1.0);
-    xSpeed = MathUtil.clamp(xSpeed, -1.0, 1.0);
-
-    // Compensate for gyro angle.
-    Vector2d input = new Vector2d(ySpeed, xSpeed);
-    input.rotate(-gyroAngle);
-
-    double[] wheelSpeeds = new double[3];
-    wheelSpeeds[MotorType.kLeft.value] = input.scalarProject(m_leftVec) + zRotation;
-    wheelSpeeds[MotorType.kRight.value] = input.scalarProject(m_rightVec) + zRotation;
-    wheelSpeeds[MotorType.kBack.value] = input.scalarProject(m_backVec) + zRotation;
-
-    normalize(wheelSpeeds);
-
-    return new WheelSpeeds(
-        wheelSpeeds[MotorType.kLeft.value],
-        wheelSpeeds[MotorType.kRight.value],
-        wheelSpeeds[MotorType.kBack.value]);
-  }
-
-  @Override
-  public void stopMotor() {
-    m_leftMotor.stopMotor();
-    m_rightMotor.stopMotor();
-    m_backMotor.stopMotor();
-    feed();
-  }
-
-  @Override
-  public String getDescription() {
-    return "KilloughDrive";
-  }
-
-  @Override
-  public void initSendable(SendableBuilder builder) {
-    builder.setSmartDashboardType("KilloughDrive");
-    builder.setActuator(true);
-    builder.setSafeState(this::stopMotor);
-    builder.addDoubleProperty("Left Motor Speed", m_leftMotor::get, m_leftMotor::set);
-    builder.addDoubleProperty("Right Motor Speed", m_rightMotor::get, m_rightMotor::set);
-    builder.addDoubleProperty("Back Motor Speed", m_backMotor::get, m_backMotor::set);
-  }
-}
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java
index d22593f..1ee160c 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java
@@ -4,16 +4,18 @@
 
 package edu.wpi.first.wpilibj.drive;
 
-import static java.util.Objects.requireNonNull;
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
 
 import edu.wpi.first.hal.FRCNetComm.tInstances;
 import edu.wpi.first.hal.FRCNetComm.tResourceType;
 import edu.wpi.first.hal.HAL;
 import edu.wpi.first.math.MathUtil;
+import edu.wpi.first.math.geometry.Rotation2d;
+import edu.wpi.first.math.geometry.Translation2d;
 import edu.wpi.first.util.sendable.Sendable;
 import edu.wpi.first.util.sendable.SendableBuilder;
 import edu.wpi.first.util.sendable.SendableRegistry;
-import edu.wpi.first.wpilibj.SpeedController;
+import edu.wpi.first.wpilibj.motorcontrol.MotorController;
 
 /**
  * A class for driving Mecanum drive platforms.
@@ -36,9 +38,10 @@
  * <p>Each drive() function provides different inverse kinematic relations for a Mecanum drive
  * robot.
  *
- * <p>The positive Y axis points ahead, the positive X axis points right, and the positive Z axis
- * points down. Rotations follow the right-hand rule, so clockwise rotation around the Z axis is
- * positive.
+ * <p>This library uses the NWU axes convention (North-West-Up as external reference in the world
+ * frame). The positive X axis points ahead, the positive Y axis points to the left, and the
+ * positive Z axis points up. Rotations follow the right-hand rule, so counterclockwise rotation
+ * around the Z axis is positive.
  *
  * <p>Note: the axis conventions used in this class differ from DifferentialDrive. This may change
  * in a future year's WPILib release.
@@ -47,22 +50,16 @@
  * be set to 0, and larger values will be scaled so that the full range is still used. This deadband
  * value can be changed with {@link #setDeadband}.
  *
- * <p>RobotDrive porting guide: <br>
- * {@link #driveCartesian(double, double, double, double)} is equivalent to RobotDrive's
- * mecanumDrive_Cartesian(double, double, double, double) if a deadband of 0 is used, and the ySpeed
- * and gyroAngle values are inverted compared to RobotDrive (eg driveCartesian(xSpeed, -ySpeed,
- * zRotation, -gyroAngle). <br>
- * {@link #drivePolar(double, double, double)} is equivalent to RobotDrive's
- * mecanumDrive_Polar(double, double, double)} if a deadband of 0 is used.
+ * <p>{@link edu.wpi.first.wpilibj.MotorSafety} is enabled by default. The driveCartesian or
+ * drivePolar methods should be called periodically to avoid Motor Safety timeouts.
  */
-@SuppressWarnings("removal")
 public class MecanumDrive extends RobotDriveBase implements Sendable, AutoCloseable {
   private static int instances;
 
-  private final SpeedController m_frontLeftMotor;
-  private final SpeedController m_rearLeftMotor;
-  private final SpeedController m_frontRightMotor;
-  private final SpeedController m_rearRightMotor;
+  private final MotorController m_frontLeftMotor;
+  private final MotorController m_rearLeftMotor;
+  private final MotorController m_frontRightMotor;
+  private final MotorController m_rearRightMotor;
 
   private boolean m_reported;
 
@@ -108,14 +105,14 @@
    * @param rearRightMotor The motor on the rear-right corner.
    */
   public MecanumDrive(
-      SpeedController frontLeftMotor,
-      SpeedController rearLeftMotor,
-      SpeedController frontRightMotor,
-      SpeedController rearRightMotor) {
-    requireNonNull(frontLeftMotor, "Front-left motor cannot be null");
-    requireNonNull(rearLeftMotor, "Rear-left motor cannot be null");
-    requireNonNull(frontRightMotor, "Front-right motor cannot be null");
-    requireNonNull(rearRightMotor, "Rear-right motor cannot be null");
+      MotorController frontLeftMotor,
+      MotorController rearLeftMotor,
+      MotorController frontRightMotor,
+      MotorController rearRightMotor) {
+    requireNonNullParam(frontLeftMotor, "frontLeftMotor", "MecanumDrive");
+    requireNonNullParam(rearLeftMotor, "rearLeftMotor", "MecanumDrive");
+    requireNonNullParam(frontRightMotor, "frontRightMotor", "MecanumDrive");
+    requireNonNullParam(rearRightMotor, "rearRightMotor", "MecanumDrive");
 
     m_frontLeftMotor = frontLeftMotor;
     m_rearLeftMotor = rearLeftMotor;
@@ -137,44 +134,42 @@
   /**
    * Drive method for Mecanum platform.
    *
-   * <p>Angles are measured clockwise from the positive X axis. The robot's speed is independent
-   * from its angle or rotation rate.
+   * <p>Angles are measured counterclockwise from the positive X axis. The robot's speed is
+   * independent of its angle or rotation rate.
    *
-   * @param ySpeed The robot's speed along the Y axis [-1.0..1.0]. Forward is positive.
-   * @param xSpeed The robot's speed along the X axis [-1.0..1.0]. Right is positive.
-   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Clockwise is
+   * @param xSpeed The robot's speed along the X axis [-1.0..1.0]. Forward is positive.
+   * @param ySpeed The robot's speed along the Y axis [-1.0..1.0]. Left is positive.
+   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Counterclockwise is
    *     positive.
    */
-  @SuppressWarnings("ParameterName")
-  public void driveCartesian(double ySpeed, double xSpeed, double zRotation) {
-    driveCartesian(ySpeed, xSpeed, zRotation, 0.0);
+  public void driveCartesian(double xSpeed, double ySpeed, double zRotation) {
+    driveCartesian(xSpeed, ySpeed, zRotation, new Rotation2d());
   }
 
   /**
    * Drive method for Mecanum platform.
    *
-   * <p>Angles are measured clockwise from the positive X axis. The robot's speed is independent
-   * from its angle or rotation rate.
+   * <p>Angles are measured counterclockwise from the positive X axis. The robot's speed is
+   * independent of its angle or rotation rate.
    *
-   * @param ySpeed The robot's speed along the Y axis [-1.0..1.0]. Forward is positive.
-   * @param xSpeed The robot's speed along the X axis [-1.0..1.0]. Right is positive.
-   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Clockwise is
+   * @param xSpeed The robot's speed along the Y axis [-1.0..1.0]. Forward is positive.
+   * @param ySpeed The robot's speed along the X axis [-1.0..1.0]. Left is positive.
+   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Counterclockwise is
    *     positive.
-   * @param gyroAngle The current angle reading from the gyro in degrees around the Z axis. Use this
-   *     to implement field-oriented controls.
+   * @param gyroAngle The gyro heading around the Z axis. Use this to implement field-oriented
+   *     controls.
    */
-  @SuppressWarnings("ParameterName")
-  public void driveCartesian(double ySpeed, double xSpeed, double zRotation, double gyroAngle) {
+  public void driveCartesian(double xSpeed, double ySpeed, double zRotation, Rotation2d gyroAngle) {
     if (!m_reported) {
       HAL.report(
           tResourceType.kResourceType_RobotDrive, tInstances.kRobotDrive2_MecanumCartesian, 4);
       m_reported = true;
     }
 
-    ySpeed = MathUtil.applyDeadband(ySpeed, m_deadband);
     xSpeed = MathUtil.applyDeadband(xSpeed, m_deadband);
+    ySpeed = MathUtil.applyDeadband(ySpeed, m_deadband);
 
-    var speeds = driveCartesianIK(ySpeed, xSpeed, zRotation, gyroAngle);
+    var speeds = driveCartesianIK(xSpeed, ySpeed, zRotation, gyroAngle);
 
     m_frontLeftMotor.set(speeds.frontLeft * m_maxOutput);
     m_frontRightMotor.set(speeds.frontRight * m_maxOutput);
@@ -187,74 +182,67 @@
   /**
    * Drive method for Mecanum platform.
    *
-   * <p>Angles are measured counter-clockwise from straight ahead. The speed at which the robot
-   * drives (translation) is independent from its angle or rotation rate.
+   * <p>Angles are measured counterclockwise from straight ahead. The speed at which the robot
+   * drives (translation) is independent of its angle or rotation rate.
    *
    * @param magnitude The robot's speed at a given angle [-1.0..1.0]. Forward is positive.
-   * @param angle The angle around the Z axis at which the robot drives in degrees [-180..180].
-   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Clockwise is
+   * @param angle The gyro heading around the Z axis at which the robot drives.
+   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Counterclockwise is
    *     positive.
    */
-  @SuppressWarnings("ParameterName")
-  public void drivePolar(double magnitude, double angle, double zRotation) {
+  public void drivePolar(double magnitude, Rotation2d angle, double zRotation) {
     if (!m_reported) {
       HAL.report(tResourceType.kResourceType_RobotDrive, tInstances.kRobotDrive2_MecanumPolar, 4);
       m_reported = true;
     }
 
     driveCartesian(
-        magnitude * Math.cos(angle * (Math.PI / 180.0)),
-        magnitude * Math.sin(angle * (Math.PI / 180.0)),
-        zRotation,
-        0.0);
+        magnitude * angle.getCos(), magnitude * angle.getSin(), zRotation, new Rotation2d());
   }
 
   /**
    * Cartesian inverse kinematics for Mecanum platform.
    *
-   * <p>Angles are measured clockwise from the positive X axis. The robot's speed is independent
-   * from its angle or rotation rate.
+   * <p>Angles are measured counterclockwise from the positive X axis. The robot's speed is
+   * independent of its angle or rotation rate.
    *
-   * @param ySpeed The robot's speed along the Y axis [-1.0..1.0]. Forward is positive.
-   * @param xSpeed The robot's speed along the X axis [-1.0..1.0]. Right is positive.
-   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Clockwise is
+   * @param xSpeed The robot's speed along the X axis [-1.0..1.0]. Forward is positive.
+   * @param ySpeed The robot's speed along the Y axis [-1.0..1.0]. Left is positive.
+   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Counterclockwise is
    *     positive.
    * @return Wheel speeds [-1.0..1.0].
    */
-  @SuppressWarnings("ParameterName")
-  public static WheelSpeeds driveCartesianIK(double ySpeed, double xSpeed, double zRotation) {
-    return driveCartesianIK(ySpeed, xSpeed, zRotation, 0.0);
+  public static WheelSpeeds driveCartesianIK(double xSpeed, double ySpeed, double zRotation) {
+    return driveCartesianIK(xSpeed, ySpeed, zRotation, new Rotation2d());
   }
 
   /**
    * Cartesian inverse kinematics for Mecanum platform.
    *
-   * <p>Angles are measured clockwise from the positive X axis. The robot's speed is independent
-   * from its angle or rotation rate.
+   * <p>Angles are measured clockwise from the positive X axis. The robot's speed is independent of
+   * its angle or rotation rate.
    *
-   * @param ySpeed The robot's speed along the Y axis [-1.0..1.0]. Forward is positive.
-   * @param xSpeed The robot's speed along the X axis [-1.0..1.0]. Right is positive.
-   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Clockwise is
+   * @param xSpeed The robot's speed along the X axis [-1.0..1.0]. Forward is positive.
+   * @param ySpeed The robot's speed along the Y axis [-1.0..1.0]. Left is positive.
+   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Counterclockwise is
    *     positive.
-   * @param gyroAngle The current angle reading from the gyro in degrees around the Z axis. Use this
-   *     to implement field-oriented controls.
+   * @param gyroAngle The gyro heading around the Z axis. Use this to implement field-oriented
+   *     controls.
    * @return Wheel speeds [-1.0..1.0].
    */
-  @SuppressWarnings("ParameterName")
   public static WheelSpeeds driveCartesianIK(
-      double ySpeed, double xSpeed, double zRotation, double gyroAngle) {
-    ySpeed = MathUtil.clamp(ySpeed, -1.0, 1.0);
+      double xSpeed, double ySpeed, double zRotation, Rotation2d gyroAngle) {
     xSpeed = MathUtil.clamp(xSpeed, -1.0, 1.0);
+    ySpeed = MathUtil.clamp(ySpeed, -1.0, 1.0);
 
     // Compensate for gyro angle.
-    Vector2d input = new Vector2d(ySpeed, xSpeed);
-    input.rotate(-gyroAngle);
+    var input = new Translation2d(xSpeed, ySpeed).rotateBy(gyroAngle.unaryMinus());
 
     double[] wheelSpeeds = new double[4];
-    wheelSpeeds[MotorType.kFrontLeft.value] = input.x + input.y + zRotation;
-    wheelSpeeds[MotorType.kFrontRight.value] = input.x - input.y - zRotation;
-    wheelSpeeds[MotorType.kRearLeft.value] = input.x - input.y + zRotation;
-    wheelSpeeds[MotorType.kRearRight.value] = input.x + input.y - zRotation;
+    wheelSpeeds[MotorType.kFrontLeft.value] = input.getX() + input.getY() + zRotation;
+    wheelSpeeds[MotorType.kFrontRight.value] = input.getX() - input.getY() - zRotation;
+    wheelSpeeds[MotorType.kRearLeft.value] = input.getX() - input.getY() + zRotation;
+    wheelSpeeds[MotorType.kRearRight.value] = input.getX() + input.getY() - zRotation;
 
     normalize(wheelSpeeds);
 
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/RobotDriveBase.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/RobotDriveBase.java
index 569f94c..c4e931d 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/RobotDriveBase.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/RobotDriveBase.java
@@ -4,10 +4,13 @@
 
 package edu.wpi.first.wpilibj.drive;
 
-import edu.wpi.first.math.MathUtil;
 import edu.wpi.first.wpilibj.MotorSafety;
 
-/** Common base class for drive platforms. */
+/**
+ * Common base class for drive platforms.
+ *
+ * <p>{@link edu.wpi.first.wpilibj.MotorSafety} is enabled by default.
+ */
 public abstract class RobotDriveBase extends MotorSafety {
   public static final double kDefaultDeadband = 0.02;
   public static final double kDefaultMaxOutput = 1.0;
@@ -78,20 +81,6 @@
   public abstract String getDescription();
 
   /**
-   * Returns 0.0 if the given value is within the specified range around zero. The remaining range
-   * between the deadband and 1.0 is scaled from 0.0 to 1.0.
-   *
-   * @param value value to clip
-   * @param deadband range around zero
-   * @return The value after the deadband is applied.
-   * @deprecated Use MathUtil.applyDeadband(double,double).
-   */
-  @Deprecated(since = "2021", forRemoval = true)
-  protected static double applyDeadband(double value, double deadband) {
-    return MathUtil.applyDeadband(value, deadband);
-  }
-
-  /**
    * Normalize all wheel speeds if the magnitude of any wheel is greater than 1.0.
    *
    * @param wheelSpeeds List of wheel speeds to normalize.
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/Vector2d.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/Vector2d.java
deleted file mode 100644
index 728cc83..0000000
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/Vector2d.java
+++ /dev/null
@@ -1,65 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.drive;
-
-/** This is a 2D vector struct that supports basic vector operations. */
-public class Vector2d {
-  @SuppressWarnings("MemberName")
-  public double x;
-
-  @SuppressWarnings("MemberName")
-  public double y;
-
-  public Vector2d() {}
-
-  public Vector2d(double x, double y) {
-    this.x = x;
-    this.y = y;
-  }
-
-  /**
-   * Rotate a vector in Cartesian space.
-   *
-   * @param angle angle in degrees by which to rotate vector counter-clockwise.
-   */
-  public void rotate(double angle) {
-    double cosA = Math.cos(angle * (Math.PI / 180.0));
-    double sinA = Math.sin(angle * (Math.PI / 180.0));
-    double[] out = new double[2];
-    out[0] = x * cosA - y * sinA;
-    out[1] = x * sinA + y * cosA;
-    x = out[0];
-    y = out[1];
-  }
-
-  /**
-   * Returns dot product of this vector with argument.
-   *
-   * @param vec Vector with which to perform dot product.
-   * @return Dot product of this vector with argument.
-   */
-  public double dot(Vector2d vec) {
-    return x * vec.x + y * vec.y;
-  }
-
-  /**
-   * Returns magnitude of vector.
-   *
-   * @return Magnitude of vector.
-   */
-  public double magnitude() {
-    return Math.sqrt(x * x + y * y);
-  }
-
-  /**
-   * Returns scalar projection of this vector onto argument.
-   *
-   * @param vec Vector onto which to project this vector.
-   * @return scalar projection of this vector onto argument.
-   */
-  public double scalarProject(Vector2d vec) {
-    return dot(vec) / vec.magnitude();
-  }
-}
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/event/BooleanEvent.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/event/BooleanEvent.java
new file mode 100644
index 0000000..a810006
--- /dev/null
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/event/BooleanEvent.java
@@ -0,0 +1,189 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj.event;
+
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
+
+import edu.wpi.first.math.filter.Debouncer;
+import java.util.function.BiFunction;
+import java.util.function.BooleanSupplier;
+
+/**
+ * This class provides an easy way to link actions to high-active logic signals. Each object
+ * represents a digital signal to which callback actions can be bound using {@link
+ * #ifHigh(Runnable)}.
+ *
+ * <p>These signals can easily be composed for advanced functionality using {@link
+ * #and(BooleanSupplier)}, {@link #or(BooleanSupplier)}, {@link #negate()} etc.
+ *
+ * <p>To get an event that activates only when this one changes, see {@link #falling()} and {@link
+ * #rising()}.
+ */
+public class BooleanEvent implements BooleanSupplier {
+  /** Poller loop. */
+  protected final EventLoop m_loop;
+  /** Condition. */
+  private final BooleanSupplier m_signal;
+
+  /**
+   * Creates a new event with the given signal determining whether it is active.
+   *
+   * @param loop the loop that polls this event
+   * @param signal the digital signal represented by this object.
+   */
+  public BooleanEvent(EventLoop loop, BooleanSupplier signal) {
+    m_loop = requireNonNullParam(loop, "loop", "BooleanEvent");
+    m_signal = requireNonNullParam(signal, "signal", "BooleanEvent");
+  }
+
+  /**
+   * Check the state of this signal (high or low).
+   *
+   * @return true for the high state, false for the low state.
+   */
+  @Override
+  public final boolean getAsBoolean() {
+    return m_signal.getAsBoolean();
+  }
+
+  /**
+   * Bind an action to this event.
+   *
+   * @param action the action to run if this event is active.
+   */
+  public final void ifHigh(Runnable action) {
+    m_loop.bind(
+        () -> {
+          if (m_signal.getAsBoolean()) {
+            action.run();
+          }
+        });
+  }
+
+  /**
+   * Get a new event that events only when this one newly changes to true.
+   *
+   * @return a new event representing when this one newly changes to true.
+   */
+  public BooleanEvent rising() {
+    return new BooleanEvent(
+        m_loop,
+        new BooleanSupplier() {
+          private boolean m_previous = m_signal.getAsBoolean();
+
+          @Override
+          public boolean getAsBoolean() {
+            boolean present = m_signal.getAsBoolean();
+            boolean ret = !m_previous && present;
+            m_previous = present;
+            return ret;
+          }
+        });
+  }
+
+  /**
+   * Get a new event that triggers only when this one newly changes to false.
+   *
+   * @return a new event representing when this one newly changes to false.
+   */
+  public BooleanEvent falling() {
+    return new BooleanEvent(
+        m_loop,
+        new BooleanSupplier() {
+          private boolean m_previous = m_signal.getAsBoolean();
+
+          @Override
+          public boolean getAsBoolean() {
+            boolean present = m_signal.getAsBoolean();
+            boolean ret = m_previous && !present;
+            m_previous = present;
+            return ret;
+          }
+        });
+  }
+
+  /**
+   * Creates a new debounced event from this event - it will become active when this event has been
+   * active for longer than the specified period.
+   *
+   * @param seconds The debounce period.
+   * @return The debounced event (rising edges debounced only)
+   */
+  public BooleanEvent debounce(double seconds) {
+    return debounce(seconds, Debouncer.DebounceType.kRising);
+  }
+
+  /**
+   * Creates a new debounced event from this event - it will become active when this event has been
+   * active for longer than the specified period.
+   *
+   * @param seconds The debounce period.
+   * @param type The debounce type.
+   * @return The debounced event.
+   */
+  public BooleanEvent debounce(double seconds, Debouncer.DebounceType type) {
+    return new BooleanEvent(
+        m_loop,
+        new BooleanSupplier() {
+          private final Debouncer m_debouncer = new Debouncer(seconds, type);
+
+          @Override
+          public boolean getAsBoolean() {
+            return m_debouncer.calculate(m_signal.getAsBoolean());
+          }
+        });
+  }
+
+  /**
+   * Creates a new event that is active when this event is inactive, i.e. that acts as the negation
+   * of this event.
+   *
+   * @return the negated event
+   */
+  public BooleanEvent negate() {
+    return new BooleanEvent(m_loop, () -> !m_signal.getAsBoolean());
+  }
+
+  /**
+   * Composes this event with another event, returning a new signal that is in the high state when
+   * both signals are in the high state.
+   *
+   * <p>The new event will use this event's polling loop.
+   *
+   * @param other the event to compose with
+   * @return the event that is active when both events are active
+   */
+  public BooleanEvent and(BooleanSupplier other) {
+    requireNonNullParam(other, "other", "and");
+    return new BooleanEvent(m_loop, () -> m_signal.getAsBoolean() && other.getAsBoolean());
+  }
+
+  /**
+   * Composes this event with another event, returning a new signal that is high when either signal
+   * is high.
+   *
+   * <p>The new event will use this event's polling loop.
+   *
+   * @param other the event to compose with
+   * @return a signal that is high when either signal is high.
+   */
+  public BooleanEvent or(BooleanSupplier other) {
+    requireNonNullParam(other, "other", "or");
+    return new BooleanEvent(m_loop, () -> m_signal.getAsBoolean() || other.getAsBoolean());
+  }
+
+  /**
+   * A method to "downcast" a BooleanEvent instance to a subclass (for example, to a command-based
+   * version of this class).
+   *
+   * @param ctor a method reference to the constructor of the subclass that accepts the loop as the
+   *     first parameter and the condition/signal as the second.
+   * @param <T> the subclass type
+   * @return an instance of the subclass.
+   */
+  public <T extends BooleanSupplier> T castTo(BiFunction<EventLoop, BooleanSupplier, T> ctor) {
+    return ctor.apply(m_loop, m_signal);
+  }
+}
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/event/EventLoop.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/event/EventLoop.java
new file mode 100644
index 0000000..3e92c01
--- /dev/null
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/event/EventLoop.java
@@ -0,0 +1,32 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj.event;
+
+import java.util.Collection;
+import java.util.LinkedHashSet;
+
+/** The loop polling {@link BooleanEvent} objects and executing the actions bound to them. */
+public final class EventLoop {
+  private final Collection<Runnable> m_bindings = new LinkedHashSet<>();
+
+  /**
+   * Bind a new action to run whenever the condition is true.
+   *
+   * @param action the action to run.
+   */
+  public void bind(Runnable action) {
+    m_bindings.add(action);
+  }
+
+  /** Poll all bindings. */
+  public void poll() {
+    m_bindings.forEach(Runnable::run);
+  }
+
+  /** Clear all bindings. */
+  public void clear() {
+    m_bindings.clear();
+  }
+}
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/event/NetworkBooleanEvent.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/event/NetworkBooleanEvent.java
new file mode 100644
index 0000000..a322883
--- /dev/null
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/event/NetworkBooleanEvent.java
@@ -0,0 +1,71 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj.event;
+
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
+
+import edu.wpi.first.networktables.BooleanSubscriber;
+import edu.wpi.first.networktables.BooleanTopic;
+import edu.wpi.first.networktables.NetworkTable;
+import edu.wpi.first.networktables.NetworkTableInstance;
+
+/** This class provides an easy way to link NetworkTables boolean topics to callback actions. */
+public class NetworkBooleanEvent extends BooleanEvent {
+  /**
+   * Creates a new event with the given boolean topic determining whether it is active.
+   *
+   * @param loop the loop that polls this event
+   * @param topic The boolean topic that contains the value
+   */
+  public NetworkBooleanEvent(EventLoop loop, BooleanTopic topic) {
+    this(loop, topic.subscribe(false));
+  }
+
+  /**
+   * Creates a new event with the given boolean subscriber determining whether it is active.
+   *
+   * @param loop the loop that polls this event
+   * @param sub The boolean subscriber that provides the value
+   */
+  public NetworkBooleanEvent(EventLoop loop, BooleanSubscriber sub) {
+    super(loop, () -> sub.getTopic().getInstance().isConnected() && sub.get());
+    requireNonNullParam(sub, "sub", "NetworkBooleanEvent");
+  }
+
+  /**
+   * Creates a new event with the given boolean topic determining whether it is active.
+   *
+   * @param loop the loop that polls this event
+   * @param table The NetworkTable that contains the topic
+   * @param topicName The topic name within the table that contains the value
+   */
+  public NetworkBooleanEvent(EventLoop loop, NetworkTable table, String topicName) {
+    this(loop, table.getBooleanTopic(topicName));
+  }
+
+  /**
+   * Creates a new event with the given boolean topic determining whether it is active.
+   *
+   * @param loop the loop that polls this event
+   * @param tableName The NetworkTable name that contains the topic
+   * @param topicName The topic name within the table that contains the value
+   */
+  public NetworkBooleanEvent(EventLoop loop, String tableName, String topicName) {
+    this(loop, NetworkTableInstance.getDefault(), tableName, topicName);
+  }
+
+  /**
+   * Creates a new event with the given boolean topic determining whether it is active.
+   *
+   * @param loop the loop that polls this event
+   * @param inst The NetworkTable instance to use
+   * @param tableName The NetworkTable that contains the topic
+   * @param topicName The topic name within the table that contains the value
+   */
+  public NetworkBooleanEvent(
+      EventLoop loop, NetworkTableInstance inst, String tableName, String topicName) {
+    this(loop, inst.getTable(tableName), topicName);
+  }
+}
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/interfaces/Accelerometer.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/interfaces/Accelerometer.java
index de2780f..3cfd27d 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/interfaces/Accelerometer.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/interfaces/Accelerometer.java
@@ -22,16 +22,16 @@
   void setRange(Range range);
 
   /**
-   * Common interface for getting the x axis acceleration.
+   * Common interface for getting the x-axis acceleration.
    *
-   * @return The acceleration along the x axis in g-forces
+   * @return The acceleration along the x-axis in g-forces
    */
   double getX();
 
   /**
-   * Common interface for getting the y axis acceleration.
+   * Common interface for getting the y-axis acceleration.
    *
-   * @return The acceleration along the y axis in g-forces
+   * @return The acceleration along the y-axis in g-forces
    */
   double getY();
 
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/interfaces/Gyro.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/interfaces/Gyro.java
index 27377be..660aad8 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/interfaces/Gyro.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/interfaces/Gyro.java
@@ -17,7 +17,7 @@
 
   /**
    * Reset the gyro. Resets the gyro to a heading of zero. This can be used if there is significant
-   * drift in the gyro and it needs to be recalibrated after it has been running.
+   * drift in the gyro, and it needs to be recalibrated after it has been running.
    */
   void reset();
 
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/internal/DriverStationModeThread.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/internal/DriverStationModeThread.java
new file mode 100644
index 0000000..03d6397
--- /dev/null
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/internal/DriverStationModeThread.java
@@ -0,0 +1,112 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj.internal;
+
+import edu.wpi.first.hal.DriverStationJNI;
+import edu.wpi.first.util.WPIUtilJNI;
+import edu.wpi.first.wpilibj.DriverStation;
+import java.util.concurrent.atomic.AtomicBoolean;
+
+/*
+ * For internal use only.
+ */
+public class DriverStationModeThread implements AutoCloseable {
+  private final AtomicBoolean m_keepAlive = new AtomicBoolean();
+  private final Thread m_thread;
+
+  private boolean m_userInDisabled;
+  private boolean m_userInAutonomous;
+  private boolean m_userInTeleop;
+  private boolean m_userInTest;
+
+  /** Internal use only. */
+  public DriverStationModeThread() {
+    m_keepAlive.set(true);
+    m_thread = new Thread(this::run, "DriverStationMode");
+    m_thread.start();
+  }
+
+  private void run() {
+    int handle = WPIUtilJNI.createEvent(false, false);
+    DriverStationJNI.provideNewDataEventHandle(handle);
+
+    while (m_keepAlive.get()) {
+      try {
+        WPIUtilJNI.waitForObjectTimeout(handle, 0.1);
+      } catch (InterruptedException e) {
+        DriverStationJNI.removeNewDataEventHandle(handle);
+        WPIUtilJNI.destroyEvent(handle);
+        Thread.currentThread().interrupt();
+        return;
+      }
+      DriverStation.refreshData();
+      if (m_userInDisabled) {
+        DriverStationJNI.observeUserProgramDisabled();
+      }
+      if (m_userInAutonomous) {
+        DriverStationJNI.observeUserProgramAutonomous();
+      }
+      if (m_userInTeleop) {
+        DriverStationJNI.observeUserProgramTeleop();
+      }
+      if (m_userInTest) {
+        DriverStationJNI.observeUserProgramTest();
+      }
+    }
+
+    DriverStationJNI.removeNewDataEventHandle(handle);
+    WPIUtilJNI.destroyEvent(handle);
+  }
+
+  /**
+   * Only to be used to tell the Driver Station what code you claim to be executing for diagnostic
+   * purposes only.
+   *
+   * @param entering If true, starting disabled code; if false, leaving disabled code
+   */
+  public void inDisabled(boolean entering) {
+    m_userInDisabled = entering;
+  }
+
+  /**
+   * Only to be used to tell the Driver Station what code you claim to be executing for diagnostic
+   * purposes only.
+   *
+   * @param entering If true, starting autonomous code; if false, leaving autonomous code
+   */
+  public void inAutonomous(boolean entering) {
+    m_userInAutonomous = entering;
+  }
+
+  /**
+   * Only to be used to tell the Driver Station what code you claim to be executing for diagnostic
+   * purposes only.
+   *
+   * @param entering If true, starting teleop code; if false, leaving teleop code
+   */
+  public void inTeleop(boolean entering) {
+    m_userInTeleop = entering;
+  }
+
+  /**
+   * Only to be used to tell the Driver Station what code you claim to be executing for diagnostic
+   * purposes only.
+   *
+   * @param entering If true, starting test code; if false, leaving test code
+   */
+  public void inTest(boolean entering) {
+    m_userInTest = entering;
+  }
+
+  @Override
+  public void close() {
+    m_keepAlive.set(false);
+    try {
+      m_thread.join();
+    } catch (InterruptedException e) {
+      Thread.currentThread().interrupt();
+    }
+  }
+}
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/livewindow/LiveWindow.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/livewindow/LiveWindow.java
index ff3e8ef..a47f866 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/livewindow/LiveWindow.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/livewindow/LiveWindow.java
@@ -4,9 +4,11 @@
 
 package edu.wpi.first.wpilibj.livewindow;
 
+import edu.wpi.first.networktables.BooleanPublisher;
 import edu.wpi.first.networktables.NetworkTable;
-import edu.wpi.first.networktables.NetworkTableEntry;
 import edu.wpi.first.networktables.NetworkTableInstance;
+import edu.wpi.first.networktables.StringPublisher;
+import edu.wpi.first.networktables.StringTopic;
 import edu.wpi.first.util.sendable.Sendable;
 import edu.wpi.first.util.sendable.SendableRegistry;
 import edu.wpi.first.wpilibj.smartdashboard.SendableBuilderImpl;
@@ -14,26 +16,42 @@
 /**
  * The LiveWindow class is the public interface for putting sensors and actuators on the LiveWindow.
  */
-public class LiveWindow {
-  private static class Component {
+public final class LiveWindow {
+  private static class Component implements AutoCloseable {
+    @Override
+    public void close() {
+      if (m_namePub != null) {
+        m_namePub.close();
+        m_namePub = null;
+      }
+      if (m_typePub != null) {
+        m_typePub.close();
+        m_typePub = null;
+      }
+    }
+
     boolean m_firstTime = true;
-    boolean m_telemetryEnabled = true;
+    boolean m_telemetryEnabled;
+    StringPublisher m_namePub;
+    StringPublisher m_typePub;
   }
 
   private static final int dataHandle = SendableRegistry.getDataHandle();
   private static final NetworkTable liveWindowTable =
       NetworkTableInstance.getDefault().getTable("LiveWindow");
   private static final NetworkTable statusTable = liveWindowTable.getSubTable(".status");
-  private static final NetworkTableEntry enabledEntry = statusTable.getEntry("LW Enabled");
+  private static final BooleanPublisher enabledPub =
+      statusTable.getBooleanTopic("LW Enabled").publish();
   private static boolean startLiveWindow;
   private static boolean liveWindowEnabled;
-  private static boolean telemetryEnabled = true;
+  private static boolean telemetryEnabled;
 
   private static Runnable enabledListener;
   private static Runnable disabledListener;
 
   static {
     SendableRegistry.setLiveWindowBuilderFactory(() -> new SendableBuilderImpl());
+    enabledPub.set(false);
   }
 
   private static Component getOrAdd(Sendable sendable) {
@@ -66,7 +84,7 @@
    *
    * <p>If it's being enabled, turn off the scheduler and remove all the commands from the queue and
    * enable all the components registered for LiveWindow. If it's being disabled, stop all the
-   * registered components and reenable the scheduler.
+   * registered components and re-enable the scheduler.
    *
    * <p>TODO: add code to disable PID loops when enabling LiveWindow. The commands should reenable
    * the PID loops themselves when they get rescheduled. This prevents arms from starting to move
@@ -95,7 +113,7 @@
           disabledListener.run();
         }
       }
-      enabledEntry.setBoolean(enabled);
+      enabledPub.set(enabled);
     }
   }
 
@@ -132,6 +150,19 @@
         });
   }
 
+  /** Enable ALL telemetry. */
+  public static synchronized void enableAllTelemetry() {
+    telemetryEnabled = true;
+    SendableRegistry.foreachLiveWindow(
+        dataHandle,
+        cbdata -> {
+          if (cbdata.data == null) {
+            cbdata.data = new Component();
+          }
+          ((Component) cbdata.data).m_telemetryEnabled = true;
+        });
+  }
+
   /**
    * Tell all the sensors to update (send) their values.
    *
@@ -177,10 +208,12 @@
             } else {
               table = ssTable.getSubTable(cbdata.name);
             }
-            table.getEntry(".name").setString(cbdata.name);
+            component.m_namePub = new StringTopic(table.getTopic(".name")).publish();
+            component.m_namePub.set(cbdata.name);
             ((SendableBuilderImpl) cbdata.builder).setTable(table);
             cbdata.sendable.initSendable(cbdata.builder);
-            ssTable.getEntry(".type").setString("LW Subsystem");
+            component.m_typePub = new StringTopic(ssTable.getTopic(".type")).publish();
+            component.m_typePub.set("LW Subsystem");
 
             component.m_firstTime = false;
           }
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/MotorController.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/MotorController.java
index ac82afa..4cd50da 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/MotorController.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/MotorController.java
@@ -5,17 +5,14 @@
 package edu.wpi.first.wpilibj.motorcontrol;
 
 import edu.wpi.first.wpilibj.RobotController;
-import edu.wpi.first.wpilibj.SpeedController;
 
 /** Interface for motor controlling devices. */
-@SuppressWarnings("removal")
-public interface MotorController extends SpeedController {
+public interface MotorController {
   /**
    * Common interface for setting the speed of a motor controller.
    *
    * @param speed The speed to set. Value should be between -1.0 and 1.0.
    */
-  @Override
   void set(double speed);
 
   /**
@@ -29,7 +26,6 @@
    *
    * @param outputVolts The voltage to output.
    */
-  @Override
   default void setVoltage(double outputVolts) {
     set(outputVolts / RobotController.getBatteryVoltage());
   }
@@ -39,7 +35,6 @@
    *
    * @return The current set speed. Value is between -1.0 and 1.0.
    */
-  @Override
   double get();
 
   /**
@@ -47,7 +42,6 @@
    *
    * @param isInverted The state of inversion true is inverted.
    */
-  @Override
   void setInverted(boolean isInverted);
 
   /**
@@ -55,17 +49,14 @@
    *
    * @return isInverted The state of the inversion true is inverted.
    */
-  @Override
   boolean getInverted();
 
   /** Disable the motor controller. */
-  @Override
   void disable();
 
   /**
    * Stops motor movement. Motor can be moved again by calling set without having to re-enable the
    * motor.
    */
-  @Override
   void stopMotor();
 }
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/MotorControllerGroup.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/MotorControllerGroup.java
index 714aac5..d9da3c8 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/MotorControllerGroup.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/MotorControllerGroup.java
@@ -55,6 +55,13 @@
   }
 
   @Override
+  public void setVoltage(double outputVolts) {
+    for (MotorController motorController : m_motorControllers) {
+      motorController.setVoltage(m_isInverted ? -outputVolts : outputVolts);
+    }
+  }
+
+  @Override
   public double get() {
     if (m_motorControllers.length > 0) {
       return m_motorControllers[0].get() * (m_isInverted ? -1 : 1);
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMMotorController.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMMotorController.java
index fe8ecba..68817a1 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMMotorController.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMMotorController.java
@@ -78,7 +78,8 @@
 
   @Override
   public void stopMotor() {
-    disable();
+    // Don't use set(0) as that will feed the watch kitty
+    m_pwm.setSpeed(0);
   }
 
   @Override
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/package.html b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/package.html
index d11ae27..fdef7b4 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/package.html
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/package.html
@@ -13,7 +13,7 @@
     utility functions like timing and field management. The library is designed
     to:
     <ul>
-      <li>Deal with all the low level interfacing to these components so you
+      <li>Deal with all the low level interfacing to these components, so you
       can concentrate on solving this year's "robot problem". This is a
       philosophical decision to let you focus on the higher-level design of
       your robot rather than deal with the details of the processor and the
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/BuiltInWidgets.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/BuiltInWidgets.java
index 8df2c46..9c96a2f 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/BuiltInWidgets.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/BuiltInWidgets.java
@@ -12,7 +12,7 @@
  * <p>For example, setting a number to be displayed with a slider:
  *
  * <pre>{@code
- * NetworkTableEntry example = Shuffleboard.getTab("My Tab")
+ * GenericEntry example = Shuffleboard.getTab("My Tab")
  *   .add("My Number", 0)
  *   .withWidget(BuiltInWidgets.kNumberSlider)
  *   .withProperties(Map.of("min", 0, "max", 1))
@@ -284,9 +284,8 @@
    * Supported types:
    *
    * <ul>
-   *   <li>{@link edu.wpi.first.wpilibj.command.Command}
-   *   <li>{@link edu.wpi.first.wpilibj.command.CommandGroup}
-   *   <li>Any custom subclass of {@code Command} or {@code CommandGroup}
+   *   <li>{@link edu.wpi.first.wpilibj2.command.Command}
+   *   <li>Any custom subclass of {@code Command}
    * </ul>
    *
    * <br>
@@ -300,7 +299,7 @@
    * Supported types:
    *
    * <ul>
-   *   <li>{@link edu.wpi.first.wpilibj.command.PIDCommand}
+   *   <li>{@link edu.wpi.first.wpilibj2.command.PIDCommand}
    *   <li>Any custom subclass of {@code PIDCommand}
    * </ul>
    *
@@ -314,7 +313,7 @@
    * Supported types:
    *
    * <ul>
-   *   <li>{@link edu.wpi.first.wpilibj.PIDController}
+   *   <li>{@link edu.wpi.first.math.controller.PIDController}
    * </ul>
    *
    * <br>
@@ -474,7 +473,7 @@
    */
   kCameraStream("Camera Stream"),
   /**
-   * Displays a field2d object.<br>
+   * Displays a Field2d object.<br>
    * Supported types:
    *
    * <ul>
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ContainerHelper.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ContainerHelper.java
index 4bfe76c..c8c0731 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ContainerHelper.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ContainerHelper.java
@@ -4,7 +4,12 @@
 
 package edu.wpi.first.wpilibj.shuffleboard;
 
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
+
+import edu.wpi.first.networktables.GenericPublisher;
 import edu.wpi.first.networktables.NetworkTableEntry;
+import edu.wpi.first.networktables.NetworkTableType;
+import edu.wpi.first.util.function.FloatSupplier;
 import edu.wpi.first.util.sendable.Sendable;
 import edu.wpi.first.util.sendable.SendableRegistry;
 import java.util.ArrayList;
@@ -13,11 +18,11 @@
 import java.util.List;
 import java.util.Map;
 import java.util.NoSuchElementException;
-import java.util.Objects;
 import java.util.Set;
 import java.util.function.BiConsumer;
 import java.util.function.BooleanSupplier;
 import java.util.function.DoubleSupplier;
+import java.util.function.LongSupplier;
 import java.util.function.Supplier;
 
 /** A helper class for Shuffleboard containers to handle common child operations. */
@@ -53,6 +58,7 @@
   }
 
   ComplexWidget add(String title, Sendable sendable) {
+    requireNonNullParam(sendable, "sendable", "add");
     checkTitle(title);
     ComplexWidget widget = new ComplexWidget(m_container, title, sendable);
     m_components.add(widget);
@@ -60,6 +66,7 @@
   }
 
   ComplexWidget add(Sendable sendable) {
+    requireNonNullParam(sendable, "sendable", "add");
     String name = SendableRegistry.getName(sendable);
     if (name.isEmpty()) {
       throw new IllegalArgumentException("Sendable must have a name");
@@ -68,61 +75,101 @@
   }
 
   SimpleWidget add(String title, Object defaultValue) {
-    Objects.requireNonNull(title, "Title cannot be null");
-    Objects.requireNonNull(defaultValue, "Default value cannot be null");
+    requireNonNullParam(defaultValue, "defaultValue", "add");
+    return add(title, NetworkTableType.getStringFromObject(defaultValue), defaultValue);
+  }
+
+  SimpleWidget add(String title, String typeString, Object defaultValue) {
+    requireNonNullParam(title, "title", "add");
+    requireNonNullParam(defaultValue, "defaultValue", "add");
     checkTitle(title);
     checkNtType(defaultValue);
 
     SimpleWidget widget = new SimpleWidget(m_container, title);
     m_components.add(widget);
-    widget.getEntry().setDefaultValue(defaultValue);
+    widget.getEntry(typeString).setDefaultValue(defaultValue);
     return widget;
   }
 
   SuppliedValueWidget<String> addString(String title, Supplier<String> valueSupplier) {
-    precheck(title, valueSupplier);
-    return addSupplied(title, valueSupplier, NetworkTableEntry::setString);
+    precheck(title, valueSupplier, "addString");
+    return addSupplied(title, "string", valueSupplier, GenericPublisher::setString);
   }
 
   SuppliedValueWidget<Double> addNumber(String title, DoubleSupplier valueSupplier) {
-    precheck(title, valueSupplier);
-    return addSupplied(title, valueSupplier::getAsDouble, NetworkTableEntry::setDouble);
+    requireNonNullParam(title, "title", "addNumber");
+    requireNonNullParam(valueSupplier, "valueSupplier", "addNumber");
+    return addDouble(title, valueSupplier);
+  }
+
+  SuppliedValueWidget<Double> addDouble(String title, DoubleSupplier valueSupplier) {
+    precheck(title, valueSupplier, "addDouble");
+    return addSupplied(title, "double", valueSupplier::getAsDouble, GenericPublisher::setDouble);
+  }
+
+  SuppliedValueWidget<Float> addFloat(String title, FloatSupplier valueSupplier) {
+    precheck(title, valueSupplier, "addFloat");
+    return addSupplied(title, "float", valueSupplier::getAsFloat, GenericPublisher::setFloat);
+  }
+
+  SuppliedValueWidget<Long> addInteger(String title, LongSupplier valueSupplier) {
+    precheck(title, valueSupplier, "addInteger");
+    return addSupplied(title, "int", valueSupplier::getAsLong, GenericPublisher::setInteger);
   }
 
   SuppliedValueWidget<Boolean> addBoolean(String title, BooleanSupplier valueSupplier) {
-    precheck(title, valueSupplier);
-    return addSupplied(title, valueSupplier::getAsBoolean, NetworkTableEntry::setBoolean);
+    precheck(title, valueSupplier, "addBoolean");
+    return addSupplied(title, "boolean", valueSupplier::getAsBoolean, GenericPublisher::setBoolean);
   }
 
   SuppliedValueWidget<String[]> addStringArray(String title, Supplier<String[]> valueSupplier) {
-    precheck(title, valueSupplier);
-    return addSupplied(title, valueSupplier, NetworkTableEntry::setStringArray);
+    precheck(title, valueSupplier, "addStringArray");
+    return addSupplied(title, "string[]", valueSupplier, GenericPublisher::setStringArray);
   }
 
   SuppliedValueWidget<double[]> addDoubleArray(String title, Supplier<double[]> valueSupplier) {
-    precheck(title, valueSupplier);
-    return addSupplied(title, valueSupplier, NetworkTableEntry::setDoubleArray);
+    precheck(title, valueSupplier, "addDoubleArray");
+    return addSupplied(title, "double[]", valueSupplier, GenericPublisher::setDoubleArray);
+  }
+
+  SuppliedValueWidget<float[]> addFloatArray(String title, Supplier<float[]> valueSupplier) {
+    precheck(title, valueSupplier, "addFloatArray");
+    return addSupplied(title, "float[]", valueSupplier, GenericPublisher::setFloatArray);
+  }
+
+  SuppliedValueWidget<long[]> addIntegerArray(String title, Supplier<long[]> valueSupplier) {
+    precheck(title, valueSupplier, "addIntegerArray");
+    return addSupplied(title, "int[]", valueSupplier, GenericPublisher::setIntegerArray);
   }
 
   SuppliedValueWidget<boolean[]> addBooleanArray(String title, Supplier<boolean[]> valueSupplier) {
-    precheck(title, valueSupplier);
-    return addSupplied(title, valueSupplier, NetworkTableEntry::setBooleanArray);
+    precheck(title, valueSupplier, "addBooleanArray");
+    return addSupplied(title, "boolean[]", valueSupplier, GenericPublisher::setBooleanArray);
   }
 
   SuppliedValueWidget<byte[]> addRaw(String title, Supplier<byte[]> valueSupplier) {
-    precheck(title, valueSupplier);
-    return addSupplied(title, valueSupplier, NetworkTableEntry::setRaw);
+    return addRaw(title, "raw", valueSupplier);
   }
 
-  private void precheck(String title, Object valueSupplier) {
-    Objects.requireNonNull(title, "Title cannot be null");
-    Objects.requireNonNull(valueSupplier, "Value supplier cannot be null");
+  SuppliedValueWidget<byte[]> addRaw(
+      String title, String typeString, Supplier<byte[]> valueSupplier) {
+    precheck(title, valueSupplier, "addRaw");
+    return addSupplied(title, typeString, valueSupplier, GenericPublisher::setRaw);
+  }
+
+  private void precheck(String title, Object valueSupplier, String methodName) {
+    requireNonNullParam(title, "title", methodName);
+    requireNonNullParam(valueSupplier, "valueSupplier", methodName);
     checkTitle(title);
   }
 
   private <T> SuppliedValueWidget<T> addSupplied(
-      String title, Supplier<T> supplier, BiConsumer<NetworkTableEntry, T> setter) {
-    SuppliedValueWidget<T> widget = new SuppliedValueWidget<>(m_container, title, supplier, setter);
+      String title,
+      String typeString,
+      Supplier<T> supplier,
+      BiConsumer<GenericPublisher, T> setter) {
+    SuppliedValueWidget<T> widget =
+        new SuppliedValueWidget<>(m_container, title, typeString, supplier, setter);
     m_components.add(widget);
     return widget;
   }
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/RecordingController.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/RecordingController.java
index a7be3c9..f8329dd 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/RecordingController.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/RecordingController.java
@@ -4,9 +4,10 @@
 
 package edu.wpi.first.wpilibj.shuffleboard;
 
+import edu.wpi.first.networktables.BooleanPublisher;
 import edu.wpi.first.networktables.NetworkTable;
-import edu.wpi.first.networktables.NetworkTableEntry;
 import edu.wpi.first.networktables.NetworkTableInstance;
+import edu.wpi.first.networktables.StringPublisher;
 import edu.wpi.first.wpilibj.DriverStation;
 
 /** Controls Shuffleboard recordings via NetworkTables. */
@@ -16,30 +17,31 @@
   private static final String kRecordingFileNameFormatKey = kRecordingTableName + "FileNameFormat";
   private static final String kEventMarkerTableName = kRecordingTableName + "events";
 
-  private final NetworkTableEntry m_recordingControlEntry;
-  private final NetworkTableEntry m_recordingFileNameFormatEntry;
+  private final BooleanPublisher m_recordingControlEntry;
+  private final StringPublisher m_recordingFileNameFormatEntry;
   private final NetworkTable m_eventsTable;
 
   RecordingController(NetworkTableInstance ntInstance) {
-    m_recordingControlEntry = ntInstance.getEntry(kRecordingControlKey);
-    m_recordingFileNameFormatEntry = ntInstance.getEntry(kRecordingFileNameFormatKey);
+    m_recordingControlEntry = ntInstance.getBooleanTopic(kRecordingControlKey).publish();
+    m_recordingFileNameFormatEntry =
+        ntInstance.getStringTopic(kRecordingFileNameFormatKey).publish();
     m_eventsTable = ntInstance.getTable(kEventMarkerTableName);
   }
 
   public void startRecording() {
-    m_recordingControlEntry.setBoolean(true);
+    m_recordingControlEntry.set(true);
   }
 
   public void stopRecording() {
-    m_recordingControlEntry.setBoolean(false);
+    m_recordingControlEntry.set(false);
   }
 
   public void setRecordingFileNameFormat(String format) {
-    m_recordingFileNameFormatEntry.setString(format);
+    m_recordingFileNameFormatEntry.set(format);
   }
 
   public void clearRecordingFileNameFormat() {
-    m_recordingFileNameFormatEntry.delete();
+    m_recordingFileNameFormatEntry.set("");
   }
 
   public void addEventMarker(String name, String description, EventImportance importance) {
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/SendableCameraWrapper.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/SendableCameraWrapper.java
index f24840f..150f0db 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/SendableCameraWrapper.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/SendableCameraWrapper.java
@@ -4,8 +4,13 @@
 
 package edu.wpi.first.wpilibj.shuffleboard;
 
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
+
 import edu.wpi.first.cscore.VideoSource;
+import edu.wpi.first.networktables.NetworkTable;
 import edu.wpi.first.networktables.NetworkTableInstance;
+import edu.wpi.first.networktables.StringArrayPublisher;
+import edu.wpi.first.networktables.StringArrayTopic;
 import edu.wpi.first.util.sendable.Sendable;
 import edu.wpi.first.util.sendable.SendableBuilder;
 import edu.wpi.first.util.sendable.SendableRegistry;
@@ -19,7 +24,14 @@
 
   private static Map<String, SendableCameraWrapper> m_wrappers = new WeakHashMap<>();
 
+  private static NetworkTable m_table;
+
+  static {
+    setNetworkTableInstance(NetworkTableInstance.getDefault());
+  }
+
   private final String m_uri;
+  private StringArrayPublisher m_streams;
 
   /**
    * Creates a new sendable wrapper. Private constructor to avoid direct instantiation with multiple
@@ -36,8 +48,20 @@
     m_uri = kProtocol + cameraName;
   }
 
+  private SendableCameraWrapper(String cameraName, String[] cameraUrls) {
+    this(cameraName);
+
+    StringArrayTopic streams = new StringArrayTopic(m_table.getTopic(cameraName + "/streams"));
+    if (streams.exists()) {
+      throw new IllegalStateException(
+          "A camera is already being streamed with the name '" + cameraName + "'");
+    }
+
+    m_streams = streams.publish();
+    m_streams.set(cameraUrls);
+  }
+
   /** Clears all cached wrapper objects. This should only be used in tests. */
-  @SuppressWarnings("PMD.DefaultPackage")
   static void clearWrappers() {
     m_wrappers.clear();
   }
@@ -45,6 +69,18 @@
   @Override
   public void close() {
     SendableRegistry.remove(this);
+    if (m_streams != null) {
+      m_streams.close();
+    }
+  }
+
+  /*
+   * Sets NetworkTable instance used for camera publisher entries.
+   *
+   * @param inst NetworkTable instance
+   */
+  public static synchronized void setNetworkTableInstance(NetworkTableInstance inst) {
+    m_table = inst.getTable("CameraPublisher");
   }
 
   /**
@@ -73,14 +109,13 @@
    * @return a sendable wrapper object for the video source, usable in Shuffleboard via {@link
    *     ShuffleboardTab#add(Sendable)} and {@link ShuffleboardLayout#add(Sendable)}
    */
-  @SuppressWarnings("PMD.CyclomaticComplexity")
   public static SendableCameraWrapper wrap(String cameraName, String... cameraUrls) {
     if (m_wrappers.containsKey(cameraName)) {
       return m_wrappers.get(cameraName);
     }
 
-    Objects.requireNonNull(cameraName, "cameraName");
-    Objects.requireNonNull(cameraUrls, "cameraUrls");
+    requireNonNullParam(cameraName, "cameraName", "wrap");
+    requireNonNullParam(cameraUrls, "cameraUrls", "wrap");
     if (cameraName.isEmpty()) {
       throw new IllegalArgumentException("Camera name not specified");
     }
@@ -91,15 +126,7 @@
       Objects.requireNonNull(cameraUrls[i], "Camera URL at index " + i + " was null");
     }
 
-    String streams = "/CameraPublisher/" + cameraName + "/streams";
-    if (NetworkTableInstance.getDefault().getEntries(streams, 0).length != 0) {
-      throw new IllegalStateException(
-          "A camera is already being streamed with the name '" + cameraName + "'");
-    }
-
-    NetworkTableInstance.getDefault().getEntry(streams).setStringArray(cameraUrls);
-
-    SendableCameraWrapper wrapper = new SendableCameraWrapper(cameraName);
+    SendableCameraWrapper wrapper = new SendableCameraWrapper(cameraName, cameraUrls);
     m_wrappers.put(cameraName, wrapper);
     return wrapper;
   }
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/Shuffleboard.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/Shuffleboard.java
index 1bea28e..c08ab6f 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/Shuffleboard.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/Shuffleboard.java
@@ -16,7 +16,7 @@
  * <p>For example, displaying a boolean entry with a toggle button:
  *
  * <pre>{@code
- * NetworkTableEntry myBoolean = Shuffleboard.getTab("Example Tab")
+ * GenericEntry myBoolean = Shuffleboard.getTab("Example Tab")
  *   .add("My Boolean", false)
  *   .withWidget("Toggle Button")
  *   .getEntry();
@@ -25,7 +25,7 @@
  * <p>Changing the colors of the boolean box:
  *
  * <pre>{@code
- * NetworkTableEntry myBoolean = Shuffleboard.getTab("Example Tab")
+ * GenericEntry myBoolean = Shuffleboard.getTab("Example Tab")
  *   .add("My Boolean", false)
  *   .withWidget("Boolean Box")
  *   .withProperties(Map.of("colorWhenTrue", "green", "colorWhenFalse", "maroon"))
@@ -36,7 +36,7 @@
  * the layout has already been generated by a previously defined entry.
  *
  * <pre>{@code
- * NetworkTableEntry myBoolean = Shuffleboard.getTab("Example Tab")
+ * GenericEntry myBoolean = Shuffleboard.getTab("Example Tab")
  *   .getLayout("List", "Example List")
  *   .add("My Boolean", false)
  *   .withWidget("Toggle Button")
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardComponent.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardComponent.java
index fd7d541..39078f4 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardComponent.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardComponent.java
@@ -4,7 +4,7 @@
 
 package edu.wpi.first.wpilibj.shuffleboard;
 
-import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
 
 import edu.wpi.first.networktables.NetworkTable;
 import java.util.Map;
@@ -115,21 +115,21 @@
     }
     // Component type
     if (getType() == null) {
-      metaTable.getEntry("PreferredComponent").delete();
+      metaTable.getEntry("PreferredComponent").unpublish();
     } else {
-      metaTable.getEntry("PreferredComponent").forceSetString(getType());
+      metaTable.getEntry("PreferredComponent").setString(getType());
     }
 
     // Tile size
     if (m_width <= 0 || m_height <= 0) {
-      metaTable.getEntry("Size").delete();
+      metaTable.getEntry("Size").unpublish();
     } else {
       metaTable.getEntry("Size").setDoubleArray(new double[] {m_width, m_height});
     }
 
     // Tile position
     if (m_column < 0 || m_row < 0) {
-      metaTable.getEntry("Position").delete();
+      metaTable.getEntry("Position").unpublish();
     } else {
       metaTable.getEntry("Position").setDoubleArray(new double[] {m_column, m_row});
     }
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardContainer.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardContainer.java
index 333623f..b19aa2a 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardContainer.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardContainer.java
@@ -5,11 +5,14 @@
 package edu.wpi.first.wpilibj.shuffleboard;
 
 import edu.wpi.first.cscore.VideoSource;
+import edu.wpi.first.networktables.NetworkTableType;
+import edu.wpi.first.util.function.FloatSupplier;
 import edu.wpi.first.util.sendable.Sendable;
 import java.util.List;
 import java.util.NoSuchElementException;
 import java.util.function.BooleanSupplier;
 import java.util.function.DoubleSupplier;
+import java.util.function.LongSupplier;
 import java.util.function.Supplier;
 
 /** Common interface for objects that can contain shuffleboard components. */
@@ -123,6 +126,19 @@
   SimpleWidget add(String title, Object defaultValue);
 
   /**
+   * Adds a widget to this container to display the given data.
+   *
+   * @param title the title of the widget
+   * @param typeString the NT type string
+   * @param defaultValue the default value of the widget
+   * @return a widget to display the sendable data
+   * @throws IllegalArgumentException if a widget already exists in this container with the given
+   *     title
+   * @see #addPersistent(String, Object) add(String title, Object defaultValue)
+   */
+  SimpleWidget add(String title, String typeString, Object defaultValue);
+
+  /**
    * Adds a widget to this container to display a video stream.
    *
    * @param title the title of the widget
@@ -173,6 +189,45 @@
    * @throws IllegalArgumentException if a widget already exists in this container with the given
    *     title
    */
+  SuppliedValueWidget<Double> addDouble(String title, DoubleSupplier valueSupplier);
+
+  /**
+   * Adds a widget to this container. The widget will display the data provided by the value
+   * supplier. Changes made on the dashboard will not propagate to the widget object, and will be
+   * overridden by values from the value supplier.
+   *
+   * @param title the title of the widget
+   * @param valueSupplier the supplier for values
+   * @return a widget to display data
+   * @throws IllegalArgumentException if a widget already exists in this container with the given
+   *     title
+   */
+  SuppliedValueWidget<Float> addFloat(String title, FloatSupplier valueSupplier);
+
+  /**
+   * Adds a widget to this container. The widget will display the data provided by the value
+   * supplier. Changes made on the dashboard will not propagate to the widget object, and will be
+   * overridden by values from the value supplier.
+   *
+   * @param title the title of the widget
+   * @param valueSupplier the supplier for values
+   * @return a widget to display data
+   * @throws IllegalArgumentException if a widget already exists in this container with the given
+   *     title
+   */
+  SuppliedValueWidget<Long> addInteger(String title, LongSupplier valueSupplier);
+
+  /**
+   * Adds a widget to this container. The widget will display the data provided by the value
+   * supplier. Changes made on the dashboard will not propagate to the widget object, and will be
+   * overridden by values from the value supplier.
+   *
+   * @param title the title of the widget
+   * @param valueSupplier the supplier for values
+   * @return a widget to display data
+   * @throws IllegalArgumentException if a widget already exists in this container with the given
+   *     title
+   */
   SuppliedValueWidget<Boolean> addBoolean(String title, BooleanSupplier valueSupplier);
 
   /**
@@ -212,6 +267,32 @@
    * @throws IllegalArgumentException if a widget already exists in this container with the given
    *     title
    */
+  SuppliedValueWidget<float[]> addFloatArray(String title, Supplier<float[]> valueSupplier);
+
+  /**
+   * Adds a widget to this container. The widget will display the data provided by the value
+   * supplier. Changes made on the dashboard will not propagate to the widget object, and will be
+   * overridden by values from the value supplier.
+   *
+   * @param title the title of the widget
+   * @param valueSupplier the supplier for values
+   * @return a widget to display data
+   * @throws IllegalArgumentException if a widget already exists in this container with the given
+   *     title
+   */
+  SuppliedValueWidget<long[]> addIntegerArray(String title, Supplier<long[]> valueSupplier);
+
+  /**
+   * Adds a widget to this container. The widget will display the data provided by the value
+   * supplier. Changes made on the dashboard will not propagate to the widget object, and will be
+   * overridden by values from the value supplier.
+   *
+   * @param title the title of the widget
+   * @param valueSupplier the supplier for values
+   * @return a widget to display data
+   * @throws IllegalArgumentException if a widget already exists in this container with the given
+   *     title
+   */
   SuppliedValueWidget<boolean[]> addBooleanArray(String title, Supplier<boolean[]> valueSupplier);
 
   /**
@@ -225,7 +306,24 @@
    * @throws IllegalArgumentException if a widget already exists in this container with the given
    *     title
    */
-  SuppliedValueWidget<byte[]> addRaw(String title, Supplier<byte[]> valueSupplier);
+  default SuppliedValueWidget<byte[]> addRaw(String title, Supplier<byte[]> valueSupplier) {
+    return addRaw(title, "raw", valueSupplier);
+  }
+
+  /**
+   * Adds a widget to this container. The widget will display the data provided by the value
+   * supplier. Changes made on the dashboard will not propagate to the widget object, and will be
+   * overridden by values from the value supplier.
+   *
+   * @param title the title of the widget
+   * @param typeString the NT type string for the value
+   * @param valueSupplier the supplier for values
+   * @return a widget to display data
+   * @throws IllegalArgumentException if a widget already exists in this container with the given
+   *     title
+   */
+  SuppliedValueWidget<byte[]> addRaw(
+      String title, String typeString, Supplier<byte[]> valueSupplier);
 
   /**
    * Adds a widget to this container to display a simple piece of data. Unlike {@link #add(String,
@@ -240,8 +338,25 @@
    * @see #add(String, Object) add(String title, Object defaultValue)
    */
   default SimpleWidget addPersistent(String title, Object defaultValue) {
+    return addPersistent(title, NetworkTableType.getStringFromObject(defaultValue), defaultValue);
+  }
+
+  /**
+   * Adds a widget to this container to display a simple piece of data. Unlike {@link #add(String,
+   * Object)}, the value in the widget will be saved on the robot and will be used when the robot
+   * program next starts rather than {@code defaultValue}.
+   *
+   * @param title the title of the widget
+   * @param typeString the NT type string
+   * @param defaultValue the default value of the widget
+   * @return a widget to display the sendable data
+   * @throws IllegalArgumentException if a widget already exists in this container with the given
+   *     title
+   * @see #add(String, Object) add(String title, Object defaultValue)
+   */
+  default SimpleWidget addPersistent(String title, String typeString, Object defaultValue) {
     SimpleWidget widget = add(title, defaultValue);
-    widget.getEntry().setPersistent();
+    widget.getEntry(typeString).getTopic().setPersistent(true);
     return widget;
   }
 }
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardInstance.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardInstance.java
index a864433..6c03ded 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardInstance.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardInstance.java
@@ -4,13 +4,13 @@
 
 package edu.wpi.first.wpilibj.shuffleboard;
 
-import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
 
 import edu.wpi.first.hal.FRCNetComm.tResourceType;
 import edu.wpi.first.hal.HAL;
 import edu.wpi.first.networktables.NetworkTable;
-import edu.wpi.first.networktables.NetworkTableEntry;
 import edu.wpi.first.networktables.NetworkTableInstance;
+import edu.wpi.first.networktables.StringPublisher;
 import java.util.LinkedHashMap;
 import java.util.Map;
 import java.util.function.Consumer;
@@ -21,7 +21,7 @@
   private boolean m_tabsChanged = false; // NOPMD redundant field initializer
   private final NetworkTable m_rootTable;
   private final NetworkTable m_rootMetaTable;
-  private final NetworkTableEntry m_selectedTabEntry;
+  private final StringPublisher m_selectedTabPub;
 
   /**
    * Creates a new Shuffleboard instance.
@@ -32,7 +32,7 @@
     requireNonNullParam(ntInstance, "ntInstance", "ShuffleboardInstance");
     m_rootTable = ntInstance.getTable(Shuffleboard.kBaseTableName);
     m_rootMetaTable = m_rootTable.getSubTable(".metadata");
-    m_selectedTabEntry = m_rootMetaTable.getEntry("Selected");
+    m_selectedTabPub = m_rootMetaTable.getStringTopic("Selected").publish();
     HAL.report(tResourceType.kResourceType_Shuffleboard, 0);
   }
 
@@ -51,7 +51,7 @@
     if (m_tabsChanged) {
       String[] tabTitles =
           m_tabs.values().stream().map(ShuffleboardTab::getTitle).toArray(String[]::new);
-      m_rootMetaTable.getEntry("Tabs").forceSetStringArray(tabTitles);
+      m_rootMetaTable.getEntry("Tabs").setStringArray(tabTitles);
       m_tabsChanged = false;
     }
     for (ShuffleboardTab tab : m_tabs.values()) {
@@ -72,12 +72,12 @@
 
   @Override
   public void selectTab(int index) {
-    m_selectedTabEntry.forceSetDouble(index);
+    selectTab(Integer.toString(index));
   }
 
   @Override
   public void selectTab(String title) {
-    m_selectedTabEntry.forceSetString(title);
+    m_selectedTabPub.set(title);
   }
 
   /**
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardLayout.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardLayout.java
index b48eebb..bb450e4 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardLayout.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardLayout.java
@@ -4,13 +4,15 @@
 
 package edu.wpi.first.wpilibj.shuffleboard;
 
-import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
 
 import edu.wpi.first.networktables.NetworkTable;
+import edu.wpi.first.util.function.FloatSupplier;
 import edu.wpi.first.util.sendable.Sendable;
 import java.util.List;
 import java.util.function.BooleanSupplier;
 import java.util.function.DoubleSupplier;
+import java.util.function.LongSupplier;
 import java.util.function.Supplier;
 
 /** A layout in a Shuffleboard tab. Layouts can contain widgets and other layouts. */
@@ -53,6 +55,11 @@
   }
 
   @Override
+  public SimpleWidget add(String title, String typeString, Object defaultValue) {
+    return m_helper.add(title, typeString, defaultValue);
+  }
+
+  @Override
   public SuppliedValueWidget<String> addString(String title, Supplier<String> valueSupplier) {
     return m_helper.addString(title, valueSupplier);
   }
@@ -63,6 +70,21 @@
   }
 
   @Override
+  public SuppliedValueWidget<Double> addDouble(String title, DoubleSupplier valueSupplier) {
+    return m_helper.addDouble(title, valueSupplier);
+  }
+
+  @Override
+  public SuppliedValueWidget<Float> addFloat(String title, FloatSupplier valueSupplier) {
+    return m_helper.addFloat(title, valueSupplier);
+  }
+
+  @Override
+  public SuppliedValueWidget<Long> addInteger(String title, LongSupplier valueSupplier) {
+    return m_helper.addInteger(title, valueSupplier);
+  }
+
+  @Override
   public SuppliedValueWidget<Boolean> addBoolean(String title, BooleanSupplier valueSupplier) {
     return m_helper.addBoolean(title, valueSupplier);
   }
@@ -80,14 +102,25 @@
   }
 
   @Override
+  public SuppliedValueWidget<float[]> addFloatArray(String title, Supplier<float[]> valueSupplier) {
+    return m_helper.addFloatArray(title, valueSupplier);
+  }
+
+  @Override
+  public SuppliedValueWidget<long[]> addIntegerArray(String title, Supplier<long[]> valueSupplier) {
+    return m_helper.addIntegerArray(title, valueSupplier);
+  }
+
+  @Override
   public SuppliedValueWidget<boolean[]> addBooleanArray(
       String title, Supplier<boolean[]> valueSupplier) {
     return m_helper.addBooleanArray(title, valueSupplier);
   }
 
   @Override
-  public SuppliedValueWidget<byte[]> addRaw(String title, Supplier<byte[]> valueSupplier) {
-    return m_helper.addRaw(title, valueSupplier);
+  public SuppliedValueWidget<byte[]> addRaw(
+      String title, String typeString, Supplier<byte[]> valueSupplier) {
+    return m_helper.addRaw(title, typeString, valueSupplier);
   }
 
   @Override
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardTab.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardTab.java
index 597eb80..f1feabb 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardTab.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardTab.java
@@ -5,10 +5,12 @@
 package edu.wpi.first.wpilibj.shuffleboard;
 
 import edu.wpi.first.networktables.NetworkTable;
+import edu.wpi.first.util.function.FloatSupplier;
 import edu.wpi.first.util.sendable.Sendable;
 import java.util.List;
 import java.util.function.BooleanSupplier;
 import java.util.function.DoubleSupplier;
+import java.util.function.LongSupplier;
 import java.util.function.Supplier;
 
 /**
@@ -67,6 +69,11 @@
   }
 
   @Override
+  public SimpleWidget add(String title, String typeString, Object defaultValue) {
+    return m_helper.add(title, typeString, defaultValue);
+  }
+
+  @Override
   public SuppliedValueWidget<String> addString(String title, Supplier<String> valueSupplier) {
     return m_helper.addString(title, valueSupplier);
   }
@@ -77,6 +84,21 @@
   }
 
   @Override
+  public SuppliedValueWidget<Double> addDouble(String title, DoubleSupplier valueSupplier) {
+    return m_helper.addDouble(title, valueSupplier);
+  }
+
+  @Override
+  public SuppliedValueWidget<Float> addFloat(String title, FloatSupplier valueSupplier) {
+    return m_helper.addFloat(title, valueSupplier);
+  }
+
+  @Override
+  public SuppliedValueWidget<Long> addInteger(String title, LongSupplier valueSupplier) {
+    return m_helper.addInteger(title, valueSupplier);
+  }
+
+  @Override
   public SuppliedValueWidget<Boolean> addBoolean(String title, BooleanSupplier valueSupplier) {
     return m_helper.addBoolean(title, valueSupplier);
   }
@@ -94,14 +116,25 @@
   }
 
   @Override
+  public SuppliedValueWidget<float[]> addFloatArray(String title, Supplier<float[]> valueSupplier) {
+    return m_helper.addFloatArray(title, valueSupplier);
+  }
+
+  @Override
+  public SuppliedValueWidget<long[]> addIntegerArray(String title, Supplier<long[]> valueSupplier) {
+    return m_helper.addIntegerArray(title, valueSupplier);
+  }
+
+  @Override
   public SuppliedValueWidget<boolean[]> addBooleanArray(
       String title, Supplier<boolean[]> valueSupplier) {
     return m_helper.addBooleanArray(title, valueSupplier);
   }
 
   @Override
-  public SuppliedValueWidget<byte[]> addRaw(String title, Supplier<byte[]> valueSupplier) {
-    return m_helper.addRaw(title, valueSupplier);
+  public SuppliedValueWidget<byte[]> addRaw(
+      String title, String typeString, Supplier<byte[]> valueSupplier) {
+    return m_helper.addRaw(title, typeString, valueSupplier);
   }
 
   @Override
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/SimpleWidget.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/SimpleWidget.java
index 2043432..33405c7 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/SimpleWidget.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/SimpleWidget.java
@@ -4,12 +4,13 @@
 
 package edu.wpi.first.wpilibj.shuffleboard;
 
+import edu.wpi.first.networktables.GenericEntry;
 import edu.wpi.first.networktables.NetworkTable;
-import edu.wpi.first.networktables.NetworkTableEntry;
 
 /** A Shuffleboard widget that handles a single data point such as a number or string. */
-public final class SimpleWidget extends ShuffleboardWidget<SimpleWidget> {
-  private NetworkTableEntry m_entry;
+public final class SimpleWidget extends ShuffleboardWidget<SimpleWidget> implements AutoCloseable {
+  private String m_typeString = "";
+  private GenericEntry m_entry;
 
   SimpleWidget(ShuffleboardContainer parent, String title) {
     super(parent, title);
@@ -20,18 +21,39 @@
    *
    * @return The NetworkTable entry that contains the data for this widget.
    */
-  public NetworkTableEntry getEntry() {
+  public GenericEntry getEntry() {
     if (m_entry == null) {
       forceGenerate();
     }
     return m_entry;
   }
 
+  /**
+   * Gets the NetworkTable entry that contains the data for this widget.
+   *
+   * @param typeString NetworkTable type string
+   * @return The NetworkTable entry that contains the data for this widget.
+   */
+  public GenericEntry getEntry(String typeString) {
+    if (m_entry == null) {
+      m_typeString = typeString;
+      forceGenerate();
+    }
+    return m_entry;
+  }
+
+  @Override
+  public void close() {
+    if (m_entry != null) {
+      m_entry.close();
+    }
+  }
+
   @Override
   public void buildInto(NetworkTable parentTable, NetworkTable metaTable) {
     buildMetadata(metaTable);
     if (m_entry == null) {
-      m_entry = parentTable.getEntry(getTitle());
+      m_entry = parentTable.getTopic(getTitle()).getGenericEntry(m_typeString);
     }
   }
 
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/SuppliedValueWidget.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/SuppliedValueWidget.java
index 497b30f..355f483 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/SuppliedValueWidget.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/SuppliedValueWidget.java
@@ -4,8 +4,10 @@
 
 package edu.wpi.first.wpilibj.shuffleboard;
 
+import edu.wpi.first.networktables.BooleanPublisher;
+import edu.wpi.first.networktables.BooleanTopic;
+import edu.wpi.first.networktables.GenericPublisher;
 import edu.wpi.first.networktables.NetworkTable;
-import edu.wpi.first.networktables.NetworkTableEntry;
 import java.util.function.BiConsumer;
 import java.util.function.Supplier;
 
@@ -14,34 +16,56 @@
  *
  * @param <T> the type of values in the widget
  */
-public final class SuppliedValueWidget<T> extends ShuffleboardWidget<SuppliedValueWidget<T>> {
+public final class SuppliedValueWidget<T> extends ShuffleboardWidget<SuppliedValueWidget<T>>
+    implements AutoCloseable {
+  private final String m_typeString;
   private final Supplier<T> m_supplier;
-  private final BiConsumer<NetworkTableEntry, T> m_setter;
+  private final BiConsumer<GenericPublisher, T> m_setter;
+  private BooleanPublisher m_controllablePub;
+  private GenericPublisher m_entry;
 
   /**
    * Package-private constructor for use by the Shuffleboard API.
    *
    * @param parent the parent container for the widget
    * @param title the title of the widget
+   * @param typeString the NetworkTables string type
    * @param supplier the supplier for values to place in the NetworkTable entry
    * @param setter the function for placing values in the NetworkTable entry
    */
   SuppliedValueWidget(
       ShuffleboardContainer parent,
       String title,
+      String typeString,
       Supplier<T> supplier,
-      BiConsumer<NetworkTableEntry, T> setter) {
+      BiConsumer<GenericPublisher, T> setter) {
     super(parent, title);
-    this.m_supplier = supplier;
-    this.m_setter = setter;
+    m_typeString = typeString;
+    m_supplier = supplier;
+    m_setter = setter;
   }
 
   @Override
   public void buildInto(NetworkTable parentTable, NetworkTable metaTable) {
     buildMetadata(metaTable);
-    metaTable.getEntry("Controllable").setBoolean(false);
+    if (m_controllablePub == null) {
+      m_controllablePub = new BooleanTopic(metaTable.getTopic("Controllable")).publish();
+      m_controllablePub.set(false);
+    }
 
-    NetworkTableEntry entry = parentTable.getEntry(getTitle());
-    m_setter.accept(entry, m_supplier.get());
+    if (m_entry == null) {
+      m_entry = parentTable.getTopic(getTitle()).genericPublish(m_typeString);
+    }
+    m_setter.accept(m_entry, m_supplier.get());
+  }
+
+  @Override
+  public void close() {
+    if (m_controllablePub != null) {
+      m_controllablePub.close();
+    }
+    if (m_entry != null) {
+      m_entry.close();
+    }
   }
 }
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ADIS16448_IMUSim.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ADIS16448_IMUSim.java
index 584a2ec..f94fa35 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ADIS16448_IMUSim.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ADIS16448_IMUSim.java
@@ -8,7 +8,7 @@
 import edu.wpi.first.wpilibj.ADIS16448_IMU;
 
 /** Class to control a simulated ADIS16448 gyroscope. */
-@SuppressWarnings({"TypeName", "AbbreviationAsWordInName"})
+@SuppressWarnings("TypeName")
 public class ADIS16448_IMUSim {
   private final SimDouble m_simGyroAngleX;
   private final SimDouble m_simGyroAngleY;
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ADIS16470_IMUSim.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ADIS16470_IMUSim.java
index eb8ceb8..5726244 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ADIS16470_IMUSim.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ADIS16470_IMUSim.java
@@ -8,7 +8,7 @@
 import edu.wpi.first.wpilibj.ADIS16470_IMU;
 
 /** Class to control a simulated ADIS16470 gyroscope. */
-@SuppressWarnings({"TypeName", "AbbreviationAsWordInName"})
+@SuppressWarnings("TypeName")
 public class ADIS16470_IMUSim {
   private final SimDouble m_simGyroAngleX;
   private final SimDouble m_simGyroAngleY;
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ADXRS450_GyroSim.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ADXRS450_GyroSim.java
index 27e06a3..0743cbd 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ADXRS450_GyroSim.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ADXRS450_GyroSim.java
@@ -8,7 +8,7 @@
 import edu.wpi.first.wpilibj.ADXRS450_Gyro;
 
 /** Class to control a simulated ADXRS450 gyroscope. */
-@SuppressWarnings({"TypeName", "AbbreviationAsWordInName"})
+@SuppressWarnings("TypeName")
 public class ADXRS450_GyroSim {
   private final SimDouble m_simAngle;
   private final SimDouble m_simRate;
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/BuiltInAccelerometerSim.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/BuiltInAccelerometerSim.java
index 5714a2d..8aba25a 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/BuiltInAccelerometerSim.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/BuiltInAccelerometerSim.java
@@ -116,7 +116,6 @@
    *
    * @param x the new reading of the X axis
    */
-  @SuppressWarnings("ParameterName")
   public void setX(double x) {
     AccelerometerDataJNI.setX(m_index, x);
   }
@@ -148,7 +147,6 @@
    *
    * @param y the new reading of the Y axis
    */
-  @SuppressWarnings("ParameterName")
   public void setY(double y) {
     AccelerometerDataJNI.setY(m_index, y);
   }
@@ -180,7 +178,6 @@
    *
    * @param z the new reading of the Z axis
    */
-  @SuppressWarnings("ParameterName")
   public void setZ(double z) {
     AccelerometerDataJNI.setZ(m_index, z);
   }
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/CTREPCMSim.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/CTREPCMSim.java
index 12ae153..3169a5d 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/CTREPCMSim.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/CTREPCMSim.java
@@ -6,17 +6,14 @@
 
 import edu.wpi.first.hal.simulation.CTREPCMDataJNI;
 import edu.wpi.first.hal.simulation.NotifyCallback;
-import edu.wpi.first.wpilibj.PneumaticsBase;
+import edu.wpi.first.wpilibj.PneumaticsControlModule;
 import edu.wpi.first.wpilibj.SensorUtil;
 
 /** Class to control a simulated Pneumatic Control Module (PCM). */
-@SuppressWarnings("AbbreviationAsWordInName")
-public class CTREPCMSim {
-  private final int m_index;
-
+public class CTREPCMSim extends PneumaticsBaseSim {
   /** Constructs for the default PCM. */
   public CTREPCMSim() {
-    m_index = SensorUtil.getDefaultCTREPCMModule();
+    super(SensorUtil.getDefaultCTREPCMModule());
   }
 
   /**
@@ -25,129 +22,16 @@
    * @param module module number
    */
   public CTREPCMSim(int module) {
-    m_index = module;
+    super(module);
   }
 
   /**
-   * Constructs from a Compressor object.
+   * Constructs from a PneumaticsControlModule object.
    *
    * @param module PCM module to simulate
    */
-  public CTREPCMSim(PneumaticsBase module) {
-    m_index = module.getModuleNumber();
-  }
-
-  /**
-   * Register a callback to be run when the solenoid output on a channel changes.
-   *
-   * @param channel the channel to monitor
-   * @param callback the callback
-   * @param initialNotify should the callback be run with the initial value
-   * @return the {@link CallbackStore} object associated with this callback. Save a reference to
-   *     this object so GC doesn't cancel the callback.
-   */
-  public CallbackStore registerSolenoidOutputCallback(
-      int channel, NotifyCallback callback, boolean initialNotify) {
-    int uid =
-        CTREPCMDataJNI.registerSolenoidOutputCallback(m_index, channel, callback, initialNotify);
-    return new CallbackStore(m_index, channel, uid, CTREPCMDataJNI::cancelSolenoidOutputCallback);
-  }
-
-  /**
-   * Check the solenoid output on a specific channel.
-   *
-   * @param channel the channel to check
-   * @return the solenoid output
-   */
-  public boolean getSolenoidOutput(int channel) {
-    return CTREPCMDataJNI.getSolenoidOutput(m_index, channel);
-  }
-
-  /**
-   * Change the solenoid output on a specific channel.
-   *
-   * @param channel the channel to check
-   * @param solenoidOutput the new solenoid output
-   */
-  public void setSolenoidOutput(int channel, boolean solenoidOutput) {
-    CTREPCMDataJNI.setSolenoidOutput(m_index, channel, solenoidOutput);
-  }
-
-  /**
-   * Register a callback to be run when the compressor is initialized.
-   *
-   * @param callback the callback
-   * @param initialNotify whether to run the callback with the initial state
-   * @return the {@link CallbackStore} object associated with this callback. Save a reference to
-   *     this object so GC doesn't cancel the callback.
-   */
-  public CallbackStore registerInitializedCallback(NotifyCallback callback, boolean initialNotify) {
-    int uid = CTREPCMDataJNI.registerInitializedCallback(m_index, callback, initialNotify);
-    return new CallbackStore(m_index, uid, CTREPCMDataJNI::cancelInitializedCallback);
-  }
-
-  /**
-   * Check whether the compressor has been initialized.
-   *
-   * @return true if initialized
-   */
-  public boolean getInitialized() {
-    return CTREPCMDataJNI.getInitialized(m_index);
-  }
-
-  /**
-   * Define whether the compressor has been initialized.
-   *
-   * @param initialized whether the compressor is initialized
-   */
-  public void setInitialized(boolean initialized) {
-    CTREPCMDataJNI.setInitialized(m_index, initialized);
-  }
-
-  /**
-   * Register a callback to be run when the compressor activates.
-   *
-   * @param callback the callback
-   * @param initialNotify whether to run the callback with the initial state
-   * @return the {@link CallbackStore} object associated with this callback. Save a reference to
-   *     this object so GC doesn't cancel the callback.
-   */
-  public CallbackStore registerCompressorOnCallback(
-      NotifyCallback callback, boolean initialNotify) {
-    int uid = CTREPCMDataJNI.registerCompressorOnCallback(m_index, callback, initialNotify);
-    return new CallbackStore(m_index, uid, CTREPCMDataJNI::cancelCompressorOnCallback);
-  }
-
-  /**
-   * Check if the compressor is on.
-   *
-   * @return true if the compressor is active
-   */
-  public boolean getCompressorOn() {
-    return CTREPCMDataJNI.getCompressorOn(m_index);
-  }
-
-  /**
-   * Set whether the compressor is active.
-   *
-   * @param compressorOn the new value
-   */
-  public void setCompressorOn(boolean compressorOn) {
-    CTREPCMDataJNI.setCompressorOn(m_index, compressorOn);
-  }
-
-  /**
-   * Register a callback to be run whenever the closed loop state changes.
-   *
-   * @param callback the callback
-   * @param initialNotify whether the callback should be called with the initial value
-   * @return the {@link CallbackStore} object associated with this callback. Save a reference to
-   *     this object so GC doesn't cancel the callback.
-   */
-  public CallbackStore registerClosedLoopEnabledCallback(
-      NotifyCallback callback, boolean initialNotify) {
-    int uid = CTREPCMDataJNI.registerClosedLoopEnabledCallback(m_index, callback, initialNotify);
-    return new CallbackStore(m_index, uid, CTREPCMDataJNI::cancelClosedLoopEnabledCallback);
+  public CTREPCMSim(PneumaticsControlModule module) {
+    super(module);
   }
 
   /**
@@ -169,70 +53,105 @@
   }
 
   /**
-   * Register a callback to be run whenever the pressure switch value changes.
+   * Register a callback to be run whenever the closed loop state changes.
    *
    * @param callback the callback
    * @param initialNotify whether the callback should be called with the initial value
    * @return the {@link CallbackStore} object associated with this callback. Save a reference to
    *     this object so GC doesn't cancel the callback.
    */
+  public CallbackStore registerClosedLoopEnabledCallback(
+      NotifyCallback callback, boolean initialNotify) {
+    int uid = CTREPCMDataJNI.registerClosedLoopEnabledCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, CTREPCMDataJNI::cancelClosedLoopEnabledCallback);
+  }
+
+  @Override
+  public boolean getInitialized() {
+    return CTREPCMDataJNI.getInitialized(m_index);
+  }
+
+  @Override
+  public void setInitialized(boolean initialized) {
+    CTREPCMDataJNI.setInitialized(m_index, initialized);
+  }
+
+  @Override
+  public CallbackStore registerInitializedCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = CTREPCMDataJNI.registerInitializedCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, CTREPCMDataJNI::cancelInitializedCallback);
+  }
+
+  @Override
+  public boolean getCompressorOn() {
+    return CTREPCMDataJNI.getCompressorOn(m_index);
+  }
+
+  @Override
+  public void setCompressorOn(boolean compressorOn) {
+    CTREPCMDataJNI.setCompressorOn(m_index, compressorOn);
+  }
+
+  @Override
+  public CallbackStore registerCompressorOnCallback(
+      NotifyCallback callback, boolean initialNotify) {
+    int uid = CTREPCMDataJNI.registerCompressorOnCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, CTREPCMDataJNI::cancelCompressorOnCallback);
+  }
+
+  @Override
+  public boolean getSolenoidOutput(int channel) {
+    return CTREPCMDataJNI.getSolenoidOutput(m_index, channel);
+  }
+
+  @Override
+  public void setSolenoidOutput(int channel, boolean solenoidOutput) {
+    CTREPCMDataJNI.setSolenoidOutput(m_index, channel, solenoidOutput);
+  }
+
+  @Override
+  public CallbackStore registerSolenoidOutputCallback(
+      int channel, NotifyCallback callback, boolean initialNotify) {
+    int uid =
+        CTREPCMDataJNI.registerSolenoidOutputCallback(m_index, channel, callback, initialNotify);
+    return new CallbackStore(m_index, channel, uid, CTREPCMDataJNI::cancelSolenoidOutputCallback);
+  }
+
+  @Override
+  public boolean getPressureSwitch() {
+    return CTREPCMDataJNI.getPressureSwitch(m_index);
+  }
+
+  @Override
+  public void setPressureSwitch(boolean pressureSwitch) {
+    CTREPCMDataJNI.setPressureSwitch(m_index, pressureSwitch);
+  }
+
+  @Override
   public CallbackStore registerPressureSwitchCallback(
       NotifyCallback callback, boolean initialNotify) {
     int uid = CTREPCMDataJNI.registerPressureSwitchCallback(m_index, callback, initialNotify);
     return new CallbackStore(m_index, uid, CTREPCMDataJNI::cancelPressureSwitchCallback);
   }
 
-  /**
-   * Check the value of the pressure switch.
-   *
-   * @return the pressure switch value
-   */
-  public boolean getPressureSwitch() {
-    return CTREPCMDataJNI.getPressureSwitch(m_index);
+  @Override
+  public double getCompressorCurrent() {
+    return CTREPCMDataJNI.getCompressorCurrent(m_index);
   }
 
-  /**
-   * Set the value of the pressure switch.
-   *
-   * @param pressureSwitch the new value
-   */
-  public void setPressureSwitch(boolean pressureSwitch) {
-    CTREPCMDataJNI.setPressureSwitch(m_index, pressureSwitch);
+  @Override
+  public void setCompressorCurrent(double compressorCurrent) {
+    CTREPCMDataJNI.setCompressorCurrent(m_index, compressorCurrent);
   }
 
-  /**
-   * Register a callback to be run whenever the compressor current changes.
-   *
-   * @param callback the callback
-   * @param initialNotify whether to call the callback with the initial state
-   * @return the {@link CallbackStore} object associated with this callback. Save a reference to
-   *     this object so GC doesn't cancel the callback.
-   */
+  @Override
   public CallbackStore registerCompressorCurrentCallback(
       NotifyCallback callback, boolean initialNotify) {
     int uid = CTREPCMDataJNI.registerCompressorCurrentCallback(m_index, callback, initialNotify);
     return new CallbackStore(m_index, uid, CTREPCMDataJNI::cancelCompressorCurrentCallback);
   }
 
-  /**
-   * Read the compressor current.
-   *
-   * @return the current of the compressor connected to this module
-   */
-  public double getCompressorCurrent() {
-    return CTREPCMDataJNI.getCompressorCurrent(m_index);
-  }
-
-  /**
-   * Set the compressor current.
-   *
-   * @param compressorCurrent the new compressor current
-   */
-  public void setCompressorCurrent(double compressorCurrent) {
-    CTREPCMDataJNI.setCompressorCurrent(m_index, compressorCurrent);
-  }
-
-  /** Reset all simulation data for this object. */
+  @Override
   public void resetData() {
     CTREPCMDataJNI.resetData(m_index);
   }
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/CallbackStore.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/CallbackStore.java
index 048d3c1..89a460f 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/CallbackStore.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/CallbackStore.java
@@ -93,16 +93,4 @@
     }
     m_cancelType = -1;
   }
-
-  @SuppressWarnings({"NoFinalizer", "deprecation"})
-  @Override
-  protected void finalize() throws Throwable {
-    try {
-      if (m_cancelType >= 0) {
-        close(); // close open files
-      }
-    } finally {
-      super.finalize();
-    }
-  }
 }
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DCMotorSim.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DCMotorSim.java
index 957075d..48c5a55 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DCMotorSim.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DCMotorSim.java
@@ -59,7 +59,6 @@
    * @param jKgMetersSquared The moment of inertia of the DC motor. If this is unknown, use the
    *     {@link #DCMotorSim(LinearSystem, DCMotor, double, Matrix)} constructor.
    */
-  @SuppressWarnings("ParameterName")
   public DCMotorSim(DCMotor gearbox, double gearing, double jKgMetersSquared) {
     super(LinearSystemId.createDCMotorSystem(gearbox, jKgMetersSquared, gearing));
     m_gearbox = gearbox;
@@ -75,7 +74,6 @@
    *     {@link #DCMotorSim(LinearSystem, DCMotor, double, Matrix)} constructor.
    * @param measurementStdDevs The standard deviations of the measurements.
    */
-  @SuppressWarnings("ParameterName")
   public DCMotorSim(
       DCMotor gearbox, double gearing, double jKgMetersSquared, Matrix<N2, N1> measurementStdDevs) {
     super(
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DIOSim.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DIOSim.java
index 83afb74..1ee1580 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DIOSim.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DIOSim.java
@@ -32,7 +32,7 @@
   }
 
   /**
-   * Constructs from an digital I/O channel number.
+   * Constructs from a digital I/O channel number.
    *
    * @param channel Channel number
    */
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DifferentialDrivetrainSim.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DifferentialDrivetrainSim.java
index 43242d1..7a746a2 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DifferentialDrivetrainSim.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DifferentialDrivetrainSim.java
@@ -44,13 +44,8 @@
   private double m_currentGearing;
   private final double m_wheelRadiusMeters;
 
-  @SuppressWarnings("MemberName")
   private Matrix<N2, N1> m_u;
-
-  @SuppressWarnings("MemberName")
   private Matrix<N7, N1> m_x;
-
-  @SuppressWarnings("MemberName")
   private Matrix<N7, N1> m_y;
 
   private final double m_rb;
@@ -72,7 +67,6 @@
    *     m/s, and position measurement standard deviations of 0.005 meters are a reasonable starting
    *     point.
    */
-  @SuppressWarnings("ParameterName")
   public DifferentialDrivetrainSim(
       DCMotor driveMotor,
       double gearing,
@@ -153,7 +147,6 @@
    *
    * @param dtSeconds the time difference
    */
-  @SuppressWarnings("LocalVariableName")
   public void update(double dtSeconds) {
     // Update state estimate with RK4
     m_x = NumericalIntegration.rk4(this::getDynamics, m_x, m_u, dtSeconds);
@@ -316,14 +309,13 @@
     m_x.set(State.kRightPosition.value, 0, 0);
   }
 
-  @SuppressWarnings({"DuplicatedCode", "LocalVariableName", "ParameterName"})
   protected Matrix<N7, N1> getDynamics(Matrix<N7, N1> x, Matrix<N2, N1> u) {
     // Because G can be factored out of B, we can divide by the old ratio and multiply
     // by the new ratio to get a new drivetrain model.
     var B = new Matrix<>(Nat.N4(), Nat.N2());
     B.assignBlock(0, 0, m_plant.getB().times(this.m_currentGearing / this.m_originalGearing));
 
-    // Because G^2 can be factored out of A, we can divide by the old ratio squared and multiply
+    // Because G² can be factored out of A, we can divide by the old ratio squared and multiply
     // by the new ratio squared to get a new drivetrain model.
     var A = new Matrix<>(Nat.N4(), Nat.N4());
     A.assignBlock(
@@ -373,10 +365,8 @@
     kLeftPosition(5),
     kRightPosition(6);
 
-    @SuppressWarnings("MemberName")
     public final int value;
 
-    @SuppressWarnings("ParameterName")
     State(int i) {
       this.value = i;
     }
@@ -393,10 +383,8 @@
     k7p31(7.31),
     k5p95(5.95);
 
-    @SuppressWarnings("MemberName")
     public final double value;
 
-    @SuppressWarnings("ParameterName")
     KitbotGearing(double i) {
       this.value = i;
     }
@@ -413,10 +401,8 @@
     kSingleNEOPerSide(DCMotor.getNEO(1)),
     kDoubleNEOPerSide(DCMotor.getNEO(2));
 
-    @SuppressWarnings("MemberName")
     public final DCMotor value;
 
-    @SuppressWarnings("ParameterName")
     KitbotMotor(DCMotor i) {
       this.value = i;
     }
@@ -426,19 +412,10 @@
   public enum KitbotWheelSize {
     kSixInch(Units.inchesToMeters(6)),
     kEightInch(Units.inchesToMeters(8)),
-    kTenInch(Units.inchesToMeters(10)),
+    kTenInch(Units.inchesToMeters(10));
 
-    @Deprecated
-    SixInch(Units.inchesToMeters(6)),
-    @Deprecated
-    EightInch(Units.inchesToMeters(8)),
-    @Deprecated
-    TenInch(Units.inchesToMeters(10));
-
-    @SuppressWarnings("MemberName")
     public final double value;
 
-    @SuppressWarnings("ParameterName")
     KitbotWheelSize(double i) {
       this.value = i;
     }
@@ -462,7 +439,7 @@
       KitbotGearing gearing,
       KitbotWheelSize wheelSize,
       Matrix<N7, N1> measurementStdDevs) {
-    // MOI estimation -- note that I = m r^2 for point masses
+    // MOI estimation -- note that I = mr² for point masses
     var batteryMoi = 12.5 / 2.2 * Math.pow(Units.inchesToMeters(10), 2);
     var gearboxMoi =
         (2.8 /* CIM motor */ * 2 / 2.2 + 2.0 /* Toughbox Mini- ish */)
@@ -486,7 +463,6 @@
    *     point.
    * @return A sim for the standard FRC kitbot.
    */
-  @SuppressWarnings("ParameterName")
   public static DifferentialDrivetrainSim createKitbotSim(
       KitbotMotor motor,
       KitbotGearing gearing,
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DoubleSolenoidSim.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DoubleSolenoidSim.java
new file mode 100644
index 0000000..baf3b02
--- /dev/null
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DoubleSolenoidSim.java
@@ -0,0 +1,88 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj.simulation;
+
+import edu.wpi.first.wpilibj.DoubleSolenoid;
+import edu.wpi.first.wpilibj.PneumaticsBase;
+import edu.wpi.first.wpilibj.PneumaticsModuleType;
+
+/** Class to control a simulated {@link edu.wpi.first.wpilibj.DoubleSolenoid}. */
+public class DoubleSolenoidSim {
+  private final PneumaticsBaseSim m_module;
+  private final int m_fwd;
+  private final int m_rev;
+
+  /**
+   * Constructs for a solenoid on the given pneumatics module.
+   *
+   * @param moduleSim the PCM the solenoid is connected to.
+   * @param fwd the forward solenoid channel.
+   * @param rev the reverse solenoid channel.
+   */
+  public DoubleSolenoidSim(PneumaticsBaseSim moduleSim, int fwd, int rev) {
+    m_module = moduleSim;
+    m_fwd = fwd;
+    m_rev = rev;
+  }
+
+  /**
+   * Constructs for a solenoid on a pneumatics module of the given type and ID.
+   *
+   * @param module the CAN ID of the pneumatics module the solenoid is connected to.
+   * @param moduleType the module type (PH or PCM)
+   * @param fwd the forward solenoid channel.
+   * @param rev the reverse solenoid channel.
+   */
+  public DoubleSolenoidSim(int module, PneumaticsModuleType moduleType, int fwd, int rev) {
+    this(PneumaticsBaseSim.getForType(module, moduleType), fwd, rev);
+  }
+
+  /**
+   * Constructs for a solenoid on a pneumatics module of the given type and default ID.
+   *
+   * @param moduleType the module type (PH or PCM)
+   * @param fwd the forward solenoid channel.
+   * @param rev the reverse solenoid channel.
+   */
+  public DoubleSolenoidSim(PneumaticsModuleType moduleType, int fwd, int rev) {
+    this(PneumaticsBase.getDefaultForType(moduleType), moduleType, fwd, rev);
+  }
+
+  /**
+   * Check the value of the double solenoid output.
+   *
+   * @return the output value of the double solenoid.
+   */
+  public DoubleSolenoid.Value get() {
+    boolean fwdState = m_module.getSolenoidOutput(m_fwd);
+    boolean revState = m_module.getSolenoidOutput(m_rev);
+    if (fwdState && !revState) {
+      return DoubleSolenoid.Value.kForward;
+    } else if (!fwdState && revState) {
+      return DoubleSolenoid.Value.kReverse;
+    } else {
+      return DoubleSolenoid.Value.kOff;
+    }
+  }
+
+  /**
+   * Set the value of the double solenoid output.
+   *
+   * @param value The value to set (Off, Forward, Reverse)
+   */
+  public void set(final DoubleSolenoid.Value value) {
+    m_module.setSolenoidOutput(m_fwd, value == DoubleSolenoid.Value.kForward);
+    m_module.setSolenoidOutput(m_rev, value == DoubleSolenoid.Value.kReverse);
+  }
+
+  /**
+   * Get the wrapped {@link PneumaticsBaseSim} object.
+   *
+   * @return the wrapped {@link PneumaticsBaseSim} object.
+   */
+  public PneumaticsBaseSim getModuleSim() {
+    return m_module;
+  }
+}
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DriverStationSim.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DriverStationSim.java
index f6da659..a429e71 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DriverStationSim.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DriverStationSim.java
@@ -5,8 +5,10 @@
 package edu.wpi.first.wpilibj.simulation;
 
 import edu.wpi.first.hal.AllianceStationID;
+import edu.wpi.first.hal.DriverStationJNI;
 import edu.wpi.first.hal.simulation.DriverStationDataJNI;
 import edu.wpi.first.hal.simulation.NotifyCallback;
+import edu.wpi.first.util.WPIUtilJNI;
 import edu.wpi.first.wpilibj.DriverStation;
 
 /** Class to control a simulated driver station. */
@@ -138,7 +140,6 @@
    *
    * @param eStop true to activate
    */
-  @SuppressWarnings("ParameterName")
   public static void setEStop(boolean eStop) {
     DriverStationDataJNI.setEStop(eStop);
   }
@@ -311,8 +312,17 @@
 
   /** Updates DriverStation data so that new values are visible to the user program. */
   public static void notifyNewData() {
+    int handle = WPIUtilJNI.createEvent(false, false);
+    DriverStationJNI.provideNewDataEventHandle(handle);
     DriverStationDataJNI.notifyNewData();
-    DriverStation.waitForData();
+    try {
+      WPIUtilJNI.waitForObject(handle);
+    } catch (InterruptedException e) {
+      e.printStackTrace();
+    }
+    DriverStationJNI.removeNewDataEventHandle(handle);
+    WPIUtilJNI.destroyEvent(handle);
+    DriverStation.refreshData();
   }
 
   /**
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ElevatorSim.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ElevatorSim.java
index ecd2379..025260a 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ElevatorSim.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ElevatorSim.java
@@ -30,6 +30,9 @@
   // The max allowable height for the elevator.
   private final double m_maxHeight;
 
+  // Whether the simulator should simulate gravity.
+  private final boolean m_simulateGravity;
+
   /**
    * Creates a simulated elevator mechanism.
    *
@@ -39,6 +42,7 @@
    * @param drumRadiusMeters The radius of the drum that the elevator spool is wrapped around.
    * @param minHeightMeters The min allowable height of the elevator.
    * @param maxHeightMeters The max allowable height of the elevator.
+   * @param simulateGravity Whether gravity should be simulated or not.
    */
   public ElevatorSim(
       LinearSystem<N2, N1, N1> plant,
@@ -46,8 +50,17 @@
       double gearing,
       double drumRadiusMeters,
       double minHeightMeters,
-      double maxHeightMeters) {
-    this(plant, gearbox, gearing, drumRadiusMeters, minHeightMeters, maxHeightMeters, null);
+      double maxHeightMeters,
+      boolean simulateGravity) {
+    this(
+        plant,
+        gearbox,
+        gearing,
+        drumRadiusMeters,
+        minHeightMeters,
+        maxHeightMeters,
+        simulateGravity,
+        null);
   }
 
   /**
@@ -59,6 +72,7 @@
    * @param drumRadiusMeters The radius of the drum that the elevator spool is wrapped around.
    * @param minHeightMeters The min allowable height of the elevator.
    * @param maxHeightMeters The max allowable height of the elevator.
+   * @param simulateGravity Whether gravity should be simulated or not.
    * @param measurementStdDevs The standard deviations of the measurements.
    */
   public ElevatorSim(
@@ -68,6 +82,7 @@
       double drumRadiusMeters,
       double minHeightMeters,
       double maxHeightMeters,
+      boolean simulateGravity,
       Matrix<N1, N1> measurementStdDevs) {
     super(plant, measurementStdDevs);
     m_gearbox = gearbox;
@@ -75,6 +90,7 @@
     m_drumRadius = drumRadiusMeters;
     m_minHeight = minHeightMeters;
     m_maxHeight = maxHeightMeters;
+    m_simulateGravity = simulateGravity;
   }
 
   /**
@@ -86,6 +102,7 @@
    * @param drumRadiusMeters The radius of the drum that the elevator spool is wrapped around.
    * @param minHeightMeters The min allowable height of the elevator.
    * @param maxHeightMeters The max allowable height of the elevator.
+   * @param simulateGravity Whether gravity should be simulated or not.
    */
   public ElevatorSim(
       DCMotor gearbox,
@@ -93,9 +110,17 @@
       double carriageMassKg,
       double drumRadiusMeters,
       double minHeightMeters,
-      double maxHeightMeters) {
+      double maxHeightMeters,
+      boolean simulateGravity) {
     this(
-        gearbox, gearing, carriageMassKg, drumRadiusMeters, minHeightMeters, maxHeightMeters, null);
+        gearbox,
+        gearing,
+        carriageMassKg,
+        drumRadiusMeters,
+        minHeightMeters,
+        maxHeightMeters,
+        simulateGravity,
+        null);
   }
 
   /**
@@ -107,6 +132,7 @@
    * @param drumRadiusMeters The radius of the drum that the elevator spool is wrapped around.
    * @param minHeightMeters The min allowable height of the elevator.
    * @param maxHeightMeters The max allowable height of the elevator.
+   * @param simulateGravity Whether gravity should be simulated or not.
    * @param measurementStdDevs The standard deviations of the measurements.
    */
   public ElevatorSim(
@@ -116,6 +142,7 @@
       double drumRadiusMeters,
       double minHeightMeters,
       double maxHeightMeters,
+      boolean simulateGravity,
       Matrix<N1, N1> measurementStdDevs) {
     super(
         LinearSystemId.createElevatorSystem(gearbox, carriageMassKg, drumRadiusMeters, gearing),
@@ -125,6 +152,7 @@
     m_drumRadius = drumRadiusMeters;
     m_minHeight = minHeightMeters;
     m_maxHeight = maxHeightMeters;
+    m_simulateGravity = simulateGravity;
   }
 
   /**
@@ -216,16 +244,18 @@
    * @param u The system inputs (voltage).
    * @param dtSeconds The time difference between controller updates.
    */
-  @SuppressWarnings({"ParameterName", "LambdaParameterName"})
   @Override
   protected Matrix<N2, N1> updateX(Matrix<N2, N1> currentXhat, Matrix<N1, N1> u, double dtSeconds) {
     // Calculate updated x-hat from Runge-Kutta.
     var updatedXhat =
         NumericalIntegration.rkdp(
-            (x, u_) ->
-                (m_plant.getA().times(x))
-                    .plus(m_plant.getB().times(u_))
-                    .plus(VecBuilder.fill(0, -9.8)),
+            (x, _u) -> {
+              Matrix<N2, N1> xdot = m_plant.getA().times(x).plus(m_plant.getB().times(_u));
+              if (m_simulateGravity) {
+                xdot = xdot.plus(VecBuilder.fill(0, -9.8));
+              }
+              return xdot;
+            },
             currentXhat,
             u,
             dtSeconds);
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/FlywheelSim.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/FlywheelSim.java
index aaf13de..90f911d 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/FlywheelSim.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/FlywheelSim.java
@@ -58,7 +58,6 @@
    * @param jKgMetersSquared The moment of inertia of the flywheel. If this is unknown, use the
    *     {@link #FlywheelSim(LinearSystem, DCMotor, double, Matrix)} constructor.
    */
-  @SuppressWarnings("ParameterName")
   public FlywheelSim(DCMotor gearbox, double gearing, double jKgMetersSquared) {
     super(LinearSystemId.createFlywheelSystem(gearbox, jKgMetersSquared, gearing));
     m_gearbox = gearbox;
@@ -74,7 +73,6 @@
    *     {@link #FlywheelSim(LinearSystem, DCMotor, double, Matrix)} constructor.
    * @param measurementStdDevs The standard deviations of the measurements.
    */
-  @SuppressWarnings("ParameterName")
   public FlywheelSim(
       DCMotor gearbox, double gearing, double jKgMetersSquared, Matrix<N1, N1> measurementStdDevs) {
     super(
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/GenericHIDSim.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/GenericHIDSim.java
index c5878ca..8a81f53 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/GenericHIDSim.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/GenericHIDSim.java
@@ -118,7 +118,7 @@
   }
 
   /**
-   * Set the type of an axis.
+   * Set the type of the provided axis channel.
    *
    * @param axis the axis
    * @param type the type
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/LinearSystemSim.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/LinearSystemSim.java
index e6ffbca..73b1170 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/LinearSystemSim.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/LinearSystemSim.java
@@ -27,19 +27,13 @@
  * @param <Inputs> The number of inputs to the system.
  * @param <Outputs> The number of outputs of the system.
  */
-@SuppressWarnings("ClassTypeParameterName")
 public class LinearSystemSim<States extends Num, Inputs extends Num, Outputs extends Num> {
   // The plant that represents the linear system.
   protected final LinearSystem<States, Inputs, Outputs> m_plant;
 
   // Variables for state, output, and input.
-  @SuppressWarnings("MemberName")
   protected Matrix<States, N1> m_x;
-
-  @SuppressWarnings("MemberName")
   protected Matrix<Outputs, N1> m_y;
-
-  @SuppressWarnings("MemberName")
   protected Matrix<Inputs, N1> m_u;
 
   // The standard deviations of measurements, used for adding noise
@@ -77,7 +71,6 @@
    *
    * @param dtSeconds The time between updates.
    */
-  @SuppressWarnings("LocalVariableName")
   public void update(double dtSeconds) {
     // Update X. By default, this is the linear system dynamics X = Ax + Bu
     m_x = updateX(m_x, m_u, dtSeconds);
@@ -115,7 +108,6 @@
    *
    * @param u The system inputs.
    */
-  @SuppressWarnings("ParameterName")
   public void setInput(Matrix<Inputs, N1> u) {
     this.m_u = clampInput(u);
   }
@@ -136,7 +128,6 @@
    *
    * @param u An array of doubles that represent the inputs of the system.
    */
-  @SuppressWarnings("ParameterName")
   public void setInput(double... u) {
     if (u.length != m_u.getNumRows()) {
       throw new MatrixDimensionException(
@@ -172,7 +163,6 @@
    * @param dtSeconds The time difference between controller updates.
    * @return The new state.
    */
-  @SuppressWarnings("ParameterName")
   protected Matrix<States, N1> updateX(
       Matrix<States, N1> currentXhat, Matrix<Inputs, N1> u, double dtSeconds) {
     return m_plant.calculateX(currentXhat, u, dtSeconds);
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/PS4ControllerSim.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/PS4ControllerSim.java
index 69109b8..fa19760 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/PS4ControllerSim.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/PS4ControllerSim.java
@@ -17,6 +17,7 @@
     super(joystick);
     setAxisCount(6);
     setButtonCount(14);
+    setPOVCount(1);
   }
 
   /**
@@ -28,6 +29,7 @@
     super(port);
     setAxisCount(6);
     setButtonCount(14);
+    setPOVCount(1);
   }
 
   /**
@@ -67,7 +69,7 @@
   }
 
   /**
-   * Change the L2 axis axis value of the controller.
+   * Change the L2 axis value of the controller.
    *
    * @param value the new value
    */
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/PWMSim.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/PWMSim.java
index 8a60e52..79781c4 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/PWMSim.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/PWMSim.java
@@ -7,6 +7,7 @@
 import edu.wpi.first.hal.simulation.NotifyCallback;
 import edu.wpi.first.hal.simulation.PWMDataJNI;
 import edu.wpi.first.wpilibj.PWM;
+import edu.wpi.first.wpilibj.motorcontrol.PWMMotorController;
 
 /** Class to control a simulated PWM output. */
 public class PWMSim {
@@ -22,6 +23,15 @@
   }
 
   /**
+   * Constructs from a PWMMotorController object.
+   *
+   * @param motorctrl PWMMotorController to simulate
+   */
+  public PWMSim(PWMMotorController motorctrl) {
+    m_index = motorctrl.getChannel();
+  }
+
+  /**
    * Constructs from a PWM channel number.
    *
    * @param channel Channel number
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/PneumaticsBaseSim.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/PneumaticsBaseSim.java
new file mode 100644
index 0000000..156562b
--- /dev/null
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/PneumaticsBaseSim.java
@@ -0,0 +1,171 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj.simulation;
+
+import edu.wpi.first.hal.simulation.NotifyCallback;
+import edu.wpi.first.wpilibj.PneumaticsBase;
+import edu.wpi.first.wpilibj.PneumaticsModuleType;
+
+/** Common base class for pneumatics module simulation classes. */
+public abstract class PneumaticsBaseSim {
+  protected final int m_index;
+
+  /**
+   * Get a module sim for a specific type.
+   *
+   * @param module the module number / CAN ID.
+   * @param type the module type.
+   * @return the module object.
+   */
+  public static PneumaticsBaseSim getForType(int module, PneumaticsModuleType type) {
+    switch (type) {
+      case CTREPCM:
+        return new CTREPCMSim(module);
+      case REVPH:
+        return new REVPHSim(module);
+      default:
+        throw new IllegalArgumentException("Unknown module type");
+    }
+  }
+
+  protected PneumaticsBaseSim(int index) {
+    m_index = index;
+  }
+
+  protected PneumaticsBaseSim(PneumaticsBase module) {
+    this(module.getModuleNumber());
+  }
+
+  /**
+   * Check whether the PCM/PH has been initialized.
+   *
+   * @return true if initialized
+   */
+  public abstract boolean getInitialized();
+
+  /**
+   * Define whether the PCM/PH has been initialized.
+   *
+   * @param initialized true for initialized
+   */
+  public abstract void setInitialized(boolean initialized);
+
+  /**
+   * Register a callback to be run when the PCM/PH is initialized.
+   *
+   * @param callback the callback
+   * @param initialNotify whether to run the callback with the initial state
+   * @return the {@link CallbackStore} object associated with this callback. Save a reference to
+   *     this object so GC doesn't cancel the callback.
+   */
+  public abstract CallbackStore registerInitializedCallback(
+      NotifyCallback callback, boolean initialNotify);
+
+  /**
+   * Check if the compressor is on.
+   *
+   * @return true if the compressor is active
+   */
+  public abstract boolean getCompressorOn();
+
+  /**
+   * Set whether the compressor is active.
+   *
+   * @param compressorOn the new value
+   */
+  public abstract void setCompressorOn(boolean compressorOn);
+
+  /**
+   * Register a callback to be run when the compressor activates.
+   *
+   * @param callback the callback
+   * @param initialNotify whether to run the callback with the initial state
+   * @return the {@link CallbackStore} object associated with this callback. Save a reference to
+   *     this object so GC doesn't cancel the callback.
+   */
+  public abstract CallbackStore registerCompressorOnCallback(
+      NotifyCallback callback, boolean initialNotify);
+
+  /**
+   * Check the solenoid output on a specific channel.
+   *
+   * @param channel the channel to check
+   * @return the solenoid output
+   */
+  public abstract boolean getSolenoidOutput(int channel);
+
+  /**
+   * Change the solenoid output on a specific channel.
+   *
+   * @param channel the channel to check
+   * @param solenoidOutput the new solenoid output
+   */
+  public abstract void setSolenoidOutput(int channel, boolean solenoidOutput);
+
+  /**
+   * Register a callback to be run when the solenoid output on a channel changes.
+   *
+   * @param channel the channel to monitor
+   * @param callback the callback
+   * @param initialNotify should the callback be run with the initial value
+   * @return the {@link CallbackStore} object associated with this callback. Save a reference to
+   *     this object so GC doesn't cancel the callback.
+   */
+  public abstract CallbackStore registerSolenoidOutputCallback(
+      int channel, NotifyCallback callback, boolean initialNotify);
+
+  /**
+   * Check the value of the pressure switch.
+   *
+   * @return the pressure switch value
+   */
+  public abstract boolean getPressureSwitch();
+
+  /**
+   * Set the value of the pressure switch.
+   *
+   * @param pressureSwitch the new value
+   */
+  public abstract void setPressureSwitch(boolean pressureSwitch);
+
+  /**
+   * Register a callback to be run whenever the pressure switch value changes.
+   *
+   * @param callback the callback
+   * @param initialNotify whether the callback should be called with the initial value
+   * @return the {@link CallbackStore} object associated with this callback. Save a reference to
+   *     this object so GC doesn't cancel the callback.
+   */
+  public abstract CallbackStore registerPressureSwitchCallback(
+      NotifyCallback callback, boolean initialNotify);
+
+  /**
+   * Read the compressor current.
+   *
+   * @return the current of the compressor connected to this module
+   */
+  public abstract double getCompressorCurrent();
+
+  /**
+   * Set the compressor current.
+   *
+   * @param compressorCurrent the new compressor current
+   */
+  public abstract void setCompressorCurrent(double compressorCurrent);
+
+  /**
+   * Register a callback to be run whenever the compressor current changes.
+   *
+   * @param callback the callback
+   * @param initialNotify whether to call the callback with the initial state
+   * @return the {@link CallbackStore} object associated with this callback. Save a reference to
+   *     this object so GC doesn't cancel the callback.
+   */
+  public abstract CallbackStore registerCompressorCurrentCallback(
+      NotifyCallback callback, boolean initialNotify);
+
+  /** Reset all simulation data for this object. */
+  public abstract void resetData();
+}
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/REVPHSim.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/REVPHSim.java
index 8e07da3..055cecc 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/REVPHSim.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/REVPHSim.java
@@ -6,17 +6,14 @@
 
 import edu.wpi.first.hal.simulation.NotifyCallback;
 import edu.wpi.first.hal.simulation.REVPHDataJNI;
-import edu.wpi.first.wpilibj.PneumaticsBase;
+import edu.wpi.first.wpilibj.PneumaticHub;
 import edu.wpi.first.wpilibj.SensorUtil;
 
 /** Class to control a simulated PneumaticHub (PH). */
-@SuppressWarnings("AbbreviationAsWordInName")
-public class REVPHSim {
-  private final int m_index;
-
+public class REVPHSim extends PneumaticsBaseSim {
   /** Constructs for the default PH. */
   public REVPHSim() {
-    m_index = SensorUtil.getDefaultREVPHModule();
+    super(SensorUtil.getDefaultREVPHModule());
   }
 
   /**
@@ -25,129 +22,16 @@
    * @param module module number
    */
   public REVPHSim(int module) {
-    m_index = module;
+    super(module);
   }
 
   /**
-   * Constructs from a Compressor object.
+   * Constructs from a PneumaticHum object.
    *
    * @param module PCM module to simulate
    */
-  public REVPHSim(PneumaticsBase module) {
-    m_index = module.getModuleNumber();
-  }
-
-  /**
-   * Register a callback to be run when the solenoid output on a channel changes.
-   *
-   * @param channel the channel to monitor
-   * @param callback the callback
-   * @param initialNotify should the callback be run with the initial value
-   * @return the {@link CallbackStore} object associated with this callback. Save a reference to
-   *     this object so GC doesn't cancel the callback.
-   */
-  public CallbackStore registerSolenoidOutputCallback(
-      int channel, NotifyCallback callback, boolean initialNotify) {
-    int uid =
-        REVPHDataJNI.registerSolenoidOutputCallback(m_index, channel, callback, initialNotify);
-    return new CallbackStore(m_index, channel, uid, REVPHDataJNI::cancelSolenoidOutputCallback);
-  }
-
-  /**
-   * Check the solenoid output on a specific channel.
-   *
-   * @param channel the channel to check
-   * @return the solenoid output
-   */
-  public boolean getSolenoidOutput(int channel) {
-    return REVPHDataJNI.getSolenoidOutput(m_index, channel);
-  }
-
-  /**
-   * Change the solenoid output on a specific channel.
-   *
-   * @param channel the channel to check
-   * @param solenoidOutput the new solenoid output
-   */
-  public void setSolenoidOutput(int channel, boolean solenoidOutput) {
-    REVPHDataJNI.setSolenoidOutput(m_index, channel, solenoidOutput);
-  }
-
-  /**
-   * Register a callback to be run when the compressor is initialized.
-   *
-   * @param callback the callback
-   * @param initialNotify whether to run the callback with the initial state
-   * @return the {@link CallbackStore} object associated with this callback. Save a reference to
-   *     this object so GC doesn't cancel the callback.
-   */
-  public CallbackStore registerInitializedCallback(NotifyCallback callback, boolean initialNotify) {
-    int uid = REVPHDataJNI.registerInitializedCallback(m_index, callback, initialNotify);
-    return new CallbackStore(m_index, uid, REVPHDataJNI::cancelInitializedCallback);
-  }
-
-  /**
-   * Check whether the compressor has been initialized.
-   *
-   * @return true if initialized
-   */
-  public boolean getInitialized() {
-    return REVPHDataJNI.getInitialized(m_index);
-  }
-
-  /**
-   * Define whether the compressor has been initialized.
-   *
-   * @param initialized whether the compressor is initialized
-   */
-  public void setInitialized(boolean initialized) {
-    REVPHDataJNI.setInitialized(m_index, initialized);
-  }
-
-  /**
-   * Register a callback to be run when the compressor activates.
-   *
-   * @param callback the callback
-   * @param initialNotify whether to run the callback with the initial state
-   * @return the {@link CallbackStore} object associated with this callback. Save a reference to
-   *     this object so GC doesn't cancel the callback.
-   */
-  public CallbackStore registerCompressorOnCallback(
-      NotifyCallback callback, boolean initialNotify) {
-    int uid = REVPHDataJNI.registerCompressorOnCallback(m_index, callback, initialNotify);
-    return new CallbackStore(m_index, uid, REVPHDataJNI::cancelCompressorOnCallback);
-  }
-
-  /**
-   * Check if the compressor is on.
-   *
-   * @return true if the compressor is active
-   */
-  public boolean getCompressorOn() {
-    return REVPHDataJNI.getCompressorOn(m_index);
-  }
-
-  /**
-   * Set whether the compressor is active.
-   *
-   * @param compressorOn the new value
-   */
-  public void setCompressorOn(boolean compressorOn) {
-    REVPHDataJNI.setCompressorOn(m_index, compressorOn);
-  }
-
-  /**
-   * Register a callback to be run whenever the closed loop state changes.
-   *
-   * @param callback the callback
-   * @param initialNotify whether the callback should be called with the initial value
-   * @return the {@link CallbackStore} object associated with this callback. Save a reference to
-   *     this object so GC doesn't cancel the callback.
-   */
-  public CallbackStore registerCompressorConfigTypeCallback(
-      NotifyCallback callback, boolean initialNotify) {
-    int uid = REVPHDataJNI.registerCompressorConfigTypeCallback(m_index, callback, initialNotify);
-    return new CallbackStore(m_index, uid, REVPHDataJNI::cancelCompressorConfigTypeCallback);
+  public REVPHSim(PneumaticHub module) {
+    super(module);
   }
 
   /**
@@ -169,70 +53,105 @@
   }
 
   /**
-   * Register a callback to be run whenever the pressure switch value changes.
+   * Register a callback to be run whenever the closed loop state changes.
    *
    * @param callback the callback
    * @param initialNotify whether the callback should be called with the initial value
    * @return the {@link CallbackStore} object associated with this callback. Save a reference to
    *     this object so GC doesn't cancel the callback.
    */
+  public CallbackStore registerCompressorConfigTypeCallback(
+      NotifyCallback callback, boolean initialNotify) {
+    int uid = REVPHDataJNI.registerCompressorConfigTypeCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, REVPHDataJNI::cancelCompressorConfigTypeCallback);
+  }
+
+  @Override
+  public boolean getInitialized() {
+    return REVPHDataJNI.getInitialized(m_index);
+  }
+
+  @Override
+  public void setInitialized(boolean initialized) {
+    REVPHDataJNI.setInitialized(m_index, initialized);
+  }
+
+  @Override
+  public CallbackStore registerInitializedCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = REVPHDataJNI.registerInitializedCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, REVPHDataJNI::cancelInitializedCallback);
+  }
+
+  @Override
+  public boolean getCompressorOn() {
+    return REVPHDataJNI.getCompressorOn(m_index);
+  }
+
+  @Override
+  public void setCompressorOn(boolean compressorOn) {
+    REVPHDataJNI.setCompressorOn(m_index, compressorOn);
+  }
+
+  @Override
+  public CallbackStore registerCompressorOnCallback(
+      NotifyCallback callback, boolean initialNotify) {
+    int uid = REVPHDataJNI.registerCompressorOnCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, REVPHDataJNI::cancelCompressorOnCallback);
+  }
+
+  @Override
+  public boolean getSolenoidOutput(int channel) {
+    return REVPHDataJNI.getSolenoidOutput(m_index, channel);
+  }
+
+  @Override
+  public void setSolenoidOutput(int channel, boolean solenoidOutput) {
+    REVPHDataJNI.setSolenoidOutput(m_index, channel, solenoidOutput);
+  }
+
+  @Override
+  public CallbackStore registerSolenoidOutputCallback(
+      int channel, NotifyCallback callback, boolean initialNotify) {
+    int uid =
+        REVPHDataJNI.registerSolenoidOutputCallback(m_index, channel, callback, initialNotify);
+    return new CallbackStore(m_index, channel, uid, REVPHDataJNI::cancelSolenoidOutputCallback);
+  }
+
+  @Override
+  public boolean getPressureSwitch() {
+    return REVPHDataJNI.getPressureSwitch(m_index);
+  }
+
+  @Override
+  public void setPressureSwitch(boolean pressureSwitch) {
+    REVPHDataJNI.setPressureSwitch(m_index, pressureSwitch);
+  }
+
+  @Override
   public CallbackStore registerPressureSwitchCallback(
       NotifyCallback callback, boolean initialNotify) {
     int uid = REVPHDataJNI.registerPressureSwitchCallback(m_index, callback, initialNotify);
     return new CallbackStore(m_index, uid, REVPHDataJNI::cancelPressureSwitchCallback);
   }
 
-  /**
-   * Check the value of the pressure switch.
-   *
-   * @return the pressure switch value
-   */
-  public boolean getPressureSwitch() {
-    return REVPHDataJNI.getPressureSwitch(m_index);
+  @Override
+  public double getCompressorCurrent() {
+    return REVPHDataJNI.getCompressorCurrent(m_index);
   }
 
-  /**
-   * Set the value of the pressure switch.
-   *
-   * @param pressureSwitch the new value
-   */
-  public void setPressureSwitch(boolean pressureSwitch) {
-    REVPHDataJNI.setPressureSwitch(m_index, pressureSwitch);
+  @Override
+  public void setCompressorCurrent(double compressorCurrent) {
+    REVPHDataJNI.setCompressorCurrent(m_index, compressorCurrent);
   }
 
-  /**
-   * Register a callback to be run whenever the compressor current changes.
-   *
-   * @param callback the callback
-   * @param initialNotify whether to call the callback with the initial state
-   * @return the {@link CallbackStore} object associated with this callback. Save a reference to
-   *     this object so GC doesn't cancel the callback.
-   */
+  @Override
   public CallbackStore registerCompressorCurrentCallback(
       NotifyCallback callback, boolean initialNotify) {
     int uid = REVPHDataJNI.registerCompressorCurrentCallback(m_index, callback, initialNotify);
     return new CallbackStore(m_index, uid, REVPHDataJNI::cancelCompressorCurrentCallback);
   }
 
-  /**
-   * Read the compressor current.
-   *
-   * @return the current of the compressor connected to this module
-   */
-  public double getCompressorCurrent() {
-    return REVPHDataJNI.getCompressorCurrent(m_index);
-  }
-
-  /**
-   * Set the compressor current.
-   *
-   * @param compressorCurrent the new compressor current
-   */
-  public void setCompressorCurrent(double compressorCurrent) {
-    REVPHDataJNI.setCompressorCurrent(m_index, compressorCurrent);
-  }
-
-  /** Reset all simulation data for this object. */
+  @Override
   public void resetData() {
     REVPHDataJNI.resetData(m_index);
   }
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/RoboRioSim.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/RoboRioSim.java
index 976ba4a..d128da8 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/RoboRioSim.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/RoboRioSim.java
@@ -21,7 +21,6 @@
    * @return the {@link CallbackStore} object associated with this callback. Save a reference to
    *     this object so GC doesn't cancel the callback.
    */
-  @SuppressWarnings("AbbreviationAsWordInName")
   public static CallbackStore registerFPGAButtonCallback(
       NotifyCallback callback, boolean initialNotify) {
     int uid = RoboRioDataJNI.registerFPGAButtonCallback(callback, initialNotify);
@@ -33,7 +32,6 @@
    *
    * @return the FPGA button state
    */
-  @SuppressWarnings("AbbreviationAsWordInName")
   public static boolean getFPGAButton() {
     return RoboRioDataJNI.getFPGAButton();
   }
@@ -43,7 +41,6 @@
    *
    * @param fpgaButton the new state
    */
-  @SuppressWarnings("AbbreviationAsWordInName")
   public static void setFPGAButton(boolean fpgaButton) {
     RoboRioDataJNI.setFPGAButton(fpgaButton);
   }
@@ -76,7 +73,6 @@
    *
    * @param vInVoltage the new voltage
    */
-  @SuppressWarnings("ParameterName")
   public static void setVInVoltage(double vInVoltage) {
     RoboRioDataJNI.setVInVoltage(vInVoltage);
   }
@@ -109,7 +105,6 @@
    *
    * @param vInCurrent the new current
    */
-  @SuppressWarnings("ParameterName")
   public static void setVInCurrent(double vInCurrent) {
     RoboRioDataJNI.setVInCurrent(vInCurrent);
   }
@@ -526,11 +521,46 @@
    *
    * @param vInVoltage the new voltage
    */
-  @SuppressWarnings("ParameterName")
   public static void setBrownoutVoltage(double vInVoltage) {
     RoboRioDataJNI.setBrownoutVoltage(vInVoltage);
   }
 
+  /**
+   * Get the serial number.
+   *
+   * @return The serial number.
+   */
+  public static String getSerialNumber() {
+    return RoboRioDataJNI.getSerialNumber();
+  }
+
+  /**
+   * Set the serial number.
+   *
+   * @param serialNumber The serial number.
+   */
+  public static void setSerialNumber(String serialNumber) {
+    RoboRioDataJNI.setSerialNumber(serialNumber);
+  }
+
+  /**
+   * Get the comments string.
+   *
+   * @return The comments string.
+   */
+  public static String getComments() {
+    return RoboRioDataJNI.getComments();
+  }
+
+  /**
+   * Set the comments string.
+   *
+   * @param comments The comments string.
+   */
+  public static void setComments(String comments) {
+    RoboRioDataJNI.setComments(comments);
+  }
+
   /** Reset all simulation data. */
   public static void resetData() {
     RoboRioDataJNI.resetData();
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SPIAccelerometerSim.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SPIAccelerometerSim.java
index da1213a..24e3cca 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SPIAccelerometerSim.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SPIAccelerometerSim.java
@@ -109,7 +109,6 @@
    *
    * @param x the new reading of the X axis
    */
-  @SuppressWarnings("ParameterName")
   public void setX(double x) {
     SPIAccelerometerDataJNI.setX(m_index, x);
   }
@@ -141,7 +140,6 @@
    *
    * @param y the new reading of the Y axis
    */
-  @SuppressWarnings("ParameterName")
   public void setY(double y) {
     SPIAccelerometerDataJNI.setY(m_index, y);
   }
@@ -173,7 +171,6 @@
    *
    * @param z the new reading of the Z axis
    */
-  @SuppressWarnings("ParameterName")
   public void setZ(double z) {
     SPIAccelerometerDataJNI.setZ(m_index, z);
   }
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SingleJointedArmSim.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SingleJointedArmSim.java
index 87981f7..b6a5e85 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SingleJointedArmSim.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SingleJointedArmSim.java
@@ -22,7 +22,6 @@
   private final double m_gearing;
 
   // The length of the arm.
-  @SuppressWarnings("MemberName")
   private final double m_r;
 
   // The minimum angle that the arm is capable of.
@@ -115,7 +114,6 @@
    * @param armMassKg The mass of the arm.
    * @param simulateGravity Whether gravity should be simulated or not.
    */
-  @SuppressWarnings("ParameterName")
   public SingleJointedArmSim(
       DCMotor gearbox,
       double gearing,
@@ -150,7 +148,6 @@
    * @param simulateGravity Whether gravity should be simulated or not.
    * @param measurementStdDevs The standard deviations of the measurements.
    */
-  @SuppressWarnings("ParameterName")
   public SingleJointedArmSim(
       DCMotor gearbox,
       double gearing,
@@ -180,7 +177,7 @@
    * @return Whether the arm would hit the lower limit.
    */
   public boolean wouldHitLowerLimit(double currentAngleRads) {
-    return currentAngleRads < this.m_minAngle;
+    return currentAngleRads <= this.m_minAngle;
   }
 
   /**
@@ -190,7 +187,7 @@
    * @return Whether the arm would hit the upper limit.
    */
   public boolean wouldHitUpperLimit(double currentAngleRads) {
-    return currentAngleRads > this.m_maxAngle;
+    return currentAngleRads >= this.m_maxAngle;
   }
 
   /**
@@ -270,7 +267,6 @@
    * @param dtSeconds The time difference between controller updates.
    */
   @Override
-  @SuppressWarnings({"ParameterName", "LambdaParameterName"})
   protected Matrix<N2, N1> updateX(Matrix<N2, N1> currentXhat, Matrix<N1, N1> u, double dtSeconds) {
     // Horizontal case:
     // Torque = F * r = I * alpha
@@ -283,8 +279,8 @@
     // cos(theta)]]
     Matrix<N2, N1> updatedXhat =
         NumericalIntegration.rkdp(
-            (Matrix<N2, N1> x, Matrix<N1, N1> u_) -> {
-              Matrix<N2, N1> xdot = m_plant.getA().times(x).plus(m_plant.getB().times(u_));
+            (Matrix<N2, N1> x, Matrix<N1, N1> _u) -> {
+              Matrix<N2, N1> xdot = m_plant.getA().times(x).plus(m_plant.getB().times(_u));
               if (m_simulateGravity) {
                 xdot =
                     xdot.plus(
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SolenoidSim.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SolenoidSim.java
new file mode 100644
index 0000000..39d3cc2
--- /dev/null
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SolenoidSim.java
@@ -0,0 +1,86 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj.simulation;
+
+import edu.wpi.first.hal.simulation.NotifyCallback;
+import edu.wpi.first.wpilibj.PneumaticsBase;
+import edu.wpi.first.wpilibj.PneumaticsModuleType;
+
+/** Class to control a simulated {@link edu.wpi.first.wpilibj.Solenoid}. */
+public class SolenoidSim {
+  private final PneumaticsBaseSim m_module;
+  private final int m_channel;
+
+  /**
+   * Constructs for a solenoid on the given pneumatics module.
+   *
+   * @param moduleSim the PCM the solenoid is connected to.
+   * @param channel the solenoid channel.
+   */
+  public SolenoidSim(PneumaticsBaseSim moduleSim, int channel) {
+    m_module = moduleSim;
+    m_channel = channel;
+  }
+
+  /**
+   * Constructs for a solenoid on a pneumatics module of the given type and ID.
+   *
+   * @param module the CAN ID of the pneumatics module the solenoid is connected to.
+   * @param moduleType the module type (PH or PCM)
+   * @param channel the solenoid channel.
+   */
+  public SolenoidSim(int module, PneumaticsModuleType moduleType, int channel) {
+    this(PneumaticsBaseSim.getForType(module, moduleType), channel);
+  }
+
+  /**
+   * Constructs for a solenoid on a pneumatics module of the given type and default ID.
+   *
+   * @param moduleType the module type (PH or PCM)
+   * @param channel the solenoid channel.
+   */
+  public SolenoidSim(PneumaticsModuleType moduleType, int channel) {
+    this(PneumaticsBase.getDefaultForType(moduleType), moduleType, channel);
+  }
+
+  /**
+   * Check the solenoid output.
+   *
+   * @return the solenoid output
+   */
+  public boolean getOutput() {
+    return m_module.getSolenoidOutput(m_channel);
+  }
+
+  /**
+   * Change the solenoid output.
+   *
+   * @param output the new solenoid output
+   */
+  public void setOutput(boolean output) {
+    m_module.setSolenoidOutput(m_channel, output);
+  }
+
+  /**
+   * Register a callback to be run when the output of this solenoid has changed.
+   *
+   * @param callback the callback
+   * @param initialNotify should the callback be run with the initial value
+   * @return the {@link CallbackStore} object associated with this callback. Save a reference to
+   *     this object so GC doesn't cancel the callback.
+   */
+  public CallbackStore registerOutputCallback(NotifyCallback callback, boolean initialNotify) {
+    return m_module.registerSolenoidOutputCallback(m_channel, callback, initialNotify);
+  }
+
+  /**
+   * Get the wrapped {@link PneumaticsBaseSim} object.
+   *
+   * @return the wrapped {@link PneumaticsBaseSim} object.
+   */
+  public PneumaticsBaseSim getPCMSim() {
+    return m_module;
+  }
+}
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/XboxControllerSim.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/XboxControllerSim.java
index 625ba81..41d200e 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/XboxControllerSim.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/XboxControllerSim.java
@@ -17,6 +17,7 @@
     super(joystick);
     setAxisCount(6);
     setButtonCount(10);
+    setPOVCount(1);
   }
 
   /**
@@ -28,6 +29,7 @@
     super(port);
     setAxisCount(6);
     setButtonCount(10);
+    setPOVCount(1);
   }
 
   /**
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/Field2d.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/Field2d.java
index b76f056..bfacb42 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/Field2d.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/Field2d.java
@@ -29,7 +29,7 @@
  * using the getObject() function. Other objects can also have multiple poses (which will show the
  * object at multiple locations).
  */
-public class Field2d implements NTSendable {
+public class Field2d implements NTSendable, AutoCloseable {
   /** Constructor. */
   public Field2d() {
     FieldObject2d obj = new FieldObject2d("Robot");
@@ -38,6 +38,13 @@
     SendableRegistry.add(this, "Field");
   }
 
+  @Override
+  public void close() {
+    for (FieldObject2d obj : m_objects) {
+      obj.close();
+    }
+  }
+
   /**
    * Set the robot pose from a Pose object.
    *
@@ -54,7 +61,6 @@
    * @param yMeters Y location, in meters
    * @param rotation rotation
    */
-  @SuppressWarnings("ParameterName")
   public synchronized void setRobotPose(double xMeters, double yMeters, Rotation2d rotation) {
     m_objects.get(0).setPose(xMeters, yMeters, rotation);
   }
@@ -84,7 +90,7 @@
     m_objects.add(obj);
     if (m_table != null) {
       synchronized (obj) {
-        obj.m_entry = m_table.getEntry(name);
+        obj.m_entry = m_table.getDoubleArrayTopic(name).getEntry(new double[] {});
       }
     }
     return obj;
@@ -107,7 +113,7 @@
       m_table = builder.getTable();
       for (FieldObject2d obj : m_objects) {
         synchronized (obj) {
-          obj.m_entry = m_table.getEntry(obj.m_name);
+          obj.m_entry = m_table.getDoubleArrayTopic(obj.m_name).getEntry(new double[] {});
           obj.updateEntry(true);
         }
       }
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/FieldObject2d.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/FieldObject2d.java
index d6c7a5e..9ffccde 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/FieldObject2d.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/FieldObject2d.java
@@ -8,14 +8,12 @@
 import edu.wpi.first.math.geometry.Rotation2d;
 import edu.wpi.first.math.geometry.Translation2d;
 import edu.wpi.first.math.trajectory.Trajectory;
-import edu.wpi.first.networktables.NetworkTableEntry;
-import java.nio.ByteBuffer;
-import java.nio.ByteOrder;
+import edu.wpi.first.networktables.DoubleArrayEntry;
 import java.util.ArrayList;
 import java.util.List;
 
 /** Game field object on a Field2d. */
-public class FieldObject2d {
+public class FieldObject2d implements AutoCloseable {
   /**
    * Package-local constructor.
    *
@@ -25,6 +23,13 @@
     m_name = name;
   }
 
+  @Override
+  public void close() {
+    if (m_entry != null) {
+      m_entry.close();
+    }
+  }
+
   /**
    * Set the pose from a Pose object.
    *
@@ -41,7 +46,6 @@
    * @param yMeters Y location, in meters
    * @param rotation rotation
    */
-  @SuppressWarnings("ParameterName")
   public synchronized void setPose(double xMeters, double yMeters, Rotation2d rotation) {
     setPose(new Pose2d(xMeters, yMeters, rotation));
   }
@@ -60,7 +64,7 @@
   }
 
   /**
-   * Set multiple poses from an list of Pose objects. The total number of poses is limited to 85.
+   * Set multiple poses from a list of Pose objects. The total number of poses is limited to 85.
    *
    * @param poses list of 2D poses
    */
@@ -73,7 +77,7 @@
   }
 
   /**
-   * Set multiple poses from an list of Pose objects. The total number of poses is limited to 85.
+   * Set multiple poses from a list of Pose objects. The total number of poses is limited to 85.
    *
    * @param poses list of 2D poses
    */
@@ -117,39 +121,20 @@
       return;
     }
 
-    if (m_poses.size() < (255 / 3)) {
-      double[] arr = new double[m_poses.size() * 3];
-      int ndx = 0;
-      for (Pose2d pose : m_poses) {
-        Translation2d translation = pose.getTranslation();
-        arr[ndx + 0] = translation.getX();
-        arr[ndx + 1] = translation.getY();
-        arr[ndx + 2] = pose.getRotation().getDegrees();
-        ndx += 3;
-      }
+    double[] arr = new double[m_poses.size() * 3];
+    int ndx = 0;
+    for (Pose2d pose : m_poses) {
+      Translation2d translation = pose.getTranslation();
+      arr[ndx + 0] = translation.getX();
+      arr[ndx + 1] = translation.getY();
+      arr[ndx + 2] = pose.getRotation().getDegrees();
+      ndx += 3;
+    }
 
-      if (setDefault) {
-        m_entry.setDefaultDoubleArray(arr);
-      } else {
-        m_entry.setDoubleArray(arr);
-      }
+    if (setDefault) {
+      m_entry.setDefault(arr);
     } else {
-      // send as raw array of doubles if too big for NT array
-      ByteBuffer output = ByteBuffer.allocate(m_poses.size() * 3 * 8);
-      output.order(ByteOrder.BIG_ENDIAN);
-
-      for (Pose2d pose : m_poses) {
-        Translation2d translation = pose.getTranslation();
-        output.putDouble(translation.getX());
-        output.putDouble(translation.getY());
-        output.putDouble(pose.getRotation().getDegrees());
-      }
-
-      if (setDefault) {
-        m_entry.setDefaultRaw(output.array());
-      } else {
-        m_entry.forceSetRaw(output.array());
-      }
+      m_entry.set(arr);
     }
   }
 
@@ -158,7 +143,7 @@
       return;
     }
 
-    double[] arr = m_entry.getDoubleArray((double[]) null);
+    double[] arr = m_entry.get((double[]) null);
     if (arr != null) {
       if ((arr.length % 3) != 0) {
         return;
@@ -168,31 +153,10 @@
       for (int i = 0; i < arr.length; i += 3) {
         m_poses.add(new Pose2d(arr[i], arr[i + 1], Rotation2d.fromDegrees(arr[i + 2])));
       }
-    } else {
-      // read as raw array of doubles
-      byte[] data = m_entry.getRaw((byte[]) null);
-      if (data == null) {
-        return;
-      }
-
-      // must be triples of doubles
-      if ((data.length % (3 * 8)) != 0) {
-        return;
-      }
-      ByteBuffer input = ByteBuffer.wrap(data);
-      input.order(ByteOrder.BIG_ENDIAN);
-
-      m_poses.clear();
-      for (int i = 0; i < (data.length / (3 * 8)); i++) {
-        double x = input.getDouble();
-        double y = input.getDouble();
-        double rot = input.getDouble();
-        m_poses.add(new Pose2d(x, y, Rotation2d.fromDegrees(rot)));
-      }
     }
   }
 
   String m_name;
-  NetworkTableEntry m_entry;
+  DoubleArrayEntry m_entry;
   private final List<Pose2d> m_poses = new ArrayList<>();
 }
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/Mechanism2d.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/Mechanism2d.java
index 8967944..d368d35 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/Mechanism2d.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/Mechanism2d.java
@@ -4,9 +4,11 @@
 
 package edu.wpi.first.wpilibj.smartdashboard;
 
+import edu.wpi.first.networktables.DoubleArrayPublisher;
 import edu.wpi.first.networktables.NTSendable;
 import edu.wpi.first.networktables.NTSendableBuilder;
 import edu.wpi.first.networktables.NetworkTable;
+import edu.wpi.first.networktables.StringPublisher;
 import edu.wpi.first.wpilibj.util.Color8Bit;
 import java.util.HashMap;
 import java.util.Map;
@@ -23,12 +25,13 @@
  * @see MechanismLigament2d
  * @see MechanismRoot2d
  */
-public final class Mechanism2d implements NTSendable {
-  private static final String kBackgroundColor = "backgroundColor";
+public final class Mechanism2d implements NTSendable, AutoCloseable {
   private NetworkTable m_table;
   private final Map<String, MechanismRoot2d> m_roots;
   private final double[] m_dims = new double[2];
   private String m_color;
+  private DoubleArrayPublisher m_dimsPub;
+  private StringPublisher m_colorPub;
 
   /**
    * Create a new Mechanism2d with the given dimensions and default color (dark blue).
@@ -58,6 +61,19 @@
     setBackgroundColor(backgroundColor);
   }
 
+  @Override
+  public void close() {
+    if (m_dimsPub != null) {
+      m_dimsPub.close();
+    }
+    if (m_colorPub != null) {
+      m_colorPub.close();
+    }
+    for (MechanismRoot2d root : m_roots.values()) {
+      root.close();
+    }
+  }
+
   /**
    * Get or create a root in this Mechanism2d with the given name and position.
    *
@@ -88,9 +104,9 @@
    * @param color the new color
    */
   public synchronized void setBackgroundColor(Color8Bit color) {
-    this.m_color = String.format("#%02X%02X%02X", color.red, color.green, color.blue);
-    if (m_table != null) {
-      m_table.getEntry(kBackgroundColor).setString(m_color);
+    m_color = color.toHexString();
+    if (m_colorPub != null) {
+      m_colorPub.set(m_color);
     }
   }
 
@@ -99,8 +115,16 @@
     builder.setSmartDashboardType("Mechanism2d");
     synchronized (this) {
       m_table = builder.getTable();
-      m_table.getEntry("dims").setDoubleArray(m_dims);
-      m_table.getEntry(kBackgroundColor).setString(m_color);
+      if (m_dimsPub != null) {
+        m_dimsPub.close();
+      }
+      m_dimsPub = m_table.getDoubleArrayTopic("dims").publish();
+      m_dimsPub.set(m_dims);
+      if (m_colorPub != null) {
+        m_colorPub.close();
+      }
+      m_colorPub = m_table.getStringTopic("backgroundColor").publish();
+      m_colorPub.set(m_color);
       for (Entry<String, MechanismRoot2d> entry : m_roots.entrySet()) {
         String name = entry.getKey();
         MechanismRoot2d root = entry.getValue();
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/MechanismLigament2d.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/MechanismLigament2d.java
index 88236de..28484a3 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/MechanismLigament2d.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/MechanismLigament2d.java
@@ -5,8 +5,10 @@
 package edu.wpi.first.wpilibj.smartdashboard;
 
 import edu.wpi.first.math.geometry.Rotation2d;
+import edu.wpi.first.networktables.DoubleEntry;
 import edu.wpi.first.networktables.NetworkTable;
-import edu.wpi.first.networktables.NetworkTableEntry;
+import edu.wpi.first.networktables.StringEntry;
+import edu.wpi.first.networktables.StringPublisher;
 import edu.wpi.first.wpilibj.util.Color8Bit;
 
 /**
@@ -16,21 +18,22 @@
  * @see Mechanism2d
  */
 public class MechanismLigament2d extends MechanismObject2d {
+  private StringPublisher m_typePub;
   private double m_angle;
-  private NetworkTableEntry m_angleEntry;
+  private DoubleEntry m_angleEntry;
   private String m_color;
-  private NetworkTableEntry m_colorEntry;
+  private StringEntry m_colorEntry;
   private double m_length;
-  private NetworkTableEntry m_lengthEntry;
+  private DoubleEntry m_lengthEntry;
   private double m_weight;
-  private NetworkTableEntry m_weightEntry;
+  private DoubleEntry m_weightEntry;
 
   /**
    * Create a new ligament.
    *
    * @param name The ligament name.
    * @param length The ligament length.
-   * @param angle The ligament angle.
+   * @param angle The ligament angle in degrees.
    * @param lineWidth The ligament's line width.
    * @param color The ligament's color.
    */
@@ -48,20 +51,42 @@
    *
    * @param name The ligament's name.
    * @param length The ligament's length.
-   * @param angle The ligament's angle relative to its parent.
+   * @param angle The ligament's angle relative to its parent in degrees.
    */
   public MechanismLigament2d(String name, double length, double angle) {
     this(name, length, angle, 10, new Color8Bit(235, 137, 52));
   }
 
+  @Override
+  public void close() {
+    super.close();
+    if (m_typePub != null) {
+      m_typePub.close();
+    }
+    if (m_angleEntry != null) {
+      m_angleEntry.close();
+    }
+    if (m_colorEntry != null) {
+      m_colorEntry.close();
+    }
+    if (m_lengthEntry != null) {
+      m_lengthEntry.close();
+    }
+    if (m_weightEntry != null) {
+      m_weightEntry.close();
+    }
+  }
+
   /**
    * Set the ligament's angle relative to its parent.
    *
-   * @param degrees the angle, in degrees
+   * @param degrees the angle in degrees
    */
   public synchronized void setAngle(double degrees) {
     m_angle = degrees;
-    flush();
+    if (m_angleEntry != null) {
+      m_angleEntry.set(degrees);
+    }
   }
 
   /**
@@ -76,11 +101,11 @@
   /**
    * Get the ligament's angle relative to its parent.
    *
-   * @return the angle, in degrees
+   * @return the angle in degrees
    */
   public synchronized double getAngle() {
     if (m_angleEntry != null) {
-      m_angle = m_angleEntry.getDouble(0.0);
+      m_angle = m_angleEntry.get();
     }
     return m_angle;
   }
@@ -92,7 +117,9 @@
    */
   public synchronized void setLength(double length) {
     m_length = length;
-    flush();
+    if (m_lengthEntry != null) {
+      m_lengthEntry.set(length);
+    }
   }
 
   /**
@@ -102,7 +129,7 @@
    */
   public synchronized double getLength() {
     if (m_lengthEntry != null) {
-      m_length = m_lengthEntry.getDouble(0.0);
+      m_length = m_lengthEntry.get();
     }
     return m_length;
   }
@@ -114,7 +141,9 @@
    */
   public synchronized void setColor(Color8Bit color) {
     m_color = String.format("#%02X%02X%02X", color.red, color.green, color.blue);
-    flush();
+    if (m_colorEntry != null) {
+      m_colorEntry.set(m_color);
+    }
   }
 
   /**
@@ -124,7 +153,7 @@
    */
   public synchronized Color8Bit getColor() {
     if (m_colorEntry != null) {
-      m_color = m_colorEntry.getString("");
+      m_color = m_colorEntry.get();
     }
     int r = 0;
     int g = 0;
@@ -150,7 +179,9 @@
    */
   public synchronized void setLineWeight(double weight) {
     m_weight = weight;
-    flush();
+    if (m_weightEntry != null) {
+      m_weightEntry.set(weight);
+    }
   }
 
   /**
@@ -160,34 +191,41 @@
    */
   public synchronized double getLineWeight() {
     if (m_weightEntry != null) {
-      m_weight = m_weightEntry.getDouble(0.0);
+      m_weight = m_weightEntry.get();
     }
     return m_weight;
   }
 
   @Override
   protected void updateEntries(NetworkTable table) {
-    table.getEntry(".type").setString("line");
-    m_angleEntry = table.getEntry("angle");
-    m_lengthEntry = table.getEntry("length");
-    m_colorEntry = table.getEntry("color");
-    m_weightEntry = table.getEntry("weight");
-    flush();
-  }
+    if (m_typePub != null) {
+      m_typePub.close();
+    }
+    m_typePub = table.getStringTopic(".type").publish();
+    m_typePub.set("line");
 
-  /** Flush latest data to NT. */
-  private void flush() {
     if (m_angleEntry != null) {
-      m_angleEntry.setDouble(m_angle);
+      m_angleEntry.close();
     }
+    m_angleEntry = table.getDoubleTopic("angle").getEntry(0.0);
+    m_angleEntry.set(m_angle);
+
     if (m_lengthEntry != null) {
-      m_lengthEntry.setDouble(m_length);
+      m_lengthEntry.close();
     }
+    m_lengthEntry = table.getDoubleTopic("length").getEntry(0.0);
+    m_lengthEntry.set(m_length);
+
     if (m_colorEntry != null) {
-      m_colorEntry.setString(m_color);
+      m_colorEntry.close();
     }
+    m_colorEntry = table.getStringTopic("color").getEntry("");
+    m_colorEntry.set(m_color);
+
     if (m_weightEntry != null) {
-      m_weightEntry.setDouble(m_weight);
+      m_weightEntry.close();
     }
+    m_weightEntry = table.getDoubleTopic("weight").getEntry(0.0);
+    m_weightEntry.set(m_weight);
   }
 }
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/MechanismObject2d.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/MechanismObject2d.java
index 584660a..2d13ce0 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/MechanismObject2d.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/MechanismObject2d.java
@@ -16,7 +16,7 @@
  *
  * @see Mechanism2d
  */
-public abstract class MechanismObject2d {
+public abstract class MechanismObject2d implements AutoCloseable {
   /** Relative to parent. */
   private final String m_name;
 
@@ -32,6 +32,13 @@
     m_name = name;
   }
 
+  @Override
+  public void close() {
+    for (MechanismObject2d obj : m_objects.values()) {
+      obj.close();
+    }
+  }
+
   /**
    * Append a Mechanism object that is based on this one.
    *
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/MechanismRoot2d.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/MechanismRoot2d.java
index ee804b7..6091132 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/MechanismRoot2d.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/MechanismRoot2d.java
@@ -4,8 +4,8 @@
 
 package edu.wpi.first.wpilibj.smartdashboard;
 
+import edu.wpi.first.networktables.DoublePublisher;
 import edu.wpi.first.networktables.NetworkTable;
-import edu.wpi.first.networktables.NetworkTableEntry;
 import java.util.HashMap;
 import java.util.Map;
 
@@ -19,14 +19,14 @@
  *
  * <p>Append other nodes by using {@link #append(MechanismObject2d)}.
  */
-public final class MechanismRoot2d {
+public final class MechanismRoot2d implements AutoCloseable {
   private final String m_name;
   private NetworkTable m_table;
   private final Map<String, MechanismObject2d> m_objects = new HashMap<>(1);
   private double m_x;
-  private NetworkTableEntry m_xEntry;
+  private DoublePublisher m_xPub;
   private double m_y;
-  private NetworkTableEntry m_yEntry;
+  private DoublePublisher m_yPub;
 
   /**
    * Package-private constructor for roots.
@@ -41,6 +41,19 @@
     m_y = y;
   }
 
+  @Override
+  public void close() {
+    if (m_xPub != null) {
+      m_xPub.close();
+    }
+    if (m_yPub != null) {
+      m_yPub.close();
+    }
+    for (MechanismObject2d obj : m_objects.values()) {
+      obj.close();
+    }
+  }
+
   /**
    * Append a Mechanism object that is based on this one.
    *
@@ -75,8 +88,14 @@
 
   synchronized void update(NetworkTable table) {
     m_table = table;
-    m_xEntry = m_table.getEntry("x");
-    m_yEntry = m_table.getEntry("y");
+    if (m_xPub != null) {
+      m_xPub.close();
+    }
+    m_xPub = m_table.getDoubleTopic("x").publish();
+    if (m_yPub != null) {
+      m_yPub.close();
+    }
+    m_yPub = m_table.getDoubleTopic("y").publish();
     flush();
     for (MechanismObject2d obj : m_objects.values()) {
       obj.update(m_table.getSubTable(obj.getName()));
@@ -88,11 +107,11 @@
   }
 
   private void flush() {
-    if (m_xEntry != null) {
-      m_xEntry.setDouble(m_x);
+    if (m_xPub != null) {
+      m_xPub.set(m_x);
     }
-    if (m_yEntry != null) {
-      m_yEntry.setDouble(m_y);
+    if (m_yPub != null) {
+      m_yPub.set(m_y);
     }
   }
 }
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableBuilderImpl.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableBuilderImpl.java
index 6c07fe3..7bb266e 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableBuilderImpl.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableBuilderImpl.java
@@ -4,59 +4,134 @@
 
 package edu.wpi.first.wpilibj.smartdashboard;
 
-import edu.wpi.first.networktables.EntryListenerFlags;
+import edu.wpi.first.networktables.BooleanArrayPublisher;
+import edu.wpi.first.networktables.BooleanArraySubscriber;
+import edu.wpi.first.networktables.BooleanArrayTopic;
+import edu.wpi.first.networktables.BooleanPublisher;
+import edu.wpi.first.networktables.BooleanSubscriber;
+import edu.wpi.first.networktables.BooleanTopic;
+import edu.wpi.first.networktables.DoubleArrayPublisher;
+import edu.wpi.first.networktables.DoubleArraySubscriber;
+import edu.wpi.first.networktables.DoubleArrayTopic;
+import edu.wpi.first.networktables.DoublePublisher;
+import edu.wpi.first.networktables.DoubleSubscriber;
+import edu.wpi.first.networktables.DoubleTopic;
+import edu.wpi.first.networktables.FloatArrayPublisher;
+import edu.wpi.first.networktables.FloatArraySubscriber;
+import edu.wpi.first.networktables.FloatArrayTopic;
+import edu.wpi.first.networktables.FloatPublisher;
+import edu.wpi.first.networktables.FloatSubscriber;
+import edu.wpi.first.networktables.FloatTopic;
+import edu.wpi.first.networktables.IntegerArrayPublisher;
+import edu.wpi.first.networktables.IntegerArraySubscriber;
+import edu.wpi.first.networktables.IntegerArrayTopic;
+import edu.wpi.first.networktables.IntegerPublisher;
+import edu.wpi.first.networktables.IntegerSubscriber;
+import edu.wpi.first.networktables.IntegerTopic;
 import edu.wpi.first.networktables.NTSendableBuilder;
 import edu.wpi.first.networktables.NetworkTable;
-import edu.wpi.first.networktables.NetworkTableEntry;
-import edu.wpi.first.networktables.NetworkTableValue;
+import edu.wpi.first.networktables.PubSubOption;
+import edu.wpi.first.networktables.Publisher;
+import edu.wpi.first.networktables.RawPublisher;
+import edu.wpi.first.networktables.RawSubscriber;
+import edu.wpi.first.networktables.RawTopic;
+import edu.wpi.first.networktables.StringArrayPublisher;
+import edu.wpi.first.networktables.StringArraySubscriber;
+import edu.wpi.first.networktables.StringArrayTopic;
+import edu.wpi.first.networktables.StringPublisher;
+import edu.wpi.first.networktables.StringSubscriber;
+import edu.wpi.first.networktables.StringTopic;
+import edu.wpi.first.networktables.Subscriber;
+import edu.wpi.first.networktables.Topic;
+import edu.wpi.first.util.WPIUtilJNI;
 import edu.wpi.first.util.function.BooleanConsumer;
+import edu.wpi.first.util.function.FloatConsumer;
+import edu.wpi.first.util.function.FloatSupplier;
 import java.util.ArrayList;
 import java.util.List;
 import java.util.function.BooleanSupplier;
 import java.util.function.Consumer;
 import java.util.function.DoubleConsumer;
 import java.util.function.DoubleSupplier;
-import java.util.function.Function;
+import java.util.function.LongConsumer;
+import java.util.function.LongSupplier;
 import java.util.function.Supplier;
 
 public class SendableBuilderImpl implements NTSendableBuilder {
-  private static class Property {
-    Property(NetworkTable table, String key) {
-      m_entry = table.getEntry(key);
-    }
-
-    @Override
-    @SuppressWarnings("NoFinalizer")
-    protected synchronized void finalize() {
-      stopListener();
-    }
-
-    void startListener() {
-      if (m_entry.isValid() && m_listener == 0 && m_createListener != null) {
-        m_listener = m_createListener.apply(m_entry);
-      }
-    }
-
-    void stopListener() {
-      if (m_entry.isValid() && m_listener != 0) {
-        m_entry.removeListener(m_listener);
-        m_listener = 0;
-      }
-    }
-
-    final NetworkTableEntry m_entry;
-    int m_listener;
-    Consumer<NetworkTableEntry> m_update;
-    Function<NetworkTableEntry, Integer> m_createListener;
+  @FunctionalInterface
+  private interface TimedConsumer<T> {
+    void accept(T value, long time);
   }
 
-  private final List<Property> m_properties = new ArrayList<>();
+  private static class Property<P extends Publisher, S extends Subscriber>
+      implements AutoCloseable {
+    @Override
+    @SuppressWarnings("PMD.AvoidCatchingGenericException")
+    public void close() {
+      try {
+        if (m_pub != null) {
+          m_pub.close();
+        }
+        if (m_sub != null) {
+          m_sub.close();
+        }
+      } catch (Exception e) {
+        // ignore
+      }
+    }
+
+    void update(boolean controllable, long time) {
+      if (controllable && m_sub != null && m_updateLocal != null) {
+        m_updateLocal.accept(m_sub);
+      }
+      if (m_pub != null && m_updateNetwork != null) {
+        m_updateNetwork.accept(m_pub, time);
+      }
+    }
+
+    P m_pub;
+    S m_sub;
+    TimedConsumer<P> m_updateNetwork;
+    Consumer<S> m_updateLocal;
+  }
+
+  private final List<Property<?, ?>> m_properties = new ArrayList<>();
   private Runnable m_safeState;
   private final List<Runnable> m_updateTables = new ArrayList<>();
   private NetworkTable m_table;
-  private NetworkTableEntry m_controllableEntry;
+  private boolean m_controllable;
   private boolean m_actuator;
 
+  private BooleanPublisher m_controllablePub;
+  private StringPublisher m_typePub;
+  private BooleanPublisher m_actuatorPub;
+
+  private final List<AutoCloseable> m_closeables = new ArrayList<>();
+
+  @Override
+  @SuppressWarnings("PMD.AvoidCatchingGenericException")
+  public void close() {
+    if (m_controllablePub != null) {
+      m_controllablePub.close();
+    }
+    if (m_typePub != null) {
+      m_typePub.close();
+    }
+    if (m_actuatorPub != null) {
+      m_actuatorPub.close();
+    }
+    for (Property<?, ?> property : m_properties) {
+      property.close();
+    }
+    for (AutoCloseable closeable : m_closeables) {
+      try {
+        closeable.close();
+      } catch (Exception e) {
+        // ignore
+      }
+    }
+  }
+
   /**
    * Set the network table. Must be called prior to any Add* functions being called.
    *
@@ -64,7 +139,8 @@
    */
   public void setTable(NetworkTable table) {
     m_table = table;
-    m_controllableEntry = table.getEntry(".controllable");
+    m_controllablePub = table.getBooleanTopic(".controllable").publish();
+    m_controllablePub.setDefault(false);
   }
 
   /**
@@ -99,10 +175,9 @@
   /** Update the network table values by calling the getters for all properties. */
   @Override
   public void update() {
-    for (Property property : m_properties) {
-      if (property.m_update != null) {
-        property.m_update.accept(property.m_entry);
-      }
+    long time = WPIUtilJNI.now();
+    for (Property<?, ?> property : m_properties) {
+      property.update(m_controllable, time);
     }
     for (Runnable updateTable : m_updateTables) {
       updateTable.run();
@@ -111,21 +186,17 @@
 
   /** Hook setters for all properties. */
   public void startListeners() {
-    for (Property property : m_properties) {
-      property.startListener();
-    }
-    if (m_controllableEntry != null) {
-      m_controllableEntry.setBoolean(true);
+    m_controllable = true;
+    if (m_controllablePub != null) {
+      m_controllablePub.set(true);
     }
   }
 
   /** Unhook setters for all properties. */
   public void stopListeners() {
-    for (Property property : m_properties) {
-      property.stopListener();
-    }
-    if (m_controllableEntry != null) {
-      m_controllableEntry.setBoolean(false);
+    m_controllable = false;
+    if (m_controllablePub != null) {
+      m_controllablePub.set(false);
     }
   }
 
@@ -155,9 +226,17 @@
   @Override
   public void clearProperties() {
     stopListeners();
+    for (Property<?, ?> property : m_properties) {
+      property.close();
+    }
     m_properties.clear();
   }
 
+  @Override
+  public void addCloseable(AutoCloseable closeable) {
+    m_closeables.add(closeable);
+  }
+
   /**
    * Set the string representation of the named data type that will be used by the smart dashboard
    * for this sendable.
@@ -166,18 +245,24 @@
    */
   @Override
   public void setSmartDashboardType(String type) {
-    m_table.getEntry(".type").setString(type);
+    if (m_typePub == null) {
+      m_typePub = m_table.getStringTopic(".type").publish();
+    }
+    m_typePub.set(type);
   }
 
   /**
-   * Set a flag indicating if this sendable should be treated as an actuator. By default this flag
+   * Set a flag indicating if this sendable should be treated as an actuator. By default, this flag
    * is false.
    *
    * @param value true if actuator, false if not
    */
   @Override
   public void setActuator(boolean value) {
-    m_table.getEntry(".actuator").setBoolean(value);
+    if (m_actuatorPub == null) {
+      m_actuatorPub = m_table.getBooleanTopic(".actuator").publish();
+    }
+    m_actuatorPub.set(value);
     m_actuator = value;
   }
 
@@ -195,7 +280,7 @@
   /**
    * Set the function that should be called to update the network table for things other than
    * properties. Note this function is not passed the network table object; instead it should use
-   * the entry handles returned by getEntry().
+   * the topics returned by getTopic().
    *
    * @param func function
    */
@@ -212,8 +297,8 @@
    * @return Network table entry
    */
   @Override
-  public NetworkTableEntry getEntry(String key) {
-    return m_table.getEntry(key);
+  public Topic getTopic(String key) {
+    return m_table.getTopic(key);
   }
 
   /**
@@ -225,23 +310,74 @@
    */
   @Override
   public void addBooleanProperty(String key, BooleanSupplier getter, BooleanConsumer setter) {
-    Property property = new Property(m_table, key);
+    Property<BooleanPublisher, BooleanSubscriber> property = new Property<>();
+    BooleanTopic topic = m_table.getBooleanTopic(key);
     if (getter != null) {
-      property.m_update = entry -> entry.setBoolean(getter.getAsBoolean());
+      property.m_pub = topic.publish();
+      property.m_updateNetwork = (pub, time) -> pub.set(getter.getAsBoolean(), time);
     }
     if (setter != null) {
-      property.m_createListener =
-          entry ->
-              entry.addListener(
-                  event -> {
-                    if (event.value.isBoolean()) {
-                      SmartDashboard.postListenerTask(
-                          () -> setter.accept(event.value.getBoolean()));
-                    }
-                  },
-                  EntryListenerFlags.kImmediate
-                      | EntryListenerFlags.kNew
-                      | EntryListenerFlags.kUpdate);
+      property.m_sub = topic.subscribe(false, PubSubOption.excludePublisher(property.m_pub));
+      property.m_updateLocal =
+          sub -> {
+            for (boolean val : sub.readQueueValues()) {
+              setter.accept(val);
+            }
+          };
+    }
+    m_properties.add(property);
+  }
+
+  /**
+   * Add an integer property.
+   *
+   * @param key property name
+   * @param getter getter function (returns current value)
+   * @param setter setter function (sets new value)
+   */
+  @Override
+  public void addIntegerProperty(String key, LongSupplier getter, LongConsumer setter) {
+    Property<IntegerPublisher, IntegerSubscriber> property = new Property<>();
+    IntegerTopic topic = m_table.getIntegerTopic(key);
+    if (getter != null) {
+      property.m_pub = topic.publish();
+      property.m_updateNetwork = (pub, time) -> pub.set(getter.getAsLong(), time);
+    }
+    if (setter != null) {
+      property.m_sub = topic.subscribe(0, PubSubOption.excludePublisher(property.m_pub));
+      property.m_updateLocal =
+          sub -> {
+            for (long val : sub.readQueueValues()) {
+              setter.accept(val);
+            }
+          };
+    }
+    m_properties.add(property);
+  }
+
+  /**
+   * Add a float property.
+   *
+   * @param key property name
+   * @param getter getter function (returns current value)
+   * @param setter setter function (sets new value)
+   */
+  @Override
+  public void addFloatProperty(String key, FloatSupplier getter, FloatConsumer setter) {
+    Property<FloatPublisher, FloatSubscriber> property = new Property<>();
+    FloatTopic topic = m_table.getFloatTopic(key);
+    if (getter != null) {
+      property.m_pub = topic.publish();
+      property.m_updateNetwork = (pub, time) -> pub.set(getter.getAsFloat(), time);
+    }
+    if (setter != null) {
+      property.m_sub = topic.subscribe(0.0f, PubSubOption.excludePublisher(property.m_pub));
+      property.m_updateLocal =
+          sub -> {
+            for (float val : sub.readQueueValues()) {
+              setter.accept(val);
+            }
+          };
     }
     m_properties.add(property);
   }
@@ -255,22 +391,20 @@
    */
   @Override
   public void addDoubleProperty(String key, DoubleSupplier getter, DoubleConsumer setter) {
-    Property property = new Property(m_table, key);
+    Property<DoublePublisher, DoubleSubscriber> property = new Property<>();
+    DoubleTopic topic = m_table.getDoubleTopic(key);
     if (getter != null) {
-      property.m_update = entry -> entry.setDouble(getter.getAsDouble());
+      property.m_pub = topic.publish();
+      property.m_updateNetwork = (pub, time) -> pub.set(getter.getAsDouble(), time);
     }
     if (setter != null) {
-      property.m_createListener =
-          entry ->
-              entry.addListener(
-                  event -> {
-                    if (event.value.isDouble()) {
-                      SmartDashboard.postListenerTask(() -> setter.accept(event.value.getDouble()));
-                    }
-                  },
-                  EntryListenerFlags.kImmediate
-                      | EntryListenerFlags.kNew
-                      | EntryListenerFlags.kUpdate);
+      property.m_sub = topic.subscribe(0.0, PubSubOption.excludePublisher(property.m_pub));
+      property.m_updateLocal =
+          sub -> {
+            for (double val : sub.readQueueValues()) {
+              setter.accept(val);
+            }
+          };
     }
     m_properties.add(property);
   }
@@ -284,22 +418,20 @@
    */
   @Override
   public void addStringProperty(String key, Supplier<String> getter, Consumer<String> setter) {
-    Property property = new Property(m_table, key);
+    Property<StringPublisher, StringSubscriber> property = new Property<>();
+    StringTopic topic = m_table.getStringTopic(key);
     if (getter != null) {
-      property.m_update = entry -> entry.setString(getter.get());
+      property.m_pub = topic.publish();
+      property.m_updateNetwork = (pub, time) -> pub.set(getter.get(), time);
     }
     if (setter != null) {
-      property.m_createListener =
-          entry ->
-              entry.addListener(
-                  event -> {
-                    if (event.value.isString()) {
-                      SmartDashboard.postListenerTask(() -> setter.accept(event.value.getString()));
-                    }
-                  },
-                  EntryListenerFlags.kImmediate
-                      | EntryListenerFlags.kNew
-                      | EntryListenerFlags.kUpdate);
+      property.m_sub = topic.subscribe("", PubSubOption.excludePublisher(property.m_pub));
+      property.m_updateLocal =
+          sub -> {
+            for (String val : sub.readQueueValues()) {
+              setter.accept(val);
+            }
+          };
     }
     m_properties.add(property);
   }
@@ -314,23 +446,79 @@
   @Override
   public void addBooleanArrayProperty(
       String key, Supplier<boolean[]> getter, Consumer<boolean[]> setter) {
-    Property property = new Property(m_table, key);
+    Property<BooleanArrayPublisher, BooleanArraySubscriber> property = new Property<>();
+    BooleanArrayTopic topic = m_table.getBooleanArrayTopic(key);
     if (getter != null) {
-      property.m_update = entry -> entry.setBooleanArray(getter.get());
+      property.m_pub = topic.publish();
+      property.m_updateNetwork = (pub, time) -> pub.set(getter.get(), time);
     }
     if (setter != null) {
-      property.m_createListener =
-          entry ->
-              entry.addListener(
-                  event -> {
-                    if (event.value.isBooleanArray()) {
-                      SmartDashboard.postListenerTask(
-                          () -> setter.accept(event.value.getBooleanArray()));
-                    }
-                  },
-                  EntryListenerFlags.kImmediate
-                      | EntryListenerFlags.kNew
-                      | EntryListenerFlags.kUpdate);
+      property.m_sub =
+          topic.subscribe(new boolean[] {}, PubSubOption.excludePublisher(property.m_pub));
+      property.m_updateLocal =
+          sub -> {
+            for (boolean[] val : sub.readQueueValues()) {
+              setter.accept(val);
+            }
+          };
+    }
+    m_properties.add(property);
+  }
+
+  /**
+   * Add an integer array property.
+   *
+   * @param key property name
+   * @param getter getter function (returns current value)
+   * @param setter setter function (sets new value)
+   */
+  @Override
+  public void addIntegerArrayProperty(
+      String key, Supplier<long[]> getter, Consumer<long[]> setter) {
+    Property<IntegerArrayPublisher, IntegerArraySubscriber> property = new Property<>();
+    IntegerArrayTopic topic = m_table.getIntegerArrayTopic(key);
+    if (getter != null) {
+      property.m_pub = topic.publish();
+      property.m_updateNetwork = (pub, time) -> pub.set(getter.get(), time);
+    }
+    if (setter != null) {
+      property.m_sub =
+          topic.subscribe(new long[] {}, PubSubOption.excludePublisher(property.m_pub));
+      property.m_updateLocal =
+          sub -> {
+            for (long[] val : sub.readQueueValues()) {
+              setter.accept(val);
+            }
+          };
+    }
+    m_properties.add(property);
+  }
+
+  /**
+   * Add a float array property.
+   *
+   * @param key property name
+   * @param getter getter function (returns current value)
+   * @param setter setter function (sets new value)
+   */
+  @Override
+  public void addFloatArrayProperty(
+      String key, Supplier<float[]> getter, Consumer<float[]> setter) {
+    Property<FloatArrayPublisher, FloatArraySubscriber> property = new Property<>();
+    FloatArrayTopic topic = m_table.getFloatArrayTopic(key);
+    if (getter != null) {
+      property.m_pub = topic.publish();
+      property.m_updateNetwork = (pub, time) -> pub.set(getter.get(), time);
+    }
+    if (setter != null) {
+      property.m_sub =
+          topic.subscribe(new float[] {}, PubSubOption.excludePublisher(property.m_pub));
+      property.m_updateLocal =
+          sub -> {
+            for (float[] val : sub.readQueueValues()) {
+              setter.accept(val);
+            }
+          };
     }
     m_properties.add(property);
   }
@@ -345,23 +533,21 @@
   @Override
   public void addDoubleArrayProperty(
       String key, Supplier<double[]> getter, Consumer<double[]> setter) {
-    Property property = new Property(m_table, key);
+    Property<DoubleArrayPublisher, DoubleArraySubscriber> property = new Property<>();
+    DoubleArrayTopic topic = m_table.getDoubleArrayTopic(key);
     if (getter != null) {
-      property.m_update = entry -> entry.setDoubleArray(getter.get());
+      property.m_pub = topic.publish();
+      property.m_updateNetwork = (pub, time) -> pub.set(getter.get(), time);
     }
     if (setter != null) {
-      property.m_createListener =
-          entry ->
-              entry.addListener(
-                  event -> {
-                    if (event.value.isDoubleArray()) {
-                      SmartDashboard.postListenerTask(
-                          () -> setter.accept(event.value.getDoubleArray()));
-                    }
-                  },
-                  EntryListenerFlags.kImmediate
-                      | EntryListenerFlags.kNew
-                      | EntryListenerFlags.kUpdate);
+      property.m_sub =
+          topic.subscribe(new double[] {}, PubSubOption.excludePublisher(property.m_pub));
+      property.m_updateLocal =
+          sub -> {
+            for (double[] val : sub.readQueueValues()) {
+              setter.accept(val);
+            }
+          };
     }
     m_properties.add(property);
   }
@@ -376,23 +562,21 @@
   @Override
   public void addStringArrayProperty(
       String key, Supplier<String[]> getter, Consumer<String[]> setter) {
-    Property property = new Property(m_table, key);
+    Property<StringArrayPublisher, StringArraySubscriber> property = new Property<>();
+    StringArrayTopic topic = m_table.getStringArrayTopic(key);
     if (getter != null) {
-      property.m_update = entry -> entry.setStringArray(getter.get());
+      property.m_pub = topic.publish();
+      property.m_updateNetwork = (pub, time) -> pub.set(getter.get(), time);
     }
     if (setter != null) {
-      property.m_createListener =
-          entry ->
-              entry.addListener(
-                  event -> {
-                    if (event.value.isStringArray()) {
-                      SmartDashboard.postListenerTask(
-                          () -> setter.accept(event.value.getStringArray()));
-                    }
-                  },
-                  EntryListenerFlags.kImmediate
-                      | EntryListenerFlags.kNew
-                      | EntryListenerFlags.kUpdate);
+      property.m_sub =
+          topic.subscribe(new String[] {}, PubSubOption.excludePublisher(property.m_pub));
+      property.m_updateLocal =
+          sub -> {
+            for (String[] val : sub.readQueueValues()) {
+              setter.accept(val);
+            }
+          };
     }
     m_properties.add(property);
   }
@@ -401,55 +585,28 @@
    * Add a raw property.
    *
    * @param key property name
+   * @param typeString type string
    * @param getter getter function (returns current value)
    * @param setter setter function (sets new value)
    */
   @Override
-  public void addRawProperty(String key, Supplier<byte[]> getter, Consumer<byte[]> setter) {
-    Property property = new Property(m_table, key);
+  public void addRawProperty(
+      String key, String typeString, Supplier<byte[]> getter, Consumer<byte[]> setter) {
+    Property<RawPublisher, RawSubscriber> property = new Property<>();
+    RawTopic topic = m_table.getRawTopic(key);
     if (getter != null) {
-      property.m_update = entry -> entry.setRaw(getter.get());
+      property.m_pub = topic.publish(typeString);
+      property.m_updateNetwork = (pub, time) -> pub.set(getter.get(), time);
     }
     if (setter != null) {
-      property.m_createListener =
-          entry ->
-              entry.addListener(
-                  event -> {
-                    if (event.value.isRaw()) {
-                      SmartDashboard.postListenerTask(() -> setter.accept(event.value.getRaw()));
-                    }
-                  },
-                  EntryListenerFlags.kImmediate
-                      | EntryListenerFlags.kNew
-                      | EntryListenerFlags.kUpdate);
-    }
-    m_properties.add(property);
-  }
-
-  /**
-   * Add a NetworkTableValue property.
-   *
-   * @param key property name
-   * @param getter getter function (returns current value)
-   * @param setter setter function (sets new value)
-   */
-  @Override
-  public void addValueProperty(
-      String key, Supplier<NetworkTableValue> getter, Consumer<NetworkTableValue> setter) {
-    Property property = new Property(m_table, key);
-    if (getter != null) {
-      property.m_update = entry -> entry.setValue(getter.get());
-    }
-    if (setter != null) {
-      property.m_createListener =
-          entry ->
-              entry.addListener(
-                  event -> {
-                    SmartDashboard.postListenerTask(() -> setter.accept(event.value));
-                  },
-                  EntryListenerFlags.kImmediate
-                      | EntryListenerFlags.kNew
-                      | EntryListenerFlags.kUpdate);
+      property.m_sub =
+          topic.subscribe(typeString, new byte[] {}, PubSubOption.excludePublisher(property.m_pub));
+      property.m_updateLocal =
+          sub -> {
+            for (byte[] val : sub.readQueueValues()) {
+              setter.accept(val);
+            }
+          };
     }
     m_properties.add(property);
   }
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableChooser.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableChooser.java
index cece5a9..c967e17 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableChooser.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableChooser.java
@@ -4,11 +4,14 @@
 
 package edu.wpi.first.wpilibj.smartdashboard;
 
-import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
 
+import edu.wpi.first.networktables.IntegerPublisher;
+import edu.wpi.first.networktables.IntegerTopic;
 import edu.wpi.first.networktables.NTSendable;
 import edu.wpi.first.networktables.NTSendableBuilder;
-import edu.wpi.first.networktables.NetworkTableEntry;
+import edu.wpi.first.networktables.StringPublisher;
+import edu.wpi.first.networktables.StringTopic;
 import edu.wpi.first.util.sendable.SendableRegistry;
 import java.util.ArrayList;
 import java.util.LinkedHashMap;
@@ -40,7 +43,7 @@
   private static final String OPTIONS = "options";
   /** The key for the instance number. */
   private static final String INSTANCE = ".instance";
-  /** A map linking strings to the objects the represent. */
+  /** A map linking strings to the objects they represent. */
   private final Map<String, V> m_map = new LinkedHashMap<>();
 
   private String m_defaultChoice = "";
@@ -56,6 +59,14 @@
   @Override
   public void close() {
     SendableRegistry.remove(this);
+    m_mutex.lock();
+    try {
+      for (StringPublisher pub : m_activePubs) {
+        pub.close();
+      }
+    } finally {
+      m_mutex.unlock();
+    }
   }
 
   /**
@@ -70,18 +81,6 @@
   }
 
   /**
-   * Adds the given object to the list of options.
-   *
-   * @param name the name of the option
-   * @param object the option
-   * @deprecated Use {@link #addOption(String, Object)} instead.
-   */
-  @Deprecated
-  public void addObject(String name, V object) {
-    addOption(name, object);
-  }
-
-  /**
    * Adds the given object to the list of options and marks it as the default. Functionally, this is
    * very close to {@link #addOption(String, Object)} except that it will use this as the default
    * option if none other is explicitly selected.
@@ -97,18 +96,6 @@
   }
 
   /**
-   * Adds the given object to the list of options and marks it as the default.
-   *
-   * @param name the name of the option
-   * @param object the option
-   * @deprecated Use {@link #setDefaultOption(String, Object)} instead.
-   */
-  @Deprecated
-  public void addDefault(String name, V object) {
-    setDefaultOption(name, object);
-  }
-
-  /**
    * Returns the selected option. If there is none selected, it will return the default. If there is
    * none selected and no default, then it will return {@code null}.
    *
@@ -128,13 +115,15 @@
   }
 
   private String m_selected;
-  private final List<NetworkTableEntry> m_activeEntries = new ArrayList<>();
+  private final List<StringPublisher> m_activePubs = new ArrayList<>();
   private final ReentrantLock m_mutex = new ReentrantLock();
 
   @Override
   public void initSendable(NTSendableBuilder builder) {
     builder.setSmartDashboardType("String Chooser");
-    builder.getEntry(INSTANCE).setDouble(m_instance);
+    IntegerPublisher instancePub = new IntegerTopic(builder.getTopic(INSTANCE)).publish();
+    instancePub.set(m_instance);
+    builder.addCloseable(instancePub);
     builder.addStringProperty(DEFAULT, () -> m_defaultChoice, null);
     builder.addStringArrayProperty(OPTIONS, () -> m_map.keySet().toArray(new String[0]), null);
     builder.addStringProperty(
@@ -154,7 +143,7 @@
         null);
     m_mutex.lock();
     try {
-      m_activeEntries.add(builder.getEntry(ACTIVE));
+      m_activePubs.add(new StringTopic(builder.getTopic(ACTIVE)).publish());
     } finally {
       m_mutex.unlock();
     }
@@ -165,8 +154,8 @@
           m_mutex.lock();
           try {
             m_selected = val;
-            for (NetworkTableEntry entry : m_activeEntries) {
-              entry.setString(val);
+            for (StringPublisher pub : m_activePubs) {
+              pub.set(val);
             }
           } finally {
             m_mutex.unlock();
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SmartDashboard.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SmartDashboard.java
index be5684b..8a8f147 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SmartDashboard.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SmartDashboard.java
@@ -11,7 +11,6 @@
 import edu.wpi.first.networktables.NetworkTableInstance;
 import edu.wpi.first.util.sendable.Sendable;
 import edu.wpi.first.util.sendable.SendableRegistry;
-import java.nio.ByteBuffer;
 import java.util.HashMap;
 import java.util.Map;
 import java.util.Set;
@@ -25,8 +24,7 @@
  */
 public final class SmartDashboard {
   /** The {@link NetworkTable} used by {@link SmartDashboard}. */
-  private static final NetworkTable table =
-      NetworkTableInstance.getDefault().getTable("SmartDashboard");
+  private static NetworkTable table;
 
   /**
    * A table linking tables in the SmartDashboard to the {@link Sendable} objects they came from.
@@ -38,6 +36,7 @@
   private static final ListenerExecutor listenerExecutor = new ListenerExecutor();
 
   static {
+    setNetworkTableInstance(NetworkTableInstance.getDefault());
     HAL.report(tResourceType.kResourceType_SmartDashboard, 0);
   }
 
@@ -46,6 +45,16 @@
   }
 
   /**
+   * Set the NetworkTable instance used for entries. For testing purposes; use with caution.
+   *
+   * @param inst NetworkTable instance
+   */
+  public static synchronized void setNetworkTableInstance(NetworkTableInstance inst) {
+    SmartDashboard.table = inst.getTable("SmartDashboard");
+    tablesToData.clear();
+  }
+
+  /**
    * Maps the specified key to the specified value in this table. The key can not be null. The value
    * can be retrieved by calling the get method with a key that is equal to the original key.
    *
@@ -68,7 +77,7 @@
   }
 
   /**
-   * Maps the specified key (where the key is the name of the {@link Sendable} to the specified
+   * Maps the specified key (where the key is the name of the {@link Sendable}) to the specified
    * value in this table. The value can be retrieved by calling the get method with a key that is
    * equal to the original key.
    *
@@ -166,45 +175,6 @@
   }
 
   /**
-   * Sets flags on the specified key in this table. The key can not be null.
-   *
-   * @param key the key name
-   * @param flags the flags to set (bitmask)
-   */
-  public static void setFlags(String key, int flags) {
-    getEntry(key).setFlags(flags);
-  }
-
-  /**
-   * Clears flags on the specified key in this table. The key can not be null.
-   *
-   * @param key the key name
-   * @param flags the flags to clear (bitmask)
-   */
-  public static void clearFlags(String key, int flags) {
-    getEntry(key).clearFlags(flags);
-  }
-
-  /**
-   * Returns the flags for the specified key.
-   *
-   * @param key the key name
-   * @return the flags, or 0 if the key is not defined
-   */
-  public static int getFlags(String key) {
-    return getEntry(key).getFlags();
-  }
-
-  /**
-   * Deletes the specified key in this table. The key can not be null.
-   *
-   * @param key the key name
-   */
-  public static void delete(String key) {
-    table.delete(key);
-  }
-
-  /**
    * Put a boolean in the table.
    *
    * @param key the key to be assigned to
@@ -496,18 +466,6 @@
   }
 
   /**
-   * Put a raw value (bytes from a byte buffer) in the table.
-   *
-   * @param key the key to be assigned to
-   * @param value the value that will be assigned
-   * @param len the length of the value
-   * @return False if the table key already exists with a different type
-   */
-  public static boolean putRaw(String key, ByteBuffer value, int len) {
-    return getEntry(key).setRaw(value, len);
-  }
-
-  /**
    * Gets the current value in the table, setting it if it does not exist.
    *
    * @param key the key
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/util/Color.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/util/Color.java
index 1287f4a..2defbd8 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/util/Color.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/util/Color.java
@@ -19,9 +19,10 @@
   public final double red;
   public final double green;
   public final double blue;
+  private String m_name;
 
   /**
-   * Constructs a Color.
+   * Constructs a Color from doubles.
    *
    * @param red Red value (0-1)
    * @param green Green value (0-1)
@@ -31,6 +32,18 @@
     this.red = roundAndClamp(red);
     this.green = roundAndClamp(green);
     this.blue = roundAndClamp(blue);
+    this.m_name = null;
+  }
+
+  /**
+   * Constructs a Color from ints.
+   *
+   * @param red Red value (0-255)
+   * @param green Green value (0-255)
+   * @param blue Blue value (0-255)
+   */
+  public Color(int red, int green, int blue) {
+    this(red / 255.0, green / 255.0, blue / 255.0);
   }
 
   /**
@@ -43,39 +56,62 @@
   }
 
   /**
+   * Constructs a Color from doubles.
+   *
+   * @param red Red value (0-1)
+   * @param green Green value (0-1)
+   * @param blue Blue value (0-1)
+   */
+  private Color(double red, double green, double blue, String name) {
+    this.red = roundAndClamp(red);
+    this.green = roundAndClamp(green);
+    this.blue = roundAndClamp(blue);
+    this.m_name = name;
+  }
+
+  /**
    * Creates a Color from HSV values.
    *
-   * @param h The h value [0-180]
+   * @param h The h value [0-180)
    * @param s The s value [0-255]
    * @param v The v value [0-255]
    * @return The color
    */
-  @SuppressWarnings("ParameterName")
   public static Color fromHSV(int h, int s, int v) {
-    if (s == 0) {
-      return new Color(v / 255.0, v / 255.0, v / 255.0);
-    }
+    // Loosely based on
+    // https://en.wikipedia.org/wiki/HSL_and_HSV#HSV_to_RGB
+    // The hue range is split into 60 degree regions where in each region there
+    // is one rgb component at a low value (m), one at a high value (v) and one
+    // that changes (X) from low to high (X+m) or high to low (v-X)
 
-    final int region = h / 30;
-    final int remainder = (h - (region * 30)) * 6;
+    // Difference between highest and lowest value of any rgb component
+    final int chroma = (s * v) / 255;
 
-    final int p = (v * (255 - s)) >> 8;
-    final int q = (v * (255 - ((s * remainder) >> 8))) >> 8;
-    final int t = (v * (255 - ((s * (255 - remainder)) >> 8))) >> 8;
+    // Because hue is 0-180 rather than 0-360 use 30 not 60
+    final int region = (h / 30) % 6;
+
+    // Remainder converted from 0-30 to 0-255
+    final int remainder = (int) Math.round((h % 30) * (255 / 30.0));
+
+    // Value of the lowest rgb component
+    final int m = v - chroma;
+
+    // Goes from 0 to chroma as hue increases
+    final int X = (chroma * remainder) >> 8;
 
     switch (region) {
       case 0:
-        return new Color(v / 255.0, t / 255.0, p / 255.0);
+        return new Color(v, X + m, m);
       case 1:
-        return new Color(q / 255.0, v / 255.0, p / 255.0);
+        return new Color(v - X, v, m);
       case 2:
-        return new Color(p / 255.0, v / 255.0, t / 255.0);
+        return new Color(m, v, X + m);
       case 3:
-        return new Color(p / 255.0, q / 255.0, v / 255.0);
+        return new Color(m, v - X, v);
       case 4:
-        return new Color(t / 255.0, p / 255.0, v / 255.0);
+        return new Color(X + m, m, v);
       default:
-        return new Color(v / 255.0, p / 255.0, q / 255.0);
+        return new Color(v, m, v - X);
     }
   }
 
@@ -99,6 +135,25 @@
     return Objects.hash(red, green, blue);
   }
 
+  @Override
+  public String toString() {
+    if (m_name == null) {
+      // cache hex conversion
+      m_name = toHexString();
+    }
+    return m_name;
+  }
+
+  /**
+   * Return this color represented as a hex string.
+   *
+   * @return a string of the format <code>#RRGGBB</code>
+   */
+  public String toHexString() {
+    return String.format(
+        "#%02X%02X%02X", (int) (red * 255), (int) (green * 255), (int) (blue * 255));
+  }
+
   private static double roundAndClamp(double value) {
     final var rounded = Math.round((value + kPrecision / 2) / kPrecision) * kPrecision;
     return MathUtil.clamp(rounded, 0.0, 1.0);
@@ -109,435 +164,494 @@
    */
 
   /** 0x1560BD. */
-  public static final Color kDenim = new Color(0.0823529412, 0.376470589, 0.7411764706);
+  public static final Color kDenim = new Color(0.0823529412, 0.376470589, 0.7411764706, "kDenim");
 
   /** 0x0066B3. */
-  public static final Color kFirstBlue = new Color(0.0, 0.4, 0.7019607844);
+  public static final Color kFirstBlue = new Color(0.0, 0.4, 0.7019607844, "kFirstBlue");
 
   /** 0xED1C24. */
-  public static final Color kFirstRed = new Color(0.9294117648, 0.1098039216, 0.1411764706);
+  public static final Color kFirstRed =
+      new Color(0.9294117648, 0.1098039216, 0.1411764706, "kFirstRed");
 
   /*
    * Standard Colors
    */
 
   /** 0xF0F8FF. */
-  public static final Color kAliceBlue = new Color(0.9411765f, 0.972549f, 1.0f);
+  public static final Color kAliceBlue = new Color(0.9411765f, 0.972549f, 1.0f, "kAliceBlue");
 
   /** 0xFAEBD7. */
-  public static final Color kAntiqueWhite = new Color(0.98039216f, 0.92156863f, 0.84313726f);
+  public static final Color kAntiqueWhite =
+      new Color(0.98039216f, 0.92156863f, 0.84313726f, "kAntiqueWhite");
 
   /** 0x00FFFF. */
-  public static final Color kAqua = new Color(0.0f, 1.0f, 1.0f);
+  public static final Color kAqua = new Color(0.0f, 1.0f, 1.0f, "kAqua");
 
   /** 0x7FFFD4. */
-  public static final Color kAquamarine = new Color(0.49803922f, 1.0f, 0.83137256f);
+  public static final Color kAquamarine = new Color(0.49803922f, 1.0f, 0.83137256f, "kAquamarine");
 
   /** 0xF0FFFF. */
-  public static final Color kAzure = new Color(0.9411765f, 1.0f, 1.0f);
+  public static final Color kAzure = new Color(0.9411765f, 1.0f, 1.0f, "kAzure");
 
   /** 0xF5F5DC. */
-  public static final Color kBeige = new Color(0.9607843f, 0.9607843f, 0.8627451f);
+  public static final Color kBeige = new Color(0.9607843f, 0.9607843f, 0.8627451f, "kBeige");
 
   /** 0xFFE4C4. */
-  public static final Color kBisque = new Color(1.0f, 0.89411765f, 0.76862746f);
+  public static final Color kBisque = new Color(1.0f, 0.89411765f, 0.76862746f, "kBisque");
 
   /** 0x000000. */
-  public static final Color kBlack = new Color(0.0f, 0.0f, 0.0f);
+  public static final Color kBlack = new Color(0.0f, 0.0f, 0.0f, "kBlack");
 
   /** 0xFFEBCD. */
-  public static final Color kBlanchedAlmond = new Color(1.0f, 0.92156863f, 0.8039216f);
+  public static final Color kBlanchedAlmond =
+      new Color(1.0f, 0.92156863f, 0.8039216f, "kBlanchedAlmond");
 
   /** 0x0000FF. */
-  public static final Color kBlue = new Color(0.0f, 0.0f, 1.0f);
+  public static final Color kBlue = new Color(0.0f, 0.0f, 1.0f, "kBlue");
 
   /** 0x8A2BE2. */
-  public static final Color kBlueViolet = new Color(0.5411765f, 0.16862746f, 0.8862745f);
+  public static final Color kBlueViolet =
+      new Color(0.5411765f, 0.16862746f, 0.8862745f, "kBlueViolet");
 
   /** 0xA52A2A. */
-  public static final Color kBrown = new Color(0.64705884f, 0.16470589f, 0.16470589f);
+  public static final Color kBrown = new Color(0.64705884f, 0.16470589f, 0.16470589f, "kBrown");
 
   /** 0xDEB887. */
-  public static final Color kBurlywood = new Color(0.87058824f, 0.72156864f, 0.5294118f);
+  public static final Color kBurlywood =
+      new Color(0.87058824f, 0.72156864f, 0.5294118f, "kBurlywood");
 
   /** 0x5F9EA0. */
-  public static final Color kCadetBlue = new Color(0.37254903f, 0.61960787f, 0.627451f);
+  public static final Color kCadetBlue =
+      new Color(0.37254903f, 0.61960787f, 0.627451f, "kCadetBlue");
 
   /** 0x7FFF00. */
-  public static final Color kChartreuse = new Color(0.49803922f, 1.0f, 0.0f);
+  public static final Color kChartreuse = new Color(0.49803922f, 1.0f, 0.0f, "kChartreuse");
 
   /** 0xD2691E. */
-  public static final Color kChocolate = new Color(0.8235294f, 0.4117647f, 0.11764706f);
+  public static final Color kChocolate =
+      new Color(0.8235294f, 0.4117647f, 0.11764706f, "kChocolate");
 
   /** 0xFF7F50. */
-  public static final Color kCoral = new Color(1.0f, 0.49803922f, 0.3137255f);
+  public static final Color kCoral = new Color(1.0f, 0.49803922f, 0.3137255f, "kCoral");
 
   /** 0x6495ED. */
-  public static final Color kCornflowerBlue = new Color(0.39215687f, 0.58431375f, 0.92941177f);
+  public static final Color kCornflowerBlue =
+      new Color(0.39215687f, 0.58431375f, 0.92941177f, "kCornflowerBlue");
 
   /** 0xFFF8DC. */
-  public static final Color kCornsilk = new Color(1.0f, 0.972549f, 0.8627451f);
+  public static final Color kCornsilk = new Color(1.0f, 0.972549f, 0.8627451f, "kCornsilk");
 
   /** 0xDC143C. */
-  public static final Color kCrimson = new Color(0.8627451f, 0.078431375f, 0.23529412f);
+  public static final Color kCrimson = new Color(0.8627451f, 0.078431375f, 0.23529412f, "kCrimson");
 
   /** 0x00FFFF. */
-  public static final Color kCyan = new Color(0.0f, 1.0f, 1.0f);
+  public static final Color kCyan = new Color(0.0f, 1.0f, 1.0f, "kCyan");
 
   /** 0x00008B. */
-  public static final Color kDarkBlue = new Color(0.0f, 0.0f, 0.54509807f);
+  public static final Color kDarkBlue = new Color(0.0f, 0.0f, 0.54509807f, "kDarkBlue");
 
   /** 0x008B8B. */
-  public static final Color kDarkCyan = new Color(0.0f, 0.54509807f, 0.54509807f);
+  public static final Color kDarkCyan = new Color(0.0f, 0.54509807f, 0.54509807f, "kDarkCyan");
 
   /** 0xB8860B. */
-  public static final Color kDarkGoldenrod = new Color(0.72156864f, 0.5254902f, 0.043137256f);
+  public static final Color kDarkGoldenrod =
+      new Color(0.72156864f, 0.5254902f, 0.043137256f, "kDarkGoldenrod");
 
   /** 0xA9A9A9. */
-  public static final Color kDarkGray = new Color(0.6627451f, 0.6627451f, 0.6627451f);
+  public static final Color kDarkGray = new Color(0.6627451f, 0.6627451f, 0.6627451f, "kDarkGray");
 
   /** 0x006400. */
-  public static final Color kDarkGreen = new Color(0.0f, 0.39215687f, 0.0f);
+  public static final Color kDarkGreen = new Color(0.0f, 0.39215687f, 0.0f, "kDarkGreen");
 
   /** 0xBDB76B. */
-  public static final Color kDarkKhaki = new Color(0.7411765f, 0.7176471f, 0.41960785f);
+  public static final Color kDarkKhaki =
+      new Color(0.7411765f, 0.7176471f, 0.41960785f, "kDarkKhaki");
 
   /** 0x8B008B. */
-  public static final Color kDarkMagenta = new Color(0.54509807f, 0.0f, 0.54509807f);
+  public static final Color kDarkMagenta =
+      new Color(0.54509807f, 0.0f, 0.54509807f, "kDarkMagenta");
 
   /** 0x556B2F. */
-  public static final Color kDarkOliveGreen = new Color(0.33333334f, 0.41960785f, 0.18431373f);
+  public static final Color kDarkOliveGreen =
+      new Color(0.33333334f, 0.41960785f, 0.18431373f, "kDarkOliveGreen");
 
   /** 0xFF8C00. */
-  public static final Color kDarkOrange = new Color(1.0f, 0.54901963f, 0.0f);
+  public static final Color kDarkOrange = new Color(1.0f, 0.54901963f, 0.0f, "kDarkOrange");
 
   /** 0x9932CC. */
-  public static final Color kDarkOrchid = new Color(0.6f, 0.19607843f, 0.8f);
+  public static final Color kDarkOrchid = new Color(0.6f, 0.19607843f, 0.8f, "kDarkOrchid");
 
   /** 0x8B0000. */
-  public static final Color kDarkRed = new Color(0.54509807f, 0.0f, 0.0f);
+  public static final Color kDarkRed = new Color(0.54509807f, 0.0f, 0.0f, "kDarkRed");
 
   /** 0xE9967A. */
-  public static final Color kDarkSalmon = new Color(0.9137255f, 0.5882353f, 0.47843137f);
+  public static final Color kDarkSalmon =
+      new Color(0.9137255f, 0.5882353f, 0.47843137f, "kDarkSalmon");
 
   /** 0x8FBC8F. */
-  public static final Color kDarkSeaGreen = new Color(0.56078434f, 0.7372549f, 0.56078434f);
+  public static final Color kDarkSeaGreen =
+      new Color(0.56078434f, 0.7372549f, 0.56078434f, "kDarkSeaGreen");
 
   /** 0x483D8B. */
-  public static final Color kDarkSlateBlue = new Color(0.28235295f, 0.23921569f, 0.54509807f);
+  public static final Color kDarkSlateBlue =
+      new Color(0.28235295f, 0.23921569f, 0.54509807f, "kDarkSlateBlue");
 
   /** 0x2F4F4F. */
-  public static final Color kDarkSlateGray = new Color(0.18431373f, 0.30980393f, 0.30980393f);
+  public static final Color kDarkSlateGray =
+      new Color(0.18431373f, 0.30980393f, 0.30980393f, "kDarkSlateGray");
 
   /** 0x00CED1. */
-  public static final Color kDarkTurquoise = new Color(0.0f, 0.80784315f, 0.81960785f);
+  public static final Color kDarkTurquoise =
+      new Color(0.0f, 0.80784315f, 0.81960785f, "kDarkTurquoise");
 
   /** 0x9400D3. */
-  public static final Color kDarkViolet = new Color(0.5803922f, 0.0f, 0.827451f);
+  public static final Color kDarkViolet = new Color(0.5803922f, 0.0f, 0.827451f, "kDarkViolet");
 
   /** 0xFF1493. */
-  public static final Color kDeepPink = new Color(1.0f, 0.078431375f, 0.5764706f);
+  public static final Color kDeepPink = new Color(1.0f, 0.078431375f, 0.5764706f, "kDeepPink");
 
   /** 0x00BFFF. */
-  public static final Color kDeepSkyBlue = new Color(0.0f, 0.7490196f, 1.0f);
+  public static final Color kDeepSkyBlue = new Color(0.0f, 0.7490196f, 1.0f, "kDeepSkyBlue");
 
   /** 0x696969. */
-  public static final Color kDimGray = new Color(0.4117647f, 0.4117647f, 0.4117647f);
+  public static final Color kDimGray = new Color(0.4117647f, 0.4117647f, 0.4117647f, "kDimGray");
 
   /** 0x1E90FF. */
-  public static final Color kDodgerBlue = new Color(0.11764706f, 0.5647059f, 1.0f);
+  public static final Color kDodgerBlue = new Color(0.11764706f, 0.5647059f, 1.0f, "kDodgerBlue");
 
   /** 0xB22222. */
-  public static final Color kFirebrick = new Color(0.69803923f, 0.13333334f, 0.13333334f);
+  public static final Color kFirebrick =
+      new Color(0.69803923f, 0.13333334f, 0.13333334f, "kFirebrick");
 
   /** 0xFFFAF0. */
-  public static final Color kFloralWhite = new Color(1.0f, 0.98039216f, 0.9411765f);
+  public static final Color kFloralWhite = new Color(1.0f, 0.98039216f, 0.9411765f, "kFloralWhite");
 
   /** 0x228B22. */
-  public static final Color kForestGreen = new Color(0.13333334f, 0.54509807f, 0.13333334f);
+  public static final Color kForestGreen =
+      new Color(0.13333334f, 0.54509807f, 0.13333334f, "kForestGreen");
 
   /** 0xFF00FF. */
-  public static final Color kFuchsia = new Color(1.0f, 0.0f, 1.0f);
+  public static final Color kFuchsia = new Color(1.0f, 0.0f, 1.0f, "kFuchsia");
 
   /** 0xDCDCDC. */
-  public static final Color kGainsboro = new Color(0.8627451f, 0.8627451f, 0.8627451f);
+  public static final Color kGainsboro =
+      new Color(0.8627451f, 0.8627451f, 0.8627451f, "kGainsboro");
 
   /** 0xF8F8FF. */
-  public static final Color kGhostWhite = new Color(0.972549f, 0.972549f, 1.0f);
+  public static final Color kGhostWhite = new Color(0.972549f, 0.972549f, 1.0f, "kGhostWhite");
 
   /** 0xFFD700. */
-  public static final Color kGold = new Color(1.0f, 0.84313726f, 0.0f);
+  public static final Color kGold = new Color(1.0f, 0.84313726f, 0.0f, "kGold");
 
   /** 0xDAA520. */
-  public static final Color kGoldenrod = new Color(0.85490197f, 0.64705884f, 0.1254902f);
+  public static final Color kGoldenrod =
+      new Color(0.85490197f, 0.64705884f, 0.1254902f, "kGoldenrod");
 
   /** 0x808080. */
-  public static final Color kGray = new Color(0.5019608f, 0.5019608f, 0.5019608f);
+  public static final Color kGray = new Color(0.5019608f, 0.5019608f, 0.5019608f, "kGray");
 
   /** 0x008000. */
-  public static final Color kGreen = new Color(0.0f, 0.5019608f, 0.0f);
+  public static final Color kGreen = new Color(0.0f, 0.5019608f, 0.0f, "kGreen");
 
   /** 0xADFF2F. */
-  public static final Color kGreenYellow = new Color(0.6784314f, 1.0f, 0.18431373f);
+  public static final Color kGreenYellow = new Color(0.6784314f, 1.0f, 0.18431373f, "kGreenYellow");
 
   /** 0xF0FFF0. */
-  public static final Color kHoneydew = new Color(0.9411765f, 1.0f, 0.9411765f);
+  public static final Color kHoneydew = new Color(0.9411765f, 1.0f, 0.9411765f, "kHoneydew");
 
   /** 0xFF69B4. */
-  public static final Color kHotPink = new Color(1.0f, 0.4117647f, 0.7058824f);
+  public static final Color kHotPink = new Color(1.0f, 0.4117647f, 0.7058824f, "kHotPink");
 
   /** 0xCD5C5C. */
-  public static final Color kIndianRed = new Color(0.8039216f, 0.36078432f, 0.36078432f);
+  public static final Color kIndianRed =
+      new Color(0.8039216f, 0.36078432f, 0.36078432f, "kIndianRed");
 
   /** 0x4B0082. */
-  public static final Color kIndigo = new Color(0.29411766f, 0.0f, 0.50980395f);
+  public static final Color kIndigo = new Color(0.29411766f, 0.0f, 0.50980395f, "kIndigo");
 
   /** 0xFFFFF0. */
-  public static final Color kIvory = new Color(1.0f, 1.0f, 0.9411765f);
+  public static final Color kIvory = new Color(1.0f, 1.0f, 0.9411765f, "kIvory");
 
   /** 0xF0E68C. */
-  public static final Color kKhaki = new Color(0.9411765f, 0.9019608f, 0.54901963f);
+  public static final Color kKhaki = new Color(0.9411765f, 0.9019608f, 0.54901963f, "kKhaki");
 
   /** 0xE6E6FA. */
-  public static final Color kLavender = new Color(0.9019608f, 0.9019608f, 0.98039216f);
+  public static final Color kLavender = new Color(0.9019608f, 0.9019608f, 0.98039216f, "kLavender");
 
   /** 0xFFF0F5. */
-  public static final Color kLavenderBlush = new Color(1.0f, 0.9411765f, 0.9607843f);
+  public static final Color kLavenderBlush =
+      new Color(1.0f, 0.9411765f, 0.9607843f, "kLavenderBlush");
 
   /** 0x7CFC00. */
-  public static final Color kLawnGreen = new Color(0.4862745f, 0.9882353f, 0.0f);
+  public static final Color kLawnGreen = new Color(0.4862745f, 0.9882353f, 0.0f, "kLawnGreen");
 
   /** 0xFFFACD. */
-  public static final Color kLemonChiffon = new Color(1.0f, 0.98039216f, 0.8039216f);
+  public static final Color kLemonChiffon =
+      new Color(1.0f, 0.98039216f, 0.8039216f, "kLemonChiffon");
 
   /** 0xADD8E6. */
-  public static final Color kLightBlue = new Color(0.6784314f, 0.84705883f, 0.9019608f);
+  public static final Color kLightBlue =
+      new Color(0.6784314f, 0.84705883f, 0.9019608f, "kLightBlue");
 
   /** 0xF08080. */
-  public static final Color kLightCoral = new Color(0.9411765f, 0.5019608f, 0.5019608f);
+  public static final Color kLightCoral =
+      new Color(0.9411765f, 0.5019608f, 0.5019608f, "kLightCoral");
 
   /** 0xE0FFFF. */
-  public static final Color kLightCyan = new Color(0.8784314f, 1.0f, 1.0f);
+  public static final Color kLightCyan = new Color(0.8784314f, 1.0f, 1.0f, "kLightCyan");
 
   /** 0xFAFAD2. */
-  public static final Color kLightGoldenrodYellow = new Color(0.98039216f, 0.98039216f, 0.8235294f);
+  public static final Color kLightGoldenrodYellow =
+      new Color(0.98039216f, 0.98039216f, 0.8235294f, "kLightGoldenrodYellow");
 
   /** 0xD3D3D3. */
-  public static final Color kLightGray = new Color(0.827451f, 0.827451f, 0.827451f);
+  public static final Color kLightGray = new Color(0.827451f, 0.827451f, 0.827451f, "kLightGray");
 
   /** 0x90EE90. */
-  public static final Color kLightGreen = new Color(0.5647059f, 0.93333334f, 0.5647059f);
+  public static final Color kLightGreen =
+      new Color(0.5647059f, 0.93333334f, 0.5647059f, "kLightGreen");
 
   /** 0xFFB6C1. */
-  public static final Color kLightPink = new Color(1.0f, 0.7137255f, 0.75686276f);
+  public static final Color kLightPink = new Color(1.0f, 0.7137255f, 0.75686276f, "kLightPink");
 
   /** 0xFFA07A. */
-  public static final Color kLightSalmon = new Color(1.0f, 0.627451f, 0.47843137f);
+  public static final Color kLightSalmon = new Color(1.0f, 0.627451f, 0.47843137f, "kLightSalmon");
 
   /** 0x20B2AA. */
-  public static final Color kLightSeaGreen = new Color(0.1254902f, 0.69803923f, 0.6666667f);
+  public static final Color kLightSeaGreen =
+      new Color(0.1254902f, 0.69803923f, 0.6666667f, "kLightSeaGreen");
 
   /** 0x87CEFA. */
-  public static final Color kLightSkyBlue = new Color(0.5294118f, 0.80784315f, 0.98039216f);
+  public static final Color kLightSkyBlue =
+      new Color(0.5294118f, 0.80784315f, 0.98039216f, "kLightSkyBlue");
 
   /** 0x778899. */
-  public static final Color kLightSlateGray = new Color(0.46666667f, 0.53333336f, 0.6f);
+  public static final Color kLightSlateGray =
+      new Color(0.46666667f, 0.53333336f, 0.6f, "kLightSlateGray");
 
   /** 0xB0C4DE. */
-  public static final Color kLightSteelBlue = new Color(0.6901961f, 0.76862746f, 0.87058824f);
+  public static final Color kLightSteelBlue =
+      new Color(0.6901961f, 0.76862746f, 0.87058824f, "kLightSteelBlue");
 
   /** 0xFFFFE0. */
-  public static final Color kLightYellow = new Color(1.0f, 1.0f, 0.8784314f);
+  public static final Color kLightYellow = new Color(1.0f, 1.0f, 0.8784314f, "kLightYellow");
 
   /** 0x00FF00. */
-  public static final Color kLime = new Color(0.0f, 1.0f, 0.0f);
+  public static final Color kLime = new Color(0.0f, 1.0f, 0.0f, "kLime");
 
   /** 0x32CD32. */
-  public static final Color kLimeGreen = new Color(0.19607843f, 0.8039216f, 0.19607843f);
+  public static final Color kLimeGreen =
+      new Color(0.19607843f, 0.8039216f, 0.19607843f, "kLimeGreen");
 
   /** 0xFAF0E6. */
-  public static final Color kLinen = new Color(0.98039216f, 0.9411765f, 0.9019608f);
+  public static final Color kLinen = new Color(0.98039216f, 0.9411765f, 0.9019608f, "kLinen");
 
   /** 0xFF00FF. */
-  public static final Color kMagenta = new Color(1.0f, 0.0f, 1.0f);
+  public static final Color kMagenta = new Color(1.0f, 0.0f, 1.0f, "kMagenta");
 
   /** 0x800000. */
-  public static final Color kMaroon = new Color(0.5019608f, 0.0f, 0.0f);
+  public static final Color kMaroon = new Color(0.5019608f, 0.0f, 0.0f, "kMaroon");
 
   /** 0x66CDAA. */
-  public static final Color kMediumAquamarine = new Color(0.4f, 0.8039216f, 0.6666667f);
+  public static final Color kMediumAquamarine =
+      new Color(0.4f, 0.8039216f, 0.6666667f, "kMediumAquamarine");
 
   /** 0x0000CD. */
-  public static final Color kMediumBlue = new Color(0.0f, 0.0f, 0.8039216f);
+  public static final Color kMediumBlue = new Color(0.0f, 0.0f, 0.8039216f, "kMediumBlue");
 
   /** 0xBA55D3. */
-  public static final Color kMediumOrchid = new Color(0.7294118f, 0.33333334f, 0.827451f);
+  public static final Color kMediumOrchid =
+      new Color(0.7294118f, 0.33333334f, 0.827451f, "kMediumOrchid");
 
   /** 0x9370DB. */
-  public static final Color kMediumPurple = new Color(0.5764706f, 0.4392157f, 0.85882354f);
+  public static final Color kMediumPurple =
+      new Color(0.5764706f, 0.4392157f, 0.85882354f, "kMediumPurple");
 
   /** 0x3CB371. */
-  public static final Color kMediumSeaGreen = new Color(0.23529412f, 0.7019608f, 0.44313726f);
+  public static final Color kMediumSeaGreen =
+      new Color(0.23529412f, 0.7019608f, 0.44313726f, "kMediumSeaGreen");
 
   /** 0x7B68EE. */
-  public static final Color kMediumSlateBlue = new Color(0.48235294f, 0.40784314f, 0.93333334f);
+  public static final Color kMediumSlateBlue =
+      new Color(0.48235294f, 0.40784314f, 0.93333334f, "kMediumSlateBlue");
 
   /** 0x00FA9A. */
-  public static final Color kMediumSpringGreen = new Color(0.0f, 0.98039216f, 0.6039216f);
+  public static final Color kMediumSpringGreen =
+      new Color(0.0f, 0.98039216f, 0.6039216f, "kMediumSpringGreen");
 
   /** 0x48D1CC. */
-  public static final Color kMediumTurquoise = new Color(0.28235295f, 0.81960785f, 0.8f);
+  public static final Color kMediumTurquoise =
+      new Color(0.28235295f, 0.81960785f, 0.8f, "kMediumTurquoise");
 
   /** 0xC71585. */
-  public static final Color kMediumVioletRed = new Color(0.78039217f, 0.08235294f, 0.52156866f);
+  public static final Color kMediumVioletRed =
+      new Color(0.78039217f, 0.08235294f, 0.52156866f, "kMediumVioletRed");
 
   /** 0x191970. */
-  public static final Color kMidnightBlue = new Color(0.09803922f, 0.09803922f, 0.4392157f);
+  public static final Color kMidnightBlue =
+      new Color(0.09803922f, 0.09803922f, 0.4392157f, "kMidnightBlue");
 
   /** 0xF5FFFA. */
-  public static final Color kMintcream = new Color(0.9607843f, 1.0f, 0.98039216f);
+  public static final Color kMintcream = new Color(0.9607843f, 1.0f, 0.98039216f, "kMintcream");
 
   /** 0xFFE4E1. */
-  public static final Color kMistyRose = new Color(1.0f, 0.89411765f, 0.88235295f);
+  public static final Color kMistyRose = new Color(1.0f, 0.89411765f, 0.88235295f, "kMistyRose");
 
   /** 0xFFE4B5. */
-  public static final Color kMoccasin = new Color(1.0f, 0.89411765f, 0.70980394f);
+  public static final Color kMoccasin = new Color(1.0f, 0.89411765f, 0.70980394f, "kMoccasin");
 
   /** 0xFFDEAD. */
-  public static final Color kNavajoWhite = new Color(1.0f, 0.87058824f, 0.6784314f);
+  public static final Color kNavajoWhite = new Color(1.0f, 0.87058824f, 0.6784314f, "kNavajoWhite");
 
   /** 0x000080. */
-  public static final Color kNavy = new Color(0.0f, 0.0f, 0.5019608f);
+  public static final Color kNavy = new Color(0.0f, 0.0f, 0.5019608f, "kNavy");
 
   /** 0xFDF5E6. */
-  public static final Color kOldLace = new Color(0.99215686f, 0.9607843f, 0.9019608f);
+  public static final Color kOldLace = new Color(0.99215686f, 0.9607843f, 0.9019608f, "kOldLace");
 
   /** 0x808000. */
-  public static final Color kOlive = new Color(0.5019608f, 0.5019608f, 0.0f);
+  public static final Color kOlive = new Color(0.5019608f, 0.5019608f, 0.0f, "kOlive");
 
   /** 0x6B8E23. */
-  public static final Color kOliveDrab = new Color(0.41960785f, 0.5568628f, 0.13725491f);
+  public static final Color kOliveDrab =
+      new Color(0.41960785f, 0.5568628f, 0.13725491f, "kOliveDrab");
 
   /** 0xFFA500. */
-  public static final Color kOrange = new Color(1.0f, 0.64705884f, 0.0f);
+  public static final Color kOrange = new Color(1.0f, 0.64705884f, 0.0f, "kOrange");
 
   /** 0xFF4500. */
-  public static final Color kOrangeRed = new Color(1.0f, 0.27058825f, 0.0f);
+  public static final Color kOrangeRed = new Color(1.0f, 0.27058825f, 0.0f, "kOrangeRed");
 
   /** 0xDA70D6. */
-  public static final Color kOrchid = new Color(0.85490197f, 0.4392157f, 0.8392157f);
+  public static final Color kOrchid = new Color(0.85490197f, 0.4392157f, 0.8392157f, "kOrchid");
 
   /** 0xEEE8AA. */
-  public static final Color kPaleGoldenrod = new Color(0.93333334f, 0.9098039f, 0.6666667f);
+  public static final Color kPaleGoldenrod =
+      new Color(0.93333334f, 0.9098039f, 0.6666667f, "kPaleGoldenrod");
 
   /** 0x98FB98. */
-  public static final Color kPaleGreen = new Color(0.59607846f, 0.9843137f, 0.59607846f);
+  public static final Color kPaleGreen =
+      new Color(0.59607846f, 0.9843137f, 0.59607846f, "kPaleGreen");
 
   /** 0xAFEEEE. */
-  public static final Color kPaleTurquoise = new Color(0.6862745f, 0.93333334f, 0.93333334f);
+  public static final Color kPaleTurquoise =
+      new Color(0.6862745f, 0.93333334f, 0.93333334f, "kPaleTurquoise");
 
   /** 0xDB7093. */
-  public static final Color kPaleVioletRed = new Color(0.85882354f, 0.4392157f, 0.5764706f);
+  public static final Color kPaleVioletRed =
+      new Color(0.85882354f, 0.4392157f, 0.5764706f, "kPaleVioletRed");
 
   /** 0xFFEFD5. */
-  public static final Color kPapayaWhip = new Color(1.0f, 0.9372549f, 0.8352941f);
+  public static final Color kPapayaWhip = new Color(1.0f, 0.9372549f, 0.8352941f, "kPapayaWhip");
 
   /** 0xFFDAB9. */
-  public static final Color kPeachPuff = new Color(1.0f, 0.85490197f, 0.7254902f);
+  public static final Color kPeachPuff = new Color(1.0f, 0.85490197f, 0.7254902f, "kPeachPuff");
 
   /** 0xCD853F. */
-  public static final Color kPeru = new Color(0.8039216f, 0.52156866f, 0.24705882f);
+  public static final Color kPeru = new Color(0.8039216f, 0.52156866f, 0.24705882f, "kPeru");
 
   /** 0xFFC0CB. */
-  public static final Color kPink = new Color(1.0f, 0.7529412f, 0.79607844f);
+  public static final Color kPink = new Color(1.0f, 0.7529412f, 0.79607844f, "kPink");
 
   /** 0xDDA0DD. */
-  public static final Color kPlum = new Color(0.8666667f, 0.627451f, 0.8666667f);
+  public static final Color kPlum = new Color(0.8666667f, 0.627451f, 0.8666667f, "kPlum");
 
   /** 0xB0E0E6. */
-  public static final Color kPowderBlue = new Color(0.6901961f, 0.8784314f, 0.9019608f);
+  public static final Color kPowderBlue =
+      new Color(0.6901961f, 0.8784314f, 0.9019608f, "kPowderBlue");
 
   /** 0x800080. */
-  public static final Color kPurple = new Color(0.5019608f, 0.0f, 0.5019608f);
+  public static final Color kPurple = new Color(0.5019608f, 0.0f, 0.5019608f, "kPurple");
 
   /** 0xFF0000. */
-  public static final Color kRed = new Color(1.0f, 0.0f, 0.0f);
+  public static final Color kRed = new Color(1.0f, 0.0f, 0.0f, "kRed");
 
   /** 0xBC8F8F. */
-  public static final Color kRosyBrown = new Color(0.7372549f, 0.56078434f, 0.56078434f);
+  public static final Color kRosyBrown =
+      new Color(0.7372549f, 0.56078434f, 0.56078434f, "kRosyBrown");
 
   /** 0x4169E1. */
-  public static final Color kRoyalBlue = new Color(0.25490198f, 0.4117647f, 0.88235295f);
+  public static final Color kRoyalBlue =
+      new Color(0.25490198f, 0.4117647f, 0.88235295f, "kRoyalBlue");
 
   /** 0x8B4513. */
-  public static final Color kSaddleBrown = new Color(0.54509807f, 0.27058825f, 0.07450981f);
+  public static final Color kSaddleBrown =
+      new Color(0.54509807f, 0.27058825f, 0.07450981f, "kSaddleBrown");
 
   /** 0xFA8072. */
-  public static final Color kSalmon = new Color(0.98039216f, 0.5019608f, 0.44705883f);
+  public static final Color kSalmon = new Color(0.98039216f, 0.5019608f, 0.44705883f, "kSalmon");
 
   /** 0xF4A460. */
-  public static final Color kSandyBrown = new Color(0.95686275f, 0.6431373f, 0.3764706f);
+  public static final Color kSandyBrown =
+      new Color(0.95686275f, 0.6431373f, 0.3764706f, "kSandyBrown");
 
   /** 0x2E8B57. */
-  public static final Color kSeaGreen = new Color(0.18039216f, 0.54509807f, 0.34117648f);
+  public static final Color kSeaGreen =
+      new Color(0.18039216f, 0.54509807f, 0.34117648f, "kSeaGreen");
 
   /** 0xFFF5EE. */
-  public static final Color kSeashell = new Color(1.0f, 0.9607843f, 0.93333334f);
+  public static final Color kSeashell = new Color(1.0f, 0.9607843f, 0.93333334f, "kSeashell");
 
   /** 0xA0522D. */
-  public static final Color kSienna = new Color(0.627451f, 0.32156864f, 0.1764706f);
+  public static final Color kSienna = new Color(0.627451f, 0.32156864f, 0.1764706f, "kSienna");
 
   /** 0xC0C0C0. */
-  public static final Color kSilver = new Color(0.7529412f, 0.7529412f, 0.7529412f);
+  public static final Color kSilver = new Color(0.7529412f, 0.7529412f, 0.7529412f, "kSilver");
 
   /** 0x87CEEB. */
-  public static final Color kSkyBlue = new Color(0.5294118f, 0.80784315f, 0.92156863f);
+  public static final Color kSkyBlue = new Color(0.5294118f, 0.80784315f, 0.92156863f, "kSkyBlue");
 
   /** 0x6A5ACD. */
-  public static final Color kSlateBlue = new Color(0.41568628f, 0.3529412f, 0.8039216f);
+  public static final Color kSlateBlue =
+      new Color(0.41568628f, 0.3529412f, 0.8039216f, "kSlateBlue");
 
   /** 0x708090. */
-  public static final Color kSlateGray = new Color(0.4392157f, 0.5019608f, 0.5647059f);
+  public static final Color kSlateGray =
+      new Color(0.4392157f, 0.5019608f, 0.5647059f, "kSlateGray");
 
   /** 0xFFFAFA. */
-  public static final Color kSnow = new Color(1.0f, 0.98039216f, 0.98039216f);
+  public static final Color kSnow = new Color(1.0f, 0.98039216f, 0.98039216f, "kSnow");
 
   /** 0x00FF7F. */
-  public static final Color kSpringGreen = new Color(0.0f, 1.0f, 0.49803922f);
+  public static final Color kSpringGreen = new Color(0.0f, 1.0f, 0.49803922f, "kSpringGreen");
 
   /** 0x4682B4. */
-  public static final Color kSteelBlue = new Color(0.27450982f, 0.50980395f, 0.7058824f);
+  public static final Color kSteelBlue =
+      new Color(0.27450982f, 0.50980395f, 0.7058824f, "kSteelBlue");
 
   /** 0xD2B48C. */
-  public static final Color kTan = new Color(0.8235294f, 0.7058824f, 0.54901963f);
+  public static final Color kTan = new Color(0.8235294f, 0.7058824f, 0.54901963f, "kTan");
 
   /** 0x008080. */
-  public static final Color kTeal = new Color(0.0f, 0.5019608f, 0.5019608f);
+  public static final Color kTeal = new Color(0.0f, 0.5019608f, 0.5019608f, "kTeal");
 
   /** 0xD8BFD8. */
-  public static final Color kThistle = new Color(0.84705883f, 0.7490196f, 0.84705883f);
+  public static final Color kThistle = new Color(0.84705883f, 0.7490196f, 0.84705883f, "kThistle");
 
   /** 0xFF6347. */
-  public static final Color kTomato = new Color(1.0f, 0.3882353f, 0.2784314f);
+  public static final Color kTomato = new Color(1.0f, 0.3882353f, 0.2784314f, "kTomato");
 
   /** 0x40E0D0. */
-  public static final Color kTurquoise = new Color(0.2509804f, 0.8784314f, 0.8156863f);
+  public static final Color kTurquoise =
+      new Color(0.2509804f, 0.8784314f, 0.8156863f, "kTurquoise");
 
   /** 0xEE82EE. */
-  public static final Color kViolet = new Color(0.93333334f, 0.50980395f, 0.93333334f);
+  public static final Color kViolet = new Color(0.93333334f, 0.50980395f, 0.93333334f, "kViolet");
 
   /** 0xF5DEB3. */
-  public static final Color kWheat = new Color(0.9607843f, 0.87058824f, 0.7019608f);
+  public static final Color kWheat = new Color(0.9607843f, 0.87058824f, 0.7019608f, "kWheat");
 
   /** 0xFFFFFF. */
-  public static final Color kWhite = new Color(1.0f, 1.0f, 1.0f);
+  public static final Color kWhite = new Color(1.0f, 1.0f, 1.0f, "kWhite");
 
   /** 0xF5F5F5. */
-  public static final Color kWhiteSmoke = new Color(0.9607843f, 0.9607843f, 0.9607843f);
+  public static final Color kWhiteSmoke =
+      new Color(0.9607843f, 0.9607843f, 0.9607843f, "kWhiteSmoke");
 
   /** 0xFFFF00. */
-  public static final Color kYellow = new Color(1.0f, 1.0f, 0.0f);
+  public static final Color kYellow = new Color(1.0f, 1.0f, 0.0f, "kYellow");
 
   /** 0x9ACD32. */
-  public static final Color kYellowGreen = new Color(0.6039216f, 0.8039216f, 0.19607843f);
+  public static final Color kYellowGreen =
+      new Color(0.6039216f, 0.8039216f, 0.19607843f, "kYellowGreen");
 }
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/util/Color8Bit.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/util/Color8Bit.java
index cd7154d..3260673 100644
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/util/Color8Bit.java
+++ b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/util/Color8Bit.java
@@ -53,4 +53,18 @@
   public int hashCode() {
     return Objects.hash(red, green, blue);
   }
+
+  @Override
+  public String toString() {
+    return toHexString();
+  }
+
+  /**
+   * Return this color represented as a hex string.
+   *
+   * @return a string of the format <code>#RRGGBB</code>
+   */
+  public String toHexString() {
+    return String.format("#%02X%02X%02X", red, green, blue);
+  }
 }
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/util/ErrorMessages.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/util/ErrorMessages.java
deleted file mode 100644
index c5b5832..0000000
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/util/ErrorMessages.java
+++ /dev/null
@@ -1,41 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.util;
-
-import static java.util.Objects.requireNonNull;
-
-/** Utility class for common WPILib error messages. */
-public final class ErrorMessages {
-  /** Utility class, so constructor is private. */
-  private ErrorMessages() {
-    throw new UnsupportedOperationException("This is a utility class!");
-  }
-
-  /**
-   * Requires that a parameter of a method not be null; prints an error message with helpful
-   * debugging instructions if the parameter is null.
-   *
-   * @param <T> Type of object.
-   * @param obj The parameter that must not be null.
-   * @param paramName The name of the parameter.
-   * @param methodName The name of the method.
-   * @return The object parameter confirmed not to be null.
-   */
-  public static <T> T requireNonNullParam(T obj, String paramName, String methodName) {
-    return requireNonNull(
-        obj,
-        "Parameter "
-            + paramName
-            + " in method "
-            + methodName
-            + " was null when it"
-            + " should not have been!  Check the stacktrace to find the responsible line of code - "
-            + "usually, it is the first line of user-written code indicated in the stacktrace.  "
-            + "Make sure all objects passed to the method in question were properly initialized -"
-            + " note that this may not be obvious if it is being called under "
-            + "dynamically-changing conditions!  Please do not seek additional technical assistance"
-            + " without doing this first!");
-  }
-}
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/vision/VisionPipeline.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/vision/VisionPipeline.java
deleted file mode 100644
index d888d3b..0000000
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/vision/VisionPipeline.java
+++ /dev/null
@@ -1,26 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.vision;
-
-import org.opencv.core.Mat;
-
-/**
- * A vision pipeline is responsible for running a group of OpenCV algorithms to extract data from an
- * image.
- *
- * @see VisionRunner
- * @see VisionThread
- * @deprecated Replaced with edu.wpi.first.vision.VisionPipeline
- */
-@Deprecated
-public interface VisionPipeline {
-  /**
-   * Processes the image input and sets the result objects. Implementations should make these
-   * objects accessible.
-   *
-   * @param image The image to process.
-   */
-  void process(Mat image);
-}
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/vision/VisionRunner.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/vision/VisionRunner.java
deleted file mode 100644
index a1002f5..0000000
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/vision/VisionRunner.java
+++ /dev/null
@@ -1,123 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.vision;
-
-import edu.wpi.first.cameraserver.CameraServerSharedStore;
-import edu.wpi.first.cscore.CvSink;
-import edu.wpi.first.cscore.VideoSource;
-import org.opencv.core.Mat;
-
-/**
- * A vision runner is a convenient wrapper object to make it easy to run vision pipelines from robot
- * code. The easiest way to use this is to run it in a {@link VisionThread} and use the listener to
- * take snapshots of the pipeline's outputs.
- *
- * @see VisionPipeline
- * @see VisionThread
- * @see <a href="package-summary.html">vision</a>
- * @deprecated Replaced with edu.wpi.first.vision.VisionRunner
- */
-@Deprecated
-public class VisionRunner<P extends VisionPipeline> {
-  private final CvSink m_cvSink = new CvSink("VisionRunner CvSink");
-  private final P m_pipeline;
-  private final Mat m_image = new Mat();
-  private final Listener<? super P> m_listener;
-  private volatile boolean m_enabled = true;
-
-  /**
-   * Listener interface for a callback that should run after a pipeline has processed its input.
-   *
-   * @param <P> the type of the pipeline this listener is for
-   */
-  @FunctionalInterface
-  public interface Listener<P extends VisionPipeline> {
-    /**
-     * Called when the pipeline has run. This shouldn't take much time to run because it will delay
-     * later calls to the pipeline's {@link VisionPipeline#process process} method. Copying the
-     * outputs and code that uses the copies should be <i>synchronized</i> on the same mutex to
-     * prevent multiple threads from reading and writing to the same memory at the same time.
-     *
-     * @param pipeline the vision pipeline that ran
-     */
-    void copyPipelineOutputs(P pipeline);
-  }
-
-  /**
-   * Creates a new vision runner. It will take images from the {@code videoSource}, send them to the
-   * {@code pipeline}, and call the {@code listener} when the pipeline has finished to alert user
-   * code when it is safe to access the pipeline's outputs.
-   *
-   * @param videoSource the video source to use to supply images for the pipeline
-   * @param pipeline the vision pipeline to run
-   * @param listener a function to call after the pipeline has finished running
-   */
-  public VisionRunner(VideoSource videoSource, P pipeline, Listener<? super P> listener) {
-    this.m_pipeline = pipeline;
-    this.m_listener = listener;
-    m_cvSink.setSource(videoSource);
-  }
-
-  /**
-   * Runs the pipeline one time, giving it the next image from the video source specified in the
-   * constructor. This will block until the source either has an image or throws an error. If the
-   * source successfully supplied a frame, the pipeline's image input will be set, the pipeline will
-   * run, and the listener specified in the constructor will be called to notify it that the
-   * pipeline ran.
-   *
-   * <p>This method is exposed to allow teams to add additional functionality or have their own ways
-   * to run the pipeline. Most teams, however, should just use {@link #runForever} in its own thread
-   * using a {@link VisionThread}.
-   */
-  public void runOnce() {
-    Long id = CameraServerSharedStore.getCameraServerShared().getRobotMainThreadId();
-
-    if (id != null && Thread.currentThread().getId() == id) {
-      throw new IllegalStateException(
-          "VisionRunner.runOnce() cannot be called from the main robot thread");
-    }
-    runOnceInternal();
-  }
-
-  private void runOnceInternal() {
-    long frameTime = m_cvSink.grabFrame(m_image);
-    if (frameTime == 0) {
-      // There was an error, report it
-      String error = m_cvSink.getError();
-      CameraServerSharedStore.getCameraServerShared().reportDriverStationError(error);
-    } else {
-      // No errors, process the image
-      m_pipeline.process(m_image);
-      m_listener.copyPipelineOutputs(m_pipeline);
-    }
-  }
-
-  /**
-   * A convenience method that calls {@link #runOnce()} in an infinite loop. This must be run in a
-   * dedicated thread, and cannot be used in the main robot thread because it will freeze the robot
-   * program.
-   *
-   * <p><strong>Do not call this method directly from the main thread.</strong>
-   *
-   * @throws IllegalStateException if this is called from the main robot thread
-   * @see VisionThread
-   */
-  public void runForever() {
-    Long id = CameraServerSharedStore.getCameraServerShared().getRobotMainThreadId();
-
-    if (id != null && Thread.currentThread().getId() == id) {
-      throw new IllegalStateException(
-          "VisionRunner.runForever() cannot be called from the main robot thread");
-    }
-    while (m_enabled && !Thread.interrupted()) {
-      runOnceInternal();
-    }
-  }
-
-  /** Stop a RunForever() loop. */
-  public void stop() {
-    m_enabled = false;
-  }
-}
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/vision/VisionThread.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/vision/VisionThread.java
deleted file mode 100644
index 5f23fe1..0000000
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/vision/VisionThread.java
+++ /dev/null
@@ -1,44 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.vision;
-
-import edu.wpi.first.cscore.VideoSource;
-
-/**
- * A vision thread is a special thread that runs a vision pipeline. It is a <i>daemon</i> thread; it
- * does not prevent the program from exiting when all other non-daemon threads have finished
- * running.
- *
- * @see VisionPipeline
- * @see VisionRunner
- * @see Thread#setDaemon(boolean)
- * @deprecated Replaced with edu.wpi.first.vision.VisionThread
- */
-@Deprecated
-public class VisionThread extends Thread {
-  /**
-   * Creates a vision thread that continuously runs a {@link VisionPipeline}.
-   *
-   * @param visionRunner the runner for a vision pipeline
-   */
-  public VisionThread(VisionRunner<?> visionRunner) {
-    super(visionRunner::runForever, "WPILib Vision Thread");
-    setDaemon(true);
-  }
-
-  /**
-   * Creates a new vision thread that continuously runs the given vision pipeline. This is
-   * equivalent to {@code new VisionThread(new VisionRunner<>(videoSource, pipeline, listener))}.
-   *
-   * @param videoSource the source for images the pipeline should process
-   * @param pipeline the pipeline to run
-   * @param listener the listener to copy outputs from the pipeline after it runs
-   * @param <P> the type of the pipeline
-   */
-  public <P extends VisionPipeline> VisionThread(
-      VideoSource videoSource, P pipeline, VisionRunner.Listener<? super P> listener) {
-    this(new VisionRunner<>(videoSource, pipeline, listener));
-  }
-}
diff --git a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/vision/package-info.java b/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/vision/package-info.java
deleted file mode 100644
index b52f4ed..0000000
--- a/third_party/allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/vision/package-info.java
+++ /dev/null
@@ -1,86 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-/**
- * Classes in the {@code edu.wpi.first.wpilibj.vision} package are designed to simplify using OpenCV
- * vision processing code from a robot program.
- *
- * <p>An example use case for grabbing a yellow tote from 2015 in autonomous: <br>
- *
- * <pre><code>
- * public class Robot extends IterativeRobot
- *     implements VisionRunner.Listener&lt;MyFindTotePipeline&gt; {
- *
- *      // A USB camera connected to the roboRIO.
- *      private {@link edu.wpi.first.cscore.VideoSource VideoSource} usbCamera;
- *
- *      // A vision pipeline. This could be handwritten or generated by GRIP.
- *      // This has to implement {@link edu.wpi.first.wpilibj.vision.VisionPipeline}.
- *      // For this example, assume that it's perfect and will always see the tote.
- *      private MyFindTotePipeline findTotePipeline;
- *      private {@link edu.wpi.first.wpilibj.vision.VisionThread} findToteThread;
- *
- *      // The object to synchronize on to make sure the vision thread doesn't
- *      // write to variables the main thread is using.
- *      private final Object visionLock = new Object();
- *
- *      // The pipeline outputs we want
- *      private boolean pipelineRan = false; // lets us know when the pipeline has actually run
- *      private double angleToTote = 0;
- *      private double distanceToTote = 0;
- *
- *     {@literal @}Override
- *      public void {@link edu.wpi.first.wpilibj.vision.VisionRunner.Listener#copyPipelineOutputs
- *          copyPipelineOutputs(MyFindTotePipeline pipeline)} {
- *          synchronized (visionLock) {
- *              // Take a snapshot of the pipeline's output because
- *              // it may have changed the next time this method is called!
- *              this.pipelineRan = true;
- *              this.angleToTote = pipeline.getAngleToTote();
- *              this.distanceToTote = pipeline.getDistanceToTote();
- *          }
- *      }
- *
- *     {@literal @}Override
- *      public void robotInit() {
- *          usbCamera = CameraServer.startAutomaticCapture(0);
- *          findTotePipeline = new MyFindTotePipeline();
- *          findToteThread = new VisionThread(usbCamera, findTotePipeline, this);
- *      }
- *
- *     {@literal @}Override
- *      public void autonomousInit() {
- *          findToteThread.start();
- *      }
- *
- *     {@literal @}Override
- *      public void autonomousPeriodic() {
- *          double angle;
- *          double distance;
- *          synchronized (visionLock) {
- *              if (!pipelineRan) {
- *                  // Wait until the pipeline has run
- *                  return;
- *              }
- *              // Copy the outputs to make sure they're all from the same run
- *              angle = this.angleToTote;
- *              distance = this.distanceToTote;
- *          }
- *          if (!aimedAtTote()) {
- *              turnToAngle(angle);
- *          } else if (!droveToTote()) {
- *              driveDistance(distance);
- *          } else if (!grabbedTote()) {
- *              grabTote();
- *          } else {
- *              // Tote was grabbed and we're done!
- *              return;
- *          }
- *      }
- *
- * }
- * </code></pre>
- */
-@java.lang.Deprecated
-package edu.wpi.first.wpilibj.vision;
diff --git a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/math/util/ErrorMessagesTest.java b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/math/util/ErrorMessagesTest.java
deleted file mode 100644
index 5153b00..0000000
--- a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/math/util/ErrorMessagesTest.java
+++ /dev/null
@@ -1,30 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.math.util;
-
-import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
-import static org.junit.jupiter.api.Assertions.assertDoesNotThrow;
-import static org.junit.jupiter.api.Assertions.assertThrows;
-
-import edu.wpi.first.wpilibj.UtilityClassTest;
-import edu.wpi.first.wpilibj.util.ErrorMessages;
-import org.junit.jupiter.api.Test;
-
-class ErrorMessagesTest extends UtilityClassTest<ErrorMessages> {
-  ErrorMessagesTest() {
-    super(ErrorMessages.class);
-  }
-
-  @Test
-  void requireNonNullParamNullTest() {
-    assertThrows(
-        NullPointerException.class, () -> requireNonNullParam(null, "testParam", "testMethod"));
-  }
-
-  @Test
-  void requireNonNullParamNotNullTest() {
-    assertDoesNotThrow(() -> requireNonNullParam("null", "testParam", "testMethod"));
-  }
-}
diff --git a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/AddressableLEDBufferTest.java b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/AddressableLEDBufferTest.java
index 031d411..9bf5d88 100644
--- a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/AddressableLEDBufferTest.java
+++ b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/AddressableLEDBufferTest.java
@@ -19,7 +19,6 @@
 class AddressableLEDBufferTest {
   @ParameterizedTest
   @MethodSource("hsvToRgbProvider")
-  @SuppressWarnings("ParameterName")
   void hsvConvertTest(int h, int s, int v, int r, int g, int b) {
     var buffer = new AddressableLEDBuffer(1);
     buffer.setHSV(0, h, s, v);
@@ -36,16 +35,16 @@
         arguments(0, 255, 255, 255, 0, 0), // Red
         arguments(60, 255, 255, 0, 255, 0), // Lime
         arguments(120, 255, 255, 0, 0, 255), // Blue
-        arguments(30, 255, 255, 254, 255, 0), // Yellow (ish)
-        arguments(90, 255, 255, 0, 254, 255), // Cyan (ish)
-        arguments(150, 255, 255, 255, 0, 254), // Magenta (ish)
+        arguments(30, 255, 255, 255, 255, 0), // Yellow
+        arguments(90, 255, 255, 0, 255, 255), // Cyan
+        arguments(150, 255, 255, 255, 0, 255), // Magenta
         arguments(0, 0, 191, 191, 191, 191), // Silver
         arguments(0, 0, 128, 128, 128, 128), // Gray
         arguments(0, 255, 128, 128, 0, 0), // Maroon
-        arguments(30, 255, 128, 127, 128, 0), // Olive (ish)
+        arguments(30, 255, 128, 128, 128, 0), // Olive
         arguments(60, 255, 128, 0, 128, 0), // Green
-        arguments(150, 255, 128, 128, 0, 127), // Purple (ish)
-        arguments(90, 255, 128, 0, 127, 128), // Teal (ish)
+        arguments(150, 255, 128, 128, 0, 128), // Purple
+        arguments(90, 255, 128, 0, 128, 128), // Teal
         arguments(120, 255, 128, 0, 0, 128) // Navy
         );
   }
diff --git a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/PS4ControllerTest.java b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/PS4ControllerTest.java
index c1ebd51..31277a3 100644
--- a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/PS4ControllerTest.java
+++ b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/PS4ControllerTest.java
@@ -18,7 +18,6 @@
 class PS4ControllerTest {
   @ParameterizedTest
   @EnumSource(value = PS4Controller.Button.class)
-  @SuppressWarnings({"VariableDeclarationUsageDistance"})
   void testButtons(PS4Controller.Button button)
       throws NoSuchMethodException, InvocationTargetException, IllegalAccessException {
     HAL.initialize(500, 0);
@@ -32,10 +31,10 @@
     String joyPressedMethodName = "get" + buttonName + "Pressed";
     String joyReleasedMethodName = "get" + buttonName + "Released";
 
-    Method simSetMethod = joysim.getClass().getMethod(simSetMethodName, boolean.class);
-    Method joyGetMethod = joy.getClass().getMethod(joyGetMethodName);
-    Method joyPressedMethod = joy.getClass().getMethod(joyPressedMethodName);
-    Method joyReleasedMethod = joy.getClass().getMethod(joyReleasedMethodName);
+    final Method simSetMethod = joysim.getClass().getMethod(simSetMethodName, boolean.class);
+    final Method joyGetMethod = joy.getClass().getMethod(joyGetMethodName);
+    final Method joyPressedMethod = joy.getClass().getMethod(joyPressedMethodName);
+    final Method joyReleasedMethod = joy.getClass().getMethod(joyReleasedMethodName);
 
     simSetMethod.invoke(joysim, false);
     joysim.notifyNewData();
@@ -59,7 +58,6 @@
 
   @ParameterizedTest
   @EnumSource(value = PS4Controller.Axis.class)
-  @SuppressWarnings({"VariableDeclarationUsageDistance"})
   void testAxes(PS4Controller.Axis axis)
       throws NoSuchMethodException, InvocationTargetException, IllegalAccessException {
     HAL.initialize(500, 0);
diff --git a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/PreferencesTest.java b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/PreferencesTest.java
index 2603d5b..e3ccfcc 100644
--- a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/PreferencesTest.java
+++ b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/PreferencesTest.java
@@ -9,107 +9,107 @@
 import static org.junit.jupiter.api.Assertions.assertFalse;
 import static org.junit.jupiter.api.Assertions.assertTrue;
 import static org.junit.jupiter.api.Assertions.fail;
+import static org.junit.jupiter.api.parallel.ExecutionMode.SAME_THREAD;
 
 import edu.wpi.first.networktables.NetworkTable;
 import edu.wpi.first.networktables.NetworkTableInstance;
+import edu.wpi.first.networktables.Topic;
 import java.io.IOException;
 import java.io.InputStream;
 import java.nio.file.Files;
 import java.nio.file.Path;
+import java.util.ArrayList;
 import java.util.Arrays;
-import java.util.Set;
+import java.util.List;
 import java.util.stream.Stream;
-import org.junit.jupiter.api.AfterAll;
 import org.junit.jupiter.api.AfterEach;
-import org.junit.jupiter.api.BeforeAll;
 import org.junit.jupiter.api.BeforeEach;
 import org.junit.jupiter.api.Nested;
 import org.junit.jupiter.api.Test;
 import org.junit.jupiter.api.io.TempDir;
+import org.junit.jupiter.api.parallel.Execution;
 import org.junit.jupiter.params.ParameterizedTest;
 import org.junit.jupiter.params.provider.MethodSource;
 
+@Execution(SAME_THREAD)
 class PreferencesTest {
-  private final Preferences m_prefs = Preferences.getInstance();
-  private final NetworkTable m_table = NetworkTableInstance.getDefault().getTable("Preferences");
+  private NetworkTableInstance m_inst;
+  private NetworkTable m_table;
 
-  private static final String kFilename = "networktables.ini";
-
-  @BeforeAll
-  static void setupAll() {
-    NetworkTableInstance.getDefault().stopServer();
-  }
+  private static final String kFilename = "networktables.json";
 
   @BeforeEach
   void setup(@TempDir Path tempDir) {
-    m_table.getKeys().forEach(m_table::delete);
+    m_inst = NetworkTableInstance.create();
+    m_table = m_inst.getTable("Preferences");
+    Preferences.setNetworkTableInstance(m_inst);
 
     Path filepath = tempDir.resolve(kFilename);
-    try (InputStream is = getClass().getResource("PreferencesTestDefault.ini").openStream()) {
+    try (InputStream is = getClass().getResource("PreferencesTestDefault.json").openStream()) {
       Files.copy(is, filepath);
     } catch (IOException ex) {
       fail(ex);
     }
 
-    NetworkTableInstance.getDefault().startServer(filepath.toString());
+    m_inst.startServer(filepath.toString(), "", 0, 0);
+    try {
+      int count = 0;
+      while (m_inst.getNetworkMode().contains(NetworkTableInstance.NetworkMode.kStarting)) {
+        Thread.sleep(100);
+        count++;
+        if (count > 30) {
+          throw new InterruptedException();
+        }
+      }
+    } catch (InterruptedException ex) {
+      fail("interrupted while waiting for server to start");
+    }
   }
 
   @AfterEach
   void cleanup() {
-    NetworkTableInstance.getDefault().stopServer();
-  }
-
-  @AfterAll
-  static void cleanupAll() {
-    NetworkTableInstance.getDefault().startServer();
+    m_inst.close();
   }
 
   @Test
   void removeAllTest() {
-    m_prefs.removeAll();
+    Preferences.removeAll();
 
-    Set<String> keys = m_table.getKeys();
-    keys.remove(".type");
+    List<String> keys = new ArrayList<>();
+    boolean anyPersistent = false;
+    for (Topic topic : m_table.getTopics()) {
+      if (topic.isPersistent()) {
+        anyPersistent = true;
+        keys.add(topic.getName());
+      }
+    }
 
-    assertTrue(
-        keys.isEmpty(),
+    assertFalse(
+        anyPersistent,
         "Preferences was not empty!  Preferences in table: " + Arrays.toString(keys.toArray()));
   }
 
   @ParameterizedTest
   @MethodSource("defaultKeyProvider")
   void defaultKeysTest(String key) {
-    assertTrue(m_prefs.containsKey(key));
+    assertTrue(Preferences.containsKey(key));
   }
 
   @ParameterizedTest
   @MethodSource("defaultKeyProvider")
   void defaultKeysAllTest(String key) {
-    assertTrue(m_prefs.getKeys().contains(key));
+    assertTrue(Preferences.getKeys().contains(key));
   }
 
   @Test
   void defaultValueTest() {
     assertAll(
-        () -> assertEquals(172L, m_prefs.getLong("checkedValueLong", 0)),
-        () -> assertEquals(0.2, m_prefs.getDouble("checkedValueDouble", 0), 1e-6),
-        () -> assertEquals("Hello. How are you?", m_prefs.getString("checkedValueString", "")),
-        () -> assertEquals(2, m_prefs.getInt("checkedValueInt", 0)),
-        () -> assertEquals(3.4, m_prefs.getFloat("checkedValueFloat", 0), 1e-6),
-        () -> assertFalse(m_prefs.getBoolean("checkedValueBoolean", true)));
-  }
-
-  @Test
-  void backupTest() {
-    m_prefs.removeAll();
-
-    assertAll(
-        () -> assertEquals(0, m_prefs.getLong("checkedValueLong", 0)),
-        () -> assertEquals(0, m_prefs.getDouble("checkedValueDouble", 0), 1e-6),
-        () -> assertEquals("", m_prefs.getString("checkedValueString", "")),
-        () -> assertEquals(0, m_prefs.getInt("checkedValueInt", 0)),
-        () -> assertEquals(0, m_prefs.getFloat("checkedValueFloat", 0), 1e-6),
-        () -> assertTrue(m_prefs.getBoolean("checkedValueBoolean", true)));
+        () -> assertEquals(172L, Preferences.getLong("checkedValueLong", 0)),
+        () -> assertEquals(0.2, Preferences.getDouble("checkedValueDouble", 0), 1e-6),
+        () -> assertEquals("Hello. How are you?", Preferences.getString("checkedValueString", "")),
+        () -> assertEquals(2, Preferences.getInt("checkedValueInt", 0)),
+        () -> assertEquals(3.4, Preferences.getFloat("checkedValueFloat", 0), 1e-6),
+        () -> assertFalse(Preferences.getBoolean("checkedValueBoolean", true)));
   }
 
   @Nested
@@ -119,10 +119,10 @@
       final String key = "test";
       final int value = 123;
 
-      m_prefs.putInt(key, value);
+      Preferences.setInt(key, value);
 
       assertAll(
-          () -> assertEquals(value, m_prefs.getInt(key, -1)),
+          () -> assertEquals(value, Preferences.getInt(key, -1)),
           () -> assertEquals(value, m_table.getEntry(key).getNumber(-1).intValue()));
     }
 
@@ -131,10 +131,10 @@
       final String key = "test";
       final long value = 190L;
 
-      m_prefs.putLong(key, value);
+      Preferences.setLong(key, value);
 
       assertAll(
-          () -> assertEquals(value, m_prefs.getLong(key, -1)),
+          () -> assertEquals(value, Preferences.getLong(key, -1)),
           () -> assertEquals(value, m_table.getEntry(key).getNumber(-1).longValue()));
     }
 
@@ -143,10 +143,10 @@
       final String key = "test";
       final float value = 9.42f;
 
-      m_prefs.putFloat(key, value);
+      Preferences.setFloat(key, value);
 
       assertAll(
-          () -> assertEquals(value, m_prefs.getFloat(key, -1), 1e-6),
+          () -> assertEquals(value, Preferences.getFloat(key, -1), 1e-6),
           () -> assertEquals(value, m_table.getEntry(key).getNumber(-1).floatValue(), 1e-6));
     }
 
@@ -155,10 +155,10 @@
       final String key = "test";
       final double value = 6.28;
 
-      m_prefs.putDouble(key, value);
+      Preferences.setDouble(key, value);
 
       assertAll(
-          () -> assertEquals(value, m_prefs.getDouble(key, -1), 1e-6),
+          () -> assertEquals(value, Preferences.getDouble(key, -1), 1e-6),
           () -> assertEquals(value, m_table.getEntry(key).getNumber(-1).doubleValue(), 1e-6));
     }
 
@@ -167,10 +167,10 @@
       final String key = "test";
       final String value = "value";
 
-      m_prefs.putString(key, value);
+      Preferences.setString(key, value);
 
       assertAll(
-          () -> assertEquals(value, m_prefs.getString(key, "")),
+          () -> assertEquals(value, Preferences.getString(key, "")),
           () -> assertEquals(value, m_table.getEntry(key).getString("")));
     }
 
@@ -179,10 +179,10 @@
       final String key = "test";
       final boolean value = true;
 
-      m_prefs.putBoolean(key, value);
+      Preferences.setBoolean(key, value);
 
       assertAll(
-          () -> assertEquals(value, m_prefs.getBoolean(key, false)),
+          () -> assertEquals(value, Preferences.getBoolean(key, false)),
           () -> assertEquals(value, m_table.getEntry(key).getBoolean(false)));
     }
   }
diff --git a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/TimedRobotTest.java b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/TimedRobotTest.java
index de5fd1c..bf143e7 100644
--- a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/TimedRobotTest.java
+++ b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/TimedRobotTest.java
@@ -5,14 +5,20 @@
 package edu.wpi.first.wpilibj;
 
 import static org.junit.jupiter.api.Assertions.assertEquals;
+import static org.junit.jupiter.api.Assertions.assertFalse;
+import static org.junit.jupiter.api.Assertions.assertThrows;
 
+import edu.wpi.first.wpilibj.livewindow.LiveWindow;
 import edu.wpi.first.wpilibj.simulation.DriverStationSim;
 import edu.wpi.first.wpilibj.simulation.SimHooks;
+import java.util.ConcurrentModificationException;
 import java.util.concurrent.atomic.AtomicInteger;
 import org.junit.jupiter.api.AfterEach;
 import org.junit.jupiter.api.BeforeEach;
 import org.junit.jupiter.api.Test;
 import org.junit.jupiter.api.parallel.ResourceLock;
+import org.junit.jupiter.params.ParameterizedTest;
+import org.junit.jupiter.params.provider.ValueSource;
 
 class TimedRobotTest {
   static class MockRobot extends TimedRobot {
@@ -119,6 +125,7 @@
   @BeforeEach
   void setup() {
     SimHooks.pauseTiming();
+    DriverStationSim.resetData();
   }
 
   @AfterEach
@@ -391,10 +398,12 @@
     robot.close();
   }
 
-  @Test
+  @ValueSource(booleans = {true, false})
+  @ParameterizedTest
   @ResourceLock("timing")
-  void testModeTest() {
+  void testModeTest(boolean isLW) {
     MockRobot robot = new MockRobot();
+    robot.enableLiveWindowInTest(isLW);
 
     Thread robotThread =
         new Thread(
@@ -415,6 +424,7 @@
     assertEquals(0, robot.m_autonomousInitCount.get());
     assertEquals(0, robot.m_teleopInitCount.get());
     assertEquals(0, robot.m_testInitCount.get());
+    assertFalse(LiveWindow.isEnabled());
 
     assertEquals(0, robot.m_robotPeriodicCount.get());
     assertEquals(0, robot.m_simulationPeriodicCount.get());
@@ -457,6 +467,9 @@
     assertEquals(0, robot.m_autonomousInitCount.get());
     assertEquals(0, robot.m_teleopInitCount.get());
     assertEquals(1, robot.m_testInitCount.get());
+    assertEquals(isLW, LiveWindow.isEnabled());
+
+    assertThrows(ConcurrentModificationException.class, () -> robot.enableLiveWindowInTest(isLW));
 
     assertEquals(2, robot.m_robotPeriodicCount.get());
     assertEquals(2, robot.m_simulationPeriodicCount.get());
@@ -470,6 +483,33 @@
     assertEquals(0, robot.m_teleopExitCount.get());
     assertEquals(0, robot.m_testExitCount.get());
 
+    DriverStationSim.setEnabled(false);
+    DriverStationSim.setAutonomous(false);
+    DriverStationSim.setTest(false);
+    DriverStationSim.notifyNewData();
+
+    SimHooks.stepTiming(0.02);
+
+    assertEquals(1, robot.m_robotInitCount.get());
+    assertEquals(1, robot.m_simulationInitCount.get());
+    assertEquals(1, robot.m_disabledInitCount.get());
+    assertEquals(0, robot.m_autonomousInitCount.get());
+    assertEquals(0, robot.m_teleopInitCount.get());
+    assertEquals(1, robot.m_testInitCount.get());
+    assertFalse(LiveWindow.isEnabled());
+
+    assertEquals(3, robot.m_robotPeriodicCount.get());
+    assertEquals(3, robot.m_simulationPeriodicCount.get());
+    assertEquals(1, robot.m_disabledPeriodicCount.get());
+    assertEquals(0, robot.m_autonomousPeriodicCount.get());
+    assertEquals(0, robot.m_teleopPeriodicCount.get());
+    assertEquals(2, robot.m_testPeriodicCount.get());
+
+    assertEquals(0, robot.m_disabledExitCount.get());
+    assertEquals(0, robot.m_autonomousExitCount.get());
+    assertEquals(0, robot.m_teleopExitCount.get());
+    assertEquals(1, robot.m_testExitCount.get());
+
     robot.endCompetition();
     try {
       robotThread.interrupt();
diff --git a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/XboxControllerTest.java b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/XboxControllerTest.java
index af9c902..b724bf4 100644
--- a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/XboxControllerTest.java
+++ b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/XboxControllerTest.java
@@ -18,7 +18,6 @@
 class XboxControllerTest {
   @ParameterizedTest
   @EnumSource(value = XboxController.Button.class)
-  @SuppressWarnings({"VariableDeclarationUsageDistance"})
   void testButtons(XboxController.Button button)
       throws NoSuchMethodException, InvocationTargetException, IllegalAccessException {
     HAL.initialize(500, 0);
@@ -32,10 +31,10 @@
     String joyPressedMethodName = "get" + buttonName + "Pressed";
     String joyReleasedMethodName = "get" + buttonName + "Released";
 
-    Method simSetMethod = joysim.getClass().getMethod(simSetMethodName, boolean.class);
-    Method joyGetMethod = joy.getClass().getMethod(joyGetMethodName);
-    Method joyPressedMethod = joy.getClass().getMethod(joyPressedMethodName);
-    Method joyReleasedMethod = joy.getClass().getMethod(joyReleasedMethodName);
+    final Method simSetMethod = joysim.getClass().getMethod(simSetMethodName, boolean.class);
+    final Method joyGetMethod = joy.getClass().getMethod(joyGetMethodName);
+    final Method joyPressedMethod = joy.getClass().getMethod(joyPressedMethodName);
+    final Method joyReleasedMethod = joy.getClass().getMethod(joyReleasedMethodName);
 
     simSetMethod.invoke(joysim, false);
     joysim.notifyNewData();
@@ -59,7 +58,6 @@
 
   @ParameterizedTest
   @EnumSource(value = XboxController.Axis.class)
-  @SuppressWarnings({"VariableDeclarationUsageDistance"})
   void testAxes(XboxController.Axis axis)
       throws NoSuchMethodException, InvocationTargetException, IllegalAccessException {
     HAL.initialize(500, 0);
diff --git a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/drive/DifferentialDriveTest.java b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/drive/DifferentialDriveTest.java
index afeac0b..4675a7f 100644
--- a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/drive/DifferentialDriveTest.java
+++ b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/drive/DifferentialDriveTest.java
@@ -18,12 +18,12 @@
     assertEquals(1.0, speeds.right, 1e-9);
 
     // Forward left turn
-    speeds = DifferentialDrive.arcadeDriveIK(0.5, -0.5, false);
+    speeds = DifferentialDrive.arcadeDriveIK(0.5, 0.5, false);
     assertEquals(0.0, speeds.left, 1e-9);
     assertEquals(0.5, speeds.right, 1e-9);
 
     // Forward right turn
-    speeds = DifferentialDrive.arcadeDriveIK(0.5, 0.5, false);
+    speeds = DifferentialDrive.arcadeDriveIK(0.5, -0.5, false);
     assertEquals(0.5, speeds.left, 1e-9);
     assertEquals(0.0, speeds.right, 1e-9);
 
@@ -33,32 +33,32 @@
     assertEquals(-1.0, speeds.right, 1e-9);
 
     // Backward left turn
-    speeds = DifferentialDrive.arcadeDriveIK(-0.5, -0.5, false);
+    speeds = DifferentialDrive.arcadeDriveIK(-0.5, 0.5, false);
     assertEquals(-0.5, speeds.left, 1e-9);
     assertEquals(0.0, speeds.right, 1e-9);
 
     // Backward right turn
-    speeds = DifferentialDrive.arcadeDriveIK(-0.5, 0.5, false);
+    speeds = DifferentialDrive.arcadeDriveIK(-0.5, -0.5, false);
     assertEquals(0.0, speeds.left, 1e-9);
     assertEquals(-0.5, speeds.right, 1e-9);
 
     // Left turn (xSpeed with negative sign)
-    speeds = DifferentialDrive.arcadeDriveIK(-0.0, -1.0, false);
+    speeds = DifferentialDrive.arcadeDriveIK(-0.0, 1.0, false);
     assertEquals(-1.0, speeds.left, 1e-9);
     assertEquals(1.0, speeds.right, 1e-9);
 
     // Left turn (xSpeed with positive sign)
-    speeds = DifferentialDrive.arcadeDriveIK(0.0, -1.0, false);
+    speeds = DifferentialDrive.arcadeDriveIK(0.0, 1.0, false);
     assertEquals(-1.0, speeds.left, 1e-9);
     assertEquals(1.0, speeds.right, 1e-9);
 
     // Right turn (xSpeed with negative sign)
-    speeds = DifferentialDrive.arcadeDriveIK(-0.0, 1.0, false);
+    speeds = DifferentialDrive.arcadeDriveIK(-0.0, -1.0, false);
     assertEquals(1.0, speeds.left, 1e-9);
     assertEquals(-1.0, speeds.right, 1e-9);
 
     // Right turn (xSpeed with positive sign)
-    speeds = DifferentialDrive.arcadeDriveIK(0.0, 1.0, false);
+    speeds = DifferentialDrive.arcadeDriveIK(0.0, -1.0, false);
     assertEquals(1.0, speeds.left, 1e-9);
     assertEquals(-1.0, speeds.right, 1e-9);
   }
@@ -71,12 +71,12 @@
     assertEquals(1.0, speeds.right, 1e-9);
 
     // Forward left turn
-    speeds = DifferentialDrive.arcadeDriveIK(0.5, -0.5, true);
+    speeds = DifferentialDrive.arcadeDriveIK(0.5, 0.5, true);
     assertEquals(0.0, speeds.left, 1e-9);
     assertEquals(0.25, speeds.right, 1e-9);
 
     // Forward right turn
-    speeds = DifferentialDrive.arcadeDriveIK(0.5, 0.5, true);
+    speeds = DifferentialDrive.arcadeDriveIK(0.5, -0.5, true);
     assertEquals(0.25, speeds.left, 1e-9);
     assertEquals(0.0, speeds.right, 1e-9);
 
@@ -86,32 +86,32 @@
     assertEquals(-1.0, speeds.right, 1e-9);
 
     // Backward left turn
-    speeds = DifferentialDrive.arcadeDriveIK(-0.5, -0.5, true);
+    speeds = DifferentialDrive.arcadeDriveIK(-0.5, 0.5, true);
     assertEquals(-0.25, speeds.left, 1e-9);
     assertEquals(0.0, speeds.right, 1e-9);
 
     // Backward right turn
-    speeds = DifferentialDrive.arcadeDriveIK(-0.5, 0.5, true);
+    speeds = DifferentialDrive.arcadeDriveIK(-0.5, -0.5, true);
     assertEquals(0.0, speeds.left, 1e-9);
     assertEquals(-0.25, speeds.right, 1e-9);
 
     // Left turn (xSpeed with negative sign)
-    speeds = DifferentialDrive.arcadeDriveIK(-0.0, -1.0, false);
+    speeds = DifferentialDrive.arcadeDriveIK(-0.0, 1.0, false);
     assertEquals(-1.0, speeds.left, 1e-9);
     assertEquals(1.0, speeds.right, 1e-9);
 
     // Left turn (xSpeed with positive sign)
-    speeds = DifferentialDrive.arcadeDriveIK(0.0, -1.0, false);
+    speeds = DifferentialDrive.arcadeDriveIK(0.0, 1.0, false);
     assertEquals(-1.0, speeds.left, 1e-9);
     assertEquals(1.0, speeds.right, 1e-9);
 
     // Right turn (xSpeed with negative sign)
-    speeds = DifferentialDrive.arcadeDriveIK(-0.0, 1.0, false);
+    speeds = DifferentialDrive.arcadeDriveIK(-0.0, -1.0, false);
     assertEquals(1.0, speeds.left, 1e-9);
     assertEquals(-1.0, speeds.right, 1e-9);
 
     // Right turn (xSpeed with positive sign)
-    speeds = DifferentialDrive.arcadeDriveIK(0.0, 1.0, false);
+    speeds = DifferentialDrive.arcadeDriveIK(0.0, -1.0, false);
     assertEquals(1.0, speeds.left, 1e-9);
     assertEquals(-1.0, speeds.right, 1e-9);
   }
@@ -124,12 +124,12 @@
     assertEquals(1.0, speeds.right, 1e-9);
 
     // Forward left turn
-    speeds = DifferentialDrive.curvatureDriveIK(0.5, -0.5, false);
+    speeds = DifferentialDrive.curvatureDriveIK(0.5, 0.5, false);
     assertEquals(0.25, speeds.left, 1e-9);
     assertEquals(0.75, speeds.right, 1e-9);
 
     // Forward right turn
-    speeds = DifferentialDrive.curvatureDriveIK(0.5, 0.5, false);
+    speeds = DifferentialDrive.curvatureDriveIK(0.5, -0.5, false);
     assertEquals(0.75, speeds.left, 1e-9);
     assertEquals(0.25, speeds.right, 1e-9);
 
@@ -139,12 +139,12 @@
     assertEquals(-1.0, speeds.right, 1e-9);
 
     // Backward left turn
-    speeds = DifferentialDrive.curvatureDriveIK(-0.5, -0.5, false);
+    speeds = DifferentialDrive.curvatureDriveIK(-0.5, 0.5, false);
     assertEquals(-0.75, speeds.left, 1e-9);
     assertEquals(-0.25, speeds.right, 1e-9);
 
     // Backward right turn
-    speeds = DifferentialDrive.curvatureDriveIK(-0.5, 0.5, false);
+    speeds = DifferentialDrive.curvatureDriveIK(-0.5, -0.5, false);
     assertEquals(-0.25, speeds.left, 1e-9);
     assertEquals(-0.75, speeds.right, 1e-9);
   }
@@ -157,12 +157,12 @@
     assertEquals(1.0, speeds.right, 1e-9);
 
     // Forward left turn
-    speeds = DifferentialDrive.curvatureDriveIK(0.5, -0.5, true);
+    speeds = DifferentialDrive.curvatureDriveIK(0.5, 0.5, true);
     assertEquals(0.0, speeds.left, 1e-9);
     assertEquals(1.0, speeds.right, 1e-9);
 
     // Forward right turn
-    speeds = DifferentialDrive.curvatureDriveIK(0.5, 0.5, true);
+    speeds = DifferentialDrive.curvatureDriveIK(0.5, -0.5, true);
     assertEquals(1.0, speeds.left, 1e-9);
     assertEquals(0.0, speeds.right, 1e-9);
 
@@ -172,12 +172,12 @@
     assertEquals(-1.0, speeds.right, 1e-9);
 
     // Backward left turn
-    speeds = DifferentialDrive.curvatureDriveIK(-0.5, -0.5, true);
+    speeds = DifferentialDrive.curvatureDriveIK(-0.5, 0.5, true);
     assertEquals(-1.0, speeds.left, 1e-9);
     assertEquals(0.0, speeds.right, 1e-9);
 
     // Backward right turn
-    speeds = DifferentialDrive.curvatureDriveIK(-0.5, 0.5, true);
+    speeds = DifferentialDrive.curvatureDriveIK(-0.5, -0.5, true);
     assertEquals(0.0, speeds.left, 1e-9);
     assertEquals(-1.0, speeds.right, 1e-9);
   }
@@ -261,12 +261,12 @@
     assertEquals(1.0, right.get(), 1e-9);
 
     // Forward left turn
-    drive.arcadeDrive(0.5, -0.5, false);
+    drive.arcadeDrive(0.5, 0.5, false);
     assertEquals(0.0, left.get(), 1e-9);
     assertEquals(0.5, right.get(), 1e-9);
 
     // Forward right turn
-    drive.arcadeDrive(0.5, 0.5, false);
+    drive.arcadeDrive(0.5, -0.5, false);
     assertEquals(0.5, left.get(), 1e-9);
     assertEquals(0.0, right.get(), 1e-9);
 
@@ -276,12 +276,12 @@
     assertEquals(-1.0, right.get(), 1e-9);
 
     // Backward left turn
-    drive.arcadeDrive(-0.5, -0.5, false);
+    drive.arcadeDrive(-0.5, 0.5, false);
     assertEquals(-0.5, left.get(), 1e-9);
     assertEquals(0.0, right.get(), 1e-9);
 
     // Backward right turn
-    drive.arcadeDrive(-0.5, 0.5, false);
+    drive.arcadeDrive(-0.5, -0.5, false);
     assertEquals(0.0, left.get(), 1e-9);
     assertEquals(-0.5, right.get(), 1e-9);
   }
@@ -299,12 +299,12 @@
     assertEquals(1.0, right.get(), 1e-9);
 
     // Forward left turn
-    drive.arcadeDrive(0.5, -0.5, true);
+    drive.arcadeDrive(0.5, 0.5, true);
     assertEquals(0.0, left.get(), 1e-9);
     assertEquals(0.25, right.get(), 1e-9);
 
     // Forward right turn
-    drive.arcadeDrive(0.5, 0.5, true);
+    drive.arcadeDrive(0.5, -0.5, true);
     assertEquals(0.25, left.get(), 1e-9);
     assertEquals(0.0, right.get(), 1e-9);
 
@@ -314,12 +314,12 @@
     assertEquals(-1.0, right.get(), 1e-9);
 
     // Backward left turn
-    drive.arcadeDrive(-0.5, -0.5, true);
+    drive.arcadeDrive(-0.5, 0.5, true);
     assertEquals(-0.25, left.get(), 1e-9);
     assertEquals(0.0, right.get(), 1e-9);
 
     // Backward right turn
-    drive.arcadeDrive(-0.5, 0.5, true);
+    drive.arcadeDrive(-0.5, -0.5, true);
     assertEquals(0.0, left.get(), 1e-9);
     assertEquals(-0.25, right.get(), 1e-9);
   }
@@ -337,12 +337,12 @@
     assertEquals(1.0, right.get(), 1e-9);
 
     // Forward left turn
-    drive.curvatureDrive(0.5, -0.5, false);
+    drive.curvatureDrive(0.5, 0.5, false);
     assertEquals(0.25, left.get(), 1e-9);
     assertEquals(0.75, right.get(), 1e-9);
 
     // Forward right turn
-    drive.curvatureDrive(0.5, 0.5, false);
+    drive.curvatureDrive(0.5, -0.5, false);
     assertEquals(0.75, left.get(), 1e-9);
     assertEquals(0.25, right.get(), 1e-9);
 
@@ -352,12 +352,12 @@
     assertEquals(-1.0, right.get(), 1e-9);
 
     // Backward left turn
-    drive.curvatureDrive(-0.5, -0.5, false);
+    drive.curvatureDrive(-0.5, 0.5, false);
     assertEquals(-0.75, left.get(), 1e-9);
     assertEquals(-0.25, right.get(), 1e-9);
 
     // Backward right turn
-    drive.curvatureDrive(-0.5, 0.5, false);
+    drive.curvatureDrive(-0.5, -0.5, false);
     assertEquals(-0.25, left.get(), 1e-9);
     assertEquals(-0.75, right.get(), 1e-9);
   }
@@ -375,12 +375,12 @@
     assertEquals(1.0, right.get(), 1e-9);
 
     // Forward left turn
-    drive.curvatureDrive(0.5, -0.5, true);
+    drive.curvatureDrive(0.5, 0.5, true);
     assertEquals(0.0, left.get(), 1e-9);
     assertEquals(1.0, right.get(), 1e-9);
 
     // Forward right turn
-    drive.curvatureDrive(0.5, 0.5, true);
+    drive.curvatureDrive(0.5, -0.5, true);
     assertEquals(1.0, left.get(), 1e-9);
     assertEquals(0.0, right.get(), 1e-9);
 
@@ -390,12 +390,12 @@
     assertEquals(-1.0, right.get(), 1e-9);
 
     // Backward left turn
-    drive.curvatureDrive(-0.5, -0.5, true);
+    drive.curvatureDrive(-0.5, 0.5, true);
     assertEquals(-1.0, left.get(), 1e-9);
     assertEquals(0.0, right.get(), 1e-9);
 
     // Backward right turn
-    drive.curvatureDrive(-0.5, 0.5, true);
+    drive.curvatureDrive(-0.5, -0.5, true);
     assertEquals(0.0, left.get(), 1e-9);
     assertEquals(-1.0, right.get(), 1e-9);
   }
diff --git a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/drive/KilloughDriveTest.java b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/drive/KilloughDriveTest.java
deleted file mode 100644
index 99858d9..0000000
--- a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/drive/KilloughDriveTest.java
+++ /dev/null
@@ -1,205 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.drive;
-
-import static org.junit.jupiter.api.Assertions.assertEquals;
-
-import edu.wpi.first.wpilibj.motorcontrol.MockMotorController;
-import org.junit.jupiter.api.Test;
-
-class KilloughDriveTest {
-  @Test
-  void testCartesianIK() {
-    var left = new MockMotorController();
-    var right = new MockMotorController();
-    var back = new MockMotorController();
-    var drive = new KilloughDrive(left, right, back);
-
-    // Forward
-    var speeds = drive.driveCartesianIK(1.0, 0.0, 0.0);
-    assertEquals(0.5, speeds.left, 1e-9);
-    assertEquals(-0.5, speeds.right, 1e-9);
-    assertEquals(0.0, speeds.back, 1e-9);
-
-    // Left
-    speeds = drive.driveCartesianIK(0.0, -1.0, 0.0);
-    assertEquals(-Math.sqrt(3) / 2, speeds.left, 1e-9);
-    assertEquals(-Math.sqrt(3) / 2, speeds.right, 1e-9);
-    assertEquals(1.0, speeds.back, 1e-9);
-
-    // Right
-    speeds = drive.driveCartesianIK(0.0, 1.0, 0.0);
-    assertEquals(Math.sqrt(3) / 2, speeds.left, 1e-9);
-    assertEquals(Math.sqrt(3) / 2, speeds.right, 1e-9);
-    assertEquals(-1.0, speeds.back, 1e-9);
-
-    // Rotate CCW
-    speeds = drive.driveCartesianIK(0.0, 0.0, -1.0);
-    assertEquals(-1.0, speeds.left, 1e-9);
-    assertEquals(-1.0, speeds.right, 1e-9);
-    assertEquals(-1.0, speeds.back, 1e-9);
-
-    // Rotate CW
-    speeds = drive.driveCartesianIK(0.0, 0.0, 1.0);
-    assertEquals(1.0, speeds.left, 1e-9);
-    assertEquals(1.0, speeds.right, 1e-9);
-    assertEquals(1.0, speeds.back, 1e-9);
-  }
-
-  @Test
-  void testCartesianIKGyro90CW() {
-    var left = new MockMotorController();
-    var right = new MockMotorController();
-    var back = new MockMotorController();
-    var drive = new KilloughDrive(left, right, back);
-
-    // Forward in global frame; left in robot frame
-    var speeds = drive.driveCartesianIK(1.0, 0.0, 0.0, 90.0);
-    assertEquals(-Math.sqrt(3) / 2, speeds.left, 1e-9);
-    assertEquals(-Math.sqrt(3) / 2, speeds.right, 1e-9);
-    assertEquals(1.0, speeds.back, 1e-9);
-
-    // Left in global frame; backward in robot frame
-    speeds = drive.driveCartesianIK(0.0, -1.0, 0.0, 90.0);
-    assertEquals(-0.5, speeds.left, 1e-9);
-    assertEquals(0.5, speeds.right, 1e-9);
-    assertEquals(0.0, speeds.back, 1e-9);
-
-    // Right in global frame; forward in robot frame
-    speeds = drive.driveCartesianIK(0.0, 1.0, 0.0, 90.0);
-    assertEquals(0.5, speeds.left, 1e-9);
-    assertEquals(-0.5, speeds.right, 1e-9);
-    assertEquals(0.0, speeds.back, 1e-9);
-
-    // Rotate CCW
-    speeds = drive.driveCartesianIK(0.0, 0.0, -1.0, 90.0);
-    assertEquals(-1.0, speeds.left, 1e-9);
-    assertEquals(-1.0, speeds.right, 1e-9);
-    assertEquals(-1.0, speeds.back, 1e-9);
-
-    // Rotate CW
-    speeds = drive.driveCartesianIK(0.0, 0.0, 1.0, 90.0);
-    assertEquals(1.0, speeds.left, 1e-9);
-    assertEquals(1.0, speeds.right, 1e-9);
-    assertEquals(1.0, speeds.back, 1e-9);
-  }
-
-  @Test
-  void testCartesian() {
-    var left = new MockMotorController();
-    var right = new MockMotorController();
-    var back = new MockMotorController();
-    var drive = new KilloughDrive(left, right, back);
-    drive.setDeadband(0.0);
-
-    // Forward
-    drive.driveCartesian(1.0, 0.0, 0.0);
-    assertEquals(0.5, left.get(), 1e-9);
-    assertEquals(-0.5, right.get(), 1e-9);
-    assertEquals(0.0, back.get(), 1e-9);
-
-    // Left
-    drive.driveCartesian(0.0, -1.0, 0.0);
-    assertEquals(-Math.sqrt(3) / 2, left.get(), 1e-9);
-    assertEquals(-Math.sqrt(3) / 2, right.get(), 1e-9);
-    assertEquals(1.0, back.get(), 1e-9);
-
-    // Right
-    drive.driveCartesian(0.0, 1.0, 0.0);
-    assertEquals(Math.sqrt(3) / 2, left.get(), 1e-9);
-    assertEquals(Math.sqrt(3) / 2, right.get(), 1e-9);
-    assertEquals(-1.0, back.get(), 1e-9);
-
-    // Rotate CCW
-    drive.driveCartesian(0.0, 0.0, -1.0);
-    assertEquals(-1.0, left.get(), 1e-9);
-    assertEquals(-1.0, right.get(), 1e-9);
-    assertEquals(-1.0, back.get(), 1e-9);
-
-    // Rotate CW
-    drive.driveCartesian(0.0, 0.0, 1.0);
-    assertEquals(1.0, left.get(), 1e-9);
-    assertEquals(1.0, right.get(), 1e-9);
-    assertEquals(1.0, back.get(), 1e-9);
-  }
-
-  @Test
-  void testCartesianGyro90CW() {
-    var left = new MockMotorController();
-    var right = new MockMotorController();
-    var back = new MockMotorController();
-    var drive = new KilloughDrive(left, right, back);
-    drive.setDeadband(0.0);
-
-    // Forward in global frame; left in robot frame
-    drive.driveCartesian(1.0, 0.0, 0.0, 90.0);
-    assertEquals(-Math.sqrt(3) / 2, left.get(), 1e-9);
-    assertEquals(-Math.sqrt(3) / 2, right.get(), 1e-9);
-    assertEquals(1.0, back.get(), 1e-9);
-
-    // Left in global frame; backward in robot frame
-    drive.driveCartesian(0.0, -1.0, 0.0, 90.0);
-    assertEquals(-0.5, left.get(), 1e-9);
-    assertEquals(0.5, right.get(), 1e-9);
-    assertEquals(0.0, back.get(), 1e-9);
-
-    // Right in global frame; forward in robot frame
-    drive.driveCartesian(0.0, 1.0, 0.0, 90.0);
-    assertEquals(0.5, left.get(), 1e-9);
-    assertEquals(-0.5, right.get(), 1e-9);
-    assertEquals(0.0, back.get(), 1e-9);
-
-    // Rotate CCW
-    drive.driveCartesian(0.0, 0.0, -1.0, 90.0);
-    assertEquals(-1.0, left.get(), 1e-9);
-    assertEquals(-1.0, right.get(), 1e-9);
-    assertEquals(-1.0, back.get(), 1e-9);
-
-    // Rotate CW
-    drive.driveCartesian(0.0, 0.0, 1.0, 90.0);
-    assertEquals(1.0, left.get(), 1e-9);
-    assertEquals(1.0, right.get(), 1e-9);
-    assertEquals(1.0, back.get(), 1e-9);
-  }
-
-  @Test
-  void testPolar() {
-    var left = new MockMotorController();
-    var right = new MockMotorController();
-    var back = new MockMotorController();
-    var drive = new KilloughDrive(left, right, back);
-    drive.setDeadband(0.0);
-
-    // Forward
-    drive.drivePolar(1.0, 0.0, 0.0);
-    assertEquals(Math.sqrt(3) / 2, left.get(), 1e-9);
-    assertEquals(Math.sqrt(3) / 2, right.get(), 1e-9);
-    assertEquals(-1.0, back.get(), 1e-9);
-
-    // Left
-    drive.drivePolar(1.0, -90.0, 0.0);
-    assertEquals(-0.5, left.get(), 1e-9);
-    assertEquals(0.5, right.get(), 1e-9);
-    assertEquals(0.0, back.get(), 1e-9);
-
-    // Right
-    drive.drivePolar(1.0, 90.0, 0.0);
-    assertEquals(0.5, left.get(), 1e-9);
-    assertEquals(-0.5, right.get(), 1e-9);
-    assertEquals(0.0, back.get(), 1e-9);
-
-    // Rotate CCW
-    drive.drivePolar(0.0, 0.0, -1.0);
-    assertEquals(-1.0, left.get(), 1e-9);
-    assertEquals(-1.0, right.get(), 1e-9);
-    assertEquals(-1.0, back.get(), 1e-9);
-
-    // Rotate CW
-    drive.drivePolar(0.0, 0.0, 1.0);
-    assertEquals(1.0, left.get(), 1e-9);
-    assertEquals(1.0, right.get(), 1e-9);
-    assertEquals(1.0, back.get(), 1e-9);
-  }
-}
diff --git a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/drive/MecanumDriveTest.java b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/drive/MecanumDriveTest.java
index bf3349c..034ba10 100644
--- a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/drive/MecanumDriveTest.java
+++ b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/drive/MecanumDriveTest.java
@@ -6,6 +6,7 @@
 
 import static org.junit.jupiter.api.Assertions.assertEquals;
 
+import edu.wpi.first.math.geometry.Rotation2d;
 import edu.wpi.first.wpilibj.motorcontrol.MockMotorController;
 import org.junit.jupiter.api.Test;
 
@@ -51,35 +52,35 @@
   @Test
   void testCartesianIKGyro90CW() {
     // Forward in global frame; left in robot frame
-    var speeds = MecanumDrive.driveCartesianIK(1.0, 0.0, 0.0, 90.0);
+    var speeds = MecanumDrive.driveCartesianIK(1.0, 0.0, 0.0, Rotation2d.fromDegrees(90.0));
     assertEquals(-1.0, speeds.frontLeft, 1e-9);
     assertEquals(1.0, speeds.frontRight, 1e-9);
     assertEquals(1.0, speeds.rearLeft, 1e-9);
     assertEquals(-1.0, speeds.rearRight, 1e-9);
 
     // Left in global frame; backward in robot frame
-    speeds = MecanumDrive.driveCartesianIK(0.0, -1.0, 0.0, 90.0);
+    speeds = MecanumDrive.driveCartesianIK(0.0, -1.0, 0.0, Rotation2d.fromDegrees(90.0));
     assertEquals(-1.0, speeds.frontLeft, 1e-9);
     assertEquals(-1.0, speeds.frontRight, 1e-9);
     assertEquals(-1.0, speeds.rearLeft, 1e-9);
     assertEquals(-1.0, speeds.rearRight, 1e-9);
 
     // Right in global frame; forward in robot frame
-    speeds = MecanumDrive.driveCartesianIK(0.0, 1.0, 0.0, 90.0);
+    speeds = MecanumDrive.driveCartesianIK(0.0, 1.0, 0.0, Rotation2d.fromDegrees(90.0));
     assertEquals(1.0, speeds.frontLeft, 1e-9);
     assertEquals(1.0, speeds.frontRight, 1e-9);
     assertEquals(1.0, speeds.rearLeft, 1e-9);
     assertEquals(1.0, speeds.rearRight, 1e-9);
 
     // Rotate CCW
-    speeds = MecanumDrive.driveCartesianIK(0.0, 0.0, -1.0, 90.0);
+    speeds = MecanumDrive.driveCartesianIK(0.0, 0.0, -1.0, Rotation2d.fromDegrees(90.0));
     assertEquals(-1.0, speeds.frontLeft, 1e-9);
     assertEquals(1.0, speeds.frontRight, 1e-9);
     assertEquals(-1.0, speeds.rearLeft, 1e-9);
     assertEquals(1.0, speeds.rearRight, 1e-9);
 
     // Rotate CW
-    speeds = MecanumDrive.driveCartesianIK(0.0, 0.0, 1.0, 90.0);
+    speeds = MecanumDrive.driveCartesianIK(0.0, 0.0, 1.0, Rotation2d.fromDegrees(90.0));
     assertEquals(1.0, speeds.frontLeft, 1e-9);
     assertEquals(-1.0, speeds.frontRight, 1e-9);
     assertEquals(1.0, speeds.rearLeft, 1e-9);
@@ -141,35 +142,35 @@
     drive.setDeadband(0.0);
 
     // Forward in global frame; left in robot frame
-    drive.driveCartesian(1.0, 0.0, 0.0, 90.0);
+    drive.driveCartesian(1.0, 0.0, 0.0, Rotation2d.fromDegrees(90.0));
     assertEquals(-1.0, fl.get(), 1e-9);
     assertEquals(1.0, fr.get(), 1e-9);
     assertEquals(1.0, rl.get(), 1e-9);
     assertEquals(-1.0, rr.get(), 1e-9);
 
     // Left in global frame; backward in robot frame
-    drive.driveCartesian(0.0, -1.0, 0.0, 90.0);
+    drive.driveCartesian(0.0, -1.0, 0.0, Rotation2d.fromDegrees(90.0));
     assertEquals(-1.0, fl.get(), 1e-9);
     assertEquals(-1.0, fr.get(), 1e-9);
     assertEquals(-1.0, rl.get(), 1e-9);
     assertEquals(-1.0, rr.get(), 1e-9);
 
     // Right in global frame; forward in robot frame
-    drive.driveCartesian(0.0, 1.0, 0.0, 90.0);
+    drive.driveCartesian(0.0, 1.0, 0.0, Rotation2d.fromDegrees(90.0));
     assertEquals(1.0, fl.get(), 1e-9);
     assertEquals(1.0, fr.get(), 1e-9);
     assertEquals(1.0, rl.get(), 1e-9);
     assertEquals(1.0, rr.get(), 1e-9);
 
     // Rotate CCW
-    drive.driveCartesian(0.0, 0.0, -1.0, 90.0);
+    drive.driveCartesian(0.0, 0.0, -1.0, Rotation2d.fromDegrees(90.0));
     assertEquals(-1.0, fl.get(), 1e-9);
     assertEquals(1.0, fr.get(), 1e-9);
     assertEquals(-1.0, rl.get(), 1e-9);
     assertEquals(1.0, rr.get(), 1e-9);
 
     // Rotate CW
-    drive.driveCartesian(0.0, 0.0, 1.0, 90.0);
+    drive.driveCartesian(0.0, 0.0, 1.0, Rotation2d.fromDegrees(90.0));
     assertEquals(1.0, fl.get(), 1e-9);
     assertEquals(-1.0, fr.get(), 1e-9);
     assertEquals(1.0, rl.get(), 1e-9);
@@ -186,35 +187,35 @@
     drive.setDeadband(0.0);
 
     // Forward
-    drive.drivePolar(1.0, 0.0, 0.0);
+    drive.drivePolar(1.0, Rotation2d.fromDegrees(0.0), 0.0);
     assertEquals(1.0, fl.get(), 1e-9);
     assertEquals(1.0, fr.get(), 1e-9);
     assertEquals(1.0, rl.get(), 1e-9);
     assertEquals(1.0, rr.get(), 1e-9);
 
     // Left
-    drive.drivePolar(1.0, -90.0, 0.0);
+    drive.drivePolar(1.0, Rotation2d.fromDegrees(-90.0), 0.0);
     assertEquals(-1.0, fl.get(), 1e-9);
     assertEquals(1.0, fr.get(), 1e-9);
     assertEquals(1.0, rl.get(), 1e-9);
     assertEquals(-1.0, rr.get(), 1e-9);
 
     // Right
-    drive.drivePolar(1.0, 90.0, 0.0);
+    drive.drivePolar(1.0, Rotation2d.fromDegrees(90.0), 0.0);
     assertEquals(1.0, fl.get(), 1e-9);
     assertEquals(-1.0, fr.get(), 1e-9);
     assertEquals(-1.0, rl.get(), 1e-9);
     assertEquals(1.0, rr.get(), 1e-9);
 
     // Rotate CCW
-    drive.drivePolar(0.0, 0.0, -1.0);
+    drive.drivePolar(0.0, Rotation2d.fromDegrees(0.0), -1.0);
     assertEquals(-1.0, fl.get(), 1e-9);
     assertEquals(1.0, fr.get(), 1e-9);
     assertEquals(-1.0, rl.get(), 1e-9);
     assertEquals(1.0, rr.get(), 1e-9);
 
     // Rotate CW
-    drive.drivePolar(0.0, 0.0, 1.0);
+    drive.drivePolar(0.0, Rotation2d.fromDegrees(0.0), 1.0);
     assertEquals(1.0, fl.get(), 1e-9);
     assertEquals(-1.0, fr.get(), 1e-9);
     assertEquals(1.0, rl.get(), 1e-9);
diff --git a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/event/BooleanEventTest.java b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/event/BooleanEventTest.java
new file mode 100644
index 0000000..59caf23
--- /dev/null
+++ b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/event/BooleanEventTest.java
@@ -0,0 +1,168 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj.event;
+
+import static org.junit.jupiter.api.Assertions.assertEquals;
+
+import java.util.concurrent.atomic.AtomicBoolean;
+import java.util.concurrent.atomic.AtomicInteger;
+import org.junit.jupiter.api.Test;
+
+class BooleanEventTest {
+  @Test
+  void testBinaryCompositions() {
+    var loop = new EventLoop();
+
+    var andCounter = new AtomicInteger(0);
+    var orCounter = new AtomicInteger(0);
+
+    assertEquals(0, andCounter.get());
+    assertEquals(0, orCounter.get());
+
+    new BooleanEvent(loop, () -> true).and(() -> false).ifHigh(andCounter::incrementAndGet);
+    new BooleanEvent(loop, () -> true).or(() -> false).ifHigh(orCounter::incrementAndGet);
+
+    loop.poll();
+
+    assertEquals(0, andCounter.get());
+    assertEquals(1, orCounter.get());
+  }
+
+  @Test
+  void testBinaryCompositionLoopSemantics() {
+    var loop1 = new EventLoop();
+    var loop2 = new EventLoop();
+
+    var counter1 = new AtomicInteger(0);
+    var counter2 = new AtomicInteger(0);
+
+    new BooleanEvent(loop1, () -> true)
+        .and(new BooleanEvent(loop2, () -> true))
+        .ifHigh(counter1::incrementAndGet);
+
+    new BooleanEvent(loop2, () -> true)
+        .and(new BooleanEvent(loop1, () -> true))
+        .ifHigh(counter2::incrementAndGet);
+
+    assertEquals(0, counter1.get());
+    assertEquals(0, counter2.get());
+
+    loop1.poll();
+
+    assertEquals(1, counter1.get());
+    assertEquals(0, counter2.get());
+
+    loop2.poll();
+
+    assertEquals(1, counter1.get());
+    assertEquals(1, counter2.get());
+  }
+
+  @Test
+  void testEdgeDecorators() {
+    var bool = new AtomicBoolean(false);
+    var counter = new AtomicInteger(0);
+
+    var loop = new EventLoop();
+
+    new BooleanEvent(loop, bool::get).falling().ifHigh(counter::decrementAndGet);
+    new BooleanEvent(loop, bool::get).rising().ifHigh(counter::incrementAndGet);
+
+    assertEquals(0, counter.get());
+
+    bool.set(false);
+    loop.poll();
+
+    assertEquals(0, counter.get());
+
+    bool.set(true);
+    loop.poll();
+
+    assertEquals(1, counter.get());
+
+    bool.set(true);
+    loop.poll();
+
+    assertEquals(1, counter.get());
+
+    bool.set(false);
+    loop.poll();
+
+    assertEquals(0, counter.get());
+  }
+
+  @Test
+  void testEdgeReuse() {
+    var loop = new EventLoop();
+    var bool = new AtomicBoolean(false);
+    var counter = new AtomicInteger(0);
+
+    var event = new BooleanEvent(loop, bool::get).rising();
+    event.ifHigh(counter::incrementAndGet);
+    event.ifHigh(counter::incrementAndGet);
+
+    assertEquals(0, counter.get());
+
+    loop.poll();
+
+    assertEquals(0, counter.get());
+
+    bool.set(true);
+    loop.poll();
+
+    assertEquals(1, counter.get()); // FIXME?: natural sense dictates counter == 2!!
+
+    loop.poll();
+
+    assertEquals(1, counter.get());
+
+    bool.set(false);
+    loop.poll();
+
+    assertEquals(1, counter.get());
+
+    bool.set(true);
+    loop.poll();
+
+    assertEquals(2, counter.get());
+  }
+
+  @Test
+  void testEdgeReconstruct() {
+    var loop = new EventLoop();
+    var bool = new AtomicBoolean(false);
+    var counter = new AtomicInteger(0);
+
+    var event = new BooleanEvent(loop, bool::get);
+    event.rising().ifHigh(counter::incrementAndGet);
+    event.rising().ifHigh(counter::incrementAndGet);
+
+    assertEquals(0, counter.get());
+
+    loop.poll();
+
+    assertEquals(0, counter.get());
+
+    bool.set(true);
+    loop.poll();
+
+    // unlike the previous test ...
+    assertEquals(2, counter.get()); // as natural sense dictates, counter == 2
+
+    loop.poll();
+
+    assertEquals(2, counter.get());
+
+    bool.set(false);
+    loop.poll();
+
+    assertEquals(2, counter.get());
+
+    bool.set(true);
+    loop.poll();
+
+    assertEquals(4, counter.get());
+  }
+}
diff --git a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/event/EventLoopTest.java b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/event/EventLoopTest.java
new file mode 100644
index 0000000..ea3c569
--- /dev/null
+++ b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/event/EventLoopTest.java
@@ -0,0 +1,61 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj.event;
+
+import static org.junit.jupiter.api.Assertions.assertEquals;
+
+import java.util.concurrent.atomic.AtomicBoolean;
+import java.util.concurrent.atomic.AtomicInteger;
+import org.junit.jupiter.api.Test;
+
+class EventLoopTest {
+  @Test
+  void testConditions() {
+    var counterTrue = new AtomicInteger(0);
+    var counterFalse = new AtomicInteger(0);
+    var loop = new EventLoop();
+    new BooleanEvent(loop, () -> true).ifHigh(counterTrue::incrementAndGet);
+    new BooleanEvent(loop, () -> false).ifHigh(counterFalse::incrementAndGet);
+
+    assertEquals(0, counterTrue.get());
+    assertEquals(0, counterFalse.get());
+
+    loop.poll();
+
+    assertEquals(1, counterTrue.get());
+    assertEquals(0, counterFalse.get());
+
+    loop.poll();
+
+    assertEquals(2, counterTrue.get());
+    assertEquals(0, counterFalse.get());
+  }
+
+  @Test
+  void testClear() {
+    var condition = new AtomicBoolean(false);
+    var counter = new AtomicInteger(0);
+    var loop = new EventLoop();
+
+    // first ensure binding works
+    new BooleanEvent(loop, condition::get).ifHigh(counter::incrementAndGet);
+
+    condition.set(false);
+    loop.poll();
+    assertEquals(0, counter.get());
+
+    condition.set(true);
+    loop.poll();
+    assertEquals(1, counter.get());
+
+    // clear bindings
+    loop.clear();
+
+    condition.set(true);
+    loop.poll();
+    // shouldn't change
+    assertEquals(1, counter.get());
+  }
+}
diff --git a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/event/NetworkBooleanEventTest.java b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/event/NetworkBooleanEventTest.java
new file mode 100644
index 0000000..045e05a
--- /dev/null
+++ b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/event/NetworkBooleanEventTest.java
@@ -0,0 +1,47 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj.event;
+
+import static org.junit.jupiter.api.Assertions.assertEquals;
+
+import edu.wpi.first.networktables.NetworkTableInstance;
+import java.util.concurrent.atomic.AtomicInteger;
+import org.junit.jupiter.api.AfterEach;
+import org.junit.jupiter.api.BeforeEach;
+import org.junit.jupiter.api.Test;
+
+class NetworkBooleanEventTest {
+  NetworkTableInstance m_inst;
+
+  @BeforeEach
+  void setup() {
+    m_inst = NetworkTableInstance.create();
+    m_inst.startLocal();
+  }
+
+  @AfterEach
+  void teardown() {
+    m_inst.close();
+  }
+
+  @Test
+  void testNetworkBooleanEvent() {
+    var loop = new EventLoop();
+    var counter = new AtomicInteger(0);
+
+    var pub = m_inst.getTable("TestTable").getBooleanTopic("Test").publish();
+
+    new NetworkBooleanEvent(loop, m_inst, "TestTable", "Test").ifHigh(counter::incrementAndGet);
+    pub.set(false);
+    loop.poll();
+    assertEquals(0, counter.get());
+    pub.set(true);
+    loop.poll();
+    assertEquals(1, counter.get());
+    pub.set(false);
+    loop.poll();
+    assertEquals(1, counter.get());
+  }
+}
diff --git a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/hal/MatchInfoDataTest.java b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/hal/MatchInfoDataTest.java
index 855ace5..b2b22a2 100644
--- a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/hal/MatchInfoDataTest.java
+++ b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/hal/MatchInfoDataTest.java
@@ -7,7 +7,7 @@
 import static org.junit.jupiter.api.Assertions.assertAll;
 import static org.junit.jupiter.api.Assertions.assertEquals;
 
-import edu.wpi.first.hal.HAL;
+import edu.wpi.first.hal.DriverStationJNI;
 import edu.wpi.first.hal.MatchInfoData;
 import edu.wpi.first.hal.simulation.DriverStationDataJNI;
 import edu.wpi.first.wpilibj.DriverStation.MatchType;
@@ -20,7 +20,7 @@
     DriverStationDataJNI.setMatchInfo("Event Name", "Game Message", 174, 191, matchType.ordinal());
 
     MatchInfoData outMatchInfo = new MatchInfoData();
-    HAL.getMatchInfo(outMatchInfo);
+    DriverStationJNI.getMatchInfo(outMatchInfo);
 
     assertAll(
         () -> assertEquals("Event Name", outMatchInfo.eventName),
diff --git a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/SendableCameraWrapperTest.java b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/SendableCameraWrapperTest.java
index 15f0b0b..ed24453 100644
--- a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/SendableCameraWrapperTest.java
+++ b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/SendableCameraWrapperTest.java
@@ -8,20 +8,22 @@
 import static org.junit.jupiter.api.Assertions.assertThrows;
 
 import edu.wpi.first.networktables.NetworkTableInstance;
-import org.junit.jupiter.api.AfterAll;
+import org.junit.jupiter.api.AfterEach;
 import org.junit.jupiter.api.BeforeEach;
 import org.junit.jupiter.api.Test;
 
 class SendableCameraWrapperTest {
+  NetworkTableInstance m_inst;
+
   @BeforeEach
   void setup() {
-    NetworkTableInstance.getDefault().deleteAllEntries();
+    m_inst = NetworkTableInstance.create();
     SendableCameraWrapper.clearWrappers();
   }
 
-  @AfterAll
-  static void tearDown() {
-    NetworkTableInstance.getDefault().deleteAllEntries();
+  @AfterEach
+  void tearDown() {
+    m_inst.close();
   }
 
   @Test
diff --git a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardInstanceTest.java b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardInstanceTest.java
index 5dfad67..53369f1 100644
--- a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardInstanceTest.java
+++ b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardInstanceTest.java
@@ -9,6 +9,7 @@
 import static org.junit.jupiter.api.Assertions.assertFalse;
 import static org.junit.jupiter.api.Assertions.assertTrue;
 
+import edu.wpi.first.networktables.GenericEntry;
 import edu.wpi.first.networktables.NetworkTableEntry;
 import edu.wpi.first.networktables.NetworkTableInstance;
 import org.junit.jupiter.api.AfterEach;
@@ -32,7 +33,7 @@
 
   @Test
   void testPathFluent() {
-    NetworkTableEntry entry =
+    GenericEntry entry =
         m_shuffleboardInstance
             .getTab("Tab Title")
             .getLayout("Layout Title", "List Layout")
@@ -45,13 +46,13 @@
         () ->
             assertEquals(
                 "/Shuffleboard/Tab Title/Layout Title/Data",
-                entry.getName(),
+                entry.getTopic().getName(),
                 "Entry path generated incorrectly"));
   }
 
   @Test
   void testNestedLayoutsFluent() {
-    NetworkTableEntry entry =
+    GenericEntry entry =
         m_shuffleboardInstance
             .getTab("Tab")
             .getLayout("First", "List")
@@ -66,7 +67,7 @@
         () ->
             assertEquals(
                 "/Shuffleboard/Tab/First/Second/Third/Fourth/Value",
-                entry.getName(),
+                entry.getTopic().getName(),
                 "Entry path generated incorrectly"));
   }
 
@@ -78,14 +79,14 @@
     ShuffleboardLayout third = second.getLayout("Third", "List");
     ShuffleboardLayout fourth = third.getLayout("Fourth", "List");
     SimpleWidget widget = fourth.add("Value", "string");
-    NetworkTableEntry entry = widget.getEntry();
+    GenericEntry entry = widget.getEntry();
 
     assertAll(
         () -> assertEquals("string", entry.getString(null), "Wrong entry value"),
         () ->
             assertEquals(
                 "/Shuffleboard/Tab/First/Second/Third/Fourth/Value",
-                entry.getName(),
+                entry.getTopic().getName(),
                 "Entry path generated incorrectly"));
   }
 
diff --git a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/SuppliedValueWidgetTest.java b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/SuppliedValueWidgetTest.java
index 036c73d..794d155 100644
--- a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/SuppliedValueWidgetTest.java
+++ b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/SuppliedValueWidgetTest.java
@@ -12,6 +12,7 @@
 import edu.wpi.first.networktables.NetworkTableEntry;
 import edu.wpi.first.networktables.NetworkTableInstance;
 import java.util.concurrent.atomic.AtomicInteger;
+import org.junit.jupiter.api.AfterEach;
 import org.junit.jupiter.api.BeforeEach;
 import org.junit.jupiter.api.Test;
 
@@ -25,6 +26,11 @@
     m_instance = new ShuffleboardInstance(m_ntInstance);
   }
 
+  @AfterEach
+  void tearDown() {
+    m_ntInstance.close();
+  }
+
   @Test
   void testAddString() {
     AtomicInteger count = new AtomicInteger(0);
diff --git a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/CTREPCMSimTest.java b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/CTREPCMSimTest.java
index ee747bc..f58f7c7 100644
--- a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/CTREPCMSimTest.java
+++ b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/CTREPCMSimTest.java
@@ -18,7 +18,6 @@
 import edu.wpi.first.wpilibj.simulation.testutils.DoubleCallback;
 import org.junit.jupiter.api.Test;
 
-@SuppressWarnings("AbbreviationAsWordInName")
 class CTREPCMSimTest {
   @Test
   void testInitialization() {
diff --git a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/DriverStationSimTest.java b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/DriverStationSimTest.java
index fb0a058..32cae28 100644
--- a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/DriverStationSimTest.java
+++ b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/DriverStationSimTest.java
@@ -37,7 +37,7 @@
   }
 
   @Test
-  void testAutonomus() {
+  void testAutonomous() {
     HAL.initialize(500, 0);
     DriverStationSim.resetData();
 
@@ -137,6 +137,7 @@
       // B1
       allianceStation = AllianceStationID.Blue1;
       DriverStationSim.setAllianceStationId(allianceStation);
+      DriverStationSim.notifyNewData();
       assertEquals(allianceStation, DriverStationSim.getAllianceStationId());
       assertEquals(DriverStation.Alliance.Blue, DriverStation.getAlliance());
       assertEquals(1, DriverStation.getLocation());
@@ -146,6 +147,7 @@
       // B2
       allianceStation = AllianceStationID.Blue2;
       DriverStationSim.setAllianceStationId(allianceStation);
+      DriverStationSim.notifyNewData();
       assertEquals(allianceStation, DriverStationSim.getAllianceStationId());
       assertEquals(DriverStation.Alliance.Blue, DriverStation.getAlliance());
       assertEquals(2, DriverStation.getLocation());
@@ -155,6 +157,7 @@
       // B3
       allianceStation = AllianceStationID.Blue3;
       DriverStationSim.setAllianceStationId(allianceStation);
+      DriverStationSim.notifyNewData();
       assertEquals(allianceStation, DriverStationSim.getAllianceStationId());
       assertEquals(DriverStation.Alliance.Blue, DriverStation.getAlliance());
       assertEquals(3, DriverStation.getLocation());
@@ -164,6 +167,7 @@
       // R1
       allianceStation = AllianceStationID.Red1;
       DriverStationSim.setAllianceStationId(allianceStation);
+      DriverStationSim.notifyNewData();
       assertEquals(allianceStation, DriverStationSim.getAllianceStationId());
       assertEquals(DriverStation.Alliance.Red, DriverStation.getAlliance());
       assertEquals(1, DriverStation.getLocation());
@@ -173,6 +177,7 @@
       // R2
       allianceStation = AllianceStationID.Red2;
       DriverStationSim.setAllianceStationId(allianceStation);
+      DriverStationSim.notifyNewData();
       assertEquals(allianceStation, DriverStationSim.getAllianceStationId());
       assertEquals(DriverStation.Alliance.Red, DriverStation.getAlliance());
       assertEquals(2, DriverStation.getLocation());
@@ -182,6 +187,7 @@
       // R3
       allianceStation = AllianceStationID.Red3;
       DriverStationSim.setAllianceStationId(allianceStation);
+      DriverStationSim.notifyNewData();
       assertEquals(allianceStation, DriverStationSim.getAllianceStationId());
       assertEquals(DriverStation.Alliance.Red, DriverStation.getAlliance());
       assertEquals(3, DriverStation.getLocation());
@@ -230,6 +236,7 @@
     try (CallbackStore cb = DriverStationSim.registerMatchTimeCallback(callback, false)) {
       final double testTime = 19.174;
       DriverStationSim.setMatchTime(testTime);
+      DriverStationSim.notifyNewData();
       assertEquals(testTime, DriverStationSim.getMatchTime());
       assertEquals(testTime, DriverStation.getMatchTime());
       assertTrue(callback.wasTriggered());
diff --git a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/ElevatorSimTest.java b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/ElevatorSimTest.java
index a2e0ef4..fd2e7ba 100644
--- a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/ElevatorSimTest.java
+++ b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/ElevatorSimTest.java
@@ -19,7 +19,6 @@
 
 class ElevatorSimTest {
   @Test
-  @SuppressWarnings({"LocalVariableName", "resource"})
   void testStateSpaceSimWithElevator() {
     RoboRioSim.resetData();
 
@@ -33,6 +32,7 @@
             0.75 * 25.4 / 1000.0,
             0.0,
             3.0,
+            true,
             VecBuilder.fill(0.01));
 
     try (var motor = new PWMVictorSPX(0);
@@ -62,18 +62,15 @@
 
   @Test
   void testMinMax() {
-    var plant =
-        LinearSystemId.createElevatorSystem(
-            DCMotor.getVex775Pro(4), 8.0, 0.75 * 25.4 / 1000.0, 14.67);
-
     var sim =
         new ElevatorSim(
-            plant,
             DCMotor.getVex775Pro(4),
             14.67,
+            8.0,
             0.75 * 25.4 / 1000.0,
             0.0,
             1.0,
+            true,
             VecBuilder.fill(0.01));
 
     for (int i = 0; i < 100; i++) {
@@ -93,17 +90,21 @@
 
   @Test
   void testStability() {
-    var sim = new ElevatorSim(DCMotor.getVex775Pro(4), 100, 4, Units.inchesToMeters(0.5), 0, 10);
+    var sim =
+        new ElevatorSim(DCMotor.getVex775Pro(4), 100, 4, Units.inchesToMeters(0.5), 0, 10, true);
 
     sim.setState(VecBuilder.fill(0, 0));
     sim.setInput(12);
-    for (int i = 0; i < 50; i++) {
+    for (int i = 0; i < 50; ++i) {
       sim.update(0.02);
     }
 
+    var system =
+        LinearSystemId.createElevatorSystem(
+            DCMotor.getVex775Pro(4), 4, Units.inchesToMeters(0.5), 100);
     assertEquals(
-        sim.m_plant.calculateX(VecBuilder.fill(0, 0), VecBuilder.fill(12), 0.02 * 50.0).get(0, 0),
+        system.calculateX(VecBuilder.fill(0, 0), VecBuilder.fill(12), 0.02 * 50.0).get(0, 0),
         sim.getPositionMeters(),
-        0.1);
+        0.01);
   }
 }
diff --git a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/EncoderSimTest.java b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/EncoderSimTest.java
index 931c0fe..eebabeb 100644
--- a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/EncoderSimTest.java
+++ b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/EncoderSimTest.java
@@ -69,6 +69,7 @@
     }
   }
 
+  @SuppressWarnings("deprecation") // Encoder.getPeriod()
   @Test
   void testPeriod() {
     HAL.initialize(500, 0);
diff --git a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/REVPHSimTest.java b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/REVPHSimTest.java
index a436831..c3c7901 100644
--- a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/REVPHSimTest.java
+++ b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/REVPHSimTest.java
@@ -19,7 +19,6 @@
 import edu.wpi.first.wpilibj.simulation.testutils.EnumCallback;
 import org.junit.jupiter.api.Test;
 
-@SuppressWarnings("AbbreviationAsWordInName")
 class REVPHSimTest {
   @Test
   void testInitialization() {
diff --git a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/RelaySimTest.java b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/RelaySimTest.java
index ba84fc5..3918361 100644
--- a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/RelaySimTest.java
+++ b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/RelaySimTest.java
@@ -18,7 +18,7 @@
 
 class RelaySimTest {
   @Test
-  void testInitializationBidrectional() {
+  void testInitializationBidirectional() {
     HAL.initialize(500, 0);
 
     RelaySim sim = new RelaySim(0);
diff --git a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/RoboRioSimTest.java b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/RoboRioSimTest.java
index c1988b3..9b15b77 100644
--- a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/RoboRioSimTest.java
+++ b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/RoboRioSimTest.java
@@ -208,4 +208,41 @@
       assertEquals(kTestFaults, RobotController.getFaultCount3V3());
     }
   }
+
+  @Test
+  void testSerialNumber() {
+    RoboRioSim.resetData();
+
+    final String kSerialNumber = "Hello";
+
+    RoboRioSim.setSerialNumber(kSerialNumber);
+    assertEquals(kSerialNumber, RoboRioSim.getSerialNumber());
+    assertEquals(kSerialNumber, RobotController.getSerialNumber());
+
+    // Make sure it truncates at 8 characters properly
+    final String kSerialNumberOverflow = "SerialNumber";
+    final String kSerialNumberTruncated = kSerialNumberOverflow.substring(0, 8);
+    RoboRioSim.setSerialNumber(kSerialNumberOverflow);
+    assertEquals(kSerialNumberTruncated, RoboRioSim.getSerialNumber());
+    assertEquals(kSerialNumberTruncated, RobotController.getSerialNumber());
+  }
+
+  @Test
+  void testComments() {
+    RoboRioSim.resetData();
+
+    final String kComments = "Hello! These are comments in the roboRIO web interface!";
+
+    RoboRioSim.setComments(kComments);
+    assertEquals(kComments, RoboRioSim.getComments());
+    assertEquals(kComments, RobotController.getComments());
+
+    final String kCommentsOverflow =
+        "Hello! These are comments in the roboRIO web interface!"
+            + " This comment exceeds 64 characters!";
+    final String kCommentsTruncated = kCommentsOverflow.substring(0, 64);
+    RoboRioSim.setComments(kCommentsOverflow);
+    assertEquals(kCommentsTruncated, RoboRioSim.getComments());
+    assertEquals(kCommentsTruncated, RobotController.getComments());
+  }
 }
diff --git a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/smartdashboard/SmartDashboardTest.java b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/smartdashboard/SmartDashboardTest.java
index dfefddb..9d2b87c 100644
--- a/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/smartdashboard/SmartDashboardTest.java
+++ b/third_party/allwpilib/wpilibj/src/test/java/edu/wpi/first/wpilibj/smartdashboard/SmartDashboardTest.java
@@ -10,11 +10,13 @@
 import edu.wpi.first.networktables.NetworkTable;
 import edu.wpi.first.networktables.NetworkTableInstance;
 import edu.wpi.first.wpilibj.UtilityClassTest;
+import org.junit.jupiter.api.AfterEach;
 import org.junit.jupiter.api.BeforeEach;
 import org.junit.jupiter.api.Test;
 
 class SmartDashboardTest extends UtilityClassTest<SmartDashboard> {
-  private final NetworkTable m_table = NetworkTableInstance.getDefault().getTable("SmartDashboard");
+  private NetworkTableInstance m_inst;
+  private NetworkTable m_table;
 
   SmartDashboardTest() {
     super(SmartDashboard.class);
@@ -22,7 +24,14 @@
 
   @BeforeEach
   void beforeEach() {
-    m_table.getKeys().forEach(m_table::delete);
+    m_inst = NetworkTableInstance.create();
+    m_table = m_inst.getTable("SmartDashboard");
+    SmartDashboard.setNetworkTableInstance(m_inst);
+  }
+
+  @AfterEach
+  void afterEach() {
+    m_inst.close();
   }
 
   @Test
diff --git a/third_party/allwpilib/wpilibj/src/test/resources/edu/wpi/first/wpilibj/PreferencesTestDefault.ini b/third_party/allwpilib/wpilibj/src/test/resources/edu/wpi/first/wpilibj/PreferencesTestDefault.ini
deleted file mode 100644
index f271944..0000000
--- a/third_party/allwpilib/wpilibj/src/test/resources/edu/wpi/first/wpilibj/PreferencesTestDefault.ini
+++ /dev/null
@@ -1,8 +0,0 @@
-[NetworkTables Storage 3.0]
-double "/Preferences/checkedValueInt"=2
-; The omission of a leading zero is intentional for testing purposes
-double "/Preferences/checkedValueDouble"=.2
-double "/Preferences/checkedValueFloat"=3.4
-double "/Preferences/checkedValueLong"=172
-string "/Preferences/checkedValueString"="Hello. How are you?"
-boolean "/Preferences/checkedValueBoolean"=false
diff --git a/third_party/allwpilib/wpilibj/src/test/resources/edu/wpi/first/wpilibj/PreferencesTestDefault.json b/third_party/allwpilib/wpilibj/src/test/resources/edu/wpi/first/wpilibj/PreferencesTestDefault.json
new file mode 100644
index 0000000..0d02b57
--- /dev/null
+++ b/third_party/allwpilib/wpilibj/src/test/resources/edu/wpi/first/wpilibj/PreferencesTestDefault.json
@@ -0,0 +1,50 @@
+[
+  {
+    "name": "/Preferences/checkedValueInt",
+    "type": "int",
+    "value": 2,
+    "properties": {
+      "persistent": true
+    }
+  },
+  {
+    "name": "/Preferences/checkedValueDouble",
+    "type": "double",
+    "value": 0.2,
+    "properties": {
+      "persistent": true
+    }
+  },
+  {
+    "name": "/Preferences/checkedValueFloat",
+    "type": "float",
+    "value": 3.4,
+    "properties": {
+      "persistent": true
+    }
+  },
+  {
+    "name": "/Preferences/checkedValueLong",
+    "type": "int",
+    "value": 172,
+    "properties": {
+      "persistent": true
+    }
+  },
+  {
+    "name": "/Preferences/checkedValueString",
+    "type": "string",
+    "value": "Hello. How are you?",
+    "properties": {
+      "persistent": true
+    }
+  },
+  {
+    "name": "/Preferences/checkedValueBoolean",
+    "type": "boolean",
+    "value": false,
+    "properties": {
+      "persistent": true
+    }
+  }
+]
diff --git a/third_party/allwpilib/wpilibjExamples/build.gradle b/third_party/allwpilib/wpilibjExamples/build.gradle
index 7d74e80..deb8af1 100644
--- a/third_party/allwpilib/wpilibjExamples/build.gradle
+++ b/third_party/allwpilib/wpilibjExamples/build.gradle
@@ -21,20 +21,20 @@
     finalizedBy jacocoTestReport
 }
 
-if (project.hasProperty('onlylinuxathena') || project.hasProperty('onlylinuxraspbian') || project.hasProperty('onlylinuxaarch64bionic')) {
+if (project.hasProperty('onlylinuxathena') || project.hasProperty('onlylinuxarm32') || project.hasProperty('onlylinuxarm64')) {
     test.enabled = false
 }
 
 dependencies {
     implementation project(':wpilibj')
-
+    implementation project(':apriltag')
     implementation project(':wpimath')
     implementation project(':hal')
     implementation project(':wpiutil')
+    implementation project(':wpinet')
     implementation project(':ntcore')
     implementation project(':cscore')
     implementation project(':cameraserver')
-    implementation project(':wpilibOldCommands')
     implementation project(':wpilibNewCommands')
 
     testImplementation 'org.junit.jupiter:junit-jupiter-api:5.8.2'
@@ -43,7 +43,7 @@
 }
 
 jacoco {
-    toolVersion = "0.8.7"
+    toolVersion = "0.8.8"
 }
 
 jacocoTestReport {
@@ -108,17 +108,20 @@
             }
             binaries.all { binary ->
                 lib project: ':wpilibNewCommands', library: 'wpilibNewCommands', linkage: 'shared'
+                lib project: ':apriltag', library: 'apriltag', linkage: 'shared'
                 lib project: ':wpilibc', library: 'wpilibc', linkage: 'shared'
                 lib project: ':wpimath', library: 'wpimath', linkage: 'shared'
-                lib project: ':wpimath', library: 'wpimathJNI', linkage: 'shared'
-                lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
+                lib project: ':wpimath', library: 'wpimathJNIShared', linkage: 'shared'
+                project(':ntcore').addNtcoreDependency(binary, 'shared')
+                project(':ntcore').addNtcoreJniDependency(binary)
                 lib project: ':cscore', library: 'cscore', linkage: 'shared'
-                lib project: ':ntcore', library: 'ntcoreJNIShared', linkage: 'shared'
                 lib project: ':cscore', library: 'cscoreJNIShared', linkage: 'shared'
                 project(':hal').addHalDependency(binary, 'shared')
                 project(':hal').addHalJniDependency(binary)
                 lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
-                lib project: ':wpiutil', library: 'wpiutilJNI', linkage: 'shared'
+                lib project: ':wpiutil', library: 'wpiutilJNIShared', linkage: 'shared'
+                lib project: ':wpinet', library: 'wpinet', linkage: 'shared'
+                lib project: ':wpinet', library: 'wpinetJNIShared', linkage: 'shared'
                 lib project: ':cameraserver', library: 'cameraserver', linkage: 'shared'
                 if (binary.targetPlatform.name == nativeUtils.wpi.platforms.roborio) {
                     nativeUtils.useRequiredLibrary(binary, 'ni_link_libraries', 'ni_runtime_libraries')
@@ -172,8 +175,9 @@
 
                             new groovy.json.JsonSlurper().parseText(exampleFile.text).each { entry ->
                                 project.tasks.create("run${entry.foldername}", JavaExec) { run ->
-                                    mainClass = "edu.wpi.first.wpilibj.examples." + entry.foldername + ".Main"
-                                    classpath = sourceSets.main.runtimeClasspath
+                                    run.group "run examples"
+                                    run.mainClass = "edu.wpi.first.wpilibj.examples." + entry.foldername + "." + entry.mainclass
+                                    run.classpath = sourceSets.main.runtimeClasspath
                                     run.dependsOn it.tasks.install
                                     run.systemProperty 'java.library.path', filePath
                                     run.environment 'LD_LIBRARY_PATH', filePath
@@ -184,6 +188,25 @@
                                         run.jvmArgs = ['-XstartOnFirstThread']
                                     }
                                 }
+                                project.tasks.create("test${entry.foldername}", Test) { testTask ->
+                                    testTask.group "verification"
+                                    testTask.useJUnitPlatform()
+                                    testTask.filter {
+                                        includeTestsMatching("edu.wpi.first.wpilibj.examples.${entry.foldername}.*")
+                                        setFailOnNoMatchingTests(false)
+                                    }
+                                    testTask.classpath = sourceSets.test.runtimeClasspath
+                                    testTask.dependsOn it.tasks.install
+
+                                    testTask.systemProperty 'junit.jupiter.extensions.autodetection.enabled', 'true'
+                                    testTask.testLogging {
+                                        events "failed"
+                                        exceptionFormat "full"
+                                    }
+                                    testTask.systemProperty 'java.library.path', filePath
+                                    testTask.environment 'LD_LIBRARY_PATH', filePath
+                                    testTask.workingDir filePath
+                                }
                             }
 
                             found = true
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/command/ReplaceMeCommand.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/command/ReplaceMeCommand.java
deleted file mode 100644
index 5ca1ca1..0000000
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/command/ReplaceMeCommand.java
+++ /dev/null
@@ -1,37 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.commands.command;
-
-import edu.wpi.first.wpilibj.command.Command;
-
-public class ReplaceMeCommand extends Command {
-  public ReplaceMeCommand() {
-    // Use requires() here to declare subsystem dependencies
-    // eg. requires(chassis);
-  }
-
-  // Called just before this Command runs the first time
-  @Override
-  protected void initialize() {}
-
-  // Called repeatedly when this Command is scheduled to run
-  @Override
-  protected void execute() {}
-
-  // Make this return true when this Command no longer needs to run execute()
-  @Override
-  protected boolean isFinished() {
-    return false;
-  }
-
-  // Called once after isFinished returns true
-  @Override
-  protected void end() {}
-
-  // Called when another command which requires one or more of the same
-  // subsystems is scheduled to run
-  @Override
-  protected void interrupted() {}
-}
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/commandgroup/ReplaceMeCommandGroup.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/commandgroup/ReplaceMeCommandGroup.java
deleted file mode 100644
index ba8e273..0000000
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/commandgroup/ReplaceMeCommandGroup.java
+++ /dev/null
@@ -1,29 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.commands.commandgroup;
-
-import edu.wpi.first.wpilibj.command.CommandGroup;
-
-public class ReplaceMeCommandGroup extends CommandGroup {
-  /** Add your docs here. */
-  public ReplaceMeCommandGroup() {
-    // Add Commands here:
-    // e.g. addSequential(new Command1());
-    // addSequential(new Command2());
-    // these will run in order.
-
-    // To run multiple commands at the same time,
-    // use addParallel()
-    // e.g. addParallel(new Command1());
-    // addSequential(new Command2());
-    // Command1 and Command2 will run in parallel.
-
-    // A command group will require all of the subsystems that each member
-    // would require.
-    // e.g. if Command1 requires chassis, and Command2 requires arm,
-    // a CommandGroup containing them would require both the chassis and the
-    // arm.
-  }
-}
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/commands.json b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/commands.json
index 8165a3c..f6f2c37 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/commands.json
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/commands.json
@@ -10,78 +10,7 @@
     "commandversion": 0
   },
   {
-    "name": "Command (Old)",
-    "description": "Create a base command",
-    "tags": [
-      "command"
-    ],
-    "foldername": "command",
-    "replacename": "ReplaceMeCommand",
-    "commandversion": 1
-  },
-  {
-    "name": "Command Group (Old)",
-    "description": "Create a command group",
-    "tags": [
-      "commandgroup"
-    ],
-    "foldername": "commandgroup",
-    "replacename": "ReplaceMeCommandGroup",
-    "commandversion": 1
-  },
-  {
-    "name": "Instant Command (Old)",
-    "description": "A command that runs immediately",
-    "tags": [
-      "instantcommand"
-    ],
-    "foldername": "instant",
-    "replacename": "ReplaceMeInstantCommand",
-    "commandversion": 1
-  },
-  {
-    "name": "Subsystem (Old)",
-    "description": "A subsystem",
-    "tags": [
-      "subsystem"
-    ],
-    "foldername": "subsystem",
-    "replacename": "ReplaceMeSubsystem",
-    "commandversion": 1
-  },
-  {
-    "name": "PID Subsystem (Old)",
-    "description": "A subsystem that runs a PID loop",
-    "tags": [
-      "pidsubsystem",
-      "pid"
-    ],
-    "foldername": "pidsubsystem",
-    "replacename": "ReplaceMePIDSubsystem",
-    "commandversion": 1
-  },
-  {
-    "name": "Timed Command (Old)",
-    "description": "A command that runs for a specified time",
-    "tags": [
-      "timedcommand"
-    ],
-    "foldername": "timed",
-    "replacename": "ReplaceMeTimedCommand",
-    "commandversion": 1
-  },
-  {
-    "name": "Trigger (Old)",
-    "description": "A command that runs off of a trigger",
-    "tags": [
-      "trigger"
-    ],
-    "foldername": "trigger",
-    "replacename": "ReplaceMeTrigger",
-    "commandversion": 1
-  },
-  {
-    "name": "Command (New)",
+    "name": "Command",
     "description": "A command.",
     "tags": [
       "command"
@@ -91,7 +20,7 @@
     "commandversion": 2
   },
   {
-    "name": "InstantCommand (New)",
+    "name": "InstantCommand",
     "description": "A command that finishes instantly.",
     "tags": [
       "instantcommand"
@@ -101,7 +30,7 @@
     "commandversion": 2
   },
   {
-    "name": "ParallelCommandGroup (New)",
+    "name": "ParallelCommandGroup",
     "description": "A command group that runs commands in parallel, ending when all commands have finished.",
     "tags": [
       "parallelcommandgroup"
@@ -111,7 +40,7 @@
     "commandversion": 2
   },
   {
-    "name": "ParallelDeadlineGroup (New)",
+    "name": "ParallelDeadlineGroup",
     "description": "A command group that runs commands in parallel, ending when a specific command has finished.",
     "tags": [
       "paralleldeadlinegroup"
@@ -121,7 +50,7 @@
     "commandversion": 2
   },
   {
-    "name": "ParallelRaceGroup (New)",
+    "name": "ParallelRaceGroup",
     "description": "A command that runs commands in parallel, ending as soon as any command has finished.",
     "tags": [
       "parallelracegroup"
@@ -131,7 +60,7 @@
     "commandversion": 2
   },
   {
-    "name": "PIDCommand (New)",
+    "name": "PIDCommand",
     "description": "A command that runs a PIDController.",
     "tags": [
       "pidcommand"
@@ -141,7 +70,7 @@
     "commandversion": 2
   },
   {
-    "name": "PIDSubsystem (New)",
+    "name": "PIDSubsystem",
     "description": "A subsystem that runs a PIDController.",
     "tags": [
       "pidsubsystem"
@@ -151,7 +80,7 @@
     "commandversion": 2
   },
   {
-    "name": "ProfiledPIDCommand (New)",
+    "name": "ProfiledPIDCommand",
     "description": "A command that runs a ProfiledPIDController.",
     "tags": [
       "profiledpidcommand"
@@ -161,7 +90,7 @@
     "commandversion": 2
   },
   {
-    "name": "ProfiledPIDSubsystem (New)",
+    "name": "ProfiledPIDSubsystem",
     "description": "A subsystem that runs a ProfiledPIDController.",
     "tags": [
       "profiledpidsubsystem"
@@ -171,7 +100,7 @@
     "commandversion": 2
   },
   {
-    "name": "SequentialCommandGroup (New)",
+    "name": "SequentialCommandGroup",
     "description": "A command group that runs commands in sequence.",
     "tags": [
       "sequentialcommandgroup"
@@ -181,7 +110,7 @@
     "commandversion": 2
   },
   {
-    "name": "Subsystem (New)",
+    "name": "Subsystem",
     "description": "A robot subsystem.",
     "tags": [
       "subsystem"
@@ -191,7 +120,7 @@
     "commandversion": 2
   },
   {
-    "name": "TrapezoidProfileCommand (New)",
+    "name": "TrapezoidProfileCommand",
     "description": "A command that executes a trapezoidal motion profile.",
     "tags": [
       "trapezoidprofilecommand"
@@ -201,7 +130,7 @@
     "commandversion": 2
   },
   {
-    "name": "TrapezoidProfileSubsystem (New)",
+    "name": "TrapezoidProfileSubsystem",
     "description": "A subystem that executes a trapezoidal motion profile.",
     "tags": [
       "trapezoidprofilesubsystem"
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/instant/ReplaceMeInstantCommand.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/instant/ReplaceMeInstantCommand.java
deleted file mode 100644
index 769b595..0000000
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/instant/ReplaceMeInstantCommand.java
+++ /dev/null
@@ -1,21 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.commands.instant;
-
-import edu.wpi.first.wpilibj.command.InstantCommand;
-
-/** Add your docs here. */
-public class ReplaceMeInstantCommand extends InstantCommand {
-  /** Add your docs here. */
-  public ReplaceMeInstantCommand() {
-    super();
-    // Use requires() here to declare subsystem dependencies
-    // eg. requires(chassis);
-  }
-
-  // Called once when the command executes
-  @Override
-  protected void initialize() {}
-}
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/pidsubsystem/ReplaceMePIDSubsystem.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/pidsubsystem/ReplaceMePIDSubsystem.java
deleted file mode 100644
index 01e7987..0000000
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/pidsubsystem/ReplaceMePIDSubsystem.java
+++ /dev/null
@@ -1,40 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.commands.pidsubsystem;
-
-import edu.wpi.first.wpilibj.command.PIDSubsystem;
-
-/** Add your docs here. */
-public class ReplaceMePIDSubsystem extends PIDSubsystem {
-  /** Add your docs here. */
-  public ReplaceMePIDSubsystem() {
-    // Intert a subsystem name and PID values here
-    super("SubsystemName", 1, 2, 3);
-    // Use these to get going:
-    // setSetpoint() - Sets where the PID controller should move the system
-    // to
-    // enable() - Enables the PID controller.
-  }
-
-  @Override
-  public void initDefaultCommand() {
-    // Set the default command for a subsystem here.
-    // setDefaultCommand(new MySpecialCommand());
-  }
-
-  @Override
-  protected double returnPIDInput() {
-    // Return your input value for the PID loop
-    // e.g. a sensor, like a potentiometer:
-    // yourPot.getAverageVoltage() / kYourMaxVoltage;
-    return 0.0;
-  }
-
-  @Override
-  protected void usePIDOutput(double output) {
-    // Use output to drive your system, like a motor
-    // e.g. yourMotor.set(output);
-  }
-}
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/subsystem/ReplaceMeSubsystem.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/subsystem/ReplaceMeSubsystem.java
deleted file mode 100644
index 671daf1..0000000
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/subsystem/ReplaceMeSubsystem.java
+++ /dev/null
@@ -1,19 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.commands.subsystem;
-
-import edu.wpi.first.wpilibj.command.Subsystem;
-
-/** Add your docs here. */
-public class ReplaceMeSubsystem extends Subsystem {
-  // Put methods for controlling this subsystem
-  // here. Call these from Commands.
-
-  @Override
-  public void initDefaultCommand() {
-    // Set the default command for a subsystem here.
-    // setDefaultCommand(new MySpecialCommand());
-  }
-}
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/timed/ReplaceMeTimedCommand.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/timed/ReplaceMeTimedCommand.java
deleted file mode 100644
index 6021382..0000000
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/timed/ReplaceMeTimedCommand.java
+++ /dev/null
@@ -1,34 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.commands.timed;
-
-import edu.wpi.first.wpilibj.command.TimedCommand;
-
-/** Add your docs here. */
-public class ReplaceMeTimedCommand extends TimedCommand {
-  /** Add your docs here. */
-  public ReplaceMeTimedCommand(double timeout) {
-    super(timeout);
-    // Use requires() here to declare subsystem dependencies
-    // eg. requires(chassis);
-  }
-
-  // Called just before this Command runs the first time
-  @Override
-  protected void initialize() {}
-
-  // Called repeatedly when this Command is scheduled to run
-  @Override
-  protected void execute() {}
-
-  // Called once after timeout
-  @Override
-  protected void end() {}
-
-  // Called when another command which requires one or more of the same
-  // subsystems is scheduled to run
-  @Override
-  protected void interrupted() {}
-}
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/trigger/ReplaceMeTrigger.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/trigger/ReplaceMeTrigger.java
deleted file mode 100644
index c1343d9..0000000
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/trigger/ReplaceMeTrigger.java
+++ /dev/null
@@ -1,15 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.commands.trigger;
-
-import edu.wpi.first.wpilibj.buttons.Trigger;
-
-/** Add your docs here. */
-public class ReplaceMeTrigger extends Trigger {
-  @Override
-  public boolean get() {
-    return false;
-  }
-}
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrive/Robot.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrive/Robot.java
index 5eef7e8..45333a5 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrive/Robot.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrive/Robot.java
@@ -32,6 +32,6 @@
     // Drive with arcade drive.
     // That means that the Y axis drives forward
     // and backward, and the X turns left and right.
-    m_robotDrive.arcadeDrive(-m_stick.getY(), m_stick.getX());
+    m_robotDrive.arcadeDrive(-m_stick.getY(), -m_stick.getX());
   }
 }
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrivexboxcontroller/Robot.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrivexboxcontroller/Robot.java
index 656165a..aa0f9a2 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrivexboxcontroller/Robot.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrivexboxcontroller/Robot.java
@@ -32,6 +32,6 @@
     // Drive with split arcade drive.
     // That means that the Y axis of the left stick moves forward
     // and backward, and the X of the right stick turns left and right.
-    m_robotDrive.arcadeDrive(-m_driverController.getLeftY(), m_driverController.getRightX());
+    m_robotDrive.arcadeDrive(-m_driverController.getLeftY(), -m_driverController.getRightX());
   }
 }
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/RobotContainer.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/RobotContainer.java
index 4717d51..1875d64 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/RobotContainer.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/RobotContainer.java
@@ -4,15 +4,13 @@
 
 package edu.wpi.first.wpilibj.examples.armbot;
 
-import static edu.wpi.first.wpilibj.XboxController.Button;
-
 import edu.wpi.first.wpilibj.XboxController;
 import edu.wpi.first.wpilibj.examples.armbot.Constants.OIConstants;
 import edu.wpi.first.wpilibj.examples.armbot.subsystems.ArmSubsystem;
 import edu.wpi.first.wpilibj.examples.armbot.subsystems.DriveSubsystem;
 import edu.wpi.first.wpilibj2.command.Command;
-import edu.wpi.first.wpilibj2.command.InstantCommand;
-import edu.wpi.first.wpilibj2.command.RunCommand;
+import edu.wpi.first.wpilibj2.command.Commands;
+import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
 import edu.wpi.first.wpilibj2.command.button.JoystickButton;
 
 /**
@@ -27,7 +25,8 @@
   private final ArmSubsystem m_robotArm = new ArmSubsystem();
 
   // The driver's controller
-  XboxController m_driverController = new XboxController(OIConstants.kDriverControllerPort);
+  CommandXboxController m_driverController =
+      new CommandXboxController(OIConstants.kDriverControllerPort);
 
   /** The container for the robot. Contains subsystems, OI devices, and commands. */
   public RobotContainer() {
@@ -39,10 +38,10 @@
     m_robotDrive.setDefaultCommand(
         // A split-stick arcade command, with forward/backward controlled by the left
         // hand, and turning controlled by the right.
-        new RunCommand(
+        Commands.run(
             () ->
                 m_robotDrive.arcadeDrive(
-                    -m_driverController.getLeftY(), m_driverController.getRightX()),
+                    -m_driverController.getLeftY(), -m_driverController.getRightX()),
             m_robotDrive));
   }
 
@@ -54,30 +53,35 @@
    */
   private void configureButtonBindings() {
     // Move the arm to 2 radians above horizontal when the 'A' button is pressed.
-    new JoystickButton(m_driverController, Button.kA.value)
-        .whenPressed(
-            () -> {
-              m_robotArm.setGoal(2);
-              m_robotArm.enable();
-            },
-            m_robotArm);
+    m_driverController
+        .a()
+        .onTrue(
+            Commands.runOnce(
+                () -> {
+                  m_robotArm.setGoal(2);
+                  m_robotArm.enable();
+                },
+                m_robotArm));
 
     // Move the arm to neutral position when the 'B' button is pressed.
-    new JoystickButton(m_driverController, Button.kB.value)
-        .whenPressed(
-            () -> {
-              m_robotArm.setGoal(Constants.ArmConstants.kArmOffsetRads);
-              m_robotArm.enable();
-            },
-            m_robotArm);
+    m_driverController
+        .b()
+        .onTrue(
+            Commands.runOnce(
+                () -> {
+                  m_robotArm.setGoal(Constants.ArmConstants.kArmOffsetRads);
+                  m_robotArm.enable();
+                },
+                m_robotArm));
 
     // Disable the arm controller when Y is pressed.
-    new JoystickButton(m_driverController, Button.kY.value).whenPressed(m_robotArm::disable);
+    m_driverController.y().onTrue(Commands.runOnce(m_robotArm::disable));
 
     // Drive at half speed when the bumper is held
-    new JoystickButton(m_driverController, Button.kRightBumper.value)
-        .whenPressed(() -> m_robotDrive.setMaxOutput(0.5))
-        .whenReleased(() -> m_robotDrive.setMaxOutput(1));
+    m_driverController
+        .rightBumper()
+        .onTrue(Commands.runOnce(() -> m_robotDrive.setMaxOutput(0.5)))
+        .onFalse(Commands.runOnce(() -> m_robotDrive.setMaxOutput(1.0)));
   }
 
   /**
@@ -94,6 +98,6 @@
    * @return the command to run in autonomous
    */
   public Command getAutonomousCommand() {
-    return new InstantCommand();
+    return Commands.none();
   }
 }
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/RobotContainer.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/RobotContainer.java
index 7ea7999..03f775c 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/RobotContainer.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/RobotContainer.java
@@ -4,15 +4,13 @@
 
 package edu.wpi.first.wpilibj.examples.armbotoffboard;
 
-import static edu.wpi.first.wpilibj.XboxController.Button;
-
 import edu.wpi.first.wpilibj.XboxController;
 import edu.wpi.first.wpilibj.examples.armbotoffboard.Constants.OIConstants;
 import edu.wpi.first.wpilibj.examples.armbotoffboard.subsystems.ArmSubsystem;
 import edu.wpi.first.wpilibj.examples.armbotoffboard.subsystems.DriveSubsystem;
 import edu.wpi.first.wpilibj2.command.Command;
-import edu.wpi.first.wpilibj2.command.InstantCommand;
-import edu.wpi.first.wpilibj2.command.RunCommand;
+import edu.wpi.first.wpilibj2.command.Commands;
+import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
 import edu.wpi.first.wpilibj2.command.button.JoystickButton;
 
 /**
@@ -27,7 +25,8 @@
   private final ArmSubsystem m_robotArm = new ArmSubsystem();
 
   // The driver's controller
-  XboxController m_driverController = new XboxController(OIConstants.kDriverControllerPort);
+  CommandXboxController m_driverController =
+      new CommandXboxController(OIConstants.kDriverControllerPort);
 
   /** The container for the robot. Contains subsystems, OI devices, and commands. */
   public RobotContainer() {
@@ -39,11 +38,8 @@
     m_robotDrive.setDefaultCommand(
         // A split-stick arcade command, with forward/backward controlled by the left
         // hand, and turning controlled by the right.
-        new RunCommand(
-            () ->
-                m_robotDrive.arcadeDrive(
-                    -m_driverController.getLeftY(), m_driverController.getRightX()),
-            m_robotDrive));
+        m_robotDrive.arcadeDriveCommand(
+            () -> -m_driverController.getLeftY(), () -> -m_driverController.getRightX()));
   }
 
   /**
@@ -54,17 +50,18 @@
    */
   private void configureButtonBindings() {
     // Move the arm to 2 radians above horizontal when the 'A' button is pressed.
-    new JoystickButton(m_driverController, Button.kA.value)
-        .whenPressed(() -> m_robotArm.setGoal(2), m_robotArm);
+    m_driverController.a().onTrue(m_robotArm.setArmGoalCommand(2));
 
     // Move the arm to neutral position when the 'B' button is pressed.
-    new JoystickButton(m_driverController, Button.kB.value)
-        .whenPressed(() -> m_robotArm.setGoal(Constants.ArmConstants.kArmOffsetRads), m_robotArm);
+    m_driverController
+        .b()
+        .onTrue(m_robotArm.setArmGoalCommand(Constants.ArmConstants.kArmOffsetRads));
 
     // Drive at half speed when the bumper is held
-    new JoystickButton(m_driverController, Button.kRightBumper.value)
-        .whenPressed(() -> m_robotDrive.setMaxOutput(0.5))
-        .whenReleased(() -> m_robotDrive.setMaxOutput(1));
+    m_driverController
+        .rightBumper()
+        .onTrue(m_robotDrive.limitOutputCommand(0.5))
+        .onFalse(m_robotDrive.limitOutputCommand(1));
   }
 
   /**
@@ -73,6 +70,6 @@
    * @return the command to run in autonomous
    */
   public Command getAutonomousCommand() {
-    return new InstantCommand();
+    return Commands.none();
   }
 }
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/subsystems/ArmSubsystem.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/subsystems/ArmSubsystem.java
index 9e70402..e083484 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/subsystems/ArmSubsystem.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/subsystems/ArmSubsystem.java
@@ -8,6 +8,8 @@
 import edu.wpi.first.math.trajectory.TrapezoidProfile;
 import edu.wpi.first.wpilibj.examples.armbotoffboard.Constants.ArmConstants;
 import edu.wpi.first.wpilibj.examples.armbotoffboard.ExampleSmartMotorController;
+import edu.wpi.first.wpilibj2.command.Command;
+import edu.wpi.first.wpilibj2.command.Commands;
 import edu.wpi.first.wpilibj2.command.TrapezoidProfileSubsystem;
 
 /** A robot arm subsystem that moves with a motion profile. */
@@ -36,4 +38,8 @@
     m_motor.setSetpoint(
         ExampleSmartMotorController.PIDMode.kPosition, setpoint.position, feedforward / 12.0);
   }
+
+  public Command setArmGoalCommand(double kArmOffsetRads) {
+    return Commands.runOnce(() -> setGoal(kArmOffsetRads), this);
+  }
 }
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/subsystems/DriveSubsystem.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/subsystems/DriveSubsystem.java
index 939bcc3..e3c9159 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/subsystems/DriveSubsystem.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/subsystems/DriveSubsystem.java
@@ -9,7 +9,10 @@
 import edu.wpi.first.wpilibj.examples.armbotoffboard.Constants.DriveConstants;
 import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
 import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
+import edu.wpi.first.wpilibj2.command.Command;
+import edu.wpi.first.wpilibj2.command.Commands;
 import edu.wpi.first.wpilibj2.command.SubsystemBase;
+import java.util.function.DoubleSupplier;
 
 public class DriveSubsystem extends SubsystemBase {
   // The motors on the left side of the drive.
@@ -54,13 +57,14 @@
   }
 
   /**
-   * Drives the robot using arcade controls.
+   * A split-stick arcade command, with forward/backward controlled by the left hand, and turning
+   * controlled by the right.
    *
-   * @param fwd the commanded forward movement
-   * @param rot the commanded rotation
+   * @param fwd supplier for the commanded forward movement
+   * @param rot supplier for the commanded rotation
    */
-  public void arcadeDrive(double fwd, double rot) {
-    m_drive.arcadeDrive(fwd, rot);
+  public Command arcadeDriveCommand(DoubleSupplier fwd, DoubleSupplier rot) {
+    return Commands.run(() -> m_drive.arcadeDrive(fwd.getAsDouble(), rot.getAsDouble()), this);
   }
 
   /** Resets the drive encoders to currently read a position of 0. */
@@ -101,7 +105,7 @@
    *
    * @param maxOutput the maximum output to which the drive will be constrained
    */
-  public void setMaxOutput(double maxOutput) {
-    m_drive.setMaxOutput(maxOutput);
+  public Command limitOutputCommand(double maxOutput) {
+    return Commands.runOnce(() -> m_drive.setMaxOutput(maxOutput));
   }
 }
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/canpdp/Robot.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/canpdp/Robot.java
index 1d5e24f..e2b699d 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/canpdp/Robot.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/canpdp/Robot.java
@@ -16,23 +16,40 @@
   private final PowerDistribution m_pdp = new PowerDistribution();
 
   @Override
+  public void robotInit() {
+    // Put the PDP itself to the dashboard
+    SmartDashboard.putData("PDP", m_pdp);
+  }
+
+  @Override
   public void robotPeriodic() {
-    /*
-     * Get the current going through channel 7, in Amperes. The PDP returns the
-     * current in increments of 0.125A. At low currents
-     * the current readings tend to be less accurate.
-     */
-    SmartDashboard.putNumber("Current Channel 7", m_pdp.getCurrent(7));
+    // Get the current going through channel 7, in Amperes.
+    // The PDP returns the current in increments of 0.125A.
+    // At low currents the current readings tend to be less accurate.
+    double current7 = m_pdp.getCurrent(7);
+    SmartDashboard.putNumber("Current Channel 7", current7);
 
-    /*
-     * Get the voltage going into the PDP, in Volts.
-     * The PDP returns the voltage in increments of 0.05 Volts.
-     */
-    SmartDashboard.putNumber("Voltage", m_pdp.getVoltage());
+    // Get the voltage going into the PDP, in Volts.
+    // The PDP returns the voltage in increments of 0.05 Volts.
+    double voltage = m_pdp.getVoltage();
+    SmartDashboard.putNumber("Voltage", voltage);
 
-    /*
-     * Retrieves the temperature of the PDP, in degrees Celsius.
-     */
-    SmartDashboard.putNumber("Temperature", m_pdp.getTemperature());
+    // Retrieves the temperature of the PDP, in degrees Celsius.
+    double temperatureCelsius = m_pdp.getTemperature();
+    SmartDashboard.putNumber("Temperature", temperatureCelsius);
+
+    // Get the total current of all channels.
+    double totalCurrent = m_pdp.getTotalCurrent();
+    SmartDashboard.putNumber("Total Current", totalCurrent);
+
+    // Get the total power of all channels.
+    // Power is the bus voltage multiplied by the current with the units Watts.
+    double totalPower = m_pdp.getTotalPower();
+    SmartDashboard.putNumber("Total Power", totalPower);
+
+    // Get the total energy of all channels.
+    // Energy is the power summed over time with units Joules.
+    double totalEnergy = m_pdp.getTotalEnergy();
+    SmartDashboard.putNumber("Total Energy", totalEnergy);
   }
 }
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdrivebot/Drivetrain.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdrivebot/Drivetrain.java
index 07b4881..8b4734a 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdrivebot/Drivetrain.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdrivebot/Drivetrain.java
@@ -72,7 +72,9 @@
     m_leftEncoder.reset();
     m_rightEncoder.reset();
 
-    m_odometry = new DifferentialDriveOdometry(m_gyro.getRotation2d());
+    m_odometry =
+        new DifferentialDriveOdometry(
+            m_gyro.getRotation2d(), m_leftEncoder.getDistance(), m_rightEncoder.getDistance());
   }
 
   /**
@@ -98,7 +100,6 @@
    * @param xSpeed Linear velocity in m/s.
    * @param rot Angular velocity in rad/s.
    */
-  @SuppressWarnings("ParameterName")
   public void drive(double xSpeed, double rot) {
     var wheelSpeeds = m_kinematics.toWheelSpeeds(new ChassisSpeeds(xSpeed, 0.0, rot));
     setSpeeds(wheelSpeeds);
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdriveposeestimator/Drivetrain.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdriveposeestimator/Drivetrain.java
index 3b5d9e2..1b1808e 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdriveposeestimator/Drivetrain.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdriveposeestimator/Drivetrain.java
@@ -54,10 +54,12 @@
   numbers used  below are robot specific, and should be tuned. */
   private final DifferentialDrivePoseEstimator m_poseEstimator =
       new DifferentialDrivePoseEstimator(
+          m_kinematics,
           m_gyro.getRotation2d(),
+          m_leftEncoder.getDistance(),
+          m_rightEncoder.getDistance(),
           new Pose2d(),
-          VecBuilder.fill(0.05, 0.05, Units.degreesToRadians(5), 0.01, 0.01),
-          VecBuilder.fill(0.02, 0.02, Units.degreesToRadians(1)),
+          VecBuilder.fill(0.05, 0.05, Units.degreesToRadians(5)),
           VecBuilder.fill(0.5, 0.5, Units.degreesToRadians(30)));
 
   // Gains are for example purposes only - must be determined for your own robot!
@@ -108,7 +110,6 @@
    * @param xSpeed Linear velocity in m/s.
    * @param rot Angular velocity in rad/s.
    */
-  @SuppressWarnings("ParameterName")
   public void drive(double xSpeed, double rot) {
     var wheelSpeeds = m_kinematics.toWheelSpeeds(new ChassisSpeeds(xSpeed, 0.0, rot));
     setSpeeds(wheelSpeeds);
@@ -117,10 +118,7 @@
   /** Updates the field-relative position. */
   public void updateOdometry() {
     m_poseEstimator.update(
-        m_gyro.getRotation2d(),
-        new DifferentialDriveWheelSpeeds(m_leftEncoder.getRate(), m_rightEncoder.getRate()),
-        m_leftEncoder.getDistance(),
-        m_rightEncoder.getDistance());
+        m_gyro.getRotation2d(), m_leftEncoder.getDistance(), m_rightEncoder.getDistance());
 
     // Also apply vision measurements. We use 0.3 seconds in the past as an example -- on
     // a real robot, this must be calculated based either on latency or timestamps.
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/RobotContainer.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/RobotContainer.java
index cc39207..6bc4b13 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/RobotContainer.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/RobotContainer.java
@@ -4,8 +4,6 @@
 
 package edu.wpi.first.wpilibj.examples.drivedistanceoffboard;
 
-import static edu.wpi.first.wpilibj.XboxController.Button;
-
 import edu.wpi.first.math.trajectory.TrapezoidProfile;
 import edu.wpi.first.wpilibj.XboxController;
 import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.Constants.DriveConstants;
@@ -13,10 +11,9 @@
 import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.commands.DriveDistanceProfiled;
 import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.subsystems.DriveSubsystem;
 import edu.wpi.first.wpilibj2.command.Command;
-import edu.wpi.first.wpilibj2.command.InstantCommand;
-import edu.wpi.first.wpilibj2.command.RunCommand;
+import edu.wpi.first.wpilibj2.command.Commands;
 import edu.wpi.first.wpilibj2.command.TrapezoidProfileCommand;
-import edu.wpi.first.wpilibj2.command.button.JoystickButton;
+import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
 
 /**
  * This class is where the bulk of the robot should be declared. Since Command-based is a
@@ -28,8 +25,13 @@
   // The robot's subsystems
   private final DriveSubsystem m_robotDrive = new DriveSubsystem();
 
+  // Retained command references
+  private final Command m_driveFullSpeed = Commands.runOnce(() -> m_robotDrive.setMaxOutput(1));
+  private final Command m_driveHalfSpeed = Commands.runOnce(() -> m_robotDrive.setMaxOutput(0.5));
+
   // The driver's controller
-  XboxController m_driverController = new XboxController(OIConstants.kDriverControllerPort);
+  CommandXboxController m_driverController =
+      new CommandXboxController(OIConstants.kDriverControllerPort);
 
   /** The container for the robot. Contains subsystems, OI devices, and commands. */
   public RobotContainer() {
@@ -41,10 +43,10 @@
     m_robotDrive.setDefaultCommand(
         // A split-stick arcade command, with forward/backward controlled by the left
         // hand, and turning controlled by the right.
-        new RunCommand(
+        Commands.run(
             () ->
                 m_robotDrive.arcadeDrive(
-                    -m_driverController.getLeftY(), m_driverController.getRightX()),
+                    -m_driverController.getLeftY(), -m_driverController.getRightX()),
             m_robotDrive));
   }
 
@@ -52,16 +54,19 @@
    * Use this method to define your button->command mappings. Buttons can be created by
    * instantiating a {@link edu.wpi.first.wpilibj.GenericHID} or one of its subclasses ({@link
    * edu.wpi.first.wpilibj.Joystick} or {@link XboxController}), and then passing it to a {@link
-   * JoystickButton}.
+   * edu.wpi.first.wpilibj2.command.button.JoystickButton}.
    */
   private void configureButtonBindings() {
+    // Drive at half speed when the bumper is held
+    m_driverController.rightBumper().onTrue(m_driveHalfSpeed).onFalse(m_driveFullSpeed);
+
     // Drive forward by 3 meters when the 'A' button is pressed, with a timeout of 10 seconds
-    new JoystickButton(m_driverController, Button.kA.value)
-        .whenPressed(new DriveDistanceProfiled(3, m_robotDrive).withTimeout(10));
+    m_driverController.a().onTrue(new DriveDistanceProfiled(3, m_robotDrive).withTimeout(10));
 
     // Do the same thing as above when the 'B' button is pressed, but defined inline
-    new JoystickButton(m_driverController, Button.kB.value)
-        .whenPressed(
+    m_driverController
+        .b()
+        .onTrue(
             new TrapezoidProfileCommand(
                     new TrapezoidProfile(
                         // Limit the max acceleration and velocity
@@ -76,11 +81,6 @@
                     m_robotDrive)
                 .beforeStarting(m_robotDrive::resetEncoders)
                 .withTimeout(10));
-
-    // Drive at half speed when the bumper is held
-    new JoystickButton(m_driverController, Button.kRightBumper.value)
-        .whenPressed(() -> m_robotDrive.setMaxOutput(0.5))
-        .whenReleased(() -> m_robotDrive.setMaxOutput(1));
   }
 
   /**
@@ -89,6 +89,6 @@
    * @return the command to run in autonomous
    */
   public Command getAutonomousCommand() {
-    return new InstantCommand();
+    return Commands.none();
   }
 }
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/dutycycleencoder/Robot.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/dutycycleencoder/Robot.java
index a12a6fd..bb99244 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/dutycycleencoder/Robot.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/dutycycleencoder/Robot.java
@@ -8,7 +8,6 @@
 import edu.wpi.first.wpilibj.TimedRobot;
 import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
 
-@SuppressWarnings("PMD.SingularField")
 public class Robot extends TimedRobot {
   private DutyCycleEncoder m_dutyCycleEncoder;
 
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/dutycycleinput/Robot.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/dutycycleinput/Robot.java
index 584fbc6..c7350b0 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/dutycycleinput/Robot.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/dutycycleinput/Robot.java
@@ -9,15 +9,12 @@
 import edu.wpi.first.wpilibj.TimedRobot;
 import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
 
-@SuppressWarnings("PMD.SingularField")
 public class Robot extends TimedRobot {
-  private DigitalInput m_input;
   private DutyCycle m_dutyCycle;
 
   @Override
   public void robotInit() {
-    m_input = new DigitalInput(0);
-    m_dutyCycle = new DutyCycle(m_input);
+    m_dutyCycle = new DutyCycle(new DigitalInput(0));
   }
 
   @Override
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorsimulation/Robot.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorsimulation/Robot.java
index 3f2bae8..4bb6654 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorsimulation/Robot.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorsimulation/Robot.java
@@ -59,6 +59,7 @@
           kElevatorDrumRadius,
           kMinElevatorHeight,
           kMaxElevatorHeight,
+          true,
           VecBuilder.fill(0.01));
   private final EncoderSim m_encoderSim = new EncoderSim(m_encoder);
 
@@ -75,6 +76,8 @@
     m_encoder.setDistancePerPulse(kElevatorEncoderDistPerPulse);
 
     // Publish Mechanism2d to SmartDashboard
+    // To view the Elevator Sim in the simulator, select Network Tables -> SmartDashboard ->
+    // Elevator Sim
     SmartDashboard.putData("Elevator Sim", m_mech2d);
   }
 
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Main.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Main.java
new file mode 100644
index 0000000..d6f3150
--- /dev/null
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Main.java
@@ -0,0 +1,26 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj.examples.eventloop;
+
+import edu.wpi.first.wpilibj.RobotBase;
+import edu.wpi.first.wpilibj.examples.encoder.Robot;
+
+/**
+ * Do NOT add any static variables to this class, or any initialization at all. Unless you know what
+ * you are doing, do not modify this file except to change the parameter class to the startRobot
+ * call.
+ */
+public final class Main {
+  private Main() {}
+
+  /**
+   * Main initialization function. Do not perform any initialization here.
+   *
+   * <p>If you change your main robot class, change the parameter type.
+   */
+  public static void main(String... args) {
+    RobotBase.startRobot(Robot::new);
+  }
+}
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Robot.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Robot.java
new file mode 100644
index 0000000..03c5577
--- /dev/null
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Robot.java
@@ -0,0 +1,92 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj.examples.eventloop;
+
+import edu.wpi.first.math.controller.PIDController;
+import edu.wpi.first.math.controller.SimpleMotorFeedforward;
+import edu.wpi.first.wpilibj.Encoder;
+import edu.wpi.first.wpilibj.Joystick;
+import edu.wpi.first.wpilibj.TimedRobot;
+import edu.wpi.first.wpilibj.Ultrasonic;
+import edu.wpi.first.wpilibj.event.BooleanEvent;
+import edu.wpi.first.wpilibj.event.EventLoop;
+import edu.wpi.first.wpilibj.motorcontrol.MotorController;
+import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
+
+public class Robot extends TimedRobot {
+  public static final int SHOT_VELOCITY = 200; // rpm
+  public static final int TOLERANCE = 8; // rpm
+  public static final int KICKER_THRESHOLD = 15; // mm
+
+  private final MotorController m_shooter = new PWMSparkMax(0);
+  private final Encoder m_shooterEncoder = new Encoder(0, 1);
+  private final PIDController m_controller = new PIDController(0.3, 0, 0);
+  private final SimpleMotorFeedforward m_ff = new SimpleMotorFeedforward(0.1, 0.065);
+
+  private final MotorController m_kicker = new PWMSparkMax(1);
+  private final Ultrasonic m_kickerSensor = new Ultrasonic(2, 3);
+
+  private final MotorController m_intake = new PWMSparkMax(2);
+
+  private final EventLoop m_loop = new EventLoop();
+  private final Joystick m_joystick = new Joystick(0);
+
+  @Override
+  public void robotInit() {
+    m_controller.setTolerance(TOLERANCE);
+
+    BooleanEvent isBallAtKicker =
+        new BooleanEvent(m_loop, () -> m_kickerSensor.getRangeMM() < KICKER_THRESHOLD);
+    BooleanEvent intakeButton = new BooleanEvent(m_loop, () -> m_joystick.getRawButton(2));
+
+    // if the thumb button is held
+    intakeButton
+        // and there is not a ball at the kicker
+        .and(isBallAtKicker.negate())
+        // activate the intake
+        .ifHigh(() -> m_intake.set(0.5));
+
+    // if the thumb button is not held
+    intakeButton
+        .negate()
+        // or there is a ball in the kicker
+        .or(isBallAtKicker)
+        // stop the intake
+        .ifHigh(m_intake::stopMotor);
+
+    BooleanEvent shootTrigger = new BooleanEvent(m_loop, m_joystick::getTrigger);
+
+    // if the trigger is held
+    shootTrigger
+        // accelerate the shooter wheel
+        .ifHigh(
+        () ->
+            m_shooter.setVoltage(
+                m_controller.calculate(m_shooterEncoder.getRate(), SHOT_VELOCITY)
+                    + m_ff.calculate(SHOT_VELOCITY)));
+    // if not, stop
+    shootTrigger.negate().ifHigh(m_shooter::stopMotor);
+
+    BooleanEvent atTargetVelocity =
+        new BooleanEvent(m_loop, m_controller::atSetpoint)
+            // debounce for more stability
+            .debounce(0.2);
+
+    // if we're at the target velocity, kick the ball into the shooter wheel
+    atTargetVelocity.ifHigh(() -> m_kicker.set(0.7));
+
+    // when we stop being at the target velocity, it means the ball was shot
+    atTargetVelocity
+        .falling()
+        // so stop the kicker
+        .ifHigh(m_kicker::stopMotor);
+  }
+
+  @Override
+  public void robotPeriodic() {
+    // poll all the bindings
+    m_loop.poll();
+  }
+}
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/examples.json b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/examples.json
index ddf5d5e..01f79e7 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/examples.json
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/examples.json
@@ -90,6 +90,17 @@
     "commandversion": 2
   },
   {
+    "name": "EventLoop",
+    "description": "Demonstrate managing a ball system using EventLoop and BooleanEvent.",
+    "tags": [
+      "EventLoop"
+    ],
+    "foldername": "eventloop",
+    "gradlebase": "java",
+    "mainclass": "Main",
+    "commandversion": 2
+  },
+  {
     "name": "Relay",
     "description": "Demonstrate controlling a Relay from Joystick buttons.",
     "tags": [
@@ -218,20 +229,7 @@
     "commandversion": 2
   },
   {
-    "name": "Motor Controller",
-    "description": "Demonstrate controlling a single motor with a joystick",
-    "tags": [
-      "Actuators",
-      "Joystick",
-      "Robot and Motor"
-    ],
-    "foldername": "motorcontrol",
-    "gradlebase": "java",
-    "mainclass": "Main",
-    "commandversion": 2
-  },
-  {
-    "name": "Motor Control With Encoder",
+    "name": "Motor Control",
     "description": "Demonstrate controlling a single motor with a Joystick and displaying the net movement of the motor using an encoder.",
     "tags": [
       "Robot and Motor",
@@ -241,7 +239,7 @@
       "Joystick",
       "Complete List"
     ],
-    "foldername": "motorcontrolencoder",
+    "foldername": "motorcontrol",
     "gradlebase": "java",
     "mainclass": "Main",
     "commandversion": 2
@@ -330,6 +328,19 @@
     "commandversion": 2
   },
   {
+    "name": "Rapid React Command Bot",
+    "description": "A fully-functional command-based fender bot for the 2022 game using the new command framework.",
+    "tags": [
+      "Complete robot",
+      "Command-based",
+      "Lambdas"
+    ],
+    "foldername": "rapidreactcommandbot",
+    "gradlebase": "java",
+    "mainclass": "Main",
+    "commandversion": 2
+  },
+  {
     "name": "Select Command Example",
     "description": "An example showing how to use the SelectCommand class from the new command framework.",
     "tags": [
@@ -710,6 +721,17 @@
     "commandversion": 2
   },
   {
+    "name": "UnitTesting",
+    "description": "Demonstrates basic unit testing for a robot project.",
+    "tags": [
+      "Testing"
+    ],
+    "foldername": "unittest",
+    "gradlebase": "java",
+    "mainclass": "Main",
+    "commandversion": 2
+  },
+  {
     "name": "DifferentialDrivePoseEstimator",
     "description": "Demonstrates the use of the DifferentialDrivePoseEstimator as a replacement for differential drive odometry.",
     "tags": [
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/frisbeebot/RobotContainer.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/frisbeebot/RobotContainer.java
index 1f00dd9..8e052bb 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/frisbeebot/RobotContainer.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/frisbeebot/RobotContainer.java
@@ -4,20 +4,13 @@
 
 package edu.wpi.first.wpilibj.examples.frisbeebot;
 
-import static edu.wpi.first.wpilibj.XboxController.Button;
-
-import edu.wpi.first.wpilibj.XboxController;
 import edu.wpi.first.wpilibj.examples.frisbeebot.Constants.AutoConstants;
 import edu.wpi.first.wpilibj.examples.frisbeebot.Constants.OIConstants;
 import edu.wpi.first.wpilibj.examples.frisbeebot.subsystems.DriveSubsystem;
 import edu.wpi.first.wpilibj.examples.frisbeebot.subsystems.ShooterSubsystem;
 import edu.wpi.first.wpilibj2.command.Command;
-import edu.wpi.first.wpilibj2.command.ConditionalCommand;
-import edu.wpi.first.wpilibj2.command.InstantCommand;
-import edu.wpi.first.wpilibj2.command.RunCommand;
-import edu.wpi.first.wpilibj2.command.WaitCommand;
-import edu.wpi.first.wpilibj2.command.WaitUntilCommand;
-import edu.wpi.first.wpilibj2.command.button.JoystickButton;
+import edu.wpi.first.wpilibj2.command.Commands;
+import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
 
 /**
  * This class is where the bulk of the robot should be declared. Since Command-based is a
@@ -30,29 +23,34 @@
   private final DriveSubsystem m_robotDrive = new DriveSubsystem();
   private final ShooterSubsystem m_shooter = new ShooterSubsystem();
 
-  // A simple autonomous routine that shoots the loaded frisbees
-  private final Command m_autoCommand =
-      // Start the command by spinning up the shooter...
-      new InstantCommand(m_shooter::enable, m_shooter)
-          .andThen(
+  private final Command m_spinUpShooter = Commands.runOnce(m_shooter::enable, m_shooter);
+  private final Command m_stopShooter = Commands.runOnce(m_shooter::disable, m_shooter);
+
+  // An autonomous routine that shoots the loaded frisbees
+  Command m_autonomousCommand =
+      Commands.sequence(
+              // Start the command by spinning up the shooter...
+              Commands.runOnce(m_shooter::enable, m_shooter),
               // Wait until the shooter is at speed before feeding the frisbees
-              new WaitUntilCommand(m_shooter::atSetpoint),
+              Commands.waitUntil(m_shooter::atSetpoint),
               // Start running the feeder
-              new InstantCommand(m_shooter::runFeeder, m_shooter),
+              Commands.runOnce(m_shooter::runFeeder, m_shooter),
               // Shoot for the specified time
-              new WaitCommand(AutoConstants.kAutoShootTimeSeconds))
-          // Add a timeout (will end the command if, for instance, the shooter never gets up to
-          // speed)
+              Commands.waitSeconds(AutoConstants.kAutoShootTimeSeconds))
+          // Add a timeout (will end the command if, for instance, the shooter
+          // never gets up to speed)
           .withTimeout(AutoConstants.kAutoTimeoutSeconds)
           // When the command ends, turn off the shooter and the feeder
           .andThen(
-              () -> {
-                m_shooter.disable();
-                m_shooter.stopFeeder();
-              });
+              Commands.runOnce(
+                  () -> {
+                    m_shooter.disable();
+                    m_shooter.stopFeeder();
+                  }));
 
   // The driver's controller
-  XboxController m_driverController = new XboxController(OIConstants.kDriverControllerPort);
+  CommandXboxController m_driverController =
+      new CommandXboxController(OIConstants.kDriverControllerPort);
 
   /** The container for the robot. Contains subsystems, OI devices, and commands. */
   public RobotContainer() {
@@ -64,45 +62,55 @@
     m_robotDrive.setDefaultCommand(
         // A split-stick arcade command, with forward/backward controlled by the left
         // hand, and turning controlled by the right.
-        new RunCommand(
+        Commands.run(
             () ->
                 m_robotDrive.arcadeDrive(
-                    -m_driverController.getLeftY(), m_driverController.getRightX()),
+                    -m_driverController.getLeftY(), -m_driverController.getRightX()),
             m_robotDrive));
   }
 
   /**
-   * Use this method to define your button->command mappings. Buttons can be created by
-   * instantiating a {@link edu.wpi.first.wpilibj.GenericHID} or one of its subclasses ({@link
-   * edu.wpi.first.wpilibj.Joystick} or {@link XboxController}), and then passing it to a {@link
-   * edu.wpi.first.wpilibj2.command.button.JoystickButton}.
+   * Use this method to define your button->command mappings. Buttons can be created via the button
+   * factories on {@link edu.wpi.first.wpilibj2.command.button.CommandGenericHID} or one of its
+   * subclasses ({@link edu.wpi.first.wpilibj2.command.button.CommandJoystick} or {@link
+   * CommandXboxController}).
    */
   private void configureButtonBindings() {
+    // Configure your button bindings here
+
+    // We can bind commands while retaining references to them in RobotContainer
+
     // Spin up the shooter when the 'A' button is pressed
-    new JoystickButton(m_driverController, Button.kA.value)
-        .whenPressed(new InstantCommand(m_shooter::enable, m_shooter));
+    m_driverController.a().onTrue(m_spinUpShooter);
 
     // Turn off the shooter when the 'B' button is pressed
-    new JoystickButton(m_driverController, Button.kB.value)
-        .whenPressed(new InstantCommand(m_shooter::disable, m_shooter));
+    m_driverController.b().onTrue(m_stopShooter);
 
-    // Run the feeder when the 'X' button is held, but only if the shooter is at speed
-    new JoystickButton(m_driverController, Button.kX.value)
-        .whenPressed(
-            new ConditionalCommand(
-                // Run the feeder
-                new InstantCommand(m_shooter::runFeeder, m_shooter),
-                // Do nothing
-                new InstantCommand(),
-                // Determine which of the above to do based on whether the shooter has reached the
-                // desired speed
-                m_shooter::atSetpoint))
-        .whenReleased(new InstantCommand(m_shooter::stopFeeder, m_shooter));
+    // We can also write them as temporary variables outside the bindings
 
-    // Drive at half speed when the bumper is held
-    new JoystickButton(m_driverController, Button.kRightBumper.value)
-        .whenPressed(() -> m_robotDrive.setMaxOutput(0.5))
-        .whenReleased(() -> m_robotDrive.setMaxOutput(1));
+    // Shoots if the shooter wheel has reached the target speed
+    Command shoot =
+        Commands.either(
+            // Run the feeder
+            Commands.runOnce(m_shooter::runFeeder, m_shooter),
+            // Do nothing
+            Commands.none(),
+            // Determine which of the above to do based on whether the shooter has reached the
+            // desired speed
+            m_shooter::atSetpoint);
+
+    Command stopFeeder = Commands.runOnce(m_shooter::stopFeeder, m_shooter);
+
+    // Shoot when the 'X' button is pressed
+    m_driverController.x().onTrue(shoot).onFalse(stopFeeder);
+
+    // We can also define commands inline at the binding!
+
+    // While holding the shoulder button, drive at half speed
+    m_driverController
+        .rightBumper()
+        .onTrue(Commands.runOnce(() -> m_robotDrive.setMaxOutput(0.5)))
+        .onFalse(Commands.runOnce(() -> m_robotDrive.setMaxOutput(1)));
   }
 
   /**
@@ -111,6 +119,6 @@
    * @return the command to run in autonomous
    */
   public Command getAutonomousCommand() {
-    return m_autoCommand;
+    return m_autonomousCommand;
   }
 }
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/RobotContainer.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/RobotContainer.java
index e4c7412..47710f9 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/RobotContainer.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/RobotContainer.java
@@ -58,7 +58,7 @@
 
     // Assign default commands
     m_drivetrain.setDefaultCommand(
-        new TankDrive(m_joystick::getLeftY, m_joystick::getRightY, m_drivetrain));
+        new TankDrive(() -> -m_joystick.getLeftY(), () -> -m_joystick.getRightY(), m_drivetrain));
 
     // Show what command your subsystem is running on the SmartDashboard
     SmartDashboard.putData(m_drivetrain);
@@ -88,15 +88,15 @@
     final JoystickButton r1 = new JoystickButton(m_joystick, 12);
 
     // Connect the buttons to commands
-    dpadUp.whenPressed(new SetElevatorSetpoint(0.25, m_elevator));
-    dpadDown.whenPressed(new SetElevatorSetpoint(0.0, m_elevator));
-    dpadRight.whenPressed(new CloseClaw(m_claw));
-    dpadLeft.whenPressed(new OpenClaw(m_claw));
+    dpadUp.onTrue(new SetElevatorSetpoint(0.25, m_elevator));
+    dpadDown.onTrue(new SetElevatorSetpoint(0.0, m_elevator));
+    dpadRight.onTrue(new CloseClaw(m_claw));
+    dpadLeft.onTrue(new OpenClaw(m_claw));
 
-    r1.whenPressed(new PrepareToPickup(m_claw, m_wrist, m_elevator));
-    r2.whenPressed(new Pickup(m_claw, m_wrist, m_elevator));
-    l1.whenPressed(new Place(m_claw, m_wrist, m_elevator));
-    l2.whenPressed(new Autonomous(m_drivetrain, m_claw, m_wrist, m_elevator));
+    r1.onTrue(new PrepareToPickup(m_claw, m_wrist, m_elevator));
+    r2.onTrue(new Pickup(m_claw, m_wrist, m_elevator));
+    l1.onTrue(new Place(m_claw, m_wrist, m_elevator));
+    l2.onTrue(new Autonomous(m_drivetrain, m_claw, m_wrist, m_elevator));
   }
 
   /**
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/Autonomous.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/Autonomous.java
index 599ed69..44a7ce7 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/Autonomous.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/Autonomous.java
@@ -8,6 +8,7 @@
 import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.Drivetrain;
 import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.Elevator;
 import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.Wrist;
+import edu.wpi.first.wpilibj2.command.Commands;
 import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
 
 /** The main autonomous command to pickup and deliver the soda to the box. */
@@ -22,6 +23,6 @@
         new Place(claw, wrist, elevator),
         new SetDistanceToBox(0.60, drive),
         // new DriveStraight(-2), // Use Encoders if ultrasonic is broken
-        parallel(new SetWristSetpoint(-45, wrist), new CloseClaw(claw)));
+        Commands.parallel(new SetWristSetpoint(-45, wrist), new CloseClaw(claw)));
   }
 }
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/Pickup.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/Pickup.java
index 4c7d267..4e6eafd 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/Pickup.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/Pickup.java
@@ -7,6 +7,7 @@
 import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.Claw;
 import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.Elevator;
 import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.Wrist;
+import edu.wpi.first.wpilibj2.command.Commands;
 import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
 
 /**
@@ -23,6 +24,7 @@
   public Pickup(Claw claw, Wrist wrist, Elevator elevator) {
     addCommands(
         new CloseClaw(claw),
-        parallel(new SetWristSetpoint(-45, wrist), new SetElevatorSetpoint(0.25, elevator)));
+        Commands.parallel(
+            new SetWristSetpoint(-45, wrist), new SetElevatorSetpoint(0.25, elevator)));
   }
 }
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/PrepareToPickup.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/PrepareToPickup.java
index 1ae5992..3c0661d 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/PrepareToPickup.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/PrepareToPickup.java
@@ -7,6 +7,7 @@
 import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.Claw;
 import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.Elevator;
 import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.Wrist;
+import edu.wpi.first.wpilibj2.command.Commands;
 import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
 
 /** Make sure the robot is in a state to pickup soda cans. */
@@ -21,6 +22,6 @@
   public PrepareToPickup(Claw claw, Wrist wrist, Elevator elevator) {
     addCommands(
         new OpenClaw(claw),
-        parallel(new SetWristSetpoint(0, wrist), new SetElevatorSetpoint(0, elevator)));
+        Commands.parallel(new SetWristSetpoint(0, wrist), new SetElevatorSetpoint(0, elevator)));
   }
 }
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gettingstarted/Robot.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gettingstarted/Robot.java
index f9499f5..45094fa 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gettingstarted/Robot.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gettingstarted/Robot.java
@@ -4,9 +4,9 @@
 
 package edu.wpi.first.wpilibj.examples.gettingstarted;
 
-import edu.wpi.first.wpilibj.Joystick;
 import edu.wpi.first.wpilibj.TimedRobot;
 import edu.wpi.first.wpilibj.Timer;
+import edu.wpi.first.wpilibj.XboxController;
 import edu.wpi.first.wpilibj.drive.DifferentialDrive;
 import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
 
@@ -20,7 +20,7 @@
   private final PWMSparkMax m_leftDrive = new PWMSparkMax(0);
   private final PWMSparkMax m_rightDrive = new PWMSparkMax(1);
   private final DifferentialDrive m_robotDrive = new DifferentialDrive(m_leftDrive, m_rightDrive);
-  private final Joystick m_stick = new Joystick(0);
+  private final XboxController m_controller = new XboxController(0);
   private final Timer m_timer = new Timer();
 
   /**
@@ -47,7 +47,8 @@
   public void autonomousPeriodic() {
     // Drive for 2 seconds
     if (m_timer.get() < 2.0) {
-      m_robotDrive.arcadeDrive(0.5, 0.0); // drive forwards half speed
+      // Drive forwards half speed, make sure to turn input squaring off
+      m_robotDrive.arcadeDrive(0.5, 0.0, false);
     } else {
       m_robotDrive.stopMotor(); // stop robot
     }
@@ -60,7 +61,7 @@
   /** This function is called periodically during teleoperated mode. */
   @Override
   public void teleopPeriodic() {
-    m_robotDrive.arcadeDrive(m_stick.getY(), m_stick.getX());
+    m_robotDrive.arcadeDrive(-m_controller.getLeftY(), -m_controller.getRightX());
   }
 
   /** This function is called once each time the robot enters test mode. */
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyro/Robot.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyro/Robot.java
index b0c6641..1f9e41d 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyro/Robot.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyro/Robot.java
@@ -50,8 +50,6 @@
   @Override
   public void teleopPeriodic() {
     double turningValue = (kAngleSetpoint - m_gyro.getAngle()) * kP;
-    // Invert the direction of the turn if we are going backwards
-    turningValue = Math.copySign(turningValue, m_joystick.getY());
-    m_myRobot.arcadeDrive(-m_joystick.getY(), turningValue);
+    m_myRobot.arcadeDrive(-m_joystick.getY(), -turningValue);
   }
 }
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyrodrivecommands/RobotContainer.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyrodrivecommands/RobotContainer.java
index b70f5bf..5caf497 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyrodrivecommands/RobotContainer.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyrodrivecommands/RobotContainer.java
@@ -45,7 +45,7 @@
         new RunCommand(
             () ->
                 m_robotDrive.arcadeDrive(
-                    -m_driverController.getLeftY(), m_driverController.getRightX()),
+                    -m_driverController.getLeftY(), -m_driverController.getRightX()),
             m_robotDrive));
   }
 
@@ -58,12 +58,12 @@
   private void configureButtonBindings() {
     // Drive at half speed when the right bumper is held
     new JoystickButton(m_driverController, Button.kR1.value)
-        .whenPressed(() -> m_robotDrive.setMaxOutput(0.5))
-        .whenReleased(() -> m_robotDrive.setMaxOutput(1));
+        .onTrue(new InstantCommand(() -> m_robotDrive.setMaxOutput(0.5)))
+        .onFalse(new InstantCommand(() -> m_robotDrive.setMaxOutput(1)));
 
     // Stabilize robot to drive straight with gyro when left bumper is held
     new JoystickButton(m_driverController, Button.kL1.value)
-        .whenHeld(
+        .whileTrue(
             new PIDCommand(
                 new PIDController(
                     DriveConstants.kStabilizationP,
@@ -80,11 +80,11 @@
 
     // Turn to 90 degrees when the 'X' button is pressed, with a 5 second timeout
     new JoystickButton(m_driverController, Button.kCross.value)
-        .whenPressed(new TurnToAngle(90, m_robotDrive).withTimeout(5));
+        .onTrue(new TurnToAngle(90, m_robotDrive).withTimeout(5));
 
     // Turn to -90 degrees with a profile when the Circle button is pressed, with a 5 second timeout
     new JoystickButton(m_driverController, Button.kCircle.value)
-        .whenPressed(new TurnToAngleProfiled(-90, m_robotDrive).withTimeout(5));
+        .onTrue(new TurnToAngleProfiled(-90, m_robotDrive).withTimeout(5));
   }
 
   /**
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyromecanum/Robot.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyromecanum/Robot.java
index 8b4391c..b86277b 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyromecanum/Robot.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyromecanum/Robot.java
@@ -51,6 +51,6 @@
   @Override
   public void teleopPeriodic() {
     m_robotDrive.driveCartesian(
-        -m_joystick.getY(), m_joystick.getX(), m_joystick.getZ(), m_gyro.getAngle());
+        -m_joystick.getY(), -m_joystick.getX(), -m_joystick.getZ(), m_gyro.getRotation2d());
   }
 }
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/RobotContainer.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/RobotContainer.java
index cda9e26..902ecbe 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/RobotContainer.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/RobotContainer.java
@@ -4,21 +4,16 @@
 
 package edu.wpi.first.wpilibj.examples.hatchbotinlined;
 
-import static edu.wpi.first.wpilibj.PS4Controller.Button;
-
 import edu.wpi.first.wpilibj.PS4Controller;
-import edu.wpi.first.wpilibj.examples.hatchbotinlined.Constants.AutoConstants;
 import edu.wpi.first.wpilibj.examples.hatchbotinlined.Constants.OIConstants;
-import edu.wpi.first.wpilibj.examples.hatchbotinlined.commands.ComplexAutoCommand;
+import edu.wpi.first.wpilibj.examples.hatchbotinlined.commands.Autos;
 import edu.wpi.first.wpilibj.examples.hatchbotinlined.subsystems.DriveSubsystem;
 import edu.wpi.first.wpilibj.examples.hatchbotinlined.subsystems.HatchSubsystem;
 import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
 import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
 import edu.wpi.first.wpilibj2.command.Command;
-import edu.wpi.first.wpilibj2.command.FunctionalCommand;
-import edu.wpi.first.wpilibj2.command.InstantCommand;
-import edu.wpi.first.wpilibj2.command.RunCommand;
-import edu.wpi.first.wpilibj2.command.button.JoystickButton;
+import edu.wpi.first.wpilibj2.command.Commands;
+import edu.wpi.first.wpilibj2.command.button.CommandPS4Controller;
 
 /**
  * This class is where the bulk of the robot should be declared. Since Command-based is a
@@ -31,30 +26,20 @@
   private final DriveSubsystem m_robotDrive = new DriveSubsystem();
   private final HatchSubsystem m_hatchSubsystem = new HatchSubsystem();
 
+  // Retained command handles
+
   // The autonomous routines
-
   // A simple auto routine that drives forward a specified distance, and then stops.
-  private final Command m_simpleAuto =
-      new FunctionalCommand(
-          // Reset encoders on command start
-          m_robotDrive::resetEncoders,
-          // Drive forward while the command is executing
-          () -> m_robotDrive.arcadeDrive(AutoConstants.kAutoDriveSpeed, 0),
-          // Stop driving at the end of the command
-          interrupt -> m_robotDrive.arcadeDrive(0, 0),
-          // End the command when the robot's driven distance exceeds the desired value
-          () -> m_robotDrive.getAverageEncoderDistance() >= AutoConstants.kAutoDriveDistanceInches,
-          // Require the drive subsystem
-          m_robotDrive);
-
+  private final Command m_simpleAuto = Autos.simpleAuto(m_robotDrive);
   // A complex auto routine that drives forward, drops a hatch, and then drives backward.
-  private final Command m_complexAuto = new ComplexAutoCommand(m_robotDrive, m_hatchSubsystem);
+  private final Command m_complexAuto = Autos.complexAuto(m_robotDrive, m_hatchSubsystem);
 
   // A chooser for autonomous commands
   SendableChooser<Command> m_chooser = new SendableChooser<>();
 
   // The driver's controller
-  PS4Controller m_driverController = new PS4Controller(OIConstants.kDriverControllerPort);
+  CommandPS4Controller m_driverController =
+      new CommandPS4Controller(OIConstants.kDriverControllerPort);
 
   /** The container for the robot. Contains subsystems, OI devices, and commands. */
   public RobotContainer() {
@@ -66,10 +51,10 @@
     m_robotDrive.setDefaultCommand(
         // A split-stick arcade command, with forward/backward controlled by the left
         // hand, and turning controlled by the right.
-        new RunCommand(
+        Commands.run(
             () ->
                 m_robotDrive.arcadeDrive(
-                    -m_driverController.getLeftY(), m_driverController.getRightX()),
+                    -m_driverController.getLeftY(), -m_driverController.getRightX()),
             m_robotDrive));
 
     // Add commands to the autonomous command chooser
@@ -88,15 +73,14 @@
    */
   private void configureButtonBindings() {
     // Grab the hatch when the Circle button is pressed.
-    new JoystickButton(m_driverController, Button.kCircle.value)
-        .whenPressed(new InstantCommand(m_hatchSubsystem::grabHatch, m_hatchSubsystem));
+    m_driverController.circle().onTrue(m_hatchSubsystem.grabHatchCommand());
     // Release the hatch when the Square button is pressed.
-    new JoystickButton(m_driverController, Button.kSquare.value)
-        .whenPressed(new InstantCommand(m_hatchSubsystem::releaseHatch, m_hatchSubsystem));
+    m_driverController.square().onTrue(m_hatchSubsystem.releaseHatchCommand());
     // While holding R1, drive at half speed
-    new JoystickButton(m_driverController, Button.kR1.value)
-        .whenPressed(() -> m_robotDrive.setMaxOutput(0.5))
-        .whenReleased(() -> m_robotDrive.setMaxOutput(1));
+    m_driverController
+        .R1()
+        .onTrue(Commands.runOnce(() -> m_robotDrive.setMaxOutput(0.5)))
+        .onFalse(Commands.runOnce(() -> m_robotDrive.setMaxOutput(1)));
   }
 
   /**
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/commands/Autos.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/commands/Autos.java
new file mode 100644
index 0000000..8af2735
--- /dev/null
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/commands/Autos.java
@@ -0,0 +1,71 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj.examples.hatchbotinlined.commands;
+
+import edu.wpi.first.wpilibj.examples.hatchbotinlined.Constants.AutoConstants;
+import edu.wpi.first.wpilibj.examples.hatchbotinlined.subsystems.DriveSubsystem;
+import edu.wpi.first.wpilibj.examples.hatchbotinlined.subsystems.HatchSubsystem;
+import edu.wpi.first.wpilibj2.command.Command;
+import edu.wpi.first.wpilibj2.command.Commands;
+import edu.wpi.first.wpilibj2.command.FunctionalCommand;
+
+/** Container for auto command factories. */
+public final class Autos {
+  /** A simple auto routine that drives forward a specified distance, and then stops. */
+  public static Command simpleAuto(DriveSubsystem drive) {
+    return new FunctionalCommand(
+        // Reset encoders on command start
+        drive::resetEncoders,
+        // Drive forward while the command is executing
+        () -> drive.arcadeDrive(AutoConstants.kAutoDriveSpeed, 0),
+        // Stop driving at the end of the command
+        interrupt -> drive.arcadeDrive(0, 0),
+        // End the command when the robot's driven distance exceeds the desired value
+        () -> drive.getAverageEncoderDistance() >= AutoConstants.kAutoDriveDistanceInches,
+        // Require the drive subsystem
+        drive);
+  }
+
+  /** A complex auto routine that drives forward, drops a hatch, and then drives backward. */
+  public static Command complexAuto(DriveSubsystem driveSubsystem, HatchSubsystem hatchSubsystem) {
+    return Commands.sequence(
+        // Drive forward up to the front of the cargo ship
+        new FunctionalCommand(
+            // Reset encoders on command start
+            driveSubsystem::resetEncoders,
+            // Drive forward while the command is executing
+            () -> driveSubsystem.arcadeDrive(AutoConstants.kAutoDriveSpeed, 0),
+            // Stop driving at the end of the command
+            interrupt -> driveSubsystem.arcadeDrive(0, 0),
+            // End the command when the robot's driven distance exceeds the desired value
+            () ->
+                driveSubsystem.getAverageEncoderDistance()
+                    >= AutoConstants.kAutoDriveDistanceInches,
+            // Require the drive subsystem
+            driveSubsystem),
+
+        // Release the hatch
+        hatchSubsystem.releaseHatchCommand(),
+
+        // Drive backward the specified distance
+        new FunctionalCommand(
+            // Reset encoders on command start
+            driveSubsystem::resetEncoders,
+            // Drive backward while the command is executing
+            () -> driveSubsystem.arcadeDrive(-AutoConstants.kAutoDriveSpeed, 0),
+            // Stop driving at the end of the command
+            interrupt -> driveSubsystem.arcadeDrive(0, 0),
+            // End the command when the robot's driven distance exceeds the desired value
+            () ->
+                driveSubsystem.getAverageEncoderDistance()
+                    <= AutoConstants.kAutoBackupDistanceInches,
+            // Require the drive subsystem
+            driveSubsystem));
+  }
+
+  private Autos() {
+    throw new UnsupportedOperationException("This is a utility class!");
+  }
+}
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/commands/ComplexAutoCommand.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/commands/ComplexAutoCommand.java
deleted file mode 100644
index 1faf45a..0000000
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/commands/ComplexAutoCommand.java
+++ /dev/null
@@ -1,57 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.examples.hatchbotinlined.commands;
-
-import edu.wpi.first.wpilibj.examples.hatchbotinlined.Constants.AutoConstants;
-import edu.wpi.first.wpilibj.examples.hatchbotinlined.subsystems.DriveSubsystem;
-import edu.wpi.first.wpilibj.examples.hatchbotinlined.subsystems.HatchSubsystem;
-import edu.wpi.first.wpilibj2.command.FunctionalCommand;
-import edu.wpi.first.wpilibj2.command.InstantCommand;
-import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
-
-/** A complex auto command that drives forward, releases a hatch, and then drives backward. */
-public class ComplexAutoCommand extends SequentialCommandGroup {
-  /**
-   * Creates a new ComplexAutoCommand.
-   *
-   * @param driveSubsystem The drive subsystem this command will run on
-   * @param hatchSubsystem The hatch subsystem this command will run on
-   */
-  public ComplexAutoCommand(DriveSubsystem driveSubsystem, HatchSubsystem hatchSubsystem) {
-    addCommands(
-        // Drive forward up to the front of the cargo ship
-        new FunctionalCommand(
-            // Reset encoders on command start
-            driveSubsystem::resetEncoders,
-            // Drive forward while the command is executing
-            () -> driveSubsystem.arcadeDrive(AutoConstants.kAutoDriveSpeed, 0),
-            // Stop driving at the end of the command
-            interrupt -> driveSubsystem.arcadeDrive(0, 0),
-            // End the command when the robot's driven distance exceeds the desired value
-            () ->
-                driveSubsystem.getAverageEncoderDistance()
-                    >= AutoConstants.kAutoDriveDistanceInches,
-            // Require the drive subsystem
-            driveSubsystem),
-
-        // Release the hatch
-        new InstantCommand(hatchSubsystem::releaseHatch, hatchSubsystem),
-
-        // Drive backward the specified distance
-        new FunctionalCommand(
-            // Reset encoders on command start
-            driveSubsystem::resetEncoders,
-            // Drive backward while the command is executing
-            () -> driveSubsystem.arcadeDrive(-AutoConstants.kAutoDriveSpeed, 0),
-            // Stop driving at the end of the command
-            interrupt -> driveSubsystem.arcadeDrive(0, 0),
-            // End the command when the robot's driven distance exceeds the desired value
-            () ->
-                driveSubsystem.getAverageEncoderDistance()
-                    <= AutoConstants.kAutoBackupDistanceInches,
-            // Require the drive subsystem
-            driveSubsystem));
-  }
-}
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/subsystems/HatchSubsystem.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/subsystems/HatchSubsystem.java
index fc508f3..b875f2c 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/subsystems/HatchSubsystem.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/subsystems/HatchSubsystem.java
@@ -10,6 +10,7 @@
 import edu.wpi.first.wpilibj.DoubleSolenoid;
 import edu.wpi.first.wpilibj.PneumaticsModuleType;
 import edu.wpi.first.wpilibj.examples.hatchbotinlined.Constants.HatchConstants;
+import edu.wpi.first.wpilibj2.command.CommandBase;
 import edu.wpi.first.wpilibj2.command.SubsystemBase;
 
 /** A hatch mechanism actuated by a single {@link edu.wpi.first.wpilibj.DoubleSolenoid}. */
@@ -21,12 +22,14 @@
           HatchConstants.kHatchSolenoidPorts[1]);
 
   /** Grabs the hatch. */
-  public void grabHatch() {
-    m_hatchSolenoid.set(kForward);
+  public CommandBase grabHatchCommand() {
+    // implicitly require `this`
+    return this.runOnce(() -> m_hatchSolenoid.set(kForward));
   }
 
   /** Releases the hatch. */
-  public void releaseHatch() {
-    m_hatchSolenoid.set(kReverse);
+  public CommandBase releaseHatchCommand() {
+    // implicitly require `this`
+    return this.runOnce(() -> m_hatchSolenoid.set(kReverse));
   }
 }
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/RobotContainer.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/RobotContainer.java
index 1f1024f..19fc2c7 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/RobotContainer.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/RobotContainer.java
@@ -60,7 +60,9 @@
         // A split-stick arcade command, with forward/backward controlled by the left
         // hand, and turning controlled by the right.
         new DefaultDrive(
-            m_robotDrive, m_driverController::getLeftY, m_driverController::getRightX));
+            m_robotDrive,
+            () -> -m_driverController.getLeftY(),
+            () -> -m_driverController.getRightX()));
 
     // Add commands to the autonomous command chooser
     m_chooser.setDefaultOption("Simple Auto", m_simpleAuto);
@@ -78,14 +80,13 @@
    */
   private void configureButtonBindings() {
     // Grab the hatch when the 'A' button is pressed.
-    new JoystickButton(m_driverController, Button.kA.value)
-        .whenPressed(new GrabHatch(m_hatchSubsystem));
+    new JoystickButton(m_driverController, Button.kA.value).onTrue(new GrabHatch(m_hatchSubsystem));
     // Release the hatch when the 'B' button is pressed.
     new JoystickButton(m_driverController, Button.kB.value)
-        .whenPressed(new ReleaseHatch(m_hatchSubsystem));
+        .onTrue(new ReleaseHatch(m_hatchSubsystem));
     // While holding the shoulder button, drive at half speed
     new JoystickButton(m_driverController, Button.kRightBumper.value)
-        .whenHeld(new HalveDriveSpeed(m_robotDrive));
+        .whileTrue(new HalveDriveSpeed(m_robotDrive));
   }
 
   /**
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumbot/Drivetrain.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumbot/Drivetrain.java
index 9210265..8849598 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumbot/Drivetrain.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumbot/Drivetrain.java
@@ -10,6 +10,7 @@
 import edu.wpi.first.math.kinematics.ChassisSpeeds;
 import edu.wpi.first.math.kinematics.MecanumDriveKinematics;
 import edu.wpi.first.math.kinematics.MecanumDriveOdometry;
+import edu.wpi.first.math.kinematics.MecanumDriveWheelPositions;
 import edu.wpi.first.math.kinematics.MecanumDriveWheelSpeeds;
 import edu.wpi.first.wpilibj.AnalogGyro;
 import edu.wpi.first.wpilibj.Encoder;
@@ -48,7 +49,7 @@
           m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation, m_backRightLocation);
 
   private final MecanumDriveOdometry m_odometry =
-      new MecanumDriveOdometry(m_kinematics, m_gyro.getRotation2d());
+      new MecanumDriveOdometry(m_kinematics, m_gyro.getRotation2d(), getCurrentDistances());
 
   // Gains are for example purposes only - must be determined for your own robot!
   private final SimpleMotorFeedforward m_feedforward = new SimpleMotorFeedforward(1, 3);
@@ -77,6 +78,19 @@
   }
 
   /**
+   * Returns the current distances measured by the drivetrain.
+   *
+   * @return The current distances measured by the drivetrain.
+   */
+  public MecanumDriveWheelPositions getCurrentDistances() {
+    return new MecanumDriveWheelPositions(
+        m_frontLeftEncoder.getDistance(),
+        m_frontRightEncoder.getDistance(),
+        m_backLeftEncoder.getDistance(),
+        m_backRightEncoder.getDistance());
+  }
+
+  /**
    * Set the desired speeds for each wheel.
    *
    * @param speeds The desired wheel speeds.
@@ -114,7 +128,6 @@
    * @param rot Angular rate of the robot.
    * @param fieldRelative Whether the provided x and y speeds are relative to the field.
    */
-  @SuppressWarnings("ParameterName")
   public void drive(double xSpeed, double ySpeed, double rot, boolean fieldRelative) {
     var mecanumDriveWheelSpeeds =
         m_kinematics.toWheelSpeeds(
@@ -127,6 +140,6 @@
 
   /** Updates the field relative position of the robot. */
   public void updateOdometry() {
-    m_odometry.update(m_gyro.getRotation2d(), getCurrentState());
+    m_odometry.update(m_gyro.getRotation2d(), getCurrentDistances());
   }
 }
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/RobotContainer.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/RobotContainer.java
index 0d36a94..bab80b6 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/RobotContainer.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/RobotContainer.java
@@ -19,6 +19,7 @@
 import edu.wpi.first.wpilibj.examples.mecanumcontrollercommand.Constants.OIConstants;
 import edu.wpi.first.wpilibj.examples.mecanumcontrollercommand.subsystems.DriveSubsystem;
 import edu.wpi.first.wpilibj2.command.Command;
+import edu.wpi.first.wpilibj2.command.InstantCommand;
 import edu.wpi.first.wpilibj2.command.MecanumControllerCommand;
 import edu.wpi.first.wpilibj2.command.RunCommand;
 import edu.wpi.first.wpilibj2.command.button.JoystickButton;
@@ -50,9 +51,9 @@
         new RunCommand(
             () ->
                 m_robotDrive.drive(
-                    m_driverController.getLeftY(),
-                    m_driverController.getRightX(),
-                    m_driverController.getLeftX(),
+                    -m_driverController.getLeftY(),
+                    -m_driverController.getRightX(),
+                    -m_driverController.getLeftX(),
                     false),
             m_robotDrive));
   }
@@ -66,8 +67,8 @@
   private void configureButtonBindings() {
     // Drive at half speed when the right bumper is held
     new JoystickButton(m_driverController, Button.kRightBumper.value)
-        .whenPressed(() -> m_robotDrive.setMaxOutput(0.5))
-        .whenReleased(() -> m_robotDrive.setMaxOutput(1));
+        .onTrue(new InstantCommand(() -> m_robotDrive.setMaxOutput(0.5)))
+        .onFalse(new InstantCommand(() -> m_robotDrive.setMaxOutput(1)));
   }
 
   /**
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/subsystems/DriveSubsystem.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/subsystems/DriveSubsystem.java
index 7874d82..50a23cd 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/subsystems/DriveSubsystem.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/subsystems/DriveSubsystem.java
@@ -7,6 +7,7 @@
 import edu.wpi.first.math.geometry.Pose2d;
 import edu.wpi.first.math.kinematics.MecanumDriveMotorVoltages;
 import edu.wpi.first.math.kinematics.MecanumDriveOdometry;
+import edu.wpi.first.math.kinematics.MecanumDriveWheelPositions;
 import edu.wpi.first.math.kinematics.MecanumDriveWheelSpeeds;
 import edu.wpi.first.wpilibj.ADXRS450_Gyro;
 import edu.wpi.first.wpilibj.Encoder;
@@ -58,7 +59,10 @@
 
   // Odometry class for tracking robot pose
   MecanumDriveOdometry m_odometry =
-      new MecanumDriveOdometry(DriveConstants.kDriveKinematics, m_gyro.getRotation2d());
+      new MecanumDriveOdometry(
+          DriveConstants.kDriveKinematics,
+          m_gyro.getRotation2d(),
+          new MecanumDriveWheelPositions());
 
   /** Creates a new DriveSubsystem. */
   public DriveSubsystem() {
@@ -77,13 +81,7 @@
   @Override
   public void periodic() {
     // Update the odometry in the periodic block
-    m_odometry.update(
-        m_gyro.getRotation2d(),
-        new MecanumDriveWheelSpeeds(
-            m_frontLeftEncoder.getRate(),
-            m_rearLeftEncoder.getRate(),
-            m_frontRightEncoder.getRate(),
-            m_rearRightEncoder.getRate()));
+    m_odometry.update(m_gyro.getRotation2d(), getCurrentWheelDistances());
   }
 
   /**
@@ -101,7 +99,7 @@
    * @param pose The pose to which to set the odometry.
    */
   public void resetOdometry(Pose2d pose) {
-    m_odometry.resetPosition(pose, m_gyro.getRotation2d());
+    m_odometry.resetPosition(m_gyro.getRotation2d(), getCurrentWheelDistances(), pose);
   }
 
   /**
@@ -113,10 +111,9 @@
    * @param rot Angular rate of the robot.
    * @param fieldRelative Whether the provided x and y speeds are relative to the field.
    */
-  @SuppressWarnings("ParameterName")
   public void drive(double xSpeed, double ySpeed, double rot, boolean fieldRelative) {
     if (fieldRelative) {
-      m_drive.driveCartesian(ySpeed, xSpeed, rot, -m_gyro.getAngle());
+      m_drive.driveCartesian(ySpeed, xSpeed, rot, m_gyro.getRotation2d());
     } else {
       m_drive.driveCartesian(ySpeed, xSpeed, rot);
     }
@@ -188,6 +185,19 @@
   }
 
   /**
+   * Gets the current wheel distance measurements.
+   *
+   * @return the current wheel distance measurements in a MecanumDriveWheelPositions object.
+   */
+  public MecanumDriveWheelPositions getCurrentWheelDistances() {
+    return new MecanumDriveWheelPositions(
+        m_frontLeftEncoder.getDistance(),
+        m_rearLeftEncoder.getDistance(),
+        m_frontRightEncoder.getDistance(),
+        m_rearRightEncoder.getDistance());
+  }
+
+  /**
    * Sets the max output of the drive. Useful for scaling the drive to drive more slowly.
    *
    * @param maxOutput the maximum output to which the drive will be constrained
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdrive/Robot.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdrive/Robot.java
index 1029f0f..c681a86 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdrive/Robot.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdrive/Robot.java
@@ -40,8 +40,8 @@
 
   @Override
   public void teleopPeriodic() {
-    // Use the joystick X axis for lateral movement, Y axis for forward
+    // Use the joystick X axis for forward movement, Y axis for lateral
     // movement, and Z axis for rotation.
-    m_robotDrive.driveCartesian(-m_stick.getY(), m_stick.getX(), m_stick.getZ(), 0.0);
+    m_robotDrive.driveCartesian(-m_stick.getY(), -m_stick.getX(), -m_stick.getZ());
   }
 }
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdriveposeestimator/Drivetrain.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdriveposeestimator/Drivetrain.java
index 427284f..299fe68 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdriveposeestimator/Drivetrain.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdriveposeestimator/Drivetrain.java
@@ -12,6 +12,7 @@
 import edu.wpi.first.math.geometry.Translation2d;
 import edu.wpi.first.math.kinematics.ChassisSpeeds;
 import edu.wpi.first.math.kinematics.MecanumDriveKinematics;
+import edu.wpi.first.math.kinematics.MecanumDriveWheelPositions;
 import edu.wpi.first.math.kinematics.MecanumDriveWheelSpeeds;
 import edu.wpi.first.math.util.Units;
 import edu.wpi.first.wpilibj.AnalogGyro;
@@ -55,11 +56,11 @@
   below are robot specific, and should be tuned. */
   private final MecanumDrivePoseEstimator m_poseEstimator =
       new MecanumDrivePoseEstimator(
-          m_gyro.getRotation2d(),
-          new Pose2d(),
           m_kinematics,
+          m_gyro.getRotation2d(),
+          getCurrentDistances(),
+          new Pose2d(),
           VecBuilder.fill(0.05, 0.05, Units.degreesToRadians(5)),
-          VecBuilder.fill(Units.degreesToRadians(0.01)),
           VecBuilder.fill(0.5, 0.5, Units.degreesToRadians(30)));
 
   // Gains are for example purposes only - must be determined for your own robot!
@@ -89,6 +90,19 @@
   }
 
   /**
+   * Returns the current distances measured by the drivetrain.
+   *
+   * @return The current distances measured by the drivetrain.
+   */
+  public MecanumDriveWheelPositions getCurrentDistances() {
+    return new MecanumDriveWheelPositions(
+        m_frontLeftEncoder.getDistance(),
+        m_frontRightEncoder.getDistance(),
+        m_backLeftEncoder.getDistance(),
+        m_backRightEncoder.getDistance());
+  }
+
+  /**
    * Set the desired speeds for each wheel.
    *
    * @param speeds The desired wheel speeds.
@@ -126,7 +140,6 @@
    * @param rot Angular rate of the robot.
    * @param fieldRelative Whether the provided x and y speeds are relative to the field.
    */
-  @SuppressWarnings("ParameterName")
   public void drive(double xSpeed, double ySpeed, double rot, boolean fieldRelative) {
     var mecanumDriveWheelSpeeds =
         m_kinematics.toWheelSpeeds(
@@ -139,7 +152,7 @@
 
   /** Updates the field relative position of the robot. */
   public void updateOdometry() {
-    m_poseEstimator.update(m_gyro.getRotation2d(), getCurrentState());
+    m_poseEstimator.update(m_gyro.getRotation2d(), getCurrentDistances());
 
     // Also apply vision measurements. We use 0.3 seconds in the past as an example -- on
     // a real robot, this must be calculated based either on latency or timestamps.
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrol/Robot.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrol/Robot.java
index 9976381..82ced20 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrol/Robot.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrol/Robot.java
@@ -4,29 +4,50 @@
 
 package edu.wpi.first.wpilibj.examples.motorcontrol;
 
+import edu.wpi.first.wpilibj.Encoder;
 import edu.wpi.first.wpilibj.Joystick;
 import edu.wpi.first.wpilibj.TimedRobot;
 import edu.wpi.first.wpilibj.motorcontrol.MotorController;
 import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
+import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
 
 /**
  * This sample program shows how to control a motor using a joystick. In the operator control part
  * of the program, the joystick is read and the value is written to the motor.
  *
- * <p>Joystick analog values range from -1 to 1 and speed controller inputs also range from -1 to 1
+ * <p>Joystick analog values range from -1 to 1 and motor controller inputs also range from -1 to 1
  * making it easy to work together.
+ *
+ * <p>In addition, the encoder value of an encoder connected to ports 0 and 1 is consistently sent
+ * to the Dashboard.
  */
 public class Robot extends TimedRobot {
   private static final int kMotorPort = 0;
   private static final int kJoystickPort = 0;
+  private static final int kEncoderPortA = 0;
+  private static final int kEncoderPortB = 1;
 
   private MotorController m_motor;
   private Joystick m_joystick;
+  private Encoder m_encoder;
 
   @Override
   public void robotInit() {
     m_motor = new PWMSparkMax(kMotorPort);
     m_joystick = new Joystick(kJoystickPort);
+    m_encoder = new Encoder(kEncoderPortA, kEncoderPortB);
+    // Use SetDistancePerPulse to set the multiplier for GetDistance
+    // This is set up assuming a 6 inch wheel with a 360 CPR encoder.
+    m_encoder.setDistancePerPulse((Math.PI * 6) / 360.0);
+  }
+
+  /*
+   * The RobotPeriodic function is called every control packet no matter the
+   * robot mode.
+   */
+  @Override
+  public void robotPeriodic() {
+    SmartDashboard.putNumber("Encoder", m_encoder.getDistance());
   }
 
   @Override
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrolencoder/Main.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrolencoder/Main.java
deleted file mode 100644
index 0ca48f6..0000000
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrolencoder/Main.java
+++ /dev/null
@@ -1,25 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.examples.motorcontrolencoder;
-
-import edu.wpi.first.wpilibj.RobotBase;
-
-/**
- * Do NOT add any static variables to this class, or any initialization at all. Unless you know what
- * you are doing, do not modify this file except to change the parameter class to the startRobot
- * call.
- */
-public final class Main {
-  private Main() {}
-
-  /**
-   * Main initialization function. Do not perform any initialization here.
-   *
-   * <p>If you change your main robot class, change the parameter type.
-   */
-  public static void main(String... args) {
-    RobotBase.startRobot(Robot::new);
-  }
-}
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrolencoder/Robot.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrolencoder/Robot.java
deleted file mode 100644
index 9b68965..0000000
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrolencoder/Robot.java
+++ /dev/null
@@ -1,57 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.examples.motorcontrolencoder;
-
-import edu.wpi.first.wpilibj.Encoder;
-import edu.wpi.first.wpilibj.Joystick;
-import edu.wpi.first.wpilibj.TimedRobot;
-import edu.wpi.first.wpilibj.motorcontrol.MotorController;
-import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
-import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
-
-/**
- * This sample program shows how to control a motor using a joystick. In the operator control part
- * of the program, the joystick is read and the value is written to the motor.
- *
- * <p>Joystick analog values range from -1 to 1 and speed controller inputs also range from -1 to 1
- * making it easy to work together.
- *
- * <p>In addition, the encoder value of an encoder connected to ports 0 and 1 is consistently sent
- * to the Dashboard.
- */
-public class Robot extends TimedRobot {
-  private static final int kMotorPort = 0;
-  private static final int kJoystickPort = 0;
-  private static final int kEncoderPortA = 0;
-  private static final int kEncoderPortB = 1;
-
-  private MotorController m_motor;
-  private Joystick m_joystick;
-  private Encoder m_encoder;
-
-  @Override
-  public void robotInit() {
-    m_motor = new PWMSparkMax(kMotorPort);
-    m_joystick = new Joystick(kJoystickPort);
-    m_encoder = new Encoder(kEncoderPortA, kEncoderPortB);
-    // Use SetDistancePerPulse to set the multiplier for GetDistance
-    // This is set up assuming a 6 inch wheel with a 360 CPR encoder.
-    m_encoder.setDistancePerPulse((Math.PI * 6) / 360.0);
-  }
-
-  /*
-   * The RobotPeriodic function is called every control packet no matter the
-   * robot mode.
-   */
-  @Override
-  public void robotPeriodic() {
-    SmartDashboard.putNumber("Encoder", m_encoder.getDistance());
-  }
-
-  @Override
-  public void teleopPeriodic() {
-    m_motor.set(m_joystick.getY());
-  }
-}
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/Constants.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/Constants.java
index b63766c..d5140ee 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/Constants.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/Constants.java
@@ -55,7 +55,7 @@
 
   public static final class AutoConstants {
     public static final double kMaxSpeedMetersPerSecond = 3;
-    public static final double kMaxAccelerationMetersPerSecondSquared = 3;
+    public static final double kMaxAccelerationMetersPerSecondSquared = 1;
 
     // Reasonable baseline values for a RAMSETE follower in units of meters and seconds
     public static final double kRamseteB = 2;
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/RobotContainer.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/RobotContainer.java
index 5df8d2f..9f0980a 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/RobotContainer.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/RobotContainer.java
@@ -22,6 +22,7 @@
 import edu.wpi.first.wpilibj.examples.ramsetecommand.Constants.OIConstants;
 import edu.wpi.first.wpilibj.examples.ramsetecommand.subsystems.DriveSubsystem;
 import edu.wpi.first.wpilibj2.command.Command;
+import edu.wpi.first.wpilibj2.command.InstantCommand;
 import edu.wpi.first.wpilibj2.command.RamseteCommand;
 import edu.wpi.first.wpilibj2.command.RunCommand;
 import edu.wpi.first.wpilibj2.command.button.JoystickButton;
@@ -53,7 +54,7 @@
         new RunCommand(
             () ->
                 m_robotDrive.arcadeDrive(
-                    -m_driverController.getLeftY(), m_driverController.getRightX()),
+                    -m_driverController.getLeftY(), -m_driverController.getRightX()),
             m_robotDrive));
   }
 
@@ -66,8 +67,8 @@
   private void configureButtonBindings() {
     // Drive at half speed when the right bumper is held
     new JoystickButton(m_driverController, Button.kRightBumper.value)
-        .whenPressed(() -> m_robotDrive.setMaxOutput(0.5))
-        .whenReleased(() -> m_robotDrive.setMaxOutput(1));
+        .onTrue(new InstantCommand(() -> m_robotDrive.setMaxOutput(0.5)))
+        .onFalse(new InstantCommand(() -> m_robotDrive.setMaxOutput(1)));
   }
 
   /**
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/subsystems/DriveSubsystem.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/subsystems/DriveSubsystem.java
index b2fe2f7..90625ce 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/subsystems/DriveSubsystem.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/subsystems/DriveSubsystem.java
@@ -64,7 +64,9 @@
     m_rightEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse);
 
     resetEncoders();
-    m_odometry = new DifferentialDriveOdometry(m_gyro.getRotation2d());
+    m_odometry =
+        new DifferentialDriveOdometry(
+            m_gyro.getRotation2d(), m_leftEncoder.getDistance(), m_rightEncoder.getDistance());
   }
 
   @Override
@@ -99,7 +101,8 @@
    */
   public void resetOdometry(Pose2d pose) {
     resetEncoders();
-    m_odometry.resetPosition(pose, m_gyro.getRotation2d());
+    m_odometry.resetPosition(
+        m_gyro.getRotation2d(), m_leftEncoder.getDistance(), m_rightEncoder.getDistance(), pose);
   }
 
   /**
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecontroller/Drivetrain.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecontroller/Drivetrain.java
index e119080..69288a1 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecontroller/Drivetrain.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecontroller/Drivetrain.java
@@ -73,7 +73,9 @@
     m_leftEncoder.reset();
     m_rightEncoder.reset();
 
-    m_odometry = new DifferentialDriveOdometry(m_gyro.getRotation2d());
+    m_odometry =
+        new DifferentialDriveOdometry(
+            m_gyro.getRotation2d(), m_leftEncoder.getDistance(), m_rightEncoder.getDistance());
   }
 
   /**
@@ -99,7 +101,6 @@
    * @param xSpeed Linear velocity in m/s.
    * @param rot Angular velocity in rad/s.
    */
-  @SuppressWarnings("ParameterName")
   public void drive(double xSpeed, double rot) {
     var wheelSpeeds = m_kinematics.toWheelSpeeds(new ChassisSpeeds(xSpeed, 0.0, rot));
     setSpeeds(wheelSpeeds);
@@ -117,7 +118,8 @@
    * @param pose The position to reset to.
    */
   public void resetOdometry(Pose2d pose) {
-    m_odometry.resetPosition(pose, m_gyro.getRotation2d());
+    m_odometry.resetPosition(
+        m_gyro.getRotation2d(), m_leftEncoder.getDistance(), m_rightEncoder.getDistance(), pose);
   }
 
   /**
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/Constants.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/Constants.java
new file mode 100644
index 0000000..6ee700c
--- /dev/null
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/Constants.java
@@ -0,0 +1,83 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj.examples.rapidreactcommandbot;
+
+import edu.wpi.first.math.util.Units;
+
+/**
+ * The Constants class provides a convenient place for teams to hold robot-wide numerical or boolean
+ * constants. This class should not be used for any other purpose. All constants should be declared
+ * globally (i.e. public static). Do not put anything functional in this class.
+ *
+ * <p>It is advised to statically import this class (or one of its inner classes) wherever the
+ * constants are needed, to reduce verbosity.
+ */
+public final class Constants {
+  public static final class DriveConstants {
+    public static final int kLeftMotor1Port = 0;
+    public static final int kLeftMotor2Port = 1;
+    public static final int kRightMotor1Port = 2;
+    public static final int kRightMotor2Port = 3;
+
+    public static final int[] kLeftEncoderPorts = {0, 1};
+    public static final int[] kRightEncoderPorts = {2, 3};
+    public static final boolean kLeftEncoderReversed = false;
+    public static final boolean kRightEncoderReversed = true;
+
+    public static final int kEncoderCPR = 1024;
+    public static final double kWheelDiameterMeters = Units.inchesToMeters(6);
+    public static final double kEncoderDistancePerPulse =
+        // Assumes the encoders are directly mounted on the wheel shafts
+        (kWheelDiameterMeters * Math.PI) / (double) kEncoderCPR;
+  }
+
+  public static final class ShooterConstants {
+    public static final int[] kEncoderPorts = {4, 5};
+    public static final boolean kEncoderReversed = false;
+    public static final int kEncoderCPR = 1024;
+    public static final double kEncoderDistancePerPulse =
+        // Distance units will be rotations
+        1.0 / (double) kEncoderCPR;
+
+    public static final int kShooterMotorPort = 4;
+    public static final int kFeederMotorPort = 5;
+
+    public static final double kShooterFreeRPS = 5300;
+    public static final double kShooterTargetRPS = 4000;
+    public static final double kShooterToleranceRPS = 50;
+
+    // These are not real PID gains, and will have to be tuned for your specific robot.
+    public static final double kP = 1;
+
+    // On a real robot the feedforward constants should be empirically determined; these are
+    // reasonable guesses.
+    public static final double kSVolts = 0.05;
+    public static final double kVVoltSecondsPerRotation =
+        // Should have value 12V at free speed...
+        12.0 / kShooterFreeRPS;
+
+    public static final double kFeederSpeed = 0.5;
+  }
+
+  public static final class IntakeConstants {
+    public static final int kMotorPort = 6;
+    public static final int[] kSolenoidPorts = {0, 1};
+  }
+
+  public static final class StorageConstants {
+    public static final int kMotorPort = 7;
+    public static final int kBallSensorPort = 6;
+  }
+
+  public static final class AutoConstants {
+    public static final double kTimeoutSeconds = 3;
+    public static final double kDriveDistanceMeters = 2;
+    public static final double kDriveSpeed = 0.5;
+  }
+
+  public static final class OIConstants {
+    public static final int kDriverControllerPort = 0;
+  }
+}
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/Main.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/Main.java
new file mode 100644
index 0000000..b72cd91
--- /dev/null
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/Main.java
@@ -0,0 +1,25 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj.examples.rapidreactcommandbot;
+
+import edu.wpi.first.wpilibj.RobotBase;
+
+/**
+ * Do NOT add any static variables to this class, or any initialization at all. Unless you know what
+ * you are doing, do not modify this file except to change the parameter class to the startRobot
+ * call.
+ */
+public final class Main {
+  private Main() {}
+
+  /**
+   * Main initialization function. Do not perform any initialization here.
+   *
+   * <p>If you change your main robot class, change the parameter type.
+   */
+  public static void main(String... args) {
+    RobotBase.startRobot(Robot::new);
+  }
+}
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/RapidReactCommandBot.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/RapidReactCommandBot.java
new file mode 100644
index 0000000..879f2c2
--- /dev/null
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/RapidReactCommandBot.java
@@ -0,0 +1,85 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj.examples.rapidreactcommandbot;
+
+import static edu.wpi.first.wpilibj2.command.Commands.parallel;
+
+import edu.wpi.first.wpilibj.examples.rapidreactcommandbot.Constants.AutoConstants;
+import edu.wpi.first.wpilibj.examples.rapidreactcommandbot.Constants.OIConstants;
+import edu.wpi.first.wpilibj.examples.rapidreactcommandbot.Constants.ShooterConstants;
+import edu.wpi.first.wpilibj.examples.rapidreactcommandbot.subsystems.Drive;
+import edu.wpi.first.wpilibj.examples.rapidreactcommandbot.subsystems.Intake;
+import edu.wpi.first.wpilibj.examples.rapidreactcommandbot.subsystems.Shooter;
+import edu.wpi.first.wpilibj.examples.rapidreactcommandbot.subsystems.Storage;
+import edu.wpi.first.wpilibj2.command.CommandBase;
+import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
+import edu.wpi.first.wpilibj2.command.button.Trigger;
+
+/**
+ * This class is where the bulk of the robot should be declared. Since Command-based is a
+ * "declarative" paradigm, very little robot logic should actually be handled in the {@link Robot}
+ * periodic methods (other than the scheduler calls). Instead, the structure of the robot (including
+ * subsystems, commands, and button mappings) should be declared here.
+ */
+public class RapidReactCommandBot {
+  // The robot's subsystems
+  private final Drive m_drive = new Drive();
+  private final Intake m_intake = new Intake();
+  private final Storage m_storage = new Storage();
+  private final Shooter m_shooter = new Shooter();
+
+  // The driver's controller
+  CommandXboxController m_driverController =
+      new CommandXboxController(OIConstants.kDriverControllerPort);
+
+  /**
+   * Use this method to define bindings between conditions and commands. These are useful for
+   * automating robot behaviors based on button and sensor input.
+   *
+   * <p>Should be called during {@link Robot#robotInit()}.
+   *
+   * <p>Event binding methods are available on the {@link Trigger} class.
+   */
+  public void configureBindings() {
+    // Automatically run the storage motor whenever the ball storage is not full,
+    // and turn it off whenever it fills.
+    new Trigger(m_storage::isFull).whileFalse(m_storage.runCommand());
+
+    // Automatically disable and retract the intake whenever the ball storage is full.
+    new Trigger(m_storage::isFull).onTrue(m_intake.retractCommand());
+
+    // Control the drive with split-stick arcade controls
+    m_drive.setDefaultCommand(
+        m_drive.arcadeDriveCommand(
+            () -> -m_driverController.getLeftY(), () -> -m_driverController.getRightX()));
+
+    // Deploy the intake with the X button
+    m_driverController.x().onTrue(m_intake.intakeCommand());
+    // Retract the intake with the Y button
+    m_driverController.y().onTrue(m_intake.retractCommand());
+
+    // Fire the shooter with the A button
+    m_driverController
+        .a()
+        .onTrue(
+            parallel(
+                    m_shooter.shootCommand(ShooterConstants.kShooterTargetRPS),
+                    m_storage.runCommand())
+                // Since we composed this inline we should give it a name
+                .withName("Shoot"));
+  }
+
+  /**
+   * Use this to define the command that runs during autonomous.
+   *
+   * <p>Scheduled during {@link Robot#autonomousInit()}.
+   */
+  public CommandBase getAutonomousCommand() {
+    // Drive forward for 2 meters at half speed with a 3 second timeout
+    return m_drive
+        .driveDistanceCommand(AutoConstants.kDriveDistanceMeters, AutoConstants.kDriveSpeed)
+        .withTimeout(AutoConstants.kTimeoutSeconds);
+  }
+}
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/Robot.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/Robot.java
new file mode 100644
index 0000000..3588677
--- /dev/null
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/Robot.java
@@ -0,0 +1,92 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj.examples.rapidreactcommandbot;
+
+import edu.wpi.first.wpilibj.TimedRobot;
+import edu.wpi.first.wpilibj2.command.Command;
+import edu.wpi.first.wpilibj2.command.CommandScheduler;
+
+/**
+ * The VM is configured to automatically run this class, and to call the functions corresponding to
+ * each mode, as described in the TimedRobot documentation. If you change the name of this class or
+ * the package after creating this project, you must also update the build.gradle file in the
+ * project.
+ */
+public class Robot extends TimedRobot {
+  private Command m_autonomousCommand;
+
+  private final RapidReactCommandBot m_robot = new RapidReactCommandBot();
+
+  /**
+   * This function is run when the robot is first started up and should be used for any
+   * initialization code.
+   */
+  @Override
+  public void robotInit() {
+    // Configure default commands and condition bindings on robot startup
+    m_robot.configureBindings();
+  }
+
+  /**
+   * This function is called every robot packet, no matter the mode. Use this for items like
+   * diagnostics that you want ran during disabled, autonomous, teleoperated and test.
+   *
+   * <p>This runs after the mode specific periodic functions, but before LiveWindow and
+   * SmartDashboard integrated updating.
+   */
+  @Override
+  public void robotPeriodic() {
+    // Runs the Scheduler.  This is responsible for polling buttons, adding newly-scheduled
+    // commands, running already-scheduled commands, removing finished or interrupted commands,
+    // and running subsystem periodic() methods.  This must be called from the robot's periodic
+    // block in order for anything in the Command-based framework to work.
+    CommandScheduler.getInstance().run();
+  }
+
+  /** This function is called once each time the robot enters Disabled mode. */
+  @Override
+  public void disabledInit() {}
+
+  @Override
+  public void disabledPeriodic() {}
+
+  @Override
+  public void autonomousInit() {
+    m_autonomousCommand = m_robot.getAutonomousCommand();
+
+    if (m_autonomousCommand != null) {
+      m_autonomousCommand.schedule();
+    }
+  }
+
+  /** This function is called periodically during autonomous. */
+  @Override
+  public void autonomousPeriodic() {}
+
+  @Override
+  public void teleopInit() {
+    // This makes sure that the autonomous stops running when
+    // teleop starts running. If you want the autonomous to
+    // continue until interrupted by another command, remove
+    // this line or comment it out.
+    if (m_autonomousCommand != null) {
+      m_autonomousCommand.cancel();
+    }
+  }
+
+  /** This function is called periodically during operator control. */
+  @Override
+  public void teleopPeriodic() {}
+
+  @Override
+  public void testInit() {
+    // Cancels all running commands at the start of test mode.
+    CommandScheduler.getInstance().cancelAll();
+  }
+
+  /** This function is called periodically during test mode. */
+  @Override
+  public void testPeriodic() {}
+}
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Drive.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Drive.java
new file mode 100644
index 0000000..eaaa8ad
--- /dev/null
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Drive.java
@@ -0,0 +1,94 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj.examples.rapidreactcommandbot.subsystems;
+
+import edu.wpi.first.wpilibj.Encoder;
+import edu.wpi.first.wpilibj.drive.DifferentialDrive;
+import edu.wpi.first.wpilibj.examples.rapidreactcommandbot.Constants.DriveConstants;
+import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
+import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
+import edu.wpi.first.wpilibj2.command.CommandBase;
+import edu.wpi.first.wpilibj2.command.SubsystemBase;
+import java.util.function.DoubleSupplier;
+
+public class Drive extends SubsystemBase {
+  // The motors on the left side of the drive.
+  private final MotorControllerGroup m_leftMotors =
+      new MotorControllerGroup(
+          new PWMSparkMax(DriveConstants.kLeftMotor1Port),
+          new PWMSparkMax(DriveConstants.kLeftMotor2Port));
+
+  // The motors on the right side of the drive.
+  private final MotorControllerGroup m_rightMotors =
+      new MotorControllerGroup(
+          new PWMSparkMax(DriveConstants.kRightMotor1Port),
+          new PWMSparkMax(DriveConstants.kRightMotor2Port));
+
+  // The robot's drive
+  private final DifferentialDrive m_drive = new DifferentialDrive(m_leftMotors, m_rightMotors);
+
+  // The left-side drive encoder
+  private final Encoder m_leftEncoder =
+      new Encoder(
+          DriveConstants.kLeftEncoderPorts[0],
+          DriveConstants.kLeftEncoderPorts[1],
+          DriveConstants.kLeftEncoderReversed);
+
+  // The right-side drive encoder
+  private final Encoder m_rightEncoder =
+      new Encoder(
+          DriveConstants.kRightEncoderPorts[0],
+          DriveConstants.kRightEncoderPorts[1],
+          DriveConstants.kRightEncoderReversed);
+
+  /** Creates a new Drive subsystem. */
+  public Drive() {
+    // We need to invert one side of the drivetrain so that positive voltages
+    // result in both sides moving forward. Depending on how your robot's
+    // gearbox is constructed, you might have to invert the left side instead.
+    m_rightMotors.setInverted(true);
+
+    // Sets the distance per pulse for the encoders
+    m_leftEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse);
+    m_rightEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse);
+  }
+
+  /**
+   * Returns a command that drives the robot with arcade controls.
+   *
+   * @param fwd the commanded forward movement
+   * @param rot the commanded rotation
+   */
+  public CommandBase arcadeDriveCommand(DoubleSupplier fwd, DoubleSupplier rot) {
+    // A split-stick arcade command, with forward/backward controlled by the left
+    // hand, and turning controlled by the right.
+    return run(() -> m_drive.arcadeDrive(fwd.getAsDouble(), rot.getAsDouble()))
+        .withName("arcadeDrive");
+  }
+
+  /**
+   * Returns a command that drives the robot forward a specified distance at a specified speed.
+   *
+   * @param distanceMeters The distance to drive forward in meters
+   * @param speed The fraction of max speed at which to drive
+   */
+  public CommandBase driveDistanceCommand(double distanceMeters, double speed) {
+    return runOnce(
+            () -> {
+              // Reset encoders at the start of the command
+              m_leftEncoder.reset();
+              m_rightEncoder.reset();
+            })
+        // Drive forward at specified speed
+        .andThen(run(() -> m_drive.arcadeDrive(speed, 0)))
+        // End command when we've traveled the specified distance
+        .until(
+            () ->
+                Math.max(m_leftEncoder.getDistance(), m_rightEncoder.getDistance())
+                    >= distanceMeters)
+        // Stop the drive when the command ends
+        .finallyDo(interrupted -> m_drive.stopMotor());
+  }
+}
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Intake.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Intake.java
new file mode 100644
index 0000000..533f596
--- /dev/null
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Intake.java
@@ -0,0 +1,39 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj.examples.rapidreactcommandbot.subsystems;
+
+import static edu.wpi.first.wpilibj.examples.rapidreactcommandbot.Constants.IntakeConstants;
+
+import edu.wpi.first.wpilibj.DoubleSolenoid;
+import edu.wpi.first.wpilibj.PneumaticsModuleType;
+import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
+import edu.wpi.first.wpilibj2.command.CommandBase;
+import edu.wpi.first.wpilibj2.command.SubsystemBase;
+
+public class Intake extends SubsystemBase {
+  private final PWMSparkMax m_motor = new PWMSparkMax(IntakeConstants.kMotorPort);
+  private final DoubleSolenoid m_pistons =
+      new DoubleSolenoid(
+          PneumaticsModuleType.REVPH,
+          IntakeConstants.kSolenoidPorts[0],
+          IntakeConstants.kSolenoidPorts[1]);
+
+  /** Returns a command that deploys the intake, and then runs the intake motor indefinitely. */
+  public CommandBase intakeCommand() {
+    return runOnce(() -> m_pistons.set(DoubleSolenoid.Value.kForward))
+        .andThen(run(() -> m_motor.set(1.0)))
+        .withName("Intake");
+  }
+
+  /** Returns a command that turns off and retracts the intake. */
+  public CommandBase retractCommand() {
+    return runOnce(
+            () -> {
+              m_motor.disable();
+              m_pistons.set(DoubleSolenoid.Value.kReverse);
+            })
+        .withName("Retract");
+  }
+}
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Shooter.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Shooter.java
new file mode 100644
index 0000000..9191fb6
--- /dev/null
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Shooter.java
@@ -0,0 +1,66 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj.examples.rapidreactcommandbot.subsystems;
+
+import static edu.wpi.first.wpilibj2.command.Commands.parallel;
+import static edu.wpi.first.wpilibj2.command.Commands.waitUntil;
+
+import edu.wpi.first.math.controller.PIDController;
+import edu.wpi.first.math.controller.SimpleMotorFeedforward;
+import edu.wpi.first.wpilibj.Encoder;
+import edu.wpi.first.wpilibj.examples.frisbeebot.Constants.ShooterConstants;
+import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
+import edu.wpi.first.wpilibj2.command.CommandBase;
+import edu.wpi.first.wpilibj2.command.SubsystemBase;
+
+public class Shooter extends SubsystemBase {
+  private final PWMSparkMax m_shooterMotor = new PWMSparkMax(ShooterConstants.kShooterMotorPort);
+  private final PWMSparkMax m_feederMotor = new PWMSparkMax(ShooterConstants.kFeederMotorPort);
+  private final Encoder m_shooterEncoder =
+      new Encoder(
+          ShooterConstants.kEncoderPorts[0],
+          ShooterConstants.kEncoderPorts[1],
+          ShooterConstants.kEncoderReversed);
+  private final SimpleMotorFeedforward m_shooterFeedforward =
+      new SimpleMotorFeedforward(
+          ShooterConstants.kSVolts, ShooterConstants.kVVoltSecondsPerRotation);
+  private final PIDController m_shooterFeedback = new PIDController(ShooterConstants.kP, 0.0, 0.0);
+
+  /** The shooter subsystem for the robot. */
+  public Shooter() {
+    m_shooterFeedback.setTolerance(ShooterConstants.kShooterToleranceRPS);
+    m_shooterEncoder.setDistancePerPulse(ShooterConstants.kEncoderDistancePerPulse);
+
+    // Set default command to turn off both the shooter and feeder motors, and then idle
+    setDefaultCommand(
+        runOnce(
+                () -> {
+                  m_shooterMotor.disable();
+                  m_feederMotor.disable();
+                })
+            .andThen(run(() -> {}))
+            .withName("Idle"));
+  }
+
+  /**
+   * Returns a command to shoot the balls currently stored in the robot. Spins the shooter flywheel
+   * up to the specified setpoint, and then runs the feeder motor.
+   *
+   * @param setpointRotationsPerSecond The desired shooter velocity
+   */
+  public CommandBase shootCommand(double setpointRotationsPerSecond) {
+    return parallel(
+            // Run the shooter flywheel at the desired setpoint using feedforward and feedback
+            run(
+                () ->
+                    m_shooterMotor.set(
+                        m_shooterFeedforward.calculate(setpointRotationsPerSecond)
+                            + m_shooterFeedback.calculate(
+                                m_shooterEncoder.getRate(), setpointRotationsPerSecond))),
+            // Wait until the shooter has reached the setpoint, and then run the feeder
+            waitUntil(m_shooterFeedback::atSetpoint).andThen(() -> m_feederMotor.set(1)))
+        .withName("Shoot");
+  }
+}
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Storage.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Storage.java
new file mode 100644
index 0000000..9b45d66
--- /dev/null
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Storage.java
@@ -0,0 +1,33 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj.examples.rapidreactcommandbot.subsystems;
+
+import static edu.wpi.first.wpilibj.examples.rapidreactcommandbot.Constants.StorageConstants;
+
+import edu.wpi.first.wpilibj.DigitalInput;
+import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
+import edu.wpi.first.wpilibj2.command.CommandBase;
+import edu.wpi.first.wpilibj2.command.SubsystemBase;
+
+public class Storage extends SubsystemBase {
+  private final PWMSparkMax m_motor = new PWMSparkMax(StorageConstants.kMotorPort);
+  private final DigitalInput m_ballSensor = new DigitalInput(StorageConstants.kBallSensorPort);
+
+  /** Create a new Storage subsystem. */
+  public Storage() {
+    // Set default command to turn off the storage motor and then idle
+    setDefaultCommand(runOnce(m_motor::disable).andThen(run(() -> {})).withName("Idle"));
+  }
+
+  /** Whether the ball storage is full. */
+  public boolean isFull() {
+    return m_ballSensor.get();
+  }
+
+  /** Returns a command that runs the storage motor indefinitely. */
+  public CommandBase runCommand() {
+    return run(() -> m_motor.set(1)).withName("run");
+  }
+}
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/RobotContainer.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/RobotContainer.java
index 8ad7bc3..a9dcacd 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/RobotContainer.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/RobotContainer.java
@@ -17,7 +17,7 @@
 import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
 import edu.wpi.first.wpilibj2.command.Command;
 import edu.wpi.first.wpilibj2.command.PrintCommand;
-import edu.wpi.first.wpilibj2.command.button.Button;
+import edu.wpi.first.wpilibj2.command.button.Trigger;
 
 /**
  * This class is where the bulk of the robot should be declared. Since Command-based is a
@@ -65,10 +65,10 @@
     m_drivetrain.setDefaultCommand(getArcadeDriveCommand());
 
     // Example of how to use the onboard IO
-    Button onboardButtonA = new Button(m_onboardIO::getButtonAPressed);
+    Trigger onboardButtonA = new Trigger(m_onboardIO::getButtonAPressed);
     onboardButtonA
-        .whenActive(new PrintCommand("Button A Pressed"))
-        .whenInactive(new PrintCommand("Button A Released"));
+        .onTrue(new PrintCommand("Button A Pressed"))
+        .onFalse(new PrintCommand("Button A Released"));
 
     // Setup SmartDashboard options
     m_chooser.setDefaultOption("Auto Routine Distance", new AutonomousDistance(m_drivetrain));
@@ -92,6 +92,6 @@
    */
   public Command getArcadeDriveCommand() {
     return new ArcadeDrive(
-        m_drivetrain, () -> -m_controller.getRawAxis(1), () -> m_controller.getRawAxis(2));
+        m_drivetrain, () -> -m_controller.getRawAxis(1), () -> -m_controller.getRawAxis(2));
   }
 }
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/sensors/RomiGyro.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/sensors/RomiGyro.java
index c21f623..a0ee53d 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/sensors/RomiGyro.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/sensors/RomiGyro.java
@@ -9,12 +9,12 @@
 import edu.wpi.first.hal.SimDouble;
 
 public class RomiGyro {
-  private SimDouble m_simRateX;
-  private SimDouble m_simRateY;
-  private SimDouble m_simRateZ;
-  private SimDouble m_simAngleX;
-  private SimDouble m_simAngleY;
-  private SimDouble m_simAngleZ;
+  private final SimDouble m_simRateX;
+  private final SimDouble m_simRateY;
+  private final SimDouble m_simRateZ;
+  private final SimDouble m_simAngleX;
+  private final SimDouble m_simAngleY;
+  private final SimDouble m_simAngleZ;
 
   private double m_angleXOffset;
   private double m_angleYOffset;
@@ -32,6 +32,14 @@
       m_simAngleX = gyroSimDevice.createDouble("angle_x", Direction.kInput, 0.0);
       m_simAngleY = gyroSimDevice.createDouble("angle_y", Direction.kInput, 0.0);
       m_simAngleZ = gyroSimDevice.createDouble("angle_z", Direction.kInput, 0.0);
+    } else {
+      m_simRateX = null;
+      m_simRateY = null;
+      m_simRateZ = null;
+
+      m_simAngleX = null;
+      m_simAngleY = null;
+      m_simAngleZ = null;
     }
   }
 
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/subsystems/OnBoardIO.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/subsystems/OnBoardIO.java
index 848aff5..0199f6a 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/subsystems/OnBoardIO.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/subsystems/OnBoardIO.java
@@ -22,12 +22,12 @@
   private final DigitalOutput m_yellowLed = new DigitalOutput(3);
 
   // DIO 1
-  private DigitalInput m_buttonB;
-  private DigitalOutput m_greenLed;
+  private final DigitalInput m_buttonB;
+  private final DigitalOutput m_greenLed;
 
   // DIO 2
-  private DigitalInput m_buttonC;
-  private DigitalOutput m_redLed;
+  private final DigitalInput m_buttonC;
+  private final DigitalOutput m_redLed;
 
   private static final double MESSAGE_INTERVAL = 1.0;
   private double m_nextMessageTime;
@@ -46,13 +46,17 @@
   public OnBoardIO(ChannelMode dio1, ChannelMode dio2) {
     if (dio1 == ChannelMode.INPUT) {
       m_buttonB = new DigitalInput(1);
+      m_greenLed = null;
     } else {
+      m_buttonB = null;
       m_greenLed = new DigitalOutput(1);
     }
 
     if (dio2 == ChannelMode.INPUT) {
       m_buttonC = new DigitalInput(2);
+      m_redLed = null;
     } else {
+      m_buttonC = null;
       m_redLed = new DigitalOutput(2);
     }
   }
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/schedulereventlogging/RobotContainer.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/schedulereventlogging/RobotContainer.java
index c798600..fcb467c 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/schedulereventlogging/RobotContainer.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/schedulereventlogging/RobotContainer.java
@@ -70,11 +70,11 @@
    */
   private void configureButtonBindings() {
     // Run instant command 1 when the 'A' button is pressed
-    new JoystickButton(m_driverController, Button.kA.value).whenPressed(m_instantCommand1);
+    new JoystickButton(m_driverController, Button.kA.value).onTrue(m_instantCommand1);
     // Run instant command 2 when the 'X' button is pressed
-    new JoystickButton(m_driverController, Button.kX.value).whenPressed(m_instantCommand2);
+    new JoystickButton(m_driverController, Button.kX.value).onTrue(m_instantCommand2);
     // Run instant command 3 when the 'Y' button is held; release early to interrupt
-    new JoystickButton(m_driverController, Button.kY.value).whenHeld(m_waitCommand);
+    new JoystickButton(m_driverController, Button.kY.value).whileTrue(m_waitCommand);
   }
 
   /**
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/shuffleboard/Robot.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/shuffleboard/Robot.java
index eb6a6d9..f9991f6 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/shuffleboard/Robot.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/shuffleboard/Robot.java
@@ -4,7 +4,7 @@
 
 package edu.wpi.first.wpilibj.examples.shuffleboard;
 
-import edu.wpi.first.networktables.NetworkTableEntry;
+import edu.wpi.first.networktables.GenericEntry;
 import edu.wpi.first.wpilibj.AnalogPotentiometer;
 import edu.wpi.first.wpilibj.Encoder;
 import edu.wpi.first.wpilibj.TimedRobot;
@@ -22,7 +22,7 @@
 
   private final PWMSparkMax m_elevatorMotor = new PWMSparkMax(2);
   private final AnalogPotentiometer m_elevatorPot = new AnalogPotentiometer(0);
-  private NetworkTableEntry m_maxSpeed;
+  private GenericEntry m_maxSpeed;
 
   @Override
   public void robotInit() {
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Drivetrain.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Drivetrain.java
index 986875a..a9f53a9 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Drivetrain.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Drivetrain.java
@@ -57,7 +57,8 @@
   private final DifferentialDriveKinematics m_kinematics =
       new DifferentialDriveKinematics(kTrackWidth);
   private final DifferentialDriveOdometry m_odometry =
-      new DifferentialDriveOdometry(m_gyro.getRotation2d());
+      new DifferentialDriveOdometry(
+          m_gyro.getRotation2d(), m_leftEncoder.getDistance(), m_rightEncoder.getDistance());
 
   // Gains are for example purposes only - must be determined for your own
   // robot!
@@ -113,7 +114,6 @@
    * @param xSpeed the speed for the x axis
    * @param rot the rotation
    */
-  @SuppressWarnings("ParameterName")
   public void drive(double xSpeed, double rot) {
     setSpeeds(m_kinematics.toWheelSpeeds(new ChassisSpeeds(xSpeed, 0, rot)));
   }
@@ -129,7 +129,8 @@
     m_leftEncoder.reset();
     m_rightEncoder.reset();
     m_drivetrainSimulator.setPose(pose);
-    m_odometry.resetPosition(pose, m_gyro.getRotation2d());
+    m_odometry.resetPosition(
+        m_gyro.getRotation2d(), m_leftEncoder.getDistance(), m_rightEncoder.getDistance(), pose);
   }
 
   /** Check the current robot pose. */
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Robot.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Robot.java
index 99178d4..1beccce 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Robot.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Robot.java
@@ -32,10 +32,6 @@
 
   @Override
   public void robotInit() {
-    // Flush NetworkTables every loop. This ensures that robot pose and other values
-    // are sent during every iteration.
-    setNetworkTablesFlushEnabled(true);
-
     m_trajectory =
         TrajectoryGenerator.generateTrajectory(
             new Pose2d(2, 2, new Rotation2d()),
@@ -65,7 +61,6 @@
   }
 
   @Override
-  @SuppressWarnings("LocalVariableName")
   public void teleopPeriodic() {
     // Get the x speed. We are inverting this because Xbox controllers return
     // negative values when we push forward.
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/Robot.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/Robot.java
index 75700c4..8eca311 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/Robot.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/Robot.java
@@ -26,10 +26,6 @@
     // Instantiate our RobotContainer.  This will perform all our button bindings, and put our
     // autonomous chooser on the dashboard.
     m_robotContainer = new RobotContainer();
-
-    // Flush NetworkTables every loop. This ensures that robot pose and other values
-    // are sent during every loop iteration.
-    setNetworkTablesFlushEnabled(true);
   }
 
   @Override
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/RobotContainer.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/RobotContainer.java
index 4636c37..6cb6e02 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/RobotContainer.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/RobotContainer.java
@@ -18,6 +18,7 @@
 import edu.wpi.first.wpilibj.XboxController.Button;
 import edu.wpi.first.wpilibj.examples.statespacedifferentialdrivesimulation.subsystems.DriveSubsystem;
 import edu.wpi.first.wpilibj2.command.Command;
+import edu.wpi.first.wpilibj2.command.InstantCommand;
 import edu.wpi.first.wpilibj2.command.RamseteCommand;
 import edu.wpi.first.wpilibj2.command.RunCommand;
 import edu.wpi.first.wpilibj2.command.button.JoystickButton;
@@ -47,10 +48,13 @@
     m_robotDrive.setDefaultCommand(
         // A split-stick arcade command, with forward/backward controlled by the left
         // hand, and turning controlled by the right.
+        // If you are using the keyboard as a joystick, it is recommended that you go
+        // to the following link to read about editing the keyboard settings.
+        // https://docs.wpilib.org/en/stable/docs/software/wpilib-tools/robot-simulation/simulation-gui.html#using-the-keyboard-as-a-joystick
         new RunCommand(
             () ->
                 m_robotDrive.arcadeDrive(
-                    -m_driverController.getLeftY(), m_driverController.getRightX()),
+                    -m_driverController.getLeftY(), -m_driverController.getRightX()),
             m_robotDrive));
   }
 
@@ -63,8 +67,8 @@
   private void configureButtonBindings() {
     // Drive at half speed when the right bumper is held
     new JoystickButton(m_driverController, Button.kRightBumper.value)
-        .whenPressed(() -> m_robotDrive.setMaxOutput(0.5))
-        .whenReleased(() -> m_robotDrive.setMaxOutput(1));
+        .onTrue(new InstantCommand(() -> m_robotDrive.setMaxOutput(0.5)))
+        .onFalse(new InstantCommand(() -> m_robotDrive.setMaxOutput(1)));
   }
 
   public DriveSubsystem getRobotDrive() {
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/subsystems/DriveSubsystem.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/subsystems/DriveSubsystem.java
index e974269..406178a 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/subsystems/DriveSubsystem.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/subsystems/DriveSubsystem.java
@@ -62,11 +62,11 @@
 
   // These classes help us simulate our drivetrain
   public DifferentialDrivetrainSim m_drivetrainSimulator;
-  private EncoderSim m_leftEncoderSim;
-  private EncoderSim m_rightEncoderSim;
+  private final EncoderSim m_leftEncoderSim;
+  private final EncoderSim m_rightEncoderSim;
   // The Field2d class shows the field in the sim GUI
-  private Field2d m_fieldSim;
-  private ADXRS450_GyroSim m_gyroSim;
+  private final Field2d m_fieldSim;
+  private final ADXRS450_GyroSim m_gyroSim;
 
   /** Creates a new DriveSubsystem. */
   public DriveSubsystem() {
@@ -80,7 +80,11 @@
     m_rightEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse);
 
     resetEncoders();
-    m_odometry = new DifferentialDriveOdometry(Rotation2d.fromDegrees(getHeading()));
+    m_odometry =
+        new DifferentialDriveOdometry(
+            Rotation2d.fromDegrees(getHeading()),
+            m_leftEncoder.getDistance(),
+            m_rightEncoder.getDistance());
 
     if (RobotBase.isSimulation()) { // If our robot is simulated
       // This class simulates our drivetrain's motion around the field.
@@ -101,6 +105,12 @@
       // the Field2d class lets us visualize our robot in the simulation GUI.
       m_fieldSim = new Field2d();
       SmartDashboard.putData("Field", m_fieldSim);
+    } else {
+      m_leftEncoderSim = null;
+      m_rightEncoderSim = null;
+      m_gyroSim = null;
+
+      m_fieldSim = null;
     }
   }
 
@@ -168,7 +178,11 @@
   public void resetOdometry(Pose2d pose) {
     resetEncoders();
     m_drivetrainSimulator.setPose(pose);
-    m_odometry.resetPosition(pose, Rotation2d.fromDegrees(getHeading()));
+    m_odometry.resetPosition(
+        Rotation2d.fromDegrees(getHeading()),
+        m_leftEncoder.getDistance(),
+        m_rightEncoder.getDistance(),
+        pose);
   }
 
   /**
@@ -188,11 +202,6 @@
    * @param rightVolts the commanded right output
    */
   public void tankDriveVolts(double leftVolts, double rightVolts) {
-    var batteryVoltage = RobotController.getBatteryVoltage();
-    if (Math.max(Math.abs(leftVolts), Math.abs(rightVolts)) > batteryVoltage) {
-      leftVolts *= batteryVoltage / 12.0;
-      rightVolts *= batteryVoltage / 12.0;
-    }
     m_leftMotors.setVoltage(leftVolts);
     m_rightMotors.setVoltage(rightVolts);
     m_drive.feed();
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervebot/Drivetrain.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervebot/Drivetrain.java
index 3b71a0c..6a45f6a 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervebot/Drivetrain.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervebot/Drivetrain.java
@@ -8,6 +8,7 @@
 import edu.wpi.first.math.kinematics.ChassisSpeeds;
 import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
 import edu.wpi.first.math.kinematics.SwerveDriveOdometry;
+import edu.wpi.first.math.kinematics.SwerveModulePosition;
 import edu.wpi.first.wpilibj.AnalogGyro;
 
 /** Represents a swerve drive style drivetrain. */
@@ -32,7 +33,15 @@
           m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation, m_backRightLocation);
 
   private final SwerveDriveOdometry m_odometry =
-      new SwerveDriveOdometry(m_kinematics, m_gyro.getRotation2d());
+      new SwerveDriveOdometry(
+          m_kinematics,
+          m_gyro.getRotation2d(),
+          new SwerveModulePosition[] {
+            m_frontLeft.getPosition(),
+            m_frontRight.getPosition(),
+            m_backLeft.getPosition(),
+            m_backRight.getPosition()
+          });
 
   public Drivetrain() {
     m_gyro.reset();
@@ -46,7 +55,6 @@
    * @param rot Angular rate of the robot.
    * @param fieldRelative Whether the provided x and y speeds are relative to the field.
    */
-  @SuppressWarnings("ParameterName")
   public void drive(double xSpeed, double ySpeed, double rot, boolean fieldRelative) {
     var swerveModuleStates =
         m_kinematics.toSwerveModuleStates(
@@ -64,9 +72,11 @@
   public void updateOdometry() {
     m_odometry.update(
         m_gyro.getRotation2d(),
-        m_frontLeft.getState(),
-        m_frontRight.getState(),
-        m_backLeft.getState(),
-        m_backRight.getState());
+        new SwerveModulePosition[] {
+          m_frontLeft.getPosition(),
+          m_frontRight.getPosition(),
+          m_backLeft.getPosition(),
+          m_backRight.getPosition()
+        });
   }
 }
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervebot/SwerveModule.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervebot/SwerveModule.java
index 9749c2d..27ea37f 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervebot/SwerveModule.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervebot/SwerveModule.java
@@ -8,6 +8,7 @@
 import edu.wpi.first.math.controller.ProfiledPIDController;
 import edu.wpi.first.math.controller.SimpleMotorFeedforward;
 import edu.wpi.first.math.geometry.Rotation2d;
+import edu.wpi.first.math.kinematics.SwerveModulePosition;
 import edu.wpi.first.math.kinematics.SwerveModuleState;
 import edu.wpi.first.math.trajectory.TrapezoidProfile;
 import edu.wpi.first.wpilibj.Encoder;
@@ -72,7 +73,7 @@
     // resolution.
     m_driveEncoder.setDistancePerPulse(2 * Math.PI * kWheelRadius / kEncoderResolution);
 
-    // Set the distance (in this case, angle) per pulse for the turning encoder.
+    // Set the distance (in this case, angle) in radians per pulse for the turning encoder.
     // This is the the angle through an entire rotation (2 * pi) divided by the
     // encoder resolution.
     m_turningEncoder.setDistancePerPulse(2 * Math.PI / kEncoderResolution);
@@ -88,7 +89,18 @@
    * @return The current state of the module.
    */
   public SwerveModuleState getState() {
-    return new SwerveModuleState(m_driveEncoder.getRate(), new Rotation2d(m_turningEncoder.get()));
+    return new SwerveModuleState(
+        m_driveEncoder.getRate(), new Rotation2d(m_turningEncoder.getDistance()));
+  }
+
+  /**
+   * Returns the current position of the module.
+   *
+   * @return The current position of the module.
+   */
+  public SwerveModulePosition getPosition() {
+    return new SwerveModulePosition(
+        m_driveEncoder.getDistance(), new Rotation2d(m_turningEncoder.getDistance()));
   }
 
   /**
@@ -99,7 +111,7 @@
   public void setDesiredState(SwerveModuleState desiredState) {
     // Optimize the reference state to avoid spinning further than 90 degrees
     SwerveModuleState state =
-        SwerveModuleState.optimize(desiredState, new Rotation2d(m_turningEncoder.get()));
+        SwerveModuleState.optimize(desiredState, new Rotation2d(m_turningEncoder.getDistance()));
 
     // Calculate the drive output from the drive PID controller.
     final double driveOutput =
@@ -109,7 +121,7 @@
 
     // Calculate the turning motor output from the turning PID controller.
     final double turnOutput =
-        m_turningPIDController.calculate(m_turningEncoder.get(), state.angle.getRadians());
+        m_turningPIDController.calculate(m_turningEncoder.getDistance(), state.angle.getRadians());
 
     final double turnFeedforward =
         m_turnFeedforward.calculate(m_turningPIDController.getSetpoint().velocity);
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/DriveSubsystem.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/DriveSubsystem.java
index c0e364b..326efee 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/DriveSubsystem.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/DriveSubsystem.java
@@ -8,6 +8,7 @@
 import edu.wpi.first.math.kinematics.ChassisSpeeds;
 import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
 import edu.wpi.first.math.kinematics.SwerveDriveOdometry;
+import edu.wpi.first.math.kinematics.SwerveModulePosition;
 import edu.wpi.first.math.kinematics.SwerveModuleState;
 import edu.wpi.first.wpilibj.ADXRS450_Gyro;
 import edu.wpi.first.wpilibj.examples.swervecontrollercommand.Constants.DriveConstants;
@@ -57,7 +58,15 @@
 
   // Odometry class for tracking robot pose
   SwerveDriveOdometry m_odometry =
-      new SwerveDriveOdometry(DriveConstants.kDriveKinematics, m_gyro.getRotation2d());
+      new SwerveDriveOdometry(
+          DriveConstants.kDriveKinematics,
+          m_gyro.getRotation2d(),
+          new SwerveModulePosition[] {
+            m_frontLeft.getPosition(),
+            m_frontRight.getPosition(),
+            m_rearLeft.getPosition(),
+            m_rearRight.getPosition()
+          });
 
   /** Creates a new DriveSubsystem. */
   public DriveSubsystem() {}
@@ -67,10 +76,12 @@
     // Update the odometry in the periodic block
     m_odometry.update(
         m_gyro.getRotation2d(),
-        m_frontLeft.getState(),
-        m_frontRight.getState(),
-        m_rearLeft.getState(),
-        m_rearRight.getState());
+        new SwerveModulePosition[] {
+          m_frontLeft.getPosition(),
+          m_frontRight.getPosition(),
+          m_rearLeft.getPosition(),
+          m_rearRight.getPosition()
+        });
   }
 
   /**
@@ -88,7 +99,15 @@
    * @param pose The pose to which to set the odometry.
    */
   public void resetOdometry(Pose2d pose) {
-    m_odometry.resetPosition(pose, m_gyro.getRotation2d());
+    m_odometry.resetPosition(
+        m_gyro.getRotation2d(),
+        new SwerveModulePosition[] {
+          m_frontLeft.getPosition(),
+          m_frontRight.getPosition(),
+          m_rearLeft.getPosition(),
+          m_rearRight.getPosition()
+        },
+        pose);
   }
 
   /**
@@ -99,7 +118,6 @@
    * @param rot Angular rate of the robot.
    * @param fieldRelative Whether the provided x and y speeds are relative to the field.
    */
-  @SuppressWarnings("ParameterName")
   public void drive(double xSpeed, double ySpeed, double rot, boolean fieldRelative) {
     var swerveModuleStates =
         DriveConstants.kDriveKinematics.toSwerveModuleStates(
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/SwerveModule.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/SwerveModule.java
index 494d0ab..46825b2 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/SwerveModule.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/SwerveModule.java
@@ -7,6 +7,7 @@
 import edu.wpi.first.math.controller.PIDController;
 import edu.wpi.first.math.controller.ProfiledPIDController;
 import edu.wpi.first.math.geometry.Rotation2d;
+import edu.wpi.first.math.kinematics.SwerveModulePosition;
 import edu.wpi.first.math.kinematics.SwerveModuleState;
 import edu.wpi.first.math.trajectory.TrapezoidProfile;
 import edu.wpi.first.wpilibj.Encoder;
@@ -65,7 +66,7 @@
     // Set whether drive encoder should be reversed or not
     m_driveEncoder.setReverseDirection(driveEncoderReversed);
 
-    // Set the distance (in this case, angle) per pulse for the turning encoder.
+    // Set the distance (in this case, angle) in radians per pulse for the turning encoder.
     // This is the the angle through an entire rotation (2 * pi) divided by the
     // encoder resolution.
     m_turningEncoder.setDistancePerPulse(ModuleConstants.kTurningEncoderDistancePerPulse);
@@ -84,7 +85,18 @@
    * @return The current state of the module.
    */
   public SwerveModuleState getState() {
-    return new SwerveModuleState(m_driveEncoder.getRate(), new Rotation2d(m_turningEncoder.get()));
+    return new SwerveModuleState(
+        m_driveEncoder.getRate(), new Rotation2d(m_turningEncoder.getDistance()));
+  }
+
+  /**
+   * Returns the current position of the module.
+   *
+   * @return The current position of the module.
+   */
+  public SwerveModulePosition getPosition() {
+    return new SwerveModulePosition(
+        m_driveEncoder.getDistance(), new Rotation2d(m_turningEncoder.getDistance()));
   }
 
   /**
@@ -95,7 +107,7 @@
   public void setDesiredState(SwerveModuleState desiredState) {
     // Optimize the reference state to avoid spinning further than 90 degrees
     SwerveModuleState state =
-        SwerveModuleState.optimize(desiredState, new Rotation2d(m_turningEncoder.get()));
+        SwerveModuleState.optimize(desiredState, new Rotation2d(m_turningEncoder.getDistance()));
 
     // Calculate the drive output from the drive PID controller.
     final double driveOutput =
@@ -103,7 +115,7 @@
 
     // Calculate the turning motor output from the turning PID controller.
     final double turnOutput =
-        m_turningPIDController.calculate(m_turningEncoder.get(), state.angle.getRadians());
+        m_turningPIDController.calculate(m_turningEncoder.getDistance(), state.angle.getRadians());
 
     // Calculate the turning motor output from the turning PID controller.
     m_driveMotor.set(driveOutput);
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervedriveposeestimator/Drivetrain.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervedriveposeestimator/Drivetrain.java
index e1d16a0..8f4c5ce 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervedriveposeestimator/Drivetrain.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervedriveposeestimator/Drivetrain.java
@@ -10,6 +10,7 @@
 import edu.wpi.first.math.geometry.Translation2d;
 import edu.wpi.first.math.kinematics.ChassisSpeeds;
 import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
+import edu.wpi.first.math.kinematics.SwerveModulePosition;
 import edu.wpi.first.math.util.Units;
 import edu.wpi.first.wpilibj.AnalogGyro;
 import edu.wpi.first.wpilibj.Timer;
@@ -39,11 +40,16 @@
   below are robot specific, and should be tuned. */
   private final SwerveDrivePoseEstimator m_poseEstimator =
       new SwerveDrivePoseEstimator(
-          m_gyro.getRotation2d(),
-          new Pose2d(),
           m_kinematics,
+          m_gyro.getRotation2d(),
+          new SwerveModulePosition[] {
+            m_frontLeft.getPosition(),
+            m_frontRight.getPosition(),
+            m_backLeft.getPosition(),
+            m_backRight.getPosition()
+          },
+          new Pose2d(),
           VecBuilder.fill(0.05, 0.05, Units.degreesToRadians(5)),
-          VecBuilder.fill(Units.degreesToRadians(0.01)),
           VecBuilder.fill(0.5, 0.5, Units.degreesToRadians(30)));
 
   public Drivetrain() {
@@ -58,7 +64,6 @@
    * @param rot Angular rate of the robot.
    * @param fieldRelative Whether the provided x and y speeds are relative to the field.
    */
-  @SuppressWarnings("ParameterName")
   public void drive(double xSpeed, double ySpeed, double rot, boolean fieldRelative) {
     var swerveModuleStates =
         m_kinematics.toSwerveModuleStates(
@@ -76,10 +81,12 @@
   public void updateOdometry() {
     m_poseEstimator.update(
         m_gyro.getRotation2d(),
-        m_frontLeft.getState(),
-        m_frontRight.getState(),
-        m_backLeft.getState(),
-        m_backRight.getState());
+        new SwerveModulePosition[] {
+          m_frontLeft.getPosition(),
+          m_frontRight.getPosition(),
+          m_backLeft.getPosition(),
+          m_backRight.getPosition()
+        });
 
     // Also apply vision measurements. We use 0.3 seconds in the past as an example -- on
     // a real robot, this must be calculated based either on latency or timestamps.
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervedriveposeestimator/SwerveModule.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervedriveposeestimator/SwerveModule.java
index d7c43dd..afd7489 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervedriveposeestimator/SwerveModule.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervedriveposeestimator/SwerveModule.java
@@ -8,6 +8,7 @@
 import edu.wpi.first.math.controller.ProfiledPIDController;
 import edu.wpi.first.math.controller.SimpleMotorFeedforward;
 import edu.wpi.first.math.geometry.Rotation2d;
+import edu.wpi.first.math.kinematics.SwerveModulePosition;
 import edu.wpi.first.math.kinematics.SwerveModuleState;
 import edu.wpi.first.math.trajectory.TrapezoidProfile;
 import edu.wpi.first.wpilibj.Encoder;
@@ -72,7 +73,7 @@
     // resolution.
     m_driveEncoder.setDistancePerPulse(2 * Math.PI * kWheelRadius / kEncoderResolution);
 
-    // Set the distance (in this case, angle) per pulse for the turning encoder.
+    // Set the distance (in this case, angle) in radians per pulse for the turning encoder.
     // This is the the angle through an entire rotation (2 * pi) divided by the
     // encoder resolution.
     m_turningEncoder.setDistancePerPulse(2 * Math.PI / kEncoderResolution);
@@ -88,7 +89,18 @@
    * @return The current state of the module.
    */
   public SwerveModuleState getState() {
-    return new SwerveModuleState(m_driveEncoder.getRate(), new Rotation2d(m_turningEncoder.get()));
+    return new SwerveModuleState(
+        m_driveEncoder.getRate(), new Rotation2d(m_turningEncoder.getDistance()));
+  }
+
+  /**
+   * Returns the current position of the module.
+   *
+   * @return The current position of the module.
+   */
+  public SwerveModulePosition getPosition() {
+    return new SwerveModulePosition(
+        m_driveEncoder.getDistance(), new Rotation2d(m_turningEncoder.getDistance()));
   }
 
   /**
@@ -99,7 +111,7 @@
   public void setDesiredState(SwerveModuleState desiredState) {
     // Optimize the reference state to avoid spinning further than 90 degrees
     SwerveModuleState state =
-        SwerveModuleState.optimize(desiredState, new Rotation2d(m_turningEncoder.get()));
+        SwerveModuleState.optimize(desiredState, new Rotation2d(m_turningEncoder.getDistance()));
 
     // Calculate the drive output from the drive PID controller.
     final double driveOutput =
@@ -109,7 +121,7 @@
 
     // Calculate the turning motor output from the turning PID controller.
     final double turnOutput =
-        m_turningPIDController.calculate(m_turningEncoder.get(), state.angle.getRadians());
+        m_turningPIDController.calculate(m_turningEncoder.getDistance(), state.angle.getRadians());
 
     final double turnFeedforward =
         m_turnFeedforward.calculate(m_turningPIDController.getSetpoint().velocity);
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/tankdrive/Robot.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/tankdrive/Robot.java
index c91767a..3883d14 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/tankdrive/Robot.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/tankdrive/Robot.java
@@ -36,6 +36,6 @@
 
   @Override
   public void teleopPeriodic() {
-    m_myRobot.tankDrive(m_leftStick.getY(), m_rightStick.getY());
+    m_myRobot.tankDrive(-m_leftStick.getY(), -m_rightStick.getY());
   }
 }
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/unittest/Constants.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/unittest/Constants.java
new file mode 100644
index 0000000..cdcfb9d
--- /dev/null
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/unittest/Constants.java
@@ -0,0 +1,25 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj.examples.unittest;
+
+/**
+ * The Constants class provides a convenient place for teams to hold robot-wide numerical or boolean
+ * constants. This class should not be used for any other purpose. All constants should be declared
+ * globally (i.e. public static). Do not put anything functional in this class.
+ *
+ * <p>It is advised to statically import this class (or one of its inner classes) wherever the
+ * constants are needed, to reduce verbosity.
+ */
+public final class Constants {
+  public static final int kJoystickIndex = 0;
+
+  public static final class IntakeConstants {
+    public static final int kMotorPort = 1;
+
+    public static final int kPistonFwdChannel = 0;
+    public static final int kPistonRevChannel = 1;
+    public static final double kIntakeSpeed = 0.5;
+  }
+}
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/unittest/Main.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/unittest/Main.java
new file mode 100644
index 0000000..4434f47
--- /dev/null
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/unittest/Main.java
@@ -0,0 +1,25 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj.examples.unittest;
+
+import edu.wpi.first.wpilibj.RobotBase;
+
+/**
+ * Do NOT add any static variables to this class, or any initialization at all. Unless you know what
+ * you are doing, do not modify this file except to change the parameter class to the startRobot
+ * call.
+ */
+public final class Main {
+  private Main() {}
+
+  /**
+   * Main initialization function. Do not perform any initialization here.
+   *
+   * <p>If you change your main robot class, change the parameter type.
+   */
+  public static void main(String... args) {
+    RobotBase.startRobot(Robot::new);
+  }
+}
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/unittest/Robot.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/unittest/Robot.java
new file mode 100644
index 0000000..9f66c27
--- /dev/null
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/unittest/Robot.java
@@ -0,0 +1,41 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj.examples.unittest;
+
+import edu.wpi.first.wpilibj.Joystick;
+import edu.wpi.first.wpilibj.TimedRobot;
+import edu.wpi.first.wpilibj.examples.unittest.Constants.IntakeConstants;
+import edu.wpi.first.wpilibj.examples.unittest.subsystems.Intake;
+
+/**
+ * The VM is configured to automatically run this class, and to call the functions corresponding to
+ * each mode, as described in the TimedRobot documentation. If you change the name of this class or
+ * the package after creating this project, you must also update the build.gradle file in the
+ * project.
+ */
+public class Robot extends TimedRobot {
+  private Intake m_intake = new Intake();
+  private Joystick m_joystick = new Joystick(Constants.kJoystickIndex);
+
+  /** This function is called periodically during operator control. */
+  @Override
+  public void teleopPeriodic() {
+    // Activate the intake while the trigger is held
+    if (m_joystick.getTrigger()) {
+      m_intake.activate(IntakeConstants.kIntakeSpeed);
+    } else {
+      m_intake.activate(0);
+    }
+
+    // Toggle deploying the intake when the top button is pressed
+    if (m_joystick.getTop()) {
+      if (m_intake.isDeployed()) {
+        m_intake.retract();
+      } else {
+        m_intake.deploy();
+      }
+    }
+  }
+}
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/unittest/subsystems/Intake.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/unittest/subsystems/Intake.java
new file mode 100644
index 0000000..a51d505
--- /dev/null
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/unittest/subsystems/Intake.java
@@ -0,0 +1,51 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj.examples.unittest.subsystems;
+
+import edu.wpi.first.wpilibj.DoubleSolenoid;
+import edu.wpi.first.wpilibj.PneumaticsModuleType;
+import edu.wpi.first.wpilibj.examples.unittest.Constants.IntakeConstants;
+import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
+
+public class Intake implements AutoCloseable {
+  private final PWMSparkMax m_motor;
+  private final DoubleSolenoid m_piston;
+
+  public Intake() {
+    m_motor = new PWMSparkMax(IntakeConstants.kMotorPort);
+    m_piston =
+        new DoubleSolenoid(
+            PneumaticsModuleType.CTREPCM,
+            IntakeConstants.kPistonFwdChannel,
+            IntakeConstants.kPistonRevChannel);
+  }
+
+  public void deploy() {
+    m_piston.set(DoubleSolenoid.Value.kForward);
+  }
+
+  public void retract() {
+    m_piston.set(DoubleSolenoid.Value.kReverse);
+    m_motor.set(0); // turn off the motor
+  }
+
+  public void activate(double speed) {
+    if (isDeployed()) {
+      m_motor.set(speed);
+    } else { // if piston isn't open, do nothing
+      m_motor.set(0);
+    }
+  }
+
+  public boolean isDeployed() {
+    return m_piston.get() == DoubleSolenoid.Value.kForward;
+  }
+
+  @Override
+  public void close() throws Exception {
+    m_piston.close();
+    m_motor.close();
+  }
+}
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/Constants.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/Constants.java
index ecfe201..0c958be 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/Constants.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/Constants.java
@@ -12,4 +12,8 @@
  * <p>It is advised to statically import this class (or one of its inner classes) wherever the
  * constants are needed, to reduce verbosity.
  */
-public final class Constants {}
+public final class Constants {
+  public static class OperatorConstants {
+    public static final int kDriverControllerPort = 0;
+  }
+}
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/RobotContainer.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/RobotContainer.java
index 75f79ae..c29ad38 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/RobotContainer.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/RobotContainer.java
@@ -4,37 +4,52 @@
 
 package edu.wpi.first.wpilibj.templates.commandbased;
 
-import edu.wpi.first.wpilibj.GenericHID;
-import edu.wpi.first.wpilibj.XboxController;
+import edu.wpi.first.wpilibj.templates.commandbased.Constants.OperatorConstants;
+import edu.wpi.first.wpilibj.templates.commandbased.commands.Autos;
 import edu.wpi.first.wpilibj.templates.commandbased.commands.ExampleCommand;
 import edu.wpi.first.wpilibj.templates.commandbased.subsystems.ExampleSubsystem;
 import edu.wpi.first.wpilibj2.command.Command;
+import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
+import edu.wpi.first.wpilibj2.command.button.Trigger;
 
 /**
  * This class is where the bulk of the robot should be declared. Since Command-based is a
  * "declarative" paradigm, very little robot logic should actually be handled in the {@link Robot}
  * periodic methods (other than the scheduler calls). Instead, the structure of the robot (including
- * subsystems, commands, and button mappings) should be declared here.
+ * subsystems, commands, and trigger mappings) should be declared here.
  */
 public class RobotContainer {
   // The robot's subsystems and commands are defined here...
   private final ExampleSubsystem m_exampleSubsystem = new ExampleSubsystem();
 
-  private final ExampleCommand m_autoCommand = new ExampleCommand(m_exampleSubsystem);
+  // Replace with CommandPS4Controller or CommandJoystick if needed
+  private final CommandXboxController m_driverController =
+      new CommandXboxController(OperatorConstants.kDriverControllerPort);
 
   /** The container for the robot. Contains subsystems, OI devices, and commands. */
   public RobotContainer() {
-    // Configure the button bindings
-    configureButtonBindings();
+    // Configure the trigger bindings
+    configureBindings();
   }
 
   /**
-   * Use this method to define your button->command mappings. Buttons can be created by
-   * instantiating a {@link GenericHID} or one of its subclasses ({@link
-   * edu.wpi.first.wpilibj.Joystick} or {@link XboxController}), and then passing it to a {@link
-   * edu.wpi.first.wpilibj2.command.button.JoystickButton}.
+   * Use this method to define your trigger->command mappings. Triggers can be created via the
+   * {@link Trigger#Trigger(java.util.function.BooleanSupplier)} constructor with an arbitrary
+   * predicate, or via the named factories in {@link
+   * edu.wpi.first.wpilibj2.command.button.CommandGenericHID}'s subclasses for {@link
+   * CommandXboxController Xbox}/{@link edu.wpi.first.wpilibj2.command.button.CommandPS4Controller
+   * PS4} controllers or {@link edu.wpi.first.wpilibj2.command.button.CommandJoystick Flight
+   * joysticks}.
    */
-  private void configureButtonBindings() {}
+  private void configureBindings() {
+    // Schedule `ExampleCommand` when `exampleCondition` changes to `true`
+    new Trigger(m_exampleSubsystem::exampleCondition)
+        .onTrue(new ExampleCommand(m_exampleSubsystem));
+
+    // Schedule `exampleMethodCommand` when the Xbox controller's B button is pressed,
+    // cancelling on release.
+    m_driverController.b().whileTrue(m_exampleSubsystem.exampleMethodCommand());
+  }
 
   /**
    * Use this to pass the autonomous command to the main {@link Robot} class.
@@ -42,7 +57,7 @@
    * @return the command to run in autonomous
    */
   public Command getAutonomousCommand() {
-    // An ExampleCommand will run in autonomous
-    return m_autoCommand;
+    // An example command will be run in autonomous
+    return Autos.exampleAuto(m_exampleSubsystem);
   }
 }
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/commands/Autos.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/commands/Autos.java
new file mode 100644
index 0000000..330a4ae
--- /dev/null
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/commands/Autos.java
@@ -0,0 +1,20 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj.templates.commandbased.commands;
+
+import edu.wpi.first.wpilibj.templates.commandbased.subsystems.ExampleSubsystem;
+import edu.wpi.first.wpilibj2.command.CommandBase;
+import edu.wpi.first.wpilibj2.command.Commands;
+
+public final class Autos {
+  /** Example static factory for an autonomous command. */
+  public static CommandBase exampleAuto(ExampleSubsystem subsystem) {
+    return Commands.sequence(subsystem.exampleMethodCommand(), new ExampleCommand(subsystem));
+  }
+
+  private Autos() {
+    throw new UnsupportedOperationException("This is a utility class!");
+  }
+}
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/subsystems/ExampleSubsystem.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/subsystems/ExampleSubsystem.java
index 8a3594b..57d86cc 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/subsystems/ExampleSubsystem.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/subsystems/ExampleSubsystem.java
@@ -4,12 +4,37 @@
 
 package edu.wpi.first.wpilibj.templates.commandbased.subsystems;
 
+import edu.wpi.first.wpilibj2.command.CommandBase;
 import edu.wpi.first.wpilibj2.command.SubsystemBase;
 
 public class ExampleSubsystem extends SubsystemBase {
   /** Creates a new ExampleSubsystem. */
   public ExampleSubsystem() {}
 
+  /**
+   * Example command factory method.
+   *
+   * @return a command
+   */
+  public CommandBase exampleMethodCommand() {
+    // Inline construction of command goes here.
+    // Subsystem::RunOnce implicitly requires `this` subsystem.
+    return runOnce(
+        () -> {
+          /* one-time action goes here */
+        });
+  }
+
+  /**
+   * An example method querying a boolean state of the subsystem (for example, a digital sensor).
+   *
+   * @return value of some boolean subsystem state, such as a digital sensor.
+   */
+  public boolean exampleCondition() {
+    // Query some boolean state, such as a digital sensor.
+    return false;
+  }
+
   @Override
   public void periodic() {
     // This method will be called once per scheduler run
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbasedskeleton/Main.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbasedskeleton/Main.java
new file mode 100644
index 0000000..efa0c2e
--- /dev/null
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbasedskeleton/Main.java
@@ -0,0 +1,15 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj.templates.commandbasedskeleton;
+
+import edu.wpi.first.wpilibj.RobotBase;
+
+public final class Main {
+  private Main() {}
+
+  public static void main(String... args) {
+    RobotBase.startRobot(Robot::new);
+  }
+}
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbasedskeleton/Robot.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbasedskeleton/Robot.java
new file mode 100644
index 0000000..f682ec8
--- /dev/null
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbasedskeleton/Robot.java
@@ -0,0 +1,73 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj.templates.commandbasedskeleton;
+
+import edu.wpi.first.wpilibj.TimedRobot;
+import edu.wpi.first.wpilibj2.command.Command;
+import edu.wpi.first.wpilibj2.command.CommandScheduler;
+
+public class Robot extends TimedRobot {
+  private Command m_autonomousCommand;
+
+  private RobotContainer m_robotContainer;
+
+  @Override
+  public void robotInit() {
+    m_robotContainer = new RobotContainer();
+  }
+
+  @Override
+  public void robotPeriodic() {
+    CommandScheduler.getInstance().run();
+  }
+
+  @Override
+  public void disabledInit() {}
+
+  @Override
+  public void disabledPeriodic() {}
+
+  @Override
+  public void disabledExit() {}
+
+  @Override
+  public void autonomousInit() {
+    m_autonomousCommand = m_robotContainer.getAutonomousCommand();
+
+    if (m_autonomousCommand != null) {
+      m_autonomousCommand.schedule();
+    }
+  }
+
+  @Override
+  public void autonomousPeriodic() {}
+
+  @Override
+  public void autonomousExit() {}
+
+  @Override
+  public void teleopInit() {
+    if (m_autonomousCommand != null) {
+      m_autonomousCommand.cancel();
+    }
+  }
+
+  @Override
+  public void teleopPeriodic() {}
+
+  @Override
+  public void teleopExit() {}
+
+  @Override
+  public void testInit() {
+    CommandScheduler.getInstance().cancelAll();
+  }
+
+  @Override
+  public void testPeriodic() {}
+
+  @Override
+  public void testExit() {}
+}
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbasedskeleton/RobotContainer.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbasedskeleton/RobotContainer.java
new file mode 100644
index 0000000..d6e4d25
--- /dev/null
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbasedskeleton/RobotContainer.java
@@ -0,0 +1,20 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj.templates.commandbasedskeleton;
+
+import edu.wpi.first.wpilibj2.command.Command;
+import edu.wpi.first.wpilibj2.command.Commands;
+
+public class RobotContainer {
+  public RobotContainer() {
+    configureBindings();
+  }
+
+  private void configureBindings() {}
+
+  public Command getAutonomousCommand() {
+    return Commands.print("No autonomous command configured");
+  }
+}
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/educational/EducationalRobot.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/educational/EducationalRobot.java
index 76d13a4..bb40caa 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/educational/EducationalRobot.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/educational/EducationalRobot.java
@@ -4,9 +4,11 @@
 
 package edu.wpi.first.wpilibj.templates.educational;
 
-import edu.wpi.first.hal.HAL;
+import edu.wpi.first.hal.DriverStationJNI;
+import edu.wpi.first.util.WPIUtilJNI;
 import edu.wpi.first.wpilibj.DriverStation;
 import edu.wpi.first.wpilibj.RobotBase;
+import edu.wpi.first.wpilibj.internal.DriverStationModeThread;
 
 /** Educational robot base class. */
 public class EducationalRobot extends RobotBase {
@@ -34,40 +36,65 @@
   public void startCompetition() {
     robotInit();
 
+    DriverStationModeThread modeThread = new DriverStationModeThread();
+
+    int event = WPIUtilJNI.createEvent(false, false);
+
+    DriverStation.provideRefreshedDataEventHandle(event);
+
     // Tell the DS that the robot is ready to be enabled
-    HAL.observeUserProgramStarting();
+    DriverStationJNI.observeUserProgramStarting();
 
     while (!Thread.currentThread().isInterrupted() && !m_exit) {
       if (isDisabled()) {
-        DriverStation.inDisabled(true);
+        modeThread.inDisabled(true);
         disabled();
-        DriverStation.inDisabled(false);
+        modeThread.inDisabled(false);
         while (isDisabled()) {
-          DriverStation.waitForData();
+          try {
+            WPIUtilJNI.waitForObject(event);
+          } catch (InterruptedException e) {
+            Thread.currentThread().interrupt();
+          }
         }
       } else if (isAutonomous()) {
-        DriverStation.inAutonomous(true);
+        modeThread.inAutonomous(true);
         autonomous();
-        DriverStation.inAutonomous(false);
+        modeThread.inAutonomous(false);
         while (isAutonomousEnabled()) {
-          DriverStation.waitForData();
+          try {
+            WPIUtilJNI.waitForObject(event);
+          } catch (InterruptedException e) {
+            Thread.currentThread().interrupt();
+          }
         }
       } else if (isTest()) {
-        DriverStation.inTest(true);
+        modeThread.inTest(true);
         test();
-        DriverStation.inTest(false);
+        modeThread.inTest(false);
         while (isTest() && isEnabled()) {
-          DriverStation.waitForData();
+          try {
+            WPIUtilJNI.waitForObject(event);
+          } catch (InterruptedException e) {
+            Thread.currentThread().interrupt();
+          }
         }
       } else {
-        DriverStation.inTeleop(true);
+        modeThread.inTeleop(true);
         teleop();
-        DriverStation.inTeleop(false);
+        modeThread.inTeleop(false);
         while (isTeleopEnabled()) {
-          DriverStation.waitForData();
+          try {
+            WPIUtilJNI.waitForObject(event);
+          } catch (InterruptedException e) {
+            Thread.currentThread().interrupt();
+          }
         }
       }
     }
+
+    DriverStation.removeRefreshedDataEventHandle(event);
+    modeThread.close();
   }
 
   @Override
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/robotbaseskeleton/Robot.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/robotbaseskeleton/Robot.java
index 787395c..f089864 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/robotbaseskeleton/Robot.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/robotbaseskeleton/Robot.java
@@ -4,11 +4,11 @@
 
 package edu.wpi.first.wpilibj.templates.robotbaseskeleton;
 
-import edu.wpi.first.hal.HAL;
+import edu.wpi.first.hal.DriverStationJNI;
+import edu.wpi.first.util.WPIUtilJNI;
 import edu.wpi.first.wpilibj.DriverStation;
 import edu.wpi.first.wpilibj.RobotBase;
-import edu.wpi.first.wpilibj.livewindow.LiveWindow;
-import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
+import edu.wpi.first.wpilibj.internal.DriverStationModeThread;
 
 /**
  * The VM is configured to automatically run this class. If you change the name of this class or the
@@ -31,44 +31,65 @@
   public void startCompetition() {
     robotInit();
 
+    DriverStationModeThread modeThread = new DriverStationModeThread();
+
+    int event = WPIUtilJNI.createEvent(false, false);
+
+    DriverStation.provideRefreshedDataEventHandle(event);
+
     // Tell the DS that the robot is ready to be enabled
-    HAL.observeUserProgramStarting();
+    DriverStationJNI.observeUserProgramStarting();
 
     while (!Thread.currentThread().isInterrupted() && !m_exit) {
       if (isDisabled()) {
-        DriverStation.inDisabled(true);
+        modeThread.inDisabled(true);
         disabled();
-        DriverStation.inDisabled(false);
+        modeThread.inDisabled(false);
         while (isDisabled()) {
-          DriverStation.waitForData();
+          try {
+            WPIUtilJNI.waitForObject(event);
+          } catch (InterruptedException e) {
+            Thread.currentThread().interrupt();
+          }
         }
       } else if (isAutonomous()) {
-        DriverStation.inAutonomous(true);
+        modeThread.inAutonomous(true);
         autonomous();
-        DriverStation.inAutonomous(false);
+        modeThread.inAutonomous(false);
         while (isAutonomousEnabled()) {
-          DriverStation.waitForData();
+          try {
+            WPIUtilJNI.waitForObject(event);
+          } catch (InterruptedException e) {
+            Thread.currentThread().interrupt();
+          }
         }
       } else if (isTest()) {
-        LiveWindow.setEnabled(true);
-        Shuffleboard.enableActuatorWidgets();
-        DriverStation.inTest(true);
+        modeThread.inTest(true);
         test();
-        DriverStation.inTest(false);
+        modeThread.inTest(false);
         while (isTest() && isEnabled()) {
-          DriverStation.waitForData();
+          try {
+            WPIUtilJNI.waitForObject(event);
+          } catch (InterruptedException e) {
+            Thread.currentThread().interrupt();
+          }
         }
-        LiveWindow.setEnabled(false);
-        Shuffleboard.disableActuatorWidgets();
       } else {
-        DriverStation.inTeleop(true);
+        modeThread.inTeleop(true);
         teleop();
-        DriverStation.inTeleop(false);
+        modeThread.inTeleop(false);
         while (isTeleopEnabled()) {
-          DriverStation.waitForData();
+          try {
+            WPIUtilJNI.waitForObject(event);
+          } catch (InterruptedException e) {
+            Thread.currentThread().interrupt();
+          }
         }
       }
     }
+
+    DriverStation.removeRefreshedDataEventHandle(event);
+    modeThread.close();
   }
 
   @Override
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romieducational/EducationalRobot.java b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romieducational/EducationalRobot.java
index 8fed60d..5a84915 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romieducational/EducationalRobot.java
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romieducational/EducationalRobot.java
@@ -4,9 +4,11 @@
 
 package edu.wpi.first.wpilibj.templates.romieducational;
 
-import edu.wpi.first.hal.HAL;
+import edu.wpi.first.hal.DriverStationJNI;
+import edu.wpi.first.util.WPIUtilJNI;
 import edu.wpi.first.wpilibj.DriverStation;
 import edu.wpi.first.wpilibj.RobotBase;
+import edu.wpi.first.wpilibj.internal.DriverStationModeThread;
 
 /** Educational robot base class. */
 public class EducationalRobot extends RobotBase {
@@ -34,40 +36,65 @@
   public void startCompetition() {
     robotInit();
 
+    DriverStationModeThread modeThread = new DriverStationModeThread();
+
+    int event = WPIUtilJNI.createEvent(false, false);
+
+    DriverStation.provideRefreshedDataEventHandle(event);
+
     // Tell the DS that the robot is ready to be enabled
-    HAL.observeUserProgramStarting();
+    DriverStationJNI.observeUserProgramStarting();
 
     while (!Thread.currentThread().isInterrupted() && !m_exit) {
       if (isDisabled()) {
-        DriverStation.inDisabled(true);
+        modeThread.inDisabled(true);
         disabled();
-        DriverStation.inDisabled(false);
+        modeThread.inDisabled(false);
         while (isDisabled()) {
-          DriverStation.waitForData();
+          try {
+            WPIUtilJNI.waitForObject(event);
+          } catch (InterruptedException e) {
+            Thread.currentThread().interrupt();
+          }
         }
       } else if (isAutonomous()) {
-        DriverStation.inAutonomous(true);
+        modeThread.inAutonomous(true);
         autonomous();
-        DriverStation.inAutonomous(false);
+        modeThread.inAutonomous(false);
         while (isAutonomousEnabled()) {
-          DriverStation.waitForData();
+          try {
+            WPIUtilJNI.waitForObject(event);
+          } catch (InterruptedException e) {
+            Thread.currentThread().interrupt();
+          }
         }
       } else if (isTest()) {
-        DriverStation.inTest(true);
+        modeThread.inTest(true);
         test();
-        DriverStation.inTest(false);
+        modeThread.inTest(false);
         while (isTest() && isEnabled()) {
-          DriverStation.waitForData();
+          try {
+            WPIUtilJNI.waitForObject(event);
+          } catch (InterruptedException e) {
+            Thread.currentThread().interrupt();
+          }
         }
       } else {
-        DriverStation.inTeleop(true);
+        modeThread.inTeleop(true);
         teleop();
-        DriverStation.inTeleop(false);
+        modeThread.inTeleop(false);
         while (isTeleopEnabled()) {
-          DriverStation.waitForData();
+          try {
+            WPIUtilJNI.waitForObject(event);
+          } catch (InterruptedException e) {
+            Thread.currentThread().interrupt();
+          }
         }
       }
     }
+
+    DriverStation.removeRefreshedDataEventHandle(event);
+    modeThread.close();
   }
 
   @Override
diff --git a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/templates.json b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/templates.json
index b2484cc..68e3bfb 100644
--- a/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/templates.json
+++ b/third_party/allwpilib/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/templates.json
@@ -11,6 +11,17 @@
     "commandversion": 2
   },
   {
+    "name": "Command Robot Skeleton (Advanced)",
+    "description": "Skeleton (stub) code for Command Robot",
+    "tags": [
+      "Command", "Skeleton"
+    ],
+    "foldername": "commandbasedskeleton",
+    "gradlebase": "java",
+    "mainclass": "Main",
+    "commandversion": 2
+  },
+  {
     "name": "Timed Robot",
     "description": "Timed style",
     "tags": [
diff --git a/third_party/allwpilib/wpilibjExamples/src/test/java/edu/wpi/first/wpilibj/examples/addressableled/RainbowTest.java b/third_party/allwpilib/wpilibjExamples/src/test/java/edu/wpi/first/wpilibj/examples/addressableled/RainbowTest.java
new file mode 100644
index 0000000..90acfb0
--- /dev/null
+++ b/third_party/allwpilib/wpilibjExamples/src/test/java/edu/wpi/first/wpilibj/examples/addressableled/RainbowTest.java
@@ -0,0 +1,54 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj.examples.addressableled;
+
+import static org.junit.jupiter.api.Assertions.assertAll;
+import static org.junit.jupiter.api.Assertions.assertEquals;
+import static org.junit.jupiter.api.Assertions.assertTrue;
+
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.wpilibj.simulation.AddressableLEDSim;
+import edu.wpi.first.wpilibj.util.Color;
+import edu.wpi.first.wpilibj.util.Color8Bit;
+import org.junit.jupiter.api.Test;
+
+class RainbowTest {
+  @Test
+  void rainbowPatternTest() {
+    HAL.initialize(500, 0);
+    try (var robot = new Robot()) {
+      robot.robotInit();
+      AddressableLEDSim ledSim = AddressableLEDSim.createForChannel(9);
+      assertTrue(ledSim.getRunning());
+      assertEquals(60, ledSim.getLength());
+
+      var rainbowFirstPixelHue = 0;
+      for (int iteration = 0; iteration < 100; iteration++) {
+        robot.robotPeriodic();
+        var data = ledSim.getData();
+        for (int i = 0; i < 60; i++) {
+          final var hue = (rainbowFirstPixelHue + (i * 180 / 60)) % 180;
+          assertIndexColor(data, i, hue, 255, 128);
+        }
+        rainbowFirstPixelHue += 3;
+        rainbowFirstPixelHue %= 180;
+      }
+    }
+  }
+
+  private void assertIndexColor(byte[] data, int index, int hue, int saturation, int value) {
+    var color = new Color8Bit(Color.fromHSV(hue, saturation, value));
+    int b = data[index * 4];
+    int g = data[(index * 4) + 1];
+    int r = data[(index * 4) + 2];
+    int z = data[(index * 4) + 3];
+
+    assertAll(
+        () -> assertEquals(0, z),
+        () -> assertEquals(color.red, r & 0xFF),
+        () -> assertEquals(color.green, g & 0xFF),
+        () -> assertEquals(color.blue, b & 0xFF));
+  }
+}
diff --git a/third_party/allwpilib/wpilibjExamples/src/test/java/edu/wpi/first/wpilibj/examples/unittest/subsystems/IntakeTest.java b/third_party/allwpilib/wpilibjExamples/src/test/java/edu/wpi/first/wpilibj/examples/unittest/subsystems/IntakeTest.java
new file mode 100644
index 0000000..33be835
--- /dev/null
+++ b/third_party/allwpilib/wpilibjExamples/src/test/java/edu/wpi/first/wpilibj/examples/unittest/subsystems/IntakeTest.java
@@ -0,0 +1,70 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj.examples.unittest.subsystems;
+
+import static org.junit.jupiter.api.Assertions.assertEquals;
+
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.wpilibj.DoubleSolenoid;
+import edu.wpi.first.wpilibj.PneumaticsModuleType;
+import edu.wpi.first.wpilibj.examples.unittest.Constants.IntakeConstants;
+import edu.wpi.first.wpilibj.simulation.DoubleSolenoidSim;
+import edu.wpi.first.wpilibj.simulation.PWMSim;
+import org.junit.jupiter.api.AfterEach;
+import org.junit.jupiter.api.BeforeEach;
+import org.junit.jupiter.api.Test;
+
+class IntakeTest {
+  static final double DELTA = 1e-2; // acceptable deviation range
+  Intake m_intake;
+  PWMSim m_simMotor;
+  DoubleSolenoidSim m_simPiston;
+
+  @BeforeEach // this method will run before each test
+  void setup() {
+    assert HAL.initialize(500, 0); // initialize the HAL, crash if failed
+    m_intake = new Intake(); // create our intake
+    m_simMotor =
+        new PWMSim(IntakeConstants.kMotorPort); // create our simulation PWM motor controller
+    m_simPiston =
+        new DoubleSolenoidSim(
+            PneumaticsModuleType.CTREPCM,
+            IntakeConstants.kPistonFwdChannel,
+            IntakeConstants.kPistonRevChannel); // create our simulation solenoid
+  }
+
+  @SuppressWarnings("PMD.SignatureDeclareThrowsException")
+  @AfterEach // this method will run after each test
+  void shutdown() throws Exception {
+    m_intake.close(); // destroy our intake object
+  }
+
+  @Test // marks this method as a test
+  void doesntWorkWhenClosed() {
+    m_intake.retract(); // close the intake
+    m_intake.activate(0.5); // try to activate the motor
+    assertEquals(
+        0.0, m_simMotor.getSpeed(), DELTA); // make sure that the value set to the motor is 0
+  }
+
+  @Test
+  void worksWhenOpen() {
+    m_intake.deploy();
+    m_intake.activate(0.5);
+    assertEquals(0.5, m_simMotor.getSpeed(), DELTA);
+  }
+
+  @Test
+  void retractTest() {
+    m_intake.retract();
+    assertEquals(DoubleSolenoid.Value.kReverse, m_simPiston.get());
+  }
+
+  @Test
+  void deployTest() {
+    m_intake.deploy();
+    assertEquals(DoubleSolenoid.Value.kForward, m_simPiston.get());
+  }
+}
diff --git a/third_party/allwpilib/wpilibjIntegrationTests/build.gradle b/third_party/allwpilib/wpilibjIntegrationTests/build.gradle
index d2daeda..06d891a 100644
--- a/third_party/allwpilib/wpilibjIntegrationTests/build.gradle
+++ b/third_party/allwpilib/wpilibjIntegrationTests/build.gradle
@@ -16,7 +16,9 @@
 apply plugin: 'com.github.johnrengelman.shadow'
 
 repositories {
-    mavenCentral()
+    maven {
+        url = 'https://frcmaven.wpi.edu/artifactory/ex-mvn'
+    }
 }
 
 dependencies {
@@ -24,6 +26,7 @@
     implementation project(':wpimath')
     implementation project(':hal')
     implementation project(':wpiutil')
+    implementation project(':wpinet')
     implementation project(':ntcore')
     implementation project(':cscore')
     implementation project(':cameraserver')
diff --git a/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/AbstractInterruptTest.java b/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/AbstractInterruptTest.java
index 219a611..bdc4675 100644
--- a/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/AbstractInterruptTest.java
+++ b/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/AbstractInterruptTest.java
@@ -52,7 +52,7 @@
   abstract void setInterruptLow();
 
   @Test(timeout = 1000)
-  public void testSingleInterruptsTriggering() throws Exception {
+  public void testSingleInterruptsTriggering() {
     // Given
     // final InterruptCounter counter = new InterruptCounter();
     // TestInterruptHandlerFunction function = new
diff --git a/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/DriverStationTest.java b/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/DriverStationTest.java
index b2e727d..cd67cbd 100644
--- a/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/DriverStationTest.java
+++ b/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/DriverStationTest.java
@@ -6,6 +6,8 @@
 
 import static org.junit.Assert.assertEquals;
 
+import edu.wpi.first.hal.DriverStationJNI;
+import edu.wpi.first.util.WPIUtilJNI;
 import edu.wpi.first.wpilibj.test.AbstractComsSetup;
 import java.util.logging.Logger;
 import org.junit.Test;
@@ -24,13 +26,23 @@
   public void waitForDataTest() {
     long startTime = RobotController.getFPGATime();
 
+    int handle = WPIUtilJNI.createEvent(false, false);
+    DriverStationJNI.provideNewDataEventHandle(handle);
+
     // Wait for data 50 times
     for (int i = 0; i < 50; i++) {
-      DriverStation.waitForData();
+      try {
+        WPIUtilJNI.waitForObject(handle);
+      } catch (InterruptedException e) {
+        e.printStackTrace();
+      }
     }
     long endTime = RobotController.getFPGATime();
     long difference = endTime - startTime;
 
+    DriverStationJNI.removeNewDataEventHandle(handle);
+    WPIUtilJNI.destroyEvent(handle);
+
     assertEquals(
         "DriverStation waitForData did not wait long enough",
         TIMER_RUNTIME,
diff --git a/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MockDS.java b/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MockDS.java
index dfd5b6c..36bd2e8 100644
--- a/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MockDS.java
+++ b/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MockDS.java
@@ -22,7 +22,7 @@
     data[5] = 0x00; // red 1 station
   }
 
-  @SuppressWarnings("MissingJavadocMethod")
+  /** Start the mock DS thread. */
   public void start() {
     m_thread =
         new Thread(
@@ -67,7 +67,7 @@
     m_thread.start();
   }
 
-  @SuppressWarnings("MissingJavadocMethod")
+  /** Stop the mock DS thread. */
   public void stop() {
     if (m_thread == null) {
       return;
diff --git a/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PCMTest.java b/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PCMTest.java
index 07e0139..e571ffa 100644
--- a/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PCMTest.java
+++ b/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PCMTest.java
@@ -70,7 +70,7 @@
 
   /** Test if the compressor turns on and off when the pressure switch is toggled. */
   @Test
-  public void testPressureSwitch() throws Exception {
+  public void testPressureSwitch() {
     final double range = 0.5;
     reset();
     pcm.enableCompressorDigital();
@@ -96,7 +96,7 @@
 
   /** Test if the correct solenoids turn on and off when they should. */
   @Test
-  public void testSolenoid() throws Exception {
+  public void testSolenoid() {
     reset();
 
     Solenoid solenoid1 = new Solenoid(PneumaticsModuleType.CTREPCM, 0);
@@ -174,7 +174,7 @@
 
   /** Test if the correct solenoids turn on and off when they should. */
   @Test
-  public void testOneShot() throws Exception {
+  public void testOneShot() {
     reset();
 
     Solenoid solenoid1 = new Solenoid(PneumaticsModuleType.CTREPCM, 0);
diff --git a/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PDPTest.java b/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PDPTest.java
index 548c2e0..f2bc522 100644
--- a/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PDPTest.java
+++ b/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PDPTest.java
@@ -45,7 +45,12 @@
     me = null;
   }
 
-  @SuppressWarnings("MissingJavadocMethod")
+  /**
+   * PDPTest constructor.
+   *
+   * @param mef Motor encoder fixture.
+   * @param expectedCurrentDraw Expected current draw in Amps.
+   */
   public PDPTest(MotorEncoderFixture<?> mef, Double expectedCurrentDraw) {
     logger.fine("Constructor with: " + mef.getType());
     if (me != null && !me.equals(mef)) {
diff --git a/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PIDTest.java b/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PIDTest.java
index c8afb4b..b5e0fc8 100644
--- a/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PIDTest.java
+++ b/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PIDTest.java
@@ -41,24 +41,32 @@
   private PIDController m_controller = null;
   private static MotorEncoderFixture<?> me = null;
 
-  @SuppressWarnings({"MemberName", "EmptyLineSeparator", "MultipleVariableDeclarations"})
-  private final Double k_p, k_i, k_d;
+  private final Double m_p;
+  private final Double m_i;
+  private final Double m_d;
 
   @Override
   protected Logger getClassLogger() {
     return logger;
   }
 
-  @SuppressWarnings({"ParameterName", "MissingJavadocMethod"})
+  /**
+   * PIDTest constructor.
+   *
+   * @param p P gain.
+   * @param i I gain.
+   * @param d D gain.
+   * @param mef Motor encoder fixture.
+   */
   public PIDTest(Double p, Double i, Double d, MotorEncoderFixture<?> mef) {
     logger.fine("Constructor with: " + mef.getType());
     if (PIDTest.me != null && !PIDTest.me.equals(mef)) {
       PIDTest.me.teardown();
     }
     PIDTest.me = mef;
-    this.k_p = p;
-    this.k_i = i;
-    this.k_d = d;
+    this.m_p = p;
+    this.m_i = i;
+    this.m_d = d;
   }
 
   @Parameters
@@ -97,7 +105,7 @@
     m_table = NetworkTableInstance.getDefault().getTable("TEST_PID");
     m_builder = new SendableBuilderImpl();
     m_builder.setTable(m_table);
-    m_controller = new PIDController(k_p, k_i, k_d);
+    m_controller = new PIDController(m_p, m_i, m_d);
     m_controller.initSendable(m_builder);
   }
 
@@ -128,9 +136,9 @@
         m_controller.getPositionError(),
         0);
     m_builder.update();
-    assertEquals(k_p, m_table.getEntry("Kp").getDouble(9999999), 0);
-    assertEquals(k_i, m_table.getEntry("Ki").getDouble(9999999), 0);
-    assertEquals(k_d, m_table.getEntry("Kd").getDouble(9999999), 0);
+    assertEquals(m_p, m_table.getEntry("Kp").getDouble(9999999), 0);
+    assertEquals(m_i, m_table.getEntry("Ki").getDouble(9999999), 0);
+    assertEquals(m_d, m_table.getEntry("Kd").getDouble(9999999), 0);
     assertEquals(reference, m_table.getEntry("reference").getDouble(9999999), 0);
     assertFalse(m_table.getEntry("enabled").getBoolean(true));
   }
diff --git a/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/MotorEncoderFixture.java b/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/MotorEncoderFixture.java
index 220db18..ca93c4a 100644
--- a/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/MotorEncoderFixture.java
+++ b/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/MotorEncoderFixture.java
@@ -38,7 +38,7 @@
   public abstract int getPDPChannel();
 
   /**
-   * Where the implementer of this class should pass the speed controller Constructor should only be
+   * Where the implementer of this class should pass the motor controller Constructor should only be
    * called from outside this class if the Motor controller is not also an implementation of PWM
    * interface.
    *
@@ -75,7 +75,7 @@
         m_encoder = new Encoder(m_alphaSource, m_betaSource);
         m_counters[0] = new Counter(m_alphaSource);
         m_counters[1] = new Counter(m_betaSource);
-        logger.fine("Creating the speed controller!");
+        logger.fine("Creating the motor controller!");
         m_motor = giveMotorController();
       }
     }
@@ -152,7 +152,6 @@
    * deallocated.
    */
   @Override
-  @SuppressWarnings("Regexp")
   public void teardown() {
     if (!m_tornDown) {
       if (m_motor != null) {
diff --git a/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractComsSetup.java b/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractComsSetup.java
index 734115c..056ff5f 100644
--- a/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractComsSetup.java
+++ b/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractComsSetup.java
@@ -4,6 +4,7 @@
 
 package edu.wpi.first.wpilibj.test;
 
+import edu.wpi.first.hal.DriverStationJNI;
 import edu.wpi.first.hal.HAL;
 import edu.wpi.first.wpilibj.DriverStation;
 import edu.wpi.first.wpilibj.MockDS;
@@ -40,7 +41,7 @@
       try {
         // Set some implementations so that the static methods work properly
         HAL.initialize(500, 0);
-        HAL.observeUserProgramStarting();
+        DriverStationJNI.observeUserProgramStarting();
         DriverStation.getAlliance();
 
         ds = new MockDS();
@@ -56,6 +57,7 @@
 
       // Wait until the robot is enabled before starting the tests
       int enableCounter = 0;
+      DriverStation.refreshData();
       while (!DriverStation.isEnabled()) {
         if (enableCounter > 50) {
           // Robot did not enable properly after 5 seconds.
@@ -69,6 +71,7 @@
           ex.printStackTrace();
         }
         TestBench.out().println("Waiting for enable: " + enableCounter++);
+        DriverStation.refreshData();
       }
       TestBench.out().println();
 
diff --git a/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractTestSuiteTest.java b/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractTestSuiteTest.java
index c41ff8a..1e48c9c 100644
--- a/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractTestSuiteTest.java
+++ b/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractTestSuiteTest.java
@@ -122,8 +122,7 @@
   public static final String METHODNAME = "aTestMethod";
 
   @Test
-  @SuppressWarnings("MethodName")
-  public void aTestMethod() {}
+  public void testMethod() {}
 }
 
 @SuppressWarnings("OneTopLevelClass")
diff --git a/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/TestBench.java b/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/TestBench.java
index 8e63dc9..258d640 100644
--- a/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/TestBench.java
+++ b/third_party/allwpilib/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/TestBench.java
@@ -210,7 +210,7 @@
     return pairs;
   }
 
-  @SuppressWarnings("MissingJavadocMethod")
+  /** Returns the analog I/O cross-connect fixture. */
   public static AnalogCrossConnectFixture getAnalogCrossConnectFixture() {
     return new AnalogCrossConnectFixture() {
       @Override
@@ -225,7 +225,7 @@
     };
   }
 
-  @SuppressWarnings("MissingJavadocMethod")
+  /** Returns the relay cross-connect fixture. */
   public static RelayCrossConnectFixture getRelayCrossConnectFixture() {
     return new RelayCrossConnectFixture() {
       @Override
@@ -311,21 +311,6 @@
   }
 
   /**
-   * Gets the singleton of the TestBench. If the TestBench is not already allocated in constructs an
-   * new instance of it. Otherwise it returns the existing instance.
-   *
-   * @return The Singleton instance of the TestBench
-   * @deprecated Use the static methods instead
-   */
-  @Deprecated
-  public static TestBench getInstance() {
-    if (instance == null) {
-      instance = new TestBench();
-    }
-    return instance;
-  }
-
-  /**
    * Provides access to the output stream for the test system. This should be used instead of
    * System.out This is gives us a way to implement changes to where the output text of this test
    * system is sent.
diff --git a/third_party/allwpilib/wpimath/.styleguide b/third_party/allwpilib/wpimath/.styleguide
index b9044c9..6ae8bbf 100644
--- a/third_party/allwpilib/wpimath/.styleguide
+++ b/third_party/allwpilib/wpimath/.styleguide
@@ -1,5 +1,6 @@
 cppHeaderFileInclude {
   \.h$
+  \.hpp$
   \.inc$
   \.inl$
 }
@@ -13,12 +14,10 @@
 }
 
 generatedFileExclude {
-  src/main/native/cpp/drake/
-  src/main/native/eigeninclude/
-  src/main/native/include/drake/
   src/main/native/include/units/base\.h$
   src/main/native/include/units/units\.h$
   src/main/native/include/unsupported/
+  src/main/native/thirdparty/
   src/test/native/cpp/UnitsTest\.cpp$
   src/test/native/cpp/drake/
   src/test/native/include/drake/
@@ -40,6 +39,7 @@
 }
 
 includeProject {
+  ^gcem/
   ^drake/
   ^Eigen/
   ^units/
diff --git a/third_party/allwpilib/wpimath/BUILD b/third_party/allwpilib/wpimath/BUILD
new file mode 100644
index 0000000..45f1eef
--- /dev/null
+++ b/third_party/allwpilib/wpimath/BUILD
@@ -0,0 +1,15 @@
+licenses(["notice"])
+
+cc_library(
+    name = "wpimath",
+    hdrs = glob(
+        [
+            "src/main/native/include/frc/fmt/**",
+        ],
+    ),
+    includes = [
+        "src/main/native/include",
+    ],
+    target_compatible_with = ["//tools/platforms/hardware:roborio"],
+    visibility = ["//visibility:public"],
+)
diff --git a/third_party/allwpilib/wpimath/CMakeLists.txt b/third_party/allwpilib/wpimath/CMakeLists.txt
index 4e1cac3..e3d90cd 100644
--- a/third_party/allwpilib/wpimath/CMakeLists.txt
+++ b/third_party/allwpilib/wpimath/CMakeLists.txt
@@ -89,7 +89,8 @@
 
 endif()
 
-file(GLOB_RECURSE wpimath_native_src src/main/native/cpp/*.cpp)
+file(GLOB_RECURSE wpimath_native_src src/main/native/cpp/*.cpp
+                                     src/main/native/thirdparty/drake/src/*.cpp)
 list(REMOVE_ITEM wpimath_native_src ${wpimath_jni_src})
 
 set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS FALSE)
@@ -100,29 +101,37 @@
 set_property(TARGET wpimath PROPERTY FOLDER "libraries")
 target_compile_definitions(wpimath PRIVATE WPILIB_EXPORTS)
 
-target_compile_features(wpimath PUBLIC cxx_std_17)
+target_compile_features(wpimath PUBLIC cxx_std_20)
 if (MSVC)
     target_compile_options(wpimath PUBLIC /bigobj)
 endif()
 wpilib_target_warnings(wpimath)
 target_link_libraries(wpimath wpiutil)
 
-if (NOT USE_VCPKG_EIGEN)
-    install(DIRECTORY src/main/native/eigeninclude/ DESTINATION "${include_dest}/wpimath")
+if (NOT USE_SYSTEM_EIGEN)
+    install(DIRECTORY src/main/native/thirdparty/eigen/include/ DESTINATION "${include_dest}/wpimath")
     target_include_directories(wpimath SYSTEM PUBLIC
-                            $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/src/main/native/eigeninclude>
-                            $<INSTALL_INTERFACE:${include_dest}/wpimath>)
+                               $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/src/main/native/thirdparty/eigen/include>
+                               $<INSTALL_INTERFACE:${include_dest}/wpimath>)
 else()
     find_package(Eigen3 CONFIG REQUIRED)
     target_link_libraries (wpimath Eigen3::Eigen)
 endif()
 
+install(DIRECTORY src/main/native/thirdparty/drake/include/ DESTINATION "${include_dest}/wpimath")
+target_include_directories(wpimath SYSTEM PUBLIC
+                           $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/src/main/native/thirdparty/drake/include>)
+
+install(DIRECTORY src/main/native/thirdparty/gcem/include/ DESTINATION "${include_dest}/wpimath")
+target_include_directories(wpimath SYSTEM PUBLIC
+                          $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/src/main/native/thirdparty/gcem/include>)
+
+install(DIRECTORY src/main/native/include/ DESTINATION "${include_dest}/wpimath")
 target_include_directories(wpimath PUBLIC
                             $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/src/main/native/include>
                             $<INSTALL_INTERFACE:${include_dest}/wpimath>)
 
 install(TARGETS wpimath EXPORT wpimath DESTINATION "${main_lib_dest}")
-install(DIRECTORY src/main/native/include/ DESTINATION "${include_dest}/wpimath")
 
 if (WITH_JAVA AND MSVC)
     install(TARGETS wpimath RUNTIME DESTINATION "${jni_lib_dest}" COMPONENT Runtime)
diff --git a/third_party/allwpilib/wpimath/algorithms.md b/third_party/allwpilib/wpimath/algorithms.md
new file mode 100644
index 0000000..04cdf94
--- /dev/null
+++ b/third_party/allwpilib/wpimath/algorithms.md
@@ -0,0 +1,88 @@
+# Algorithms
+
+## Closed form Kalman gain for continuous Kalman filter with A = 0 and C = I
+
+### Derivation
+
+Model is
+
+```
+  dx/dt = Ax + Bu
+  y = Cx + Du
+```
+
+where A = 0, B = 0, C = I, and D = 0.
+
+The optimal cost-to-go is the P that satisfies
+
+```
+  AᵀP + PA − PBR⁻¹BᵀP + Q = 0
+```
+
+Let A = Aᵀ and B = Cᵀ for state observers.
+
+```
+  AP + PAᵀ − PCᵀR⁻¹CP + Q = 0
+```
+
+Let A = 0, C = I.
+
+```
+  −PR⁻¹P + Q = 0
+```
+
+Solve for P. P, Q, and R are all diagonal, so this can be solved element-wise.
+
+```
+  −pr⁻¹p + q = 0
+  −pr⁻¹p = −q
+  pr⁻¹p = q
+  p²r⁻¹ = q
+  p² = qr
+  p = sqrt(qr)
+```
+
+Now solve for the Kalman gain.
+
+```
+  K = PCᵀ(CPCᵀ + R)⁻¹
+  K = P(P + R)⁻¹
+  k = p(p + r)⁻¹
+  k = sqrt(qr)(sqrt(qr) + r)⁻¹
+  k = sqrt(qr)/(sqrt(qr) + r)
+```
+
+Multiply by sqrt(q/r)/sqrt(q/r).
+
+```
+  k = q/(q + r sqrt(q/r))
+  k = q/(q + sqrt(qr²/r))
+  k = q/(q + sqrt(qr))
+```
+
+### Corner cases
+
+For q = 0 and r ≠ 0,
+
+```
+  k = 0/(0 + sqrt(0))
+  k = 0/0
+```
+
+Apply L'Hôpital's rule to k with respect to q.
+
+```
+  k = 1/(1 + r/(2sqrt(qr)))
+  k = 2sqrt(qr)/(2sqrt(qr) + r)
+  k = 2sqrt(0)/(2sqrt(0) + r)
+  k = 0/r
+  k = 0
+```
+
+For q ≠ 0 and r = 0,
+
+```
+  k = q / (q + sqrt(0))
+  k = q / q
+  k = 1
+```
diff --git a/third_party/allwpilib/wpimath/build.gradle b/third_party/allwpilib/wpimath/build.gradle
index c31f04c..9e7c3a8 100644
--- a/third_party/allwpilib/wpimath/build.gradle
+++ b/third_party/allwpilib/wpimath/build.gradle
@@ -9,12 +9,34 @@
 
     nativeName = 'wpimath'
     devMain = 'edu.wpi.first.math.DevMain'
+
+    splitSetup = {
+        it.sources {
+            drakeCpp(CppSourceSet) {
+                source {
+                    srcDirs 'src/main/native/thirdparty/drake/src'
+                    include '**/*.cpp'
+                }
+                exportedHeaders {
+                    srcDirs 'src/main/native/thirdparty/drake/include',
+                            'src/main/native/thirdparty/eigen/include',
+                            'src/main/native/thirdparty/gcem/include'
+                }
+            }
+        }
+    }
 }
 
 apply from: "${rootDir}/shared/jni/setupBuild.gradle"
 
 cppHeadersZip {
-    from('src/main/native/eigeninclude') {
+    from('src/main/native/thirdparty/drake/include') {
+        into '/'
+    }
+    from('src/main/native/thirdparty/eigen/include') {
+        into '/'
+    }
+    from('src/main/native/thirdparty/gcem/include') {
         into '/'
     }
 }
@@ -24,7 +46,10 @@
         all {
             it.sources.each {
                 it.exportedHeaders {
-                    srcDirs 'src/main/native/include', 'src/main/native/eigeninclude'
+                    srcDirs 'src/main/native/include',
+                            'src/main/native/thirdparty/drake/include',
+                            'src/main/native/thirdparty/eigen/include',
+                            'src/main/native/thirdparty/gcem/include'
                 }
             }
         }
diff --git a/third_party/allwpilib/wpimath/generate_numbers.py b/third_party/allwpilib/wpimath/generate_numbers.py
index c52ddb4..c9da1a4 100644
--- a/third_party/allwpilib/wpimath/generate_numbers.py
+++ b/third_party/allwpilib/wpimath/generate_numbers.py
@@ -29,9 +29,11 @@
     dirname, _ = os.path.split(os.path.abspath(__file__))
     cmake_binary_dir = sys.argv[1]
 
-    env = Environment(loader=FileSystemLoader(f"{dirname}/src/generate"),
-                      autoescape=False,
-                      keep_trailing_newline=True)
+    env = Environment(
+        loader=FileSystemLoader(f"{dirname}/src/generate"),
+        autoescape=False,
+        keep_trailing_newline=True,
+    )
 
     template = env.get_template("GenericNumber.java.jinja")
     rootPath = f"{cmake_binary_dir}/generated/main/java/edu/wpi/first/math/numbers"
diff --git a/third_party/allwpilib/wpimath/src/dev/native/cpp/main.cpp b/third_party/allwpilib/wpimath/src/dev/native/cpp/main.cpp
index 54952b7..447d3f2 100644
--- a/third_party/allwpilib/wpimath/src/dev/native/cpp/main.cpp
+++ b/third_party/allwpilib/wpimath/src/dev/native/cpp/main.cpp
@@ -2,9 +2,10 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
+#include <numbers>
+
 #include <fmt/core.h>
-#include <wpi/numbers>
 
 int main() {
-  fmt::print("{}\n", wpi::numbers::pi);
+  fmt::print("{}\n", std::numbers::pi);
 }
diff --git a/third_party/allwpilib/wpimath/src/generate/Nat.java.jinja b/third_party/allwpilib/wpimath/src/generate/Nat.java.jinja
index 31451d2..cbc0ddb 100644
--- a/third_party/allwpilib/wpimath/src/generate/Nat.java.jinja
+++ b/third_party/allwpilib/wpimath/src/generate/Nat.java.jinja
@@ -16,7 +16,6 @@
  *
  * @param <T> The {@link Num} this represents.
  */
-@SuppressWarnings({"MethodName", "unused"})
 public interface Nat<T extends Num> {
   /**
    * The number this interface represents.
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/ComputerVisionUtil.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/ComputerVisionUtil.java
new file mode 100644
index 0000000..7b1c377
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/ComputerVisionUtil.java
@@ -0,0 +1,38 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.math;
+
+import edu.wpi.first.math.geometry.Pose3d;
+import edu.wpi.first.math.geometry.Transform3d;
+
+public final class ComputerVisionUtil {
+  private ComputerVisionUtil() {
+    throw new AssertionError("utility class");
+  }
+
+  /**
+   * Returns the robot's pose in the field coordinate system given an object's field-relative pose,
+   * the transformation from the camera's pose to the object's pose (obtained via computer vision),
+   * and the transformation from the robot's pose to the camera's pose.
+   *
+   * <p>The object could be a target or a fiducial marker.
+   *
+   * @param objectInField An object's field-relative pose.
+   * @param cameraToObject The transformation from the camera's pose to the object's pose. This
+   *     comes from computer vision.
+   * @param robotToCamera The transformation from the robot's pose to the camera's pose. This can
+   *     either be a constant for a rigidly mounted camera, or variable if the camera is mounted to
+   *     a turret. If the camera was mounted 3 inches in front of the "origin" (usually physical
+   *     center) of the robot, this would be new Transform3d(Units.inchesToMeters(3.0), 0.0, 0.0,
+   *     new Rotation3d()).
+   * @return The robot's field-relative pose.
+   */
+  public static Pose3d objectToRobotPose(
+      Pose3d objectInField, Transform3d cameraToObject, Transform3d robotToCamera) {
+    final var objectToCamera = cameraToObject.inverse();
+    final var cameraToRobot = robotToCamera.inverse();
+    return objectInField.plus(objectToCamera).plus(cameraToRobot);
+  }
+}
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/Drake.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/Drake.java
index 766f7e9..55bc5b2 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/Drake.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/Drake.java
@@ -10,7 +10,7 @@
   private Drake() {}
 
   /**
-   * Solves the discrete alegebraic Riccati equation.
+   * Solves the discrete algebraic Riccati equation.
    *
    * @param A System matrix.
    * @param B Input matrix.
@@ -18,7 +18,6 @@
    * @param R Input cost matrix.
    * @return Solution of DARE.
    */
-  @SuppressWarnings({"LocalVariableName", "ParameterName"})
   public static SimpleMatrix discreteAlgebraicRiccatiEquation(
       SimpleMatrix A, SimpleMatrix B, SimpleMatrix Q, SimpleMatrix R) {
     var S = new SimpleMatrix(A.numRows(), A.numCols());
@@ -34,7 +33,7 @@
   }
 
   /**
-   * Solves the discrete alegebraic Riccati equation.
+   * Solves the discrete algebraic Riccati equation.
    *
    * @param <States> Number of states.
    * @param <Inputs> Number of inputs.
@@ -44,7 +43,6 @@
    * @param R Input cost matrix.
    * @return Solution of DARE.
    */
-  @SuppressWarnings({"ParameterName", "MethodTypeParameterName"})
   public static <States extends Num, Inputs extends Num>
       Matrix<States, States> discreteAlgebraicRiccatiEquation(
           Matrix<States, States> A,
@@ -57,7 +55,7 @@
   }
 
   /**
-   * Solves the discrete alegebraic Riccati equation.
+   * Solves the discrete algebraic Riccati equation.
    *
    * @param A System matrix.
    * @param B Input matrix.
@@ -66,7 +64,6 @@
    * @param N State-input cross-term cost matrix.
    * @return Solution of DARE.
    */
-  @SuppressWarnings({"LocalVariableName", "ParameterName"})
   public static SimpleMatrix discreteAlgebraicRiccatiEquation(
       SimpleMatrix A, SimpleMatrix B, SimpleMatrix Q, SimpleMatrix R, SimpleMatrix N) {
     // See
@@ -88,7 +85,7 @@
   }
 
   /**
-   * Solves the discrete alegebraic Riccati equation.
+   * Solves the discrete algebraic Riccati equation.
    *
    * @param <States> Number of states.
    * @param <Inputs> Number of inputs.
@@ -99,7 +96,6 @@
    * @param N State-input cross-term cost matrix.
    * @return Solution of DARE.
    */
-  @SuppressWarnings({"ParameterName", "MethodTypeParameterName"})
   public static <States extends Num, Inputs extends Num>
       Matrix<States, States> discreteAlgebraicRiccatiEquation(
           Matrix<States, States> A,
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/InterpolatingMatrixTreeMap.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/InterpolatingMatrixTreeMap.java
new file mode 100644
index 0000000..a7b922c
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/InterpolatingMatrixTreeMap.java
@@ -0,0 +1,91 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.math;
+
+import java.util.TreeMap;
+
+/**
+ * Interpolating Tree Maps are used to get values at points that are not defined by making a guess
+ * from points that are defined. This uses linear interpolation.
+ */
+public class InterpolatingMatrixTreeMap<K extends Number, R extends Num, C extends Num> {
+  private final TreeMap<K, Matrix<R, C>> m_map = new TreeMap<>();
+
+  /**
+   * Inserts a key-value pair.
+   *
+   * @param key The key.
+   * @param value The value.
+   */
+  public void put(K key, Matrix<R, C> value) {
+    m_map.put(key, value);
+  }
+
+  /**
+   * Returns the value associated with a given key.
+   *
+   * <p>If there's no matching key, the value returned will be a linear interpolation between the
+   * keys before and after the provided one.
+   *
+   * @param key The key.
+   * @return The value associated with the given key.
+   */
+  public Matrix<R, C> get(K key) {
+    Matrix<R, C> val = m_map.get(key);
+    if (val == null) {
+      K ceilingKey = m_map.ceilingKey(key);
+      K floorKey = m_map.floorKey(key);
+
+      if (ceilingKey == null && floorKey == null) {
+        return null;
+      }
+      if (ceilingKey == null) {
+        return m_map.get(floorKey);
+      }
+      if (floorKey == null) {
+        return m_map.get(ceilingKey);
+      }
+      Matrix<R, C> floor = m_map.get(floorKey);
+      Matrix<R, C> ceiling = m_map.get(ceilingKey);
+
+      return interpolate(floor, ceiling, inverseInterpolate(ceilingKey, key, floorKey));
+    } else {
+      return val;
+    }
+  }
+
+  /**
+   * Return the value interpolated between val1 and val2 by the interpolant d.
+   *
+   * @param val1 The lower part of the interpolation range.
+   * @param val2 The upper part of the interpolation range.
+   * @param d The interpolant in the range [0, 1].
+   * @return The interpolated value.
+   */
+  public Matrix<R, C> interpolate(Matrix<R, C> val1, Matrix<R, C> val2, double d) {
+    var dydx = val2.minus(val1);
+    return dydx.times(d).plus(val1);
+  }
+
+  /**
+   * Return where within interpolation range [0, 1] q is between down and up.
+   *
+   * @param up Upper part of interpolation range.
+   * @param q Query.
+   * @param down Lower part of interpolation range.
+   * @return Interpolant in range [0, 1].
+   */
+  public double inverseInterpolate(K up, K q, K down) {
+    double upperToLower = up.doubleValue() - down.doubleValue();
+    if (upperToLower <= 0) {
+      return 0.0;
+    }
+    double queryToLower = q.doubleValue() - down.doubleValue();
+    if (queryToLower <= 0) {
+      return 0.0;
+    }
+    return queryToLower / upperToLower;
+  }
+}
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/MatBuilder.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/MatBuilder.java
index e5b1952..2ee010f 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/MatBuilder.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/MatBuilder.java
@@ -24,7 +24,6 @@
    * @param data The data to fill the matrix with.
    * @return The constructed matrix.
    */
-  @SuppressWarnings("LineLength")
   public final Matrix<R, C> fill(double... data) {
     if (Objects.requireNonNull(data).length != this.m_rows.getNum() * this.m_cols.getNum()) {
       throw new IllegalArgumentException(
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/MathUtil.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/MathUtil.java
index 25b9f92..95ed5bf 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/MathUtil.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/MathUtil.java
@@ -35,6 +35,63 @@
 
   /**
    * Returns 0.0 if the given value is within the specified range around zero. The remaining range
+   * between the deadband and the maximum magnitude is scaled from 0.0 to the maximum magnitude.
+   *
+   * @param value Value to clip.
+   * @param deadband Range around zero.
+   * @param maxMagnitude The maximum magnitude of the input. Can be infinite.
+   * @return The value after the deadband is applied.
+   */
+  public static double applyDeadband(double value, double deadband, double maxMagnitude) {
+    if (Math.abs(value) > deadband) {
+      if (maxMagnitude / deadband > 1.0e12) {
+        // If max magnitude is sufficiently large, the implementation encounters
+        // roundoff error.  Implementing the limiting behavior directly avoids
+        // the problem.
+        return value > 0.0 ? value - deadband : value + deadband;
+      }
+      if (value > 0.0) {
+        // Map deadband to 0 and map max to max.
+        //
+        // y - y₁ = m(x - x₁)
+        // y - y₁ = (y₂ - y₁)/(x₂ - x₁) (x - x₁)
+        // y = (y₂ - y₁)/(x₂ - x₁) (x - x₁) + y₁
+        //
+        // (x₁, y₁) = (deadband, 0) and (x₂, y₂) = (max, max).
+        // x₁ = deadband
+        // y₁ = 0
+        // x₂ = max
+        // y₂ = max
+        //
+        // y = (max - 0)/(max - deadband) (x - deadband) + 0
+        // y = max/(max - deadband) (x - deadband)
+        // y = max (x - deadband)/(max - deadband)
+        return maxMagnitude * (value - deadband) / (maxMagnitude - deadband);
+      } else {
+        // Map -deadband to 0 and map -max to -max.
+        //
+        // y - y₁ = m(x - x₁)
+        // y - y₁ = (y₂ - y₁)/(x₂ - x₁) (x - x₁)
+        // y = (y₂ - y₁)/(x₂ - x₁) (x - x₁) + y₁
+        //
+        // (x₁, y₁) = (-deadband, 0) and (x₂, y₂) = (-max, -max).
+        // x₁ = -deadband
+        // y₁ = 0
+        // x₂ = -max
+        // y₂ = -max
+        //
+        // y = (-max - 0)/(-max + deadband) (x + deadband) + 0
+        // y = max/(max - deadband) (x + deadband)
+        // y = max (x + deadband)/(max - deadband)
+        return maxMagnitude * (value + deadband) / (maxMagnitude - deadband);
+      }
+    } else {
+      return 0.0;
+    }
+  }
+
+  /**
+   * Returns 0.0 if the given value is within the specified range around zero. The remaining range
    * between the deadband and 1.0 is scaled from 0.0 to 1.0.
    *
    * @param value Value to clip.
@@ -42,15 +99,7 @@
    * @return The value after the deadband is applied.
    */
   public static double applyDeadband(double value, double deadband) {
-    if (Math.abs(value) > deadband) {
-      if (value > 0.0) {
-        return (value - deadband) / (1.0 - deadband);
-      } else {
-        return (value + deadband) / (1.0 - deadband);
-      }
-    } else {
-      return 0.0;
-    }
+    return applyDeadband(value, deadband, 1);
   }
 
   /**
@@ -93,7 +142,6 @@
    * @param t How far between the two values to interpolate. This is clamped to [0, 1].
    * @return The interpolated value.
    */
-  @SuppressWarnings("ParameterName")
   public static double interpolate(double startValue, double endValue, double t) {
     return startValue + (endValue - startValue) * MathUtil.clamp(t, 0, 1);
   }
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/Matrix.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/Matrix.java
index 113758b..b8e7c28 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/Matrix.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/Matrix.java
@@ -323,16 +323,42 @@
    * <p>The matrix equation could also be written as x = A<sup>-1</sup>b. Where the pseudo inverse
    * is used if A is not square.
    *
+   * <p>Note that this method does not support solving using a QR decomposition with full-pivoting,
+   * as only column-pivoting is supported. For full-pivoting, use {@link
+   * #solveFullPivHouseholderQr}.
+   *
    * @param <C2> Columns in b.
    * @param b The right-hand side of the equation to solve.
    * @return The solution to the linear system.
    */
-  @SuppressWarnings("ParameterName")
   public final <C2 extends Num> Matrix<C, C2> solve(Matrix<R, C2> b) {
     return new Matrix<>(this.m_storage.solve(Objects.requireNonNull(b).m_storage));
   }
 
   /**
+   * Solves the least-squares problem Ax=B using a QR decomposition with full pivoting, where this
+   * matrix is A.
+   *
+   * @param <R2> Number of rows in B.
+   * @param <C2> Number of columns in B.
+   * @param other The B matrix.
+   * @return The solution matrix.
+   */
+  public final <R2 extends Num, C2 extends Num> Matrix<C, C2> solveFullPivHouseholderQr(
+      Matrix<R2, C2> other) {
+    Matrix<C, C2> solution = new Matrix<>(new SimpleMatrix(this.getNumCols(), other.getNumCols()));
+    WPIMathJNI.solveFullPivHouseholderQr(
+        this.getData(),
+        this.getNumRows(),
+        this.getNumCols(),
+        other.getData(),
+        other.getNumRows(),
+        other.getNumCols(),
+        solution.getData());
+    return solution;
+  }
+
+  /**
    * Computes the matrix exponential using Eigen's solver. This method only works for square
    * matrices, and will otherwise throw an {@link MatrixDimensionException}.
    *
@@ -437,7 +463,6 @@
    * @param b Scalar.
    * @return The element by element power of "this" and b.
    */
-  @SuppressWarnings("ParameterName")
   public final Matrix<R, C> elementPower(double b) {
     return new Matrix<>(this.m_storage.elementPower(b));
   }
@@ -450,7 +475,6 @@
    * @param b Scalar.
    * @return The element by element power of "this" and b.
    */
-  @SuppressWarnings("ParameterName")
   public final Matrix<R, C> elementPower(int b) {
     return new Matrix<>(this.m_storage.elementPower((double) b));
   }
@@ -549,10 +573,9 @@
    * Decompose "this" matrix using Cholesky Decomposition. If the "this" matrix is zeros, it will
    * return the zero matrix.
    *
-   * @param lowerTriangular Whether or not we want to decompose to the lower triangular Cholesky
-   *     matrix.
+   * @param lowerTriangular Whether we want to decompose to the lower triangular Cholesky matrix.
    * @return The decomposed matrix.
-   * @throws RuntimeException if the matrix could not be decomposed(ie. is not positive
+   * @throws RuntimeException if the matrix could not be decomposed(i.e. is not positive
    *     semidefinite).
    */
   public Matrix<R, C> lltDecompose(boolean lowerTriangular) {
@@ -646,10 +669,10 @@
    * same symbolic meaning they both must be either Double.NaN, Double.POSITIVE_INFINITY, or
    * Double.NEGATIVE_INFINITY.
    *
-   * <p>NOTE:It is recommend to use {@link Matrix#isEqual(Matrix, double)} over this method when
+   * <p>NOTE:It is recommended to use {@link Matrix#isEqual(Matrix, double)} over this method when
    * checking if two matrices are equal as {@link Matrix#isEqual(Matrix, double)} will return false
    * if an element is uncountable. This method should only be used when uncountable elements need to
-   * compared.
+   * be compared.
    *
    * @param other The {@link Matrix} to check against this one.
    * @param tolerance The tolerance to check equality with.
@@ -677,6 +700,20 @@
         this.m_storage.getDDRM(), other.m_storage.getDDRM(), tolerance);
   }
 
+  /**
+   * Performs an inplace Cholesky rank update (or downdate).
+   *
+   * <p>If this matrix contains L where A = LLᵀ before the update, it will contain L where LLᵀ = A +
+   * σvvᵀ after the update.
+   *
+   * @param v Vector to use for the update.
+   * @param sigma Sigma to use for the update.
+   * @param lowerTriangular Whether this matrix is lower triangular.
+   */
+  public void rankUpdate(Matrix<R, N1> v, double sigma, boolean lowerTriangular) {
+    WPIMathJNI.rankUpdate(this.getData(), this.getNumRows(), v.getData(), sigma, lowerTriangular);
+  }
+
   @Override
   public String toString() {
     return m_storage.toString();
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/MatrixUtils.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/MatrixUtils.java
deleted file mode 100644
index 7600e31..0000000
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/MatrixUtils.java
+++ /dev/null
@@ -1,80 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.math;
-
-import edu.wpi.first.math.numbers.N1;
-import java.util.Objects;
-import org.ejml.simple.SimpleMatrix;
-
-@Deprecated
-public final class MatrixUtils {
-  private MatrixUtils() {
-    throw new AssertionError("utility class");
-  }
-
-  /**
-   * Creates a new matrix of zeros.
-   *
-   * @param rows The number of rows in the matrix.
-   * @param cols The number of columns in the matrix.
-   * @param <R> The number of rows in the matrix as a generic.
-   * @param <C> The number of columns in the matrix as a generic.
-   * @return An RxC matrix filled with zeros.
-   */
-  @SuppressWarnings("LineLength")
-  public static <R extends Num, C extends Num> Matrix<R, C> zeros(Nat<R> rows, Nat<C> cols) {
-    return new Matrix<>(
-        new SimpleMatrix(
-            Objects.requireNonNull(rows).getNum(), Objects.requireNonNull(cols).getNum()));
-  }
-
-  /**
-   * Creates a new vector of zeros.
-   *
-   * @param nums The size of the desired vector.
-   * @param <N> The size of the desired vector as a generic.
-   * @return A vector of size N filled with zeros.
-   */
-  public static <N extends Num> Matrix<N, N1> zeros(Nat<N> nums) {
-    return new Matrix<>(new SimpleMatrix(Objects.requireNonNull(nums).getNum(), 1));
-  }
-
-  /**
-   * Creates the identity matrix of the given dimension.
-   *
-   * @param dim The dimension of the desired matrix.
-   * @param <D> The dimension of the desired matrix as a generic.
-   * @return The DxD identity matrix.
-   */
-  public static <D extends Num> Matrix<D, D> eye(Nat<D> dim) {
-    return new Matrix<>(SimpleMatrix.identity(Objects.requireNonNull(dim).getNum()));
-  }
-
-  /**
-   * Entrypoint to the MatBuilder class for creation of custom matrices with the given dimensions
-   * and contents.
-   *
-   * @param rows The number of rows of the desired matrix.
-   * @param cols The number of columns of the desired matrix.
-   * @param <R> The number of rows of the desired matrix as a generic.
-   * @param <C> The number of columns of the desired matrix as a generic.
-   * @return A builder to construct the matrix.
-   */
-  public static <R extends Num, C extends Num> MatBuilder<R, C> mat(Nat<R> rows, Nat<C> cols) {
-    return new MatBuilder<>(rows, cols);
-  }
-
-  /**
-   * Entrypoint to the VecBuilder class for creation of custom vectors with the given size and
-   * contents.
-   *
-   * @param dim The dimension of the vector.
-   * @param <D> The dimension of the vector as a generic.
-   * @return A builder to construct the vector.
-   */
-  public static <D extends Num> VecBuilder<D> vec(Nat<D> dim) {
-    return new VecBuilder<>(dim);
-  }
-}
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/Pair.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/Pair.java
index d1a68c7..8ddf1ae 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/Pair.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/Pair.java
@@ -21,7 +21,6 @@
     return m_second;
   }
 
-  @SuppressWarnings("ParameterName")
   public static <A, B> Pair<A, B> of(A a, B b) {
     return new Pair<>(a, b);
   }
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/SimpleMatrixUtils.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/SimpleMatrixUtils.java
index fc78dd1..e1680eb 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/SimpleMatrixUtils.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/SimpleMatrixUtils.java
@@ -21,36 +21,34 @@
    * @param matrix The matrix to compute the exponential of.
    * @return The resultant matrix.
    */
-  @SuppressWarnings({"LocalVariableName", "LineLength"})
   public static SimpleMatrix expm(SimpleMatrix matrix) {
     BiFunction<SimpleMatrix, SimpleMatrix, SimpleMatrix> solveProvider = SimpleBase::solve;
     SimpleMatrix A = matrix;
     double A_L1 = NormOps_DDRM.inducedP1(matrix.getDDRM());
-    int n_squarings = 0;
+    int nSquarings = 0;
 
     if (A_L1 < 1.495585217958292e-002) {
-      Pair<SimpleMatrix, SimpleMatrix> pair = _pade3(A);
-      return dispatchPade(pair.getFirst(), pair.getSecond(), n_squarings, solveProvider);
+      Pair<SimpleMatrix, SimpleMatrix> pair = pade3(A);
+      return dispatchPade(pair.getFirst(), pair.getSecond(), nSquarings, solveProvider);
     } else if (A_L1 < 2.539398330063230e-001) {
-      Pair<SimpleMatrix, SimpleMatrix> pair = _pade5(A);
-      return dispatchPade(pair.getFirst(), pair.getSecond(), n_squarings, solveProvider);
+      Pair<SimpleMatrix, SimpleMatrix> pair = pade5(A);
+      return dispatchPade(pair.getFirst(), pair.getSecond(), nSquarings, solveProvider);
     } else if (A_L1 < 9.504178996162932e-001) {
-      Pair<SimpleMatrix, SimpleMatrix> pair = _pade7(A);
-      return dispatchPade(pair.getFirst(), pair.getSecond(), n_squarings, solveProvider);
+      Pair<SimpleMatrix, SimpleMatrix> pair = pade7(A);
+      return dispatchPade(pair.getFirst(), pair.getSecond(), nSquarings, solveProvider);
     } else if (A_L1 < 2.097847961257068e+000) {
-      Pair<SimpleMatrix, SimpleMatrix> pair = _pade9(A);
-      return dispatchPade(pair.getFirst(), pair.getSecond(), n_squarings, solveProvider);
+      Pair<SimpleMatrix, SimpleMatrix> pair = pade9(A);
+      return dispatchPade(pair.getFirst(), pair.getSecond(), nSquarings, solveProvider);
     } else {
       double maxNorm = 5.371920351148152;
       double log = Math.log(A_L1 / maxNorm) / Math.log(2); // logb(2, arg)
-      n_squarings = (int) Math.max(0, Math.ceil(log));
-      A = A.divide(Math.pow(2.0, n_squarings));
-      Pair<SimpleMatrix, SimpleMatrix> pair = _pade13(A);
-      return dispatchPade(pair.getFirst(), pair.getSecond(), n_squarings, solveProvider);
+      nSquarings = (int) Math.max(0, Math.ceil(log));
+      A = A.divide(Math.pow(2.0, nSquarings));
+      Pair<SimpleMatrix, SimpleMatrix> pair = pade13(A);
+      return dispatchPade(pair.getFirst(), pair.getSecond(), nSquarings, solveProvider);
     }
   }
 
-  @SuppressWarnings({"LocalVariableName", "ParameterName", "LineLength"})
   private static SimpleMatrix dispatchPade(
       SimpleMatrix U,
       SimpleMatrix V,
@@ -68,8 +66,7 @@
     return R;
   }
 
-  @SuppressWarnings({"MethodName", "LocalVariableName", "ParameterName"})
-  private static Pair<SimpleMatrix, SimpleMatrix> _pade3(SimpleMatrix A) {
+  private static Pair<SimpleMatrix, SimpleMatrix> pade3(SimpleMatrix A) {
     double[] b = new double[] {120, 60, 12, 1};
     SimpleMatrix ident = eye(A.numRows(), A.numCols());
 
@@ -79,8 +76,7 @@
     return new Pair<>(U, V);
   }
 
-  @SuppressWarnings({"MethodName", "LocalVariableName", "ParameterName"})
-  private static Pair<SimpleMatrix, SimpleMatrix> _pade5(SimpleMatrix A) {
+  private static Pair<SimpleMatrix, SimpleMatrix> pade5(SimpleMatrix A) {
     double[] b = new double[] {30240, 15120, 3360, 420, 30, 1};
     SimpleMatrix ident = eye(A.numRows(), A.numCols());
     SimpleMatrix A2 = A.mult(A);
@@ -92,8 +88,7 @@
     return new Pair<>(U, V);
   }
 
-  @SuppressWarnings({"MethodName", "LocalVariableName", "LineLength", "ParameterName"})
-  private static Pair<SimpleMatrix, SimpleMatrix> _pade7(SimpleMatrix A) {
+  private static Pair<SimpleMatrix, SimpleMatrix> pade7(SimpleMatrix A) {
     double[] b = new double[] {17297280, 8648640, 1995840, 277200, 25200, 1512, 56, 1};
     SimpleMatrix ident = eye(A.numRows(), A.numCols());
     SimpleMatrix A2 = A.mult(A);
@@ -108,8 +103,7 @@
     return new Pair<>(U, V);
   }
 
-  @SuppressWarnings({"MethodName", "LocalVariableName", "ParameterName", "LineLength"})
-  private static Pair<SimpleMatrix, SimpleMatrix> _pade9(SimpleMatrix A) {
+  private static Pair<SimpleMatrix, SimpleMatrix> pade9(SimpleMatrix A) {
     double[] b =
         new double[] {
           17643225600.0, 8821612800.0, 2075673600, 302702400, 30270240, 2162160, 110880, 3960, 90, 1
@@ -137,8 +131,7 @@
     return new Pair<>(U, V);
   }
 
-  @SuppressWarnings({"MethodName", "LocalVariableName", "LineLength", "ParameterName"})
-  private static Pair<SimpleMatrix, SimpleMatrix> _pade13(SimpleMatrix A) {
+  private static Pair<SimpleMatrix, SimpleMatrix> pade13(SimpleMatrix A) {
     double[] b =
         new double[] {
           64764752532480000.0,
@@ -199,7 +192,7 @@
    *
    * @param src The matrix to decompose.
    * @return The decomposed matrix.
-   * @throws RuntimeException if the matrix could not be decomposed (ie. is not positive
+   * @throws RuntimeException if the matrix could not be decomposed (i.e. is not positive
    *     semidefinite).
    */
   public static SimpleMatrix lltDecompose(SimpleMatrix src) {
@@ -213,7 +206,7 @@
    * @param src The matrix to decompose.
    * @param lowerTriangular if we want to decompose to the lower triangular Cholesky matrix.
    * @return The decomposed matrix.
-   * @throws RuntimeException if the matrix could not be decomposed (ie. is not positive
+   * @throws RuntimeException if the matrix could not be decomposed (i.e. is not positive
    *     semidefinite).
    */
   public static SimpleMatrix lltDecompose(SimpleMatrix src, boolean lowerTriangular) {
@@ -245,7 +238,6 @@
    * @param A the matrix to exponentiate.
    * @return the exponential of A.
    */
-  @SuppressWarnings("ParameterName")
   public static SimpleMatrix exp(SimpleMatrix A) {
     SimpleMatrix toReturn = new SimpleMatrix(A.numRows(), A.numRows());
     WPIMathJNI.exp(A.getDDRM().getData(), A.numRows(), toReturn.getDDRM().getData());
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/StateSpaceUtil.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/StateSpaceUtil.java
index 69430eb..a041845 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/StateSpaceUtil.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/StateSpaceUtil.java
@@ -11,7 +11,6 @@
 import java.util.Random;
 import org.ejml.simple.SimpleMatrix;
 
-@SuppressWarnings("ParameterName")
 public final class StateSpaceUtil {
   private static Random rand = new Random();
 
@@ -31,7 +30,6 @@
    *     output measurement.
    * @return Process noise or measurement noise covariance matrix.
    */
-  @SuppressWarnings("MethodTypeParameterName")
   public static <States extends Num> Matrix<States, States> makeCovarianceMatrix(
       Nat<States> states, Matrix<States, N1> stdDevs) {
     var result = new Matrix<>(states, states);
@@ -61,24 +59,28 @@
   /**
    * Creates a cost matrix from the given vector for use with LQR.
    *
-   * <p>The cost matrix is constructed using Bryson's rule. The inverse square of each element in
-   * the input is taken and placed on the cost matrix diagonal.
+   * <p>The cost matrix is constructed using Bryson's rule. The inverse square of each tolerance is
+   * placed on the cost matrix diagonal. If a tolerance is infinity, its cost matrix entry is set to
+   * zero.
    *
-   * @param <States> Nat representing the states of the system.
-   * @param costs An array. For a Q matrix, its elements are the maximum allowed excursions of the
-   *     states from the reference. For an R matrix, its elements are the maximum allowed excursions
-   *     of the control inputs from no actuation.
+   * @param <Elements> Nat representing the number of system states or inputs.
+   * @param tolerances An array. For a Q matrix, its elements are the maximum allowed excursions of
+   *     the states from the reference. For an R matrix, its elements are the maximum allowed
+   *     excursions of the control inputs from no actuation.
    * @return State excursion or control effort cost matrix.
    */
-  @SuppressWarnings("MethodTypeParameterName")
-  public static <States extends Num> Matrix<States, States> makeCostMatrix(
-      Matrix<States, N1> costs) {
-    Matrix<States, States> result =
-        new Matrix<>(new SimpleMatrix(costs.getNumRows(), costs.getNumRows()));
+  public static <Elements extends Num> Matrix<Elements, Elements> makeCostMatrix(
+      Matrix<Elements, N1> tolerances) {
+    Matrix<Elements, Elements> result =
+        new Matrix<>(new SimpleMatrix(tolerances.getNumRows(), tolerances.getNumRows()));
     result.fill(0.0);
 
-    for (int i = 0; i < costs.getNumRows(); i++) {
-      result.set(i, i, 1.0 / (Math.pow(costs.get(i, 0), 2)));
+    for (int i = 0; i < tolerances.getNumRows(); i++) {
+      if (tolerances.get(i, 0) == Double.POSITIVE_INFINITY) {
+        result.set(i, i, 0.0);
+      } else {
+        result.set(i, i, 1.0 / (Math.pow(tolerances.get(i, 0), 2)));
+      }
     }
 
     return result;
@@ -97,7 +99,6 @@
    * @param B Input matrix.
    * @return If the system is stabilizable.
    */
-  @SuppressWarnings("MethodTypeParameterName")
   public static <States extends Num, Inputs extends Num> boolean isStabilizable(
       Matrix<States, States> A, Matrix<States, Inputs> B) {
     return WPIMathJNI.isStabilizable(A.getNumRows(), B.getNumCols(), A.getData(), B.getData());
@@ -116,7 +117,6 @@
    * @param C Output matrix.
    * @return If the system is detectable.
    */
-  @SuppressWarnings("MethodTypeParameterName")
   public static <States extends Num, Outputs extends Num> boolean isDetectable(
       Matrix<States, States> A, Matrix<Outputs, States> C) {
     return WPIMathJNI.isStabilizable(
@@ -142,7 +142,6 @@
    * @param <I> The number of inputs.
    * @return The clamped input.
    */
-  @SuppressWarnings({"ParameterName", "LocalVariableName"})
   public static <I extends Num> Matrix<I, N1> clampInputMaxMagnitude(
       Matrix<I, N1> u, Matrix<I, N1> umin, Matrix<I, N1> umax) {
     var result = new Matrix<I, N1>(new SimpleMatrix(u.getNumRows(), 1));
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/Vector.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/Vector.java
index 9b06e71..1aebdde 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/Vector.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/Vector.java
@@ -61,4 +61,35 @@
   public Vector<R> div(double value) {
     return new Vector<>(this.m_storage.divide(value));
   }
+
+  /**
+   * Returns the dot product of this vector with another.
+   *
+   * @param other The other vector.
+   * @return The dot product.
+   */
+  public double dot(Vector<R> other) {
+    double dot = 0.0;
+
+    for (int i = 0; i < getNumRows(); ++i) {
+      dot += get(i, 0) * other.get(i, 0);
+    }
+
+    return dot;
+  }
+
+  /**
+   * Returns the norm of this vector.
+   *
+   * @return The norm.
+   */
+  public double norm() {
+    double squaredNorm = 0.0;
+
+    for (int i = 0; i < getNumRows(); ++i) {
+      squaredNorm += get(i, 0) * get(i, 0);
+    }
+
+    return Math.sqrt(squaredNorm);
+  }
 }
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/WPIMathJNI.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/WPIMathJNI.java
index 54445d3..40a5c63 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/WPIMathJNI.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/WPIMathJNI.java
@@ -125,6 +125,19 @@
    */
   public static native String serializeTrajectory(double[] elements);
 
+  /**
+   * Performs an inplace rank one update (or downdate) of an upper triangular Cholesky decomposition
+   * matrix.
+   *
+   * @param mat Array of elements of the matrix to be updated.
+   * @param lowerTriangular Whether mat is lower triangular.
+   * @param rows How many rows there are.
+   * @param vec Vector to use for the rank update.
+   * @param sigma Sigma value to use for the rank update.
+   */
+  public static native void rankUpdate(
+      double[] mat, int rows, double[] vec, double sigma, boolean lowerTriangular);
+
   public static class Helper {
     private static AtomicBoolean extractOnStaticLoad = new AtomicBoolean(true);
 
@@ -136,4 +149,18 @@
       extractOnStaticLoad.set(load);
     }
   }
+
+  /**
+   * Solves the least-squares problem Ax=B using a QR decomposition with full pivoting.
+   *
+   * @param A Array of elements of the A matrix.
+   * @param Arows Number of rows of the A matrix.
+   * @param Acols Number of rows of the A matrix.
+   * @param B Array of elements of the B matrix.
+   * @param Brows Number of rows of the B matrix.
+   * @param Bcols Number of rows of the B matrix.
+   * @param dst Array to store solution in. If A is m-n and B is m-p, dst is n-p.
+   */
+  public static native void solveFullPivHouseholderQr(
+      double[] A, int Arows, int Acols, double[] B, int Brows, int Bcols, double[] dst);
 }
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/ArmFeedforward.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/ArmFeedforward.java
index 2991511..2e9a8d8 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/ArmFeedforward.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/ArmFeedforward.java
@@ -8,10 +8,9 @@
  * A helper class that computes feedforward outputs for a simple arm (modeled as a motor acting
  * against the force of gravity on a beam suspended at an angle).
  */
-@SuppressWarnings("MemberName")
 public class ArmFeedforward {
   public final double ks;
-  public final double kcos;
+  public final double kg;
   public final double kv;
   public final double ka;
 
@@ -20,13 +19,13 @@
    * units of the computed feedforward.
    *
    * @param ks The static gain.
-   * @param kcos The gravity gain.
+   * @param kg The gravity gain.
    * @param kv The velocity gain.
    * @param ka The acceleration gain.
    */
-  public ArmFeedforward(double ks, double kcos, double kv, double ka) {
+  public ArmFeedforward(double ks, double kg, double kv, double ka) {
     this.ks = ks;
-    this.kcos = kcos;
+    this.kg = kg;
     this.kv = kv;
     this.ka = ka;
   }
@@ -36,17 +35,19 @@
    * Units of the gain values will dictate units of the computed feedforward.
    *
    * @param ks The static gain.
-   * @param kcos The gravity gain.
+   * @param kg The gravity gain.
    * @param kv The velocity gain.
    */
-  public ArmFeedforward(double ks, double kcos, double kv) {
-    this(ks, kcos, kv, 0);
+  public ArmFeedforward(double ks, double kg, double kv) {
+    this(ks, kg, kv, 0);
   }
 
   /**
    * Calculates the feedforward from the gains and setpoints.
    *
-   * @param positionRadians The position (angle) setpoint.
+   * @param positionRadians The position (angle) setpoint. This angle should be measured from the
+   *     horizontal (i.e. if the provided angle is 0, the arm should be parallel with the floor). If
+   *     your encoder does not follow this convention, an offset should be added.
    * @param velocityRadPerSec The velocity setpoint.
    * @param accelRadPerSecSquared The acceleration setpoint.
    * @return The computed feedforward.
@@ -54,7 +55,7 @@
   public double calculate(
       double positionRadians, double velocityRadPerSec, double accelRadPerSecSquared) {
     return ks * Math.signum(velocityRadPerSec)
-        + kcos * Math.cos(positionRadians)
+        + kg * Math.cos(positionRadians)
         + kv * velocityRadPerSec
         + ka * accelRadPerSecSquared;
   }
@@ -63,7 +64,9 @@
    * Calculates the feedforward from the gains and velocity setpoint (acceleration is assumed to be
    * zero).
    *
-   * @param positionRadians The position (angle) setpoint.
+   * @param positionRadians The position (angle) setpoint. This angle should be measured from the
+   *     horizontal (i.e. if the provided angle is 0, the arm should be parallel with the floor). If
+   *     your encoder does not follow this convention, an offset should be added.
    * @param velocity The velocity setpoint.
    * @return The computed feedforward.
    */
@@ -81,13 +84,15 @@
    * you a simultaneously-achievable velocity constraint.
    *
    * @param maxVoltage The maximum voltage that can be supplied to the arm.
-   * @param angle The angle of the arm.
+   * @param angle The angle of the arm. This angle should be measured from the horizontal (i.e. if
+   *     the provided angle is 0, the arm should be parallel with the floor). If your encoder does
+   *     not follow this convention, an offset should be added.
    * @param acceleration The acceleration of the arm.
    * @return The maximum possible velocity at the given acceleration and angle.
    */
   public double maxAchievableVelocity(double maxVoltage, double angle, double acceleration) {
     // Assume max velocity is positive
-    return (maxVoltage - ks - Math.cos(angle) * kcos - acceleration * ka) / kv;
+    return (maxVoltage - ks - Math.cos(angle) * kg - acceleration * ka) / kv;
   }
 
   /**
@@ -97,13 +102,15 @@
    * you a simultaneously-achievable velocity constraint.
    *
    * @param maxVoltage The maximum voltage that can be supplied to the arm.
-   * @param angle The angle of the arm.
+   * @param angle The angle of the arm. This angle should be measured from the horizontal (i.e. if
+   *     the provided angle is 0, the arm should be parallel with the floor). If your encoder does
+   *     not follow this convention, an offset should be added.
    * @param acceleration The acceleration of the arm.
    * @return The minimum possible velocity at the given acceleration and angle.
    */
   public double minAchievableVelocity(double maxVoltage, double angle, double acceleration) {
     // Assume min velocity is negative, ks flips sign
-    return (-maxVoltage + ks - Math.cos(angle) * kcos - acceleration * ka) / kv;
+    return (-maxVoltage + ks - Math.cos(angle) * kg - acceleration * ka) / kv;
   }
 
   /**
@@ -113,12 +120,14 @@
    * simultaneously-achievable acceleration constraint.
    *
    * @param maxVoltage The maximum voltage that can be supplied to the arm.
-   * @param angle The angle of the arm.
+   * @param angle The angle of the arm. This angle should be measured from the horizontal (i.e. if
+   *     the provided angle is 0, the arm should be parallel with the floor). If your encoder does
+   *     not follow this convention, an offset should be added.
    * @param velocity The velocity of the arm.
    * @return The maximum possible acceleration at the given velocity.
    */
   public double maxAchievableAcceleration(double maxVoltage, double angle, double velocity) {
-    return (maxVoltage - ks * Math.signum(velocity) - Math.cos(angle) * kcos - velocity * kv) / ka;
+    return (maxVoltage - ks * Math.signum(velocity) - Math.cos(angle) * kg - velocity * kv) / ka;
   }
 
   /**
@@ -128,7 +137,9 @@
    * simultaneously-achievable acceleration constraint.
    *
    * @param maxVoltage The maximum voltage that can be supplied to the arm.
-   * @param angle The angle of the arm.
+   * @param angle The angle of the arm. This angle should be measured from the horizontal (i.e. if
+   *     the provided angle is 0, the arm should be parallel with the floor). If your encoder does
+   *     not follow this convention, an offset should be added.
    * @param velocity The velocity of the arm.
    * @return The minimum possible acceleration at the given velocity.
    */
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/ControlAffinePlantInversionFeedforward.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/ControlAffinePlantInversionFeedforward.java
index d4beabd..385c5c0 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/ControlAffinePlantInversionFeedforward.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/ControlAffinePlantInversionFeedforward.java
@@ -29,16 +29,13 @@
  * <p>For more on the underlying math, read
  * https://file.tavsys.net/control/controls-engineering-in-frc.pdf.
  */
-@SuppressWarnings({"ParameterName", "LocalVariableName", "MemberName", "ClassTypeParameterName"})
 public class ControlAffinePlantInversionFeedforward<States extends Num, Inputs extends Num> {
   /** The current reference state. */
-  @SuppressWarnings("MemberName")
   private Matrix<States, N1> m_r;
 
   /** The computed feedforward. */
   private Matrix<Inputs, N1> m_uff;
 
-  @SuppressWarnings("MemberName")
   private final Matrix<States, Inputs> m_B;
 
   private final Nat<Inputs> m_inputs;
@@ -181,7 +178,6 @@
    * @param nextR The reference state of the future timestep (k + dt).
    * @return The calculated feedforward.
    */
-  @SuppressWarnings({"ParameterName", "LocalVariableName"})
   public Matrix<Inputs, N1> calculate(Matrix<States, N1> r, Matrix<States, N1> nextR) {
     var rDot = (nextR.minus(r)).div(m_dt);
 
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/DifferentialDriveAccelerationLimiter.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/DifferentialDriveAccelerationLimiter.java
new file mode 100644
index 0000000..8c47765
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/DifferentialDriveAccelerationLimiter.java
@@ -0,0 +1,130 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.math.controller;
+
+import edu.wpi.first.math.MatBuilder;
+import edu.wpi.first.math.Nat;
+import edu.wpi.first.math.numbers.N2;
+import edu.wpi.first.math.system.LinearSystem;
+
+/**
+ * Filters the provided voltages to limit a differential drive's linear and angular acceleration.
+ *
+ * <p>The differential drive model can be created via the functions in {@link
+ * edu.wpi.first.math.system.plant.LinearSystemId}.
+ */
+public class DifferentialDriveAccelerationLimiter {
+  private final LinearSystem<N2, N2, N2> m_system;
+  private final double m_trackwidth;
+  private final double m_minLinearAccel;
+  private final double m_maxLinearAccel;
+  private final double m_maxAngularAccel;
+
+  /**
+   * Constructs a DifferentialDriveAccelerationLimiter.
+   *
+   * @param system The differential drive dynamics.
+   * @param trackwidth The distance between the differential drive's left and right wheels in
+   *     meters.
+   * @param maxLinearAccel The maximum linear acceleration in meters per second squared.
+   * @param maxAngularAccel The maximum angular acceleration in radians per second squared.
+   */
+  public DifferentialDriveAccelerationLimiter(
+      LinearSystem<N2, N2, N2> system,
+      double trackwidth,
+      double maxLinearAccel,
+      double maxAngularAccel) {
+    this(system, trackwidth, -maxLinearAccel, maxLinearAccel, maxAngularAccel);
+  }
+
+  /**
+   * Constructs a DifferentialDriveAccelerationLimiter.
+   *
+   * @param system The differential drive dynamics.
+   * @param trackwidth The distance between the differential drive's left and right wheels in
+   *     meters.
+   * @param minLinearAccel The minimum (most negative) linear acceleration in meters per second
+   *     squared.
+   * @param maxLinearAccel The maximum (most positive) linear acceleration in meters per second
+   *     squared.
+   * @param maxAngularAccel The maximum angular acceleration in radians per second squared.
+   * @throws IllegalArgumentException if minimum linear acceleration is greater than maximum linear
+   *     acceleration
+   */
+  public DifferentialDriveAccelerationLimiter(
+      LinearSystem<N2, N2, N2> system,
+      double trackwidth,
+      double minLinearAccel,
+      double maxLinearAccel,
+      double maxAngularAccel) {
+    if (minLinearAccel > maxLinearAccel) {
+      throw new IllegalArgumentException("maxLinearAccel must be greater than minLinearAccel");
+    }
+    m_system = system;
+    m_trackwidth = trackwidth;
+    m_minLinearAccel = minLinearAccel;
+    m_maxLinearAccel = maxLinearAccel;
+    m_maxAngularAccel = maxAngularAccel;
+  }
+
+  /**
+   * Returns the next voltage pair subject to acceleration constraints.
+   *
+   * @param leftVelocity The left wheel velocity in meters per second.
+   * @param rightVelocity The right wheel velocity in meters per second.
+   * @param leftVoltage The unconstrained left motor voltage.
+   * @param rightVoltage The unconstrained right motor voltage.
+   * @return The constrained wheel voltages.
+   */
+  public DifferentialDriveWheelVoltages calculate(
+      double leftVelocity, double rightVelocity, double leftVoltage, double rightVoltage) {
+    var u = new MatBuilder<>(Nat.N2(), Nat.N1()).fill(leftVoltage, rightVoltage);
+
+    // Find unconstrained wheel accelerations
+    var x = new MatBuilder<>(Nat.N2(), Nat.N1()).fill(leftVelocity, rightVelocity);
+    var dxdt = m_system.getA().times(x).plus(m_system.getB().times(u));
+
+    // Convert from wheel accelerations to linear and angular accelerations
+    //
+    // a = (dxdt(0) + dx/dt(1)) / 2
+    //   = 0.5 dxdt(0) + 0.5 dxdt(1)
+    //
+    // α = (dxdt(1) - dxdt(0)) / trackwidth
+    //   = -1/trackwidth dxdt(0) + 1/trackwidth dxdt(1)
+    //
+    // [a] = [          0.5           0.5][dxdt(0)]
+    // [α]   [-1/trackwidth  1/trackwidth][dxdt(1)]
+    //
+    // accels = M dxdt where M = [0.5, 0.5; -1/trackwidth, 1/trackwidth]
+    var M =
+        new MatBuilder<>(Nat.N2(), Nat.N2())
+            .fill(0.5, 0.5, -1.0 / m_trackwidth, 1.0 / m_trackwidth);
+    var accels = M.times(dxdt);
+
+    // Constrain the linear and angular accelerations
+    if (accels.get(0, 0) > m_maxLinearAccel) {
+      accels.set(0, 0, m_maxLinearAccel);
+    } else if (accels.get(0, 0) < m_minLinearAccel) {
+      accels.set(0, 0, m_minLinearAccel);
+    }
+    if (accels.get(1, 0) > m_maxAngularAccel) {
+      accels.set(1, 0, m_maxAngularAccel);
+    } else if (accels.get(1, 0) < -m_maxAngularAccel) {
+      accels.set(1, 0, -m_maxAngularAccel);
+    }
+
+    // Convert the constrained linear and angular accelerations back to wheel
+    // accelerations
+    dxdt = M.solve(accels);
+
+    // Find voltages for the given wheel accelerations
+    //
+    // dx/dt = Ax + Bu
+    // u = B⁻¹(dx/dt - Ax)
+    u = m_system.getB().solve(dxdt.minus(m_system.getA().times(x)));
+
+    return new DifferentialDriveWheelVoltages(u.get(0, 0), u.get(1, 0));
+  }
+}
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/DifferentialDriveFeedforward.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/DifferentialDriveFeedforward.java
new file mode 100644
index 0000000..4d0c94f
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/DifferentialDriveFeedforward.java
@@ -0,0 +1,70 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.math.controller;
+
+import edu.wpi.first.math.VecBuilder;
+import edu.wpi.first.math.numbers.N2;
+import edu.wpi.first.math.system.LinearSystem;
+import edu.wpi.first.math.system.plant.LinearSystemId;
+
+/** A helper class which computes the feedforward outputs for a differential drive drivetrain. */
+public class DifferentialDriveFeedforward {
+  private final LinearSystem<N2, N2, N2> m_plant;
+
+  /**
+   * Creates a new DifferentialDriveFeedforward with the specified parameters.
+   *
+   * @param kVLinear The linear velocity gain in volts per (meters per second).
+   * @param kALinear The linear acceleration gain in volts per (meters per second squared).
+   * @param kVAngular The angular velocity gain in volts per (radians per second).
+   * @param kAAngular The angular acceleration gain in volts per (radians per second squared).
+   * @param trackwidth The distance between the differential drive's left and right wheels, in
+   *     meters.
+   */
+  public DifferentialDriveFeedforward(
+      double kVLinear, double kALinear, double kVAngular, double kAAngular, double trackwidth) {
+    m_plant =
+        LinearSystemId.identifyDrivetrainSystem(
+            kVLinear, kALinear, kVAngular, kAAngular, trackwidth);
+  }
+
+  /**
+   * Creates a new DifferentialDriveFeedforward with the specified parameters.
+   *
+   * @param kVLinear The linear velocity gain in volts per (meters per second).
+   * @param kALinear The linear acceleration gain in volts per (meters per second squared).
+   * @param kVAngular The angular velocity gain in volts per (meters per second).
+   * @param kAAngular The angular acceleration gain in volts per (meters per second squared).
+   */
+  public DifferentialDriveFeedforward(
+      double kVLinear, double kALinear, double kVAngular, double kAAngular) {
+    m_plant = LinearSystemId.identifyDrivetrainSystem(kVLinear, kALinear, kVAngular, kAAngular);
+  }
+
+  /**
+   * Calculates the differential drive feedforward inputs given velocity setpoints.
+   *
+   * @param currentLeftVelocity The current left velocity of the differential drive in
+   *     meters/second.
+   * @param nextLeftVelocity The next left velocity of the differential drive in meters/second.
+   * @param currentRightVelocity The current right velocity of the differential drive in
+   *     meters/second.
+   * @param nextRightVelocity The next right velocity of the differential drive in meters/second.
+   * @param dtSeconds Discretization timestep.
+   * @return A DifferentialDriveWheelVoltages object containing the computed feedforward voltages.
+   */
+  public DifferentialDriveWheelVoltages calculate(
+      double currentLeftVelocity,
+      double nextLeftVelocity,
+      double currentRightVelocity,
+      double nextRightVelocity,
+      double dtSeconds) {
+    var feedforward = new LinearPlantInversionFeedforward<>(m_plant, dtSeconds);
+    var r = VecBuilder.fill(currentLeftVelocity, currentRightVelocity);
+    var nextR = VecBuilder.fill(nextLeftVelocity, nextRightVelocity);
+    var u = feedforward.calculate(r, nextR);
+    return new DifferentialDriveWheelVoltages(u.get(0, 0), u.get(1, 0));
+  }
+}
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/DifferentialDriveWheelVoltages.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/DifferentialDriveWheelVoltages.java
new file mode 100644
index 0000000..2fbd0aa
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/DifferentialDriveWheelVoltages.java
@@ -0,0 +1,18 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.math.controller;
+
+/** Motor voltages for a differential drive. */
+public class DifferentialDriveWheelVoltages {
+  public double left;
+  public double right;
+
+  public DifferentialDriveWheelVoltages() {}
+
+  public DifferentialDriveWheelVoltages(double left, double right) {
+    this.left = left;
+    this.right = right;
+  }
+}
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/ElevatorFeedforward.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/ElevatorFeedforward.java
index 248015f..9f4dd86 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/ElevatorFeedforward.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/ElevatorFeedforward.java
@@ -8,7 +8,6 @@
  * A helper class that computes feedforward outputs for a simple elevator (modeled as a motor acting
  * against the force of gravity).
  */
-@SuppressWarnings("MemberName")
 public class ElevatorFeedforward {
   public final double ks;
   public final double kg;
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/HolonomicDriveController.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/HolonomicDriveController.java
index be813cc..e43c6ff 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/HolonomicDriveController.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/HolonomicDriveController.java
@@ -8,6 +8,7 @@
 import edu.wpi.first.math.geometry.Rotation2d;
 import edu.wpi.first.math.kinematics.ChassisSpeeds;
 import edu.wpi.first.math.trajectory.Trajectory;
+import edu.wpi.first.math.util.Units;
 
 /**
  * This holonomic drive controller can be used to follow trajectories using a holonomic drivetrain
@@ -20,7 +21,6 @@
  * are decoupled from translations, users can specify a custom heading that the drivetrain should
  * point toward. This heading reference is profiled for smoothness.
  */
-@SuppressWarnings("MemberName")
 public class HolonomicDriveController {
   private Pose2d m_poseError = new Pose2d();
   private Rotation2d m_rotationError = new Rotation2d();
@@ -40,12 +40,12 @@
    * @param yController A PID Controller to respond to error in the field-relative y direction.
    * @param thetaController A profiled PID controller to respond to error in angle.
    */
-  @SuppressWarnings("ParameterName")
   public HolonomicDriveController(
       PIDController xController, PIDController yController, ProfiledPIDController thetaController) {
     m_xController = xController;
     m_yController = yController;
     m_thetaController = thetaController;
+    m_thetaController.enableContinuousInput(0, Units.degreesToRadians(360.0));
   }
 
   /**
@@ -75,15 +75,17 @@
   /**
    * Returns the next output of the holonomic drive controller.
    *
-   * @param currentPose The current pose.
-   * @param poseRef The desired pose.
-   * @param linearVelocityRefMeters The linear velocity reference.
-   * @param angleRef The angular reference.
+   * @param currentPose The current pose, as measured by odometry or pose estimator.
+   * @param trajectoryPose The desired trajectory pose, as sampled for the current timestep.
+   * @param desiredLinearVelocityMetersPerSecond The desired linear velocity.
+   * @param desiredHeading The desired heading.
    * @return The next output of the holonomic drive controller.
    */
-  @SuppressWarnings("LocalVariableName")
   public ChassisSpeeds calculate(
-      Pose2d currentPose, Pose2d poseRef, double linearVelocityRefMeters, Rotation2d angleRef) {
+      Pose2d currentPose,
+      Pose2d trajectoryPose,
+      double desiredLinearVelocityMetersPerSecond,
+      Rotation2d desiredHeading) {
     // If this is the first run, then we need to reset the theta controller to the current pose's
     // heading.
     if (m_firstRun) {
@@ -92,21 +94,22 @@
     }
 
     // Calculate feedforward velocities (field-relative).
-    double xFF = linearVelocityRefMeters * poseRef.getRotation().getCos();
-    double yFF = linearVelocityRefMeters * poseRef.getRotation().getSin();
+    double xFF = desiredLinearVelocityMetersPerSecond * trajectoryPose.getRotation().getCos();
+    double yFF = desiredLinearVelocityMetersPerSecond * trajectoryPose.getRotation().getSin();
     double thetaFF =
-        m_thetaController.calculate(currentPose.getRotation().getRadians(), angleRef.getRadians());
+        m_thetaController.calculate(
+            currentPose.getRotation().getRadians(), desiredHeading.getRadians());
 
-    m_poseError = poseRef.relativeTo(currentPose);
-    m_rotationError = angleRef.minus(currentPose.getRotation());
+    m_poseError = trajectoryPose.relativeTo(currentPose);
+    m_rotationError = desiredHeading.minus(currentPose.getRotation());
 
     if (!m_enabled) {
       return ChassisSpeeds.fromFieldRelativeSpeeds(xFF, yFF, thetaFF, currentPose.getRotation());
     }
 
     // Calculate feedback velocities (based on position error).
-    double xFeedback = m_xController.calculate(currentPose.getX(), poseRef.getX());
-    double yFeedback = m_yController.calculate(currentPose.getY(), poseRef.getY());
+    double xFeedback = m_xController.calculate(currentPose.getX(), trajectoryPose.getX());
+    double yFeedback = m_yController.calculate(currentPose.getY(), trajectoryPose.getY());
 
     // Return next output.
     return ChassisSpeeds.fromFieldRelativeSpeeds(
@@ -116,15 +119,15 @@
   /**
    * Returns the next output of the holonomic drive controller.
    *
-   * @param currentPose The current pose.
-   * @param desiredState The desired trajectory state.
-   * @param angleRef The desired end-angle.
+   * @param currentPose The current pose, as measured by odometry or pose estimator.
+   * @param desiredState The desired trajectory pose, as sampled for the current timestep.
+   * @param desiredHeading The desired heading.
    * @return The next output of the holonomic drive controller.
    */
   public ChassisSpeeds calculate(
-      Pose2d currentPose, Trajectory.State desiredState, Rotation2d angleRef) {
+      Pose2d currentPose, Trajectory.State desiredState, Rotation2d desiredHeading) {
     return calculate(
-        currentPose, desiredState.poseMeters, desiredState.velocityMetersPerSecond, angleRef);
+        currentPose, desiredState.poseMeters, desiredState.velocityMetersPerSecond, desiredHeading);
   }
 
   /**
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/ImplicitModelFollower.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/ImplicitModelFollower.java
new file mode 100644
index 0000000..7aa4cfa
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/ImplicitModelFollower.java
@@ -0,0 +1,117 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.math.controller;
+
+import edu.wpi.first.math.Matrix;
+import edu.wpi.first.math.Num;
+import edu.wpi.first.math.numbers.N1;
+import edu.wpi.first.math.system.LinearSystem;
+import org.ejml.simple.SimpleMatrix;
+
+/**
+ * Contains the controller coefficients and logic for an implicit model follower.
+ *
+ * <p>Implicit model following lets us design a feedback controller that erases the dynamics of our
+ * system and makes it behave like some other system. This can be used to make a drivetrain more
+ * controllable during teleop driving by making it behave like a slower or more benign drivetrain.
+ *
+ * <p>For more on the underlying math, read appendix B.3 in
+ * https://file.tavsys.net/control/controls-engineering-in-frc.pdf.
+ */
+public class ImplicitModelFollower<States extends Num, Inputs extends Num, Outputs extends Num> {
+  // Computed controller output
+  private Matrix<Inputs, N1> m_u;
+
+  // State space conversion gain
+  private Matrix<Inputs, States> m_A;
+
+  // Input space conversion gain
+  private Matrix<Inputs, Inputs> m_B;
+
+  /**
+   * Constructs a controller with the given coefficients and plant.
+   *
+   * @param plant The plant being controlled.
+   * @param plantRef The plant whose dynamics should be followed.
+   */
+  public ImplicitModelFollower(
+      LinearSystem<States, Inputs, Outputs> plant, LinearSystem<States, Inputs, Outputs> plantRef) {
+    this(plant.getA(), plant.getB(), plantRef.getA(), plantRef.getB());
+  }
+
+  /**
+   * Constructs a controller with the given coefficients and plant.
+   *
+   * @param A Continuous system matrix of the plant being controlled.
+   * @param B Continuous input matrix of the plant being controlled.
+   * @param Aref Continuous system matrix whose dynamics should be followed.
+   * @param Bref Continuous input matrix whose dynamics should be followed.
+   */
+  public ImplicitModelFollower(
+      Matrix<States, States> A,
+      Matrix<States, Inputs> B,
+      Matrix<States, States> Aref,
+      Matrix<States, Inputs> Bref) {
+    m_u = new Matrix<>(new SimpleMatrix(B.getNumCols(), 1));
+
+    // Find u_imf that makes real model match reference model.
+    //
+    // dx/dt = Ax + Bu_imf
+    // dz/dt = A_ref z + B_ref u
+    //
+    // Let x = z.
+    //
+    // dx/dt = dz/dt
+    // Ax + Bu_imf = Aref x + B_ref u
+    // Bu_imf = A_ref x - Ax + B_ref u
+    // Bu_imf = (A_ref - A)x + B_ref u
+    // u_imf = B⁻¹((A_ref - A)x + Bref u)
+    // u_imf = -B⁻¹(A - A_ref)x + B⁻¹B_ref u
+
+    // The first term makes the open-loop poles that of the reference
+    // system, and the second term makes the input behave like that of the
+    // reference system.
+    m_A = B.solve(A.minus(Aref)).times(-1.0);
+    m_B = B.solve(Bref);
+
+    reset();
+  }
+
+  /**
+   * Returns the control input vector u.
+   *
+   * @return The control input.
+   */
+  public Matrix<Inputs, N1> getU() {
+    return m_u;
+  }
+
+  /**
+   * Returns an element of the control input vector u.
+   *
+   * @param i Row of u.
+   * @return The row of the control input vector.
+   */
+  public double getU(int i) {
+    return m_u.get(i, 0);
+  }
+
+  /** Resets the controller. */
+  public void reset() {
+    m_u.fill(0.0);
+  }
+
+  /**
+   * Returns the next output of the controller.
+   *
+   * @param x The current state x.
+   * @param u The current input for the original model.
+   * @return The next controller output.
+   */
+  public Matrix<Inputs, N1> calculate(Matrix<States, N1> x, Matrix<Inputs, N1> u) {
+    m_u = m_A.times(x).plus(m_B.times(u));
+    return m_u;
+  }
+}
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/LTVDifferentialDriveController.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/LTVDifferentialDriveController.java
new file mode 100644
index 0000000..46254a3
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/LTVDifferentialDriveController.java
@@ -0,0 +1,270 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.math.controller;
+
+import edu.wpi.first.math.InterpolatingMatrixTreeMap;
+import edu.wpi.first.math.MatBuilder;
+import edu.wpi.first.math.MathUtil;
+import edu.wpi.first.math.Matrix;
+import edu.wpi.first.math.Nat;
+import edu.wpi.first.math.StateSpaceUtil;
+import edu.wpi.first.math.Vector;
+import edu.wpi.first.math.geometry.Pose2d;
+import edu.wpi.first.math.numbers.N1;
+import edu.wpi.first.math.numbers.N2;
+import edu.wpi.first.math.numbers.N5;
+import edu.wpi.first.math.system.LinearSystem;
+import edu.wpi.first.math.trajectory.Trajectory;
+
+/**
+ * The linear time-varying differential drive controller has a similar form to the LQR, but the
+ * model used to compute the controller gain is the nonlinear model linearized around the
+ * drivetrain's current state. We precomputed gains for important places in our state-space, then
+ * interpolated between them with a LUT to save computational resources.
+ *
+ * <p>See section 8.7 in Controls Engineering in FRC for a derivation of the control law we used
+ * shown in theorem 8.7.4.
+ */
+public class LTVDifferentialDriveController {
+  private final double m_trackwidth;
+
+  // LUT from drivetrain linear velocity to LQR gain
+  private final InterpolatingMatrixTreeMap<Double, N2, N5> m_table =
+      new InterpolatingMatrixTreeMap<>();
+
+  private Matrix<N5, N1> m_error = new Matrix<>(Nat.N5(), Nat.N1());
+  private Matrix<N5, N1> m_tolerance = new Matrix<>(Nat.N5(), Nat.N1());
+
+  /** States of the drivetrain system. */
+  private enum State {
+    kX(0),
+    kY(1),
+    kHeading(2),
+    kLeftVelocity(3),
+    kRightVelocity(4);
+
+    public final int value;
+
+    State(int i) {
+      this.value = i;
+    }
+  }
+
+  /**
+   * Constructs a linear time-varying differential drive controller.
+   *
+   * @param plant The differential drive velocity plant.
+   * @param trackwidth The distance between the differential drive's left and right wheels in
+   *     meters.
+   * @param qelems The maximum desired error tolerance for each state.
+   * @param relems The maximum desired control effort for each input.
+   * @param dt Discretization timestep in seconds.
+   */
+  public LTVDifferentialDriveController(
+      LinearSystem<N2, N2, N2> plant,
+      double trackwidth,
+      Vector<N5> qelems,
+      Vector<N2> relems,
+      double dt) {
+    m_trackwidth = trackwidth;
+
+    // Control law derivation is in section 8.7 of
+    // https://file.tavsys.net/control/controls-engineering-in-frc.pdf
+    var A =
+        new MatBuilder<>(Nat.N5(), Nat.N5())
+            .fill(
+                0.0,
+                0.0,
+                0.0,
+                0.5,
+                0.5,
+                0.0,
+                0.0,
+                0.0,
+                0.0,
+                0.0,
+                0.0,
+                0.0,
+                0.0,
+                -1.0 / m_trackwidth,
+                1.0 / m_trackwidth,
+                0.0,
+                0.0,
+                0.0,
+                plant.getA(0, 0),
+                plant.getA(0, 1),
+                0.0,
+                0.0,
+                0.0,
+                plant.getA(1, 0),
+                plant.getA(1, 1));
+    var B =
+        new MatBuilder<>(Nat.N5(), Nat.N2())
+            .fill(
+                0.0,
+                0.0,
+                0.0,
+                0.0,
+                0.0,
+                0.0,
+                plant.getB(0, 0),
+                plant.getB(0, 1),
+                plant.getB(1, 0),
+                plant.getB(1, 1));
+    var Q = StateSpaceUtil.makeCostMatrix(qelems);
+    var R = StateSpaceUtil.makeCostMatrix(relems);
+
+    // dx/dt = Ax + Bu
+    // 0 = Ax + Bu
+    // Ax = -Bu
+    // x = -A⁻¹Bu
+    double maxV =
+        plant
+            .getA()
+            .solve(plant.getB().times(new MatBuilder<>(Nat.N2(), Nat.N1()).fill(12.0, 12.0)))
+            .times(-1.0)
+            .get(0, 0);
+
+    for (double velocity = -maxV; velocity < maxV; velocity += 0.01) {
+      // The DARE is ill-conditioned if the velocity is close to zero, so don't
+      // let the system stop.
+      if (Math.abs(velocity) < 1e-4) {
+        m_table.put(velocity, new Matrix<>(Nat.N2(), Nat.N5()));
+      } else {
+        A.set(State.kY.value, State.kHeading.value, velocity);
+        m_table.put(velocity, new LinearQuadraticRegulator<N5, N2, N5>(A, B, Q, R, dt).getK());
+      }
+    }
+  }
+
+  /**
+   * Returns true if the pose error is within tolerance of the reference.
+   *
+   * @return True if the pose error is within tolerance of the reference.
+   */
+  public boolean atReference() {
+    return Math.abs(m_error.get(0, 0)) < m_tolerance.get(0, 0)
+        && Math.abs(m_error.get(1, 0)) < m_tolerance.get(1, 0)
+        && Math.abs(m_error.get(2, 0)) < m_tolerance.get(2, 0)
+        && Math.abs(m_error.get(3, 0)) < m_tolerance.get(3, 0)
+        && Math.abs(m_error.get(4, 0)) < m_tolerance.get(4, 0);
+  }
+
+  /**
+   * Sets the pose error which is considered tolerable for use with atReference().
+   *
+   * @param poseTolerance Pose error which is tolerable.
+   * @param leftVelocityTolerance Left velocity error which is tolerable in meters per second.
+   * @param rightVelocityTolerance Right velocity error which is tolerable in meters per second.
+   */
+  public void setTolerance(
+      Pose2d poseTolerance, double leftVelocityTolerance, double rightVelocityTolerance) {
+    m_tolerance =
+        new MatBuilder<>(Nat.N5(), Nat.N1())
+            .fill(
+                poseTolerance.getX(),
+                poseTolerance.getY(),
+                poseTolerance.getRotation().getRadians(),
+                leftVelocityTolerance,
+                rightVelocityTolerance);
+  }
+
+  /**
+   * Returns the left and right output voltages of the LTV controller.
+   *
+   * <p>The reference pose, linear velocity, and angular velocity should come from a drivetrain
+   * trajectory.
+   *
+   * @param currentPose The current pose.
+   * @param leftVelocity The current left velocity in meters per second.
+   * @param rightVelocity The current right velocity in meters per second.
+   * @param poseRef The desired pose.
+   * @param leftVelocityRef The desired left velocity in meters per second.
+   * @param rightVelocityRef The desired right velocity in meters per second.
+   * @return Left and right output voltages of the LTV controller.
+   */
+  public DifferentialDriveWheelVoltages calculate(
+      Pose2d currentPose,
+      double leftVelocity,
+      double rightVelocity,
+      Pose2d poseRef,
+      double leftVelocityRef,
+      double rightVelocityRef) {
+    // This implements the linear time-varying differential drive controller in
+    // theorem 9.6.3 of https://tavsys.net/controls-in-frc.
+    var x =
+        new MatBuilder<>(Nat.N5(), Nat.N1())
+            .fill(
+                currentPose.getX(),
+                currentPose.getY(),
+                currentPose.getRotation().getRadians(),
+                leftVelocity,
+                rightVelocity);
+
+    var inRobotFrame = Matrix.eye(Nat.N5());
+    inRobotFrame.set(0, 0, Math.cos(x.get(State.kHeading.value, 0)));
+    inRobotFrame.set(0, 1, Math.sin(x.get(State.kHeading.value, 0)));
+    inRobotFrame.set(1, 0, -Math.sin(x.get(State.kHeading.value, 0)));
+    inRobotFrame.set(1, 1, Math.cos(x.get(State.kHeading.value, 0)));
+
+    var r =
+        new MatBuilder<>(Nat.N5(), Nat.N1())
+            .fill(
+                poseRef.getX(),
+                poseRef.getY(),
+                poseRef.getRotation().getRadians(),
+                leftVelocityRef,
+                rightVelocityRef);
+    m_error = r.minus(x);
+    m_error.set(
+        State.kHeading.value, 0, MathUtil.angleModulus(m_error.get(State.kHeading.value, 0)));
+
+    double velocity = (leftVelocity + rightVelocity) / 2.0;
+    var K = m_table.get(velocity);
+
+    var u = K.times(inRobotFrame).times(m_error);
+
+    return new DifferentialDriveWheelVoltages(u.get(0, 0), u.get(1, 0));
+  }
+
+  /**
+   * Returns the left and right output voltages of the LTV controller.
+   *
+   * <p>The reference pose, linear velocity, and angular velocity should come from a drivetrain
+   * trajectory.
+   *
+   * @param currentPose The current pose.
+   * @param leftVelocity The left velocity in meters per second.
+   * @param rightVelocity The right velocity in meters per second.
+   * @param desiredState The desired pose, linear velocity, and angular velocity from a trajectory.
+   * @return The left and right output voltages of the LTV controller.
+   */
+  public DifferentialDriveWheelVoltages calculate(
+      Pose2d currentPose,
+      double leftVelocity,
+      double rightVelocity,
+      Trajectory.State desiredState) {
+    // v = (v_r + v_l) / 2     (1)
+    // w = (v_r - v_l) / (2r)  (2)
+    // k = w / v               (3)
+    //
+    // v_l = v - wr
+    // v_l = v - (vk)r
+    // v_l = v(1 - kr)
+    //
+    // v_r = v + wr
+    // v_r = v + (vk)r
+    // v_r = v(1 + kr)
+    return calculate(
+        currentPose,
+        leftVelocity,
+        rightVelocity,
+        desiredState.poseMeters,
+        desiredState.velocityMetersPerSecond
+            * (1 - (desiredState.curvatureRadPerMeter * m_trackwidth / 2.0)),
+        desiredState.velocityMetersPerSecond
+            * (1 + (desiredState.curvatureRadPerMeter * m_trackwidth / 2.0)));
+  }
+}
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/LTVUnicycleController.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/LTVUnicycleController.java
new file mode 100644
index 0000000..701f21b
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/LTVUnicycleController.java
@@ -0,0 +1,226 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.math.controller;
+
+import edu.wpi.first.math.InterpolatingMatrixTreeMap;
+import edu.wpi.first.math.MatBuilder;
+import edu.wpi.first.math.Matrix;
+import edu.wpi.first.math.Nat;
+import edu.wpi.first.math.StateSpaceUtil;
+import edu.wpi.first.math.VecBuilder;
+import edu.wpi.first.math.Vector;
+import edu.wpi.first.math.geometry.Pose2d;
+import edu.wpi.first.math.kinematics.ChassisSpeeds;
+import edu.wpi.first.math.numbers.N2;
+import edu.wpi.first.math.numbers.N3;
+import edu.wpi.first.math.trajectory.Trajectory;
+
+/**
+ * The linear time-varying unicycle controller has a similar form to the LQR, but the model used to
+ * compute the controller gain is the nonlinear model linearized around the drivetrain's current
+ * state.
+ *
+ * <p>See section 8.9 in Controls Engineering in FRC for a derivation of the control law we used
+ * shown in theorem 8.9.1.
+ */
+public class LTVUnicycleController {
+  // LUT from drivetrain linear velocity to LQR gain
+  private final InterpolatingMatrixTreeMap<Double, N2, N3> m_table =
+      new InterpolatingMatrixTreeMap<>();
+
+  private Pose2d m_poseError;
+  private Pose2d m_poseTolerance;
+  private boolean m_enabled = true;
+
+  /** States of the drivetrain system. */
+  private enum State {
+    kX(0),
+    kY(1),
+    kHeading(2);
+
+    public final int value;
+
+    State(int i) {
+      this.value = i;
+    }
+  }
+
+  /**
+   * Constructs a linear time-varying unicycle controller with default maximum desired error
+   * tolerances of (0.0625 m, 0.125 m, 2 rad) and default maximum desired control effort of (1 m/s,
+   * 2 rad/s).
+   *
+   * @param dt Discretization timestep in seconds.
+   */
+  public LTVUnicycleController(double dt) {
+    this(VecBuilder.fill(0.0625, 0.125, 2.0), VecBuilder.fill(1.0, 2.0), dt, 9.0);
+  }
+
+  /**
+   * Constructs a linear time-varying unicycle controller with default maximum desired error
+   * tolerances of (0.0625 m, 0.125 m, 2 rad) and default maximum desired control effort of (1 m/s,
+   * 2 rad/s).
+   *
+   * @param dt Discretization timestep in seconds.
+   * @param maxVelocity The maximum velocity in meters per second for the controller gain lookup
+   *     table. The default is 9 m/s.
+   */
+  public LTVUnicycleController(double dt, double maxVelocity) {
+    this(VecBuilder.fill(0.0625, 0.125, 2.0), VecBuilder.fill(1.0, 2.0), dt, maxVelocity);
+  }
+
+  /**
+   * Constructs a linear time-varying unicycle controller.
+   *
+   * @param qelems The maximum desired error tolerance for each state.
+   * @param relems The maximum desired control effort for each input.
+   * @param dt Discretization timestep in seconds.
+   */
+  public LTVUnicycleController(Vector<N3> qelems, Vector<N2> relems, double dt) {
+    this(qelems, relems, dt, 9.0);
+  }
+
+  /**
+   * Constructs a linear time-varying unicycle controller.
+   *
+   * @param qelems The maximum desired error tolerance for each state.
+   * @param relems The maximum desired control effort for each input.
+   * @param dt Discretization timestep in seconds.
+   * @param maxVelocity The maximum velocity in meters per second for the controller gain lookup
+   *     table. The default is 9 m/s.
+   */
+  public LTVUnicycleController(
+      Vector<N3> qelems, Vector<N2> relems, double dt, double maxVelocity) {
+    // The change in global pose for a unicycle is defined by the following
+    // three equations.
+    //
+    // ẋ = v cosθ
+    // ẏ = v sinθ
+    // θ̇ = ω
+    //
+    // Here's the model as a vector function where x = [x  y  θ]ᵀ and
+    // u = [v  ω]ᵀ.
+    //
+    //           [v cosθ]
+    // f(x, u) = [v sinθ]
+    //           [  ω   ]
+    //
+    // To create an LQR, we need to linearize this.
+    //
+    //               [0  0  −v sinθ]                  [cosθ  0]
+    // ∂f(x, u)/∂x = [0  0   v cosθ]    ∂f(x, u)/∂u = [sinθ  0]
+    //               [0  0     0   ]                  [ 0    1]
+    //
+    // We're going to make a cross-track error controller, so we'll apply a
+    // clockwise rotation matrix to the global tracking error to transform it
+    // into the robot's coordinate frame. Since the cross-track error is always
+    // measured from the robot's coordinate frame, the model used to compute the
+    // LQR should be linearized around θ = 0 at all times.
+    //
+    //     [0  0  −v sin0]        [cos0  0]
+    // A = [0  0   v cos0]    B = [sin0  0]
+    //     [0  0     0   ]        [ 0    1]
+    //
+    //     [0  0  0]              [1  0]
+    // A = [0  0  v]          B = [0  0]
+    //     [0  0  0]              [0  1]
+    var A = new Matrix<>(Nat.N3(), Nat.N3());
+    var B = new MatBuilder<>(Nat.N3(), Nat.N2()).fill(1.0, 0.0, 0.0, 0.0, 0.0, 1.0);
+    var Q = StateSpaceUtil.makeCostMatrix(qelems);
+    var R = StateSpaceUtil.makeCostMatrix(relems);
+
+    for (double velocity = -maxVelocity; velocity < maxVelocity; velocity += 0.01) {
+      // The DARE is ill-conditioned if the velocity is close to zero, so don't
+      // let the system stop.
+      if (Math.abs(velocity) < 1e-4) {
+        m_table.put(velocity, new Matrix<>(Nat.N2(), Nat.N3()));
+      } else {
+        A.set(State.kY.value, State.kHeading.value, velocity);
+        m_table.put(velocity, new LinearQuadraticRegulator<N3, N2, N3>(A, B, Q, R, dt).getK());
+      }
+    }
+  }
+
+  /**
+   * Returns true if the pose error is within tolerance of the reference.
+   *
+   * @return True if the pose error is within tolerance of the reference.
+   */
+  public boolean atReference() {
+    final var eTranslate = m_poseError.getTranslation();
+    final var eRotate = m_poseError.getRotation();
+    final var tolTranslate = m_poseTolerance.getTranslation();
+    final var tolRotate = m_poseTolerance.getRotation();
+    return Math.abs(eTranslate.getX()) < tolTranslate.getX()
+        && Math.abs(eTranslate.getY()) < tolTranslate.getY()
+        && Math.abs(eRotate.getRadians()) < tolRotate.getRadians();
+  }
+
+  /**
+   * Sets the pose error which is considered tolerable for use with atReference().
+   *
+   * @param poseTolerance Pose error which is tolerable.
+   */
+  public void setTolerance(Pose2d poseTolerance) {
+    m_poseTolerance = poseTolerance;
+  }
+
+  /**
+   * Returns the linear and angular velocity outputs of the LTV controller.
+   *
+   * <p>The reference pose, linear velocity, and angular velocity should come from a drivetrain
+   * trajectory.
+   *
+   * @param currentPose The current pose.
+   * @param poseRef The desired pose.
+   * @param linearVelocityRef The desired linear velocity in meters per second.
+   * @param angularVelocityRef The desired angular velocity in radians per second.
+   * @return The linear and angular velocity outputs of the LTV controller.
+   */
+  public ChassisSpeeds calculate(
+      Pose2d currentPose, Pose2d poseRef, double linearVelocityRef, double angularVelocityRef) {
+    if (!m_enabled) {
+      return new ChassisSpeeds(linearVelocityRef, 0.0, angularVelocityRef);
+    }
+
+    m_poseError = poseRef.relativeTo(currentPose);
+
+    var K = m_table.get(linearVelocityRef);
+    var e =
+        new MatBuilder<>(Nat.N3(), Nat.N1())
+            .fill(m_poseError.getX(), m_poseError.getY(), m_poseError.getRotation().getRadians());
+    var u = K.times(e);
+
+    return new ChassisSpeeds(
+        linearVelocityRef + u.get(0, 0), 0.0, angularVelocityRef + u.get(1, 0));
+  }
+
+  /**
+   * Returns the next output of the LTV controller.
+   *
+   * <p>The reference pose, linear velocity, and angular velocity should come from a drivetrain
+   * trajectory.
+   *
+   * @param currentPose The current pose.
+   * @param desiredState The desired pose, linear velocity, and angular velocity from a trajectory.
+   * @return The linear and angular velocity outputs of the LTV controller.
+   */
+  public ChassisSpeeds calculate(Pose2d currentPose, Trajectory.State desiredState) {
+    return calculate(
+        currentPose,
+        desiredState.poseMeters,
+        desiredState.velocityMetersPerSecond,
+        desiredState.velocityMetersPerSecond * desiredState.curvatureRadPerMeter);
+  }
+
+  /**
+   * Enables and disables the controller for troubleshooting purposes.
+   *
+   * @param enabled If the controller is enabled or not.
+   */
+  public void setEnabled(boolean enabled) {
+    m_enabled = enabled;
+  }
+}
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/LinearPlantInversionFeedforward.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/LinearPlantInversionFeedforward.java
index 627c272..a762851 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/LinearPlantInversionFeedforward.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/LinearPlantInversionFeedforward.java
@@ -20,20 +20,16 @@
  * <p>For more on the underlying math, read
  * https://file.tavsys.net/control/controls-engineering-in-frc.pdf.
  */
-@SuppressWarnings({"ParameterName", "LocalVariableName", "MemberName", "ClassTypeParameterName"})
 public class LinearPlantInversionFeedforward<
     States extends Num, Inputs extends Num, Outputs extends Num> {
   /** The current reference state. */
-  @SuppressWarnings("MemberName")
   private Matrix<States, N1> m_r;
 
   /** The computed feedforward. */
   private Matrix<Inputs, N1> m_uff;
 
-  @SuppressWarnings("MemberName")
   private final Matrix<States, Inputs> m_B;
 
-  @SuppressWarnings("MemberName")
   private final Matrix<States, States> m_A;
 
   /**
@@ -54,7 +50,6 @@
    * @param B Continuous input matrix of the plant being controlled.
    * @param dtSeconds Discretization timestep.
    */
-  @SuppressWarnings({"ParameterName", "LocalVariableName"})
   public LinearPlantInversionFeedforward(
       Matrix<States, States> A, Matrix<States, Inputs> B, double dtSeconds) {
     var discABPair = Discretization.discretizeAB(A, B, dtSeconds);
@@ -143,7 +138,6 @@
    * @param nextR The reference state of the future timestep (k + dt).
    * @return The calculated feedforward.
    */
-  @SuppressWarnings({"ParameterName", "LocalVariableName"})
   public Matrix<Inputs, N1> calculate(Matrix<States, N1> r, Matrix<States, N1> nextR) {
     m_uff = new Matrix<>(m_B.solve(nextR.minus(m_A.times(r))));
 
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/LinearQuadraticRegulator.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/LinearQuadraticRegulator.java
index e244c5f..dce1748 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/LinearQuadraticRegulator.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/LinearQuadraticRegulator.java
@@ -7,7 +7,6 @@
 import edu.wpi.first.math.Drake;
 import edu.wpi.first.math.MathSharedStore;
 import edu.wpi.first.math.Matrix;
-import edu.wpi.first.math.Nat;
 import edu.wpi.first.math.Num;
 import edu.wpi.first.math.StateSpaceUtil;
 import edu.wpi.first.math.Vector;
@@ -23,18 +22,14 @@
  * <p>For more on the underlying math, read
  * https://file.tavsys.net/control/controls-engineering-in-frc.pdf.
  */
-@SuppressWarnings("ClassTypeParameterName")
 public class LinearQuadraticRegulator<States extends Num, Inputs extends Num, Outputs extends Num> {
   /** The current reference state. */
-  @SuppressWarnings("MemberName")
   private Matrix<States, N1> m_r;
 
   /** The computed and capped controller output. */
-  @SuppressWarnings("MemberName")
   private Matrix<Inputs, N1> m_u;
 
   // Controller gain.
-  @SuppressWarnings("MemberName")
   private Matrix<Inputs, States> m_K;
 
   /**
@@ -44,6 +39,7 @@
    * @param qelms The maximum desired error tolerance for each state.
    * @param relms The maximum desired control effort for each input.
    * @param dtSeconds Discretization timestep.
+   * @throws IllegalArgumentException If the system is uncontrollable.
    */
   public LinearQuadraticRegulator(
       LinearSystem<States, Inputs, Outputs> plant,
@@ -66,8 +62,8 @@
    * @param qelms The maximum desired error tolerance for each state.
    * @param relms The maximum desired control effort for each input.
    * @param dtSeconds Discretization timestep.
+   * @throws IllegalArgumentException If the system is uncontrollable.
    */
-  @SuppressWarnings({"ParameterName", "LocalVariableName"})
   public LinearQuadraticRegulator(
       Matrix<States, States> A,
       Matrix<States, Inputs> B,
@@ -90,8 +86,8 @@
    * @param Q The state cost matrix.
    * @param R The input cost matrix.
    * @param dtSeconds Discretization timestep.
+   * @throws IllegalArgumentException If the system is uncontrollable.
    */
-  @SuppressWarnings({"LocalVariableName", "ParameterName"})
   public LinearQuadraticRegulator(
       Matrix<States, States> A,
       Matrix<States, Inputs> B,
@@ -141,8 +137,8 @@
    * @param R The input cost matrix.
    * @param N The state-input cross-term cost matrix.
    * @param dtSeconds Discretization timestep.
+   * @throws IllegalArgumentException If the system is uncontrollable.
    */
-  @SuppressWarnings({"ParameterName", "LocalVariableName"})
   public LinearQuadraticRegulator(
       Matrix<States, States> A,
       Matrix<States, Inputs> B,
@@ -172,24 +168,6 @@
   }
 
   /**
-   * Constructs a controller with the given coefficients and plant.
-   *
-   * @param states The number of states.
-   * @param inputs The number of inputs.
-   * @param k The gain matrix.
-   */
-  @SuppressWarnings("ParameterName")
-  public LinearQuadraticRegulator(
-      Nat<States> states, Nat<Inputs> inputs, Matrix<Inputs, States> k) {
-    m_K = k;
-
-    m_r = new Matrix<>(states, Nat.N1());
-    m_u = new Matrix<>(inputs, Nat.N1());
-
-    reset();
-  }
-
-  /**
    * Returns the control input vector u.
    *
    * @return The control input.
@@ -248,7 +226,6 @@
    * @param x The current state x.
    * @return The next controller output.
    */
-  @SuppressWarnings("ParameterName")
   public Matrix<Inputs, N1> calculate(Matrix<States, N1> x) {
     m_u = m_K.times(m_r.minus(x));
     return m_u;
@@ -261,7 +238,6 @@
    * @param nextR the next reference vector r.
    * @return The next controller output.
    */
-  @SuppressWarnings("ParameterName")
   public Matrix<Inputs, N1> calculate(Matrix<States, N1> x, Matrix<States, N1> nextR) {
     m_r = nextR;
     return calculate(x);
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/PIDController.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/PIDController.java
index 12c4175..5e82909 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/PIDController.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/PIDController.java
@@ -35,7 +35,7 @@
 
   private double m_minimumInput;
 
-  // Do the endpoints wrap around? eg. Absolute encoder
+  // Do the endpoints wrap around? e.g. Absolute encoder
   private boolean m_continuous;
 
   // The error at the time of the most recent call to calculate()
@@ -175,12 +175,39 @@
   }
 
   /**
+   * Returns the position tolerance of this controller.
+   *
+   * @return the position tolerance of the controller.
+   */
+  public double getPositionTolerance() {
+    return m_positionTolerance;
+  }
+
+  /**
+   * Returns the velocity tolerance of this controller.
+   *
+   * @return the velocity tolerance of the controller.
+   */
+  public double getVelocityTolerance() {
+    return m_velocityTolerance;
+  }
+
+  /**
    * Sets the setpoint for the PIDController.
    *
    * @param setpoint The desired setpoint.
    */
   public void setSetpoint(double setpoint) {
     m_setpoint = setpoint;
+
+    if (m_continuous) {
+      double errorBound = (m_maximumInput - m_minimumInput) / 2.0;
+      m_positionError = MathUtil.inputModulus(m_setpoint - m_measurement, -errorBound, errorBound);
+    } else {
+      m_positionError = m_setpoint - m_measurement;
+    }
+
+    m_velocityError = (m_positionError - m_prevError) / m_period;
   }
 
   /**
@@ -200,18 +227,8 @@
    * @return Whether the error is within the acceptable bounds.
    */
   public boolean atSetpoint() {
-    double positionError;
-    if (m_continuous) {
-      double errorBound = (m_maximumInput - m_minimumInput) / 2.0;
-      positionError = MathUtil.inputModulus(m_setpoint - m_measurement, -errorBound, errorBound);
-    } else {
-      positionError = m_setpoint - m_measurement;
-    }
-
-    double velocityError = (positionError - m_prevError) / m_period;
-
-    return Math.abs(positionError) < m_positionTolerance
-        && Math.abs(velocityError) < m_velocityTolerance;
+    return Math.abs(m_positionError) < m_positionTolerance
+        && Math.abs(m_velocityError) < m_velocityTolerance;
   }
 
   /**
@@ -303,8 +320,7 @@
    * @return The next controller output.
    */
   public double calculate(double measurement, double setpoint) {
-    // Set setpoint to provided value
-    setSetpoint(setpoint);
+    m_setpoint = setpoint;
     return calculate(measurement);
   }
 
@@ -322,7 +338,7 @@
       double errorBound = (m_maximumInput - m_minimumInput) / 2.0;
       m_positionError = MathUtil.inputModulus(m_setpoint - m_measurement, -errorBound, errorBound);
     } else {
-      m_positionError = m_setpoint - measurement;
+      m_positionError = m_setpoint - m_measurement;
     }
 
     m_velocityError = (m_positionError - m_prevError) / m_period;
@@ -340,8 +356,10 @@
 
   /** Resets the previous error and the integral term. */
   public void reset() {
+    m_positionError = 0;
     m_prevError = 0;
     m_totalError = 0;
+    m_velocityError = 0;
   }
 
   @Override
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/ProfiledPIDController.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/ProfiledPIDController.java
index 3ebcbd8..02cc17d 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/ProfiledPIDController.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/ProfiledPIDController.java
@@ -10,6 +10,7 @@
 import edu.wpi.first.math.trajectory.TrapezoidProfile;
 import edu.wpi.first.util.sendable.Sendable;
 import edu.wpi.first.util.sendable.SendableBuilder;
+import edu.wpi.first.util.sendable.SendableRegistry;
 
 /**
  * Implements a PID control loop whose setpoint is constrained by a trapezoid profile. Users should
@@ -33,7 +34,6 @@
    * @param Kd The derivative coefficient.
    * @param constraints Velocity and acceleration constraints for goal.
    */
-  @SuppressWarnings("ParameterName")
   public ProfiledPIDController(
       double Kp, double Ki, double Kd, TrapezoidProfile.Constraints constraints) {
     this(Kp, Ki, Kd, constraints, 0.02);
@@ -48,12 +48,13 @@
    * @param constraints Velocity and acceleration constraints for goal.
    * @param period The period between controller updates in seconds. The default is 0.02 seconds.
    */
-  @SuppressWarnings("ParameterName")
   public ProfiledPIDController(
       double Kp, double Ki, double Kd, TrapezoidProfile.Constraints constraints, double period) {
     m_controller = new PIDController(Kp, Ki, Kd, period);
     m_constraints = constraints;
     instances++;
+
+    SendableRegistry.add(this, "ProfiledPIDController", instances);
     MathSharedStore.reportUsage(MathUsageId.kController_ProfiledPIDController, instances);
   }
 
@@ -66,7 +67,6 @@
    * @param Ki Integral coefficient
    * @param Kd Differential coefficient
    */
-  @SuppressWarnings("ParameterName")
   public void setPID(double Kp, double Ki, double Kd) {
     m_controller.setPID(Kp, Ki, Kd);
   }
@@ -76,7 +76,6 @@
    *
    * @param Kp proportional coefficient
    */
-  @SuppressWarnings("ParameterName")
   public void setP(double Kp) {
     m_controller.setP(Kp);
   }
@@ -86,7 +85,6 @@
    *
    * @param Ki integral coefficient
    */
-  @SuppressWarnings("ParameterName")
   public void setI(double Ki) {
     m_controller.setI(Ki);
   }
@@ -96,7 +94,6 @@
    *
    * @param Kd differential coefficient
    */
-  @SuppressWarnings("ParameterName")
   public void setD(double Kd) {
     m_controller.setD(Kd);
   }
@@ -138,6 +135,24 @@
   }
 
   /**
+   * Returns the position tolerance of this controller.
+   *
+   * @return the position tolerance of the controller.
+   */
+  public double getPositionTolerance() {
+    return m_controller.getPositionTolerance();
+  }
+
+  /**
+   * Returns the velocity tolerance of this controller.
+   *
+   * @return the velocity tolerance of the controller.
+   */
+  public double getVelocityTolerance() {
+    return m_controller.getVelocityTolerance();
+  }
+
+  /**
    * Sets the goal for the ProfiledPIDController.
    *
    * @param goal The desired goal state.
@@ -282,7 +297,7 @@
    */
   public double calculate(double measurement) {
     if (m_controller.isContinuousInputEnabled()) {
-      // Get error which is smallest distance between goal and measurement
+      // Get error which is the smallest distance between goal and measurement
       double errorBound = (m_maximumInput - m_minimumInput) / 2.0;
       double goalMinDistance =
           MathUtil.inputModulus(m_goal.position - measurement, -errorBound, errorBound);
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/RamseteController.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/RamseteController.java
index a1d6237..5683987 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/RamseteController.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/RamseteController.java
@@ -33,10 +33,8 @@
  * derivation and analysis.
  */
 public class RamseteController {
-  @SuppressWarnings("MemberName")
   private final double m_b;
 
-  @SuppressWarnings("MemberName")
   private final double m_zeta;
 
   private Pose2d m_poseError = new Pose2d();
@@ -51,7 +49,6 @@
    * @param zeta Tuning parameter (0 rad⁻¹ &lt; zeta &lt; 1 rad⁻¹) for which larger values provide
    *     more damping in response.
    */
-  @SuppressWarnings("ParameterName")
   public RamseteController(double b, double zeta) {
     m_b = b;
     m_zeta = zeta;
@@ -101,7 +98,6 @@
    * @param angularVelocityRefRadiansPerSecond The desired angular velocity in radians per second.
    * @return The next controller output.
    */
-  @SuppressWarnings("LocalVariableName")
   public ChassisSpeeds calculate(
       Pose2d currentPose,
       Pose2d poseRef,
@@ -120,8 +116,11 @@
     final double vRef = linearVelocityRefMeters;
     final double omegaRef = angularVelocityRefRadiansPerSecond;
 
+    // k = 2ζ√(ω_ref² + b v_ref²)
     double k = 2.0 * m_zeta * Math.sqrt(Math.pow(omegaRef, 2) + m_b * Math.pow(vRef, 2));
 
+    // v_cmd = v_ref cos(e_θ) + k e_x
+    // ω_cmd = ω_ref + k e_θ + b v_ref sinc(e_θ) e_y
     return new ChassisSpeeds(
         vRef * m_poseError.getRotation().getCos() + k * eX,
         0.0,
@@ -138,7 +137,6 @@
    * @param desiredState The desired pose, linear velocity, and angular velocity from a trajectory.
    * @return The next controller output.
    */
-  @SuppressWarnings("LocalVariableName")
   public ChassisSpeeds calculate(Pose2d currentPose, Trajectory.State desiredState) {
     return calculate(
         currentPose,
@@ -161,7 +159,6 @@
    *
    * @param x Value of which to take sinc(x).
    */
-  @SuppressWarnings("ParameterName")
   private static double sinc(double x) {
     if (Math.abs(x) < 1e-9) {
       return 1.0 - 1.0 / 6.0 * x * x;
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/SimpleMotorFeedforward.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/SimpleMotorFeedforward.java
index a1e5f68..714d705 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/SimpleMotorFeedforward.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/controller/SimpleMotorFeedforward.java
@@ -9,7 +9,6 @@
 import edu.wpi.first.math.system.plant.LinearSystemId;
 
 /** A helper class that computes feedforward outputs for a simple permanent-magnet DC motor. */
-@SuppressWarnings("MemberName")
 public class SimpleMotorFeedforward {
   public final double ks;
   public final double kv;
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/AngleStatistics.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/AngleStatistics.java
index a6d8b44..0f91a1d 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/AngleStatistics.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/AngleStatistics.java
@@ -87,7 +87,6 @@
    * @param angleStateIdx The row containing the angles.
    * @return Mean of sigma points.
    */
-  @SuppressWarnings("checkstyle:ParameterName")
   public static <S extends Num> Matrix<S, N1> angleMean(
       Matrix<S, ?> sigmas, Matrix<?, N1> Wm, int angleStateIdx) {
     double[] angleSigmas = sigmas.extractRowVector(angleStateIdx).getData();
@@ -115,7 +114,6 @@
    * @param angleStateIdx The row containing the angles.
    * @return Function returning mean of sigma points.
    */
-  @SuppressWarnings("LambdaParameterName")
   public static <S extends Num> BiFunction<Matrix<S, ?>, Matrix<?, N1>, Matrix<S, N1>> angleMean(
       int angleStateIdx) {
     return (sigmas, Wm) -> angleMean(sigmas, Wm, angleStateIdx);
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/DifferentialDrivePoseEstimator.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/DifferentialDrivePoseEstimator.java
index b199d4d..b5fe591 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/DifferentialDrivePoseEstimator.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/DifferentialDrivePoseEstimator.java
@@ -4,158 +4,109 @@
 
 package edu.wpi.first.math.estimator;
 
-import edu.wpi.first.math.MatBuilder;
+import edu.wpi.first.math.MathUtil;
 import edu.wpi.first.math.Matrix;
 import edu.wpi.first.math.Nat;
-import edu.wpi.first.math.StateSpaceUtil;
 import edu.wpi.first.math.VecBuilder;
 import edu.wpi.first.math.geometry.Pose2d;
 import edu.wpi.first.math.geometry.Rotation2d;
-import edu.wpi.first.math.kinematics.DifferentialDriveWheelSpeeds;
+import edu.wpi.first.math.geometry.Twist2d;
+import edu.wpi.first.math.interpolation.Interpolatable;
+import edu.wpi.first.math.interpolation.TimeInterpolatableBuffer;
+import edu.wpi.first.math.kinematics.DifferentialDriveKinematics;
+import edu.wpi.first.math.kinematics.DifferentialDriveOdometry;
 import edu.wpi.first.math.numbers.N1;
 import edu.wpi.first.math.numbers.N3;
-import edu.wpi.first.math.numbers.N5;
 import edu.wpi.first.util.WPIUtilJNI;
-import java.util.function.BiConsumer;
+import java.util.Map;
+import java.util.Objects;
 
 /**
- * This class wraps an {@link edu.wpi.first.math.estimator.UnscentedKalmanFilter Unscented Kalman
- * Filter} to fuse latency-compensated vision measurements with differential drive encoder
- * measurements. It will correct for noisy vision measurements and encoder drift. It is intended to
- * be an easy drop-in for {@link edu.wpi.first.math.kinematics.DifferentialDriveOdometry}; in fact,
- * if you never call {@link DifferentialDrivePoseEstimator#addVisionMeasurement} and only call
- * {@link DifferentialDrivePoseEstimator#update} then this will behave exactly the same as
+ * This class wraps {@link DifferentialDriveOdometry Differential Drive Odometry} to fuse
+ * latency-compensated vision measurements with differential drive encoder measurements. It is
+ * intended to be a drop-in replacement for {@link DifferentialDriveOdometry}; in fact, if you never
+ * call {@link DifferentialDrivePoseEstimator#addVisionMeasurement} and only call {@link
+ * DifferentialDrivePoseEstimator#update} then this will behave exactly the same as
  * DifferentialDriveOdometry.
  *
- * <p>{@link DifferentialDrivePoseEstimator#update} should be called every robot loop (if your robot
- * loops are faster than the default then you should change the {@link
- * DifferentialDrivePoseEstimator#DifferentialDrivePoseEstimator(Rotation2d, Pose2d, Matrix, Matrix,
- * Matrix, double) nominal delta time}.) {@link DifferentialDrivePoseEstimator#addVisionMeasurement}
- * can be called as infrequently as you want; if you never call it then this class will behave
- * exactly like regular encoder odometry.
+ * <p>{@link DifferentialDrivePoseEstimator#update} should be called every robot loop.
  *
- * <p>The state-space system used internally has the following states (x), inputs (u), and outputs
- * (y):
- *
- * <p><strong> x = [x, y, theta, dist_l, dist_r]ᵀ </strong> in the field coordinate system
- * containing x position, y position, heading, left encoder distance, and right encoder distance.
- *
- * <p><strong> u = [v_x, v_y, omega]ᵀ </strong> containing x velocity, y velocity, and angular rate
- * in the field coordinate system.
- *
- * <p>NB: Using velocities make things considerably easier, because it means that teams don't have
- * to worry about getting an accurate model. Basically, we suspect that it's easier for teams to get
- * good encoder data than it is for them to perform system identification well enough to get a good
- * model.
- *
- * <p><strong> y = [x, y, theta]ᵀ </strong> from vision containing x position, y position, and
- * heading; or <strong>y = [dist_l, dist_r, theta] </strong> containing left encoder position, right
- * encoder position, and gyro heading.
+ * <p>{@link DifferentialDrivePoseEstimator#addVisionMeasurement} can be called as infrequently as
+ * you want; if you never call it then this class will behave exactly like regular encoder odometry.
  */
 public class DifferentialDrivePoseEstimator {
-  final UnscentedKalmanFilter<N5, N3, N3> m_observer; // Package-private to allow for unit testing
-  private final BiConsumer<Matrix<N3, N1>, Matrix<N3, N1>> m_visionCorrect;
-  private final KalmanFilterLatencyCompensator<N5, N3, N3> m_latencyCompensator;
+  private final DifferentialDriveKinematics m_kinematics;
+  private final DifferentialDriveOdometry m_odometry;
+  private final Matrix<N3, N1> m_q = new Matrix<>(Nat.N3(), Nat.N1());
+  private Matrix<N3, N3> m_visionK = new Matrix<>(Nat.N3(), Nat.N3());
 
-  private final double m_nominalDt; // Seconds
-  private double m_prevTimeSeconds = -1.0;
-
-  private Rotation2d m_gyroOffset;
-  private Rotation2d m_previousAngle;
-
-  private Matrix<N3, N3> m_visionContR;
+  private final TimeInterpolatableBuffer<InterpolationRecord> m_poseBuffer =
+      TimeInterpolatableBuffer.createBuffer(1.5);
 
   /**
-   * Constructs a DifferentialDrivePoseEstimator.
+   * Constructs a DifferentialDrivePoseEstimator with default standard deviations for the model and
+   * vision measurements.
    *
+   * <p>The default standard deviations of the model states are 0.02 meters for x, 0.02 meters for
+   * y, and 0.01 radians for heading. The default standard deviations of the vision measurements are
+   * 0.1 meters for x, 0.1 meters for y, and 0.1 radians for heading.
+   *
+   * @param kinematics A correctly-configured kinematics object for your drivetrain.
    * @param gyroAngle The current gyro angle.
+   * @param leftDistanceMeters The distance traveled by the left encoder.
+   * @param rightDistanceMeters The distance traveled by the right encoder.
    * @param initialPoseMeters The starting pose estimate.
-   * @param stateStdDevs Standard deviations of model states. Increase these numbers to trust your
-   *     model's state estimates less. This matrix is in the form [x, y, theta, dist_l, dist_r]ᵀ,
-   *     with units in meters and radians.
-   * @param localMeasurementStdDevs Standard deviations of the encoder and gyro measurements.
-   *     Increase these numbers to trust sensor readings from encoders and gyros less. This matrix
-   *     is in the form [dist_l, dist_r, theta]ᵀ, with units in meters and radians.
-   * @param visionMeasurementStdDevs Standard deviations of the vision measurements. Increase these
-   *     numbers to trust global measurements from vision less. This matrix is in the form [x, y,
-   *     theta]ᵀ, with units in meters and radians.
    */
   public DifferentialDrivePoseEstimator(
+      DifferentialDriveKinematics kinematics,
       Rotation2d gyroAngle,
-      Pose2d initialPoseMeters,
-      Matrix<N5, N1> stateStdDevs,
-      Matrix<N3, N1> localMeasurementStdDevs,
-      Matrix<N3, N1> visionMeasurementStdDevs) {
+      double leftDistanceMeters,
+      double rightDistanceMeters,
+      Pose2d initialPoseMeters) {
     this(
+        kinematics,
         gyroAngle,
+        leftDistanceMeters,
+        rightDistanceMeters,
         initialPoseMeters,
-        stateStdDevs,
-        localMeasurementStdDevs,
-        visionMeasurementStdDevs,
-        0.02);
+        VecBuilder.fill(0.02, 0.02, 0.01),
+        VecBuilder.fill(0.1, 0.1, 0.1));
   }
 
   /**
    * Constructs a DifferentialDrivePoseEstimator.
    *
-   * @param gyroAngle The current gyro angle.
-   * @param initialPoseMeters The starting pose estimate.
-   * @param stateStdDevs Standard deviations of model states. Increase these numbers to trust your
-   *     model's state estimates less. This matrix is in the form [x, y, theta, dist_l, dist_r]ᵀ,
-   *     with units in meters and radians.
-   * @param localMeasurementStdDevs Standard deviations of the encoder and gyro measurements.
-   *     Increase these numbers to trust sensor readings from encoders and gyros less. This matrix
-   *     is in the form [dist_l, dist_r, theta]ᵀ, with units in meters and radians.
-   * @param visionMeasurementStdDevs Standard deviations of the vision measurements. Increase these
-   *     numbers to trust global measurements from vision less. This matrix is in the form [x, y,
-   *     theta]ᵀ, with units in meters and radians.
-   * @param nominalDtSeconds The time in seconds between each robot loop.
+   * @param kinematics A correctly-configured kinematics object for your drivetrain.
+   * @param gyroAngle The gyro angle of the robot.
+   * @param leftDistanceMeters The distance traveled by the left encoder.
+   * @param rightDistanceMeters The distance traveled by the right encoder.
+   * @param initialPoseMeters The estimated initial pose.
+   * @param stateStdDevs Standard deviations of the pose estimate (x position in meters, y position
+   *     in meters, and heading in radians). Increase these numbers to trust your state estimate
+   *     less.
+   * @param visionMeasurementStdDevs Standard deviations of the vision pose measurement (x position
+   *     in meters, y position in meters, and heading in radians). Increase these numbers to trust
+   *     the vision pose measurement less.
    */
-  @SuppressWarnings("ParameterName")
   public DifferentialDrivePoseEstimator(
+      DifferentialDriveKinematics kinematics,
       Rotation2d gyroAngle,
+      double leftDistanceMeters,
+      double rightDistanceMeters,
       Pose2d initialPoseMeters,
-      Matrix<N5, N1> stateStdDevs,
-      Matrix<N3, N1> localMeasurementStdDevs,
-      Matrix<N3, N1> visionMeasurementStdDevs,
-      double nominalDtSeconds) {
-    m_nominalDt = nominalDtSeconds;
+      Matrix<N3, N1> stateStdDevs,
+      Matrix<N3, N1> visionMeasurementStdDevs) {
+    m_kinematics = kinematics;
+    m_odometry =
+        new DifferentialDriveOdometry(
+            gyroAngle, leftDistanceMeters, rightDistanceMeters, initialPoseMeters);
 
-    m_observer =
-        new UnscentedKalmanFilter<>(
-            Nat.N5(),
-            Nat.N3(),
-            this::f,
-            (x, u) -> VecBuilder.fill(x.get(3, 0), x.get(4, 0), x.get(2, 0)),
-            stateStdDevs,
-            localMeasurementStdDevs,
-            AngleStatistics.angleMean(2),
-            AngleStatistics.angleMean(2),
-            AngleStatistics.angleResidual(2),
-            AngleStatistics.angleResidual(2),
-            AngleStatistics.angleAdd(2),
-            m_nominalDt);
-    m_latencyCompensator = new KalmanFilterLatencyCompensator<>();
+    for (int i = 0; i < 3; ++i) {
+      m_q.set(i, 0, stateStdDevs.get(i, 0) * stateStdDevs.get(i, 0));
+    }
 
     // Initialize vision R
     setVisionMeasurementStdDevs(visionMeasurementStdDevs);
-
-    m_visionCorrect =
-        (u, y) ->
-            m_observer.correct(
-                Nat.N3(),
-                u,
-                y,
-                (x, u1) -> new Matrix<>(x.getStorage().extractMatrix(0, 3, 0, 1)),
-                m_visionContR,
-                AngleStatistics.angleMean(2),
-                AngleStatistics.angleResidual(2),
-                AngleStatistics.angleResidual(2),
-                AngleStatistics.angleAdd(2));
-
-    m_gyroOffset = initialPoseMeters.getRotation().minus(gyroAngle);
-    m_previousAngle = initialPoseMeters.getRotation();
-    m_observer.setXhat(fillStateVector(initialPoseMeters, 0.0, 0.0));
   }
 
   /**
@@ -168,109 +119,122 @@
    *     theta]ᵀ, with units in meters and radians.
    */
   public void setVisionMeasurementStdDevs(Matrix<N3, N1> visionMeasurementStdDevs) {
-    m_visionContR = StateSpaceUtil.makeCovarianceMatrix(Nat.N3(), visionMeasurementStdDevs);
-  }
+    var r = new double[3];
+    for (int i = 0; i < 3; ++i) {
+      r[i] = visionMeasurementStdDevs.get(i, 0) * visionMeasurementStdDevs.get(i, 0);
+    }
 
-  @SuppressWarnings({"ParameterName", "MethodName"})
-  private Matrix<N5, N1> f(Matrix<N5, N1> x, Matrix<N3, N1> u) {
-    // Apply a rotation matrix. Note that we do *not* add x--Runge-Kutta does that for us.
-    var theta = x.get(2, 0);
-    var toFieldRotation =
-        new MatBuilder<>(Nat.N5(), Nat.N5())
-            .fill(
-                Math.cos(theta),
-                -Math.sin(theta),
-                0,
-                0,
-                0,
-                Math.sin(theta),
-                Math.cos(theta),
-                0,
-                0,
-                0,
-                0,
-                0,
-                1,
-                0,
-                0,
-                0,
-                0,
-                0,
-                1,
-                0,
-                0,
-                0,
-                0,
-                0,
-                1);
-    return toFieldRotation.times(
-        VecBuilder.fill(u.get(0, 0), u.get(1, 0), u.get(2, 0), u.get(0, 0), u.get(1, 0)));
+    // Solve for closed form Kalman gain for continuous Kalman filter with A = 0
+    // and C = I. See wpimath/algorithms.md.
+    for (int row = 0; row < 3; ++row) {
+      if (m_q.get(row, 0) == 0.0) {
+        m_visionK.set(row, row, 0.0);
+      } else {
+        m_visionK.set(
+            row, row, m_q.get(row, 0) / (m_q.get(row, 0) + Math.sqrt(m_q.get(row, 0) * r[row])));
+      }
+    }
   }
 
   /**
    * Resets the robot's position on the field.
    *
-   * <p>You NEED to reset your encoders (to zero) when calling this method.
-   *
    * <p>The gyroscope angle does not need to be reset here on the user's robot code. The library
    * automatically takes care of offsetting the gyro angle.
    *
-   * @param poseMeters The position on the field that your robot is at.
    * @param gyroAngle The angle reported by the gyroscope.
+   * @param leftPositionMeters The distance traveled by the left encoder.
+   * @param rightPositionMeters The distance traveled by the right encoder.
+   * @param poseMeters The position on the field that your robot is at.
    */
-  public void resetPosition(Pose2d poseMeters, Rotation2d gyroAngle) {
+  public void resetPosition(
+      Rotation2d gyroAngle,
+      double leftPositionMeters,
+      double rightPositionMeters,
+      Pose2d poseMeters) {
     // Reset state estimate and error covariance
-    m_observer.reset();
-    m_latencyCompensator.reset();
-
-    m_observer.setXhat(fillStateVector(poseMeters, 0.0, 0.0));
-
-    m_gyroOffset = getEstimatedPosition().getRotation().minus(gyroAngle);
-    m_previousAngle = poseMeters.getRotation();
+    m_odometry.resetPosition(gyroAngle, leftPositionMeters, rightPositionMeters, poseMeters);
+    m_poseBuffer.clear();
   }
 
   /**
-   * Gets the pose of the robot at the current time as estimated by the Unscented Kalman Filter.
+   * Gets the estimated robot pose.
    *
    * @return The estimated robot pose in meters.
    */
   public Pose2d getEstimatedPosition() {
-    return new Pose2d(
-        m_observer.getXhat(0), m_observer.getXhat(1), new Rotation2d(m_observer.getXhat(2)));
+    return m_odometry.getPoseMeters();
   }
 
   /**
-   * Add a vision measurement to the Unscented Kalman Filter. This will correct the odometry pose
-   * estimate while still accounting for measurement noise.
+   * Adds a vision measurement to the Kalman Filter. This will correct the odometry pose estimate
+   * while still accounting for measurement noise.
    *
    * <p>This method can be called as infrequently as you want, as long as you are calling {@link
    * DifferentialDrivePoseEstimator#update} every loop.
    *
+   * <p>To promote stability of the pose estimate and make it robust to bad vision data, we
+   * recommend only adding vision measurements that are already within one meter or so of the
+   * current pose estimate.
+   *
    * @param visionRobotPoseMeters The pose of the robot as measured by the vision camera.
    * @param timestampSeconds The timestamp of the vision measurement in seconds. Note that if you
    *     don't use your own time source by calling {@link
-   *     DifferentialDrivePoseEstimator#updateWithTime} then you must use a timestamp with an epoch
-   *     since FPGA startup (i.e. the epoch of this timestamp is the same epoch as
-   *     Timer.getFPGATimestamp.) This means that you should use Timer.getFPGATimestamp as your time
-   *     source in this case.
+   *     DifferentialDrivePoseEstimator#updateWithTime(double,Rotation2d,double,double)} then you
+   *     must use a timestamp with an epoch since FPGA startup (i.e., the epoch of this timestamp is
+   *     the same epoch as {@link edu.wpi.first.wpilibj.Timer#getFPGATimestamp()}.) This means that
+   *     you should use {@link edu.wpi.first.wpilibj.Timer#getFPGATimestamp()} as your time source
+   *     or sync the epochs.
    */
   public void addVisionMeasurement(Pose2d visionRobotPoseMeters, double timestampSeconds) {
-    m_latencyCompensator.applyPastGlobalMeasurement(
-        Nat.N3(),
-        m_observer,
-        m_nominalDt,
-        StateSpaceUtil.poseTo3dVector(visionRobotPoseMeters),
-        m_visionCorrect,
-        timestampSeconds);
+    // Step 1: Get the pose odometry measured at the moment the vision measurement was made.
+    var sample = m_poseBuffer.getSample(timestampSeconds);
+
+    if (sample.isEmpty()) {
+      return;
+    }
+
+    // Step 2: Measure the twist between the odometry pose and the vision pose.
+    var twist = sample.get().poseMeters.log(visionRobotPoseMeters);
+
+    // Step 3: We should not trust the twist entirely, so instead we scale this twist by a Kalman
+    // gain matrix representing how much we trust vision measurements compared to our current pose.
+    var k_times_twist = m_visionK.times(VecBuilder.fill(twist.dx, twist.dy, twist.dtheta));
+
+    // Step 4: Convert back to Twist2d.
+    var scaledTwist =
+        new Twist2d(k_times_twist.get(0, 0), k_times_twist.get(1, 0), k_times_twist.get(2, 0));
+
+    // Step 5: Reset Odometry to state at sample with vision adjustment.
+    m_odometry.resetPosition(
+        sample.get().gyroAngle,
+        sample.get().leftMeters,
+        sample.get().rightMeters,
+        sample.get().poseMeters.exp(scaledTwist));
+
+    // Step 6: Replay odometry inputs between sample time and latest recorded sample to update the
+    // pose buffer and correct odometry.
+    for (Map.Entry<Double, InterpolationRecord> entry :
+        m_poseBuffer.getInternalBuffer().tailMap(timestampSeconds).entrySet()) {
+      updateWithTime(
+          entry.getKey(),
+          entry.getValue().gyroAngle,
+          entry.getValue().leftMeters,
+          entry.getValue().rightMeters);
+    }
   }
 
   /**
-   * Add a vision measurement to the Unscented Kalman Filter. This will correct the odometry pose
-   * estimate while still accounting for measurement noise.
+   * Adds a vision measurement to the Kalman Filter. This will correct the odometry pose estimate
+   * while still accounting for measurement noise.
    *
    * <p>This method can be called as infrequently as you want, as long as you are calling {@link
    * DifferentialDrivePoseEstimator#update} every loop.
    *
+   * <p>To promote stability of the pose estimate and make it robust to bad vision data, we
+   * recommend only adding vision measurements that are already within one meter or so of the
+   * current pose estimate.
+   *
    * <p>Note that the vision measurement standard deviations passed into this method will continue
    * to apply to future measurements until a subsequent call to {@link
    * DifferentialDrivePoseEstimator#setVisionMeasurementStdDevs(Matrix)} or this method.
@@ -278,13 +242,14 @@
    * @param visionRobotPoseMeters The pose of the robot as measured by the vision camera.
    * @param timestampSeconds The timestamp of the vision measurement in seconds. Note that if you
    *     don't use your own time source by calling {@link
-   *     DifferentialDrivePoseEstimator#updateWithTime} then you must use a timestamp with an epoch
-   *     since FPGA startup (i.e. the epoch of this timestamp is the same epoch as
-   *     Timer.getFPGATimestamp.) This means that you should use Timer.getFPGATimestamp as your time
-   *     source in this case.
-   * @param visionMeasurementStdDevs Standard deviations of the vision measurements. Increase these
-   *     numbers to trust global measurements from vision less. This matrix is in the form [x, y,
-   *     theta]ᵀ, with units in meters and radians.
+   *     DifferentialDrivePoseEstimator#updateWithTime(double,Rotation2d,double,double)}, then you
+   *     must use a timestamp with an epoch since FPGA startup (i.e., the epoch of this timestamp is
+   *     the same epoch as {@link edu.wpi.first.wpilibj.Timer#getFPGATimestamp()}). This means that
+   *     you should use {@link edu.wpi.first.wpilibj.Timer#getFPGATimestamp()} as your time source
+   *     in this case.
+   * @param visionMeasurementStdDevs Standard deviations of the vision pose measurement (x position
+   *     in meters, y position in meters, and heading in radians). Increase these numbers to trust
+   *     the vision pose measurement less.
    */
   public void addVisionMeasurement(
       Pose2d visionRobotPoseMeters,
@@ -295,78 +260,127 @@
   }
 
   /**
-   * Updates the the Unscented Kalman Filter using only wheel encoder information. Note that this
-   * should be called every loop.
+   * Updates the pose estimator with wheel encoder and gyro information. This should be called every
+   * loop.
    *
    * @param gyroAngle The current gyro angle.
-   * @param wheelVelocitiesMetersPerSecond The velocities of the wheels in meters per second.
-   * @param distanceLeftMeters The total distance travelled by the left wheel in meters since the
-   *     last time you called {@link DifferentialDrivePoseEstimator#resetPosition}.
-   * @param distanceRightMeters The total distance travelled by the right wheel in meters since the
-   *     last time you called {@link DifferentialDrivePoseEstimator#resetPosition}.
+   * @param distanceLeftMeters The total distance travelled by the left wheel in meters.
+   * @param distanceRightMeters The total distance travelled by the right wheel in meters.
    * @return The estimated pose of the robot in meters.
    */
   public Pose2d update(
-      Rotation2d gyroAngle,
-      DifferentialDriveWheelSpeeds wheelVelocitiesMetersPerSecond,
-      double distanceLeftMeters,
-      double distanceRightMeters) {
+      Rotation2d gyroAngle, double distanceLeftMeters, double distanceRightMeters) {
     return updateWithTime(
-        WPIUtilJNI.now() * 1.0e-6,
-        gyroAngle,
-        wheelVelocitiesMetersPerSecond,
-        distanceLeftMeters,
-        distanceRightMeters);
+        WPIUtilJNI.now() * 1.0e-6, gyroAngle, distanceLeftMeters, distanceRightMeters);
   }
 
   /**
-   * Updates the the Unscented Kalman Filter using only wheel encoder information. Note that this
-   * should be called every loop.
+   * Updates the pose estimator with wheel encoder and gyro information. This should be called every
+   * loop.
    *
    * @param currentTimeSeconds Time at which this method was called, in seconds.
    * @param gyroAngle The current gyro angle.
-   * @param wheelVelocitiesMetersPerSecond The velocities of the wheels in meters per second.
-   * @param distanceLeftMeters The total distance travelled by the left wheel in meters since the
-   *     last time you called {@link DifferentialDrivePoseEstimator#resetPosition}.
-   * @param distanceRightMeters The total distance travelled by the right wheel in meters since the
-   *     last time you called {@link DifferentialDrivePoseEstimator#resetPosition}.
+   * @param distanceLeftMeters The total distance travelled by the left wheel in meters.
+   * @param distanceRightMeters The total distance travelled by the right wheel in meters.
    * @return The estimated pose of the robot in meters.
    */
-  @SuppressWarnings({"LocalVariableName", "ParameterName"})
   public Pose2d updateWithTime(
       double currentTimeSeconds,
       Rotation2d gyroAngle,
-      DifferentialDriveWheelSpeeds wheelVelocitiesMetersPerSecond,
       double distanceLeftMeters,
       double distanceRightMeters) {
-    double dt = m_prevTimeSeconds >= 0 ? currentTimeSeconds - m_prevTimeSeconds : m_nominalDt;
-    m_prevTimeSeconds = currentTimeSeconds;
-
-    var angle = gyroAngle.plus(m_gyroOffset);
-    // Diff drive forward kinematics:
-    // v_c = (v_l + v_r) / 2
-    var wheelVels = wheelVelocitiesMetersPerSecond;
-    var u =
-        VecBuilder.fill(
-            (wheelVels.leftMetersPerSecond + wheelVels.rightMetersPerSecond) / 2,
-            0,
-            angle.minus(m_previousAngle).getRadians() / dt);
-    m_previousAngle = angle;
-
-    var localY = VecBuilder.fill(distanceLeftMeters, distanceRightMeters, angle.getRadians());
-    m_latencyCompensator.addObserverState(m_observer, u, localY, currentTimeSeconds);
-    m_observer.predict(u, dt);
-    m_observer.correct(u, localY);
+    m_odometry.update(gyroAngle, distanceLeftMeters, distanceRightMeters);
+    m_poseBuffer.addSample(
+        currentTimeSeconds,
+        new InterpolationRecord(
+            getEstimatedPosition(), gyroAngle, distanceLeftMeters, distanceRightMeters));
 
     return getEstimatedPosition();
   }
 
-  private static Matrix<N5, N1> fillStateVector(Pose2d pose, double leftDist, double rightDist) {
-    return VecBuilder.fill(
-        pose.getTranslation().getX(),
-        pose.getTranslation().getY(),
-        pose.getRotation().getRadians(),
-        leftDist,
-        rightDist);
+  /**
+   * Represents an odometry record. The record contains the inputs provided as well as the pose that
+   * was observed based on these inputs, as well as the previous record and its inputs.
+   */
+  private class InterpolationRecord implements Interpolatable<InterpolationRecord> {
+    // The pose observed given the current sensor inputs and the previous pose.
+    private final Pose2d poseMeters;
+
+    // The current gyro angle.
+    private final Rotation2d gyroAngle;
+
+    // The distance traveled by the left encoder.
+    private final double leftMeters;
+
+    // The distance traveled by the right encoder.
+    private final double rightMeters;
+
+    /**
+     * Constructs an Interpolation Record with the specified parameters.
+     *
+     * @param pose The pose observed given the current sensor inputs and the previous pose.
+     * @param gyro The current gyro angle.
+     * @param leftMeters The distance traveled by the left encoder.
+     * @param rightMeters The distanced traveled by the right encoder.
+     */
+    private InterpolationRecord(
+        Pose2d poseMeters, Rotation2d gyro, double leftMeters, double rightMeters) {
+      this.poseMeters = poseMeters;
+      this.gyroAngle = gyro;
+      this.leftMeters = leftMeters;
+      this.rightMeters = rightMeters;
+    }
+
+    /**
+     * Return the interpolated record. This object is assumed to be the starting position, or lower
+     * bound.
+     *
+     * @param endValue The upper bound, or end.
+     * @param t How far between the lower and upper bound we are. This should be bounded in [0, 1].
+     * @return The interpolated value.
+     */
+    @Override
+    public InterpolationRecord interpolate(InterpolationRecord endValue, double t) {
+      if (t < 0) {
+        return this;
+      } else if (t >= 1) {
+        return endValue;
+      } else {
+        // Find the new left distance.
+        var left_lerp = MathUtil.interpolate(this.leftMeters, endValue.leftMeters, t);
+
+        // Find the new right distance.
+        var right_lerp = MathUtil.interpolate(this.rightMeters, endValue.rightMeters, t);
+
+        // Find the new gyro angle.
+        var gyro_lerp = gyroAngle.interpolate(endValue.gyroAngle, t);
+
+        // Create a twist to represent this change based on the interpolated sensor inputs.
+        Twist2d twist = m_kinematics.toTwist2d(left_lerp - leftMeters, right_lerp - rightMeters);
+        twist.dtheta = gyro_lerp.minus(gyroAngle).getRadians();
+
+        return new InterpolationRecord(poseMeters.exp(twist), gyro_lerp, left_lerp, right_lerp);
+      }
+    }
+
+    @Override
+    public boolean equals(Object obj) {
+      if (this == obj) {
+        return true;
+      }
+      if (!(obj instanceof InterpolationRecord)) {
+        return false;
+      }
+      InterpolationRecord record = (InterpolationRecord) obj;
+      return Objects.equals(gyroAngle, record.gyroAngle)
+          && Double.compare(leftMeters, record.leftMeters) == 0
+          && Double.compare(rightMeters, record.rightMeters) == 0
+          && Objects.equals(poseMeters, record.poseMeters);
+    }
+
+    @Override
+    public int hashCode() {
+      return Objects.hash(gyroAngle, leftMeters, rightMeters, poseMeters);
+    }
   }
 }
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/ExtendedKalmanFilter.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/ExtendedKalmanFilter.java
index d4f9e56..5f9e52e 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/ExtendedKalmanFilter.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/ExtendedKalmanFilter.java
@@ -34,16 +34,13 @@
  * https://file.tavsys.net/control/controls-engineering-in-frc.pdf chapter 9 "Stochastic control
  * theory".
  */
-@SuppressWarnings("ClassTypeParameterName")
 public class ExtendedKalmanFilter<States extends Num, Inputs extends Num, Outputs extends Num>
     implements KalmanTypeFilter<States, Inputs, Outputs> {
   private final Nat<States> m_states;
   private final Nat<Outputs> m_outputs;
 
-  @SuppressWarnings("MemberName")
   private final BiFunction<Matrix<States, N1>, Matrix<Inputs, N1>, Matrix<States, N1>> m_f;
 
-  @SuppressWarnings("MemberName")
   private final BiFunction<Matrix<States, N1>, Matrix<Inputs, N1>, Matrix<Outputs, N1>> m_h;
 
   private BiFunction<Matrix<Outputs, N1>, Matrix<Outputs, N1>, Matrix<Outputs, N1>> m_residualFuncY;
@@ -53,10 +50,8 @@
   private final Matrix<States, States> m_initP;
   private final Matrix<Outputs, Outputs> m_contR;
 
-  @SuppressWarnings("MemberName")
   private Matrix<States, N1> m_xHat;
 
-  @SuppressWarnings("MemberName")
   private Matrix<States, States> m_P;
 
   private double m_dtSeconds;
@@ -73,7 +68,6 @@
    * @param measurementStdDevs Standard deviations of measurements.
    * @param dtSeconds Nominal discretization timestep.
    */
-  @SuppressWarnings("ParameterName")
   public ExtendedKalmanFilter(
       Nat<States> states,
       Nat<Inputs> inputs,
@@ -111,7 +105,6 @@
    * @param addFuncX A function that adds two state vectors.
    * @param dtSeconds Nominal discretization timestep.
    */
-  @SuppressWarnings("ParameterName")
   public ExtendedKalmanFilter(
       Nat<States> states,
       Nat<Inputs> inputs,
@@ -133,7 +126,7 @@
     m_addFuncX = addFuncX;
 
     m_contQ = StateSpaceUtil.makeCovarianceMatrix(states, stateStdDevs);
-    this.m_contR = StateSpaceUtil.makeCovarianceMatrix(outputs, measurementStdDevs);
+    m_contR = StateSpaceUtil.makeCovarianceMatrix(outputs, measurementStdDevs);
     m_dtSeconds = dtSeconds;
 
     reset();
@@ -207,7 +200,7 @@
    * Returns an element of the state estimate x-hat.
    *
    * @param row Row of x-hat.
-   * @return the value of the state estimate x-hat at i.
+   * @return the value of the state estimate x-hat at that row.
    */
   @Override
   public double getXhat(int row) {
@@ -219,7 +212,6 @@
    *
    * @param xHat The state estimate x-hat.
    */
-  @SuppressWarnings("ParameterName")
   @Override
   public void setXhat(Matrix<States, N1> xHat) {
     m_xHat = xHat;
@@ -248,7 +240,6 @@
    * @param u New control input from controller.
    * @param dtSeconds Timestep for prediction.
    */
-  @SuppressWarnings("ParameterName")
   @Override
   public void predict(Matrix<Inputs, N1> u, double dtSeconds) {
     predict(u, m_f, dtSeconds);
@@ -258,10 +249,9 @@
    * Project the model into the future with a new control input u.
    *
    * @param u New control input from controller.
-   * @param f The function used to linearlize the model.
+   * @param f The function used to linearize the model.
    * @param dtSeconds Timestep for prediction.
    */
-  @SuppressWarnings("ParameterName")
   public void predict(
       Matrix<Inputs, N1> u,
       BiFunction<Matrix<States, N1>, Matrix<Inputs, N1>, Matrix<States, N1>> f,
@@ -288,7 +278,6 @@
    * @param u Same control input used in the predict step.
    * @param y Measurement vector.
    */
-  @SuppressWarnings("ParameterName")
   @Override
   public void correct(Matrix<Inputs, N1> u, Matrix<Outputs, N1> y) {
     correct(m_outputs, u, y, m_h, m_contR, m_residualFuncY, m_addFuncX);
@@ -306,16 +295,15 @@
    * @param u Same control input used in the predict step.
    * @param y Measurement vector.
    * @param h A vector-valued function of x and u that returns the measurement vector.
-   * @param R Discrete measurement noise covariance matrix.
+   * @param contR Continuous measurement noise covariance matrix.
    */
-  @SuppressWarnings({"ParameterName", "MethodTypeParameterName"})
   public <Rows extends Num> void correct(
       Nat<Rows> rows,
       Matrix<Inputs, N1> u,
       Matrix<Rows, N1> y,
       BiFunction<Matrix<States, N1>, Matrix<Inputs, N1>, Matrix<Rows, N1>> h,
-      Matrix<Rows, Rows> R) {
-    correct(rows, u, y, h, R, Matrix::minus, Matrix::plus);
+      Matrix<Rows, Rows> contR) {
+    correct(rows, u, y, h, contR, Matrix::minus, Matrix::plus);
   }
 
   /**
@@ -330,22 +318,21 @@
    * @param u Same control input used in the predict step.
    * @param y Measurement vector.
    * @param h A vector-valued function of x and u that returns the measurement vector.
-   * @param R Discrete measurement noise covariance matrix.
+   * @param contR Continuous measurement noise covariance matrix.
    * @param residualFuncY A function that computes the residual of two measurement vectors (i.e. it
    *     subtracts them.)
    * @param addFuncX A function that adds two state vectors.
    */
-  @SuppressWarnings({"ParameterName", "MethodTypeParameterName"})
   public <Rows extends Num> void correct(
       Nat<Rows> rows,
       Matrix<Inputs, N1> u,
       Matrix<Rows, N1> y,
       BiFunction<Matrix<States, N1>, Matrix<Inputs, N1>, Matrix<Rows, N1>> h,
-      Matrix<Rows, Rows> R,
+      Matrix<Rows, Rows> contR,
       BiFunction<Matrix<Rows, N1>, Matrix<Rows, N1>, Matrix<Rows, N1>> residualFuncY,
       BiFunction<Matrix<States, N1>, Matrix<States, N1>, Matrix<States, N1>> addFuncX) {
     final var C = NumericalJacobian.numericalJacobianX(rows, m_states, h, m_xHat, u);
-    final var discR = Discretization.discretizeR(R, m_dtSeconds);
+    final var discR = Discretization.discretizeR(contR, m_dtSeconds);
 
     final var S = C.times(m_P).times(C.transpose()).plus(discR);
 
@@ -366,7 +353,13 @@
     // x̂ₖ₊₁⁺ = x̂ₖ₊₁⁻ + K(y − h(x̂ₖ₊₁⁻, uₖ₊₁))
     m_xHat = addFuncX.apply(m_xHat, K.times(residualFuncY.apply(y, h.apply(m_xHat, u))));
 
-    // Pₖ₊₁⁺ = (I − KC)Pₖ₊₁⁻
-    m_P = Matrix.eye(m_states).minus(K.times(C)).times(m_P);
+    // Pₖ₊₁⁺ = (I−Kₖ₊₁C)Pₖ₊₁⁻(I−Kₖ₊₁C)ᵀ + Kₖ₊₁RKₖ₊₁ᵀ
+    // Use Joseph form for numerical stability
+    m_P =
+        Matrix.eye(m_states)
+            .minus(K.times(C))
+            .times(m_P)
+            .times(Matrix.eye(m_states).minus(K.times(C)).transpose())
+            .plus(K.times(discR).times(K.transpose()));
   }
 }
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/KalmanFilter.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/KalmanFilter.java
index c992d2f..24d6d91 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/KalmanFilter.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/KalmanFilter.java
@@ -29,18 +29,15 @@
  * https://file.tavsys.net/control/controls-engineering-in-frc.pdf chapter 9 "Stochastic control
  * theory".
  */
-@SuppressWarnings("ClassTypeParameterName")
 public class KalmanFilter<States extends Num, Inputs extends Num, Outputs extends Num> {
   private final Nat<States> m_states;
 
   private final LinearSystem<States, Inputs, Outputs> m_plant;
 
   /** The steady-state Kalman gain matrix. */
-  @SuppressWarnings("MemberName")
   private final Matrix<States, Outputs> m_K;
 
   /** The state estimate. */
-  @SuppressWarnings("MemberName")
   private Matrix<States, N1> m_xHat;
 
   /**
@@ -52,8 +49,8 @@
    * @param stateStdDevs Standard deviations of model states.
    * @param measurementStdDevs Standard deviations of measurements.
    * @param dtSeconds Nominal discretization timestep.
+   * @throws IllegalArgumentException If the system is unobservable.
    */
-  @SuppressWarnings("LocalVariableName")
   public KalmanFilter(
       Nat<States> states,
       Nat<Outputs> outputs,
@@ -172,7 +169,7 @@
    * Returns an element of the state estimate x-hat.
    *
    * @param row Row of x-hat.
-   * @return the state estimate x-hat at i.
+   * @return the state estimate x-hat at that row.
    */
   public double getXhat(int row) {
     return m_xHat.get(row, 0);
@@ -184,7 +181,6 @@
    * @param u New control input from controller.
    * @param dtSeconds Timestep for prediction.
    */
-  @SuppressWarnings("ParameterName")
   public void predict(Matrix<Inputs, N1> u, double dtSeconds) {
     this.m_xHat = m_plant.calculateX(m_xHat, u, dtSeconds);
   }
@@ -195,7 +191,6 @@
    * @param u Same control input used in the last predict step.
    * @param y Measurement vector.
    */
-  @SuppressWarnings("ParameterName")
   public void correct(Matrix<Inputs, N1> u, Matrix<Outputs, N1> y) {
     final var C = m_plant.getC();
     final var D = m_plant.getD();
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/KalmanFilterLatencyCompensator.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/KalmanFilterLatencyCompensator.java
index 89f35e5..15e7bd4 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/KalmanFilterLatencyCompensator.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/KalmanFilterLatencyCompensator.java
@@ -33,9 +33,8 @@
    * @param observer The observer.
    * @param u The input at the timestamp.
    * @param localY The local output at the timestamp
-   * @param timestampSeconds The timesnap of the state.
+   * @param timestampSeconds The timestamp of the state.
    */
-  @SuppressWarnings("ParameterName")
   public void addObserverState(
       KalmanTypeFilter<S, I, O> observer,
       Matrix<I, N1> u,
@@ -60,7 +59,6 @@
    * @param globalMeasurementCorrect The function take calls correct() on the observer.
    * @param timestampSeconds The timestamp of the measurement.
    */
-  @SuppressWarnings("ParameterName")
   public <R extends Num> void applyPastGlobalMeasurement(
       Nat<R> rows,
       KalmanTypeFilter<S, I, O> observer,
@@ -119,7 +117,7 @@
 
       // Index of snapshot taken before the global measurement. Since we already
       // handled the case where the index points to the first snapshot, this
-      // computation is guaranteed to be nonnegative.
+      // computation is guaranteed to be non-negative.
       int prevIdx = nextIdx - 1;
 
       // Find the snapshot closest in time to global measurement
@@ -165,14 +163,12 @@
   }
 
   /** This class contains all the information about our observer at a given time. */
-  @SuppressWarnings("MemberName")
   public class ObserverSnapshot {
     public final Matrix<S, N1> xHat;
     public final Matrix<S, S> errorCovariances;
     public final Matrix<I, N1> inputs;
     public final Matrix<O, N1> localMeasurements;
 
-    @SuppressWarnings("ParameterName")
     private ObserverSnapshot(
         KalmanTypeFilter<S, I, O> observer, Matrix<I, N1> u, Matrix<O, N1> localY) {
       this.xHat = observer.getXhat();
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/KalmanTypeFilter.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/KalmanTypeFilter.java
index 3fd3957..7a100f5 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/KalmanTypeFilter.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/KalmanTypeFilter.java
@@ -8,7 +8,6 @@
 import edu.wpi.first.math.Num;
 import edu.wpi.first.math.numbers.N1;
 
-@SuppressWarnings({"ParameterName", "InterfaceTypeParameterName"})
 interface KalmanTypeFilter<States extends Num, Inputs extends Num, Outputs extends Num> {
   Matrix<States, States> getP();
 
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/MecanumDrivePoseEstimator.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/MecanumDrivePoseEstimator.java
index d6f1075..448b8d3 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/MecanumDrivePoseEstimator.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/MecanumDrivePoseEstimator.java
@@ -4,157 +4,101 @@
 
 package edu.wpi.first.math.estimator;
 
+import edu.wpi.first.math.MathUtil;
 import edu.wpi.first.math.Matrix;
 import edu.wpi.first.math.Nat;
-import edu.wpi.first.math.StateSpaceUtil;
 import edu.wpi.first.math.VecBuilder;
 import edu.wpi.first.math.geometry.Pose2d;
 import edu.wpi.first.math.geometry.Rotation2d;
-import edu.wpi.first.math.geometry.Translation2d;
+import edu.wpi.first.math.geometry.Twist2d;
+import edu.wpi.first.math.interpolation.Interpolatable;
+import edu.wpi.first.math.interpolation.TimeInterpolatableBuffer;
 import edu.wpi.first.math.kinematics.MecanumDriveKinematics;
-import edu.wpi.first.math.kinematics.MecanumDriveWheelSpeeds;
+import edu.wpi.first.math.kinematics.MecanumDriveOdometry;
+import edu.wpi.first.math.kinematics.MecanumDriveWheelPositions;
 import edu.wpi.first.math.numbers.N1;
 import edu.wpi.first.math.numbers.N3;
 import edu.wpi.first.util.WPIUtilJNI;
-import java.util.function.BiConsumer;
+import java.util.Map;
+import java.util.Objects;
 
 /**
- * This class wraps an {@link UnscentedKalmanFilter Unscented Kalman Filter} to fuse
- * latency-compensated vision measurements with mecanum drive encoder velocity measurements. It will
- * correct for noisy measurements and encoder drift. It is intended to be an easy but more accurate
- * drop-in for {@link edu.wpi.first.math.kinematics.MecanumDriveOdometry}.
+ * This class wraps {@link MecanumDriveOdometry Mecanum Drive Odometry} to fuse latency-compensated
+ * vision measurements with mecanum drive encoder distance measurements. It will correct for noisy
+ * measurements and encoder drift. It is intended to be a drop-in replacement for {@link
+ * edu.wpi.first.math.kinematics.MecanumDriveOdometry}.
  *
- * <p>{@link MecanumDrivePoseEstimator#update} should be called every robot loop. If your loops are
- * faster or slower than the default of 0.02s, then you should change the nominal delta time using
- * the secondary constructor: {@link MecanumDrivePoseEstimator#MecanumDrivePoseEstimator(Rotation2d,
- * Pose2d, MecanumDriveKinematics, Matrix, Matrix, Matrix, double)}.
+ * <p>{@link MecanumDrivePoseEstimator#update} should be called every robot loop.
  *
  * <p>{@link MecanumDrivePoseEstimator#addVisionMeasurement} can be called as infrequently as you
  * want; if you never call it, then this class will behave mostly like regular encoder odometry.
- *
- * <p>The state-space system used internally has the following states (x), inputs (u), and outputs
- * (y):
- *
- * <p><strong> x = [x, y, theta]ᵀ </strong> in the field coordinate system containing x position, y
- * position, and heading.
- *
- * <p><strong> u = [v_x, v_y, omega]ᵀ </strong> containing x velocity, y velocity, and angular rate
- * in the field coordinate system.
- *
- * <p><strong> y = [x, y, theta]ᵀ </strong> from vision containing x position, y position, and
- * heading; or <strong> y = [theta]ᵀ </strong> containing gyro heading.
  */
 public class MecanumDrivePoseEstimator {
-  private final UnscentedKalmanFilter<N3, N3, N1> m_observer;
   private final MecanumDriveKinematics m_kinematics;
-  private final BiConsumer<Matrix<N3, N1>, Matrix<N3, N1>> m_visionCorrect;
-  private final KalmanFilterLatencyCompensator<N3, N3, N1> m_latencyCompensator;
+  private final MecanumDriveOdometry m_odometry;
+  private final Matrix<N3, N1> m_q = new Matrix<>(Nat.N3(), Nat.N1());
+  private Matrix<N3, N3> m_visionK = new Matrix<>(Nat.N3(), Nat.N3());
 
-  private final double m_nominalDt; // Seconds
-  private double m_prevTimeSeconds = -1.0;
-
-  private Rotation2d m_gyroOffset;
-  private Rotation2d m_previousAngle;
-
-  private Matrix<N3, N3> m_visionContR;
+  private final TimeInterpolatableBuffer<InterpolationRecord> m_poseBuffer =
+      TimeInterpolatableBuffer.createBuffer(1.5);
 
   /**
-   * Constructs a MecanumDrivePoseEstimator.
+   * Constructs a MecanumDrivePoseEstimator with default standard deviations for the model and
+   * vision measurements.
    *
-   * @param gyroAngle The current gyro angle.
-   * @param initialPoseMeters The starting pose estimate.
+   * <p>The default standard deviations of the model states are 0.1 meters for x, 0.1 meters for y,
+   * and 0.1 radians for heading. The default standard deviations of the vision measurements are
+   * 0.45 meters for x, 0.45 meters for y, and 0.45 radians for heading.
+   *
    * @param kinematics A correctly-configured kinematics object for your drivetrain.
-   * @param stateStdDevs Standard deviations of model states. Increase these numbers to trust your
-   *     model's state estimates less. This matrix is in the form [x, y, theta]ᵀ, with units in
-   *     meters and radians.
-   * @param localMeasurementStdDevs Standard deviations of the encoder and gyro measurements.
-   *     Increase these numbers to trust sensor readings from encoders and gyros less. This matrix
-   *     is in the form [theta], with units in radians.
-   * @param visionMeasurementStdDevs Standard deviations of the vision measurements. Increase these
-   *     numbers to trust global measurements from vision less. This matrix is in the form [x, y,
-   *     theta]ᵀ, with units in meters and radians.
+   * @param gyroAngle The current gyro angle.
+   * @param wheelPositions The distances driven by each wheel.
+   * @param initialPoseMeters The starting pose estimate.
    */
   public MecanumDrivePoseEstimator(
-      Rotation2d gyroAngle,
-      Pose2d initialPoseMeters,
       MecanumDriveKinematics kinematics,
-      Matrix<N3, N1> stateStdDevs,
-      Matrix<N1, N1> localMeasurementStdDevs,
-      Matrix<N3, N1> visionMeasurementStdDevs) {
+      Rotation2d gyroAngle,
+      MecanumDriveWheelPositions wheelPositions,
+      Pose2d initialPoseMeters) {
     this(
-        gyroAngle,
-        initialPoseMeters,
         kinematics,
-        stateStdDevs,
-        localMeasurementStdDevs,
-        visionMeasurementStdDevs,
-        0.02);
+        gyroAngle,
+        wheelPositions,
+        initialPoseMeters,
+        VecBuilder.fill(0.1, 0.1, 0.1),
+        VecBuilder.fill(0.45, 0.45, 0.45));
   }
 
   /**
    * Constructs a MecanumDrivePoseEstimator.
    *
-   * @param gyroAngle The current gyro angle.
-   * @param initialPoseMeters The starting pose estimate.
    * @param kinematics A correctly-configured kinematics object for your drivetrain.
-   * @param stateStdDevs Standard deviations of model states. Increase these numbers to trust your
-   *     model's state estimates less. This matrix is in the form [x, y, theta]ᵀ, with units in
-   *     meters and radians.
-   * @param localMeasurementStdDevs Standard deviations of the encoder and gyro measurements.
-   *     Increase these numbers to trust sensor readings from encoders and gyros less. This matrix
-   *     is in the form [theta], with units in radians.
-   * @param visionMeasurementStdDevs Standard deviations of the vision measurements. Increase these
-   *     numbers to trust global measurements from vision less. This matrix is in the form [x, y,
-   *     theta]ᵀ, with units in meters and radians.
-   * @param nominalDtSeconds The time in seconds between each robot loop.
+   * @param gyroAngle The current gyro angle.
+   * @param wheelPositions The distance measured by each wheel.
+   * @param initialPoseMeters The starting pose estimate.
+   * @param stateStdDevs Standard deviations of the pose estimate (x position in meters, y position
+   *     in meters, and heading in radians). Increase these numbers to trust your state estimate
+   *     less.
+   * @param visionMeasurementStdDevs Standard deviations of the vision pose measurement (x position
+   *     in meters, y position in meters, and heading in radians). Increase these numbers to trust
+   *     the vision pose measurement less.
    */
-  @SuppressWarnings("ParameterName")
   public MecanumDrivePoseEstimator(
-      Rotation2d gyroAngle,
-      Pose2d initialPoseMeters,
       MecanumDriveKinematics kinematics,
+      Rotation2d gyroAngle,
+      MecanumDriveWheelPositions wheelPositions,
+      Pose2d initialPoseMeters,
       Matrix<N3, N1> stateStdDevs,
-      Matrix<N1, N1> localMeasurementStdDevs,
-      Matrix<N3, N1> visionMeasurementStdDevs,
-      double nominalDtSeconds) {
-    m_nominalDt = nominalDtSeconds;
-
-    m_observer =
-        new UnscentedKalmanFilter<>(
-            Nat.N3(),
-            Nat.N1(),
-            (x, u) -> u,
-            (x, u) -> x.extractRowVector(2),
-            stateStdDevs,
-            localMeasurementStdDevs,
-            AngleStatistics.angleMean(2),
-            AngleStatistics.angleMean(0),
-            AngleStatistics.angleResidual(2),
-            AngleStatistics.angleResidual(0),
-            AngleStatistics.angleAdd(2),
-            m_nominalDt);
+      Matrix<N3, N1> visionMeasurementStdDevs) {
     m_kinematics = kinematics;
-    m_latencyCompensator = new KalmanFilterLatencyCompensator<>();
+    m_odometry = new MecanumDriveOdometry(kinematics, gyroAngle, wheelPositions, initialPoseMeters);
+
+    for (int i = 0; i < 3; ++i) {
+      m_q.set(i, 0, stateStdDevs.get(i, 0) * stateStdDevs.get(i, 0));
+    }
 
     // Initialize vision R
     setVisionMeasurementStdDevs(visionMeasurementStdDevs);
-
-    m_visionCorrect =
-        (u, y) ->
-            m_observer.correct(
-                Nat.N3(),
-                u,
-                y,
-                (x, u1) -> x,
-                m_visionContR,
-                AngleStatistics.angleMean(2),
-                AngleStatistics.angleResidual(2),
-                AngleStatistics.angleResidual(2),
-                AngleStatistics.angleAdd(2));
-
-    m_gyroOffset = initialPoseMeters.getRotation().minus(gyroAngle);
-    m_previousAngle = initialPoseMeters.getRotation();
-    m_observer.setXhat(StateSpaceUtil.poseTo3dVector(initialPoseMeters));
   }
 
   /**
@@ -167,85 +111,128 @@
    *     theta]ᵀ, with units in meters and radians.
    */
   public void setVisionMeasurementStdDevs(Matrix<N3, N1> visionMeasurementStdDevs) {
-    m_visionContR = StateSpaceUtil.makeCovarianceMatrix(Nat.N3(), visionMeasurementStdDevs);
+    var r = new double[3];
+    for (int i = 0; i < 3; ++i) {
+      r[i] = visionMeasurementStdDevs.get(i, 0) * visionMeasurementStdDevs.get(i, 0);
+    }
+
+    // Solve for closed form Kalman gain for continuous Kalman filter with A = 0
+    // and C = I. See wpimath/algorithms.md.
+    for (int row = 0; row < 3; ++row) {
+      if (m_q.get(row, 0) == 0.0) {
+        m_visionK.set(row, row, 0.0);
+      } else {
+        m_visionK.set(
+            row, row, m_q.get(row, 0) / (m_q.get(row, 0) + Math.sqrt(m_q.get(row, 0) * r[row])));
+      }
+    }
   }
 
   /**
    * Resets the robot's position on the field.
    *
-   * <p>You NEED to reset your encoders (to zero) when calling this method.
-   *
    * <p>The gyroscope angle does not need to be reset in the user's robot code. The library
    * automatically takes care of offsetting the gyro angle.
    *
-   * @param poseMeters The position on the field that your robot is at.
    * @param gyroAngle The angle reported by the gyroscope.
+   * @param wheelPositions The distances driven by each wheel.
+   * @param poseMeters The position on the field that your robot is at.
    */
-  public void resetPosition(Pose2d poseMeters, Rotation2d gyroAngle) {
+  public void resetPosition(
+      Rotation2d gyroAngle, MecanumDriveWheelPositions wheelPositions, Pose2d poseMeters) {
     // Reset state estimate and error covariance
-    m_observer.reset();
-    m_latencyCompensator.reset();
-
-    m_observer.setXhat(StateSpaceUtil.poseTo3dVector(poseMeters));
-
-    m_gyroOffset = getEstimatedPosition().getRotation().minus(gyroAngle);
-    m_previousAngle = poseMeters.getRotation();
+    m_odometry.resetPosition(gyroAngle, wheelPositions, poseMeters);
+    m_poseBuffer.clear();
   }
 
   /**
-   * Gets the pose of the robot at the current time as estimated by the Unscented Kalman Filter.
+   * Gets the estimated robot pose.
    *
    * @return The estimated robot pose in meters.
    */
   public Pose2d getEstimatedPosition() {
-    return new Pose2d(
-        m_observer.getXhat(0), m_observer.getXhat(1), new Rotation2d(m_observer.getXhat(2)));
+    return m_odometry.getPoseMeters();
   }
 
   /**
-   * Add a vision measurement to the Unscented Kalman Filter. This will correct the odometry pose
-   * estimate while still accounting for measurement noise.
+   * Adds a vision measurement to the Kalman Filter. This will correct the odometry pose estimate
+   * while still accounting for measurement noise.
    *
    * <p>This method can be called as infrequently as you want, as long as you are calling {@link
    * MecanumDrivePoseEstimator#update} every loop.
    *
+   * <p>To promote stability of the pose estimate and make it robust to bad vision data, we
+   * recommend only adding vision measurements that are already within one meter or so of the
+   * current pose estimate.
+   *
    * @param visionRobotPoseMeters The pose of the robot as measured by the vision camera.
    * @param timestampSeconds The timestamp of the vision measurement in seconds. Note that if you
-   *     don't use your own time source by calling {@link MecanumDrivePoseEstimator#updateWithTime}
-   *     then you must use a timestamp with an epoch since FPGA startup (i.e. the epoch of this
-   *     timestamp is the same epoch as Timer.getFPGATimestamp.) This means that you should use
-   *     Timer.getFPGATimestamp as your time source or sync the epochs.
+   *     don't use your own time source by calling {@link
+   *     MecanumDrivePoseEstimator#updateWithTime(double,Rotation2d,MecanumDriveWheelPositions)}
+   *     then you must use a timestamp with an epoch since FPGA startup (i.e., the epoch of this
+   *     timestamp is the same epoch as {@link edu.wpi.first.wpilibj.Timer#getFPGATimestamp()}.)
+   *     This means that you should use {@link edu.wpi.first.wpilibj.Timer#getFPGATimestamp()} as
+   *     your time source or sync the epochs.
    */
   public void addVisionMeasurement(Pose2d visionRobotPoseMeters, double timestampSeconds) {
-    m_latencyCompensator.applyPastGlobalMeasurement(
-        Nat.N3(),
-        m_observer,
-        m_nominalDt,
-        StateSpaceUtil.poseTo3dVector(visionRobotPoseMeters),
-        m_visionCorrect,
-        timestampSeconds);
+    // Step 1: Get the pose odometry measured at the moment the vision measurement was made.
+    var sample = m_poseBuffer.getSample(timestampSeconds);
+
+    if (sample.isEmpty()) {
+      return;
+    }
+
+    // Step 2: Measure the twist between the odometry pose and the vision pose.
+    var twist = sample.get().poseMeters.log(visionRobotPoseMeters);
+
+    // Step 3: We should not trust the twist entirely, so instead we scale this twist by a Kalman
+    // gain matrix representing how much we trust vision measurements compared to our current pose.
+    var k_times_twist = m_visionK.times(VecBuilder.fill(twist.dx, twist.dy, twist.dtheta));
+
+    // Step 4: Convert back to Twist2d.
+    var scaledTwist =
+        new Twist2d(k_times_twist.get(0, 0), k_times_twist.get(1, 0), k_times_twist.get(2, 0));
+
+    // Step 5: Reset Odometry to state at sample with vision adjustment.
+    m_odometry.resetPosition(
+        sample.get().gyroAngle,
+        sample.get().wheelPositions,
+        sample.get().poseMeters.exp(scaledTwist));
+
+    // Step 6: Replay odometry inputs between sample time and latest recorded sample to update the
+    // pose buffer and correct odometry.
+    for (Map.Entry<Double, InterpolationRecord> entry :
+        m_poseBuffer.getInternalBuffer().tailMap(timestampSeconds).entrySet()) {
+      updateWithTime(entry.getKey(), entry.getValue().gyroAngle, entry.getValue().wheelPositions);
+    }
   }
 
   /**
-   * Add a vision measurement to the Unscented Kalman Filter. This will correct the odometry pose
-   * estimate while still accounting for measurement noise.
+   * Adds a vision measurement to the Kalman Filter. This will correct the odometry pose estimate
+   * while still accounting for measurement noise.
    *
    * <p>This method can be called as infrequently as you want, as long as you are calling {@link
    * MecanumDrivePoseEstimator#update} every loop.
    *
+   * <p>To promote stability of the pose estimate and make it robust to bad vision data, we
+   * recommend only adding vision measurements that are already within one meter or so of the
+   * current pose estimate.
+   *
    * <p>Note that the vision measurement standard deviations passed into this method will continue
    * to apply to future measurements until a subsequent call to {@link
    * MecanumDrivePoseEstimator#setVisionMeasurementStdDevs(Matrix)} or this method.
    *
    * @param visionRobotPoseMeters The pose of the robot as measured by the vision camera.
    * @param timestampSeconds The timestamp of the vision measurement in seconds. Note that if you
-   *     don't use your own time source by calling {@link MecanumDrivePoseEstimator#updateWithTime}
-   *     then you must use a timestamp with an epoch since FPGA startup (i.e. the epoch of this
-   *     timestamp is the same epoch as Timer.getFPGATimestamp.) This means that you should use
-   *     Timer.getFPGATimestamp as your time source in this case.
-   * @param visionMeasurementStdDevs Standard deviations of the vision measurements. Increase these
-   *     numbers to trust global measurements from vision less. This matrix is in the form [x, y,
-   *     theta]ᵀ, with units in meters and radians.
+   *     don't use your own time source by calling {@link
+   *     MecanumDrivePoseEstimator#updateWithTime(double,Rotation2d,MecanumDriveWheelPositions)},
+   *     then you must use a timestamp with an epoch since FPGA startup (i.e., the epoch of this
+   *     timestamp is the same epoch as {@link edu.wpi.first.wpilibj.Timer#getFPGATimestamp()}).
+   *     This means that you should use {@link edu.wpi.first.wpilibj.Timer#getFPGATimestamp()} as
+   *     your time source in this case.
+   * @param visionMeasurementStdDevs Standard deviations of the vision pose measurement (x position
+   *     in meters, y position in meters, and heading in radians). Increase these numbers to trust
+   *     the vision pose measurement less.
    */
   public void addVisionMeasurement(
       Pose2d visionRobotPoseMeters,
@@ -256,50 +243,141 @@
   }
 
   /**
-   * Updates the the Unscented Kalman Filter using only wheel encoder information. This should be
-   * called every loop, and the correct loop period must be passed into the constructor of this
-   * class.
+   * Updates the pose estimator with wheel encoder and gyro information. This should be called every
+   * loop.
    *
    * @param gyroAngle The current gyro angle.
-   * @param wheelSpeeds The current speeds of the mecanum drive wheels.
+   * @param wheelPositions The distances driven by each wheel.
    * @return The estimated pose of the robot in meters.
    */
-  public Pose2d update(Rotation2d gyroAngle, MecanumDriveWheelSpeeds wheelSpeeds) {
-    return updateWithTime(WPIUtilJNI.now() * 1.0e-6, gyroAngle, wheelSpeeds);
+  public Pose2d update(Rotation2d gyroAngle, MecanumDriveWheelPositions wheelPositions) {
+    return updateWithTime(WPIUtilJNI.now() * 1.0e-6, gyroAngle, wheelPositions);
   }
 
   /**
-   * Updates the the Unscented Kalman Filter using only wheel encoder information. This should be
-   * called every loop, and the correct loop period must be passed into the constructor of this
-   * class.
+   * Updates the pose estimator with wheel encoder and gyro information. This should be called every
+   * loop.
    *
    * @param currentTimeSeconds Time at which this method was called, in seconds.
    * @param gyroAngle The current gyroscope angle.
-   * @param wheelSpeeds The current speeds of the mecanum drive wheels.
+   * @param wheelPositions The distances driven by each wheel.
    * @return The estimated pose of the robot in meters.
    */
-  @SuppressWarnings("LocalVariableName")
   public Pose2d updateWithTime(
-      double currentTimeSeconds, Rotation2d gyroAngle, MecanumDriveWheelSpeeds wheelSpeeds) {
-    double dt = m_prevTimeSeconds >= 0 ? currentTimeSeconds - m_prevTimeSeconds : m_nominalDt;
-    m_prevTimeSeconds = currentTimeSeconds;
+      double currentTimeSeconds, Rotation2d gyroAngle, MecanumDriveWheelPositions wheelPositions) {
+    m_odometry.update(gyroAngle, wheelPositions);
 
-    var angle = gyroAngle.plus(m_gyroOffset);
-    var omega = angle.minus(m_previousAngle).getRadians() / dt;
-
-    var chassisSpeeds = m_kinematics.toChassisSpeeds(wheelSpeeds);
-    var fieldRelativeVelocities =
-        new Translation2d(chassisSpeeds.vxMetersPerSecond, chassisSpeeds.vyMetersPerSecond)
-            .rotateBy(angle);
-
-    var u = VecBuilder.fill(fieldRelativeVelocities.getX(), fieldRelativeVelocities.getY(), omega);
-    m_previousAngle = angle;
-
-    var localY = VecBuilder.fill(angle.getRadians());
-    m_latencyCompensator.addObserverState(m_observer, u, localY, currentTimeSeconds);
-    m_observer.predict(u, dt);
-    m_observer.correct(u, localY);
+    m_poseBuffer.addSample(
+        currentTimeSeconds,
+        new InterpolationRecord(
+            getEstimatedPosition(),
+            gyroAngle,
+            new MecanumDriveWheelPositions(
+                wheelPositions.frontLeftMeters,
+                wheelPositions.frontRightMeters,
+                wheelPositions.rearLeftMeters,
+                wheelPositions.rearRightMeters)));
 
     return getEstimatedPosition();
   }
+
+  /**
+   * Represents an odometry record. The record contains the inputs provided as well as the pose that
+   * was observed based on these inputs, as well as the previous record and its inputs.
+   */
+  private class InterpolationRecord implements Interpolatable<InterpolationRecord> {
+    // The pose observed given the current sensor inputs and the previous pose.
+    private final Pose2d poseMeters;
+
+    // The current gyro angle.
+    private final Rotation2d gyroAngle;
+
+    // The distances traveled by each wheel encoder.
+    private final MecanumDriveWheelPositions wheelPositions;
+
+    /**
+     * Constructs an Interpolation Record with the specified parameters.
+     *
+     * @param pose The pose observed given the current sensor inputs and the previous pose.
+     * @param gyro The current gyro angle.
+     * @param wheelPositions The distances traveled by each wheel encoder.
+     */
+    private InterpolationRecord(
+        Pose2d poseMeters, Rotation2d gyro, MecanumDriveWheelPositions wheelPositions) {
+      this.poseMeters = poseMeters;
+      this.gyroAngle = gyro;
+      this.wheelPositions = wheelPositions;
+    }
+
+    /**
+     * Return the interpolated record. This object is assumed to be the starting position, or lower
+     * bound.
+     *
+     * @param endValue The upper bound, or end.
+     * @param t How far between the lower and upper bound we are. This should be bounded in [0, 1].
+     * @return The interpolated value.
+     */
+    @Override
+    public InterpolationRecord interpolate(InterpolationRecord endValue, double t) {
+      if (t < 0) {
+        return this;
+      } else if (t >= 1) {
+        return endValue;
+      } else {
+        // Find the new wheel distances.
+        var wheels_lerp =
+            new MecanumDriveWheelPositions(
+                MathUtil.interpolate(
+                    this.wheelPositions.frontLeftMeters,
+                    endValue.wheelPositions.frontLeftMeters,
+                    t),
+                MathUtil.interpolate(
+                    this.wheelPositions.frontRightMeters,
+                    endValue.wheelPositions.frontRightMeters,
+                    t),
+                MathUtil.interpolate(
+                    this.wheelPositions.rearLeftMeters, endValue.wheelPositions.rearLeftMeters, t),
+                MathUtil.interpolate(
+                    this.wheelPositions.rearRightMeters,
+                    endValue.wheelPositions.rearRightMeters,
+                    t));
+
+        // Find the distance travelled between this measurement and the interpolated measurement.
+        var wheels_delta =
+            new MecanumDriveWheelPositions(
+                wheels_lerp.frontLeftMeters - this.wheelPositions.frontLeftMeters,
+                wheels_lerp.frontRightMeters - this.wheelPositions.frontRightMeters,
+                wheels_lerp.rearLeftMeters - this.wheelPositions.rearLeftMeters,
+                wheels_lerp.rearRightMeters - this.wheelPositions.rearRightMeters);
+
+        // Find the new gyro angle.
+        var gyro_lerp = gyroAngle.interpolate(endValue.gyroAngle, t);
+
+        // Create a twist to represent this change based on the interpolated sensor inputs.
+        Twist2d twist = m_kinematics.toTwist2d(wheels_delta);
+        twist.dtheta = gyro_lerp.minus(gyroAngle).getRadians();
+
+        return new InterpolationRecord(poseMeters.exp(twist), gyro_lerp, wheels_lerp);
+      }
+    }
+
+    @Override
+    public boolean equals(Object obj) {
+      if (this == obj) {
+        return true;
+      }
+      if (!(obj instanceof InterpolationRecord)) {
+        return false;
+      }
+      InterpolationRecord record = (InterpolationRecord) obj;
+      return Objects.equals(gyroAngle, record.gyroAngle)
+          && Objects.equals(wheelPositions, record.wheelPositions)
+          && Objects.equals(poseMeters, record.poseMeters);
+    }
+
+    @Override
+    public int hashCode() {
+      return Objects.hash(gyroAngle, wheelPositions, poseMeters);
+    }
+  }
 }
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/MerweScaledSigmaPoints.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/MerweScaledSigmaPoints.java
index fb0628b..24835f6 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/MerweScaledSigmaPoints.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/MerweScaledSigmaPoints.java
@@ -71,16 +71,15 @@
    * of the filter.
    *
    * @param x An array of the means.
-   * @param P Covariance of the filter.
-   * @return Two dimensional array of sigma points. Each column contains all of the sigmas for one
+   * @param s Square-root covariance of the filter.
+   * @return Two-dimensional array of sigma points. Each column contains all the sigmas for one
    *     dimension in the problem space. Ordered by Xi_0, Xi_{1..n}, Xi_{n+1..2n}.
    */
-  @SuppressWarnings({"ParameterName", "LocalVariableName"})
-  public Matrix<S, ?> sigmaPoints(Matrix<S, N1> x, Matrix<S, S> P) {
+  public Matrix<S, ?> squareRootSigmaPoints(Matrix<S, N1> x, Matrix<S, S> s) {
     double lambda = Math.pow(m_alpha, 2) * (m_states.getNum() + m_kappa) - m_states.getNum();
+    double eta = Math.sqrt(lambda + m_states.getNum());
 
-    var intermediate = P.times(lambda + m_states.getNum());
-    var U = intermediate.lltDecompose(true); // Lower triangular
+    Matrix<S, S> U = s.times(eta);
 
     // 2 * states + 1 by states
     Matrix<S, ?> sigmas =
@@ -101,7 +100,6 @@
    *
    * @param beta Incorporates prior knowledge of the distribution of the mean.
    */
-  @SuppressWarnings("LocalVariableName")
   private void computeWeights(double beta) {
     double lambda = Math.pow(m_alpha, 2) * (m_states.getNum() + m_kappa) - m_states.getNum();
     double c = 0.5 / (m_states.getNum() + lambda);
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/SwerveDrivePoseEstimator.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/SwerveDrivePoseEstimator.java
index 8782b7b..57451a0 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/SwerveDrivePoseEstimator.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/SwerveDrivePoseEstimator.java
@@ -4,157 +4,103 @@
 
 package edu.wpi.first.math.estimator;
 
+import edu.wpi.first.math.MathUtil;
 import edu.wpi.first.math.Matrix;
 import edu.wpi.first.math.Nat;
-import edu.wpi.first.math.StateSpaceUtil;
 import edu.wpi.first.math.VecBuilder;
 import edu.wpi.first.math.geometry.Pose2d;
 import edu.wpi.first.math.geometry.Rotation2d;
-import edu.wpi.first.math.geometry.Translation2d;
+import edu.wpi.first.math.geometry.Twist2d;
+import edu.wpi.first.math.interpolation.Interpolatable;
+import edu.wpi.first.math.interpolation.TimeInterpolatableBuffer;
 import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
-import edu.wpi.first.math.kinematics.SwerveModuleState;
+import edu.wpi.first.math.kinematics.SwerveDriveOdometry;
+import edu.wpi.first.math.kinematics.SwerveModulePosition;
 import edu.wpi.first.math.numbers.N1;
 import edu.wpi.first.math.numbers.N3;
 import edu.wpi.first.util.WPIUtilJNI;
-import java.util.function.BiConsumer;
+import java.util.Arrays;
+import java.util.Map;
+import java.util.Objects;
 
 /**
- * This class wraps an {@link UnscentedKalmanFilter Unscented Kalman Filter} to fuse
- * latency-compensated vision measurements with swerve drive encoder velocity measurements. It will
- * correct for noisy measurements and encoder drift. It is intended to be an easy but more accurate
- * drop-in for {@link edu.wpi.first.math.kinematics.SwerveDriveOdometry}.
+ * This class wraps {@link SwerveDriveOdometry Swerve Drive Odometry} to fuse latency-compensated
+ * vision measurements with swerve drive encoder distance measurements. It is intended to be a
+ * drop-in replacement for {@link edu.wpi.first.math.kinematics.SwerveDriveOdometry}.
  *
- * <p>{@link SwerveDrivePoseEstimator#update} should be called every robot loop. If your loops are
- * faster or slower than the default of 0.02s, then you should change the nominal delta time using
- * the secondary constructor: {@link SwerveDrivePoseEstimator#SwerveDrivePoseEstimator(Rotation2d,
- * Pose2d, SwerveDriveKinematics, Matrix, Matrix, Matrix, double)}.
+ * <p>{@link SwerveDrivePoseEstimator#update} should be called every robot loop.
  *
  * <p>{@link SwerveDrivePoseEstimator#addVisionMeasurement} can be called as infrequently as you
- * want; if you never call it, then this class will behave mostly like regular encoder odometry.
- *
- * <p>The state-space system used internally has the following states (x), inputs (u), and outputs
- * (y):
- *
- * <p><strong> x = [x, y, theta]ᵀ </strong> in the field coordinate system containing x position, y
- * position, and heading.
- *
- * <p><strong> u = [v_x, v_y, omega]ᵀ </strong> containing x velocity, y velocity, and angular rate
- * in the field coordinate system.
- *
- * <p><strong> y = [x, y, theta]ᵀ </strong> from vision containing x position, y position, and
- * heading; or <strong> y = [theta]ᵀ </strong> containing gyro heading.
+ * want; if you never call it, then this class will behave as regular encoder odometry.
  */
 public class SwerveDrivePoseEstimator {
-  private final UnscentedKalmanFilter<N3, N3, N1> m_observer;
   private final SwerveDriveKinematics m_kinematics;
-  private final BiConsumer<Matrix<N3, N1>, Matrix<N3, N1>> m_visionCorrect;
-  private final KalmanFilterLatencyCompensator<N3, N3, N1> m_latencyCompensator;
+  private final SwerveDriveOdometry m_odometry;
+  private final Matrix<N3, N1> m_q = new Matrix<>(Nat.N3(), Nat.N1());
+  private final int m_numModules;
+  private Matrix<N3, N3> m_visionK = new Matrix<>(Nat.N3(), Nat.N3());
 
-  private final double m_nominalDt; // Seconds
-  private double m_prevTimeSeconds = -1.0;
-
-  private Rotation2d m_gyroOffset;
-  private Rotation2d m_previousAngle;
-
-  private Matrix<N3, N3> m_visionContR;
+  private final TimeInterpolatableBuffer<InterpolationRecord> m_poseBuffer =
+      TimeInterpolatableBuffer.createBuffer(1.5);
 
   /**
-   * Constructs a SwerveDrivePoseEstimator.
+   * Constructs a SwerveDrivePoseEstimator with default standard deviations for the model and vision
+   * measurements.
    *
-   * @param gyroAngle The current gyro angle.
-   * @param initialPoseMeters The starting pose estimate.
+   * <p>The default standard deviations of the model states are 0.1 meters for x, 0.1 meters for y,
+   * and 0.1 radians for heading. The default standard deviations of the vision measurements are 0.9
+   * meters for x, 0.9 meters for y, and 0.9 radians for heading.
+   *
    * @param kinematics A correctly-configured kinematics object for your drivetrain.
-   * @param stateStdDevs Standard deviations of model states. Increase these numbers to trust your
-   *     model's state estimates less. This matrix is in the form [x, y, theta]ᵀ, with units in
-   *     meters and radians.
-   * @param localMeasurementStdDevs Standard deviations of the encoder and gyro measurements.
-   *     Increase these numbers to trust sensor readings from encoders and gyros less. This matrix
-   *     is in the form [theta], with units in radians.
-   * @param visionMeasurementStdDevs Standard deviations of the vision measurements. Increase these
-   *     numbers to trust global measurements from vision less. This matrix is in the form [x, y,
-   *     theta]ᵀ, with units in meters and radians.
+   * @param gyroAngle The current gyro angle.
+   * @param modulePositions The current distance measurements and rotations of the swerve modules.
+   * @param initialPoseMeters The starting pose estimate.
    */
   public SwerveDrivePoseEstimator(
-      Rotation2d gyroAngle,
-      Pose2d initialPoseMeters,
       SwerveDriveKinematics kinematics,
-      Matrix<N3, N1> stateStdDevs,
-      Matrix<N1, N1> localMeasurementStdDevs,
-      Matrix<N3, N1> visionMeasurementStdDevs) {
+      Rotation2d gyroAngle,
+      SwerveModulePosition[] modulePositions,
+      Pose2d initialPoseMeters) {
     this(
-        gyroAngle,
-        initialPoseMeters,
         kinematics,
-        stateStdDevs,
-        localMeasurementStdDevs,
-        visionMeasurementStdDevs,
-        0.02);
+        gyroAngle,
+        modulePositions,
+        initialPoseMeters,
+        VecBuilder.fill(0.1, 0.1, 0.1),
+        VecBuilder.fill(0.9, 0.9, 0.9));
   }
 
   /**
    * Constructs a SwerveDrivePoseEstimator.
    *
-   * @param gyroAngle The current gyro angle.
-   * @param initialPoseMeters The starting pose estimate.
    * @param kinematics A correctly-configured kinematics object for your drivetrain.
-   * @param stateStdDevs Standard deviations of model states. Increase these numbers to trust your
-   *     model's state estimates less. This matrix is in the form [x, y, theta]ᵀ, with units in
-   *     meters and radians.
-   * @param localMeasurementStdDevs Standard deviations of the encoder and gyro measurements.
-   *     Increase these numbers to trust sensor readings from encoders and gyros less. This matrix
-   *     is in the form [theta], with units in radians.
-   * @param visionMeasurementStdDevs Standard deviations of the vision measurements. Increase these
-   *     numbers to trust global measurements from vision less. This matrix is in the form [x, y,
-   *     theta]ᵀ, with units in meters and radians.
-   * @param nominalDtSeconds The time in seconds between each robot loop.
+   * @param gyroAngle The current gyro angle.
+   * @param modulePositions The current distance and rotation measurements of the swerve modules.
+   * @param initialPoseMeters The starting pose estimate.
+   * @param stateStdDevs Standard deviations of the pose estimate (x position in meters, y position
+   *     in meters, and heading in radians). Increase these numbers to trust your state estimate
+   *     less.
+   * @param visionMeasurementStdDevs Standard deviations of the vision pose measurement (x position
+   *     in meters, y position in meters, and heading in radians). Increase these numbers to trust
+   *     the vision pose measurement less.
    */
-  @SuppressWarnings("ParameterName")
   public SwerveDrivePoseEstimator(
-      Rotation2d gyroAngle,
-      Pose2d initialPoseMeters,
       SwerveDriveKinematics kinematics,
+      Rotation2d gyroAngle,
+      SwerveModulePosition[] modulePositions,
+      Pose2d initialPoseMeters,
       Matrix<N3, N1> stateStdDevs,
-      Matrix<N1, N1> localMeasurementStdDevs,
-      Matrix<N3, N1> visionMeasurementStdDevs,
-      double nominalDtSeconds) {
-    m_nominalDt = nominalDtSeconds;
-
-    m_observer =
-        new UnscentedKalmanFilter<>(
-            Nat.N3(),
-            Nat.N1(),
-            (x, u) -> u,
-            (x, u) -> x.extractRowVector(2),
-            stateStdDevs,
-            localMeasurementStdDevs,
-            AngleStatistics.angleMean(2),
-            AngleStatistics.angleMean(0),
-            AngleStatistics.angleResidual(2),
-            AngleStatistics.angleResidual(0),
-            AngleStatistics.angleAdd(2),
-            m_nominalDt);
+      Matrix<N3, N1> visionMeasurementStdDevs) {
     m_kinematics = kinematics;
-    m_latencyCompensator = new KalmanFilterLatencyCompensator<>();
+    m_odometry = new SwerveDriveOdometry(kinematics, gyroAngle, modulePositions, initialPoseMeters);
 
-    // Initialize vision R
+    for (int i = 0; i < 3; ++i) {
+      m_q.set(i, 0, stateStdDevs.get(i, 0) * stateStdDevs.get(i, 0));
+    }
+
+    m_numModules = modulePositions.length;
+
     setVisionMeasurementStdDevs(visionMeasurementStdDevs);
-
-    m_visionCorrect =
-        (u, y) ->
-            m_observer.correct(
-                Nat.N3(),
-                u,
-                y,
-                (x, u1) -> x,
-                m_visionContR,
-                AngleStatistics.angleMean(2),
-                AngleStatistics.angleResidual(2),
-                AngleStatistics.angleResidual(2),
-                AngleStatistics.angleAdd(2));
-
-    m_gyroOffset = initialPoseMeters.getRotation().minus(gyroAngle);
-    m_previousAngle = initialPoseMeters.getRotation();
-    m_observer.setXhat(StateSpaceUtil.poseTo3dVector(initialPoseMeters));
   }
 
   /**
@@ -167,85 +113,128 @@
    *     theta]ᵀ, with units in meters and radians.
    */
   public void setVisionMeasurementStdDevs(Matrix<N3, N1> visionMeasurementStdDevs) {
-    m_visionContR = StateSpaceUtil.makeCovarianceMatrix(Nat.N3(), visionMeasurementStdDevs);
+    var r = new double[3];
+    for (int i = 0; i < 3; ++i) {
+      r[i] = visionMeasurementStdDevs.get(i, 0) * visionMeasurementStdDevs.get(i, 0);
+    }
+
+    // Solve for closed form Kalman gain for continuous Kalman filter with A = 0
+    // and C = I. See wpimath/algorithms.md.
+    for (int row = 0; row < 3; ++row) {
+      if (m_q.get(row, 0) == 0.0) {
+        m_visionK.set(row, row, 0.0);
+      } else {
+        m_visionK.set(
+            row, row, m_q.get(row, 0) / (m_q.get(row, 0) + Math.sqrt(m_q.get(row, 0) * r[row])));
+      }
+    }
   }
 
   /**
    * Resets the robot's position on the field.
    *
-   * <p>You NEED to reset your encoders (to zero) when calling this method.
-   *
    * <p>The gyroscope angle does not need to be reset in the user's robot code. The library
    * automatically takes care of offsetting the gyro angle.
    *
-   * @param poseMeters The position on the field that your robot is at.
    * @param gyroAngle The angle reported by the gyroscope.
+   * @param modulePositions The current distance measurements and rotations of the swerve modules.
+   * @param poseMeters The position on the field that your robot is at.
    */
-  public void resetPosition(Pose2d poseMeters, Rotation2d gyroAngle) {
+  public void resetPosition(
+      Rotation2d gyroAngle, SwerveModulePosition[] modulePositions, Pose2d poseMeters) {
     // Reset state estimate and error covariance
-    m_observer.reset();
-    m_latencyCompensator.reset();
-
-    m_observer.setXhat(StateSpaceUtil.poseTo3dVector(poseMeters));
-
-    m_gyroOffset = getEstimatedPosition().getRotation().minus(gyroAngle);
-    m_previousAngle = poseMeters.getRotation();
+    m_odometry.resetPosition(gyroAngle, modulePositions, poseMeters);
+    m_poseBuffer.clear();
   }
 
   /**
-   * Gets the pose of the robot at the current time as estimated by the Unscented Kalman Filter.
+   * Gets the estimated robot pose.
    *
    * @return The estimated robot pose in meters.
    */
   public Pose2d getEstimatedPosition() {
-    return new Pose2d(
-        m_observer.getXhat(0), m_observer.getXhat(1), new Rotation2d(m_observer.getXhat(2)));
+    return m_odometry.getPoseMeters();
   }
 
   /**
-   * Add a vision measurement to the Unscented Kalman Filter. This will correct the odometry pose
-   * estimate while still accounting for measurement noise.
+   * Adds a vision measurement to the Kalman Filter. This will correct the odometry pose estimate
+   * while still accounting for measurement noise.
    *
    * <p>This method can be called as infrequently as you want, as long as you are calling {@link
    * SwerveDrivePoseEstimator#update} every loop.
    *
+   * <p>To promote stability of the pose estimate and make it robust to bad vision data, we
+   * recommend only adding vision measurements that are already within one meter or so of the
+   * current pose estimate.
+   *
    * @param visionRobotPoseMeters The pose of the robot as measured by the vision camera.
    * @param timestampSeconds The timestamp of the vision measurement in seconds. Note that if you
-   *     don't use your own time source by calling {@link SwerveDrivePoseEstimator#updateWithTime}
-   *     then you must use a timestamp with an epoch since FPGA startup (i.e. the epoch of this
-   *     timestamp is the same epoch as Timer.getFPGATimestamp.) This means that you should use
-   *     Timer.getFPGATimestamp as your time source or sync the epochs.
+   *     don't use your own time source by calling {@link
+   *     SwerveDrivePoseEstimator#updateWithTime(double,Rotation2d,SwerveModulePosition[])} then you
+   *     must use a timestamp with an epoch since FPGA startup (i.e., the epoch of this timestamp is
+   *     the same epoch as {@link edu.wpi.first.wpilibj.Timer#getFPGATimestamp()}.) This means that
+   *     you should use {@link edu.wpi.first.wpilibj.Timer#getFPGATimestamp()} as your time source
+   *     or sync the epochs.
    */
   public void addVisionMeasurement(Pose2d visionRobotPoseMeters, double timestampSeconds) {
-    m_latencyCompensator.applyPastGlobalMeasurement(
-        Nat.N3(),
-        m_observer,
-        m_nominalDt,
-        StateSpaceUtil.poseTo3dVector(visionRobotPoseMeters),
-        m_visionCorrect,
-        timestampSeconds);
+    // Step 1: Get the pose odometry measured at the moment the vision measurement was made.
+    var sample = m_poseBuffer.getSample(timestampSeconds);
+
+    if (sample.isEmpty()) {
+      return;
+    }
+
+    // Step 2: Measure the twist between the odometry pose and the vision pose.
+    var twist = sample.get().poseMeters.log(visionRobotPoseMeters);
+
+    // Step 3: We should not trust the twist entirely, so instead we scale this twist by a Kalman
+    // gain matrix representing how much we trust vision measurements compared to our current pose.
+    var k_times_twist = m_visionK.times(VecBuilder.fill(twist.dx, twist.dy, twist.dtheta));
+
+    // Step 4: Convert back to Twist2d.
+    var scaledTwist =
+        new Twist2d(k_times_twist.get(0, 0), k_times_twist.get(1, 0), k_times_twist.get(2, 0));
+
+    // Step 5: Reset Odometry to state at sample with vision adjustment.
+    m_odometry.resetPosition(
+        sample.get().gyroAngle,
+        sample.get().modulePositions,
+        sample.get().poseMeters.exp(scaledTwist));
+
+    // Step 6: Replay odometry inputs between sample time and latest recorded sample to update the
+    // pose buffer and correct odometry.
+    for (Map.Entry<Double, InterpolationRecord> entry :
+        m_poseBuffer.getInternalBuffer().tailMap(timestampSeconds).entrySet()) {
+      updateWithTime(entry.getKey(), entry.getValue().gyroAngle, entry.getValue().modulePositions);
+    }
   }
 
   /**
-   * Add a vision measurement to the Unscented Kalman Filter. This will correct the odometry pose
-   * estimate while still accounting for measurement noise.
+   * Adds a vision measurement to the Kalman Filter. This will correct the odometry pose estimate
+   * while still accounting for measurement noise.
    *
    * <p>This method can be called as infrequently as you want, as long as you are calling {@link
    * SwerveDrivePoseEstimator#update} every loop.
    *
+   * <p>To promote stability of the pose estimate and make it robust to bad vision data, we
+   * recommend only adding vision measurements that are already within one meter or so of the
+   * current pose estimate.
+   *
    * <p>Note that the vision measurement standard deviations passed into this method will continue
    * to apply to future measurements until a subsequent call to {@link
    * SwerveDrivePoseEstimator#setVisionMeasurementStdDevs(Matrix)} or this method.
    *
    * @param visionRobotPoseMeters The pose of the robot as measured by the vision camera.
    * @param timestampSeconds The timestamp of the vision measurement in seconds. Note that if you
-   *     don't use your own time source by calling {@link SwerveDrivePoseEstimator#updateWithTime}
-   *     then you must use a timestamp with an epoch since FPGA startup (i.e. the epoch of this
-   *     timestamp is the same epoch as Timer.getFPGATimestamp.) This means that you should use
-   *     Timer.getFPGATimestamp as your time source in this case.
-   * @param visionMeasurementStdDevs Standard deviations of the vision measurements. Increase these
-   *     numbers to trust global measurements from vision less. This matrix is in the form [x, y,
-   *     theta]ᵀ, with units in meters and radians.
+   *     don't use your own time source by calling {@link
+   *     SwerveDrivePoseEstimator#updateWithTime(double,Rotation2d,SwerveModulePosition[])}, then
+   *     you must use a timestamp with an epoch since FPGA startup (i.e., the epoch of this
+   *     timestamp is the same epoch as {@link edu.wpi.first.wpilibj.Timer#getFPGATimestamp()}).
+   *     This means that you should use {@link edu.wpi.first.wpilibj.Timer#getFPGATimestamp()} as
+   *     your time source in this case.
+   * @param visionMeasurementStdDevs Standard deviations of the vision pose measurement (x position
+   *     in meters, y position in meters, and heading in radians). Increase these numbers to trust
+   *     the vision pose measurement less.
    */
   public void addVisionMeasurement(
       Pose2d visionRobotPoseMeters,
@@ -256,50 +245,140 @@
   }
 
   /**
-   * Updates the the Unscented Kalman Filter using only wheel encoder information. This should be
-   * called every loop, and the correct loop period must be passed into the constructor of this
-   * class.
+   * Updates the pose estimator with wheel encoder and gyro information. This should be called every
+   * loop.
    *
    * @param gyroAngle The current gyro angle.
-   * @param moduleStates The current velocities and rotations of the swerve modules.
+   * @param modulePositions The current distance measurements and rotations of the swerve modules.
    * @return The estimated pose of the robot in meters.
    */
-  public Pose2d update(Rotation2d gyroAngle, SwerveModuleState... moduleStates) {
-    return updateWithTime(WPIUtilJNI.now() * 1.0e-6, gyroAngle, moduleStates);
+  public Pose2d update(Rotation2d gyroAngle, SwerveModulePosition[] modulePositions) {
+    return updateWithTime(WPIUtilJNI.now() * 1.0e-6, gyroAngle, modulePositions);
   }
 
   /**
-   * Updates the the Unscented Kalman Filter using only wheel encoder information. This should be
-   * called every loop, and the correct loop period must be passed into the constructor of this
-   * class.
+   * Updates the pose estimator with wheel encoder and gyro information. This should be called every
+   * loop.
    *
    * @param currentTimeSeconds Time at which this method was called, in seconds.
    * @param gyroAngle The current gyroscope angle.
-   * @param moduleStates The current velocities and rotations of the swerve modules.
+   * @param modulePositions The current distance measurements and rotations of the swerve modules.
    * @return The estimated pose of the robot in meters.
    */
-  @SuppressWarnings("LocalVariableName")
   public Pose2d updateWithTime(
-      double currentTimeSeconds, Rotation2d gyroAngle, SwerveModuleState... moduleStates) {
-    double dt = m_prevTimeSeconds >= 0 ? currentTimeSeconds - m_prevTimeSeconds : m_nominalDt;
-    m_prevTimeSeconds = currentTimeSeconds;
+      double currentTimeSeconds, Rotation2d gyroAngle, SwerveModulePosition[] modulePositions) {
+    if (modulePositions.length != m_numModules) {
+      throw new IllegalArgumentException(
+          "Number of modules is not consistent with number of wheel locations provided in "
+              + "constructor");
+    }
 
-    var angle = gyroAngle.plus(m_gyroOffset);
-    var omega = angle.minus(m_previousAngle).getRadians() / dt;
+    var internalModulePositions = new SwerveModulePosition[m_numModules];
 
-    var chassisSpeeds = m_kinematics.toChassisSpeeds(moduleStates);
-    var fieldRelativeVelocities =
-        new Translation2d(chassisSpeeds.vxMetersPerSecond, chassisSpeeds.vyMetersPerSecond)
-            .rotateBy(angle);
+    for (int i = 0; i < m_numModules; i++) {
+      internalModulePositions[i] =
+          new SwerveModulePosition(modulePositions[i].distanceMeters, modulePositions[i].angle);
+    }
 
-    var u = VecBuilder.fill(fieldRelativeVelocities.getX(), fieldRelativeVelocities.getY(), omega);
-    m_previousAngle = angle;
+    m_odometry.update(gyroAngle, internalModulePositions);
 
-    var localY = VecBuilder.fill(angle.getRadians());
-    m_latencyCompensator.addObserverState(m_observer, u, localY, currentTimeSeconds);
-    m_observer.predict(u, dt);
-    m_observer.correct(u, localY);
+    m_poseBuffer.addSample(
+        currentTimeSeconds,
+        new InterpolationRecord(getEstimatedPosition(), gyroAngle, internalModulePositions));
 
     return getEstimatedPosition();
   }
+
+  /**
+   * Represents an odometry record. The record contains the inputs provided as well as the pose that
+   * was observed based on these inputs, as well as the previous record and its inputs.
+   */
+  private class InterpolationRecord implements Interpolatable<InterpolationRecord> {
+    // The pose observed given the current sensor inputs and the previous pose.
+    private final Pose2d poseMeters;
+
+    // The current gyro angle.
+    private final Rotation2d gyroAngle;
+
+    // The distances and rotations measured at each module.
+    private final SwerveModulePosition[] modulePositions;
+
+    /**
+     * Constructs an Interpolation Record with the specified parameters.
+     *
+     * @param pose The pose observed given the current sensor inputs and the previous pose.
+     * @param gyro The current gyro angle.
+     * @param wheelPositions The distances and rotations measured at each wheel.
+     */
+    private InterpolationRecord(
+        Pose2d poseMeters, Rotation2d gyro, SwerveModulePosition[] modulePositions) {
+      this.poseMeters = poseMeters;
+      this.gyroAngle = gyro;
+      this.modulePositions = modulePositions;
+    }
+
+    /**
+     * Return the interpolated record. This object is assumed to be the starting position, or lower
+     * bound.
+     *
+     * @param endValue The upper bound, or end.
+     * @param t How far between the lower and upper bound we are. This should be bounded in [0, 1].
+     * @return The interpolated value.
+     */
+    @Override
+    public InterpolationRecord interpolate(InterpolationRecord endValue, double t) {
+      if (t < 0) {
+        return this;
+      } else if (t >= 1) {
+        return endValue;
+      } else {
+        // Find the new wheel distances.
+        var modulePositions = new SwerveModulePosition[m_numModules];
+
+        // Find the distance travelled between this measurement and the interpolated measurement.
+        var moduleDeltas = new SwerveModulePosition[m_numModules];
+
+        for (int i = 0; i < m_numModules; i++) {
+          double ds =
+              MathUtil.interpolate(
+                  this.modulePositions[i].distanceMeters,
+                  endValue.modulePositions[i].distanceMeters,
+                  t);
+          Rotation2d theta =
+              this.modulePositions[i].angle.interpolate(endValue.modulePositions[i].angle, t);
+          modulePositions[i] = new SwerveModulePosition(ds, theta);
+          moduleDeltas[i] =
+              new SwerveModulePosition(ds - this.modulePositions[i].distanceMeters, theta);
+        }
+
+        // Find the new gyro angle.
+        var gyro_lerp = gyroAngle.interpolate(endValue.gyroAngle, t);
+
+        // Create a twist to represent this change based on the interpolated sensor inputs.
+        Twist2d twist = m_kinematics.toTwist2d(moduleDeltas);
+        twist.dtheta = gyro_lerp.minus(gyroAngle).getRadians();
+
+        return new InterpolationRecord(poseMeters.exp(twist), gyro_lerp, modulePositions);
+      }
+    }
+
+    @Override
+    public boolean equals(Object obj) {
+      if (this == obj) {
+        return true;
+      }
+      if (!(obj instanceof InterpolationRecord)) {
+        return false;
+      }
+      InterpolationRecord record = (InterpolationRecord) obj;
+      return Objects.equals(gyroAngle, record.gyroAngle)
+          && Arrays.equals(modulePositions, record.modulePositions)
+          && Objects.equals(poseMeters, record.poseMeters);
+    }
+
+    @Override
+    public int hashCode() {
+      return Objects.hash(gyroAngle, Arrays.hashCode(modulePositions), poseMeters);
+    }
+  }
 }
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/UnscentedKalmanFilter.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/UnscentedKalmanFilter.java
index ffc2c15..d668564 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/UnscentedKalmanFilter.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/estimator/UnscentedKalmanFilter.java
@@ -14,6 +14,7 @@
 import edu.wpi.first.math.system.NumericalIntegration;
 import edu.wpi.first.math.system.NumericalJacobian;
 import java.util.function.BiFunction;
+import org.ejml.dense.row.decomposition.qr.QRDecompositionHouseholder_DDRM;
 import org.ejml.simple.SimpleMatrix;
 
 /**
@@ -33,8 +34,10 @@
  * <p>For more on the underlying math, read
  * https://file.tavsys.net/control/controls-engineering-in-frc.pdf chapter 9 "Stochastic control
  * theory".
+ *
+ * <p>This class implements a square-root-form unscented Kalman filter (SR-UKF). For more
+ * information about the SR-UKF, see https://www.researchgate.net/publication/3908304.
  */
-@SuppressWarnings({"MemberName", "ClassTypeParameterName"})
 public class UnscentedKalmanFilter<States extends Num, Inputs extends Num, Outputs extends Num>
     implements KalmanTypeFilter<States, Inputs, Outputs> {
   private final Nat<States> m_states;
@@ -50,7 +53,7 @@
   private BiFunction<Matrix<States, N1>, Matrix<States, N1>, Matrix<States, N1>> m_addFuncX;
 
   private Matrix<States, N1> m_xHat;
-  private Matrix<States, States> m_P;
+  private Matrix<States, States> m_S;
   private final Matrix<States, States> m_contQ;
   private final Matrix<Outputs, Outputs> m_contR;
   private Matrix<States, ?> m_sigmasF;
@@ -69,7 +72,6 @@
    * @param measurementStdDevs Standard deviations of measurements.
    * @param nominalDtSeconds Nominal discretization timestep.
    */
-  @SuppressWarnings("LambdaParameterName")
   public UnscentedKalmanFilter(
       Nat<States> states,
       Nat<Outputs> outputs,
@@ -115,7 +117,6 @@
    * @param addFuncX A function that adds two state vectors.
    * @param nominalDtSeconds Nominal discretization timestep.
    */
-  @SuppressWarnings("ParameterName")
   public UnscentedKalmanFilter(
       Nat<States> states,
       Nat<Outputs> outputs,
@@ -151,15 +152,16 @@
     reset();
   }
 
-  @SuppressWarnings({"ParameterName", "LocalVariableName"})
-  static <S extends Num, C extends Num> Pair<Matrix<C, N1>, Matrix<C, C>> unscentedTransform(
-      Nat<S> s,
-      Nat<C> dim,
-      Matrix<C, ?> sigmas,
-      Matrix<?, N1> Wm,
-      Matrix<?, N1> Wc,
-      BiFunction<Matrix<C, ?>, Matrix<?, N1>, Matrix<C, N1>> meanFunc,
-      BiFunction<Matrix<C, N1>, Matrix<C, N1>, Matrix<C, N1>> residualFunc) {
+  static <S extends Num, C extends Num>
+      Pair<Matrix<C, N1>, Matrix<C, C>> squareRootUnscentedTransform(
+          Nat<S> s,
+          Nat<C> dim,
+          Matrix<C, ?> sigmas,
+          Matrix<?, N1> Wm,
+          Matrix<?, N1> Wc,
+          BiFunction<Matrix<C, ?>, Matrix<?, N1>, Matrix<C, N1>> meanFunc,
+          BiFunction<Matrix<C, N1>, Matrix<C, N1>, Matrix<C, N1>> residualFunc,
+          Matrix<C, C> squareRootR) {
     if (sigmas.getNumRows() != dim.getNum() || sigmas.getNumCols() != 2 * s.getNum() + 1) {
       throw new IllegalArgumentException(
           "Sigmas must be covDim by 2 * states + 1! Got "
@@ -184,28 +186,64 @@
     //      k=1
     Matrix<C, N1> x = meanFunc.apply(sigmas, Wm);
 
-    // New covariance is the sum of the outer product of the residuals times the
-    // weights
-    Matrix<C, ?> y = new Matrix<>(new SimpleMatrix(dim.getNum(), 2 * s.getNum() + 1));
-    for (int i = 0; i < 2 * s.getNum() + 1; i++) {
-      // y[:, i] = sigmas[:, i] - x
-      y.setColumn(i, residualFunc.apply(sigmas.extractColumnVector(i), x));
+    Matrix<C, ?> Sbar = new Matrix<>(new SimpleMatrix(dim.getNum(), 2 * s.getNum() + dim.getNum()));
+    for (int i = 0; i < 2 * s.getNum(); i++) {
+      Sbar.setColumn(
+          i,
+          residualFunc.apply(sigmas.extractColumnVector(1 + i), x).times(Math.sqrt(Wc.get(1, 0))));
     }
-    Matrix<C, C> P =
-        y.times(Matrix.changeBoundsUnchecked(Wc.diag()))
-            .times(Matrix.changeBoundsUnchecked(y.transpose()));
+    Sbar.assignBlock(0, 2 * s.getNum(), squareRootR);
 
-    return new Pair<>(x, P);
+    QRDecompositionHouseholder_DDRM qr = new QRDecompositionHouseholder_DDRM();
+    var qrStorage = Sbar.transpose().getStorage();
+
+    if (!qr.decompose(qrStorage.getDDRM())) {
+      throw new RuntimeException("QR decomposition failed! Input matrix:\n" + qrStorage.toString());
+    }
+
+    Matrix<C, C> newS = new Matrix<>(new SimpleMatrix(qr.getR(null, true)));
+    newS.rankUpdate(residualFunc.apply(sigmas.extractColumnVector(0), x), Wc.get(0, 0), false);
+
+    return new Pair<>(x, newS);
   }
 
   /**
-   * Returns the error covariance matrix P.
+   * Returns the square-root error covariance matrix S.
+   *
+   * @return the square-root error covariance matrix S.
+   */
+  public Matrix<States, States> getS() {
+    return m_S;
+  }
+
+  /**
+   * Returns an element of the square-root error covariance matrix S.
+   *
+   * @param row Row of S.
+   * @param col Column of S.
+   * @return the value of the square-root error covariance matrix S at (i, j).
+   */
+  public double getS(int row, int col) {
+    return m_S.get(row, col);
+  }
+
+  /**
+   * Sets the entire square-root error covariance matrix S.
+   *
+   * @param newS The new value of S to use.
+   */
+  public void setS(Matrix<States, States> newS) {
+    m_S = newS;
+  }
+
+  /**
+   * Returns the reconstructed error covariance matrix P.
    *
    * @return the error covariance matrix P.
    */
   @Override
   public Matrix<States, States> getP() {
-    return m_P;
+    return m_S.transpose().times(m_S);
   }
 
   /**
@@ -214,10 +252,12 @@
    * @param row Row of P.
    * @param col Column of P.
    * @return the value of the error covariance matrix P at (i, j).
+   * @throws UnsupportedOperationException indexing into the reconstructed P matrix is not supported
    */
   @Override
   public double getP(int row, int col) {
-    return m_P.get(row, col);
+    throw new UnsupportedOperationException(
+        "indexing into the reconstructed P matrix is not supported");
   }
 
   /**
@@ -227,7 +267,7 @@
    */
   @Override
   public void setP(Matrix<States, States> newP) {
-    m_P = newP;
+    m_S = newP.lltDecompose(false);
   }
 
   /**
@@ -244,7 +284,7 @@
    * Returns an element of the state estimate x-hat.
    *
    * @param row Row of x-hat.
-   * @return the value of the state estimate x-hat at i.
+   * @return the value of the state estimate x-hat at 'i'.
    */
   @Override
   public double getXhat(int row) {
@@ -256,7 +296,6 @@
    *
    * @param xHat The state estimate x-hat.
    */
-  @SuppressWarnings("ParameterName")
   @Override
   public void setXhat(Matrix<States, N1> xHat) {
     m_xHat = xHat;
@@ -277,7 +316,7 @@
   @Override
   public void reset() {
     m_xHat = new Matrix<>(m_states, Nat.N1());
-    m_P = new Matrix<>(m_states, m_states);
+    m_S = new Matrix<>(m_states, m_states);
     m_sigmasF = new Matrix<>(new SimpleMatrix(m_states.getNum(), 2 * m_states.getNum() + 1));
   }
 
@@ -287,15 +326,15 @@
    * @param u New control input from controller.
    * @param dtSeconds Timestep for prediction.
    */
-  @SuppressWarnings({"LocalVariableName", "ParameterName"})
   @Override
   public void predict(Matrix<Inputs, N1> u, double dtSeconds) {
     // Discretize Q before projecting mean and covariance forward
     Matrix<States, States> contA =
         NumericalJacobian.numericalJacobianX(m_states, m_states, m_f, m_xHat, u);
     var discQ = Discretization.discretizeAQTaylor(contA, m_contQ, dtSeconds).getSecond();
+    var squareRootDiscQ = discQ.lltDecompose(true);
 
-    var sigmas = m_pts.sigmaPoints(m_xHat, m_P);
+    var sigmas = m_pts.squareRootSigmaPoints(m_xHat, m_S);
 
     for (int i = 0; i < m_pts.getNumSigmas(); ++i) {
       Matrix<States, N1> x = sigmas.extractColumnVector(i);
@@ -304,17 +343,18 @@
     }
 
     var ret =
-        unscentedTransform(
+        squareRootUnscentedTransform(
             m_states,
             m_states,
             m_sigmasF,
             m_pts.getWm(),
             m_pts.getWc(),
             m_meanFuncX,
-            m_residualFuncX);
+            m_residualFuncX,
+            squareRootDiscQ);
 
     m_xHat = ret.getFirst();
-    m_P = ret.getSecond().plus(discQ);
+    m_S = ret.getSecond();
     m_dtSeconds = dtSeconds;
   }
 
@@ -324,7 +364,6 @@
    * @param u Same control input used in the predict step.
    * @param y Measurement vector.
    */
-  @SuppressWarnings("ParameterName")
   @Override
   public void correct(Matrix<Inputs, N1> u, Matrix<Outputs, N1> y) {
     correct(
@@ -345,7 +384,6 @@
    * @param h A vector-valued function of x and u that returns the measurement vector.
    * @param R Measurement noise covariance matrix (continuous-time).
    */
-  @SuppressWarnings({"ParameterName", "LambdaParameterName", "LocalVariableName"})
   public <R extends Num> void correct(
       Nat<R> rows,
       Matrix<Inputs, N1> u,
@@ -382,7 +420,6 @@
    *     subtracts them.)
    * @param addFuncX A function that adds two state vectors.
    */
-  @SuppressWarnings({"ParameterName", "LocalVariableName"})
   public <R extends Num> void correct(
       Nat<R> rows,
       Matrix<Inputs, N1> u,
@@ -394,10 +431,11 @@
       BiFunction<Matrix<States, N1>, Matrix<States, N1>, Matrix<States, N1>> residualFuncX,
       BiFunction<Matrix<States, N1>, Matrix<States, N1>, Matrix<States, N1>> addFuncX) {
     final var discR = Discretization.discretizeR(R, m_dtSeconds);
+    final var squareRootDiscR = discR.lltDecompose(true);
 
     // Transform sigma points into measurement space
     Matrix<R, ?> sigmasH = new Matrix<>(new SimpleMatrix(rows.getNum(), 2 * m_states.getNum() + 1));
-    var sigmas = m_pts.sigmaPoints(m_xHat, m_P);
+    var sigmas = m_pts.squareRootSigmaPoints(m_xHat, m_S);
     for (int i = 0; i < m_pts.getNumSigmas(); i++) {
       Matrix<R, N1> hRet = h.apply(sigmas.extractColumnVector(i), u);
       sigmasH.setColumn(i, hRet);
@@ -405,10 +443,17 @@
 
     // Mean and covariance of prediction passed through unscented transform
     var transRet =
-        unscentedTransform(
-            m_states, rows, sigmasH, m_pts.getWm(), m_pts.getWc(), meanFuncY, residualFuncY);
+        squareRootUnscentedTransform(
+            m_states,
+            rows,
+            sigmasH,
+            m_pts.getWm(),
+            m_pts.getWc(),
+            meanFuncY,
+            residualFuncY,
+            squareRootDiscR);
     var yHat = transRet.getFirst();
-    var Py = transRet.getSecond().plus(discR);
+    var Sy = transRet.getSecond();
 
     // Compute cross covariance of the state and the measurements
     Matrix<States, R> Pxy = new Matrix<>(m_states, rows);
@@ -420,17 +465,20 @@
       Pxy = Pxy.plus(dx.times(dy).times(m_pts.getWc(i)));
     }
 
-    // K = P_{xy} P_y⁻¹
-    // Kᵀ = P_yᵀ⁻¹ P_{xy}ᵀ
-    // P_yᵀKᵀ = P_{xy}ᵀ
-    // Kᵀ = P_yᵀ.solve(P_{xy}ᵀ)
-    // K = (P_yᵀ.solve(P_{xy}ᵀ)ᵀ
-    Matrix<States, R> K = new Matrix<>(Py.transpose().solve(Pxy.transpose()).transpose());
+    // K = (P_{xy} / S_yᵀ) / S_y
+    // K = (S_y \ P_{xy}ᵀ)ᵀ / S_y
+    // K = (S_yᵀ \ (S_y \ P_{xy}ᵀ))ᵀ
+    Matrix<States, R> K =
+        Sy.transpose()
+            .solveFullPivHouseholderQr(Sy.solveFullPivHouseholderQr(Pxy.transpose()))
+            .transpose();
 
     // x̂ₖ₊₁⁺ = x̂ₖ₊₁⁻ + K(y − ŷ)
     m_xHat = addFuncX.apply(m_xHat, K.times(residualFuncY.apply(y, yHat)));
 
-    // Pₖ₊₁⁺ = Pₖ₊₁⁻ − KP_yKᵀ
-    m_P = m_P.minus(K.times(Py).times(K.transpose()));
+    Matrix<States, R> U = K.times(Sy);
+    for (int i = 0; i < rows.getNum(); i++) {
+      m_S.rankUpdate(U.extractColumnVector(i), -1, false);
+    }
   }
 }
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/filter/LinearFilter.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/filter/LinearFilter.java
index 5eac0b3..98dd4e1 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/filter/LinearFilter.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/filter/LinearFilter.java
@@ -128,9 +128,7 @@
     }
 
     double[] ffGains = new double[taps];
-    for (int i = 0; i < ffGains.length; i++) {
-      ffGains[i] = 1.0 / taps;
-    }
+    Arrays.fill(ffGains, 1.0 / taps);
 
     double[] fbGains = new double[0];
 
@@ -144,20 +142,17 @@
    * <p>Stencil points are the indices of the samples to use in the finite difference. 0 is the
    * current sample, -1 is the previous sample, -2 is the sample before that, etc. Don't use
    * positive stencil points (samples from the future) if the LinearFilter will be used for
-   * stream-based online filtering.
+   * stream-based online filtering (e.g., taking derivative of encoder samples in real-time).
    *
    * @param derivative The order of the derivative to compute.
-   * @param samples The number of samples to use to compute the given derivative. This must be one
-   *     more than the order of derivative or higher.
-   * @param stencil List of stencil points.
+   * @param stencil List of stencil points. Its length is the number of samples to use to compute
+   *     the given derivative. This must be one more than the order of the derivative or higher.
    * @param period The period in seconds between samples taken by the user.
    * @return Linear filter.
    * @throws IllegalArgumentException if derivative &lt; 1, samples &lt;= 0, or derivative &gt;=
    *     samples.
    */
-  @SuppressWarnings("LocalVariableName")
-  public static LinearFilter finiteDifference(
-      int derivative, int samples, int[] stencil, double period) {
+  public static LinearFilter finiteDifference(int derivative, int[] stencil, double period) {
     // See
     // https://en.wikipedia.org/wiki/Finite_difference_coefficient#Arbitrary_stencil_points
     //
@@ -170,7 +165,7 @@
     // [s₁ⁿ⁻¹ ⋯ sₙⁿ⁻¹][aₙ]      [δₙ₋₁,d]
     //
     // where δᵢ,ⱼ are the Kronecker delta. The FIR gains are the elements of the
-    // vector a in reverse order divided by hᵈ.
+    // vector 'a' in reverse order divided by hᵈ.
     //
     // The order of accuracy of the approximation is of the form O(hⁿ⁻ᵈ).
 
@@ -179,6 +174,8 @@
           "Order of derivative must be greater than or equal to one.");
     }
 
+    int samples = stencil.length;
+
     if (samples <= 0) {
       throw new IllegalArgumentException("Number of samples must be greater than zero.");
     }
@@ -236,7 +233,7 @@
       stencil[i] = -(samples - 1) + i;
     }
 
-    return finiteDifference(derivative, samples, stencil, period);
+    return finiteDifference(derivative, stencil, period);
   }
 
   /** Reset the filter state. */
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/filter/SlewRateLimiter.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/filter/SlewRateLimiter.java
index d3aa7d8..668b8b1 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/filter/SlewRateLimiter.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/filter/SlewRateLimiter.java
@@ -14,29 +14,50 @@
  * edu.wpi.first.math.trajectory.TrapezoidProfile} instead.
  */
 public class SlewRateLimiter {
-  private final double m_rateLimit;
+  private final double m_positiveRateLimit;
+  private final double m_negativeRateLimit;
   private double m_prevVal;
   private double m_prevTime;
 
   /**
-   * Creates a new SlewRateLimiter with the given rate limit and initial value.
+   * Creates a new SlewRateLimiter with the given positive and negative rate limits and initial
+   * value.
    *
-   * @param rateLimit The rate-of-change limit, in units per second.
+   * @param positiveRateLimit The rate-of-change limit in the positive direction, in units per
+   *     second. This is expected to be positive.
+   * @param negativeRateLimit The rate-of-change limit in the negative direction, in units per
+   *     second. This is expected to be negative.
    * @param initialValue The initial value of the input.
    */
-  public SlewRateLimiter(double rateLimit, double initialValue) {
-    m_rateLimit = rateLimit;
+  public SlewRateLimiter(double positiveRateLimit, double negativeRateLimit, double initialValue) {
+    m_positiveRateLimit = positiveRateLimit;
+    m_negativeRateLimit = negativeRateLimit;
     m_prevVal = initialValue;
     m_prevTime = WPIUtilJNI.now() * 1e-6;
   }
 
   /**
-   * Creates a new SlewRateLimiter with the given rate limit and an initial value of zero.
+   * Creates a new SlewRateLimiter with the given positive rate limit and negative rate limit of
+   * -rateLimit and initial value.
+   *
+   * @param rateLimit The rate-of-change limit, in units per second.
+   * @param initalValue The initial value of the input.
+   * @deprecated Use SlewRateLimiter(double positiveRateLimit, double negativeRateLimit, double
+   *     initalValue) instead.
+   */
+  @Deprecated(since = "2023", forRemoval = true)
+  public SlewRateLimiter(double rateLimit, double initalValue) {
+    this(rateLimit, -rateLimit, initalValue);
+  }
+
+  /**
+   * Creates a new SlewRateLimiter with the given positive rate limit and negative rate limit of
+   * -rateLimit.
    *
    * @param rateLimit The rate-of-change limit, in units per second.
    */
   public SlewRateLimiter(double rateLimit) {
-    this(rateLimit, 0);
+    this(rateLimit, -rateLimit, 0);
   }
 
   /**
@@ -49,7 +70,10 @@
     double currentTime = WPIUtilJNI.now() * 1e-6;
     double elapsedTime = currentTime - m_prevTime;
     m_prevVal +=
-        MathUtil.clamp(input - m_prevVal, -m_rateLimit * elapsedTime, m_rateLimit * elapsedTime);
+        MathUtil.clamp(
+            input - m_prevVal,
+            m_negativeRateLimit * elapsedTime,
+            m_positiveRateLimit * elapsedTime);
     m_prevTime = currentTime;
     return m_prevVal;
   }
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/CoordinateAxis.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/CoordinateAxis.java
new file mode 100644
index 0000000..d6033f8
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/CoordinateAxis.java
@@ -0,0 +1,87 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.math.geometry;
+
+import edu.wpi.first.math.VecBuilder;
+import edu.wpi.first.math.Vector;
+import edu.wpi.first.math.numbers.N3;
+
+/** A class representing a coordinate system axis within the NWU coordinate system. */
+public class CoordinateAxis {
+  private static final CoordinateAxis m_n = new CoordinateAxis(1.0, 0.0, 0.0);
+  private static final CoordinateAxis m_s = new CoordinateAxis(-1.0, 0.0, 0.0);
+  private static final CoordinateAxis m_e = new CoordinateAxis(0.0, -1.0, 0.0);
+  private static final CoordinateAxis m_w = new CoordinateAxis(0.0, 1.0, 0.0);
+  private static final CoordinateAxis m_u = new CoordinateAxis(0.0, 0.0, 1.0);
+  private static final CoordinateAxis m_d = new CoordinateAxis(0.0, 0.0, -1.0);
+
+  final Vector<N3> m_axis;
+
+  /**
+   * Constructs a coordinate system axis within the NWU coordinate system and normalizes it.
+   *
+   * @param x The x component.
+   * @param y The y component.
+   * @param z The z component.
+   */
+  public CoordinateAxis(double x, double y, double z) {
+    double norm = Math.sqrt(x * x + y * y + z * z);
+    m_axis = VecBuilder.fill(x / norm, y / norm, z / norm);
+  }
+
+  /**
+   * Returns a coordinate axis corresponding to +X in the NWU coordinate system.
+   *
+   * @return A coordinate axis corresponding to +X in the NWU coordinate system.
+   */
+  public static CoordinateAxis N() {
+    return m_n;
+  }
+
+  /**
+   * Returns a coordinate axis corresponding to -X in the NWU coordinate system.
+   *
+   * @return A coordinate axis corresponding to -X in the NWU coordinate system.
+   */
+  public static CoordinateAxis S() {
+    return m_s;
+  }
+
+  /**
+   * Returns a coordinate axis corresponding to -Y in the NWU coordinate system.
+   *
+   * @return A coordinate axis corresponding to -Y in the NWU coordinate system.
+   */
+  public static CoordinateAxis E() {
+    return m_e;
+  }
+
+  /**
+   * Returns a coordinate axis corresponding to +Y in the NWU coordinate system.
+   *
+   * @return A coordinate axis corresponding to +Y in the NWU coordinate system.
+   */
+  public static CoordinateAxis W() {
+    return m_w;
+  }
+
+  /**
+   * Returns a coordinate axis corresponding to +Z in the NWU coordinate system.
+   *
+   * @return A coordinate axis corresponding to +Z in the NWU coordinate system.
+   */
+  public static CoordinateAxis U() {
+    return m_u;
+  }
+
+  /**
+   * Returns a coordinate axis corresponding to -Z in the NWU coordinate system.
+   *
+   * @return A coordinate axis corresponding to -Z in the NWU coordinate system.
+   */
+  public static CoordinateAxis D() {
+    return m_d;
+  }
+}
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/CoordinateSystem.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/CoordinateSystem.java
new file mode 100644
index 0000000..5733177
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/CoordinateSystem.java
@@ -0,0 +1,130 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.math.geometry;
+
+import edu.wpi.first.math.Matrix;
+import edu.wpi.first.math.Nat;
+
+/** A helper class that converts Pose3d objects between different standard coordinate frames. */
+public class CoordinateSystem {
+  private static final CoordinateSystem m_nwu =
+      new CoordinateSystem(CoordinateAxis.N(), CoordinateAxis.W(), CoordinateAxis.U());
+  private static final CoordinateSystem m_edn =
+      new CoordinateSystem(CoordinateAxis.E(), CoordinateAxis.D(), CoordinateAxis.N());
+  private static final CoordinateSystem m_ned =
+      new CoordinateSystem(CoordinateAxis.N(), CoordinateAxis.E(), CoordinateAxis.D());
+
+  // Rotation from this coordinate system to NWU coordinate system
+  private final Rotation3d m_rotation;
+
+  /**
+   * Constructs a coordinate system with the given cardinal directions for each axis.
+   *
+   * @param positiveX The cardinal direction of the positive x-axis.
+   * @param positiveY The cardinal direction of the positive y-axis.
+   * @param positiveZ The cardinal direction of the positive z-axis.
+   * @throws IllegalArgumentException if the coordinate system isn't special orthogonal
+   */
+  public CoordinateSystem(
+      CoordinateAxis positiveX, CoordinateAxis positiveY, CoordinateAxis positiveZ) {
+    // Construct a change of basis matrix from the source coordinate system to the
+    // NWU coordinate system. Each column vector in the change of basis matrix is
+    // one of the old basis vectors mapped to its representation in the new basis.
+    var R = new Matrix<>(Nat.N3(), Nat.N3());
+    R.assignBlock(0, 0, positiveX.m_axis);
+    R.assignBlock(0, 1, positiveY.m_axis);
+    R.assignBlock(0, 2, positiveZ.m_axis);
+
+    // The change of basis matrix should be a pure rotation. The Rotation3d
+    // constructor will verify this by checking for special orthogonality.
+    m_rotation = new Rotation3d(R);
+  }
+
+  /**
+   * Returns an instance of the North-West-Up (NWU) coordinate system.
+   *
+   * <p>The +X axis is north, the +Y axis is west, and the +Z axis is up.
+   *
+   * @return An instance of the North-West-Up (NWU) coordinate system.
+   */
+  public static CoordinateSystem NWU() {
+    return m_nwu;
+  }
+
+  /**
+   * Returns an instance of the East-Down-North (EDN) coordinate system.
+   *
+   * <p>The +X axis is east, the +Y axis is down, and the +Z axis is north.
+   *
+   * @return An instance of the East-Down-North (EDN) coordinate system.
+   */
+  public static CoordinateSystem EDN() {
+    return m_edn;
+  }
+
+  /**
+   * Returns an instance of the North-East-Down (NED) coordinate system.
+   *
+   * <p>The +X axis is north, the +Y axis is east, and the +Z axis is down.
+   *
+   * @return An instance of the North-East-Down (NED) coordinate system.
+   */
+  public static CoordinateSystem NED() {
+    return m_ned;
+  }
+
+  /**
+   * Converts the given translation from one coordinate system to another.
+   *
+   * @param translation The translation to convert.
+   * @param from The coordinate system the pose starts in.
+   * @param to The coordinate system to which to convert.
+   * @return The given translation in the desired coordinate system.
+   */
+  public static Translation3d convert(
+      Translation3d translation, CoordinateSystem from, CoordinateSystem to) {
+    return translation.rotateBy(from.m_rotation.minus(to.m_rotation));
+  }
+
+  /**
+   * Converts the given rotation from one coordinate system to another.
+   *
+   * @param rotation The rotation to convert.
+   * @param from The coordinate system the rotation starts in.
+   * @param to The coordinate system to which to convert.
+   * @return The given rotation in the desired coordinate system.
+   */
+  public static Rotation3d convert(
+      Rotation3d rotation, CoordinateSystem from, CoordinateSystem to) {
+    return rotation.rotateBy(from.m_rotation.minus(to.m_rotation));
+  }
+
+  /**
+   * Converts the given pose from one coordinate system to another.
+   *
+   * @param pose The pose to convert.
+   * @param from The coordinate system the pose starts in.
+   * @param to The coordinate system to which to convert.
+   * @return The given pose in the desired coordinate system.
+   */
+  public static Pose3d convert(Pose3d pose, CoordinateSystem from, CoordinateSystem to) {
+    return new Pose3d(
+        convert(pose.getTranslation(), from, to), convert(pose.getRotation(), from, to));
+  }
+
+  /**
+   * Converts the given transform from one coordinate system to another.
+   *
+   * @param transform The transform to convert.
+   * @param from The coordinate system the transform starts in.
+   * @param to The coordinate system to which to convert.
+   * @return The given transform in the desired coordinate system.
+   */
+  public static Transform3d convert(
+      Transform3d transform, CoordinateSystem from, CoordinateSystem to) {
+    return new Transform3d(
+        convert(transform.getTranslation(), from, to), convert(transform.getRotation(), from, to));
+  }
+}
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/Pose2d.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/Pose2d.java
index f64eff4..bce832e 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/Pose2d.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/Pose2d.java
@@ -11,17 +11,14 @@
 import edu.wpi.first.math.interpolation.Interpolatable;
 import java.util.Objects;
 
-/** Represents a 2d pose containing translational and rotational elements. */
+/** Represents a 2D pose containing translational and rotational elements. */
 @JsonIgnoreProperties(ignoreUnknown = true)
 @JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE)
 public class Pose2d implements Interpolatable<Pose2d> {
   private final Translation2d m_translation;
   private final Rotation2d m_rotation;
 
-  /**
-   * Constructs a pose at the origin facing toward the positive X axis. (Translation2d{0, 0} and
-   * Rotation{0})
-   */
+  /** Constructs a pose at the origin facing toward the positive X axis. */
   public Pose2d() {
     m_translation = new Translation2d();
     m_rotation = new Rotation2d();
@@ -42,8 +39,7 @@
   }
 
   /**
-   * Convenience constructors that takes in x and y values directly instead of having to construct a
-   * Translation2d.
+   * Constructs a pose with x and y translations instead of a separate Translation2d.
    *
    * @param x The x component of the translational component of the pose.
    * @param y The y component of the translational component of the pose.
@@ -57,8 +53,11 @@
   /**
    * Transforms the pose by the given transformation and returns the new transformed pose.
    *
-   * <p>The matrix multiplication is as follows [x_new] [cos, -sin, 0][transform.x] [y_new] += [sin,
-   * cos, 0][transform.y] [t_new] [0, 0, 1][transform.t]
+   * <pre>
+   * [x_new]    [cos, -sin, 0][transform.x]
+   * [y_new] += [sin,  cos, 0][transform.y]
+   * [t_new]    [  0,    0, 1][transform.t]
+   * </pre>
    *
    * @param other The transform to transform the pose by.
    * @return The transformed pose.
@@ -117,6 +116,26 @@
   }
 
   /**
+   * Multiplies the current pose by a scalar.
+   *
+   * @param scalar The scalar.
+   * @return The new scaled Pose2d.
+   */
+  public Pose2d times(double scalar) {
+    return new Pose2d(m_translation.times(scalar), m_rotation.times(scalar));
+  }
+
+  /**
+   * Divides the current pose by a scalar.
+   *
+   * @param scalar The scalar.
+   * @return The new scaled Pose2d.
+   */
+  public Pose2d div(double scalar) {
+    return times(1.0 / scalar);
+  }
+
+  /**
    * Transforms the pose by the given transformation and returns the new pose. See + operator for
    * the matrix multiplication performed.
    *
@@ -126,11 +145,11 @@
   public Pose2d transformBy(Transform2d other) {
     return new Pose2d(
         m_translation.plus(other.getTranslation().rotateBy(m_rotation)),
-        m_rotation.plus(other.getRotation()));
+        other.getRotation().plus(m_rotation));
   }
 
   /**
-   * Returns the other pose relative to the current pose.
+   * Returns the current pose relative to the given pose.
    *
    * <p>This function can often be used for trajectory tracking or pose stabilization algorithms to
    * get the error between the reference and the current pose.
@@ -160,8 +179,8 @@
    *
    * @param twist The change in pose in the robot's coordinate frame since the previous pose update.
    *     For example, if a non-holonomic robot moves forward 0.01 meters and changes angle by 0.5
-   *     degrees since the previous pose update, the twist would be Twist2d{0.01, 0.0,
-   *     toRadians(0.5)}
+   *     degrees since the previous pose update, the twist would be Twist2d(0.01, 0.0,
+   *     Units.degreesToRadians(0.5)).
    * @return The new pose of the robot.
    */
   public Pose2d exp(Twist2d twist) {
@@ -190,8 +209,8 @@
   }
 
   /**
-   * Returns a Twist2d that maps this pose to the end pose. If c is the output of a.Log(b), then
-   * a.Exp(c) would yield b.
+   * Returns a Twist2d that maps this pose to the end pose. If c is the output of {@code a.Log(b)},
+   * then {@code a.Exp(c)} would yield b.
    *
    * @param end The end pose for the transformation.
    * @return The twist that maps this to end.
@@ -245,7 +264,6 @@
   }
 
   @Override
-  @SuppressWarnings("ParameterName")
   public Pose2d interpolate(Pose2d endValue, double t) {
     if (t < 0) {
       return this;
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/Pose3d.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/Pose3d.java
new file mode 100644
index 0000000..8e3a3fe
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/Pose3d.java
@@ -0,0 +1,364 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.math.geometry;
+
+import com.fasterxml.jackson.annotation.JsonAutoDetect;
+import com.fasterxml.jackson.annotation.JsonCreator;
+import com.fasterxml.jackson.annotation.JsonIgnoreProperties;
+import com.fasterxml.jackson.annotation.JsonProperty;
+import edu.wpi.first.math.MatBuilder;
+import edu.wpi.first.math.Matrix;
+import edu.wpi.first.math.Nat;
+import edu.wpi.first.math.VecBuilder;
+import edu.wpi.first.math.Vector;
+import edu.wpi.first.math.interpolation.Interpolatable;
+import edu.wpi.first.math.numbers.N3;
+import java.util.Objects;
+
+/** Represents a 3D pose containing translational and rotational elements. */
+@JsonIgnoreProperties(ignoreUnknown = true)
+@JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE)
+public class Pose3d implements Interpolatable<Pose3d> {
+  private final Translation3d m_translation;
+  private final Rotation3d m_rotation;
+
+  /** Constructs a pose at the origin facing toward the positive X axis. */
+  public Pose3d() {
+    m_translation = new Translation3d();
+    m_rotation = new Rotation3d();
+  }
+
+  /**
+   * Constructs a pose with the specified translation and rotation.
+   *
+   * @param translation The translational component of the pose.
+   * @param rotation The rotational component of the pose.
+   */
+  @JsonCreator
+  public Pose3d(
+      @JsonProperty(required = true, value = "translation") Translation3d translation,
+      @JsonProperty(required = true, value = "rotation") Rotation3d rotation) {
+    m_translation = translation;
+    m_rotation = rotation;
+  }
+
+  /**
+   * Constructs a pose with x, y, and z translations instead of a separate Translation3d.
+   *
+   * @param x The x component of the translational component of the pose.
+   * @param y The y component of the translational component of the pose.
+   * @param z The z component of the translational component of the pose.
+   * @param rotation The rotational component of the pose.
+   */
+  public Pose3d(double x, double y, double z, Rotation3d rotation) {
+    m_translation = new Translation3d(x, y, z);
+    m_rotation = rotation;
+  }
+
+  /**
+   * Constructs a 3D pose from a 2D pose in the X-Y plane.
+   *
+   * @param pose The 2D pose.
+   */
+  public Pose3d(Pose2d pose) {
+    m_translation = new Translation3d(pose.getX(), pose.getY(), 0.0);
+    m_rotation = new Rotation3d(0.0, 0.0, pose.getRotation().getRadians());
+  }
+
+  /**
+   * Transforms the pose by the given transformation and returns the new transformed pose.
+   *
+   * @param other The transform to transform the pose by.
+   * @return The transformed pose.
+   */
+  public Pose3d plus(Transform3d other) {
+    return transformBy(other);
+  }
+
+  /**
+   * Returns the Transform3d that maps the one pose to another.
+   *
+   * @param other The initial pose of the transformation.
+   * @return The transform that maps the other pose to the current pose.
+   */
+  public Transform3d minus(Pose3d other) {
+    final var pose = this.relativeTo(other);
+    return new Transform3d(pose.getTranslation(), pose.getRotation());
+  }
+
+  /**
+   * Returns the translation component of the transformation.
+   *
+   * @return The translational component of the pose.
+   */
+  @JsonProperty
+  public Translation3d getTranslation() {
+    return m_translation;
+  }
+
+  /**
+   * Returns the X component of the pose's translation.
+   *
+   * @return The x component of the pose's translation.
+   */
+  public double getX() {
+    return m_translation.getX();
+  }
+
+  /**
+   * Returns the Y component of the pose's translation.
+   *
+   * @return The y component of the pose's translation.
+   */
+  public double getY() {
+    return m_translation.getY();
+  }
+
+  /**
+   * Returns the Z component of the pose's translation.
+   *
+   * @return The z component of the pose's translation.
+   */
+  public double getZ() {
+    return m_translation.getZ();
+  }
+
+  /**
+   * Returns the rotational component of the transformation.
+   *
+   * @return The rotational component of the pose.
+   */
+  @JsonProperty
+  public Rotation3d getRotation() {
+    return m_rotation;
+  }
+
+  /**
+   * Multiplies the current pose by a scalar.
+   *
+   * @param scalar The scalar.
+   * @return The new scaled Pose3d.
+   */
+  public Pose3d times(double scalar) {
+    return new Pose3d(m_translation.times(scalar), m_rotation.times(scalar));
+  }
+
+  /**
+   * Divides the current pose by a scalar.
+   *
+   * @param scalar The scalar.
+   * @return The new scaled Pose3d.
+   */
+  public Pose3d div(double scalar) {
+    return times(1.0 / scalar);
+  }
+
+  /**
+   * Transforms the pose by the given transformation and returns the new pose. See + operator for
+   * the matrix multiplication performed.
+   *
+   * @param other The transform to transform the pose by.
+   * @return The transformed pose.
+   */
+  public Pose3d transformBy(Transform3d other) {
+    return new Pose3d(
+        m_translation.plus(other.getTranslation().rotateBy(m_rotation)),
+        other.getRotation().plus(m_rotation));
+  }
+
+  /**
+   * Returns the current pose relative to the given pose.
+   *
+   * <p>This function can often be used for trajectory tracking or pose stabilization algorithms to
+   * get the error between the reference and the current pose.
+   *
+   * @param other The pose that is the origin of the new coordinate frame that the current pose will
+   *     be converted into.
+   * @return The current pose relative to the new origin pose.
+   */
+  public Pose3d relativeTo(Pose3d other) {
+    var transform = new Transform3d(other, this);
+    return new Pose3d(transform.getTranslation(), transform.getRotation());
+  }
+
+  /**
+   * Obtain a new Pose3d from a (constant curvature) velocity.
+   *
+   * <p>The twist is a change in pose in the robot's coordinate frame since the previous pose
+   * update. When the user runs exp() on the previous known field-relative pose with the argument
+   * being the twist, the user will receive the new field-relative pose.
+   *
+   * <p>"Exp" represents the pose exponential, which is solving a differential equation moving the
+   * pose forward in time.
+   *
+   * @param twist The change in pose in the robot's coordinate frame since the previous pose update.
+   *     For example, if a non-holonomic robot moves forward 0.01 meters and changes angle by 0.5
+   *     degrees since the previous pose update, the twist would be Twist3d(0.01, 0.0, 0.0, new new
+   *     Rotation3d(0.0, 0.0, Units.degreesToRadians(0.5))).
+   * @return The new pose of the robot.
+   */
+  public Pose3d exp(Twist3d twist) {
+    final var Omega = rotationVectorToMatrix(VecBuilder.fill(twist.rx, twist.ry, twist.rz));
+    final var OmegaSq = Omega.times(Omega);
+
+    double thetaSq = twist.rx * twist.rx + twist.ry * twist.ry + twist.rz * twist.rz;
+
+    // Get left Jacobian of SO3. See first line in right column of
+    // http://asrl.utias.utoronto.ca/~tdb/bib/barfoot_ser17_identities.pdf
+    Matrix<N3, N3> J;
+    if (thetaSq < 1E-9 * 1E-9) {
+      // J = I + 0.5ω
+      J = Matrix.eye(Nat.N3()).plus(Omega.times(0.5));
+    } else {
+      double theta = Math.sqrt(thetaSq);
+      // J = I + (1 − cos(θ))/θ² ω + (θ − sin(θ))/θ³ ω²
+      J =
+          Matrix.eye(Nat.N3())
+              .plus(Omega.times((1.0 - Math.cos(theta)) / thetaSq))
+              .plus(OmegaSq.times((theta - Math.sin(theta)) / (thetaSq * theta)));
+    }
+
+    // Get translation component
+    final var translation =
+        J.times(new MatBuilder<>(Nat.N3(), Nat.N1()).fill(twist.dx, twist.dy, twist.dz));
+
+    final var transform =
+        new Transform3d(
+            new Translation3d(translation.get(0, 0), translation.get(1, 0), translation.get(2, 0)),
+            new Rotation3d(twist.rx, twist.ry, twist.rz));
+
+    return this.plus(transform);
+  }
+
+  /**
+   * Returns a Twist3d that maps this pose to the end pose. If c is the output of {@code a.Log(b)},
+   * then {@code a.Exp(c)} would yield b.
+   *
+   * @param end The end pose for the transformation.
+   * @return The twist that maps this to end.
+   */
+  public Twist3d log(Pose3d end) {
+    final var transform = end.relativeTo(this);
+
+    final var rotVec = transform.getRotation().getQuaternion().toRotationVector();
+
+    final var Omega = rotationVectorToMatrix(rotVec);
+    final var OmegaSq = Omega.times(Omega);
+
+    double thetaSq =
+        rotVec.get(0, 0) * rotVec.get(0, 0)
+            + rotVec.get(1, 0) * rotVec.get(1, 0)
+            + rotVec.get(2, 0) * rotVec.get(2, 0);
+
+    // Get left Jacobian inverse of SO3. See fourth line in right column of
+    // http://asrl.utias.utoronto.ca/~tdb/bib/barfoot_ser17_identities.pdf
+    Matrix<N3, N3> Jinv;
+    if (thetaSq < 1E-9 * 1E-9) {
+      // J⁻¹ = I − 0.5ω + 1/12 ω²
+      Jinv = Matrix.eye(Nat.N3()).minus(Omega.times(0.5)).plus(OmegaSq.times(1.0 / 12.0));
+    } else {
+      double theta = Math.sqrt(thetaSq);
+      double halfTheta = 0.5 * theta;
+
+      // J⁻¹ = I − 0.5ω + (1 − 0.5θ cos(θ/2) / sin(θ/2))/θ² ω²
+      Jinv =
+          Matrix.eye(Nat.N3())
+              .minus(Omega.times(0.5))
+              .plus(
+                  OmegaSq.times(
+                      (1.0 - 0.5 * theta * Math.cos(halfTheta) / Math.sin(halfTheta)) / thetaSq));
+    }
+
+    // Get dtranslation component
+    final var dtranslation =
+        Jinv.times(
+            new MatBuilder<>(Nat.N3(), Nat.N1())
+                .fill(transform.getX(), transform.getY(), transform.getZ()));
+
+    return new Twist3d(
+        dtranslation.get(0, 0),
+        dtranslation.get(1, 0),
+        dtranslation.get(2, 0),
+        rotVec.get(0, 0),
+        rotVec.get(1, 0),
+        rotVec.get(2, 0));
+  }
+
+  /**
+   * Returns a Pose2d representing this Pose3d projected into the X-Y plane.
+   *
+   * @return A Pose2d representing this Pose3d projected into the X-Y plane.
+   */
+  public Pose2d toPose2d() {
+    return new Pose2d(m_translation.toTranslation2d(), m_rotation.toRotation2d());
+  }
+
+  @Override
+  public String toString() {
+    return String.format("Pose3d(%s, %s)", m_translation, m_rotation);
+  }
+
+  /**
+   * Checks equality between this Pose3d and another object.
+   *
+   * @param obj The other object.
+   * @return Whether the two objects are equal or not.
+   */
+  @Override
+  public boolean equals(Object obj) {
+    if (obj instanceof Pose3d) {
+      return ((Pose3d) obj).m_translation.equals(m_translation)
+          && ((Pose3d) obj).m_rotation.equals(m_rotation);
+    }
+    return false;
+  }
+
+  @Override
+  public int hashCode() {
+    return Objects.hash(m_translation, m_rotation);
+  }
+
+  @Override
+  public Pose3d interpolate(Pose3d endValue, double t) {
+    if (t < 0) {
+      return this;
+    } else if (t >= 1) {
+      return endValue;
+    } else {
+      var twist = this.log(endValue);
+      var scaledTwist =
+          new Twist3d(
+              twist.dx * t, twist.dy * t, twist.dz * t, twist.rx * t, twist.ry * t, twist.rz * t);
+      return this.exp(scaledTwist);
+    }
+  }
+
+  /**
+   * Applies the hat operator to a rotation vector.
+   *
+   * <p>It takes a rotation vector and returns the corresponding matrix representation of the Lie
+   * algebra element (a 3x3 rotation matrix).
+   *
+   * @param rotation The rotation vector.
+   * @return The rotation vector as a 3x3 rotation matrix.
+   */
+  private Matrix<N3, N3> rotationVectorToMatrix(Vector<N3> rotation) {
+    // Given a rotation vector <a, b, c>,
+    //         [ 0 -c  b]
+    // Omega = [ c  0 -a]
+    //         [-b  a  0]
+    return new MatBuilder<>(Nat.N3(), Nat.N3())
+        .fill(
+            0.0,
+            -rotation.get(2, 0),
+            rotation.get(1, 0),
+            rotation.get(2, 0),
+            0.0,
+            -rotation.get(0, 0),
+            -rotation.get(1, 0),
+            rotation.get(0, 0),
+            0.0);
+  }
+}
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/Quaternion.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/Quaternion.java
new file mode 100644
index 0000000..cadfaa4
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/Quaternion.java
@@ -0,0 +1,186 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.math.geometry;
+
+import com.fasterxml.jackson.annotation.JsonAutoDetect;
+import com.fasterxml.jackson.annotation.JsonCreator;
+import com.fasterxml.jackson.annotation.JsonIgnoreProperties;
+import com.fasterxml.jackson.annotation.JsonProperty;
+import edu.wpi.first.math.VecBuilder;
+import edu.wpi.first.math.Vector;
+import edu.wpi.first.math.numbers.N3;
+import java.util.Objects;
+
+@JsonIgnoreProperties(ignoreUnknown = true)
+@JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE)
+public class Quaternion {
+  private final double m_r;
+  private final Vector<N3> m_v;
+
+  /** Constructs a quaternion with a default angle of 0 degrees. */
+  public Quaternion() {
+    m_r = 1.0;
+    m_v = VecBuilder.fill(0.0, 0.0, 0.0);
+  }
+
+  /**
+   * Constructs a quaternion with the given components.
+   *
+   * @param w W component of the quaternion.
+   * @param x X component of the quaternion.
+   * @param y Y component of the quaternion.
+   * @param z Z component of the quaternion.
+   */
+  @JsonCreator
+  public Quaternion(
+      @JsonProperty(required = true, value = "W") double w,
+      @JsonProperty(required = true, value = "X") double x,
+      @JsonProperty(required = true, value = "Y") double y,
+      @JsonProperty(required = true, value = "Z") double z) {
+    m_r = w;
+    m_v = VecBuilder.fill(x, y, z);
+  }
+
+  /**
+   * Multiply with another quaternion.
+   *
+   * @param other The other quaternion.
+   * @return The quaternion product.
+   */
+  public Quaternion times(Quaternion other) {
+    // https://en.wikipedia.org/wiki/Quaternion#Scalar_and_vector_parts
+    final var r1 = m_r;
+    final var v1 = m_v;
+    final var r2 = other.m_r;
+    final var v2 = other.m_v;
+
+    // v₁ x v₂
+    var cross =
+        VecBuilder.fill(
+            v1.get(1, 0) * v2.get(2, 0) - v2.get(1, 0) * v1.get(2, 0),
+            v2.get(0, 0) * v1.get(2, 0) - v1.get(0, 0) * v2.get(2, 0),
+            v1.get(0, 0) * v2.get(1, 0) - v2.get(0, 0) * v1.get(1, 0));
+
+    // v = r₁v₂ + r₂v₁ + v₁ x v₂
+    final var v = v2.times(r1).plus(v1.times(r2)).plus(cross);
+
+    return new Quaternion(r1 * r2 - v1.dot(v2), v.get(0, 0), v.get(1, 0), v.get(2, 0));
+  }
+
+  @Override
+  public String toString() {
+    return String.format(
+        "Quaternion(%s, %s, %s, %s)", m_r, m_v.get(0, 0), m_v.get(1, 0), m_v.get(2, 0));
+  }
+
+  /**
+   * Checks equality between this Quaternion and another object.
+   *
+   * @param obj The other object.
+   * @return Whether the two objects are equal or not.
+   */
+  @Override
+  public boolean equals(Object obj) {
+    if (obj instanceof Quaternion) {
+      var other = (Quaternion) obj;
+
+      return Math.abs(m_r * other.m_r + m_v.dot(other.m_v)) > 1.0 - 1E-9;
+    }
+    return false;
+  }
+
+  @Override
+  public int hashCode() {
+    return Objects.hash(m_r, m_v);
+  }
+
+  /**
+   * Returns the inverse of the quaternion.
+   *
+   * @return The inverse quaternion.
+   */
+  public Quaternion inverse() {
+    return new Quaternion(m_r, -m_v.get(0, 0), -m_v.get(1, 0), -m_v.get(2, 0));
+  }
+
+  /**
+   * Normalizes the quaternion.
+   *
+   * @return The normalized quaternion.
+   */
+  public Quaternion normalize() {
+    double norm = Math.sqrt(getW() * getW() + getX() * getX() + getY() * getY() + getZ() * getZ());
+    if (norm == 0.0) {
+      return new Quaternion();
+    } else {
+      return new Quaternion(getW() / norm, getX() / norm, getY() / norm, getZ() / norm);
+    }
+  }
+
+  /**
+   * Returns W component of the quaternion.
+   *
+   * @return W component of the quaternion.
+   */
+  @JsonProperty(value = "W")
+  public double getW() {
+    return m_r;
+  }
+
+  /**
+   * Returns X component of the quaternion.
+   *
+   * @return X component of the quaternion.
+   */
+  @JsonProperty(value = "X")
+  public double getX() {
+    return m_v.get(0, 0);
+  }
+
+  /**
+   * Returns Y component of the quaternion.
+   *
+   * @return Y component of the quaternion.
+   */
+  @JsonProperty(value = "Y")
+  public double getY() {
+    return m_v.get(1, 0);
+  }
+
+  /**
+   * Returns Z component of the quaternion.
+   *
+   * @return Z component of the quaternion.
+   */
+  @JsonProperty(value = "Z")
+  public double getZ() {
+    return m_v.get(2, 0);
+  }
+
+  /**
+   * Returns the rotation vector representation of this quaternion.
+   *
+   * <p>This is also the log operator of SO(3).
+   *
+   * @return The rotation vector representation of this quaternion.
+   */
+  public Vector<N3> toRotationVector() {
+    // See equation (31) in "Integrating Generic Sensor Fusion Algorithms with
+    // Sound State Representation through Encapsulation of Manifolds"
+    //
+    // https://arxiv.org/pdf/1107.1119.pdf
+    double norm = m_v.norm();
+
+    if (norm < 1e-9) {
+      return m_v.times(2.0 / getW() - 2.0 / 3.0 * norm * norm / (getW() * getW() * getW()));
+    } else {
+      if (getW() < 0.0) {
+        return m_v.times(2.0 * Math.atan2(-norm, -getW()) / norm);
+      } else {
+        return m_v.times(2.0 * Math.atan2(norm, getW()) / norm);
+      }
+    }
+  }
+}
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/Rotation2d.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/Rotation2d.java
index 08e5438..5be6156 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/Rotation2d.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/Rotation2d.java
@@ -10,9 +10,16 @@
 import com.fasterxml.jackson.annotation.JsonProperty;
 import edu.wpi.first.math.MathUtil;
 import edu.wpi.first.math.interpolation.Interpolatable;
+import edu.wpi.first.math.util.Units;
 import java.util.Objects;
 
-/** A rotation in a 2d coordinate frame represented a point on the unit circle (cosine and sine). */
+/**
+ * A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
+ *
+ * <p>The angle is continuous, that is if a Rotation2d is constructed with 361 degrees, it will
+ * return 361 degrees. This allows algorithms that wouldn't want to see a discontinuity in the
+ * rotations as it sweeps past from 360 to 0 on the second time around.
+ */
 @JsonIgnoreProperties(ignoreUnknown = true)
 @JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE)
 public class Rotation2d implements Interpolatable<Rotation2d> {
@@ -28,7 +35,7 @@
   }
 
   /**
-   * Constructs a Rotation2d with the given radian value. The x and y don't have to be normalized.
+   * Constructs a Rotation2d with the given radian value.
    *
    * @param value The value of the angle in radians.
    */
@@ -58,6 +65,16 @@
   }
 
   /**
+   * Constructs and returns a Rotation2d with the given radian value.
+   *
+   * @param radians The value of the angle in radians.
+   * @return The rotation object with the desired angle value.
+   */
+  public static Rotation2d fromRadians(double radians) {
+    return new Rotation2d(radians);
+  }
+
+  /**
    * Constructs and returns a Rotation2d with the given degree value.
    *
    * @param degrees The value of the angle in degrees.
@@ -68,9 +85,20 @@
   }
 
   /**
+   * Constructs and returns a Rotation2d with the given number of rotations.
+   *
+   * @param rotations The value of the angle in rotations.
+   * @return The rotation object with the desired angle value.
+   */
+  public static Rotation2d fromRotations(double rotations) {
+    return new Rotation2d(Units.rotationsToRadians(rotations));
+  }
+
+  /**
    * Adds two rotations together, with the result being bounded between -pi and pi.
    *
-   * <p>For example, Rotation2d.fromDegrees(30) + Rotation2d.fromDegrees(60) = Rotation2d{-pi/2}
+   * <p>For example, <code>Rotation2d.fromDegrees(30).plus(Rotation2d.fromDegrees(60))</code> equals
+   * <code>Rotation2d(Math.PI/2.0)</code>
    *
    * @param other The rotation to add.
    * @return The sum of the two rotations.
@@ -82,7 +110,8 @@
   /**
    * Subtracts the new rotation from the current rotation and returns the new rotation.
    *
-   * <p>For example, Rotation2d.fromDegrees(10) - Rotation2d.fromDegrees(100) = Rotation2d{-pi/2}
+   * <p>For example, <code>Rotation2d.fromDegrees(10).minus(Rotation2d.fromDegrees(100))</code>
+   * equals <code>Rotation2d(-Math.PI/2.0)</code>
    *
    * @param other The rotation to subtract.
    * @return The difference between the two rotations.
@@ -112,6 +141,16 @@
   }
 
   /**
+   * Divides the current rotation by a scalar.
+   *
+   * @param scalar The scalar.
+   * @return The new scaled Rotation2d.
+   */
+  public Rotation2d div(double scalar) {
+    return times(1.0 / scalar);
+  }
+
+  /**
    * Adds the new rotation to the current rotation using a rotation matrix.
    *
    * <p>The matrix multiplication is as follows:
@@ -131,9 +170,10 @@
   }
 
   /**
-   * Returns the radian value of the rotation.
+   * Returns the radian value of the Rotation2d.
    *
-   * @return The radian value of the rotation.
+   * @return The radian value of the Rotation2d.
+   * @see edu.wpi.first.math.MathUtil#angleModulus(double) to constrain the angle within (-pi, pi]
    */
   @JsonProperty
   public double getRadians() {
@@ -141,36 +181,47 @@
   }
 
   /**
-   * Returns the degree value of the rotation.
+   * Returns the degree value of the Rotation2d.
    *
-   * @return The degree value of the rotation.
+   * @return The degree value of the Rotation2d.
+   * @see edu.wpi.first.math.MathUtil#inputModulus(double, double, double) to constrain the angle
+   *     within (-180, 180]
    */
   public double getDegrees() {
     return Math.toDegrees(m_value);
   }
 
   /**
-   * Returns the cosine of the rotation.
+   * Returns the number of rotations of the Rotation2d.
    *
-   * @return The cosine of the rotation.
+   * @return The number of rotations of the Rotation2d.
+   */
+  public double getRotations() {
+    return Units.radiansToRotations(m_value);
+  }
+
+  /**
+   * Returns the cosine of the Rotation2d.
+   *
+   * @return The cosine of the Rotation2d.
    */
   public double getCos() {
     return m_cos;
   }
 
   /**
-   * Returns the sine of the rotation.
+   * Returns the sine of the Rotation2d.
    *
-   * @return The sine of the rotation.
+   * @return The sine of the Rotation2d.
    */
   public double getSin() {
     return m_sin;
   }
 
   /**
-   * Returns the tangent of the rotation.
+   * Returns the tangent of the Rotation2d.
    *
-   * @return The tangent of the rotation.
+   * @return The tangent of the Rotation2d.
    */
   public double getTan() {
     return m_sin / m_cos;
@@ -202,8 +253,7 @@
   }
 
   @Override
-  @SuppressWarnings("ParameterName")
   public Rotation2d interpolate(Rotation2d endValue, double t) {
-    return new Rotation2d(MathUtil.interpolate(this.getRadians(), endValue.getRadians(), t));
+    return plus(endValue.minus(this).times(MathUtil.clamp(t, 0, 1)));
   }
 }
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/Rotation3d.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/Rotation3d.java
new file mode 100644
index 0000000..3226e31
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/Rotation3d.java
@@ -0,0 +1,403 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.math.geometry;
+
+import com.fasterxml.jackson.annotation.JsonAutoDetect;
+import com.fasterxml.jackson.annotation.JsonCreator;
+import com.fasterxml.jackson.annotation.JsonIgnoreProperties;
+import com.fasterxml.jackson.annotation.JsonProperty;
+import edu.wpi.first.math.MatBuilder;
+import edu.wpi.first.math.MathSharedStore;
+import edu.wpi.first.math.MathUtil;
+import edu.wpi.first.math.Matrix;
+import edu.wpi.first.math.Nat;
+import edu.wpi.first.math.VecBuilder;
+import edu.wpi.first.math.Vector;
+import edu.wpi.first.math.interpolation.Interpolatable;
+import edu.wpi.first.math.numbers.N3;
+import java.util.Objects;
+import org.ejml.dense.row.factory.DecompositionFactory_DDRM;
+
+/** A rotation in a 3D coordinate frame represented by a quaternion. */
+@JsonIgnoreProperties(ignoreUnknown = true)
+@JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE)
+public class Rotation3d implements Interpolatable<Rotation3d> {
+  private Quaternion m_q = new Quaternion();
+
+  /** Constructs a Rotation3d with a default angle of 0 degrees. */
+  public Rotation3d() {}
+
+  /**
+   * Constructs a Rotation3d from a quaternion.
+   *
+   * @param q The quaternion.
+   */
+  @JsonCreator
+  public Rotation3d(@JsonProperty(required = true, value = "quaternion") Quaternion q) {
+    m_q = q.normalize();
+  }
+
+  /**
+   * Constructs a Rotation3d from extrinsic roll, pitch, and yaw.
+   *
+   * <p>Extrinsic rotations occur in that order around the axes in the fixed global frame rather
+   * than the body frame.
+   *
+   * <p>Angles are measured counterclockwise with the rotation axis pointing "out of the page". If
+   * you point your right thumb along the positive axis direction, your fingers curl in the
+   * direction of positive rotation.
+   *
+   * @param roll The counterclockwise rotation angle around the X axis (roll) in radians.
+   * @param pitch The counterclockwise rotation angle around the Y axis (pitch) in radians.
+   * @param yaw The counterclockwise rotation angle around the Z axis (yaw) in radians.
+   */
+  public Rotation3d(double roll, double pitch, double yaw) {
+    // https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles#Euler_angles_to_quaternion_conversion
+    double cr = Math.cos(roll * 0.5);
+    double sr = Math.sin(roll * 0.5);
+
+    double cp = Math.cos(pitch * 0.5);
+    double sp = Math.sin(pitch * 0.5);
+
+    double cy = Math.cos(yaw * 0.5);
+    double sy = Math.sin(yaw * 0.5);
+
+    m_q =
+        new Quaternion(
+            cr * cp * cy + sr * sp * sy,
+            sr * cp * cy - cr * sp * sy,
+            cr * sp * cy + sr * cp * sy,
+            cr * cp * sy - sr * sp * cy);
+  }
+
+  /**
+   * Constructs a Rotation3d with the given axis-angle representation. The axis doesn't have to be
+   * normalized.
+   *
+   * @param axis The rotation axis.
+   * @param angleRadians The rotation around the axis in radians.
+   */
+  public Rotation3d(Vector<N3> axis, double angleRadians) {
+    double norm = axis.norm();
+    if (norm == 0.0) {
+      return;
+    }
+
+    // https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles#Definition
+    var v = axis.times(1.0 / norm).times(Math.sin(angleRadians / 2.0));
+    m_q = new Quaternion(Math.cos(angleRadians / 2.0), v.get(0, 0), v.get(1, 0), v.get(2, 0));
+  }
+
+  /**
+   * Constructs a Rotation3d from a rotation matrix.
+   *
+   * @param rotationMatrix The rotation matrix.
+   * @throws IllegalArgumentException if the rotation matrix isn't special orthogonal.
+   */
+  public Rotation3d(Matrix<N3, N3> rotationMatrix) {
+    final var R = rotationMatrix;
+
+    // Require that the rotation matrix is special orthogonal. This is true if
+    // the matrix is orthogonal (RRᵀ = I) and normalized (determinant is 1).
+    if (R.times(R.transpose()).minus(Matrix.eye(Nat.N3())).normF() > 1e-9) {
+      var builder = new StringBuilder("Rotation matrix isn't orthogonal\n\nR =\n");
+      builder.append(R.getStorage().toString()).append('\n');
+
+      var msg = builder.toString();
+      MathSharedStore.reportError(msg, Thread.currentThread().getStackTrace());
+      throw new IllegalArgumentException(msg);
+    }
+    if (Math.abs(R.det() - 1.0) > 1e-9) {
+      var builder =
+          new StringBuilder("Rotation matrix is orthogonal but not special orthogonal\n\nR =\n");
+      builder.append(R.getStorage().toString()).append('\n');
+
+      var msg = builder.toString();
+      MathSharedStore.reportError(msg, Thread.currentThread().getStackTrace());
+      throw new IllegalArgumentException(msg);
+    }
+
+    // Turn rotation matrix into a quaternion
+    // https://www.euclideanspace.com/maths/geometry/rotations/conversions/matrixToQuaternion/
+    double trace = R.get(0, 0) + R.get(1, 1) + R.get(2, 2);
+    double w;
+    double x;
+    double y;
+    double z;
+
+    if (trace > 0.0) {
+      double s = 0.5 / Math.sqrt(trace + 1.0);
+      w = 0.25 / s;
+      x = (R.get(2, 1) - R.get(1, 2)) * s;
+      y = (R.get(0, 2) - R.get(2, 0)) * s;
+      z = (R.get(1, 0) - R.get(0, 1)) * s;
+    } else {
+      if (R.get(0, 0) > R.get(1, 1) && R.get(0, 0) > R.get(2, 2)) {
+        double s = 2.0 * Math.sqrt(1.0 + R.get(0, 0) - R.get(1, 1) - R.get(2, 2));
+        w = (R.get(2, 1) - R.get(1, 2)) / s;
+        x = 0.25 * s;
+        y = (R.get(0, 1) + R.get(1, 0)) / s;
+        z = (R.get(0, 2) + R.get(2, 0)) / s;
+      } else if (R.get(1, 1) > R.get(2, 2)) {
+        double s = 2.0 * Math.sqrt(1.0 + R.get(1, 1) - R.get(0, 0) - R.get(2, 2));
+        w = (R.get(0, 2) - R.get(2, 0)) / s;
+        x = (R.get(0, 1) + R.get(1, 0)) / s;
+        y = 0.25 * s;
+        z = (R.get(1, 2) + R.get(2, 1)) / s;
+      } else {
+        double s = 2.0 * Math.sqrt(1.0 + R.get(2, 2) - R.get(0, 0) - R.get(1, 1));
+        w = (R.get(1, 0) - R.get(0, 1)) / s;
+        x = (R.get(0, 2) + R.get(2, 0)) / s;
+        y = (R.get(1, 2) + R.get(2, 1)) / s;
+        z = 0.25 * s;
+      }
+    }
+
+    m_q = new Quaternion(w, x, y, z);
+  }
+
+  /**
+   * Constructs a Rotation3d that rotates the initial vector onto the final vector.
+   *
+   * <p>This is useful for turning a 3D vector (final) into an orientation relative to a coordinate
+   * system vector (initial).
+   *
+   * @param initial The initial vector.
+   * @param last The final vector.
+   */
+  public Rotation3d(Vector<N3> initial, Vector<N3> last) {
+    double dot = initial.dot(last);
+    double normProduct = initial.norm() * last.norm();
+    double dotNorm = dot / normProduct;
+
+    if (dotNorm > 1.0 - 1E-9) {
+      // If the dot product is 1, the two vectors point in the same direction so
+      // there's no rotation. The default initialization of m_q will work.
+      return;
+    } else if (dotNorm < -1.0 + 1E-9) {
+      // If the dot product is -1, the two vectors point in opposite directions
+      // so a 180 degree rotation is required. Any orthogonal vector can be used
+      // for it. Q in the QR decomposition is an orthonormal basis, so it
+      // contains orthogonal unit vectors.
+      var X =
+          new MatBuilder<>(Nat.N3(), Nat.N1())
+              .fill(initial.get(0, 0), initial.get(1, 0), initial.get(2, 0));
+      final var qr = DecompositionFactory_DDRM.qr(3, 1);
+      qr.decompose(X.getStorage().getMatrix());
+      final var Q = qr.getQ(null, false);
+
+      // w = cos(θ/2) = cos(90°) = 0
+      //
+      // For x, y, and z, we use the second column of Q because the first is
+      // parallel instead of orthogonal. The third column would also work.
+      m_q = new Quaternion(0.0, Q.get(0, 1), Q.get(1, 1), Q.get(2, 1));
+    } else {
+      // initial x last
+      var axis =
+          VecBuilder.fill(
+              initial.get(1, 0) * last.get(2, 0) - last.get(1, 0) * initial.get(2, 0),
+              last.get(0, 0) * initial.get(2, 0) - initial.get(0, 0) * last.get(2, 0),
+              initial.get(0, 0) * last.get(1, 0) - last.get(0, 0) * initial.get(1, 0));
+
+      // https://stackoverflow.com/a/11741520
+      m_q =
+          new Quaternion(normProduct + dot, axis.get(0, 0), axis.get(1, 0), axis.get(2, 0))
+              .normalize();
+    }
+  }
+
+  /**
+   * Adds two rotations together.
+   *
+   * @param other The rotation to add.
+   * @return The sum of the two rotations.
+   */
+  public Rotation3d plus(Rotation3d other) {
+    return rotateBy(other);
+  }
+
+  /**
+   * Subtracts the new rotation from the current rotation and returns the new rotation.
+   *
+   * @param other The rotation to subtract.
+   * @return The difference between the two rotations.
+   */
+  public Rotation3d minus(Rotation3d other) {
+    return rotateBy(other.unaryMinus());
+  }
+
+  /**
+   * Takes the inverse of the current rotation.
+   *
+   * @return The inverse of the current rotation.
+   */
+  public Rotation3d unaryMinus() {
+    return new Rotation3d(m_q.inverse());
+  }
+
+  /**
+   * Multiplies the current rotation by a scalar.
+   *
+   * @param scalar The scalar.
+   * @return The new scaled Rotation3d.
+   */
+  public Rotation3d times(double scalar) {
+    // https://en.wikipedia.org/wiki/Slerp#Quaternion_Slerp
+    if (m_q.getW() >= 0.0) {
+      return new Rotation3d(
+          VecBuilder.fill(m_q.getX(), m_q.getY(), m_q.getZ()),
+          2.0 * scalar * Math.acos(m_q.getW()));
+    } else {
+      return new Rotation3d(
+          VecBuilder.fill(-m_q.getX(), -m_q.getY(), -m_q.getZ()),
+          2.0 * scalar * Math.acos(-m_q.getW()));
+    }
+  }
+
+  /**
+   * Divides the current rotation by a scalar.
+   *
+   * @param scalar The scalar.
+   * @return The new scaled Rotation3d.
+   */
+  public Rotation3d div(double scalar) {
+    return times(1.0 / scalar);
+  }
+
+  /**
+   * Adds the new rotation to the current rotation.
+   *
+   * @param other The rotation to rotate by.
+   * @return The new rotated Rotation3d.
+   */
+  public Rotation3d rotateBy(Rotation3d other) {
+    return new Rotation3d(other.m_q.times(m_q));
+  }
+
+  /**
+   * Returns the quaternion representation of the Rotation3d.
+   *
+   * @return The quaternion representation of the Rotation3d.
+   */
+  @JsonProperty(value = "quaternion")
+  public Quaternion getQuaternion() {
+    return m_q;
+  }
+
+  /**
+   * Returns the counterclockwise rotation angle around the X axis (roll) in radians.
+   *
+   * @return The counterclockwise rotation angle around the X axis (roll) in radians.
+   */
+  public double getX() {
+    final var w = m_q.getW();
+    final var x = m_q.getX();
+    final var y = m_q.getY();
+    final var z = m_q.getZ();
+
+    // https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles#Quaternion_to_Euler_angles_conversion
+    return Math.atan2(2.0 * (w * x + y * z), 1.0 - 2.0 * (x * x + y * y));
+  }
+
+  /**
+   * Returns the counterclockwise rotation angle around the Y axis (pitch) in radians.
+   *
+   * @return The counterclockwise rotation angle around the Y axis (pitch) in radians.
+   */
+  public double getY() {
+    final var w = m_q.getW();
+    final var x = m_q.getX();
+    final var y = m_q.getY();
+    final var z = m_q.getZ();
+
+    // https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles#Quaternion_to_Euler_angles_conversion
+    double ratio = 2.0 * (w * y - z * x);
+    if (Math.abs(ratio) >= 1.0) {
+      return Math.copySign(Math.PI / 2.0, ratio);
+    } else {
+      return Math.asin(ratio);
+    }
+  }
+
+  /**
+   * Returns the counterclockwise rotation angle around the Z axis (yaw) in radians.
+   *
+   * @return The counterclockwise rotation angle around the Z axis (yaw) in radians.
+   */
+  public double getZ() {
+    final var w = m_q.getW();
+    final var x = m_q.getX();
+    final var y = m_q.getY();
+    final var z = m_q.getZ();
+
+    // https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles#Quaternion_to_Euler_angles_conversion
+    return Math.atan2(2.0 * (w * z + x * y), 1.0 - 2.0 * (y * y + z * z));
+  }
+
+  /**
+   * Returns the axis in the axis-angle representation of this rotation.
+   *
+   * @return The axis in the axis-angle representation.
+   */
+  public Vector<N3> getAxis() {
+    double norm =
+        Math.sqrt(m_q.getX() * m_q.getX() + m_q.getY() * m_q.getY() + m_q.getZ() * m_q.getZ());
+    if (norm == 0.0) {
+      return VecBuilder.fill(0.0, 0.0, 0.0);
+    } else {
+      return VecBuilder.fill(m_q.getX() / norm, m_q.getY() / norm, m_q.getZ() / norm);
+    }
+  }
+
+  /**
+   * Returns the angle in radians in the axis-angle representation of this rotation.
+   *
+   * @return The angle in radians in the axis-angle representation of this rotation.
+   */
+  public double getAngle() {
+    double norm =
+        Math.sqrt(m_q.getX() * m_q.getX() + m_q.getY() * m_q.getY() + m_q.getZ() * m_q.getZ());
+    return 2.0 * Math.atan2(norm, m_q.getW());
+  }
+
+  /**
+   * Returns a Rotation2d representing this Rotation3d projected into the X-Y plane.
+   *
+   * @return A Rotation2d representing this Rotation3d projected into the X-Y plane.
+   */
+  public Rotation2d toRotation2d() {
+    return new Rotation2d(getZ());
+  }
+
+  @Override
+  public String toString() {
+    return String.format("Rotation3d(%s)", m_q);
+  }
+
+  /**
+   * Checks equality between this Rotation3d and another object.
+   *
+   * @param obj The other object.
+   * @return Whether the two objects are equal or not.
+   */
+  @Override
+  public boolean equals(Object obj) {
+    if (obj instanceof Rotation3d) {
+      var other = (Rotation3d) obj;
+      return m_q.equals(other.m_q);
+    }
+    return false;
+  }
+
+  @Override
+  public int hashCode() {
+    return Objects.hash(m_q);
+  }
+
+  @Override
+  public Rotation3d interpolate(Rotation3d endValue, double t) {
+    return plus(endValue.minus(this).times(MathUtil.clamp(t, 0, 1)));
+  }
+}
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/Transform2d.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/Transform2d.java
index dd35670..c3c6b0c 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/Transform2d.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/Transform2d.java
@@ -47,7 +47,7 @@
   }
 
   /**
-   * Scales the transform by the scalar.
+   * Multiplies the transform by the scalar.
    *
    * @param scalar The scalar.
    * @return The scaled Transform2d.
@@ -57,6 +57,16 @@
   }
 
   /**
+   * Divides the transform by the scalar.
+   *
+   * @param scalar The scalar.
+   * @return The scaled Transform2d.
+   */
+  public Transform2d div(double scalar) {
+    return times(1.0 / scalar);
+  }
+
+  /**
    * Composes two transformations.
    *
    * @param other The transform to compose with this one.
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/Transform3d.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/Transform3d.java
new file mode 100644
index 0000000..4920ef6
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/Transform3d.java
@@ -0,0 +1,162 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.math.geometry;
+
+import java.util.Objects;
+
+/** Represents a transformation for a Pose3d. */
+public class Transform3d {
+  private final Translation3d m_translation;
+  private final Rotation3d m_rotation;
+
+  /**
+   * Constructs the transform that maps the initial pose to the final pose.
+   *
+   * @param initial The initial pose for the transformation.
+   * @param last The final pose for the transformation.
+   */
+  public Transform3d(Pose3d initial, Pose3d last) {
+    // We are rotating the difference between the translations
+    // using a clockwise rotation matrix. This transforms the global
+    // delta into a local delta (relative to the initial pose).
+    m_translation =
+        last.getTranslation()
+            .minus(initial.getTranslation())
+            .rotateBy(initial.getRotation().unaryMinus());
+
+    m_rotation = last.getRotation().minus(initial.getRotation());
+  }
+
+  /**
+   * Constructs a transform with the given translation and rotation components.
+   *
+   * @param translation Translational component of the transform.
+   * @param rotation Rotational component of the transform.
+   */
+  public Transform3d(Translation3d translation, Rotation3d rotation) {
+    m_translation = translation;
+    m_rotation = rotation;
+  }
+
+  /** Constructs the identity transform -- maps an initial pose to itself. */
+  public Transform3d() {
+    m_translation = new Translation3d();
+    m_rotation = new Rotation3d();
+  }
+
+  /**
+   * Multiplies the transform by the scalar.
+   *
+   * @param scalar The scalar.
+   * @return The scaled Transform3d.
+   */
+  public Transform3d times(double scalar) {
+    return new Transform3d(m_translation.times(scalar), m_rotation.times(scalar));
+  }
+
+  /**
+   * Divides the transform by the scalar.
+   *
+   * @param scalar The scalar.
+   * @return The scaled Transform3d.
+   */
+  public Transform3d div(double scalar) {
+    return times(1.0 / scalar);
+  }
+
+  /**
+   * Composes two transformations.
+   *
+   * @param other The transform to compose with this one.
+   * @return The composition of the two transformations.
+   */
+  public Transform3d plus(Transform3d other) {
+    return new Transform3d(new Pose3d(), new Pose3d().transformBy(this).transformBy(other));
+  }
+
+  /**
+   * Returns the translation component of the transformation.
+   *
+   * @return The translational component of the transform.
+   */
+  public Translation3d getTranslation() {
+    return m_translation;
+  }
+
+  /**
+   * Returns the X component of the transformation's translation.
+   *
+   * @return The x component of the transformation's translation.
+   */
+  public double getX() {
+    return m_translation.getX();
+  }
+
+  /**
+   * Returns the Y component of the transformation's translation.
+   *
+   * @return The y component of the transformation's translation.
+   */
+  public double getY() {
+    return m_translation.getY();
+  }
+
+  /**
+   * Returns the Z component of the transformation's translation.
+   *
+   * @return The z component of the transformation's translation.
+   */
+  public double getZ() {
+    return m_translation.getZ();
+  }
+
+  /**
+   * Returns the rotational component of the transformation.
+   *
+   * @return Reference to the rotational component of the transform.
+   */
+  public Rotation3d getRotation() {
+    return m_rotation;
+  }
+
+  /**
+   * Invert the transformation. This is useful for undoing a transformation.
+   *
+   * @return The inverted transformation.
+   */
+  public Transform3d inverse() {
+    // We are rotating the difference between the translations
+    // using a clockwise rotation matrix. This transforms the global
+    // delta into a local delta (relative to the initial pose).
+    return new Transform3d(
+        getTranslation().unaryMinus().rotateBy(getRotation().unaryMinus()),
+        getRotation().unaryMinus());
+  }
+
+  @Override
+  public String toString() {
+    return String.format("Transform3d(%s, %s)", m_translation, m_rotation);
+  }
+
+  /**
+   * Checks equality between this Transform3d and another object.
+   *
+   * @param obj The other object.
+   * @return Whether the two objects are equal or not.
+   */
+  @Override
+  public boolean equals(Object obj) {
+    if (obj instanceof Transform3d) {
+      return ((Transform3d) obj).m_translation.equals(m_translation)
+          && ((Transform3d) obj).m_rotation.equals(m_rotation);
+    }
+    return false;
+  }
+
+  @Override
+  public int hashCode() {
+    return Objects.hash(m_translation, m_rotation);
+  }
+}
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/Translation2d.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/Translation2d.java
index 84eaea8..2d57edc 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/Translation2d.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/Translation2d.java
@@ -13,13 +13,11 @@
 import java.util.Objects;
 
 /**
- * Represents a translation in 2d space. This object can be used to represent a point or a vector.
+ * Represents a translation in 2D space. This object can be used to represent a point or a vector.
  *
- * <p>This assumes that you are using conventional mathematical axes. When the robot is placed on
- * the origin, facing toward the X direction, moving forward increases the X, whereas moving to the
- * left increases the Y.
+ * <p>This assumes that you are using conventional mathematical axes. When the robot is at the
+ * origin facing in the positive X direction, forward is positive X and left is positive Y.
  */
-@SuppressWarnings({"ParameterName", "MemberName"})
 @JsonIgnoreProperties(ignoreUnknown = true)
 @JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE)
 public class Translation2d implements Interpolatable<Translation2d> {
@@ -58,10 +56,9 @@
   }
 
   /**
-   * Calculates the distance between two translations in 2d space.
+   * Calculates the distance between two translations in 2D space.
    *
-   * <p>This function uses the pythagorean theorem to calculate the distance. distance = sqrt((x2 -
-   * x1)^2 + (y2 - y1)^2)
+   * <p>The distance between translations is defined as √((x₂−x₁)²+(y₂−y₁)²).
    *
    * @param other The translation to compute the distance to.
    * @return The distance between the two translations.
@@ -73,7 +70,7 @@
   /**
    * Returns the X component of the translation.
    *
-   * @return The x component of the translation.
+   * @return The X component of the translation.
    */
   @JsonProperty
   public double getX() {
@@ -83,7 +80,7 @@
   /**
    * Returns the Y component of the translation.
    *
-   * @return The y component of the translation.
+   * @return The Y component of the translation.
    */
   @JsonProperty
   public double getY() {
@@ -100,13 +97,27 @@
   }
 
   /**
-   * Applies a rotation to the translation in 2d space.
+   * Returns the angle this translation forms with the positive X axis.
+   *
+   * @return The angle of the translation
+   */
+  public Rotation2d getAngle() {
+    return new Rotation2d(m_x, m_y);
+  }
+
+  /**
+   * Applies a rotation to the translation in 2D space.
    *
    * <p>This multiplies the translation vector by a counterclockwise rotation matrix of the given
-   * angle. [x_new] [other.cos, -other.sin][x] [y_new] = [other.sin, other.cos][y]
+   * angle.
    *
-   * <p>For example, rotating a Translation2d of {2, 0} by 90 degrees will return a Translation2d of
-   * {0, 2}.
+   * <pre>
+   * [x_new]   [other.cos, -other.sin][x]
+   * [y_new] = [other.sin,  other.cos][y]
+   * </pre>
+   *
+   * <p>For example, rotating a Translation2d of &lt;2, 0&gt; by 90 degrees will return a
+   * Translation2d of &lt;0, 2&gt;.
    *
    * @param other The rotation to rotate the translation by.
    * @return The new rotated translation.
@@ -117,9 +128,9 @@
   }
 
   /**
-   * Adds two translations in 2d space and returns the sum. This is similar to vector addition.
+   * Returns the sum of two translations in 2D space.
    *
-   * <p>For example, Translation2d{1.0, 2.5} + Translation2d{2.0, 5.5} = Translation2d{3.0, 8.0}
+   * <p>For example, Translation3d(1.0, 2.5) + Translation3d(2.0, 5.5) = Translation3d{3.0, 8.0).
    *
    * @param other The translation to add.
    * @return The sum of the translations.
@@ -129,9 +140,9 @@
   }
 
   /**
-   * Subtracts the other translation from the other translation and returns the difference.
+   * Returns the difference between two translations.
    *
-   * <p>For example, Translation2d{5.0, 4.0} - Translation2d{1.0, 2.0} = Translation2d{4.0, 2.0}
+   * <p>For example, Translation2d(5.0, 4.0) - Translation2d(1.0, 2.0) = Translation2d(4.0, 2.0).
    *
    * @param other The translation to subtract.
    * @return The difference between the two translations.
@@ -142,7 +153,7 @@
 
   /**
    * Returns the inverse of the current translation. This is equivalent to rotating by 180 degrees,
-   * flipping the point over both axes, or simply negating both components of the translation.
+   * flipping the point over both axes, or negating all components of the translation.
    *
    * @return The inverse of the current translation.
    */
@@ -151,9 +162,9 @@
   }
 
   /**
-   * Multiplies the translation by a scalar and returns the new translation.
+   * Returns the translation multiplied by a scalar.
    *
-   * <p>For example, Translation2d{2.0, 2.5} * 2 = Translation2d{4.0, 5.0}
+   * <p>For example, Translation2d(2.0, 2.5) * 2 = Translation2d(4.0, 5.0).
    *
    * @param scalar The scalar to multiply by.
    * @return The scaled translation.
@@ -163,9 +174,9 @@
   }
 
   /**
-   * Divides the translation by a scalar and returns the new translation.
+   * Returns the translation divided by a scalar.
    *
-   * <p>For example, Translation2d{2.0, 2.5} / 2 = Translation2d{1.0, 1.25}
+   * <p>For example, Translation3d(2.0, 2.5) / 2 = Translation3d(1.0, 1.25).
    *
    * @param scalar The scalar to multiply by.
    * @return The reference to the new mutated object.
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/Translation3d.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/Translation3d.java
new file mode 100644
index 0000000..810f56c
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/Translation3d.java
@@ -0,0 +1,234 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.math.geometry;
+
+import com.fasterxml.jackson.annotation.JsonAutoDetect;
+import com.fasterxml.jackson.annotation.JsonCreator;
+import com.fasterxml.jackson.annotation.JsonIgnoreProperties;
+import com.fasterxml.jackson.annotation.JsonProperty;
+import edu.wpi.first.math.MathUtil;
+import edu.wpi.first.math.interpolation.Interpolatable;
+import java.util.Objects;
+
+/**
+ * Represents a translation in 3D space. This object can be used to represent a point or a vector.
+ *
+ * <p>This assumes that you are using conventional mathematical axes. When the robot is at the
+ * origin facing in the positive X direction, forward is positive X, left is positive Y, and up is
+ * positive Z.
+ */
+@JsonIgnoreProperties(ignoreUnknown = true)
+@JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE)
+public class Translation3d implements Interpolatable<Translation3d> {
+  private final double m_x;
+  private final double m_y;
+  private final double m_z;
+
+  /** Constructs a Translation3d with X, Y, and Z components equal to zero. */
+  public Translation3d() {
+    this(0.0, 0.0, 0.0);
+  }
+
+  /**
+   * Constructs a Translation3d with the X, Y, and Z components equal to the provided values.
+   *
+   * @param x The x component of the translation.
+   * @param y The y component of the translation.
+   * @param z The z component of the translation.
+   */
+  @JsonCreator
+  public Translation3d(
+      @JsonProperty(required = true, value = "x") double x,
+      @JsonProperty(required = true, value = "y") double y,
+      @JsonProperty(required = true, value = "z") double z) {
+    m_x = x;
+    m_y = y;
+    m_z = z;
+  }
+
+  /**
+   * Constructs a Translation3d with the provided distance and angle. This is essentially converting
+   * from polar coordinates to Cartesian coordinates.
+   *
+   * @param distance The distance from the origin to the end of the translation.
+   * @param angle The angle between the x-axis and the translation vector.
+   */
+  public Translation3d(double distance, Rotation3d angle) {
+    final var rectangular = new Translation3d(distance, 0.0, 0.0).rotateBy(angle);
+    m_x = rectangular.getX();
+    m_y = rectangular.getY();
+    m_z = rectangular.getZ();
+  }
+
+  /**
+   * Calculates the distance between two translations in 3D space.
+   *
+   * <p>The distance between translations is defined as √((x₂−x₁)²+(y₂−y₁)²+(z₂−z₁)²).
+   *
+   * @param other The translation to compute the distance to.
+   * @return The distance between the two translations.
+   */
+  public double getDistance(Translation3d other) {
+    return Math.sqrt(
+        Math.pow(other.m_x - m_x, 2) + Math.pow(other.m_y - m_y, 2) + Math.pow(other.m_z - m_z, 2));
+  }
+
+  /**
+   * Returns the X component of the translation.
+   *
+   * @return The X component of the translation.
+   */
+  @JsonProperty
+  public double getX() {
+    return m_x;
+  }
+
+  /**
+   * Returns the Y component of the translation.
+   *
+   * @return The Y component of the translation.
+   */
+  @JsonProperty
+  public double getY() {
+    return m_y;
+  }
+
+  /**
+   * Returns the Z component of the translation.
+   *
+   * @return The Z component of the translation.
+   */
+  @JsonProperty
+  public double getZ() {
+    return m_z;
+  }
+
+  /**
+   * Returns the norm, or distance from the origin to the translation.
+   *
+   * @return The norm of the translation.
+   */
+  public double getNorm() {
+    return Math.sqrt(m_x * m_x + m_y * m_y + m_z * m_z);
+  }
+
+  /**
+   * Applies a rotation to the translation in 3D space.
+   *
+   * <p>For example, rotating a Translation3d of &lt;2, 0, 0&gt; by 90 degrees around the Z axis
+   * will return a Translation3d of &lt;0, 2, 0&gt;.
+   *
+   * @param other The rotation to rotate the translation by.
+   * @return The new rotated translation.
+   */
+  public Translation3d rotateBy(Rotation3d other) {
+    final var p = new Quaternion(0.0, m_x, m_y, m_z);
+    final var qprime = other.getQuaternion().times(p).times(other.getQuaternion().inverse());
+    return new Translation3d(qprime.getX(), qprime.getY(), qprime.getZ());
+  }
+
+  /**
+   * Returns a Translation2d representing this Translation3d projected into the X-Y plane.
+   *
+   * @return A Translation2d representing this Translation3d projected into the X-Y plane.
+   */
+  public Translation2d toTranslation2d() {
+    return new Translation2d(m_x, m_y);
+  }
+
+  /**
+   * Returns the sum of two translations in 3D space.
+   *
+   * <p>For example, Translation3d(1.0, 2.5, 3.5) + Translation3d(2.0, 5.5, 7.5) =
+   * Translation3d{3.0, 8.0, 11.0).
+   *
+   * @param other The translation to add.
+   * @return The sum of the translations.
+   */
+  public Translation3d plus(Translation3d other) {
+    return new Translation3d(m_x + other.m_x, m_y + other.m_y, m_z + other.m_z);
+  }
+
+  /**
+   * Returns the difference between two translations.
+   *
+   * <p>For example, Translation3d(5.0, 4.0, 3.0) - Translation3d(1.0, 2.0, 3.0) =
+   * Translation3d(4.0, 2.0, 0.0).
+   *
+   * @param other The translation to subtract.
+   * @return The difference between the two translations.
+   */
+  public Translation3d minus(Translation3d other) {
+    return new Translation3d(m_x - other.m_x, m_y - other.m_y, m_z - other.m_z);
+  }
+
+  /**
+   * Returns the inverse of the current translation. This is equivalent to negating all components
+   * of the translation.
+   *
+   * @return The inverse of the current translation.
+   */
+  public Translation3d unaryMinus() {
+    return new Translation3d(-m_x, -m_y, -m_z);
+  }
+
+  /**
+   * Returns the translation multiplied by a scalar.
+   *
+   * <p>For example, Translation3d(2.0, 2.5, 4.5) * 2 = Translation3d(4.0, 5.0, 9.0).
+   *
+   * @param scalar The scalar to multiply by.
+   * @return The scaled translation.
+   */
+  public Translation3d times(double scalar) {
+    return new Translation3d(m_x * scalar, m_y * scalar, m_z * scalar);
+  }
+
+  /**
+   * Returns the translation divided by a scalar.
+   *
+   * <p>For example, Translation3d(2.0, 2.5, 4.5) / 2 = Translation3d(1.0, 1.25, 2.25).
+   *
+   * @param scalar The scalar to multiply by.
+   * @return The reference to the new mutated object.
+   */
+  public Translation3d div(double scalar) {
+    return new Translation3d(m_x / scalar, m_y / scalar, m_z / scalar);
+  }
+
+  @Override
+  public String toString() {
+    return String.format("Translation3d(X: %.2f, Y: %.2f, Z: %.2f)", m_x, m_y, m_z);
+  }
+
+  /**
+   * Checks equality between this Translation3d and another object.
+   *
+   * @param obj The other object.
+   * @return Whether the two objects are equal or not.
+   */
+  @Override
+  public boolean equals(Object obj) {
+    if (obj instanceof Translation3d) {
+      return Math.abs(((Translation3d) obj).m_x - m_x) < 1E-9
+          && Math.abs(((Translation3d) obj).m_y - m_y) < 1E-9
+          && Math.abs(((Translation3d) obj).m_z - m_z) < 1E-9;
+    }
+    return false;
+  }
+
+  @Override
+  public int hashCode() {
+    return Objects.hash(m_x, m_y, m_z);
+  }
+
+  @Override
+  public Translation3d interpolate(Translation3d endValue, double t) {
+    return new Translation3d(
+        MathUtil.interpolate(this.getX(), endValue.getX(), t),
+        MathUtil.interpolate(this.getY(), endValue.getY(), t),
+        MathUtil.interpolate(this.getZ(), endValue.getZ(), t));
+  }
+}
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/Twist2d.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/Twist2d.java
index c73d236..be6831e 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/Twist2d.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/Twist2d.java
@@ -7,12 +7,11 @@
 import java.util.Objects;
 
 /**
- * A change in distance along arc since the last pose update. We can use ideas from differential
- * calculus to create new Pose2ds from a Twist2d and vise versa.
+ * A change in distance along a 2D arc since the last pose update. We can use ideas from
+ * differential calculus to create new Pose2d objects from a Twist2d and vise versa.
  *
  * <p>A Twist can be used to represent a difference between two poses.
  */
-@SuppressWarnings("MemberName")
 public class Twist2d {
   /** Linear "dx" component. */
   public double dx;
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/Twist3d.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/Twist3d.java
new file mode 100644
index 0000000..b78505e
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/geometry/Twist3d.java
@@ -0,0 +1,85 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.math.geometry;
+
+import java.util.Objects;
+
+/**
+ * A change in distance along a 3D arc since the last pose update. We can use ideas from
+ * differential calculus to create new Pose3d objects from a Twist3d and vise versa.
+ *
+ * <p>A Twist can be used to represent a difference between two poses.
+ */
+public class Twist3d {
+  /** Linear "dx" component. */
+  public double dx;
+
+  /** Linear "dy" component. */
+  public double dy;
+
+  /** Linear "dz" component. */
+  public double dz;
+
+  /** Rotation vector x component (radians). */
+  public double rx;
+
+  /** Rotation vector y component (radians). */
+  public double ry;
+
+  /** Rotation vector z component (radians). */
+  public double rz;
+
+  public Twist3d() {}
+
+  /**
+   * Constructs a Twist3d with the given values.
+   *
+   * @param dx Change in x direction relative to robot.
+   * @param dy Change in y direction relative to robot.
+   * @param dz Change in z direction relative to robot.
+   * @param rx Rotation vector x component.
+   * @param ry Rotation vector y component.
+   * @param rz Rotation vector z component.
+   */
+  public Twist3d(double dx, double dy, double dz, double rx, double ry, double rz) {
+    this.dx = dx;
+    this.dy = dy;
+    this.dz = dz;
+    this.rx = rx;
+    this.ry = ry;
+    this.rz = rz;
+  }
+
+  @Override
+  public String toString() {
+    return String.format(
+        "Twist3d(dX: %.2f, dY: %.2f, dZ: %.2f, rX: %.2f, rY: %.2f, rZ: %.2f)",
+        dx, dy, dz, rx, ry, rz);
+  }
+
+  /**
+   * Checks equality between this Twist3d and another object.
+   *
+   * @param obj The other object.
+   * @return Whether the two objects are equal or not.
+   */
+  @Override
+  public boolean equals(Object obj) {
+    if (obj instanceof Twist3d) {
+      return Math.abs(((Twist3d) obj).dx - dx) < 1E-9
+          && Math.abs(((Twist3d) obj).dy - dy) < 1E-9
+          && Math.abs(((Twist3d) obj).dz - dz) < 1E-9
+          && Math.abs(((Twist3d) obj).rx - rx) < 1E-9
+          && Math.abs(((Twist3d) obj).ry - ry) < 1E-9
+          && Math.abs(((Twist3d) obj).rz - rz) < 1E-9;
+    }
+    return false;
+  }
+
+  @Override
+  public int hashCode() {
+    return Objects.hash(dx, dy, dz, rx, ry, rz);
+  }
+}
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/interpolation/Interpolatable.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/interpolation/Interpolatable.java
index f10820f..9fe09fe 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/interpolation/Interpolatable.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/interpolation/Interpolatable.java
@@ -20,6 +20,5 @@
    * @param t How far between the lower and upper bound we are. This should be bounded in [0, 1].
    * @return The interpolated value.
    */
-  @SuppressWarnings("ParameterName")
   T interpolate(T endValue, double t);
 }
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/interpolation/TimeInterpolatableBuffer.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/interpolation/TimeInterpolatableBuffer.java
index 676bd7c..7e0712d 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/interpolation/TimeInterpolatableBuffer.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/interpolation/TimeInterpolatableBuffer.java
@@ -6,6 +6,7 @@
 
 import edu.wpi.first.math.MathUtil;
 import java.util.NavigableMap;
+import java.util.Optional;
 import java.util.TreeMap;
 
 /**
@@ -16,10 +17,10 @@
  *
  * @param <T> The type stored in this buffer.
  */
-public class TimeInterpolatableBuffer<T> {
+public final class TimeInterpolatableBuffer<T> {
   private final double m_historySize;
   private final InterpolateFunction<T> m_interpolatingFunc;
-  private final NavigableMap<Double, T> m_buffer = new TreeMap<>();
+  private final NavigableMap<Double, T> m_pastSnapshots = new TreeMap<>();
 
   private TimeInterpolatableBuffer(
       InterpolateFunction<T> interpolateFunction, double historySizeSeconds) {
@@ -70,7 +71,7 @@
    */
   public void addSample(double timeSeconds, T sample) {
     cleanUp(timeSeconds);
-    m_buffer.put(timeSeconds, sample);
+    m_pastSnapshots.put(timeSeconds, sample);
   }
 
   /**
@@ -79,10 +80,10 @@
    * @param time The current timestamp.
    */
   private void cleanUp(double time) {
-    while (!m_buffer.isEmpty()) {
-      var entry = m_buffer.firstEntry();
+    while (!m_pastSnapshots.isEmpty()) {
+      var entry = m_pastSnapshots.firstEntry();
       if (time - entry.getKey() >= m_historySize) {
-        m_buffer.remove(entry.getKey());
+        m_pastSnapshots.remove(entry.getKey());
       } else {
         return;
       }
@@ -91,48 +92,58 @@
 
   /** Clear all old samples. */
   public void clear() {
-    m_buffer.clear();
+    m_pastSnapshots.clear();
   }
 
   /**
-   * Sample the buffer at the given time. If the buffer is empty, this will return null.
+   * Sample the buffer at the given time. If the buffer is empty, an empty Optional is returned.
    *
    * @param timeSeconds The time at which to sample.
-   * @return The interpolated value at that timestamp. Might be null.
+   * @return The interpolated value at that timestamp or an empty Optional.
    */
-  @SuppressWarnings("UnnecessaryParentheses")
-  public T getSample(double timeSeconds) {
-    if (m_buffer.isEmpty()) {
-      return null;
+  public Optional<T> getSample(double timeSeconds) {
+    if (m_pastSnapshots.isEmpty()) {
+      return Optional.empty();
     }
 
     // Special case for when the requested time is the same as a sample
-    var nowEntry = m_buffer.get(timeSeconds);
+    var nowEntry = m_pastSnapshots.get(timeSeconds);
     if (nowEntry != null) {
-      return nowEntry;
+      return Optional.of(nowEntry);
     }
 
-    var topBound = m_buffer.ceilingEntry(timeSeconds);
-    var bottomBound = m_buffer.floorEntry(timeSeconds);
+    var topBound = m_pastSnapshots.ceilingEntry(timeSeconds);
+    var bottomBound = m_pastSnapshots.floorEntry(timeSeconds);
 
     // Return null if neither sample exists, and the opposite bound if the other is null
     if (topBound == null && bottomBound == null) {
-      return null;
+      return Optional.empty();
     } else if (topBound == null) {
-      return bottomBound.getValue();
+      return Optional.of(bottomBound.getValue());
     } else if (bottomBound == null) {
-      return topBound.getValue();
+      return Optional.of(topBound.getValue());
     } else {
       // Otherwise, interpolate. Because T is between [0, 1], we want the ratio of (the difference
       // between the current time and bottom bound) and (the difference between top and bottom
       // bounds).
-      return m_interpolatingFunc.interpolate(
-          bottomBound.getValue(),
-          topBound.getValue(),
-          ((timeSeconds - bottomBound.getKey()) / (topBound.getKey() - bottomBound.getKey())));
+      return Optional.of(
+          m_interpolatingFunc.interpolate(
+              bottomBound.getValue(),
+              topBound.getValue(),
+              (timeSeconds - bottomBound.getKey()) / (topBound.getKey() - bottomBound.getKey())));
     }
   }
 
+  /**
+   * Grant access to the internal sample buffer. Used in Pose Estimation to replay odometry inputs
+   * stored within this buffer.
+   *
+   * @return The internal sample buffer.
+   */
+  public NavigableMap<Double, T> getInternalBuffer() {
+    return m_pastSnapshots;
+  }
+
   public interface InterpolateFunction<T> {
     /**
      * Return the interpolated value. This object is assumed to be the starting position, or lower
@@ -143,7 +154,6 @@
      * @param t How far between the lower and upper bound we are. This should be bounded in [0, 1].
      * @return The interpolated value.
      */
-    @SuppressWarnings("ParameterName")
     T interpolate(T start, T end, double t);
   }
 }
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/ChassisSpeeds.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/ChassisSpeeds.java
index 451c008..6c98337 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/ChassisSpeeds.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/ChassisSpeeds.java
@@ -16,7 +16,6 @@
  * component because it can never move sideways. Holonomic drivetrains such as swerve and mecanum
  * will often have all three components.
  */
-@SuppressWarnings("MemberName")
 public class ChassisSpeeds {
   /** Represents forward velocity w.r.t the robot frame of reference. (Fwd is +) */
   public double vxMetersPerSecond;
@@ -69,6 +68,27 @@
         omegaRadiansPerSecond);
   }
 
+  /**
+   * Converts a user provided field-relative ChassisSpeeds object into a robot-relative
+   * ChassisSpeeds object.
+   *
+   * @param fieldRelativeSpeeds The ChassisSpeeds object representing the speeds in the field frame
+   *     of reference. Positive x is away from your alliance wall. Positive y is to your left when
+   *     standing behind the alliance wall.
+   * @param robotAngle The angle of the robot as measured by a gyroscope. The robot's angle is
+   *     considered to be zero when it is facing directly away from your alliance station wall.
+   *     Remember that this should be CCW positive.
+   * @return ChassisSpeeds object representing the speeds in the robot's frame of reference.
+   */
+  public static ChassisSpeeds fromFieldRelativeSpeeds(
+      ChassisSpeeds fieldRelativeSpeeds, Rotation2d robotAngle) {
+    return fromFieldRelativeSpeeds(
+        fieldRelativeSpeeds.vxMetersPerSecond,
+        fieldRelativeSpeeds.vyMetersPerSecond,
+        fieldRelativeSpeeds.omegaRadiansPerSecond,
+        robotAngle);
+  }
+
   @Override
   public String toString() {
     return String.format(
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveKinematics.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveKinematics.java
index 7984e39..0dfb016 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveKinematics.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveKinematics.java
@@ -6,6 +6,7 @@
 
 import edu.wpi.first.math.MathSharedStore;
 import edu.wpi.first.math.MathUsageId;
+import edu.wpi.first.math.geometry.Twist2d;
 
 /**
  * Helper class that converts a chassis velocity (dx and dtheta components) to left and right wheel
@@ -15,7 +16,6 @@
  * whereas forward kinematics converts left and right component velocities into a linear and angular
  * chassis speed.
  */
-@SuppressWarnings("MemberName")
 public class DifferentialDriveKinematics {
   public final double trackWidthMeters;
 
@@ -58,4 +58,20 @@
         chassisSpeeds.vxMetersPerSecond
             + trackWidthMeters / 2 * chassisSpeeds.omegaRadiansPerSecond);
   }
+
+  /**
+   * Performs forward kinematics to return the resulting Twist2d from the given left and right side
+   * distance deltas. This method is often used for odometry -- determining the robot's position on
+   * the field using changes in the distance driven by each wheel on the robot.
+   *
+   * @param leftDistanceMeters The distance measured by the left side encoder.
+   * @param rightDistanceMeters The distance measured by the right side encoder.
+   * @return The resulting Twist2d.
+   */
+  public Twist2d toTwist2d(double leftDistanceMeters, double rightDistanceMeters) {
+    return new Twist2d(
+        (leftDistanceMeters + rightDistanceMeters) / 2,
+        0,
+        (rightDistanceMeters - leftDistanceMeters) / trackWidthMeters);
+  }
 }
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveOdometry.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveOdometry.java
index 0139573..e8f97f5 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveOdometry.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveOdometry.java
@@ -33,42 +33,59 @@
    * Constructs a DifferentialDriveOdometry object.
    *
    * @param gyroAngle The angle reported by the gyroscope.
+   * @param leftDistanceMeters The distance traveled by the left encoder.
+   * @param rightDistanceMeters The distance traveled by the right encoder.
    * @param initialPoseMeters The starting position of the robot on the field.
    */
-  public DifferentialDriveOdometry(Rotation2d gyroAngle, Pose2d initialPoseMeters) {
+  public DifferentialDriveOdometry(
+      Rotation2d gyroAngle,
+      double leftDistanceMeters,
+      double rightDistanceMeters,
+      Pose2d initialPoseMeters) {
     m_poseMeters = initialPoseMeters;
     m_gyroOffset = m_poseMeters.getRotation().minus(gyroAngle);
     m_previousAngle = initialPoseMeters.getRotation();
+
+    m_prevLeftDistance = leftDistanceMeters;
+    m_prevRightDistance = rightDistanceMeters;
+
     MathSharedStore.reportUsage(MathUsageId.kOdometry_DifferentialDrive, 1);
   }
 
   /**
-   * Constructs a DifferentialDriveOdometry object with the default pose at the origin.
+   * Constructs a DifferentialDriveOdometry object.
    *
    * @param gyroAngle The angle reported by the gyroscope.
+   * @param leftDistanceMeters The distance traveled by the left encoder.
+   * @param rightDistanceMeters The distance traveled by the right encoder.
    */
-  public DifferentialDriveOdometry(Rotation2d gyroAngle) {
-    this(gyroAngle, new Pose2d());
+  public DifferentialDriveOdometry(
+      Rotation2d gyroAngle, double leftDistanceMeters, double rightDistanceMeters) {
+    this(gyroAngle, leftDistanceMeters, rightDistanceMeters, new Pose2d());
   }
 
   /**
    * Resets the robot's position on the field.
    *
-   * <p>You NEED to reset your encoders (to zero) when calling this method.
-   *
    * <p>The gyroscope angle does not need to be reset here on the user's robot code. The library
    * automatically takes care of offsetting the gyro angle.
    *
-   * @param poseMeters The position on the field that your robot is at.
    * @param gyroAngle The angle reported by the gyroscope.
+   * @param leftDistanceMeters The distance traveled by the left encoder.
+   * @param rightDistanceMeters The distance traveled by the right encoder.
+   * @param poseMeters The position on the field that your robot is at.
    */
-  public void resetPosition(Pose2d poseMeters, Rotation2d gyroAngle) {
+  public void resetPosition(
+      Rotation2d gyroAngle,
+      double leftDistanceMeters,
+      double rightDistanceMeters,
+      Pose2d poseMeters) {
     m_poseMeters = poseMeters;
     m_previousAngle = poseMeters.getRotation();
     m_gyroOffset = m_poseMeters.getRotation().minus(gyroAngle);
 
-    m_prevLeftDistance = 0.0;
-    m_prevRightDistance = 0.0;
+    m_prevLeftDistance = leftDistanceMeters;
+    m_prevRightDistance = rightDistanceMeters;
   }
 
   /**
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveWheelSpeeds.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveWheelSpeeds.java
index 20a38a9..d4b235e 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveWheelSpeeds.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveWheelSpeeds.java
@@ -5,7 +5,6 @@
 package edu.wpi.first.math.kinematics;
 
 /** Represents the wheel speeds for a differential drive drivetrain. */
-@SuppressWarnings("MemberName")
 public class DifferentialDriveWheelSpeeds {
   /** Speed of the left side of the robot. */
   public double leftMetersPerSecond;
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveKinematics.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveKinematics.java
index 0807aba..23204d4 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveKinematics.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveKinematics.java
@@ -7,6 +7,7 @@
 import edu.wpi.first.math.MathSharedStore;
 import edu.wpi.first.math.MathUsageId;
 import edu.wpi.first.math.geometry.Translation2d;
+import edu.wpi.first.math.geometry.Twist2d;
 import org.ejml.simple.SimpleMatrix;
 
 /**
@@ -15,8 +16,8 @@
  *
  * <p>The inverse kinematics (converting from a desired chassis velocity to individual wheel speeds)
  * uses the relative locations of the wheels with respect to the center of rotation. The center of
- * rotation for inverse kinematics is also variable. This means that you can set your set your
- * center of rotation in a corner of the robot to perform special evasion maneuvers.
+ * rotation for inverse kinematics is also variable. This means that you can set your center of
+ * rotation in a corner of the robot to perform special evasion maneuvers.
  *
  * <p>Forward kinematics (converting an array of wheel speeds into the overall chassis motion) is
  * performs the exact opposite of what inverse kinematics does. Since this is an overdetermined
@@ -154,6 +155,28 @@
   }
 
   /**
+   * Performs forward kinematics to return the resulting Twist2d from the given wheel deltas. This
+   * method is often used for odometry -- determining the robot's position on the field using
+   * changes in the distance driven by each wheel on the robot.
+   *
+   * @param wheelDeltas The distances driven by each wheel.
+   * @return The resulting Twist2d.
+   */
+  public Twist2d toTwist2d(MecanumDriveWheelPositions wheelDeltas) {
+    var wheelDeltasVector = new SimpleMatrix(4, 1);
+    wheelDeltasVector.setColumn(
+        0,
+        0,
+        wheelDeltas.frontLeftMeters,
+        wheelDeltas.frontRightMeters,
+        wheelDeltas.rearLeftMeters,
+        wheelDeltas.rearRightMeters);
+    var twist = m_forwardKinematics.mult(wheelDeltasVector);
+
+    return new Twist2d(twist.get(0, 0), twist.get(1, 0), twist.get(2, 0));
+  }
+
+  /**
    * Construct inverse kinematics matrix from wheel locations.
    *
    * @param fl The location of the front-left wheel relative to the physical center of the robot.
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveMotorVoltages.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveMotorVoltages.java
index b504acc..a63eaea 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveMotorVoltages.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveMotorVoltages.java
@@ -5,7 +5,6 @@
 package edu.wpi.first.math.kinematics;
 
 /** Represents the motor voltages for a mecanum drive drivetrain. */
-@SuppressWarnings("MemberName")
 public class MecanumDriveMotorVoltages {
   /** Voltage of the front left motor. */
   public double frontLeftVoltage;
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveOdometry.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveOdometry.java
index b3c79c9..40a77e2 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveOdometry.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveOdometry.java
@@ -8,8 +8,6 @@
 import edu.wpi.first.math.MathUsageId;
 import edu.wpi.first.math.geometry.Pose2d;
 import edu.wpi.first.math.geometry.Rotation2d;
-import edu.wpi.first.math.geometry.Twist2d;
-import edu.wpi.first.util.WPIUtilJNI;
 
 /**
  * Class for mecanum drive odometry. Odometry allows you to track the robot's position on the field
@@ -21,7 +19,7 @@
 public class MecanumDriveOdometry {
   private final MecanumDriveKinematics m_kinematics;
   private Pose2d m_poseMeters;
-  private double m_prevTimeSeconds = -1;
+  private MecanumDriveWheelPositions m_previousWheelPositions;
 
   private Rotation2d m_gyroOffset;
   private Rotation2d m_previousAngle;
@@ -31,14 +29,24 @@
    *
    * @param kinematics The mecanum drive kinematics for your drivetrain.
    * @param gyroAngle The angle reported by the gyroscope.
+   * @param wheelPositions The distances driven by each wheel.
    * @param initialPoseMeters The starting position of the robot on the field.
    */
   public MecanumDriveOdometry(
-      MecanumDriveKinematics kinematics, Rotation2d gyroAngle, Pose2d initialPoseMeters) {
+      MecanumDriveKinematics kinematics,
+      Rotation2d gyroAngle,
+      MecanumDriveWheelPositions wheelPositions,
+      Pose2d initialPoseMeters) {
     m_kinematics = kinematics;
     m_poseMeters = initialPoseMeters;
     m_gyroOffset = m_poseMeters.getRotation().minus(gyroAngle);
     m_previousAngle = initialPoseMeters.getRotation();
+    m_previousWheelPositions =
+        new MecanumDriveWheelPositions(
+            wheelPositions.frontLeftMeters,
+            wheelPositions.frontRightMeters,
+            wheelPositions.rearLeftMeters,
+            wheelPositions.rearRightMeters);
     MathSharedStore.reportUsage(MathUsageId.kOdometry_MecanumDrive, 1);
   }
 
@@ -47,9 +55,13 @@
    *
    * @param kinematics The mecanum drive kinematics for your drivetrain.
    * @param gyroAngle The angle reported by the gyroscope.
+   * @param wheelPositions The distances driven by each wheel.
    */
-  public MecanumDriveOdometry(MecanumDriveKinematics kinematics, Rotation2d gyroAngle) {
-    this(kinematics, gyroAngle, new Pose2d());
+  public MecanumDriveOdometry(
+      MecanumDriveKinematics kinematics,
+      Rotation2d gyroAngle,
+      MecanumDriveWheelPositions wheelPositions) {
+    this(kinematics, gyroAngle, wheelPositions, new Pose2d());
   }
 
   /**
@@ -58,13 +70,21 @@
    * <p>The gyroscope angle does not need to be reset here on the user's robot code. The library
    * automatically takes care of offsetting the gyro angle.
    *
-   * @param poseMeters The position on the field that your robot is at.
    * @param gyroAngle The angle reported by the gyroscope.
+   * @param wheelPositions The distances driven by each wheel.
+   * @param poseMeters The position on the field that your robot is at.
    */
-  public void resetPosition(Pose2d poseMeters, Rotation2d gyroAngle) {
+  public void resetPosition(
+      Rotation2d gyroAngle, MecanumDriveWheelPositions wheelPositions, Pose2d poseMeters) {
     m_poseMeters = poseMeters;
     m_previousAngle = poseMeters.getRotation();
     m_gyroOffset = m_poseMeters.getRotation().minus(gyroAngle);
+    m_previousWheelPositions =
+        new MecanumDriveWheelPositions(
+            wheelPositions.frontLeftMeters,
+            wheelPositions.frontRightMeters,
+            wheelPositions.rearLeftMeters,
+            wheelPositions.rearRightMeters);
   }
 
   /**
@@ -78,48 +98,37 @@
 
   /**
    * Updates the robot's position on the field using forward kinematics and integration of the pose
-   * over time. This method takes in the current time as a parameter to calculate period (difference
-   * between two timestamps). The period is used to calculate the change in distance from a
-   * velocity. This also takes in an angle parameter which is used instead of the angular rate that
-   * is calculated from forward kinematics.
+   * over time. This method takes in an angle parameter which is used instead of the angular rate
+   * that is calculated from forward kinematics, in addition to the current distance measurement at
+   * each wheel.
    *
-   * @param currentTimeSeconds The current time in seconds.
    * @param gyroAngle The angle reported by the gyroscope.
-   * @param wheelSpeeds The current wheel speeds.
+   * @param wheelPositions The distances driven by each wheel.
    * @return The new pose of the robot.
    */
-  public Pose2d updateWithTime(
-      double currentTimeSeconds, Rotation2d gyroAngle, MecanumDriveWheelSpeeds wheelSpeeds) {
-    double period = m_prevTimeSeconds >= 0 ? currentTimeSeconds - m_prevTimeSeconds : 0.0;
-    m_prevTimeSeconds = currentTimeSeconds;
-
+  public Pose2d update(Rotation2d gyroAngle, MecanumDriveWheelPositions wheelPositions) {
     var angle = gyroAngle.plus(m_gyroOffset);
 
-    var chassisState = m_kinematics.toChassisSpeeds(wheelSpeeds);
-    var newPose =
-        m_poseMeters.exp(
-            new Twist2d(
-                chassisState.vxMetersPerSecond * period,
-                chassisState.vyMetersPerSecond * period,
-                angle.minus(m_previousAngle).getRadians()));
+    var wheelDeltas =
+        new MecanumDriveWheelPositions(
+            wheelPositions.frontLeftMeters - m_previousWheelPositions.frontLeftMeters,
+            wheelPositions.frontRightMeters - m_previousWheelPositions.frontRightMeters,
+            wheelPositions.rearLeftMeters - m_previousWheelPositions.rearLeftMeters,
+            wheelPositions.rearRightMeters - m_previousWheelPositions.rearRightMeters);
+
+    var twist = m_kinematics.toTwist2d(wheelDeltas);
+    twist.dtheta = angle.minus(m_previousAngle).getRadians();
+    var newPose = m_poseMeters.exp(twist);
 
     m_previousAngle = angle;
     m_poseMeters = new Pose2d(newPose.getTranslation(), angle);
-    return m_poseMeters;
-  }
+    m_previousWheelPositions =
+        new MecanumDriveWheelPositions(
+            wheelPositions.frontLeftMeters,
+            wheelPositions.frontRightMeters,
+            wheelPositions.rearLeftMeters,
+            wheelPositions.rearRightMeters);
 
-  /**
-   * Updates the robot's position on the field using forward kinematics and integration of the pose
-   * over time. This method automatically calculates the current time to calculate period
-   * (difference between two timestamps). The period is used to calculate the change in distance
-   * from a velocity. This also takes in an angle parameter which is used instead of the angular
-   * rate that is calculated from forward kinematics.
-   *
-   * @param gyroAngle The angle reported by the gyroscope.
-   * @param wheelSpeeds The current wheel speeds.
-   * @return The new pose of the robot.
-   */
-  public Pose2d update(Rotation2d gyroAngle, MecanumDriveWheelSpeeds wheelSpeeds) {
-    return updateWithTime(WPIUtilJNI.now() * 1.0e-6, gyroAngle, wheelSpeeds);
+    return m_poseMeters;
   }
 }
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveWheelPositions.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveWheelPositions.java
new file mode 100644
index 0000000..9ff3341
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveWheelPositions.java
@@ -0,0 +1,49 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.math.kinematics;
+
+public class MecanumDriveWheelPositions {
+  /** Distance measured by the front left wheel. */
+  public double frontLeftMeters;
+
+  /** Distance measured by the front right wheel. */
+  public double frontRightMeters;
+
+  /** Distance measured by the rear left wheel. */
+  public double rearLeftMeters;
+
+  /** Distance measured by the rear right wheel. */
+  public double rearRightMeters;
+
+  /** Constructs a MecanumDriveWheelPositions with zeros for all member fields. */
+  public MecanumDriveWheelPositions() {}
+
+  /**
+   * Constructs a MecanumDriveWheelPositions.
+   *
+   * @param frontLeftMeters Distance measured by the front left wheel.
+   * @param frontRightMeters Distance measured by the front right wheel.
+   * @param rearLeftMeters Distance measured by the rear left wheel.
+   * @param rearRightMeters Distance measured by the rear right wheel.
+   */
+  public MecanumDriveWheelPositions(
+      double frontLeftMeters,
+      double frontRightMeters,
+      double rearLeftMeters,
+      double rearRightMeters) {
+    this.frontLeftMeters = frontLeftMeters;
+    this.frontRightMeters = frontRightMeters;
+    this.rearLeftMeters = rearLeftMeters;
+    this.rearRightMeters = rearRightMeters;
+  }
+
+  @Override
+  public String toString() {
+    return String.format(
+        "MecanumDriveWheelPositions(Front Left: %.2f m, Front Right: %.2f m, "
+            + "Rear Left: %.2f m, Rear Right: %.2f m)",
+        frontLeftMeters, frontRightMeters, rearLeftMeters, rearRightMeters);
+  }
+}
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveWheelSpeeds.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveWheelSpeeds.java
index ef354ef..1dcfc85 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveWheelSpeeds.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveWheelSpeeds.java
@@ -6,7 +6,6 @@
 
 import java.util.stream.DoubleStream;
 
-@SuppressWarnings("MemberName")
 public class MecanumDriveWheelSpeeds {
   /** Speed of the front left wheel. */
   public double frontLeftMetersPerSecond;
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveDriveKinematics.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveDriveKinematics.java
index dc1b9e4..98df547 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveDriveKinematics.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveDriveKinematics.java
@@ -8,6 +8,7 @@
 import edu.wpi.first.math.MathUsageId;
 import edu.wpi.first.math.geometry.Rotation2d;
 import edu.wpi.first.math.geometry.Translation2d;
+import edu.wpi.first.math.geometry.Twist2d;
 import java.util.Arrays;
 import java.util.Collections;
 import org.ejml.simple.SimpleMatrix;
@@ -18,8 +19,8 @@
  *
  * <p>The inverse kinematics (converting from a desired chassis velocity to individual module
  * states) uses the relative locations of the modules with respect to the center of rotation. The
- * center of rotation for inverse kinematics is also variable. This means that you can set your set
- * your center of rotation in a corner of the robot to perform special evasion maneuvers.
+ * center of rotation for inverse kinematics is also variable. This means that you can set your
+ * center of rotation in a corner of the robot to perform special evasion maneuvers.
  *
  * <p>Forward kinematics (converting an array of module states into the overall chassis motion) is
  * performs the exact opposite of what inverse kinematics does. Since this is an overdetermined
@@ -38,13 +39,15 @@
 
   private final int m_numModules;
   private final Translation2d[] m_modules;
+  private final SwerveModuleState[] m_moduleStates;
   private Translation2d m_prevCoR = new Translation2d();
 
   /**
    * Constructs a swerve drive kinematics object. This takes in a variable number of wheel locations
-   * as Translation2ds. The order in which you pass in the wheel locations is the same order that
-   * you will receive the module states when performing inverse kinematics. It is also expected that
-   * you pass in the module states in the same order when calling the forward kinematics methods.
+   * as Translation2d objects. The order in which you pass in the wheel locations is the same order
+   * that you will receive the module states when performing inverse kinematics. It is also expected
+   * that you pass in the module states in the same order when calling the forward kinematics
+   * methods.
    *
    * @param wheelsMeters The locations of the wheels relative to the physical center of the robot.
    */
@@ -54,6 +57,8 @@
     }
     m_numModules = wheelsMeters.length;
     m_modules = Arrays.copyOf(wheelsMeters, m_numModules);
+    m_moduleStates = new SwerveModuleState[m_numModules];
+    Arrays.fill(m_moduleStates, new SwerveModuleState());
     m_inverseKinematics = new SimpleMatrix(m_numModules * 2, 3);
 
     for (int i = 0; i < m_numModules; i++) {
@@ -74,6 +79,9 @@
    * argument is defaulted to that use case. However, if you wish to change the center of rotation
    * for evasive maneuvers, vision alignment, or for any other use case, you can do so.
    *
+   * <p>In the case that the desired chassis speeds are zero (i.e. the robot will be stationary),
+   * the previously calculated module angle will be maintained.
+   *
    * @param chassisSpeeds The desired chassis speed.
    * @param centerOfRotationMeters The center of rotation. For example, if you set the center of
    *     rotation at one corner of the robot and provide a chassis speed that only has a dtheta
@@ -83,9 +91,19 @@
    *     attainable max velocity. Use the {@link #desaturateWheelSpeeds(SwerveModuleState[], double)
    *     DesaturateWheelSpeeds} function to rectify this issue.
    */
-  @SuppressWarnings("LocalVariableName")
+  @SuppressWarnings("PMD.MethodReturnsInternalArray")
   public SwerveModuleState[] toSwerveModuleStates(
       ChassisSpeeds chassisSpeeds, Translation2d centerOfRotationMeters) {
+    if (chassisSpeeds.vxMetersPerSecond == 0.0
+        && chassisSpeeds.vyMetersPerSecond == 0.0
+        && chassisSpeeds.omegaRadiansPerSecond == 0.0) {
+      for (int i = 0; i < m_numModules; i++) {
+        m_moduleStates[i].speedMetersPerSecond = 0.0;
+      }
+
+      return m_moduleStates;
+    }
+
     if (!centerOfRotationMeters.equals(m_prevCoR)) {
       for (int i = 0; i < m_numModules; i++) {
         m_inverseKinematics.setRow(
@@ -113,7 +131,6 @@
         chassisSpeeds.omegaRadiansPerSecond);
 
     var moduleStatesMatrix = m_inverseKinematics.mult(chassisSpeedsVector);
-    SwerveModuleState[] moduleStates = new SwerveModuleState[m_numModules];
 
     for (int i = 0; i < m_numModules; i++) {
       double x = moduleStatesMatrix.get(i * 2, 0);
@@ -122,10 +139,10 @@
       double speed = Math.hypot(x, y);
       Rotation2d angle = new Rotation2d(x, y);
 
-      moduleStates[i] = new SwerveModuleState(speed, angle);
+      m_moduleStates[i] = new SwerveModuleState(speed, angle);
     }
 
-    return moduleStates;
+    return m_moduleStates;
   }
 
   /**
@@ -171,6 +188,35 @@
   }
 
   /**
+   * Performs forward kinematics to return the resulting chassis state from the given module states.
+   * This method is often used for odometry -- determining the robot's position on the field using
+   * data from the real-world speed and angle of each module on the robot.
+   *
+   * @param wheelDeltas The latest change in position of the modules (as a SwerveModulePosition
+   *     type) as measured from respective encoders and gyros. The order of the swerve module states
+   *     should be same as passed into the constructor of this class.
+   * @return The resulting Twist2d.
+   */
+  public Twist2d toTwist2d(SwerveModulePosition... wheelDeltas) {
+    if (wheelDeltas.length != m_numModules) {
+      throw new IllegalArgumentException(
+          "Number of modules is not consistent with number of wheel locations provided in "
+              + "constructor");
+    }
+    var moduleDeltaMatrix = new SimpleMatrix(m_numModules * 2, 1);
+
+    for (int i = 0; i < m_numModules; i++) {
+      var module = wheelDeltas[i];
+      moduleDeltaMatrix.set(i * 2, 0, module.distanceMeters * module.angle.getCos());
+      moduleDeltaMatrix.set(i * 2 + 1, module.distanceMeters * module.angle.getSin());
+    }
+
+    var chassisDeltaVector = m_forwardKinematics.mult(moduleDeltaMatrix);
+    return new Twist2d(
+        chassisDeltaVector.get(0, 0), chassisDeltaVector.get(1, 0), chassisDeltaVector.get(2, 0));
+  }
+
+  /**
    * Renormalizes the wheel speeds if any individual speed is above the specified maximum.
    *
    * <p>Sometimes, after inverse kinematics, the requested speed from one or more modules may be
@@ -192,4 +238,48 @@
       }
     }
   }
+
+  /**
+   * Renormalizes the wheel speeds if any individual speed is above the specified maximum, as well
+   * as getting rid of joystick saturation at edges of joystick.
+   *
+   * <p>Sometimes, after inverse kinematics, the requested speed from one or more modules may be
+   * above the max attainable speed for the driving motor on that module. To fix this issue, one can
+   * reduce all the wheel speeds to make sure that all requested module speeds are at-or-below the
+   * absolute threshold, while maintaining the ratio of speeds between modules.
+   *
+   * @param moduleStates Reference to array of module states. The array will be mutated with the
+   *     normalized speeds!
+   * @param currentChassisSpeed The current speed of the robot
+   * @param attainableMaxModuleSpeedMetersPerSecond The absolute max speed that a module can reach
+   * @param attainableMaxTranslationalSpeedMetersPerSecond The absolute max speed that your robot
+   *     can reach while translating
+   * @param attainableMaxRotationalVelocityRadiansPerSecond The absolute max speed the robot can
+   *     reach while rotating
+   */
+  public static void desaturateWheelSpeeds(
+      SwerveModuleState[] moduleStates,
+      ChassisSpeeds currentChassisSpeed,
+      double attainableMaxModuleSpeedMetersPerSecond,
+      double attainableMaxTranslationalSpeedMetersPerSecond,
+      double attainableMaxRotationalVelocityRadiansPerSecond) {
+    double realMaxSpeed = Collections.max(Arrays.asList(moduleStates)).speedMetersPerSecond;
+
+    if (attainableMaxTranslationalSpeedMetersPerSecond == 0
+        || attainableMaxRotationalVelocityRadiansPerSecond == 0
+        || realMaxSpeed == 0) {
+      return;
+    }
+    double translationalK =
+        Math.hypot(currentChassisSpeed.vxMetersPerSecond, currentChassisSpeed.vyMetersPerSecond)
+            / attainableMaxTranslationalSpeedMetersPerSecond;
+    double rotationalK =
+        Math.abs(currentChassisSpeed.omegaRadiansPerSecond)
+            / attainableMaxRotationalVelocityRadiansPerSecond;
+    double k = Math.max(translationalK, rotationalK);
+    double scale = Math.min(k * attainableMaxModuleSpeedMetersPerSecond / realMaxSpeed, 1);
+    for (SwerveModuleState moduleState : moduleStates) {
+      moduleState.speedMetersPerSecond *= scale;
+    }
+  }
 }
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveDriveOdometry.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveDriveOdometry.java
index 8b4161e..c2e188f 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveDriveOdometry.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveDriveOdometry.java
@@ -8,8 +8,6 @@
 import edu.wpi.first.math.MathUsageId;
 import edu.wpi.first.math.geometry.Pose2d;
 import edu.wpi.first.math.geometry.Rotation2d;
-import edu.wpi.first.math.geometry.Twist2d;
-import edu.wpi.first.util.WPIUtilJNI;
 
 /**
  * Class for swerve drive odometry. Odometry allows you to track the robot's position on the field
@@ -22,24 +20,38 @@
 public class SwerveDriveOdometry {
   private final SwerveDriveKinematics m_kinematics;
   private Pose2d m_poseMeters;
-  private double m_prevTimeSeconds = -1;
 
   private Rotation2d m_gyroOffset;
   private Rotation2d m_previousAngle;
+  private final int m_numModules;
+  private SwerveModulePosition[] m_previousModulePositions;
 
   /**
    * Constructs a SwerveDriveOdometry object.
    *
    * @param kinematics The swerve drive kinematics for your drivetrain.
    * @param gyroAngle The angle reported by the gyroscope.
+   * @param modulePositions The wheel positions reported by each module.
    * @param initialPose The starting position of the robot on the field.
    */
   public SwerveDriveOdometry(
-      SwerveDriveKinematics kinematics, Rotation2d gyroAngle, Pose2d initialPose) {
+      SwerveDriveKinematics kinematics,
+      Rotation2d gyroAngle,
+      SwerveModulePosition[] modulePositions,
+      Pose2d initialPose) {
     m_kinematics = kinematics;
     m_poseMeters = initialPose;
     m_gyroOffset = m_poseMeters.getRotation().minus(gyroAngle);
     m_previousAngle = initialPose.getRotation();
+    m_numModules = modulePositions.length;
+
+    m_previousModulePositions = new SwerveModulePosition[m_numModules];
+    for (int index = 0; index < m_numModules; index++) {
+      m_previousModulePositions[index] =
+          new SwerveModulePosition(
+              modulePositions[index].distanceMeters, modulePositions[index].angle);
+    }
+
     MathSharedStore.reportUsage(MathUsageId.kOdometry_SwerveDrive, 1);
   }
 
@@ -48,9 +60,13 @@
    *
    * @param kinematics The swerve drive kinematics for your drivetrain.
    * @param gyroAngle The angle reported by the gyroscope.
+   * @param modulePositions The wheel positions reported by each module.
    */
-  public SwerveDriveOdometry(SwerveDriveKinematics kinematics, Rotation2d gyroAngle) {
-    this(kinematics, gyroAngle, new Pose2d());
+  public SwerveDriveOdometry(
+      SwerveDriveKinematics kinematics,
+      Rotation2d gyroAngle,
+      SwerveModulePosition[] modulePositions) {
+    this(kinematics, gyroAngle, modulePositions, new Pose2d());
   }
 
   /**
@@ -59,13 +75,28 @@
    * <p>The gyroscope angle does not need to be reset here on the user's robot code. The library
    * automatically takes care of offsetting the gyro angle.
    *
-   * @param pose The position on the field that your robot is at.
+   * <p>Similarly, module positions do not need to be reset in user code.
+   *
    * @param gyroAngle The angle reported by the gyroscope.
+   * @param modulePositions The wheel positions reported by each module.,
+   * @param pose The position on the field that your robot is at.
    */
-  public void resetPosition(Pose2d pose, Rotation2d gyroAngle) {
+  public void resetPosition(
+      Rotation2d gyroAngle, SwerveModulePosition[] modulePositions, Pose2d pose) {
+    if (modulePositions.length != m_numModules) {
+      throw new IllegalArgumentException(
+          "Number of modules is not consistent with number of wheel locations provided in "
+              + "constructor");
+    }
+
     m_poseMeters = pose;
     m_previousAngle = pose.getRotation();
     m_gyroOffset = m_poseMeters.getRotation().minus(gyroAngle);
+    for (int index = 0; index < m_numModules; index++) {
+      m_previousModulePositions[index] =
+          new SwerveModulePosition(
+              modulePositions[index].distanceMeters, modulePositions[index].angle);
+    }
   }
 
   /**
@@ -79,51 +110,43 @@
 
   /**
    * Updates the robot's position on the field using forward kinematics and integration of the pose
-   * over time. This method takes in the current time as a parameter to calculate period (difference
-   * between two timestamps). The period is used to calculate the change in distance from a
-   * velocity. This also takes in an angle parameter which is used instead of the angular rate that
-   * is calculated from forward kinematics.
-   *
-   * @param currentTimeSeconds The current time in seconds.
-   * @param gyroAngle The angle reported by the gyroscope.
-   * @param moduleStates The current state of all swerve modules. Please provide the states in the
-   *     same order in which you instantiated your SwerveDriveKinematics.
-   * @return The new pose of the robot.
-   */
-  public Pose2d updateWithTime(
-      double currentTimeSeconds, Rotation2d gyroAngle, SwerveModuleState... moduleStates) {
-    double period = m_prevTimeSeconds >= 0 ? currentTimeSeconds - m_prevTimeSeconds : 0.0;
-    m_prevTimeSeconds = currentTimeSeconds;
-
-    var angle = gyroAngle.plus(m_gyroOffset);
-
-    var chassisState = m_kinematics.toChassisSpeeds(moduleStates);
-    var newPose =
-        m_poseMeters.exp(
-            new Twist2d(
-                chassisState.vxMetersPerSecond * period,
-                chassisState.vyMetersPerSecond * period,
-                angle.minus(m_previousAngle).getRadians()));
-
-    m_previousAngle = angle;
-    m_poseMeters = new Pose2d(newPose.getTranslation(), angle);
-
-    return m_poseMeters;
-  }
-
-  /**
-   * Updates the robot's position on the field using forward kinematics and integration of the pose
    * over time. This method automatically calculates the current time to calculate period
    * (difference between two timestamps). The period is used to calculate the change in distance
    * from a velocity. This also takes in an angle parameter which is used instead of the angular
    * rate that is calculated from forward kinematics.
    *
    * @param gyroAngle The angle reported by the gyroscope.
-   * @param moduleStates The current state of all swerve modules. Please provide the states in the
-   *     same order in which you instantiated your SwerveDriveKinematics.
+   * @param modulePositions The current position of all swerve modules. Please provide the positions
+   *     in the same order in which you instantiated your SwerveDriveKinematics.
    * @return The new pose of the robot.
    */
-  public Pose2d update(Rotation2d gyroAngle, SwerveModuleState... moduleStates) {
-    return updateWithTime(WPIUtilJNI.now() * 1.0e-6, gyroAngle, moduleStates);
+  public Pose2d update(Rotation2d gyroAngle, SwerveModulePosition[] modulePositions) {
+    if (modulePositions.length != m_numModules) {
+      throw new IllegalArgumentException(
+          "Number of modules is not consistent with number of wheel locations provided in "
+              + "constructor");
+    }
+
+    var moduleDeltas = new SwerveModulePosition[m_numModules];
+    for (int index = 0; index < m_numModules; index++) {
+      var current = modulePositions[index];
+      var previous = m_previousModulePositions[index];
+
+      moduleDeltas[index] =
+          new SwerveModulePosition(current.distanceMeters - previous.distanceMeters, current.angle);
+      previous.distanceMeters = current.distanceMeters;
+    }
+
+    var angle = gyroAngle.plus(m_gyroOffset);
+
+    var twist = m_kinematics.toTwist2d(moduleDeltas);
+    twist.dtheta = angle.minus(m_previousAngle).getRadians();
+
+    var newPose = m_poseMeters.exp(twist);
+
+    m_previousAngle = angle;
+    m_poseMeters = new Pose2d(newPose.getTranslation(), angle);
+
+    return m_poseMeters;
   }
 }
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveModulePosition.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveModulePosition.java
new file mode 100644
index 0000000..cdd7834
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveModulePosition.java
@@ -0,0 +1,62 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.math.kinematics;
+
+import edu.wpi.first.math.geometry.Rotation2d;
+import java.util.Objects;
+
+/** Represents the state of one swerve module. */
+public class SwerveModulePosition implements Comparable<SwerveModulePosition> {
+  /** Distance measured by the wheel of the module. */
+  public double distanceMeters;
+
+  /** Angle of the module. */
+  public Rotation2d angle = Rotation2d.fromDegrees(0);
+
+  /** Constructs a SwerveModulePosition with zeros for distance and angle. */
+  public SwerveModulePosition() {}
+
+  /**
+   * Constructs a SwerveModulePosition.
+   *
+   * @param distanceMeters The distance measured by the wheel of the module.
+   * @param angle The angle of the module.
+   */
+  public SwerveModulePosition(double distanceMeters, Rotation2d angle) {
+    this.distanceMeters = distanceMeters;
+    this.angle = angle;
+  }
+
+  @Override
+  public boolean equals(Object obj) {
+    if (obj instanceof SwerveModulePosition) {
+      return Double.compare(distanceMeters, ((SwerveModulePosition) obj).distanceMeters) == 0;
+    }
+    return false;
+  }
+
+  @Override
+  public int hashCode() {
+    return Objects.hash(distanceMeters);
+  }
+
+  /**
+   * Compares two swerve module positions. One swerve module is "greater" than the other if its
+   * distance is higher than the other.
+   *
+   * @param other The other swerve module.
+   * @return 1 if this is greater, 0 if both are equal, -1 if other is greater.
+   */
+  @Override
+  public int compareTo(SwerveModulePosition other) {
+    return Double.compare(this.distanceMeters, other.distanceMeters);
+  }
+
+  @Override
+  public String toString() {
+    return String.format(
+        "SwerveModulePosition(Distance: %.2f m, Angle: %s)", distanceMeters, angle);
+  }
+}
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveModuleState.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveModuleState.java
index 6a9c48c..ec7fd9f 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveModuleState.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveModuleState.java
@@ -8,7 +8,6 @@
 import java.util.Objects;
 
 /** Represents the state of one swerve module. */
-@SuppressWarnings("MemberName")
 public class SwerveModuleState implements Comparable<SwerveModuleState> {
   /** Speed of the wheel of the module. */
   public double speedMetersPerSecond;
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/spline/CubicHermiteSpline.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/spline/CubicHermiteSpline.java
index 9bbeaf6..6e13039 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/spline/CubicHermiteSpline.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/spline/CubicHermiteSpline.java
@@ -19,7 +19,6 @@
    * @param yInitialControlVector The control vector for the initial point in the y dimension.
    * @param yFinalControlVector The control vector for the final point in the y dimension.
    */
-  @SuppressWarnings("ParameterName")
   public CubicHermiteSpline(
       double[] xInitialControlVector,
       double[] xFinalControlVector,
@@ -81,25 +80,25 @@
   private SimpleMatrix makeHermiteBasis() {
     if (hermiteBasis == null) {
       // Given P(i), P'(i), P(i+1), P'(i+1), the control vectors, we want to find
-      // the coefficients of the spline P(t) = a3 * t^3 + a2 * t^2 + a1 * t + a0.
+      // the coefficients of the spline P(t) = a₃t³ + a₂t² + a₁t + a₀.
       //
-      // P(i)    = P(0)  = a0
-      // P'(i)   = P'(0) = a1
-      // P(i+1)  = P(1)  = a3 + a2 + a1 + a0
-      // P'(i+1) = P'(1) = 3 * a3 + 2 * a2 + a1
+      // P(i)    = P(0)  = a₀
+      // P'(i)   = P'(0) = a₁
+      // P(i+1)  = P(1)  = a₃ + a₂ + a₁ + a₀
+      // P'(i+1) = P'(1) = 3a₃ + 2a₂ + a₁
       //
-      // [ P(i)    ] = [ 0 0 0 1 ][ a3 ]
-      // [ P'(i)   ] = [ 0 0 1 0 ][ a2 ]
-      // [ P(i+1)  ] = [ 1 1 1 1 ][ a1 ]
-      // [ P'(i+1) ] = [ 3 2 1 0 ][ a0 ]
+      // [P(i)   ] = [0 0 0 1][a₃]
+      // [P'(i)  ] = [0 0 1 0][a₂]
+      // [P(i+1) ] = [1 1 1 1][a₁]
+      // [P'(i+1)] = [3 2 1 0][a₀]
       //
       // To solve for the coefficients, we can invert the 4x4 matrix and move it
       // to the other side of the equation.
       //
-      // [ a3 ] = [  2  1 -2  1 ][ P(i)    ]
-      // [ a2 ] = [ -3 -2  3 -1 ][ P'(i)   ]
-      // [ a1 ] = [  0  1  0  0 ][ P(i+1)  ]
-      // [ a0 ] = [  1  0  0  0 ][ P'(i+1) ]
+      // [a₃] = [ 2  1 -2  1][P(i)   ]
+      // [a₂] = [-3 -2  3 -1][P'(i)  ]
+      // [a₁] = [ 0  1  0  0][P(i+1) ]
+      // [a₀] = [ 1  0  0  0][P'(i+1)]
       hermiteBasis =
           new SimpleMatrix(
               4,
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/spline/PoseWithCurvature.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/spline/PoseWithCurvature.java
index 8bad7b1..30b3cae 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/spline/PoseWithCurvature.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/spline/PoseWithCurvature.java
@@ -7,7 +7,6 @@
 import edu.wpi.first.math.geometry.Pose2d;
 
 /** Represents a pair of a pose and a curvature. */
-@SuppressWarnings("MemberName")
 public class PoseWithCurvature {
   // Represents the pose.
   public Pose2d poseMeters;
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/spline/QuinticHermiteSpline.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/spline/QuinticHermiteSpline.java
index 4017044..be90999 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/spline/QuinticHermiteSpline.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/spline/QuinticHermiteSpline.java
@@ -19,7 +19,6 @@
    * @param yInitialControlVector The control vector for the initial point in the y dimension.
    * @param yFinalControlVector The control vector for the final point in the y dimension.
    */
-  @SuppressWarnings("ParameterName")
   public QuinticHermiteSpline(
       double[] xInitialControlVector,
       double[] xFinalControlVector,
@@ -80,33 +79,33 @@
    */
   private SimpleMatrix makeHermiteBasis() {
     if (hermiteBasis == null) {
-      // Given P(i), P'(i), P''(i), P(i+1), P'(i+1), P''(i+1), the control
-      // vectors, we want to find the coefficients of the spline
-      // P(t) = a5 * t^5 + a4 * t^4 + a3 * t^3 + a2 * t^2 + a1 * t + a0.
+      // Given P(i), P'(i), P"(i), P(i+1), P'(i+1), P"(i+1), the control vectors,
+      // we want to find the coefficients of the spline
+      // P(t) = a₅t⁵ + a₄t⁴ + a₃t³ + a₂t² + a₁t + a₀.
       //
-      // P(i)     = P(0)   = a0
-      // P'(i)    = P'(0)  = a1
-      // P''(i)   = P''(0) = 2 * a2
-      // P(i+1)   = P(1)   = a5 + a4 + a3 + a2 + a1 + a0
-      // P'(i+1)  = P'(1)  = 5 * a5 + 4 * a4 + 3 * a3 + 2 * a2 + a1
-      // P''(i+1) = P''(1) = 20 * a5 + 12 * a4 + 6 * a3 + 2 * a2
+      // P(i)    = P(0)  = a₀
+      // P'(i)   = P'(0) = a₁
+      // P''(i)  = P"(0) = 2a₂
+      // P(i+1)  = P(1)  = a₅ + a₄ + a₃ + a₂ + a₁ + a₀
+      // P'(i+1) = P'(1) = 5a₅ + 4a₄ + 3a₃ + 2a₂ + a₁
+      // P"(i+1) = P"(1) = 20a₅ + 12a₄ + 6a₃ + 2a₂
       //
-      // [ P(i)     ] = [  0  0  0  0  0  1 ][ a5 ]
-      // [ P'(i)    ] = [  0  0  0  0  1  0 ][ a4 ]
-      // [ P''(i)   ] = [  0  0  0  2  0  0 ][ a3 ]
-      // [ P(i+1)   ] = [  1  1  1  1  1  1 ][ a2 ]
-      // [ P'(i+1)  ] = [  5  4  3  2  1  0 ][ a1 ]
-      // [ P''(i+1) ] = [ 20 12  6  2  0  0 ][ a0 ]
+      // [P(i)   ] = [ 0  0  0  0  0  1][a₅]
+      // [P'(i)  ] = [ 0  0  0  0  1  0][a₄]
+      // [P"(i)  ] = [ 0  0  0  2  0  0][a₃]
+      // [P(i+1) ] = [ 1  1  1  1  1  1][a₂]
+      // [P'(i+1)] = [ 5  4  3  2  1  0][a₁]
+      // [P"(i+1)] = [20 12  6  2  0  0][a₀]
       //
       // To solve for the coefficients, we can invert the 6x6 matrix and move it
       // to the other side of the equation.
       //
-      // [ a5 ] = [  -6.0  -3.0  -0.5   6.0  -3.0   0.5 ][ P(i)     ]
-      // [ a4 ] = [  15.0   8.0   1.5 -15.0   7.0  -1.0 ][ P'(i)    ]
-      // [ a3 ] = [ -10.0  -6.0  -1.5  10.0  -4.0   0.5 ][ P''(i)   ]
-      // [ a2 ] = [   0.0   0.0   0.5   0.0   0.0   0.0 ][ P(i+1)   ]
-      // [ a1 ] = [   0.0   1.0   0.0   0.0   0.0   0.0 ][ P'(i+1)  ]
-      // [ a0 ] = [   1.0   0.0   0.0   0.0   0.0   0.0 ][ P''(i+1) ]
+      // [a₅] = [ -6.0  -3.0  -0.5   6.0  -3.0   0.5][P(i)   ]
+      // [a₄] = [ 15.0   8.0   1.5 -15.0   7.0  -1.0][P'(i)  ]
+      // [a₃] = [-10.0  -6.0  -1.5  10.0  -4.0   0.5][P"(i)  ]
+      // [a₂] = [  0.0   0.0   0.5   0.0   0.0   0.0][P(i+1) ]
+      // [a₁] = [  0.0   1.0   0.0   0.0   0.0   0.0][P'(i+1)]
+      // [a₀] = [  1.0   0.0   0.0   0.0   0.0   0.0][P"(i+1)]
       hermiteBasis =
           new SimpleMatrix(
               6,
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/spline/Spline.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/spline/Spline.java
index 5451eea..83b35f3 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/spline/Spline.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/spline/Spline.java
@@ -35,7 +35,6 @@
    * @param t The point t
    * @return The pose and curvature at that point.
    */
-  @SuppressWarnings("ParameterName")
   public PoseWithCurvature getPoint(double t) {
     SimpleMatrix polynomialBases = new SimpleMatrix(m_degree + 1, 1);
     final var coefficients = getCoefficients();
@@ -46,7 +45,7 @@
     }
 
     // This simply multiplies by the coefficients. We need to divide out t some
-    // n number of times where n is the derivative we want to take.
+    // n number of times when n is the derivative we want to take.
     SimpleMatrix combined = coefficients.mult(polynomialBases);
 
     // Get x and y
@@ -85,7 +84,6 @@
    * <p>Each element in each array represents the value of the derivative at the index. For example,
    * the value of x[2] is the second derivative in the x dimension.
    */
-  @SuppressWarnings("MemberName")
   public static class ControlVector {
     public double[] x;
     public double[] y;
@@ -96,7 +94,6 @@
      * @param x The x dimension of the control vector.
      * @param y The y dimension of the control vector.
      */
-    @SuppressWarnings("ParameterName")
     public ControlVector(double[] x, double[] y) {
       this.x = Arrays.copyOf(x, x.length);
       this.y = Arrays.copyOf(y, y.length);
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/spline/SplineHelper.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/spline/SplineHelper.java
index e5c67f8..651b028 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/spline/SplineHelper.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/spline/SplineHelper.java
@@ -46,7 +46,7 @@
    * Returns quintic splines from a set of waypoints.
    *
    * @param waypoints The waypoints
-   * @return List of splines.
+   * @return array of splines.
    */
   public static QuinticHermiteSpline[] getQuinticSplinesFromWaypoints(List<Pose2d> waypoints) {
     QuinticHermiteSpline[] splines = new QuinticHermiteSpline[waypoints.size() - 1];
@@ -78,7 +78,6 @@
    * @return A vector of cubic hermite splines that interpolate through the provided waypoints and
    *     control vectors.
    */
-  @SuppressWarnings("LocalVariableName")
   public static CubicHermiteSpline[] getCubicSplinesFromControlVectors(
       Spline.ControlVector start, Translation2d[] waypoints, Spline.ControlVector end) {
     CubicHermiteSpline[] splines = new CubicHermiteSpline[waypoints.length + 1];
@@ -202,7 +201,6 @@
    * @param controlVectors The control vectors.
    * @return A vector of quintic hermite splines that interpolate through the provided waypoints.
    */
-  @SuppressWarnings("LocalVariableName")
   public static QuinticHermiteSpline[] getQuinticSplinesFromControlVectors(
       Spline.ControlVector[] controlVectors) {
     QuinticHermiteSpline[] splines = new QuinticHermiteSpline[controlVectors.length - 1];
@@ -228,7 +226,6 @@
    * @param d the vector on the rhs
    * @param solutionVector the unknown (solution) vector, modified in-place
    */
-  @SuppressWarnings({"ParameterName", "LocalVariableName"})
   private static void thomasAlgorithm(
       double[] a, double[] b, double[] c, double[] d, double[] solutionVector) {
     int N = d.length;
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/spline/SplineParameterizer.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/spline/SplineParameterizer.java
index 88afc6d..c1a87f2 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/spline/SplineParameterizer.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/spline/SplineParameterizer.java
@@ -46,7 +46,6 @@
    */
   private static final int kMaxIterations = 5000;
 
-  @SuppressWarnings("MemberName")
   private static class StackContents {
     final double t1;
     final double t0;
@@ -57,7 +56,6 @@
     }
   }
 
-  @SuppressWarnings("serial")
   public static class MalformedSplineException extends RuntimeException {
     /**
      * Create a new exception with the given message.
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/system/Discretization.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/system/Discretization.java
index ffbd99e..1871803 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/system/Discretization.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/system/Discretization.java
@@ -9,7 +9,6 @@
 import edu.wpi.first.math.Pair;
 import org.ejml.simple.SimpleMatrix;
 
-@SuppressWarnings({"ParameterName", "MethodTypeParameterName"})
 public final class Discretization {
   private Discretization() {
     // Utility class
@@ -25,6 +24,7 @@
    */
   public static <States extends Num> Matrix<States, States> discretizeA(
       Matrix<States, States> contA, double dtSeconds) {
+    // A_d = eᴬᵀ
     return contA.times(dtSeconds).exp();
   }
 
@@ -38,24 +38,26 @@
    * @param dtSeconds Discretization timestep.
    * @return a Pair representing discA and diskB.
    */
-  @SuppressWarnings("LocalVariableName")
   public static <States extends Num, Inputs extends Num>
       Pair<Matrix<States, States>, Matrix<States, Inputs>> discretizeAB(
           Matrix<States, States> contA, Matrix<States, Inputs> contB, double dtSeconds) {
-    var scaledA = contA.times(dtSeconds);
-    var scaledB = contB.times(dtSeconds);
-
     int states = contA.getNumRows();
     int inputs = contB.getNumCols();
+
+    // M = [A  B]
+    //     [0  0]
     var M = new Matrix<>(new SimpleMatrix(states + inputs, states + inputs));
-    M.assignBlock(0, 0, scaledA);
-    M.assignBlock(0, scaledA.getNumCols(), scaledB);
-    var phi = M.exp();
+    M.assignBlock(0, 0, contA);
+    M.assignBlock(0, contA.getNumCols(), contB);
+
+    //  ϕ = eᴹᵀ = [A_d  B_d]
+    //            [ 0    I ]
+    var phi = M.times(dtSeconds).exp();
 
     var discA = new Matrix<States, States>(new SimpleMatrix(states, states));
-    var discB = new Matrix<States, Inputs>(new SimpleMatrix(states, inputs));
-
     discA.extractFrom(0, 0, phi);
+
+    var discB = new Matrix<States, Inputs>(new SimpleMatrix(states, inputs));
     discB.extractFrom(0, contB.getNumRows(), phi);
 
     return new Pair<>(discA, discB);
@@ -70,7 +72,6 @@
    * @param dtSeconds Discretization timestep.
    * @return a pair representing the discrete system matrix and process noise covariance matrix.
    */
-  @SuppressWarnings("LocalVariableName")
   public static <States extends Num>
       Pair<Matrix<States, States>, Matrix<States, States>> discretizeAQ(
           Matrix<States, States> contA, Matrix<States, States> contQ, double dtSeconds) {
@@ -79,18 +80,22 @@
     // Make continuous Q symmetric if it isn't already
     Matrix<States, States> Q = contQ.plus(contQ.transpose()).div(2.0);
 
-    // Set up the matrix M = [[-A, Q], [0, A.T]]
+    // M = [−A  Q ]
+    //     [ 0  Aᵀ]
     final var M = new Matrix<>(new SimpleMatrix(2 * states, 2 * states));
     M.assignBlock(0, 0, contA.times(-1.0));
     M.assignBlock(0, states, Q);
     M.assignBlock(states, 0, new Matrix<>(new SimpleMatrix(states, states)));
     M.assignBlock(states, states, contA.transpose());
 
+    // ϕ = eᴹᵀ = [−A_d  A_d⁻¹Q_d]
+    //           [ 0      A_dᵀ  ]
     final var phi = M.times(dtSeconds).exp();
 
-    // Phi12 = phi[0:States,        States:2*States]
-    // Phi22 = phi[States:2*States, States:2*States]
+    // ϕ₁₂ = A_d⁻¹Q_d
     final Matrix<States, States> phi12 = phi.block(states, states, 0, states);
+
+    // ϕ₂₂ = A_dᵀ
     final Matrix<States, States> phi22 = phi.block(states, states, states, states);
 
     final var discA = phi22.transpose();
@@ -109,9 +114,12 @@
    * <p>Rather than solving a 2N x 2N matrix exponential like in DiscretizeQ() (which is expensive),
    * we take advantage of the structure of the block matrix of A and Q.
    *
-   * <p>The exponential of A*t, which is only N x N, is relatively cheap. 2) The upper-right quarter
-   * of the 2N x 2N matrix, which we can approximate using a taylor series to several terms and
-   * still be substantially cheaper than taking the big exponential.
+   * <ul>
+   *   <li>eᴬᵀ, which is only N x N, is relatively cheap.
+   *   <li>The upper-right quarter of the 2N x 2N matrix, which we can approximate using a taylor
+   *       series to several terms and still be substantially cheaper than taking the big
+   *       exponential.
+   * </ul>
    *
    * @param <States> Nat representing the number of states.
    * @param contA Continuous system matrix.
@@ -119,10 +127,44 @@
    * @param dtSeconds Discretization timestep.
    * @return a pair representing the discrete system matrix and process noise covariance matrix.
    */
-  @SuppressWarnings("LocalVariableName")
   public static <States extends Num>
       Pair<Matrix<States, States>, Matrix<States, States>> discretizeAQTaylor(
           Matrix<States, States> contA, Matrix<States, States> contQ, double dtSeconds) {
+    //       T
+    // Q_d = ∫ e^(Aτ) Q e^(Aᵀτ) dτ
+    //       0
+    //
+    // M = [−A  Q ]
+    //     [ 0  Aᵀ]
+    // ϕ = eᴹᵀ
+    // ϕ₁₂ = A_d⁻¹Q_d
+    //
+    // Taylor series of ϕ:
+    //
+    //   ϕ = eᴹᵀ = I + MT + 1/2 M²T² + 1/6 M³T³ + …
+    //   ϕ = eᴹᵀ = I + MT + 1/2 T²M² + 1/6 T³M³ + …
+    //
+    // Taylor series of ϕ expanded for ϕ₁₂:
+    //
+    //   ϕ₁₂ = 0 + QT + 1/2 T² (−AQ + QAᵀ) + 1/6 T³ (−A lastTerm + Q Aᵀ²) + …
+    //
+    // ```
+    // lastTerm = Q
+    // lastCoeff = T
+    // ATn = Aᵀ
+    // ϕ₁₂ = lastTerm lastCoeff = QT
+    //
+    // for i in range(2, 6):
+    //   // i = 2
+    //   lastTerm = −A lastTerm + Q ATn = −AQ + QAᵀ
+    //   lastCoeff *= T/i → lastCoeff *= T/2 = 1/2 T²
+    //   ATn *= Aᵀ = Aᵀ²
+    //
+    //   // i = 3
+    //   lastTerm = −A lastTerm + Q ATn = −A (−AQ + QAᵀ) + QAᵀ² = …
+    //   …
+    // ```
+
     // Make continuous Q symmetric if it isn't already
     Matrix<States, States> Q = contQ.plus(contQ.transpose()).div(2.0);
 
@@ -130,17 +172,18 @@
     double lastCoeff = dtSeconds;
 
     // Aᵀⁿ
-    Matrix<States, States> Atn = contA.transpose();
+    Matrix<States, States> ATn = contA.transpose();
+
     Matrix<States, States> phi12 = lastTerm.times(lastCoeff);
 
     // i = 6 i.e. 5th order should be enough precision
     for (int i = 2; i < 6; ++i) {
-      lastTerm = contA.times(-1).times(lastTerm).plus(Q.times(Atn));
+      lastTerm = contA.times(-1).times(lastTerm).plus(Q.times(ATn));
       lastCoeff *= dtSeconds / ((double) i);
 
       phi12 = phi12.plus(lastTerm.times(lastCoeff));
 
-      Atn = Atn.times(contA.transpose());
+      ATn = ATn.times(contA.transpose());
     }
 
     var discA = discretizeA(contA, dtSeconds);
@@ -157,11 +200,12 @@
    * Note that dt=0.0 divides R by zero.
    *
    * @param <O> Nat representing the number of outputs.
-   * @param R Continuous measurement noise covariance matrix.
+   * @param contR Continuous measurement noise covariance matrix.
    * @param dtSeconds Discretization timestep.
    * @return Discretized version of the provided continuous measurement noise covariance matrix.
    */
-  public static <O extends Num> Matrix<O, O> discretizeR(Matrix<O, O> R, double dtSeconds) {
-    return R.div(dtSeconds);
+  public static <O extends Num> Matrix<O, O> discretizeR(Matrix<O, O> contR, double dtSeconds) {
+    // R_d = 1/T R
+    return contR.div(dtSeconds);
   }
 }
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/system/LinearSystem.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/system/LinearSystem.java
index 9e35cfd..d7b6602 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/system/LinearSystem.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/system/LinearSystem.java
@@ -8,76 +8,70 @@
 import edu.wpi.first.math.Num;
 import edu.wpi.first.math.numbers.N1;
 
-@SuppressWarnings("ClassTypeParameterName")
 public class LinearSystem<States extends Num, Inputs extends Num, Outputs extends Num> {
   /** Continuous system matrix. */
-  @SuppressWarnings("MemberName")
   private final Matrix<States, States> m_A;
 
   /** Continuous input matrix. */
-  @SuppressWarnings("MemberName")
   private final Matrix<States, Inputs> m_B;
 
   /** Output matrix. */
-  @SuppressWarnings("MemberName")
   private final Matrix<Outputs, States> m_C;
 
   /** Feedthrough matrix. */
-  @SuppressWarnings("MemberName")
   private final Matrix<Outputs, Inputs> m_D;
 
   /**
    * Construct a new LinearSystem from the four system matrices.
    *
-   * @param a The system matrix A.
-   * @param b The input matrix B.
-   * @param c The output matrix C.
-   * @param d The feedthrough matrix D.
+   * @param A The system matrix A.
+   * @param B The input matrix B.
+   * @param C The output matrix C.
+   * @param D The feedthrough matrix D.
    * @throws IllegalArgumentException if any matrix element isn't finite.
    */
-  @SuppressWarnings("ParameterName")
   public LinearSystem(
-      Matrix<States, States> a,
-      Matrix<States, Inputs> b,
-      Matrix<Outputs, States> c,
-      Matrix<Outputs, Inputs> d) {
-    for (int row = 0; row < a.getNumRows(); ++row) {
-      for (int col = 0; col < a.getNumCols(); ++col) {
-        if (!Double.isFinite(a.get(row, col))) {
+      Matrix<States, States> A,
+      Matrix<States, Inputs> B,
+      Matrix<Outputs, States> C,
+      Matrix<Outputs, Inputs> D) {
+    for (int row = 0; row < A.getNumRows(); ++row) {
+      for (int col = 0; col < A.getNumCols(); ++col) {
+        if (!Double.isFinite(A.get(row, col))) {
           throw new IllegalArgumentException(
               "Elements of A aren't finite. This is usually due to model implementation errors.");
         }
       }
     }
-    for (int row = 0; row < b.getNumRows(); ++row) {
-      for (int col = 0; col < b.getNumCols(); ++col) {
-        if (!Double.isFinite(b.get(row, col))) {
+    for (int row = 0; row < B.getNumRows(); ++row) {
+      for (int col = 0; col < B.getNumCols(); ++col) {
+        if (!Double.isFinite(B.get(row, col))) {
           throw new IllegalArgumentException(
               "Elements of B aren't finite. This is usually due to model implementation errors.");
         }
       }
     }
-    for (int row = 0; row < c.getNumRows(); ++row) {
-      for (int col = 0; col < c.getNumCols(); ++col) {
-        if (!Double.isFinite(c.get(row, col))) {
+    for (int row = 0; row < C.getNumRows(); ++row) {
+      for (int col = 0; col < C.getNumCols(); ++col) {
+        if (!Double.isFinite(C.get(row, col))) {
           throw new IllegalArgumentException(
               "Elements of C aren't finite. This is usually due to model implementation errors.");
         }
       }
     }
-    for (int row = 0; row < d.getNumRows(); ++row) {
-      for (int col = 0; col < d.getNumCols(); ++col) {
-        if (!Double.isFinite(d.get(row, col))) {
+    for (int row = 0; row < D.getNumRows(); ++row) {
+      for (int col = 0; col < D.getNumCols(); ++col) {
+        if (!Double.isFinite(D.get(row, col))) {
           throw new IllegalArgumentException(
               "Elements of D aren't finite. This is usually due to model implementation errors.");
         }
       }
     }
 
-    this.m_A = a;
-    this.m_B = b;
-    this.m_C = c;
-    this.m_D = d;
+    this.m_A = A;
+    this.m_B = B;
+    this.m_C = C;
+    this.m_D = D;
   }
 
   /**
@@ -170,7 +164,6 @@
    * @param dtSeconds Timestep for model update.
    * @return the updated x.
    */
-  @SuppressWarnings("ParameterName")
   public Matrix<States, N1> calculateX(
       Matrix<States, N1> x, Matrix<Inputs, N1> clampedU, double dtSeconds) {
     var discABpair = Discretization.discretizeAB(m_A, m_B, dtSeconds);
@@ -187,7 +180,6 @@
    * @param clampedU The control input.
    * @return the updated output matrix Y.
    */
-  @SuppressWarnings("ParameterName")
   public Matrix<Outputs, N1> calculateY(Matrix<States, N1> x, Matrix<Inputs, N1> clampedU) {
     return m_C.times(x).plus(m_D.times(clampedU));
   }
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/system/LinearSystemLoop.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/system/LinearSystemLoop.java
index dcd4e58..02b1da0 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/system/LinearSystemLoop.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/system/LinearSystemLoop.java
@@ -21,14 +21,13 @@
  *
  * <p>For everything in this file, "inputs" and "outputs" are defined from the perspective of the
  * plant. This means U is an input and Y is an output (because you give the plant U (powers) and it
- * gives you back a Y (sensor values). This is the opposite of what they mean from the perspective
+ * gives you back a Y (sensor values)). This is the opposite of what they mean from the perspective
  * of the controller (U is an output because that's what goes to the motors and Y is an input
  * because that's what comes back from the sensors).
  *
  * <p>For more on the underlying math, read
  * https://file.tavsys.net/control/controls-engineering-in-frc.pdf.
  */
-@SuppressWarnings("ClassTypeParameterName")
 public class LinearSystemLoop<States extends Num, Inputs extends Num, Outputs extends Num> {
   private final LinearQuadraticRegulator<States, Inputs, Outputs> m_controller;
   private final LinearPlantInversionFeedforward<States, Inputs, Outputs> m_feedforward;
@@ -315,7 +314,6 @@
    *
    * @param y Measurement vector.
    */
-  @SuppressWarnings("ParameterName")
   public void correct(Matrix<Outputs, N1> y) {
     getObserver().correct(getU(), y);
   }
@@ -327,7 +325,6 @@
    *
    * @param dtSeconds Timestep for model update.
    */
-  @SuppressWarnings("LocalVariableName")
   public void predict(double dtSeconds) {
     var u =
         clampInput(
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/system/NumericalIntegration.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/system/NumericalIntegration.java
index 274b10a..94be369 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/system/NumericalIntegration.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/system/NumericalIntegration.java
@@ -24,7 +24,7 @@
    * @param dtSeconds The time over which to integrate.
    * @return the integration of dx/dt = f(x) for dt.
    */
-  @SuppressWarnings("ParameterName")
+  @SuppressWarnings("overloads")
   public static double rk4(DoubleFunction<Double> f, double x, double dtSeconds) {
     final var h = dtSeconds;
     final var k1 = f.apply(x);
@@ -44,7 +44,7 @@
    * @param dtSeconds The time over which to integrate.
    * @return The result of Runge Kutta integration (4th order).
    */
-  @SuppressWarnings("ParameterName")
+  @SuppressWarnings("overloads")
   public static double rk4(
       BiFunction<Double, Double, Double> f, double x, Double u, double dtSeconds) {
     final var h = dtSeconds;
@@ -68,7 +68,7 @@
    * @param dtSeconds The time over which to integrate.
    * @return the integration of dx/dt = f(x, u) for dt.
    */
-  @SuppressWarnings({"ParameterName", "MethodTypeParameterName"})
+  @SuppressWarnings("overloads")
   public static <States extends Num, Inputs extends Num> Matrix<States, N1> rk4(
       BiFunction<Matrix<States, N1>, Matrix<Inputs, N1>, Matrix<States, N1>> f,
       Matrix<States, N1> x,
@@ -93,7 +93,7 @@
    * @param dtSeconds The time over which to integrate.
    * @return 4th order Runge-Kutta integration of dx/dt = f(x) for dt.
    */
-  @SuppressWarnings({"ParameterName", "MethodTypeParameterName"})
+  @SuppressWarnings("overloads")
   public static <States extends Num> Matrix<States, N1> rk4(
       Function<Matrix<States, N1>, Matrix<States, N1>> f, Matrix<States, N1> x, double dtSeconds) {
     final var h = dtSeconds;
@@ -107,139 +107,6 @@
   }
 
   /**
-   * Performs adaptive RKF45 integration of dx/dt = f(x, u) for dt, as described in
-   * https://en.wikipedia.org/wiki/Runge%E2%80%93Kutta%E2%80%93Fehlberg_method. By default, the max
-   * error is 1e-6.
-   *
-   * @param <States> A Num representing the states of the system to integrate.
-   * @param <Inputs> A Num representing the inputs of the system to integrate.
-   * @param f The function to integrate. It must take two arguments x and u.
-   * @param x The initial value of x.
-   * @param u The value u held constant over the integration period.
-   * @param dtSeconds The time over which to integrate.
-   * @return the integration of dx/dt = f(x, u) for dt.
-   */
-  @SuppressWarnings("MethodTypeParameterName")
-  public static <States extends Num, Inputs extends Num> Matrix<States, N1> rkf45(
-      BiFunction<Matrix<States, N1>, Matrix<Inputs, N1>, Matrix<States, N1>> f,
-      Matrix<States, N1> x,
-      Matrix<Inputs, N1> u,
-      double dtSeconds) {
-    return rkf45(f, x, u, dtSeconds, 1e-6);
-  }
-
-  /**
-   * Performs adaptive RKF45 integration of dx/dt = f(x, u) for dt, as described in
-   * https://en.wikipedia.org/wiki/Runge%E2%80%93Kutta%E2%80%93Fehlberg_method
-   *
-   * @param <States> A Num representing the states of the system to integrate.
-   * @param <Inputs> A Num representing the inputs of the system to integrate.
-   * @param f The function to integrate. It must take two arguments x and u.
-   * @param x The initial value of x.
-   * @param u The value u held constant over the integration period.
-   * @param dtSeconds The time over which to integrate.
-   * @param maxError The maximum acceptable truncation error. Usually a small number like 1e-6.
-   * @return the integration of dx/dt = f(x, u) for dt.
-   */
-  @SuppressWarnings("MethodTypeParameterName")
-  public static <States extends Num, Inputs extends Num> Matrix<States, N1> rkf45(
-      BiFunction<Matrix<States, N1>, Matrix<Inputs, N1>, Matrix<States, N1>> f,
-      Matrix<States, N1> x,
-      Matrix<Inputs, N1> u,
-      double dtSeconds,
-      double maxError) {
-    // See
-    // https://en.wikipedia.org/wiki/Runge%E2%80%93Kutta%E2%80%93Fehlberg_method
-    // for the Butcher tableau the following arrays came from.
-
-    // final double[5][5]
-    final double[][] A = {
-      {1.0 / 4.0},
-      {3.0 / 32.0, 9.0 / 32.0},
-      {1932.0 / 2197.0, -7200.0 / 2197.0, 7296.0 / 2197.0},
-      {439.0 / 216.0, -8.0, 3680.0 / 513.0, -845.0 / 4104.0},
-      {-8.0 / 27.0, 2.0, -3544.0 / 2565.0, 1859.0 / 4104.0, -11.0 / 40.0}
-    };
-
-    // final double[6]
-    final double[] b1 = {
-      16.0 / 135.0, 0.0, 6656.0 / 12825.0, 28561.0 / 56430.0, -9.0 / 50.0, 2.0 / 55.0
-    };
-
-    // final double[6]
-    final double[] b2 = {25.0 / 216.0, 0.0, 1408.0 / 2565.0, 2197.0 / 4104.0, -1.0 / 5.0, 0.0};
-
-    Matrix<States, N1> newX;
-    double truncationError;
-
-    double dtElapsed = 0.0;
-    double h = dtSeconds;
-
-    // Loop until we've gotten to our desired dt
-    while (dtElapsed < dtSeconds) {
-      do {
-        // Only allow us to advance up to the dt remaining
-        h = Math.min(h, dtSeconds - dtElapsed);
-
-        // Notice how the derivative in the Wikipedia notation is dy/dx.
-        // That means their y is our x and their x is our t
-        var k1 = f.apply(x, u);
-        var k2 = f.apply(x.plus(k1.times(A[0][0]).times(h)), u);
-        var k3 = f.apply(x.plus(k1.times(A[1][0]).plus(k2.times(A[1][1])).times(h)), u);
-        var k4 =
-            f.apply(
-                x.plus(k1.times(A[2][0]).plus(k2.times(A[2][1])).plus(k3.times(A[2][2])).times(h)),
-                u);
-        var k5 =
-            f.apply(
-                x.plus(
-                    k1.times(A[3][0])
-                        .plus(k2.times(A[3][1]))
-                        .plus(k3.times(A[3][2]))
-                        .plus(k4.times(A[3][3]))
-                        .times(h)),
-                u);
-        var k6 =
-            f.apply(
-                x.plus(
-                    k1.times(A[4][0])
-                        .plus(k2.times(A[4][1]))
-                        .plus(k3.times(A[4][2]))
-                        .plus(k4.times(A[4][3]))
-                        .plus(k5.times(A[4][4]))
-                        .times(h)),
-                u);
-
-        newX =
-            x.plus(
-                k1.times(b1[0])
-                    .plus(k2.times(b1[1]))
-                    .plus(k3.times(b1[2]))
-                    .plus(k4.times(b1[3]))
-                    .plus(k5.times(b1[4]))
-                    .plus(k6.times(b1[5]))
-                    .times(h));
-        truncationError =
-            (k1.times(b1[0] - b2[0])
-                    .plus(k2.times(b1[1] - b2[1]))
-                    .plus(k3.times(b1[2] - b2[2]))
-                    .plus(k4.times(b1[3] - b2[3]))
-                    .plus(k5.times(b1[4] - b2[4]))
-                    .plus(k6.times(b1[5] - b2[5]))
-                    .times(h))
-                .normF();
-
-        h *= 0.9 * Math.pow(maxError / truncationError, 1.0 / 5.0);
-      } while (truncationError > maxError);
-
-      dtElapsed += h;
-      x = newX;
-    }
-
-    return x;
-  }
-
-  /**
    * Performs adaptive Dormand-Prince integration of dx/dt = f(x, u) for dt. By default, the max
    * error is 1e-6.
    *
@@ -251,7 +118,7 @@
    * @param dtSeconds The time over which to integrate.
    * @return the integration of dx/dt = f(x, u) for dt.
    */
-  @SuppressWarnings("MethodTypeParameterName")
+  @SuppressWarnings("overloads")
   public static <States extends Num, Inputs extends Num> Matrix<States, N1> rkdp(
       BiFunction<Matrix<States, N1>, Matrix<Inputs, N1>, Matrix<States, N1>> f,
       Matrix<States, N1> x,
@@ -272,7 +139,7 @@
    * @param maxError The maximum acceptable truncation error. Usually a small number like 1e-6.
    * @return the integration of dx/dt = f(x, u) for dt.
    */
-  @SuppressWarnings("MethodTypeParameterName")
+  @SuppressWarnings("overloads")
   public static <States extends Num, Inputs extends Num> Matrix<States, N1> rkdp(
       BiFunction<Matrix<States, N1>, Matrix<Inputs, N1>, Matrix<States, N1>> f,
       Matrix<States, N1> x,
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/system/NumericalJacobian.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/system/NumericalJacobian.java
index 6c2c896..43eba93 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/system/NumericalJacobian.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/system/NumericalJacobian.java
@@ -30,7 +30,6 @@
    * @param x Vector argument.
    * @return The numerical Jacobian with respect to x for f(x, u, ...).
    */
-  @SuppressWarnings({"ParameterName", "MethodTypeParameterName"})
   public static <Rows extends Num, Cols extends Num, States extends Num>
       Matrix<Rows, Cols> numericalJacobian(
           Nat<Rows> rows,
@@ -44,7 +43,6 @@
       var dxMinus = x.copy();
       dxPlus.set(i, 0, dxPlus.get(i, 0) + kEpsilon);
       dxMinus.set(i, 0, dxMinus.get(i, 0) - kEpsilon);
-      @SuppressWarnings("LocalVariableName")
       var dF = f.apply(dxPlus).minus(f.apply(dxMinus)).div(2 * kEpsilon);
 
       result.setColumn(i, Matrix.changeBoundsUnchecked(dF));
@@ -67,7 +65,6 @@
    * @param u Input vector.
    * @return The numerical Jacobian with respect to x for f(x, u, ...).
    */
-  @SuppressWarnings({"LambdaParameterName", "MethodTypeParameterName"})
   public static <Rows extends Num, States extends Num, Inputs extends Num, Outputs extends Num>
       Matrix<Rows, States> numericalJacobianX(
           Nat<Rows> rows,
@@ -91,7 +88,6 @@
    * @param u Input vector.
    * @return the numerical Jacobian with respect to u for f(x, u).
    */
-  @SuppressWarnings({"LambdaParameterName", "MethodTypeParameterName"})
   public static <Rows extends Num, States extends Num, Inputs extends Num>
       Matrix<Rows, Inputs> numericalJacobianU(
           Nat<Rows> rows,
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/system/plant/DCMotor.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/system/plant/DCMotor.java
index 94c117f..cd431f7 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/system/plant/DCMotor.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/system/plant/DCMotor.java
@@ -8,28 +8,13 @@
 
 /** Holds the constants for a DC motor. */
 public class DCMotor {
-  @SuppressWarnings("MemberName")
   public final double nominalVoltageVolts;
-
-  @SuppressWarnings("MemberName")
   public final double stallTorqueNewtonMeters;
-
-  @SuppressWarnings("MemberName")
   public final double stallCurrentAmps;
-
-  @SuppressWarnings("MemberName")
   public final double freeCurrentAmps;
-
-  @SuppressWarnings("MemberName")
   public final double freeSpeedRadPerSec;
-
-  @SuppressWarnings("MemberName")
   public final double rOhms;
-
-  @SuppressWarnings("MemberName")
   public final double KvRadPerSecPerVolt;
-
-  @SuppressWarnings("MemberName")
   public final double KtNMPerAmp;
 
   /**
@@ -64,7 +49,7 @@
   /**
    * Estimate the current being drawn by this motor.
    *
-   * @param speedRadiansPerSec The speed of the rotor.
+   * @param speedRadiansPerSec The speed of the motor.
    * @param voltageInputVolts The input voltage.
    * @return The estimated current.
    */
@@ -73,6 +58,54 @@
   }
 
   /**
+   * Calculate the torque produced by the motor for a given current.
+   *
+   * @param currentAmpere The current drawn by the motor.
+   * @return The torque produced.
+   */
+  public double getTorque(double currentAmpere) {
+    return currentAmpere * KtNMPerAmp;
+  }
+
+  /**
+   * Calculate the voltage provided to the motor at a given torque and angular velocity.
+   *
+   * @param torqueNm The torque produced by the motor.
+   * @param speedRadiansPerSec The speed of the motor.
+   * @return The voltage of the motor.
+   */
+  public double getVoltage(double torqueNm, double speedRadiansPerSec) {
+    return 1.0 / KvRadPerSecPerVolt * speedRadiansPerSec + 1.0 / KtNMPerAmp * rOhms * torqueNm;
+  }
+
+  /**
+   * Calculate the speed of the motor at a given torque and input voltage.
+   *
+   * @param torqueNm The torque produced by the motor.
+   * @param voltageInputVolts The voltage applied to the motor.
+   * @return The speed of the motor.
+   */
+  public double getSpeed(double torqueNm, double voltageInputVolts) {
+    return voltageInputVolts - 1.0 / KtNMPerAmp * torqueNm * rOhms * KvRadPerSecPerVolt;
+  }
+
+  /**
+   * Returns a copy of this motor with the given gearbox reduction applied.
+   *
+   * @param gearboxReduction The gearbox reduction.
+   * @return A motor with the gearbox reduction applied.
+   */
+  public DCMotor withReduction(double gearboxReduction) {
+    return new DCMotor(
+        nominalVoltageVolts,
+        stallTorqueNewtonMeters * gearboxReduction,
+        stallCurrentAmps,
+        freeCurrentAmps,
+        freeSpeedRadPerSec / gearboxReduction,
+        1);
+  }
+
+  /**
    * Return a gearbox of CIM motors.
    *
    * @param numMotors Number of motors in the gearbox.
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/system/plant/LinearSystemId.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/system/plant/LinearSystemId.java
index 1a05eb6..332e690 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/system/plant/LinearSystemId.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/system/plant/LinearSystemId.java
@@ -20,14 +20,13 @@
    * Create a state-space model of an elevator system. The states of the system are [position,
    * velocity]ᵀ, inputs are [voltage], and outputs are [position].
    *
-   * @param motor The motor (or gearbox) attached to the arm.
+   * @param motor The motor (or gearbox) attached to the carriage.
    * @param massKg The mass of the elevator carriage, in kilograms.
-   * @param radiusMeters The radius of thd driving drum of the elevator, in meters.
+   * @param radiusMeters The radius of the elevator's driving drum, in meters.
    * @param G The reduction between motor and drum, as a ratio of output to input.
    * @return A LinearSystem representing the given characterized constants.
    * @throws IllegalArgumentException if massKg &lt;= 0, radiusMeters &lt;= 0, or G &lt;= 0.
    */
-  @SuppressWarnings("ParameterName")
   public static LinearSystem<N2, N1, N1> createElevatorSystem(
       DCMotor motor, double massKg, double radiusMeters, double G) {
     if (massKg <= 0.0) {
@@ -63,15 +62,14 @@
    * velocity], inputs are [voltage], and outputs are [angular velocity].
    *
    * @param motor The motor (or gearbox) attached to the flywheel.
-   * @param jKgMetersSquared The moment of inertia J of the flywheel.
+   * @param JKgMetersSquared The moment of inertia J of the flywheel.
    * @param G The reduction between motor and drum, as a ratio of output to input.
    * @return A LinearSystem representing the given characterized constants.
-   * @throws IllegalArgumentException if jKgMetersSquared &lt;= 0 or G &lt;= 0.
+   * @throws IllegalArgumentException if JKgMetersSquared &lt;= 0 or G &lt;= 0.
    */
-  @SuppressWarnings("ParameterName")
   public static LinearSystem<N1, N1, N1> createFlywheelSystem(
-      DCMotor motor, double jKgMetersSquared, double G) {
-    if (jKgMetersSquared <= 0.0) {
+      DCMotor motor, double JKgMetersSquared, double G) {
+    if (JKgMetersSquared <= 0.0) {
       throw new IllegalArgumentException("J must be greater than zero.");
     }
     if (G <= 0.0) {
@@ -83,8 +81,8 @@
             -G
                 * G
                 * motor.KtNMPerAmp
-                / (motor.KvRadPerSecPerVolt * motor.rOhms * jKgMetersSquared)),
-        VecBuilder.fill(G * motor.KtNMPerAmp / (motor.rOhms * jKgMetersSquared)),
+                / (motor.KvRadPerSecPerVolt * motor.rOhms * JKgMetersSquared)),
+        VecBuilder.fill(G * motor.KtNMPerAmp / (motor.rOhms * JKgMetersSquared)),
         Matrix.eye(Nat.N1()),
         new Matrix<>(Nat.N1(), Nat.N1()));
   }
@@ -94,16 +92,15 @@
    * position, angular velocity], inputs are [voltage], and outputs are [angular position, angular
    * velocity].
    *
-   * @param motor The motor (or gearbox) attached to the DC motor.
-   * @param jKgMetersSquared The moment of inertia J of the DC motor.
+   * @param motor The motor (or gearbox) attached to system.
+   * @param JKgMetersSquared The moment of inertia J of the DC motor.
    * @param G The reduction between motor and drum, as a ratio of output to input.
    * @return A LinearSystem representing the given characterized constants.
-   * @throws IllegalArgumentException if jKgMetersSquared &lt;= 0 or G &lt;= 0.
+   * @throws IllegalArgumentException if JKgMetersSquared &lt;= 0 or G &lt;= 0.
    */
-  @SuppressWarnings("ParameterName")
   public static LinearSystem<N2, N1, N2> createDCMotorSystem(
-      DCMotor motor, double jKgMetersSquared, double G) {
-    if (jKgMetersSquared <= 0.0) {
+      DCMotor motor, double JKgMetersSquared, double G) {
+    if (JKgMetersSquared <= 0.0) {
       throw new IllegalArgumentException("J must be greater than zero.");
     }
     if (G <= 0.0) {
@@ -119,26 +116,26 @@
                 -G
                     * G
                     * motor.KtNMPerAmp
-                    / (motor.KvRadPerSecPerVolt * motor.rOhms * jKgMetersSquared)),
-        VecBuilder.fill(0, G * motor.KtNMPerAmp / (motor.rOhms * jKgMetersSquared)),
+                    / (motor.KvRadPerSecPerVolt * motor.rOhms * JKgMetersSquared)),
+        VecBuilder.fill(0, G * motor.KtNMPerAmp / (motor.rOhms * JKgMetersSquared)),
         Matrix.eye(Nat.N2()),
         new Matrix<>(Nat.N2(), Nat.N1()));
   }
 
   /**
    * Create a state-space model of a differential drive drivetrain. In this model, the states are
-   * [v_left, v_right]ᵀ, inputs are [V_left, V_right]ᵀ and outputs are [v_left, v_right]ᵀ.
+   * [left velocity, right velocity]ᵀ, inputs are [left voltage, right voltage]ᵀ, and outputs are
+   * [left velocity, right velocity]ᵀ.
    *
-   * @param motor the gearbox representing the motors driving the drivetrain.
-   * @param massKg the mass of the robot.
-   * @param rMeters the radius of the wheels in meters.
-   * @param rbMeters the radius of the base (half the track width) in meters.
-   * @param JKgMetersSquared the moment of inertia of the robot.
-   * @param G the gearing reduction as output over input.
+   * @param motor The motor (or gearbox) driving the drivetrain.
+   * @param massKg The mass of the robot in kilograms.
+   * @param rMeters The radius of the wheels in meters.
+   * @param rbMeters The radius of the base (half the track width) in meters.
+   * @param JKgMetersSquared The moment of inertia of the robot.
+   * @param G The gearing reduction as output over input.
    * @return A LinearSystem representing a differential drivetrain.
    * @throws IllegalArgumentException if m &lt;= 0, r &lt;= 0, rb &lt;= 0, J &lt;= 0, or G &lt;= 0.
    */
-  @SuppressWarnings({"LocalVariableName", "ParameterName"})
   public static LinearSystem<N2, N2, N2> createDrivetrainVelocitySystem(
       DCMotor motor,
       double massKg,
@@ -181,16 +178,15 @@
    * angular velocity], inputs are [voltage], and outputs are [angle].
    *
    * @param motor The motor (or gearbox) attached to the arm.
-   * @param jKgSquaredMeters The moment of inertia J of the arm.
+   * @param JKgSquaredMeters The moment of inertia J of the arm.
    * @param G The gearing between the motor and arm, in output over input. Most of the time this
    *     will be greater than 1.
    * @return A LinearSystem representing the given characterized constants.
    */
-  @SuppressWarnings("ParameterName")
   public static LinearSystem<N2, N1, N1> createSingleJointedArmSystem(
-      DCMotor motor, double jKgSquaredMeters, double G) {
-    if (jKgSquaredMeters <= 0.0) {
-      throw new IllegalArgumentException("jKgSquaredMeters must be greater than zero.");
+      DCMotor motor, double JKgSquaredMeters, double G) {
+    if (JKgSquaredMeters <= 0.0) {
+      throw new IllegalArgumentException("JKgSquaredMeters must be greater than zero.");
     }
     if (G <= 0.0) {
       throw new IllegalArgumentException("G must be greater than zero.");
@@ -204,27 +200,30 @@
                 0,
                 -Math.pow(G, 2)
                     * motor.KtNMPerAmp
-                    / (motor.KvRadPerSecPerVolt * motor.rOhms * jKgSquaredMeters)),
-        VecBuilder.fill(0, G * motor.KtNMPerAmp / (motor.rOhms * jKgSquaredMeters)),
+                    / (motor.KvRadPerSecPerVolt * motor.rOhms * JKgSquaredMeters)),
+        VecBuilder.fill(0, G * motor.KtNMPerAmp / (motor.rOhms * JKgSquaredMeters)),
         Matrix.mat(Nat.N1(), Nat.N2()).fill(1, 0),
         new Matrix<>(Nat.N1(), Nat.N1()));
   }
 
   /**
-   * Identify a velocity system from it's kV (volts/(unit/sec)) and kA (volts/(unit/sec^2). These
-   * constants cam be found using SysId. The states of the system are [velocity], inputs are
-   * [voltage], and outputs are [velocity].
+   * Create a state-space model for a 1 DOF velocity system from its kV (volts/(unit/sec)) and kA
+   * (volts/(unit/sec²). These constants cam be found using SysId. The states of the system are
+   * [velocity], inputs are [voltage], and outputs are [velocity].
    *
    * <p>The distance unit you choose MUST be an SI unit (i.e. meters or radians). You can use the
    * {@link edu.wpi.first.math.util.Units} class for converting between unit types.
    *
-   * @param kV The velocity gain, in volts per (units per second)
-   * @param kA The acceleration gain, in volts per (units per second squared)
+   * <p>The parameters provided by the user are from this feedforward model:
+   *
+   * <p>u = K_v v + K_a a
+   *
+   * @param kV The velocity gain, in volts/(unit/sec)
+   * @param kA The acceleration gain, in volts/(unit/sec^2)
    * @return A LinearSystem representing the given characterized constants.
    * @throws IllegalArgumentException if kV &lt;= 0 or kA &lt;= 0.
    * @see <a href="https://github.com/wpilibsuite/sysid">https://github.com/wpilibsuite/sysid</a>
    */
-  @SuppressWarnings("ParameterName")
   public static LinearSystem<N1, N1, N1> identifyVelocitySystem(double kV, double kA) {
     if (kV <= 0.0) {
       throw new IllegalArgumentException("Kv must be greater than zero.");
@@ -241,20 +240,23 @@
   }
 
   /**
-   * Identify a position system from it's kV (volts/(unit/sec)) and kA (volts/(unit/sec^2). These
-   * constants cam be found using SysId. The states of the system are [position, velocity]ᵀ, inputs
-   * are [voltage], and outputs are [position].
+   * Create a state-space model for a 1 DOF position system from its kV (volts/(unit/sec)) and kA
+   * (volts/(unit/sec²). These constants cam be found using SysId. The states of the system are
+   * [position, velocity]ᵀ, inputs are [voltage], and outputs are [position].
    *
    * <p>The distance unit you choose MUST be an SI unit (i.e. meters or radians). You can use the
    * {@link edu.wpi.first.math.util.Units} class for converting between unit types.
    *
-   * @param kV The velocity gain, in volts per (units per second)
-   * @param kA The acceleration gain, in volts per (units per second squared)
+   * <p>The parameters provided by the user are from this feedforward model:
+   *
+   * <p>u = K_v v + K_a a
+   *
+   * @param kV The velocity gain, in volts/(unit/sec)
+   * @param kA The acceleration gain, in volts/(unit/sec²)
    * @return A LinearSystem representing the given characterized constants.
    * @throws IllegalArgumentException if kV &lt;= 0 or kA &lt;= 0.
    * @see <a href="https://github.com/wpilibsuite/sysid">https://github.com/wpilibsuite/sysid</a>
    */
-  @SuppressWarnings("ParameterName")
   public static LinearSystem<N2, N1, N1> identifyPositionSystem(double kV, double kA) {
     if (kV <= 0.0) {
       throw new IllegalArgumentException("Kv must be greater than zero.");
@@ -271,22 +273,23 @@
   }
 
   /**
-   * Identify a standard differential drive drivetrain, given the drivetrain's kV and kA in both
-   * linear (volts/(meter/sec) and volts/(meter/sec^2)) and angular (volts/(meter/sec) and
-   * volts/(meter/sec^2)) cases. This can be found using SysId. The states of the system are [left
-   * velocity, right velocity]ᵀ, inputs are [left voltage, right voltage]ᵀ, and outputs are [left
-   * velocity, right velocity]ᵀ.
+   * Identify a differential drive drivetrain given the drivetrain's kV and kA in both linear
+   * {(volts/(meter/sec), (volts/(meter/sec²))} and angular {(volts/(radian/sec)),
+   * (volts/(radian/sec²))} cases. These constants can be found using SysId.
    *
-   * @param kVLinear The linear velocity gain, volts per (meter per second).
-   * @param kALinear The linear acceleration gain, volts per (meter per second squared).
-   * @param kVAngular The angular velocity gain, volts per (meter per second).
-   * @param kAAngular The angular acceleration gain, volts per (meter per second squared).
+   * <p>States: [[left velocity], [right velocity]]<br>
+   * Inputs: [[left voltage], [right voltage]]<br>
+   * Outputs: [[left velocity], [right velocity]]
+   *
+   * @param kVLinear The linear velocity gain in volts per (meters per second).
+   * @param kALinear The linear acceleration gain in volts per (meters per second squared).
+   * @param kVAngular The angular velocity gain in volts per (meters per second).
+   * @param kAAngular The angular acceleration gain in volts per (meters per second squared).
    * @return A LinearSystem representing the given characterized constants.
    * @throws IllegalArgumentException if kVLinear &lt;= 0, kALinear &lt;= 0, kVAngular &lt;= 0, or
    *     kAAngular &lt;= 0.
    * @see <a href="https://github.com/wpilibsuite/sysid">https://github.com/wpilibsuite/sysid</a>
    */
-  @SuppressWarnings("ParameterName")
   public static LinearSystem<N2, N2, N2> identifyDrivetrainSystem(
       double kVLinear, double kALinear, double kVAngular, double kAAngular) {
     if (kVLinear <= 0.0) {
@@ -315,23 +318,25 @@
   }
 
   /**
-   * Identify a standard differential drive drivetrain, given the drivetrain's kV and kA in both
-   * linear (volts/(meter/sec) and volts/(meter/sec^2)) and angular (volts/(radian/sec) and
-   * volts/(radian/sec^2)) cases. This can be found using SysId. The states of the system are [left
-   * velocity, right velocity]ᵀ, inputs are [left voltage, right voltage]ᵀ, and outputs are [left
-   * velocity, right velocity]ᵀ.
+   * Identify a differential drive drivetrain given the drivetrain's kV and kA in both linear
+   * {(volts/(meter/sec)), (volts/(meter/sec²))} and angular {(volts/(radian/sec)),
+   * (volts/(radian/sec²))} cases. This can be found using SysId.
    *
-   * @param kVLinear The linear velocity gain, volts per (meter per second).
-   * @param kALinear The linear acceleration gain, volts per (meter per second squared).
-   * @param kVAngular The angular velocity gain, volts per (radians per second).
-   * @param kAAngular The angular acceleration gain, volts per (radians per second squared).
-   * @param trackwidth The width of the drivetrain in meters.
+   * <p>States: [[left velocity], [right velocity]]<br>
+   * Inputs: [[left voltage], [right voltage]]<br>
+   * Outputs: [[left velocity], [right velocity]]
+   *
+   * @param kVLinear The linear velocity gain in volts per (meters per second).
+   * @param kALinear The linear acceleration gain in volts per (meters per second squared).
+   * @param kVAngular The angular velocity gain in volts per (radians per second).
+   * @param kAAngular The angular acceleration gain in volts per (radians per second squared).
+   * @param trackwidth The distance between the differential drive's left and right wheels, in
+   *     meters.
    * @return A LinearSystem representing the given characterized constants.
    * @throws IllegalArgumentException if kVLinear &lt;= 0, kALinear &lt;= 0, kVAngular &lt;= 0,
    *     kAAngular &lt;= 0, or trackwidth &lt;= 0.
    * @see <a href="https://github.com/wpilibsuite/sysid">https://github.com/wpilibsuite/sysid</a>
    */
-  @SuppressWarnings("ParameterName")
   public static LinearSystem<N2, N2, N2> identifyDrivetrainSystem(
       double kVLinear, double kALinear, double kVAngular, double kAAngular, double trackwidth) {
     if (kVLinear <= 0.0) {
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/trajectory/Trajectory.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/trajectory/Trajectory.java
index 2ec4244..f716dc0 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/trajectory/Trajectory.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/trajectory/Trajectory.java
@@ -44,7 +44,6 @@
    * @param t The fraction for interpolation.
    * @return The interpolated value.
    */
-  @SuppressWarnings("ParameterName")
   private static double lerp(double startValue, double endValue, double t) {
     return startValue + (endValue - startValue) * t;
   }
@@ -57,7 +56,6 @@
    * @param t The fraction for interpolation.
    * @return The interpolated pose.
    */
-  @SuppressWarnings("ParameterName")
   private static Pose2d lerp(Pose2d startValue, Pose2d endValue, double t) {
     return startValue.plus((endValue.minus(startValue)).times(t));
   }
@@ -254,7 +252,6 @@
    * Represents a time-parameterized trajectory. The trajectory contains of various States that
    * represent the pose, curvature, time elapsed, velocity, and acceleration at that point.
    */
-  @SuppressWarnings("MemberName")
   public static class State {
     // The time elapsed since the beginning of the trajectory.
     @JsonProperty("time")
@@ -309,7 +306,6 @@
      * @param i The interpolant (fraction).
      * @return The interpolated state.
      */
-    @SuppressWarnings("ParameterName")
     State interpolate(State endValue, double i) {
       // Find the new t value.
       final double newT = lerp(timeSeconds, endValue.timeSeconds, i);
@@ -332,7 +328,7 @@
       final double newV = velocityMetersPerSecond + (accelerationMetersPerSecondSq * deltaT);
 
       // Calculate the change in position.
-      // delta_s = v_0 t + 0.5 at^2
+      // delta_s = v_0 t + 0.5at²
       final double newS =
           (velocityMetersPerSecond * deltaT
                   + 0.5 * accelerationMetersPerSecondSq * Math.pow(deltaT, 2))
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/trajectory/TrajectoryGenerator.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/trajectory/TrajectoryGenerator.java
index 0827c15..ce90ce6 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/trajectory/TrajectoryGenerator.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/trajectory/TrajectoryGenerator.java
@@ -15,14 +15,13 @@
 import edu.wpi.first.math.spline.SplineParameterizer;
 import edu.wpi.first.math.spline.SplineParameterizer.MalformedSplineException;
 import java.util.ArrayList;
-import java.util.Arrays;
 import java.util.Collection;
 import java.util.List;
 import java.util.function.BiConsumer;
 
 public final class TrajectoryGenerator {
   private static final Trajectory kDoNothingTrajectory =
-      new Trajectory(Arrays.asList(new Trajectory.State()));
+      new Trajectory(List.of(new Trajectory.State()));
   private static BiConsumer<String, StackTraceElement[]> errorFunc;
 
   /** Private constructor because this is a utility class. */
@@ -193,7 +192,6 @@
    * @param config The configuration for the trajectory.
    * @return The generated trajectory.
    */
-  @SuppressWarnings("LocalVariableName")
   public static Trajectory generateTrajectory(List<Pose2d> waypoints, TrajectoryConfig config) {
     final var flip = new Transform2d(new Translation2d(), Rotation2d.fromDegrees(180.0));
 
@@ -263,7 +261,6 @@
   }
 
   // Work around type erasure signatures
-  @SuppressWarnings("serial")
   public static class ControlVectorList extends ArrayList<Spline.ControlVector> {
     public ControlVectorList(int initialCapacity) {
       super(initialCapacity);
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/trajectory/TrajectoryParameterizer.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/trajectory/TrajectoryParameterizer.java
index d7fbf59..cf9b6f8 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/trajectory/TrajectoryParameterizer.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/trajectory/TrajectoryParameterizer.java
@@ -90,7 +90,7 @@
       // acceleration, since acceleration limits may be a function of velocity.
       while (true) {
         // Enforce global max velocity and max reachable velocity by global
-        // acceleration limit. vf = std::sqrt(vi^2 + 2*a*d).
+        // acceleration limit. v_f = √(v_i² + 2ad).
         constrainedState.maxVelocityMetersPerSecond =
             Math.min(
                 maxVelocityMetersPerSecond,
@@ -164,7 +164,7 @@
 
       while (true) {
         // Enforce max velocity limit (reverse)
-        // vf = std::sqrt(vi^2 + 2*a*d), where vi = successor.
+        // v_f = √(v_i² + 2ad), where v_i = successor.
         double newMaxVelocity =
             Math.sqrt(
                 successor.maxVelocityMetersPerSecond * successor.maxVelocityMetersPerSecond
@@ -294,7 +294,6 @@
     }
   }
 
-  @SuppressWarnings("MemberName")
   private static class ConstrainedState {
     PoseWithCurvature pose;
     double distanceMeters;
@@ -320,7 +319,6 @@
     }
   }
 
-  @SuppressWarnings("serial")
   public static class TrajectoryGenerationException extends RuntimeException {
     public TrajectoryGenerationException(String message) {
       super(message);
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/trajectory/TrajectoryUtil.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/trajectory/TrajectoryUtil.java
index 5fb2c34..2cbba90 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/trajectory/TrajectoryUtil.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/trajectory/TrajectoryUtil.java
@@ -68,7 +68,7 @@
   }
 
   /**
-   * Imports a Trajectory from a PathWeaver-style JSON file.
+   * Imports a Trajectory from a JSON file exported from PathWeaver.
    *
    * @param path The path of the json file to import from
    * @return The trajectory represented by the file.
@@ -90,7 +90,7 @@
   }
 
   /**
-   * Deserializes a Trajectory from PathWeaver-style JSON.
+   * Deserializes a Trajectory from JSON exported from PathWeaver.
    *
    * @param json The string containing the serialized JSON
    * @return the trajectory represented by the JSON
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/trajectory/TrapezoidProfile.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/trajectory/TrapezoidProfile.java
index d41a8eb..3b6559e 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/trajectory/TrapezoidProfile.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/trajectory/TrapezoidProfile.java
@@ -51,10 +51,8 @@
   private double m_endDeccel;
 
   public static class Constraints {
-    @SuppressWarnings("MemberName")
     public final double maxVelocity;
 
-    @SuppressWarnings("MemberName")
     public final double maxAcceleration;
 
     /**
@@ -71,10 +69,8 @@
   }
 
   public static class State {
-    @SuppressWarnings("MemberName")
     public double position;
 
-    @SuppressWarnings("MemberName")
     public double velocity;
 
     public State() {}
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/trajectory/constraint/CentripetalAccelerationConstraint.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/trajectory/constraint/CentripetalAccelerationConstraint.java
index 13138e8..7a47fca 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/trajectory/constraint/CentripetalAccelerationConstraint.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/trajectory/constraint/CentripetalAccelerationConstraint.java
@@ -38,12 +38,12 @@
   @Override
   public double getMaxVelocityMetersPerSecond(
       Pose2d poseMeters, double curvatureRadPerMeter, double velocityMetersPerSecond) {
-    // ac = v^2 / r
-    // k (curvature) = 1 / r
+    // ac = v²/r
+    // k (curvature) = 1/r
 
-    // therefore, ac = v^2 * k
-    // ac / k = v^2
-    // v = std::sqrt(ac / k)
+    // therefore, ac = v²k
+    // ac/k = v²
+    // v = √(ac/k)
 
     return Math.sqrt(
         m_maxCentripetalAccelerationMetersPerSecondSq / Math.abs(curvatureRadPerMeter));
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/trajectory/constraint/DifferentialDriveVoltageConstraint.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/trajectory/constraint/DifferentialDriveVoltageConstraint.java
index 4c7e814..0cc6bc5 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/trajectory/constraint/DifferentialDriveVoltageConstraint.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/trajectory/constraint/DifferentialDriveVoltageConstraint.java
@@ -111,7 +111,7 @@
                       / 2);
     }
 
-    // When turning about a point inside of the wheelbase (i.e. radius less than half
+    // When turning about a point inside the wheelbase (i.e. radius less than half
     // the trackwidth), the inner wheel's direction changes, but the magnitude remains
     // the same.  The formula above changes sign for the inner wheel when this happens.
     // We can accurately account for this by simply negating the inner wheel.
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/trajectory/constraint/EllipticalRegionConstraint.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/trajectory/constraint/EllipticalRegionConstraint.java
index c3bd226..e0647f2 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/trajectory/constraint/EllipticalRegionConstraint.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/trajectory/constraint/EllipticalRegionConstraint.java
@@ -23,7 +23,6 @@
    * @param rotation The rotation to apply to all radii around the origin.
    * @param constraint The constraint to enforce when the robot is within the region.
    */
-  @SuppressWarnings("ParameterName")
   public EllipticalRegionConstraint(
       Translation2d center,
       double xWidth,
@@ -65,11 +64,16 @@
    * @return Whether the robot pose is within the constraint region.
    */
   public boolean isPoseInRegion(Pose2d robotPose) {
-    // The region (disk) bounded by the ellipse is given by the equation:
-    // ((x-h)^2)/Rx^2) + ((y-k)^2)/Ry^2) <= 1
+    // The region bounded by the ellipse is given by the equation:
+    //
+    // (x−h)²/Rx² + (y−k)²/Ry² ≤ 1
+    //
+    // Multiply by Rx²Ry² for efficiency reasons:
+    //
+    // (x−h)²Ry² + (y−k)²Rx² ≤ Rx²Ry²
+    //
     // If the inequality is satisfied, then it is inside the ellipse; otherwise
     // it is outside the ellipse.
-    // Both sides have been multiplied by Rx^2 * Ry^2 for efficiency reasons.
     return Math.pow(robotPose.getX() - m_center.getX(), 2) * Math.pow(m_radii.getY(), 2)
             + Math.pow(robotPose.getY() - m_center.getY(), 2) * Math.pow(m_radii.getX(), 2)
         <= Math.pow(m_radii.getX(), 2) * Math.pow(m_radii.getY(), 2);
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/trajectory/constraint/TrajectoryConstraint.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/trajectory/constraint/TrajectoryConstraint.java
index bbf30f7..cc0087c 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/trajectory/constraint/TrajectoryConstraint.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/trajectory/constraint/TrajectoryConstraint.java
@@ -36,7 +36,6 @@
       Pose2d poseMeters, double curvatureRadPerMeter, double velocityMetersPerSecond);
 
   /** Represents a minimum and maximum acceleration. */
-  @SuppressWarnings("MemberName")
   class MinMax {
     public double minAccelerationMetersPerSecondSq = -Double.MAX_VALUE;
     public double maxAccelerationMetersPerSecondSq = +Double.MAX_VALUE;
diff --git a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/util/Units.java b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/util/Units.java
index 017f4d0..ce2b38e 100644
--- a/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/util/Units.java
+++ b/third_party/allwpilib/wpimath/src/main/java/edu/wpi/first/math/util/Units.java
@@ -91,7 +91,7 @@
    * Converts given degrees to rotations.
    *
    * @param degrees The degrees to convert.
-   * @return rotations Converted from radians.
+   * @return rotations Converted from degrees.
    */
   public static double degreesToRotations(double degrees) {
     return degrees / 360;
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/ComputerVisionUtil.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/ComputerVisionUtil.cpp
new file mode 100644
index 0000000..97968dc
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/ComputerVisionUtil.cpp
@@ -0,0 +1,19 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/ComputerVisionUtil.h"
+
+#include "units/math.h"
+
+namespace frc {
+
+frc::Pose3d ObjectToRobotPose(const frc::Pose3d& objectInField,
+                              const frc::Transform3d& cameraToObject,
+                              const frc::Transform3d& robotToCamera) {
+  const auto objectToCamera = cameraToObject.Inverse();
+  const auto cameraToRobot = robotToCamera.Inverse();
+  return objectInField + objectToCamera + cameraToRobot;
+}
+
+}  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/MathUtil.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/MathUtil.cpp
deleted file mode 100644
index 19cd214..0000000
--- a/third_party/allwpilib/wpimath/src/main/native/cpp/MathUtil.cpp
+++ /dev/null
@@ -1,23 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/MathUtil.h"
-
-#include <cmath>
-
-namespace frc {
-
-double ApplyDeadband(double value, double deadband) {
-  if (std::abs(value) > deadband) {
-    if (value > 0.0) {
-      return (value - deadband) / (1.0 - deadband);
-    } else {
-      return (value + deadband) / (1.0 - deadband);
-    }
-  } else {
-    return 0.0;
-  }
-}
-
-}  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/StateSpaceUtil.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/StateSpaceUtil.cpp
index 8f1145d..fc532db 100644
--- a/third_party/allwpilib/wpimath/src/main/native/cpp/StateSpaceUtil.cpp
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/StateSpaceUtil.cpp
@@ -6,33 +6,31 @@
 
 namespace frc {
 
-Eigen::Vector<double, 3> PoseTo3dVector(const Pose2d& pose) {
-  return Eigen::Vector<double, 3>{pose.Translation().X().value(),
-                                  pose.Translation().Y().value(),
-                                  pose.Rotation().Radians().value()};
+Vectord<3> PoseTo3dVector(const Pose2d& pose) {
+  return Vectord<3>{pose.Translation().X().value(),
+                    pose.Translation().Y().value(),
+                    pose.Rotation().Radians().value()};
 }
 
-Eigen::Vector<double, 4> PoseTo4dVector(const Pose2d& pose) {
-  return Eigen::Vector<double, 4>{pose.Translation().X().value(),
-                                  pose.Translation().Y().value(),
-                                  pose.Rotation().Cos(), pose.Rotation().Sin()};
+Vectord<4> PoseTo4dVector(const Pose2d& pose) {
+  return Vectord<4>{pose.Translation().X().value(),
+                    pose.Translation().Y().value(), pose.Rotation().Cos(),
+                    pose.Rotation().Sin()};
 }
 
 template <>
-bool IsStabilizable<1, 1>(const Eigen::Matrix<double, 1, 1>& A,
-                          const Eigen::Matrix<double, 1, 1>& B) {
+bool IsStabilizable<1, 1>(const Matrixd<1, 1>& A, const Matrixd<1, 1>& B) {
   return detail::IsStabilizableImpl<1, 1>(A, B);
 }
 
 template <>
-bool IsStabilizable<2, 1>(const Eigen::Matrix<double, 2, 2>& A,
-                          const Eigen::Matrix<double, 2, 1>& B) {
+bool IsStabilizable<2, 1>(const Matrixd<2, 2>& A, const Matrixd<2, 1>& B) {
   return detail::IsStabilizableImpl<2, 1>(A, B);
 }
 
-Eigen::Vector<double, 3> PoseToVector(const Pose2d& pose) {
-  return Eigen::Vector<double, 3>{pose.X().value(), pose.Y().value(),
-                                  pose.Rotation().Radians().value()};
+Vectord<3> PoseToVector(const Pose2d& pose) {
+  return Vectord<3>{pose.X().value(), pose.Y().value(),
+                    pose.Rotation().Radians().value()};
 }
 
 }  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/controller/DifferentialDriveAccelerationLimiter.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/controller/DifferentialDriveAccelerationLimiter.cpp
new file mode 100644
index 0000000..9788023
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/controller/DifferentialDriveAccelerationLimiter.cpp
@@ -0,0 +1,85 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/controller/DifferentialDriveAccelerationLimiter.h"
+
+#include <utility>
+
+#include "Eigen/QR"
+
+using namespace frc;
+
+DifferentialDriveAccelerationLimiter::DifferentialDriveAccelerationLimiter(
+    LinearSystem<2, 2, 2> system, units::meter_t trackwidth,
+    units::meters_per_second_squared_t maxLinearAccel,
+    units::radians_per_second_squared_t maxAngularAccel)
+    : DifferentialDriveAccelerationLimiter(system, trackwidth, -maxLinearAccel,
+                                           maxLinearAccel, maxAngularAccel) {}
+
+DifferentialDriveAccelerationLimiter::DifferentialDriveAccelerationLimiter(
+    LinearSystem<2, 2, 2> system, units::meter_t trackwidth,
+    units::meters_per_second_squared_t minLinearAccel,
+    units::meters_per_second_squared_t maxLinearAccel,
+    units::radians_per_second_squared_t maxAngularAccel)
+    : m_system{std::move(system)},
+      m_trackwidth{trackwidth},
+      m_minLinearAccel{minLinearAccel},
+      m_maxLinearAccel{maxLinearAccel},
+      m_maxAngularAccel{maxAngularAccel} {
+  if (minLinearAccel > maxLinearAccel) {
+    throw std::invalid_argument(
+        "maxLinearAccel must be greater than minLinearAccel");
+  }
+}
+
+DifferentialDriveWheelVoltages DifferentialDriveAccelerationLimiter::Calculate(
+    units::meters_per_second_t leftVelocity,
+    units::meters_per_second_t rightVelocity, units::volt_t leftVoltage,
+    units::volt_t rightVoltage) {
+  Vectord<2> u{leftVoltage.value(), rightVoltage.value()};
+
+  // Find unconstrained wheel accelerations
+  Vectord<2> x{leftVelocity.value(), rightVelocity.value()};
+  Vectord<2> dxdt = m_system.A() * x + m_system.B() * u;
+
+  // Convert from wheel accelerations to linear and angular accelerations
+  //
+  // a = (dxdt(0) + dx/dt(1)) / 2
+  //   = 0.5 dxdt(0) + 0.5 dxdt(1)
+  //
+  // α = (dxdt(1) - dxdt(0)) / trackwidth
+  //   = -1/trackwidth dxdt(0) + 1/trackwidth dxdt(1)
+  //
+  // [a] = [          0.5           0.5][dxdt(0)]
+  // [α]   [-1/trackwidth  1/trackwidth][dxdt(1)]
+  //
+  // accels = M dxdt where M = [0.5, 0.5; -1/trackwidth, 1/trackwidth]
+  Matrixd<2, 2> M{{0.5, 0.5},
+                  {-1.0 / m_trackwidth.value(), 1.0 / m_trackwidth.value()}};
+  Vectord<2> accels = M * dxdt;
+
+  // Constrain the linear and angular accelerations
+  if (accels(0) > m_maxLinearAccel.value()) {
+    accels(0) = m_maxLinearAccel.value();
+  } else if (accels(0) < m_minLinearAccel.value()) {
+    accels(0) = m_minLinearAccel.value();
+  }
+  if (accels(1) > m_maxAngularAccel.value()) {
+    accels(1) = m_maxAngularAccel.value();
+  } else if (accels(1) < -m_maxAngularAccel.value()) {
+    accels(1) = -m_maxAngularAccel.value();
+  }
+
+  // Convert the constrained linear and angular accelerations back to wheel
+  // accelerations
+  dxdt = M.householderQr().solve(accels);
+
+  // Find voltages for the given wheel accelerations
+  //
+  // dx/dt = Ax + Bu
+  // u = B⁻¹(dx/dt - Ax)
+  u = m_system.B().householderQr().solve(dxdt - m_system.A() * x);
+
+  return {units::volt_t{u(0)}, units::volt_t{u(1)}};
+}
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/controller/DifferentialDriveFeedforward.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/controller/DifferentialDriveFeedforward.cpp
new file mode 100644
index 0000000..e1b2732
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/controller/DifferentialDriveFeedforward.cpp
@@ -0,0 +1,37 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/controller/DifferentialDriveFeedforward.h"
+
+#include "frc/EigenCore.h"
+#include "frc/controller/LinearPlantInversionFeedforward.h"
+#include "frc/system/plant/LinearSystemId.h"
+
+using namespace frc;
+
+DifferentialDriveFeedforward::DifferentialDriveFeedforward(
+    decltype(1_V / 1_mps) kVLinear, decltype(1_V / 1_mps_sq) kALinear,
+    decltype(1_V / 1_rad_per_s) kVAngular,
+    decltype(1_V / 1_rad_per_s_sq) kAAngular, units::meter_t trackwidth)
+    : m_plant{frc::LinearSystemId::IdentifyDrivetrainSystem(
+          kVLinear, kALinear, kVAngular, kAAngular, trackwidth)} {}
+
+DifferentialDriveFeedforward::DifferentialDriveFeedforward(
+    decltype(1_V / 1_mps) kVLinear, decltype(1_V / 1_mps_sq) kALinear,
+    decltype(1_V / 1_mps) kVAngular, decltype(1_V / 1_mps_sq) kAAngular)
+    : m_plant{frc::LinearSystemId::IdentifyDrivetrainSystem(
+          kVLinear, kALinear, kVAngular, kAAngular)} {}
+
+DifferentialDriveWheelVoltages DifferentialDriveFeedforward::Calculate(
+    units::meters_per_second_t currentLeftVelocity,
+    units::meters_per_second_t nextLeftVelocity,
+    units::meters_per_second_t currentRightVelocity,
+    units::meters_per_second_t nextRightVelocity, units::second_t dt) {
+  frc::LinearPlantInversionFeedforward<2, 2> feedforward{m_plant, dt};
+
+  frc::Vectord<2> r{currentLeftVelocity, currentRightVelocity};
+  frc::Vectord<2> nextR{nextLeftVelocity, nextRightVelocity};
+  auto u = feedforward.Calculate(r, nextR);
+  return {units::volt_t{u(0)}, units::volt_t{u(1)}};
+}
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/controller/HolonomicDriveController.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/controller/HolonomicDriveController.cpp
index 23b22cd..def7234 100644
--- a/third_party/allwpilib/wpimath/src/main/native/cpp/controller/HolonomicDriveController.cpp
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/controller/HolonomicDriveController.cpp
@@ -15,7 +15,9 @@
     ProfiledPIDController<units::radian> thetaController)
     : m_xController(std::move(xController)),
       m_yController(std::move(yController)),
-      m_thetaController(std::move(thetaController)) {}
+      m_thetaController(std::move(thetaController)) {
+  m_thetaController.EnableContinuousInput(0_deg, 360.0_deg);
+}
 
 bool HolonomicDriveController::AtReference() const {
   const auto& eTranslate = m_poseError.Translation();
@@ -32,8 +34,9 @@
 }
 
 ChassisSpeeds HolonomicDriveController::Calculate(
-    const Pose2d& currentPose, const Pose2d& poseRef,
-    units::meters_per_second_t linearVelocityRef, const Rotation2d& angleRef) {
+    const Pose2d& currentPose, const Pose2d& trajectoryPose,
+    units::meters_per_second_t desiredLinearVelocity,
+    const Rotation2d& desiredHeading) {
   // If this is the first run, then we need to reset the theta controller to the
   // current pose's heading.
   if (m_firstRun) {
@@ -42,13 +45,13 @@
   }
 
   // Calculate feedforward velocities (field-relative)
-  auto xFF = linearVelocityRef * poseRef.Rotation().Cos();
-  auto yFF = linearVelocityRef * poseRef.Rotation().Sin();
-  auto thetaFF = units::radians_per_second_t(m_thetaController.Calculate(
-      currentPose.Rotation().Radians(), angleRef.Radians()));
+  auto xFF = desiredLinearVelocity * trajectoryPose.Rotation().Cos();
+  auto yFF = desiredLinearVelocity * trajectoryPose.Rotation().Sin();
+  auto thetaFF = units::radians_per_second_t{m_thetaController.Calculate(
+      currentPose.Rotation().Radians(), desiredHeading.Radians())};
 
-  m_poseError = poseRef.RelativeTo(currentPose);
-  m_rotationError = angleRef - currentPose.Rotation();
+  m_poseError = trajectoryPose.RelativeTo(currentPose);
+  m_rotationError = desiredHeading - currentPose.Rotation();
 
   if (!m_enabled) {
     return ChassisSpeeds::FromFieldRelativeSpeeds(xFF, yFF, thetaFF,
@@ -56,10 +59,10 @@
   }
 
   // Calculate feedback velocities (based on position error).
-  auto xFeedback = units::meters_per_second_t(
-      m_xController.Calculate(currentPose.X().value(), poseRef.X().value()));
-  auto yFeedback = units::meters_per_second_t(
-      m_yController.Calculate(currentPose.Y().value(), poseRef.Y().value()));
+  auto xFeedback = units::meters_per_second_t{m_xController.Calculate(
+      currentPose.X().value(), trajectoryPose.X().value())};
+  auto yFeedback = units::meters_per_second_t{m_yController.Calculate(
+      currentPose.Y().value(), trajectoryPose.Y().value())};
 
   // Return next output.
   return ChassisSpeeds::FromFieldRelativeSpeeds(
@@ -68,9 +71,9 @@
 
 ChassisSpeeds HolonomicDriveController::Calculate(
     const Pose2d& currentPose, const Trajectory::State& desiredState,
-    const Rotation2d& angleRef) {
+    const Rotation2d& desiredHeading) {
   return Calculate(currentPose, desiredState.pose, desiredState.velocity,
-                   angleRef);
+                   desiredHeading);
 }
 
 void HolonomicDriveController::SetEnabled(bool enabled) {
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/controller/LTVDifferentialDriveController.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/controller/LTVDifferentialDriveController.cpp
new file mode 100644
index 0000000..17a0c56
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/controller/LTVDifferentialDriveController.cpp
@@ -0,0 +1,153 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/controller/LTVDifferentialDriveController.h"
+
+#include <cmath>
+
+#include "frc/MathUtil.h"
+#include "frc/StateSpaceUtil.h"
+#include "frc/controller/LinearQuadraticRegulator.h"
+
+using namespace frc;
+
+namespace {
+
+/**
+ * States of the drivetrain system.
+ */
+class State {
+ public:
+  /// X position in global coordinate frame.
+  [[maybe_unused]] static constexpr int kX = 0;
+
+  /// Y position in global coordinate frame.
+  static constexpr int kY = 1;
+
+  /// Heading in global coordinate frame.
+  static constexpr int kHeading = 2;
+
+  /// Left encoder velocity.
+  [[maybe_unused]] static constexpr int kLeftVelocity = 3;
+
+  /// Right encoder velocity.
+  [[maybe_unused]] static constexpr int kRightVelocity = 4;
+};
+
+}  // namespace
+
+LTVDifferentialDriveController::LTVDifferentialDriveController(
+    const frc::LinearSystem<2, 2, 2>& plant, units::meter_t trackwidth,
+    const wpi::array<double, 5>& Qelems, const wpi::array<double, 2>& Relems,
+    units::second_t dt)
+    : m_trackwidth{trackwidth} {
+  // Control law derivation is in section 8.7 of
+  // https://file.tavsys.net/control/controls-engineering-in-frc.pdf
+  Matrixd<5, 5> A{
+      {0.0, 0.0, 0.0, 0.5, 0.5},
+      {0.0, 0.0, 0.0, 0.0, 0.0},
+      {0.0, 0.0, 0.0, -1.0 / m_trackwidth.value(), 1.0 / m_trackwidth.value()},
+      {0.0, 0.0, 0.0, plant.A(0, 0), plant.A(0, 1)},
+      {0.0, 0.0, 0.0, plant.A(1, 0), plant.A(1, 1)}};
+  Matrixd<5, 2> B{{0.0, 0.0},
+                  {0.0, 0.0},
+                  {0.0, 0.0},
+                  {plant.B(0, 0), plant.B(0, 1)},
+                  {plant.B(1, 0), plant.B(1, 1)}};
+  Matrixd<5, 5> Q = frc::MakeCostMatrix(Qelems);
+  Matrixd<2, 2> R = frc::MakeCostMatrix(Relems);
+
+  // dx/dt = Ax + Bu
+  // 0 = Ax + Bu
+  // Ax = -Bu
+  // x = -A⁻¹Bu
+  units::meters_per_second_t maxV{
+      -plant.A().householderQr().solve(plant.B() * Vectord<2>{12.0, 12.0})(0)};
+
+  for (auto velocity = -maxV; velocity < maxV; velocity += 0.01_mps) {
+    // The DARE is ill-conditioned if the velocity is close to zero, so don't
+    // let the system stop.
+    if (units::math::abs(velocity) < 1e-4_mps) {
+      m_table.insert(velocity, Matrixd<2, 5>::Zero());
+    } else {
+      A(State::kY, State::kHeading) = velocity.value();
+      m_table.insert(velocity,
+                     frc::LinearQuadraticRegulator<5, 2>{A, B, Q, R, dt}.K());
+    }
+  }
+}
+
+bool LTVDifferentialDriveController::AtReference() const {
+  return std::abs(m_error(0)) < m_tolerance(0) &&
+         std::abs(m_error(1)) < m_tolerance(1) &&
+         std::abs(m_error(2)) < m_tolerance(2) &&
+         std::abs(m_error(3)) < m_tolerance(3) &&
+         std::abs(m_error(4)) < m_tolerance(4);
+}
+
+void LTVDifferentialDriveController::SetTolerance(
+    const Pose2d& poseTolerance,
+    units::meters_per_second_t leftVelocityTolerance,
+    units::meters_per_second_t rightVelocityTolerance) {
+  m_tolerance =
+      Vectord<5>{poseTolerance.X().value(), poseTolerance.Y().value(),
+                 poseTolerance.Rotation().Radians().value(),
+                 leftVelocityTolerance.value(), rightVelocityTolerance.value()};
+}
+
+DifferentialDriveWheelVoltages LTVDifferentialDriveController::Calculate(
+    const Pose2d& currentPose, units::meters_per_second_t leftVelocity,
+    units::meters_per_second_t rightVelocity, const Pose2d& poseRef,
+    units::meters_per_second_t leftVelocityRef,
+    units::meters_per_second_t rightVelocityRef) {
+  // This implements the linear time-varying differential drive controller in
+  // theorem 9.6.3 of https://tavsys.net/controls-in-frc.
+  Vectord<5> x{currentPose.X().value(), currentPose.Y().value(),
+               currentPose.Rotation().Radians().value(), leftVelocity.value(),
+               rightVelocity.value()};
+
+  Matrixd<5, 5> inRobotFrame = Matrixd<5, 5>::Identity();
+  inRobotFrame(0, 0) = std::cos(x(State::kHeading));
+  inRobotFrame(0, 1) = std::sin(x(State::kHeading));
+  inRobotFrame(1, 0) = -std::sin(x(State::kHeading));
+  inRobotFrame(1, 1) = std::cos(x(State::kHeading));
+
+  Vectord<5> r{poseRef.X().value(), poseRef.Y().value(),
+               poseRef.Rotation().Radians().value(), leftVelocityRef.value(),
+               rightVelocityRef.value()};
+  m_error = r - x;
+  m_error(State::kHeading) =
+      frc::AngleModulus(units::radian_t{m_error(State::kHeading)}).value();
+
+  units::meters_per_second_t velocity{(leftVelocity + rightVelocity) / 2.0};
+  const auto& K = m_table[velocity];
+
+  Vectord<2> u = K * inRobotFrame * m_error;
+
+  return DifferentialDriveWheelVoltages{units::volt_t{u(0)},
+                                        units::volt_t{u(1)}};
+}
+
+DifferentialDriveWheelVoltages LTVDifferentialDriveController::Calculate(
+    const Pose2d& currentPose, units::meters_per_second_t leftVelocity,
+    units::meters_per_second_t rightVelocity,
+    const Trajectory::State& desiredState) {
+  // v = (v_r + v_l) / 2     (1)
+  // w = (v_r - v_l) / (2r)  (2)
+  // k = w / v               (3)
+  //
+  // v_l = v - wr
+  // v_l = v - (vk)r
+  // v_l = v(1 - kr)
+  //
+  // v_r = v + wr
+  // v_r = v + (vk)r
+  // v_r = v(1 + kr)
+  return Calculate(
+      currentPose, leftVelocity, rightVelocity, desiredState.pose,
+      desiredState.velocity *
+          (1 - (desiredState.curvature / 1_rad * m_trackwidth / 2.0)),
+      desiredState.velocity *
+          (1 + (desiredState.curvature / 1_rad * m_trackwidth / 2.0)));
+}
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/controller/LTVUnicycleController.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/controller/LTVUnicycleController.cpp
new file mode 100644
index 0000000..256b757
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/controller/LTVUnicycleController.cpp
@@ -0,0 +1,133 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/controller/LTVUnicycleController.h"
+
+#include "frc/StateSpaceUtil.h"
+#include "frc/controller/LinearQuadraticRegulator.h"
+#include "units/math.h"
+
+using namespace frc;
+
+namespace {
+
+/**
+ * States of the drivetrain system.
+ */
+class State {
+ public:
+  /// X position in global coordinate frame.
+  [[maybe_unused]] static constexpr int kX = 0;
+
+  /// Y position in global coordinate frame.
+  static constexpr int kY = 1;
+
+  /// Heading in global coordinate frame.
+  static constexpr int kHeading = 2;
+};
+
+}  // namespace
+
+LTVUnicycleController::LTVUnicycleController(
+    units::second_t dt, units::meters_per_second_t maxVelocity)
+    : LTVUnicycleController{{0.0625, 0.125, 2.0}, {1.0, 2.0}, dt, maxVelocity} {
+}
+
+LTVUnicycleController::LTVUnicycleController(
+    const wpi::array<double, 3>& Qelems, const wpi::array<double, 2>& Relems,
+    units::second_t dt, units::meters_per_second_t maxVelocity) {
+  // The change in global pose for a unicycle is defined by the following three
+  // equations.
+  //
+  // ẋ = v cosθ
+  // ẏ = v sinθ
+  // θ̇ = ω
+  //
+  // Here's the model as a vector function where x = [x  y  θ]ᵀ and u = [v  ω]ᵀ.
+  //
+  //           [v cosθ]
+  // f(x, u) = [v sinθ]
+  //           [  ω   ]
+  //
+  // To create an LQR, we need to linearize this.
+  //
+  //               [0  0  −v sinθ]                  [cosθ  0]
+  // ∂f(x, u)/∂x = [0  0   v cosθ]    ∂f(x, u)/∂u = [sinθ  0]
+  //               [0  0     0   ]                  [ 0    1]
+  //
+  // We're going to make a cross-track error controller, so we'll apply a
+  // clockwise rotation matrix to the global tracking error to transform it into
+  // the robot's coordinate frame. Since the cross-track error is always
+  // measured from the robot's coordinate frame, the model used to compute the
+  // LQR should be linearized around θ = 0 at all times.
+  //
+  //     [0  0  −v sin0]        [cos0  0]
+  // A = [0  0   v cos0]    B = [sin0  0]
+  //     [0  0     0   ]        [ 0    1]
+  //
+  //     [0  0  0]              [1  0]
+  // A = [0  0  v]          B = [0  0]
+  //     [0  0  0]              [0  1]
+  Matrixd<3, 3> A = Matrixd<3, 3>::Zero();
+  Matrixd<3, 2> B{{1.0, 0.0}, {0.0, 0.0}, {0.0, 1.0}};
+  Matrixd<3, 3> Q = frc::MakeCostMatrix(Qelems);
+  Matrixd<2, 2> R = frc::MakeCostMatrix(Relems);
+
+  for (auto velocity = -maxVelocity; velocity < maxVelocity;
+       velocity += 0.01_mps) {
+    // The DARE is ill-conditioned if the velocity is close to zero, so don't
+    // let the system stop.
+    if (units::math::abs(velocity) < 1e-4_mps) {
+      m_table.insert(velocity, Matrixd<2, 3>::Zero());
+    } else {
+      A(State::kY, State::kHeading) = velocity.value();
+      m_table.insert(velocity,
+                     frc::LinearQuadraticRegulator<3, 2>{A, B, Q, R, dt}.K());
+    }
+  }
+}
+
+bool LTVUnicycleController::AtReference() const {
+  const auto& eTranslate = m_poseError.Translation();
+  const auto& eRotate = m_poseError.Rotation();
+  const auto& tolTranslate = m_poseTolerance.Translation();
+  const auto& tolRotate = m_poseTolerance.Rotation();
+  return units::math::abs(eTranslate.X()) < tolTranslate.X() &&
+         units::math::abs(eTranslate.Y()) < tolTranslate.Y() &&
+         units::math::abs(eRotate.Radians()) < tolRotate.Radians();
+}
+
+void LTVUnicycleController::SetTolerance(const Pose2d& poseTolerance) {
+  m_poseTolerance = poseTolerance;
+}
+
+ChassisSpeeds LTVUnicycleController::Calculate(
+    const Pose2d& currentPose, const Pose2d& poseRef,
+    units::meters_per_second_t linearVelocityRef,
+    units::radians_per_second_t angularVelocityRef) {
+  if (!m_enabled) {
+    return ChassisSpeeds{linearVelocityRef, 0_mps, angularVelocityRef};
+  }
+
+  m_poseError = poseRef.RelativeTo(currentPose);
+
+  const auto& K = m_table[linearVelocityRef];
+  Vectord<3> e{m_poseError.X().value(), m_poseError.Y().value(),
+               m_poseError.Rotation().Radians().value()};
+  Vectord<2> u = K * e;
+
+  return ChassisSpeeds{linearVelocityRef + units::meters_per_second_t{u(0)},
+                       0_mps,
+                       angularVelocityRef + units::radians_per_second_t{u(1)}};
+}
+
+ChassisSpeeds LTVUnicycleController::Calculate(
+    const Pose2d& currentPose, const Trajectory::State& desiredState) {
+  return Calculate(currentPose, desiredState.pose, desiredState.velocity,
+                   desiredState.velocity * desiredState.curvature);
+}
+
+void LTVUnicycleController::SetEnabled(bool enabled) {
+  m_enabled = enabled;
+}
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/controller/LinearQuadraticRegulator.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/controller/LinearQuadraticRegulator.cpp
index 4d2fbe9..2ab27d1 100644
--- a/third_party/allwpilib/wpimath/src/main/native/cpp/controller/LinearQuadraticRegulator.cpp
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/controller/LinearQuadraticRegulator.cpp
@@ -6,61 +6,11 @@
 
 namespace frc {
 
-LinearQuadraticRegulator<1, 1>::LinearQuadraticRegulator(
-    const Eigen::Matrix<double, 1, 1>& A, const Eigen::Matrix<double, 1, 1>& B,
-    const wpi::array<double, 1>& Qelems, const wpi::array<double, 1>& Relems,
-    units::second_t dt)
-    : LinearQuadraticRegulator(A, B, MakeCostMatrix(Qelems),
-                               MakeCostMatrix(Relems), dt) {}
-
-LinearQuadraticRegulator<1, 1>::LinearQuadraticRegulator(
-    const Eigen::Matrix<double, 1, 1>& A, const Eigen::Matrix<double, 1, 1>& B,
-    const Eigen::Matrix<double, 1, 1>& Q, const Eigen::Matrix<double, 1, 1>& R,
-    units::second_t dt)
-    : detail::LinearQuadraticRegulatorImpl<1, 1>(A, B, Q, R, dt) {}
-
-LinearQuadraticRegulator<1, 1>::LinearQuadraticRegulator(
-    const Eigen::Matrix<double, 1, 1>& A, const Eigen::Matrix<double, 1, 1>& B,
-    const Eigen::Matrix<double, 1, 1>& Q, const Eigen::Matrix<double, 1, 1>& R,
-    const Eigen::Matrix<double, 1, 1>& N, units::second_t dt)
-    : detail::LinearQuadraticRegulatorImpl<1, 1>(A, B, Q, R, N, dt) {}
-
-LinearQuadraticRegulator<2, 1>::LinearQuadraticRegulator(
-    const Eigen::Matrix<double, 2, 2>& A, const Eigen::Matrix<double, 2, 1>& B,
-    const wpi::array<double, 2>& Qelems, const wpi::array<double, 1>& Relems,
-    units::second_t dt)
-    : LinearQuadraticRegulator(A, B, MakeCostMatrix(Qelems),
-                               MakeCostMatrix(Relems), dt) {}
-
-LinearQuadraticRegulator<2, 1>::LinearQuadraticRegulator(
-    const Eigen::Matrix<double, 2, 2>& A, const Eigen::Matrix<double, 2, 1>& B,
-    const Eigen::Matrix<double, 2, 2>& Q, const Eigen::Matrix<double, 1, 1>& R,
-    units::second_t dt)
-    : detail::LinearQuadraticRegulatorImpl<2, 1>(A, B, Q, R, dt) {}
-
-LinearQuadraticRegulator<2, 1>::LinearQuadraticRegulator(
-    const Eigen::Matrix<double, 2, 2>& A, const Eigen::Matrix<double, 2, 1>& B,
-    const Eigen::Matrix<double, 2, 2>& Q, const Eigen::Matrix<double, 1, 1>& R,
-    const Eigen::Matrix<double, 2, 1>& N, units::second_t dt)
-    : detail::LinearQuadraticRegulatorImpl<2, 1>(A, B, Q, R, N, dt) {}
-
-LinearQuadraticRegulator<2, 2>::LinearQuadraticRegulator(
-    const Eigen::Matrix<double, 2, 2>& A, const Eigen::Matrix<double, 2, 2>& B,
-    const wpi::array<double, 2>& Qelems, const wpi::array<double, 2>& Relems,
-    units::second_t dt)
-    : LinearQuadraticRegulator(A, B, MakeCostMatrix(Qelems),
-                               MakeCostMatrix(Relems), dt) {}
-
-LinearQuadraticRegulator<2, 2>::LinearQuadraticRegulator(
-    const Eigen::Matrix<double, 2, 2>& A, const Eigen::Matrix<double, 2, 2>& B,
-    const Eigen::Matrix<double, 2, 2>& Q, const Eigen::Matrix<double, 2, 2>& R,
-    units::second_t dt)
-    : detail::LinearQuadraticRegulatorImpl<2, 2>(A, B, Q, R, dt) {}
-
-LinearQuadraticRegulator<2, 2>::LinearQuadraticRegulator(
-    const Eigen::Matrix<double, 2, 2>& A, const Eigen::Matrix<double, 2, 2>& B,
-    const Eigen::Matrix<double, 2, 2>& Q, const Eigen::Matrix<double, 2, 2>& R,
-    const Eigen::Matrix<double, 2, 2>& N, units::second_t dt)
-    : detail::LinearQuadraticRegulatorImpl<2, 2>(A, B, Q, R, N, dt) {}
+template class EXPORT_TEMPLATE_DEFINE(WPILIB_DLLEXPORT)
+    LinearQuadraticRegulator<1, 1>;
+template class EXPORT_TEMPLATE_DEFINE(WPILIB_DLLEXPORT)
+    LinearQuadraticRegulator<2, 1>;
+template class EXPORT_TEMPLATE_DEFINE(WPILIB_DLLEXPORT)
+    LinearQuadraticRegulator<2, 2>;
 
 }  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/controller/PIDController.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/controller/PIDController.cpp
index 34af2aa..6c89d25 100644
--- a/third_party/allwpilib/wpimath/src/main/native/cpp/controller/PIDController.cpp
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/controller/PIDController.cpp
@@ -24,7 +24,7 @@
         period.value());
     m_period = 20_ms;
     wpi::math::MathSharedStore::ReportWarning(
-        "{}", "Controller period defaulted to 20ms.");
+        "Controller period defaulted to 20ms.");
   }
   static int instances = 0;
   instances++;
@@ -65,11 +65,29 @@
 }
 
 units::second_t PIDController::GetPeriod() const {
-  return units::second_t(m_period);
+  return m_period;
+}
+
+double PIDController::GetPositionTolerance() const {
+  return m_positionTolerance;
+}
+
+double PIDController::GetVelocityTolerance() const {
+  return m_velocityTolerance;
 }
 
 void PIDController::SetSetpoint(double setpoint) {
   m_setpoint = setpoint;
+
+  if (m_continuous) {
+    double errorBound = (m_maximumInput - m_minimumInput) / 2.0;
+    m_positionError =
+        frc::InputModulus(m_setpoint - m_measurement, -errorBound, errorBound);
+  } else {
+    m_positionError = m_setpoint - m_measurement;
+  }
+
+  m_velocityError = (m_positionError - m_prevError) / m_period.value();
 }
 
 double PIDController::GetSetpoint() const {
@@ -77,19 +95,8 @@
 }
 
 bool PIDController::AtSetpoint() const {
-  double positionError;
-  if (m_continuous) {
-    double errorBound = (m_maximumInput - m_minimumInput) / 2.0;
-    positionError =
-        frc::InputModulus(m_setpoint - m_measurement, -errorBound, errorBound);
-  } else {
-    positionError = m_setpoint - m_measurement;
-  }
-
-  double velocityError = (positionError - m_prevError) / m_period.value();
-
-  return std::abs(positionError) < m_positionTolerance &&
-         std::abs(velocityError) < m_velocityTolerance;
+  return std::abs(m_positionError) < m_positionTolerance &&
+         std::abs(m_velocityError) < m_velocityTolerance;
 }
 
 void PIDController::EnableContinuousInput(double minimumInput,
@@ -136,7 +143,7 @@
     m_positionError =
         frc::InputModulus(m_setpoint - m_measurement, -errorBound, errorBound);
   } else {
-    m_positionError = m_setpoint - measurement;
+    m_positionError = m_setpoint - m_measurement;
   }
 
   m_velocityError = (m_positionError - m_prevError) / m_period.value();
@@ -151,14 +158,15 @@
 }
 
 double PIDController::Calculate(double measurement, double setpoint) {
-  // Set setpoint to provided value
-  SetSetpoint(setpoint);
+  m_setpoint = setpoint;
   return Calculate(measurement);
 }
 
 void PIDController::Reset() {
+  m_positionError = 0;
   m_prevError = 0;
   m_totalError = 0;
+  m_velocityError = 0;
 }
 
 void PIDController::InitSendable(wpi::SendableBuilder& builder) {
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/controller/ProfiledPIDController.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/controller/ProfiledPIDController.cpp
index fa58427..be678cb 100644
--- a/third_party/allwpilib/wpimath/src/main/native/cpp/controller/ProfiledPIDController.cpp
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/controller/ProfiledPIDController.cpp
@@ -4,9 +4,7 @@
 
 #include "frc/controller/ProfiledPIDController.h"
 
-void frc::detail::ReportProfiledPIDController() {
+int frc::detail::IncrementAndGetProfiledPIDControllerInstances() {
   static int instances = 0;
-  ++instances;
-  wpi::math::MathSharedStore::ReportUsage(
-      wpi::math::MathUsageId::kController_ProfiledPIDController, instances);
+  return ++instances;
 }
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/controller/RamseteController.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/controller/RamseteController.cpp
index 0fea864..576b0a9 100644
--- a/third_party/allwpilib/wpimath/src/main/native/cpp/controller/RamseteController.cpp
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/controller/RamseteController.cpp
@@ -24,17 +24,13 @@
   }
 }
 
-RamseteController::RamseteController(double b, double zeta)
-    : RamseteController(units::unit_t<b_unit>{b},
-                        units::unit_t<zeta_unit>{zeta}) {}
-
 RamseteController::RamseteController(units::unit_t<b_unit> b,
                                      units::unit_t<zeta_unit> zeta)
     : m_b{b}, m_zeta{zeta} {}
 
 RamseteController::RamseteController()
-    : RamseteController(units::unit_t<b_unit>{2.0},
-                        units::unit_t<zeta_unit>{0.7}) {}
+    : RamseteController{units::unit_t<b_unit>{2.0},
+                        units::unit_t<zeta_unit>{0.7}} {}
 
 bool RamseteController::AtReference() const {
   const auto& eTranslate = m_poseError.Translation();
@@ -67,10 +63,13 @@
   const auto& vRef = linearVelocityRef;
   const auto& omegaRef = angularVelocityRef;
 
+  // k = 2ζ√(ω_ref² + b v_ref²)
   auto k = 2.0 * m_zeta *
            units::math::sqrt(units::math::pow<2>(omegaRef) +
                              m_b * units::math::pow<2>(vRef));
 
+  // v_cmd = v_ref cos(e_θ) + k e_x
+  // ω_cmd = ω_ref + k e_θ + b v_ref sinc(e_θ) e_y
   return ChassisSpeeds{vRef * m_poseError.Rotation().Cos() + k * eX, 0_mps,
                        omegaRef + k * eTheta + m_b * vRef * Sinc(eTheta) * eY};
 }
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/estimator/DifferentialDrivePoseEstimator.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/estimator/DifferentialDrivePoseEstimator.cpp
index c5ed7a1..39e0d8c 100644
--- a/third_party/allwpilib/wpimath/src/main/native/cpp/estimator/DifferentialDrivePoseEstimator.cpp
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/estimator/DifferentialDrivePoseEstimator.cpp
@@ -11,135 +11,154 @@
 
 using namespace frc;
 
+DifferentialDrivePoseEstimator::InterpolationRecord
+DifferentialDrivePoseEstimator::InterpolationRecord::Interpolate(
+    DifferentialDriveKinematics& kinematics, InterpolationRecord endValue,
+    double i) const {
+  if (i < 0) {
+    return *this;
+  } else if (i > 1) {
+    return endValue;
+  } else {
+    // Find the interpolated left distance.
+    auto left = wpi::Lerp(this->leftDistance, endValue.leftDistance, i);
+    // Find the interpolated right distance.
+    auto right = wpi::Lerp(this->rightDistance, endValue.rightDistance, i);
+
+    // Find the new gyro angle.
+    auto gyro = wpi::Lerp(this->gyroAngle, endValue.gyroAngle, i);
+
+    // Create a twist to represent this changed based on the interpolated
+    // sensor inputs.
+    auto twist =
+        kinematics.ToTwist2d(left - leftDistance, right - rightDistance);
+    twist.dtheta = (gyro - gyroAngle).Radians();
+
+    return {pose.Exp(twist), gyro, left, right};
+  }
+}
+
 DifferentialDrivePoseEstimator::DifferentialDrivePoseEstimator(
-    const Rotation2d& gyroAngle, const Pose2d& initialPose,
-    const wpi::array<double, 5>& stateStdDevs,
-    const wpi::array<double, 3>& localMeasurementStdDevs,
-    const wpi::array<double, 3>& visionMeasurmentStdDevs,
-    units::second_t nominalDt)
-    : m_observer(
-          &DifferentialDrivePoseEstimator::F,
-          [](const Eigen::Vector<double, 5>& x,
-             const Eigen::Vector<double, 3>& u) {
-            return Eigen::Vector<double, 3>{x(3, 0), x(4, 0), x(2, 0)};
-          },
-          stateStdDevs, localMeasurementStdDevs, frc::AngleMean<5, 5>(2),
-          frc::AngleMean<3, 5>(2), frc::AngleResidual<5>(2),
-          frc::AngleResidual<3>(2), frc::AngleAdd<5>(2), nominalDt),
-      m_nominalDt(nominalDt) {
-  SetVisionMeasurementStdDevs(visionMeasurmentStdDevs);
+    DifferentialDriveKinematics& kinematics, const Rotation2d& gyroAngle,
+    units::meter_t leftDistance, units::meter_t rightDistance,
+    const Pose2d& initialPose)
+    : DifferentialDrivePoseEstimator{
+          kinematics,  gyroAngle,          leftDistance,   rightDistance,
+          initialPose, {0.02, 0.02, 0.01}, {0.1, 0.1, 0.1}} {}
 
-  // Create correction mechanism for vision measurements.
-  m_visionCorrect = [&](const Eigen::Vector<double, 3>& u,
-                        const Eigen::Vector<double, 3>& y) {
-    m_observer.Correct<3>(
-        u, y,
-        [](const Eigen::Vector<double, 5>& x, const Eigen::Vector<double, 3>&) {
-          return x.block<3, 1>(0, 0);
-        },
-        m_visionContR, frc::AngleMean<3, 5>(2), frc::AngleResidual<3>(2),
-        frc::AngleResidual<5>(2), frc::AngleAdd<5>(2));
-  };
+DifferentialDrivePoseEstimator::DifferentialDrivePoseEstimator(
+    DifferentialDriveKinematics& kinematics, const Rotation2d& gyroAngle,
+    units::meter_t leftDistance, units::meter_t rightDistance,
+    const Pose2d& initialPose, const wpi::array<double, 3>& stateStdDevs,
+    const wpi::array<double, 3>& visionMeasurementStdDevs)
+    : m_kinematics{kinematics},
+      m_odometry{gyroAngle, leftDistance, rightDistance, initialPose} {
+  for (size_t i = 0; i < 3; ++i) {
+    m_q[i] = stateStdDevs[i] * stateStdDevs[i];
+  }
 
-  m_gyroOffset = initialPose.Rotation() - gyroAngle;
-  m_previousAngle = initialPose.Rotation();
-  m_observer.SetXhat(FillStateVector(initialPose, 0_m, 0_m));
+  SetVisionMeasurementStdDevs(visionMeasurementStdDevs);
 }
 
 void DifferentialDrivePoseEstimator::SetVisionMeasurementStdDevs(
-    const wpi::array<double, 3>& visionMeasurmentStdDevs) {
-  // Create R (covariances) for vision measurements.
-  m_visionContR = frc::MakeCovMatrix(visionMeasurmentStdDevs);
+    const wpi::array<double, 3>& visionMeasurementStdDevs) {
+  wpi::array<double, 3> r{wpi::empty_array};
+  for (size_t i = 0; i < 3; ++i) {
+    r[i] = visionMeasurementStdDevs[i] * visionMeasurementStdDevs[i];
+  }
+
+  // Solve for closed form Kalman gain for continuous Kalman filter with A = 0
+  // and C = I. See wpimath/algorithms.md.
+  for (size_t row = 0; row < 3; ++row) {
+    if (m_q[row] == 0.0) {
+      m_visionK(row, row) = 0.0;
+    } else {
+      m_visionK(row, row) =
+          m_q[row] / (m_q[row] + std::sqrt(m_q[row] * r[row]));
+    }
+  }
 }
 
-void DifferentialDrivePoseEstimator::ResetPosition(
-    const Pose2d& pose, const Rotation2d& gyroAngle) {
+void DifferentialDrivePoseEstimator::ResetPosition(const Rotation2d& gyroAngle,
+                                                   units::meter_t leftDistance,
+                                                   units::meter_t rightDistance,
+                                                   const Pose2d& pose) {
   // Reset state estimate and error covariance
-  m_observer.Reset();
-  m_latencyCompensator.Reset();
-
-  m_observer.SetXhat(FillStateVector(pose, 0_m, 0_m));
-
-  m_gyroOffset = GetEstimatedPosition().Rotation() - gyroAngle;
-  m_previousAngle = pose.Rotation();
+  m_odometry.ResetPosition(gyroAngle, leftDistance, rightDistance, pose);
+  m_poseBuffer.Clear();
 }
 
 Pose2d DifferentialDrivePoseEstimator::GetEstimatedPosition() const {
-  return Pose2d(units::meter_t(m_observer.Xhat(0)),
-                units::meter_t(m_observer.Xhat(1)),
-                Rotation2d(units::radian_t(m_observer.Xhat(2))));
+  return m_odometry.GetPose();
 }
 
 void DifferentialDrivePoseEstimator::AddVisionMeasurement(
     const Pose2d& visionRobotPose, units::second_t timestamp) {
-  m_latencyCompensator.ApplyPastGlobalMeasurement<3>(
-      &m_observer, m_nominalDt, PoseTo3dVector(visionRobotPose),
-      m_visionCorrect, timestamp);
+  // Step 1: Get the estimated pose from when the vision measurement was made.
+  auto sample = m_poseBuffer.Sample(timestamp);
+
+  if (!sample.has_value()) {
+    return;
+  }
+
+  // Step 2: Measure the twist between the odometry pose and the vision pose.
+  auto twist = sample.value().pose.Log(visionRobotPose);
+
+  // Step 3: We should not trust the twist entirely, so instead we scale this
+  // twist by a Kalman gain matrix representing how much we trust vision
+  // measurements compared to our current pose.
+  frc::Vectord<3> k_times_twist =
+      m_visionK *
+      frc::Vectord<3>{twist.dx.value(), twist.dy.value(), twist.dtheta.value()};
+
+  // Step 4: Convert back to Twist2d.
+  Twist2d scaledTwist{units::meter_t{k_times_twist(0)},
+                      units::meter_t{k_times_twist(1)},
+                      units::radian_t{k_times_twist(2)}};
+
+  // Step 5: Reset Odometry to state at sample with vision adjustment.
+  m_odometry.ResetPosition(
+      sample.value().gyroAngle, sample.value().leftDistance,
+      sample.value().rightDistance, sample.value().pose.Exp(scaledTwist));
+
+  // Step 6: Replay odometry inputs between sample time and latest recorded
+  // sample to update the pose buffer and correct odometry.
+  auto internal_buf = m_poseBuffer.GetInternalBuffer();
+
+  auto first_newer_record =
+      std::lower_bound(internal_buf.begin(), internal_buf.end(), timestamp,
+                       [](const auto& pair, auto t) { return t > pair.first; });
+
+  for (auto entry = first_newer_record + 1; entry != internal_buf.end();
+       entry++) {
+    UpdateWithTime(entry->first, entry->second.gyroAngle,
+                   entry->second.leftDistance, entry->second.rightDistance);
+  }
 }
 
-Pose2d DifferentialDrivePoseEstimator::Update(
-    const Rotation2d& gyroAngle,
-    const DifferentialDriveWheelSpeeds& wheelSpeeds,
-    units::meter_t leftDistance, units::meter_t rightDistance) {
+Pose2d DifferentialDrivePoseEstimator::Update(const Rotation2d& gyroAngle,
+                                              units::meter_t leftDistance,
+                                              units::meter_t rightDistance) {
   return UpdateWithTime(units::microsecond_t(wpi::Now()), gyroAngle,
-                        wheelSpeeds, leftDistance, rightDistance);
+                        leftDistance, rightDistance);
 }
 
 Pose2d DifferentialDrivePoseEstimator::UpdateWithTime(
     units::second_t currentTime, const Rotation2d& gyroAngle,
-    const DifferentialDriveWheelSpeeds& wheelSpeeds,
     units::meter_t leftDistance, units::meter_t rightDistance) {
-  auto dt = m_prevTime >= 0_s ? currentTime - m_prevTime : m_nominalDt;
-  m_prevTime = currentTime;
+  m_odometry.Update(gyroAngle, leftDistance, rightDistance);
 
-  auto angle = gyroAngle + m_gyroOffset;
-  auto omega = (gyroAngle - m_previousAngle).Radians() / dt;
+  // fmt::print("odo, {}, {}, {}, {}, {}, {}\n",
+  //   gyroAngle.Radians(),
+  //   leftDistance,
+  //   rightDistance,
+  //   GetEstimatedPosition().X(),
+  //   GetEstimatedPosition().Y(),
+  //   GetEstimatedPosition().Rotation().Radians()
+  // );
 
-  auto u = Eigen::Vector<double, 3>{
-      (wheelSpeeds.left + wheelSpeeds.right).value() / 2.0, 0.0, omega.value()};
-
-  m_previousAngle = angle;
-
-  auto localY = Eigen::Vector<double, 3>{
-      leftDistance.value(), rightDistance.value(), angle.Radians().value()};
-
-  m_latencyCompensator.AddObserverState(m_observer, u, localY, currentTime);
-  m_observer.Predict(u, dt);
-  m_observer.Correct(u, localY);
+  m_poseBuffer.AddSample(currentTime, {GetEstimatedPosition(), gyroAngle,
+                                       leftDistance, rightDistance});
 
   return GetEstimatedPosition();
 }
-
-Eigen::Vector<double, 5> DifferentialDrivePoseEstimator::F(
-    const Eigen::Vector<double, 5>& x, const Eigen::Vector<double, 3>& u) {
-  // Apply a rotation matrix. Note that we do not add x because Runge-Kutta does
-  // that for us.
-  auto& theta = x(2);
-  Eigen::Matrix<double, 5, 5> toFieldRotation{
-      {std::cos(theta), -std::sin(theta), 0.0, 0.0, 0.0},
-      {std::sin(theta), std::cos(theta), 0.0, 0.0, 0.0},
-      {0.0, 0.0, 1.0, 0.0, 0.0},
-      {0.0, 0.0, 0.0, 1.0, 0.0},
-      {0.0, 0.0, 0.0, 0.0, 1.0}};
-  return toFieldRotation *
-         Eigen::Vector<double, 5>{u(0, 0), u(1, 0), u(2, 0), u(0, 0), u(1, 0)};
-}
-
-template <int Dim>
-wpi::array<double, Dim> DifferentialDrivePoseEstimator::StdDevMatrixToArray(
-    const Eigen::Vector<double, Dim>& stdDevs) {
-  wpi::array<double, Dim> array;
-  for (size_t i = 0; i < Dim; ++i) {
-    array[i] = stdDevs(i);
-  }
-  return array;
-}
-
-Eigen::Vector<double, 5> DifferentialDrivePoseEstimator::FillStateVector(
-    const Pose2d& pose, units::meter_t leftDistance,
-    units::meter_t rightDistance) {
-  return Eigen::Vector<double, 5>{pose.Translation().X().value(),
-                                  pose.Translation().Y().value(),
-                                  pose.Rotation().Radians().value(),
-                                  leftDistance.value(), rightDistance.value()};
-}
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/estimator/KalmanFilter.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/estimator/KalmanFilter.cpp
index 1209eae..a56efe4 100644
--- a/third_party/allwpilib/wpimath/src/main/native/cpp/estimator/KalmanFilter.cpp
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/estimator/KalmanFilter.cpp
@@ -6,16 +6,7 @@
 
 namespace frc {
 
-KalmanFilter<1, 1, 1>::KalmanFilter(
-    LinearSystem<1, 1, 1>& plant, const wpi::array<double, 1>& stateStdDevs,
-    const wpi::array<double, 1>& measurementStdDevs, units::second_t dt)
-    : detail::KalmanFilterImpl<1, 1, 1>{plant, stateStdDevs, measurementStdDevs,
-                                        dt} {}
-
-KalmanFilter<2, 1, 1>::KalmanFilter(
-    LinearSystem<2, 1, 1>& plant, const wpi::array<double, 2>& stateStdDevs,
-    const wpi::array<double, 1>& measurementStdDevs, units::second_t dt)
-    : detail::KalmanFilterImpl<2, 1, 1>{plant, stateStdDevs, measurementStdDevs,
-                                        dt} {}
+template class EXPORT_TEMPLATE_DEFINE(WPILIB_DLLEXPORT) KalmanFilter<1, 1, 1>;
+template class EXPORT_TEMPLATE_DEFINE(WPILIB_DLLEXPORT) KalmanFilter<2, 1, 1>;
 
 }  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/estimator/MecanumDrivePoseEstimator.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/estimator/MecanumDrivePoseEstimator.cpp
index 9d93647..9642e08 100644
--- a/third_party/allwpilib/wpimath/src/main/native/cpp/estimator/MecanumDrivePoseEstimator.cpp
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/estimator/MecanumDrivePoseEstimator.cpp
@@ -11,106 +11,159 @@
 
 using namespace frc;
 
+frc::MecanumDrivePoseEstimator::InterpolationRecord
+frc::MecanumDrivePoseEstimator::InterpolationRecord::Interpolate(
+    MecanumDriveKinematics& kinematics, InterpolationRecord endValue,
+    double i) const {
+  if (i < 0) {
+    return *this;
+  } else if (i > 1) {
+    return endValue;
+  } else {
+    // Find the new wheel distance measurements.
+    MecanumDriveWheelPositions wheels_lerp{
+        wpi::Lerp(this->wheelPositions.frontLeft,
+                  endValue.wheelPositions.frontLeft, i),
+        wpi::Lerp(this->wheelPositions.frontRight,
+                  endValue.wheelPositions.frontRight, i),
+        wpi::Lerp(this->wheelPositions.rearLeft,
+                  endValue.wheelPositions.rearLeft, i),
+        wpi::Lerp(this->wheelPositions.rearRight,
+                  endValue.wheelPositions.rearRight, i)};
+
+    // Find the distance between this measurement and the
+    // interpolated measurement.
+    MecanumDriveWheelPositions wheels_delta{
+        wheels_lerp.frontLeft - this->wheelPositions.frontLeft,
+        wheels_lerp.frontRight - this->wheelPositions.frontRight,
+        wheels_lerp.rearLeft - this->wheelPositions.rearLeft,
+        wheels_lerp.rearRight - this->wheelPositions.rearRight};
+
+    // Find the new gyro angle.
+    auto gyro = wpi::Lerp(this->gyroAngle, endValue.gyroAngle, i);
+
+    // Create a twist to represent this changed based on the interpolated
+    // sensor inputs.
+    auto twist = kinematics.ToTwist2d(wheels_delta);
+    twist.dtheta = (gyro - gyroAngle).Radians();
+
+    return {pose.Exp(twist), gyro, wheels_lerp};
+  }
+}
+
 frc::MecanumDrivePoseEstimator::MecanumDrivePoseEstimator(
-    const Rotation2d& gyroAngle, const Pose2d& initialPose,
-    MecanumDriveKinematics kinematics,
+    MecanumDriveKinematics& kinematics, const Rotation2d& gyroAngle,
+    const MecanumDriveWheelPositions& wheelPositions, const Pose2d& initialPose)
+    : MecanumDrivePoseEstimator{kinematics,      gyroAngle,
+                                wheelPositions,  initialPose,
+                                {0.1, 0.1, 0.1}, {0.45, 0.45, 0.45}} {}
+
+frc::MecanumDrivePoseEstimator::MecanumDrivePoseEstimator(
+    MecanumDriveKinematics& kinematics, const Rotation2d& gyroAngle,
+    const MecanumDriveWheelPositions& wheelPositions, const Pose2d& initialPose,
     const wpi::array<double, 3>& stateStdDevs,
-    const wpi::array<double, 1>& localMeasurementStdDevs,
-    const wpi::array<double, 3>& visionMeasurementStdDevs,
-    units::second_t nominalDt)
-    : m_observer(
-          [](const Eigen::Vector<double, 3>& x,
-             const Eigen::Vector<double, 3>& u) { return u; },
-          [](const Eigen::Vector<double, 3>& x,
-             const Eigen::Vector<double, 3>& u) { return x.block<1, 1>(2, 0); },
-          stateStdDevs, localMeasurementStdDevs, frc::AngleMean<3, 3>(2),
-          frc::AngleMean<1, 3>(0), frc::AngleResidual<3>(2),
-          frc::AngleResidual<1>(0), frc::AngleAdd<3>(2), nominalDt),
-      m_kinematics(kinematics),
-      m_nominalDt(nominalDt) {
+    const wpi::array<double, 3>& visionMeasurementStdDevs)
+    : m_kinematics{kinematics},
+      m_odometry{kinematics, gyroAngle, wheelPositions, initialPose} {
+  for (size_t i = 0; i < 3; ++i) {
+    m_q[i] = stateStdDevs[i] * stateStdDevs[i];
+  }
+
   SetVisionMeasurementStdDevs(visionMeasurementStdDevs);
-
-  // Create vision correction mechanism.
-  m_visionCorrect = [&](const Eigen::Vector<double, 3>& u,
-                        const Eigen::Vector<double, 3>& y) {
-    m_observer.Correct<3>(
-        u, y,
-        [](const Eigen::Vector<double, 3>& x, const Eigen::Vector<double, 3>&) {
-          return x;
-        },
-        m_visionContR, frc::AngleMean<3, 3>(2), frc::AngleResidual<3>(2),
-        frc::AngleResidual<3>(2), frc::AngleAdd<3>(2));
-  };
-
-  // Set initial state.
-  m_observer.SetXhat(PoseTo3dVector(initialPose));
-
-  // Calculate offsets.
-  m_gyroOffset = initialPose.Rotation() - gyroAngle;
-  m_previousAngle = initialPose.Rotation();
 }
 
 void frc::MecanumDrivePoseEstimator::SetVisionMeasurementStdDevs(
-    const wpi::array<double, 3>& visionMeasurmentStdDevs) {
-  // Create R (covariances) for vision measurements.
-  m_visionContR = frc::MakeCovMatrix(visionMeasurmentStdDevs);
+    const wpi::array<double, 3>& visionMeasurementStdDevs) {
+  wpi::array<double, 3> r{wpi::empty_array};
+  for (size_t i = 0; i < 3; ++i) {
+    r[i] = visionMeasurementStdDevs[i] * visionMeasurementStdDevs[i];
+  }
+
+  // Solve for closed form Kalman gain for continuous Kalman filter with A = 0
+  // and C = I. See wpimath/algorithms.md.
+  for (size_t row = 0; row < 3; ++row) {
+    if (m_q[row] == 0.0) {
+      m_visionK(row, row) = 0.0;
+    } else {
+      m_visionK(row, row) =
+          m_q[row] / (m_q[row] + std::sqrt(m_q[row] * r[row]));
+    }
+  }
 }
 
 void frc::MecanumDrivePoseEstimator::ResetPosition(
-    const Pose2d& pose, const Rotation2d& gyroAngle) {
+    const Rotation2d& gyroAngle,
+    const MecanumDriveWheelPositions& wheelPositions, const Pose2d& pose) {
   // Reset state estimate and error covariance
-  m_observer.Reset();
-  m_latencyCompensator.Reset();
-
-  m_observer.SetXhat(PoseTo3dVector(pose));
-
-  m_gyroOffset = pose.Rotation() - gyroAngle;
-  m_previousAngle = pose.Rotation();
+  m_odometry.ResetPosition(gyroAngle, wheelPositions, pose);
+  m_poseBuffer.Clear();
 }
 
 Pose2d frc::MecanumDrivePoseEstimator::GetEstimatedPosition() const {
-  return Pose2d(m_observer.Xhat(0) * 1_m, m_observer.Xhat(1) * 1_m,
-                Rotation2d(units::radian_t{m_observer.Xhat(2)}));
+  return m_odometry.GetPose();
 }
 
 void frc::MecanumDrivePoseEstimator::AddVisionMeasurement(
     const Pose2d& visionRobotPose, units::second_t timestamp) {
-  m_latencyCompensator.ApplyPastGlobalMeasurement<3>(
-      &m_observer, m_nominalDt, PoseTo3dVector(visionRobotPose),
-      m_visionCorrect, timestamp);
+  // Step 1: Get the estimated pose from when the vision measurement was made.
+  auto sample = m_poseBuffer.Sample(timestamp);
+
+  if (!sample.has_value()) {
+    return;
+  }
+
+  // Step 2: Measure the twist between the odometry pose and the vision pose
+  auto twist = sample.value().pose.Log(visionRobotPose);
+
+  // Step 3: We should not trust the twist entirely, so instead we scale this
+  // twist by a Kalman gain matrix representing how much we trust vision
+  // measurements compared to our current pose.
+  frc::Vectord<3> k_times_twist =
+      m_visionK *
+      frc::Vectord<3>{twist.dx.value(), twist.dy.value(), twist.dtheta.value()};
+
+  // Step 4: Convert back to Twist2d
+  Twist2d scaledTwist{units::meter_t{k_times_twist(0)},
+                      units::meter_t{k_times_twist(1)},
+                      units::radian_t{k_times_twist(2)}};
+
+  // Step 5: Reset Odometry to state at sample with vision adjustment.
+  m_odometry.ResetPosition(sample.value().gyroAngle,
+                           sample.value().wheelPositions,
+                           sample.value().pose.Exp(scaledTwist));
+
+  // Step 6: Replay odometry inputs between sample time and latest recorded
+  // sample to update the pose buffer and correct odometry.
+  auto internal_buf = m_poseBuffer.GetInternalBuffer();
+
+  auto upper_bound =
+      std::lower_bound(internal_buf.begin(), internal_buf.end(), timestamp,
+                       [](const auto& pair, auto t) { return t > pair.first; });
+
+  for (auto entry = upper_bound; entry != internal_buf.end(); entry++) {
+    UpdateWithTime(entry->first, entry->second.gyroAngle,
+                   entry->second.wheelPositions);
+  }
 }
 
 Pose2d frc::MecanumDrivePoseEstimator::Update(
-    const Rotation2d& gyroAngle, const MecanumDriveWheelSpeeds& wheelSpeeds) {
+    const Rotation2d& gyroAngle,
+    const MecanumDriveWheelPositions& wheelPositions) {
   return UpdateWithTime(units::microsecond_t(wpi::Now()), gyroAngle,
-                        wheelSpeeds);
+                        wheelPositions);
 }
 
 Pose2d frc::MecanumDrivePoseEstimator::UpdateWithTime(
     units::second_t currentTime, const Rotation2d& gyroAngle,
-    const MecanumDriveWheelSpeeds& wheelSpeeds) {
-  auto dt = m_prevTime >= 0_s ? currentTime - m_prevTime : m_nominalDt;
-  m_prevTime = currentTime;
+    const MecanumDriveWheelPositions& wheelPositions) {
+  m_odometry.Update(gyroAngle, wheelPositions);
 
-  auto angle = gyroAngle + m_gyroOffset;
-  auto omega = (angle - m_previousAngle).Radians() / dt;
+  MecanumDriveWheelPositions internalWheelPositions{
+      wheelPositions.frontLeft, wheelPositions.frontRight,
+      wheelPositions.rearLeft, wheelPositions.rearRight};
 
-  auto chassisSpeeds = m_kinematics.ToChassisSpeeds(wheelSpeeds);
-  auto fieldRelativeVelocities =
-      Translation2d(chassisSpeeds.vx * 1_s, chassisSpeeds.vy * 1_s)
-          .RotateBy(angle);
-
-  Eigen::Vector<double, 3> u{fieldRelativeVelocities.X().value(),
-                             fieldRelativeVelocities.Y().value(),
-                             omega.value()};
-
-  Eigen::Vector<double, 1> localY{angle.Radians().value()};
-  m_previousAngle = angle;
-
-  m_latencyCompensator.AddObserverState(m_observer, u, localY, currentTime);
-
-  m_observer.Predict(u, dt);
-  m_observer.Correct(u, localY);
+  m_poseBuffer.AddSample(
+      currentTime, {GetEstimatedPosition(), gyroAngle, internalWheelPositions});
 
   return GetEstimatedPosition();
 }
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/estimator/SwerveDrivePoseEstimator.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/estimator/SwerveDrivePoseEstimator.cpp
new file mode 100644
index 0000000..f2ed301
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/estimator/SwerveDrivePoseEstimator.cpp
@@ -0,0 +1,12 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/estimator/SwerveDrivePoseEstimator.h"
+
+namespace frc {
+
+template class EXPORT_TEMPLATE_DEFINE(WPILIB_DLLEXPORT)
+    SwerveDrivePoseEstimator<4>;
+
+}  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/estimator/UnscentedKalmanFilter.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/estimator/UnscentedKalmanFilter.cpp
new file mode 100644
index 0000000..d5e869b
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/estimator/UnscentedKalmanFilter.cpp
@@ -0,0 +1,14 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/estimator/UnscentedKalmanFilter.h"
+
+namespace frc {
+
+template class EXPORT_TEMPLATE_DEFINE(WPILIB_DLLEXPORT)
+    UnscentedKalmanFilter<3, 3, 1>;
+template class EXPORT_TEMPLATE_DEFINE(WPILIB_DLLEXPORT)
+    UnscentedKalmanFilter<5, 3, 3>;
+
+}  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/geometry/CoordinateAxis.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/geometry/CoordinateAxis.cpp
new file mode 100644
index 0000000..1d9c42a
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/geometry/CoordinateAxis.cpp
@@ -0,0 +1,41 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/geometry/CoordinateAxis.h"
+
+using namespace frc;
+
+CoordinateAxis::CoordinateAxis(double x, double y, double z) : m_axis{x, y, z} {
+  m_axis /= m_axis.norm();
+}
+
+const CoordinateAxis& CoordinateAxis::N() {
+  static const CoordinateAxis instance{1.0, 0.0, 0.0};
+  return instance;
+}
+
+const CoordinateAxis& CoordinateAxis::S() {
+  static const CoordinateAxis instance{-1.0, 0.0, 0.0};
+  return instance;
+}
+
+const CoordinateAxis& CoordinateAxis::E() {
+  static const CoordinateAxis instance{0.0, -1.0, 0.0};
+  return instance;
+}
+
+const CoordinateAxis& CoordinateAxis::W() {
+  static const CoordinateAxis instance{0.0, 1.0, 0.0};
+  return instance;
+}
+
+const CoordinateAxis& CoordinateAxis::U() {
+  static const CoordinateAxis instance{0.0, 0.0, 1.0};
+  return instance;
+}
+
+const CoordinateAxis& CoordinateAxis::D() {
+  static const CoordinateAxis instance{0.0, 0.0, -1.0};
+  return instance;
+}
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/geometry/CoordinateSystem.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/geometry/CoordinateSystem.cpp
new file mode 100644
index 0000000..d1ee93d
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/geometry/CoordinateSystem.cpp
@@ -0,0 +1,73 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/geometry/CoordinateSystem.h"
+
+#include <cmath>
+#include <stdexcept>
+#include <utility>
+
+#include "Eigen/QR"
+
+using namespace frc;
+
+CoordinateSystem::CoordinateSystem(const CoordinateAxis& positiveX,
+                                   const CoordinateAxis& positiveY,
+                                   const CoordinateAxis& positiveZ) {
+  // Construct a change of basis matrix from the source coordinate system to the
+  // NWU coordinate system. Each column vector in the change of basis matrix is
+  // one of the old basis vectors mapped to its representation in the new basis.
+  Matrixd<3, 3> R;
+  R.block<3, 1>(0, 0) = positiveX.m_axis;
+  R.block<3, 1>(0, 1) = positiveY.m_axis;
+  R.block<3, 1>(0, 2) = positiveZ.m_axis;
+
+  // The change of basis matrix should be a pure rotation. The Rotation3d
+  // constructor will verify this by checking for special orthogonality.
+  m_rotation = Rotation3d{R};
+}
+
+const CoordinateSystem& CoordinateSystem::NWU() {
+  static const CoordinateSystem instance{
+      CoordinateAxis::N(), CoordinateAxis::W(), CoordinateAxis::U()};
+  return instance;
+}
+
+const CoordinateSystem& CoordinateSystem::EDN() {
+  static const CoordinateSystem instance{
+      CoordinateAxis::E(), CoordinateAxis::D(), CoordinateAxis::N()};
+  return instance;
+}
+
+const CoordinateSystem& CoordinateSystem::NED() {
+  static const CoordinateSystem instance{
+      CoordinateAxis::N(), CoordinateAxis::E(), CoordinateAxis::D()};
+  return instance;
+}
+
+Translation3d CoordinateSystem::Convert(const Translation3d& translation,
+                                        const CoordinateSystem& from,
+                                        const CoordinateSystem& to) {
+  return translation.RotateBy(from.m_rotation - to.m_rotation);
+}
+
+Rotation3d CoordinateSystem::Convert(const Rotation3d& rotation,
+                                     const CoordinateSystem& from,
+                                     const CoordinateSystem& to) {
+  return rotation.RotateBy(from.m_rotation - to.m_rotation);
+}
+
+Pose3d CoordinateSystem::Convert(const Pose3d& pose,
+                                 const CoordinateSystem& from,
+                                 const CoordinateSystem& to) {
+  return Pose3d{Convert(pose.Translation(), from, to),
+                Convert(pose.Rotation(), from, to)};
+}
+
+Transform3d CoordinateSystem::Convert(const Transform3d& transform,
+                                      const CoordinateSystem& from,
+                                      const CoordinateSystem& to) {
+  return Transform3d{Convert(transform.Translation(), from, to),
+                     Convert(transform.Rotation(), from, to)};
+}
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/geometry/Pose2d.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/geometry/Pose2d.cpp
index b7176cd..2648a90 100644
--- a/third_party/allwpilib/wpimath/src/main/native/cpp/geometry/Pose2d.cpp
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/geometry/Pose2d.cpp
@@ -10,32 +10,9 @@
 
 using namespace frc;
 
-Pose2d::Pose2d(Translation2d translation, Rotation2d rotation)
-    : m_translation(translation), m_rotation(rotation) {}
-
-Pose2d::Pose2d(units::meter_t x, units::meter_t y, Rotation2d rotation)
-    : m_translation(x, y), m_rotation(rotation) {}
-
-Pose2d Pose2d::operator+(const Transform2d& other) const {
-  return TransformBy(other);
-}
-
 Transform2d Pose2d::operator-(const Pose2d& other) const {
   const auto pose = this->RelativeTo(other);
-  return Transform2d(pose.Translation(), pose.Rotation());
-}
-
-bool Pose2d::operator==(const Pose2d& other) const {
-  return m_translation == other.m_translation && m_rotation == other.m_rotation;
-}
-
-bool Pose2d::operator!=(const Pose2d& other) const {
-  return !operator==(other);
-}
-
-Pose2d Pose2d::TransformBy(const Transform2d& other) const {
-  return {m_translation + (other.Translation().RotateBy(m_rotation)),
-          m_rotation + other.Rotation()};
+  return Transform2d{pose.Translation(), pose.Rotation()};
 }
 
 Pose2d Pose2d::RelativeTo(const Pose2d& other) const {
@@ -87,7 +64,7 @@
           {halfThetaByTanOfHalfDtheta, -halfDtheta}) *
       std::hypot(halfThetaByTanOfHalfDtheta, halfDtheta);
 
-  return {translationPart.X(), translationPart.Y(), units::radian_t(dtheta)};
+  return {translationPart.X(), translationPart.Y(), units::radian_t{dtheta}};
 }
 
 void frc::to_json(wpi::json& json, const Pose2d& pose) {
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/geometry/Pose3d.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/geometry/Pose3d.cpp
new file mode 100644
index 0000000..4732c4d
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/geometry/Pose3d.cpp
@@ -0,0 +1,155 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/geometry/Pose3d.h"
+
+#include <cmath>
+
+#include <wpi/json.h>
+
+using namespace frc;
+
+namespace {
+
+/**
+ * Applies the hat operator to a rotation vector.
+ *
+ * It takes a rotation vector and returns the corresponding matrix
+ * representation of the Lie algebra element (a 3x3 rotation matrix).
+ *
+ * @param rotation The rotation vector.
+ * @return The rotation vector as a 3x3 rotation matrix.
+ */
+Matrixd<3, 3> RotationVectorToMatrix(const Vectord<3>& rotation) {
+  // Given a rotation vector <a, b, c>,
+  //         [ 0 -c  b]
+  // Omega = [ c  0 -a]
+  //         [-b  a  0]
+  return Matrixd<3, 3>{{0.0, -rotation(2), rotation(1)},
+                       {rotation(2), 0.0, -rotation(0)},
+                       {-rotation(1), rotation(0), 0.0}};
+}
+}  // namespace
+
+Pose3d::Pose3d(Translation3d translation, Rotation3d rotation)
+    : m_translation(std::move(translation)), m_rotation(std::move(rotation)) {}
+
+Pose3d::Pose3d(units::meter_t x, units::meter_t y, units::meter_t z,
+               Rotation3d rotation)
+    : m_translation(x, y, z), m_rotation(std::move(rotation)) {}
+
+Pose3d::Pose3d(const Pose2d& pose)
+    : m_translation(pose.X(), pose.Y(), 0_m),
+      m_rotation(0_rad, 0_rad, pose.Rotation().Radians()) {}
+
+Pose3d Pose3d::operator+(const Transform3d& other) const {
+  return TransformBy(other);
+}
+
+Transform3d Pose3d::operator-(const Pose3d& other) const {
+  const auto pose = this->RelativeTo(other);
+  return Transform3d{pose.Translation(), pose.Rotation()};
+}
+
+Pose3d Pose3d::operator*(double scalar) const {
+  return Pose3d{m_translation * scalar, m_rotation * scalar};
+}
+
+Pose3d Pose3d::operator/(double scalar) const {
+  return *this * (1.0 / scalar);
+}
+
+Pose3d Pose3d::TransformBy(const Transform3d& other) const {
+  return {m_translation + (other.Translation().RotateBy(m_rotation)),
+          other.Rotation() + m_rotation};
+}
+
+Pose3d Pose3d::RelativeTo(const Pose3d& other) const {
+  const Transform3d transform{other, *this};
+  return {transform.Translation(), transform.Rotation()};
+}
+
+Pose3d Pose3d::Exp(const Twist3d& twist) const {
+  Matrixd<3, 3> Omega = RotationVectorToMatrix(
+      Vectord<3>{twist.rx.value(), twist.ry.value(), twist.rz.value()});
+  Matrixd<3, 3> OmegaSq = Omega * Omega;
+
+  double thetaSq =
+      (twist.rx * twist.rx + twist.ry * twist.ry + twist.rz * twist.rz).value();
+
+  // Get left Jacobian of SO3. See first line in right column of
+  // http://asrl.utias.utoronto.ca/~tdb/bib/barfoot_ser17_identities.pdf
+  Matrixd<3, 3> J;
+  if (thetaSq < 1E-9 * 1E-9) {
+    // V = I + 0.5ω
+    J = Matrixd<3, 3>::Identity() + 0.5 * Omega;
+  } else {
+    double theta = std::sqrt(thetaSq);
+    // J = I + (1 − std::cos(θ))/θ² ω + (θ − std::sin(θ))/θ³ ω²
+    J = Matrixd<3, 3>::Identity() + (1.0 - std::cos(theta)) / thetaSq * Omega +
+        (theta - std::sin(theta)) / (thetaSq * theta) * OmegaSq;
+  }
+
+  // Get translation component
+  Vectord<3> translation =
+      J * Vectord<3>{twist.dx.value(), twist.dy.value(), twist.dz.value()};
+
+  const Transform3d transform{Translation3d{units::meter_t{translation(0)},
+                                            units::meter_t{translation(1)},
+                                            units::meter_t{translation(2)}},
+                              Rotation3d{twist.rx, twist.ry, twist.rz}};
+
+  return *this + transform;
+}
+
+Twist3d Pose3d::Log(const Pose3d& end) const {
+  const auto transform = end.RelativeTo(*this);
+
+  Vectord<3> rotVec = transform.Rotation().GetQuaternion().ToRotationVector();
+
+  Matrixd<3, 3> Omega = RotationVectorToMatrix(rotVec);
+  Matrixd<3, 3> OmegaSq = Omega * Omega;
+
+  double thetaSq = rotVec.squaredNorm();
+
+  // Get left Jacobian inverse of SO3. See fourth line in right column of
+  // http://asrl.utias.utoronto.ca/~tdb/bib/barfoot_ser17_identities.pdf
+  Matrixd<3, 3> Jinv;
+  if (thetaSq < 1E-9 * 1E-9) {
+    // J⁻¹ = I − 0.5ω + 1/12 ω²
+    Jinv = Matrixd<3, 3>::Identity() - 0.5 * Omega + 1.0 / 12.0 * OmegaSq;
+  } else {
+    double theta = std::sqrt(thetaSq);
+    double halfTheta = 0.5 * theta;
+
+    // J⁻¹ = I − 0.5ω + (1 − 0.5θ std::cos(θ/2) / std::sin(θ/2))/θ² ω²
+    Jinv = Matrixd<3, 3>::Identity() - 0.5 * Omega +
+           (1.0 - 0.5 * theta * std::cos(halfTheta) / std::sin(halfTheta)) /
+               thetaSq * OmegaSq;
+  }
+
+  // Get dtranslation component
+  Vectord<3> dtranslation =
+      Jinv * Vectord<3>{transform.X().value(), transform.Y().value(),
+                        transform.Z().value()};
+
+  return Twist3d{
+      units::meter_t{dtranslation(0)}, units::meter_t{dtranslation(1)},
+      units::meter_t{dtranslation(2)}, units::radian_t{rotVec(0)},
+      units::radian_t{rotVec(1)},      units::radian_t{rotVec(2)}};
+}
+
+Pose2d Pose3d::ToPose2d() const {
+  return Pose2d{m_translation.X(), m_translation.Y(), m_rotation.Z()};
+}
+
+void frc::to_json(wpi::json& json, const Pose3d& pose) {
+  json = wpi::json{{"translation", pose.Translation()},
+                   {"rotation", pose.Rotation()}};
+}
+
+void frc::from_json(const wpi::json& json, Pose3d& pose) {
+  pose = Pose3d{json.at("translation").get<Translation3d>(),
+                json.at("rotation").get<Rotation3d>()};
+}
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/geometry/Quaternion.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/geometry/Quaternion.cpp
new file mode 100644
index 0000000..9c2ceda
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/geometry/Quaternion.cpp
@@ -0,0 +1,94 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/geometry/Quaternion.h"
+
+#include <wpi/json.h>
+
+using namespace frc;
+
+Quaternion::Quaternion(double w, double x, double y, double z)
+    : m_r{w}, m_v{x, y, z} {}
+
+Quaternion Quaternion::operator*(const Quaternion& other) const {
+  // https://en.wikipedia.org/wiki/Quaternion#Scalar_and_vector_parts
+  const auto& r1 = m_r;
+  const auto& v1 = m_v;
+  const auto& r2 = other.m_r;
+  const auto& v2 = other.m_v;
+
+  // v₁ x v₂
+  Eigen::Vector3d cross{v1(1) * v2(2) - v2(1) * v1(2),
+                        v2(0) * v1(2) - v1(0) * v2(2),
+                        v1(0) * v2(1) - v2(0) * v1(1)};
+
+  // v = r₁v₂ + r₂v₁ + v₁ x v₂
+  Eigen::Vector3d v = r1 * v2 + r2 * v1 + cross;
+
+  return Quaternion{r1 * r2 - v1.dot(v2), v(0), v(1), v(2)};
+}
+
+bool Quaternion::operator==(const Quaternion& other) const {
+  return std::abs(m_r * other.m_r + m_v.dot(other.m_v)) > 1.0 - 1E-9;
+}
+
+Quaternion Quaternion::Inverse() const {
+  return Quaternion{m_r, -m_v(0), -m_v(1), -m_v(2)};
+}
+
+Quaternion Quaternion::Normalize() const {
+  double norm = std::sqrt(W() * W() + X() * X() + Y() * Y() + Z() * Z());
+  if (norm == 0.0) {
+    return Quaternion{};
+  } else {
+    return Quaternion{W() / norm, X() / norm, Y() / norm, Z() / norm};
+  }
+}
+
+double Quaternion::W() const {
+  return m_r;
+}
+
+double Quaternion::X() const {
+  return m_v(0);
+}
+
+double Quaternion::Y() const {
+  return m_v(1);
+}
+
+double Quaternion::Z() const {
+  return m_v(2);
+}
+
+Eigen::Vector3d Quaternion::ToRotationVector() const {
+  // See equation (31) in "Integrating Generic Sensor Fusion Algorithms with
+  // Sound State Representation through Encapsulation of Manifolds"
+  //
+  // https://arxiv.org/pdf/1107.1119.pdf
+  double norm = m_v.norm();
+
+  if (norm < 1e-9) {
+    return (2.0 / W() - 2.0 / 3.0 * norm * norm / (W() * W() * W())) * m_v;
+  } else {
+    if (W() < 0.0) {
+      return 2.0 * std::atan2(-norm, -W()) / norm * m_v;
+    } else {
+      return 2.0 * std::atan2(norm, W()) / norm * m_v;
+    }
+  }
+}
+
+void frc::to_json(wpi::json& json, const Quaternion& quaternion) {
+  json = wpi::json{{"W", quaternion.W()},
+                   {"X", quaternion.X()},
+                   {"Y", quaternion.Y()},
+                   {"Z", quaternion.Z()}};
+}
+
+void frc::from_json(const wpi::json& json, Quaternion& quaternion) {
+  quaternion =
+      Quaternion{json.at("W").get<double>(), json.at("X").get<double>(),
+                 json.at("Y").get<double>(), json.at("Z").get<double>()};
+}
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/geometry/Rotation2d.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/geometry/Rotation2d.cpp
index 27af5ed..921e1f8 100644
--- a/third_party/allwpilib/wpimath/src/main/native/cpp/geometry/Rotation2d.cpp
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/geometry/Rotation2d.cpp
@@ -12,57 +12,6 @@
 
 using namespace frc;
 
-Rotation2d::Rotation2d(units::radian_t value)
-    : m_value(value),
-      m_cos(units::math::cos(value)),
-      m_sin(units::math::sin(value)) {}
-
-Rotation2d::Rotation2d(units::degree_t value)
-    : m_value(value),
-      m_cos(units::math::cos(value)),
-      m_sin(units::math::sin(value)) {}
-
-Rotation2d::Rotation2d(double x, double y) {
-  const auto magnitude = std::hypot(x, y);
-  if (magnitude > 1e-6) {
-    m_sin = y / magnitude;
-    m_cos = x / magnitude;
-  } else {
-    m_sin = 0.0;
-    m_cos = 1.0;
-  }
-  m_value = units::radian_t(std::atan2(m_sin, m_cos));
-}
-
-Rotation2d Rotation2d::operator+(const Rotation2d& other) const {
-  return RotateBy(other);
-}
-
-Rotation2d Rotation2d::operator-(const Rotation2d& other) const {
-  return *this + -other;
-}
-
-Rotation2d Rotation2d::operator-() const {
-  return Rotation2d(-m_value);
-}
-
-Rotation2d Rotation2d::operator*(double scalar) const {
-  return Rotation2d(m_value * scalar);
-}
-
-bool Rotation2d::operator==(const Rotation2d& other) const {
-  return std::hypot(m_cos - other.m_cos, m_sin - other.m_sin) < 1E-9;
-}
-
-bool Rotation2d::operator!=(const Rotation2d& other) const {
-  return !operator==(other);
-}
-
-Rotation2d Rotation2d::RotateBy(const Rotation2d& other) const {
-  return {Cos() * other.Cos() - Sin() * other.Sin(),
-          Cos() * other.Sin() + Sin() * other.Cos()};
-}
-
 void frc::to_json(wpi::json& json, const Rotation2d& rotation) {
   json = wpi::json{{"radians", rotation.Radians().value()}};
 }
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/geometry/Rotation3d.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/geometry/Rotation3d.cpp
new file mode 100644
index 0000000..298f0e6
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/geometry/Rotation3d.cpp
@@ -0,0 +1,242 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/geometry/Rotation3d.h"
+
+#include <cmath>
+#include <numbers>
+
+#include <wpi/json.h>
+
+#include "Eigen/Core"
+#include "Eigen/LU"
+#include "Eigen/QR"
+#include "frc/fmt/Eigen.h"
+#include "units/math.h"
+#include "wpimath/MathShared.h"
+
+using namespace frc;
+
+Rotation3d::Rotation3d(const Quaternion& q) {
+  m_q = q.Normalize();
+}
+
+Rotation3d::Rotation3d(units::radian_t roll, units::radian_t pitch,
+                       units::radian_t yaw) {
+  // https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles#Euler_angles_to_quaternion_conversion
+  double cr = units::math::cos(roll * 0.5);
+  double sr = units::math::sin(roll * 0.5);
+
+  double cp = units::math::cos(pitch * 0.5);
+  double sp = units::math::sin(pitch * 0.5);
+
+  double cy = units::math::cos(yaw * 0.5);
+  double sy = units::math::sin(yaw * 0.5);
+
+  m_q = Quaternion{cr * cp * cy + sr * sp * sy, sr * cp * cy - cr * sp * sy,
+                   cr * sp * cy + sr * cp * sy, cr * cp * sy - sr * sp * cy};
+}
+
+Rotation3d::Rotation3d(const Vectord<3>& axis, units::radian_t angle) {
+  double norm = axis.norm();
+  if (norm == 0.0) {
+    return;
+  }
+
+  // https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles#Definition
+  Vectord<3> v = axis / norm * units::math::sin(angle / 2.0);
+  m_q = Quaternion{units::math::cos(angle / 2.0), v(0), v(1), v(2)};
+}
+
+Rotation3d::Rotation3d(const Matrixd<3, 3>& rotationMatrix) {
+  const auto& R = rotationMatrix;
+
+  // Require that the rotation matrix is special orthogonal. This is true if the
+  // matrix is orthogonal (RRᵀ = I) and normalized (determinant is 1).
+  if ((R * R.transpose() - Matrixd<3, 3>::Identity()).norm() > 1e-9) {
+    std::string msg =
+        fmt::format("Rotation matrix isn't orthogonal\n\nR =\n{}\n", R);
+
+    wpi::math::MathSharedStore::ReportError(msg);
+    throw std::domain_error(msg);
+  }
+  if (std::abs(R.determinant() - 1.0) > 1e-9) {
+    std::string msg = fmt::format(
+        "Rotation matrix is orthogonal but not special orthogonal\n\nR =\n{}\n",
+        R);
+
+    wpi::math::MathSharedStore::ReportError(msg);
+    throw std::domain_error(msg);
+  }
+
+  // Turn rotation matrix into a quaternion
+  // https://www.euclideanspace.com/maths/geometry/rotations/conversions/matrixToQuaternion/
+  double trace = R(0, 0) + R(1, 1) + R(2, 2);
+  double w;
+  double x;
+  double y;
+  double z;
+
+  if (trace > 0.0) {
+    double s = 0.5 / std::sqrt(trace + 1.0);
+    w = 0.25 / s;
+    x = (R(2, 1) - R(1, 2)) * s;
+    y = (R(0, 2) - R(2, 0)) * s;
+    z = (R(1, 0) - R(0, 1)) * s;
+  } else {
+    if (R(0, 0) > R(1, 1) && R(0, 0) > R(2, 2)) {
+      double s = 2.0 * std::sqrt(1.0 + R(0, 0) - R(1, 1) - R(2, 2));
+      w = (R(2, 1) - R(1, 2)) / s;
+      x = 0.25 * s;
+      y = (R(0, 1) + R(1, 0)) / s;
+      z = (R(0, 2) + R(2, 0)) / s;
+    } else if (R(1, 1) > R(2, 2)) {
+      double s = 2.0 * std::sqrt(1.0 + R(1, 1) - R(0, 0) - R(2, 2));
+      w = (R(0, 2) - R(2, 0)) / s;
+      x = (R(0, 1) + R(1, 0)) / s;
+      y = 0.25 * s;
+      z = (R(1, 2) + R(2, 1)) / s;
+    } else {
+      double s = 2.0 * std::sqrt(1.0 + R(2, 2) - R(0, 0) - R(1, 1));
+      w = (R(1, 0) - R(0, 1)) / s;
+      x = (R(0, 2) + R(2, 0)) / s;
+      y = (R(1, 2) + R(2, 1)) / s;
+      z = 0.25 * s;
+    }
+  }
+
+  m_q = Quaternion{w, x, y, z};
+}
+
+Rotation3d::Rotation3d(const Vectord<3>& initial, const Vectord<3>& final) {
+  double dot = initial.dot(final);
+  double normProduct = initial.norm() * final.norm();
+  double dotNorm = dot / normProduct;
+
+  if (dotNorm > 1.0 - 1E-9) {
+    // If the dot product is 1, the two vectors point in the same direction so
+    // there's no rotation. The default initialization of m_q will work.
+    return;
+  } else if (dotNorm < -1.0 + 1E-9) {
+    // If the dot product is -1, the two vectors point in opposite directions so
+    // a 180 degree rotation is required. Any orthogonal vector can be used for
+    // it. Q in the QR decomposition is an orthonormal basis, so it contains
+    // orthogonal unit vectors.
+    Eigen::Matrix<double, 3, 1> X = initial;
+    Eigen::HouseholderQR<decltype(X)> qr{X};
+    Eigen::Matrix<double, 3, 3> Q = qr.householderQ();
+
+    // w = std::cos(θ/2) = std::cos(90°) = 0
+    //
+    // For x, y, and z, we use the second column of Q because the first is
+    // parallel instead of orthogonal. The third column would also work.
+    m_q = Quaternion{0.0, Q(0, 1), Q(1, 1), Q(2, 1)};
+  } else {
+    // initial x final
+    Eigen::Vector3d axis{initial(1) * final(2) - final(1) * initial(2),
+                         final(0) * initial(2) - initial(0) * final(2),
+                         initial(0) * final(1) - final(0) * initial(1)};
+
+    // https://stackoverflow.com/a/11741520
+    m_q = Quaternion{normProduct + dot, axis(0), axis(1), axis(2)}.Normalize();
+  }
+}
+
+Rotation3d Rotation3d::operator+(const Rotation3d& other) const {
+  return RotateBy(other);
+}
+
+Rotation3d Rotation3d::operator-(const Rotation3d& other) const {
+  return *this + -other;
+}
+
+Rotation3d Rotation3d::operator-() const {
+  return Rotation3d{m_q.Inverse()};
+}
+
+Rotation3d Rotation3d::operator*(double scalar) const {
+  // https://en.wikipedia.org/wiki/Slerp#Quaternion_Slerp
+  if (m_q.W() >= 0.0) {
+    return Rotation3d{{m_q.X(), m_q.Y(), m_q.Z()},
+                      2.0 * units::radian_t{scalar * std::acos(m_q.W())}};
+  } else {
+    return Rotation3d{{-m_q.X(), -m_q.Y(), -m_q.Z()},
+                      2.0 * units::radian_t{scalar * std::acos(-m_q.W())}};
+  }
+}
+
+Rotation3d Rotation3d::operator/(double scalar) const {
+  return *this * (1.0 / scalar);
+}
+
+Rotation3d Rotation3d::RotateBy(const Rotation3d& other) const {
+  return Rotation3d{other.m_q * m_q};
+}
+
+const Quaternion& Rotation3d::GetQuaternion() const {
+  return m_q;
+}
+
+units::radian_t Rotation3d::X() const {
+  double w = m_q.W();
+  double x = m_q.X();
+  double y = m_q.Y();
+  double z = m_q.Z();
+
+  // https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles#Quaternion_to_Euler_angles_conversion
+  return units::radian_t{
+      std::atan2(2.0 * (w * x + y * z), 1.0 - 2.0 * (x * x + y * y))};
+}
+
+units::radian_t Rotation3d::Y() const {
+  double w = m_q.W();
+  double x = m_q.X();
+  double y = m_q.Y();
+  double z = m_q.Z();
+
+  // https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles#Quaternion_to_Euler_angles_conversion
+  double ratio = 2.0 * (w * y - z * x);
+  if (std::abs(ratio) >= 1.0) {
+    return units::radian_t{std::copysign(std::numbers::pi / 2.0, ratio)};
+  } else {
+    return units::radian_t{std::asin(ratio)};
+  }
+}
+
+units::radian_t Rotation3d::Z() const {
+  double w = m_q.W();
+  double x = m_q.X();
+  double y = m_q.Y();
+  double z = m_q.Z();
+
+  // https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles#Quaternion_to_Euler_angles_conversion
+  return units::radian_t{
+      std::atan2(2.0 * (w * z + x * y), 1.0 - 2.0 * (y * y + z * z))};
+}
+
+Vectord<3> Rotation3d::Axis() const {
+  double norm = std::hypot(m_q.X(), m_q.Y(), m_q.Z());
+  if (norm == 0.0) {
+    return {0.0, 0.0, 0.0};
+  } else {
+    return {m_q.X() / norm, m_q.Y() / norm, m_q.Z() / norm};
+  }
+}
+
+units::radian_t Rotation3d::Angle() const {
+  double norm = std::hypot(m_q.X(), m_q.Y(), m_q.Z());
+  return units::radian_t{2.0 * std::atan2(norm, m_q.W())};
+}
+
+Rotation2d Rotation3d::ToRotation2d() const {
+  return Rotation2d{Z()};
+}
+
+void frc::to_json(wpi::json& json, const Rotation3d& rotation) {
+  json = wpi::json{{"quaternion", rotation.GetQuaternion()}};
+}
+
+void frc::from_json(const wpi::json& json, Rotation3d& rotation) {
+  rotation = Rotation3d{json.at("quaternion").get<Quaternion>()};
+}
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/geometry/Transform2d.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/geometry/Transform2d.cpp
index 0808f35..25b0590 100644
--- a/third_party/allwpilib/wpimath/src/main/native/cpp/geometry/Transform2d.cpp
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/geometry/Transform2d.cpp
@@ -18,24 +18,6 @@
   m_rotation = final.Rotation() - initial.Rotation();
 }
 
-Transform2d::Transform2d(Translation2d translation, Rotation2d rotation)
-    : m_translation(translation), m_rotation(rotation) {}
-
-Transform2d Transform2d::Inverse() const {
-  // We are rotating the difference between the translations
-  // using a clockwise rotation matrix. This transforms the global
-  // delta into a local delta (relative to the initial pose).
-  return Transform2d{(-Translation()).RotateBy(-Rotation()), -Rotation()};
-}
-
 Transform2d Transform2d::operator+(const Transform2d& other) const {
   return Transform2d{Pose2d{}, Pose2d{}.TransformBy(*this).TransformBy(other)};
 }
-
-bool Transform2d::operator==(const Transform2d& other) const {
-  return m_translation == other.m_translation && m_rotation == other.m_rotation;
-}
-
-bool Transform2d::operator!=(const Transform2d& other) const {
-  return !operator==(other);
-}
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/geometry/Transform3d.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/geometry/Transform3d.cpp
new file mode 100644
index 0000000..1cfabaa
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/geometry/Transform3d.cpp
@@ -0,0 +1,33 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/geometry/Transform3d.h"
+
+#include "frc/geometry/Pose3d.h"
+
+using namespace frc;
+
+Transform3d::Transform3d(Pose3d initial, Pose3d final) {
+  // We are rotating the difference between the translations
+  // using a clockwise rotation matrix. This transforms the global
+  // delta into a local delta (relative to the initial pose).
+  m_translation = (final.Translation() - initial.Translation())
+                      .RotateBy(-initial.Rotation());
+
+  m_rotation = final.Rotation() - initial.Rotation();
+}
+
+Transform3d::Transform3d(Translation3d translation, Rotation3d rotation)
+    : m_translation(std::move(translation)), m_rotation(std::move(rotation)) {}
+
+Transform3d Transform3d::Inverse() const {
+  // We are rotating the difference between the translations
+  // using a clockwise rotation matrix. This transforms the global
+  // delta into a local delta (relative to the initial pose).
+  return Transform3d{(-Translation()).RotateBy(-Rotation()), -Rotation()};
+}
+
+Transform3d Transform3d::operator+(const Transform3d& other) const {
+  return Transform3d{Pose3d{}, Pose3d{}.TransformBy(*this).TransformBy(other)};
+}
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/geometry/Translation2d.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/geometry/Translation2d.cpp
index 5a30ec2..d463696 100644
--- a/third_party/allwpilib/wpimath/src/main/native/cpp/geometry/Translation2d.cpp
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/geometry/Translation2d.cpp
@@ -10,12 +10,6 @@
 
 using namespace frc;
 
-Translation2d::Translation2d(units::meter_t x, units::meter_t y)
-    : m_x(x), m_y(y) {}
-
-Translation2d::Translation2d(units::meter_t distance, const Rotation2d& angle)
-    : m_x(distance * angle.Cos()), m_y(distance * angle.Sin()) {}
-
 units::meter_t Translation2d::Distance(const Translation2d& other) const {
   return units::math::hypot(other.m_x - m_x, other.m_y - m_y);
 }
@@ -24,40 +18,11 @@
   return units::math::hypot(m_x, m_y);
 }
 
-Translation2d Translation2d::RotateBy(const Rotation2d& other) const {
-  return {m_x * other.Cos() - m_y * other.Sin(),
-          m_x * other.Sin() + m_y * other.Cos()};
-}
-
-Translation2d Translation2d::operator+(const Translation2d& other) const {
-  return {X() + other.X(), Y() + other.Y()};
-}
-
-Translation2d Translation2d::operator-(const Translation2d& other) const {
-  return *this + -other;
-}
-
-Translation2d Translation2d::operator-() const {
-  return {-m_x, -m_y};
-}
-
-Translation2d Translation2d::operator*(double scalar) const {
-  return {scalar * m_x, scalar * m_y};
-}
-
-Translation2d Translation2d::operator/(double scalar) const {
-  return *this * (1.0 / scalar);
-}
-
 bool Translation2d::operator==(const Translation2d& other) const {
   return units::math::abs(m_x - other.m_x) < 1E-9_m &&
          units::math::abs(m_y - other.m_y) < 1E-9_m;
 }
 
-bool Translation2d::operator!=(const Translation2d& other) const {
-  return !operator==(other);
-}
-
 void frc::to_json(wpi::json& json, const Translation2d& translation) {
   json =
       wpi::json{{"x", translation.X().value()}, {"y", translation.Y().value()}};
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/geometry/Translation3d.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/geometry/Translation3d.cpp
new file mode 100644
index 0000000..2c53791
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/geometry/Translation3d.cpp
@@ -0,0 +1,54 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/geometry/Translation3d.h"
+
+#include <wpi/json.h>
+
+#include "units/length.h"
+#include "units/math.h"
+
+using namespace frc;
+
+Translation3d::Translation3d(units::meter_t distance, const Rotation3d& angle) {
+  auto rectangular = Translation3d{distance, 0_m, 0_m}.RotateBy(angle);
+  m_x = rectangular.X();
+  m_y = rectangular.Y();
+  m_z = rectangular.Z();
+}
+
+units::meter_t Translation3d::Distance(const Translation3d& other) const {
+  return units::math::sqrt(units::math::pow<2>(other.m_x - m_x) +
+                           units::math::pow<2>(other.m_y - m_y) +
+                           units::math::pow<2>(other.m_z - m_z));
+}
+
+units::meter_t Translation3d::Norm() const {
+  return units::math::sqrt(m_x * m_x + m_y * m_y + m_z * m_z);
+}
+
+Translation3d Translation3d::RotateBy(const Rotation3d& other) const {
+  Quaternion p{0.0, m_x.value(), m_y.value(), m_z.value()};
+  auto qprime = other.GetQuaternion() * p * other.GetQuaternion().Inverse();
+  return Translation3d{units::meter_t{qprime.X()}, units::meter_t{qprime.Y()},
+                       units::meter_t{qprime.Z()}};
+}
+
+bool Translation3d::operator==(const Translation3d& other) const {
+  return units::math::abs(m_x - other.m_x) < 1E-9_m &&
+         units::math::abs(m_y - other.m_y) < 1E-9_m &&
+         units::math::abs(m_z - other.m_z) < 1E-9_m;
+}
+
+void frc::to_json(wpi::json& json, const Translation3d& translation) {
+  json = wpi::json{{"x", translation.X().value()},
+                   {"y", translation.Y().value()},
+                   {"z", translation.Z().value()}};
+}
+
+void frc::from_json(const wpi::json& json, Translation3d& translation) {
+  translation = Translation3d{units::meter_t{json.at("x").get<double>()},
+                              units::meter_t{json.at("y").get<double>()},
+                              units::meter_t{json.at("z").get<double>()}};
+}
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/jni/WPIMathJNI.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/jni/WPIMathJNI.cpp
index b036833..fd8a223 100644
--- a/third_party/allwpilib/wpimath/src/main/native/cpp/jni/WPIMathJNI.cpp
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/jni/WPIMathJNI.cpp
@@ -8,6 +8,7 @@
 
 #include <wpi/jni_util.h>
 
+#include "Eigen/Cholesky"
 #include "Eigen/Core"
 #include "Eigen/Eigenvalues"
 #include "Eigen/QR"
@@ -70,7 +71,7 @@
   return elements;
 }
 
-frc::Trajectory CreateTrajectoryFromElements(wpi::span<const double> elements) {
+frc::Trajectory CreateTrajectoryFromElements(std::span<const double> elements) {
   // Make sure that the elements have the correct length.
   assert(elements.size() % 7 == 0);
 
@@ -307,4 +308,60 @@
   }
 }
 
+/*
+ * Class:     edu_wpi_first_math_WPIMathJNI
+ * Method:    rankUpdate
+ * Signature: ([DI[DDZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_math_WPIMathJNI_rankUpdate
+  (JNIEnv* env, jclass, jdoubleArray mat, jint rows, jdoubleArray vec,
+   jdouble sigma, jboolean lowerTriangular)
+{
+  jdouble* matBody = env->GetDoubleArrayElements(mat, nullptr);
+  jdouble* vecBody = env->GetDoubleArrayElements(vec, nullptr);
+
+  Eigen::Map<
+      Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor>>
+      L{matBody, rows, rows};
+  Eigen::Map<Eigen::Vector<double, Eigen::Dynamic>> v{vecBody, rows};
+
+  if (lowerTriangular == JNI_TRUE) {
+    Eigen::internal::llt_inplace<double, Eigen::Lower>::rankUpdate(L, v, sigma);
+  } else {
+    Eigen::internal::llt_inplace<double, Eigen::Upper>::rankUpdate(L, v, sigma);
+  }
+
+  env->ReleaseDoubleArrayElements(mat, matBody, 0);
+  env->ReleaseDoubleArrayElements(vec, vecBody, 0);
+}
+
+/*
+ * Class:     edu_wpi_first_math_WPIMathJNI
+ * Method:    solveFullPivHouseholderQr
+ * Signature: ([DII[DII[D)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_math_WPIMathJNI_solveFullPivHouseholderQr
+  (JNIEnv* env, jclass, jdoubleArray A, jint Arows, jint Acols, jdoubleArray B,
+   jint Brows, jint Bcols, jdoubleArray dst)
+{
+  jdouble* nativeA = env->GetDoubleArrayElements(A, nullptr);
+  jdouble* nativeB = env->GetDoubleArrayElements(B, nullptr);
+
+  Eigen::Map<
+      Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor>>
+      Amat{nativeA, Arows, Acols};
+  Eigen::Map<
+      Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor>>
+      Bmat{nativeB, Brows, Bcols};
+
+  Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> Xmat =
+      Amat.fullPivHouseholderQr().solve(Bmat);
+
+  env->ReleaseDoubleArrayElements(A, nativeA, 0);
+  env->ReleaseDoubleArrayElements(B, nativeB, 0);
+  env->SetDoubleArrayRegion(dst, 0, Brows * Bcols, Xmat.data());
+}
+
 }  // extern "C"
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/kinematics/DifferentialDriveOdometry.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/kinematics/DifferentialDriveOdometry.cpp
index c4a4311..1ff7a8a 100644
--- a/third_party/allwpilib/wpimath/src/main/native/cpp/kinematics/DifferentialDriveOdometry.cpp
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/kinematics/DifferentialDriveOdometry.cpp
@@ -9,8 +9,11 @@
 using namespace frc;
 
 DifferentialDriveOdometry::DifferentialDriveOdometry(
-    const Rotation2d& gyroAngle, const Pose2d& initialPose)
-    : m_pose(initialPose) {
+    const Rotation2d& gyroAngle, units::meter_t leftDistance,
+    units::meter_t rightDistance, const Pose2d& initialPose)
+    : m_pose(initialPose),
+      m_prevLeftDistance(leftDistance),
+      m_prevRightDistance(rightDistance) {
   m_previousAngle = m_pose.Rotation();
   m_gyroOffset = m_pose.Rotation() - gyroAngle;
   wpi::math::MathSharedStore::ReportUsage(
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/kinematics/MecanumDriveKinematics.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/kinematics/MecanumDriveKinematics.cpp
index c4a71fd..298dd7f 100644
--- a/third_party/allwpilib/wpimath/src/main/native/cpp/kinematics/MecanumDriveKinematics.cpp
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/kinematics/MecanumDriveKinematics.cpp
@@ -25,8 +25,7 @@
                                       chassisSpeeds.vy.value(),
                                       chassisSpeeds.omega.value()};
 
-  Eigen::Vector<double, 4> wheelsVector =
-      m_inverseKinematics * chassisSpeedsVector;
+  Vectord<4> wheelsVector = m_inverseKinematics * chassisSpeedsVector;
 
   MecanumDriveWheelSpeeds wheelSpeeds;
   wheelSpeeds.frontLeft = units::meters_per_second_t{wheelsVector(0)};
@@ -38,7 +37,7 @@
 
 ChassisSpeeds MecanumDriveKinematics::ToChassisSpeeds(
     const MecanumDriveWheelSpeeds& wheelSpeeds) const {
-  Eigen::Vector<double, 4> wheelSpeedsVector{
+  Vectord<4> wheelSpeedsVector{
       wheelSpeeds.frontLeft.value(), wheelSpeeds.frontRight.value(),
       wheelSpeeds.rearLeft.value(), wheelSpeeds.rearRight.value()};
 
@@ -50,13 +49,24 @@
           units::radians_per_second_t{chassisSpeedsVector(2)}};
 }
 
+Twist2d MecanumDriveKinematics::ToTwist2d(
+    const MecanumDriveWheelPositions& wheelDeltas) const {
+  Vectord<4> wheelDeltasVector{
+      wheelDeltas.frontLeft.value(), wheelDeltas.frontRight.value(),
+      wheelDeltas.rearLeft.value(), wheelDeltas.rearRight.value()};
+
+  Eigen::Vector3d twistVector = m_forwardKinematics.solve(wheelDeltasVector);
+
+  return {units::meter_t{twistVector(0)},  // NOLINT
+          units::meter_t{twistVector(1)}, units::radian_t{twistVector(2)}};
+}
+
 void MecanumDriveKinematics::SetInverseKinematics(Translation2d fl,
                                                   Translation2d fr,
                                                   Translation2d rl,
                                                   Translation2d rr) const {
-  m_inverseKinematics =
-      Eigen::Matrix<double, 4, 3>{{1, -1, (-(fl.X() + fl.Y())).value()},
-                                  {1, 1, (fr.X() - fr.Y()).value()},
-                                  {1, 1, (rl.X() - rl.Y()).value()},
-                                  {1, -1, (-(rr.X() + rr.Y())).value()}};
+  m_inverseKinematics = Matrixd<4, 3>{{1, -1, (-(fl.X() + fl.Y())).value()},
+                                      {1, 1, (fr.X() - fr.Y()).value()},
+                                      {1, 1, (rl.X() - rl.Y()).value()},
+                                      {1, -1, (-(rr.X() + rr.Y())).value()}};
 }
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/kinematics/MecanumDriveOdometry.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/kinematics/MecanumDriveOdometry.cpp
index bbeee58..394adaf 100644
--- a/third_party/allwpilib/wpimath/src/main/native/cpp/kinematics/MecanumDriveOdometry.cpp
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/kinematics/MecanumDriveOdometry.cpp
@@ -8,32 +8,37 @@
 
 using namespace frc;
 
-MecanumDriveOdometry::MecanumDriveOdometry(MecanumDriveKinematics kinematics,
-                                           const Rotation2d& gyroAngle,
-                                           const Pose2d& initialPose)
-    : m_kinematics(kinematics), m_pose(initialPose) {
+MecanumDriveOdometry::MecanumDriveOdometry(
+    MecanumDriveKinematics kinematics, const Rotation2d& gyroAngle,
+    const MecanumDriveWheelPositions& wheelPositions, const Pose2d& initialPose)
+    : m_kinematics(kinematics),
+      m_pose(initialPose),
+      m_previousWheelPositions(wheelPositions) {
   m_previousAngle = m_pose.Rotation();
   m_gyroOffset = m_pose.Rotation() - gyroAngle;
   wpi::math::MathSharedStore::ReportUsage(
       wpi::math::MathUsageId::kOdometry_MecanumDrive, 1);
 }
 
-const Pose2d& MecanumDriveOdometry::UpdateWithTime(
-    units::second_t currentTime, const Rotation2d& gyroAngle,
-    MecanumDriveWheelSpeeds wheelSpeeds) {
-  units::second_t deltaTime =
-      (m_previousTime >= 0_s) ? currentTime - m_previousTime : 0_s;
-  m_previousTime = currentTime;
-
+const Pose2d& MecanumDriveOdometry::Update(
+    const Rotation2d& gyroAngle,
+    const MecanumDriveWheelPositions& wheelPositions) {
   auto angle = gyroAngle + m_gyroOffset;
 
-  auto [dx, dy, dtheta] = m_kinematics.ToChassisSpeeds(wheelSpeeds);
-  static_cast<void>(dtheta);
+  MecanumDriveWheelPositions wheelDeltas{
+      wheelPositions.frontLeft - m_previousWheelPositions.frontLeft,
+      wheelPositions.frontRight - m_previousWheelPositions.frontRight,
+      wheelPositions.rearLeft - m_previousWheelPositions.rearLeft,
+      wheelPositions.rearRight - m_previousWheelPositions.rearRight,
+  };
 
-  auto newPose = m_pose.Exp(
-      {dx * deltaTime, dy * deltaTime, (angle - m_previousAngle).Radians()});
+  auto twist = m_kinematics.ToTwist2d(wheelDeltas);
+  twist.dtheta = (angle - m_previousAngle).Radians();
+
+  auto newPose = m_pose.Exp(twist);
 
   m_previousAngle = angle;
+  m_previousWheelPositions = wheelPositions;
   m_pose = {newPose.Translation(), angle};
 
   return m_pose;
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/kinematics/SwerveDriveKinematics.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/kinematics/SwerveDriveKinematics.cpp
new file mode 100644
index 0000000..5e6cf28
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/kinematics/SwerveDriveKinematics.cpp
@@ -0,0 +1,12 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/kinematics/SwerveDriveKinematics.h"
+
+namespace frc {
+
+template class EXPORT_TEMPLATE_DEFINE(WPILIB_DLLEXPORT)
+    SwerveDriveKinematics<4>;
+
+}  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/kinematics/SwerveDriveOdometry.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/kinematics/SwerveDriveOdometry.cpp
new file mode 100644
index 0000000..7a9d065
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/kinematics/SwerveDriveOdometry.cpp
@@ -0,0 +1,11 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/kinematics/SwerveDriveOdometry.h"
+
+namespace frc {
+
+template class EXPORT_TEMPLATE_DEFINE(WPILIB_DLLEXPORT) SwerveDriveOdometry<4>;
+
+}  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/spline/SplineHelper.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/spline/SplineHelper.cpp
index cec620c..e8bbb46 100644
--- a/third_party/allwpilib/wpimath/src/main/native/cpp/spline/SplineHelper.cpp
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/spline/SplineHelper.cpp
@@ -20,10 +20,10 @@
 
   if (waypoints.size() > 1) {
     waypoints.emplace(waypoints.begin(),
-                      Translation2d{units::meter_t(xInitial[0]),
-                                    units::meter_t(yInitial[0])});
+                      Translation2d{units::meter_t{xInitial[0]},
+                                    units::meter_t{yInitial[0]}});
     waypoints.emplace_back(
-        Translation2d{units::meter_t(xFinal[0]), units::meter_t(yFinal[0])});
+        Translation2d{units::meter_t{xFinal[0]}, units::meter_t{yFinal[0]}});
 
     // Populate tridiagonal system for clamped cubic
     /* See:
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/system/LinearSystemLoop.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/system/LinearSystemLoop.cpp
new file mode 100644
index 0000000..16979d9
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/system/LinearSystemLoop.cpp
@@ -0,0 +1,14 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/system/LinearSystemLoop.h"
+
+namespace frc {
+
+template class EXPORT_TEMPLATE_DEFINE(WPILIB_DLLEXPORT)
+    LinearSystemLoop<1, 1, 1>;
+template class EXPORT_TEMPLATE_DEFINE(WPILIB_DLLEXPORT)
+    LinearSystemLoop<2, 1, 1>;
+
+}  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/system/plant/LinearSystemId.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/system/plant/LinearSystemId.cpp
new file mode 100644
index 0000000..3527092
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/system/plant/LinearSystemId.cpp
@@ -0,0 +1,193 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/system/plant/LinearSystemId.h"
+
+using namespace frc;
+
+LinearSystem<2, 1, 1> LinearSystemId::ElevatorSystem(DCMotor motor,
+                                                     units::kilogram_t mass,
+                                                     units::meter_t radius,
+                                                     double G) {
+  if (mass <= 0_kg) {
+    throw std::domain_error("mass must be greater than zero.");
+  }
+  if (radius <= 0_m) {
+    throw std::domain_error("radius must be greater than zero.");
+  }
+  if (G <= 0.0) {
+    throw std::domain_error("G must be greater than zero.");
+  }
+
+  Matrixd<2, 2> A{
+      {0.0, 1.0},
+      {0.0, (-std::pow(G, 2) * motor.Kt /
+             (motor.R * units::math::pow<2>(radius) * mass * motor.Kv))
+                .value()}};
+  Matrixd<2, 1> B{0.0, (G * motor.Kt / (motor.R * radius * mass)).value()};
+  Matrixd<1, 2> C{1.0, 0.0};
+  Matrixd<1, 1> D{0.0};
+
+  return LinearSystem<2, 1, 1>(A, B, C, D);
+}
+
+LinearSystem<2, 1, 1> LinearSystemId::SingleJointedArmSystem(
+    DCMotor motor, units::kilogram_square_meter_t J, double G) {
+  if (J <= 0_kg_sq_m) {
+    throw std::domain_error("J must be greater than zero.");
+  }
+  if (G <= 0.0) {
+    throw std::domain_error("G must be greater than zero.");
+  }
+
+  Matrixd<2, 2> A{
+      {0.0, 1.0},
+      {0.0, (-std::pow(G, 2) * motor.Kt / (motor.Kv * motor.R * J)).value()}};
+  Matrixd<2, 1> B{0.0, (G * motor.Kt / (motor.R * J)).value()};
+  Matrixd<1, 2> C{1.0, 0.0};
+  Matrixd<1, 1> D{0.0};
+
+  return LinearSystem<2, 1, 1>(A, B, C, D);
+}
+
+LinearSystem<2, 2, 2> LinearSystemId::IdentifyDrivetrainSystem(
+    decltype(1_V / 1_mps) kVLinear, decltype(1_V / 1_mps_sq) kALinear,
+    decltype(1_V / 1_mps) kVAngular, decltype(1_V / 1_mps_sq) kAAngular) {
+  if (kVLinear <= decltype(kVLinear){0}) {
+    throw std::domain_error("Kv,linear must be greater than zero.");
+  }
+  if (kALinear <= decltype(kALinear){0}) {
+    throw std::domain_error("Ka,linear must be greater than zero.");
+  }
+  if (kVAngular <= decltype(kVAngular){0}) {
+    throw std::domain_error("Kv,angular must be greater than zero.");
+  }
+  if (kAAngular <= decltype(kAAngular){0}) {
+    throw std::domain_error("Ka,angular must be greater than zero.");
+  }
+
+  double A1 = -(kVLinear.value() / kALinear.value() +
+                kVAngular.value() / kAAngular.value());
+  double A2 = -(kVLinear.value() / kALinear.value() -
+                kVAngular.value() / kAAngular.value());
+  double B1 = 1.0 / kALinear.value() + 1.0 / kAAngular.value();
+  double B2 = 1.0 / kALinear.value() - 1.0 / kAAngular.value();
+
+  Matrixd<2, 2> A = 0.5 * Matrixd<2, 2>{{A1, A2}, {A2, A1}};
+  Matrixd<2, 2> B = 0.5 * Matrixd<2, 2>{{B1, B2}, {B2, B1}};
+  Matrixd<2, 2> C{{1.0, 0.0}, {0.0, 1.0}};
+  Matrixd<2, 2> D{{0.0, 0.0}, {0.0, 0.0}};
+
+  return LinearSystem<2, 2, 2>(A, B, C, D);
+}
+
+LinearSystem<2, 2, 2> LinearSystemId::IdentifyDrivetrainSystem(
+    decltype(1_V / 1_mps) kVLinear, decltype(1_V / 1_mps_sq) kALinear,
+    decltype(1_V / 1_rad_per_s) kVAngular,
+    decltype(1_V / 1_rad_per_s_sq) kAAngular, units::meter_t trackwidth) {
+  if (kVLinear <= decltype(kVLinear){0}) {
+    throw std::domain_error("Kv,linear must be greater than zero.");
+  }
+  if (kALinear <= decltype(kALinear){0}) {
+    throw std::domain_error("Ka,linear must be greater than zero.");
+  }
+  if (kVAngular <= decltype(kVAngular){0}) {
+    throw std::domain_error("Kv,angular must be greater than zero.");
+  }
+  if (kAAngular <= decltype(kAAngular){0}) {
+    throw std::domain_error("Ka,angular must be greater than zero.");
+  }
+  if (trackwidth <= 0_m) {
+    throw std::domain_error("r must be greater than zero.");
+  }
+
+  // We want to find a factor to include in Kv,angular that will convert
+  // `u = Kv,angular omega` to `u = Kv,angular v`.
+  //
+  // v = omega r
+  // omega = v/r
+  // omega = 1/r v
+  // omega = 1/(trackwidth/2) v
+  // omega = 2/trackwidth v
+  //
+  // So multiplying by 2/trackwidth converts the angular gains from V/(rad/s)
+  // to V/(m/s).
+  return IdentifyDrivetrainSystem(kVLinear, kALinear,
+                                  kVAngular * 2.0 / trackwidth * 1_rad,
+                                  kAAngular * 2.0 / trackwidth * 1_rad);
+}
+
+LinearSystem<1, 1, 1> LinearSystemId::FlywheelSystem(
+    DCMotor motor, units::kilogram_square_meter_t J, double G) {
+  if (J <= 0_kg_sq_m) {
+    throw std::domain_error("J must be greater than zero.");
+  }
+  if (G <= 0.0) {
+    throw std::domain_error("G must be greater than zero.");
+  }
+
+  Matrixd<1, 1> A{
+      (-std::pow(G, 2) * motor.Kt / (motor.Kv * motor.R * J)).value()};
+  Matrixd<1, 1> B{(G * motor.Kt / (motor.R * J)).value()};
+  Matrixd<1, 1> C{1.0};
+  Matrixd<1, 1> D{0.0};
+
+  return LinearSystem<1, 1, 1>(A, B, C, D);
+}
+
+LinearSystem<2, 1, 2> LinearSystemId::DCMotorSystem(
+    DCMotor motor, units::kilogram_square_meter_t J, double G) {
+  if (J <= 0_kg_sq_m) {
+    throw std::domain_error("J must be greater than zero.");
+  }
+  if (G <= 0.0) {
+    throw std::domain_error("G must be greater than zero.");
+  }
+
+  Matrixd<2, 2> A{
+      {0.0, 1.0},
+      {0.0, (-std::pow(G, 2) * motor.Kt / (motor.Kv * motor.R * J)).value()}};
+  Matrixd<2, 1> B{0.0, (G * motor.Kt / (motor.R * J)).value()};
+  Matrixd<2, 2> C{{1.0, 0.0}, {0.0, 1.0}};
+  Matrixd<2, 1> D{0.0, 0.0};
+
+  return LinearSystem<2, 1, 2>(A, B, C, D);
+}
+
+LinearSystem<2, 2, 2> LinearSystemId::DrivetrainVelocitySystem(
+    const DCMotor& motor, units::kilogram_t mass, units::meter_t r,
+    units::meter_t rb, units::kilogram_square_meter_t J, double G) {
+  if (mass <= 0_kg) {
+    throw std::domain_error("mass must be greater than zero.");
+  }
+  if (r <= 0_m) {
+    throw std::domain_error("r must be greater than zero.");
+  }
+  if (rb <= 0_m) {
+    throw std::domain_error("rb must be greater than zero.");
+  }
+  if (J <= 0_kg_sq_m) {
+    throw std::domain_error("J must be greater than zero.");
+  }
+  if (G <= 0.0) {
+    throw std::domain_error("G must be greater than zero.");
+  }
+
+  auto C1 = -std::pow(G, 2) * motor.Kt /
+            (motor.Kv * motor.R * units::math::pow<2>(r));
+  auto C2 = G * motor.Kt / (motor.R * r);
+
+  Matrixd<2, 2> A{{((1 / mass + units::math::pow<2>(rb) / J) * C1).value(),
+                   ((1 / mass - units::math::pow<2>(rb) / J) * C1).value()},
+                  {((1 / mass - units::math::pow<2>(rb) / J) * C1).value(),
+                   ((1 / mass + units::math::pow<2>(rb) / J) * C1).value()}};
+  Matrixd<2, 2> B{{((1 / mass + units::math::pow<2>(rb) / J) * C2).value(),
+                   ((1 / mass - units::math::pow<2>(rb) / J) * C2).value()},
+                  {((1 / mass - units::math::pow<2>(rb) / J) * C2).value(),
+                   ((1 / mass + units::math::pow<2>(rb) / J) * C2).value()}};
+  Matrixd<2, 2> C{{1.0, 0.0}, {0.0, 1.0}};
+  Matrixd<2, 2> D{{0.0, 0.0}, {0.0, 0.0}};
+
+  return LinearSystem<2, 2, 2>(A, B, C, D);
+}
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/trajectory/Trajectory.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/trajectory/Trajectory.cpp
index ecb36c2..de47547 100644
--- a/third_party/allwpilib/wpimath/src/main/native/cpp/trajectory/Trajectory.cpp
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/trajectory/Trajectory.cpp
@@ -13,16 +13,6 @@
 
 using namespace frc;
 
-bool Trajectory::State::operator==(const Trajectory::State& other) const {
-  return t == other.t && velocity == other.velocity &&
-         acceleration == other.acceleration && pose == other.pose &&
-         curvature == other.curvature;
-}
-
-bool Trajectory::State::operator!=(const Trajectory::State& other) const {
-  return !operator==(other);
-}
-
 Trajectory::State Trajectory::State::Interpolate(State endValue,
                                                  double i) const {
   // Find the new [t] value.
@@ -46,7 +36,7 @@
   const units::meters_per_second_t newV = velocity + (acceleration * deltaT);
 
   // Calculate the change in position.
-  // delta_s = v_0 t + 0.5 at^2
+  // delta_s = v_0 t + 0.5at²
   const units::meter_t newS =
       (velocity * deltaT + 0.5 * acceleration * deltaT * deltaT) *
       (reversing ? -1.0 : 1.0);
@@ -163,11 +153,3 @@
       units::meters_per_second_squared_t{json.at("acceleration").get<double>()};
   state.curvature = units::curvature_t{json.at("curvature").get<double>()};
 }
-
-bool Trajectory::operator==(const Trajectory& other) const {
-  return m_states == other.States();
-}
-
-bool Trajectory::operator!=(const Trajectory& other) const {
-  return !operator==(other);
-}
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/trajectory/TrajectoryGenerator.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/trajectory/TrajectoryGenerator.cpp
index 1884758..c7a7e9a 100644
--- a/third_party/allwpilib/wpimath/src/main/native/cpp/trajectory/TrajectoryGenerator.cpp
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/trajectory/TrajectoryGenerator.cpp
@@ -30,7 +30,7 @@
     Spline<3>::ControlVector initial,
     const std::vector<Translation2d>& interiorWaypoints,
     Spline<3>::ControlVector end, const TrajectoryConfig& config) {
-  const Transform2d flip{Translation2d(), Rotation2d(180_deg)};
+  const Transform2d flip{Translation2d{}, 180_deg};
 
   // Make theta normal for trajectory generation if path is reversed.
   // Flip the headings.
@@ -76,7 +76,7 @@
 Trajectory TrajectoryGenerator::GenerateTrajectory(
     std::vector<Spline<5>::ControlVector> controlVectors,
     const TrajectoryConfig& config) {
-  const Transform2d flip{Translation2d(), Rotation2d(180_deg)};
+  const Transform2d flip{Translation2d{}, 180_deg};
   // Make theta normal for trajectory generation if path is reversed.
   if (config.IsReversed()) {
     for (auto& vector : controlVectors) {
@@ -112,7 +112,7 @@
 Trajectory TrajectoryGenerator::GenerateTrajectory(
     const std::vector<Pose2d>& waypoints, const TrajectoryConfig& config) {
   auto newWaypoints = waypoints;
-  const Transform2d flip{Translation2d(), Rotation2d(180_deg)};
+  const Transform2d flip{Translation2d{}, 180_deg};
   if (config.IsReversed()) {
     for (auto& waypoint : newWaypoints) {
       waypoint = waypoint + flip;
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/trajectory/TrajectoryParameterizer.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/trajectory/TrajectoryParameterizer.cpp
index d397d0c..92d52ed 100644
--- a/third_party/allwpilib/wpimath/src/main/native/cpp/trajectory/TrajectoryParameterizer.cpp
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/trajectory/TrajectoryParameterizer.cpp
@@ -62,7 +62,7 @@
     // acceleration, since acceleration limits may be a function of velocity.
     while (true) {
       // Enforce global max velocity and max reachable velocity by global
-      // acceleration limit. vf = std::sqrt(vi^2 + 2*a*d).
+      // acceleration limit. v_f = √(v_i² + 2ad).
 
       constrainedState.maxVelocity = units::math::min(
           maxVelocity,
@@ -126,7 +126,7 @@
 
     while (true) {
       // Enforce max velocity limit (reverse)
-      // vf = std::sqrt(vi^2 + 2*a*d), where vi = successor.
+      // v_f = √(v_i² + 2ad), where v_i = successor.
       units::meters_per_second_t newMaxVelocity =
           units::math::sqrt(successor.maxVelocity * successor.maxVelocity +
                             successor.minAcceleration * ds * 2.0);
@@ -187,10 +187,10 @@
     if (i > 0) {
       states.at(i - 1).acceleration = reversed ? -accel : accel;
       if (units::math::abs(accel) > 1E-6_mps_sq) {
-        // v_f = v_0 + a * t
+        // v_f = v_0 + at
         dt = (state.maxVelocity - v) / accel;
       } else if (units::math::abs(v) > 1E-6_mps) {
-        // delta_x = v * t
+        // delta_x = vt
         dt = ds / v;
       } else {
         throw std::runtime_error(fmt::format(
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/trajectory/constraint/CentripetalAccelerationConstraint.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/trajectory/constraint/CentripetalAccelerationConstraint.cpp
index 738d243..40913a8 100644
--- a/third_party/allwpilib/wpimath/src/main/native/cpp/trajectory/constraint/CentripetalAccelerationConstraint.cpp
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/trajectory/constraint/CentripetalAccelerationConstraint.cpp
@@ -15,12 +15,12 @@
 units::meters_per_second_t CentripetalAccelerationConstraint::MaxVelocity(
     const Pose2d& pose, units::curvature_t curvature,
     units::meters_per_second_t velocity) const {
-  // ac = v^2 / r
-  // k (curvature) = 1 / r
+  // ac = v²/r
+  // k (curvature) = 1/r
 
-  // therefore, ac = v^2 * k
-  // ac / k = v^2
-  // v = std::sqrt(ac / k)
+  // therefore, ac = v²k
+  // ac/k = v²
+  // v = √(ac/k)
 
   // We have to multiply by 1_rad here to get the units to cancel out nicely.
   // The units library defines a unit for radians although it is technically
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/trajectory/constraint/DifferentialDriveVoltageConstraint.cpp b/third_party/allwpilib/wpimath/src/main/native/cpp/trajectory/constraint/DifferentialDriveVoltageConstraint.cpp
index 7c10201..d60b4b6 100644
--- a/third_party/allwpilib/wpimath/src/main/native/cpp/trajectory/constraint/DifferentialDriveVoltageConstraint.cpp
+++ b/third_party/allwpilib/wpimath/src/main/native/cpp/trajectory/constraint/DifferentialDriveVoltageConstraint.cpp
@@ -23,7 +23,7 @@
 units::meters_per_second_t DifferentialDriveVoltageConstraint::MaxVelocity(
     const Pose2d& pose, units::curvature_t curvature,
     units::meters_per_second_t velocity) const {
-  return units::meters_per_second_t(std::numeric_limits<double>::max());
+  return units::meters_per_second_t{std::numeric_limits<double>::max()};
 }
 
 TrajectoryConstraint::MinMax
@@ -33,8 +33,8 @@
   auto wheelSpeeds =
       m_kinematics.ToWheelSpeeds({speed, 0_mps, speed * curvature});
 
-  auto maxWheelSpeed = std::max(wheelSpeeds.left, wheelSpeeds.right);
-  auto minWheelSpeed = std::min(wheelSpeeds.left, wheelSpeeds.right);
+  auto maxWheelSpeed = (std::max)(wheelSpeeds.left, wheelSpeeds.right);
+  auto minWheelSpeed = (std::min)(wheelSpeeds.left, wheelSpeeds.right);
 
   // Calculate maximum/minimum possible accelerations from motor dynamics
   // and max/min wheel speeds
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/util/DisableStupidWarnings.h b/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/util/DisableStupidWarnings.h
deleted file mode 100644
index 3bec072..0000000
--- a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/util/DisableStupidWarnings.h
+++ /dev/null
@@ -1,110 +0,0 @@
-#ifndef EIGEN_WARNINGS_DISABLED
-#define EIGEN_WARNINGS_DISABLED
-
-#ifdef _MSC_VER
-  // 4100 - unreferenced formal parameter (occurred e.g. in aligned_allocator::destroy(pointer p))
-  // 4101 - unreferenced local variable
-  // 4181 - qualifier applied to reference type ignored
-  // 4211 - nonstandard extension used : redefined extern to static
-  // 4244 - 'argument' : conversion from 'type1' to 'type2', possible loss of data
-  // 4273 - QtAlignedMalloc, inconsistent DLL linkage
-  // 4324 - structure was padded due to declspec(align())
-  // 4503 - decorated name length exceeded, name was truncated
-  // 4512 - assignment operator could not be generated
-  // 4522 - 'class' : multiple assignment operators specified
-  // 4700 - uninitialized local variable 'xyz' used
-  // 4714 - function marked as __forceinline not inlined
-  // 4717 - 'function' : recursive on all control paths, function will cause runtime stack overflow
-  // 4800 - 'type' : forcing value to bool 'true' or 'false' (performance warning)
-  #ifndef EIGEN_PERMANENTLY_DISABLE_STUPID_WARNINGS
-    #pragma warning( push )
-  #endif
-  #pragma warning( disable : 4100 4101 4181 4211 4244 4273 4324 4503 4512 4522 4700 4714 4717 4800)
-
-#elif defined __INTEL_COMPILER
-  // 2196 - routine is both "inline" and "noinline" ("noinline" assumed)
-  //        ICC 12 generates this warning even without any inline keyword, when defining class methods 'inline' i.e. inside of class body
-  //        typedef that may be a reference type.
-  // 279  - controlling expression is constant
-  //        ICC 12 generates this warning on assert(constant_expression_depending_on_template_params) and frankly this is a legitimate use case.
-  // 1684 - conversion from pointer to same-sized integral type (potential portability problem)
-  // 2259 - non-pointer conversion from "Eigen::Index={ptrdiff_t={long}}" to "int" may lose significant bits
-  #ifndef EIGEN_PERMANENTLY_DISABLE_STUPID_WARNINGS
-    #pragma warning push
-  #endif
-  #pragma warning disable 2196 279 1684 2259
-
-#elif defined __clang__
-  // -Wconstant-logical-operand - warning: use of logical && with constant operand; switch to bitwise & or remove constant
-  //     this is really a stupid warning as it warns on compile-time expressions involving enums
-  #ifndef EIGEN_PERMANENTLY_DISABLE_STUPID_WARNINGS
-    #pragma clang diagnostic push
-  #endif
-  #pragma clang diagnostic ignored "-Wconstant-logical-operand"
-  #if __clang_major__ >= 3 && __clang_minor__ >= 5
-    #pragma clang diagnostic ignored "-Wabsolute-value"
-  #endif
-  #if __clang_major__ >= 10
-    #pragma clang diagnostic ignored "-Wimplicit-int-float-conversion"
-  #endif
-  #if ( defined(__ALTIVEC__) || defined(__VSX__) ) && __cplusplus < 201103L
-    // warning: generic selections are a C11-specific feature
-    // ignoring warnings thrown at vec_ctf in Altivec/PacketMath.h
-    #pragma clang diagnostic ignored "-Wc11-extensions"
-  #endif
-
-#elif defined __GNUC__
-
-  #if (!defined(EIGEN_PERMANENTLY_DISABLE_STUPID_WARNINGS)) &&  (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 6))
-    #pragma GCC diagnostic push
-  #endif
-  // g++ warns about local variables shadowing member functions, which is too strict
-  #pragma GCC diagnostic ignored "-Wshadow"
-  #if __GNUC__ == 4 && __GNUC_MINOR__ < 8
-    // Until g++-4.7 there are warnings when comparing unsigned int vs 0, even in templated functions:
-    #pragma GCC diagnostic ignored "-Wtype-limits"
-  #endif
-  #if __GNUC__>=6
-    #pragma GCC diagnostic ignored "-Wignored-attributes"
-  #endif
-  #if __GNUC__==7
-    // See: https://gcc.gnu.org/bugzilla/show_bug.cgi?id=89325
-    #pragma GCC diagnostic ignored "-Wattributes"
-  #endif
-  #if __GNUC__==11
-    // This warning is a false positive
-    #pragma GCC diagnostic ignored "-Wmaybe-uninitialized"
-  #endif
-#endif
-
-#if defined __NVCC__
-  #pragma diag_suppress boolean_controlling_expr_is_constant
-  // Disable the "statement is unreachable" message
-  #pragma diag_suppress code_is_unreachable
-  // Disable the "dynamic initialization in unreachable code" message
-  #pragma diag_suppress initialization_not_reachable
-  // Disable the "invalid error number" message that we get with older versions of nvcc
-  #pragma diag_suppress 1222
-  // Disable the "calling a __host__ function from a __host__ __device__ function is not allowed" messages (yes, there are many of them and they seem to change with every version of the compiler)
-  #pragma diag_suppress 2527
-  #pragma diag_suppress 2529
-  #pragma diag_suppress 2651
-  #pragma diag_suppress 2653
-  #pragma diag_suppress 2668
-  #pragma diag_suppress 2669
-  #pragma diag_suppress 2670
-  #pragma diag_suppress 2671
-  #pragma diag_suppress 2735
-  #pragma diag_suppress 2737
-  #pragma diag_suppress 2739
-#endif
-
-#else
-// warnings already disabled:
-# ifndef EIGEN_WARNINGS_DISABLED_2
-#  define EIGEN_WARNINGS_DISABLED_2
-# elif defined(EIGEN_INTERNAL_DEBUGGING)
-#  error "Do not include \"DisableStupidWarnings.h\" recursively more than twice!"
-# endif
-
-#endif // not EIGEN_WARNINGS_DISABLED
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/unsupported/Eigen/AutoDiff b/third_party/allwpilib/wpimath/src/main/native/eigeninclude/unsupported/Eigen/AutoDiff
deleted file mode 100644
index 7a4ff46..0000000
--- a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/unsupported/Eigen/AutoDiff
+++ /dev/null
@@ -1,46 +0,0 @@
-// This file is part of Eigen, a lightweight C++ template library
-// for linear algebra.
-//
-// Copyright (C) 2008-2009 Gael Guennebaud <g.gael@free.fr>
-//
-// This Source Code Form is subject to the terms of the Mozilla
-// Public License v. 2.0. If a copy of the MPL was not distributed
-// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
-
-#ifndef EIGEN_AUTODIFF_MODULE
-#define EIGEN_AUTODIFF_MODULE
-
-namespace Eigen {
-
-/**
-  * \defgroup AutoDiff_Module Auto Diff module
-  *
-  * This module features forward automatic differentation via a simple
-  * templated scalar type wrapper AutoDiffScalar.
-  *
-  * Warning : this should NOT be confused with numerical differentiation, which
-  * is a different method and has its own module in Eigen : \ref NumericalDiff_Module.
-  *
-  * \code
-  * #include <unsupported/Eigen/AutoDiff>
-  * \endcode
-  */
-//@{
-
-}
-#include "../../Eigen/src/Core/util/DisableStupidWarnings.h"
-
-
-#include "src/AutoDiff/AutoDiffScalar.h"
-// #include "src/AutoDiff/AutoDiffVector.h"
-#include "src/AutoDiff/AutoDiffJacobian.h"
-
-#include "../../Eigen/src/Core/util/ReenableStupidWarnings.h"
-
-
-
-namespace Eigen {
-//@}
-}
-
-#endif // EIGEN_AUTODIFF_MODULE
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/unsupported/Eigen/src/AutoDiff/AutoDiffJacobian.h b/third_party/allwpilib/wpimath/src/main/native/eigeninclude/unsupported/Eigen/src/AutoDiff/AutoDiffJacobian.h
deleted file mode 100644
index 33b6c39..0000000
--- a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/unsupported/Eigen/src/AutoDiff/AutoDiffJacobian.h
+++ /dev/null
@@ -1,108 +0,0 @@
-// This file is part of Eigen, a lightweight C++ template library
-// for linear algebra.
-//
-// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>
-//
-// This Source Code Form is subject to the terms of the Mozilla
-// Public License v. 2.0. If a copy of the MPL was not distributed
-// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
-
-#ifndef EIGEN_AUTODIFF_JACOBIAN_H
-#define EIGEN_AUTODIFF_JACOBIAN_H
-
-namespace Eigen
-{
-
-template<typename Functor> class AutoDiffJacobian : public Functor
-{
-public:
-  AutoDiffJacobian() : Functor() {}
-  AutoDiffJacobian(const Functor& f) : Functor(f) {}
-
-  // forward constructors
-#if EIGEN_HAS_VARIADIC_TEMPLATES
-  template<typename... T>
-  AutoDiffJacobian(const T& ...Values) : Functor(Values...) {}
-#else
-  template<typename T0>
-  AutoDiffJacobian(const T0& a0) : Functor(a0) {}
-  template<typename T0, typename T1>
-  AutoDiffJacobian(const T0& a0, const T1& a1) : Functor(a0, a1) {}
-  template<typename T0, typename T1, typename T2>
-  AutoDiffJacobian(const T0& a0, const T1& a1, const T2& a2) : Functor(a0, a1, a2) {}
-#endif
-
-  typedef typename Functor::InputType InputType;
-  typedef typename Functor::ValueType ValueType;
-  typedef typename ValueType::Scalar Scalar;
-
-  enum {
-    InputsAtCompileTime = InputType::RowsAtCompileTime,
-    ValuesAtCompileTime = ValueType::RowsAtCompileTime
-  };
-
-  typedef Matrix<Scalar, ValuesAtCompileTime, InputsAtCompileTime> JacobianType;
-  typedef typename JacobianType::Index Index;
-
-  typedef Matrix<Scalar, InputsAtCompileTime, 1> DerivativeType;
-  typedef AutoDiffScalar<DerivativeType> ActiveScalar;
-
-  typedef Matrix<ActiveScalar, InputsAtCompileTime, 1> ActiveInput;
-  typedef Matrix<ActiveScalar, ValuesAtCompileTime, 1> ActiveValue;
-
-#if EIGEN_HAS_VARIADIC_TEMPLATES
-  // Some compilers don't accept variadic parameters after a default parameter,
-  // i.e., we can't just write _jac=0 but we need to overload operator():
-  EIGEN_STRONG_INLINE
-  void operator() (const InputType& x, ValueType* v) const
-  {
-      this->operator()(x, v, 0);
-  }
-  template<typename... ParamsType>
-  void operator() (const InputType& x, ValueType* v, JacobianType* _jac,
-                   const ParamsType&... Params) const
-#else
-  void operator() (const InputType& x, ValueType* v, JacobianType* _jac=0) const
-#endif
-  {
-    eigen_assert(v!=0);
-
-    if (!_jac)
-    {
-#if EIGEN_HAS_VARIADIC_TEMPLATES
-      Functor::operator()(x, v, Params...);
-#else
-      Functor::operator()(x, v);
-#endif
-      return;
-    }
-
-    JacobianType& jac = *_jac;
-
-    ActiveInput ax = x.template cast<ActiveScalar>();
-    ActiveValue av(jac.rows());
-
-    if(InputsAtCompileTime==Dynamic)
-      for (Index j=0; j<jac.rows(); j++)
-        av[j].derivatives().resize(x.rows());
-
-    for (Index i=0; i<jac.cols(); i++)
-      ax[i].derivatives() = DerivativeType::Unit(x.rows(),i);
-
-#if EIGEN_HAS_VARIADIC_TEMPLATES
-    Functor::operator()(ax, &av, Params...);
-#else
-    Functor::operator()(ax, &av);
-#endif
-
-    for (Index i=0; i<jac.rows(); i++)
-    {
-      (*v)[i] = av[i].value();
-      jac.row(i) = av[i].derivatives();
-    }
-  }
-};
-
-}
-
-#endif // EIGEN_AUTODIFF_JACOBIAN_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/unsupported/Eigen/src/AutoDiff/AutoDiffScalar.h b/third_party/allwpilib/wpimath/src/main/native/eigeninclude/unsupported/Eigen/src/AutoDiff/AutoDiffScalar.h
deleted file mode 100644
index 0f166e3..0000000
--- a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/unsupported/Eigen/src/AutoDiff/AutoDiffScalar.h
+++ /dev/null
@@ -1,730 +0,0 @@
-// This file is part of Eigen, a lightweight C++ template library
-// for linear algebra.
-//
-// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>
-//
-// This Source Code Form is subject to the terms of the Mozilla
-// Public License v. 2.0. If a copy of the MPL was not distributed
-// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
-
-#ifndef EIGEN_AUTODIFF_SCALAR_H
-#define EIGEN_AUTODIFF_SCALAR_H
-
-namespace Eigen {
-
-namespace internal {
-
-template<typename A, typename B>
-struct make_coherent_impl {
-  static void run(A&, B&) {}
-};
-
-// resize a to match b is a.size()==0, and conversely.
-template<typename A, typename B>
-void make_coherent(const A& a, const B&b)
-{
-  make_coherent_impl<A,B>::run(a.const_cast_derived(), b.const_cast_derived());
-}
-
-template<typename DerivativeType, bool Enable> struct auto_diff_special_op;
-
-} // end namespace internal
-
-template<typename DerivativeType> class AutoDiffScalar;
-
-template<typename NewDerType>
-inline AutoDiffScalar<NewDerType> MakeAutoDiffScalar(const typename NewDerType::Scalar& value, const NewDerType &der) {
-  return AutoDiffScalar<NewDerType>(value,der);
-}
-
-/** \class AutoDiffScalar
-  * \brief A scalar type replacement with automatic differentiation capability
-  *
-  * \param DerivativeType the vector type used to store/represent the derivatives. The base scalar type
-  *                 as well as the number of derivatives to compute are determined from this type.
-  *                 Typical choices include, e.g., \c Vector4f for 4 derivatives, or \c VectorXf
-  *                 if the number of derivatives is not known at compile time, and/or, the number
-  *                 of derivatives is large.
-  *                 Note that DerivativeType can also be a reference (e.g., \c VectorXf&) to wrap a
-  *                 existing vector into an AutoDiffScalar.
-  *                 Finally, DerivativeType can also be any Eigen compatible expression.
-  *
-  * This class represents a scalar value while tracking its respective derivatives using Eigen's expression
-  * template mechanism.
-  *
-  * It supports the following list of global math function:
-  *  - std::abs, std::sqrt, std::pow, std::exp, std::log, std::sin, std::cos,
-  *  - internal::abs, internal::sqrt, numext::pow, internal::exp, internal::log, internal::sin, internal::cos,
-  *  - internal::conj, internal::real, internal::imag, numext::abs2.
-  *
-  * AutoDiffScalar can be used as the scalar type of an Eigen::Matrix object. However,
-  * in that case, the expression template mechanism only occurs at the top Matrix level,
-  * while derivatives are computed right away.
-  *
-  */
-
-template<typename DerivativeType>
-class AutoDiffScalar
-  : public internal::auto_diff_special_op
-            <DerivativeType, !internal::is_same<typename internal::traits<typename internal::remove_all<DerivativeType>::type>::Scalar,
-                                          typename NumTraits<typename internal::traits<typename internal::remove_all<DerivativeType>::type>::Scalar>::Real>::value>
-{
-  public:
-    typedef internal::auto_diff_special_op
-            <DerivativeType, !internal::is_same<typename internal::traits<typename internal::remove_all<DerivativeType>::type>::Scalar,
-                       typename NumTraits<typename internal::traits<typename internal::remove_all<DerivativeType>::type>::Scalar>::Real>::value> Base;
-    typedef typename internal::remove_all<DerivativeType>::type DerType;
-    typedef typename internal::traits<DerType>::Scalar Scalar;
-    typedef typename NumTraits<Scalar>::Real Real;
-
-    using Base::operator+;
-    using Base::operator*;
-
-    /** Default constructor without any initialization. */
-    AutoDiffScalar() {}
-
-    /** Constructs an active scalar from its \a value,
-        and initializes the \a nbDer derivatives such that it corresponds to the \a derNumber -th variable */
-    AutoDiffScalar(const Scalar& value, int nbDer, int derNumber)
-      : m_value(value), m_derivatives(DerType::Zero(nbDer))
-    {
-      m_derivatives.coeffRef(derNumber) = Scalar(1);
-    }
-
-    /** Conversion from a scalar constant to an active scalar.
-      * The derivatives are set to zero. */
-    /*explicit*/ AutoDiffScalar(const Real& value)
-      : m_value(value)
-    {
-      if(m_derivatives.size()>0)
-        m_derivatives.setZero();
-    }
-
-    /** Constructs an active scalar from its \a value and derivatives \a der */
-    AutoDiffScalar(const Scalar& value, const DerType& der)
-      : m_value(value), m_derivatives(der)
-    {}
-
-    template<typename OtherDerType>
-    AutoDiffScalar(const AutoDiffScalar<OtherDerType>& other
-#ifndef EIGEN_PARSED_BY_DOXYGEN
-    , typename internal::enable_if<
-            internal::is_same<Scalar, typename internal::traits<typename internal::remove_all<OtherDerType>::type>::Scalar>::value
-        &&  internal::is_convertible<OtherDerType,DerType>::value , void*>::type = 0
-#endif
-    )
-      : m_value(other.value()), m_derivatives(other.derivatives())
-    {}
-
-    friend  std::ostream & operator << (std::ostream & s, const AutoDiffScalar& a)
-    {
-      return s << a.value();
-    }
-
-    AutoDiffScalar(const AutoDiffScalar& other)
-      : m_value(other.value()), m_derivatives(other.derivatives())
-    {}
-
-    template<typename OtherDerType>
-    inline AutoDiffScalar& operator=(const AutoDiffScalar<OtherDerType>& other)
-    {
-      m_value = other.value();
-      m_derivatives = other.derivatives();
-      return *this;
-    }
-
-    inline AutoDiffScalar& operator=(const AutoDiffScalar& other)
-    {
-      m_value = other.value();
-      m_derivatives = other.derivatives();
-      return *this;
-    }
-
-    inline AutoDiffScalar& operator=(const Scalar& other)
-    {
-      m_value = other;
-      if(m_derivatives.size()>0)
-        m_derivatives.setZero();
-      return *this;
-    }
-
-//     inline operator const Scalar& () const { return m_value; }
-//     inline operator Scalar& () { return m_value; }
-
-    inline const Scalar& value() const { return m_value; }
-    inline Scalar& value() { return m_value; }
-
-    inline const DerType& derivatives() const { return m_derivatives; }
-    inline DerType& derivatives() { return m_derivatives; }
-
-    inline bool operator< (const Scalar& other) const  { return m_value <  other; }
-    inline bool operator<=(const Scalar& other) const  { return m_value <= other; }
-    inline bool operator> (const Scalar& other) const  { return m_value >  other; }
-    inline bool operator>=(const Scalar& other) const  { return m_value >= other; }
-    inline bool operator==(const Scalar& other) const  { return m_value == other; }
-    inline bool operator!=(const Scalar& other) const  { return m_value != other; }
-
-    friend inline bool operator< (const Scalar& a, const AutoDiffScalar& b) { return a <  b.value(); }
-    friend inline bool operator<=(const Scalar& a, const AutoDiffScalar& b) { return a <= b.value(); }
-    friend inline bool operator> (const Scalar& a, const AutoDiffScalar& b) { return a >  b.value(); }
-    friend inline bool operator>=(const Scalar& a, const AutoDiffScalar& b) { return a >= b.value(); }
-    friend inline bool operator==(const Scalar& a, const AutoDiffScalar& b) { return a == b.value(); }
-    friend inline bool operator!=(const Scalar& a, const AutoDiffScalar& b) { return a != b.value(); }
-
-    template<typename OtherDerType> inline bool operator< (const AutoDiffScalar<OtherDerType>& b) const  { return m_value <  b.value(); }
-    template<typename OtherDerType> inline bool operator<=(const AutoDiffScalar<OtherDerType>& b) const  { return m_value <= b.value(); }
-    template<typename OtherDerType> inline bool operator> (const AutoDiffScalar<OtherDerType>& b) const  { return m_value >  b.value(); }
-    template<typename OtherDerType> inline bool operator>=(const AutoDiffScalar<OtherDerType>& b) const  { return m_value >= b.value(); }
-    template<typename OtherDerType> inline bool operator==(const AutoDiffScalar<OtherDerType>& b) const  { return m_value == b.value(); }
-    template<typename OtherDerType> inline bool operator!=(const AutoDiffScalar<OtherDerType>& b) const  { return m_value != b.value(); }
-
-    inline const AutoDiffScalar<DerType&> operator+(const Scalar& other) const
-    {
-      return AutoDiffScalar<DerType&>(m_value + other, m_derivatives);
-    }
-
-    friend inline const AutoDiffScalar<DerType&> operator+(const Scalar& a, const AutoDiffScalar& b)
-    {
-      return AutoDiffScalar<DerType&>(a + b.value(), b.derivatives());
-    }
-
-//     inline const AutoDiffScalar<DerType&> operator+(const Real& other) const
-//     {
-//       return AutoDiffScalar<DerType&>(m_value + other, m_derivatives);
-//     }
-
-//     friend inline const AutoDiffScalar<DerType&> operator+(const Real& a, const AutoDiffScalar& b)
-//     {
-//       return AutoDiffScalar<DerType&>(a + b.value(), b.derivatives());
-//     }
-
-    inline AutoDiffScalar& operator+=(const Scalar& other)
-    {
-      value() += other;
-      return *this;
-    }
-
-    template<typename OtherDerType>
-    inline const AutoDiffScalar<CwiseBinaryOp<internal::scalar_sum_op<Scalar>,const DerType,const typename internal::remove_all<OtherDerType>::type> >
-    operator+(const AutoDiffScalar<OtherDerType>& other) const
-    {
-      internal::make_coherent(m_derivatives, other.derivatives());
-      return AutoDiffScalar<CwiseBinaryOp<internal::scalar_sum_op<Scalar>,const DerType,const typename internal::remove_all<OtherDerType>::type> >(
-        m_value + other.value(),
-        m_derivatives + other.derivatives());
-    }
-
-    template<typename OtherDerType>
-    inline AutoDiffScalar&
-    operator+=(const AutoDiffScalar<OtherDerType>& other)
-    {
-      (*this) = (*this) + other;
-      return *this;
-    }
-
-    inline const AutoDiffScalar<DerType&> operator-(const Scalar& b) const
-    {
-      return AutoDiffScalar<DerType&>(m_value - b, m_derivatives);
-    }
-
-    friend inline const AutoDiffScalar<CwiseUnaryOp<internal::scalar_opposite_op<Scalar>, const DerType> >
-    operator-(const Scalar& a, const AutoDiffScalar& b)
-    {
-      return AutoDiffScalar<CwiseUnaryOp<internal::scalar_opposite_op<Scalar>, const DerType> >
-            (a - b.value(), -b.derivatives());
-    }
-
-    inline AutoDiffScalar& operator-=(const Scalar& other)
-    {
-      value() -= other;
-      return *this;
-    }
-
-    template<typename OtherDerType>
-    inline const AutoDiffScalar<CwiseBinaryOp<internal::scalar_difference_op<Scalar>, const DerType,const typename internal::remove_all<OtherDerType>::type> >
-    operator-(const AutoDiffScalar<OtherDerType>& other) const
-    {
-      internal::make_coherent(m_derivatives, other.derivatives());
-      return AutoDiffScalar<CwiseBinaryOp<internal::scalar_difference_op<Scalar>, const DerType,const typename internal::remove_all<OtherDerType>::type> >(
-        m_value - other.value(),
-        m_derivatives - other.derivatives());
-    }
-
-    template<typename OtherDerType>
-    inline AutoDiffScalar&
-    operator-=(const AutoDiffScalar<OtherDerType>& other)
-    {
-      *this = *this - other;
-      return *this;
-    }
-
-    inline const AutoDiffScalar<CwiseUnaryOp<internal::scalar_opposite_op<Scalar>, const DerType> >
-    operator-() const
-    {
-      return AutoDiffScalar<CwiseUnaryOp<internal::scalar_opposite_op<Scalar>, const DerType> >(
-        -m_value,
-        -m_derivatives);
-    }
-
-    inline const AutoDiffScalar<EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(DerType,Scalar,product) >
-    operator*(const Scalar& other) const
-    {
-      return MakeAutoDiffScalar(m_value * other, m_derivatives * other);
-    }
-
-    friend inline const AutoDiffScalar<EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(DerType,Scalar,product) >
-    operator*(const Scalar& other, const AutoDiffScalar& a)
-    {
-      return MakeAutoDiffScalar(a.value() * other, a.derivatives() * other);
-    }
-
-//     inline const AutoDiffScalar<typename CwiseUnaryOp<internal::scalar_multiple_op<Real>, DerType>::Type >
-//     operator*(const Real& other) const
-//     {
-//       return AutoDiffScalar<typename CwiseUnaryOp<internal::scalar_multiple_op<Real>, DerType>::Type >(
-//         m_value * other,
-//         (m_derivatives * other));
-//     }
-//
-//     friend inline const AutoDiffScalar<typename CwiseUnaryOp<internal::scalar_multiple_op<Real>, DerType>::Type >
-//     operator*(const Real& other, const AutoDiffScalar& a)
-//     {
-//       return AutoDiffScalar<typename CwiseUnaryOp<internal::scalar_multiple_op<Real>, DerType>::Type >(
-//         a.value() * other,
-//         a.derivatives() * other);
-//     }
-
-    inline const AutoDiffScalar<EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(DerType,Scalar,product) >
-    operator/(const Scalar& other) const
-    {
-      return MakeAutoDiffScalar(m_value / other, (m_derivatives * (Scalar(1)/other)));
-    }
-
-    friend inline const AutoDiffScalar<EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(DerType,Scalar,product) >
-    operator/(const Scalar& other, const AutoDiffScalar& a)
-    {
-      return MakeAutoDiffScalar(other / a.value(), a.derivatives() * (Scalar(-other) / (a.value()*a.value())));
-    }
-
-//     inline const AutoDiffScalar<typename CwiseUnaryOp<internal::scalar_multiple_op<Real>, DerType>::Type >
-//     operator/(const Real& other) const
-//     {
-//       return AutoDiffScalar<typename CwiseUnaryOp<internal::scalar_multiple_op<Real>, DerType>::Type >(
-//         m_value / other,
-//         (m_derivatives * (Real(1)/other)));
-//     }
-//
-//     friend inline const AutoDiffScalar<typename CwiseUnaryOp<internal::scalar_multiple_op<Real>, DerType>::Type >
-//     operator/(const Real& other, const AutoDiffScalar& a)
-//     {
-//       return AutoDiffScalar<typename CwiseUnaryOp<internal::scalar_multiple_op<Real>, DerType>::Type >(
-//         other / a.value(),
-//         a.derivatives() * (-Real(1)/other));
-//     }
-
-    template<typename OtherDerType>
-    inline const AutoDiffScalar<EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(
-        CwiseBinaryOp<internal::scalar_difference_op<Scalar> EIGEN_COMMA
-          const EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(DerType,Scalar,product) EIGEN_COMMA
-          const EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(typename internal::remove_all<OtherDerType>::type,Scalar,product) >,Scalar,product) >
-    operator/(const AutoDiffScalar<OtherDerType>& other) const
-    {
-      internal::make_coherent(m_derivatives, other.derivatives());
-      return MakeAutoDiffScalar(
-        m_value / other.value(),
-          ((m_derivatives * other.value()) - (other.derivatives() * m_value))
-        * (Scalar(1)/(other.value()*other.value())));
-    }
-
-    template<typename OtherDerType>
-    inline const AutoDiffScalar<CwiseBinaryOp<internal::scalar_sum_op<Scalar>,
-        const EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(DerType,Scalar,product),
-        const EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(typename internal::remove_all<OtherDerType>::type,Scalar,product) > >
-    operator*(const AutoDiffScalar<OtherDerType>& other) const
-    {
-      internal::make_coherent(m_derivatives, other.derivatives());
-      return MakeAutoDiffScalar(
-        m_value * other.value(),
-        (m_derivatives * other.value()) + (other.derivatives() * m_value));
-    }
-
-    inline AutoDiffScalar& operator*=(const Scalar& other)
-    {
-      *this = *this * other;
-      return *this;
-    }
-
-    template<typename OtherDerType>
-    inline AutoDiffScalar& operator*=(const AutoDiffScalar<OtherDerType>& other)
-    {
-      *this = *this * other;
-      return *this;
-    }
-
-    inline AutoDiffScalar& operator/=(const Scalar& other)
-    {
-      *this = *this / other;
-      return *this;
-    }
-
-    template<typename OtherDerType>
-    inline AutoDiffScalar& operator/=(const AutoDiffScalar<OtherDerType>& other)
-    {
-      *this = *this / other;
-      return *this;
-    }
-
-  protected:
-    Scalar m_value;
-    DerType m_derivatives;
-
-};
-
-namespace internal {
-
-template<typename DerivativeType>
-struct auto_diff_special_op<DerivativeType, true>
-//   : auto_diff_scalar_op<DerivativeType, typename NumTraits<Scalar>::Real,
-//                            is_same<Scalar,typename NumTraits<Scalar>::Real>::value>
-{
-  typedef typename remove_all<DerivativeType>::type DerType;
-  typedef typename traits<DerType>::Scalar Scalar;
-  typedef typename NumTraits<Scalar>::Real Real;
-
-//   typedef auto_diff_scalar_op<DerivativeType, typename NumTraits<Scalar>::Real,
-//                            is_same<Scalar,typename NumTraits<Scalar>::Real>::value> Base;
-
-//   using Base::operator+;
-//   using Base::operator+=;
-//   using Base::operator-;
-//   using Base::operator-=;
-//   using Base::operator*;
-//   using Base::operator*=;
-
-  const AutoDiffScalar<DerivativeType>& derived() const { return *static_cast<const AutoDiffScalar<DerivativeType>*>(this); }
-  AutoDiffScalar<DerivativeType>& derived() { return *static_cast<AutoDiffScalar<DerivativeType>*>(this); }
-
-
-  inline const AutoDiffScalar<DerType&> operator+(const Real& other) const
-  {
-    return AutoDiffScalar<DerType&>(derived().value() + other, derived().derivatives());
-  }
-
-  friend inline const AutoDiffScalar<DerType&> operator+(const Real& a, const AutoDiffScalar<DerivativeType>& b)
-  {
-    return AutoDiffScalar<DerType&>(a + b.value(), b.derivatives());
-  }
-
-  inline AutoDiffScalar<DerivativeType>& operator+=(const Real& other)
-  {
-    derived().value() += other;
-    return derived();
-  }
-
-
-  inline const AutoDiffScalar<typename CwiseUnaryOp<bind2nd_op<scalar_product_op<Scalar,Real> >, DerType>::Type >
-  operator*(const Real& other) const
-  {
-    return AutoDiffScalar<typename CwiseUnaryOp<bind2nd_op<scalar_product_op<Scalar,Real> >, DerType>::Type >(
-      derived().value() * other,
-      derived().derivatives() * other);
-  }
-
-  friend inline const AutoDiffScalar<typename CwiseUnaryOp<bind1st_op<scalar_product_op<Real,Scalar> >, DerType>::Type >
-  operator*(const Real& other, const AutoDiffScalar<DerivativeType>& a)
-  {
-    return AutoDiffScalar<typename CwiseUnaryOp<bind1st_op<scalar_product_op<Real,Scalar> >, DerType>::Type >(
-      a.value() * other,
-      a.derivatives() * other);
-  }
-
-  inline AutoDiffScalar<DerivativeType>& operator*=(const Scalar& other)
-  {
-    *this = *this * other;
-    return derived();
-  }
-};
-
-template<typename DerivativeType>
-struct auto_diff_special_op<DerivativeType, false>
-{
-  void operator*() const;
-  void operator-() const;
-  void operator+() const;
-};
-
-template<typename BinOp, typename A, typename B, typename RefType>
-void make_coherent_expression(CwiseBinaryOp<BinOp,A,B> xpr, const RefType &ref)
-{
-  make_coherent(xpr.const_cast_derived().lhs(), ref);
-  make_coherent(xpr.const_cast_derived().rhs(), ref);
-}
-
-template<typename UnaryOp, typename A, typename RefType>
-void make_coherent_expression(const CwiseUnaryOp<UnaryOp,A> &xpr, const RefType &ref)
-{
-  make_coherent(xpr.nestedExpression().const_cast_derived(), ref);
-}
-
-// needed for compilation only
-template<typename UnaryOp, typename A, typename RefType>
-void make_coherent_expression(const CwiseNullaryOp<UnaryOp,A> &, const RefType &)
-{}
-
-template<typename A_Scalar, int A_Rows, int A_Cols, int A_Options, int A_MaxRows, int A_MaxCols, typename B>
-struct make_coherent_impl<Matrix<A_Scalar, A_Rows, A_Cols, A_Options, A_MaxRows, A_MaxCols>, B> {
-  typedef Matrix<A_Scalar, A_Rows, A_Cols, A_Options, A_MaxRows, A_MaxCols> A;
-  static void run(A& a, B& b) {
-    if((A_Rows==Dynamic || A_Cols==Dynamic) && (a.size()==0))
-    {
-      a.resize(b.size());
-      a.setZero();
-    }
-    else if (B::SizeAtCompileTime==Dynamic && a.size()!=0 && b.size()==0)
-    {
-      make_coherent_expression(b,a);
-    }
-  }
-};
-
-template<typename A, typename B_Scalar, int B_Rows, int B_Cols, int B_Options, int B_MaxRows, int B_MaxCols>
-struct make_coherent_impl<A, Matrix<B_Scalar, B_Rows, B_Cols, B_Options, B_MaxRows, B_MaxCols> > {
-  typedef Matrix<B_Scalar, B_Rows, B_Cols, B_Options, B_MaxRows, B_MaxCols> B;
-  static void run(A& a, B& b) {
-    if((B_Rows==Dynamic || B_Cols==Dynamic) && (b.size()==0))
-    {
-      b.resize(a.size());
-      b.setZero();
-    }
-    else if (A::SizeAtCompileTime==Dynamic && b.size()!=0 && a.size()==0)
-    {
-      make_coherent_expression(a,b);
-    }
-  }
-};
-
-template<typename A_Scalar, int A_Rows, int A_Cols, int A_Options, int A_MaxRows, int A_MaxCols,
-         typename B_Scalar, int B_Rows, int B_Cols, int B_Options, int B_MaxRows, int B_MaxCols>
-struct make_coherent_impl<Matrix<A_Scalar, A_Rows, A_Cols, A_Options, A_MaxRows, A_MaxCols>,
-                          Matrix<B_Scalar, B_Rows, B_Cols, B_Options, B_MaxRows, B_MaxCols> > {
-  typedef Matrix<A_Scalar, A_Rows, A_Cols, A_Options, A_MaxRows, A_MaxCols> A;
-  typedef Matrix<B_Scalar, B_Rows, B_Cols, B_Options, B_MaxRows, B_MaxCols> B;
-  static void run(A& a, B& b) {
-    if((A_Rows==Dynamic || A_Cols==Dynamic) && (a.size()==0))
-    {
-      a.resize(b.size());
-      a.setZero();
-    }
-    else if((B_Rows==Dynamic || B_Cols==Dynamic) && (b.size()==0))
-    {
-      b.resize(a.size());
-      b.setZero();
-    }
-  }
-};
-
-} // end namespace internal
-
-template<typename DerType, typename BinOp>
-struct ScalarBinaryOpTraits<AutoDiffScalar<DerType>,typename DerType::Scalar,BinOp>
-{
-  typedef AutoDiffScalar<DerType> ReturnType;
-};
-
-template<typename DerType, typename BinOp>
-struct ScalarBinaryOpTraits<typename DerType::Scalar,AutoDiffScalar<DerType>, BinOp>
-{
-  typedef AutoDiffScalar<DerType> ReturnType;
-};
-
-
-// The following is an attempt to let Eigen's known about expression template, but that's more tricky!
-
-// template<typename DerType, typename BinOp>
-// struct ScalarBinaryOpTraits<AutoDiffScalar<DerType>,AutoDiffScalar<DerType>, BinOp>
-// {
-//   enum { Defined = 1 };
-//   typedef AutoDiffScalar<typename DerType::PlainObject> ReturnType;
-// };
-//
-// template<typename DerType1,typename DerType2, typename BinOp>
-// struct ScalarBinaryOpTraits<AutoDiffScalar<DerType1>,AutoDiffScalar<DerType2>, BinOp>
-// {
-//   enum { Defined = 1 };//internal::is_same<typename DerType1::Scalar,typename DerType2::Scalar>::value };
-//   typedef AutoDiffScalar<typename DerType1::PlainObject> ReturnType;
-// };
-
-#define EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(FUNC,CODE) \
-  template<typename DerType> \
-  inline const Eigen::AutoDiffScalar< \
-  EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(typename Eigen::internal::remove_all<DerType>::type, typename Eigen::internal::traits<typename Eigen::internal::remove_all<DerType>::type>::Scalar, product) > \
-  FUNC(const Eigen::AutoDiffScalar<DerType>& x) { \
-    using namespace Eigen; \
-    typedef typename Eigen::internal::traits<typename Eigen::internal::remove_all<DerType>::type>::Scalar Scalar; \
-    EIGEN_UNUSED_VARIABLE(sizeof(Scalar)); \
-    CODE; \
-  }
-
-template<typename DerType>
-struct CleanedUpDerType {
-  typedef AutoDiffScalar<typename Eigen::internal::remove_all<DerType>::type::PlainObject> type;
-};
-
-template<typename DerType>
-inline const AutoDiffScalar<DerType>& conj(const AutoDiffScalar<DerType>& x)  { return x; }
-template<typename DerType>
-inline const AutoDiffScalar<DerType>& real(const AutoDiffScalar<DerType>& x)  { return x; }
-template<typename DerType>
-inline typename DerType::Scalar imag(const AutoDiffScalar<DerType>&)    { return 0.; }
-template<typename DerType, typename T>
-inline typename CleanedUpDerType<DerType>::type (min)(const AutoDiffScalar<DerType>& x, const T& y) {
-  typedef typename CleanedUpDerType<DerType>::type ADS;
-  return (x <= y ? ADS(x) : ADS(y));
-}
-template<typename DerType, typename T>
-inline typename CleanedUpDerType<DerType>::type (max)(const AutoDiffScalar<DerType>& x, const T& y) {
-  typedef typename CleanedUpDerType<DerType>::type ADS;
-  return (x >= y ? ADS(x) : ADS(y));
-}
-template<typename DerType, typename T>
-inline typename CleanedUpDerType<DerType>::type (min)(const T& x, const AutoDiffScalar<DerType>& y) {
-  typedef typename CleanedUpDerType<DerType>::type ADS;
-  return (x < y ? ADS(x) : ADS(y));
-}
-template<typename DerType, typename T>
-inline typename CleanedUpDerType<DerType>::type (max)(const T& x, const AutoDiffScalar<DerType>& y) {
-  typedef typename CleanedUpDerType<DerType>::type ADS;
-  return (x > y ? ADS(x) : ADS(y));
-}
-template<typename DerType>
-inline typename CleanedUpDerType<DerType>::type (min)(const AutoDiffScalar<DerType>& x, const AutoDiffScalar<DerType>& y) {
-  return (x.value() < y.value() ? x : y);
-}
-template<typename DerType>
-inline typename CleanedUpDerType<DerType>::type (max)(const AutoDiffScalar<DerType>& x, const AutoDiffScalar<DerType>& y) {
-  return (x.value() >= y.value() ? x : y);
-}
-
-
-EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(abs,
-  using std::abs;
-  return Eigen::MakeAutoDiffScalar(abs(x.value()), x.derivatives() * (x.value()<0 ? -1 : 1) );)
-
-EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(abs2,
-  using numext::abs2;
-  return Eigen::MakeAutoDiffScalar(abs2(x.value()), x.derivatives() * (Scalar(2)*x.value()));)
-
-EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(sqrt,
-  using std::sqrt;
-  Scalar sqrtx = sqrt(x.value());
-  return Eigen::MakeAutoDiffScalar(sqrtx,x.derivatives() * (Scalar(0.5) / sqrtx));)
-
-EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(cos,
-  using std::cos;
-  using std::sin;
-  return Eigen::MakeAutoDiffScalar(cos(x.value()), x.derivatives() * (-sin(x.value())));)
-
-EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(sin,
-  using std::sin;
-  using std::cos;
-  return Eigen::MakeAutoDiffScalar(sin(x.value()),x.derivatives() * cos(x.value()));)
-
-EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(exp,
-  using std::exp;
-  Scalar expx = exp(x.value());
-  return Eigen::MakeAutoDiffScalar(expx,x.derivatives() * expx);)
-
-EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(log,
-  using std::log;
-  return Eigen::MakeAutoDiffScalar(log(x.value()),x.derivatives() * (Scalar(1)/x.value()));)
-
-template<typename DerType>
-inline const Eigen::AutoDiffScalar<
-EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(typename internal::remove_all<DerType>::type,typename internal::traits<typename internal::remove_all<DerType>::type>::Scalar,product) >
-pow(const Eigen::AutoDiffScalar<DerType> &x, const typename internal::traits<typename internal::remove_all<DerType>::type>::Scalar &y)
-{
-  using namespace Eigen;
-  using std::pow;
-  return Eigen::MakeAutoDiffScalar(pow(x.value(),y), x.derivatives() * (y * pow(x.value(),y-1)));
-}
-
-
-template<typename DerTypeA,typename DerTypeB>
-inline const AutoDiffScalar<Matrix<typename internal::traits<typename internal::remove_all<DerTypeA>::type>::Scalar,Dynamic,1> >
-atan2(const AutoDiffScalar<DerTypeA>& a, const AutoDiffScalar<DerTypeB>& b)
-{
-  using std::atan2;
-  typedef typename internal::traits<typename internal::remove_all<DerTypeA>::type>::Scalar Scalar;
-  typedef AutoDiffScalar<Matrix<Scalar,Dynamic,1> > PlainADS;
-  PlainADS ret;
-  ret.value() = atan2(a.value(), b.value());
-  
-  Scalar squared_hypot = a.value() * a.value() + b.value() * b.value();
-  
-  // if (squared_hypot==0) the derivation is undefined and the following results in a NaN:
-  ret.derivatives() = (a.derivatives() * b.value() - a.value() * b.derivatives()) / squared_hypot;
-
-  return ret;
-}
-
-EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(tan,
-  using std::tan;
-  using std::cos;
-  return Eigen::MakeAutoDiffScalar(tan(x.value()),x.derivatives() * (Scalar(1)/numext::abs2(cos(x.value()))));)
-
-EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(asin,
-  using std::sqrt;
-  using std::asin;
-  return Eigen::MakeAutoDiffScalar(asin(x.value()),x.derivatives() * (Scalar(1)/sqrt(1-numext::abs2(x.value()))));)
-  
-EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(acos,
-  using std::sqrt;
-  using std::acos;
-  return Eigen::MakeAutoDiffScalar(acos(x.value()),x.derivatives() * (Scalar(-1)/sqrt(1-numext::abs2(x.value()))));)
-
-EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(tanh,
-  using std::cosh;
-  using std::tanh;
-  return Eigen::MakeAutoDiffScalar(tanh(x.value()),x.derivatives() * (Scalar(1)/numext::abs2(cosh(x.value()))));)
-
-EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(sinh,
-  using std::sinh;
-  using std::cosh;
-  return Eigen::MakeAutoDiffScalar(sinh(x.value()),x.derivatives() * cosh(x.value()));)
-
-EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(cosh,
-  using std::sinh;
-  using std::cosh;
-  return Eigen::MakeAutoDiffScalar(cosh(x.value()),x.derivatives() * sinh(x.value()));)
-
-#undef EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY
-
-template<typename DerType> struct NumTraits<AutoDiffScalar<DerType> >
-  : NumTraits< typename NumTraits<typename internal::remove_all<DerType>::type::Scalar>::Real >
-{
-  typedef typename internal::remove_all<DerType>::type DerTypeCleaned;
-  typedef AutoDiffScalar<Matrix<typename NumTraits<typename DerTypeCleaned::Scalar>::Real,DerTypeCleaned::RowsAtCompileTime,DerTypeCleaned::ColsAtCompileTime,
-                                0, DerTypeCleaned::MaxRowsAtCompileTime, DerTypeCleaned::MaxColsAtCompileTime> > Real;
-  typedef AutoDiffScalar<DerType> NonInteger;
-  typedef AutoDiffScalar<DerType> Nested;
-  typedef typename NumTraits<typename DerTypeCleaned::Scalar>::Literal Literal;
-  enum{
-    RequireInitialization = 1
-  };
-};
-
-}
-
-namespace std {
-
-template <typename T>
-class numeric_limits<Eigen::AutoDiffScalar<T> >
-  : public numeric_limits<typename T::Scalar> {};
-
-template <typename T>
-class numeric_limits<Eigen::AutoDiffScalar<T&> >
-  : public numeric_limits<typename T::Scalar> {};
-
-}  // namespace std
-
-#endif // EIGEN_AUTODIFF_SCALAR_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/unsupported/Eigen/src/AutoDiff/AutoDiffVector.h b/third_party/allwpilib/wpimath/src/main/native/eigeninclude/unsupported/Eigen/src/AutoDiff/AutoDiffVector.h
deleted file mode 100644
index 8c2d048..0000000
--- a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/unsupported/Eigen/src/AutoDiff/AutoDiffVector.h
+++ /dev/null
@@ -1,220 +0,0 @@
-// This file is part of Eigen, a lightweight C++ template library
-// for linear algebra.
-//
-// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>
-//
-// This Source Code Form is subject to the terms of the Mozilla
-// Public License v. 2.0. If a copy of the MPL was not distributed
-// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
-
-#ifndef EIGEN_AUTODIFF_VECTOR_H
-#define EIGEN_AUTODIFF_VECTOR_H
-
-namespace Eigen {
-
-/* \class AutoDiffScalar
-  * \brief A scalar type replacement with automatic differentation capability
-  *
-  * \param DerType the vector type used to store/represent the derivatives (e.g. Vector3f)
-  *
-  * This class represents a scalar value while tracking its respective derivatives.
-  *
-  * It supports the following list of global math function:
-  *  - std::abs, std::sqrt, std::pow, std::exp, std::log, std::sin, std::cos,
-  *  - internal::abs, internal::sqrt, numext::pow, internal::exp, internal::log, internal::sin, internal::cos,
-  *  - internal::conj, internal::real, internal::imag, numext::abs2.
-  *
-  * AutoDiffScalar can be used as the scalar type of an Eigen::Matrix object. However,
-  * in that case, the expression template mechanism only occurs at the top Matrix level,
-  * while derivatives are computed right away.
-  *
-  */
-template<typename ValueType, typename JacobianType>
-class AutoDiffVector
-{
-  public:
-    //typedef typename internal::traits<ValueType>::Scalar Scalar;
-    typedef typename internal::traits<ValueType>::Scalar BaseScalar;
-    typedef AutoDiffScalar<Matrix<BaseScalar,JacobianType::RowsAtCompileTime,1> > ActiveScalar;
-    typedef ActiveScalar Scalar;
-    typedef AutoDiffScalar<typename JacobianType::ColXpr> CoeffType;
-    typedef typename JacobianType::Index Index;
-
-    inline AutoDiffVector() {}
-
-    inline AutoDiffVector(const ValueType& values)
-      : m_values(values)
-    {
-      m_jacobian.setZero();
-    }
-
-
-    CoeffType operator[] (Index i) { return CoeffType(m_values[i], m_jacobian.col(i)); }
-    const CoeffType operator[] (Index i) const { return CoeffType(m_values[i], m_jacobian.col(i)); }
-
-    CoeffType operator() (Index i) { return CoeffType(m_values[i], m_jacobian.col(i)); }
-    const CoeffType operator() (Index i) const { return CoeffType(m_values[i], m_jacobian.col(i)); }
-
-    CoeffType coeffRef(Index i) { return CoeffType(m_values[i], m_jacobian.col(i)); }
-    const CoeffType coeffRef(Index i) const { return CoeffType(m_values[i], m_jacobian.col(i)); }
-
-    Index size() const { return m_values.size(); }
-
-    // FIXME here we could return an expression of the sum
-    Scalar sum() const { /*std::cerr << "sum \n\n";*/ /*std::cerr << m_jacobian.rowwise().sum() << "\n\n";*/ return Scalar(m_values.sum(), m_jacobian.rowwise().sum()); }
-
-
-    inline AutoDiffVector(const ValueType& values, const JacobianType& jac)
-      : m_values(values), m_jacobian(jac)
-    {}
-
-    template<typename OtherValueType, typename OtherJacobianType>
-    inline AutoDiffVector(const AutoDiffVector<OtherValueType, OtherJacobianType>& other)
-      : m_values(other.values()), m_jacobian(other.jacobian())
-    {}
-
-    inline AutoDiffVector(const AutoDiffVector& other)
-      : m_values(other.values()), m_jacobian(other.jacobian())
-    {}
-
-    template<typename OtherValueType, typename OtherJacobianType>
-    inline AutoDiffVector& operator=(const AutoDiffVector<OtherValueType, OtherJacobianType>& other)
-    {
-      m_values = other.values();
-      m_jacobian = other.jacobian();
-      return *this;
-    }
-
-    inline AutoDiffVector& operator=(const AutoDiffVector& other)
-    {
-      m_values = other.values();
-      m_jacobian = other.jacobian();
-      return *this;
-    }
-
-    inline const ValueType& values() const { return m_values; }
-    inline ValueType& values() { return m_values; }
-
-    inline const JacobianType& jacobian() const { return m_jacobian; }
-    inline JacobianType& jacobian() { return m_jacobian; }
-
-    template<typename OtherValueType,typename OtherJacobianType>
-    inline const AutoDiffVector<
-      typename MakeCwiseBinaryOp<internal::scalar_sum_op<BaseScalar>,ValueType,OtherValueType>::Type,
-      typename MakeCwiseBinaryOp<internal::scalar_sum_op<BaseScalar>,JacobianType,OtherJacobianType>::Type >
-    operator+(const AutoDiffVector<OtherValueType,OtherJacobianType>& other) const
-    {
-      return AutoDiffVector<
-      typename MakeCwiseBinaryOp<internal::scalar_sum_op<BaseScalar>,ValueType,OtherValueType>::Type,
-      typename MakeCwiseBinaryOp<internal::scalar_sum_op<BaseScalar>,JacobianType,OtherJacobianType>::Type >(
-        m_values + other.values(),
-        m_jacobian + other.jacobian());
-    }
-
-    template<typename OtherValueType, typename OtherJacobianType>
-    inline AutoDiffVector&
-    operator+=(const AutoDiffVector<OtherValueType,OtherJacobianType>& other)
-    {
-      m_values += other.values();
-      m_jacobian += other.jacobian();
-      return *this;
-    }
-
-    template<typename OtherValueType,typename OtherJacobianType>
-    inline const AutoDiffVector<
-      typename MakeCwiseBinaryOp<internal::scalar_difference_op<Scalar>,ValueType,OtherValueType>::Type,
-      typename MakeCwiseBinaryOp<internal::scalar_difference_op<Scalar>,JacobianType,OtherJacobianType>::Type >
-    operator-(const AutoDiffVector<OtherValueType,OtherJacobianType>& other) const
-    {
-      return AutoDiffVector<
-        typename MakeCwiseBinaryOp<internal::scalar_difference_op<Scalar>,ValueType,OtherValueType>::Type,
-        typename MakeCwiseBinaryOp<internal::scalar_difference_op<Scalar>,JacobianType,OtherJacobianType>::Type >(
-          m_values - other.values(),
-          m_jacobian - other.jacobian());
-    }
-
-    template<typename OtherValueType, typename OtherJacobianType>
-    inline AutoDiffVector&
-    operator-=(const AutoDiffVector<OtherValueType,OtherJacobianType>& other)
-    {
-      m_values -= other.values();
-      m_jacobian -= other.jacobian();
-      return *this;
-    }
-
-    inline const AutoDiffVector<
-      typename MakeCwiseUnaryOp<internal::scalar_opposite_op<Scalar>, ValueType>::Type,
-      typename MakeCwiseUnaryOp<internal::scalar_opposite_op<Scalar>, JacobianType>::Type >
-    operator-() const
-    {
-      return AutoDiffVector<
-        typename MakeCwiseUnaryOp<internal::scalar_opposite_op<Scalar>, ValueType>::Type,
-        typename MakeCwiseUnaryOp<internal::scalar_opposite_op<Scalar>, JacobianType>::Type >(
-          -m_values,
-          -m_jacobian);
-    }
-
-    inline const AutoDiffVector<
-      typename MakeCwiseUnaryOp<internal::scalar_multiple_op<Scalar>, ValueType>::Type,
-      typename MakeCwiseUnaryOp<internal::scalar_multiple_op<Scalar>, JacobianType>::Type>
-    operator*(const BaseScalar& other) const
-    {
-      return AutoDiffVector<
-        typename MakeCwiseUnaryOp<internal::scalar_multiple_op<Scalar>, ValueType>::Type,
-        typename MakeCwiseUnaryOp<internal::scalar_multiple_op<Scalar>, JacobianType>::Type >(
-          m_values * other,
-          m_jacobian * other);
-    }
-
-    friend inline const AutoDiffVector<
-      typename MakeCwiseUnaryOp<internal::scalar_multiple_op<Scalar>, ValueType>::Type,
-      typename MakeCwiseUnaryOp<internal::scalar_multiple_op<Scalar>, JacobianType>::Type >
-    operator*(const Scalar& other, const AutoDiffVector& v)
-    {
-      return AutoDiffVector<
-        typename MakeCwiseUnaryOp<internal::scalar_multiple_op<Scalar>, ValueType>::Type,
-        typename MakeCwiseUnaryOp<internal::scalar_multiple_op<Scalar>, JacobianType>::Type >(
-          v.values() * other,
-          v.jacobian() * other);
-    }
-
-//     template<typename OtherValueType,typename OtherJacobianType>
-//     inline const AutoDiffVector<
-//       CwiseBinaryOp<internal::scalar_multiple_op<Scalar>, ValueType, OtherValueType>
-//       CwiseBinaryOp<internal::scalar_sum_op<Scalar>,
-//         CwiseUnaryOp<internal::scalar_multiple_op<Scalar>, JacobianType>,
-//         CwiseUnaryOp<internal::scalar_multiple_op<Scalar>, OtherJacobianType> > >
-//     operator*(const AutoDiffVector<OtherValueType,OtherJacobianType>& other) const
-//     {
-//       return AutoDiffVector<
-//         CwiseBinaryOp<internal::scalar_multiple_op<Scalar>, ValueType, OtherValueType>
-//         CwiseBinaryOp<internal::scalar_sum_op<Scalar>,
-//           CwiseUnaryOp<internal::scalar_multiple_op<Scalar>, JacobianType>,
-//           CwiseUnaryOp<internal::scalar_multiple_op<Scalar>, OtherJacobianType> > >(
-//             m_values.cwise() * other.values(),
-//             (m_jacobian * other.values()) + (m_values * other.jacobian()));
-//     }
-
-    inline AutoDiffVector& operator*=(const Scalar& other)
-    {
-      m_values *= other;
-      m_jacobian *= other;
-      return *this;
-    }
-
-    template<typename OtherValueType,typename OtherJacobianType>
-    inline AutoDiffVector& operator*=(const AutoDiffVector<OtherValueType,OtherJacobianType>& other)
-    {
-      *this = *this * other;
-      return *this;
-    }
-
-  protected:
-    ValueType m_values;
-    JacobianType m_jacobian;
-
-};
-
-}
-
-#endif // EIGEN_AUTODIFF_VECTOR_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/drake/common/drake_assert.h b/third_party/allwpilib/wpimath/src/main/native/include/drake/common/drake_assert.h
deleted file mode 100644
index e9c3aa2..0000000
--- a/third_party/allwpilib/wpimath/src/main/native/include/drake/common/drake_assert.h
+++ /dev/null
@@ -1,162 +0,0 @@
-#pragma once
-
-#include <type_traits>
-
-/// @file
-/// Provides Drake's assertion implementation.  This is intended to be used
-/// both within Drake and by other software.  Drake's asserts can be armed
-/// and disarmed independently from the system-wide asserts.
-
-#ifdef DRAKE_DOXYGEN_CXX
-/// @p DRAKE_ASSERT(condition) is similar to the built-in @p assert(condition)
-/// from the C++ system header @p <cassert>.  Unless Drake's assertions are
-/// disarmed by the pre-processor definitions listed below, @p DRAKE_ASSERT
-/// will evaluate @p condition and iff the value is false will trigger an
-/// assertion failure with a message showing at least the condition text,
-/// function name, file, and line.
-///
-/// By default, assertion failures will :abort() the program.  However, when
-/// using the pydrake python bindings, assertion failures will instead throw a
-/// C++ exception that causes a python SystemExit exception.
-///
-/// Assertions are enabled or disabled using the following pre-processor macros:
-///
-/// - If @p DRAKE_ENABLE_ASSERTS is defined, then @p DRAKE_ASSERT is armed.
-/// - If @p DRAKE_DISABLE_ASSERTS is defined, then @p DRAKE_ASSERT is disarmed.
-/// - If both macros are defined, then it is a compile-time error.
-/// - If neither are defined, then NDEBUG governs assertions as usual.
-///
-/// This header will define exactly one of either @p DRAKE_ASSERT_IS_ARMED or
-/// @p DRAKE_ASSERT_IS_DISARMED to indicate whether @p DRAKE_ASSERT is armed.
-///
-/// This header will define both `constexpr bool drake::kDrakeAssertIsArmed`
-/// and `constexpr bool drake::kDrakeAssertIsDisarmed` globals.
-///
-/// One difference versus the standard @p assert(condition) is that the
-/// @p condition within @p DRAKE_ASSERT is always syntax-checked, even if
-/// Drake's assertions are disarmed.
-///
-/// Treat @p DRAKE_ASSERT like a statement -- it must always be used
-/// in block scope, and must always be followed by a semicolon.
-#define DRAKE_ASSERT(condition)
-/// Like @p DRAKE_ASSERT, except that the expression must be void-valued; this
-/// allows for guarding expensive assertion-checking subroutines using the same
-/// macros as stand-alone assertions.
-#define DRAKE_ASSERT_VOID(expression)
-/// Evaluates @p condition and iff the value is false will trigger an assertion
-/// failure with a message showing at least the condition text, function name,
-/// file, and line.
-#define DRAKE_DEMAND(condition)
-/// Silences a "no return value" compiler warning by calling a function that
-/// always raises an exception or aborts (i.e., a function marked noreturn).
-/// Only use this macro at a point where (1) a point in the code is truly
-/// unreachable, (2) the fact that it's unreachable is knowable from only
-/// reading the function itself (and not, e.g., some larger design invariant),
-/// and (3) there is a compiler warning if this macro were removed.  The most
-/// common valid use is with a switch-case-return block where all cases are
-/// accounted for but the enclosing function is supposed to return a value.  Do
-/// *not* use this macro as a "logic error" assertion; it should *only* be used
-/// to silence false positive warnings.  When in doubt, throw an exception
-/// manually instead of using this macro.
-#define DRAKE_UNREACHABLE()
-#else  //  DRAKE_DOXYGEN_CXX
-
-// Users should NOT set these; only this header should set them.
-#ifdef DRAKE_ASSERT_IS_ARMED
-# error Unexpected DRAKE_ASSERT_IS_ARMED defined.
-#endif
-#ifdef DRAKE_ASSERT_IS_DISARMED
-# error Unexpected DRAKE_ASSERT_IS_DISARMED defined.
-#endif
-
-// Decide whether Drake assertions are enabled.
-#if defined(DRAKE_ENABLE_ASSERTS) && defined(DRAKE_DISABLE_ASSERTS)
-# error Conflicting assertion toggles.
-#elif defined(DRAKE_ENABLE_ASSERTS)
-# define DRAKE_ASSERT_IS_ARMED
-#elif defined(DRAKE_DISABLE_ASSERTS) || defined(NDEBUG)
-# define DRAKE_ASSERT_IS_DISARMED
-#else
-# define DRAKE_ASSERT_IS_ARMED
-#endif
-
-namespace drake {
-namespace internal {
-// Abort the program with an error message.
-[[noreturn]] void Abort(const char* condition, const char* func,
-                        const char* file, int line);
-// Report an assertion failure; will either Abort(...) or throw.
-[[noreturn]] void AssertionFailed(const char* condition, const char* func,
-                                  const char* file, int line);
-}  // namespace internal
-namespace assert {
-// Allows for specialization of how to bool-convert Conditions used in
-// assertions, in case they are not intrinsically convertible.  See
-// symbolic_formula.h for an example use.  This is a public interface to
-// extend; it is intended to be specialized by unusual Scalar types that
-// require special handling.
-template <typename Condition>
-struct ConditionTraits {
-  static constexpr bool is_valid = std::is_convertible_v<Condition, bool>;
-  static bool Evaluate(const Condition& value) {
-    return value;
-  }
-};
-}  // namespace assert
-}  // namespace drake
-
-#define DRAKE_UNREACHABLE()                                             \
-  ::drake::internal::Abort(                                             \
-      "Unreachable code was reached?!", __func__, __FILE__, __LINE__)
-
-#define DRAKE_DEMAND(condition)                                              \
-  do {                                                                       \
-    typedef ::drake::assert::ConditionTraits<                                \
-        typename std::remove_cv_t<decltype(condition)>> Trait;               \
-    static_assert(Trait::is_valid, "Condition should be bool-convertible."); \
-    static_assert(                                                           \
-        !std::is_pointer_v<decltype(condition)>,                             \
-        "When using DRAKE_DEMAND on a raw pointer, always write out "        \
-        "DRAKE_DEMAND(foo != nullptr), do not write DRAKE_DEMAND(foo) "      \
-        "and rely on implicit pointer-to-bool conversion.");                 \
-    if (!Trait::Evaluate(condition)) {                                       \
-      ::drake::internal::AssertionFailed(                                    \
-           #condition, __func__, __FILE__, __LINE__);                        \
-    }                                                                        \
-  } while (0)
-
-#ifdef DRAKE_ASSERT_IS_ARMED
-// Assertions are enabled.
-namespace drake {
-constexpr bool kDrakeAssertIsArmed = true;
-constexpr bool kDrakeAssertIsDisarmed = false;
-}  // namespace drake
-# define DRAKE_ASSERT(condition) DRAKE_DEMAND(condition)
-# define DRAKE_ASSERT_VOID(expression) do {                     \
-    static_assert(                                              \
-        std::is_convertible_v<decltype(expression), void>,      \
-        "Expression should be void.");                          \
-    expression;                                                 \
-  } while (0)
-#else
-// Assertions are disabled, so just typecheck the expression.
-namespace drake {
-constexpr bool kDrakeAssertIsArmed = false;
-constexpr bool kDrakeAssertIsDisarmed = true;
-}  // namespace drake
-# define DRAKE_ASSERT(condition) do {                                        \
-    typedef ::drake::assert::ConditionTraits<                                \
-        typename std::remove_cv_t<decltype(condition)>> Trait;               \
-    static_assert(Trait::is_valid, "Condition should be bool-convertible."); \
-    static_assert(                                                           \
-        !std::is_pointer_v<decltype(condition)>,                             \
-        "When using DRAKE_ASSERT on a raw pointer, always write out "        \
-        "DRAKE_ASSERT(foo != nullptr), do not write DRAKE_ASSERT(foo) "      \
-        "and rely on implicit pointer-to-bool conversion.");                 \
-  } while (0)
-# define DRAKE_ASSERT_VOID(expression) static_assert(           \
-    std::is_convertible_v<decltype(expression), void>,          \
-    "Expression should be void.")
-#endif
-
-#endif  // DRAKE_DOXYGEN_CXX
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/ComputerVisionUtil.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/ComputerVisionUtil.h
new file mode 100644
index 0000000..54f9752
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/ComputerVisionUtil.h
@@ -0,0 +1,37 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <wpi/SymbolExports.h>
+
+#include "frc/geometry/Pose3d.h"
+#include "frc/geometry/Transform3d.h"
+
+namespace frc {
+
+/**
+ * Returns the robot's pose in the field coordinate system given an object's
+ * field-relative pose, the transformation from the camera's pose to the
+ * object's pose (obtained via computer vision), and the transformation from the
+ * robot's pose to the camera's pose.
+ *
+ * The object could be a target or a fiducial marker.
+ *
+ * @param objectInField An object's field-relative pose.
+ * @param cameraToObject The transformation from the camera's pose to the
+ *   object's pose. This comes from computer vision.
+ * @param robotToCamera The transformation from the robot's pose to the camera's
+ *   pose. This can either be a constant for a rigidly mounted camera, or
+ *   variable if the camera is mounted to a turret. If the camera was mounted 3
+ *   inches in front of the "origin" (usually physical center) of the robot,
+ *   this would be frc::Transform3d{3_in, 0_in, 0_in, frc::Rotation3d{}}.
+ * @return The robot's field-relative pose.
+ */
+WPILIB_DLLEXPORT
+frc::Pose3d ObjectToRobotPose(const frc::Pose3d& objectInField,
+                              const frc::Transform3d& cameraToObject,
+                              const frc::Transform3d& robotToCamera);
+
+}  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/EigenCore.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/EigenCore.h
new file mode 100644
index 0000000..b33e9e2
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/EigenCore.h
@@ -0,0 +1,23 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include "Eigen/Core"
+
+namespace frc {
+
+template <int Size>
+using Vectord = Eigen::Vector<double, Size>;
+
+template <int Rows, int Cols,
+          int Options = Eigen::AutoAlign |
+                        ((Rows == 1 && Cols != 1) ? Eigen::RowMajor
+                         : (Cols == 1 && Rows != 1)
+                             ? Eigen::ColMajor
+                             : EIGEN_DEFAULT_MATRIX_STORAGE_ORDER_OPTION),
+          int MaxRows = Rows, int MaxCols = Cols>
+using Matrixd = Eigen::Matrix<double, Rows, Cols, Options, MaxRows, MaxCols>;
+
+}  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/MathUtil.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/MathUtil.h
index 54a77af..24bf857 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/MathUtil.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/MathUtil.h
@@ -4,22 +4,84 @@
 
 #pragma once
 
+#include <numbers>
+
 #include <wpi/SymbolExports.h>
-#include <wpi/numbers>
 
 #include "units/angle.h"
+#include "units/base.h"
+#include "units/math.h"
 
 namespace frc {
 
 /**
- * Returns 0.0 if the given value is within the specified range around zero.
- * The remaining range between the deadband and 1.0 is scaled from 0.0 to 1.0.
+ * Returns 0.0 if the given value is within the specified range around zero. The
+ * remaining range between the deadband and the maximum magnitude is scaled from
+ * 0.0 to the maximum magnitude.
  *
- * @param value    Value to clip.
+ * @param value Value to clip.
  * @param deadband Range around zero.
+ * @param maxMagnitude The maximum magnitude of the input (defaults to 1). Can
+ * be infinite.
+ * @return The value after the deadband is applied.
  */
-WPILIB_DLLEXPORT
-double ApplyDeadband(double value, double deadband);
+template <typename T,
+          typename = std::enable_if_t<std::disjunction_v<
+              std::is_floating_point<T>, units::traits::is_unit_t<T>>>>
+T ApplyDeadband(T value, T deadband, T maxMagnitude = T{1.0}) {
+  T magnitude;
+  if constexpr (std::is_floating_point_v<T>) {
+    magnitude = std::abs(value);
+  } else {
+    magnitude = units::math::abs(value);
+  }
+
+  if (magnitude > deadband) {
+    if (maxMagnitude / deadband > 1.0E12) {
+      // If max magnitude is sufficiently large, the implementation encounters
+      // roundoff error.  Implementing the limiting behavior directly avoids
+      // the problem.
+      return value > T{0.0} ? value - deadband : value + deadband;
+    }
+    if (value > T{0.0}) {
+      // Map deadband to 0 and map max to max.
+      //
+      // y - y₁ = m(x - x₁)
+      // y - y₁ = (y₂ - y₁)/(x₂ - x₁) (x - x₁)
+      // y = (y₂ - y₁)/(x₂ - x₁) (x - x₁) + y₁
+      //
+      // (x₁, y₁) = (deadband, 0) and (x₂, y₂) = (max, max).
+      // x₁ = deadband
+      // y₁ = 0
+      // x₂ = max
+      // y₂ = max
+      //
+      // y = (max - 0)/(max - deadband) (x - deadband) + 0
+      // y = max/(max - deadband) (x - deadband)
+      // y = max (x - deadband)/(max - deadband)
+      return maxMagnitude * (value - deadband) / (maxMagnitude - deadband);
+    } else {
+      // Map -deadband to 0 and map -max to -max.
+      //
+      // y - y₁ = m(x - x₁)
+      // y - y₁ = (y₂ - y₁)/(x₂ - x₁) (x - x₁)
+      // y = (y₂ - y₁)/(x₂ - x₁) (x - x₁) + y₁
+      //
+      // (x₁, y₁) = (-deadband, 0) and (x₂, y₂) = (-max, -max).
+      // x₁ = -deadband
+      // y₁ = 0
+      // x₂ = -max
+      // y₂ = -max
+      //
+      // y = (-max - 0)/(-max + deadband) (x + deadband) + 0
+      // y = max/(max - deadband) (x + deadband)
+      // y = max (x + deadband)/(max - deadband)
+      return maxMagnitude * (value + deadband) / (maxMagnitude - deadband);
+    }
+  } else {
+    return T{0.0};
+  }
+}
 
 /**
  * Returns modulus of input.
@@ -51,8 +113,8 @@
 WPILIB_DLLEXPORT
 constexpr units::radian_t AngleModulus(units::radian_t angle) {
   return InputModulus<units::radian_t>(angle,
-                                       units::radian_t{-wpi::numbers::pi},
-                                       units::radian_t{wpi::numbers::pi});
+                                       units::radian_t{-std::numbers::pi},
+                                       units::radian_t{std::numbers::pi});
 }
 
 }  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/StateSpaceUtil.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/StateSpaceUtil.h
index 5fdd18c..0345b46 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/StateSpaceUtil.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/StateSpaceUtil.h
@@ -6,15 +6,16 @@
 
 #include <array>
 #include <cmath>
+#include <limits>
 #include <random>
 #include <type_traits>
 
 #include <wpi/SymbolExports.h>
 #include <wpi/deprecated.h>
 
-#include "Eigen/Core"
 #include "Eigen/Eigenvalues"
 #include "Eigen/QR"
+#include "frc/EigenCore.h"
 #include "frc/geometry/Pose2d.h"
 
 namespace frc {
@@ -32,7 +33,11 @@
 
 template <typename Matrix, typename T, typename... Ts>
 void CostMatrixImpl(Matrix& result, T elem, Ts... elems) {
-  result(result.rows() - (sizeof...(Ts) + 1)) = 1.0 / std::pow(elem, 2);
+  if (elem == std::numeric_limits<double>::infinity()) {
+    result(result.rows() - (sizeof...(Ts) + 1)) = 0.0;
+  } else {
+    result(result.rows() - (sizeof...(Ts) + 1)) = 1.0 / std::pow(elem, 2);
+  }
   if constexpr (sizeof...(Ts) > 0) {
     CostMatrixImpl(result, elems...);
   }
@@ -59,9 +64,9 @@
 }
 
 template <int States, int Inputs>
-bool IsStabilizableImpl(const Eigen::Matrix<double, States, States>& A,
-                        const Eigen::Matrix<double, States, Inputs>& B) {
-  Eigen::EigenSolver<Eigen::Matrix<double, States, States>> es{A};
+bool IsStabilizableImpl(const Matrixd<States, States>& A,
+                        const Matrixd<States, Inputs>& B) {
+  Eigen::EigenSolver<Matrixd<States, States>> es{A};
 
   for (int i = 0; i < States; ++i) {
     if (es.eigenvalues()[i].real() * es.eigenvalues()[i].real() +
@@ -89,47 +94,23 @@
 }  // namespace detail
 
 /**
- * Creates a matrix from the given list of elements.
- *
- * The elements of the matrix are filled in in row-major order.
- *
- * @param elems An array of elements in the matrix.
- * @return A matrix containing the given elements.
- * @deprecated Use Eigen::Matrix or Eigen::Vector initializer list constructor.
- */
-template <int Rows, int Cols, typename... Ts,
-          typename =
-              std::enable_if_t<std::conjunction_v<std::is_same<double, Ts>...>>>
-WPI_DEPRECATED(
-    "Use Eigen::Matrix or Eigen::Vector initializer list constructor")
-Eigen::Matrix<double, Rows, Cols> MakeMatrix(Ts... elems) {
-  static_assert(
-      sizeof...(elems) == Rows * Cols,
-      "Number of provided elements doesn't match matrix dimensionality");
-
-  Eigen::Matrix<double, Rows, Cols> result;
-  detail::MatrixImpl<Rows, Cols>(result, elems...);
-  return result;
-}
-
-/**
  * Creates a cost matrix from the given vector for use with LQR.
  *
  * The cost matrix is constructed using Bryson's rule. The inverse square of
- * each element in the input is taken and placed on the cost matrix diagonal.
+ * each tolerance is placed on the cost matrix diagonal. If a tolerance is
+ * infinity, its cost matrix entry is set to zero.
  *
- * @param costs An array. For a Q matrix, its elements are the maximum allowed
- *              excursions of the states from the reference. For an R matrix,
- *              its elements are the maximum allowed excursions of the control
- *              inputs from no actuation.
+ * @param tolerances An array. For a Q matrix, its elements are the maximum
+ *                   allowed excursions of the states from the reference. For an
+ *                   R matrix, its elements are the maximum allowed excursions
+ *                   of the control inputs from no actuation.
  * @return State excursion or control effort cost matrix.
  */
 template <typename... Ts, typename = std::enable_if_t<
                               std::conjunction_v<std::is_same<double, Ts>...>>>
-Eigen::Matrix<double, sizeof...(Ts), sizeof...(Ts)> MakeCostMatrix(
-    Ts... costs) {
+Matrixd<sizeof...(Ts), sizeof...(Ts)> MakeCostMatrix(Ts... tolerances) {
   Eigen::DiagonalMatrix<double, sizeof...(Ts)> result;
-  detail::CostMatrixImpl(result.diagonal(), costs...);
+  detail::CostMatrixImpl(result.diagonal(), tolerances...);
   return result;
 }
 
@@ -147,8 +128,7 @@
  */
 template <typename... Ts, typename = std::enable_if_t<
                               std::conjunction_v<std::is_same<double, Ts>...>>>
-Eigen::Matrix<double, sizeof...(Ts), sizeof...(Ts)> MakeCovMatrix(
-    Ts... stdDevs) {
+Matrixd<sizeof...(Ts), sizeof...(Ts)> MakeCovMatrix(Ts... stdDevs) {
   Eigen::DiagonalMatrix<double, sizeof...(Ts)> result;
   detail::CovMatrixImpl(result.diagonal(), stdDevs...);
   return result;
@@ -167,7 +147,7 @@
  * @return State excursion or control effort cost matrix.
  */
 template <size_t N>
-Eigen::Matrix<double, N, N> MakeCostMatrix(const std::array<double, N>& costs) {
+Matrixd<N, N> MakeCostMatrix(const std::array<double, N>& costs) {
   Eigen::DiagonalMatrix<double, N> result;
   auto& diag = result.diagonal();
   for (size_t i = 0; i < N; ++i) {
@@ -189,8 +169,7 @@
  * @return Process noise or measurement noise covariance matrix.
  */
 template <size_t N>
-Eigen::Matrix<double, N, N> MakeCovMatrix(
-    const std::array<double, N>& stdDevs) {
+Matrixd<N, N> MakeCovMatrix(const std::array<double, N>& stdDevs) {
   Eigen::DiagonalMatrix<double, N> result;
   auto& diag = result.diagonal();
   for (size_t i = 0; i < N; ++i) {
@@ -201,8 +180,8 @@
 
 template <typename... Ts, typename = std::enable_if_t<
                               std::conjunction_v<std::is_same<double, Ts>...>>>
-Eigen::Matrix<double, sizeof...(Ts), 1> MakeWhiteNoiseVector(Ts... stdDevs) {
-  Eigen::Matrix<double, sizeof...(Ts), 1> result;
+Matrixd<sizeof...(Ts), 1> MakeWhiteNoiseVector(Ts... stdDevs) {
+  Matrixd<sizeof...(Ts), 1> result;
   detail::WhiteNoiseVectorImpl(result, stdDevs...);
   return result;
 }
@@ -216,12 +195,11 @@
  * @return White noise vector.
  */
 template <int N>
-Eigen::Vector<double, N> MakeWhiteNoiseVector(
-    const std::array<double, N>& stdDevs) {
+Vectord<N> MakeWhiteNoiseVector(const std::array<double, N>& stdDevs) {
   std::random_device rd;
   std::mt19937 gen{rd()};
 
-  Eigen::Vector<double, N> result;
+  Vectord<N> result;
   for (int i = 0; i < N; ++i) {
     // Passing a standard deviation of 0.0 to std::normal_distribution is
     // undefined behavior
@@ -243,7 +221,7 @@
  * @return The vector.
  */
 WPILIB_DLLEXPORT
-Eigen::Vector<double, 3> PoseTo3dVector(const Pose2d& pose);
+Vectord<3> PoseTo3dVector(const Pose2d& pose);
 
 /**
  * Converts a Pose2d into a vector of [x, y, std::cos(theta), std::sin(theta)].
@@ -253,7 +231,7 @@
  * @return The vector.
  */
 WPILIB_DLLEXPORT
-Eigen::Vector<double, 4> PoseTo4dVector(const Pose2d& pose);
+Vectord<4> PoseTo4dVector(const Pose2d& pose);
 
 /**
  * Returns true if (A, B) is a stabilizable pair.
@@ -268,8 +246,8 @@
  * @param B Input matrix.
  */
 template <int States, int Inputs>
-bool IsStabilizable(const Eigen::Matrix<double, States, States>& A,
-                    const Eigen::Matrix<double, States, Inputs>& B) {
+bool IsStabilizable(const Matrixd<States, States>& A,
+                    const Matrixd<States, Inputs>& B) {
   return detail::IsStabilizableImpl<States, Inputs>(A, B);
 }
 
@@ -286,8 +264,8 @@
  * @param C Output matrix.
  */
 template <int States, int Outputs>
-bool IsDetectable(const Eigen::Matrix<double, States, States>& A,
-                  const Eigen::Matrix<double, Outputs, States>& C) {
+bool IsDetectable(const Matrixd<States, States>& A,
+                  const Matrixd<Outputs, States>& C) {
   return detail::IsStabilizableImpl<States, Outputs>(A.transpose(),
                                                      C.transpose());
 }
@@ -295,14 +273,14 @@
 // Template specializations are used here to make common state-input pairs
 // compile faster.
 template <>
-WPILIB_DLLEXPORT bool IsStabilizable<1, 1>(
-    const Eigen::Matrix<double, 1, 1>& A, const Eigen::Matrix<double, 1, 1>& B);
+WPILIB_DLLEXPORT bool IsStabilizable<1, 1>(const Matrixd<1, 1>& A,
+                                           const Matrixd<1, 1>& B);
 
 // Template specializations are used here to make common state-input pairs
 // compile faster.
 template <>
-WPILIB_DLLEXPORT bool IsStabilizable<2, 1>(
-    const Eigen::Matrix<double, 2, 2>& A, const Eigen::Matrix<double, 2, 1>& B);
+WPILIB_DLLEXPORT bool IsStabilizable<2, 1>(const Matrixd<2, 2>& A,
+                                           const Matrixd<2, 1>& B);
 
 /**
  * Converts a Pose2d into a vector of [x, y, theta].
@@ -312,7 +290,7 @@
  * @return The vector.
  */
 WPILIB_DLLEXPORT
-Eigen::Vector<double, 3> PoseToVector(const Pose2d& pose);
+Vectord<3> PoseToVector(const Pose2d& pose);
 
 /**
  * Clamps input vector between system's minimum and maximum allowable input.
@@ -324,11 +302,10 @@
  * @return Clamped input vector.
  */
 template <int Inputs>
-Eigen::Vector<double, Inputs> ClampInputMaxMagnitude(
-    const Eigen::Vector<double, Inputs>& u,
-    const Eigen::Vector<double, Inputs>& umin,
-    const Eigen::Vector<double, Inputs>& umax) {
-  Eigen::Vector<double, Inputs> result;
+Vectord<Inputs> ClampInputMaxMagnitude(const Vectord<Inputs>& u,
+                                       const Vectord<Inputs>& umin,
+                                       const Vectord<Inputs>& umax) {
+  Vectord<Inputs> result;
   for (int i = 0; i < Inputs; ++i) {
     result(i) = std::clamp(u(i), umin(i), umax(i));
   }
@@ -345,8 +322,8 @@
  * @return The normalizedInput
  */
 template <int Inputs>
-Eigen::Vector<double, Inputs> DesaturateInputVector(
-    const Eigen::Vector<double, Inputs>& u, double maxMagnitude) {
+Vectord<Inputs> DesaturateInputVector(const Vectord<Inputs>& u,
+                                      double maxMagnitude) {
   double maxValue = u.template lpNorm<Eigen::Infinity>();
 
   if (maxValue > maxMagnitude) {
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/ArmFeedforward.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/ArmFeedforward.h
index 1f0e407..5621803 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/ArmFeedforward.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/ArmFeedforward.h
@@ -37,7 +37,7 @@
    * @param kS   The static gain, in volts.
    * @param kG The gravity gain, in volts.
    * @param kV   The velocity gain, in volt seconds per radian.
-   * @param kA   The acceleration gain, in volt seconds^2 per radian.
+   * @param kA   The acceleration gain, in volt seconds² per radian.
    */
   constexpr ArmFeedforward(
       units::volt_t kS, units::volt_t kG, units::unit_t<kv_unit> kV,
@@ -47,9 +47,13 @@
   /**
    * Calculates the feedforward from the gains and setpoints.
    *
-   * @param angle        The angle setpoint, in radians.
+   * @param angle        The angle setpoint, in radians. This angle should be
+   *                     measured from the horizontal (i.e. if the provided
+   *                     angle is 0, the arm should be parallel to the floor).
+   *                     If your encoder does not follow this convention, an
+   *                     offset should be added.
    * @param velocity     The velocity setpoint, in radians per second.
-   * @param acceleration The acceleration setpoint, in radians per second^2.
+   * @param acceleration The acceleration setpoint, in radians per second².
    * @return The computed feedforward, in volts.
    */
   units::volt_t Calculate(units::unit_t<Angle> angle,
@@ -70,8 +74,12 @@
    * achievable - enter the acceleration constraint, and this will give you
    * a simultaneously-achievable velocity constraint.
    *
-   * @param maxVoltage The maximum voltage that can be supplied to the arm.
-   * @param angle The angle of the arm
+   * @param maxVoltage   The maximum voltage that can be supplied to the arm.
+   * @param angle        The angle of the arm. This angle should be measured
+   *                     from the horizontal (i.e. if the provided angle is 0,
+   *                     the arm should be parallel to the floor). If your
+   *                     encoder does not follow this convention, an offset
+   *                     should be added.
    * @param acceleration The acceleration of the arm.
    * @return The maximum possible velocity at the given acceleration and angle.
    */
@@ -91,8 +99,12 @@
    * achievable - enter the acceleration constraint, and this will give you
    * a simultaneously-achievable velocity constraint.
    *
-   * @param maxVoltage The maximum voltage that can be supplied to the arm.
-   * @param angle The angle of the arm
+   * @param maxVoltage   The maximum voltage that can be supplied to the arm.
+   * @param angle        The angle of the arm. This angle should be measured
+   *                     from the horizontal (i.e. if the provided angle is 0,
+   *                     the arm should be parallel to the floor). If your
+   *                     encoder does not follow this convention, an offset
+   *                     should be added.
    * @param acceleration The acceleration of the arm.
    * @return The minimum possible velocity at the given acceleration and angle.
    */
@@ -113,8 +125,12 @@
    * a simultaneously-achievable acceleration constraint.
    *
    * @param maxVoltage The maximum voltage that can be supplied to the arm.
-   * @param angle The angle of the arm
-   * @param velocity The velocity of the arm.
+   * @param angle      The angle of the arm. This angle should be measured
+   *                   from the horizontal (i.e. if the provided angle is 0,
+   *                   the arm should be parallel to the floor). If your
+   *                   encoder does not follow this convention, an offset
+   *                   should be added.
+   * @param velocity   The velocity of the arm.
    * @return The maximum possible acceleration at the given velocity and angle.
    */
   units::unit_t<Acceleration> MaxAchievableAcceleration(
@@ -133,8 +149,12 @@
    * a simultaneously-achievable acceleration constraint.
    *
    * @param maxVoltage The maximum voltage that can be supplied to the arm.
-   * @param angle The angle of the arm
-   * @param velocity The velocity of the arm.
+   * @param angle      The angle of the arm. This angle should be measured
+   *                   from the horizontal (i.e. if the provided angle is 0,
+   *                   the arm should be parallel to the floor). If your
+   *                   encoder does not follow this convention, an offset
+   *                   should be added.
+   * @param velocity   The velocity of the arm.
    * @return The minimum possible acceleration at the given velocity and angle.
    */
   units::unit_t<Acceleration> MinAchievableAcceleration(
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/ControlAffinePlantInversionFeedforward.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/ControlAffinePlantInversionFeedforward.h
index 656f767..21aad25 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/ControlAffinePlantInversionFeedforward.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/ControlAffinePlantInversionFeedforward.h
@@ -7,8 +7,8 @@
 #include <array>
 #include <functional>
 
-#include "Eigen/Core"
 #include "Eigen/QR"
+#include "frc/EigenCore.h"
 #include "frc/system/NumericalJacobian.h"
 #include "units/time.h"
 
@@ -39,6 +39,9 @@
 template <int States, int Inputs>
 class ControlAffinePlantInversionFeedforward {
  public:
+  using StateVector = Vectord<States>;
+  using InputVector = Vectord<Inputs>;
+
   /**
    * Constructs a feedforward with given model dynamics as a function
    * of state and input.
@@ -50,15 +53,11 @@
    * @param dt The timestep between calls of calculate().
    */
   ControlAffinePlantInversionFeedforward(
-      std::function<
-          Eigen::Vector<double, States>(const Eigen::Vector<double, States>&,
-                                        const Eigen::Vector<double, Inputs>&)>
-          f,
+      std::function<StateVector(const StateVector&, const InputVector&)> f,
       units::second_t dt)
       : m_dt(dt), m_f(f) {
-    m_B = NumericalJacobianU<States, States, Inputs>(
-        f, Eigen::Vector<double, States>::Zero(),
-        Eigen::Vector<double, Inputs>::Zero());
+    m_B = NumericalJacobianU<States, States, Inputs>(f, StateVector::Zero(),
+                                                     InputVector::Zero());
 
     Reset();
   }
@@ -73,14 +72,12 @@
    * @param dt The timestep between calls of calculate().
    */
   ControlAffinePlantInversionFeedforward(
-      std::function<
-          Eigen::Vector<double, States>(const Eigen::Vector<double, States>&)>
-          f,
-      const Eigen::Matrix<double, States, Inputs>& B, units::second_t dt)
+      std::function<StateVector(const StateVector&)> f,
+      const Matrixd<States, Inputs>& B, units::second_t dt)
       : m_B(B), m_dt(dt) {
-    m_f = [=](const Eigen::Vector<double, States>& x,
-              const Eigen::Vector<double, Inputs>& u)
-        -> Eigen::Vector<double, States> { return f(x); };
+    m_f = [=](const StateVector& x, const InputVector& u) -> StateVector {
+      return f(x);
+    };
 
     Reset();
   }
@@ -95,7 +92,7 @@
    *
    * @return The calculated feedforward.
    */
-  const Eigen::Vector<double, Inputs>& Uff() const { return m_uff; }
+  const InputVector& Uff() const { return m_uff; }
 
   /**
    * Returns an element of the previously calculated feedforward.
@@ -104,14 +101,14 @@
    *
    * @return The row of the calculated feedforward.
    */
-  double Uff(int i) const { return m_uff(i, 0); }
+  double Uff(int i) const { return m_uff(i); }
 
   /**
    * Returns the current reference vector r.
    *
    * @return The current reference vector.
    */
-  const Eigen::Vector<double, States>& R() const { return m_r; }
+  const StateVector& R() const { return m_r; }
 
   /**
    * Returns an element of the reference vector r.
@@ -120,14 +117,14 @@
    *
    * @return The row of the current reference vector.
    */
-  double R(int i) const { return m_r(i, 0); }
+  double R(int i) const { return m_r(i); }
 
   /**
    * Resets the feedforward with a specified initial state vector.
    *
    * @param initialState The initial state vector.
    */
-  void Reset(const Eigen::Vector<double, States>& initialState) {
+  void Reset(const StateVector& initialState) {
     m_r = initialState;
     m_uff.setZero();
   }
@@ -146,15 +143,14 @@
    * reference.
    *
    * If this method is used the initial state of the system is the one set using
-   * Reset(const Eigen::Vector<double, States>&). If the initial state is not
+   * Reset(const StateVector&). If the initial state is not
    * set it defaults to a zero vector.
    *
    * @param nextR The reference state of the future timestep (k + dt).
    *
    * @return The calculated feedforward.
    */
-  Eigen::Vector<double, Inputs> Calculate(
-      const Eigen::Vector<double, States>& nextR) {
+  InputVector Calculate(const StateVector& nextR) {
     return Calculate(m_r, nextR);
   }
 
@@ -166,36 +162,30 @@
    *
    * @return The calculated feedforward.
    */
-  Eigen::Vector<double, Inputs> Calculate(
-      const Eigen::Vector<double, States>& r,
-      const Eigen::Vector<double, States>& nextR) {
-    Eigen::Vector<double, States> rDot = (nextR - r) / m_dt.value();
+  InputVector Calculate(const StateVector& r, const StateVector& nextR) {
+    StateVector rDot = (nextR - r) / m_dt.value();
 
-    m_uff = m_B.householderQr().solve(
-        rDot - m_f(r, Eigen::Vector<double, Inputs>::Zero()));
+    m_uff = m_B.householderQr().solve(rDot - m_f(r, InputVector::Zero()));
 
     m_r = nextR;
     return m_uff;
   }
 
  private:
-  Eigen::Matrix<double, States, Inputs> m_B;
+  Matrixd<States, Inputs> m_B;
 
   units::second_t m_dt;
 
   /**
    * The model dynamics.
    */
-  std::function<Eigen::Vector<double, States>(
-      const Eigen::Vector<double, States>&,
-      const Eigen::Vector<double, Inputs>&)>
-      m_f;
+  std::function<StateVector(const StateVector&, const InputVector&)> m_f;
 
   // Current reference
-  Eigen::Vector<double, States> m_r;
+  StateVector m_r;
 
   // Computed feedforward
-  Eigen::Vector<double, Inputs> m_uff;
+  InputVector m_uff;
 };
 
 }  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/DifferentialDriveAccelerationLimiter.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/DifferentialDriveAccelerationLimiter.h
new file mode 100644
index 0000000..3a5148a
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/DifferentialDriveAccelerationLimiter.h
@@ -0,0 +1,83 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <wpi/SymbolExports.h>
+
+#include "Eigen/Core"
+#include "frc/controller/DifferentialDriveWheelVoltages.h"
+#include "frc/system/LinearSystem.h"
+#include "units/acceleration.h"
+#include "units/angular_acceleration.h"
+#include "units/length.h"
+#include "units/velocity.h"
+#include "units/voltage.h"
+
+namespace frc {
+
+/**
+ * Filters the provided voltages to limit a differential drive's linear and
+ * angular acceleration.
+ *
+ * The differential drive model can be created via the functions in
+ * LinearSystemId.
+ */
+class WPILIB_DLLEXPORT DifferentialDriveAccelerationLimiter {
+ public:
+  /**
+   * Constructs a DifferentialDriveAccelerationLimiter.
+   *
+   * @param system The differential drive dynamics.
+   * @param trackwidth The distance between the differential drive's left and
+   *                   right wheels.
+   * @param maxLinearAccel The maximum linear acceleration.
+   * @param maxAngularAccel The maximum angular acceleration.
+   */
+  DifferentialDriveAccelerationLimiter(
+      LinearSystem<2, 2, 2> system, units::meter_t trackwidth,
+      units::meters_per_second_squared_t maxLinearAccel,
+      units::radians_per_second_squared_t maxAngularAccel);
+
+  /**
+   * Constructs a DifferentialDriveAccelerationLimiter.
+   *
+   * @param system The differential drive dynamics.
+   * @param trackwidth The distance between the differential drive's left and
+   *                   right wheels.
+   * @param minLinearAccel The minimum (most negative) linear acceleration.
+   * @param maxLinearAccel The maximum (most positive) linear acceleration.
+   * @param maxAngularAccel The maximum angular acceleration.
+   * @throws std::invalid_argument if minimum linear acceleration is greater
+   * than maximum linear acceleration
+   */
+  DifferentialDriveAccelerationLimiter(
+      LinearSystem<2, 2, 2> system, units::meter_t trackwidth,
+      units::meters_per_second_squared_t minLinearAccel,
+      units::meters_per_second_squared_t maxLinearAccel,
+      units::radians_per_second_squared_t maxAngularAccel);
+
+  /**
+   * Returns the next voltage pair subject to acceleraiton constraints.
+   *
+   * @param leftVelocity The left wheel velocity.
+   * @param rightVelocity The right wheel velocity.
+   * @param leftVoltage The unconstrained left motor voltage.
+   * @param rightVoltage The unconstrained right motor voltage.
+   * @return The constrained wheel voltages.
+   */
+  DifferentialDriveWheelVoltages Calculate(
+      units::meters_per_second_t leftVelocity,
+      units::meters_per_second_t rightVelocity, units::volt_t leftVoltage,
+      units::volt_t rightVoltage);
+
+ private:
+  LinearSystem<2, 2, 2> m_system;
+  units::meter_t m_trackwidth;
+  units::meters_per_second_squared_t m_minLinearAccel;
+  units::meters_per_second_squared_t m_maxLinearAccel;
+  units::radians_per_second_squared_t m_maxAngularAccel;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/DifferentialDriveFeedforward.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/DifferentialDriveFeedforward.h
new file mode 100644
index 0000000..716bc78
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/DifferentialDriveFeedforward.h
@@ -0,0 +1,83 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <wpi/SymbolExports.h>
+
+#include "frc/controller/DifferentialDriveWheelVoltages.h"
+#include "frc/system/LinearSystem.h"
+#include "units/acceleration.h"
+#include "units/angular_acceleration.h"
+#include "units/angular_velocity.h"
+#include "units/length.h"
+#include "units/time.h"
+#include "units/velocity.h"
+#include "units/voltage.h"
+
+namespace frc {
+/**
+ * A helper class which computes the feedforward outputs for a differential
+ * drive drivetrain.
+ */
+class WPILIB_DLLEXPORT DifferentialDriveFeedforward {
+  frc::LinearSystem<2, 2, 2> m_plant;
+
+ public:
+  /**
+   * Creates a new DifferentialDriveFeedforward with the specified parameters.
+   *
+   * @param kVLinear The linear velocity gain in volts per (meters per second).
+   * @param kALinear The linear acceleration gain in volts per (meters per
+   * second squared).
+   * @param kVAngular The angular velocity gain in volts per (radians per
+   * second).
+   * @param kAAngular The angular acceleration gain in volts per (radians per
+   * second squared).
+   * @param trackwidth The distance between the differential drive's left and
+   * right wheels, in meters.
+   */
+  DifferentialDriveFeedforward(decltype(1_V / 1_mps) kVLinear,
+                               decltype(1_V / 1_mps_sq) kALinear,
+                               decltype(1_V / 1_rad_per_s) kVAngular,
+                               decltype(1_V / 1_rad_per_s_sq) kAAngular,
+                               units::meter_t trackwidth);
+
+  /**
+   * Creates a new DifferentialDriveFeedforward with the specified parameters.
+   *
+   * @param kVLinear The linear velocity gain in volts per (meters per second).
+   * @param kALinear The linear acceleration gain in volts per (meters per
+   * second squared).
+   * @param kVAngular The angular velocity gain in volts per (meters per
+   * second).
+   * @param kAAngular The angular acceleration gain in volts per (meters per
+   * second squared).
+   */
+  DifferentialDriveFeedforward(decltype(1_V / 1_mps) kVLinear,
+                               decltype(1_V / 1_mps_sq) kALinear,
+                               decltype(1_V / 1_mps) kVAngular,
+                               decltype(1_V / 1_mps_sq) kAAngular);
+
+  /**
+   * Calculates the differential drive feedforward inputs given velocity
+   * setpoints.
+   *
+   * @param currentLeftVelocity The current left velocity of the differential
+   * drive in meters/second.
+   * @param nextLeftVelocity The next left velocity of the differential drive in
+   * meters/second.
+   * @param currentRightVelocity The current right velocity of the differential
+   * drive in meters/second.
+   * @param nextRightVelocity The next right velocity of the differential drive
+   * in meters/second.
+   * @param dt Discretization timestep.
+   */
+  DifferentialDriveWheelVoltages Calculate(
+      units::meters_per_second_t currentLeftVelocity,
+      units::meters_per_second_t nextLeftVelocity,
+      units::meters_per_second_t currentRightVelocity,
+      units::meters_per_second_t nextRightVelocity, units::second_t dt);
+};
+}  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/DifferentialDriveWheelVoltages.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/DifferentialDriveWheelVoltages.h
new file mode 100644
index 0000000..48f341e
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/DifferentialDriveWheelVoltages.h
@@ -0,0 +1,19 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include "units/voltage.h"
+
+namespace frc {
+
+/**
+ * Motor voltages for a differential drive.
+ */
+struct DifferentialDriveWheelVoltages {
+  units::volt_t left = 0_V;
+  units::volt_t right = 0_V;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/ElevatorFeedforward.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/ElevatorFeedforward.h
index 269a7e6..bbe7720 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/ElevatorFeedforward.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/ElevatorFeedforward.h
@@ -6,6 +6,7 @@
 
 #include <wpi/MathExtras.h>
 
+#include "units/length.h"
 #include "units/time.h"
 #include "units/voltage.h"
 
@@ -14,9 +15,9 @@
  * A helper class that computes feedforward outputs for a simple elevator
  * (modeled as a motor acting against the force of gravity).
  */
-template <class Distance>
 class ElevatorFeedforward {
  public:
+  using Distance = units::meters;
   using Velocity =
       units::compound_unit<Distance, units::inverse<units::seconds>>;
   using Acceleration =
@@ -33,7 +34,7 @@
    * @param kS The static gain, in volts.
    * @param kG The gravity gain, in volts.
    * @param kV The velocity gain, in volt seconds per distance.
-   * @param kA The acceleration gain, in volt seconds^2 per distance.
+   * @param kA The acceleration gain, in volt seconds² per distance.
    */
   constexpr ElevatorFeedforward(
       units::volt_t kS, units::volt_t kG, units::unit_t<kv_unit> kV,
@@ -44,7 +45,7 @@
    * Calculates the feedforward from the gains and setpoints.
    *
    * @param velocity     The velocity setpoint, in distance per second.
-   * @param acceleration The acceleration setpoint, in distance per second^2.
+   * @param acceleration The acceleration setpoint, in distance per second².
    * @return The computed feedforward, in volts.
    */
   constexpr units::volt_t Calculate(units::unit_t<Velocity> velocity,
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/HolonomicDriveController.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/HolonomicDriveController.h
index 398a872..9a749c6 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/HolonomicDriveController.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/HolonomicDriveController.h
@@ -45,6 +45,12 @@
       frc2::PIDController xController, frc2::PIDController yController,
       ProfiledPIDController<units::radian> thetaController);
 
+  HolonomicDriveController(const HolonomicDriveController&) = default;
+  HolonomicDriveController& operator=(const HolonomicDriveController&) =
+      default;
+  HolonomicDriveController(HolonomicDriveController&&) = default;
+  HolonomicDriveController& operator=(HolonomicDriveController&&) = default;
+
   /**
    * Returns true if the pose error is within tolerance of the reference.
    */
@@ -61,32 +67,32 @@
   /**
    * Returns the next output of the holonomic drive controller.
    *
-   * The reference pose, linear velocity, and angular velocity should come from
-   * a drivetrain trajectory.
-   *
-   * @param currentPose        The current pose.
-   * @param poseRef            The desired pose.
-   * @param linearVelocityRef  The desired linear velocity.
-   * @param angleRef           The desired ending angle.
+   * @param currentPose The current pose, as measured by odometry or pose
+   * estimator.
+   * @param trajectoryPose The desired trajectory pose, as sampled for the
+   * current timestep.
+   * @param desiredLinearVelocity The desired linear velocity.
+   * @param desiredHeading The desired heading.
+   * @return The next output of the holonomic drive controller.
    */
-  ChassisSpeeds Calculate(const Pose2d& currentPose, const Pose2d& poseRef,
-                          units::meters_per_second_t linearVelocityRef,
-                          const Rotation2d& angleRef);
+  ChassisSpeeds Calculate(const Pose2d& currentPose,
+                          const Pose2d& trajectoryPose,
+                          units::meters_per_second_t desiredLinearVelocity,
+                          const Rotation2d& desiredHeading);
 
   /**
    * Returns the next output of the holonomic drive controller.
    *
-   * The reference pose, linear velocity, and angular velocity should come from
-   * a drivetrain trajectory.
-   *
-   * @param currentPose  The current pose.
-   * @param desiredState The desired pose, linear velocity, and angular velocity
-   *                     from a trajectory.
-   * @param angleRef     The desired ending angle.
+   * @param currentPose The current pose, as measured by odometry or pose
+   * estimator.
+   * @param desiredState The desired trajectory pose, as sampled for the current
+   * timestep.
+   * @param desiredHeading The desired heading.
+   * @return The next output of the holonomic drive controller.
    */
   ChassisSpeeds Calculate(const Pose2d& currentPose,
                           const Trajectory::State& desiredState,
-                          const Rotation2d& angleRef);
+                          const Rotation2d& desiredHeading);
 
   /**
    * Enables and disables the controller for troubleshooting purposes. When
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/ImplicitModelFollower.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/ImplicitModelFollower.h
new file mode 100644
index 0000000..eef1fc0
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/ImplicitModelFollower.h
@@ -0,0 +1,123 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <frc/system/LinearSystem.h>
+
+#include "Eigen/QR"
+#include "frc/EigenCore.h"
+#include "units/time.h"
+
+namespace frc {
+
+/**
+ * Contains the controller coefficients and logic for an implicit model
+ * follower.
+ *
+ * Implicit model following lets us design a feedback controller that erases the
+ * dynamics of our system and makes it behave like some other system. This can
+ * be used to make a drivetrain more controllable during teleop driving by
+ * making it behave like a slower or more benign drivetrain.
+ *
+ * For more on the underlying math, read appendix B.3 in
+ * https://file.tavsys.net/control/controls-engineering-in-frc.pdf.
+ */
+template <int States, int Inputs>
+class ImplicitModelFollower {
+ public:
+  using StateVector = Vectord<States>;
+  using InputVector = Vectord<Inputs>;
+
+  /**
+   * Constructs a controller with the given coefficients and plant.
+   *
+   * @param plant    The plant being controlled.
+   * @param plantRef The plant whose dynamics should be followed.
+   */
+  template <int Outputs>
+  ImplicitModelFollower(const LinearSystem<States, Inputs, Outputs>& plant,
+                        const LinearSystem<States, Inputs, Outputs>& plantRef)
+      : ImplicitModelFollower<States, Inputs>(plant.A(), plant.B(),
+                                              plantRef.A(), plantRef.B()) {}
+
+  /**
+   * Constructs a controller with the given coefficients and plant.
+   *
+   * @param A    Continuous system matrix of the plant being controlled.
+   * @param B    Continuous input matrix of the plant being controlled.
+   * @param Aref Continuous system matrix whose dynamics should be followed.
+   * @param Bref Continuous input matrix whose dynamics should be followed.
+   */
+  ImplicitModelFollower(const Matrixd<States, States>& A,
+                        const Matrixd<States, Inputs>& B,
+                        const Matrixd<States, States>& Aref,
+                        const Matrixd<States, Inputs>& Bref) {
+    // Find u_imf that makes real model match reference model.
+    //
+    // dx/dt = Ax + Bu_imf
+    // dz/dt = A_ref z + B_ref u
+    //
+    // Let x = z.
+    //
+    // dx/dt = dz/dt
+    // Ax + Bu_imf = Aref x + B_ref u
+    // Bu_imf = A_ref x - Ax + B_ref u
+    // Bu_imf = (A_ref - A)x + B_ref u
+    // u_imf = B⁻¹((A_ref - A)x + Bref u)
+    // u_imf = -B⁻¹(A - A_ref)x + B⁻¹B_ref u
+
+    // The first term makes the open-loop poles that of the reference
+    // system, and the second term makes the input behave like that of the
+    // reference system.
+    m_A = -B.householderQr().solve(A - Aref);
+    m_B = B.householderQr().solve(Bref);
+
+    Reset();
+  }
+
+  /**
+   * Returns the control input vector u.
+   *
+   * @return The control input.
+   */
+  const InputVector& U() const { return m_u; }
+
+  /**
+   * Returns an element of the control input vector u.
+   *
+   * @param i Row of u.
+   *
+   * @return The row of the control input vector.
+   */
+  double U(int i) const { return m_u(i); }
+
+  /**
+   * Resets the controller.
+   */
+  void Reset() { m_u.setZero(); }
+
+  /**
+   * Returns the next output of the controller.
+   *
+   * @param x The current state x.
+   * @param u The current input for the original model.
+   */
+  InputVector Calculate(const StateVector& x, const InputVector& u) {
+    m_u = m_A * x + m_B * u;
+    return m_u;
+  }
+
+ private:
+  // Computed controller output
+  InputVector m_u;
+
+  // State space conversion gain
+  Matrixd<Inputs, States> m_A;
+
+  // Input space conversion gain
+  Matrixd<Inputs, Inputs> m_B;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/LTVDifferentialDriveController.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/LTVDifferentialDriveController.h
new file mode 100644
index 0000000..0a336aa
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/LTVDifferentialDriveController.h
@@ -0,0 +1,125 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <wpi/SymbolExports.h>
+#include <wpi/array.h>
+#include <wpi/interpolating_map.h>
+
+#include "frc/EigenCore.h"
+#include "frc/controller/DifferentialDriveWheelVoltages.h"
+#include "frc/geometry/Pose2d.h"
+#include "frc/system/LinearSystem.h"
+#include "frc/trajectory/Trajectory.h"
+#include "units/length.h"
+#include "units/time.h"
+#include "units/velocity.h"
+#include "units/voltage.h"
+
+namespace frc {
+
+/**
+ * The linear time-varying differential drive controller has a similar form to
+ * the LQR, but the model used to compute the controller gain is the nonlinear
+ * model linearized around the drivetrain's current state. We precomputed gains
+ * for important places in our state-space, then interpolated between them with
+ * a LUT to save computational resources.
+ *
+ * See section 8.7 in Controls Engineering in FRC for a derivation of the
+ * control law we used shown in theorem 8.7.4.
+ */
+class WPILIB_DLLEXPORT LTVDifferentialDriveController {
+ public:
+  /**
+   * Constructs a linear time-varying differential drive controller.
+   *
+   * @param plant      The differential drive velocity plant.
+   * @param trackwidth The distance between the differential drive's left and
+   *                   right wheels.
+   * @param Qelems     The maximum desired error tolerance for each state.
+   * @param Relems     The maximum desired control effort for each input.
+   * @param dt         Discretization timestep.
+   */
+  LTVDifferentialDriveController(const frc::LinearSystem<2, 2, 2>& plant,
+                                 units::meter_t trackwidth,
+                                 const wpi::array<double, 5>& Qelems,
+                                 const wpi::array<double, 2>& Relems,
+                                 units::second_t dt);
+
+  /**
+   * Move constructor.
+   */
+  LTVDifferentialDriveController(LTVDifferentialDriveController&&) = default;
+
+  /**
+   * Move assignment operator.
+   */
+  LTVDifferentialDriveController& operator=(LTVDifferentialDriveController&&) =
+      default;
+
+  /**
+   * Returns true if the pose error is within tolerance of the reference.
+   */
+  bool AtReference() const;
+
+  /**
+   * Sets the pose error which is considered tolerable for use with
+   * AtReference().
+   *
+   * @param poseTolerance Pose error which is tolerable.
+   * @param leftVelocityTolerance Left velocity error which is tolerable.
+   * @param rightVelocityTolerance Right velocity error which is tolerable.
+   */
+  void SetTolerance(const Pose2d& poseTolerance,
+                    units::meters_per_second_t leftVelocityTolerance,
+                    units::meters_per_second_t rightVelocityTolerance);
+
+  /**
+   * Returns the left and right output voltages of the LTV controller.
+   *
+   * The reference pose, linear velocity, and angular velocity should come from
+   * a drivetrain trajectory.
+   *
+   * @param currentPose      The current pose.
+   * @param leftVelocity     The current left velocity.
+   * @param rightVelocity    The current right velocity.
+   * @param poseRef          The desired pose.
+   * @param leftVelocityRef  The desired left velocity.
+   * @param rightVelocityRef The desired right velocity.
+   */
+  DifferentialDriveWheelVoltages Calculate(
+      const Pose2d& currentPose, units::meters_per_second_t leftVelocity,
+      units::meters_per_second_t rightVelocity, const Pose2d& poseRef,
+      units::meters_per_second_t leftVelocityRef,
+      units::meters_per_second_t rightVelocityRef);
+
+  /**
+   * Returns the left and right output voltages of the LTV controller.
+   *
+   * The reference pose, linear velocity, and angular velocity should come from
+   * a drivetrain trajectory.
+   *
+   * @param currentPose  The current pose.
+   * @param leftVelocity The left velocity.
+   * @param rightVelocity The right velocity.
+   * @param desiredState The desired pose, linear velocity, and angular velocity
+   *                     from a trajectory.
+   */
+  DifferentialDriveWheelVoltages Calculate(
+      const Pose2d& currentPose, units::meters_per_second_t leftVelocity,
+      units::meters_per_second_t rightVelocity,
+      const Trajectory::State& desiredState);
+
+ private:
+  units::meter_t m_trackwidth;
+
+  // LUT from drivetrain linear velocity to LQR gain
+  wpi::interpolating_map<units::meters_per_second_t, Matrixd<2, 5>> m_table;
+
+  Vectord<5> m_error;
+  Vectord<5> m_tolerance;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/LTVUnicycleController.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/LTVUnicycleController.h
new file mode 100644
index 0000000..83cfe4b
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/LTVUnicycleController.h
@@ -0,0 +1,123 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <wpi/SymbolExports.h>
+#include <wpi/array.h>
+#include <wpi/interpolating_map.h>
+
+#include "frc/EigenCore.h"
+#include "frc/geometry/Pose2d.h"
+#include "frc/kinematics/DifferentialDriveKinematics.h"
+#include "frc/trajectory/Trajectory.h"
+#include "units/angular_velocity.h"
+#include "units/time.h"
+#include "units/velocity.h"
+
+namespace frc {
+
+/**
+ * The linear time-varying unicycle controller has a similar form to the LQR,
+ * but the model used to compute the controller gain is the nonlinear model
+ * linearized around the drivetrain's current state.
+ *
+ * See section 8.9 in Controls Engineering in FRC for a derivation of the
+ * control law we used shown in theorem 8.9.1.
+ */
+class WPILIB_DLLEXPORT LTVUnicycleController {
+ public:
+  /**
+   * Constructs a linear time-varying unicycle controller with default maximum
+   * desired error tolerances of (0.0625 m, 0.125 m, 2 rad) and default maximum
+   * desired control effort of (1 m/s, 2 rad/s).
+   *
+   * @param dt Discretization timestep.
+   * @param maxVelocity The maximum velocity for the controller gain lookup
+   *                    table.
+   */
+  explicit LTVUnicycleController(
+      units::second_t dt, units::meters_per_second_t maxVelocity = 9_mps);
+
+  /**
+   * Constructs a linear time-varying unicycle controller.
+   *
+   * @param Qelems The maximum desired error tolerance for each state.
+   * @param Relems The maximum desired control effort for each input.
+   * @param dt     Discretization timestep.
+   * @param maxVelocity The maximum velocity for the controller gain lookup
+   *                    table.
+   */
+  LTVUnicycleController(const wpi::array<double, 3>& Qelems,
+                        const wpi::array<double, 2>& Relems, units::second_t dt,
+                        units::meters_per_second_t maxVelocity = 9_mps);
+
+  /**
+   * Move constructor.
+   */
+  LTVUnicycleController(LTVUnicycleController&&) = default;
+
+  /**
+   * Move assignment operator.
+   */
+  LTVUnicycleController& operator=(LTVUnicycleController&&) = default;
+
+  /**
+   * Returns true if the pose error is within tolerance of the reference.
+   */
+  bool AtReference() const;
+
+  /**
+   * Sets the pose error which is considered tolerable for use with
+   * AtReference().
+   *
+   * @param poseTolerance Pose error which is tolerable.
+   */
+  void SetTolerance(const Pose2d& poseTolerance);
+
+  /**
+   * Returns the linear and angular velocity outputs of the LTV controller.
+   *
+   * The reference pose, linear velocity, and angular velocity should come from
+   * a drivetrain trajectory.
+   *
+   * @param currentPose        The current pose.
+   * @param poseRef            The desired pose.
+   * @param linearVelocityRef  The desired linear velocity.
+   * @param angularVelocityRef The desired angular velocity.
+   */
+  ChassisSpeeds Calculate(const Pose2d& currentPose, const Pose2d& poseRef,
+                          units::meters_per_second_t linearVelocityRef,
+                          units::radians_per_second_t angularVelocityRef);
+
+  /**
+   * Returns the linear and angular velocity outputs of the LTV controller.
+   *
+   * The reference pose, linear velocity, and angular velocity should come from
+   * a drivetrain trajectory.
+   *
+   * @param currentPose  The current pose.
+   * @param desiredState The desired pose, linear velocity, and angular velocity
+   *                     from a trajectory.
+   */
+  ChassisSpeeds Calculate(const Pose2d& currentPose,
+                          const Trajectory::State& desiredState);
+
+  /**
+   * Enables and disables the controller for troubleshooting purposes.
+   *
+   * @param enabled If the controller is enabled or not.
+   */
+  void SetEnabled(bool enabled);
+
+ private:
+  // LUT from drivetrain linear velocity to LQR gain
+  wpi::interpolating_map<units::meters_per_second_t, Matrixd<2, 3>> m_table;
+
+  Pose2d m_poseError;
+  Pose2d m_poseTolerance;
+  bool m_enabled = true;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/LinearPlantInversionFeedforward.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/LinearPlantInversionFeedforward.h
index 519368d..d4cc3c4 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/LinearPlantInversionFeedforward.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/LinearPlantInversionFeedforward.h
@@ -7,8 +7,8 @@
 #include <array>
 #include <functional>
 
-#include "Eigen/Core"
 #include "Eigen/QR"
+#include "frc/EigenCore.h"
 #include "frc/system/Discretization.h"
 #include "frc/system/LinearSystem.h"
 #include "units/time.h"
@@ -31,6 +31,9 @@
 template <int States, int Inputs>
 class LinearPlantInversionFeedforward {
  public:
+  using StateVector = Vectord<States>;
+  using InputVector = Vectord<Inputs>;
+
   /**
    * Constructs a feedforward with the given plant.
    *
@@ -50,9 +53,9 @@
    * @param B  Continuous input matrix of the plant being controlled.
    * @param dt Discretization timestep.
    */
-  LinearPlantInversionFeedforward(
-      const Eigen::Matrix<double, States, States>& A,
-      const Eigen::Matrix<double, States, Inputs>& B, units::second_t dt)
+  LinearPlantInversionFeedforward(const Matrixd<States, States>& A,
+                                  const Matrixd<States, Inputs>& B,
+                                  units::second_t dt)
       : m_dt(dt) {
     DiscretizeAB<States, Inputs>(A, B, dt, &m_A, &m_B);
     Reset();
@@ -63,7 +66,7 @@
    *
    * @return The calculated feedforward.
    */
-  const Eigen::Vector<double, Inputs>& Uff() const { return m_uff; }
+  const InputVector& Uff() const { return m_uff; }
 
   /**
    * Returns an element of the previously calculated feedforward.
@@ -72,14 +75,14 @@
    *
    * @return The row of the calculated feedforward.
    */
-  double Uff(int i) const { return m_uff(i, 0); }
+  double Uff(int i) const { return m_uff(i); }
 
   /**
    * Returns the current reference vector r.
    *
    * @return The current reference vector.
    */
-  const Eigen::Vector<double, States>& R() const { return m_r; }
+  const StateVector& R() const { return m_r; }
 
   /**
    * Returns an element of the reference vector r.
@@ -88,14 +91,14 @@
    *
    * @return The row of the current reference vector.
    */
-  double R(int i) const { return m_r(i, 0); }
+  double R(int i) const { return m_r(i); }
 
   /**
    * Resets the feedforward with a specified initial state vector.
    *
    * @param initialState The initial state vector.
    */
-  void Reset(const Eigen::Vector<double, States>& initialState) {
+  void Reset(const StateVector& initialState) {
     m_r = initialState;
     m_uff.setZero();
   }
@@ -114,16 +117,15 @@
    * reference.
    *
    * If this method is used the initial state of the system is the one set using
-   * Reset(const Eigen::Vector<double, States>&). If the initial state is not
+   * Reset(const StateVector&). If the initial state is not
    * set it defaults to a zero vector.
    *
    * @param nextR The reference state of the future timestep (k + dt).
    *
    * @return The calculated feedforward.
    */
-  Eigen::Vector<double, Inputs> Calculate(
-      const Eigen::Vector<double, States>& nextR) {
-    return Calculate(m_r, nextR);  // NOLINT
+  InputVector Calculate(const StateVector& nextR) {
+    return Calculate(m_r, nextR);
   }
 
   /**
@@ -134,25 +136,23 @@
    *
    * @return The calculated feedforward.
    */
-  Eigen::Vector<double, Inputs> Calculate(
-      const Eigen::Vector<double, States>& r,
-      const Eigen::Vector<double, States>& nextR) {
+  InputVector Calculate(const StateVector& r, const StateVector& nextR) {
     m_uff = m_B.householderQr().solve(nextR - (m_A * r));
     m_r = nextR;
     return m_uff;
   }
 
  private:
-  Eigen::Matrix<double, States, States> m_A;
-  Eigen::Matrix<double, States, Inputs> m_B;
+  Matrixd<States, States> m_A;
+  Matrixd<States, Inputs> m_B;
 
   units::second_t m_dt;
 
   // Current reference
-  Eigen::Vector<double, States> m_r;
+  StateVector m_r;
 
   // Computed feedforward
-  Eigen::Vector<double, Inputs> m_uff;
+  InputVector m_uff;
 };
 
 }  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/LinearQuadraticRegulator.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/LinearQuadraticRegulator.h
index 44a8501..50d6566 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/LinearQuadraticRegulator.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/LinearQuadraticRegulator.h
@@ -4,26 +4,14 @@
 
 #pragma once
 
-#include <frc/fmt/Eigen.h>
-
-#include <string>
-
 #include <wpi/SymbolExports.h>
 #include <wpi/array.h>
 
-#include "Eigen/Cholesky"
-#include "Eigen/Core"
-#include "Eigen/Eigenvalues"
-#include "drake/math/discrete_algebraic_riccati_equation.h"
-#include "frc/StateSpaceUtil.h"
-#include "frc/system/Discretization.h"
+#include "frc/EigenCore.h"
 #include "frc/system/LinearSystem.h"
 #include "units/time.h"
-#include "unsupported/Eigen/MatrixFunctions"
-#include "wpimath/MathShared.h"
 
 namespace frc {
-namespace detail {
 
 /**
  * Contains the controller coefficients and logic for a linear-quadratic
@@ -37,8 +25,14 @@
  * @tparam Inputs Number of inputs.
  */
 template <int States, int Inputs>
-class LinearQuadraticRegulatorImpl {
+class LinearQuadraticRegulator {
  public:
+  using StateVector = Vectord<States>;
+  using InputVector = Vectord<Inputs>;
+
+  using StateArray = wpi::array<double, States>;
+  using InputArray = wpi::array<double, Inputs>;
+
   /**
    * Constructs a controller with the given coefficients and plant.
    *
@@ -46,14 +40,12 @@
    * @param Qelems The maximum desired error tolerance for each state.
    * @param Relems The maximum desired control effort for each input.
    * @param dt     Discretization timestep.
+   * @throws std::invalid_argument If the system is uncontrollable.
    */
   template <int Outputs>
-  LinearQuadraticRegulatorImpl(
-      const LinearSystem<States, Inputs, Outputs>& plant,
-      const wpi::array<double, States>& Qelems,
-      const wpi::array<double, Inputs>& Relems, units::second_t dt)
-      : LinearQuadraticRegulatorImpl(plant.A(), plant.B(), Qelems, Relems, dt) {
-  }
+  LinearQuadraticRegulator(const LinearSystem<States, Inputs, Outputs>& plant,
+                           const StateArray& Qelems, const InputArray& Relems,
+                           units::second_t dt);
 
   /**
    * Constructs a controller with the given coefficients and plant.
@@ -63,14 +55,12 @@
    * @param Qelems The maximum desired error tolerance for each state.
    * @param Relems The maximum desired control effort for each input.
    * @param dt     Discretization timestep.
+   * @throws std::invalid_argument If the system is uncontrollable.
    */
-  LinearQuadraticRegulatorImpl(const Eigen::Matrix<double, States, States>& A,
-                               const Eigen::Matrix<double, States, Inputs>& B,
-                               const wpi::array<double, States>& Qelems,
-                               const wpi::array<double, Inputs>& Relems,
-                               units::second_t dt)
-      : LinearQuadraticRegulatorImpl(A, B, MakeCostMatrix(Qelems),
-                                     MakeCostMatrix(Relems), dt) {}
+  LinearQuadraticRegulator(const Matrixd<States, States>& A,
+                           const Matrixd<States, Inputs>& B,
+                           const StateArray& Qelems, const InputArray& Relems,
+                           units::second_t dt);
 
   /**
    * Constructs a controller with the given coefficients and plant.
@@ -80,36 +70,13 @@
    * @param Q  The state cost matrix.
    * @param R  The input cost matrix.
    * @param dt Discretization timestep.
+   * @throws std::invalid_argument If the system is uncontrollable.
    */
-  LinearQuadraticRegulatorImpl(const Eigen::Matrix<double, States, States>& A,
-                               const Eigen::Matrix<double, States, Inputs>& B,
-                               const Eigen::Matrix<double, States, States>& Q,
-                               const Eigen::Matrix<double, Inputs, Inputs>& R,
-                               units::second_t dt) {
-    Eigen::Matrix<double, States, States> discA;
-    Eigen::Matrix<double, States, Inputs> discB;
-    DiscretizeAB<States, Inputs>(A, B, dt, &discA, &discB);
-
-    if (!IsStabilizable<States, Inputs>(discA, discB)) {
-      std::string msg = fmt::format(
-          "The system passed to the LQR is uncontrollable!\n\nA =\n{}\nB "
-          "=\n{}\n",
-          discA, discB);
-
-      wpi::math::MathSharedStore::ReportError(msg);
-      throw std::invalid_argument(msg);
-    }
-
-    Eigen::Matrix<double, States, States> S =
-        drake::math::DiscreteAlgebraicRiccatiEquation(discA, discB, Q, R);
-
-    // K = (BᵀSB + R)⁻¹BᵀSA
-    m_K = (discB.transpose() * S * discB + R)
-              .llt()
-              .solve(discB.transpose() * S * discA);
-
-    Reset();
-  }
+  LinearQuadraticRegulator(const Matrixd<States, States>& A,
+                           const Matrixd<States, Inputs>& B,
+                           const Matrixd<States, States>& Q,
+                           const Matrixd<Inputs, Inputs>& R,
+                           units::second_t dt);
 
   /**
    * Constructs a controller with the given coefficients and plant.
@@ -120,36 +87,22 @@
    * @param R  The input cost matrix.
    * @param N  The state-input cross-term cost matrix.
    * @param dt Discretization timestep.
+   * @throws std::invalid_argument If the system is uncontrollable.
    */
-  LinearQuadraticRegulatorImpl(const Eigen::Matrix<double, States, States>& A,
-                               const Eigen::Matrix<double, States, Inputs>& B,
-                               const Eigen::Matrix<double, States, States>& Q,
-                               const Eigen::Matrix<double, Inputs, Inputs>& R,
-                               const Eigen::Matrix<double, States, Inputs>& N,
-                               units::second_t dt) {
-    Eigen::Matrix<double, States, States> discA;
-    Eigen::Matrix<double, States, Inputs> discB;
-    DiscretizeAB<States, Inputs>(A, B, dt, &discA, &discB);
+  LinearQuadraticRegulator(const Matrixd<States, States>& A,
+                           const Matrixd<States, Inputs>& B,
+                           const Matrixd<States, States>& Q,
+                           const Matrixd<Inputs, Inputs>& R,
+                           const Matrixd<States, Inputs>& N,
+                           units::second_t dt);
 
-    Eigen::Matrix<double, States, States> S =
-        drake::math::DiscreteAlgebraicRiccatiEquation(discA, discB, Q, R, N);
-
-    // K = (BᵀSB + R)⁻¹(BᵀSA + Nᵀ)
-    m_K = (discB.transpose() * S * discB + R)
-              .llt()
-              .solve(discB.transpose() * S * discA + N.transpose());
-
-    Reset();
-  }
-
-  LinearQuadraticRegulatorImpl(LinearQuadraticRegulatorImpl&&) = default;
-  LinearQuadraticRegulatorImpl& operator=(LinearQuadraticRegulatorImpl&&) =
-      default;
+  LinearQuadraticRegulator(LinearQuadraticRegulator&&) = default;
+  LinearQuadraticRegulator& operator=(LinearQuadraticRegulator&&) = default;
 
   /**
    * Returns the controller matrix K.
    */
-  const Eigen::Matrix<double, Inputs, States>& K() const { return m_K; }
+  const Matrixd<Inputs, States>& K() const { return m_K; }
 
   /**
    * Returns an element of the controller matrix K.
@@ -164,7 +117,7 @@
    *
    * @return The reference vector.
    */
-  const Eigen::Vector<double, States>& R() const { return m_r; }
+  const StateVector& R() const { return m_r; }
 
   /**
    * Returns an element of the reference vector r.
@@ -173,14 +126,14 @@
    *
    * @return The row of the reference vector.
    */
-  double R(int i) const { return m_r(i, 0); }
+  double R(int i) const { return m_r(i); }
 
   /**
    * Returns the control input vector u.
    *
    * @return The control input.
    */
-  const Eigen::Vector<double, Inputs>& U() const { return m_u; }
+  const InputVector& U() const { return m_u; }
 
   /**
    * Returns an element of the control input vector u.
@@ -189,7 +142,7 @@
    *
    * @return The row of the control input vector.
    */
-  double U(int i) const { return m_u(i, 0); }
+  double U(int i) const { return m_u(i); }
 
   /**
    * Resets the controller.
@@ -204,11 +157,7 @@
    *
    * @param x The current state x.
    */
-  Eigen::Vector<double, Inputs> Calculate(
-      const Eigen::Vector<double, States>& x) {
-    m_u = m_K * (m_r - x);
-    return m_u;
-  }
+  InputVector Calculate(const StateVector& x);
 
   /**
    * Returns the next output of the controller.
@@ -216,12 +165,7 @@
    * @param x     The current state x.
    * @param nextR The next reference vector r.
    */
-  Eigen::Vector<double, Inputs> Calculate(
-      const Eigen::Vector<double, States>& x,
-      const Eigen::Vector<double, States>& nextR) {
-    m_r = nextR;
-    return Calculate(x);
-  }
+  InputVector Calculate(const StateVector& x, const StateVector& nextR);
 
   /**
    * Adjusts LQR controller gain to compensate for a pure time delay in the
@@ -241,209 +185,26 @@
    */
   template <int Outputs>
   void LatencyCompensate(const LinearSystem<States, Inputs, Outputs>& plant,
-                         units::second_t dt, units::second_t inputDelay) {
-    Eigen::Matrix<double, States, States> discA;
-    Eigen::Matrix<double, States, Inputs> discB;
-    DiscretizeAB<States, Inputs>(plant.A(), plant.B(), dt, &discA, &discB);
-
-    m_K = m_K * (discA - discB * m_K).pow(inputDelay / dt);
-  }
+                         units::second_t dt, units::second_t inputDelay);
 
  private:
   // Current reference
-  Eigen::Vector<double, States> m_r;
+  StateVector m_r;
 
   // Computed controller output
-  Eigen::Vector<double, Inputs> m_u;
+  InputVector m_u;
 
   // Controller gain
-  Eigen::Matrix<double, Inputs, States> m_K;
+  Matrixd<Inputs, States> m_K;
 };
 
-}  // namespace detail
-
-template <int States, int Inputs>
-class LinearQuadraticRegulator
-    : public detail::LinearQuadraticRegulatorImpl<States, Inputs> {
- public:
-  /**
-   * Constructs a controller with the given coefficients and plant.
-   *
-   * @tparam Outputs The number of outputs.
-   * @param plant  The plant being controlled.
-   * @param Qelems The maximum desired error tolerance for each state.
-   * @param Relems The maximum desired control effort for each input.
-   * @param dt     Discretization timestep.
-   */
-  template <int Outputs>
-  LinearQuadraticRegulator(const LinearSystem<States, Inputs, Outputs>& plant,
-                           const wpi::array<double, States>& Qelems,
-                           const wpi::array<double, Inputs>& Relems,
-                           units::second_t dt)
-      : LinearQuadraticRegulator(plant.A(), plant.B(), Qelems, Relems, dt) {}
-
-  /**
-   * Constructs a controller with the given coefficients and plant.
-   *
-   * @param A      Continuous system matrix of the plant being controlled.
-   * @param B      Continuous input matrix of the plant being controlled.
-   * @param Qelems The maximum desired error tolerance for each state.
-   * @param Relems The maximum desired control effort for each input.
-   * @param dt     Discretization timestep.
-   */
-  LinearQuadraticRegulator(const Eigen::Matrix<double, States, States>& A,
-                           const Eigen::Matrix<double, States, Inputs>& B,
-                           const wpi::array<double, States>& Qelems,
-                           const wpi::array<double, Inputs>& Relems,
-                           units::second_t dt)
-      : LinearQuadraticRegulator(A, B, MakeCostMatrix(Qelems),
-                                 MakeCostMatrix(Relems), dt) {}
-
-  /**
-   * Constructs a controller with the given coefficients and plant.
-   *
-   * @param A  Continuous system matrix of the plant being controlled.
-   * @param B  Continuous input matrix of the plant being controlled.
-   * @param Q  The state cost matrix.
-   * @param R  The input cost matrix.
-   * @param dt Discretization timestep.
-   */
-  LinearQuadraticRegulator(const Eigen::Matrix<double, States, States>& A,
-                           const Eigen::Matrix<double, States, Inputs>& B,
-                           const Eigen::Matrix<double, States, States>& Q,
-                           const Eigen::Matrix<double, Inputs, Inputs>& R,
-                           units::second_t dt)
-      : detail::LinearQuadraticRegulatorImpl<States, Inputs>{A, B, Q, R, dt} {}
-
-  /**
-   * Constructs a controller with the given coefficients and plant.
-   *
-   * @param A  Continuous system matrix of the plant being controlled.
-   * @param B  Continuous input matrix of the plant being controlled.
-   * @param Q  The state cost matrix.
-   * @param R  The input cost matrix.
-   * @param N  The state-input cross-term cost matrix.
-   * @param dt Discretization timestep.
-   */
-  LinearQuadraticRegulator(const Eigen::Matrix<double, States, States>& A,
-                           const Eigen::Matrix<double, States, Inputs>& B,
-                           const Eigen::Matrix<double, States, States>& Q,
-                           const Eigen::Matrix<double, Inputs, Inputs>& R,
-                           const Eigen::Matrix<double, States, Inputs>& N,
-                           units::second_t dt)
-      : detail::LinearQuadraticRegulatorImpl<States, Inputs>{A, B, Q,
-                                                             R, N, dt} {}
-
-  LinearQuadraticRegulator(LinearQuadraticRegulator&&) = default;
-  LinearQuadraticRegulator& operator=(LinearQuadraticRegulator&&) = default;
-};
-
-// Template specializations are used here to make common state-input pairs
-// compile faster.
-template <>
-class WPILIB_DLLEXPORT LinearQuadraticRegulator<1, 1>
-    : public detail::LinearQuadraticRegulatorImpl<1, 1> {
- public:
-  template <int Outputs>
-  LinearQuadraticRegulator(const LinearSystem<1, 1, Outputs>& plant,
-                           const wpi::array<double, 1>& Qelems,
-                           const wpi::array<double, 1>& Relems,
-                           units::second_t dt)
-      : LinearQuadraticRegulator(plant.A(), plant.B(), Qelems, Relems, dt) {}
-
-  LinearQuadraticRegulator(const Eigen::Matrix<double, 1, 1>& A,
-                           const Eigen::Matrix<double, 1, 1>& B,
-                           const wpi::array<double, 1>& Qelems,
-                           const wpi::array<double, 1>& Relems,
-                           units::second_t dt);
-
-  LinearQuadraticRegulator(const Eigen::Matrix<double, 1, 1>& A,
-                           const Eigen::Matrix<double, 1, 1>& B,
-                           const Eigen::Matrix<double, 1, 1>& Q,
-                           const Eigen::Matrix<double, 1, 1>& R,
-                           units::second_t dt);
-
-  LinearQuadraticRegulator(const Eigen::Matrix<double, 1, 1>& A,
-                           const Eigen::Matrix<double, 1, 1>& B,
-                           const Eigen::Matrix<double, 1, 1>& Q,
-                           const Eigen::Matrix<double, 1, 1>& R,
-                           const Eigen::Matrix<double, 1, 1>& N,
-                           units::second_t dt);
-
-  LinearQuadraticRegulator(LinearQuadraticRegulator&&) = default;
-  LinearQuadraticRegulator& operator=(LinearQuadraticRegulator&&) = default;
-};
-
-// Template specializations are used here to make common state-input pairs
-// compile faster.
-template <>
-class WPILIB_DLLEXPORT LinearQuadraticRegulator<2, 1>
-    : public detail::LinearQuadraticRegulatorImpl<2, 1> {
- public:
-  template <int Outputs>
-  LinearQuadraticRegulator(const LinearSystem<2, 1, Outputs>& plant,
-                           const wpi::array<double, 2>& Qelems,
-                           const wpi::array<double, 1>& Relems,
-                           units::second_t dt)
-      : LinearQuadraticRegulator(plant.A(), plant.B(), Qelems, Relems, dt) {}
-
-  LinearQuadraticRegulator(const Eigen::Matrix<double, 2, 2>& A,
-                           const Eigen::Matrix<double, 2, 1>& B,
-                           const wpi::array<double, 2>& Qelems,
-                           const wpi::array<double, 1>& Relems,
-                           units::second_t dt);
-
-  LinearQuadraticRegulator(const Eigen::Matrix<double, 2, 2>& A,
-                           const Eigen::Matrix<double, 2, 1>& B,
-                           const Eigen::Matrix<double, 2, 2>& Q,
-                           const Eigen::Matrix<double, 1, 1>& R,
-                           units::second_t dt);
-
-  LinearQuadraticRegulator(const Eigen::Matrix<double, 2, 2>& A,
-                           const Eigen::Matrix<double, 2, 1>& B,
-                           const Eigen::Matrix<double, 2, 2>& Q,
-                           const Eigen::Matrix<double, 1, 1>& R,
-                           const Eigen::Matrix<double, 2, 1>& N,
-                           units::second_t dt);
-
-  LinearQuadraticRegulator(LinearQuadraticRegulator&&) = default;
-  LinearQuadraticRegulator& operator=(LinearQuadraticRegulator&&) = default;
-};
-
-// Template specializations are used here to make common state-input pairs
-// compile faster.
-template <>
-class WPILIB_DLLEXPORT LinearQuadraticRegulator<2, 2>
-    : public detail::LinearQuadraticRegulatorImpl<2, 2> {
- public:
-  template <int Outputs>
-  LinearQuadraticRegulator(const LinearSystem<2, 2, Outputs>& plant,
-                           const wpi::array<double, 2>& Qelems,
-                           const wpi::array<double, 2>& Relems,
-                           units::second_t dt)
-      : LinearQuadraticRegulator(plant.A(), plant.B(), Qelems, Relems, dt) {}
-
-  LinearQuadraticRegulator(const Eigen::Matrix<double, 2, 2>& A,
-                           const Eigen::Matrix<double, 2, 2>& B,
-                           const wpi::array<double, 2>& Qelems,
-                           const wpi::array<double, 2>& Relems,
-                           units::second_t dt);
-
-  LinearQuadraticRegulator(const Eigen::Matrix<double, 2, 2>& A,
-                           const Eigen::Matrix<double, 2, 2>& B,
-                           const Eigen::Matrix<double, 2, 2>& Q,
-                           const Eigen::Matrix<double, 2, 2>& R,
-                           units::second_t dt);
-
-  LinearQuadraticRegulator(const Eigen::Matrix<double, 2, 2>& A,
-                           const Eigen::Matrix<double, 2, 2>& B,
-                           const Eigen::Matrix<double, 2, 2>& Q,
-                           const Eigen::Matrix<double, 2, 2>& R,
-                           const Eigen::Matrix<double, 2, 2>& N,
-                           units::second_t dt);
-
-  LinearQuadraticRegulator(LinearQuadraticRegulator&&) = default;
-  LinearQuadraticRegulator& operator=(LinearQuadraticRegulator&&) = default;
-};
+extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
+    LinearQuadraticRegulator<1, 1>;
+extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
+    LinearQuadraticRegulator<2, 1>;
+extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
+    LinearQuadraticRegulator<2, 2>;
 
 }  // namespace frc
+
+#include "LinearQuadraticRegulator.inc"
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/LinearQuadraticRegulator.inc b/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/LinearQuadraticRegulator.inc
new file mode 100644
index 0000000..87d37ec
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/LinearQuadraticRegulator.inc
@@ -0,0 +1,113 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <stdexcept>
+#include <string>
+
+#include "Eigen/Cholesky"
+#include "Eigen/Eigenvalues"
+#include "drake/math/discrete_algebraic_riccati_equation.h"
+#include "frc/StateSpaceUtil.h"
+#include "frc/controller/LinearQuadraticRegulator.h"
+#include "frc/fmt/Eigen.h"
+#include "frc/system/Discretization.h"
+#include "unsupported/Eigen/MatrixFunctions"
+#include "wpimath/MathShared.h"
+
+namespace frc {
+
+template <int States, int Inputs>
+template <int Outputs>
+LinearQuadraticRegulator<States, Inputs>::LinearQuadraticRegulator(
+    const LinearSystem<States, Inputs, Outputs>& plant,
+    const StateArray& Qelems, const InputArray& Relems, units::second_t dt)
+    : LinearQuadraticRegulator(plant.A(), plant.B(), Qelems, Relems, dt) {}
+
+template <int States, int Inputs>
+LinearQuadraticRegulator<States, Inputs>::LinearQuadraticRegulator(
+    const Matrixd<States, States>& A, const Matrixd<States, Inputs>& B,
+    const StateArray& Qelems, const InputArray& Relems, units::second_t dt)
+    : LinearQuadraticRegulator(A, B, MakeCostMatrix(Qelems),
+                               MakeCostMatrix(Relems), dt) {}
+
+template <int States, int Inputs>
+LinearQuadraticRegulator<States, Inputs>::LinearQuadraticRegulator(
+    const Matrixd<States, States>& A, const Matrixd<States, Inputs>& B,
+    const Matrixd<States, States>& Q, const Matrixd<Inputs, Inputs>& R,
+    units::second_t dt) {
+  Matrixd<States, States> discA;
+  Matrixd<States, Inputs> discB;
+  DiscretizeAB<States, Inputs>(A, B, dt, &discA, &discB);
+
+  if (!IsStabilizable<States, Inputs>(discA, discB)) {
+    std::string msg = fmt::format(
+        "The system passed to the LQR is uncontrollable!\n\nA =\n{}\nB "
+        "=\n{}\n",
+        discA, discB);
+
+    wpi::math::MathSharedStore::ReportError(msg);
+    throw std::invalid_argument(msg);
+  }
+
+  Matrixd<States, States> S =
+      drake::math::DiscreteAlgebraicRiccatiEquation(discA, discB, Q, R);
+
+  // K = (BᵀSB + R)⁻¹BᵀSA
+  m_K = (discB.transpose() * S * discB + R)
+            .llt()
+            .solve(discB.transpose() * S * discA);
+
+  Reset();
+}
+
+template <int States, int Inputs>
+LinearQuadraticRegulator<States, Inputs>::LinearQuadraticRegulator(
+    const Matrixd<States, States>& A, const Matrixd<States, Inputs>& B,
+    const Matrixd<States, States>& Q, const Matrixd<Inputs, Inputs>& R,
+    const Matrixd<States, Inputs>& N, units::second_t dt) {
+  Matrixd<States, States> discA;
+  Matrixd<States, Inputs> discB;
+  DiscretizeAB<States, Inputs>(A, B, dt, &discA, &discB);
+
+  Matrixd<States, States> S =
+      drake::math::DiscreteAlgebraicRiccatiEquation(discA, discB, Q, R, N);
+
+  // K = (BᵀSB + R)⁻¹(BᵀSA + Nᵀ)
+  m_K = (discB.transpose() * S * discB + R)
+            .llt()
+            .solve(discB.transpose() * S * discA + N.transpose());
+
+  Reset();
+}
+
+template <int States, int Inputs>
+typename LinearQuadraticRegulator<States, Inputs>::InputVector
+LinearQuadraticRegulator<States, Inputs>::Calculate(const StateVector& x) {
+  m_u = m_K * (m_r - x);
+  return m_u;
+}
+
+template <int States, int Inputs>
+typename LinearQuadraticRegulator<States, Inputs>::InputVector
+LinearQuadraticRegulator<States, Inputs>::Calculate(const StateVector& x,
+                                                    const StateVector& nextR) {
+  m_r = nextR;
+  return Calculate(x);
+}
+
+template <int States, int Inputs>
+template <int Outputs>
+void LinearQuadraticRegulator<States, Inputs>::LatencyCompensate(
+    const LinearSystem<States, Inputs, Outputs>& plant, units::second_t dt,
+    units::second_t inputDelay) {
+  Matrixd<States, States> discA;
+  Matrixd<States, Inputs> discB;
+  DiscretizeAB<States, Inputs>(plant.A(), plant.B(), dt, &discA, &discB);
+
+  m_K = m_K * (discA - discB * m_K).pow(inputDelay / dt);
+}
+
+}  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/PIDController.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/PIDController.h
index 98625f8..d6a41d1 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/PIDController.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/PIDController.h
@@ -102,6 +102,20 @@
   units::second_t GetPeriod() const;
 
   /**
+   * Gets the position tolerance of this controller.
+   *
+   * @return The position tolerance of the controller.
+   */
+  double GetPositionTolerance() const;
+
+  /**
+   * Gets the velocity tolerance of this controller.
+   *
+   * @return The velocity tolerance of the controller.
+   */
+  double GetVelocityTolerance() const;
+
+  /**
    * Sets the setpoint for the PIDController.
    *
    * @param setpoint The desired setpoint.
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/ProfiledPIDController.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/ProfiledPIDController.h
index e0b10c7..8491118 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/ProfiledPIDController.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/ProfiledPIDController.h
@@ -22,7 +22,7 @@
 namespace frc {
 namespace detail {
 WPILIB_DLLEXPORT
-void ReportProfiledPIDController();
+int IncrementAndGetProfiledPIDControllerInstances();
 }  // namespace detail
 
 /**
@@ -59,7 +59,10 @@
   ProfiledPIDController(double Kp, double Ki, double Kd,
                         Constraints constraints, units::second_t period = 20_ms)
       : m_controller(Kp, Ki, Kd, period), m_constraints(constraints) {
-    detail::ReportProfiledPIDController();
+    int instances = detail::IncrementAndGetProfiledPIDControllerInstances();
+    wpi::math::MathSharedStore::ReportUsage(
+        wpi::math::MathUsageId::kController_ProfiledPIDController, instances);
+    wpi::SendableRegistry::Add(this, "ProfiledPIDController", instances);
   }
 
   ~ProfiledPIDController() override = default;
@@ -132,6 +135,24 @@
   units::second_t GetPeriod() const { return m_controller.GetPeriod(); }
 
   /**
+   * Gets the position tolerance of this controller.
+   *
+   * @return The position tolerance of the controller.
+   */
+  double GetPositionTolerance() const {
+    return m_controller.GetPositionTolerance();
+  }
+
+  /**
+   * Gets the velocity tolerance of this controller.
+   *
+   * @return The velocity tolerance of the controller.
+   */
+  double GetVelocityTolerance() const {
+    return m_controller.GetVelocityTolerance();
+  }
+
+  /**
    * Sets the goal for the ProfiledPIDController.
    *
    * @param goal The desired unprofiled setpoint.
@@ -143,7 +164,7 @@
    *
    * @param goal The desired unprofiled setpoint.
    */
-  void SetGoal(Distance_t goal) { m_goal = {goal, Velocity_t(0)}; }
+  void SetGoal(Distance_t goal) { m_goal = {goal, Velocity_t{0}}; }
 
   /**
    * Gets the goal for the ProfiledPIDController.
@@ -224,9 +245,9 @@
    * @param positionTolerance Position error which is tolerable.
    * @param velocityTolerance Velocity error which is tolerable.
    */
-  void SetTolerance(
-      Distance_t positionTolerance,
-      Velocity_t velocityTolerance = std::numeric_limits<double>::infinity()) {
+  void SetTolerance(Distance_t positionTolerance,
+                    Velocity_t velocityTolerance = Velocity_t{
+                        std::numeric_limits<double>::infinity()}) {
     m_controller.SetTolerance(positionTolerance.value(),
                               velocityTolerance.value());
   }
@@ -237,14 +258,14 @@
    * @return The error.
    */
   Distance_t GetPositionError() const {
-    return Distance_t(m_controller.GetPositionError());
+    return Distance_t{m_controller.GetPositionError()};
   }
 
   /**
    * Returns the change in error per second.
    */
   Velocity_t GetVelocityError() const {
-    return Velocity_t(m_controller.GetVelocityError());
+    return Velocity_t{m_controller.GetVelocityError()};
   }
 
   /**
@@ -339,7 +360,7 @@
    * velocity is assumed to be zero.
    */
   void Reset(Distance_t measuredPosition) {
-    Reset(measuredPosition, Velocity_t(0));
+    Reset(measuredPosition, Velocity_t{0});
   }
 
   void InitSendable(wpi::SendableBuilder& builder) override {
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/RamseteController.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/RamseteController.h
index bb23f46..d031101 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/RamseteController.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/RamseteController.h
@@ -5,7 +5,6 @@
 #pragma once
 
 #include <wpi/SymbolExports.h>
-#include <wpi/deprecated.h>
 
 #include "frc/geometry/Pose2d.h"
 #include "frc/kinematics/ChassisSpeeds.h"
@@ -58,17 +57,6 @@
    * @param zeta Tuning parameter (0 rad⁻¹ < zeta < 1 rad⁻¹) for which larger
    *             values provide more damping in response.
    */
-  WPI_DEPRECATED("Use unit-safe constructor instead")
-  RamseteController(double b, double zeta);
-
-  /**
-   * Construct a Ramsete unicycle controller.
-   *
-   * @param b    Tuning parameter (b > 0 rad²/m²) for which larger values make
-   *             convergence more aggressive like a proportional term.
-   * @param zeta Tuning parameter (0 rad⁻¹ < zeta < 1 rad⁻¹) for which larger
-   *             values provide more damping in response.
-   */
   RamseteController(units::unit_t<b_unit> b, units::unit_t<zeta_unit> zeta);
 
   /**
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/SimpleMotorFeedforward.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/SimpleMotorFeedforward.h
index df1a52c..86b40ea 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/SimpleMotorFeedforward.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/controller/SimpleMotorFeedforward.h
@@ -6,7 +6,7 @@
 
 #include <wpi/MathExtras.h>
 
-#include "Eigen/Core"
+#include "frc/EigenCore.h"
 #include "frc/controller/LinearPlantInversionFeedforward.h"
 #include "frc/system/plant/LinearSystemId.h"
 #include "units/time.h"
@@ -35,7 +35,7 @@
    *
    * @param kS The static gain, in volts.
    * @param kV The velocity gain, in volt seconds per distance.
-   * @param kA The acceleration gain, in volt seconds^2 per distance.
+   * @param kA The acceleration gain, in volt seconds² per distance.
    */
   constexpr SimpleMotorFeedforward(
       units::volt_t kS, units::unit_t<kv_unit> kV,
@@ -46,7 +46,7 @@
    * Calculates the feedforward from the gains and setpoints.
    *
    * @param velocity     The velocity setpoint, in distance per second.
-   * @param acceleration The acceleration setpoint, in distance per second^2.
+   * @param acceleration The acceleration setpoint, in distance per second².
    * @return The computed feedforward, in volts.
    */
   constexpr units::volt_t Calculate(units::unit_t<Velocity> velocity,
@@ -70,8 +70,8 @@
     auto plant = LinearSystemId::IdentifyVelocitySystem<Distance>(kV, kA);
     LinearPlantInversionFeedforward<1, 1> feedforward{plant, dt};
 
-    Eigen::Vector<double, 1> r{currentVelocity.value()};
-    Eigen::Vector<double, 1> nextR{nextVelocity.value()};
+    Vectord<1> r{currentVelocity.value()};
+    Vectord<1> nextR{nextVelocity.value()};
 
     return kS * wpi::sgn(currentVelocity.value()) +
            units::volt_t{feedforward.Calculate(r, nextR)(0)};
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/AngleStatistics.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/AngleStatistics.h
index 3ddabc1..0512c68c 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/AngleStatistics.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/AngleStatistics.h
@@ -4,9 +4,9 @@
 
 #pragma once
 
-#include <wpi/numbers>
+#include <numbers>
 
-#include "Eigen/Core"
+#include "frc/EigenCore.h"
 #include "frc/MathUtil.h"
 
 namespace frc {
@@ -21,10 +21,9 @@
  * @param angleStateIdx The row containing angles to be normalized.
  */
 template <int States>
-Eigen::Vector<double, States> AngleResidual(
-    const Eigen::Vector<double, States>& a,
-    const Eigen::Vector<double, States>& b, int angleStateIdx) {
-  Eigen::Vector<double, States> ret = a - b;
+Vectord<States> AngleResidual(const Vectord<States>& a,
+                              const Vectord<States>& b, int angleStateIdx) {
+  Vectord<States> ret = a - b;
   ret[angleStateIdx] =
       AngleModulus(units::radian_t{ret[angleStateIdx]}).value();
   return ret;
@@ -38,8 +37,7 @@
  * @param angleStateIdx The row containing angles to be normalized.
  */
 template <int States>
-std::function<Eigen::Vector<double, States>(
-    const Eigen::Vector<double, States>&, const Eigen::Vector<double, States>&)>
+std::function<Vectord<States>(const Vectord<States>&, const Vectord<States>&)>
 AngleResidual(int angleStateIdx) {
   return [=](auto a, auto b) {
     return AngleResidual<States>(a, b, angleStateIdx);
@@ -56,12 +54,11 @@
  * @param angleStateIdx The row containing angles to be normalized.
  */
 template <int States>
-Eigen::Vector<double, States> AngleAdd(const Eigen::Vector<double, States>& a,
-                                       const Eigen::Vector<double, States>& b,
-                                       int angleStateIdx) {
-  Eigen::Vector<double, States> ret = a + b;
+Vectord<States> AngleAdd(const Vectord<States>& a, const Vectord<States>& b,
+                         int angleStateIdx) {
+  Vectord<States> ret = a + b;
   ret[angleStateIdx] =
-      InputModulus(ret[angleStateIdx], -wpi::numbers::pi, wpi::numbers::pi);
+      InputModulus(ret[angleStateIdx], -std::numbers::pi, std::numbers::pi);
   return ret;
 }
 
@@ -73,8 +70,7 @@
  * @param angleStateIdx The row containing angles to be normalized.
  */
 template <int States>
-std::function<Eigen::Vector<double, States>(
-    const Eigen::Vector<double, States>&, const Eigen::Vector<double, States>&)>
+std::function<Vectord<States>(const Vectord<States>&, const Vectord<States>&)>
 AngleAdd(int angleStateIdx) {
   return [=](auto a, auto b) { return AngleAdd<States>(a, b, angleStateIdx); };
 }
@@ -91,17 +87,21 @@
  * @param angleStatesIdx The row containing the angles.
  */
 template <int CovDim, int States>
-Eigen::Vector<double, CovDim> AngleMean(
-    const Eigen::Matrix<double, CovDim, 2 * States + 1>& sigmas,
-    const Eigen::Vector<double, 2 * States + 1>& Wm, int angleStatesIdx) {
-  double sumSin = sigmas.row(angleStatesIdx)
-                      .unaryExpr([](auto it) { return std::sin(it); })
+Vectord<CovDim> AngleMean(const Matrixd<CovDim, 2 * States + 1>& sigmas,
+                          const Vectord<2 * States + 1>& Wm,
+                          int angleStatesIdx) {
+  double sumSin = (sigmas.row(angleStatesIdx).unaryExpr([](auto it) {
+                    return std::sin(it);
+                  }) *
+                   Wm)
                       .sum();
-  double sumCos = sigmas.row(angleStatesIdx)
-                      .unaryExpr([](auto it) { return std::cos(it); })
+  double sumCos = (sigmas.row(angleStatesIdx).unaryExpr([](auto it) {
+                    return std::cos(it);
+                  }) *
+                   Wm)
                       .sum();
 
-  Eigen::Vector<double, CovDim> ret = sigmas * Wm;
+  Vectord<CovDim> ret = sigmas * Wm;
   ret[angleStatesIdx] = std::atan2(sumSin, sumCos);
   return ret;
 }
@@ -116,9 +116,8 @@
  * @param angleStateIdx The row containing the angles.
  */
 template <int CovDim, int States>
-std::function<Eigen::Vector<double, CovDim>(
-    const Eigen::Matrix<double, CovDim, 2 * States + 1>&,
-    const Eigen::Vector<double, 2 * States + 1>&)>
+std::function<Vectord<CovDim>(const Matrixd<CovDim, 2 * States + 1>&,
+                              const Vectord<2 * States + 1>&)>
 AngleMean(int angleStateIdx) {
   return [=](auto sigmas, auto Wm) {
     return AngleMean<CovDim, States>(sigmas, Wm, angleStateIdx);
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/DifferentialDrivePoseEstimator.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/DifferentialDrivePoseEstimator.h
index 12810fa..339ccc9 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/DifferentialDrivePoseEstimator.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/DifferentialDrivePoseEstimator.h
@@ -7,17 +7,18 @@
 #include <wpi/SymbolExports.h>
 #include <wpi/array.h>
 
-#include "Eigen/Core"
-#include "frc/estimator/KalmanFilterLatencyCompensator.h"
-#include "frc/estimator/UnscentedKalmanFilter.h"
+#include "frc/EigenCore.h"
 #include "frc/geometry/Pose2d.h"
 #include "frc/geometry/Rotation2d.h"
+#include "frc/interpolation/TimeInterpolatableBuffer.h"
+#include "frc/kinematics/DifferentialDriveKinematics.h"
+#include "frc/kinematics/DifferentialDriveOdometry.h"
 #include "frc/kinematics/DifferentialDriveWheelSpeeds.h"
 #include "units/time.h"
 
 namespace frc {
 /**
- * This class wraps an Unscented Kalman Filter to fuse latency-compensated
+ * This class wraps Differential Drive Odometry to fuse latency-compensated
  * vision measurements with differential drive encoder measurements. It will
  * correct for noisy vision measurements and encoder drift. It is intended to be
  * an easy drop-in for DifferentialDriveOdometry. In fact, if you never call
@@ -25,77 +26,68 @@
  * same as DifferentialDriveOdometry.
  *
  * Update() should be called every robot loop (if your robot loops are faster or
- * slower than the default, then you should change the nominal delta time via
- * the constructor).
+ * slower than the default of 20 ms, then you should change the nominal delta
+ * time via the constructor).
  *
  * AddVisionMeasurement() can be called as infrequently as you want; if you
  * never call it, then this class will behave like regular encoder odometry.
- *
- * The state-space system used internally has the following states (x), inputs
- * (u), and outputs (y):
- *
- * <strong> x = [x, y, theta, dist_l, dist_r]ᵀ </strong> in the field coordinate
- * system containing x position, y position, heading, left encoder distance,
- * and right encoder distance.
- *
- * <strong> u = [v_x, v_y, omega]ᵀ </strong> containing x velocity, y velocity,
- * and angular velocity in the field coordinate system.
- *
- * NB: Using velocities make things considerably easier, because it means that
- * teams don't have to worry about getting an accurate model. Basically, we
- * suspect that it's easier for teams to get good encoder data than it is for
- * them to perform system identification well enough to get a good model.
- *
- * <strong> y = [x, y, theta]ᵀ </strong> from vision containing x position, y
- * position, and heading; or <strong>y = [dist_l, dist_r, theta] </strong>
- * containing left encoder position, right encoder position, and gyro heading.
  */
 class WPILIB_DLLEXPORT DifferentialDrivePoseEstimator {
  public:
   /**
-   * Constructs a DifferentialDrivePoseEstimator.
+   * Constructs a DifferentialDrivePoseEstimator with default standard
+   * deviations for the model and vision measurements.
    *
-   * @param gyroAngle                The gyro angle of the robot.
-   * @param initialPose              The estimated initial pose.
-   * @param stateStdDevs             Standard deviations of model states.
-   *                                 Increase these numbers to trust your
-   *                                 model's state estimates less. This matrix
-   *                                 is in the form
-   *                                 [x, y, theta, dist_l, dist_r]ᵀ,
-   *                                 with units in meters and radians.
-   * @param localMeasurementStdDevs  Standard deviations of the encoder and gyro
-   *                                 measurements. Increase these numbers to
-   *                                 trust sensor readings from
-   *                                 encoders and gyros less.
-   *                                 This matrix is in the form
-   *                                 [dist_l, dist_r, theta]ᵀ, with units in
-   *                                 meters and radians.
-   * @param visionMeasurementStdDevs Standard deviations of the vision
-   *                                 measurements. Increase these numbers to
-   *                                 trust global measurements from
-   *                                 vision less. This matrix is in the form
-   *                                 [x, y, theta]ᵀ, with units in meters and
-   *                                 radians.
-   * @param nominalDt                The period of the loop calling Update().
+   * The default standard deviations of the model states are
+   * 0.02 meters for x, 0.02 meters for y, and 0.01 radians for heading.
+   * The default standard deviations of the vision measurements are
+   * 0.1 meters for x, 0.1 meters for y, and 0.1 radians for heading.
+   *
+   * @param kinematics A correctly-configured kinematics object for your
+   *     drivetrain.
+   * @param gyroAngle The gyro angle of the robot.
+   * @param leftDistance The distance traveled by the left encoder.
+   * @param rightDistance The distance traveled by the right encoder.
+   * @param initialPose The estimated initial pose.
    */
-  DifferentialDrivePoseEstimator(
-      const Rotation2d& gyroAngle, const Pose2d& initialPose,
-      const wpi::array<double, 5>& stateStdDevs,
-      const wpi::array<double, 3>& localMeasurementStdDevs,
-      const wpi::array<double, 3>& visionMeasurementStdDevs,
-      units::second_t nominalDt = 0.02_s);
+  DifferentialDrivePoseEstimator(DifferentialDriveKinematics& kinematics,
+                                 const Rotation2d& gyroAngle,
+                                 units::meter_t leftDistance,
+                                 units::meter_t rightDistance,
+                                 const Pose2d& initialPose);
 
   /**
-   * Sets the pose estimator's trust of global measurements. This might be used
+   * Constructs a DifferentialDrivePoseEstimator.
+   *
+   * @param kinematics A correctly-configured kinematics object for your
+   *     drivetrain.
+   * @param gyroAngle The gyro angle of the robot.
+   * @param leftDistance The distance traveled by the left encoder.
+   * @param rightDistance The distance traveled by the right encoder.
+   * @param initialPose The estimated initial pose.
+   * @param stateStdDevs Standard deviations of the pose estimate (x position in
+   *     meters, y position in meters, and heading in radians). Increase these
+   *     numbers to trust your state estimate less.
+   * @param visionMeasurementStdDevs Standard deviations of the vision pose
+   *     measurement (x position in meters, y position in meters, and heading in
+   *     radians). Increase these numbers to trust the vision pose measurement
+   *     less.
+   */
+  DifferentialDrivePoseEstimator(
+      DifferentialDriveKinematics& kinematics, const Rotation2d& gyroAngle,
+      units::meter_t leftDistance, units::meter_t rightDistance,
+      const Pose2d& initialPose, const wpi::array<double, 3>& stateStdDevs,
+      const wpi::array<double, 3>& visionMeasurementStdDevs);
+
+  /**
+   * Sets the pose estimator's trust in vision measurements. This might be used
    * to change trust in vision measurements after the autonomous period, or to
    * change trust as distance to a vision target increases.
    *
-   * @param visionMeasurementStdDevs Standard deviations of the vision
-   *                                 measurements. Increase these numbers to
-   *                                 trust global measurements from vision
-   *                                 less. This matrix is in the form
-   *                                 [x, y, theta]ᵀ, with units in meters and
-   *                                 radians.
+   * @param visionMeasurementStdDevs Standard deviations of the vision pose
+   *     measurement (x position in meters, y position in meters, and heading in
+   *     radians). Increase these numbers to trust the vision pose measurement
+   *     less.
    */
   void SetVisionMeasurementStdDevs(
       const wpi::array<double, 3>& visionMeasurementStdDevs);
@@ -103,74 +95,71 @@
   /**
    * Resets the robot's position on the field.
    *
-   * You NEED to reset your encoders to zero when calling this method. The
-   * gyroscope angle does not need to be reset here on the user's robot code.
-   * The library automatically takes care of offsetting the gyro angle.
-   *
-   * @param pose The estimated pose of the robot on the field.
    * @param gyroAngle The current gyro angle.
+   * @param leftDistance The distance traveled by the left encoder.
+   * @param rightDistance The distance traveled by the right encoder.
+   * @param pose The estimated pose of the robot on the field.
    */
-  void ResetPosition(const Pose2d& pose, const Rotation2d& gyroAngle);
+  void ResetPosition(const Rotation2d& gyroAngle, units::meter_t leftDistance,
+                     units::meter_t rightDistance, const Pose2d& pose);
 
   /**
-   * Returns the pose of the robot at the current time as estimated by the
-   * Unscented Kalman Filter.
+   * Gets the estimated robot pose.
    *
    * @return The estimated robot pose.
    */
   Pose2d GetEstimatedPosition() const;
 
   /**
-   * Adds a vision measurement to the Unscented Kalman Filter. This will correct
+   * Adds a vision measurement to the Kalman Filter. This will correct
    * the odometry pose estimate while still accounting for measurement noise.
    *
    * This method can be called as infrequently as you want, as long as you are
    * calling Update() every loop.
    *
+   * To promote stability of the pose estimate and make it robust to bad vision
+   * data, we recommend only adding vision measurements that are already within
+   * one meter or so of the current pose estimate.
+   *
    * @param visionRobotPose The pose of the robot as measured by the vision
-   *                        camera.
-   * @param timestamp       The timestamp of the vision measurement in seconds.
-   *                        Note that if you don't use your own time source by
-   *                        calling UpdateWithTime(), then you must use a
-   *                        timestamp with an epoch since FPGA startup (i.e. the
-   *                        epoch of this timestamp is the same epoch as
-   *                        frc::Timer::GetFPGATimestamp(). This means that
-   *                        you should use frc::Timer::GetFPGATimestamp() as
-   *                        your time source in this case.
+   *     camera.
+   * @param timestamp The timestamp of the vision measurement in seconds. Note
+   *     that if you don't use your own time source by calling UpdateWithTime(),
+   *     then you must use a timestamp with an epoch since FPGA startup (i.e.,
+   *     the epoch of this timestamp is the same epoch as
+   *     frc::Timer::GetFPGATimestamp(). This means that you should use
+   *     frc::Timer::GetFPGATimestamp() as your time source in this case.
    */
   void AddVisionMeasurement(const Pose2d& visionRobotPose,
                             units::second_t timestamp);
 
   /**
-   * Adds a vision measurement to the Unscented Kalman Filter. This will correct
+   * Adds a vision measurement to the Kalman Filter. This will correct
    * the odometry pose estimate while still accounting for measurement noise.
    *
    * This method can be called as infrequently as you want, as long as you are
    * calling Update() every loop.
    *
+   * To promote stability of the pose estimate and make it robust to bad vision
+   * data, we recommend only adding vision measurements that are already within
+   * one meter or so of the current pose estimate.
+   *
    * Note that the vision measurement standard deviations passed into this
    * method will continue to apply to future measurements until a subsequent
    * call to SetVisionMeasurementStdDevs() or this method.
    *
-   * @param visionRobotPose          The pose of the robot as measured by the
-   *                                 vision camera.
-   * @param timestamp                The timestamp of the vision measurement in
-   *                                 seconds. Note that if you don't use your
-   *                                 own time source by calling
-   *                                 UpdateWithTime(), then you must use a
-   *                                 timestamp with an epoch since FPGA startup
-   *                                 (i.e. the epoch of this timestamp is the
-   *                                 same epoch as
-   *                                 frc::Timer::GetFPGATimestamp(). This means
-   *                                 that you should use
-   *                                 frc::Timer::GetFPGATimestamp() as your
-   *                                 time source in this case.
-   * @param visionMeasurementStdDevs Standard deviations of the vision
-   *                                 measurements. Increase these numbers to
-   *                                 trust global measurements from vision
-   *                                 less. This matrix is in the form
-   *                                 [x, y, theta]ᵀ, with units in meters and
-   *                                 radians.
+   * @param visionRobotPose The pose of the robot as measured by the vision
+   *     camera.
+   * @param timestamp The timestamp of the vision measurement in seconds. Note
+   *     that if you don't use your own time source by calling UpdateWithTime(),
+   *     then you must use a timestamp with an epoch since FPGA startup (i.e.,
+   *     the epoch of this timestamp is the same epoch as
+   *     frc::Timer::GetFPGATimestamp(). This means that you should use
+   *     frc::Timer::GetFPGATimestamp() as your time source in this case.
+   * @param visionMeasurementStdDevs Standard deviations of the vision pose
+   *     measurement (x position in meters, y position in meters, and heading in
+   *     radians). Increase these numbers to trust the vision pose measurement
+   *     less.
    */
   void AddVisionMeasurement(
       const Pose2d& visionRobotPose, units::second_t timestamp,
@@ -180,27 +169,24 @@
   }
 
   /**
-   * Updates the Unscented Kalman Filter using only wheel encoder information.
-   * Note that this should be called every loop iteration.
+   * Updates the pose estimator with wheel encoder and gyro information. This
+   * should be called every loop.
    *
    * @param gyroAngle     The current gyro angle.
-   * @param wheelSpeeds   The velocities of the wheels in meters per second.
    * @param leftDistance  The distance traveled by the left encoder.
    * @param rightDistance The distance traveled by the right encoder.
    *
    * @return The estimated pose of the robot.
    */
-  Pose2d Update(const Rotation2d& gyroAngle,
-                const DifferentialDriveWheelSpeeds& wheelSpeeds,
-                units::meter_t leftDistance, units::meter_t rightDistance);
+  Pose2d Update(const Rotation2d& gyroAngle, units::meter_t leftDistance,
+                units::meter_t rightDistance);
 
   /**
-   * Updates the Unscented Kalman Filter using only wheel encoder information.
-   * Note that this should be called every loop iteration.
+   * Updates the pose estimator with wheel encoder and gyro information. This
+   * should be called every loop.
    *
    * @param currentTime   The time at which this method was called.
    * @param gyroAngle     The current gyro angle.
-   * @param wheelSpeeds   The velocities of the wheels in meters per second.
    * @param leftDistance  The distance traveled by the left encoder.
    * @param rightDistance The distance traveled by the right encoder.
    *
@@ -208,35 +194,62 @@
    */
   Pose2d UpdateWithTime(units::second_t currentTime,
                         const Rotation2d& gyroAngle,
-                        const DifferentialDriveWheelSpeeds& wheelSpeeds,
                         units::meter_t leftDistance,
                         units::meter_t rightDistance);
 
  private:
-  UnscentedKalmanFilter<5, 3, 3> m_observer;
-  KalmanFilterLatencyCompensator<5, 3, 3, UnscentedKalmanFilter<5, 3, 3>>
-      m_latencyCompensator;
-  std::function<void(const Eigen::Vector<double, 3>& u,
-                     const Eigen::Vector<double, 3>& y)>
-      m_visionCorrect;
+  struct InterpolationRecord {
+    // The pose observed given the current sensor inputs and the previous pose.
+    Pose2d pose;
 
-  Eigen::Matrix<double, 3, 3> m_visionContR;
+    // The current gyro angle.
+    Rotation2d gyroAngle;
 
-  units::second_t m_nominalDt;
-  units::second_t m_prevTime = -1_s;
+    // The distance traveled by the left encoder.
+    units::meter_t leftDistance;
 
-  Rotation2d m_gyroOffset;
-  Rotation2d m_previousAngle;
+    // The distance traveled by the right encoder.
+    units::meter_t rightDistance;
 
-  template <int Dim>
-  static wpi::array<double, Dim> StdDevMatrixToArray(
-      const Eigen::Vector<double, Dim>& stdDevs);
+    /**
+     * Checks equality between this InterpolationRecord and another object.
+     *
+     * @param other The other object.
+     * @return Whether the two objects are equal.
+     */
+    bool operator==(const InterpolationRecord& other) const = default;
 
-  static Eigen::Vector<double, 5> F(const Eigen::Vector<double, 5>& x,
-                                    const Eigen::Vector<double, 3>& u);
-  static Eigen::Vector<double, 5> FillStateVector(const Pose2d& pose,
-                                                  units::meter_t leftDistance,
-                                                  units::meter_t rightDistance);
+    /**
+     * Checks inequality between this InterpolationRecord and another object.
+     *
+     * @param other The other object.
+     * @return Whether the two objects are not equal.
+     */
+    bool operator!=(const InterpolationRecord& other) const = default;
+
+    /**
+     * Interpolates between two InterpolationRecords.
+     *
+     * @param endValue The end value for the interpolation.
+     * @param i The interpolant (fraction).
+     *
+     * @return The interpolated state.
+     */
+    InterpolationRecord Interpolate(DifferentialDriveKinematics& kinematics,
+                                    InterpolationRecord endValue,
+                                    double i) const;
+  };
+
+  DifferentialDriveKinematics& m_kinematics;
+  DifferentialDriveOdometry m_odometry;
+  wpi::array<double, 3> m_q{wpi::empty_array};
+  Eigen::Matrix3d m_visionK = Eigen::Matrix3d::Zero();
+
+  TimeInterpolatableBuffer<InterpolationRecord> m_poseBuffer{
+      1.5_s, [this](const InterpolationRecord& start,
+                    const InterpolationRecord& end, double t) {
+        return start.Interpolate(this->m_kinematics, end, t);
+      }};
 };
 
 }  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/ExtendedKalmanFilter.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/ExtendedKalmanFilter.h
index 3e5edb8..b09e8d9 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/ExtendedKalmanFilter.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/ExtendedKalmanFilter.h
@@ -8,13 +8,7 @@
 
 #include <wpi/array.h>
 
-#include "Eigen/Cholesky"
-#include "Eigen/Core"
-#include "drake/math/discrete_algebraic_riccati_equation.h"
-#include "frc/StateSpaceUtil.h"
-#include "frc/system/Discretization.h"
-#include "frc/system/NumericalIntegration.h"
-#include "frc/system/NumericalJacobian.h"
+#include "frc/EigenCore.h"
 #include "units/time.h"
 
 namespace frc {
@@ -46,6 +40,15 @@
 template <int States, int Inputs, int Outputs>
 class ExtendedKalmanFilter {
  public:
+  using StateVector = Vectord<States>;
+  using InputVector = Vectord<Inputs>;
+  using OutputVector = Vectord<Outputs>;
+
+  using StateArray = wpi::array<double, States>;
+  using OutputArray = wpi::array<double, Outputs>;
+
+  using StateMatrix = Matrixd<States, States>;
+
   /**
    * Constructs an extended Kalman filter.
    *
@@ -57,52 +60,11 @@
    * @param measurementStdDevs Standard deviations of measurements.
    * @param dt                 Nominal discretization timestep.
    */
-  ExtendedKalmanFilter(std::function<Eigen::Vector<double, States>(
-                           const Eigen::Vector<double, States>&,
-                           const Eigen::Vector<double, Inputs>&)>
-                           f,
-                       std::function<Eigen::Vector<double, Outputs>(
-                           const Eigen::Vector<double, States>&,
-                           const Eigen::Vector<double, Inputs>&)>
-                           h,
-                       const wpi::array<double, States>& stateStdDevs,
-                       const wpi::array<double, Outputs>& measurementStdDevs,
-                       units::second_t dt)
-      : m_f(f), m_h(h) {
-    m_contQ = MakeCovMatrix(stateStdDevs);
-    m_contR = MakeCovMatrix(measurementStdDevs);
-    m_residualFuncY = [](auto a, auto b) -> Eigen::Vector<double, Outputs> {
-      return a - b;
-    };
-    m_addFuncX = [](auto a, auto b) -> Eigen::Vector<double, States> {
-      return a + b;
-    };
-    m_dt = dt;
-
-    Reset();
-
-    Eigen::Matrix<double, States, States> contA =
-        NumericalJacobianX<States, States, Inputs>(
-            m_f, m_xHat, Eigen::Vector<double, Inputs>::Zero());
-    Eigen::Matrix<double, Outputs, States> C =
-        NumericalJacobianX<Outputs, States, Inputs>(
-            m_h, m_xHat, Eigen::Vector<double, Inputs>::Zero());
-
-    Eigen::Matrix<double, States, States> discA;
-    Eigen::Matrix<double, States, States> discQ;
-    DiscretizeAQTaylor<States>(contA, m_contQ, dt, &discA, &discQ);
-
-    Eigen::Matrix<double, Outputs, Outputs> discR =
-        DiscretizeR<Outputs>(m_contR, dt);
-
-    if (IsDetectable<States, Outputs>(discA, C) && Outputs <= States) {
-      m_initP = drake::math::DiscreteAlgebraicRiccatiEquation(
-          discA.transpose(), C.transpose(), discQ, discR);
-    } else {
-      m_initP = Eigen::Matrix<double, States, States>::Zero();
-    }
-    m_P = m_initP;
-  }
+  ExtendedKalmanFilter(
+      std::function<StateVector(const StateVector&, const InputVector&)> f,
+      std::function<OutputVector(const StateVector&, const InputVector&)> h,
+      const StateArray& stateStdDevs, const OutputArray& measurementStdDevs,
+      units::second_t dt);
 
   /**
    * Constructs an extended Kalman filter.
@@ -118,59 +80,20 @@
    * @param addFuncX           A function that adds two state vectors.
    * @param dt                 Nominal discretization timestep.
    */
-  ExtendedKalmanFilter(std::function<Eigen::Vector<double, States>(
-                           const Eigen::Vector<double, States>&,
-                           const Eigen::Vector<double, Inputs>&)>
-                           f,
-                       std::function<Eigen::Vector<double, Outputs>(
-                           const Eigen::Vector<double, States>&,
-                           const Eigen::Vector<double, Inputs>&)>
-                           h,
-                       const wpi::array<double, States>& stateStdDevs,
-                       const wpi::array<double, Outputs>& measurementStdDevs,
-                       std::function<Eigen::Vector<double, Outputs>(
-                           const Eigen::Vector<double, Outputs>&,
-                           const Eigen::Vector<double, Outputs>&)>
-                           residualFuncY,
-                       std::function<Eigen::Vector<double, States>(
-                           const Eigen::Vector<double, States>&,
-                           const Eigen::Vector<double, States>&)>
-                           addFuncX,
-                       units::second_t dt)
-      : m_f(f), m_h(h), m_residualFuncY(residualFuncY), m_addFuncX(addFuncX) {
-    m_contQ = MakeCovMatrix(stateStdDevs);
-    m_contR = MakeCovMatrix(measurementStdDevs);
-    m_dt = dt;
-
-    Reset();
-
-    Eigen::Matrix<double, States, States> contA =
-        NumericalJacobianX<States, States, Inputs>(
-            m_f, m_xHat, Eigen::Vector<double, Inputs>::Zero());
-    Eigen::Matrix<double, Outputs, States> C =
-        NumericalJacobianX<Outputs, States, Inputs>(
-            m_h, m_xHat, Eigen::Vector<double, Inputs>::Zero());
-
-    Eigen::Matrix<double, States, States> discA;
-    Eigen::Matrix<double, States, States> discQ;
-    DiscretizeAQTaylor<States>(contA, m_contQ, dt, &discA, &discQ);
-
-    Eigen::Matrix<double, Outputs, Outputs> discR =
-        DiscretizeR<Outputs>(m_contR, dt);
-
-    if (IsDetectable<States, Outputs>(discA, C) && Outputs <= States) {
-      m_initP = drake::math::DiscreteAlgebraicRiccatiEquation(
-          discA.transpose(), C.transpose(), discQ, discR);
-    } else {
-      m_initP = Eigen::Matrix<double, States, States>::Zero();
-    }
-    m_P = m_initP;
-  }
+  ExtendedKalmanFilter(
+      std::function<StateVector(const StateVector&, const InputVector&)> f,
+      std::function<OutputVector(const StateVector&, const InputVector&)> h,
+      const StateArray& stateStdDevs, const OutputArray& measurementStdDevs,
+      std::function<OutputVector(const OutputVector&, const OutputVector&)>
+          residualFuncY,
+      std::function<StateVector(const StateVector&, const StateVector&)>
+          addFuncX,
+      units::second_t dt);
 
   /**
    * Returns the error covariance matrix P.
    */
-  const Eigen::Matrix<double, States, States>& P() const { return m_P; }
+  const StateMatrix& P() const { return m_P; }
 
   /**
    * Returns an element of the error covariance matrix P.
@@ -185,26 +108,26 @@
    *
    * @param P The error covariance matrix P.
    */
-  void SetP(const Eigen::Matrix<double, States, States>& P) { m_P = P; }
+  void SetP(const StateMatrix& P) { m_P = P; }
 
   /**
    * Returns the state estimate x-hat.
    */
-  const Eigen::Vector<double, States>& Xhat() const { return m_xHat; }
+  const StateVector& Xhat() const { return m_xHat; }
 
   /**
    * Returns an element of the state estimate x-hat.
    *
    * @param i Row of x-hat.
    */
-  double Xhat(int i) const { return m_xHat(i, 0); }
+  double Xhat(int i) const { return m_xHat(i); }
 
   /**
    * Set initial state estimate x-hat.
    *
    * @param xHat The state estimate x-hat.
    */
-  void SetXhat(const Eigen::Vector<double, States>& xHat) { m_xHat = xHat; }
+  void SetXhat(const StateVector& xHat) { m_xHat = xHat; }
 
   /**
    * Set an element of the initial state estimate x-hat.
@@ -212,7 +135,7 @@
    * @param i     Row of x-hat.
    * @param value Value for element of x-hat.
    */
-  void SetXhat(int i, double value) { m_xHat(i, 0) = value; }
+  void SetXhat(int i, double value) { m_xHat(i) = value; }
 
   /**
    * Resets the observer.
@@ -228,23 +151,7 @@
    * @param u  New control input from controller.
    * @param dt Timestep for prediction.
    */
-  void Predict(const Eigen::Vector<double, Inputs>& u, units::second_t dt) {
-    // Find continuous A
-    Eigen::Matrix<double, States, States> contA =
-        NumericalJacobianX<States, States, Inputs>(m_f, m_xHat, u);
-
-    // Find discrete A and Q
-    Eigen::Matrix<double, States, States> discA;
-    Eigen::Matrix<double, States, States> discQ;
-    DiscretizeAQTaylor<States>(contA, m_contQ, dt, &discA, &discQ);
-
-    m_xHat = RK4(m_f, m_xHat, u, dt);
-
-    // Pₖ₊₁⁻ = APₖ⁻Aᵀ + Q
-    m_P = discA * m_P * discA.transpose() + discQ;
-
-    m_dt = dt;
-  }
+  void Predict(const InputVector& u, units::second_t dt);
 
   /**
    * Correct the state estimate x-hat using the measurements in y.
@@ -252,27 +159,15 @@
    * @param u Same control input used in the predict step.
    * @param y Measurement vector.
    */
-  void Correct(const Eigen::Vector<double, Inputs>& u,
-               const Eigen::Vector<double, Outputs>& y) {
+  void Correct(const InputVector& u, const OutputVector& y) {
     Correct<Outputs>(u, y, m_h, m_contR, m_residualFuncY, m_addFuncX);
   }
 
   template <int Rows>
-  void Correct(const Eigen::Vector<double, Inputs>& u,
-               const Eigen::Vector<double, Rows>& y,
-               std::function<Eigen::Vector<double, Rows>(
-                   const Eigen::Vector<double, States>&,
-                   const Eigen::Vector<double, Inputs>&)>
-                   h,
-               const Eigen::Matrix<double, Rows, Rows>& R) {
-    auto residualFuncY = [](auto a, auto b) -> Eigen::Vector<double, Rows> {
-      return a - b;
-    };
-    auto addFuncX = [](auto a, auto b) -> Eigen::Vector<double, States> {
-      return a + b;
-    };
-    Correct<Rows>(u, y, h, R, residualFuncY, addFuncX);
-  }
+  void Correct(
+      const InputVector& u, const Vectord<Rows>& y,
+      std::function<Vectord<Rows>(const StateVector&, const InputVector&)> h,
+      const Matrixd<Rows, Rows>& R);
 
   /**
    * Correct the state estimate x-hat using the measurements in y.
@@ -291,73 +186,30 @@
    * @param addFuncX      A function that adds two state vectors.
    */
   template <int Rows>
-  void Correct(const Eigen::Vector<double, Inputs>& u,
-               const Eigen::Vector<double, Rows>& y,
-               std::function<Eigen::Vector<double, Rows>(
-                   const Eigen::Vector<double, States>&,
-                   const Eigen::Vector<double, Inputs>&)>
-                   h,
-               const Eigen::Matrix<double, Rows, Rows>& R,
-               std::function<Eigen::Vector<double, Rows>(
-                   const Eigen::Vector<double, Rows>&,
-                   const Eigen::Vector<double, Rows>&)>
-                   residualFuncY,
-               std::function<Eigen::Vector<double, States>(
-                   const Eigen::Vector<double, States>&,
-                   const Eigen::Vector<double, States>)>
-                   addFuncX) {
-    const Eigen::Matrix<double, Rows, States> C =
-        NumericalJacobianX<Rows, States, Inputs>(h, m_xHat, u);
-    const Eigen::Matrix<double, Rows, Rows> discR = DiscretizeR<Rows>(R, m_dt);
-
-    Eigen::Matrix<double, Rows, Rows> S = C * m_P * C.transpose() + discR;
-
-    // We want to put K = PCᵀS⁻¹ into Ax = b form so we can solve it more
-    // efficiently.
-    //
-    // K = PCᵀS⁻¹
-    // KS = PCᵀ
-    // (KS)ᵀ = (PCᵀ)ᵀ
-    // SᵀKᵀ = CPᵀ
-    //
-    // The solution of Ax = b can be found via x = A.solve(b).
-    //
-    // Kᵀ = Sᵀ.solve(CPᵀ)
-    // K = (Sᵀ.solve(CPᵀ))ᵀ
-    Eigen::Matrix<double, States, Rows> K =
-        S.transpose().ldlt().solve(C * m_P.transpose()).transpose();
-
-    // x̂ₖ₊₁⁺ = x̂ₖ₊₁⁻ + K(y − h(x̂ₖ₊₁⁻, uₖ₊₁))
-    m_xHat = addFuncX(m_xHat, K * residualFuncY(y, h(m_xHat, u)));
-
-    // Pₖ₊₁⁺ = (I − KC)Pₖ₊₁⁻
-    m_P = (Eigen::Matrix<double, States, States>::Identity() - K * C) * m_P;
-  }
+  void Correct(
+      const InputVector& u, const Vectord<Rows>& y,
+      std::function<Vectord<Rows>(const StateVector&, const InputVector&)> h,
+      const Matrixd<Rows, Rows>& R,
+      std::function<Vectord<Rows>(const Vectord<Rows>&, const Vectord<Rows>&)>
+          residualFuncY,
+      std::function<StateVector(const StateVector&, const StateVector&)>
+          addFuncX);
 
  private:
-  std::function<Eigen::Vector<double, States>(
-      const Eigen::Vector<double, States>&,
-      const Eigen::Vector<double, Inputs>&)>
-      m_f;
-  std::function<Eigen::Vector<double, Outputs>(
-      const Eigen::Vector<double, States>&,
-      const Eigen::Vector<double, Inputs>&)>
-      m_h;
-  std::function<Eigen::Vector<double, Outputs>(
-      const Eigen::Vector<double, Outputs>&,
-      const Eigen::Vector<double, Outputs>)>
+  std::function<StateVector(const StateVector&, const InputVector&)> m_f;
+  std::function<OutputVector(const StateVector&, const InputVector&)> m_h;
+  std::function<OutputVector(const OutputVector&, const OutputVector&)>
       m_residualFuncY;
-  std::function<Eigen::Vector<double, States>(
-      const Eigen::Vector<double, States>&,
-      const Eigen::Vector<double, States>)>
-      m_addFuncX;
-  Eigen::Vector<double, States> m_xHat;
-  Eigen::Matrix<double, States, States> m_P;
-  Eigen::Matrix<double, States, States> m_contQ;
-  Eigen::Matrix<double, Outputs, Outputs> m_contR;
+  std::function<StateVector(const StateVector&, const StateVector&)> m_addFuncX;
+  StateVector m_xHat;
+  StateMatrix m_P;
+  StateMatrix m_contQ;
+  Matrixd<Outputs, Outputs> m_contR;
   units::second_t m_dt;
 
-  Eigen::Matrix<double, States, States> m_initP;
+  StateMatrix m_initP;
 };
 
 }  // namespace frc
+
+#include "ExtendedKalmanFilter.inc"
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/ExtendedKalmanFilter.inc b/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/ExtendedKalmanFilter.inc
new file mode 100644
index 0000000..a56b8b5
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/ExtendedKalmanFilter.inc
@@ -0,0 +1,160 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include "Eigen/Cholesky"
+#include "drake/math/discrete_algebraic_riccati_equation.h"
+#include "frc/StateSpaceUtil.h"
+#include "frc/estimator/ExtendedKalmanFilter.h"
+#include "frc/system/Discretization.h"
+#include "frc/system/NumericalIntegration.h"
+#include "frc/system/NumericalJacobian.h"
+
+namespace frc {
+
+template <int States, int Inputs, int Outputs>
+ExtendedKalmanFilter<States, Inputs, Outputs>::ExtendedKalmanFilter(
+    std::function<StateVector(const StateVector&, const InputVector&)> f,
+    std::function<OutputVector(const StateVector&, const InputVector&)> h,
+    const StateArray& stateStdDevs, const OutputArray& measurementStdDevs,
+    units::second_t dt)
+    : m_f(f), m_h(h) {
+  m_contQ = MakeCovMatrix(stateStdDevs);
+  m_contR = MakeCovMatrix(measurementStdDevs);
+  m_residualFuncY = [](auto a, auto b) -> OutputVector { return a - b; };
+  m_addFuncX = [](auto a, auto b) -> StateVector { return a + b; };
+  m_dt = dt;
+
+  Reset();
+
+  StateMatrix contA = NumericalJacobianX<States, States, Inputs>(
+      m_f, m_xHat, InputVector::Zero());
+  Matrixd<Outputs, States> C = NumericalJacobianX<Outputs, States, Inputs>(
+      m_h, m_xHat, InputVector::Zero());
+
+  StateMatrix discA;
+  StateMatrix discQ;
+  DiscretizeAQTaylor<States>(contA, m_contQ, dt, &discA, &discQ);
+
+  Matrixd<Outputs, Outputs> discR = DiscretizeR<Outputs>(m_contR, dt);
+
+  if (IsDetectable<States, Outputs>(discA, C) && Outputs <= States) {
+    m_initP = drake::math::DiscreteAlgebraicRiccatiEquation(
+        discA.transpose(), C.transpose(), discQ, discR);
+  } else {
+    m_initP = StateMatrix::Zero();
+  }
+  m_P = m_initP;
+}
+
+template <int States, int Inputs, int Outputs>
+ExtendedKalmanFilter<States, Inputs, Outputs>::ExtendedKalmanFilter(
+    std::function<StateVector(const StateVector&, const InputVector&)> f,
+    std::function<OutputVector(const StateVector&, const InputVector&)> h,
+    const StateArray& stateStdDevs, const OutputArray& measurementStdDevs,
+    std::function<OutputVector(const OutputVector&, const OutputVector&)>
+        residualFuncY,
+    std::function<StateVector(const StateVector&, const StateVector&)> addFuncX,
+    units::second_t dt)
+    : m_f(f), m_h(h), m_residualFuncY(residualFuncY), m_addFuncX(addFuncX) {
+  m_contQ = MakeCovMatrix(stateStdDevs);
+  m_contR = MakeCovMatrix(measurementStdDevs);
+  m_dt = dt;
+
+  Reset();
+
+  StateMatrix contA = NumericalJacobianX<States, States, Inputs>(
+      m_f, m_xHat, InputVector::Zero());
+  Matrixd<Outputs, States> C = NumericalJacobianX<Outputs, States, Inputs>(
+      m_h, m_xHat, InputVector::Zero());
+
+  StateMatrix discA;
+  StateMatrix discQ;
+  DiscretizeAQTaylor<States>(contA, m_contQ, dt, &discA, &discQ);
+
+  Matrixd<Outputs, Outputs> discR = DiscretizeR<Outputs>(m_contR, dt);
+
+  if (IsDetectable<States, Outputs>(discA, C) && Outputs <= States) {
+    m_initP = drake::math::DiscreteAlgebraicRiccatiEquation(
+        discA.transpose(), C.transpose(), discQ, discR);
+  } else {
+    m_initP = StateMatrix::Zero();
+  }
+  m_P = m_initP;
+}
+
+template <int States, int Inputs, int Outputs>
+void ExtendedKalmanFilter<States, Inputs, Outputs>::Predict(
+    const InputVector& u, units::second_t dt) {
+  // Find continuous A
+  StateMatrix contA =
+      NumericalJacobianX<States, States, Inputs>(m_f, m_xHat, u);
+
+  // Find discrete A and Q
+  StateMatrix discA;
+  StateMatrix discQ;
+  DiscretizeAQTaylor<States>(contA, m_contQ, dt, &discA, &discQ);
+
+  m_xHat = RK4(m_f, m_xHat, u, dt);
+
+  // Pₖ₊₁⁻ = APₖ⁻Aᵀ + Q
+  m_P = discA * m_P * discA.transpose() + discQ;
+
+  m_dt = dt;
+}
+
+template <int States, int Inputs, int Outputs>
+template <int Rows>
+void ExtendedKalmanFilter<States, Inputs, Outputs>::Correct(
+    const InputVector& u, const Vectord<Rows>& y,
+    std::function<Vectord<Rows>(const StateVector&, const InputVector&)> h,
+    const Matrixd<Rows, Rows>& R) {
+  auto residualFuncY = [](auto a, auto b) -> Vectord<Rows> { return a - b; };
+  auto addFuncX = [](auto a, auto b) -> StateVector { return a + b; };
+  Correct<Rows>(u, y, h, R, residualFuncY, addFuncX);
+}
+
+template <int States, int Inputs, int Outputs>
+template <int Rows>
+void ExtendedKalmanFilter<States, Inputs, Outputs>::Correct(
+    const InputVector& u, const Vectord<Rows>& y,
+    std::function<Vectord<Rows>(const StateVector&, const InputVector&)> h,
+    const Matrixd<Rows, Rows>& R,
+    std::function<Vectord<Rows>(const Vectord<Rows>&, const Vectord<Rows>&)>
+        residualFuncY,
+    std::function<StateVector(const StateVector&, const StateVector&)>
+        addFuncX) {
+  const Matrixd<Rows, States> C =
+      NumericalJacobianX<Rows, States, Inputs>(h, m_xHat, u);
+  const Matrixd<Rows, Rows> discR = DiscretizeR<Rows>(R, m_dt);
+
+  Matrixd<Rows, Rows> S = C * m_P * C.transpose() + discR;
+
+  // We want to put K = PCᵀS⁻¹ into Ax = b form so we can solve it more
+  // efficiently.
+  //
+  // K = PCᵀS⁻¹
+  // KS = PCᵀ
+  // (KS)ᵀ = (PCᵀ)ᵀ
+  // SᵀKᵀ = CPᵀ
+  //
+  // The solution of Ax = b can be found via x = A.solve(b).
+  //
+  // Kᵀ = Sᵀ.solve(CPᵀ)
+  // K = (Sᵀ.solve(CPᵀ))ᵀ
+  Matrixd<States, Rows> K =
+      S.transpose().ldlt().solve(C * m_P.transpose()).transpose();
+
+  // x̂ₖ₊₁⁺ = x̂ₖ₊₁⁻ + Kₖ₊₁(y − h(x̂ₖ₊₁⁻, uₖ₊₁))
+  m_xHat = addFuncX(m_xHat, K * residualFuncY(y, h(m_xHat, u)));
+
+  // Pₖ₊₁⁺ = (I−Kₖ₊₁C)Pₖ₊₁⁻(I−Kₖ₊₁C)ᵀ + Kₖ₊₁RKₖ₊₁ᵀ
+  // Use Joseph form for numerical stability
+  m_P = (StateMatrix::Identity() - K * C) * m_P *
+            (StateMatrix::Identity() - K * C).transpose() +
+        K * discR * K.transpose();
+}
+
+}  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/KalmanFilter.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/KalmanFilter.h
index 3aa4dbd..2121284 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/KalmanFilter.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/KalmanFilter.h
@@ -4,25 +4,14 @@
 
 #pragma once
 
-#include <frc/fmt/Eigen.h>
-
-#include <cmath>
-#include <string>
-
 #include <wpi/SymbolExports.h>
 #include <wpi/array.h>
 
-#include "Eigen/Cholesky"
-#include "Eigen/Core"
-#include "drake/math/discrete_algebraic_riccati_equation.h"
-#include "frc/StateSpaceUtil.h"
-#include "frc/system/Discretization.h"
+#include "frc/EigenCore.h"
 #include "frc/system/LinearSystem.h"
 #include "units/time.h"
-#include "wpimath/MathShared.h"
 
 namespace frc {
-namespace detail {
 
 /**
  * A Kalman filter combines predictions from a model and measurements to give an
@@ -45,8 +34,15 @@
  * @tparam Outputs The number of outputs.
  */
 template <int States, int Inputs, int Outputs>
-class KalmanFilterImpl {
+class KalmanFilter {
  public:
+  using StateVector = Vectord<States>;
+  using InputVector = Vectord<Inputs>;
+  using OutputVector = Vectord<Outputs>;
+
+  using StateArray = wpi::array<double, States>;
+  using OutputArray = wpi::array<double, Outputs>;
+
   /**
    * Constructs a state-space observer with the given plant.
    *
@@ -54,65 +50,19 @@
    * @param stateStdDevs       Standard deviations of model states.
    * @param measurementStdDevs Standard deviations of measurements.
    * @param dt                 Nominal discretization timestep.
+   * @throws std::invalid_argument If the system is unobservable.
    */
-  KalmanFilterImpl(LinearSystem<States, Inputs, Outputs>& plant,
-                   const wpi::array<double, States>& stateStdDevs,
-                   const wpi::array<double, Outputs>& measurementStdDevs,
-                   units::second_t dt) {
-    m_plant = &plant;
+  KalmanFilter(LinearSystem<States, Inputs, Outputs>& plant,
+               const StateArray& stateStdDevs,
+               const OutputArray& measurementStdDevs, units::second_t dt);
 
-    auto contQ = MakeCovMatrix(stateStdDevs);
-    auto contR = MakeCovMatrix(measurementStdDevs);
-
-    Eigen::Matrix<double, States, States> discA;
-    Eigen::Matrix<double, States, States> discQ;
-    DiscretizeAQTaylor<States>(plant.A(), contQ, dt, &discA, &discQ);
-
-    auto discR = DiscretizeR<Outputs>(contR, dt);
-
-    const auto& C = plant.C();
-
-    if (!IsDetectable<States, Outputs>(discA, C)) {
-      std::string msg = fmt::format(
-          "The system passed to the Kalman filter is "
-          "unobservable!\n\nA =\n{}\nC =\n{}\n",
-          discA, C);
-
-      wpi::math::MathSharedStore::ReportError(msg);
-      throw std::invalid_argument(msg);
-    }
-
-    Eigen::Matrix<double, States, States> P =
-        drake::math::DiscreteAlgebraicRiccatiEquation(
-            discA.transpose(), C.transpose(), discQ, discR);
-
-    // S = CPCᵀ + R
-    Eigen::Matrix<double, Outputs, Outputs> S = C * P * C.transpose() + discR;
-
-    // We want to put K = PCᵀS⁻¹ into Ax = b form so we can solve it more
-    // efficiently.
-    //
-    // K = PCᵀS⁻¹
-    // KS = PCᵀ
-    // (KS)ᵀ = (PCᵀ)ᵀ
-    // SᵀKᵀ = CPᵀ
-    //
-    // The solution of Ax = b can be found via x = A.solve(b).
-    //
-    // Kᵀ = Sᵀ.solve(CPᵀ)
-    // K = (Sᵀ.solve(CPᵀ))ᵀ
-    m_K = S.transpose().ldlt().solve(C * P.transpose()).transpose();
-
-    Reset();
-  }
-
-  KalmanFilterImpl(KalmanFilterImpl&&) = default;
-  KalmanFilterImpl& operator=(KalmanFilterImpl&&) = default;
+  KalmanFilter(KalmanFilter&&) = default;
+  KalmanFilter& operator=(KalmanFilter&&) = default;
 
   /**
    * Returns the steady-state Kalman gain matrix K.
    */
-  const Eigen::Matrix<double, States, Outputs>& K() const { return m_K; }
+  const Matrixd<States, Outputs>& K() const { return m_K; }
 
   /**
    * Returns an element of the steady-state Kalman gain matrix K.
@@ -125,7 +75,7 @@
   /**
    * Returns the state estimate x-hat.
    */
-  const Eigen::Vector<double, States>& Xhat() const { return m_xHat; }
+  const StateVector& Xhat() const { return m_xHat; }
 
   /**
    * Returns an element of the state estimate x-hat.
@@ -139,7 +89,7 @@
    *
    * @param xHat The state estimate x-hat.
    */
-  void SetXhat(const Eigen::Vector<double, States>& xHat) { m_xHat = xHat; }
+  void SetXhat(const StateVector& xHat) { m_xHat = xHat; }
 
   /**
    * Set an element of the initial state estimate x-hat.
@@ -160,9 +110,7 @@
    * @param u  New control input from controller.
    * @param dt Timestep for prediction.
    */
-  void Predict(const Eigen::Vector<double, Inputs>& u, units::second_t dt) {
-    m_xHat = m_plant->CalculateX(m_xHat, u, dt);
-  }
+  void Predict(const InputVector& u, units::second_t dt);
 
   /**
    * Correct the state estimate x-hat using the measurements in y.
@@ -170,11 +118,7 @@
    * @param u Same control input used in the last predict step.
    * @param y Measurement vector.
    */
-  void Correct(const Eigen::Vector<double, Inputs>& u,
-               const Eigen::Vector<double, Outputs>& y) {
-    // x̂ₖ₊₁⁺ = x̂ₖ₊₁⁻ + K(y − (Cx̂ₖ₊₁⁻ + Duₖ₊₁))
-    m_xHat += m_K * (y - (m_plant->C() * m_xHat + m_plant->D() * u));
-  }
+  void Correct(const InputVector& u, const OutputVector& y);
 
  private:
   LinearSystem<States, Inputs, Outputs>* m_plant;
@@ -182,66 +126,19 @@
   /**
    * The steady-state Kalman gain matrix.
    */
-  Eigen::Matrix<double, States, Outputs> m_K;
+  Matrixd<States, Outputs> m_K;
 
   /**
    * The state estimate.
    */
-  Eigen::Vector<double, States> m_xHat;
+  StateVector m_xHat;
 };
 
-}  // namespace detail
-
-template <int States, int Inputs, int Outputs>
-class KalmanFilter : public detail::KalmanFilterImpl<States, Inputs, Outputs> {
- public:
-  /**
-   * Constructs a state-space observer with the given plant.
-   *
-   * @param plant              The plant used for the prediction step.
-   * @param stateStdDevs       Standard deviations of model states.
-   * @param measurementStdDevs Standard deviations of measurements.
-   * @param dt                 Nominal discretization timestep.
-   */
-  KalmanFilter(LinearSystem<States, Inputs, Outputs>& plant,
-               const wpi::array<double, States>& stateStdDevs,
-               const wpi::array<double, Outputs>& measurementStdDevs,
-               units::second_t dt)
-      : detail::KalmanFilterImpl<States, Inputs, Outputs>{
-            plant, stateStdDevs, measurementStdDevs, dt} {}
-
-  KalmanFilter(KalmanFilter&&) = default;
-  KalmanFilter& operator=(KalmanFilter&&) = default;
-};
-
-// Template specializations are used here to make common state-input-output
-// triplets compile faster.
-template <>
-class WPILIB_DLLEXPORT KalmanFilter<1, 1, 1>
-    : public detail::KalmanFilterImpl<1, 1, 1> {
- public:
-  KalmanFilter(LinearSystem<1, 1, 1>& plant,
-               const wpi::array<double, 1>& stateStdDevs,
-               const wpi::array<double, 1>& measurementStdDevs,
-               units::second_t dt);
-
-  KalmanFilter(KalmanFilter&&) = default;
-  KalmanFilter& operator=(KalmanFilter&&) = default;
-};
-
-// Template specializations are used here to make common state-input-output
-// triplets compile faster.
-template <>
-class WPILIB_DLLEXPORT KalmanFilter<2, 1, 1>
-    : public detail::KalmanFilterImpl<2, 1, 1> {
- public:
-  KalmanFilter(LinearSystem<2, 1, 1>& plant,
-               const wpi::array<double, 2>& stateStdDevs,
-               const wpi::array<double, 1>& measurementStdDevs,
-               units::second_t dt);
-
-  KalmanFilter(KalmanFilter&&) = default;
-  KalmanFilter& operator=(KalmanFilter&&) = default;
-};
+extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
+    KalmanFilter<1, 1, 1>;
+extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
+    KalmanFilter<2, 1, 1>;
 
 }  // namespace frc
+
+#include "KalmanFilter.inc"
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/KalmanFilter.inc b/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/KalmanFilter.inc
new file mode 100644
index 0000000..ca4f37c
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/KalmanFilter.inc
@@ -0,0 +1,86 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <frc/fmt/Eigen.h>
+
+#include <cmath>
+#include <stdexcept>
+#include <string>
+
+#include "Eigen/Cholesky"
+#include "drake/math/discrete_algebraic_riccati_equation.h"
+#include "frc/StateSpaceUtil.h"
+#include "frc/estimator/KalmanFilter.h"
+#include "frc/system/Discretization.h"
+#include "wpimath/MathShared.h"
+
+namespace frc {
+
+template <int States, int Inputs, int Outputs>
+KalmanFilter<States, Inputs, Outputs>::KalmanFilter(
+    LinearSystem<States, Inputs, Outputs>& plant,
+    const StateArray& stateStdDevs, const OutputArray& measurementStdDevs,
+    units::second_t dt) {
+  m_plant = &plant;
+
+  auto contQ = MakeCovMatrix(stateStdDevs);
+  auto contR = MakeCovMatrix(measurementStdDevs);
+
+  Matrixd<States, States> discA;
+  Matrixd<States, States> discQ;
+  DiscretizeAQTaylor<States>(plant.A(), contQ, dt, &discA, &discQ);
+
+  auto discR = DiscretizeR<Outputs>(contR, dt);
+
+  const auto& C = plant.C();
+
+  if (!IsDetectable<States, Outputs>(discA, C)) {
+    std::string msg = fmt::format(
+        "The system passed to the Kalman filter is "
+        "unobservable!\n\nA =\n{}\nC =\n{}\n",
+        discA, C);
+
+    wpi::math::MathSharedStore::ReportError(msg);
+    throw std::invalid_argument(msg);
+  }
+
+  Matrixd<States, States> P = drake::math::DiscreteAlgebraicRiccatiEquation(
+      discA.transpose(), C.transpose(), discQ, discR);
+
+  // S = CPCᵀ + R
+  Matrixd<Outputs, Outputs> S = C * P * C.transpose() + discR;
+
+  // We want to put K = PCᵀS⁻¹ into Ax = b form so we can solve it more
+  // efficiently.
+  //
+  // K = PCᵀS⁻¹
+  // KS = PCᵀ
+  // (KS)ᵀ = (PCᵀ)ᵀ
+  // SᵀKᵀ = CPᵀ
+  //
+  // The solution of Ax = b can be found via x = A.solve(b).
+  //
+  // Kᵀ = Sᵀ.solve(CPᵀ)
+  // K = (Sᵀ.solve(CPᵀ))ᵀ
+  m_K = S.transpose().ldlt().solve(C * P.transpose()).transpose();
+
+  Reset();
+}
+
+template <int States, int Inputs, int Outputs>
+void KalmanFilter<States, Inputs, Outputs>::Predict(const InputVector& u,
+                                                    units::second_t dt) {
+  m_xHat = m_plant->CalculateX(m_xHat, u, dt);
+}
+
+template <int States, int Inputs, int Outputs>
+void KalmanFilter<States, Inputs, Outputs>::Correct(const InputVector& u,
+                                                    const OutputVector& y) {
+  // x̂ₖ₊₁⁺ = x̂ₖ₊₁⁻ + K(y − (Cx̂ₖ₊₁⁻ + Duₖ₊₁))
+  m_xHat += m_K * (y - (m_plant->C() * m_xHat + m_plant->D() * u));
+}
+
+}  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/KalmanFilterLatencyCompensator.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/KalmanFilterLatencyCompensator.h
index 5cb8eb2..d6e4127 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/KalmanFilterLatencyCompensator.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/KalmanFilterLatencyCompensator.h
@@ -10,7 +10,7 @@
 #include <utility>
 #include <vector>
 
-#include "Eigen/Core"
+#include "frc/EigenCore.h"
 #include "units/math.h"
 #include "units/time.h"
 
@@ -20,16 +20,15 @@
 class KalmanFilterLatencyCompensator {
  public:
   struct ObserverSnapshot {
-    Eigen::Vector<double, States> xHat;
-    Eigen::Matrix<double, States, States> errorCovariances;
-    Eigen::Vector<double, Inputs> inputs;
-    Eigen::Vector<double, Outputs> localMeasurements;
+    Vectord<States> xHat;
+    Matrixd<States, States> squareRootErrorCovariances;
+    Vectord<Inputs> inputs;
+    Vectord<Outputs> localMeasurements;
 
-    ObserverSnapshot(const KalmanFilterType& observer,
-                     const Eigen::Vector<double, Inputs>& u,
-                     const Eigen::Vector<double, Outputs>& localY)
+    ObserverSnapshot(const KalmanFilterType& observer, const Vectord<Inputs>& u,
+                     const Vectord<Outputs>& localY)
         : xHat(observer.Xhat()),
-          errorCovariances(observer.P()),
+          squareRootErrorCovariances(observer.S()),
           inputs(u),
           localMeasurements(localY) {}
   };
@@ -47,10 +46,8 @@
    * @param localY    The local output at the timestamp
    * @param timestamp The timesnap of the state.
    */
-  void AddObserverState(const KalmanFilterType& observer,
-                        Eigen::Vector<double, Inputs> u,
-                        Eigen::Vector<double, Outputs> localY,
-                        units::second_t timestamp) {
+  void AddObserverState(const KalmanFilterType& observer, Vectord<Inputs> u,
+                        Vectord<Outputs> localY, units::second_t timestamp) {
     // Add the new state into the vector.
     m_pastObserverSnapshots.emplace_back(timestamp,
                                          ObserverSnapshot{observer, u, localY});
@@ -74,10 +71,8 @@
    */
   template <int Rows>
   void ApplyPastGlobalMeasurement(
-      KalmanFilterType* observer, units::second_t nominalDt,
-      Eigen::Vector<double, Rows> y,
-      std::function<void(const Eigen::Vector<double, Inputs>& u,
-                         const Eigen::Vector<double, Rows>& y)>
+      KalmanFilterType* observer, units::second_t nominalDt, Vectord<Rows> y,
+      std::function<void(const Vectord<Inputs>& u, const Vectord<Rows>& y)>
           globalMeasurementCorrect,
       units::second_t timestamp) {
     if (m_pastObserverSnapshots.size() == 0) {
@@ -140,7 +135,7 @@
       auto& [key, snapshot] = m_pastObserverSnapshots[i];
 
       if (i == indexOfClosestEntry) {
-        observer->SetP(snapshot.errorCovariances);
+        observer->SetS(snapshot.squareRootErrorCovariances);
         observer->SetXhat(snapshot.xHat);
       }
 
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/MecanumDrivePoseEstimator.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/MecanumDrivePoseEstimator.h
index e9817ef..d1967e9 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/MecanumDrivePoseEstimator.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/MecanumDrivePoseEstimator.h
@@ -9,89 +9,82 @@
 #include <wpi/SymbolExports.h>
 #include <wpi/array.h>
 
-#include "Eigen/Core"
-#include "frc/estimator/KalmanFilterLatencyCompensator.h"
-#include "frc/estimator/UnscentedKalmanFilter.h"
+#include "frc/EigenCore.h"
 #include "frc/geometry/Pose2d.h"
 #include "frc/geometry/Rotation2d.h"
+#include "frc/interpolation/TimeInterpolatableBuffer.h"
 #include "frc/kinematics/MecanumDriveKinematics.h"
+#include "frc/kinematics/MecanumDriveOdometry.h"
 #include "units/time.h"
 
 namespace frc {
 /**
- * This class wraps an Unscented Kalman Filter to fuse latency-compensated
+ * This class wraps Mecanum Drive Odometry to fuse latency-compensated
  * vision measurements with mecanum drive encoder velocity measurements. It will
  * correct for noisy measurements and encoder drift. It is intended to be an
- * easy but more accurate drop-in for MecanumDriveOdometry.
+ * easy drop-in for MecanumDriveOdometry.
  *
  * Update() should be called every robot loop. If your loops are faster or
- * slower than the default of 0.02s, then you should change the nominal delta
+ * slower than the default of 20 ms, then you should change the nominal delta
  * time by specifying it in the constructor.
  *
  * AddVisionMeasurement() can be called as infrequently as you want; if you
  * never call it, then this class will behave mostly like regular encoder
  * odometry.
- *
- * The state-space system used internally has the following states (x), inputs
- * (u), and outputs (y):
- *
- * <strong> x = [x, y, theta]ᵀ </strong> in the field coordinate system
- * containing x position, y position, and heading.
- *
- * <strong> u = [v_x, v_y, omega]ᵀ </strong> containing x velocity, y velocity,
- * and angular velocity in the field coordinate system.
- *
- * <strong> y = [x, y, theta]ᵀ </strong> from vision containing x position, y
- * position, and heading; or <strong> y = [theta]ᵀ </strong> containing gyro
- * heading.
  */
 class WPILIB_DLLEXPORT MecanumDrivePoseEstimator {
  public:
   /**
-   * Constructs a MecanumDrivePoseEstimator.
+   * Constructs a MecanumDrivePoseEstimator with default standard deviations
+   * for the model and vision measurements.
    *
-   * @param gyroAngle                The current gyro angle.
-   * @param initialPose              The starting pose estimate.
-   * @param kinematics               A correctly-configured kinematics object
-   *                                 for your drivetrain.
-   * @param stateStdDevs             Standard deviations of model states.
-   *                                 Increase these numbers to trust your
-   *                                 model's state estimates less. This matrix
-   *                                 is in the form [x, y, theta]ᵀ, with units
-   *                                 in meters and radians.
-   * @param localMeasurementStdDevs  Standard deviations of the encoder and gyro
-   *                                 measurements. Increase these numbers to
-   *                                 trust sensor readings from encoders
-   *                                 and gyros less. This matrix is in the form
-   *                                 [theta], with units in radians.
-   * @param visionMeasurementStdDevs Standard deviations of the vision
-   *                                 measurements. Increase these numbers to
-   *                                 trust global measurements from vision
-   *                                 less. This matrix is in the form
-   *                                 [x, y, theta]ᵀ, with units in meters and
-   *                                 radians.
-   * @param nominalDt                The time in seconds between each robot
-   *                                 loop.
+   * The default standard deviations of the model states are
+   * 0.1 meters for x, 0.1 meters for y, and 0.1 radians for heading.
+   * The default standard deviations of the vision measurements are
+   * 0.45 meters for x, 0.45 meters for y, and 0.45 radians for heading.
+   *
+   * @param kinematics A correctly-configured kinematics object for your
+   *     drivetrain.
+   * @param gyroAngle The current gyro angle.
+   * @param wheelPositions The distance measured by each wheel.
+   * @param initialPose The starting pose estimate.
    */
-  MecanumDrivePoseEstimator(
-      const Rotation2d& gyroAngle, const Pose2d& initialPose,
-      MecanumDriveKinematics kinematics,
-      const wpi::array<double, 3>& stateStdDevs,
-      const wpi::array<double, 1>& localMeasurementStdDevs,
-      const wpi::array<double, 3>& visionMeasurementStdDevs,
-      units::second_t nominalDt = 0.02_s);
+  MecanumDrivePoseEstimator(MecanumDriveKinematics& kinematics,
+                            const Rotation2d& gyroAngle,
+                            const MecanumDriveWheelPositions& wheelPositions,
+                            const Pose2d& initialPose);
 
   /**
-   * Sets the pose estimator's trust of global measurements. This might be used
+   * Constructs a MecanumDrivePoseEstimator.
+   *
+   * @param kinematics A correctly-configured kinematics object for your
+   *     drivetrain.
+   * @param gyroAngle The current gyro angle.
+   * @param wheelPositions The distance measured by each wheel.
+   * @param initialPose The starting pose estimate.
+   * @param stateStdDevs Standard deviations of the pose estimate (x position in
+   *     meters, y position in meters, and heading in radians). Increase these
+   *     numbers to trust your state estimate less.
+   * @param visionMeasurementStdDevs Standard deviations of the vision pose
+   *     measurement (x position in meters, y position in meters, and heading in
+   *     radians). Increase these numbers to trust the vision pose measurement
+   *     less.
+   */
+  MecanumDrivePoseEstimator(
+      MecanumDriveKinematics& kinematics, const Rotation2d& gyroAngle,
+      const MecanumDriveWheelPositions& wheelPositions,
+      const Pose2d& initialPose, const wpi::array<double, 3>& stateStdDevs,
+      const wpi::array<double, 3>& visionMeasurementStdDevs);
+
+  /**
+   * Sets the pose estimator's trust in vision measurements. This might be used
    * to change trust in vision measurements after the autonomous period, or to
    * change trust as distance to a vision target increases.
    *
-   * @param visionMeasurementStdDevs Standard deviations of the vision
-   *                                 measurements. Increase these numbers to
-   *                                 trust global measurements from vision
-   *                                 less. This matrix is in the form
-   *                                 [x, y, theta]ᵀ, with units in meters and
-   *                                 radians.
+   * @param visionMeasurementStdDevs Standard deviations of the vision pose
+   *     measurement (x position in meters, y position in meters, and heading in
+   *     radians). Increase these numbers to trust the vision pose measurement
+   *     less.
    */
   void SetVisionMeasurementStdDevs(
       const wpi::array<double, 3>& visionMeasurementStdDevs);
@@ -99,75 +92,74 @@
   /**
    * Resets the robot's position on the field.
    *
-   * <p>You NEED to reset your encoders (to zero) when calling this method.
-   *
-   * <p>The gyroscope angle does not need to be reset in the user's robot code.
+   * The gyroscope angle does not need to be reset in the user's robot code.
    * The library automatically takes care of offsetting the gyro angle.
    *
-   * @param pose      The position on the field that your robot is at.
    * @param gyroAngle The angle reported by the gyroscope.
+   * @param wheelPositions The distances measured at each wheel.
+   * @param pose      The position on the field that your robot is at.
    */
-  void ResetPosition(const Pose2d& pose, const Rotation2d& gyroAngle);
+  void ResetPosition(const Rotation2d& gyroAngle,
+                     const MecanumDriveWheelPositions& wheelPositions,
+                     const Pose2d& pose);
 
   /**
-   * Gets the pose of the robot at the current time as estimated by the Extended
-   * Kalman Filter.
+   * Gets the estimated robot pose.
    *
    * @return The estimated robot pose in meters.
    */
   Pose2d GetEstimatedPosition() const;
 
   /**
-   * Add a vision measurement to the Unscented Kalman Filter. This will correct
+   * Add a vision measurement to the Kalman Filter. This will correct
    * the odometry pose estimate while still accounting for measurement noise.
    *
    * This method can be called as infrequently as you want, as long as you are
    * calling Update() every loop.
    *
+   * To promote stability of the pose estimate and make it robust to bad vision
+   * data, we recommend only adding vision measurements that are already within
+   * one meter or so of the current pose estimate.
+   *
    * @param visionRobotPose The pose of the robot as measured by the vision
-   *                        camera.
-   * @param timestamp       The timestamp of the vision measurement in seconds.
-   *                        Note that if you don't use your own time source by
-   *                        calling UpdateWithTime() then you must use a
-   *                        timestamp with an epoch since FPGA startup
-   *                        (i.e. the epoch of this timestamp is the same
-   *                        epoch as Timer#GetFPGATimestamp.) This means
-   *                        that you should use Timer#GetFPGATimestamp as your
-   *                        time source or sync the epochs.
+   *     camera.
+   * @param timestamp The timestamp of the vision measurement in seconds. Note
+   *     that if you don't use your own time source by calling UpdateWithTime()
+   *     then you must use a timestamp with an epoch since FPGA startup (i.e.,
+   *     the epoch of this timestamp is the same epoch as
+   *     frc::Timer::GetFPGATimestamp().) This means that you should use
+   *     frc::Timer::GetFPGATimestamp() as your time source or sync the epochs.
    */
   void AddVisionMeasurement(const Pose2d& visionRobotPose,
                             units::second_t timestamp);
 
   /**
-   * Adds a vision measurement to the Unscented Kalman Filter. This will correct
+   * Adds a vision measurement to the Kalman Filter. This will correct
    * the odometry pose estimate while still accounting for measurement noise.
    *
    * This method can be called as infrequently as you want, as long as you are
    * calling Update() every loop.
    *
+   * To promote stability of the pose estimate and make it robust to bad vision
+   * data, we recommend only adding vision measurements that are already within
+   * one meter or so of the current pose estimate.
+   *
    * Note that the vision measurement standard deviations passed into this
    * method will continue to apply to future measurements until a subsequent
    * call to SetVisionMeasurementStdDevs() or this method.
    *
-   * @param visionRobotPose          The pose of the robot as measured by the
-   *                                 vision camera.
-   * @param timestamp                The timestamp of the vision measurement in
-   *                                 seconds. Note that if you don't use your
-   *                                 own time source by calling
-   *                                 UpdateWithTime(), then you must use a
-   *                                 timestamp with an epoch since FPGA startup
-   *                                 (i.e. the epoch of this timestamp is the
-   *                                 same epoch as
-   *                                 frc::Timer::GetFPGATimestamp(). This means
-   *                                 that you should use
-   *                                 frc::Timer::GetFPGATimestamp() as your
-   *                                 time source in this case.
-   * @param visionMeasurementStdDevs Standard deviations of the vision
-   *                                 measurements. Increase these numbers to
-   *                                 trust global measurements from vision
-   *                                 less. This matrix is in the form
-   *                                 [x, y, theta]ᵀ, with units in meters and
-   *                                 radians.
+   * @param visionRobotPose The pose of the robot as measured by the vision
+   *     camera.
+   * @param timestamp The timestamp of the vision measurement in seconds. Note
+   *     that if you don't use your own time source by calling UpdateWithTime(),
+   *     then you must use a timestamp with an epoch since FPGA startup (i.e.,
+   *     the epoch of this timestamp is the same epoch as
+   *     frc::Timer::GetFPGATimestamp(). This means that you should use
+   *     frc::Timer::GetFPGATimestamp() as your time source in this case.
+   * @param visionMeasurementStdDevs Standard deviations of the vision pose
+   *     measurement (x position in meters, y position in meters, and heading in
+   *     radians). Increase these numbers to trust the vision pose measurement
+   *     less.
    */
   void AddVisionMeasurement(
       const Pose2d& visionRobotPose, units::second_t timestamp,
@@ -177,57 +169,79 @@
   }
 
   /**
-   * Updates the the Unscented Kalman Filter using only wheel encoder
-   * information. This should be called every loop, and the correct loop period
-   * must be passed into the constructor of this class.
+   * Updates the pose estimator with wheel encoder and gyro information. This
+   * should be called every loop.
    *
    * @param gyroAngle   The current gyro angle.
-   * @param wheelSpeeds The current speeds of the mecanum drive wheels.
+   * @param wheelPositions The distances measured at each wheel.
    * @return The estimated pose of the robot in meters.
    */
   Pose2d Update(const Rotation2d& gyroAngle,
-                const MecanumDriveWheelSpeeds& wheelSpeeds);
+                const MecanumDriveWheelPositions& wheelPositions);
 
   /**
-   * Updates the the Unscented Kalman Filter using only wheel encoder
-   * information. This should be called every loop, and the correct loop period
-   * must be passed into the constructor of this class.
+   * Updates the pose estimator with wheel encoder and gyro information. This
+   * should be called every loop.
    *
    * @param currentTime Time at which this method was called, in seconds.
    * @param gyroAngle   The current gyroscope angle.
-   * @param wheelSpeeds The current speeds of the mecanum drive wheels.
+   * @param wheelPositions The distances measured at each wheel.
    * @return The estimated pose of the robot in meters.
    */
   Pose2d UpdateWithTime(units::second_t currentTime,
                         const Rotation2d& gyroAngle,
-                        const MecanumDriveWheelSpeeds& wheelSpeeds);
+                        const MecanumDriveWheelPositions& wheelPositions);
 
  private:
-  UnscentedKalmanFilter<3, 3, 1> m_observer;
-  MecanumDriveKinematics m_kinematics;
-  KalmanFilterLatencyCompensator<3, 3, 1, UnscentedKalmanFilter<3, 3, 1>>
-      m_latencyCompensator;
-  std::function<void(const Eigen::Vector<double, 3>& u,
-                     const Eigen::Vector<double, 3>& y)>
-      m_visionCorrect;
+  struct InterpolationRecord {
+    // The pose observed given the current sensor inputs and the previous pose.
+    Pose2d pose;
 
-  Eigen::Matrix3d m_visionContR;
+    // The current gyroscope angle.
+    Rotation2d gyroAngle;
 
-  units::second_t m_nominalDt;
-  units::second_t m_prevTime = -1_s;
+    // The distances measured at each wheel.
+    MecanumDriveWheelPositions wheelPositions;
 
-  Rotation2d m_gyroOffset;
-  Rotation2d m_previousAngle;
+    /**
+     * Checks equality between this InterpolationRecord and another object.
+     *
+     * @param other The other object.
+     * @return Whether the two objects are equal.
+     */
+    bool operator==(const InterpolationRecord& other) const = default;
 
-  template <int Dim>
-  static wpi::array<double, Dim> StdDevMatrixToArray(
-      const Eigen::Vector<double, Dim>& vector) {
-    wpi::array<double, Dim> array;
-    for (size_t i = 0; i < Dim; ++i) {
-      array[i] = vector(i);
-    }
-    return array;
-  }
+    /**
+     * Checks inequality between this InterpolationRecord and another object.
+     *
+     * @param other The other object.
+     * @return Whether the two objects are not equal.
+     */
+    bool operator!=(const InterpolationRecord& other) const = default;
+
+    /**
+     * Interpolates between two InterpolationRecords.
+     *
+     * @param endValue The end value for the interpolation.
+     * @param i The interpolant (fraction).
+     *
+     * @return The interpolated state.
+     */
+    InterpolationRecord Interpolate(MecanumDriveKinematics& kinematics,
+                                    InterpolationRecord endValue,
+                                    double i) const;
+  };
+
+  MecanumDriveKinematics& m_kinematics;
+  MecanumDriveOdometry m_odometry;
+  wpi::array<double, 3> m_q{wpi::empty_array};
+  Eigen::Matrix3d m_visionK = Eigen::Matrix3d::Zero();
+
+  TimeInterpolatableBuffer<InterpolationRecord> m_poseBuffer{
+      1.5_s, [this](const InterpolationRecord& start,
+                    const InterpolationRecord& end, double t) {
+        return start.Interpolate(this->m_kinematics, end, t);
+      }};
 };
 
 }  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/MerweScaledSigmaPoints.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/MerweScaledSigmaPoints.h
index 42f5593..b2e0e45 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/MerweScaledSigmaPoints.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/MerweScaledSigmaPoints.h
@@ -6,8 +6,7 @@
 
 #include <cmath>
 
-#include "Eigen/Cholesky"
-#include "Eigen/Core"
+#include "frc/EigenCore.h"
 
 namespace frc {
 
@@ -52,24 +51,23 @@
 
   /**
    * Computes the sigma points for an unscented Kalman filter given the mean
-   * (x) and covariance(P) of the filter.
+   * (x) and square-root covariance(S) of the filter.
    *
    * @param x An array of the means.
-   * @param P Covariance of the filter.
+   * @param S Square-root covariance of the filter.
    *
    * @return Two dimensional array of sigma points. Each column contains all of
    *         the sigmas for one dimension in the problem space. Ordered by
    *         Xi_0, Xi_{1..n}, Xi_{n+1..2n}.
    *
    */
-  Eigen::Matrix<double, States, 2 * States + 1> SigmaPoints(
-      const Eigen::Vector<double, States>& x,
-      const Eigen::Matrix<double, States, States>& P) {
+  Matrixd<States, 2 * States + 1> SquareRootSigmaPoints(
+      const Vectord<States>& x, const Matrixd<States, States>& S) {
     double lambda = std::pow(m_alpha, 2) * (States + m_kappa) - States;
-    Eigen::Matrix<double, States, States> U =
-        ((lambda + States) * P).llt().matrixL();
+    double eta = std::sqrt(lambda + States);
+    Matrixd<States, States> U = eta * S;
 
-    Eigen::Matrix<double, States, 2 * States + 1> sigmas;
+    Matrixd<States, 2 * States + 1> sigmas;
     sigmas.template block<States, 1>(0, 0) = x;
     for (int k = 0; k < States; ++k) {
       sigmas.template block<States, 1>(0, k + 1) =
@@ -84,7 +82,7 @@
   /**
    * Returns the weight for each sigma point for the mean.
    */
-  const Eigen::Vector<double, 2 * States + 1>& Wm() const { return m_Wm; }
+  const Vectord<2 * States + 1>& Wm() const { return m_Wm; }
 
   /**
    * Returns an element of the weight for each sigma point for the mean.
@@ -96,7 +94,7 @@
   /**
    * Returns the weight for each sigma point for the covariance.
    */
-  const Eigen::Vector<double, 2 * States + 1>& Wc() const { return m_Wc; }
+  const Vectord<2 * States + 1>& Wc() const { return m_Wc; }
 
   /**
    * Returns an element of the weight for each sigma point for the covariance.
@@ -106,8 +104,8 @@
   double Wc(int i) const { return m_Wc(i, 0); }
 
  private:
-  Eigen::Vector<double, 2 * States + 1> m_Wm;
-  Eigen::Vector<double, 2 * States + 1> m_Wc;
+  Vectord<2 * States + 1> m_Wm;
+  Vectord<2 * States + 1> m_Wc;
   double m_alpha;
   int m_kappa;
 
@@ -120,8 +118,8 @@
     double lambda = std::pow(m_alpha, 2) * (States + m_kappa) - States;
 
     double c = 0.5 / (States + lambda);
-    m_Wm = Eigen::Vector<double, 2 * States + 1>::Constant(c);
-    m_Wc = Eigen::Vector<double, 2 * States + 1>::Constant(c);
+    m_Wm = Vectord<2 * States + 1>::Constant(c);
+    m_Wc = Vectord<2 * States + 1>::Constant(c);
 
     m_Wm(0) = lambda / (States + lambda);
     m_Wc(0) = lambda / (States + lambda) + (1 - std::pow(m_alpha, 2) + beta);
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/SwerveDrivePoseEstimator.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/SwerveDrivePoseEstimator.h
index 7422a3c..d07bafe 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/SwerveDrivePoseEstimator.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/SwerveDrivePoseEstimator.h
@@ -4,224 +4,240 @@
 
 #pragma once
 
-#include <limits>
+#include <cmath>
 
+#include <fmt/format.h>
+#include <wpi/SymbolExports.h>
 #include <wpi/array.h>
 #include <wpi/timestamp.h>
 
-#include "Eigen/Core"
-#include "frc/StateSpaceUtil.h"
-#include "frc/estimator/AngleStatistics.h"
-#include "frc/estimator/KalmanFilterLatencyCompensator.h"
-#include "frc/estimator/UnscentedKalmanFilter.h"
+#include "frc/EigenCore.h"
 #include "frc/geometry/Pose2d.h"
 #include "frc/geometry/Rotation2d.h"
+#include "frc/interpolation/TimeInterpolatableBuffer.h"
 #include "frc/kinematics/SwerveDriveKinematics.h"
+#include "frc/kinematics/SwerveDriveOdometry.h"
 #include "units/time.h"
 
 namespace frc {
+
 /**
- * This class wraps an Unscented Kalman Filter to fuse latency-compensated
- * vision measurements with swerve drive encoder velocity measurements. It will
- * correct for noisy measurements and encoder drift. It is intended to be an
- * easy but more accurate drop-in for SwerveDriveOdometry.
+ * This class wraps Swerve Drive Odometry to fuse latency-compensated
+ * vision measurements with swerve drive encoder distance measurements. It is
+ * intended to be a drop-in for SwerveDriveOdometry.
  *
- * Update() should be called every robot loop. If your loops are faster or
- * slower than the default of 0.02s, then you should change the nominal delta
- * time by specifying it in the constructor.
+ * Update() should be called every robot loop.
  *
  * AddVisionMeasurement() can be called as infrequently as you want; if you
- * never call it, then this class will behave mostly like regular encoder
+ * never call it, then this class will behave as regular encoder
  * odometry.
- *
- * The state-space system used internally has the following states (x), inputs
- * (u), and outputs (y):
- *
- * <strong> x = [x, y, theta]ᵀ </strong> in the field coordinate system
- * containing x position, y position, and heading.
- *
- * <strong> u = [v_x, v_y, omega]ᵀ </strong> containing x velocity, y velocity,
- * and angular velocity in the field coordinate system.
- *
- * <strong> y = [x, y, theta]ᵀ </strong> from vision containing x position, y
- * position, and heading; or <strong> y = [theta]ᵀ </strong> containing gyro
- * heading.
  */
 template <size_t NumModules>
 class SwerveDrivePoseEstimator {
  public:
   /**
-   * Constructs a SwerveDrivePoseEstimator.
+   * Constructs a SwerveDrivePoseEstimator with default standard deviations
+   * for the model and vision measurements.
    *
-   * @param gyroAngle                The current gyro angle.
-   * @param initialPose              The starting pose estimate.
-   * @param kinematics               A correctly-configured kinematics object
-   *                                 for your drivetrain.
-   * @param stateStdDevs             Standard deviations of model states.
-   *                                 Increase these numbers to trust your
-   *                                 model's state estimates less. This matrix
-   *                                 is in the form [x, y, theta]ᵀ, with units
-   *                                 in meters and radians.
-   * @param localMeasurementStdDevs  Standard deviations of the encoder and gyro
-   *                                 measurements. Increase these numbers to
-   *                                 trust sensor readings from encoders
-   *                                 and gyros less. This matrix is in the form
-   *                                 [theta], with units in radians.
-   * @param visionMeasurementStdDevs Standard deviations of the vision
-   *                                 measurements. Increase these numbers to
-   *                                 trust global measurements from vision
-   *                                 less. This matrix is in the form
-   *                                 [x, y, theta]ᵀ, with units in meters and
-   *                                 radians.
-   * @param nominalDt                The time in seconds between each robot
-   *                                 loop.
+   * The default standard deviations of the model states are
+   * 0.1 meters for x, 0.1 meters for y, and 0.1 radians for heading.
+   * The default standard deviations of the vision measurements are
+   * 0.9 meters for x, 0.9 meters for y, and 0.9 radians for heading.
+   *
+   * @param kinematics A correctly-configured kinematics object for your
+   *     drivetrain.
+   * @param gyroAngle The current gyro angle.
+   * @param modulePositions The current distance and rotation measurements of
+   *     the swerve modules.
+   * @param initialPose The starting pose estimate.
    */
   SwerveDrivePoseEstimator(
-      const Rotation2d& gyroAngle, const Pose2d& initialPose,
       SwerveDriveKinematics<NumModules>& kinematics,
-      const wpi::array<double, 3>& stateStdDevs,
-      const wpi::array<double, 1>& localMeasurementStdDevs,
-      const wpi::array<double, 3>& visionMeasurementStdDevs,
-      units::second_t nominalDt = 0.02_s)
-      : m_observer([](const Eigen::Vector<double, 3>& x,
-                      const Eigen::Vector<double, 3>& u) { return u; },
-                   [](const Eigen::Vector<double, 3>& x,
-                      const Eigen::Vector<double, 3>& u) {
-                     return x.block<1, 1>(2, 0);
-                   },
-                   stateStdDevs, localMeasurementStdDevs,
-                   frc::AngleMean<3, 3>(2), frc::AngleMean<1, 3>(0),
-                   frc::AngleResidual<3>(2), frc::AngleResidual<1>(0),
-                   frc::AngleAdd<3>(2), nominalDt),
-        m_kinematics(kinematics),
-        m_nominalDt(nominalDt) {
+      const Rotation2d& gyroAngle,
+      const wpi::array<SwerveModulePosition, NumModules>& modulePositions,
+      const Pose2d& initialPose)
+      : SwerveDrivePoseEstimator{kinematics,      gyroAngle,
+                                 modulePositions, initialPose,
+                                 {0.1, 0.1, 0.1}, {0.9, 0.9, 0.9}} {}
+
+  /**
+   * Constructs a SwerveDrivePoseEstimator.
+   *
+   * @param kinematics A correctly-configured kinematics object for your
+   *     drivetrain.
+   * @param gyroAngle The current gyro angle.
+   * @param modulePositions The current distance and rotation measurements of
+   *     the swerve modules.
+   * @param initialPose The starting pose estimate.
+   * @param stateStdDevs Standard deviations of the pose estimate (x position in
+   *     meters, y position in meters, and heading in radians). Increase these
+   *     numbers to trust your state estimate less.
+   * @param visionMeasurementStdDevs Standard deviations of the vision pose
+   *     measurement (x position in meters, y position in meters, and heading in
+   *     radians). Increase these numbers to trust the vision pose measurement
+   *     less.
+   */
+  SwerveDrivePoseEstimator(
+      SwerveDriveKinematics<NumModules>& kinematics,
+      const Rotation2d& gyroAngle,
+      const wpi::array<SwerveModulePosition, NumModules>& modulePositions,
+      const Pose2d& initialPose, const wpi::array<double, 3>& stateStdDevs,
+      const wpi::array<double, 3>& visionMeasurementStdDevs)
+      : m_kinematics{kinematics},
+        m_odometry{kinematics, gyroAngle, modulePositions, initialPose} {
+    for (size_t i = 0; i < 3; ++i) {
+      m_q[i] = stateStdDevs[i] * stateStdDevs[i];
+    }
+
     SetVisionMeasurementStdDevs(visionMeasurementStdDevs);
-
-    // Create correction mechanism for vision measurements.
-    m_visionCorrect = [&](const Eigen::Vector<double, 3>& u,
-                          const Eigen::Vector<double, 3>& y) {
-      m_observer.Correct<3>(
-          u, y,
-          [](const Eigen::Vector<double, 3>& x,
-             const Eigen::Vector<double, 3>& u) { return x; },
-          m_visionContR, frc::AngleMean<3, 3>(2), frc::AngleResidual<3>(2),
-          frc::AngleResidual<3>(2), frc::AngleAdd<3>(2));
-    };
-
-    // Set initial state.
-    m_observer.SetXhat(PoseTo3dVector(initialPose));
-
-    // Calculate offsets.
-    m_gyroOffset = initialPose.Rotation() - gyroAngle;
-    m_previousAngle = initialPose.Rotation();
   }
 
   /**
    * Resets the robot's position on the field.
    *
-   * You NEED to reset your encoders (to zero) when calling this method.
-   *
    * The gyroscope angle does not need to be reset in the user's robot code.
    * The library automatically takes care of offsetting the gyro angle.
    *
-   * @param pose      The position on the field that your robot is at.
-   * @param gyroAngle The angle reported by the gyroscope.
+   * @param gyroAngle       The angle reported by the gyroscope.
+   * @param modulePositions The current distance and rotation measurements of
+   *                        the swerve modules.
+   * @param pose            The position on the field that your robot is at.
    */
-  void ResetPosition(const Pose2d& pose, const Rotation2d& gyroAngle) {
+  void ResetPosition(
+      const Rotation2d& gyroAngle,
+      const wpi::array<SwerveModulePosition, NumModules>& modulePositions,
+      const Pose2d& pose) {
     // Reset state estimate and error covariance
-    m_observer.Reset();
-    m_latencyCompensator.Reset();
-
-    m_observer.SetXhat(PoseTo3dVector(pose));
-
-    m_gyroOffset = pose.Rotation() - gyroAngle;
-    m_previousAngle = pose.Rotation();
+    m_odometry.ResetPosition(gyroAngle, modulePositions, pose);
+    m_poseBuffer.Clear();
   }
 
   /**
-   * Gets the pose of the robot at the current time as estimated by the Extended
-   * Kalman Filter.
+   * Gets the estimated robot pose.
    *
    * @return The estimated robot pose in meters.
    */
-  Pose2d GetEstimatedPosition() const {
-    return Pose2d(m_observer.Xhat(0) * 1_m, m_observer.Xhat(1) * 1_m,
-                  Rotation2d(units::radian_t{m_observer.Xhat(2)}));
-  }
+  Pose2d GetEstimatedPosition() const { return m_odometry.GetPose(); }
 
   /**
-   * Sets the pose estimator's trust of global measurements. This might be used
+   * Sets the pose estimator's trust in vision measurements. This might be used
    * to change trust in vision measurements after the autonomous period, or to
    * change trust as distance to a vision target increases.
    *
-   * @param visionMeasurementStdDevs Standard deviations of the vision
-   *                                 measurements. Increase these numbers to
-   *                                 trust global measurements from vision
-   *                                 less. This matrix is in the form
-   *                                 [x, y, theta]ᵀ, with units in meters and
-   *                                 radians.
+   * @param visionMeasurementStdDevs Standard deviations of the vision pose
+   *     measurement (x position in meters, y position in meters, and heading in
+   *     radians). Increase these numbers to trust the vision pose measurement
+   *     less.
    */
   void SetVisionMeasurementStdDevs(
       const wpi::array<double, 3>& visionMeasurementStdDevs) {
-    // Create R (covariances) for vision measurements.
-    m_visionContR = frc::MakeCovMatrix(visionMeasurementStdDevs);
+    wpi::array<double, 3> r{wpi::empty_array};
+    for (size_t i = 0; i < 3; ++i) {
+      r[i] = visionMeasurementStdDevs[i] * visionMeasurementStdDevs[i];
+    }
+
+    // Solve for closed form Kalman gain for continuous Kalman filter with A = 0
+    // and C = I. See wpimath/algorithms.md.
+    for (size_t row = 0; row < 3; ++row) {
+      if (m_q[row] == 0.0) {
+        m_visionK(row, row) = 0.0;
+      } else {
+        m_visionK(row, row) =
+            m_q[row] / (m_q[row] + std::sqrt(m_q[row] * r[row]));
+      }
+    }
   }
 
   /**
-   * Add a vision measurement to the Unscented Kalman Filter. This will correct
-   * the odometry pose estimate while still accounting for measurement noise.
+   * Adds a vision measurement to the Kalman Filter. This will correct the
+   * odometry pose estimate while still accounting for measurement noise.
    *
    * This method can be called as infrequently as you want, as long as you are
    * calling Update() every loop.
    *
+   * To promote stability of the pose estimate and make it robust to bad vision
+   * data, we recommend only adding vision measurements that are already within
+   * one meter or so of the current pose estimate.
+   *
    * @param visionRobotPose The pose of the robot as measured by the vision
-   *                        camera.
-   * @param timestamp       The timestamp of the vision measurement in seconds.
-   *                        Note that if you don't use your own time source by
-   *                        calling UpdateWithTime() then you must use a
-   *                        timestamp with an epoch since FPGA startup
-   *                        (i.e. the epoch of this timestamp is the same
-   *                        epoch as Timer#GetFPGATimestamp.) This means
-   *                        that you should use Timer#GetFPGATimestamp as your
-   *                        time source or sync the epochs.
+   *    camera.
+   * @param timestamp The timestamp of the vision measurement in seconds. Note
+   *     that if you don't use your own time source by calling UpdateWithTime()
+   *     then you must use a timestamp with an epoch since FPGA startup (i.e.,
+   *     the epoch of this timestamp is the same epoch as
+   *     frc::Timer::GetFPGATimestamp().) This means that you should use
+   *     frc::Timer::GetFPGATimestamp() as your time source or sync the epochs.
    */
   void AddVisionMeasurement(const Pose2d& visionRobotPose,
                             units::second_t timestamp) {
-    m_latencyCompensator.ApplyPastGlobalMeasurement<3>(
-        &m_observer, m_nominalDt, PoseTo3dVector(visionRobotPose),
-        m_visionCorrect, timestamp);
+    // Step 1: Get the estimated pose from when the vision measurement was made.
+    auto sample = m_poseBuffer.Sample(timestamp);
+
+    if (!sample.has_value()) {
+      return;
+    }
+
+    // Step 2: Measure the twist between the odometry pose and the vision pose
+    auto twist = sample.value().pose.Log(visionRobotPose);
+
+    // Step 3: We should not trust the twist entirely, so instead we scale this
+    // twist by a Kalman gain matrix representing how much we trust vision
+    // measurements compared to our current pose.
+    frc::Vectord<3> k_times_twist =
+        m_visionK * frc::Vectord<3>{twist.dx.value(), twist.dy.value(),
+                                    twist.dtheta.value()};
+
+    // Step 4: Convert back to Twist2d
+    Twist2d scaledTwist{units::meter_t{k_times_twist(0)},
+                        units::meter_t{k_times_twist(1)},
+                        units::radian_t{k_times_twist(2)}};
+
+    // Step 5: Reset Odometry to state at sample with vision adjustment.
+    m_odometry.ResetPosition(sample.value().gyroAngle,
+                             sample.value().modulePostions,
+                             sample.value().pose.Exp(scaledTwist));
+
+    // Step 6: Replay odometry inputs between sample time and latest recorded
+    // sample to update the pose buffer and correct odometry.
+    auto internal_buf = m_poseBuffer.GetInternalBuffer();
+
+    auto upper_bound = std::lower_bound(
+        internal_buf.begin(), internal_buf.end(), timestamp,
+        [](const auto& pair, auto t) { return t > pair.first; });
+
+    for (auto entry = upper_bound; entry != internal_buf.end(); entry++) {
+      UpdateWithTime(entry->first, entry->second.gyroAngle,
+                     entry->second.modulePostions);
+    }
   }
 
   /**
-   * Adds a vision measurement to the Unscented Kalman Filter. This will correct
-   * the odometry pose estimate while still accounting for measurement noise.
+   * Adds a vision measurement to the Kalman Filter. This will correct the
+   * odometry pose estimate while still accounting for measurement noise.
    *
    * This method can be called as infrequently as you want, as long as you are
    * calling Update() every loop.
    *
+   * To promote stability of the pose estimate and make it robust to bad vision
+   * data, we recommend only adding vision measurements that are already within
+   * one meter or so of the current pose estimate.
+   *
    * Note that the vision measurement standard deviations passed into this
    * method will continue to apply to future measurements until a subsequent
    * call to SetVisionMeasurementStdDevs() or this method.
    *
-   * @param visionRobotPose          The pose of the robot as measured by the
-   *                                 vision camera.
-   * @param timestamp                The timestamp of the vision measurement in
-   *                                 seconds. Note that if you don't use your
-   *                                 own time source by calling
-   *                                 UpdateWithTime(), then you must use a
-   *                                 timestamp with an epoch since FPGA startup
-   *                                 (i.e. the epoch of this timestamp is the
-   *                                 same epoch as
-   *                                 frc::Timer::GetFPGATimestamp(). This means
-   *                                 that you should use
-   *                                 frc::Timer::GetFPGATimestamp() as your
-   *                                 time source in this case.
-   * @param visionMeasurementStdDevs Standard deviations of the vision
-   *                                 measurements. Increase these numbers to
-   *                                 trust global measurements from vision
-   *                                 less. This matrix is in the form
-   *                                 [x, y, theta]ᵀ, with units in meters and
-   *                                 radians.
+   * @param visionRobotPose The pose of the robot as measured by the vision
+   *     camera.
+   * @param timestamp The timestamp of the vision measurement in seconds. Note
+   *     that if you don't use your own time source by calling UpdateWithTime(),
+   *     then you must use a timestamp with an epoch since FPGA startup (i.e.,
+   *     the epoch of this timestamp is the same epoch as
+   *     frc::Timer::GetFPGATimestamp(). This means that you should use
+   *     frc::Timer::GetFPGATimestamp() as your time source in this case.
+   * @param visionMeasurementStdDevs Standard deviations of the vision pose
+   *     measurement (x position in meters, y position in meters, and heading in
+   *     radians). Increase these numbers to trust the vision pose measurement
+   *     less.
    */
   void AddVisionMeasurement(
       const Pose2d& visionRobotPose, units::second_t timestamp,
@@ -231,87 +247,140 @@
   }
 
   /**
-   * Updates the the Unscented Kalman Filter using only wheel encoder
-   * information. This should be called every loop, and the correct loop period
-   * must be passed into the constructor of this class.
+   * Updates the pose estimator with wheel encoder and gyro information. This
+   * should be called every loop.
    *
-   * @param gyroAngle    The current gyro angle.
-   * @param moduleStates The current velocities and rotations of the swerve
-   *                     modules.
-   * @return The estimated pose of the robot in meters.
+   * @param gyroAngle       The current gyro angle.
+   * @param modulePositions The current distance and rotation measurements of
+   *                        the swerve modules.
+   * @return The estimated robot pose in meters.
    */
-  template <typename... ModuleState>
-  Pose2d Update(const Rotation2d& gyroAngle, ModuleState&&... moduleStates) {
+  Pose2d Update(
+      const Rotation2d& gyroAngle,
+      const wpi::array<SwerveModulePosition, NumModules>& modulePositions) {
     return UpdateWithTime(units::microsecond_t(wpi::Now()), gyroAngle,
-                          moduleStates...);
+                          modulePositions);
   }
 
   /**
-   * Updates the the Unscented Kalman Filter using only wheel encoder
-   * information. This should be called every loop, and the correct loop period
-   * must be passed into the constructor of this class.
+   * Updates the pose estimator with wheel encoder and gyro information. This
+   * should be called every loop.
    *
-   * @param currentTime  Time at which this method was called, in seconds.
-   * @param gyroAngle    The current gyroscope angle.
-   * @param moduleStates The current velocities and rotations of the swerve
-   *                     modules.
-   * @return The estimated pose of the robot in meters.
+   * @param currentTime     Time at which this method was called, in seconds.
+   * @param gyroAngle       The current gyro angle.
+   * @param modulePositions The current distance traveled and rotations of
+   *                        the swerve modules.
+   * @return The estimated robot pose in meters.
    */
-  template <typename... ModuleState>
-  Pose2d UpdateWithTime(units::second_t currentTime,
-                        const Rotation2d& gyroAngle,
-                        ModuleState&&... moduleStates) {
-    auto dt = m_prevTime >= 0_s ? currentTime - m_prevTime : m_nominalDt;
-    m_prevTime = currentTime;
+  Pose2d UpdateWithTime(
+      units::second_t currentTime, const Rotation2d& gyroAngle,
+      const wpi::array<SwerveModulePosition, NumModules>& modulePositions) {
+    m_odometry.Update(gyroAngle, modulePositions);
 
-    auto angle = gyroAngle + m_gyroOffset;
-    auto omega = (angle - m_previousAngle).Radians() / dt;
+    wpi::array<SwerveModulePosition, NumModules> internalModulePositions{
+        wpi::empty_array};
 
-    auto chassisSpeeds = m_kinematics.ToChassisSpeeds(moduleStates...);
-    auto fieldRelativeSpeeds =
-        Translation2d(chassisSpeeds.vx * 1_s, chassisSpeeds.vy * 1_s)
-            .RotateBy(angle);
+    for (size_t i = 0; i < NumModules; i++) {
+      internalModulePositions[i].distance = modulePositions[i].distance;
+      internalModulePositions[i].angle = modulePositions[i].angle;
+    }
 
-    Eigen::Vector<double, 3> u{fieldRelativeSpeeds.X().value(),
-                               fieldRelativeSpeeds.Y().value(), omega.value()};
-
-    Eigen::Vector<double, 1> localY{angle.Radians().value()};
-    m_previousAngle = angle;
-
-    m_latencyCompensator.AddObserverState(m_observer, u, localY, currentTime);
-
-    m_observer.Predict(u, dt);
-    m_observer.Correct(u, localY);
+    m_poseBuffer.AddSample(currentTime, {GetEstimatedPosition(), gyroAngle,
+                                         internalModulePositions});
 
     return GetEstimatedPosition();
   }
 
  private:
-  UnscentedKalmanFilter<3, 3, 1> m_observer;
-  SwerveDriveKinematics<NumModules>& m_kinematics;
-  KalmanFilterLatencyCompensator<3, 3, 1, UnscentedKalmanFilter<3, 3, 1>>
-      m_latencyCompensator;
-  std::function<void(const Eigen::Vector<double, 3>& u,
-                     const Eigen::Vector<double, 3>& y)>
-      m_visionCorrect;
+  struct InterpolationRecord {
+    // The pose observed given the current sensor inputs and the previous pose.
+    Pose2d pose;
 
-  Eigen::Matrix3d m_visionContR;
+    // The current gyroscope angle.
+    Rotation2d gyroAngle;
 
-  units::second_t m_nominalDt;
-  units::second_t m_prevTime = -1_s;
+    // The distances traveled and rotations meaured at each module.
+    wpi::array<SwerveModulePosition, NumModules> modulePostions;
 
-  Rotation2d m_gyroOffset;
-  Rotation2d m_previousAngle;
+    /**
+     * Checks equality between this InterpolationRecord and another object.
+     *
+     * @param other The other object.
+     * @return Whether the two objects are equal.
+     */
+    bool operator==(const InterpolationRecord& other) const = default;
 
-  template <int Dim>
-  static wpi::array<double, Dim> StdDevMatrixToArray(
-      const Eigen::Vector<double, Dim>& vector) {
-    wpi::array<double, Dim> array;
-    for (size_t i = 0; i < Dim; ++i) {
-      array[i] = vector(i);
+    /**
+     * Checks inequality between this InterpolationRecord and another object.
+     *
+     * @param other The other object.
+     * @return Whether the two objects are not equal.
+     */
+    bool operator!=(const InterpolationRecord& other) const = default;
+
+    /**
+     * Interpolates between two InterpolationRecords.
+     *
+     * @param endValue The end value for the interpolation.
+     * @param i The interpolant (fraction).
+     *
+     * @return The interpolated state.
+     */
+    InterpolationRecord Interpolate(
+        SwerveDriveKinematics<NumModules>& kinematics,
+        InterpolationRecord endValue, double i) const {
+      if (i < 0) {
+        return *this;
+      } else if (i > 1) {
+        return endValue;
+      } else {
+        // Find the new module distances.
+        wpi::array<SwerveModulePosition, NumModules> modulePositions{
+            wpi::empty_array};
+        // Find the distance between this measurement and the
+        // interpolated measurement.
+        wpi::array<SwerveModulePosition, NumModules> modulesDelta{
+            wpi::empty_array};
+
+        for (size_t i = 0; i < NumModules; i++) {
+          modulePositions[i].distance =
+              wpi::Lerp(this->modulePostions[i].distance,
+                        endValue.modulePostions[i].distance, i);
+          modulePositions[i].angle =
+              wpi::Lerp(this->modulePostions[i].angle,
+                        endValue.modulePostions[i].angle, i);
+
+          modulesDelta[i].distance =
+              modulePositions[i].distance - this->modulePostions[i].distance;
+          modulesDelta[i].angle = modulePositions[i].angle;
+        }
+
+        // Find the new gyro angle.
+        auto gyro = wpi::Lerp(this->gyroAngle, endValue.gyroAngle, i);
+
+        // Create a twist to represent this changed based on the interpolated
+        // sensor inputs.
+        auto twist = kinematics.ToTwist2d(modulesDelta);
+        twist.dtheta = (gyro - gyroAngle).Radians();
+
+        return {pose.Exp(twist), gyro, modulePositions};
+      }
     }
-    return array;
-  }
+  };
+
+  SwerveDriveKinematics<NumModules>& m_kinematics;
+  SwerveDriveOdometry<NumModules> m_odometry;
+  wpi::array<double, 3> m_q{wpi::empty_array};
+  Eigen::Matrix3d m_visionK = Eigen::Matrix3d::Zero();
+
+  TimeInterpolatableBuffer<InterpolationRecord> m_poseBuffer{
+      1.5_s, [this](const InterpolationRecord& start,
+                    const InterpolationRecord& end, double t) {
+        return start.Interpolate(this->m_kinematics, end, t);
+      }};
 };
 
+extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
+    SwerveDrivePoseEstimator<4>;
+
 }  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/UnscentedKalmanFilter.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/UnscentedKalmanFilter.h
index 3aa3e59..39ce615 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/UnscentedKalmanFilter.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/UnscentedKalmanFilter.h
@@ -6,16 +6,11 @@
 
 #include <functional>
 
+#include <wpi/SymbolExports.h>
 #include <wpi/array.h>
 
-#include "Eigen/Cholesky"
-#include "Eigen/Core"
-#include "frc/StateSpaceUtil.h"
+#include "frc/EigenCore.h"
 #include "frc/estimator/MerweScaledSigmaPoints.h"
-#include "frc/estimator/UnscentedTransform.h"
-#include "frc/system/Discretization.h"
-#include "frc/system/NumericalIntegration.h"
-#include "frc/system/NumericalJacobian.h"
 #include "units/time.h"
 
 namespace frc {
@@ -40,6 +35,10 @@
  * https://file.tavsys.net/control/controls-engineering-in-frc.pdf chapter 9
  * "Stochastic control theory".
  *
+ * <p> This class implements a square-root-form unscented Kalman filter
+ * (SR-UKF). For more information about the SR-UKF, see
+ * https://www.researchgate.net/publication/3908304.
+ *
  * @tparam States The number of states.
  * @tparam Inputs The number of inputs.
  * @tparam Outputs The number of outputs.
@@ -47,6 +46,15 @@
 template <int States, int Inputs, int Outputs>
 class UnscentedKalmanFilter {
  public:
+  using StateVector = Vectord<States>;
+  using InputVector = Vectord<Inputs>;
+  using OutputVector = Vectord<Outputs>;
+
+  using StateArray = wpi::array<double, States>;
+  using OutputArray = wpi::array<double, Outputs>;
+
+  using StateMatrix = Matrixd<States, States>;
+
   /**
    * Constructs an unscented Kalman filter.
    *
@@ -58,39 +66,11 @@
    * @param measurementStdDevs Standard deviations of measurements.
    * @param dt                 Nominal discretization timestep.
    */
-  UnscentedKalmanFilter(std::function<Eigen::Vector<double, States>(
-                            const Eigen::Vector<double, States>&,
-                            const Eigen::Vector<double, Inputs>&)>
-                            f,
-                        std::function<Eigen::Vector<double, Outputs>(
-                            const Eigen::Vector<double, States>&,
-                            const Eigen::Vector<double, Inputs>&)>
-                            h,
-                        const wpi::array<double, States>& stateStdDevs,
-                        const wpi::array<double, Outputs>& measurementStdDevs,
-                        units::second_t dt)
-      : m_f(f), m_h(h) {
-    m_contQ = MakeCovMatrix(stateStdDevs);
-    m_contR = MakeCovMatrix(measurementStdDevs);
-    m_meanFuncX = [](auto sigmas, auto Wm) -> Eigen::Vector<double, States> {
-      return sigmas * Wm;
-    };
-    m_meanFuncY = [](auto sigmas, auto Wc) -> Eigen::Vector<double, Outputs> {
-      return sigmas * Wc;
-    };
-    m_residualFuncX = [](auto a, auto b) -> Eigen::Vector<double, States> {
-      return a - b;
-    };
-    m_residualFuncY = [](auto a, auto b) -> Eigen::Vector<double, Outputs> {
-      return a - b;
-    };
-    m_addFuncX = [](auto a, auto b) -> Eigen::Vector<double, States> {
-      return a + b;
-    };
-    m_dt = dt;
-
-    Reset();
-  }
+  UnscentedKalmanFilter(
+      std::function<StateVector(const StateVector&, const InputVector&)> f,
+      std::function<OutputVector(const StateVector&, const InputVector&)> h,
+      const StateArray& stateStdDevs, const OutputArray& measurementStdDevs,
+      units::second_t dt);
 
   /**
    * Constructs an unscented Kalman filter with custom mean, residual, and
@@ -117,89 +97,74 @@
    * @param dt                 Nominal discretization timestep.
    */
   UnscentedKalmanFilter(
-      std::function<
-          Eigen::Vector<double, States>(const Eigen::Vector<double, States>&,
-                                        const Eigen::Vector<double, Inputs>&)>
-          f,
-      std::function<
-          Eigen::Vector<double, Outputs>(const Eigen::Vector<double, States>&,
-                                         const Eigen::Vector<double, Inputs>&)>
-          h,
-      const wpi::array<double, States>& stateStdDevs,
-      const wpi::array<double, Outputs>& measurementStdDevs,
-      std::function<Eigen::Vector<double, States>(
-          const Eigen::Matrix<double, States, 2 * States + 1>&,
-          const Eigen::Vector<double, 2 * States + 1>&)>
+      std::function<StateVector(const StateVector&, const InputVector&)> f,
+      std::function<OutputVector(const StateVector&, const InputVector&)> h,
+      const StateArray& stateStdDevs, const OutputArray& measurementStdDevs,
+      std::function<StateVector(const Matrixd<States, 2 * States + 1>&,
+                                const Vectord<2 * States + 1>&)>
           meanFuncX,
-      std::function<Eigen::Vector<double, Outputs>(
-          const Eigen::Matrix<double, Outputs, 2 * States + 1>&,
-          const Eigen::Vector<double, 2 * States + 1>&)>
+      std::function<OutputVector(const Matrixd<Outputs, 2 * States + 1>&,
+                                 const Vectord<2 * States + 1>&)>
           meanFuncY,
-      std::function<
-          Eigen::Vector<double, States>(const Eigen::Vector<double, States>&,
-                                        const Eigen::Vector<double, States>&)>
+      std::function<StateVector(const StateVector&, const StateVector&)>
           residualFuncX,
-      std::function<
-          Eigen::Vector<double, Outputs>(const Eigen::Vector<double, Outputs>&,
-                                         const Eigen::Vector<double, Outputs>&)>
+      std::function<OutputVector(const OutputVector&, const OutputVector&)>
           residualFuncY,
-      std::function<
-          Eigen::Vector<double, States>(const Eigen::Vector<double, States>&,
-                                        const Eigen::Vector<double, States>&)>
+      std::function<StateVector(const StateVector&, const StateVector&)>
           addFuncX,
-      units::second_t dt)
-      : m_f(f),
-        m_h(h),
-        m_meanFuncX(meanFuncX),
-        m_meanFuncY(meanFuncY),
-        m_residualFuncX(residualFuncX),
-        m_residualFuncY(residualFuncY),
-        m_addFuncX(addFuncX) {
-    m_contQ = MakeCovMatrix(stateStdDevs);
-    m_contR = MakeCovMatrix(measurementStdDevs);
-    m_dt = dt;
-
-    Reset();
-  }
+      units::second_t dt);
 
   /**
-   * Returns the error covariance matrix P.
+   * Returns the square-root error covariance matrix S.
    */
-  const Eigen::Matrix<double, States, States>& P() const { return m_P; }
+  const StateMatrix& S() const { return m_S; }
 
   /**
-   * Returns an element of the error covariance matrix P.
+   * Returns an element of the square-root error covariance matrix S.
    *
-   * @param i Row of P.
-   * @param j Column of P.
+   * @param i Row of S.
+   * @param j Column of S.
    */
-  double P(int i, int j) const { return m_P(i, j); }
+  double S(int i, int j) const { return m_S(i, j); }
 
   /**
-   * Set the current error covariance matrix P.
+   * Set the current square-root error covariance matrix S.
+   *
+   * @param S The square-root error covariance matrix S.
+   */
+  void SetS(const StateMatrix& S) { m_S = S; }
+
+  /**
+   * Returns the reconstructed error covariance matrix P.
+   */
+  StateMatrix P() const { return m_S.transpose() * m_S; }
+
+  /**
+   * Set the current square-root error covariance matrix S by taking the square
+   * root of P.
    *
    * @param P The error covariance matrix P.
    */
-  void SetP(const Eigen::Matrix<double, States, States>& P) { m_P = P; }
+  void SetP(const StateMatrix& P) { m_S = P.llt().matrixU(); }
 
   /**
    * Returns the state estimate x-hat.
    */
-  const Eigen::Vector<double, States>& Xhat() const { return m_xHat; }
+  const StateVector& Xhat() const { return m_xHat; }
 
   /**
    * Returns an element of the state estimate x-hat.
    *
    * @param i Row of x-hat.
    */
-  double Xhat(int i) const { return m_xHat(i, 0); }
+  double Xhat(int i) const { return m_xHat(i); }
 
   /**
    * Set initial state estimate x-hat.
    *
    * @param xHat The state estimate x-hat.
    */
-  void SetXhat(const Eigen::Vector<double, States>& xHat) { m_xHat = xHat; }
+  void SetXhat(const StateVector& xHat) { m_xHat = xHat; }
 
   /**
    * Set an element of the initial state estimate x-hat.
@@ -207,14 +172,14 @@
    * @param i     Row of x-hat.
    * @param value Value for element of x-hat.
    */
-  void SetXhat(int i, double value) { m_xHat(i, 0) = value; }
+  void SetXhat(int i, double value) { m_xHat(i) = value; }
 
   /**
    * Resets the observer.
    */
   void Reset() {
     m_xHat.setZero();
-    m_P.setZero();
+    m_S.setZero();
     m_sigmasF.setZero();
   }
 
@@ -224,31 +189,7 @@
    * @param u  New control input from controller.
    * @param dt Timestep for prediction.
    */
-  void Predict(const Eigen::Vector<double, Inputs>& u, units::second_t dt) {
-    m_dt = dt;
-
-    // Discretize Q before projecting mean and covariance forward
-    Eigen::Matrix<double, States, States> contA =
-        NumericalJacobianX<States, States, Inputs>(m_f, m_xHat, u);
-    Eigen::Matrix<double, States, States> discA;
-    Eigen::Matrix<double, States, States> discQ;
-    DiscretizeAQTaylor<States>(contA, m_contQ, dt, &discA, &discQ);
-
-    Eigen::Matrix<double, States, 2 * States + 1> sigmas =
-        m_pts.SigmaPoints(m_xHat, m_P);
-
-    for (int i = 0; i < m_pts.NumSigmas(); ++i) {
-      Eigen::Vector<double, States> x = sigmas.template block<States, 1>(0, i);
-      m_sigmasF.template block<States, 1>(0, i) = RK4(m_f, x, u, dt);
-    }
-
-    auto ret = UnscentedTransform<States, States>(
-        m_sigmasF, m_pts.Wm(), m_pts.Wc(), m_meanFuncX, m_residualFuncX);
-    m_xHat = std::get<0>(ret);
-    m_P = std::get<1>(ret);
-
-    m_P += discQ;
-  }
+  void Predict(const InputVector& u, units::second_t dt);
 
   /**
    * Correct the state estimate x-hat using the measurements in y.
@@ -256,8 +197,7 @@
    * @param u Same control input used in the predict step.
    * @param y Measurement vector.
    */
-  void Correct(const Eigen::Vector<double, Inputs>& u,
-               const Eigen::Vector<double, Outputs>& y) {
+  void Correct(const InputVector& u, const OutputVector& y) {
     Correct<Outputs>(u, y, m_h, m_contR, m_meanFuncY, m_residualFuncY,
                      m_residualFuncX, m_addFuncX);
   }
@@ -276,28 +216,10 @@
    * @param R Measurement noise covariance matrix (continuous-time).
    */
   template <int Rows>
-  void Correct(const Eigen::Vector<double, Inputs>& u,
-               const Eigen::Vector<double, Rows>& y,
-               std::function<Eigen::Vector<double, Rows>(
-                   const Eigen::Vector<double, States>&,
-                   const Eigen::Vector<double, Inputs>&)>
-                   h,
-               const Eigen::Matrix<double, Rows, Rows>& R) {
-    auto meanFuncY = [](auto sigmas, auto Wc) -> Eigen::Vector<double, Rows> {
-      return sigmas * Wc;
-    };
-    auto residualFuncX = [](auto a, auto b) -> Eigen::Vector<double, States> {
-      return a - b;
-    };
-    auto residualFuncY = [](auto a, auto b) -> Eigen::Vector<double, Rows> {
-      return a - b;
-    };
-    auto addFuncX = [](auto a, auto b) -> Eigen::Vector<double, States> {
-      return a + b;
-    };
-    Correct<Rows>(u, y, h, R, meanFuncY, residualFuncY, residualFuncX,
-                  addFuncX);
-  }
+  void Correct(
+      const InputVector& u, const Vectord<Rows>& y,
+      std::function<Vectord<Rows>(const StateVector&, const InputVector&)> h,
+      const Matrixd<Rows, Rows>& R);
 
   /**
    * Correct the state estimate x-hat using the measurements in y.
@@ -320,109 +242,49 @@
    * @param addFuncX      A function that adds two state vectors.
    */
   template <int Rows>
-  void Correct(const Eigen::Vector<double, Inputs>& u,
-               const Eigen::Vector<double, Rows>& y,
-               std::function<Eigen::Vector<double, Rows>(
-                   const Eigen::Vector<double, States>&,
-                   const Eigen::Vector<double, Inputs>&)>
-                   h,
-               const Eigen::Matrix<double, Rows, Rows>& R,
-               std::function<Eigen::Vector<double, Rows>(
-                   const Eigen::Matrix<double, Rows, 2 * States + 1>&,
-                   const Eigen::Vector<double, 2 * States + 1>&)>
-                   meanFuncY,
-               std::function<Eigen::Vector<double, Rows>(
-                   const Eigen::Vector<double, Rows>&,
-                   const Eigen::Vector<double, Rows>&)>
-                   residualFuncY,
-               std::function<Eigen::Vector<double, States>(
-                   const Eigen::Vector<double, States>&,
-                   const Eigen::Vector<double, States>&)>
-                   residualFuncX,
-               std::function<Eigen::Vector<double, States>(
-                   const Eigen::Vector<double, States>&,
-                   const Eigen::Vector<double, States>)>
-                   addFuncX) {
-    const Eigen::Matrix<double, Rows, Rows> discR = DiscretizeR<Rows>(R, m_dt);
-
-    // Transform sigma points into measurement space
-    Eigen::Matrix<double, Rows, 2 * States + 1> sigmasH;
-    Eigen::Matrix<double, States, 2 * States + 1> sigmas =
-        m_pts.SigmaPoints(m_xHat, m_P);
-    for (int i = 0; i < m_pts.NumSigmas(); ++i) {
-      sigmasH.template block<Rows, 1>(0, i) =
-          h(sigmas.template block<States, 1>(0, i), u);
-    }
-
-    // Mean and covariance of prediction passed through UT
-    auto [yHat, Py] = UnscentedTransform<Rows, States>(
-        sigmasH, m_pts.Wm(), m_pts.Wc(), meanFuncY, residualFuncY);
-    Py += discR;
-
-    // Compute cross covariance of the state and the measurements
-    Eigen::Matrix<double, States, Rows> Pxy;
-    Pxy.setZero();
-    for (int i = 0; i < m_pts.NumSigmas(); ++i) {
-      // Pxy += (sigmas_f[:, i] - x̂)(sigmas_h[:, i] - ŷ)ᵀ W_c[i]
-      Pxy +=
-          m_pts.Wc(i) *
-          (residualFuncX(m_sigmasF.template block<States, 1>(0, i), m_xHat)) *
-          (residualFuncY(sigmasH.template block<Rows, 1>(0, i), yHat))
-              .transpose();
-    }
-
-    // K = P_{xy} P_y⁻¹
-    // Kᵀ = P_yᵀ⁻¹ P_{xy}ᵀ
-    // P_yᵀKᵀ = P_{xy}ᵀ
-    // Kᵀ = P_yᵀ.solve(P_{xy}ᵀ)
-    // K = (P_yᵀ.solve(P_{xy}ᵀ)ᵀ
-    Eigen::Matrix<double, States, Rows> K =
-        Py.transpose().ldlt().solve(Pxy.transpose()).transpose();
-
-    // x̂ₖ₊₁⁺ = x̂ₖ₊₁⁻ + K(y − ŷ)
-    m_xHat = addFuncX(m_xHat, K * residualFuncY(y, yHat));
-
-    // Pₖ₊₁⁺ = Pₖ₊₁⁻ − KP_yKᵀ
-    m_P -= K * Py * K.transpose();
-  }
+  void Correct(
+      const InputVector& u, const Vectord<Rows>& y,
+      std::function<Vectord<Rows>(const StateVector&, const InputVector&)> h,
+      const Matrixd<Rows, Rows>& R,
+      std::function<Vectord<Rows>(const Matrixd<Rows, 2 * States + 1>&,
+                                  const Vectord<2 * States + 1>&)>
+          meanFuncY,
+      std::function<Vectord<Rows>(const Vectord<Rows>&, const Vectord<Rows>&)>
+          residualFuncY,
+      std::function<StateVector(const StateVector&, const StateVector&)>
+          residualFuncX,
+      std::function<StateVector(const StateVector&, const StateVector&)>
+          addFuncX);
 
  private:
-  std::function<Eigen::Vector<double, States>(
-      const Eigen::Vector<double, States>&,
-      const Eigen::Vector<double, Inputs>&)>
-      m_f;
-  std::function<Eigen::Vector<double, Outputs>(
-      const Eigen::Vector<double, States>&,
-      const Eigen::Vector<double, Inputs>&)>
-      m_h;
-  std::function<Eigen::Vector<double, States>(
-      const Eigen::Matrix<double, States, 2 * States + 1>&,
-      const Eigen::Vector<double, 2 * States + 1>&)>
+  std::function<StateVector(const StateVector&, const InputVector&)> m_f;
+  std::function<OutputVector(const StateVector&, const InputVector&)> m_h;
+  std::function<StateVector(const Matrixd<States, 2 * States + 1>&,
+                            const Vectord<2 * States + 1>&)>
       m_meanFuncX;
-  std::function<Eigen::Vector<double, Outputs>(
-      const Eigen::Matrix<double, Outputs, 2 * States + 1>&,
-      const Eigen::Vector<double, 2 * States + 1>&)>
+  std::function<OutputVector(const Matrixd<Outputs, 2 * States + 1>&,
+                             const Vectord<2 * States + 1>&)>
       m_meanFuncY;
-  std::function<Eigen::Vector<double, States>(
-      const Eigen::Vector<double, States>&,
-      const Eigen::Vector<double, States>&)>
+  std::function<StateVector(const StateVector&, const StateVector&)>
       m_residualFuncX;
-  std::function<Eigen::Vector<double, Outputs>(
-      const Eigen::Vector<double, Outputs>&,
-      const Eigen::Vector<double, Outputs>)>
+  std::function<OutputVector(const OutputVector&, const OutputVector&)>
       m_residualFuncY;
-  std::function<Eigen::Vector<double, States>(
-      const Eigen::Vector<double, States>&,
-      const Eigen::Vector<double, States>)>
-      m_addFuncX;
-  Eigen::Vector<double, States> m_xHat;
-  Eigen::Matrix<double, States, States> m_P;
-  Eigen::Matrix<double, States, States> m_contQ;
-  Eigen::Matrix<double, Outputs, Outputs> m_contR;
-  Eigen::Matrix<double, States, 2 * States + 1> m_sigmasF;
+  std::function<StateVector(const StateVector&, const StateVector&)> m_addFuncX;
+  StateVector m_xHat;
+  StateMatrix m_S;
+  StateMatrix m_contQ;
+  Matrixd<Outputs, Outputs> m_contR;
+  Matrixd<States, 2 * States + 1> m_sigmasF;
   units::second_t m_dt;
 
   MerweScaledSigmaPoints<States> m_pts;
 };
 
+extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
+    UnscentedKalmanFilter<3, 3, 1>;
+extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
+    UnscentedKalmanFilter<5, 3, 3>;
+
 }  // namespace frc
+
+#include "UnscentedKalmanFilter.inc"
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/UnscentedKalmanFilter.inc b/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/UnscentedKalmanFilter.inc
new file mode 100644
index 0000000..a6744bf
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/UnscentedKalmanFilter.inc
@@ -0,0 +1,174 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include "Eigen/Cholesky"
+#include "frc/StateSpaceUtil.h"
+#include "frc/estimator/UnscentedKalmanFilter.h"
+#include "frc/estimator/UnscentedTransform.h"
+#include "frc/system/Discretization.h"
+#include "frc/system/NumericalIntegration.h"
+#include "frc/system/NumericalJacobian.h"
+
+namespace frc {
+
+template <int States, int Inputs, int Outputs>
+UnscentedKalmanFilter<States, Inputs, Outputs>::UnscentedKalmanFilter(
+    std::function<StateVector(const StateVector&, const InputVector&)> f,
+    std::function<OutputVector(const StateVector&, const InputVector&)> h,
+    const StateArray& stateStdDevs, const OutputArray& measurementStdDevs,
+    units::second_t dt)
+    : m_f(f), m_h(h) {
+  m_contQ = MakeCovMatrix(stateStdDevs);
+  m_contR = MakeCovMatrix(measurementStdDevs);
+  m_meanFuncX = [](auto sigmas, auto Wm) -> StateVector { return sigmas * Wm; };
+  m_meanFuncY = [](auto sigmas, auto Wc) -> OutputVector {
+    return sigmas * Wc;
+  };
+  m_residualFuncX = [](auto a, auto b) -> StateVector { return a - b; };
+  m_residualFuncY = [](auto a, auto b) -> OutputVector { return a - b; };
+  m_addFuncX = [](auto a, auto b) -> StateVector { return a + b; };
+  m_dt = dt;
+
+  Reset();
+}
+
+template <int States, int Inputs, int Outputs>
+UnscentedKalmanFilter<States, Inputs, Outputs>::UnscentedKalmanFilter(
+    std::function<StateVector(const StateVector&, const InputVector&)> f,
+    std::function<OutputVector(const StateVector&, const InputVector&)> h,
+    const StateArray& stateStdDevs, const OutputArray& measurementStdDevs,
+    std::function<StateVector(const Matrixd<States, 2 * States + 1>&,
+                              const Vectord<2 * States + 1>&)>
+        meanFuncX,
+    std::function<OutputVector(const Matrixd<Outputs, 2 * States + 1>&,
+                               const Vectord<2 * States + 1>&)>
+        meanFuncY,
+    std::function<StateVector(const StateVector&, const StateVector&)>
+        residualFuncX,
+    std::function<OutputVector(const OutputVector&, const OutputVector&)>
+        residualFuncY,
+    std::function<StateVector(const StateVector&, const StateVector&)> addFuncX,
+    units::second_t dt)
+    : m_f(f),
+      m_h(h),
+      m_meanFuncX(meanFuncX),
+      m_meanFuncY(meanFuncY),
+      m_residualFuncX(residualFuncX),
+      m_residualFuncY(residualFuncY),
+      m_addFuncX(addFuncX) {
+  m_contQ = MakeCovMatrix(stateStdDevs);
+  m_contR = MakeCovMatrix(measurementStdDevs);
+  m_dt = dt;
+
+  Reset();
+}
+
+template <int States, int Inputs, int Outputs>
+void UnscentedKalmanFilter<States, Inputs, Outputs>::Predict(
+    const InputVector& u, units::second_t dt) {
+  m_dt = dt;
+
+  // Discretize Q before projecting mean and covariance forward
+  StateMatrix contA =
+      NumericalJacobianX<States, States, Inputs>(m_f, m_xHat, u);
+  StateMatrix discA;
+  StateMatrix discQ;
+  DiscretizeAQTaylor<States>(contA, m_contQ, m_dt, &discA, &discQ);
+  Eigen::internal::llt_inplace<double, Eigen::Lower>::blocked(discQ);
+
+  Matrixd<States, 2 * States + 1> sigmas =
+      m_pts.SquareRootSigmaPoints(m_xHat, m_S);
+
+  for (int i = 0; i < m_pts.NumSigmas(); ++i) {
+    StateVector x = sigmas.template block<States, 1>(0, i);
+    m_sigmasF.template block<States, 1>(0, i) = RK4(m_f, x, u, dt);
+  }
+
+  auto [xHat, S] = SquareRootUnscentedTransform<States, States>(
+      m_sigmasF, m_pts.Wm(), m_pts.Wc(), m_meanFuncX, m_residualFuncX,
+      discQ.template triangularView<Eigen::Lower>());
+  m_xHat = xHat;
+  m_S = S;
+}
+
+template <int States, int Inputs, int Outputs>
+template <int Rows>
+void UnscentedKalmanFilter<States, Inputs, Outputs>::Correct(
+    const InputVector& u, const Vectord<Rows>& y,
+    std::function<Vectord<Rows>(const StateVector&, const InputVector&)> h,
+    const Matrixd<Rows, Rows>& R) {
+  auto meanFuncY = [](auto sigmas, auto Wc) -> Vectord<Rows> {
+    return sigmas * Wc;
+  };
+  auto residualFuncX = [](auto a, auto b) -> StateVector { return a - b; };
+  auto residualFuncY = [](auto a, auto b) -> Vectord<Rows> { return a - b; };
+  auto addFuncX = [](auto a, auto b) -> StateVector { return a + b; };
+  Correct<Rows>(u, y, h, R, meanFuncY, residualFuncY, residualFuncX, addFuncX);
+}
+
+template <int States, int Inputs, int Outputs>
+template <int Rows>
+void UnscentedKalmanFilter<States, Inputs, Outputs>::Correct(
+    const InputVector& u, const Vectord<Rows>& y,
+    std::function<Vectord<Rows>(const StateVector&, const InputVector&)> h,
+    const Matrixd<Rows, Rows>& R,
+    std::function<Vectord<Rows>(const Matrixd<Rows, 2 * States + 1>&,
+                                const Vectord<2 * States + 1>&)>
+        meanFuncY,
+    std::function<Vectord<Rows>(const Vectord<Rows>&, const Vectord<Rows>&)>
+        residualFuncY,
+    std::function<StateVector(const StateVector&, const StateVector&)>
+        residualFuncX,
+    std::function<StateVector(const StateVector&, const StateVector&)>
+        addFuncX) {
+  Matrixd<Rows, Rows> discR = DiscretizeR<Rows>(R, m_dt);
+  Eigen::internal::llt_inplace<double, Eigen::Lower>::blocked(discR);
+
+  // Transform sigma points into measurement space
+  Matrixd<Rows, 2 * States + 1> sigmasH;
+  Matrixd<States, 2 * States + 1> sigmas =
+      m_pts.SquareRootSigmaPoints(m_xHat, m_S);
+  for (int i = 0; i < m_pts.NumSigmas(); ++i) {
+    sigmasH.template block<Rows, 1>(0, i) =
+        h(sigmas.template block<States, 1>(0, i), u);
+  }
+
+  // Mean and covariance of prediction passed through UT
+  auto [yHat, Sy] = SquareRootUnscentedTransform<Rows, States>(
+      sigmasH, m_pts.Wm(), m_pts.Wc(), meanFuncY, residualFuncY,
+      discR.template triangularView<Eigen::Lower>());
+
+  // Compute cross covariance of the state and the measurements
+  Matrixd<States, Rows> Pxy;
+  Pxy.setZero();
+  for (int i = 0; i < m_pts.NumSigmas(); ++i) {
+    // Pxy += (sigmas_f[:, i] - x̂)(sigmas_h[:, i] - ŷ)ᵀ W_c[i]
+    Pxy += m_pts.Wc(i) *
+           (residualFuncX(m_sigmasF.template block<States, 1>(0, i), m_xHat)) *
+           (residualFuncY(sigmasH.template block<Rows, 1>(0, i), yHat))
+               .transpose();
+  }
+
+  // K = (P_{xy} / S_yᵀ) / S_y
+  // K = (S_y \ P_{xy}ᵀ)ᵀ / S_y
+  // K = (S_yᵀ \ (S_y \ P_{xy}ᵀ))ᵀ
+  Matrixd<States, Rows> K =
+      Sy.transpose()
+          .fullPivHouseholderQr()
+          .solve(Sy.fullPivHouseholderQr().solve(Pxy.transpose()))
+          .transpose();
+
+  // x̂ₖ₊₁⁺ = x̂ₖ₊₁⁻ + K(y − ŷ)
+  m_xHat = addFuncX(m_xHat, K * residualFuncY(y, yHat));
+
+  Matrixd<States, Rows> U = K * Sy;
+  for (int i = 0; i < Rows; i++) {
+    Eigen::internal::llt_inplace<double, Eigen::Upper>::rankUpdate(
+        m_S, U.template block<States, 1>(0, i), -1);
+  }
+}
+
+}  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/UnscentedTransform.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/UnscentedTransform.h
index 2df0a47..e28f094 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/UnscentedTransform.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/estimator/UnscentedTransform.h
@@ -6,15 +6,17 @@
 
 #include <tuple>
 
-#include "Eigen/Core"
+#include "Eigen/QR"
+#include "frc/EigenCore.h"
 
 namespace frc {
 
 /**
  * Computes unscented transform of a set of sigma points and weights. CovDim
- * returns the mean and covariance in a tuple.
+ * returns the mean and square-root covariance of the sigma points in a tuple.
  *
- * This works in conjunction with the UnscentedKalmanFilter class.
+ * This works in conjunction with the UnscentedKalmanFilter class. For use with
+ * square-root form UKFs.
  *
  * @tparam CovDim      Dimension of covariance of sigma points after passing
  *                     through the transform.
@@ -26,41 +28,48 @@
  *                     vectors using a given set of weights.
  * @param residualFunc A function that computes the residual of two state
  *                     vectors (i.e. it subtracts them.)
+ * @param squareRootR  Square-root of the noise covaraince of the sigma points.
  *
- * @return Tuple of x, mean of sigma points; P, covariance of sigma points after
- *         passing through the transform.
+ * @return Tuple of x, mean of sigma points; S, square-root covariance of
+ * sigmas.
  */
 template <int CovDim, int States>
-std::tuple<Eigen::Vector<double, CovDim>, Eigen::Matrix<double, CovDim, CovDim>>
-UnscentedTransform(const Eigen::Matrix<double, CovDim, 2 * States + 1>& sigmas,
-                   const Eigen::Vector<double, 2 * States + 1>& Wm,
-                   const Eigen::Vector<double, 2 * States + 1>& Wc,
-                   std::function<Eigen::Vector<double, CovDim>(
-                       const Eigen::Matrix<double, CovDim, 2 * States + 1>&,
-                       const Eigen::Vector<double, 2 * States + 1>&)>
-                       meanFunc,
-                   std::function<Eigen::Vector<double, CovDim>(
-                       const Eigen::Vector<double, CovDim>&,
-                       const Eigen::Vector<double, CovDim>&)>
-                       residualFunc) {
+std::tuple<Vectord<CovDim>, Matrixd<CovDim, CovDim>>
+SquareRootUnscentedTransform(
+    const Matrixd<CovDim, 2 * States + 1>& sigmas,
+    const Vectord<2 * States + 1>& Wm, const Vectord<2 * States + 1>& Wc,
+    std::function<Vectord<CovDim>(const Matrixd<CovDim, 2 * States + 1>&,
+                                  const Vectord<2 * States + 1>&)>
+        meanFunc,
+    std::function<Vectord<CovDim>(const Vectord<CovDim>&,
+                                  const Vectord<CovDim>&)>
+        residualFunc,
+    const Matrixd<CovDim, CovDim>& squareRootR) {
   // New mean is usually just the sum of the sigmas * weight:
   //       n
   // dot = Σ W[k] Xᵢ[k]
   //      k=1
-  Eigen::Vector<double, CovDim> x = meanFunc(sigmas, Wm);
+  Vectord<CovDim> x = meanFunc(sigmas, Wm);
 
-  // New covariance is the sum of the outer product of the residuals times the
-  // weights
-  Eigen::Matrix<double, CovDim, 2 * States + 1> y;
-  for (int i = 0; i < 2 * States + 1; ++i) {
-    // y[:, i] = sigmas[:, i] - x
-    y.template block<CovDim, 1>(0, i) =
-        residualFunc(sigmas.template block<CovDim, 1>(0, i), x);
+  Matrixd<CovDim, States * 2 + CovDim> Sbar;
+  for (int i = 0; i < States * 2; i++) {
+    Sbar.template block<CovDim, 1>(0, i) =
+        std::sqrt(Wc[1]) *
+        residualFunc(sigmas.template block<CovDim, 1>(0, 1 + i), x);
   }
-  Eigen::Matrix<double, CovDim, CovDim> P =
-      y * Eigen::DiagonalMatrix<double, 2 * States + 1>(Wc) * y.transpose();
+  Sbar.template block<CovDim, CovDim>(0, States * 2) = squareRootR;
 
-  return std::make_tuple(x, P);
+  // Merwe defines the QR decomposition as Aᵀ = QR
+  Matrixd<CovDim, CovDim> S = Sbar.transpose()
+                                  .householderQr()
+                                  .matrixQR()
+                                  .template block<CovDim, CovDim>(0, 0)
+                                  .template triangularView<Eigen::Upper>();
+
+  Eigen::internal::llt_inplace<double, Eigen::Upper>::rankUpdate(
+      S, residualFunc(sigmas.template block<CovDim, 1>(0, 0), x), Wc[0]);
+
+  return std::make_tuple(x, S);
 }
 
 }  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/filter/Debouncer.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/filter/Debouncer.h
index 7307102..a929f37 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/filter/Debouncer.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/filter/Debouncer.h
@@ -4,6 +4,7 @@
 
 #pragma once
 
+#include <wpi/SymbolExports.h>
 #include <wpi/timestamp.h>
 
 #include "units/time.h"
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/filter/LinearFilter.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/filter/LinearFilter.h
index 6295327..0fb4f48 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/filter/LinearFilter.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/filter/LinearFilter.h
@@ -7,15 +7,15 @@
 #include <algorithm>
 #include <cmath>
 #include <initializer_list>
+#include <span>
 #include <stdexcept>
 #include <vector>
 
 #include <wpi/array.h>
 #include <wpi/circular_buffer.h>
-#include <wpi/span.h>
 
-#include "Eigen/Core"
 #include "Eigen/QR"
+#include "frc/EigenCore.h"
 #include "units/time.h"
 #include "wpimath/MathShared.h"
 
@@ -80,7 +80,7 @@
    * @param ffGains The "feedforward" or FIR gains.
    * @param fbGains The "feedback" or IIR gains.
    */
-  LinearFilter(wpi::span<const double> ffGains, wpi::span<const double> fbGains)
+  LinearFilter(std::span<const double> ffGains, std::span<const double> fbGains)
       : m_inputs(ffGains.size()),
         m_outputs(fbGains.size()),
         m_inputGains(ffGains.begin(), ffGains.end()),
@@ -157,6 +157,7 @@
    *
    * @param taps The number of samples to average over. Higher = smoother but
    *             slower
+   * @throws std::runtime_error if number of taps is less than 1.
    */
   static LinearFilter<T> MovingAverage(int taps) {
     if (taps <= 0) {
@@ -175,12 +176,12 @@
    * difference. 0 is the current sample, -1 is the previous sample, -2 is the
    * sample before that, etc. Don't use positive stencil points (samples from
    * the future) if the LinearFilter will be used for stream-based online
-   * filtering.
+   * filtering (e.g., taking derivative of encoder samples in real-time).
    *
    * @tparam Derivative The order of the derivative to compute.
    * @tparam Samples    The number of samples to use to compute the given
    *                    derivative. This must be one more than the order of
-   *                    derivative or higher.
+   *                    the derivative or higher.
    * @param stencil     List of stencil points.
    * @param period      The period in seconds between samples taken by the user.
    */
@@ -209,7 +210,7 @@
     static_assert(Derivative < Samples,
                   "Order of derivative must be less than number of samples.");
 
-    Eigen::Matrix<double, Samples, Samples> S;
+    Matrixd<Samples, Samples> S;
     for (int row = 0; row < Samples; ++row) {
       for (int col = 0; col < Samples; ++col) {
         S(row, col) = std::pow(stencil[col], row);
@@ -217,12 +218,12 @@
     }
 
     // Fill in Kronecker deltas: https://en.wikipedia.org/wiki/Kronecker_delta
-    Eigen::Vector<double, Samples> d;
+    Vectord<Samples> d;
     for (int i = 0; i < Samples; ++i) {
       d(i) = (i == Derivative) ? Factorial(Derivative) : 0.0;
     }
 
-    Eigen::Vector<double, Samples> a =
+    Vectord<Samples> a =
         S.householderQr().solve(d) / std::pow(period.value(), Derivative);
 
     // Reverse gains list
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/filter/SlewRateLimiter.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/filter/SlewRateLimiter.h
index f99c1af..542cd94 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/filter/SlewRateLimiter.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/filter/SlewRateLimiter.h
@@ -6,6 +6,7 @@
 
 #include <algorithm>
 
+#include <wpi/deprecated.h>
 #include <wpi/timestamp.h>
 
 #include "units/time.h"
@@ -28,15 +29,45 @@
   using Rate_t = units::unit_t<Rate>;
 
   /**
-   * Creates a new SlewRateLimiter with the given rate limit and initial value.
+   * Creates a new SlewRateLimiter with the given positive and negative rate
+   * limits and initial value.
+   *
+   * @param positiveRateLimit The rate-of-change limit in the positive
+   *                          direction, in units per second. This is expected
+   *                          to be positive.
+   * @param negativeRateLimit The rate-of-change limit in the negative
+   *                          direction, in units per second. This is expected
+   *                          to be negative.
+   * @param initialValue The initial value of the input.
+   */
+  SlewRateLimiter(Rate_t positiveRateLimit, Rate_t negativeRateLimit,
+                  Unit_t initialValue = Unit_t{0})
+      : m_positiveRateLimit{positiveRateLimit},
+        m_negativeRateLimit{negativeRateLimit},
+        m_prevVal{initialValue},
+        m_prevTime{units::microsecond_t(wpi::Now())} {}
+
+  /**
+   * Creates a new SlewRateLimiter with the given positive rate limit and
+   * negative rate limit of -rateLimit.
+   *
+   * @param rateLimit The rate-of-change limit.
+   */
+  explicit SlewRateLimiter(Rate_t rateLimit)
+      : SlewRateLimiter(rateLimit, -rateLimit) {}
+
+  /**
+   * Creates a new SlewRateLimiter with the given positive rate limit and
+   * negative rate limit of -rateLimit and initial value.
    *
    * @param rateLimit The rate-of-change limit.
    * @param initialValue The initial value of the input.
    */
-  explicit SlewRateLimiter(Rate_t rateLimit, Unit_t initialValue = Unit_t{0})
-      : m_rateLimit{rateLimit},
-        m_prevVal{initialValue},
-        m_prevTime{units::microsecond_t(wpi::Now())} {}
+  WPI_DEPRECATED(
+      "Use SlewRateLimiter(Rate_t positiveRateLimit, Rate_t negativeRateLimit, "
+      "Unit_t initalValue) instead")
+  SlewRateLimiter(Rate_t rateLimit, Unit_t initialValue)
+      : SlewRateLimiter(rateLimit, -rateLimit, initialValue) {}
 
   /**
    * Filters the input to limit its slew rate.
@@ -48,8 +79,9 @@
   Unit_t Calculate(Unit_t input) {
     units::second_t currentTime = units::microsecond_t(wpi::Now());
     units::second_t elapsedTime = currentTime - m_prevTime;
-    m_prevVal += std::clamp(input - m_prevVal, -m_rateLimit * elapsedTime,
-                            m_rateLimit * elapsedTime);
+    m_prevVal +=
+        std::clamp(input - m_prevVal, m_negativeRateLimit * elapsedTime,
+                   m_positiveRateLimit * elapsedTime);
     m_prevTime = currentTime;
     return m_prevVal;
   }
@@ -66,7 +98,8 @@
   }
 
  private:
-  Rate_t m_rateLimit;
+  Rate_t m_positiveRateLimit;
+  Rate_t m_negativeRateLimit;
   Unit_t m_prevVal;
   units::second_t m_prevTime;
 };
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/fmt/Eigen.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/fmt/Eigen.h
index f6cc7b6..c6b2ee6 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/fmt/Eigen.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/fmt/Eigen.h
@@ -7,9 +7,10 @@
 #include <fmt/format.h>
 
 #include "Eigen/Core"
+#include "Eigen/SparseCore"
 
 /**
- * Formatter for Eigen::Matrix<>.
+ * Formatter for Eigen::Matrix<double, Rows, Cols>.
  *
  * @tparam Rows Number of rows.
  * @tparam Cols Number of columns.
@@ -51,12 +52,68 @@
   auto format(const Eigen::Matrix<double, Rows, Cols, Args...>& mat,
               FormatContext& ctx) {
     auto out = ctx.out();
-    for (int i = 0; i < Rows; ++i) {
-      for (int j = 0; j < Cols; ++j) {
+    for (int i = 0; i < mat.rows(); ++i) {
+      for (int j = 0; j < mat.cols(); ++j) {
         out = fmt::format_to(out, "  {:f}", mat(i, j));
       }
 
-      if (i < Rows - 1) {
+      if (i < mat.rows() - 1) {
+        out = fmt::format_to(out, "\n");
+      }
+    }
+
+    return out;
+  }
+};
+
+/**
+ * Formatter for Eigen::SparseMatrix<double>.
+ *
+ * @tparam Options Union of bit flags controlling the storage scheme.
+ * @tparam StorageIndex The type of the indices.
+ */
+template <int Options, typename StorageIndex>
+struct fmt::formatter<Eigen::SparseMatrix<double, Options, StorageIndex>> {
+  /**
+   * Storage for format specifier.
+   */
+  char presentation = 'f';
+
+  /**
+   * Format string parser.
+   *
+   * @param ctx Format string context.
+   */
+  constexpr auto parse(fmt::format_parse_context& ctx) {
+    auto it = ctx.begin(), end = ctx.end();
+    if (it != end && (*it == 'f' || *it == 'e')) {
+      presentation = *it++;
+    }
+
+    if (it != end && *it != '}') {
+      throw fmt::format_error("invalid format");
+    }
+
+    return it;
+  }
+
+  /**
+   * Writes out a formatted matrix.
+   *
+   * @tparam FormatContext Format string context type.
+   * @param mat Matrix to format.
+   * @param ctx Format string context.
+   */
+  template <typename FormatContext>
+  auto format(const Eigen::SparseMatrix<double, Options, StorageIndex>& mat,
+              FormatContext& ctx) {
+    auto out = ctx.out();
+    for (int i = 0; i < mat.rows(); ++i) {
+      for (int j = 0; j < mat.cols(); ++j) {
+        out = fmt::format_to(out, "  {:f}", mat.coeff(i, j));
+      }
+
+      if (i < mat.rows() - 1) {
         out = fmt::format_to(out, "\n");
       }
     }
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/CoordinateAxis.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/CoordinateAxis.h
new file mode 100644
index 0000000..58b966a
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/CoordinateAxis.h
@@ -0,0 +1,73 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <wpi/SymbolExports.h>
+
+#include "frc/EigenCore.h"
+#include "frc/geometry/Pose3d.h"
+#include "frc/geometry/Rotation3d.h"
+
+namespace frc {
+
+/**
+ * A class representing a coordinate system axis within the NWU coordinate
+ * system.
+ */
+class WPILIB_DLLEXPORT CoordinateAxis {
+ public:
+  /**
+   * Constructs a coordinate system axis within the NWU coordinate system and
+   * normalizes it.
+   *
+   * @param x The x component.
+   * @param y The y component.
+   * @param z The z component.
+   */
+  CoordinateAxis(double x, double y, double z);
+
+  CoordinateAxis(const CoordinateAxis&) = default;
+  CoordinateAxis& operator=(const CoordinateAxis&) = default;
+
+  CoordinateAxis(CoordinateAxis&&) = default;
+  CoordinateAxis& operator=(CoordinateAxis&&) = default;
+
+  /**
+   * Returns a coordinate axis corresponding to +X in the NWU coordinate system.
+   */
+  static const CoordinateAxis& N();
+
+  /**
+   * Returns a coordinate axis corresponding to -X in the NWU coordinate system.
+   */
+  static const CoordinateAxis& S();
+
+  /**
+   * Returns a coordinate axis corresponding to -Y in the NWU coordinate system.
+   */
+  static const CoordinateAxis& E();
+
+  /**
+   * Returns a coordinate axis corresponding to +Y in the NWU coordinate system.
+   */
+  static const CoordinateAxis& W();
+
+  /**
+   * Returns a coordinate axis corresponding to +Z in the NWU coordinate system.
+   */
+  static const CoordinateAxis& U();
+
+  /**
+   * Returns a coordinate axis corresponding to -Z in the NWU coordinate system.
+   */
+  static const CoordinateAxis& D();
+
+ private:
+  friend class CoordinateSystem;
+
+  Vectord<3> m_axis;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/CoordinateSystem.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/CoordinateSystem.h
new file mode 100644
index 0000000..232455f
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/CoordinateSystem.h
@@ -0,0 +1,114 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <wpi/SymbolExports.h>
+
+#include "frc/EigenCore.h"
+#include "frc/geometry/CoordinateAxis.h"
+#include "frc/geometry/Pose3d.h"
+#include "frc/geometry/Rotation3d.h"
+#include "frc/geometry/Translation3d.h"
+
+namespace frc {
+
+/**
+ * A helper class that converts Pose3d objects between different standard
+ * coordinate frames.
+ */
+class WPILIB_DLLEXPORT CoordinateSystem {
+ public:
+  /**
+   * Constructs a coordinate system with the given cardinal directions for each
+   * axis.
+   *
+   * @param positiveX The cardinal direction of the positive x-axis.
+   * @param positiveY The cardinal direction of the positive y-axis.
+   * @param positiveZ The cardinal direction of the positive z-axis.
+   * @throws std::domain_error if the coordinate system isn't special orthogonal
+   */
+  CoordinateSystem(const CoordinateAxis& positiveX,
+                   const CoordinateAxis& positiveY,
+                   const CoordinateAxis& positiveZ);
+
+  CoordinateSystem(const CoordinateSystem&) = default;
+  CoordinateSystem& operator=(const CoordinateSystem&) = default;
+  CoordinateSystem(CoordinateSystem&&) = default;
+  CoordinateSystem& operator=(CoordinateSystem&&) = default;
+
+  /**
+   * Returns an instance of the North-West-Up (NWU) coordinate system.
+   *
+   * The +X axis is north, the +Y axis is west, and the +Z axis is up.
+   */
+  static const CoordinateSystem& NWU();
+
+  /**
+   * Returns an instance of the East-Down-North (EDN) coordinate system.
+   *
+   * The +X axis is east, the +Y axis is down, and the +Z axis is north.
+   */
+  static const CoordinateSystem& EDN();
+
+  /**
+   * Returns an instance of the NED coordinate system.
+   *
+   * The +X axis is north, the +Y axis is east, and the +Z axis is down.
+   */
+  static const CoordinateSystem& NED();
+
+  /**
+   * Converts the given translation from one coordinate system to another.
+   *
+   * @param translation The translation to convert.
+   * @param from The coordinate system the translation starts in.
+   * @param to The coordinate system to which to convert.
+   * @return The given translation in the desired coordinate system.
+   */
+  static Translation3d Convert(const Translation3d& translation,
+                               const CoordinateSystem& from,
+                               const CoordinateSystem& to);
+
+  /**
+   * Converts the given rotation from one coordinate system to another.
+   *
+   * @param rotation The rotation to convert.
+   * @param from The coordinate system the rotation starts in.
+   * @param to The coordinate system to which to convert.
+   * @return The given rotation in the desired coordinate system.
+   */
+  static Rotation3d Convert(const Rotation3d& rotation,
+                            const CoordinateSystem& from,
+                            const CoordinateSystem& to);
+
+  /**
+   * Converts the given pose from one coordinate system to another.
+   *
+   * @param pose The pose to convert.
+   * @param from The coordinate system the pose starts in.
+   * @param to The coordinate system to which to convert.
+   * @return The given pose in the desired coordinate system.
+   */
+  static Pose3d Convert(const Pose3d& pose, const CoordinateSystem& from,
+                        const CoordinateSystem& to);
+
+  /**
+   * Converts the given transform from one coordinate system to another.
+   *
+   * @param transform The transform to convert.
+   * @param from The coordinate system the transform starts in.
+   * @param to The coordinate system to which to convert.
+   * @return The given transform in the desired coordinate system.
+   */
+  static Transform3d Convert(const Transform3d& transform,
+                             const CoordinateSystem& from,
+                             const CoordinateSystem& to);
+
+ private:
+  // Rotation from this coordinate system to NWU coordinate system
+  Rotation3d m_rotation;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Pose2d.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Pose2d.h
index ebaa7c1..d096e8c 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Pose2d.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Pose2d.h
@@ -17,13 +17,12 @@
 namespace frc {
 
 /**
- * Represents a 2d pose containing translational and rotational elements.
+ * Represents a 2D pose containing translational and rotational elements.
  */
 class WPILIB_DLLEXPORT Pose2d {
  public:
   /**
    * Constructs a pose at the origin facing toward the positive X axis.
-   * (Translation2d{0, 0} and Rotation{0})
    */
   constexpr Pose2d() = default;
 
@@ -33,31 +32,33 @@
    * @param translation The translational component of the pose.
    * @param rotation The rotational component of the pose.
    */
-  Pose2d(Translation2d translation, Rotation2d rotation);
+  constexpr Pose2d(Translation2d translation, Rotation2d rotation);
 
   /**
-   * Convenience constructors that takes in x and y values directly instead of
-   * having to construct a Translation2d.
+   * Constructs a pose with x and y translations instead of a separate
+   * Translation2d.
    *
    * @param x The x component of the translational component of the pose.
    * @param y The y component of the translational component of the pose.
    * @param rotation The rotational component of the pose.
    */
-  Pose2d(units::meter_t x, units::meter_t y, Rotation2d rotation);
+  constexpr Pose2d(units::meter_t x, units::meter_t y, Rotation2d rotation);
 
   /**
    * Transforms the pose by the given transformation and returns the new
    * transformed pose.
    *
+   * <pre>
    * [x_new]    [cos, -sin, 0][transform.x]
    * [y_new] += [sin,  cos, 0][transform.y]
-   * [t_new]    [0,    0,   1][transform.t]
+   * [t_new]    [  0,    0, 1][transform.t]
+   * </pre>
    *
    * @param other The transform to transform the pose by.
    *
    * @return The transformed pose.
    */
-  Pose2d operator+(const Transform2d& other) const;
+  constexpr Pose2d operator+(const Transform2d& other) const;
 
   /**
    * Returns the Transform2d that maps the one pose to another.
@@ -69,47 +70,54 @@
 
   /**
    * Checks equality between this Pose2d and another object.
-   *
-   * @param other The other object.
-   * @return Whether the two objects are equal.
    */
-  bool operator==(const Pose2d& other) const;
-
-  /**
-   * Checks inequality between this Pose2d and another object.
-   *
-   * @param other The other object.
-   * @return Whether the two objects are not equal.
-   */
-  bool operator!=(const Pose2d& other) const;
+  bool operator==(const Pose2d&) const = default;
 
   /**
    * Returns the underlying translation.
    *
    * @return Reference to the translational component of the pose.
    */
-  const Translation2d& Translation() const { return m_translation; }
+  constexpr const Translation2d& Translation() const { return m_translation; }
 
   /**
    * Returns the X component of the pose's translation.
    *
    * @return The x component of the pose's translation.
    */
-  units::meter_t X() const { return m_translation.X(); }
+  constexpr units::meter_t X() const { return m_translation.X(); }
 
   /**
    * Returns the Y component of the pose's translation.
    *
    * @return The y component of the pose's translation.
    */
-  units::meter_t Y() const { return m_translation.Y(); }
+  constexpr units::meter_t Y() const { return m_translation.Y(); }
 
   /**
    * Returns the underlying rotation.
    *
    * @return Reference to the rotational component of the pose.
    */
-  const Rotation2d& Rotation() const { return m_rotation; }
+  constexpr const Rotation2d& Rotation() const { return m_rotation; }
+
+  /**
+   * Multiplies the current pose by a scalar.
+   *
+   * @param scalar The scalar.
+   *
+   * @return The new scaled Pose2d.
+   */
+  constexpr Pose2d operator*(double scalar) const;
+
+  /**
+   * Divides the current pose by a scalar.
+   *
+   * @param scalar The scalar.
+   *
+   * @return The new scaled Pose2d.
+   */
+  constexpr Pose2d operator/(double scalar) const;
 
   /**
    * Transforms the pose by the given transformation and returns the new pose.
@@ -119,10 +127,10 @@
    *
    * @return The transformed pose.
    */
-  Pose2d TransformBy(const Transform2d& other) const;
+  constexpr Pose2d TransformBy(const Transform2d& other) const;
 
   /**
-   * Returns the other pose relative to the current pose.
+   * Returns the current pose relative to the given pose.
    *
    * This function can often be used for trajectory tracking or pose
    * stabilization algorithms to get the error between the reference and the
@@ -152,7 +160,7 @@
    * @param twist The change in pose in the robot's coordinate frame since the
    * previous pose update. For example, if a non-holonomic robot moves forward
    * 0.01 meters and changes angle by 0.5 degrees since the previous pose
-   * update, the twist would be Twist2d{0.01, 0.0, toRadians(0.5)}
+   * update, the twist would be Twist2d{0.01_m, 0_m, 0.5_deg}.
    *
    * @return The new pose of the robot.
    */
@@ -180,3 +188,5 @@
 void from_json(const wpi::json& json, Pose2d& pose);
 
 }  // namespace frc
+
+#include "Pose2d.inc"
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Pose2d.inc b/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Pose2d.inc
new file mode 100644
index 0000000..c549f26
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Pose2d.inc
@@ -0,0 +1,39 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <utility>
+
+#include "frc/geometry/Pose2d.h"
+#include "frc/geometry/Rotation2d.h"
+#include "units/length.h"
+
+namespace frc {
+
+constexpr Pose2d::Pose2d(Translation2d translation, Rotation2d rotation)
+    : m_translation(std::move(translation)), m_rotation(std::move(rotation)) {}
+
+constexpr Pose2d::Pose2d(units::meter_t x, units::meter_t y,
+                         Rotation2d rotation)
+    : m_translation(x, y), m_rotation(std::move(rotation)) {}
+
+constexpr Pose2d Pose2d::operator+(const Transform2d& other) const {
+  return TransformBy(other);
+}
+
+constexpr Pose2d Pose2d::operator*(double scalar) const {
+  return Pose2d{m_translation * scalar, m_rotation * scalar};
+}
+
+constexpr Pose2d Pose2d::operator/(double scalar) const {
+  return *this * (1.0 / scalar);
+}
+
+constexpr Pose2d Pose2d::TransformBy(const Transform2d& other) const {
+  return {m_translation + (other.Translation().RotateBy(m_rotation)),
+          other.Rotation() + m_rotation};
+}
+
+}  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Pose3d.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Pose3d.h
new file mode 100644
index 0000000..8c7ace3
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Pose3d.h
@@ -0,0 +1,204 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <wpi/SymbolExports.h>
+
+#include "Pose2d.h"
+#include "Transform3d.h"
+#include "Translation3d.h"
+#include "Twist3d.h"
+
+namespace wpi {
+class json;
+}  // namespace wpi
+
+namespace frc {
+
+/**
+ * Represents a 3D pose containing translational and rotational elements.
+ */
+class WPILIB_DLLEXPORT Pose3d {
+ public:
+  /**
+   * Constructs a pose at the origin facing toward the positive X axis.
+   */
+  constexpr Pose3d() = default;
+
+  /**
+   * Constructs a pose with the specified translation and rotation.
+   *
+   * @param translation The translational component of the pose.
+   * @param rotation The rotational component of the pose.
+   */
+  Pose3d(Translation3d translation, Rotation3d rotation);
+
+  /**
+   * Constructs a pose with x, y, and z translations instead of a separate
+   * Translation3d.
+   *
+   * @param x The x component of the translational component of the pose.
+   * @param y The y component of the translational component of the pose.
+   * @param z The z component of the translational component of the pose.
+   * @param rotation The rotational component of the pose.
+   */
+  Pose3d(units::meter_t x, units::meter_t y, units::meter_t z,
+         Rotation3d rotation);
+
+  /**
+   * Constructs a 3D pose from a 2D pose in the X-Y plane.
+   *
+   * @param pose The 2D pose.
+   */
+  explicit Pose3d(const Pose2d& pose);
+
+  /**
+   * Transforms the pose by the given transformation and returns the new
+   * transformed pose.
+   *
+   * @param other The transform to transform the pose by.
+   *
+   * @return The transformed pose.
+   */
+  Pose3d operator+(const Transform3d& other) const;
+
+  /**
+   * Returns the Transform3d that maps the one pose to another.
+   *
+   * @param other The initial pose of the transformation.
+   * @return The transform that maps the other pose to the current pose.
+   */
+  Transform3d operator-(const Pose3d& other) const;
+
+  /**
+   * Checks equality between this Pose3d and another object.
+   */
+  bool operator==(const Pose3d&) const = default;
+
+  /**
+   * Returns the underlying translation.
+   *
+   * @return Reference to the translational component of the pose.
+   */
+  const Translation3d& Translation() const { return m_translation; }
+
+  /**
+   * Returns the X component of the pose's translation.
+   *
+   * @return The x component of the pose's translation.
+   */
+  units::meter_t X() const { return m_translation.X(); }
+
+  /**
+   * Returns the Y component of the pose's translation.
+   *
+   * @return The y component of the pose's translation.
+   */
+  units::meter_t Y() const { return m_translation.Y(); }
+
+  /**
+   * Returns the Z component of the pose's translation.
+   *
+   * @return The z component of the pose's translation.
+   */
+  units::meter_t Z() const { return m_translation.Z(); }
+
+  /**
+   * Returns the underlying rotation.
+   *
+   * @return Reference to the rotational component of the pose.
+   */
+  const Rotation3d& Rotation() const { return m_rotation; }
+
+  /**
+   * Multiplies the current pose by a scalar.
+   *
+   * @param scalar The scalar.
+   *
+   * @return The new scaled Pose2d.
+   */
+  Pose3d operator*(double scalar) const;
+
+  /**
+   * Divides the current pose by a scalar.
+   *
+   * @param scalar The scalar.
+   *
+   * @return The new scaled Pose2d.
+   */
+  Pose3d operator/(double scalar) const;
+
+  /**
+   * Transforms the pose by the given transformation and returns the new pose.
+   * See + operator for the matrix multiplication performed.
+   *
+   * @param other The transform to transform the pose by.
+   *
+   * @return The transformed pose.
+   */
+  Pose3d TransformBy(const Transform3d& other) const;
+
+  /**
+   * Returns the current pose relative to the given pose.
+   *
+   * This function can often be used for trajectory tracking or pose
+   * stabilization algorithms to get the error between the reference and the
+   * current pose.
+   *
+   * @param other The pose that is the origin of the new coordinate frame that
+   * the current pose will be converted into.
+   *
+   * @return The current pose relative to the new origin pose.
+   */
+  Pose3d RelativeTo(const Pose3d& other) const;
+
+  /**
+   * Obtain a new Pose3d from a (constant curvature) velocity.
+   *
+   * The twist is a change in pose in the robot's coordinate frame since the
+   * previous pose update. When the user runs exp() on the previous known
+   * field-relative pose with the argument being the twist, the user will
+   * receive the new field-relative pose.
+   *
+   * "Exp" represents the pose exponential, which is solving a differential
+   * equation moving the pose forward in time.
+   *
+   * @param twist The change in pose in the robot's coordinate frame since the
+   * previous pose update. For example, if a non-holonomic robot moves forward
+   * 0.01 meters and changes angle by 0.5 degrees since the previous pose
+   * update, the twist would be Twist3d{0.01_m, 0_m, 0_m, Rotation3d{0.0, 0.0,
+   * 0.5_deg}}.
+   *
+   * @return The new pose of the robot.
+   */
+  Pose3d Exp(const Twist3d& twist) const;
+
+  /**
+   * Returns a Twist3d that maps this pose to the end pose. If c is the output
+   * of a.Log(b), then a.Exp(c) would yield b.
+   *
+   * @param end The end pose for the transformation.
+   *
+   * @return The twist that maps this to end.
+   */
+  Twist3d Log(const Pose3d& end) const;
+
+  /**
+   * Returns a Pose2d representing this Pose3d projected into the X-Y plane.
+   */
+  Pose2d ToPose2d() const;
+
+ private:
+  Translation3d m_translation;
+  Rotation3d m_rotation;
+};
+
+WPILIB_DLLEXPORT
+void to_json(wpi::json& json, const Pose3d& pose);
+
+WPILIB_DLLEXPORT
+void from_json(const wpi::json& json, Pose3d& pose);
+
+}  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Quaternion.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Quaternion.h
new file mode 100644
index 0000000..b5a318b
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Quaternion.h
@@ -0,0 +1,97 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <wpi/SymbolExports.h>
+
+#include "frc/EigenCore.h"
+
+namespace wpi {
+class json;
+}  // namespace wpi
+
+namespace frc {
+
+class WPILIB_DLLEXPORT Quaternion {
+ public:
+  /**
+   * Constructs a quaternion with a default angle of 0 degrees.
+   */
+  Quaternion() = default;
+
+  /**
+   * Constructs a quaternion with the given components.
+   *
+   * @param w W component of the quaternion.
+   * @param x X component of the quaternion.
+   * @param y Y component of the quaternion.
+   * @param z Z component of the quaternion.
+   */
+  Quaternion(double w, double x, double y, double z);
+
+  /**
+   * Multiply with another quaternion.
+   *
+   * @param other The other quaternion.
+   */
+  Quaternion operator*(const Quaternion& other) const;
+
+  /**
+   * Checks equality between this Quaternion and another object.
+   *
+   * @param other The other object.
+   * @return Whether the two objects are equal.
+   */
+  bool operator==(const Quaternion& other) const;
+
+  /**
+   * Returns the inverse of the quaternion.
+   */
+  Quaternion Inverse() const;
+
+  /**
+   * Normalizes the quaternion.
+   */
+  Quaternion Normalize() const;
+
+  /**
+   * Returns W component of the quaternion.
+   */
+  double W() const;
+
+  /**
+   * Returns X component of the quaternion.
+   */
+  double X() const;
+
+  /**
+   * Returns Y component of the quaternion.
+   */
+  double Y() const;
+
+  /**
+   * Returns Z component of the quaternion.
+   */
+  double Z() const;
+
+  /**
+   * Returns the rotation vector representation of this quaternion.
+   *
+   * This is also the log operator of SO(3).
+   */
+  Eigen::Vector3d ToRotationVector() const;
+
+ private:
+  double m_r = 1.0;
+  Eigen::Vector3d m_v{0.0, 0.0, 0.0};
+};
+
+WPILIB_DLLEXPORT
+void to_json(wpi::json& json, const Quaternion& quaternion);
+
+WPILIB_DLLEXPORT
+void from_json(const wpi::json& json, Quaternion& quaternion);
+
+}  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Rotation2d.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Rotation2d.h
index 94a17fc..406ef3c 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Rotation2d.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Rotation2d.h
@@ -15,8 +15,13 @@
 namespace frc {
 
 /**
- * A rotation in a 2d coordinate frame represented a point on the unit circle
+ * A rotation in a 2D coordinate frame represented by a point on the unit circle
  * (cosine and sine).
+ *
+ * The angle is continuous, that is if a Rotation2d is constructed with 361
+ * degrees, it will return 361 degrees. This allows algorithms that wouldn't
+ * want to see a discontinuity in the rotations as it sweeps past from 360 to 0
+ * on the second time around.
  */
 class WPILIB_DLLEXPORT Rotation2d {
  public:
@@ -30,14 +35,14 @@
    *
    * @param value The value of the angle in radians.
    */
-  Rotation2d(units::radian_t value);  // NOLINT
+  constexpr Rotation2d(units::radian_t value);  // NOLINT
 
   /**
    * Constructs a Rotation2d with the given degree value.
    *
    * @param value The value of the angle in degrees.
    */
-  Rotation2d(units::degree_t value);  // NOLINT
+  constexpr Rotation2d(units::degree_t value);  // NOLINT
 
   /**
    * Constructs a Rotation2d with the given x and y (cosine and sine)
@@ -46,33 +51,33 @@
    * @param x The x component or cosine of the rotation.
    * @param y The y component or sine of the rotation.
    */
-  Rotation2d(double x, double y);
+  constexpr Rotation2d(double x, double y);
 
   /**
    * Adds two rotations together, with the result being bounded between -pi and
    * pi.
    *
-   * For example, Rotation2d.FromDegrees(30) + Rotation2d.FromDegrees(60) =
-   * Rotation2d{-pi/2}
+   * For example, <code>Rotation2d{30_deg} + Rotation2d{60_deg}</code> equals
+   * <code>Rotation2d{units::radian_t{std::numbers::pi/2.0}}</code>
    *
    * @param other The rotation to add.
    *
    * @return The sum of the two rotations.
    */
-  Rotation2d operator+(const Rotation2d& other) const;
+  constexpr Rotation2d operator+(const Rotation2d& other) const;
 
   /**
    * Subtracts the new rotation from the current rotation and returns the new
    * rotation.
    *
-   * For example, Rotation2d.FromDegrees(10) - Rotation2d.FromDegrees(100) =
-   * Rotation2d{-pi/2}
+   * For example, <code>Rotation2d{10_deg} - Rotation2d{100_deg}</code> equals
+   * <code>Rotation2d{units::radian_t{-std::numbers::pi/2.0}}</code>
    *
    * @param other The rotation to subtract.
    *
    * @return The difference between the two rotations.
    */
-  Rotation2d operator-(const Rotation2d& other) const;
+  constexpr Rotation2d operator-(const Rotation2d& other) const;
 
   /**
    * Takes the inverse of the current rotation. This is simply the negative of
@@ -80,15 +85,25 @@
    *
    * @return The inverse of the current rotation.
    */
-  Rotation2d operator-() const;
+  constexpr Rotation2d operator-() const;
 
   /**
    * Multiplies the current rotation by a scalar.
+   *
    * @param scalar The scalar.
    *
    * @return The new scaled Rotation2d.
    */
-  Rotation2d operator*(double scalar) const;
+  constexpr Rotation2d operator*(double scalar) const;
+
+  /**
+   * Divides the current rotation by a scalar.
+   *
+   * @param scalar The scalar.
+   *
+   * @return The new scaled Rotation2d.
+   */
+  constexpr Rotation2d operator/(double scalar) const;
 
   /**
    * Checks equality between this Rotation2d and another object.
@@ -96,15 +111,7 @@
    * @param other The other object.
    * @return Whether the two objects are equal.
    */
-  bool operator==(const Rotation2d& other) const;
-
-  /**
-   * Checks inequality between this Rotation2d and another object.
-   *
-   * @param other The other object.
-   * @return Whether the two objects are not equal.
-   */
-  bool operator!=(const Rotation2d& other) const;
+  constexpr bool operator==(const Rotation2d& other) const;
 
   /**
    * Adds the new rotation to the current rotation using a rotation matrix.
@@ -119,42 +126,44 @@
    *
    * @return The new rotated Rotation2d.
    */
-  Rotation2d RotateBy(const Rotation2d& other) const;
+  constexpr Rotation2d RotateBy(const Rotation2d& other) const;
 
   /**
    * Returns the radian value of the rotation.
    *
    * @return The radian value of the rotation.
+   * @see AngleModulus to constrain the angle within (-pi, pi]
    */
-  units::radian_t Radians() const { return m_value; }
+  constexpr units::radian_t Radians() const { return m_value; }
 
   /**
    * Returns the degree value of the rotation.
    *
    * @return The degree value of the rotation.
+   * @see InputModulus to constrain the angle within (-180, 180]
    */
-  units::degree_t Degrees() const { return m_value; }
+  constexpr units::degree_t Degrees() const { return m_value; }
 
   /**
    * Returns the cosine of the rotation.
    *
    * @return The cosine of the rotation.
    */
-  double Cos() const { return m_cos; }
+  constexpr double Cos() const { return m_cos; }
 
   /**
    * Returns the sine of the rotation.
    *
    * @return The sine of the rotation.
    */
-  double Sin() const { return m_sin; }
+  constexpr double Sin() const { return m_sin; }
 
   /**
    * Returns the tangent of the rotation.
    *
    * @return The tangent of the rotation.
    */
-  double Tan() const { return m_sin / m_cos; }
+  constexpr double Tan() const { return Sin() / Cos(); }
 
  private:
   units::radian_t m_value = 0_rad;
@@ -169,3 +178,5 @@
 void from_json(const wpi::json& json, Rotation2d& rotation);
 
 }  // namespace frc
+
+#include "Rotation2d.inc"
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Rotation2d.inc b/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Rotation2d.inc
new file mode 100644
index 0000000..eb31ebd
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Rotation2d.inc
@@ -0,0 +1,70 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <type_traits>
+
+#include "frc/geometry/Rotation2d.h"
+#include "gcem.hpp"
+#include "units/angle.h"
+
+namespace frc {
+
+constexpr Rotation2d::Rotation2d(units::radian_t value)
+    : m_value(value),
+      m_cos(std::is_constant_evaluated() ? gcem::cos(value.to<double>())
+                                         : std::cos(value.to<double>())),
+      m_sin(std::is_constant_evaluated() ? gcem::sin(value.to<double>())
+                                         : std::sin(value.to<double>())) {}
+
+constexpr Rotation2d::Rotation2d(units::degree_t value)
+    : Rotation2d(units::radian_t{value}) {}
+
+constexpr Rotation2d::Rotation2d(double x, double y) {
+  const auto magnitude = gcem::hypot(x, y);
+  if (magnitude > 1e-6) {
+    m_sin = y / magnitude;
+    m_cos = x / magnitude;
+  } else {
+    m_sin = 0.0;
+    m_cos = 1.0;
+  }
+  m_value =
+      units::radian_t{std::is_constant_evaluated() ? gcem::atan2(m_sin, m_cos)
+                                                   : std::atan2(m_sin, m_cos)};
+}
+
+constexpr Rotation2d Rotation2d::operator-() const {
+  return Rotation2d{-m_value};
+}
+
+constexpr Rotation2d Rotation2d::operator*(double scalar) const {
+  return Rotation2d(m_value * scalar);
+}
+
+constexpr Rotation2d Rotation2d::operator+(const Rotation2d& other) const {
+  return RotateBy(other);
+}
+
+constexpr Rotation2d Rotation2d::operator-(const Rotation2d& other) const {
+  return *this + -other;
+}
+
+constexpr Rotation2d Rotation2d::operator/(double scalar) const {
+  return *this * (1.0 / scalar);
+}
+
+constexpr bool Rotation2d::operator==(const Rotation2d& other) const {
+  return (std::is_constant_evaluated()
+              ? gcem::hypot(Cos() - other.Cos(), Sin() - other.Sin())
+              : std::hypot(Cos() - other.Cos(), Sin() - other.Sin())) < 1E-9;
+}
+
+constexpr Rotation2d Rotation2d::RotateBy(const Rotation2d& other) const {
+  return {Cos() * other.Cos() - Sin() * other.Sin(),
+          Cos() * other.Sin() + Sin() * other.Cos()};
+}
+
+}  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Rotation3d.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Rotation3d.h
new file mode 100644
index 0000000..7c1a60d
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Rotation3d.h
@@ -0,0 +1,186 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <wpi/SymbolExports.h>
+
+#include "Quaternion.h"
+#include "Rotation2d.h"
+#include "frc/EigenCore.h"
+#include "units/angle.h"
+
+namespace wpi {
+class json;
+}  // namespace wpi
+
+namespace frc {
+
+/**
+ * A rotation in a 3D coordinate frame represented by a quaternion.
+ */
+class WPILIB_DLLEXPORT Rotation3d {
+ public:
+  /**
+   * Constructs a Rotation3d with a default angle of 0 degrees.
+   */
+  Rotation3d() = default;
+
+  /**
+   * Constructs a Rotation3d from a quaternion.
+   *
+   * @param q The quaternion.
+   */
+  explicit Rotation3d(const Quaternion& q);
+
+  /**
+   * Constructs a Rotation3d from extrinsic roll, pitch, and yaw.
+   *
+   * Extrinsic rotations occur in that order around the axes in the fixed global
+   * frame rather than the body frame.
+   *
+   * Angles are measured counterclockwise with the rotation axis pointing "out
+   * of the page". If you point your right thumb along the positive axis
+   * direction, your fingers curl in the direction of positive rotation.
+   *
+   * @param roll The counterclockwise rotation angle around the X axis (roll).
+   * @param pitch The counterclockwise rotation angle around the Y axis (pitch).
+   * @param yaw The counterclockwise rotation angle around the Z axis (yaw).
+   */
+  Rotation3d(units::radian_t roll, units::radian_t pitch, units::radian_t yaw);
+
+  /**
+   * Constructs a Rotation3d with the given axis-angle representation. The axis
+   * doesn't have to be normalized.
+   *
+   * @param axis The rotation axis.
+   * @param angle The rotation around the axis.
+   */
+  Rotation3d(const Vectord<3>& axis, units::radian_t angle);
+
+  /**
+   * Constructs a Rotation3d from a rotation matrix.
+   *
+   * @param rotationMatrix The rotation matrix.
+   * @throws std::domain_error if the rotation matrix isn't special orthogonal.
+   */
+  explicit Rotation3d(const Matrixd<3, 3>& rotationMatrix);
+
+  /**
+   * Constructs a Rotation3d that rotates the initial vector onto the final
+   * vector.
+   *
+   * This is useful for turning a 3D vector (final) into an orientation relative
+   * to a coordinate system vector (initial).
+   *
+   * @param initial The initial vector.
+   * @param final The final vector.
+   */
+  Rotation3d(const Vectord<3>& initial, const Vectord<3>& final);
+
+  /**
+   * Adds two rotations together.
+   *
+   * @param other The rotation to add.
+   *
+   * @return The sum of the two rotations.
+   */
+  Rotation3d operator+(const Rotation3d& other) const;
+
+  /**
+   * Subtracts the new rotation from the current rotation and returns the new
+   * rotation.
+   *
+   * @param other The rotation to subtract.
+   *
+   * @return The difference between the two rotations.
+   */
+  Rotation3d operator-(const Rotation3d& other) const;
+
+  /**
+   * Takes the inverse of the current rotation.
+   *
+   * @return The inverse of the current rotation.
+   */
+  Rotation3d operator-() const;
+
+  /**
+   * Multiplies the current rotation by a scalar.
+   *
+   * @param scalar The scalar.
+   *
+   * @return The new scaled Rotation3d.
+   */
+  Rotation3d operator*(double scalar) const;
+
+  /**
+   * Divides the current rotation by a scalar.
+   *
+   * @param scalar The scalar.
+   *
+   * @return The new scaled Rotation3d.
+   */
+  Rotation3d operator/(double scalar) const;
+
+  /**
+   * Checks equality between this Rotation3d and another object.
+   */
+  bool operator==(const Rotation3d&) const = default;
+
+  /**
+   * Adds the new rotation to the current rotation.
+   *
+   * @param other The rotation to rotate by.
+   *
+   * @return The new rotated Rotation3d.
+   */
+  Rotation3d RotateBy(const Rotation3d& other) const;
+
+  /**
+   * Returns the quaternion representation of the Rotation3d.
+   */
+  const Quaternion& GetQuaternion() const;
+
+  /**
+   * Returns the counterclockwise rotation angle around the X axis (roll).
+   */
+  units::radian_t X() const;
+
+  /**
+   * Returns the counterclockwise rotation angle around the Y axis (pitch).
+   */
+  units::radian_t Y() const;
+
+  /**
+   * Returns the counterclockwise rotation angle around the Z axis (yaw).
+   */
+  units::radian_t Z() const;
+
+  /**
+   * Returns the axis in the axis-angle representation of this rotation.
+   */
+  Vectord<3> Axis() const;
+
+  /**
+   * Returns the angle in the axis-angle representation of this rotation.
+   */
+  units::radian_t Angle() const;
+
+  /**
+   * Returns a Rotation2d representing this Rotation3d projected into the X-Y
+   * plane.
+   */
+  Rotation2d ToRotation2d() const;
+
+ private:
+  Quaternion m_q;
+};
+
+WPILIB_DLLEXPORT
+void to_json(wpi::json& json, const Rotation3d& rotation);
+
+WPILIB_DLLEXPORT
+void from_json(const wpi::json& json, Rotation3d& rotation);
+
+}  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Transform2d.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Transform2d.h
index 3d5e1d6..3c21ec1 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Transform2d.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Transform2d.h
@@ -31,7 +31,7 @@
    * @param translation Translational component of the transform.
    * @param rotation Rotational component of the transform.
    */
-  Transform2d(Translation2d translation, Rotation2d rotation);
+  constexpr Transform2d(Translation2d translation, Rotation2d rotation);
 
   /**
    * Constructs the identity transform -- maps an initial pose to itself.
@@ -43,47 +43,57 @@
    *
    * @return Reference to the translational component of the transform.
    */
-  const Translation2d& Translation() const { return m_translation; }
+  constexpr const Translation2d& Translation() const { return m_translation; }
 
   /**
    * Returns the X component of the transformation's translation.
    *
    * @return The x component of the transformation's translation.
    */
-  units::meter_t X() const { return m_translation.X(); }
+  constexpr units::meter_t X() const { return m_translation.X(); }
 
   /**
    * Returns the Y component of the transformation's translation.
    *
    * @return The y component of the transformation's translation.
    */
-  units::meter_t Y() const { return m_translation.Y(); }
+  constexpr units::meter_t Y() const { return m_translation.Y(); }
 
   /**
    * Returns the rotational component of the transformation.
    *
    * @return Reference to the rotational component of the transform.
    */
-  const Rotation2d& Rotation() const { return m_rotation; }
+  constexpr const Rotation2d& Rotation() const { return m_rotation; }
 
   /**
    * Invert the transformation. This is useful for undoing a transformation.
    *
    * @return The inverted transformation.
    */
-  Transform2d Inverse() const;
+  constexpr Transform2d Inverse() const;
 
   /**
-   * Scales the transform by the scalar.
+   * Multiplies the transform by the scalar.
    *
    * @param scalar The scalar.
    * @return The scaled Transform2d.
    */
-  Transform2d operator*(double scalar) const {
+  constexpr Transform2d operator*(double scalar) const {
     return Transform2d(m_translation * scalar, m_rotation * scalar);
   }
 
   /**
+   * Divides the transform by the scalar.
+   *
+   * @param scalar The scalar.
+   * @return The scaled Transform2d.
+   */
+  constexpr Transform2d operator/(double scalar) const {
+    return *this * (1.0 / scalar);
+  }
+
+  /**
    * Composes two transformations.
    *
    * @param other The transform to compose with this one.
@@ -93,22 +103,13 @@
 
   /**
    * Checks equality between this Transform2d and another object.
-   *
-   * @param other The other object.
-   * @return Whether the two objects are equal.
    */
-  bool operator==(const Transform2d& other) const;
-
-  /**
-   * Checks inequality between this Transform2d and another object.
-   *
-   * @param other The other object.
-   * @return Whether the two objects are not equal.
-   */
-  bool operator!=(const Transform2d& other) const;
+  bool operator==(const Transform2d&) const = default;
 
  private:
   Translation2d m_translation;
   Rotation2d m_rotation;
 };
 }  // namespace frc
+
+#include "Transform2d.inc"
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Transform2d.inc b/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Transform2d.inc
new file mode 100644
index 0000000..f851a05
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Transform2d.inc
@@ -0,0 +1,26 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <utility>
+
+#include "frc/geometry/Rotation2d.h"
+#include "frc/geometry/Transform2d.h"
+#include "frc/geometry/Translation2d.h"
+
+namespace frc {
+
+constexpr Transform2d::Transform2d(Translation2d translation,
+                                   Rotation2d rotation)
+    : m_translation(std::move(translation)), m_rotation(std::move(rotation)) {}
+
+constexpr Transform2d Transform2d::Inverse() const {
+  // We are rotating the difference between the translations
+  // using a clockwise rotation matrix. This transforms the global
+  // delta into a local delta (relative to the initial pose).
+  return Transform2d{(-Translation()).RotateBy(-Rotation()), -Rotation()};
+}
+
+}  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Transform3d.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Transform3d.h
new file mode 100644
index 0000000..5f50ec2
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Transform3d.h
@@ -0,0 +1,118 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <wpi/SymbolExports.h>
+
+#include "Translation3d.h"
+
+namespace frc {
+
+class WPILIB_DLLEXPORT Pose3d;
+
+/**
+ * Represents a transformation for a Pose3d.
+ */
+class WPILIB_DLLEXPORT Transform3d {
+ public:
+  /**
+   * Constructs the transform that maps the initial pose to the final pose.
+   *
+   * @param initial The initial pose for the transformation.
+   * @param final The final pose for the transformation.
+   */
+  Transform3d(Pose3d initial, Pose3d final);
+
+  /**
+   * Constructs a transform with the given translation and rotation components.
+   *
+   * @param translation Translational component of the transform.
+   * @param rotation Rotational component of the transform.
+   */
+  Transform3d(Translation3d translation, Rotation3d rotation);
+
+  /**
+   * Constructs the identity transform -- maps an initial pose to itself.
+   */
+  constexpr Transform3d() = default;
+
+  /**
+   * Returns the translation component of the transformation.
+   *
+   * @return Reference to the translational component of the transform.
+   */
+  const Translation3d& Translation() const { return m_translation; }
+
+  /**
+   * Returns the X component of the transformation's translation.
+   *
+   * @return The x component of the transformation's translation.
+   */
+  units::meter_t X() const { return m_translation.X(); }
+
+  /**
+   * Returns the Y component of the transformation's translation.
+   *
+   * @return The y component of the transformation's translation.
+   */
+  units::meter_t Y() const { return m_translation.Y(); }
+
+  /**
+   * Returns the Z component of the transformation's translation.
+   *
+   * @return The z component of the transformation's translation.
+   */
+  units::meter_t Z() const { return m_translation.Z(); }
+
+  /**
+   * Returns the rotational component of the transformation.
+   *
+   * @return Reference to the rotational component of the transform.
+   */
+  const Rotation3d& Rotation() const { return m_rotation; }
+
+  /**
+   * Invert the transformation. This is useful for undoing a transformation.
+   *
+   * @return The inverted transformation.
+   */
+  Transform3d Inverse() const;
+
+  /**
+   * Multiplies the transform by the scalar.
+   *
+   * @param scalar The scalar.
+   * @return The scaled Transform3d.
+   */
+  Transform3d operator*(double scalar) const {
+    return Transform3d(m_translation * scalar, m_rotation * scalar);
+  }
+
+  /**
+   * Divides the transform by the scalar.
+   *
+   * @param scalar The scalar.
+   * @return The scaled Transform3d.
+   */
+  Transform3d operator/(double scalar) const { return *this * (1.0 / scalar); }
+
+  /**
+   * Composes two transformations.
+   *
+   * @param other The transform to compose with this one.
+   * @return The composition of the two transformations.
+   */
+  Transform3d operator+(const Transform3d& other) const;
+
+  /**
+   * Checks equality between this Transform3d and another object.
+   */
+  bool operator==(const Transform3d&) const = default;
+
+ private:
+  Translation3d m_translation;
+  Rotation3d m_rotation;
+};
+}  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Translation2d.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Translation2d.h
index 204da30..e168510 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Translation2d.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Translation2d.h
@@ -16,12 +16,12 @@
 namespace frc {
 
 /**
- * Represents a translation in 2d space.
+ * Represents a translation in 2D space.
  * This object can be used to represent a point or a vector.
  *
  * This assumes that you are using conventional mathematical axes.
- * When the robot is placed on the origin, facing toward the X direction,
- * moving forward increases the X, whereas moving to the left increases the Y.
+ * When the robot is at the origin facing in the positive X direction, forward
+ * is positive X and left is positive Y.
  */
 class WPILIB_DLLEXPORT Translation2d {
  public:
@@ -37,7 +37,7 @@
    * @param x The x component of the translation.
    * @param y The y component of the translation.
    */
-  Translation2d(units::meter_t x, units::meter_t y);
+  constexpr Translation2d(units::meter_t x, units::meter_t y);
 
   /**
    * Constructs a Translation2d with the provided distance and angle. This is
@@ -46,13 +46,12 @@
    * @param distance The distance from the origin to the end of the translation.
    * @param angle The angle between the x-axis and the translation vector.
    */
-  Translation2d(units::meter_t distance, const Rotation2d& angle);
+  constexpr Translation2d(units::meter_t distance, const Rotation2d& angle);
 
   /**
-   * Calculates the distance between two translations in 2d space.
+   * Calculates the distance between two translations in 2D space.
    *
-   * This function uses the pythagorean theorem to calculate the distance.
-   * distance = std::sqrt((x2 - x1)^2 + (y2 - y1)^2)
+   * The distance between translations is defined as √((x₂−x₁)²+(y₂−y₁)²).
    *
    * @param other The translation to compute the distance to.
    *
@@ -63,16 +62,16 @@
   /**
    * Returns the X component of the translation.
    *
-   * @return The x component of the translation.
+   * @return The X component of the translation.
    */
-  units::meter_t X() const { return m_x; }
+  constexpr units::meter_t X() const { return m_x; }
 
   /**
    * Returns the Y component of the translation.
    *
-   * @return The y component of the translation.
+   * @return The Y component of the translation.
    */
-  units::meter_t Y() const { return m_y; }
+  constexpr units::meter_t Y() const { return m_y; }
 
   /**
    * Returns the norm, or distance from the origin to the translation.
@@ -82,79 +81,86 @@
   units::meter_t Norm() const;
 
   /**
-   * Applies a rotation to the translation in 2d space.
+   * Returns the angle this translation forms with the positive X axis.
+   *
+   * @return The angle of the translation
+   */
+  constexpr Rotation2d Angle() const;
+
+  /**
+   * Applies a rotation to the translation in 2D space.
    *
    * This multiplies the translation vector by a counterclockwise rotation
    * matrix of the given angle.
    *
+   * <pre>
    * [x_new]   [other.cos, -other.sin][x]
    * [y_new] = [other.sin,  other.cos][y]
+   * </pre>
    *
-   * For example, rotating a Translation2d of {2, 0} by 90 degrees will return a
-   * Translation2d of {0, 2}.
+   * For example, rotating a Translation2d of &lt;2, 0&gt; by 90 degrees will
+   * return a Translation2d of &lt;0, 2&gt;.
    *
    * @param other The rotation to rotate the translation by.
    *
    * @return The new rotated translation.
    */
-  Translation2d RotateBy(const Rotation2d& other) const;
+  constexpr Translation2d RotateBy(const Rotation2d& other) const;
 
   /**
-   * Adds two translations in 2d space and returns the sum. This is similar to
-   * vector addition.
+   * Returns the sum of two translations in 2D space.
    *
-   * For example, Translation2d{1.0, 2.5} + Translation2d{2.0, 5.5} =
-   * Translation2d{3.0, 8.0}
+   * For example, Translation3d{1.0, 2.5} + Translation3d{2.0, 5.5} =
+   * Translation3d{3.0, 8.0}.
    *
    * @param other The translation to add.
    *
    * @return The sum of the translations.
    */
-  Translation2d operator+(const Translation2d& other) const;
+  constexpr Translation2d operator+(const Translation2d& other) const;
 
   /**
-   * Subtracts the other translation from the other translation and returns the
-   * difference.
+   * Returns the difference between two translations.
    *
    * For example, Translation2d{5.0, 4.0} - Translation2d{1.0, 2.0} =
-   * Translation2d{4.0, 2.0}
+   * Translation2d{4.0, 2.0}.
    *
    * @param other The translation to subtract.
    *
    * @return The difference between the two translations.
    */
-  Translation2d operator-(const Translation2d& other) const;
+  constexpr Translation2d operator-(const Translation2d& other) const;
 
   /**
    * Returns the inverse of the current translation. This is equivalent to
-   * rotating by 180 degrees, flipping the point over both axes, or simply
-   * negating both components of the translation.
+   * rotating by 180 degrees, flipping the point over both axes, or negating all
+   * components of the translation.
    *
    * @return The inverse of the current translation.
    */
-  Translation2d operator-() const;
+  constexpr Translation2d operator-() const;
 
   /**
-   * Multiplies the translation by a scalar and returns the new translation.
+   * Returns the translation multiplied by a scalar.
    *
-   * For example, Translation2d{2.0, 2.5} * 2 = Translation2d{4.0, 5.0}
+   * For example, Translation2d{2.0, 2.5} * 2 = Translation2d{4.0, 5.0}.
    *
    * @param scalar The scalar to multiply by.
    *
    * @return The scaled translation.
    */
-  Translation2d operator*(double scalar) const;
+  constexpr Translation2d operator*(double scalar) const;
 
   /**
-   * Divides the translation by a scalar and returns the new translation.
+   * Returns the translation divided by a scalar.
    *
-   * For example, Translation2d{2.0, 2.5} / 2 = Translation2d{1.0, 1.25}
+   * For example, Translation2d{2.0, 2.5} / 2 = Translation2d{1.0, 1.25}.
    *
    * @param scalar The scalar to divide by.
    *
    * @return The scaled translation.
    */
-  Translation2d operator/(double scalar) const;
+  constexpr Translation2d operator/(double scalar) const;
 
   /**
    * Checks equality between this Translation2d and another object.
@@ -164,14 +170,6 @@
    */
   bool operator==(const Translation2d& other) const;
 
-  /**
-   * Checks inequality between this Translation2d and another object.
-   *
-   * @param other The other object.
-   * @return Whether the two objects are not equal.
-   */
-  bool operator!=(const Translation2d& other) const;
-
  private:
   units::meter_t m_x = 0_m;
   units::meter_t m_y = 0_m;
@@ -184,3 +182,5 @@
 void from_json(const wpi::json& json, Translation2d& state);
 
 }  // namespace frc
+
+#include "Translation2d.inc"
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Translation2d.inc b/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Translation2d.inc
new file mode 100644
index 0000000..3be897f
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Translation2d.inc
@@ -0,0 +1,50 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include "frc/geometry/Translation2d.h"
+#include "units/length.h"
+
+namespace frc {
+
+constexpr Translation2d::Translation2d(units::meter_t x, units::meter_t y)
+    : m_x(x), m_y(y) {}
+
+constexpr Translation2d::Translation2d(units::meter_t distance,
+                                       const Rotation2d& angle)
+    : m_x(distance * angle.Cos()), m_y(distance * angle.Sin()) {}
+
+constexpr Rotation2d Translation2d::Angle() const {
+  return Rotation2d{m_x.value(), m_y.value()};
+}
+
+constexpr Translation2d Translation2d::RotateBy(const Rotation2d& other) const {
+  return {m_x * other.Cos() - m_y * other.Sin(),
+          m_x * other.Sin() + m_y * other.Cos()};
+}
+
+constexpr Translation2d Translation2d::operator+(
+    const Translation2d& other) const {
+  return {X() + other.X(), Y() + other.Y()};
+}
+
+constexpr Translation2d Translation2d::operator-(
+    const Translation2d& other) const {
+  return *this + -other;
+}
+
+constexpr Translation2d Translation2d::operator-() const {
+  return {-m_x, -m_y};
+}
+
+constexpr Translation2d Translation2d::operator*(double scalar) const {
+  return {scalar * m_x, scalar * m_y};
+}
+
+constexpr Translation2d Translation2d::operator/(double scalar) const {
+  return operator*(1.0 / scalar);
+}
+
+}  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Translation3d.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Translation3d.h
new file mode 100644
index 0000000..ab641fa
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Translation3d.h
@@ -0,0 +1,189 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <wpi/SymbolExports.h>
+
+#include "Rotation3d.h"
+#include "Translation2d.h"
+#include "units/length.h"
+
+namespace wpi {
+class json;
+}  // namespace wpi
+
+namespace frc {
+
+/**
+ * Represents a translation in 3D space.
+ * This object can be used to represent a point or a vector.
+ *
+ * This assumes that you are using conventional mathematical axes. When the
+ * robot is at the origin facing in the positive X direction, forward is
+ * positive X, left is positive Y, and up is positive Z.
+ */
+class WPILIB_DLLEXPORT Translation3d {
+ public:
+  /**
+   * Constructs a Translation3d with X, Y, and Z components equal to zero.
+   */
+  constexpr Translation3d() = default;
+
+  /**
+   * Constructs a Translation3d with the X, Y, and Z components equal to the
+   * provided values.
+   *
+   * @param x The x component of the translation.
+   * @param y The y component of the translation.
+   * @param z The z component of the translation.
+   */
+  constexpr Translation3d(units::meter_t x, units::meter_t y, units::meter_t z);
+
+  /**
+   * Constructs a Translation3d with the provided distance and angle. This is
+   * essentially converting from polar coordinates to Cartesian coordinates.
+   *
+   * @param distance The distance from the origin to the end of the translation.
+   * @param angle The angle between the x-axis and the translation vector.
+   */
+  Translation3d(units::meter_t distance, const Rotation3d& angle);
+
+  /**
+   * Calculates the distance between two translations in 3D space.
+   *
+   * The distance between translations is defined as
+   * √((x₂−x₁)²+(y₂−y₁)²+(z₂−z₁)²).
+   *
+   * @param other The translation to compute the distance to.
+   *
+   * @return The distance between the two translations.
+   */
+  units::meter_t Distance(const Translation3d& other) const;
+
+  /**
+   * Returns the X component of the translation.
+   *
+   * @return The Z component of the translation.
+   */
+  constexpr units::meter_t X() const { return m_x; }
+
+  /**
+   * Returns the Y component of the translation.
+   *
+   * @return The Y component of the translation.
+   */
+  constexpr units::meter_t Y() const { return m_y; }
+
+  /**
+   * Returns the Z component of the translation.
+   *
+   * @return The Z component of the translation.
+   */
+  constexpr units::meter_t Z() const { return m_z; }
+
+  /**
+   * Returns the norm, or distance from the origin to the translation.
+   *
+   * @return The norm of the translation.
+   */
+  units::meter_t Norm() const;
+
+  /**
+   * Applies a rotation to the translation in 3D space.
+   *
+   * For example, rotating a Translation3d of &lt;2, 0, 0&gt; by 90 degrees
+   * around the Z axis will return a Translation3d of &lt;0, 2, 0&gt;.
+   *
+   * @param other The rotation to rotate the translation by.
+   *
+   * @return The new rotated translation.
+   */
+  Translation3d RotateBy(const Rotation3d& other) const;
+
+  /**
+   * Returns a Translation2d representing this Translation3d projected into the
+   * X-Y plane.
+   */
+  constexpr Translation2d ToTranslation2d() const;
+
+  /**
+   * Returns the sum of two translations in 3D space.
+   *
+   * For example, Translation3d{1.0, 2.5, 3.5} + Translation3d{2.0, 5.5, 7.5} =
+   * Translation3d{3.0, 8.0, 11.0}.
+   *
+   * @param other The translation to add.
+   *
+   * @return The sum of the translations.
+   */
+  constexpr Translation3d operator+(const Translation3d& other) const;
+
+  /**
+   * Returns the difference between two translations.
+   *
+   * For example, Translation3d{5.0, 4.0, 3.0} - Translation3d{1.0, 2.0, 3.0} =
+   * Translation3d{4.0, 2.0, 0.0}.
+   *
+   * @param other The translation to subtract.
+   *
+   * @return The difference between the two translations.
+   */
+  constexpr Translation3d operator-(const Translation3d& other) const;
+
+  /**
+   * Returns the inverse of the current translation. This is equivalent to
+   * negating all components of the translation.
+   *
+   * @return The inverse of the current translation.
+   */
+  constexpr Translation3d operator-() const;
+
+  /**
+   * Returns the translation multiplied by a scalar.
+   *
+   * For example, Translation3d{2.0, 2.5, 4.5} * 2 = Translation3d{4.0, 5.0,
+   * 9.0}.
+   *
+   * @param scalar The scalar to multiply by.
+   *
+   * @return The scaled translation.
+   */
+  constexpr Translation3d operator*(double scalar) const;
+
+  /**
+   * Returns the translation divided by a scalar.
+   *
+   * For example, Translation3d{2.0, 2.5, 4.5} / 2 = Translation3d{1.0, 1.25,
+   * 2.25}.
+   *
+   * @param scalar The scalar to divide by.
+   *
+   * @return The scaled translation.
+   */
+  constexpr Translation3d operator/(double scalar) const;
+
+  /**
+   * Checks equality between this Translation3d and another object.
+   *
+   * @param other The other object.
+   * @return Whether the two objects are equal.
+   */
+  bool operator==(const Translation3d& other) const;
+
+ private:
+  units::meter_t m_x = 0_m;
+  units::meter_t m_y = 0_m;
+  units::meter_t m_z = 0_m;
+};
+
+WPILIB_DLLEXPORT
+void to_json(wpi::json& json, const Translation3d& state);
+
+WPILIB_DLLEXPORT
+void from_json(const wpi::json& json, Translation3d& state);
+
+}  // namespace frc
+
+#include "Translation3d.inc"
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Translation3d.inc b/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Translation3d.inc
new file mode 100644
index 0000000..8ab6e94
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Translation3d.inc
@@ -0,0 +1,44 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include "frc/geometry/Translation2d.h"
+#include "frc/geometry/Translation3d.h"
+#include "units/length.h"
+#include "units/math.h"
+
+namespace frc {
+
+constexpr Translation3d::Translation3d(units::meter_t x, units::meter_t y,
+                                       units::meter_t z)
+    : m_x(x), m_y(y), m_z(z) {}
+
+constexpr Translation2d Translation3d::ToTranslation2d() const {
+  return Translation2d{m_x, m_y};
+}
+
+constexpr Translation3d Translation3d::operator+(
+    const Translation3d& other) const {
+  return {X() + other.X(), Y() + other.Y(), Z() + other.Z()};
+}
+
+constexpr Translation3d Translation3d::operator-(
+    const Translation3d& other) const {
+  return operator+(-other);
+}
+
+constexpr Translation3d Translation3d::operator-() const {
+  return {-m_x, -m_y, -m_z};
+}
+
+constexpr Translation3d Translation3d::operator*(double scalar) const {
+  return {scalar * m_x, scalar * m_y, scalar * m_z};
+}
+
+constexpr Translation3d Translation3d::operator/(double scalar) const {
+  return operator*(1.0 / scalar);
+}
+
+}  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Twist2d.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Twist2d.h
index 6ad2b38..620b688 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Twist2d.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Twist2d.h
@@ -12,9 +12,9 @@
 
 namespace frc {
 /**
- * A change in distance along arc since the last pose update. We can use ideas
- * from differential calculus to create new Pose2ds from a Twist2d and vise
- * versa.
+ * A change in distance along a 2D arc since the last pose update. We can use
+ * ideas from differential calculus to create new Pose2ds from a Twist2d and
+ * vise versa.
  *
  * A Twist can be used to represent a difference between two poses.
  */
@@ -47,20 +47,12 @@
   }
 
   /**
-   * Checks inequality between this Twist2d and another object.
-   *
-   * @param other The other object.
-   * @return Whether the two objects are not equal.
-   */
-  bool operator!=(const Twist2d& other) const { return !operator==(other); }
-
-  /**
    * Scale this by a given factor.
    *
    * @param factor The factor by which to scale.
    * @return The scaled Twist2d.
    */
-  Twist2d operator*(double factor) const {
+  constexpr Twist2d operator*(double factor) const {
     return Twist2d{dx * factor, dy * factor, dtheta * factor};
   }
 };
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Twist3d.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Twist3d.h
new file mode 100644
index 0000000..3040ab3
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/geometry/Twist3d.h
@@ -0,0 +1,79 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <wpi/SymbolExports.h>
+
+#include "frc/geometry/Rotation3d.h"
+#include "units/angle.h"
+#include "units/length.h"
+#include "units/math.h"
+
+namespace frc {
+/**
+ * A change in distance along a 3D arc since the last pose update. We can use
+ * ideas from differential calculus to create new Pose3ds from a Twist3d and
+ * vise versa.
+ *
+ * A Twist can be used to represent a difference between two poses.
+ */
+struct WPILIB_DLLEXPORT Twist3d {
+  /**
+   * Linear "dx" component
+   */
+  units::meter_t dx = 0_m;
+
+  /**
+   * Linear "dy" component
+   */
+  units::meter_t dy = 0_m;
+
+  /**
+   * Linear "dz" component
+   */
+  units::meter_t dz = 0_m;
+
+  /**
+   * Rotation vector x component.
+   */
+  units::radian_t rx = 0_rad;
+
+  /**
+   * Rotation vector y component.
+   */
+  units::radian_t ry = 0_rad;
+
+  /**
+   * Rotation vector z component.
+   */
+  units::radian_t rz = 0_rad;
+
+  /**
+   * Checks equality between this Twist3d and another object.
+   *
+   * @param other The other object.
+   * @return Whether the two objects are equal.
+   */
+  bool operator==(const Twist3d& other) const {
+    return units::math::abs(dx - other.dx) < 1E-9_m &&
+           units::math::abs(dy - other.dy) < 1E-9_m &&
+           units::math::abs(dz - other.dz) < 1E-9_m &&
+           units::math::abs(rx - other.rx) < 1E-9_rad &&
+           units::math::abs(ry - other.ry) < 1E-9_rad &&
+           units::math::abs(rz - other.rz) < 1E-9_rad;
+  }
+
+  /**
+   * Scale this by a given factor.
+   *
+   * @param factor The factor by which to scale.
+   * @return The scaled Twist3d.
+   */
+  constexpr Twist3d operator*(double factor) const {
+    return Twist3d{dx * factor, dy * factor, dz * factor,
+                   rx * factor, ry * factor, rz * factor};
+  }
+};
+}  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/interpolation/TimeInterpolatableBuffer.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/interpolation/TimeInterpolatableBuffer.h
index a049e40..771fe84 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/interpolation/TimeInterpolatableBuffer.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/interpolation/TimeInterpolatableBuffer.h
@@ -4,9 +4,11 @@
 
 #pragma once
 
+#include <algorithm>
 #include <array>
 #include <functional>
 #include <map>
+#include <optional>
 #include <utility>
 #include <vector>
 
@@ -81,12 +83,16 @@
   void Clear() { m_pastSnapshots.clear(); }
 
   /**
-   * Sample the buffer at the given time. If there are no elements in the
-   * buffer, calling this function results in undefined behavior.
+   * Sample the buffer at the given time. If the buffer is empty, an empty
+   * optional is returned.
    *
    * @param time The time at which to sample the buffer.
    */
-  T Sample(units::second_t time) {
+  std::optional<T> Sample(units::second_t time) {
+    if (m_pastSnapshots.empty()) {
+      return {};
+    }
+
     // We will perform a binary search to find the index of the element in the
     // vector that has a timestamp that is equal to or greater than the vision
     // measurement timestamp.
@@ -114,6 +120,14 @@
     return m_interpolatingFunc(lower_bound->second, upper_bound->second, t);
   }
 
+  /**
+   * Grant access to the internal sample buffer. Used in Pose Estimation to
+   * replay odometry inputs stored within this buffer.
+   */
+  std::vector<std::pair<units::second_t, T>>& GetInternalBuffer() {
+    return m_pastSnapshots;
+  }
+
  private:
   units::second_t m_historySize;
   std::vector<std::pair<units::second_t, T>> m_pastSnapshots;
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/ChassisSpeeds.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/ChassisSpeeds.h
index 7414dec..37fe768 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/ChassisSpeeds.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/ChassisSpeeds.h
@@ -60,5 +60,26 @@
     return {vx * robotAngle.Cos() + vy * robotAngle.Sin(),
             -vx * robotAngle.Sin() + vy * robotAngle.Cos(), omega};
   }
+
+  /**
+   * Converts a user provided field-relative ChassisSpeeds object into a
+   * robot-relative ChassisSpeeds object.
+   *
+   * @param fieldRelativeSpeeds The ChassisSpeeds object representing the speeds
+   *    in the field frame of reference. Positive x is away from your alliance
+   *    wall. Positive y is to your left when standing behind the alliance wall.
+   * @param robotAngle The angle of the robot as measured by a gyroscope. The
+   *    robot's angle is considered to be zero when it is facing directly away
+   *    from your alliance station wall. Remember that this should be CCW
+   *    positive.
+   * @return ChassisSpeeds object representing the speeds in the robot's frame
+   *    of reference.
+   */
+  static ChassisSpeeds FromFieldRelativeSpeeds(
+      const ChassisSpeeds& fieldRelativeSpeeds, const Rotation2d& robotAngle) {
+    return FromFieldRelativeSpeeds(fieldRelativeSpeeds.vx,
+                                   fieldRelativeSpeeds.vy,
+                                   fieldRelativeSpeeds.omega, robotAngle);
+  }
 };
 }  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/DifferentialDriveKinematics.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/DifferentialDriveKinematics.h
index 4bf27ff..930c7a6 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/DifferentialDriveKinematics.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/DifferentialDriveKinematics.h
@@ -6,6 +6,7 @@
 
 #include <wpi/SymbolExports.h>
 
+#include "frc/geometry/Twist2d.h"
 #include "frc/kinematics/ChassisSpeeds.h"
 #include "frc/kinematics/DifferentialDriveWheelSpeeds.h"
 #include "units/angle.h"
@@ -64,6 +65,20 @@
             chassisSpeeds.vx + trackWidth / 2 * chassisSpeeds.omega / 1_rad};
   }
 
+  /**
+   * Returns a twist from left and right distance deltas using
+   * forward kinematics.
+   *
+   * @param leftDistance The distance measured by the left encoder.
+   * @param rightDistance The distance measured by the right encoder.
+   * @return The resulting Twist2d.
+   */
+  constexpr Twist2d ToTwist2d(const units::meter_t leftDistance,
+                              const units::meter_t rightDistance) const {
+    return {(leftDistance + rightDistance) / 2, 0_m,
+            (rightDistance - leftDistance) / trackWidth * 1_rad};
+  }
+
   units::meter_t trackWidth;
 };
 }  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/DifferentialDriveOdometry.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/DifferentialDriveOdometry.h
index 8e992ef..cc198ac 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/DifferentialDriveOdometry.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/DifferentialDriveOdometry.h
@@ -27,30 +27,41 @@
   /**
    * Constructs a DifferentialDriveOdometry object.
    *
+   * IF leftDistance and rightDistance are unspecified,
+   * You NEED to reset your encoders (to zero).
+   *
    * @param gyroAngle The angle reported by the gyroscope.
+   * @param leftDistance The distance traveled by the left encoder.
+   * @param rightDistance The distance traveled by the right encoder.
    * @param initialPose The starting position of the robot on the field.
    */
   explicit DifferentialDriveOdometry(const Rotation2d& gyroAngle,
-                                     const Pose2d& initialPose = Pose2d());
+                                     units::meter_t leftDistance,
+                                     units::meter_t rightDistance,
+                                     const Pose2d& initialPose = Pose2d{});
 
   /**
    * Resets the robot's position on the field.
    *
-   * You NEED to reset your encoders (to zero) when calling this method.
+   * IF leftDistance and rightDistance are unspecified,
+   * You NEED to reset your encoders (to zero).
    *
    * The gyroscope angle does not need to be reset here on the user's robot
    * code. The library automatically takes care of offsetting the gyro angle.
    *
    * @param pose The position on the field that your robot is at.
    * @param gyroAngle The angle reported by the gyroscope.
+   * @param leftDistance The distance traveled by the left encoder.
+   * @param rightDistance The distance traveled by the right encoder.
    */
-  void ResetPosition(const Pose2d& pose, const Rotation2d& gyroAngle) {
+  void ResetPosition(const Rotation2d& gyroAngle, units::meter_t leftDistance,
+                     units::meter_t rightDistance, const Pose2d& pose) {
     m_pose = pose;
     m_previousAngle = pose.Rotation();
     m_gyroOffset = m_pose.Rotation() - gyroAngle;
 
-    m_prevLeftDistance = 0_m;
-    m_prevRightDistance = 0_m;
+    m_prevLeftDistance = leftDistance;
+    m_prevRightDistance = rightDistance;
   }
 
   /**
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/MecanumDriveKinematics.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/MecanumDriveKinematics.h
index 9a7cef9..2880cef 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/MecanumDriveKinematics.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/MecanumDriveKinematics.h
@@ -6,10 +6,12 @@
 
 #include <wpi/SymbolExports.h>
 
-#include "Eigen/Core"
 #include "Eigen/QR"
+#include "frc/EigenCore.h"
 #include "frc/geometry/Translation2d.h"
+#include "frc/geometry/Twist2d.h"
 #include "frc/kinematics/ChassisSpeeds.h"
+#include "frc/kinematics/MecanumDriveWheelPositions.h"
 #include "frc/kinematics/MecanumDriveWheelSpeeds.h"
 #include "wpimath/MathShared.h"
 
@@ -99,7 +101,7 @@
    */
   MecanumDriveWheelSpeeds ToWheelSpeeds(
       const ChassisSpeeds& chassisSpeeds,
-      const Translation2d& centerOfRotation = Translation2d()) const;
+      const Translation2d& centerOfRotation = Translation2d{}) const;
 
   /**
    * Performs forward kinematics to return the resulting chassis state from the
@@ -114,9 +116,21 @@
   ChassisSpeeds ToChassisSpeeds(
       const MecanumDriveWheelSpeeds& wheelSpeeds) const;
 
+  /**
+   * Performs forward kinematics to return the resulting Twist2d from the
+   * given wheel position deltas. This method is often used for odometry --
+   * determining the robot's position on the field using data from the
+   * distance driven by each wheel on the robot.
+   *
+   * @param wheelDeltas The change in distance driven by each wheel.
+   *
+   * @return The resulting chassis speed.
+   */
+  Twist2d ToTwist2d(const MecanumDriveWheelPositions& wheelDeltas) const;
+
  private:
-  mutable Eigen::Matrix<double, 4, 3> m_inverseKinematics;
-  Eigen::HouseholderQR<Eigen::Matrix<double, 4, 3>> m_forwardKinematics;
+  mutable Matrixd<4, 3> m_inverseKinematics;
+  Eigen::HouseholderQR<Matrixd<4, 3>> m_forwardKinematics;
   Translation2d m_frontLeftWheel;
   Translation2d m_frontRightWheel;
   Translation2d m_rearLeftWheel;
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/MecanumDriveOdometry.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/MecanumDriveOdometry.h
index bdd1239..5e949ca 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/MecanumDriveOdometry.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/MecanumDriveOdometry.h
@@ -30,11 +30,13 @@
    *
    * @param kinematics The mecanum drive kinematics for your drivetrain.
    * @param gyroAngle The angle reported by the gyroscope.
+   * @param wheelPositions The current distances measured by each wheel.
    * @param initialPose The starting position of the robot on the field.
    */
-  explicit MecanumDriveOdometry(MecanumDriveKinematics kinematics,
-                                const Rotation2d& gyroAngle,
-                                const Pose2d& initialPose = Pose2d());
+  explicit MecanumDriveOdometry(
+      MecanumDriveKinematics kinematics, const Rotation2d& gyroAngle,
+      const MecanumDriveWheelPositions& wheelPositions,
+      const Pose2d& initialPose = Pose2d{});
 
   /**
    * Resets the robot's position on the field.
@@ -42,13 +44,17 @@
    * The gyroscope angle does not need to be reset here on the user's robot
    * code. The library automatically takes care of offsetting the gyro angle.
    *
-   * @param pose The position on the field that your robot is at.
    * @param gyroAngle The angle reported by the gyroscope.
+   * @param wheelPositions The current distances measured by each wheel.
+   * @param pose The position on the field that your robot is at.
    */
-  void ResetPosition(const Pose2d& pose, const Rotation2d& gyroAngle) {
+  void ResetPosition(const Rotation2d& gyroAngle,
+                     const MecanumDriveWheelPositions& wheelPositions,
+                     const Pose2d& pose) {
     m_pose = pose;
     m_previousAngle = pose.Rotation();
     m_gyroOffset = m_pose.Rotation() - gyroAngle;
+    m_previousWheelPositions = wheelPositions;
   }
 
   /**
@@ -59,45 +65,23 @@
 
   /**
    * Updates the robot's position on the field using forward kinematics and
-   * integration of the pose over time. This method takes in the current time as
-   * a parameter to calculate period (difference between two timestamps). The
-   * period is used to calculate the change in distance from a velocity. This
-   * also takes in an angle parameter which is used instead of the
-   * angular rate that is calculated from forward kinematics.
-   *
-   * @param currentTime The current time.
-   * @param gyroAngle The angle reported by the gyroscope.
-   * @param wheelSpeeds The current wheel speeds.
-   *
-   * @return The new pose of the robot.
-   */
-  const Pose2d& UpdateWithTime(units::second_t currentTime,
-                               const Rotation2d& gyroAngle,
-                               MecanumDriveWheelSpeeds wheelSpeeds);
-
-  /**
-   * Updates the robot's position on the field using forward kinematics and
-   * integration of the pose over time. This method automatically calculates
-   * the current time to calculate period (difference between two timestamps).
-   * The period is used to calculate the change in distance from a velocity.
-   * This also takes in an angle parameter which is used instead of the
-   * angular rate that is calculated from forward kinematics.
+   * integration of the pose over time. This method takes in an angle parameter
+   * which is used instead of the angular rate that is calculated from forward
+   * kinematics, in addition to the current distance measurement at each wheel.
    *
    * @param gyroAngle The angle reported by the gyroscope.
-   * @param wheelSpeeds The current wheel speeds.
+   * @param wheelPositions The current distances measured by each wheel.
    *
    * @return The new pose of the robot.
    */
   const Pose2d& Update(const Rotation2d& gyroAngle,
-                       MecanumDriveWheelSpeeds wheelSpeeds) {
-    return UpdateWithTime(wpi::Now() * 1.0e-6_s, gyroAngle, wheelSpeeds);
-  }
+                       const MecanumDriveWheelPositions& wheelPositions);
 
  private:
   MecanumDriveKinematics m_kinematics;
   Pose2d m_pose;
 
-  units::second_t m_previousTime = -1_s;
+  MecanumDriveWheelPositions m_previousWheelPositions;
   Rotation2d m_previousAngle;
   Rotation2d m_gyroOffset;
 };
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/MecanumDriveWheelPositions.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/MecanumDriveWheelPositions.h
new file mode 100644
index 0000000..b69aceb
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/MecanumDriveWheelPositions.h
@@ -0,0 +1,53 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <wpi/SymbolExports.h>
+
+#include "units/length.h"
+
+namespace frc {
+/**
+ * Represents the wheel speeds for a mecanum drive drivetrain.
+ */
+struct WPILIB_DLLEXPORT MecanumDriveWheelPositions {
+  /**
+   * Distance driven by the front-left wheel.
+   */
+  units::meter_t frontLeft = 0_m;
+
+  /**
+   * Distance driven by the front-right wheel.
+   */
+  units::meter_t frontRight = 0_m;
+
+  /**
+   * Distance driven by the rear-left wheel.
+   */
+  units::meter_t rearLeft = 0_m;
+
+  /**
+   * Distance driven by the rear-right wheel.
+   */
+  units::meter_t rearRight = 0_m;
+
+  /**
+   * Checks equality between this MecanumDriveWheelPositions and another object.
+   *
+   * @param other The other object.
+   * @return Whether the two objects are equal.
+   */
+  bool operator==(const MecanumDriveWheelPositions& other) const = default;
+
+  /**
+   * Checks inequality between this MecanumDriveWheelPositions and another
+   * object.
+   *
+   * @param other The other object.
+   * @return Whether the two objects are not equal.
+   */
+  bool operator!=(const MecanumDriveWheelPositions& other) const = default;
+};
+}  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/SwerveDriveKinematics.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/SwerveDriveKinematics.h
index 9801092..97ee233 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/SwerveDriveKinematics.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/SwerveDriveKinematics.h
@@ -6,13 +6,16 @@
 
 #include <cstddef>
 
+#include <wpi/SymbolExports.h>
 #include <wpi/array.h>
 
-#include "Eigen/Core"
 #include "Eigen/QR"
+#include "frc/EigenCore.h"
 #include "frc/geometry/Rotation2d.h"
 #include "frc/geometry/Translation2d.h"
+#include "frc/geometry/Twist2d.h"
 #include "frc/kinematics/ChassisSpeeds.h"
+#include "frc/kinematics/SwerveModulePosition.h"
 #include "frc/kinematics/SwerveModuleState.h"
 #include "units/velocity.h"
 #include "wpimath/MathShared.h"
@@ -58,7 +61,7 @@
    */
   template <typename... Wheels>
   explicit SwerveDriveKinematics(Translation2d wheel, Wheels&&... wheels)
-      : m_modules{wheel, wheels...} {
+      : m_modules{wheel, wheels...}, m_moduleStates(wpi::empty_array) {
     static_assert(sizeof...(wheels) >= 1,
                   "A swerve drive requires at least two modules");
 
@@ -78,7 +81,7 @@
 
   explicit SwerveDriveKinematics(
       const wpi::array<Translation2d, NumModules>& wheels)
-      : m_modules{wheels} {
+      : m_modules{wheels}, m_moduleStates(wpi::empty_array) {
     for (size_t i = 0; i < NumModules; i++) {
       // clang-format off
       m_inverseKinematics.template block<2, 3>(i * 2, 0) <<
@@ -106,6 +109,9 @@
    * However, if you wish to change the center of rotation for evasive
    * maneuvers, vision alignment, or for any other use case, you can do so.
    *
+   * In the case that the desired chassis speeds are zero (i.e. the robot will
+   * be stationary), the previously calculated module angle will be maintained.
+   *
    * @param chassisSpeeds The desired chassis speed.
    * @param centerOfRotation The center of rotation. For example, if you set the
    * center of rotation at one corner of the robot and provide a chassis speed
@@ -125,7 +131,7 @@
    */
   wpi::array<SwerveModuleState, NumModules> ToSwerveModuleStates(
       const ChassisSpeeds& chassisSpeeds,
-      const Translation2d& centerOfRotation = Translation2d()) const;
+      const Translation2d& centerOfRotation = Translation2d{}) const;
 
   /**
    * Performs forward kinematics to return the resulting chassis state from the
@@ -159,6 +165,38 @@
       wpi::array<SwerveModuleState, NumModules> moduleStates) const;
 
   /**
+   * Performs forward kinematics to return the resulting Twist2d from the
+   * given module position deltas. This method is often used for odometry --
+   * determining the robot's position on the field using data from the
+   * real-world position delta and angle of each module on the robot.
+   *
+   * @param wheelDeltas The latest change in position of the modules (as a
+   * SwerveModulePosition type) as measured from respective encoders and gyros.
+   * The order of the swerve module states should be same as passed into the
+   * constructor of this class.
+   *
+   * @return The resulting Twist2d.
+   */
+  template <typename... ModuleDeltas>
+  Twist2d ToTwist2d(ModuleDeltas&&... wheelDeltas) const;
+
+  /**
+   * Performs forward kinematics to return the resulting Twist2d from the
+   * given module position deltas. This method is often used for odometry --
+   * determining the robot's position on the field using data from the
+   * real-world position delta and angle of each module on the robot.
+   *
+   * @param wheelDeltas The latest change in position of the modules (as a
+   * SwerveModulePosition type) as measured from respective encoders and gyros.
+   * The order of the swerve module states should be same as passed into the
+   * constructor of this class.
+   *
+   * @return The resulting Twist2d.
+   */
+  Twist2d ToTwist2d(
+      wpi::array<SwerveModulePosition, NumModules> wheelDeltas) const;
+
+  /**
    * Renormalizes the wheel speeds if any individual speed is above the
    * specified maximum.
    *
@@ -177,14 +215,46 @@
       wpi::array<SwerveModuleState, NumModules>* moduleStates,
       units::meters_per_second_t attainableMaxSpeed);
 
+  /**
+   * Renormalizes the wheel speeds if any individual speed is above the
+   * specified maximum, as well as getting rid of joystick saturation at edges
+   * of joystick.
+   *
+   * Sometimes, after inverse kinematics, the requested speed
+   * from one or more modules may be above the max attainable speed for the
+   * driving motor on that module. To fix this issue, one can reduce all the
+   * wheel speeds to make sure that all requested module speeds are at-or-below
+   * the absolute threshold, while maintaining the ratio of speeds between
+   * modules.
+   *
+   * @param moduleStates Reference to array of module states. The array will be
+   * mutated with the normalized speeds!
+   * @param currentChassisSpeed Current speed of the robot
+   * @param attainableMaxModuleSpeed The absolute max speed a module can reach
+   * @param attainableMaxRobotTranslationSpeed The absolute max speed the robot
+   * can reach while translating
+   * @param attainableMaxRobotRotationSpeed The absolute max speed the robot can
+   * reach while rotating
+   */
+  static void DesaturateWheelSpeeds(
+      wpi::array<SwerveModuleState, NumModules>* moduleStates,
+      ChassisSpeeds currentChassisSpeed,
+      units::meters_per_second_t attainableMaxModuleSpeed,
+      units::meters_per_second_t attainableMaxRobotTranslationSpeed,
+      units::radians_per_second_t attainableMaxRobotRotationSpeed);
+
  private:
-  mutable Eigen::Matrix<double, NumModules * 2, 3> m_inverseKinematics;
-  Eigen::HouseholderQR<Eigen::Matrix<double, NumModules * 2, 3>>
-      m_forwardKinematics;
+  mutable Matrixd<NumModules * 2, 3> m_inverseKinematics;
+  Eigen::HouseholderQR<Matrixd<NumModules * 2, 3>> m_forwardKinematics;
   wpi::array<Translation2d, NumModules> m_modules;
+  mutable wpi::array<SwerveModuleState, NumModules> m_moduleStates;
 
   mutable Translation2d m_previousCoR;
 };
+
+extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
+    SwerveDriveKinematics<4>;
+
 }  // namespace frc
 
 #include "SwerveDriveKinematics.inc"
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/SwerveDriveKinematics.inc b/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/SwerveDriveKinematics.inc
index 7b958c1..c7f26e0 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/SwerveDriveKinematics.inc
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/SwerveDriveKinematics.inc
@@ -5,7 +5,9 @@
 #pragma once
 
 #include <algorithm>
+#include <utility>
 
+#include "frc/kinematics/ChassisSpeeds.h"
 #include "frc/kinematics/SwerveDriveKinematics.h"
 #include "units/math.h"
 
@@ -20,12 +22,21 @@
 SwerveDriveKinematics<NumModules>::ToSwerveModuleStates(
     const ChassisSpeeds& chassisSpeeds,
     const Translation2d& centerOfRotation) const {
+  if (chassisSpeeds.vx == 0_mps && chassisSpeeds.vy == 0_mps &&
+      chassisSpeeds.omega == 0_rad_per_s) {
+    for (size_t i = 0; i < NumModules; i++) {
+      m_moduleStates[i].speed = 0_mps;
+    }
+
+    return m_moduleStates;
+  }
+
   // We have a new center of rotation. We need to compute the matrix again.
   if (centerOfRotation != m_previousCoR) {
     for (size_t i = 0; i < NumModules; i++) {
       // clang-format off
       m_inverseKinematics.template block<2, 3>(i * 2, 0) =
-        Eigen::Matrix<double, 2, 3>{
+        Matrixd<2, 3>{
           {1, 0, (-m_modules[i].Y() + centerOfRotation.Y()).value()},
           {0, 1, (+m_modules[i].X() - centerOfRotation.X()).value()}};
       // clang-format on
@@ -37,21 +48,20 @@
                                       chassisSpeeds.vy.value(),
                                       chassisSpeeds.omega.value()};
 
-  Eigen::Matrix<double, NumModules * 2, 1> moduleStatesMatrix =
+  Matrixd<NumModules * 2, 1> moduleStateMatrix =
       m_inverseKinematics * chassisSpeedsVector;
-  wpi::array<SwerveModuleState, NumModules> moduleStates{wpi::empty_array};
 
   for (size_t i = 0; i < NumModules; i++) {
-    units::meters_per_second_t x{moduleStatesMatrix(i * 2, 0)};
-    units::meters_per_second_t y{moduleStatesMatrix(i * 2 + 1, 0)};
+    units::meters_per_second_t x{moduleStateMatrix(i * 2, 0)};
+    units::meters_per_second_t y{moduleStateMatrix(i * 2 + 1, 0)};
 
     auto speed = units::math::hypot(x, y);
     Rotation2d rotation{x.value(), y.value()};
 
-    moduleStates[i] = {speed, rotation};
+    m_moduleStates[i] = {speed, rotation};
   }
 
-  return moduleStates;
+  return m_moduleStates;
 }
 
 template <size_t NumModules>
@@ -70,17 +80,16 @@
 template <size_t NumModules>
 ChassisSpeeds SwerveDriveKinematics<NumModules>::ToChassisSpeeds(
     wpi::array<SwerveModuleState, NumModules> moduleStates) const {
-  Eigen::Matrix<double, NumModules * 2, 1> moduleStatesMatrix;
+  Matrixd<NumModules * 2, 1> moduleStateMatrix;
 
   for (size_t i = 0; i < NumModules; ++i) {
     SwerveModuleState module = moduleStates[i];
-    moduleStatesMatrix(i * 2, 0) = module.speed.value() * module.angle.Cos();
-    moduleStatesMatrix(i * 2 + 1, 0) =
-        module.speed.value() * module.angle.Sin();
+    moduleStateMatrix(i * 2, 0) = module.speed.value() * module.angle.Cos();
+    moduleStateMatrix(i * 2 + 1, 0) = module.speed.value() * module.angle.Sin();
   }
 
   Eigen::Vector3d chassisSpeedsVector =
-      m_forwardKinematics.solve(moduleStatesMatrix);
+      m_forwardKinematics.solve(moduleStateMatrix);
 
   return {units::meters_per_second_t{chassisSpeedsVector(0)},
           units::meters_per_second_t{chassisSpeedsVector(1)},
@@ -88,6 +97,39 @@
 }
 
 template <size_t NumModules>
+template <typename... ModuleDeltas>
+Twist2d SwerveDriveKinematics<NumModules>::ToTwist2d(
+    ModuleDeltas&&... wheelDeltas) const {
+  static_assert(sizeof...(wheelDeltas) == NumModules,
+                "Number of modules is not consistent with number of wheel "
+                "locations provided in constructor.");
+
+  wpi::array<SwerveModulePosition, NumModules> moduleDeltas{wheelDeltas...};
+
+  return this->ToTwist2d(moduleDeltas);
+}
+
+template <size_t NumModules>
+Twist2d SwerveDriveKinematics<NumModules>::ToTwist2d(
+    wpi::array<SwerveModulePosition, NumModules> moduleDeltas) const {
+  Matrixd<NumModules * 2, 1> moduleDeltaMatrix;
+
+  for (size_t i = 0; i < NumModules; ++i) {
+    SwerveModulePosition module = moduleDeltas[i];
+    moduleDeltaMatrix(i * 2, 0) = module.distance.value() * module.angle.Cos();
+    moduleDeltaMatrix(i * 2 + 1, 0) =
+        module.distance.value() * module.angle.Sin();
+  }
+
+  Eigen::Vector3d chassisDeltaVector =
+      m_forwardKinematics.solve(moduleDeltaMatrix);
+
+  return {units::meter_t{chassisDeltaVector(0)},
+          units::meter_t{chassisDeltaVector(1)},
+          units::radian_t{chassisDeltaVector(2)}};
+}
+
+template <size_t NumModules>
 void SwerveDriveKinematics<NumModules>::DesaturateWheelSpeeds(
     wpi::array<SwerveModuleState, NumModules>* moduleStates,
     units::meters_per_second_t attainableMaxSpeed) {
@@ -106,4 +148,41 @@
   }
 }
 
+template <size_t NumModules>
+void SwerveDriveKinematics<NumModules>::DesaturateWheelSpeeds(
+    wpi::array<SwerveModuleState, NumModules>* moduleStates,
+    ChassisSpeeds currentChassisSpeed,
+    units::meters_per_second_t attainableMaxModuleSpeed,
+    units::meters_per_second_t attainableMaxRobotTranslationSpeed,
+    units::radians_per_second_t attainableMaxRobotRotationSpeed) {
+  auto& states = *moduleStates;
+
+  auto realMaxSpeed = std::max_element(states.begin(), states.end(),
+                                       [](const auto& a, const auto& b) {
+                                         return units::math::abs(a.speed) <
+                                                units::math::abs(b.speed);
+                                       })
+                          ->speed;
+
+  if (attainableMaxRobotTranslationSpeed == 0_mps ||
+      attainableMaxRobotRotationSpeed == 0_rad_per_s || realMaxSpeed == 0_mps) {
+    return;
+  }
+
+  auto translationalK =
+      units::math::hypot(currentChassisSpeed.vx, currentChassisSpeed.vy) /
+      attainableMaxRobotTranslationSpeed;
+
+  auto rotationalK = units::math::abs(currentChassisSpeed.omega) /
+                     attainableMaxRobotRotationSpeed;
+
+  auto k = units::math::max(translationalK, rotationalK);
+
+  auto scale = units::math::min(k * attainableMaxModuleSpeed / realMaxSpeed,
+                                units::scalar_t(1));
+  for (auto& module : states) {
+    module.speed = module.speed * scale;
+  }
+}
+
 }  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/SwerveDriveOdometry.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/SwerveDriveOdometry.h
index d1a4958..015c2c0 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/SwerveDriveOdometry.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/SwerveDriveOdometry.h
@@ -8,10 +8,11 @@
 #include <cstddef>
 #include <ctime>
 
+#include <wpi/SymbolExports.h>
 #include <wpi/timestamp.h>
 
 #include "SwerveDriveKinematics.h"
-#include "SwerveModuleState.h"
+#include "SwerveModulePosition.h"
 #include "frc/geometry/Pose2d.h"
 #include "units/time.h"
 
@@ -34,11 +35,13 @@
    *
    * @param kinematics The swerve drive kinematics for your drivetrain.
    * @param gyroAngle The angle reported by the gyroscope.
+   * @param modulePositions The wheel positions reported by each module.
    * @param initialPose The starting position of the robot on the field.
    */
-  SwerveDriveOdometry(SwerveDriveKinematics<NumModules> kinematics,
-                      const Rotation2d& gyroAngle,
-                      const Pose2d& initialPose = Pose2d());
+  SwerveDriveOdometry(
+      SwerveDriveKinematics<NumModules> kinematics, const Rotation2d& gyroAngle,
+      const wpi::array<SwerveModulePosition, NumModules>& modulePositions,
+      const Pose2d& initialPose = Pose2d{});
 
   /**
    * Resets the robot's position on the field.
@@ -46,14 +49,14 @@
    * The gyroscope angle does not need to be reset here on the user's robot
    * code. The library automatically takes care of offsetting the gyro angle.
    *
-   * @param pose The position on the field that your robot is at.
    * @param gyroAngle The angle reported by the gyroscope.
+   * @param modulePositions The wheel positions reported by each module.
+   * @param pose The position on the field that your robot is at.
    */
-  void ResetPosition(const Pose2d& pose, const Rotation2d& gyroAngle) {
-    m_pose = pose;
-    m_previousAngle = pose.Rotation();
-    m_gyroOffset = m_pose.Rotation() - gyroAngle;
-  }
+  void ResetPosition(
+      const Rotation2d& gyroAngle,
+      const wpi::array<SwerveModulePosition, NumModules>& modulePositions,
+      const Pose2d& pose);
 
   /**
    * Returns the position of the robot on the field.
@@ -63,55 +66,35 @@
 
   /**
    * Updates the robot's position on the field using forward kinematics and
-   * integration of the pose over time. This method takes in the current time as
-   * a parameter to calculate period (difference between two timestamps). The
-   * period is used to calculate the change in distance from a velocity. This
-   * also takes in an angle parameter which is used instead of the
-   * angular rate that is calculated from forward kinematics.
+   * integration of the pose over time. This also takes in an angle parameter
+   * which is used instead of the angular rate that is calculated from forward
+   * kinematics.
    *
-   * @param currentTime The current time.
    * @param gyroAngle The angle reported by the gyroscope.
-   * @param moduleStates The current state of all swerve modules. Please provide
-   *                     the states in the same order in which you instantiated
-   *                     your SwerveDriveKinematics.
+   * @param modulePositions The current position of all swerve modules. Please
+   * provide the positions in the same order in which you instantiated your
+   * SwerveDriveKinematics.
    *
    * @return The new pose of the robot.
    */
-  template <typename... ModuleStates>
-  const Pose2d& UpdateWithTime(units::second_t currentTime,
-                               const Rotation2d& gyroAngle,
-                               ModuleStates&&... moduleStates);
-
-  /**
-   * Updates the robot's position on the field using forward kinematics and
-   * integration of the pose over time. This method automatically calculates
-   * the current time to calculate period (difference between two timestamps).
-   * The period is used to calculate the change in distance from a velocity.
-   * This also takes in an angle parameter which is used instead of the
-   * angular rate that is calculated from forward kinematics.
-   *
-   * @param gyroAngle The angle reported by the gyroscope.
-   * @param moduleStates The current state of all swerve modules. Please provide
-   *                     the states in the same order in which you instantiated
-   *                     your SwerveDriveKinematics.
-   *
-   * @return The new pose of the robot.
-   */
-  template <typename... ModuleStates>
-  const Pose2d& Update(const Rotation2d& gyroAngle,
-                       ModuleStates&&... moduleStates) {
-    return UpdateWithTime(wpi::Now() * 1.0e-6_s, gyroAngle, moduleStates...);
-  }
+  const Pose2d& Update(
+      const Rotation2d& gyroAngle,
+      const wpi::array<SwerveModulePosition, NumModules>& modulePositions);
 
  private:
   SwerveDriveKinematics<NumModules> m_kinematics;
   Pose2d m_pose;
 
-  units::second_t m_previousTime = -1_s;
   Rotation2d m_previousAngle;
   Rotation2d m_gyroOffset;
+
+  wpi::array<SwerveModulePosition, NumModules> m_previousModulePositions{
+      wpi::empty_array};
 };
 
+extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
+    SwerveDriveOdometry<4>;
+
 }  // namespace frc
 
 #include "SwerveDriveOdometry.inc"
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/SwerveDriveOdometry.inc b/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/SwerveDriveOdometry.inc
index 96db930..64b46c1 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/SwerveDriveOdometry.inc
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/SwerveDriveOdometry.inc
@@ -11,30 +11,56 @@
 template <size_t NumModules>
 SwerveDriveOdometry<NumModules>::SwerveDriveOdometry(
     SwerveDriveKinematics<NumModules> kinematics, const Rotation2d& gyroAngle,
+    const wpi::array<SwerveModulePosition, NumModules>& modulePositions,
     const Pose2d& initialPose)
     : m_kinematics(kinematics), m_pose(initialPose) {
   m_previousAngle = m_pose.Rotation();
   m_gyroOffset = m_pose.Rotation() - gyroAngle;
+
+  for (size_t i = 0; i < NumModules; i++) {
+    m_previousModulePositions[i] = {modulePositions[i].distance,
+                                    modulePositions[i].angle};
+  }
+
   wpi::math::MathSharedStore::ReportUsage(
       wpi::math::MathUsageId::kOdometry_SwerveDrive, 1);
 }
 
 template <size_t NumModules>
-template <typename... ModuleStates>
-const Pose2d& frc::SwerveDriveOdometry<NumModules>::UpdateWithTime(
-    units::second_t currentTime, const Rotation2d& gyroAngle,
-    ModuleStates&&... moduleStates) {
-  units::second_t deltaTime =
-      (m_previousTime >= 0_s) ? currentTime - m_previousTime : 0_s;
-  m_previousTime = currentTime;
+void SwerveDriveOdometry<NumModules>::ResetPosition(
+    const Rotation2d& gyroAngle,
+    const wpi::array<SwerveModulePosition, NumModules>& modulePositions,
+    const Pose2d& pose) {
+  m_pose = pose;
+  m_previousAngle = pose.Rotation();
+  m_gyroOffset = m_pose.Rotation() - gyroAngle;
+
+  for (size_t i = 0; i < NumModules; i++) {
+    m_previousModulePositions[i].distance = modulePositions[i].distance;
+  }
+}
+
+template <size_t NumModules>
+const Pose2d& frc::SwerveDriveOdometry<NumModules>::Update(
+    const Rotation2d& gyroAngle,
+    const wpi::array<SwerveModulePosition, NumModules>& modulePositions) {
+  auto moduleDeltas =
+      wpi::array<SwerveModulePosition, NumModules>(wpi::empty_array);
+  for (size_t index = 0; index < NumModules; index++) {
+    auto lastPosition = m_previousModulePositions[index];
+    auto currentPosition = modulePositions[index];
+    moduleDeltas[index] = {currentPosition.distance - lastPosition.distance,
+                           currentPosition.angle};
+
+    m_previousModulePositions[index].distance = modulePositions[index].distance;
+  }
 
   auto angle = gyroAngle + m_gyroOffset;
 
-  auto [dx, dy, dtheta] = m_kinematics.ToChassisSpeeds(moduleStates...);
-  static_cast<void>(dtheta);
+  auto twist = m_kinematics.ToTwist2d(moduleDeltas);
+  twist.dtheta = (angle - m_previousAngle).Radians();
 
-  auto newPose = m_pose.Exp(
-      {dx * deltaTime, dy * deltaTime, (angle - m_previousAngle).Radians()});
+  auto newPose = m_pose.Exp(twist);
 
   m_previousAngle = angle;
   m_pose = {newPose.Translation(), angle};
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/SwerveModulePosition.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/SwerveModulePosition.h
new file mode 100644
index 0000000..18ed464
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/kinematics/SwerveModulePosition.h
@@ -0,0 +1,29 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <wpi/SymbolExports.h>
+
+#include "frc/geometry/Rotation2d.h"
+#include "units/angle.h"
+#include "units/length.h"
+#include "units/math.h"
+
+namespace frc {
+/**
+ * Represents the position of one swerve module.
+ */
+struct WPILIB_DLLEXPORT SwerveModulePosition {
+  /**
+   * Distance the wheel of a module has traveled
+   */
+  units::meter_t distance = 0_m;
+
+  /**
+   * Angle of the module.
+   */
+  Rotation2d angle;
+};
+}  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/spline/CubicHermiteSpline.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/spline/CubicHermiteSpline.h
index 8126349..0636707 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/spline/CubicHermiteSpline.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/spline/CubicHermiteSpline.h
@@ -7,7 +7,7 @@
 #include <wpi/SymbolExports.h>
 #include <wpi/array.h>
 
-#include "Eigen/Core"
+#include "frc/EigenCore.h"
 #include "frc/spline/Spline.h"
 
 namespace frc {
@@ -40,44 +40,41 @@
    * Returns the coefficients matrix.
    * @return The coefficients matrix.
    */
-  Eigen::Matrix<double, 6, 3 + 1> Coefficients() const override {
-    return m_coefficients;
-  }
+  Matrixd<6, 3 + 1> Coefficients() const override { return m_coefficients; }
 
  private:
-  Eigen::Matrix<double, 6, 4> m_coefficients =
-      Eigen::Matrix<double, 6, 4>::Zero();
+  Matrixd<6, 4> m_coefficients = Matrixd<6, 4>::Zero();
 
   /**
    * Returns the hermite basis matrix for cubic hermite spline interpolation.
    * @return The hermite basis matrix for cubic hermite spline interpolation.
    */
-  static Eigen::Matrix<double, 4, 4> MakeHermiteBasis() {
+  static Matrixd<4, 4> MakeHermiteBasis() {
     // Given P(i), P'(i), P(i+1), P'(i+1), the control vectors, we want to find
-    // the coefficients of the spline P(t) = a3 * t^3 + a2 * t^2 + a1 * t + a0.
+    // the coefficients of the spline P(t) = a₃t³ + a₂t² + a₁t + a₀.
     //
-    // P(i)    = P(0)  = a0
-    // P'(i)   = P'(0) = a1
-    // P(i+1)  = P(1)  = a3 + a2 + a1 + a0
-    // P'(i+1) = P'(1) = 3 * a3 + 2 * a2 + a1
+    // P(i)    = P(0)  = a₀
+    // P'(i)   = P'(0) = a₁
+    // P(i+1)  = P(1)  = a₃ + a₂ + a₁ + a₀
+    // P'(i+1) = P'(1) = 3a₃ + 2a₂ + a₁
     //
-    // [ P(i)    ] = [ 0 0 0 1 ][ a3 ]
-    // [ P'(i)   ] = [ 0 0 1 0 ][ a2 ]
-    // [ P(i+1)  ] = [ 1 1 1 1 ][ a1 ]
-    // [ P'(i+1) ] = [ 3 2 1 0 ][ a0 ]
+    // [P(i)   ] = [0 0 0 1][a₃]
+    // [P'(i)  ] = [0 0 1 0][a₂]
+    // [P(i+1) ] = [1 1 1 1][a₁]
+    // [P'(i+1)] = [3 2 1 0][a₀]
     //
     // To solve for the coefficients, we can invert the 4x4 matrix and move it
     // to the other side of the equation.
     //
-    // [ a3 ] = [  2  1 -2  1 ][ P(i)    ]
-    // [ a2 ] = [ -3 -2  3 -1 ][ P'(i)   ]
-    // [ a1 ] = [  0  1  0  0 ][ P(i+1)  ]
-    // [ a0 ] = [  1  0  0  0 ][ P'(i+1) ]
+    // [a₃] = [ 2  1 -2  1][P(i)   ]
+    // [a₂] = [-3 -2  3 -1][P'(i)  ]
+    // [a₁] = [ 0  1  0  0][P(i+1) ]
+    // [a₀] = [ 1  0  0  0][P'(i+1)]
 
-    static const Eigen::Matrix<double, 4, 4> basis{{+2.0, +1.0, -2.0, +1.0},
-                                                   {-3.0, -2.0, +3.0, -1.0},
-                                                   {+0.0, +1.0, +0.0, +0.0},
-                                                   {+1.0, +0.0, +0.0, +0.0}};
+    static const Matrixd<4, 4> basis{{+2.0, +1.0, -2.0, +1.0},
+                                     {-3.0, -2.0, +3.0, -1.0},
+                                     {+0.0, +1.0, +0.0, +0.0},
+                                     {+1.0, +0.0, +0.0, +0.0}};
     return basis;
   }
 
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/spline/QuinticHermiteSpline.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/spline/QuinticHermiteSpline.h
index 5ba3e2a..ad03a23 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/spline/QuinticHermiteSpline.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/spline/QuinticHermiteSpline.h
@@ -7,7 +7,7 @@
 #include <wpi/SymbolExports.h>
 #include <wpi/array.h>
 
-#include "Eigen/Core"
+#include "frc/EigenCore.h"
 #include "frc/spline/Spline.h"
 
 namespace frc {
@@ -40,48 +40,45 @@
    * Returns the coefficients matrix.
    * @return The coefficients matrix.
    */
-  Eigen::Matrix<double, 6, 6> Coefficients() const override {
-    return m_coefficients;
-  }
+  Matrixd<6, 6> Coefficients() const override { return m_coefficients; }
 
  private:
-  Eigen::Matrix<double, 6, 6> m_coefficients =
-      Eigen::Matrix<double, 6, 6>::Zero();
+  Matrixd<6, 6> m_coefficients = Matrixd<6, 6>::Zero();
 
   /**
    * Returns the hermite basis matrix for quintic hermite spline interpolation.
    * @return The hermite basis matrix for quintic hermite spline interpolation.
    */
-  static Eigen::Matrix<double, 6, 6> MakeHermiteBasis() {
-    // Given P(i), P'(i), P''(i), P(i+1), P'(i+1), P''(i+1), the control
-    // vectors, we want to find the coefficients of the spline
-    // P(t) = a5 * t^5 + a4 * t^4 + a3 * t^3 + a2 * t^2 + a1 * t + a0.
+  static Matrixd<6, 6> MakeHermiteBasis() {
+    // Given P(i), P'(i), P"(i), P(i+1), P'(i+1), P"(i+1), the control vectors,
+    // we want to find the coefficients of the spline
+    // P(t) = a₅t⁵ + a₄t⁴ + a₃t³ + a₂t² + a₁t + a₀.
     //
-    // P(i)     = P(0)   = a0
-    // P'(i)    = P'(0)  = a1
-    // P''(i)   = P''(0) = 2 * a2
-    // P(i+1)   = P(1)   = a5 + a4 + a3 + a2 + a1 + a0
-    // P'(i+1)  = P'(1)  = 5 * a5 + 4 * a4 + 3 * a3 + 2 * a2 + a1
-    // P''(i+1) = P''(1) = 20 * a5 + 12 * a4 + 6 * a3 + 2 * a2
+    // P(i)    = P(0)  = a₀
+    // P'(i)   = P'(0) = a₁
+    // P''(i)  = P"(0) = 2a₂
+    // P(i+1)  = P(1)  = a₅ + a₄ + a₃ + a₂ + a₁ + a₀
+    // P'(i+1) = P'(1) = 5a₅ + 4a₄ + 3a₃ + 2a₂ + a₁
+    // P"(i+1) = P"(1) = 20a₅ + 12a₄ + 6a₃ + 2a₂
     //
-    // [ P(i)     ] = [  0  0  0  0  0  1 ][ a5 ]
-    // [ P'(i)    ] = [  0  0  0  0  1  0 ][ a4 ]
-    // [ P''(i)   ] = [  0  0  0  2  0  0 ][ a3 ]
-    // [ P(i+1)   ] = [  1  1  1  1  1  1 ][ a2 ]
-    // [ P'(i+1)  ] = [  5  4  3  2  1  0 ][ a1 ]
-    // [ P''(i+1) ] = [ 20 12  6  2  0  0 ][ a0 ]
+    // [P(i)   ] = [ 0  0  0  0  0  1][a₅]
+    // [P'(i)  ] = [ 0  0  0  0  1  0][a₄]
+    // [P"(i)  ] = [ 0  0  0  2  0  0][a₃]
+    // [P(i+1) ] = [ 1  1  1  1  1  1][a₂]
+    // [P'(i+1)] = [ 5  4  3  2  1  0][a₁]
+    // [P"(i+1)] = [20 12  6  2  0  0][a₀]
     //
     // To solve for the coefficients, we can invert the 6x6 matrix and move it
     // to the other side of the equation.
     //
-    // [ a5 ] = [  -6.0  -3.0  -0.5   6.0  -3.0   0.5 ][ P(i)     ]
-    // [ a4 ] = [  15.0   8.0   1.5 -15.0   7.0  -1.0 ][ P'(i)    ]
-    // [ a3 ] = [ -10.0  -6.0  -1.5  10.0  -4.0   0.5 ][ P''(i)   ]
-    // [ a2 ] = [   0.0   0.0   0.5   0.0   0.0   0.0 ][ P(i+1)   ]
-    // [ a1 ] = [   0.0   1.0   0.0   0.0   0.0   0.0 ][ P'(i+1)  ]
-    // [ a0 ] = [   1.0   0.0   0.0   0.0   0.0   0.0 ][ P''(i+1) ]
+    // [a₅] = [ -6.0  -3.0  -0.5   6.0  -3.0   0.5][P(i)   ]
+    // [a₄] = [ 15.0   8.0   1.5 -15.0   7.0  -1.0][P'(i)  ]
+    // [a₃] = [-10.0  -6.0  -1.5  10.0  -4.0   0.5][P"(i)  ]
+    // [a₂] = [  0.0   0.0   0.5   0.0   0.0   0.0][P(i+1) ]
+    // [a₁] = [  0.0   1.0   0.0   0.0   0.0   0.0][P'(i+1)]
+    // [a₀] = [  1.0   0.0   0.0   0.0   0.0   0.0][P"(i+1)]
 
-    static const Eigen::Matrix<double, 6, 6> basis{
+    static const Matrixd<6, 6> basis{
         {-06.0, -03.0, -00.5, +06.0, -03.0, +00.5},
         {+15.0, +08.0, +01.5, -15.0, +07.0, -01.0},
         {-10.0, -06.0, -01.5, +10.0, -04.0, +00.5},
@@ -100,11 +97,10 @@
    *
    * @return The control vector matrix for a dimension.
    */
-  static Eigen::Vector<double, 6> ControlVectorFromArrays(
-      wpi::array<double, 3> initialVector, wpi::array<double, 3> finalVector) {
-    return Eigen::Vector<double, 6>{initialVector[0], initialVector[1],
-                                    initialVector[2], finalVector[0],
-                                    finalVector[1],   finalVector[2]};
+  static Vectord<6> ControlVectorFromArrays(wpi::array<double, 3> initialVector,
+                                            wpi::array<double, 3> finalVector) {
+    return Vectord<6>{initialVector[0], initialVector[1], initialVector[2],
+                      finalVector[0],   finalVector[1],   finalVector[2]};
   }
 };
 }  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/spline/Spline.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/spline/Spline.h
index 2dd248a..b5ff024 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/spline/Spline.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/spline/Spline.h
@@ -9,7 +9,7 @@
 
 #include <wpi/array.h>
 
-#include "Eigen/Core"
+#include "frc/EigenCore.h"
 #include "frc/geometry/Pose2d.h"
 #include "units/curvature.h"
 #include "units/length.h"
@@ -55,7 +55,7 @@
    * @return The pose and curvature at that point.
    */
   PoseWithCurvature GetPoint(double t) const {
-    Eigen::Vector<double, Degree + 1> polynomialBases;
+    Vectord<Degree + 1> polynomialBases;
 
     // Populate the polynomial bases
     for (int i = 0; i <= Degree; i++) {
@@ -64,7 +64,7 @@
 
     // This simply multiplies by the coefficients. We need to divide out t some
     // n number of times where n is the derivative we want to take.
-    Eigen::Vector<double, 6> combined = Coefficients() * polynomialBases;
+    Vectord<6> combined = Coefficients() * polynomialBases;
 
     double dx, dy, ddx, ddy;
 
@@ -90,8 +90,8 @@
         (dx * ddy - ddx * dy) / ((dx * dx + dy * dy) * std::hypot(dx, dy));
 
     return {
-        {FromVector(combined.template block<2, 1>(0, 0)), Rotation2d(dx, dy)},
-        units::curvature_t(curvature)};
+        {FromVector(combined.template block<2, 1>(0, 0)), Rotation2d{dx, dy}},
+        units::curvature_t{curvature}};
   }
 
  protected:
@@ -100,7 +100,7 @@
    *
    * @return The coefficients of the spline.
    */
-  virtual Eigen::Matrix<double, 6, Degree + 1> Coefficients() const = 0;
+  virtual Matrixd<6, Degree + 1> Coefficients() const = 0;
 
   /**
    * Converts a Translation2d into a vector that is compatible with Eigen.
@@ -119,7 +119,7 @@
    * @return The Translation2d.
    */
   static Translation2d FromVector(const Eigen::Vector2d& vector) {
-    return Translation2d(units::meter_t(vector(0)), units::meter_t(vector(1)));
+    return Translation2d{units::meter_t{vector(0)}, units::meter_t{vector(1)}};
   }
 };
 }  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/system/Discretization.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/system/Discretization.h
index 722bb5f..957b875 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/system/Discretization.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/system/Discretization.h
@@ -4,7 +4,7 @@
 
 #pragma once
 
-#include "Eigen/Core"
+#include "frc/EigenCore.h"
 #include "units/time.h"
 #include "unsupported/Eigen/MatrixFunctions"
 
@@ -19,9 +19,9 @@
  * @param discA Storage for discrete system matrix.
  */
 template <int States>
-void DiscretizeA(const Eigen::Matrix<double, States, States>& contA,
-                 units::second_t dt,
-                 Eigen::Matrix<double, States, States>* discA) {
+void DiscretizeA(const Matrixd<States, States>& contA, units::second_t dt,
+                 Matrixd<States, States>* discA) {
+  // A_d = eᴬᵀ
   *discA = (contA * dt.value()).exp();
 }
 
@@ -37,21 +37,23 @@
  * @param discB Storage for discrete input matrix.
  */
 template <int States, int Inputs>
-void DiscretizeAB(const Eigen::Matrix<double, States, States>& contA,
-                  const Eigen::Matrix<double, States, Inputs>& contB,
-                  units::second_t dt,
-                  Eigen::Matrix<double, States, States>* discA,
-                  Eigen::Matrix<double, States, Inputs>* discB) {
-  // Matrices are blocked here to minimize matrix exponentiation calculations
-  Eigen::Matrix<double, States + Inputs, States + Inputs> Mcont;
-  Mcont.setZero();
-  Mcont.template block<States, States>(0, 0) = contA * dt.value();
-  Mcont.template block<States, Inputs>(0, States) = contB * dt.value();
+void DiscretizeAB(const Matrixd<States, States>& contA,
+                  const Matrixd<States, Inputs>& contB, units::second_t dt,
+                  Matrixd<States, States>* discA,
+                  Matrixd<States, Inputs>* discB) {
+  // M = [A  B]
+  //     [0  0]
+  Matrixd<States + Inputs, States + Inputs> M;
+  M.setZero();
+  M.template block<States, States>(0, 0) = contA;
+  M.template block<States, Inputs>(0, States) = contB;
 
-  // Discretize A and B with the given timestep
-  Eigen::Matrix<double, States + Inputs, States + Inputs> Mdisc = Mcont.exp();
-  *discA = Mdisc.template block<States, States>(0, 0);
-  *discB = Mdisc.template block<States, Inputs>(0, States);
+  // ϕ = eᴹᵀ = [A_d  B_d]
+  //           [ 0    I ]
+  Matrixd<States + Inputs, States + Inputs> phi = (M * dt.value()).exp();
+
+  *discA = phi.template block<States, States>(0, 0);
+  *discB = phi.template block<States, Inputs>(0, States);
 }
 
 /**
@@ -65,29 +67,30 @@
  * @param discQ Storage for discrete process noise covariance matrix.
  */
 template <int States>
-void DiscretizeAQ(const Eigen::Matrix<double, States, States>& contA,
-                  const Eigen::Matrix<double, States, States>& contQ,
-                  units::second_t dt,
-                  Eigen::Matrix<double, States, States>* discA,
-                  Eigen::Matrix<double, States, States>* discQ) {
+void DiscretizeAQ(const Matrixd<States, States>& contA,
+                  const Matrixd<States, States>& contQ, units::second_t dt,
+                  Matrixd<States, States>* discA,
+                  Matrixd<States, States>* discQ) {
   // Make continuous Q symmetric if it isn't already
-  Eigen::Matrix<double, States, States> Q = (contQ + contQ.transpose()) / 2.0;
+  Matrixd<States, States> Q = (contQ + contQ.transpose()) / 2.0;
 
-  // Set up the matrix M = [[-A, Q], [0, A.T]]
-  Eigen::Matrix<double, 2 * States, 2 * States> M;
+  // M = [−A  Q ]
+  //     [ 0  Aᵀ]
+  Matrixd<2 * States, 2 * States> M;
   M.template block<States, States>(0, 0) = -contA;
   M.template block<States, States>(0, States) = Q;
   M.template block<States, States>(States, 0).setZero();
   M.template block<States, States>(States, States) = contA.transpose();
 
-  Eigen::Matrix<double, 2 * States, 2 * States> phi = (M * dt.value()).exp();
+  // ϕ = eᴹᵀ = [−A_d  A_d⁻¹Q_d]
+  //           [ 0      A_dᵀ  ]
+  Matrixd<2 * States, 2 * States> phi = (M * dt.value()).exp();
 
-  // Phi12 = phi[0:States,        States:2*States]
-  // Phi22 = phi[States:2*States, States:2*States]
-  Eigen::Matrix<double, States, States> phi12 =
-      phi.block(0, States, States, States);
-  Eigen::Matrix<double, States, States> phi22 =
-      phi.block(States, States, States, States);
+  // ϕ₁₂ = A_d⁻¹Q_d
+  Matrixd<States, States> phi12 = phi.block(0, States, States, States);
+
+  // ϕ₂₂ = A_dᵀ
+  Matrixd<States, States> phi22 = phi.block(States, States, States, States);
 
   *discA = phi22.transpose();
 
@@ -104,10 +107,12 @@
  * (which is expensive), we take advantage of the structure of the block matrix
  * of A and Q.
  *
- * 1) The exponential of A*t, which is only N x N, is relatively cheap.
- * 2) The upper-right quarter of the 2N x 2N matrix, which we can approximate
- *    using a taylor series to several terms and still be substantially cheaper
- *    than taking the big exponential.
+ * <ul>
+ *   <li>eᴬᵀ, which is only N x N, is relatively cheap.
+ *   <li>The upper-right quarter of the 2N x 2N matrix, which we can approximate
+ *       using a taylor series to several terms and still be substantially
+ *       cheaper than taking the big exponential.
+ * </ul>
  *
  * @tparam States Number of states.
  * @param contA Continuous system matrix.
@@ -117,30 +122,64 @@
  * @param discQ Storage for discrete process noise covariance matrix.
  */
 template <int States>
-void DiscretizeAQTaylor(const Eigen::Matrix<double, States, States>& contA,
-                        const Eigen::Matrix<double, States, States>& contQ,
-                        units::second_t dt,
-                        Eigen::Matrix<double, States, States>* discA,
-                        Eigen::Matrix<double, States, States>* discQ) {
-  // Make continuous Q symmetric if it isn't already
-  Eigen::Matrix<double, States, States> Q = (contQ + contQ.transpose()) / 2.0;
+void DiscretizeAQTaylor(const Matrixd<States, States>& contA,
+                        const Matrixd<States, States>& contQ,
+                        units::second_t dt, Matrixd<States, States>* discA,
+                        Matrixd<States, States>* discQ) {
+  //       T
+  // Q_d = ∫ e^(Aτ) Q e^(Aᵀτ) dτ
+  //       0
+  //
+  // M = [−A  Q ]
+  //     [ 0  Aᵀ]
+  // ϕ = eᴹᵀ
+  // ϕ₁₂ = A_d⁻¹Q_d
+  //
+  // Taylor series of ϕ:
+  //
+  //   ϕ = eᴹᵀ = I + MT + 1/2 M²T² + 1/6 M³T³ + …
+  //   ϕ = eᴹᵀ = I + MT + 1/2 T²M² + 1/6 T³M³ + …
+  //
+  // Taylor series of ϕ expanded for ϕ₁₂:
+  //
+  //   ϕ₁₂ = 0 + QT + 1/2 T² (−AQ + QAᵀ) + 1/6 T³ (−A lastTerm + Q Aᵀ²) + …
+  //
+  // ```
+  // lastTerm = Q
+  // lastCoeff = T
+  // ATn = Aᵀ
+  // ϕ₁₂ = lastTerm lastCoeff = QT
+  //
+  // for i in range(2, 6):
+  //   // i = 2
+  //   lastTerm = −A lastTerm + Q ATn = −AQ + QAᵀ
+  //   lastCoeff *= T/i → lastCoeff *= T/2 = 1/2 T²
+  //   ATn *= Aᵀ = Aᵀ²
+  //
+  //   // i = 3
+  //   lastTerm = −A lastTerm + Q ATn = −A (−AQ + QAᵀ) + QAᵀ² = …
+  //   …
+  // ```
 
-  Eigen::Matrix<double, States, States> lastTerm = Q;
+  // Make continuous Q symmetric if it isn't already
+  Matrixd<States, States> Q = (contQ + contQ.transpose()) / 2.0;
+
+  Matrixd<States, States> lastTerm = Q;
   double lastCoeff = dt.value();
 
   // Aᵀⁿ
-  Eigen::Matrix<double, States, States> Atn = contA.transpose();
+  Matrixd<States, States> ATn = contA.transpose();
 
-  Eigen::Matrix<double, States, States> phi12 = lastTerm * lastCoeff;
+  Matrixd<States, States> phi12 = lastTerm * lastCoeff;
 
   // i = 6 i.e. 5th order should be enough precision
   for (int i = 2; i < 6; ++i) {
-    lastTerm = -contA * lastTerm + Q * Atn;
+    lastTerm = -contA * lastTerm + Q * ATn;
     lastCoeff *= dt.value() / static_cast<double>(i);
 
     phi12 += lastTerm * lastCoeff;
 
-    Atn *= contA.transpose();
+    ATn *= contA.transpose();
   }
 
   DiscretizeA<States>(contA, dt, discA);
@@ -159,8 +198,9 @@
  * @param dt Discretization timestep.
  */
 template <int Outputs>
-Eigen::Matrix<double, Outputs, Outputs> DiscretizeR(
-    const Eigen::Matrix<double, Outputs, Outputs>& R, units::second_t dt) {
+Matrixd<Outputs, Outputs> DiscretizeR(const Matrixd<Outputs, Outputs>& R,
+                                      units::second_t dt) {
+  // R_d = 1/T R
   return R / dt.value();
 }
 
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/system/LinearSystem.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/system/LinearSystem.h
index bd3ff40..dff2433 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/system/LinearSystem.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/system/LinearSystem.h
@@ -8,7 +8,7 @@
 #include <functional>
 #include <stdexcept>
 
-#include "Eigen/Core"
+#include "frc/EigenCore.h"
 #include "frc/StateSpaceUtil.h"
 #include "frc/system/Discretization.h"
 #include "units/time.h"
@@ -30,6 +30,10 @@
 template <int States, int Inputs, int Outputs>
 class LinearSystem {
  public:
+  using StateVector = Vectord<States>;
+  using InputVector = Vectord<Inputs>;
+  using OutputVector = Vectord<Outputs>;
+
   /**
    * Constructs a discrete plant with the given continuous system coefficients.
    *
@@ -39,10 +43,10 @@
    * @param D    Feedthrough matrix.
    * @throws std::domain_error if any matrix element isn't finite.
    */
-  LinearSystem(const Eigen::Matrix<double, States, States>& A,
-               const Eigen::Matrix<double, States, Inputs>& B,
-               const Eigen::Matrix<double, Outputs, States>& C,
-               const Eigen::Matrix<double, Outputs, Inputs>& D) {
+  LinearSystem(const Matrixd<States, States>& A,
+               const Matrixd<States, Inputs>& B,
+               const Matrixd<Outputs, States>& C,
+               const Matrixd<Outputs, Inputs>& D) {
     if (!A.allFinite()) {
       throw std::domain_error(
           "Elements of A aren't finite. This is usually due to model "
@@ -78,7 +82,7 @@
   /**
    * Returns the system matrix A.
    */
-  const Eigen::Matrix<double, States, States>& A() const { return m_A; }
+  const Matrixd<States, States>& A() const { return m_A; }
 
   /**
    * Returns an element of the system matrix A.
@@ -91,7 +95,7 @@
   /**
    * Returns the input matrix B.
    */
-  const Eigen::Matrix<double, States, Inputs>& B() const { return m_B; }
+  const Matrixd<States, Inputs>& B() const { return m_B; }
 
   /**
    * Returns an element of the input matrix B.
@@ -104,7 +108,7 @@
   /**
    * Returns the output matrix C.
    */
-  const Eigen::Matrix<double, Outputs, States>& C() const { return m_C; }
+  const Matrixd<Outputs, States>& C() const { return m_C; }
 
   /**
    * Returns an element of the output matrix C.
@@ -117,7 +121,7 @@
   /**
    * Returns the feedthrough matrix D.
    */
-  const Eigen::Matrix<double, Outputs, Inputs>& D() const { return m_D; }
+  const Matrixd<Outputs, Inputs>& D() const { return m_D; }
 
   /**
    * Returns an element of the feedthrough matrix D.
@@ -137,11 +141,10 @@
    * @param clampedU The control input.
    * @param dt       Timestep for model update.
    */
-  Eigen::Vector<double, States> CalculateX(
-      const Eigen::Vector<double, States>& x,
-      const Eigen::Vector<double, Inputs>& clampedU, units::second_t dt) const {
-    Eigen::Matrix<double, States, States> discA;
-    Eigen::Matrix<double, States, Inputs> discB;
+  StateVector CalculateX(const StateVector& x, const InputVector& clampedU,
+                         units::second_t dt) const {
+    Matrixd<States, States> discA;
+    Matrixd<States, Inputs> discB;
     DiscretizeAB<States, Inputs>(m_A, m_B, dt, &discA, &discB);
 
     return discA * x + discB * clampedU;
@@ -156,9 +159,8 @@
    * @param x The current state.
    * @param clampedU The control input.
    */
-  Eigen::Vector<double, Outputs> CalculateY(
-      const Eigen::Vector<double, States>& x,
-      const Eigen::Vector<double, Inputs>& clampedU) const {
+  OutputVector CalculateY(const StateVector& x,
+                          const InputVector& clampedU) const {
     return m_C * x + m_D * clampedU;
   }
 
@@ -166,22 +168,22 @@
   /**
    * Continuous system matrix.
    */
-  Eigen::Matrix<double, States, States> m_A;
+  Matrixd<States, States> m_A;
 
   /**
    * Continuous input matrix.
    */
-  Eigen::Matrix<double, States, Inputs> m_B;
+  Matrixd<States, Inputs> m_B;
 
   /**
    * Output matrix.
    */
-  Eigen::Matrix<double, Outputs, States> m_C;
+  Matrixd<Outputs, States> m_C;
 
   /**
    * Feedthrough matrix.
    */
-  Eigen::Matrix<double, Outputs, Inputs> m_D;
+  Matrixd<Outputs, Inputs> m_D;
 };
 
 }  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/system/LinearSystemLoop.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/system/LinearSystemLoop.h
index a18c03b..1300a82 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/system/LinearSystemLoop.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/system/LinearSystemLoop.h
@@ -4,7 +4,9 @@
 
 #pragma once
 
-#include "Eigen/Core"
+#include <wpi/SymbolExports.h>
+
+#include "frc/EigenCore.h"
 #include "frc/controller/LinearPlantInversionFeedforward.h"
 #include "frc/controller/LinearQuadraticRegulator.h"
 #include "frc/estimator/KalmanFilter.h"
@@ -35,6 +37,10 @@
 template <int States, int Inputs, int Outputs>
 class LinearSystemLoop {
  public:
+  using StateVector = Vectord<States>;
+  using InputVector = Vectord<Inputs>;
+  using OutputVector = Vectord<Outputs>;
+
   /**
    * Constructs a state-space loop with the given plant, controller, and
    * observer. By default, the initial reference is all zeros. Users should
@@ -53,7 +59,7 @@
                    units::volt_t maxVoltage, units::second_t dt)
       : LinearSystemLoop(
             plant, controller, observer,
-            [=](const Eigen::Vector<double, Inputs>& u) {
+            [=](const InputVector& u) {
               return frc::DesaturateInputVector<Inputs>(u, maxVoltage.value());
             },
             dt) {}
@@ -73,9 +79,7 @@
   LinearSystemLoop(LinearSystem<States, Inputs, Outputs>& plant,
                    LinearQuadraticRegulator<States, Inputs>& controller,
                    KalmanFilter<States, Inputs, Outputs>& observer,
-                   std::function<Eigen::Vector<double, Inputs>(
-                       const Eigen::Vector<double, Inputs>&)>
-                       clampFunction,
+                   std::function<InputVector(const InputVector&)> clampFunction,
                    units::second_t dt)
       : LinearSystemLoop(
             controller,
@@ -97,11 +101,10 @@
       LinearQuadraticRegulator<States, Inputs>& controller,
       const LinearPlantInversionFeedforward<States, Inputs>& feedforward,
       KalmanFilter<States, Inputs, Outputs>& observer, units::volt_t maxVoltage)
-      : LinearSystemLoop(controller, feedforward, observer,
-                         [=](const Eigen::Vector<double, Inputs>& u) {
-                           return frc::DesaturateInputVector<Inputs>(
-                               u, maxVoltage.value());
-                         }) {}
+      : LinearSystemLoop(
+            controller, feedforward, observer, [=](const InputVector& u) {
+              return frc::DesaturateInputVector<Inputs>(u, maxVoltage.value());
+            }) {}
 
   /**
    * Constructs a state-space loop with the given controller, feedforward,
@@ -117,9 +120,7 @@
       LinearQuadraticRegulator<States, Inputs>& controller,
       const LinearPlantInversionFeedforward<States, Inputs>& feedforward,
       KalmanFilter<States, Inputs, Outputs>& observer,
-      std::function<
-          Eigen::Vector<double, Inputs>(const Eigen::Vector<double, Inputs>&)>
-          clampFunction)
+      std::function<InputVector(const InputVector&)> clampFunction)
       : m_controller(&controller),
         m_feedforward(feedforward),
         m_observer(&observer),
@@ -134,9 +135,7 @@
   /**
    * Returns the observer's state estimate x-hat.
    */
-  const Eigen::Vector<double, States>& Xhat() const {
-    return m_observer->Xhat();
-  }
+  const StateVector& Xhat() const { return m_observer->Xhat(); }
 
   /**
    * Returns an element of the observer's state estimate x-hat.
@@ -148,7 +147,7 @@
   /**
    * Returns the controller's next reference r.
    */
-  const Eigen::Vector<double, States>& NextR() const { return m_nextR; }
+  const StateVector& NextR() const { return m_nextR; }
 
   /**
    * Returns an element of the controller's next reference r.
@@ -160,7 +159,7 @@
   /**
    * Returns the controller's calculated control input u.
    */
-  Eigen::Vector<double, Inputs> U() const {
+  InputVector U() const {
     return ClampInput(m_controller->U() + m_feedforward.Uff());
   }
 
@@ -176,9 +175,7 @@
    *
    * @param xHat The initial state estimate x-hat.
    */
-  void SetXhat(const Eigen::Vector<double, States>& xHat) {
-    m_observer->SetXhat(xHat);
-  }
+  void SetXhat(const StateVector& xHat) { m_observer->SetXhat(xHat); }
 
   /**
    * Set an element of the initial state estimate x-hat.
@@ -193,7 +190,7 @@
    *
    * @param nextR Next reference.
    */
-  void SetNextR(const Eigen::Vector<double, States>& nextR) { m_nextR = nextR; }
+  void SetNextR(const StateVector& nextR) { m_nextR = nextR; }
 
   /**
    * Return the controller used internally.
@@ -215,7 +212,7 @@
    * Return the observer used internally.
    */
   const KalmanFilter<States, Inputs, Outputs>& Observer() const {
-    return m_observer;
+    return *m_observer;
   }
 
   /**
@@ -225,7 +222,7 @@
    *
    * @param initialState The initial state.
    */
-  void Reset(const Eigen::Vector<double, States>& initialState) {
+  void Reset(const StateVector& initialState) {
     m_nextR.setZero();
     m_controller->Reset();
     m_feedforward.Reset(initialState);
@@ -235,18 +232,14 @@
   /**
    * Returns difference between reference r and current state x-hat.
    */
-  Eigen::Vector<double, States> Error() const {
-    return m_controller->R() - m_observer->Xhat();
-  }
+  StateVector Error() const { return m_controller->R() - m_observer->Xhat(); }
 
   /**
    * Correct the state estimate x-hat using the measurements in y.
    *
    * @param y Measurement vector.
    */
-  void Correct(const Eigen::Vector<double, Outputs>& y) {
-    m_observer->Correct(U(), y);
-  }
+  void Correct(const OutputVector& y) { m_observer->Correct(U(), y); }
 
   /**
    * Sets new controller output, projects model forward, and runs observer
@@ -258,7 +251,7 @@
    * @param dt Timestep for model update.
    */
   void Predict(units::second_t dt) {
-    Eigen::Vector<double, Inputs> u =
+    InputVector u =
         ClampInput(m_controller->Calculate(m_observer->Xhat(), m_nextR) +
                    m_feedforward.Calculate(m_nextR));
     m_observer->Predict(u, dt);
@@ -270,10 +263,7 @@
    * @param u Input vector to clamp.
    * @return Clamped input vector.
    */
-  Eigen::Vector<double, Inputs> ClampInput(
-      const Eigen::Vector<double, Inputs>& u) const {
-    return m_clampFunc(u);
-  }
+  InputVector ClampInput(const InputVector& u) const { return m_clampFunc(u); }
 
  protected:
   LinearQuadraticRegulator<States, Inputs>* m_controller;
@@ -283,12 +273,10 @@
   /**
    * Clamping function.
    */
-  std::function<Eigen::Vector<double, Inputs>(
-      const Eigen::Vector<double, Inputs>&)>
-      m_clampFunc;
+  std::function<InputVector(const InputVector&)> m_clampFunc;
 
   // Reference to go to in the next cycle (used by feedforward controller).
-  Eigen::Vector<double, States> m_nextR;
+  StateVector m_nextR;
 
   // These are accessible from non-templated subclasses.
   static constexpr int kStates = States;
@@ -296,4 +284,9 @@
   static constexpr int kOutputs = Outputs;
 };
 
+extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
+    LinearSystemLoop<1, 1, 1>;
+extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
+    LinearSystemLoop<2, 1, 1>;
+
 }  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/system/NumericalIntegration.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/system/NumericalIntegration.h
index 68d047f..bb856ec 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/system/NumericalIntegration.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/system/NumericalIntegration.h
@@ -54,80 +54,6 @@
 }
 
 /**
- * Performs adaptive RKF45 integration of dx/dt = f(x, u) for dt, as described
- * in https://en.wikipedia.org/wiki/Runge%E2%80%93Kutta%E2%80%93Fehlberg_method
- *
- * @param f        The function to integrate. It must take two arguments x and
- *                 u.
- * @param x        The initial value of x.
- * @param u        The value u held constant over the integration period.
- * @param dt       The time over which to integrate.
- * @param maxError The maximum acceptable truncation error. Usually a small
- *                 number like 1e-6.
- */
-template <typename F, typename T, typename U>
-T RKF45(F&& f, T x, U u, units::second_t dt, double maxError = 1e-6) {
-  // See
-  // https://en.wikipedia.org/wiki/Runge%E2%80%93Kutta%E2%80%93Fehlberg_method
-  // for the Butcher tableau the following arrays came from.
-  constexpr int kDim = 6;
-
-  // clang-format off
-  constexpr double A[kDim - 1][kDim - 1]{
-      {     1.0 / 4.0},
-      {     3.0 / 32.0,       9.0 / 32.0},
-      {1932.0 / 2197.0, -7200.0 / 2197.0,  7296.0 / 2197.0},
-      {  439.0 / 216.0,             -8.0,   3680.0 / 513.0, -845.0 / 4104.0},
-      {    -8.0 / 27.0,              2.0, -3544.0 / 2565.0, 1859.0 / 4104.0, -11.0 / 40.0}};
-  // clang-format on
-
-  constexpr std::array<double, kDim> b1{16.0 / 135.0,     0.0,
-                                        6656.0 / 12825.0, 28561.0 / 56430.0,
-                                        -9.0 / 50.0,      2.0 / 55.0};
-  constexpr std::array<double, kDim> b2{
-      25.0 / 216.0, 0.0, 1408.0 / 2565.0, 2197.0 / 4104.0, -1.0 / 5.0, 0.0};
-
-  T newX;
-  double truncationError;
-
-  double dtElapsed = 0.0;
-  double h = dt.value();
-
-  // Loop until we've gotten to our desired dt
-  while (dtElapsed < dt.value()) {
-    do {
-      // Only allow us to advance up to the dt remaining
-      h = std::min(h, dt.value() - dtElapsed);
-
-      // Notice how the derivative in the Wikipedia notation is dy/dx.
-      // That means their y is our x and their x is our t
-      // clang-format off
-      T k1 = f(x, u);
-      T k2 = f(x + h * (A[0][0] * k1), u);
-      T k3 = f(x + h * (A[1][0] * k1 + A[1][1] * k2), u);
-      T k4 = f(x + h * (A[2][0] * k1 + A[2][1] * k2 + A[2][2] * k3), u);
-      T k5 = f(x + h * (A[3][0] * k1 + A[3][1] * k2 + A[3][2] * k3 + A[3][3] * k4), u);
-      T k6 = f(x + h * (A[4][0] * k1 + A[4][1] * k2 + A[4][2] * k3 + A[4][3] * k4 + A[4][4] * k5), u);
-      // clang-format on
-
-      newX = x + h * (b1[0] * k1 + b1[1] * k2 + b1[2] * k3 + b1[3] * k4 +
-                      b1[4] * k5 + b1[5] * k6);
-      truncationError = (h * ((b1[0] - b2[0]) * k1 + (b1[1] - b2[1]) * k2 +
-                              (b1[2] - b2[2]) * k3 + (b1[3] - b2[3]) * k4 +
-                              (b1[4] - b2[4]) * k5 + (b1[5] - b2[5]) * k6))
-                            .norm();
-
-      h *= 0.9 * std::pow(maxError / truncationError, 1.0 / 5.0);
-    } while (truncationError > maxError);
-
-    dtElapsed += h;
-    x = newX;
-  }
-
-  return x;
-}
-
-/**
  * Performs adaptive Dormand-Prince integration of dx/dt = f(x, u) for dt.
  *
  * @param f        The function to integrate. It must take two arguments x and
@@ -173,7 +99,7 @@
   while (dtElapsed < dt.value()) {
     do {
       // Only allow us to advance up to the dt remaining
-      h = std::min(h, dt.value() - dtElapsed);
+      h = (std::min)(h, dt.value() - dtElapsed);
 
       // clang-format off
       T k1 = f(x, u);
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/system/NumericalJacobian.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/system/NumericalJacobian.h
index 5f1bc78..c4cb695 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/system/NumericalJacobian.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/system/NumericalJacobian.h
@@ -4,7 +4,7 @@
 
 #pragma once
 
-#include "Eigen/Core"
+#include "frc/EigenCore.h"
 
 namespace frc {
 
@@ -17,16 +17,16 @@
  * @param x     Vector argument.
  */
 template <int Rows, int Cols, typename F>
-auto NumericalJacobian(F&& f, const Eigen::Vector<double, Cols>& x) {
+auto NumericalJacobian(F&& f, const Vectord<Cols>& x) {
   constexpr double kEpsilon = 1e-5;
-  Eigen::Matrix<double, Rows, Cols> result;
+  Matrixd<Rows, Cols> result;
   result.setZero();
 
   // It's more expensive, but +- epsilon will be more accurate
   for (int i = 0; i < Cols; ++i) {
-    Eigen::Vector<double, Cols> dX_plus = x;
+    Vectord<Cols> dX_plus = x;
     dX_plus(i) += kEpsilon;
-    Eigen::Vector<double, Cols> dX_minus = x;
+    Vectord<Cols> dX_minus = x;
     dX_minus(i) -= kEpsilon;
     result.col(i) = (f(dX_plus) - f(dX_minus)) / (kEpsilon * 2.0);
   }
@@ -48,12 +48,10 @@
  * @param args     Remaining arguments to f(x, u, ...).
  */
 template <int Rows, int States, int Inputs, typename F, typename... Args>
-auto NumericalJacobianX(F&& f, const Eigen::Vector<double, States>& x,
-                        const Eigen::Vector<double, Inputs>& u,
-                        Args&&... args) {
+auto NumericalJacobianX(F&& f, const Vectord<States>& x,
+                        const Vectord<Inputs>& u, Args&&... args) {
   return NumericalJacobian<Rows, States>(
-      [&](const Eigen::Vector<double, States>& x) { return f(x, u, args...); },
-      x);
+      [&](const Vectord<States>& x) { return f(x, u, args...); }, x);
 }
 
 /**
@@ -70,12 +68,10 @@
  * @param args     Remaining arguments to f(x, u, ...).
  */
 template <int Rows, int States, int Inputs, typename F, typename... Args>
-auto NumericalJacobianU(F&& f, const Eigen::Vector<double, States>& x,
-                        const Eigen::Vector<double, Inputs>& u,
-                        Args&&... args) {
+auto NumericalJacobianU(F&& f, const Vectord<States>& x,
+                        const Vectord<Inputs>& u, Args&&... args) {
   return NumericalJacobian<Rows, Inputs>(
-      [&](const Eigen::Vector<double, Inputs>& u) { return f(x, u, args...); },
-      u);
+      [&](const Vectord<Inputs>& u) { return f(x, u, args...); }, u);
 }
 
 }  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/system/plant/DCMotor.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/system/plant/DCMotor.h
index a519b0e..831f532 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/system/plant/DCMotor.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/system/plant/DCMotor.h
@@ -76,6 +76,49 @@
   }
 
   /**
+   * Returns torque produced by the motor with a given current.
+   *
+   * @param current     The current drawn by the motor.
+   */
+  constexpr units::newton_meter_t Torque(units::ampere_t current) const {
+    return current * Kt;
+  }
+
+  /**
+   * Returns the voltage provided to the motor for a given torque and
+   * angular velocity.
+   *
+   * @param torque      The torque produced by the motor.
+   * @param speed       The current angular velocity of the motor.
+   */
+  constexpr units::volt_t Voltage(units::newton_meter_t torque,
+                                  units::radians_per_second_t speed) const {
+    return 1.0 / Kv * speed + 1.0 / Kt * R * torque;
+  }
+
+  /**
+   * Returns the speed produced by the motor at a given torque and input
+   * voltage.
+   *
+   * @param torque        The torque produced by the motor.
+   * @param inputVoltage  The input voltage provided to the motor.
+   */
+  constexpr units::radians_per_second_t Speed(
+      units::newton_meter_t torque, units::volt_t inputVoltage) const {
+    return inputVoltage * Kv - 1.0 / Kt * torque * R * Kv;
+  }
+
+  /**
+   * Returns a copy of this motor with the given gearbox reduction applied.
+   *
+   * @param gearboxReduction  The gearbox reduction.
+   */
+  constexpr DCMotor WithReduction(double gearboxReduction) {
+    return DCMotor(nominalVoltage, stallTorque * gearboxReduction, stallCurrent,
+                   freeCurrent, freeSpeed / gearboxReduction);
+  }
+
+  /**
    * Returns instance of CIM.
    */
   static constexpr DCMotor CIM(int numMotors = 1) {
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/system/plant/LinearSystemId.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/system/plant/LinearSystemId.h
index 26142bf..3e69545 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/system/plant/LinearSystemId.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/system/plant/LinearSystemId.h
@@ -31,94 +31,49 @@
       units::inverse<units::seconds>>>;
 
   /**
-   * Constructs the state-space model for an elevator.
+   * Create a state-space model of the elevator system. The states of the system
+   * are [position, velocity], inputs are [voltage], and outputs are [position].
    *
-   * States: [[position], [velocity]]
-   * Inputs: [[voltage]]
-   * Outputs: [[position]]
-   *
-   * @param motor Instance of DCMotor.
-   * @param m Carriage mass.
-   * @param r Pulley radius.
+   * @param motor The motor (or gearbox) attached to the carriage.
+   * @param mass The mass of the elevator carriage, in kilograms.
+   * @param radius The radius of the elevator's driving drum, in meters.
    * @param G Gear ratio from motor to carriage.
-   * @throws std::domain_error if m <= 0, r <= 0, or G <= 0.
+   * @throws std::domain_error if mass <= 0, radius <= 0, or G <= 0.
    */
   static LinearSystem<2, 1, 1> ElevatorSystem(DCMotor motor,
-                                              units::kilogram_t m,
-                                              units::meter_t r, double G) {
-    if (m <= 0_kg) {
-      throw std::domain_error("m must be greater than zero.");
-    }
-    if (r <= 0_m) {
-      throw std::domain_error("r must be greater than zero.");
-    }
-    if (G <= 0.0) {
-      throw std::domain_error("G must be greater than zero.");
-    }
-
-    Eigen::Matrix<double, 2, 2> A{
-        {0.0, 1.0},
-        {0.0, (-std::pow(G, 2) * motor.Kt /
-               (motor.R * units::math::pow<2>(r) * m * motor.Kv))
-                  .value()}};
-    Eigen::Matrix<double, 2, 1> B{0.0,
-                                  (G * motor.Kt / (motor.R * r * m)).value()};
-    Eigen::Matrix<double, 1, 2> C{1.0, 0.0};
-    Eigen::Matrix<double, 1, 1> D{0.0};
-
-    return LinearSystem<2, 1, 1>(A, B, C, D);
-  }
+                                              units::kilogram_t mass,
+                                              units::meter_t radius, double G);
 
   /**
-   * Constructs the state-space model for a single-jointed arm.
+   * Create a state-space model of a single-jointed arm system.The states of the
+   * system are [angle, angular velocity], inputs are [voltage], and outputs are
+   * [angle].
    *
-   * States: [[angle], [angular velocity]]
-   * Inputs: [[voltage]]
-   * Outputs: [[angle]]
-   *
-   * @param motor Instance of DCMotor.
-   * @param J Moment of inertia.
-   * @param G Gear ratio from motor to carriage.
+   * @param motor The motor (or gearbox) attached to the arm.
+   * @param J The moment of inertia J of the arm.
+   * @param G Gear ratio from motor to arm.
    * @throws std::domain_error if J <= 0 or G <= 0.
    */
   static LinearSystem<2, 1, 1> SingleJointedArmSystem(
-      DCMotor motor, units::kilogram_square_meter_t J, double G) {
-    if (J <= 0_kg_sq_m) {
-      throw std::domain_error("J must be greater than zero.");
-    }
-    if (G <= 0.0) {
-      throw std::domain_error("G must be greater than zero.");
-    }
-
-    Eigen::Matrix<double, 2, 2> A{
-        {0.0, 1.0},
-        {0.0, (-std::pow(G, 2) * motor.Kt / (motor.Kv * motor.R * J)).value()}};
-    Eigen::Matrix<double, 2, 1> B{0.0, (G * motor.Kt / (motor.R * J)).value()};
-    Eigen::Matrix<double, 1, 2> C{1.0, 0.0};
-    Eigen::Matrix<double, 1, 1> D{0.0};
-
-    return LinearSystem<2, 1, 1>(A, B, C, D);
-  }
+      DCMotor motor, units::kilogram_square_meter_t J, double G);
 
   /**
-   * Constructs the state-space model for a 1 DOF velocity-only system from
-   * system identification data.
+   * Create a state-space model for a 1 DOF velocity system from its kV
+   * (volts/(unit/sec)) and kA (volts/(unit/sec²)). These constants can be
+   * found using SysId. The states of the system are [velocity], inputs are
+   * [voltage], and outputs are [velocity].
    *
    * You MUST use an SI unit (i.e. meters or radians) for the Distance template
    * argument. You may still use non-SI units (such as feet or inches) for the
    * actual method arguments; they will automatically be converted to SI
    * internally.
    *
-   * States: [[velocity]]
-   * Inputs: [[voltage]]
-   * Outputs: [[velocity]]
-   *
    * The parameters provided by the user are from this feedforward model:
    *
    * u = K_v v + K_a a
    *
-   * @param kV The velocity gain, in volt seconds per distance.
-   * @param kA The acceleration gain, in volt seconds^2 per distance.
+   * @param kV The velocity gain, in volts/(unit/sec).
+   * @param kA The acceleration gain, in volts/(unit/sec²).
    * @throws std::domain_error if kV <= 0 or kA <= 0.
    */
   template <typename Distance, typename = std::enable_if_t<
@@ -134,33 +89,32 @@
       throw std::domain_error("Ka must be greater than zero.");
     }
 
-    Eigen::Matrix<double, 1, 1> A{-kV.value() / kA.value()};
-    Eigen::Matrix<double, 1, 1> B{1.0 / kA.value()};
-    Eigen::Matrix<double, 1, 1> C{1.0};
-    Eigen::Matrix<double, 1, 1> D{0.0};
+    Matrixd<1, 1> A{-kV.value() / kA.value()};
+    Matrixd<1, 1> B{1.0 / kA.value()};
+    Matrixd<1, 1> C{1.0};
+    Matrixd<1, 1> D{0.0};
 
     return LinearSystem<1, 1, 1>(A, B, C, D);
   }
 
   /**
-   * Constructs the state-space model for a 1 DOF position system from system
-   * identification data.
+   * Create a state-space model for a 1 DOF position system from its kV
+   * (volts/(unit/sec)) and kA (volts/(unit/sec²)). These constants can be
+   * found using SysId. the states of the system are [position, velocity],
+   * inputs are [voltage], and outputs are [position].
    *
    * You MUST use an SI unit (i.e. meters or radians) for the Distance template
    * argument. You may still use non-SI units (such as feet or inches) for the
    * actual method arguments; they will automatically be converted to SI
    * internally.
    *
-   * States: [[position], [velocity]]
-   * Inputs: [[voltage]]
-   * Outputs: [[position]]
-   *
    * The parameters provided by the user are from this feedforward model:
    *
    * u = K_v v + K_a a
    *
-   * @param kV The velocity gain, in volt seconds per distance.
-   * @param kA The acceleration gain, in volt seconds^2 per distance.
+   * @param kV The velocity gain, in volts/(unit/sec).
+   * @param kA The acceleration gain, in volts/(unit/sec²).
+   *
    * @throws std::domain_error if kV <= 0 or kA <= 0.
    */
   template <typename Distance, typename = std::enable_if_t<
@@ -176,236 +130,111 @@
       throw std::domain_error("Ka must be greater than zero.");
     }
 
-    Eigen::Matrix<double, 2, 2> A{{0.0, 1.0}, {0.0, -kV.value() / kA.value()}};
-    Eigen::Matrix<double, 2, 1> B{0.0, 1.0 / kA.value()};
-    Eigen::Matrix<double, 1, 2> C{1.0, 0.0};
-    Eigen::Matrix<double, 1, 1> D{0.0};
+    Matrixd<2, 2> A{{0.0, 1.0}, {0.0, -kV.value() / kA.value()}};
+    Matrixd<2, 1> B{0.0, 1.0 / kA.value()};
+    Matrixd<1, 2> C{1.0, 0.0};
+    Matrixd<1, 1> D{0.0};
 
     return LinearSystem<2, 1, 1>(A, B, C, D);
   }
 
   /**
-   * Constructs the state-space model for a 2 DOF drivetrain velocity system
-   * from system identification data.
+   * Identify a differential drive drivetrain given the drivetrain's kV and kA
+   * in both linear {(volts/(meter/sec), (volts/(meter/sec²))} and angular
+   * {(volts/(radian/sec), (volts/(radian/sec²))} cases. These constants can be
+   * found using SysId.
    *
-   * States: [[left velocity], [right velocity]]
-   * Inputs: [[left voltage], [right voltage]]
+   * States: [[left velocity], [right velocity]]<br>
+   * Inputs: [[left voltage], [right voltage]]<br>
    * Outputs: [[left velocity], [right velocity]]
    *
-   * @param kVlinear  The linear velocity gain in volts per (meter per second).
-   * @param kAlinear  The linear acceleration gain in volts per (meter per
+   * @param kVLinear  The linear velocity gain in volts per (meters per second).
+   * @param kALinear  The linear acceleration gain in volts per (meters per
    *                  second squared).
-   * @param kVangular The angular velocity gain in volts per (meter per second).
-   * @param kAangular The angular acceleration gain in volts per (meter per
+   * @param kVAngular The angular velocity gain in volts per (meters per
+   *                  second).
+   * @param kAAngular The angular acceleration gain in volts per (meters per
    *                  second squared).
-   * @throws domain_error if kVlinear <= 0, kAlinear <= 0, kVangular <= 0,
-   *         or kAangular <= 0.
+   * @throws domain_error if kVLinear <= 0, kALinear <= 0, kVAngular <= 0,
+   *         or kAAngular <= 0.
    */
   static LinearSystem<2, 2, 2> IdentifyDrivetrainSystem(
-      decltype(1_V / 1_mps) kVlinear, decltype(1_V / 1_mps_sq) kAlinear,
-      decltype(1_V / 1_mps) kVangular, decltype(1_V / 1_mps_sq) kAangular) {
-    if (kVlinear <= decltype(kVlinear){0}) {
-      throw std::domain_error("Kv,linear must be greater than zero.");
-    }
-    if (kAlinear <= decltype(kAlinear){0}) {
-      throw std::domain_error("Ka,linear must be greater than zero.");
-    }
-    if (kVangular <= decltype(kVangular){0}) {
-      throw std::domain_error("Kv,angular must be greater than zero.");
-    }
-    if (kAangular <= decltype(kAangular){0}) {
-      throw std::domain_error("Ka,angular must be greater than zero.");
-    }
-
-    double A1 = -(kVlinear.value() / kAlinear.value() +
-                  kVangular.value() / kAangular.value());
-    double A2 = -(kVlinear.value() / kAlinear.value() -
-                  kVangular.value() / kAangular.value());
-    double B1 = 1.0 / kAlinear.value() + 1.0 / kAangular.value();
-    double B2 = 1.0 / kAlinear.value() - 1.0 / kAangular.value();
-
-    Eigen::Matrix<double, 2, 2> A =
-        0.5 * Eigen::Matrix<double, 2, 2>{{A1, A2}, {A2, A1}};
-    Eigen::Matrix<double, 2, 2> B =
-        0.5 * Eigen::Matrix<double, 2, 2>{{B1, B2}, {B2, B1}};
-    Eigen::Matrix<double, 2, 2> C{{1.0, 0.0}, {0.0, 1.0}};
-    Eigen::Matrix<double, 2, 2> D{{0.0, 0.0}, {0.0, 0.0}};
-
-    return LinearSystem<2, 2, 2>(A, B, C, D);
-  }
+      decltype(1_V / 1_mps) kVLinear, decltype(1_V / 1_mps_sq) kALinear,
+      decltype(1_V / 1_mps) kVAngular, decltype(1_V / 1_mps_sq) kAAngular);
 
   /**
-   * Constructs the state-space model for a 2 DOF drivetrain velocity system
-   * from system identification data.
+   * Identify a differential drive drivetrain given the drivetrain's kV and kA
+   * in both linear {(volts/(meter/sec)), (volts/(meter/sec²))} and angular
+   * {(volts/(radian/sec)), (volts/(radian/sec²))} cases. This can be found
+   * using SysId.
    *
-   * States: [[left velocity], [right velocity]]
-   * Inputs: [[left voltage], [right voltage]]
+   * States: [[left velocity], [right velocity]]<br>
+   * Inputs: [[left voltage], [right voltage]]<br>
    * Outputs: [[left velocity], [right velocity]]
    *
-   * @param kVlinear   The linear velocity gain in volts per (meter per second).
-   * @param kAlinear   The linear acceleration gain in volts per (meter per
+   * @param kVLinear   The linear velocity gain in volts per (meters per
+   * second).
+   * @param kALinear   The linear acceleration gain in volts per (meters per
    *                   second squared).
-   * @param kVangular  The angular velocity gain in volts per (radian per
+   * @param kVAngular  The angular velocity gain in volts per (radians per
    *                   second).
-   * @param kAangular  The angular acceleration gain in volts per (radian per
+   * @param kAAngular  The angular acceleration gain in volts per (radians per
    *                   second squared).
-   * @param trackwidth The width of the drivetrain.
-   * @throws domain_error if kVlinear <= 0, kAlinear <= 0, kVangular <= 0,
-   *         kAangular <= 0, or trackwidth <= 0.
+   * @param trackwidth The distance between the differential drive's left and
+   *                   right wheels, in meters.
+   * @throws domain_error if kVLinear <= 0, kALinear <= 0, kVAngular <= 0,
+   *         kAAngular <= 0, or trackwidth <= 0.
    */
   static LinearSystem<2, 2, 2> IdentifyDrivetrainSystem(
-      decltype(1_V / 1_mps) kVlinear, decltype(1_V / 1_mps_sq) kAlinear,
-      decltype(1_V / 1_rad_per_s) kVangular,
-      decltype(1_V / 1_rad_per_s_sq) kAangular, units::meter_t trackwidth) {
-    if (kVlinear <= decltype(kVlinear){0}) {
-      throw std::domain_error("Kv,linear must be greater than zero.");
-    }
-    if (kAlinear <= decltype(kAlinear){0}) {
-      throw std::domain_error("Ka,linear must be greater than zero.");
-    }
-    if (kVangular <= decltype(kVangular){0}) {
-      throw std::domain_error("Kv,angular must be greater than zero.");
-    }
-    if (kAangular <= decltype(kAangular){0}) {
-      throw std::domain_error("Ka,angular must be greater than zero.");
-    }
-    if (trackwidth <= 0_m) {
-      throw std::domain_error("r must be greater than zero.");
-    }
-
-    // We want to find a factor to include in Kv,angular that will convert
-    // `u = Kv,angular omega` to `u = Kv,angular v`.
-    //
-    // v = omega r
-    // omega = v/r
-    // omega = 1/r v
-    // omega = 1/(trackwidth/2) v
-    // omega = 2/trackwidth v
-    //
-    // So multiplying by 2/trackwidth converts the angular gains from V/(rad/s)
-    // to V/(m/s).
-    return IdentifyDrivetrainSystem(kVlinear, kAlinear,
-                                    kVangular * 2.0 / trackwidth * 1_rad,
-                                    kAangular * 2.0 / trackwidth * 1_rad);
-  }
+      decltype(1_V / 1_mps) kVLinear, decltype(1_V / 1_mps_sq) kALinear,
+      decltype(1_V / 1_rad_per_s) kVAngular,
+      decltype(1_V / 1_rad_per_s_sq) kAAngular, units::meter_t trackwidth);
 
   /**
-   * Constructs the state-space model for a flywheel.
+   * Create a state-space model of a flywheel system, the states of the system
+   * are [angular velocity], inputs are [voltage], and outputs are [angular
+   * velocity].
    *
-   * States: [[angular velocity]]
-   * Inputs: [[voltage]]
-   * Outputs: [[angular velocity]]
-   *
-   * @param motor Instance of DCMotor.
-   * @param J Moment of inertia.
-   * @param G Gear ratio from motor to carriage.
+   * @param motor The motor (or gearbox) attached to the flywheel.
+   * @param J The moment of inertia J of the flywheel.
+   * @param G Gear ratio from motor to flywheel.
    * @throws std::domain_error if J <= 0 or G <= 0.
    */
   static LinearSystem<1, 1, 1> FlywheelSystem(DCMotor motor,
                                               units::kilogram_square_meter_t J,
-                                              double G) {
-    if (J <= 0_kg_sq_m) {
-      throw std::domain_error("J must be greater than zero.");
-    }
-    if (G <= 0.0) {
-      throw std::domain_error("G must be greater than zero.");
-    }
-
-    Eigen::Matrix<double, 1, 1> A{
-        (-std::pow(G, 2) * motor.Kt / (motor.Kv * motor.R * J)).value()};
-    Eigen::Matrix<double, 1, 1> B{(G * motor.Kt / (motor.R * J)).value()};
-    Eigen::Matrix<double, 1, 1> C{1.0};
-    Eigen::Matrix<double, 1, 1> D{0.0};
-
-    return LinearSystem<1, 1, 1>(A, B, C, D);
-  }
+                                              double G);
 
   /**
-   * Constructs the state-space model for a DC motor motor.
+   * Create a state-space model of a DC motor system. The states of the system
+   * are [angular position, angular velocity], inputs are [voltage], and outputs
+   * are [angular position, angular velocity].
    *
-   * States: [[angular position, angular velocity]]
-   * Inputs: [[voltage]]
-   * Outputs: [[angular position, angular velocity]]
-   *
-   * @param motor Instance of DCMotor.
-   * @param J Moment of inertia.
-   * @param G Gear ratio from motor to carriage.
+   * @param motor The motor (or gearbox) attached to the system.
+   * @param J the moment of inertia J of the DC motor.
+   * @param G Gear ratio from motor to output.
    * @throws std::domain_error if J <= 0 or G <= 0.
    */
   static LinearSystem<2, 1, 2> DCMotorSystem(DCMotor motor,
                                              units::kilogram_square_meter_t J,
-                                             double G) {
-    if (J <= 0_kg_sq_m) {
-      throw std::domain_error("J must be greater than zero.");
-    }
-    if (G <= 0.0) {
-      throw std::domain_error("G must be greater than zero.");
-    }
-
-    Eigen::Matrix<double, 2, 2> A{
-        {0.0, 1.0},
-        {0.0, (-std::pow(G, 2) * motor.Kt / (motor.Kv * motor.R * J)).value()}};
-    Eigen::Matrix<double, 2, 1> B{0.0, (G * motor.Kt / (motor.R * J)).value()};
-    Eigen::Matrix<double, 2, 2> C{{1.0, 0.0}, {0.0, 1.0}};
-    Eigen::Matrix<double, 2, 1> D{0.0, 0.0};
-
-    return LinearSystem<2, 1, 2>(A, B, C, D);
-  }
-
+                                             double G);
   /**
-   * Constructs the state-space model for a drivetrain.
+   * Create a state-space model of differential drive drivetrain. In this model,
+   * the states are [left velocity, right velocity], the inputs are [left
+   * voltage, right voltage], and the outputs are [left velocity, right
+   * velocity]
    *
-   * States: [[left velocity], [right velocity]]
-   * Inputs: [[left voltage], [right voltage]]
-   * Outputs: [[left velocity], [right velocity]]
-   *
-   * @param motor Instance of DCMotor.
-   * @param m Drivetrain mass.
-   * @param r Wheel radius.
-   * @param rb Robot radius.
-   * @param J Moment of inertia.
+   * @param motor The motor (or gearbox) driving the drivetrain.
+   * @param mass The mass of the robot in kilograms.
+   * @param r The radius of the wheels in meters.
+   * @param rb The radius of the base (half of the track width), in meters.
+   * @param J The moment of inertia of the robot.
    * @param G Gear ratio from motor to wheel.
-   * @throws std::domain_error if m <= 0, r <= 0, rb <= 0, J <= 0, or
+   * @throws std::domain_error if mass <= 0, r <= 0, rb <= 0, J <= 0, or
    *         G <= 0.
    */
   static LinearSystem<2, 2, 2> DrivetrainVelocitySystem(
-      const DCMotor& motor, units::kilogram_t m, units::meter_t r,
-      units::meter_t rb, units::kilogram_square_meter_t J, double G) {
-    if (m <= 0_kg) {
-      throw std::domain_error("m must be greater than zero.");
-    }
-    if (r <= 0_m) {
-      throw std::domain_error("r must be greater than zero.");
-    }
-    if (rb <= 0_m) {
-      throw std::domain_error("rb must be greater than zero.");
-    }
-    if (J <= 0_kg_sq_m) {
-      throw std::domain_error("J must be greater than zero.");
-    }
-    if (G <= 0.0) {
-      throw std::domain_error("G must be greater than zero.");
-    }
-
-    auto C1 = -std::pow(G, 2) * motor.Kt /
-              (motor.Kv * motor.R * units::math::pow<2>(r));
-    auto C2 = G * motor.Kt / (motor.R * r);
-
-    Eigen::Matrix<double, 2, 2> A{
-        {((1 / m + units::math::pow<2>(rb) / J) * C1).value(),
-         ((1 / m - units::math::pow<2>(rb) / J) * C1).value()},
-        {((1 / m - units::math::pow<2>(rb) / J) * C1).value(),
-         ((1 / m + units::math::pow<2>(rb) / J) * C1).value()}};
-    Eigen::Matrix<double, 2, 2> B{
-        {((1 / m + units::math::pow<2>(rb) / J) * C2).value(),
-         ((1 / m - units::math::pow<2>(rb) / J) * C2).value()},
-        {((1 / m - units::math::pow<2>(rb) / J) * C2).value(),
-         ((1 / m + units::math::pow<2>(rb) / J) * C2).value()}};
-    Eigen::Matrix<double, 2, 2> C{{1.0, 0.0}, {0.0, 1.0}};
-    Eigen::Matrix<double, 2, 2> D{{0.0, 0.0}, {0.0, 0.0}};
-
-    return LinearSystem<2, 2, 2>(A, B, C, D);
-  }
+      const DCMotor& motor, units::kilogram_t mass, units::meter_t r,
+      units::meter_t rb, units::kilogram_square_meter_t J, double G);
 };
 
 }  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/trajectory/Trajectory.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/trajectory/Trajectory.h
index d071ca3..f5ee79b 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/trajectory/Trajectory.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/trajectory/Trajectory.h
@@ -48,19 +48,8 @@
 
     /**
      * Checks equality between this State and another object.
-     *
-     * @param other The other object.
-     * @return Whether the two objects are equal.
      */
-    bool operator==(const State& other) const;
-
-    /**
-     * Checks inequality between this State and another object.
-     *
-     * @param other The other object.
-     * @return Whether the two objects are not equal.
-     */
-    bool operator!=(const State& other) const;
+    bool operator==(const State&) const = default;
 
     /**
      * Interpolates between two States.
@@ -140,19 +129,8 @@
 
   /**
    * Checks equality between this Trajectory and another object.
-   *
-   * @param other The other object.
-   * @return Whether the two objects are equal.
    */
-  bool operator==(const Trajectory& other) const;
-
-  /**
-   * Checks inequality between this Trajectory and another object.
-   *
-   * @param other The other object.
-   * @return Whether the two objects are inequal.
-   */
-  bool operator!=(const Trajectory& other) const;
+  bool operator==(const Trajectory&) const = default;
 
  private:
   std::vector<State> m_states;
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/trajectory/TrajectoryParameterizer.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/trajectory/TrajectoryParameterizer.h
index eea1c07..807b315 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/trajectory/TrajectoryParameterizer.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/trajectory/TrajectoryParameterizer.h
@@ -81,7 +81,7 @@
    * the trajectory, max velocity, min acceleration and max acceleration.
    */
   struct ConstrainedState {
-    PoseWithCurvature pose = {Pose2d(), units::curvature_t(0.0)};
+    PoseWithCurvature pose = {Pose2d{}, units::curvature_t{0.0}};
     units::meter_t distance = 0_m;
     units::meters_per_second_t maxVelocity = 0_mps;
     units::meters_per_second_squared_t minAcceleration = 0_mps_sq;
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/trajectory/TrajectoryUtil.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/trajectory/TrajectoryUtil.h
index 6e52a09..3ba882f 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/trajectory/TrajectoryUtil.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/trajectory/TrajectoryUtil.h
@@ -25,7 +25,7 @@
   static void ToPathweaverJson(const Trajectory& trajectory,
                                std::string_view path);
   /**
-   * Imports a Trajectory from a PathWeaver-style JSON file.
+   * Imports a Trajectory from a JSON file exported from PathWeaver.
    *
    * @param path The path of the json file to import from.
    *
@@ -34,7 +34,7 @@
   static Trajectory FromPathweaverJson(std::string_view path);
 
   /**
-   * Deserializes a Trajectory from PathWeaver-style JSON.
+   * Deserializes a Trajectory from JSON exported from PathWeaver.
    *
    * @param trajectory the trajectory to export
    *
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/trajectory/TrapezoidProfile.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/trajectory/TrapezoidProfile.h
index 0e623eb..24a8253 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/trajectory/TrapezoidProfile.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/trajectory/TrapezoidProfile.h
@@ -19,14 +19,14 @@
  *
  * Initialization:
  * @code{.cpp}
- * TrapezoidalMotionProfile::Constraints constraints{kMaxV, kMaxA};
+ * TrapezoidProfile::Constraints constraints{kMaxV, kMaxA};
  * double previousProfiledReference = initialReference;
  * @endcode
  *
  * Run on update:
  * @code{.cpp}
- * TrapezoidalMotionProfile profile{constraints, unprofiledReference,
- *                                  previousProfiledReference};
+ * TrapezoidProfile profile{constraints, unprofiledReference,
+ *                          previousProfiledReference};
  * previousProfiledReference = profile.Calculate(timeSincePreviousUpdate);
  * @endcode
  *
@@ -68,10 +68,7 @@
    public:
     Distance_t position{0};
     Velocity_t velocity{0};
-    bool operator==(const State& rhs) const {
-      return position == rhs.position && velocity == rhs.velocity;
-    }
-    bool operator!=(const State& rhs) const { return !(*this == rhs); }
+    bool operator==(const State&) const = default;
   };
 
   /**
@@ -82,7 +79,7 @@
    * @param initial     The initial state (usually the current state).
    */
   TrapezoidProfile(Constraints constraints, State goal,
-                   State initial = State{Distance_t(0), Velocity_t(0)});
+                   State initial = State{Distance_t{0}, Velocity_t{0}});
 
   TrapezoidProfile(const TrapezoidProfile&) = default;
   TrapezoidProfile& operator=(const TrapezoidProfile&) = default;
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/trajectory/TrapezoidProfile.inc b/third_party/allwpilib/wpimath/src/main/native/include/frc/trajectory/TrapezoidProfile.inc
index 4ec0f42..19eb1f3 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/trajectory/TrapezoidProfile.inc
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/trajectory/TrapezoidProfile.inc
@@ -46,10 +46,10 @@
       accelerationTime * accelerationTime * m_constraints.maxAcceleration;
 
   // Handle the case where the profile never reaches full speed
-  if (fullSpeedDist < Distance_t(0)) {
+  if (fullSpeedDist < Distance_t{0}) {
     accelerationTime =
         units::math::sqrt(fullTrapezoidDist / m_constraints.maxAcceleration);
-    fullSpeedDist = Distance_t(0);
+    fullSpeedDist = Distance_t{0};
   }
 
   m_endAccel = accelerationTime - cutoffBegin;
@@ -110,7 +110,7 @@
 
   Distance_t distToTarget = units::math::abs(target - position);
 
-  if (distToTarget < Distance_t(1e-6)) {
+  if (distToTarget < Distance_t{1e-6}) {
     return 0_s;
   }
 
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/trajectory/constraint/EllipticalRegionConstraint.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/trajectory/constraint/EllipticalRegionConstraint.h
index e2ef37b..f9f0d2e 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/trajectory/constraint/EllipticalRegionConstraint.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/trajectory/constraint/EllipticalRegionConstraint.h
@@ -44,8 +44,8 @@
     if (IsPoseInRegion(pose)) {
       return m_constraint.MaxVelocity(pose, curvature, velocity);
     } else {
-      return units::meters_per_second_t(
-          std::numeric_limits<double>::infinity());
+      return units::meters_per_second_t{
+          std::numeric_limits<double>::infinity()};
     }
   }
 
@@ -66,11 +66,16 @@
    * @return Whether the robot pose is within the constraint region.
    */
   bool IsPoseInRegion(const Pose2d& pose) const {
-    // The region (disk) bounded by the ellipse is given by the equation:
-    // ((x-h)^2)/Rx^2) + ((y-k)^2)/Ry^2) <= 1
+    // The region bounded by the ellipse is given by the equation:
+    //
+    // (x−h)²/Rx² + (y−k)²/Ry² ≤ 1
+    //
+    // Multiply by Rx²Ry² for efficiency reasons:
+    //
+    // (x−h)²Ry² + (y−k)²Rx² ≤ Rx²Ry²
+    //
     // If the inequality is satisfied, then it is inside the ellipse; otherwise
     // it is outside the ellipse.
-    // Both sides have been multiplied by Rx^2 * Ry^2 for efficiency reasons.
     return units::math::pow<2>(pose.X() - m_center.X()) *
                    units::math::pow<2>(m_radii.Y()) +
                units::math::pow<2>(pose.Y() - m_center.Y()) *
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/frc/trajectory/constraint/RectangularRegionConstraint.h b/third_party/allwpilib/wpimath/src/main/native/include/frc/trajectory/constraint/RectangularRegionConstraint.h
index c5bc559..18522fe 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/frc/trajectory/constraint/RectangularRegionConstraint.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/frc/trajectory/constraint/RectangularRegionConstraint.h
@@ -41,8 +41,8 @@
     if (IsPoseInRegion(pose)) {
       return m_constraint.MaxVelocity(pose, curvature, velocity);
     } else {
-      return units::meters_per_second_t(
-          std::numeric_limits<double>::infinity());
+      return units::meters_per_second_t{
+          std::numeric_limits<double>::infinity()};
     }
   }
 
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/units/angular_acceleration.h b/third_party/allwpilib/wpimath/src/main/native/include/units/angular_acceleration.h
index 6a411c4..632982b 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/units/angular_acceleration.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/units/angular_acceleration.h
@@ -25,6 +25,16 @@
 UNIT_ADD(angular_acceleration, degrees_per_second_squared,
          degrees_per_second_squared, deg_per_s_sq,
          compound_unit<angle::degrees, inverse<squared<time::seconds>>>)
+UNIT_ADD(angular_acceleration, turns_per_second_squared,
+         turns_per_second_squared, tr_per_s_sq,
+         compound_unit<angle::turns, inverse<squared<time::seconds>>>)
+UNIT_ADD(angular_acceleration, revolutions_per_minute_squared,
+         revolutions_per_minute_squared, rev_per_m_sq,
+         compound_unit<angle::turns, inverse<squared<time::minutes>>>)
+UNIT_ADD(angular_acceleration, revolutions_per_minute_per_second,
+         revolutions_per_minute_per_second, rev_per_m_per_s,
+         compound_unit<angle::turns, compound_unit<inverse<time::minutes>,
+                                                   inverse<time::seconds>>>)
 
 UNIT_ADD_CATEGORY_TRAIT(angular_acceleration)
 
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/units/base.h b/third_party/allwpilib/wpimath/src/main/native/include/units/base.h
index bc9fb44..9d021b1 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/units/base.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/units/base.h
@@ -1,9 +1,6 @@
-/*----------------------------------------------------------------------------*/
-/* Copyright (c) 2020 FIRST. All Rights Reserved.                             */
-/* Open Source Software - may be modified and shared by FRC teams. The code   */
-/* must be accompanied by the FIRST BSD license file in the root directory of */
-/* the project.                                                               */
-/*----------------------------------------------------------------------------*/
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
 
 // Copyright (c) 2016 Nic Holthaus
 //
@@ -78,14 +75,13 @@
 	#include <iostream>
 	#include <locale>
 	#include <string>
-#else
+#endif
+#if !defined(UNIT_LIB_DISABLE_FMT)
 	#include <locale>
 	#include <string>
 	#include <fmt/format.h>
 #endif
 
-#include <wpi/SymbolExports.h>
-
 //------------------------------
 //	STRING FORMATTER
 //------------------------------
@@ -180,7 +176,7 @@
  * @param		abbrev - abbreviated unit name, e.g. 'm'
  * @note		When UNIT_LIB_ENABLE_IOSTREAM isn't defined, the macro does not generate any code
  */
-#if !defined(UNIT_LIB_ENABLE_IOSTREAM)
+#if !defined(UNIT_LIB_DISABLE_FMT)
 	#define UNIT_ADD_IO(namespaceName, nameSingular, abbrev)\
 	}\
 	template <>\
@@ -205,7 +201,8 @@
 			return units::detail::to_string(obj()) + std::string(" "#abbrev);\
 		}\
 	}
-#else
+#endif
+#if defined(UNIT_LIB_ENABLE_IOSTREAM)
 	#define UNIT_ADD_IO(namespaceName, nameSingular, abbrev)\
 	namespace namespaceName\
 	{\
@@ -872,7 +869,7 @@
 	 *				- A `std::ratio` defining the conversion factor to the base unit type. (e.g. `std::ratio<1,12>` for inches to feet)
 	 *				- A base unit that the unit is derived from (or a unit category. Must be of type `unit` or `base_unit`)
 	 *				- An exponent representing factors of PI required by the conversion. (e.g. `std::ratio<-1>` for a radians to degrees conversion)
-	 *				- a ratio representing a datum translation required for the conversion (e.g. `std::ratio<32>` for a farenheit to celsius conversion)
+	 *				- a ratio representing a datum translation required for the conversion (e.g. `std::ratio<32>` for a fahrenheit to celsius conversion)
 	 *
 	 *				Typically, a specific unit, like `meters`, would be implemented as a type alias
 	 *				of `unit`, i.e. `using meters = unit<std::ratio<1>, units::category::length_unit`, or
@@ -2328,7 +2325,7 @@
 
 	// unary addition: +T
 	template<class Units, typename T, template<typename> class NonLinearScale>
-	inline unit_t<Units, T, NonLinearScale> operator+(const unit_t<Units, T, NonLinearScale>& u) noexcept
+	constexpr inline unit_t<Units, T, NonLinearScale> operator+(const unit_t<Units, T, NonLinearScale>& u) noexcept
 	{
 		return u;
 	}
@@ -2352,7 +2349,7 @@
 
 	// unary addition: -T
 	template<class Units, typename T, template<typename> class NonLinearScale>
-	inline unit_t<Units, T, NonLinearScale> operator-(const unit_t<Units, T, NonLinearScale>& u) noexcept
+	constexpr inline unit_t<Units, T, NonLinearScale> operator-(const unit_t<Units, T, NonLinearScale>& u) noexcept
 	{
 		return unit_t<Units, T, NonLinearScale>(-u());
 	}
@@ -2869,13 +2866,16 @@
 	namespace dimensionless
 	{
 		typedef unit_t<scalar, UNIT_LIB_DEFAULT_TYPE, decibel_scale> dB_t;
-#if defined(UNIT_LIB_ENABLE_IOSTREAM)
-		inline std::ostream& operator<<(std::ostream& os, const dB_t& obj) { os << obj() << " dB"; return os; }
 		typedef dB_t dBi_t;
 	}
-#else
+#if defined(UNIT_LIB_ENABLE_IOSTREAM)
+	namespace dimensionless
+	{
+		inline std::ostream& operator<<(std::ostream& os, const dB_t& obj) { os << obj() << " dB"; return os; }
+	}
+#endif
 }
-}
+#if !defined(UNIT_LIB_DISABLE_FMT)
 template <>
 struct fmt::formatter<units::dimensionless::dB_t> : fmt::formatter<double>
 {
@@ -2888,13 +2888,9 @@
 		return fmt::format_to(out, " dB");
 	}
 };
-
-namespace units {
-namespace dimensionless {
-		typedef dB_t dBi_t;
-	}
 #endif
 
+namespace units {
 	//------------------------------
 	//	DECIBEL ARITHMETIC
 	//------------------------------
@@ -3444,4 +3440,6 @@
 using namespace units::literals;
 #endif  // UNIT_HAS_LITERAL_SUPPORT
 
+#if !defined(UNIT_LIB_DISABLE_FMT)
 #include "frc/fmt/Units.h"
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/units/units.h b/third_party/allwpilib/wpimath/src/main/native/include/units/units.h
deleted file mode 100644
index 8d47679..0000000
--- a/third_party/allwpilib/wpimath/src/main/native/include/units/units.h
+++ /dev/null
@@ -1,59 +0,0 @@
-/*----------------------------------------------------------------------------*/
-/* Copyright (c) 2020 FIRST. All Rights Reserved.                             */
-/* Open Source Software - may be modified and shared by FRC teams. The code   */
-/* must be accompanied by the FIRST BSD license file in the root directory of */
-/* the project.                                                               */
-/*----------------------------------------------------------------------------*/
-
-#pragma once
-
-// clang-format off
-#ifdef _MSC_VER
-#pragma message("warning: Including this header drastically increases compilation times and is bad style. Include only what you use instead.")
-#else
-#warning "Including this header drastically increases compilation times and is bad style. Include only what you use instead."
-#endif
-
-// clang-format on
-
-#include "units/acceleration.h"
-#include "units/angle.h"
-#include "units/angular_acceleration.h"
-#include "units/angular_velocity.h"
-#include "units/area.h"
-#include "units/capacitance.h"
-#include "units/charge.h"
-#include "units/concentration.h"
-#include "units/conductance.h"
-#include "units/constants.h"
-#include "units/current.h"
-#include "units/curvature.h"
-#include "units/data.h"
-#include "units/data_transfer_rate.h"
-#include "units/density.h"
-#include "units/dimensionless.h"
-#include "units/energy.h"
-#include "units/force.h"
-#include "units/frequency.h"
-#include "units/illuminance.h"
-#include "units/impedance.h"
-#include "units/inductance.h"
-#include "units/length.h"
-#include "units/luminous_flux.h"
-#include "units/luminous_intensity.h"
-#include "units/magnetic_field_strength.h"
-#include "units/magnetic_flux.h"
-#include "units/mass.h"
-#include "units/math.h"
-#include "units/moment_of_inertia.h"
-#include "units/power.h"
-#include "units/pressure.h"
-#include "units/radiation.h"
-#include "units/solid_angle.h"
-#include "units/substance.h"
-#include "units/temperature.h"
-#include "units/time.h"
-#include "units/torque.h"
-#include "units/velocity.h"
-#include "units/voltage.h"
-#include "units/volume.h"
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/wpimath/MathShared.h b/third_party/allwpilib/wpimath/src/main/native/include/wpimath/MathShared.h
index f4a1795..3b9b3cd 100644
--- a/third_party/allwpilib/wpimath/src/main/native/include/wpimath/MathShared.h
+++ b/third_party/allwpilib/wpimath/src/main/native/include/wpimath/MathShared.h
@@ -34,12 +34,12 @@
 
   template <typename S, typename... Args>
   inline void ReportError(const S& format, Args&&... args) {
-    ReportErrorV(format, fmt::make_args_checked<Args...>(format, args...));
+    ReportErrorV(format, fmt::make_format_args(args...));
   }
 
   template <typename S, typename... Args>
   inline void ReportWarning(const S& format, Args&&... args) {
-    ReportWarningV(format, fmt::make_args_checked<Args...>(format, args...));
+    ReportWarningV(format, fmt::make_format_args(args...));
   }
 };
 
@@ -55,7 +55,7 @@
 
   template <typename S, typename... Args>
   static inline void ReportError(const S& format, Args&&... args) {
-    ReportErrorV(format, fmt::make_args_checked<Args...>(format, args...));
+    ReportErrorV(format, fmt::make_format_args(args...));
   }
 
   static void ReportWarningV(fmt::string_view format, fmt::format_args args) {
@@ -64,7 +64,7 @@
 
   template <typename S, typename... Args>
   static inline void ReportWarning(const S& format, Args&&... args) {
-    ReportWarningV(format, fmt::make_args_checked<Args...>(format, args...));
+    ReportWarningV(format, fmt::make_format_args(args...));
   }
 
   static void ReportUsage(MathUsageId id, int count) {
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/drake/include/drake/common/drake_assert.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/drake/include/drake/common/drake_assert.h
new file mode 100644
index 0000000..47097ed
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/drake/include/drake/common/drake_assert.h
@@ -0,0 +1,162 @@
+#pragma once
+
+#include <type_traits>
+
+/// @file
+/// Provides Drake's assertion implementation.  This is intended to be used
+/// both within Drake and by other software.  Drake's asserts can be armed
+/// and disarmed independently from the system-wide asserts.
+
+#ifdef DRAKE_DOXYGEN_CXX
+/// @p DRAKE_ASSERT(condition) is similar to the built-in @p assert(condition)
+/// from the C++ system header @p <cassert>.  Unless Drake's assertions are
+/// disarmed by the pre-processor definitions listed below, @p DRAKE_ASSERT
+/// will evaluate @p condition and iff the value is false will trigger an
+/// assertion failure with a message showing at least the condition text,
+/// function name, file, and line.
+///
+/// By default, assertion failures will :abort() the program.  However, when
+/// using the pydrake python bindings, assertion failures will instead throw a
+/// C++ exception that causes a python SystemExit exception.
+///
+/// Assertions are enabled or disabled using the following pre-processor macros:
+///
+/// - If @p DRAKE_ENABLE_ASSERTS is defined, then @p DRAKE_ASSERT is armed.
+/// - If @p DRAKE_DISABLE_ASSERTS is defined, then @p DRAKE_ASSERT is disarmed.
+/// - If both macros are defined, then it is a compile-time error.
+/// - If neither are defined, then NDEBUG governs assertions as usual.
+///
+/// This header will define exactly one of either @p DRAKE_ASSERT_IS_ARMED or
+/// @p DRAKE_ASSERT_IS_DISARMED to indicate whether @p DRAKE_ASSERT is armed.
+///
+/// This header will define both `constexpr bool drake::kDrakeAssertIsArmed`
+/// and `constexpr bool drake::kDrakeAssertIsDisarmed` globals.
+///
+/// One difference versus the standard @p assert(condition) is that the
+/// @p condition within @p DRAKE_ASSERT is always syntax-checked, even if
+/// Drake's assertions are disarmed.
+///
+/// Treat @p DRAKE_ASSERT like a statement -- it must always be used
+/// in block scope, and must always be followed by a semicolon.
+#define DRAKE_ASSERT(condition)
+/// Like @p DRAKE_ASSERT, except that the expression must be void-valued; this
+/// allows for guarding expensive assertion-checking subroutines using the same
+/// macros as stand-alone assertions.
+#define DRAKE_ASSERT_VOID(expression)
+/// Evaluates @p condition and iff the value is false will trigger an assertion
+/// failure with a message showing at least the condition text, function name,
+/// file, and line.
+#define DRAKE_DEMAND(condition)
+/// Silences a "no return value" compiler warning by calling a function that
+/// always raises an exception or aborts (i.e., a function marked noreturn).
+/// Only use this macro at a point where (1) a point in the code is truly
+/// unreachable, (2) the fact that it's unreachable is knowable from only
+/// reading the function itself (and not, e.g., some larger design invariant),
+/// and (3) there is a compiler warning if this macro were removed.  The most
+/// common valid use is with a switch-case-return block where all cases are
+/// accounted for but the enclosing function is supposed to return a value.  Do
+/// *not* use this macro as a "logic error" assertion; it should *only* be used
+/// to silence false positive warnings.  When in doubt, throw an exception
+/// manually instead of using this macro.
+#define DRAKE_UNREACHABLE()
+#else  //  DRAKE_DOXYGEN_CXX
+
+// Users should NOT set these; only this header should set them.
+#ifdef DRAKE_ASSERT_IS_ARMED
+# error Unexpected DRAKE_ASSERT_IS_ARMED defined.
+#endif
+#ifdef DRAKE_ASSERT_IS_DISARMED
+# error Unexpected DRAKE_ASSERT_IS_DISARMED defined.
+#endif
+
+// Decide whether Drake assertions are enabled.
+#if defined(DRAKE_ENABLE_ASSERTS) && defined(DRAKE_DISABLE_ASSERTS)
+# error Conflicting assertion toggles.
+#elif defined(DRAKE_ENABLE_ASSERTS)
+# define DRAKE_ASSERT_IS_ARMED
+#elif defined(DRAKE_DISABLE_ASSERTS) || defined(NDEBUG)
+# define DRAKE_ASSERT_IS_DISARMED
+#else
+# define DRAKE_ASSERT_IS_ARMED
+#endif
+
+namespace drake {
+namespace internal {
+// Abort the program with an error message.
+[[noreturn]] void Abort(const char* condition, const char* func,
+                        const char* file, int line);
+// Report an assertion failure; will either Abort(...) or throw.
+[[noreturn]] void AssertionFailed(const char* condition, const char* func,
+                                  const char* file, int line);
+}  // namespace internal
+namespace assert {
+// Allows for specialization of how to bool-convert Conditions used in
+// assertions, in case they are not intrinsically convertible.  See
+// common/symbolic/expression/formula.h for an example use.  This is a public
+// interface to extend; it is intended to be specialized by unusual Scalar
+// types that require special handling.
+template <typename Condition>
+struct ConditionTraits {
+  static constexpr bool is_valid = std::is_convertible_v<Condition, bool>;
+  static bool Evaluate(const Condition& value) {
+    return value;
+  }
+};
+}  // namespace assert
+}  // namespace drake
+
+#define DRAKE_UNREACHABLE()                                             \
+  ::drake::internal::Abort(                                             \
+      "Unreachable code was reached?!", __func__, __FILE__, __LINE__)
+
+#define DRAKE_DEMAND(condition)                                              \
+  do {                                                                       \
+    typedef ::drake::assert::ConditionTraits<                                \
+        typename std::remove_cv_t<decltype(condition)>> Trait;               \
+    static_assert(Trait::is_valid, "Condition should be bool-convertible."); \
+    static_assert(                                                           \
+        !std::is_pointer_v<decltype(condition)>,                             \
+        "When using DRAKE_DEMAND on a raw pointer, always write out "        \
+        "DRAKE_DEMAND(foo != nullptr), do not write DRAKE_DEMAND(foo) "      \
+        "and rely on implicit pointer-to-bool conversion.");                 \
+    if (!Trait::Evaluate(condition)) {                                       \
+      ::drake::internal::AssertionFailed(                                    \
+           #condition, __func__, __FILE__, __LINE__);                        \
+    }                                                                        \
+  } while (0)
+
+#ifdef DRAKE_ASSERT_IS_ARMED
+// Assertions are enabled.
+namespace drake {
+constexpr bool kDrakeAssertIsArmed = true;
+constexpr bool kDrakeAssertIsDisarmed = false;
+}  // namespace drake
+# define DRAKE_ASSERT(condition) DRAKE_DEMAND(condition)
+# define DRAKE_ASSERT_VOID(expression) do {                     \
+    static_assert(                                              \
+        std::is_convertible_v<decltype(expression), void>,      \
+        "Expression should be void.");                          \
+    expression;                                                 \
+  } while (0)
+#else
+// Assertions are disabled, so just typecheck the expression.
+namespace drake {
+constexpr bool kDrakeAssertIsArmed = false;
+constexpr bool kDrakeAssertIsDisarmed = true;
+}  // namespace drake
+# define DRAKE_ASSERT(condition) do {                                        \
+    typedef ::drake::assert::ConditionTraits<                                \
+        typename std::remove_cv_t<decltype(condition)>> Trait;               \
+    static_assert(Trait::is_valid, "Condition should be bool-convertible."); \
+    static_assert(                                                           \
+        !std::is_pointer_v<decltype(condition)>,                             \
+        "When using DRAKE_ASSERT on a raw pointer, always write out "        \
+        "DRAKE_ASSERT(foo != nullptr), do not write DRAKE_ASSERT(foo) "      \
+        "and rely on implicit pointer-to-bool conversion.");                 \
+  } while (0)
+# define DRAKE_ASSERT_VOID(expression) static_assert(           \
+    std::is_convertible_v<decltype(expression), void>,          \
+    "Expression should be void.")
+#endif
+
+#endif  // DRAKE_DOXYGEN_CXX
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/drake/common/drake_assertion_error.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/drake/include/drake/common/drake_assertion_error.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/include/drake/common/drake_assertion_error.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/drake/include/drake/common/drake_assertion_error.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/drake/common/drake_copyable.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/drake/include/drake/common/drake_copyable.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/include/drake/common/drake_copyable.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/drake/include/drake/common/drake_copyable.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/drake/common/drake_throw.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/drake/include/drake/common/drake_throw.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/include/drake/common/drake_throw.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/drake/include/drake/common/drake_throw.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/drake/common/is_approx_equal_abstol.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/drake/include/drake/common/is_approx_equal_abstol.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/include/drake/common/is_approx_equal_abstol.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/drake/include/drake/common/is_approx_equal_abstol.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/drake/common/never_destroyed.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/drake/include/drake/common/never_destroyed.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/include/drake/common/never_destroyed.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/drake/include/drake/common/never_destroyed.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/include/drake/math/discrete_algebraic_riccati_equation.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/drake/include/drake/math/discrete_algebraic_riccati_equation.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/include/drake/math/discrete_algebraic_riccati_equation.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/drake/include/drake/math/discrete_algebraic_riccati_equation.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/drake/common/drake_assert_and_throw.cpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/drake/src/common/drake_assert_and_throw.cpp
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/cpp/drake/common/drake_assert_and_throw.cpp
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/drake/src/common/drake_assert_and_throw.cpp
diff --git a/third_party/allwpilib/wpimath/src/main/native/cpp/drake/math/discrete_algebraic_riccati_equation.cpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/drake/src/math/discrete_algebraic_riccati_equation.cpp
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/cpp/drake/math/discrete_algebraic_riccati_equation.cpp
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/drake/src/math/discrete_algebraic_riccati_equation.cpp
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/Cholesky b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/Cholesky
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/Cholesky
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/Cholesky
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/Core b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/Core
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/Core
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/Core
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/Eigenvalues b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/Eigenvalues
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/Eigenvalues
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/Eigenvalues
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/Householder b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/Householder
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/Householder
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/Householder
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/IterativeLinearSolvers b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/IterativeLinearSolvers
new file mode 100644
index 0000000..957d575
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/IterativeLinearSolvers
@@ -0,0 +1,48 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_ITERATIVELINEARSOLVERS_MODULE_H
+#define EIGEN_ITERATIVELINEARSOLVERS_MODULE_H
+
+#include "SparseCore"
+#include "OrderingMethods"
+
+#include "src/Core/util/DisableStupidWarnings.h"
+
+/** 
+  * \defgroup IterativeLinearSolvers_Module IterativeLinearSolvers module
+  *
+  * This module currently provides iterative methods to solve problems of the form \c A \c x = \c b, where \c A is a squared matrix, usually very large and sparse.
+  * Those solvers are accessible via the following classes:
+  *  - ConjugateGradient for selfadjoint (hermitian) matrices,
+  *  - LeastSquaresConjugateGradient for rectangular least-square problems,
+  *  - BiCGSTAB for general square matrices.
+  *
+  * These iterative solvers are associated with some preconditioners:
+  *  - IdentityPreconditioner - not really useful
+  *  - DiagonalPreconditioner - also called Jacobi preconditioner, work very well on diagonal dominant matrices.
+  *  - IncompleteLUT - incomplete LU factorization with dual thresholding
+  *
+  * Such problems can also be solved using the direct sparse decomposition modules: SparseCholesky, CholmodSupport, UmfPackSupport, SuperLUSupport.
+  *
+    \code
+    #include <Eigen/IterativeLinearSolvers>
+    \endcode
+  */
+
+#include "src/IterativeLinearSolvers/SolveWithGuess.h"
+#include "src/IterativeLinearSolvers/IterativeSolverBase.h"
+#include "src/IterativeLinearSolvers/BasicPreconditioners.h"
+#include "src/IterativeLinearSolvers/ConjugateGradient.h"
+#include "src/IterativeLinearSolvers/LeastSquareConjugateGradient.h"
+#include "src/IterativeLinearSolvers/BiCGSTAB.h"
+#include "src/IterativeLinearSolvers/IncompleteLUT.h"
+#include "src/IterativeLinearSolvers/IncompleteCholesky.h"
+
+#include "src/Core/util/ReenableStupidWarnings.h"
+
+#endif // EIGEN_ITERATIVELINEARSOLVERS_MODULE_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/Jacobi b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/Jacobi
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/Jacobi
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/Jacobi
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/LU b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/LU
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/LU
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/LU
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/OrderingMethods b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/OrderingMethods
new file mode 100644
index 0000000..29691a6
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/OrderingMethods
@@ -0,0 +1,70 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_ORDERINGMETHODS_MODULE_H
+#define EIGEN_ORDERINGMETHODS_MODULE_H
+
+#include "SparseCore"
+
+#include "src/Core/util/DisableStupidWarnings.h"
+
+/** 
+  * \defgroup OrderingMethods_Module OrderingMethods module
+  *
+  * This module is currently for internal use only
+  * 
+  * It defines various built-in and external ordering methods for sparse matrices. 
+  * They are typically used to reduce the number of elements during 
+  * the sparse matrix decomposition (LLT, LU, QR).
+  * Precisely, in a preprocessing step, a permutation matrix P is computed using 
+  * those ordering methods and applied to the columns of the matrix. 
+  * Using for instance the sparse Cholesky decomposition, it is expected that 
+  * the nonzeros elements in LLT(A*P) will be much smaller than that in LLT(A).
+  * 
+  * 
+  * Usage : 
+  * \code
+  * #include <Eigen/OrderingMethods>
+  * \endcode
+  * 
+  * A simple usage is as a template parameter in the sparse decomposition classes : 
+  * 
+  * \code 
+  * SparseLU<MatrixType, COLAMDOrdering<int> > solver;
+  * \endcode 
+  * 
+  * \code 
+  * SparseQR<MatrixType, COLAMDOrdering<int> > solver;
+  * \endcode
+  * 
+  * It is possible as well to call directly a particular ordering method for your own purpose, 
+  * \code 
+  * AMDOrdering<int> ordering;
+  * PermutationMatrix<Dynamic, Dynamic, int> perm;
+  * SparseMatrix<double> A; 
+  * //Fill the matrix ...
+  * 
+  * ordering(A, perm); // Call AMD
+  * \endcode
+  * 
+  * \note Some of these methods (like AMD or METIS), need the sparsity pattern 
+  * of the input matrix to be symmetric. When the matrix is structurally unsymmetric, 
+  * Eigen computes internally the pattern of \f$A^T*A\f$ before calling the method.
+  * If your matrix is already symmetric (at leat in structure), you can avoid that
+  * by calling the method with a SelfAdjointView type.
+  * 
+  * \code
+  *  // Call the ordering on the pattern of the lower triangular matrix A
+  * ordering(A.selfadjointView<Lower>(), perm);
+  * \endcode
+  */
+
+#include "src/OrderingMethods/Amd.h"
+#include "src/OrderingMethods/Ordering.h"
+#include "src/Core/util/ReenableStupidWarnings.h"
+
+#endif // EIGEN_ORDERINGMETHODS_MODULE_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/QR b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/QR
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/QR
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/QR
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/SVD b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/SVD
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/SVD
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/SVD
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/SparseCholesky b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/SparseCholesky
new file mode 100644
index 0000000..d2b1f12
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/SparseCholesky
@@ -0,0 +1,37 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2008-2013 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_SPARSECHOLESKY_MODULE_H
+#define EIGEN_SPARSECHOLESKY_MODULE_H
+
+#include "SparseCore"
+#include "OrderingMethods"
+
+#include "src/Core/util/DisableStupidWarnings.h"
+
+/** 
+  * \defgroup SparseCholesky_Module SparseCholesky module
+  *
+  * This module currently provides two variants of the direct sparse Cholesky decomposition for selfadjoint (hermitian) matrices.
+  * Those decompositions are accessible via the following classes:
+  *  - SimplicialLLt,
+  *  - SimplicialLDLt
+  *
+  * Such problems can also be solved using the ConjugateGradient solver from the IterativeLinearSolvers module.
+  *
+  * \code
+  * #include <Eigen/SparseCholesky>
+  * \endcode
+  */
+
+#include "src/SparseCholesky/SimplicialCholesky.h"
+#include "src/SparseCholesky/SimplicialCholesky_impl.h"
+#include "src/Core/util/ReenableStupidWarnings.h"
+
+#endif // EIGEN_SPARSECHOLESKY_MODULE_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/SparseCore b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/SparseCore
new file mode 100644
index 0000000..76966c4
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/SparseCore
@@ -0,0 +1,69 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_SPARSECORE_MODULE_H
+#define EIGEN_SPARSECORE_MODULE_H
+
+#include "Core"
+
+#include "src/Core/util/DisableStupidWarnings.h"
+
+#include <vector>
+#include <map>
+#include <cstdlib>
+#include <cstring>
+#include <algorithm>
+
+/** 
+  * \defgroup SparseCore_Module SparseCore module
+  *
+  * This module provides a sparse matrix representation, and basic associated matrix manipulations
+  * and operations.
+  *
+  * See the \ref TutorialSparse "Sparse tutorial"
+  *
+  * \code
+  * #include <Eigen/SparseCore>
+  * \endcode
+  *
+  * This module depends on: Core.
+  */
+
+#include "src/SparseCore/SparseUtil.h"
+#include "src/SparseCore/SparseMatrixBase.h"
+#include "src/SparseCore/SparseAssign.h"
+#include "src/SparseCore/CompressedStorage.h"
+#include "src/SparseCore/AmbiVector.h"
+#include "src/SparseCore/SparseCompressedBase.h"
+#include "src/SparseCore/SparseMatrix.h"
+#include "src/SparseCore/SparseMap.h"
+#include "src/SparseCore/MappedSparseMatrix.h"
+#include "src/SparseCore/SparseVector.h"
+#include "src/SparseCore/SparseRef.h"
+#include "src/SparseCore/SparseCwiseUnaryOp.h"
+#include "src/SparseCore/SparseCwiseBinaryOp.h"
+#include "src/SparseCore/SparseTranspose.h"
+#include "src/SparseCore/SparseBlock.h"
+#include "src/SparseCore/SparseDot.h"
+#include "src/SparseCore/SparseRedux.h"
+#include "src/SparseCore/SparseView.h"
+#include "src/SparseCore/SparseDiagonalProduct.h"
+#include "src/SparseCore/ConservativeSparseSparseProduct.h"
+#include "src/SparseCore/SparseSparseProductWithPruning.h"
+#include "src/SparseCore/SparseProduct.h"
+#include "src/SparseCore/SparseDenseProduct.h"
+#include "src/SparseCore/SparseSelfAdjointView.h"
+#include "src/SparseCore/SparseTriangularView.h"
+#include "src/SparseCore/TriangularSolver.h"
+#include "src/SparseCore/SparsePermutation.h"
+#include "src/SparseCore/SparseFuzzy.h"
+#include "src/SparseCore/SparseSolverBase.h"
+
+#include "src/Core/util/ReenableStupidWarnings.h"
+
+#endif // EIGEN_SPARSECORE_MODULE_H
+
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/SparseLU b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/SparseLU
new file mode 100644
index 0000000..37c4a5c
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/SparseLU
@@ -0,0 +1,50 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>
+// Copyright (C) 2012 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_SPARSELU_MODULE_H
+#define EIGEN_SPARSELU_MODULE_H
+
+#include "SparseCore"
+
+/** 
+  * \defgroup SparseLU_Module SparseLU module
+  * This module defines a supernodal factorization of general sparse matrices.
+  * The code is fully optimized for supernode-panel updates with specialized kernels.
+  * Please, see the documentation of the SparseLU class for more details.
+  */
+
+// Ordering interface
+#include "OrderingMethods"
+
+#include "src/Core/util/DisableStupidWarnings.h"
+
+#include "src/SparseLU/SparseLU_gemm_kernel.h"
+
+#include "src/SparseLU/SparseLU_Structs.h"
+#include "src/SparseLU/SparseLU_SupernodalMatrix.h"
+#include "src/SparseLU/SparseLUImpl.h"
+#include "src/SparseCore/SparseColEtree.h"
+#include "src/SparseLU/SparseLU_Memory.h"
+#include "src/SparseLU/SparseLU_heap_relax_snode.h"
+#include "src/SparseLU/SparseLU_relax_snode.h"
+#include "src/SparseLU/SparseLU_pivotL.h"
+#include "src/SparseLU/SparseLU_panel_dfs.h"
+#include "src/SparseLU/SparseLU_kernel_bmod.h"
+#include "src/SparseLU/SparseLU_panel_bmod.h"
+#include "src/SparseLU/SparseLU_column_dfs.h"
+#include "src/SparseLU/SparseLU_column_bmod.h"
+#include "src/SparseLU/SparseLU_copy_to_ucol.h"
+#include "src/SparseLU/SparseLU_pruneL.h"
+#include "src/SparseLU/SparseLU_Utils.h"
+#include "src/SparseLU/SparseLU.h"
+
+#include "src/Core/util/ReenableStupidWarnings.h"
+
+#endif // EIGEN_SPARSELU_MODULE_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/SparseQR b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/SparseQR
new file mode 100644
index 0000000..f5fc5fa
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/SparseQR
@@ -0,0 +1,36 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_SPARSEQR_MODULE_H
+#define EIGEN_SPARSEQR_MODULE_H
+
+#include "SparseCore"
+#include "OrderingMethods"
+#include "src/Core/util/DisableStupidWarnings.h"
+
+/** \defgroup SparseQR_Module SparseQR module
+  * \brief Provides QR decomposition for sparse matrices
+  * 
+  * This module provides a simplicial version of the left-looking Sparse QR decomposition. 
+  * The columns of the input matrix should be reordered to limit the fill-in during the 
+  * decomposition. Built-in methods (COLAMD, AMD) or external  methods (METIS) can be used to this end.
+  * See the \link OrderingMethods_Module OrderingMethods\endlink module for the list 
+  * of built-in and external ordering methods.
+  * 
+  * \code
+  * #include <Eigen/SparseQR>
+  * \endcode
+  * 
+  * 
+  */
+
+#include "src/SparseCore/SparseColEtree.h"
+#include "src/SparseQR/SparseQR.h"
+
+#include "src/Core/util/ReenableStupidWarnings.h"
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/StdDeque b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/StdDeque
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/StdDeque
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/StdDeque
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/StdList b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/StdList
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/StdList
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/StdList
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/StdVector b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/StdVector
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/StdVector
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/StdVector
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Cholesky/LDLT.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Cholesky/LDLT.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Cholesky/LDLT.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Cholesky/LDLT.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Cholesky/LLT.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Cholesky/LLT.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Cholesky/LLT.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Cholesky/LLT.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/ArithmeticSequence.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/ArithmeticSequence.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/ArithmeticSequence.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/ArithmeticSequence.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Array.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Array.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Array.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Array.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/ArrayBase.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/ArrayBase.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/ArrayBase.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/ArrayBase.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/ArrayWrapper.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/ArrayWrapper.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/ArrayWrapper.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/ArrayWrapper.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Assign.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Assign.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Assign.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Assign.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/AssignEvaluator.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/AssignEvaluator.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/AssignEvaluator.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/AssignEvaluator.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/BandMatrix.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/BandMatrix.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/BandMatrix.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/BandMatrix.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Block.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Block.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Block.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Block.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/BooleanRedux.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/BooleanRedux.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/BooleanRedux.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/BooleanRedux.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/CommaInitializer.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/CommaInitializer.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/CommaInitializer.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/CommaInitializer.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/ConditionEstimator.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/ConditionEstimator.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/ConditionEstimator.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/ConditionEstimator.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/CoreEvaluators.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/CoreEvaluators.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/CoreEvaluators.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/CoreEvaluators.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/CoreIterators.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/CoreIterators.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/CoreIterators.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/CoreIterators.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/CwiseBinaryOp.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/CwiseBinaryOp.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/CwiseBinaryOp.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/CwiseBinaryOp.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/CwiseNullaryOp.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/CwiseNullaryOp.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/CwiseNullaryOp.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/CwiseNullaryOp.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/CwiseTernaryOp.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/CwiseTernaryOp.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/CwiseTernaryOp.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/CwiseTernaryOp.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/CwiseUnaryOp.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/CwiseUnaryOp.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/CwiseUnaryOp.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/CwiseUnaryOp.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/CwiseUnaryView.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/CwiseUnaryView.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/CwiseUnaryView.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/CwiseUnaryView.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/DenseBase.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/DenseBase.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/DenseBase.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/DenseBase.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/DenseCoeffsBase.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/DenseCoeffsBase.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/DenseCoeffsBase.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/DenseCoeffsBase.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/DenseStorage.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/DenseStorage.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/DenseStorage.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/DenseStorage.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Diagonal.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Diagonal.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Diagonal.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Diagonal.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/DiagonalMatrix.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/DiagonalMatrix.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/DiagonalMatrix.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/DiagonalMatrix.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/DiagonalProduct.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/DiagonalProduct.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/DiagonalProduct.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/DiagonalProduct.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Dot.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Dot.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Dot.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Dot.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/EigenBase.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/EigenBase.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/EigenBase.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/EigenBase.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/ForceAlignedAccess.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/ForceAlignedAccess.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/ForceAlignedAccess.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/ForceAlignedAccess.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Fuzzy.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Fuzzy.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Fuzzy.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Fuzzy.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/GeneralProduct.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/GeneralProduct.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/GeneralProduct.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/GeneralProduct.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/GenericPacketMath.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/GenericPacketMath.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/GenericPacketMath.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/GenericPacketMath.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/GlobalFunctions.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/GlobalFunctions.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/GlobalFunctions.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/GlobalFunctions.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/IO.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/IO.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/IO.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/IO.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/IndexedView.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/IndexedView.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/IndexedView.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/IndexedView.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Inverse.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Inverse.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Inverse.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Inverse.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Map.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Map.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Map.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Map.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/MapBase.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/MapBase.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/MapBase.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/MapBase.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/MathFunctions.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/MathFunctions.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/MathFunctions.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/MathFunctions.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/MathFunctionsImpl.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/MathFunctionsImpl.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/MathFunctionsImpl.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/MathFunctionsImpl.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Matrix.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Matrix.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Matrix.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Matrix.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/MatrixBase.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/MatrixBase.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/MatrixBase.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/MatrixBase.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/NestByValue.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/NestByValue.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/NestByValue.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/NestByValue.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/NoAlias.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/NoAlias.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/NoAlias.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/NoAlias.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/NumTraits.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/NumTraits.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/NumTraits.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/NumTraits.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/PartialReduxEvaluator.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/PartialReduxEvaluator.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/PartialReduxEvaluator.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/PartialReduxEvaluator.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/PermutationMatrix.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/PermutationMatrix.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/PermutationMatrix.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/PermutationMatrix.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/PlainObjectBase.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/PlainObjectBase.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/PlainObjectBase.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/PlainObjectBase.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Product.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Product.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Product.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Product.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/ProductEvaluators.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/ProductEvaluators.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/ProductEvaluators.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/ProductEvaluators.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Random.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Random.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Random.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Random.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Redux.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Redux.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Redux.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Redux.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Ref.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Ref.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Ref.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Ref.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Replicate.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Replicate.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Replicate.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Replicate.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Reshaped.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Reshaped.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Reshaped.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Reshaped.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/ReturnByValue.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/ReturnByValue.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/ReturnByValue.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/ReturnByValue.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Reverse.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Reverse.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Reverse.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Reverse.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Select.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Select.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Select.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Select.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/SelfAdjointView.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/SelfAdjointView.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/SelfAdjointView.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/SelfAdjointView.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/SelfCwiseBinaryOp.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/SelfCwiseBinaryOp.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/SelfCwiseBinaryOp.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/SelfCwiseBinaryOp.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Solve.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Solve.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Solve.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Solve.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/SolveTriangular.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/SolveTriangular.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/SolveTriangular.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/SolveTriangular.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/SolverBase.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/SolverBase.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/SolverBase.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/SolverBase.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/StableNorm.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/StableNorm.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/StableNorm.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/StableNorm.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/StlIterators.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/StlIterators.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/StlIterators.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/StlIterators.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Stride.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Stride.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Stride.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Stride.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Swap.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Swap.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Swap.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Swap.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Transpose.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Transpose.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Transpose.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Transpose.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Transpositions.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Transpositions.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Transpositions.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Transpositions.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/TriangularMatrix.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/TriangularMatrix.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/TriangularMatrix.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/TriangularMatrix.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/VectorBlock.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/VectorBlock.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/VectorBlock.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/VectorBlock.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/VectorwiseOp.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/VectorwiseOp.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/VectorwiseOp.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/VectorwiseOp.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Visitor.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Visitor.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/Visitor.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/Visitor.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/AVX/Complex.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/AVX/Complex.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/AVX/Complex.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/AVX/Complex.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/AVX/MathFunctions.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/AVX/MathFunctions.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/AVX/MathFunctions.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/AVX/MathFunctions.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/AVX/PacketMath.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/AVX/PacketMath.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/AVX/PacketMath.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/AVX/PacketMath.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/AVX/TypeCasting.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/AVX/TypeCasting.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/AVX/TypeCasting.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/AVX/TypeCasting.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/Default/BFloat16.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/Default/BFloat16.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/Default/BFloat16.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/Default/BFloat16.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/Default/ConjHelper.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/Default/ConjHelper.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/Default/ConjHelper.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/Default/ConjHelper.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/Default/GenericPacketMathFunctions.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/Default/GenericPacketMathFunctions.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/Default/GenericPacketMathFunctions.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/Default/GenericPacketMathFunctions.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/Default/GenericPacketMathFunctionsFwd.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/Default/GenericPacketMathFunctionsFwd.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/Default/GenericPacketMathFunctionsFwd.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/Default/GenericPacketMathFunctionsFwd.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/Default/Half.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/Default/Half.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/Default/Half.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/Default/Half.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/Default/Settings.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/Default/Settings.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/Default/Settings.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/Default/Settings.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/Default/TypeCasting.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/Default/TypeCasting.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/Default/TypeCasting.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/Default/TypeCasting.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/NEON/Complex.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/NEON/Complex.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/NEON/Complex.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/NEON/Complex.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/NEON/GeneralBlockPanelKernel.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/NEON/GeneralBlockPanelKernel.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/NEON/GeneralBlockPanelKernel.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/NEON/GeneralBlockPanelKernel.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/NEON/MathFunctions.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/NEON/MathFunctions.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/NEON/MathFunctions.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/NEON/MathFunctions.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/NEON/PacketMath.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/NEON/PacketMath.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/NEON/PacketMath.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/NEON/PacketMath.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/NEON/TypeCasting.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/NEON/TypeCasting.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/NEON/TypeCasting.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/NEON/TypeCasting.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/SSE/Complex.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/SSE/Complex.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/SSE/Complex.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/SSE/Complex.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/SSE/MathFunctions.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/SSE/MathFunctions.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/SSE/MathFunctions.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/SSE/MathFunctions.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/SSE/PacketMath.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/SSE/PacketMath.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/SSE/PacketMath.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/SSE/PacketMath.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/SSE/TypeCasting.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/SSE/TypeCasting.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/arch/SSE/TypeCasting.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/arch/SSE/TypeCasting.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/functors/AssignmentFunctors.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/functors/AssignmentFunctors.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/functors/AssignmentFunctors.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/functors/AssignmentFunctors.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/functors/BinaryFunctors.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/functors/BinaryFunctors.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/functors/BinaryFunctors.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/functors/BinaryFunctors.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/functors/NullaryFunctors.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/functors/NullaryFunctors.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/functors/NullaryFunctors.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/functors/NullaryFunctors.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/functors/StlFunctors.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/functors/StlFunctors.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/functors/StlFunctors.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/functors/StlFunctors.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/functors/TernaryFunctors.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/functors/TernaryFunctors.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/functors/TernaryFunctors.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/functors/TernaryFunctors.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/functors/UnaryFunctors.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/functors/UnaryFunctors.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/functors/UnaryFunctors.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/functors/UnaryFunctors.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/products/GeneralBlockPanelKernel.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/products/GeneralBlockPanelKernel.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/products/GeneralBlockPanelKernel.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/products/GeneralBlockPanelKernel.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/products/GeneralMatrixMatrix.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/products/GeneralMatrixMatrix.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/products/GeneralMatrixMatrix.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/products/GeneralMatrixMatrix.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/products/GeneralMatrixVector.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/products/GeneralMatrixVector.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/products/GeneralMatrixVector.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/products/GeneralMatrixVector.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/products/Parallelizer.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/products/Parallelizer.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/products/Parallelizer.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/products/Parallelizer.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/products/SelfadjointMatrixMatrix.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/products/SelfadjointMatrixMatrix.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/products/SelfadjointMatrixMatrix.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/products/SelfadjointMatrixMatrix.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/products/SelfadjointMatrixVector.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/products/SelfadjointMatrixVector.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/products/SelfadjointMatrixVector.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/products/SelfadjointMatrixVector.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/products/SelfadjointProduct.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/products/SelfadjointProduct.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/products/SelfadjointProduct.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/products/SelfadjointProduct.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/products/SelfadjointRank2Update.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/products/SelfadjointRank2Update.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/products/SelfadjointRank2Update.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/products/SelfadjointRank2Update.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/products/TriangularMatrixMatrix.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/products/TriangularMatrixMatrix.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/products/TriangularMatrixMatrix.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/products/TriangularMatrixMatrix.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/products/TriangularMatrixVector.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/products/TriangularMatrixVector.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/products/TriangularMatrixVector.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/products/TriangularMatrixVector.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/products/TriangularSolverMatrix.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/products/TriangularSolverMatrix.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/products/TriangularSolverMatrix.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/products/TriangularSolverMatrix.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/products/TriangularSolverVector.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/products/TriangularSolverVector.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/products/TriangularSolverVector.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/products/TriangularSolverVector.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/util/BlasUtil.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/util/BlasUtil.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/util/BlasUtil.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/util/BlasUtil.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/util/ConfigureVectorization.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/util/ConfigureVectorization.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/util/ConfigureVectorization.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/util/ConfigureVectorization.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/util/Constants.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/util/Constants.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/util/Constants.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/util/Constants.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/util/DisableStupidWarnings.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/util/DisableStupidWarnings.h
new file mode 100644
index 0000000..d973255
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/util/DisableStupidWarnings.h
@@ -0,0 +1,117 @@
+#ifndef EIGEN_WARNINGS_DISABLED
+#define EIGEN_WARNINGS_DISABLED
+
+#ifdef _MSC_VER
+  // 4100 - unreferenced formal parameter (occurred e.g. in aligned_allocator::destroy(pointer p))
+  // 4101 - unreferenced local variable
+  // 4181 - qualifier applied to reference type ignored
+  // 4211 - nonstandard extension used : redefined extern to static
+  // 4244 - 'argument' : conversion from 'type1' to 'type2', possible loss of data
+  // 4273 - QtAlignedMalloc, inconsistent DLL linkage
+  // 4324 - structure was padded due to declspec(align())
+  // 4503 - decorated name length exceeded, name was truncated
+  // 4512 - assignment operator could not be generated
+  // 4522 - 'class' : multiple assignment operators specified
+  // 4700 - uninitialized local variable 'xyz' used
+  // 4714 - function marked as __forceinline not inlined
+  // 4717 - 'function' : recursive on all control paths, function will cause runtime stack overflow
+  // 4800 - 'type' : forcing value to bool 'true' or 'false' (performance warning)
+  #ifndef EIGEN_PERMANENTLY_DISABLE_STUPID_WARNINGS
+    #pragma warning( push )
+  #endif
+  #pragma warning( disable : 4100 4101 4181 4211 4244 4273 4324 4503 4512 4522 4700 4714 4717 4800)
+
+#elif defined __INTEL_COMPILER
+  // 2196 - routine is both "inline" and "noinline" ("noinline" assumed)
+  //        ICC 12 generates this warning even without any inline keyword, when defining class methods 'inline' i.e. inside of class body
+  //        typedef that may be a reference type.
+  // 279  - controlling expression is constant
+  //        ICC 12 generates this warning on assert(constant_expression_depending_on_template_params) and frankly this is a legitimate use case.
+  // 1684 - conversion from pointer to same-sized integral type (potential portability problem)
+  // 2259 - non-pointer conversion from "Eigen::Index={ptrdiff_t={long}}" to "int" may lose significant bits
+  #ifndef EIGEN_PERMANENTLY_DISABLE_STUPID_WARNINGS
+    #pragma warning push
+  #endif
+  #pragma warning disable 2196 279 1684 2259
+
+#elif defined __clang__
+  // -Wconstant-logical-operand - warning: use of logical && with constant operand; switch to bitwise & or remove constant
+  //     this is really a stupid warning as it warns on compile-time expressions involving enums
+  #ifndef EIGEN_PERMANENTLY_DISABLE_STUPID_WARNINGS
+    #pragma clang diagnostic push
+  #endif
+  #pragma clang diagnostic ignored "-Wconstant-logical-operand"
+  #if __clang_major__ >= 3 && __clang_minor__ >= 5
+    #pragma clang diagnostic ignored "-Wabsolute-value"
+  #endif
+  #if __clang_major__ >= 10
+    #pragma clang diagnostic ignored "-Wimplicit-int-float-conversion"
+  #endif
+  #if ( defined(__ALTIVEC__) || defined(__VSX__) ) && __cplusplus < 201103L
+    // warning: generic selections are a C11-specific feature
+    // ignoring warnings thrown at vec_ctf in Altivec/PacketMath.h
+    #pragma clang diagnostic ignored "-Wc11-extensions"
+  #endif
+
+#elif defined __GNUC__
+
+  #if (!defined(EIGEN_PERMANENTLY_DISABLE_STUPID_WARNINGS)) &&  (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 6))
+    #pragma GCC diagnostic push
+  #endif
+  // g++ warns about local variables shadowing member functions, which is too strict
+  #pragma GCC diagnostic ignored "-Wshadow"
+  #if __GNUC__ == 4 && __GNUC_MINOR__ < 8
+    // Until g++-4.7 there are warnings when comparing unsigned int vs 0, even in templated functions:
+    #pragma GCC diagnostic ignored "-Wtype-limits"
+  #endif
+  #if __GNUC__>=6
+    #pragma GCC diagnostic ignored "-Wignored-attributes"
+  #endif
+  #if __GNUC__==7
+    // See: https://gcc.gnu.org/bugzilla/show_bug.cgi?id=89325
+    #pragma GCC diagnostic ignored "-Wattributes"
+  #endif
+  #if __GNUC__>=8
+    #pragma GCC diagnostic ignored "-Wclass-memaccess"
+  #endif
+  #if __GNUC__>=11
+    // This warning is a false positive
+    #pragma GCC diagnostic ignored "-Wmaybe-uninitialized"
+  #endif
+  #if __GNUC__==12
+    // This warning is a false positive
+    #pragma GCC diagnostic ignored "-Warray-bounds"
+  #endif
+#endif
+
+#if defined __NVCC__
+  #pragma diag_suppress boolean_controlling_expr_is_constant
+  // Disable the "statement is unreachable" message
+  #pragma diag_suppress code_is_unreachable
+  // Disable the "dynamic initialization in unreachable code" message
+  #pragma diag_suppress initialization_not_reachable
+  // Disable the "invalid error number" message that we get with older versions of nvcc
+  #pragma diag_suppress 1222
+  // Disable the "calling a __host__ function from a __host__ __device__ function is not allowed" messages (yes, there are many of them and they seem to change with every version of the compiler)
+  #pragma diag_suppress 2527
+  #pragma diag_suppress 2529
+  #pragma diag_suppress 2651
+  #pragma diag_suppress 2653
+  #pragma diag_suppress 2668
+  #pragma diag_suppress 2669
+  #pragma diag_suppress 2670
+  #pragma diag_suppress 2671
+  #pragma diag_suppress 2735
+  #pragma diag_suppress 2737
+  #pragma diag_suppress 2739
+#endif
+
+#else
+// warnings already disabled:
+# ifndef EIGEN_WARNINGS_DISABLED_2
+#  define EIGEN_WARNINGS_DISABLED_2
+# elif defined(EIGEN_INTERNAL_DEBUGGING)
+#  error "Do not include \"DisableStupidWarnings.h\" recursively more than twice!"
+# endif
+
+#endif // not EIGEN_WARNINGS_DISABLED
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/util/ForwardDeclarations.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/util/ForwardDeclarations.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/util/ForwardDeclarations.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/util/ForwardDeclarations.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/util/IndexedViewHelper.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/util/IndexedViewHelper.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/util/IndexedViewHelper.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/util/IndexedViewHelper.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/util/IntegralConstant.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/util/IntegralConstant.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/util/IntegralConstant.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/util/IntegralConstant.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/util/Macros.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/util/Macros.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/util/Macros.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/util/Macros.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/util/Memory.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/util/Memory.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/util/Memory.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/util/Memory.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/util/Meta.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/util/Meta.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/util/Meta.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/util/Meta.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/util/ReenableStupidWarnings.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/util/ReenableStupidWarnings.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/util/ReenableStupidWarnings.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/util/ReenableStupidWarnings.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/util/ReshapedHelper.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/util/ReshapedHelper.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/util/ReshapedHelper.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/util/ReshapedHelper.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/util/StaticAssert.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/util/StaticAssert.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/util/StaticAssert.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/util/StaticAssert.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/util/SymbolicIndex.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/util/SymbolicIndex.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/util/SymbolicIndex.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/util/SymbolicIndex.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/util/XprHelper.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/util/XprHelper.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Core/util/XprHelper.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Core/util/XprHelper.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Eigenvalues/ComplexEigenSolver.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Eigenvalues/ComplexEigenSolver.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Eigenvalues/ComplexEigenSolver.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Eigenvalues/ComplexEigenSolver.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Eigenvalues/ComplexSchur.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Eigenvalues/ComplexSchur.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Eigenvalues/ComplexSchur.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Eigenvalues/ComplexSchur.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Eigenvalues/EigenSolver.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Eigenvalues/EigenSolver.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Eigenvalues/EigenSolver.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Eigenvalues/EigenSolver.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Eigenvalues/HessenbergDecomposition.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Eigenvalues/HessenbergDecomposition.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Eigenvalues/HessenbergDecomposition.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Eigenvalues/HessenbergDecomposition.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Eigenvalues/RealQZ.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Eigenvalues/RealQZ.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Eigenvalues/RealQZ.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Eigenvalues/RealQZ.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Eigenvalues/RealSchur.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Eigenvalues/RealSchur.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Eigenvalues/RealSchur.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Eigenvalues/RealSchur.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Eigenvalues/Tridiagonalization.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Eigenvalues/Tridiagonalization.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Eigenvalues/Tridiagonalization.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Eigenvalues/Tridiagonalization.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Householder/BlockHouseholder.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Householder/BlockHouseholder.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Householder/BlockHouseholder.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Householder/BlockHouseholder.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Householder/Householder.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Householder/Householder.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Householder/Householder.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Householder/Householder.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Householder/HouseholderSequence.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Householder/HouseholderSequence.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Householder/HouseholderSequence.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Householder/HouseholderSequence.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/IterativeLinearSolvers/BasicPreconditioners.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/IterativeLinearSolvers/BasicPreconditioners.h
new file mode 100644
index 0000000..a117fc1
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/IterativeLinearSolvers/BasicPreconditioners.h
@@ -0,0 +1,226 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2011-2014 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_BASIC_PRECONDITIONERS_H
+#define EIGEN_BASIC_PRECONDITIONERS_H
+
+namespace Eigen {
+
+/** \ingroup IterativeLinearSolvers_Module
+  * \brief A preconditioner based on the digonal entries
+  *
+  * This class allows to approximately solve for A.x = b problems assuming A is a diagonal matrix.
+  * In other words, this preconditioner neglects all off diagonal entries and, in Eigen's language, solves for:
+    \code
+    A.diagonal().asDiagonal() . x = b
+    \endcode
+  *
+  * \tparam _Scalar the type of the scalar.
+  *
+  * \implsparsesolverconcept
+  *
+  * This preconditioner is suitable for both selfadjoint and general problems.
+  * The diagonal entries are pre-inverted and stored into a dense vector.
+  *
+  * \note A variant that has yet to be implemented would attempt to preserve the norm of each column.
+  *
+  * \sa class LeastSquareDiagonalPreconditioner, class ConjugateGradient
+  */
+template <typename _Scalar>
+class DiagonalPreconditioner
+{
+    typedef _Scalar Scalar;
+    typedef Matrix<Scalar,Dynamic,1> Vector;
+  public:
+    typedef typename Vector::StorageIndex StorageIndex;
+    enum {
+      ColsAtCompileTime = Dynamic,
+      MaxColsAtCompileTime = Dynamic
+    };
+
+    DiagonalPreconditioner() : m_isInitialized(false) {}
+
+    template<typename MatType>
+    explicit DiagonalPreconditioner(const MatType& mat) : m_invdiag(mat.cols())
+    {
+      compute(mat);
+    }
+
+    EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT { return m_invdiag.size(); }
+    EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT { return m_invdiag.size(); }
+
+    template<typename MatType>
+    DiagonalPreconditioner& analyzePattern(const MatType& )
+    {
+      return *this;
+    }
+
+    template<typename MatType>
+    DiagonalPreconditioner& factorize(const MatType& mat)
+    {
+      m_invdiag.resize(mat.cols());
+      for(int j=0; j<mat.outerSize(); ++j)
+      {
+        typename MatType::InnerIterator it(mat,j);
+        while(it && it.index()!=j) ++it;
+        if(it && it.index()==j && it.value()!=Scalar(0))
+          m_invdiag(j) = Scalar(1)/it.value();
+        else
+          m_invdiag(j) = Scalar(1);
+      }
+      m_isInitialized = true;
+      return *this;
+    }
+
+    template<typename MatType>
+    DiagonalPreconditioner& compute(const MatType& mat)
+    {
+      return factorize(mat);
+    }
+
+    /** \internal */
+    template<typename Rhs, typename Dest>
+    void _solve_impl(const Rhs& b, Dest& x) const
+    {
+      x = m_invdiag.array() * b.array() ;
+    }
+
+    template<typename Rhs> inline const Solve<DiagonalPreconditioner, Rhs>
+    solve(const MatrixBase<Rhs>& b) const
+    {
+      eigen_assert(m_isInitialized && "DiagonalPreconditioner is not initialized.");
+      eigen_assert(m_invdiag.size()==b.rows()
+                && "DiagonalPreconditioner::solve(): invalid number of rows of the right hand side matrix b");
+      return Solve<DiagonalPreconditioner, Rhs>(*this, b.derived());
+    }
+
+    ComputationInfo info() { return Success; }
+
+  protected:
+    Vector m_invdiag;
+    bool m_isInitialized;
+};
+
+/** \ingroup IterativeLinearSolvers_Module
+  * \brief Jacobi preconditioner for LeastSquaresConjugateGradient
+  *
+  * This class allows to approximately solve for A' A x  = A' b problems assuming A' A is a diagonal matrix.
+  * In other words, this preconditioner neglects all off diagonal entries and, in Eigen's language, solves for:
+    \code
+    (A.adjoint() * A).diagonal().asDiagonal() * x = b
+    \endcode
+  *
+  * \tparam _Scalar the type of the scalar.
+  *
+  * \implsparsesolverconcept
+  *
+  * The diagonal entries are pre-inverted and stored into a dense vector.
+  *
+  * \sa class LeastSquaresConjugateGradient, class DiagonalPreconditioner
+  */
+template <typename _Scalar>
+class LeastSquareDiagonalPreconditioner : public DiagonalPreconditioner<_Scalar>
+{
+    typedef _Scalar Scalar;
+    typedef typename NumTraits<Scalar>::Real RealScalar;
+    typedef DiagonalPreconditioner<_Scalar> Base;
+    using Base::m_invdiag;
+  public:
+
+    LeastSquareDiagonalPreconditioner() : Base() {}
+
+    template<typename MatType>
+    explicit LeastSquareDiagonalPreconditioner(const MatType& mat) : Base()
+    {
+      compute(mat);
+    }
+
+    template<typename MatType>
+    LeastSquareDiagonalPreconditioner& analyzePattern(const MatType& )
+    {
+      return *this;
+    }
+
+    template<typename MatType>
+    LeastSquareDiagonalPreconditioner& factorize(const MatType& mat)
+    {
+      // Compute the inverse squared-norm of each column of mat
+      m_invdiag.resize(mat.cols());
+      if(MatType::IsRowMajor)
+      {
+        m_invdiag.setZero();
+        for(Index j=0; j<mat.outerSize(); ++j)
+        {
+          for(typename MatType::InnerIterator it(mat,j); it; ++it)
+            m_invdiag(it.index()) += numext::abs2(it.value());
+        }
+        for(Index j=0; j<mat.cols(); ++j)
+          if(numext::real(m_invdiag(j))>RealScalar(0))
+            m_invdiag(j) = RealScalar(1)/numext::real(m_invdiag(j));
+      }
+      else
+      {
+        for(Index j=0; j<mat.outerSize(); ++j)
+        {
+          RealScalar sum = mat.col(j).squaredNorm();
+          if(sum>RealScalar(0))
+            m_invdiag(j) = RealScalar(1)/sum;
+          else
+            m_invdiag(j) = RealScalar(1);
+        }
+      }
+      Base::m_isInitialized = true;
+      return *this;
+    }
+
+    template<typename MatType>
+    LeastSquareDiagonalPreconditioner& compute(const MatType& mat)
+    {
+      return factorize(mat);
+    }
+
+    ComputationInfo info() { return Success; }
+
+  protected:
+};
+
+/** \ingroup IterativeLinearSolvers_Module
+  * \brief A naive preconditioner which approximates any matrix as the identity matrix
+  *
+  * \implsparsesolverconcept
+  *
+  * \sa class DiagonalPreconditioner
+  */
+class IdentityPreconditioner
+{
+  public:
+
+    IdentityPreconditioner() {}
+
+    template<typename MatrixType>
+    explicit IdentityPreconditioner(const MatrixType& ) {}
+
+    template<typename MatrixType>
+    IdentityPreconditioner& analyzePattern(const MatrixType& ) { return *this; }
+
+    template<typename MatrixType>
+    IdentityPreconditioner& factorize(const MatrixType& ) { return *this; }
+
+    template<typename MatrixType>
+    IdentityPreconditioner& compute(const MatrixType& ) { return *this; }
+
+    template<typename Rhs>
+    inline const Rhs& solve(const Rhs& b) const { return b; }
+
+    ComputationInfo info() { return Success; }
+};
+
+} // end namespace Eigen
+
+#endif // EIGEN_BASIC_PRECONDITIONERS_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/IterativeLinearSolvers/BiCGSTAB.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/IterativeLinearSolvers/BiCGSTAB.h
new file mode 100644
index 0000000..153acef
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/IterativeLinearSolvers/BiCGSTAB.h
@@ -0,0 +1,212 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2011-2014 Gael Guennebaud <gael.guennebaud@inria.fr>
+// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_BICGSTAB_H
+#define EIGEN_BICGSTAB_H
+
+namespace Eigen { 
+
+namespace internal {
+
+/** \internal Low-level bi conjugate gradient stabilized algorithm
+  * \param mat The matrix A
+  * \param rhs The right hand side vector b
+  * \param x On input and initial solution, on output the computed solution.
+  * \param precond A preconditioner being able to efficiently solve for an
+  *                approximation of Ax=b (regardless of b)
+  * \param iters On input the max number of iteration, on output the number of performed iterations.
+  * \param tol_error On input the tolerance error, on output an estimation of the relative error.
+  * \return false in the case of numerical issue, for example a break down of BiCGSTAB. 
+  */
+template<typename MatrixType, typename Rhs, typename Dest, typename Preconditioner>
+bool bicgstab(const MatrixType& mat, const Rhs& rhs, Dest& x,
+              const Preconditioner& precond, Index& iters,
+              typename Dest::RealScalar& tol_error)
+{
+  using std::sqrt;
+  using std::abs;
+  typedef typename Dest::RealScalar RealScalar;
+  typedef typename Dest::Scalar Scalar;
+  typedef Matrix<Scalar,Dynamic,1> VectorType;
+  RealScalar tol = tol_error;
+  Index maxIters = iters;
+
+  Index n = mat.cols();
+  VectorType r  = rhs - mat * x;
+  VectorType r0 = r;
+  
+  RealScalar r0_sqnorm = r0.squaredNorm();
+  RealScalar rhs_sqnorm = rhs.squaredNorm();
+  if(rhs_sqnorm == 0)
+  {
+    x.setZero();
+    return true;
+  }
+  Scalar rho    = 1;
+  Scalar alpha  = 1;
+  Scalar w      = 1;
+  
+  VectorType v = VectorType::Zero(n), p = VectorType::Zero(n);
+  VectorType y(n),  z(n);
+  VectorType kt(n), ks(n);
+
+  VectorType s(n), t(n);
+
+  RealScalar tol2 = tol*tol*rhs_sqnorm;
+  RealScalar eps2 = NumTraits<Scalar>::epsilon()*NumTraits<Scalar>::epsilon();
+  Index i = 0;
+  Index restarts = 0;
+
+  while ( r.squaredNorm() > tol2 && i<maxIters )
+  {
+    Scalar rho_old = rho;
+
+    rho = r0.dot(r);
+    if (abs(rho) < eps2*r0_sqnorm)
+    {
+      // The new residual vector became too orthogonal to the arbitrarily chosen direction r0
+      // Let's restart with a new r0:
+      r  = rhs - mat * x;
+      r0 = r;
+      rho = r0_sqnorm = r.squaredNorm();
+      if(restarts++ == 0)
+        i = 0;
+    }
+    Scalar beta = (rho/rho_old) * (alpha / w);
+    p = r + beta * (p - w * v);
+    
+    y = precond.solve(p);
+    
+    v.noalias() = mat * y;
+
+    alpha = rho / r0.dot(v);
+    s = r - alpha * v;
+
+    z = precond.solve(s);
+    t.noalias() = mat * z;
+
+    RealScalar tmp = t.squaredNorm();
+    if(tmp>RealScalar(0))
+      w = t.dot(s) / tmp;
+    else
+      w = Scalar(0);
+    x += alpha * y + w * z;
+    r = s - w * t;
+    ++i;
+  }
+  tol_error = sqrt(r.squaredNorm()/rhs_sqnorm);
+  iters = i;
+  return true; 
+}
+
+}
+
+template< typename _MatrixType,
+          typename _Preconditioner = DiagonalPreconditioner<typename _MatrixType::Scalar> >
+class BiCGSTAB;
+
+namespace internal {
+
+template< typename _MatrixType, typename _Preconditioner>
+struct traits<BiCGSTAB<_MatrixType,_Preconditioner> >
+{
+  typedef _MatrixType MatrixType;
+  typedef _Preconditioner Preconditioner;
+};
+
+}
+
+/** \ingroup IterativeLinearSolvers_Module
+  * \brief A bi conjugate gradient stabilized solver for sparse square problems
+  *
+  * This class allows to solve for A.x = b sparse linear problems using a bi conjugate gradient
+  * stabilized algorithm. The vectors x and b can be either dense or sparse.
+  *
+  * \tparam _MatrixType the type of the sparse matrix A, can be a dense or a sparse matrix.
+  * \tparam _Preconditioner the type of the preconditioner. Default is DiagonalPreconditioner
+  *
+  * \implsparsesolverconcept
+  *
+  * The maximal number of iterations and tolerance value can be controlled via the setMaxIterations()
+  * and setTolerance() methods. The defaults are the size of the problem for the maximal number of iterations
+  * and NumTraits<Scalar>::epsilon() for the tolerance.
+  * 
+  * The tolerance corresponds to the relative residual error: |Ax-b|/|b|
+  * 
+  * \b Performance: when using sparse matrices, best performance is achied for a row-major sparse matrix format.
+  * Moreover, in this case multi-threading can be exploited if the user code is compiled with OpenMP enabled.
+  * See \ref TopicMultiThreading for details.
+  * 
+  * This class can be used as the direct solver classes. Here is a typical usage example:
+  * \include BiCGSTAB_simple.cpp
+  * 
+  * By default the iterations start with x=0 as an initial guess of the solution.
+  * One can control the start using the solveWithGuess() method.
+  * 
+  * BiCGSTAB can also be used in a matrix-free context, see the following \link MatrixfreeSolverExample example \endlink.
+  *
+  * \sa class SimplicialCholesky, DiagonalPreconditioner, IdentityPreconditioner
+  */
+template< typename _MatrixType, typename _Preconditioner>
+class BiCGSTAB : public IterativeSolverBase<BiCGSTAB<_MatrixType,_Preconditioner> >
+{
+  typedef IterativeSolverBase<BiCGSTAB> Base;
+  using Base::matrix;
+  using Base::m_error;
+  using Base::m_iterations;
+  using Base::m_info;
+  using Base::m_isInitialized;
+public:
+  typedef _MatrixType MatrixType;
+  typedef typename MatrixType::Scalar Scalar;
+  typedef typename MatrixType::RealScalar RealScalar;
+  typedef _Preconditioner Preconditioner;
+
+public:
+
+  /** Default constructor. */
+  BiCGSTAB() : Base() {}
+
+  /** Initialize the solver with matrix \a A for further \c Ax=b solving.
+    * 
+    * This constructor is a shortcut for the default constructor followed
+    * by a call to compute().
+    * 
+    * \warning this class stores a reference to the matrix A as well as some
+    * precomputed values that depend on it. Therefore, if \a A is changed
+    * this class becomes invalid. Call compute() to update it with the new
+    * matrix A, or modify a copy of A.
+    */
+  template<typename MatrixDerived>
+  explicit BiCGSTAB(const EigenBase<MatrixDerived>& A) : Base(A.derived()) {}
+
+  ~BiCGSTAB() {}
+
+  /** \internal */
+  template<typename Rhs,typename Dest>
+  void _solve_vector_with_guess_impl(const Rhs& b, Dest& x) const
+  {    
+    m_iterations = Base::maxIterations();
+    m_error = Base::m_tolerance;
+    
+    bool ret = internal::bicgstab(matrix(), b, x, Base::m_preconditioner, m_iterations, m_error);
+
+    m_info = (!ret) ? NumericalIssue
+           : m_error <= Base::m_tolerance ? Success
+           : NoConvergence;
+  }
+
+protected:
+
+};
+
+} // end namespace Eigen
+
+#endif // EIGEN_BICGSTAB_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/IterativeLinearSolvers/ConjugateGradient.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/IterativeLinearSolvers/ConjugateGradient.h
new file mode 100644
index 0000000..5d8c6b4
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/IterativeLinearSolvers/ConjugateGradient.h
@@ -0,0 +1,229 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2011-2014 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_CONJUGATE_GRADIENT_H
+#define EIGEN_CONJUGATE_GRADIENT_H
+
+namespace Eigen { 
+
+namespace internal {
+
+/** \internal Low-level conjugate gradient algorithm
+  * \param mat The matrix A
+  * \param rhs The right hand side vector b
+  * \param x On input and initial solution, on output the computed solution.
+  * \param precond A preconditioner being able to efficiently solve for an
+  *                approximation of Ax=b (regardless of b)
+  * \param iters On input the max number of iteration, on output the number of performed iterations.
+  * \param tol_error On input the tolerance error, on output an estimation of the relative error.
+  */
+template<typename MatrixType, typename Rhs, typename Dest, typename Preconditioner>
+EIGEN_DONT_INLINE
+void conjugate_gradient(const MatrixType& mat, const Rhs& rhs, Dest& x,
+                        const Preconditioner& precond, Index& iters,
+                        typename Dest::RealScalar& tol_error)
+{
+  using std::sqrt;
+  using std::abs;
+  typedef typename Dest::RealScalar RealScalar;
+  typedef typename Dest::Scalar Scalar;
+  typedef Matrix<Scalar,Dynamic,1> VectorType;
+  
+  RealScalar tol = tol_error;
+  Index maxIters = iters;
+  
+  Index n = mat.cols();
+
+  VectorType residual = rhs - mat * x; //initial residual
+
+  RealScalar rhsNorm2 = rhs.squaredNorm();
+  if(rhsNorm2 == 0) 
+  {
+    x.setZero();
+    iters = 0;
+    tol_error = 0;
+    return;
+  }
+  const RealScalar considerAsZero = (std::numeric_limits<RealScalar>::min)();
+  RealScalar threshold = numext::maxi(RealScalar(tol*tol*rhsNorm2),considerAsZero);
+  RealScalar residualNorm2 = residual.squaredNorm();
+  if (residualNorm2 < threshold)
+  {
+    iters = 0;
+    tol_error = sqrt(residualNorm2 / rhsNorm2);
+    return;
+  }
+
+  VectorType p(n);
+  p = precond.solve(residual);      // initial search direction
+
+  VectorType z(n), tmp(n);
+  RealScalar absNew = numext::real(residual.dot(p));  // the square of the absolute value of r scaled by invM
+  Index i = 0;
+  while(i < maxIters)
+  {
+    tmp.noalias() = mat * p;                    // the bottleneck of the algorithm
+
+    Scalar alpha = absNew / p.dot(tmp);         // the amount we travel on dir
+    x += alpha * p;                             // update solution
+    residual -= alpha * tmp;                    // update residual
+    
+    residualNorm2 = residual.squaredNorm();
+    if(residualNorm2 < threshold)
+      break;
+    
+    z = precond.solve(residual);                // approximately solve for "A z = residual"
+
+    RealScalar absOld = absNew;
+    absNew = numext::real(residual.dot(z));     // update the absolute value of r
+    RealScalar beta = absNew / absOld;          // calculate the Gram-Schmidt value used to create the new search direction
+    p = z + beta * p;                           // update search direction
+    i++;
+  }
+  tol_error = sqrt(residualNorm2 / rhsNorm2);
+  iters = i;
+}
+
+}
+
+template< typename _MatrixType, int _UpLo=Lower,
+          typename _Preconditioner = DiagonalPreconditioner<typename _MatrixType::Scalar> >
+class ConjugateGradient;
+
+namespace internal {
+
+template< typename _MatrixType, int _UpLo, typename _Preconditioner>
+struct traits<ConjugateGradient<_MatrixType,_UpLo,_Preconditioner> >
+{
+  typedef _MatrixType MatrixType;
+  typedef _Preconditioner Preconditioner;
+};
+
+}
+
+/** \ingroup IterativeLinearSolvers_Module
+  * \brief A conjugate gradient solver for sparse (or dense) self-adjoint problems
+  *
+  * This class allows to solve for A.x = b linear problems using an iterative conjugate gradient algorithm.
+  * The matrix A must be selfadjoint. The matrix A and the vectors x and b can be either dense or sparse.
+  *
+  * \tparam _MatrixType the type of the matrix A, can be a dense or a sparse matrix.
+  * \tparam _UpLo the triangular part that will be used for the computations. It can be Lower,
+  *               \c Upper, or \c Lower|Upper in which the full matrix entries will be considered.
+  *               Default is \c Lower, best performance is \c Lower|Upper.
+  * \tparam _Preconditioner the type of the preconditioner. Default is DiagonalPreconditioner
+  *
+  * \implsparsesolverconcept
+  *
+  * The maximal number of iterations and tolerance value can be controlled via the setMaxIterations()
+  * and setTolerance() methods. The defaults are the size of the problem for the maximal number of iterations
+  * and NumTraits<Scalar>::epsilon() for the tolerance.
+  * 
+  * The tolerance corresponds to the relative residual error: |Ax-b|/|b|
+  * 
+  * \b Performance: Even though the default value of \c _UpLo is \c Lower, significantly higher performance is
+  * achieved when using a complete matrix and \b Lower|Upper as the \a _UpLo template parameter. Moreover, in this
+  * case multi-threading can be exploited if the user code is compiled with OpenMP enabled.
+  * See \ref TopicMultiThreading for details.
+  * 
+  * This class can be used as the direct solver classes. Here is a typical usage example:
+    \code
+    int n = 10000;
+    VectorXd x(n), b(n);
+    SparseMatrix<double> A(n,n);
+    // fill A and b
+    ConjugateGradient<SparseMatrix<double>, Lower|Upper> cg;
+    cg.compute(A);
+    x = cg.solve(b);
+    std::cout << "#iterations:     " << cg.iterations() << std::endl;
+    std::cout << "estimated error: " << cg.error()      << std::endl;
+    // update b, and solve again
+    x = cg.solve(b);
+    \endcode
+  * 
+  * By default the iterations start with x=0 as an initial guess of the solution.
+  * One can control the start using the solveWithGuess() method.
+  * 
+  * ConjugateGradient can also be used in a matrix-free context, see the following \link MatrixfreeSolverExample example \endlink.
+  *
+  * \sa class LeastSquaresConjugateGradient, class SimplicialCholesky, DiagonalPreconditioner, IdentityPreconditioner
+  */
+template< typename _MatrixType, int _UpLo, typename _Preconditioner>
+class ConjugateGradient : public IterativeSolverBase<ConjugateGradient<_MatrixType,_UpLo,_Preconditioner> >
+{
+  typedef IterativeSolverBase<ConjugateGradient> Base;
+  using Base::matrix;
+  using Base::m_error;
+  using Base::m_iterations;
+  using Base::m_info;
+  using Base::m_isInitialized;
+public:
+  typedef _MatrixType MatrixType;
+  typedef typename MatrixType::Scalar Scalar;
+  typedef typename MatrixType::RealScalar RealScalar;
+  typedef _Preconditioner Preconditioner;
+
+  enum {
+    UpLo = _UpLo
+  };
+
+public:
+
+  /** Default constructor. */
+  ConjugateGradient() : Base() {}
+
+  /** Initialize the solver with matrix \a A for further \c Ax=b solving.
+    * 
+    * This constructor is a shortcut for the default constructor followed
+    * by a call to compute().
+    * 
+    * \warning this class stores a reference to the matrix A as well as some
+    * precomputed values that depend on it. Therefore, if \a A is changed
+    * this class becomes invalid. Call compute() to update it with the new
+    * matrix A, or modify a copy of A.
+    */
+  template<typename MatrixDerived>
+  explicit ConjugateGradient(const EigenBase<MatrixDerived>& A) : Base(A.derived()) {}
+
+  ~ConjugateGradient() {}
+
+  /** \internal */
+  template<typename Rhs,typename Dest>
+  void _solve_vector_with_guess_impl(const Rhs& b, Dest& x) const
+  {
+    typedef typename Base::MatrixWrapper MatrixWrapper;
+    typedef typename Base::ActualMatrixType ActualMatrixType;
+    enum {
+      TransposeInput  =   (!MatrixWrapper::MatrixFree)
+                      &&  (UpLo==(Lower|Upper))
+                      &&  (!MatrixType::IsRowMajor)
+                      &&  (!NumTraits<Scalar>::IsComplex)
+    };
+    typedef typename internal::conditional<TransposeInput,Transpose<const ActualMatrixType>, ActualMatrixType const&>::type RowMajorWrapper;
+    EIGEN_STATIC_ASSERT(EIGEN_IMPLIES(MatrixWrapper::MatrixFree,UpLo==(Lower|Upper)),MATRIX_FREE_CONJUGATE_GRADIENT_IS_COMPATIBLE_WITH_UPPER_UNION_LOWER_MODE_ONLY);
+    typedef typename internal::conditional<UpLo==(Lower|Upper),
+                                           RowMajorWrapper,
+                                           typename MatrixWrapper::template ConstSelfAdjointViewReturnType<UpLo>::Type
+                                          >::type SelfAdjointWrapper;
+
+    m_iterations = Base::maxIterations();
+    m_error = Base::m_tolerance;
+
+    RowMajorWrapper row_mat(matrix());
+    internal::conjugate_gradient(SelfAdjointWrapper(row_mat), b, x, Base::m_preconditioner, m_iterations, m_error);
+    m_info = m_error <= Base::m_tolerance ? Success : NoConvergence;
+  }
+
+protected:
+
+};
+
+} // end namespace Eigen
+
+#endif // EIGEN_CONJUGATE_GRADIENT_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/IterativeLinearSolvers/IncompleteCholesky.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/IterativeLinearSolvers/IncompleteCholesky.h
new file mode 100644
index 0000000..7803fd8
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/IterativeLinearSolvers/IncompleteCholesky.h
@@ -0,0 +1,394 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>
+// Copyright (C) 2015 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_INCOMPLETE_CHOlESKY_H
+#define EIGEN_INCOMPLETE_CHOlESKY_H
+
+#include <vector>
+#include <list>
+
+namespace Eigen {
+/**
+  * \brief Modified Incomplete Cholesky with dual threshold
+  *
+  * References : C-J. Lin and J. J. Moré, Incomplete Cholesky Factorizations with
+  *              Limited memory, SIAM J. Sci. Comput.  21(1), pp. 24-45, 1999
+  *
+  * \tparam Scalar the scalar type of the input matrices
+  * \tparam _UpLo The triangular part that will be used for the computations. It can be Lower
+    *               or Upper. Default is Lower.
+  * \tparam _OrderingType The ordering method to use, either AMDOrdering<> or NaturalOrdering<>. Default is AMDOrdering<int>,
+  *                       unless EIGEN_MPL2_ONLY is defined, in which case the default is NaturalOrdering<int>.
+  *
+  * \implsparsesolverconcept
+  *
+  * It performs the following incomplete factorization: \f$ S P A P' S \approx L L' \f$
+  * where L is a lower triangular factor, S is a diagonal scaling matrix, and P is a
+  * fill-in reducing permutation as computed by the ordering method.
+  *
+  * \b Shifting \b strategy: Let \f$ B = S P A P' S \f$  be the scaled matrix on which the factorization is carried out,
+  * and \f$ \beta \f$ be the minimum value of the diagonal. If \f$ \beta > 0 \f$ then, the factorization is directly performed
+  * on the matrix B. Otherwise, the factorization is performed on the shifted matrix \f$ B + (\sigma+|\beta| I \f$ where
+  * \f$ \sigma \f$ is the initial shift value as returned and set by setInitialShift() method. The default value is \f$ \sigma = 10^{-3} \f$.
+  * If the factorization fails, then the shift in doubled until it succeed or a maximum of ten attempts. If it still fails, as returned by
+  * the info() method, then you can either increase the initial shift, or better use another preconditioning technique.
+  *
+  */
+template <typename Scalar, int _UpLo = Lower, typename _OrderingType = AMDOrdering<int> >
+class IncompleteCholesky : public SparseSolverBase<IncompleteCholesky<Scalar,_UpLo,_OrderingType> >
+{
+  protected:
+    typedef SparseSolverBase<IncompleteCholesky<Scalar,_UpLo,_OrderingType> > Base;
+    using Base::m_isInitialized;
+  public:
+    typedef typename NumTraits<Scalar>::Real RealScalar;
+    typedef _OrderingType OrderingType;
+    typedef typename OrderingType::PermutationType PermutationType;
+    typedef typename PermutationType::StorageIndex StorageIndex;
+    typedef SparseMatrix<Scalar,ColMajor,StorageIndex> FactorType;
+    typedef Matrix<Scalar,Dynamic,1> VectorSx;
+    typedef Matrix<RealScalar,Dynamic,1> VectorRx;
+    typedef Matrix<StorageIndex,Dynamic, 1> VectorIx;
+    typedef std::vector<std::list<StorageIndex> > VectorList;
+    enum { UpLo = _UpLo };
+    enum {
+      ColsAtCompileTime = Dynamic,
+      MaxColsAtCompileTime = Dynamic
+    };
+  public:
+
+    /** Default constructor leaving the object in a partly non-initialized stage.
+      *
+      * You must call compute() or the pair analyzePattern()/factorize() to make it valid.
+      *
+      * \sa IncompleteCholesky(const MatrixType&)
+      */
+    IncompleteCholesky() : m_initialShift(1e-3),m_analysisIsOk(false),m_factorizationIsOk(false) {}
+
+    /** Constructor computing the incomplete factorization for the given matrix \a matrix.
+      */
+    template<typename MatrixType>
+    IncompleteCholesky(const MatrixType& matrix) : m_initialShift(1e-3),m_analysisIsOk(false),m_factorizationIsOk(false)
+    {
+      compute(matrix);
+    }
+
+    /** \returns number of rows of the factored matrix */
+    EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT { return m_L.rows(); }
+
+    /** \returns number of columns of the factored matrix */
+    EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT { return m_L.cols(); }
+
+
+    /** \brief Reports whether previous computation was successful.
+      *
+      * It triggers an assertion if \c *this has not been initialized through the respective constructor,
+      * or a call to compute() or analyzePattern().
+      *
+      * \returns \c Success if computation was successful,
+      *          \c NumericalIssue if the matrix appears to be negative.
+      */
+    ComputationInfo info() const
+    {
+      eigen_assert(m_isInitialized && "IncompleteCholesky is not initialized.");
+      return m_info;
+    }
+
+    /** \brief Set the initial shift parameter \f$ \sigma \f$.
+      */
+    void setInitialShift(RealScalar shift) { m_initialShift = shift; }
+
+    /** \brief Computes the fill reducing permutation vector using the sparsity pattern of \a mat
+      */
+    template<typename MatrixType>
+    void analyzePattern(const MatrixType& mat)
+    {
+      OrderingType ord;
+      PermutationType pinv;
+      ord(mat.template selfadjointView<UpLo>(), pinv);
+      if(pinv.size()>0) m_perm = pinv.inverse();
+      else              m_perm.resize(0);
+      m_L.resize(mat.rows(), mat.cols());
+      m_analysisIsOk = true;
+      m_isInitialized = true;
+      m_info = Success;
+    }
+
+    /** \brief Performs the numerical factorization of the input matrix \a mat
+      *
+      * The method analyzePattern() or compute() must have been called beforehand
+      * with a matrix having the same pattern.
+      *
+      * \sa compute(), analyzePattern()
+      */
+    template<typename MatrixType>
+    void factorize(const MatrixType& mat);
+
+    /** Computes or re-computes the incomplete Cholesky factorization of the input matrix \a mat
+      *
+      * It is a shortcut for a sequential call to the analyzePattern() and factorize() methods.
+      *
+      * \sa analyzePattern(), factorize()
+      */
+    template<typename MatrixType>
+    void compute(const MatrixType& mat)
+    {
+      analyzePattern(mat);
+      factorize(mat);
+    }
+
+    // internal
+    template<typename Rhs, typename Dest>
+    void _solve_impl(const Rhs& b, Dest& x) const
+    {
+      eigen_assert(m_factorizationIsOk && "factorize() should be called first");
+      if (m_perm.rows() == b.rows())  x = m_perm * b;
+      else                            x = b;
+      x = m_scale.asDiagonal() * x;
+      x = m_L.template triangularView<Lower>().solve(x);
+      x = m_L.adjoint().template triangularView<Upper>().solve(x);
+      x = m_scale.asDiagonal() * x;
+      if (m_perm.rows() == b.rows())
+        x = m_perm.inverse() * x;
+    }
+
+    /** \returns the sparse lower triangular factor L */
+    const FactorType& matrixL() const { eigen_assert("m_factorizationIsOk"); return m_L; }
+
+    /** \returns a vector representing the scaling factor S */
+    const VectorRx& scalingS() const { eigen_assert("m_factorizationIsOk"); return m_scale; }
+
+    /** \returns the fill-in reducing permutation P (can be empty for a natural ordering) */
+    const PermutationType& permutationP() const { eigen_assert("m_analysisIsOk"); return m_perm; }
+
+  protected:
+    FactorType m_L;              // The lower part stored in CSC
+    VectorRx m_scale;            // The vector for scaling the matrix
+    RealScalar m_initialShift;   // The initial shift parameter
+    bool m_analysisIsOk;
+    bool m_factorizationIsOk;
+    ComputationInfo m_info;
+    PermutationType m_perm;
+
+  private:
+    inline void updateList(Ref<const VectorIx> colPtr, Ref<VectorIx> rowIdx, Ref<VectorSx> vals, const Index& col, const Index& jk, VectorIx& firstElt, VectorList& listCol);
+};
+
+// Based on the following paper:
+//   C-J. Lin and J. J. Moré, Incomplete Cholesky Factorizations with
+//   Limited memory, SIAM J. Sci. Comput.  21(1), pp. 24-45, 1999
+//   http://ftp.mcs.anl.gov/pub/tech_reports/reports/P682.pdf
+template<typename Scalar, int _UpLo, typename OrderingType>
+template<typename _MatrixType>
+void IncompleteCholesky<Scalar,_UpLo, OrderingType>::factorize(const _MatrixType& mat)
+{
+  using std::sqrt;
+  eigen_assert(m_analysisIsOk && "analyzePattern() should be called first");
+
+  // Dropping strategy : Keep only the p largest elements per column, where p is the number of elements in the column of the original matrix. Other strategies will be added
+
+  // Apply the fill-reducing permutation computed in analyzePattern()
+  if (m_perm.rows() == mat.rows() ) // To detect the null permutation
+  {
+    // The temporary is needed to make sure that the diagonal entry is properly sorted
+    FactorType tmp(mat.rows(), mat.cols());
+    tmp = mat.template selfadjointView<_UpLo>().twistedBy(m_perm);
+    m_L.template selfadjointView<Lower>() = tmp.template selfadjointView<Lower>();
+  }
+  else
+  {
+    m_L.template selfadjointView<Lower>() = mat.template selfadjointView<_UpLo>();
+  }
+
+  Index n = m_L.cols();
+  Index nnz = m_L.nonZeros();
+  Map<VectorSx> vals(m_L.valuePtr(), nnz);         //values
+  Map<VectorIx> rowIdx(m_L.innerIndexPtr(), nnz);  //Row indices
+  Map<VectorIx> colPtr( m_L.outerIndexPtr(), n+1); // Pointer to the beginning of each row
+  VectorIx firstElt(n-1); // for each j, points to the next entry in vals that will be used in the factorization
+  VectorList listCol(n);  // listCol(j) is a linked list of columns to update column j
+  VectorSx col_vals(n);   // Store a  nonzero values in each column
+  VectorIx col_irow(n);   // Row indices of nonzero elements in each column
+  VectorIx col_pattern(n);
+  col_pattern.fill(-1);
+  StorageIndex col_nnz;
+
+
+  // Computes the scaling factors
+  m_scale.resize(n);
+  m_scale.setZero();
+  for (Index j = 0; j < n; j++)
+    for (Index k = colPtr[j]; k < colPtr[j+1]; k++)
+    {
+      m_scale(j) += numext::abs2(vals(k));
+      if(rowIdx[k]!=j)
+        m_scale(rowIdx[k]) += numext::abs2(vals(k));
+    }
+
+  m_scale = m_scale.cwiseSqrt().cwiseSqrt();
+
+  for (Index j = 0; j < n; ++j)
+    if(m_scale(j)>(std::numeric_limits<RealScalar>::min)())
+      m_scale(j) = RealScalar(1)/m_scale(j);
+    else
+      m_scale(j) = 1;
+
+  // TODO disable scaling if not needed, i.e., if it is roughly uniform? (this will make solve() faster)
+
+  // Scale and compute the shift for the matrix
+  RealScalar mindiag = NumTraits<RealScalar>::highest();
+  for (Index j = 0; j < n; j++)
+  {
+    for (Index k = colPtr[j]; k < colPtr[j+1]; k++)
+      vals[k] *= (m_scale(j)*m_scale(rowIdx[k]));
+    eigen_internal_assert(rowIdx[colPtr[j]]==j && "IncompleteCholesky: only the lower triangular part must be stored");
+    mindiag = numext::mini(numext::real(vals[colPtr[j]]), mindiag);
+  }
+
+  FactorType L_save = m_L;
+
+  RealScalar shift = 0;
+  if(mindiag <= RealScalar(0.))
+    shift = m_initialShift - mindiag;
+
+  m_info = NumericalIssue;
+
+  // Try to perform the incomplete factorization using the current shift
+  int iter = 0;
+  do
+  {
+    // Apply the shift to the diagonal elements of the matrix
+    for (Index j = 0; j < n; j++)
+      vals[colPtr[j]] += shift;
+
+    // jki version of the Cholesky factorization
+    Index j=0;
+    for (; j < n; ++j)
+    {
+      // Left-looking factorization of the j-th column
+      // First, load the j-th column into col_vals
+      Scalar diag = vals[colPtr[j]];  // It is assumed that only the lower part is stored
+      col_nnz = 0;
+      for (Index i = colPtr[j] + 1; i < colPtr[j+1]; i++)
+      {
+        StorageIndex l = rowIdx[i];
+        col_vals(col_nnz) = vals[i];
+        col_irow(col_nnz) = l;
+        col_pattern(l) = col_nnz;
+        col_nnz++;
+      }
+      {
+        typename std::list<StorageIndex>::iterator k;
+        // Browse all previous columns that will update column j
+        for(k = listCol[j].begin(); k != listCol[j].end(); k++)
+        {
+          Index jk = firstElt(*k); // First element to use in the column
+          eigen_internal_assert(rowIdx[jk]==j);
+          Scalar v_j_jk = numext::conj(vals[jk]);
+
+          jk += 1;
+          for (Index i = jk; i < colPtr[*k+1]; i++)
+          {
+            StorageIndex l = rowIdx[i];
+            if(col_pattern[l]<0)
+            {
+              col_vals(col_nnz) = vals[i] * v_j_jk;
+              col_irow[col_nnz] = l;
+              col_pattern(l) = col_nnz;
+              col_nnz++;
+            }
+            else
+              col_vals(col_pattern[l]) -= vals[i] * v_j_jk;
+          }
+          updateList(colPtr,rowIdx,vals, *k, jk, firstElt, listCol);
+        }
+      }
+
+      // Scale the current column
+      if(numext::real(diag) <= 0)
+      {
+        if(++iter>=10)
+          return;
+
+        // increase shift
+        shift = numext::maxi(m_initialShift,RealScalar(2)*shift);
+        // restore m_L, col_pattern, and listCol
+        vals = Map<const VectorSx>(L_save.valuePtr(), nnz);
+        rowIdx = Map<const VectorIx>(L_save.innerIndexPtr(), nnz);
+        colPtr = Map<const VectorIx>(L_save.outerIndexPtr(), n+1);
+        col_pattern.fill(-1);
+        for(Index i=0; i<n; ++i)
+          listCol[i].clear();
+
+        break;
+      }
+
+      RealScalar rdiag = sqrt(numext::real(diag));
+      vals[colPtr[j]] = rdiag;
+      for (Index k = 0; k<col_nnz; ++k)
+      {
+        Index i = col_irow[k];
+        //Scale
+        col_vals(k) /= rdiag;
+        //Update the remaining diagonals with col_vals
+        vals[colPtr[i]] -= numext::abs2(col_vals(k));
+      }
+      // Select the largest p elements
+      // p is the original number of elements in the column (without the diagonal)
+      Index p = colPtr[j+1] - colPtr[j] - 1 ;
+      Ref<VectorSx> cvals = col_vals.head(col_nnz);
+      Ref<VectorIx> cirow = col_irow.head(col_nnz);
+      internal::QuickSplit(cvals,cirow, p);
+      // Insert the largest p elements in the matrix
+      Index cpt = 0;
+      for (Index i = colPtr[j]+1; i < colPtr[j+1]; i++)
+      {
+        vals[i] = col_vals(cpt);
+        rowIdx[i] = col_irow(cpt);
+        // restore col_pattern:
+        col_pattern(col_irow(cpt)) = -1;
+        cpt++;
+      }
+      // Get the first smallest row index and put it after the diagonal element
+      Index jk = colPtr(j)+1;
+      updateList(colPtr,rowIdx,vals,j,jk,firstElt,listCol);
+    }
+
+    if(j==n)
+    {
+      m_factorizationIsOk = true;
+      m_info = Success;
+    }
+  } while(m_info!=Success);
+}
+
+template<typename Scalar, int _UpLo, typename OrderingType>
+inline void IncompleteCholesky<Scalar,_UpLo, OrderingType>::updateList(Ref<const VectorIx> colPtr, Ref<VectorIx> rowIdx, Ref<VectorSx> vals, const Index& col, const Index& jk, VectorIx& firstElt, VectorList& listCol)
+{
+  if (jk < colPtr(col+1) )
+  {
+    Index p = colPtr(col+1) - jk;
+    Index minpos;
+    rowIdx.segment(jk,p).minCoeff(&minpos);
+    minpos += jk;
+    if (rowIdx(minpos) != rowIdx(jk))
+    {
+      //Swap
+      std::swap(rowIdx(jk),rowIdx(minpos));
+      std::swap(vals(jk),vals(minpos));
+    }
+    firstElt(col) = internal::convert_index<StorageIndex,Index>(jk);
+    listCol[rowIdx(jk)].push_back(internal::convert_index<StorageIndex,Index>(col));
+  }
+}
+
+} // end namespace Eigen
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/IterativeLinearSolvers/IncompleteLUT.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/IterativeLinearSolvers/IncompleteLUT.h
new file mode 100644
index 0000000..cdcf709
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/IterativeLinearSolvers/IncompleteLUT.h
@@ -0,0 +1,453 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>
+// Copyright (C) 2014 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_INCOMPLETE_LUT_H
+#define EIGEN_INCOMPLETE_LUT_H
+
+
+namespace Eigen {
+
+namespace internal {
+
+/** \internal
+  * Compute a quick-sort split of a vector
+  * On output, the vector row is permuted such that its elements satisfy
+  * abs(row(i)) >= abs(row(ncut)) if i<ncut
+  * abs(row(i)) <= abs(row(ncut)) if i>ncut
+  * \param row The vector of values
+  * \param ind The array of index for the elements in @p row
+  * \param ncut  The number of largest elements to keep
+  **/
+template <typename VectorV, typename VectorI>
+Index QuickSplit(VectorV &row, VectorI &ind, Index ncut)
+{
+  typedef typename VectorV::RealScalar RealScalar;
+  using std::swap;
+  using std::abs;
+  Index mid;
+  Index n = row.size(); /* length of the vector */
+  Index first, last ;
+
+  ncut--; /* to fit the zero-based indices */
+  first = 0;
+  last = n-1;
+  if (ncut < first || ncut > last ) return 0;
+
+  do {
+    mid = first;
+    RealScalar abskey = abs(row(mid));
+    for (Index j = first + 1; j <= last; j++) {
+      if ( abs(row(j)) > abskey) {
+        ++mid;
+        swap(row(mid), row(j));
+        swap(ind(mid), ind(j));
+      }
+    }
+    /* Interchange for the pivot element */
+    swap(row(mid), row(first));
+    swap(ind(mid), ind(first));
+
+    if (mid > ncut) last = mid - 1;
+    else if (mid < ncut ) first = mid + 1;
+  } while (mid != ncut );
+
+  return 0; /* mid is equal to ncut */
+}
+
+}// end namespace internal
+
+/** \ingroup IterativeLinearSolvers_Module
+  * \class IncompleteLUT
+  * \brief Incomplete LU factorization with dual-threshold strategy
+  *
+  * \implsparsesolverconcept
+  *
+  * During the numerical factorization, two dropping rules are used :
+  *  1) any element whose magnitude is less than some tolerance is dropped.
+  *    This tolerance is obtained by multiplying the input tolerance @p droptol
+  *    by the average magnitude of all the original elements in the current row.
+  *  2) After the elimination of the row, only the @p fill largest elements in
+  *    the L part and the @p fill largest elements in the U part are kept
+  *    (in addition to the diagonal element ). Note that @p fill is computed from
+  *    the input parameter @p fillfactor which is used the ratio to control the fill_in
+  *    relatively to the initial number of nonzero elements.
+  *
+  * The two extreme cases are when @p droptol=0 (to keep all the @p fill*2 largest elements)
+  * and when @p fill=n/2 with @p droptol being different to zero.
+  *
+  * References : Yousef Saad, ILUT: A dual threshold incomplete LU factorization,
+  *              Numerical Linear Algebra with Applications, 1(4), pp 387-402, 1994.
+  *
+  * NOTE : The following implementation is derived from the ILUT implementation
+  * in the SPARSKIT package, Copyright (C) 2005, the Regents of the University of Minnesota
+  *  released under the terms of the GNU LGPL:
+  *    http://www-users.cs.umn.edu/~saad/software/SPARSKIT/README
+  * However, Yousef Saad gave us permission to relicense his ILUT code to MPL2.
+  * See the Eigen mailing list archive, thread: ILUT, date: July 8, 2012:
+  *   http://listengine.tuxfamily.org/lists.tuxfamily.org/eigen/2012/07/msg00064.html
+  * alternatively, on GMANE:
+  *   http://comments.gmane.org/gmane.comp.lib.eigen/3302
+  */
+template <typename _Scalar, typename _StorageIndex = int>
+class IncompleteLUT : public SparseSolverBase<IncompleteLUT<_Scalar, _StorageIndex> >
+{
+  protected:
+    typedef SparseSolverBase<IncompleteLUT> Base;
+    using Base::m_isInitialized;
+  public:
+    typedef _Scalar Scalar;
+    typedef _StorageIndex StorageIndex;
+    typedef typename NumTraits<Scalar>::Real RealScalar;
+    typedef Matrix<Scalar,Dynamic,1> Vector;
+    typedef Matrix<StorageIndex,Dynamic,1> VectorI;
+    typedef SparseMatrix<Scalar,RowMajor,StorageIndex> FactorType;
+
+    enum {
+      ColsAtCompileTime = Dynamic,
+      MaxColsAtCompileTime = Dynamic
+    };
+
+  public:
+
+    IncompleteLUT()
+      : m_droptol(NumTraits<Scalar>::dummy_precision()), m_fillfactor(10),
+        m_analysisIsOk(false), m_factorizationIsOk(false)
+    {}
+
+    template<typename MatrixType>
+    explicit IncompleteLUT(const MatrixType& mat, const RealScalar& droptol=NumTraits<Scalar>::dummy_precision(), int fillfactor = 10)
+      : m_droptol(droptol),m_fillfactor(fillfactor),
+        m_analysisIsOk(false),m_factorizationIsOk(false)
+    {
+      eigen_assert(fillfactor != 0);
+      compute(mat);
+    }
+
+    EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT { return m_lu.rows(); }
+
+    EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT { return m_lu.cols(); }
+
+    /** \brief Reports whether previous computation was successful.
+      *
+      * \returns \c Success if computation was successful,
+      *          \c NumericalIssue if the matrix.appears to be negative.
+      */
+    ComputationInfo info() const
+    {
+      eigen_assert(m_isInitialized && "IncompleteLUT is not initialized.");
+      return m_info;
+    }
+
+    template<typename MatrixType>
+    void analyzePattern(const MatrixType& amat);
+
+    template<typename MatrixType>
+    void factorize(const MatrixType& amat);
+
+    /**
+      * Compute an incomplete LU factorization with dual threshold on the matrix mat
+      * No pivoting is done in this version
+      *
+      **/
+    template<typename MatrixType>
+    IncompleteLUT& compute(const MatrixType& amat)
+    {
+      analyzePattern(amat);
+      factorize(amat);
+      return *this;
+    }
+
+    void setDroptol(const RealScalar& droptol);
+    void setFillfactor(int fillfactor);
+
+    template<typename Rhs, typename Dest>
+    void _solve_impl(const Rhs& b, Dest& x) const
+    {
+      x = m_Pinv * b;
+      x = m_lu.template triangularView<UnitLower>().solve(x);
+      x = m_lu.template triangularView<Upper>().solve(x);
+      x = m_P * x;
+    }
+
+protected:
+
+    /** keeps off-diagonal entries; drops diagonal entries */
+    struct keep_diag {
+      inline bool operator() (const Index& row, const Index& col, const Scalar&) const
+      {
+        return row!=col;
+      }
+    };
+
+protected:
+
+    FactorType m_lu;
+    RealScalar m_droptol;
+    int m_fillfactor;
+    bool m_analysisIsOk;
+    bool m_factorizationIsOk;
+    ComputationInfo m_info;
+    PermutationMatrix<Dynamic,Dynamic,StorageIndex> m_P;     // Fill-reducing permutation
+    PermutationMatrix<Dynamic,Dynamic,StorageIndex> m_Pinv;  // Inverse permutation
+};
+
+/**
+ * Set control parameter droptol
+ *  \param droptol   Drop any element whose magnitude is less than this tolerance
+ **/
+template<typename Scalar, typename StorageIndex>
+void IncompleteLUT<Scalar,StorageIndex>::setDroptol(const RealScalar& droptol)
+{
+  this->m_droptol = droptol;
+}
+
+/**
+ * Set control parameter fillfactor
+ * \param fillfactor  This is used to compute the  number @p fill_in of largest elements to keep on each row.
+ **/
+template<typename Scalar, typename StorageIndex>
+void IncompleteLUT<Scalar,StorageIndex>::setFillfactor(int fillfactor)
+{
+  this->m_fillfactor = fillfactor;
+}
+
+template <typename Scalar, typename StorageIndex>
+template<typename _MatrixType>
+void IncompleteLUT<Scalar,StorageIndex>::analyzePattern(const _MatrixType& amat)
+{
+  // Compute the Fill-reducing permutation
+  // Since ILUT does not perform any numerical pivoting,
+  // it is highly preferable to keep the diagonal through symmetric permutations.
+  // To this end, let's symmetrize the pattern and perform AMD on it.
+  SparseMatrix<Scalar,ColMajor, StorageIndex> mat1 = amat;
+  SparseMatrix<Scalar,ColMajor, StorageIndex> mat2 = amat.transpose();
+  // FIXME for a matrix with nearly symmetric pattern, mat2+mat1 is the appropriate choice.
+  //       on the other hand for a really non-symmetric pattern, mat2*mat1 should be preferred...
+  SparseMatrix<Scalar,ColMajor, StorageIndex> AtA = mat2 + mat1;
+  AMDOrdering<StorageIndex> ordering;
+  ordering(AtA,m_P);
+  m_Pinv  = m_P.inverse(); // cache the inverse permutation
+  m_analysisIsOk = true;
+  m_factorizationIsOk = false;
+  m_isInitialized = true;
+}
+
+template <typename Scalar, typename StorageIndex>
+template<typename _MatrixType>
+void IncompleteLUT<Scalar,StorageIndex>::factorize(const _MatrixType& amat)
+{
+  using std::sqrt;
+  using std::swap;
+  using std::abs;
+  using internal::convert_index;
+
+  eigen_assert((amat.rows() == amat.cols()) && "The factorization should be done on a square matrix");
+  Index n = amat.cols();  // Size of the matrix
+  m_lu.resize(n,n);
+  // Declare Working vectors and variables
+  Vector u(n) ;     // real values of the row -- maximum size is n --
+  VectorI ju(n);   // column position of the values in u -- maximum size  is n
+  VectorI jr(n);   // Indicate the position of the nonzero elements in the vector u -- A zero location is indicated by -1
+
+  // Apply the fill-reducing permutation
+  eigen_assert(m_analysisIsOk && "You must first call analyzePattern()");
+  SparseMatrix<Scalar,RowMajor, StorageIndex> mat;
+  mat = amat.twistedBy(m_Pinv);
+
+  // Initialization
+  jr.fill(-1);
+  ju.fill(0);
+  u.fill(0);
+
+  // number of largest elements to keep in each row:
+  Index fill_in = (amat.nonZeros()*m_fillfactor)/n + 1;
+  if (fill_in > n) fill_in = n;
+
+  // number of largest nonzero elements to keep in the L and the U part of the current row:
+  Index nnzL = fill_in/2;
+  Index nnzU = nnzL;
+  m_lu.reserve(n * (nnzL + nnzU + 1));
+
+  // global loop over the rows of the sparse matrix
+  for (Index ii = 0; ii < n; ii++)
+  {
+    // 1 - copy the lower and the upper part of the row i of mat in the working vector u
+
+    Index sizeu = 1; // number of nonzero elements in the upper part of the current row
+    Index sizel = 0; // number of nonzero elements in the lower part of the current row
+    ju(ii)    = convert_index<StorageIndex>(ii);
+    u(ii)     = 0;
+    jr(ii)    = convert_index<StorageIndex>(ii);
+    RealScalar rownorm = 0;
+
+    typename FactorType::InnerIterator j_it(mat, ii); // Iterate through the current row ii
+    for (; j_it; ++j_it)
+    {
+      Index k = j_it.index();
+      if (k < ii)
+      {
+        // copy the lower part
+        ju(sizel) = convert_index<StorageIndex>(k);
+        u(sizel) = j_it.value();
+        jr(k) = convert_index<StorageIndex>(sizel);
+        ++sizel;
+      }
+      else if (k == ii)
+      {
+        u(ii) = j_it.value();
+      }
+      else
+      {
+        // copy the upper part
+        Index jpos = ii + sizeu;
+        ju(jpos) = convert_index<StorageIndex>(k);
+        u(jpos) = j_it.value();
+        jr(k) = convert_index<StorageIndex>(jpos);
+        ++sizeu;
+      }
+      rownorm += numext::abs2(j_it.value());
+    }
+
+    // 2 - detect possible zero row
+    if(rownorm==0)
+    {
+      m_info = NumericalIssue;
+      return;
+    }
+    // Take the 2-norm of the current row as a relative tolerance
+    rownorm = sqrt(rownorm);
+
+    // 3 - eliminate the previous nonzero rows
+    Index jj = 0;
+    Index len = 0;
+    while (jj < sizel)
+    {
+      // In order to eliminate in the correct order,
+      // we must select first the smallest column index among  ju(jj:sizel)
+      Index k;
+      Index minrow = ju.segment(jj,sizel-jj).minCoeff(&k); // k is relative to the segment
+      k += jj;
+      if (minrow != ju(jj))
+      {
+        // swap the two locations
+        Index j = ju(jj);
+        swap(ju(jj), ju(k));
+        jr(minrow) = convert_index<StorageIndex>(jj);
+        jr(j) = convert_index<StorageIndex>(k);
+        swap(u(jj), u(k));
+      }
+      // Reset this location
+      jr(minrow) = -1;
+
+      // Start elimination
+      typename FactorType::InnerIterator ki_it(m_lu, minrow);
+      while (ki_it && ki_it.index() < minrow) ++ki_it;
+      eigen_internal_assert(ki_it && ki_it.col()==minrow);
+      Scalar fact = u(jj) / ki_it.value();
+
+      // drop too small elements
+      if(abs(fact) <= m_droptol)
+      {
+        jj++;
+        continue;
+      }
+
+      // linear combination of the current row ii and the row minrow
+      ++ki_it;
+      for (; ki_it; ++ki_it)
+      {
+        Scalar prod = fact * ki_it.value();
+        Index j     = ki_it.index();
+        Index jpos  = jr(j);
+        if (jpos == -1) // fill-in element
+        {
+          Index newpos;
+          if (j >= ii) // dealing with the upper part
+          {
+            newpos = ii + sizeu;
+            sizeu++;
+            eigen_internal_assert(sizeu<=n);
+          }
+          else // dealing with the lower part
+          {
+            newpos = sizel;
+            sizel++;
+            eigen_internal_assert(sizel<=ii);
+          }
+          ju(newpos) = convert_index<StorageIndex>(j);
+          u(newpos) = -prod;
+          jr(j) = convert_index<StorageIndex>(newpos);
+        }
+        else
+          u(jpos) -= prod;
+      }
+      // store the pivot element
+      u(len)  = fact;
+      ju(len) = convert_index<StorageIndex>(minrow);
+      ++len;
+
+      jj++;
+    } // end of the elimination on the row ii
+
+    // reset the upper part of the pointer jr to zero
+    for(Index k = 0; k <sizeu; k++) jr(ju(ii+k)) = -1;
+
+    // 4 - partially sort and insert the elements in the m_lu matrix
+
+    // sort the L-part of the row
+    sizel = len;
+    len = (std::min)(sizel, nnzL);
+    typename Vector::SegmentReturnType ul(u.segment(0, sizel));
+    typename VectorI::SegmentReturnType jul(ju.segment(0, sizel));
+    internal::QuickSplit(ul, jul, len);
+
+    // store the largest m_fill elements of the L part
+    m_lu.startVec(ii);
+    for(Index k = 0; k < len; k++)
+      m_lu.insertBackByOuterInnerUnordered(ii,ju(k)) = u(k);
+
+    // store the diagonal element
+    // apply a shifting rule to avoid zero pivots (we are doing an incomplete factorization)
+    if (u(ii) == Scalar(0))
+      u(ii) = sqrt(m_droptol) * rownorm;
+    m_lu.insertBackByOuterInnerUnordered(ii, ii) = u(ii);
+
+    // sort the U-part of the row
+    // apply the dropping rule first
+    len = 0;
+    for(Index k = 1; k < sizeu; k++)
+    {
+      if(abs(u(ii+k)) > m_droptol * rownorm )
+      {
+        ++len;
+        u(ii + len)  = u(ii + k);
+        ju(ii + len) = ju(ii + k);
+      }
+    }
+    sizeu = len + 1; // +1 to take into account the diagonal element
+    len = (std::min)(sizeu, nnzU);
+    typename Vector::SegmentReturnType uu(u.segment(ii+1, sizeu-1));
+    typename VectorI::SegmentReturnType juu(ju.segment(ii+1, sizeu-1));
+    internal::QuickSplit(uu, juu, len);
+
+    // store the largest elements of the U part
+    for(Index k = ii + 1; k < ii + len; k++)
+      m_lu.insertBackByOuterInnerUnordered(ii,ju(k)) = u(k);
+  }
+  m_lu.finalize();
+  m_lu.makeCompressed();
+
+  m_factorizationIsOk = true;
+  m_info = Success;
+}
+
+} // end namespace Eigen
+
+#endif // EIGEN_INCOMPLETE_LUT_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/IterativeLinearSolvers/IterativeSolverBase.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/IterativeLinearSolvers/IterativeSolverBase.h
new file mode 100644
index 0000000..28a0c51
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/IterativeLinearSolvers/IterativeSolverBase.h
@@ -0,0 +1,444 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2011-2014 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_ITERATIVE_SOLVER_BASE_H
+#define EIGEN_ITERATIVE_SOLVER_BASE_H
+
+namespace Eigen {
+
+namespace internal {
+
+template<typename MatrixType>
+struct is_ref_compatible_impl
+{
+private:
+  template <typename T0>
+  struct any_conversion
+  {
+    template <typename T> any_conversion(const volatile T&);
+    template <typename T> any_conversion(T&);
+  };
+  struct yes {int a[1];};
+  struct no  {int a[2];};
+
+  template<typename T>
+  static yes test(const Ref<const T>&, int);
+  template<typename T>
+  static no  test(any_conversion<T>, ...);
+
+public:
+  static MatrixType ms_from;
+  enum { value = sizeof(test<MatrixType>(ms_from, 0))==sizeof(yes) };
+};
+
+template<typename MatrixType>
+struct is_ref_compatible
+{
+  enum { value = is_ref_compatible_impl<typename remove_all<MatrixType>::type>::value };
+};
+
+template<typename MatrixType, bool MatrixFree = !internal::is_ref_compatible<MatrixType>::value>
+class generic_matrix_wrapper;
+
+// We have an explicit matrix at hand, compatible with Ref<>
+template<typename MatrixType>
+class generic_matrix_wrapper<MatrixType,false>
+{
+public:
+  typedef Ref<const MatrixType> ActualMatrixType;
+  template<int UpLo> struct ConstSelfAdjointViewReturnType {
+    typedef typename ActualMatrixType::template ConstSelfAdjointViewReturnType<UpLo>::Type Type;
+  };
+
+  enum {
+    MatrixFree = false
+  };
+
+  generic_matrix_wrapper()
+    : m_dummy(0,0), m_matrix(m_dummy)
+  {}
+
+  template<typename InputType>
+  generic_matrix_wrapper(const InputType &mat)
+    : m_matrix(mat)
+  {}
+
+  const ActualMatrixType& matrix() const
+  {
+    return m_matrix;
+  }
+
+  template<typename MatrixDerived>
+  void grab(const EigenBase<MatrixDerived> &mat)
+  {
+    m_matrix.~Ref<const MatrixType>();
+    ::new (&m_matrix) Ref<const MatrixType>(mat.derived());
+  }
+
+  void grab(const Ref<const MatrixType> &mat)
+  {
+    if(&(mat.derived()) != &m_matrix)
+    {
+      m_matrix.~Ref<const MatrixType>();
+      ::new (&m_matrix) Ref<const MatrixType>(mat);
+    }
+  }
+
+protected:
+  MatrixType m_dummy; // used to default initialize the Ref<> object
+  ActualMatrixType m_matrix;
+};
+
+// MatrixType is not compatible with Ref<> -> matrix-free wrapper
+template<typename MatrixType>
+class generic_matrix_wrapper<MatrixType,true>
+{
+public:
+  typedef MatrixType ActualMatrixType;
+  template<int UpLo> struct ConstSelfAdjointViewReturnType
+  {
+    typedef ActualMatrixType Type;
+  };
+
+  enum {
+    MatrixFree = true
+  };
+
+  generic_matrix_wrapper()
+    : mp_matrix(0)
+  {}
+
+  generic_matrix_wrapper(const MatrixType &mat)
+    : mp_matrix(&mat)
+  {}
+
+  const ActualMatrixType& matrix() const
+  {
+    return *mp_matrix;
+  }
+
+  void grab(const MatrixType &mat)
+  {
+    mp_matrix = &mat;
+  }
+
+protected:
+  const ActualMatrixType *mp_matrix;
+};
+
+}
+
+/** \ingroup IterativeLinearSolvers_Module
+  * \brief Base class for linear iterative solvers
+  *
+  * \sa class SimplicialCholesky, DiagonalPreconditioner, IdentityPreconditioner
+  */
+template< typename Derived>
+class IterativeSolverBase : public SparseSolverBase<Derived>
+{
+protected:
+  typedef SparseSolverBase<Derived> Base;
+  using Base::m_isInitialized;
+
+public:
+  typedef typename internal::traits<Derived>::MatrixType MatrixType;
+  typedef typename internal::traits<Derived>::Preconditioner Preconditioner;
+  typedef typename MatrixType::Scalar Scalar;
+  typedef typename MatrixType::StorageIndex StorageIndex;
+  typedef typename MatrixType::RealScalar RealScalar;
+
+  enum {
+    ColsAtCompileTime = MatrixType::ColsAtCompileTime,
+    MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime
+  };
+
+public:
+
+  using Base::derived;
+
+  /** Default constructor. */
+  IterativeSolverBase()
+  {
+    init();
+  }
+
+  /** Initialize the solver with matrix \a A for further \c Ax=b solving.
+    *
+    * This constructor is a shortcut for the default constructor followed
+    * by a call to compute().
+    *
+    * \warning this class stores a reference to the matrix A as well as some
+    * precomputed values that depend on it. Therefore, if \a A is changed
+    * this class becomes invalid. Call compute() to update it with the new
+    * matrix A, or modify a copy of A.
+    */
+  template<typename MatrixDerived>
+  explicit IterativeSolverBase(const EigenBase<MatrixDerived>& A)
+    : m_matrixWrapper(A.derived())
+  {
+    init();
+    compute(matrix());
+  }
+
+  ~IterativeSolverBase() {}
+
+  /** Initializes the iterative solver for the sparsity pattern of the matrix \a A for further solving \c Ax=b problems.
+    *
+    * Currently, this function mostly calls analyzePattern on the preconditioner. In the future
+    * we might, for instance, implement column reordering for faster matrix vector products.
+    */
+  template<typename MatrixDerived>
+  Derived& analyzePattern(const EigenBase<MatrixDerived>& A)
+  {
+    grab(A.derived());
+    m_preconditioner.analyzePattern(matrix());
+    m_isInitialized = true;
+    m_analysisIsOk = true;
+    m_info = m_preconditioner.info();
+    return derived();
+  }
+
+  /** Initializes the iterative solver with the numerical values of the matrix \a A for further solving \c Ax=b problems.
+    *
+    * Currently, this function mostly calls factorize on the preconditioner.
+    *
+    * \warning this class stores a reference to the matrix A as well as some
+    * precomputed values that depend on it. Therefore, if \a A is changed
+    * this class becomes invalid. Call compute() to update it with the new
+    * matrix A, or modify a copy of A.
+    */
+  template<typename MatrixDerived>
+  Derived& factorize(const EigenBase<MatrixDerived>& A)
+  {
+    eigen_assert(m_analysisIsOk && "You must first call analyzePattern()");
+    grab(A.derived());
+    m_preconditioner.factorize(matrix());
+    m_factorizationIsOk = true;
+    m_info = m_preconditioner.info();
+    return derived();
+  }
+
+  /** Initializes the iterative solver with the matrix \a A for further solving \c Ax=b problems.
+    *
+    * Currently, this function mostly initializes/computes the preconditioner. In the future
+    * we might, for instance, implement column reordering for faster matrix vector products.
+    *
+    * \warning this class stores a reference to the matrix A as well as some
+    * precomputed values that depend on it. Therefore, if \a A is changed
+    * this class becomes invalid. Call compute() to update it with the new
+    * matrix A, or modify a copy of A.
+    */
+  template<typename MatrixDerived>
+  Derived& compute(const EigenBase<MatrixDerived>& A)
+  {
+    grab(A.derived());
+    m_preconditioner.compute(matrix());
+    m_isInitialized = true;
+    m_analysisIsOk = true;
+    m_factorizationIsOk = true;
+    m_info = m_preconditioner.info();
+    return derived();
+  }
+
+  /** \internal */
+  EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT { return matrix().rows(); }
+
+  /** \internal */
+  EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT { return matrix().cols(); }
+
+  /** \returns the tolerance threshold used by the stopping criteria.
+    * \sa setTolerance()
+    */
+  RealScalar tolerance() const { return m_tolerance; }
+
+  /** Sets the tolerance threshold used by the stopping criteria.
+    *
+    * This value is used as an upper bound to the relative residual error: |Ax-b|/|b|.
+    * The default value is the machine precision given by NumTraits<Scalar>::epsilon()
+    */
+  Derived& setTolerance(const RealScalar& tolerance)
+  {
+    m_tolerance = tolerance;
+    return derived();
+  }
+
+  /** \returns a read-write reference to the preconditioner for custom configuration. */
+  Preconditioner& preconditioner() { return m_preconditioner; }
+
+  /** \returns a read-only reference to the preconditioner. */
+  const Preconditioner& preconditioner() const { return m_preconditioner; }
+
+  /** \returns the max number of iterations.
+    * It is either the value set by setMaxIterations or, by default,
+    * twice the number of columns of the matrix.
+    */
+  Index maxIterations() const
+  {
+    return (m_maxIterations<0) ? 2*matrix().cols() : m_maxIterations;
+  }
+
+  /** Sets the max number of iterations.
+    * Default is twice the number of columns of the matrix.
+    */
+  Derived& setMaxIterations(Index maxIters)
+  {
+    m_maxIterations = maxIters;
+    return derived();
+  }
+
+  /** \returns the number of iterations performed during the last solve */
+  Index iterations() const
+  {
+    eigen_assert(m_isInitialized && "ConjugateGradient is not initialized.");
+    return m_iterations;
+  }
+
+  /** \returns the tolerance error reached during the last solve.
+    * It is a close approximation of the true relative residual error |Ax-b|/|b|.
+    */
+  RealScalar error() const
+  {
+    eigen_assert(m_isInitialized && "ConjugateGradient is not initialized.");
+    return m_error;
+  }
+
+  /** \returns the solution x of \f$ A x = b \f$ using the current decomposition of A
+    * and \a x0 as an initial solution.
+    *
+    * \sa solve(), compute()
+    */
+  template<typename Rhs,typename Guess>
+  inline const SolveWithGuess<Derived, Rhs, Guess>
+  solveWithGuess(const MatrixBase<Rhs>& b, const Guess& x0) const
+  {
+    eigen_assert(m_isInitialized && "Solver is not initialized.");
+    eigen_assert(derived().rows()==b.rows() && "solve(): invalid number of rows of the right hand side matrix b");
+    return SolveWithGuess<Derived, Rhs, Guess>(derived(), b.derived(), x0);
+  }
+
+  /** \returns Success if the iterations converged, and NoConvergence otherwise. */
+  ComputationInfo info() const
+  {
+    eigen_assert(m_isInitialized && "IterativeSolverBase is not initialized.");
+    return m_info;
+  }
+
+  /** \internal */
+  template<typename Rhs, typename DestDerived>
+  void _solve_with_guess_impl(const Rhs& b, SparseMatrixBase<DestDerived> &aDest) const
+  {
+    eigen_assert(rows()==b.rows());
+
+    Index rhsCols = b.cols();
+    Index size = b.rows();
+    DestDerived& dest(aDest.derived());
+    typedef typename DestDerived::Scalar DestScalar;
+    Eigen::Matrix<DestScalar,Dynamic,1> tb(size);
+    Eigen::Matrix<DestScalar,Dynamic,1> tx(cols());
+    // We do not directly fill dest because sparse expressions have to be free of aliasing issue.
+    // For non square least-square problems, b and dest might not have the same size whereas they might alias each-other.
+    typename DestDerived::PlainObject tmp(cols(),rhsCols);
+    ComputationInfo global_info = Success;
+    for(Index k=0; k<rhsCols; ++k)
+    {
+      tb = b.col(k);
+      tx = dest.col(k);
+      derived()._solve_vector_with_guess_impl(tb,tx);
+      tmp.col(k) = tx.sparseView(0);
+
+      // The call to _solve_vector_with_guess_impl updates m_info, so if it failed for a previous column
+      // we need to restore it to the worst value.
+      if(m_info==NumericalIssue)
+        global_info = NumericalIssue;
+      else if(m_info==NoConvergence)
+        global_info = NoConvergence;
+    }
+    m_info = global_info;
+    dest.swap(tmp);
+  }
+
+  template<typename Rhs, typename DestDerived>
+  typename internal::enable_if<Rhs::ColsAtCompileTime!=1 && DestDerived::ColsAtCompileTime!=1>::type
+  _solve_with_guess_impl(const Rhs& b, MatrixBase<DestDerived> &aDest) const
+  {
+    eigen_assert(rows()==b.rows());
+
+    Index rhsCols = b.cols();
+    DestDerived& dest(aDest.derived());
+    ComputationInfo global_info = Success;
+    for(Index k=0; k<rhsCols; ++k)
+    {
+      typename DestDerived::ColXpr xk(dest,k);
+      typename Rhs::ConstColXpr bk(b,k);
+      derived()._solve_vector_with_guess_impl(bk,xk);
+
+      // The call to _solve_vector_with_guess updates m_info, so if it failed for a previous column
+      // we need to restore it to the worst value.
+      if(m_info==NumericalIssue)
+        global_info = NumericalIssue;
+      else if(m_info==NoConvergence)
+        global_info = NoConvergence;
+    }
+    m_info = global_info;
+  }
+
+  template<typename Rhs, typename DestDerived>
+  typename internal::enable_if<Rhs::ColsAtCompileTime==1 || DestDerived::ColsAtCompileTime==1>::type
+  _solve_with_guess_impl(const Rhs& b, MatrixBase<DestDerived> &dest) const
+  {
+    derived()._solve_vector_with_guess_impl(b,dest.derived());
+  }
+
+  /** \internal default initial guess = 0 */
+  template<typename Rhs,typename Dest>
+  void _solve_impl(const Rhs& b, Dest& x) const
+  {
+    x.setZero();
+    derived()._solve_with_guess_impl(b,x);
+  }
+
+protected:
+  void init()
+  {
+    m_isInitialized = false;
+    m_analysisIsOk = false;
+    m_factorizationIsOk = false;
+    m_maxIterations = -1;
+    m_tolerance = NumTraits<Scalar>::epsilon();
+  }
+
+  typedef internal::generic_matrix_wrapper<MatrixType> MatrixWrapper;
+  typedef typename MatrixWrapper::ActualMatrixType ActualMatrixType;
+
+  const ActualMatrixType& matrix() const
+  {
+    return m_matrixWrapper.matrix();
+  }
+
+  template<typename InputType>
+  void grab(const InputType &A)
+  {
+    m_matrixWrapper.grab(A);
+  }
+
+  MatrixWrapper m_matrixWrapper;
+  Preconditioner m_preconditioner;
+
+  Index m_maxIterations;
+  RealScalar m_tolerance;
+
+  mutable RealScalar m_error;
+  mutable Index m_iterations;
+  mutable ComputationInfo m_info;
+  mutable bool m_analysisIsOk, m_factorizationIsOk;
+};
+
+} // end namespace Eigen
+
+#endif // EIGEN_ITERATIVE_SOLVER_BASE_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/IterativeLinearSolvers/LeastSquareConjugateGradient.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/IterativeLinearSolvers/LeastSquareConjugateGradient.h
new file mode 100644
index 0000000..203fd0e
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/IterativeLinearSolvers/LeastSquareConjugateGradient.h
@@ -0,0 +1,198 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2015 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_LEAST_SQUARE_CONJUGATE_GRADIENT_H
+#define EIGEN_LEAST_SQUARE_CONJUGATE_GRADIENT_H
+
+namespace Eigen { 
+
+namespace internal {
+
+/** \internal Low-level conjugate gradient algorithm for least-square problems
+  * \param mat The matrix A
+  * \param rhs The right hand side vector b
+  * \param x On input and initial solution, on output the computed solution.
+  * \param precond A preconditioner being able to efficiently solve for an
+  *                approximation of A'Ax=b (regardless of b)
+  * \param iters On input the max number of iteration, on output the number of performed iterations.
+  * \param tol_error On input the tolerance error, on output an estimation of the relative error.
+  */
+template<typename MatrixType, typename Rhs, typename Dest, typename Preconditioner>
+EIGEN_DONT_INLINE
+void least_square_conjugate_gradient(const MatrixType& mat, const Rhs& rhs, Dest& x,
+                                     const Preconditioner& precond, Index& iters,
+                                     typename Dest::RealScalar& tol_error)
+{
+  using std::sqrt;
+  using std::abs;
+  typedef typename Dest::RealScalar RealScalar;
+  typedef typename Dest::Scalar Scalar;
+  typedef Matrix<Scalar,Dynamic,1> VectorType;
+  
+  RealScalar tol = tol_error;
+  Index maxIters = iters;
+  
+  Index m = mat.rows(), n = mat.cols();
+
+  VectorType residual        = rhs - mat * x;
+  VectorType normal_residual = mat.adjoint() * residual;
+
+  RealScalar rhsNorm2 = (mat.adjoint()*rhs).squaredNorm();
+  if(rhsNorm2 == 0) 
+  {
+    x.setZero();
+    iters = 0;
+    tol_error = 0;
+    return;
+  }
+  RealScalar threshold = tol*tol*rhsNorm2;
+  RealScalar residualNorm2 = normal_residual.squaredNorm();
+  if (residualNorm2 < threshold)
+  {
+    iters = 0;
+    tol_error = sqrt(residualNorm2 / rhsNorm2);
+    return;
+  }
+  
+  VectorType p(n);
+  p = precond.solve(normal_residual);                         // initial search direction
+
+  VectorType z(n), tmp(m);
+  RealScalar absNew = numext::real(normal_residual.dot(p));  // the square of the absolute value of r scaled by invM
+  Index i = 0;
+  while(i < maxIters)
+  {
+    tmp.noalias() = mat * p;
+
+    Scalar alpha = absNew / tmp.squaredNorm();      // the amount we travel on dir
+    x += alpha * p;                                 // update solution
+    residual -= alpha * tmp;                        // update residual
+    normal_residual = mat.adjoint() * residual;     // update residual of the normal equation
+    
+    residualNorm2 = normal_residual.squaredNorm();
+    if(residualNorm2 < threshold)
+      break;
+    
+    z = precond.solve(normal_residual);             // approximately solve for "A'A z = normal_residual"
+
+    RealScalar absOld = absNew;
+    absNew = numext::real(normal_residual.dot(z));  // update the absolute value of r
+    RealScalar beta = absNew / absOld;              // calculate the Gram-Schmidt value used to create the new search direction
+    p = z + beta * p;                               // update search direction
+    i++;
+  }
+  tol_error = sqrt(residualNorm2 / rhsNorm2);
+  iters = i;
+}
+
+}
+
+template< typename _MatrixType,
+          typename _Preconditioner = LeastSquareDiagonalPreconditioner<typename _MatrixType::Scalar> >
+class LeastSquaresConjugateGradient;
+
+namespace internal {
+
+template< typename _MatrixType, typename _Preconditioner>
+struct traits<LeastSquaresConjugateGradient<_MatrixType,_Preconditioner> >
+{
+  typedef _MatrixType MatrixType;
+  typedef _Preconditioner Preconditioner;
+};
+
+}
+
+/** \ingroup IterativeLinearSolvers_Module
+  * \brief A conjugate gradient solver for sparse (or dense) least-square problems
+  *
+  * This class allows to solve for A x = b linear problems using an iterative conjugate gradient algorithm.
+  * The matrix A can be non symmetric and rectangular, but the matrix A' A should be positive-definite to guaranty stability.
+  * Otherwise, the SparseLU or SparseQR classes might be preferable.
+  * The matrix A and the vectors x and b can be either dense or sparse.
+  *
+  * \tparam _MatrixType the type of the matrix A, can be a dense or a sparse matrix.
+  * \tparam _Preconditioner the type of the preconditioner. Default is LeastSquareDiagonalPreconditioner
+  *
+  * \implsparsesolverconcept
+  * 
+  * The maximal number of iterations and tolerance value can be controlled via the setMaxIterations()
+  * and setTolerance() methods. The defaults are the size of the problem for the maximal number of iterations
+  * and NumTraits<Scalar>::epsilon() for the tolerance.
+  * 
+  * This class can be used as the direct solver classes. Here is a typical usage example:
+    \code
+    int m=1000000, n = 10000;
+    VectorXd x(n), b(m);
+    SparseMatrix<double> A(m,n);
+    // fill A and b
+    LeastSquaresConjugateGradient<SparseMatrix<double> > lscg;
+    lscg.compute(A);
+    x = lscg.solve(b);
+    std::cout << "#iterations:     " << lscg.iterations() << std::endl;
+    std::cout << "estimated error: " << lscg.error()      << std::endl;
+    // update b, and solve again
+    x = lscg.solve(b);
+    \endcode
+  * 
+  * By default the iterations start with x=0 as an initial guess of the solution.
+  * One can control the start using the solveWithGuess() method.
+  * 
+  * \sa class ConjugateGradient, SparseLU, SparseQR
+  */
+template< typename _MatrixType, typename _Preconditioner>
+class LeastSquaresConjugateGradient : public IterativeSolverBase<LeastSquaresConjugateGradient<_MatrixType,_Preconditioner> >
+{
+  typedef IterativeSolverBase<LeastSquaresConjugateGradient> Base;
+  using Base::matrix;
+  using Base::m_error;
+  using Base::m_iterations;
+  using Base::m_info;
+  using Base::m_isInitialized;
+public:
+  typedef _MatrixType MatrixType;
+  typedef typename MatrixType::Scalar Scalar;
+  typedef typename MatrixType::RealScalar RealScalar;
+  typedef _Preconditioner Preconditioner;
+
+public:
+
+  /** Default constructor. */
+  LeastSquaresConjugateGradient() : Base() {}
+
+  /** Initialize the solver with matrix \a A for further \c Ax=b solving.
+    * 
+    * This constructor is a shortcut for the default constructor followed
+    * by a call to compute().
+    * 
+    * \warning this class stores a reference to the matrix A as well as some
+    * precomputed values that depend on it. Therefore, if \a A is changed
+    * this class becomes invalid. Call compute() to update it with the new
+    * matrix A, or modify a copy of A.
+    */
+  template<typename MatrixDerived>
+  explicit LeastSquaresConjugateGradient(const EigenBase<MatrixDerived>& A) : Base(A.derived()) {}
+
+  ~LeastSquaresConjugateGradient() {}
+
+  /** \internal */
+  template<typename Rhs,typename Dest>
+  void _solve_vector_with_guess_impl(const Rhs& b, Dest& x) const
+  {
+    m_iterations = Base::maxIterations();
+    m_error = Base::m_tolerance;
+
+    internal::least_square_conjugate_gradient(matrix(), b, x, Base::m_preconditioner, m_iterations, m_error);
+    m_info = m_error <= Base::m_tolerance ? Success : NoConvergence;
+  }
+
+};
+
+} // end namespace Eigen
+
+#endif // EIGEN_LEAST_SQUARE_CONJUGATE_GRADIENT_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/IterativeLinearSolvers/SolveWithGuess.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/IterativeLinearSolvers/SolveWithGuess.h
new file mode 100644
index 0000000..7b89657
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/IterativeLinearSolvers/SolveWithGuess.h
@@ -0,0 +1,117 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2014 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_SOLVEWITHGUESS_H
+#define EIGEN_SOLVEWITHGUESS_H
+
+namespace Eigen {
+
+template<typename Decomposition, typename RhsType, typename GuessType> class SolveWithGuess;
+
+/** \class SolveWithGuess
+  * \ingroup IterativeLinearSolvers_Module
+  *
+  * \brief Pseudo expression representing a solving operation
+  *
+  * \tparam Decomposition the type of the matrix or decomposion object
+  * \tparam Rhstype the type of the right-hand side
+  *
+  * This class represents an expression of A.solve(B)
+  * and most of the time this is the only way it is used.
+  *
+  */
+namespace internal {
+
+
+template<typename Decomposition, typename RhsType, typename GuessType>
+struct traits<SolveWithGuess<Decomposition, RhsType, GuessType> >
+  : traits<Solve<Decomposition,RhsType> >
+{};
+
+}
+
+
+template<typename Decomposition, typename RhsType, typename GuessType>
+class SolveWithGuess : public internal::generic_xpr_base<SolveWithGuess<Decomposition,RhsType,GuessType>, MatrixXpr, typename internal::traits<RhsType>::StorageKind>::type
+{
+public:
+  typedef typename internal::traits<SolveWithGuess>::Scalar Scalar;
+  typedef typename internal::traits<SolveWithGuess>::PlainObject PlainObject;
+  typedef typename internal::generic_xpr_base<SolveWithGuess<Decomposition,RhsType,GuessType>, MatrixXpr, typename internal::traits<RhsType>::StorageKind>::type Base;
+  typedef typename internal::ref_selector<SolveWithGuess>::type Nested;
+
+  SolveWithGuess(const Decomposition &dec, const RhsType &rhs, const GuessType &guess)
+    : m_dec(dec), m_rhs(rhs), m_guess(guess)
+  {}
+
+  EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR
+  Index rows() const EIGEN_NOEXCEPT { return m_dec.cols(); }
+  EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR
+  Index cols() const EIGEN_NOEXCEPT { return m_rhs.cols(); }
+
+  EIGEN_DEVICE_FUNC const Decomposition& dec()   const { return m_dec; }
+  EIGEN_DEVICE_FUNC const RhsType&       rhs()   const { return m_rhs; }
+  EIGEN_DEVICE_FUNC const GuessType&     guess() const { return m_guess; }
+
+protected:
+  const Decomposition &m_dec;
+  const RhsType       &m_rhs;
+  const GuessType     &m_guess;
+
+private:
+  Scalar coeff(Index row, Index col) const;
+  Scalar coeff(Index i) const;
+};
+
+namespace internal {
+
+// Evaluator of SolveWithGuess -> eval into a temporary
+template<typename Decomposition, typename RhsType, typename GuessType>
+struct evaluator<SolveWithGuess<Decomposition,RhsType, GuessType> >
+  : public evaluator<typename SolveWithGuess<Decomposition,RhsType,GuessType>::PlainObject>
+{
+  typedef SolveWithGuess<Decomposition,RhsType,GuessType> SolveType;
+  typedef typename SolveType::PlainObject PlainObject;
+  typedef evaluator<PlainObject> Base;
+
+  evaluator(const SolveType& solve)
+    : m_result(solve.rows(), solve.cols())
+  {
+    ::new (static_cast<Base*>(this)) Base(m_result);
+    m_result = solve.guess();
+    solve.dec()._solve_with_guess_impl(solve.rhs(), m_result);
+  }
+
+protected:
+  PlainObject m_result;
+};
+
+// Specialization for "dst = dec.solveWithGuess(rhs)"
+// NOTE we need to specialize it for Dense2Dense to avoid ambiguous specialization error and a Sparse2Sparse specialization must exist somewhere
+template<typename DstXprType, typename DecType, typename RhsType, typename GuessType, typename Scalar>
+struct Assignment<DstXprType, SolveWithGuess<DecType,RhsType,GuessType>, internal::assign_op<Scalar,Scalar>, Dense2Dense>
+{
+  typedef SolveWithGuess<DecType,RhsType,GuessType> SrcXprType;
+  static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op<Scalar,Scalar> &)
+  {
+    Index dstRows = src.rows();
+    Index dstCols = src.cols();
+    if((dst.rows()!=dstRows) || (dst.cols()!=dstCols))
+      dst.resize(dstRows, dstCols);
+
+    dst = src.guess();
+    src.dec()._solve_with_guess_impl(src.rhs(), dst/*, src.guess()*/);
+  }
+};
+
+} // end namespace internal
+
+} // end namespace Eigen
+
+#endif // EIGEN_SOLVEWITHGUESS_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Jacobi/Jacobi.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Jacobi/Jacobi.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/Jacobi/Jacobi.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/Jacobi/Jacobi.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/LU/Determinant.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/LU/Determinant.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/LU/Determinant.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/LU/Determinant.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/LU/FullPivLU.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/LU/FullPivLU.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/LU/FullPivLU.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/LU/FullPivLU.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/LU/InverseImpl.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/LU/InverseImpl.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/LU/InverseImpl.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/LU/InverseImpl.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/LU/PartialPivLU.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/LU/PartialPivLU.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/LU/PartialPivLU.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/LU/PartialPivLU.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/LU/arch/InverseSize4.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/LU/arch/InverseSize4.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/LU/arch/InverseSize4.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/LU/arch/InverseSize4.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/OrderingMethods/Amd.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/OrderingMethods/Amd.h
new file mode 100644
index 0000000..7ca3f33
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/OrderingMethods/Amd.h
@@ -0,0 +1,435 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2010 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+/*
+NOTE: this routine has been adapted from the CSparse library:
+
+Copyright (c) 2006, Timothy A. Davis.
+http://www.suitesparse.com
+
+The author of CSparse, Timothy A. Davis., has executed a license with Google LLC
+to permit distribution of this code and derivative works as part of Eigen under
+the Mozilla Public License v. 2.0, as stated at the top of this file.
+*/
+
+#ifndef EIGEN_SPARSE_AMD_H
+#define EIGEN_SPARSE_AMD_H
+
+namespace Eigen { 
+
+namespace internal {
+  
+template<typename T> inline T amd_flip(const T& i) { return -i-2; }
+template<typename T> inline T amd_unflip(const T& i) { return i<0 ? amd_flip(i) : i; }
+template<typename T0, typename T1> inline bool amd_marked(const T0* w, const T1& j) { return w[j]<0; }
+template<typename T0, typename T1> inline void amd_mark(const T0* w, const T1& j) { return w[j] = amd_flip(w[j]); }
+
+/* clear w */
+template<typename StorageIndex>
+static StorageIndex cs_wclear (StorageIndex mark, StorageIndex lemax, StorageIndex *w, StorageIndex n)
+{
+  StorageIndex k;
+  if(mark < 2 || (mark + lemax < 0))
+  {
+    for(k = 0; k < n; k++)
+      if(w[k] != 0)
+        w[k] = 1;
+    mark = 2;
+  }
+  return (mark);     /* at this point, w[0..n-1] < mark holds */
+}
+
+/* depth-first search and postorder of a tree rooted at node j */
+template<typename StorageIndex>
+StorageIndex cs_tdfs(StorageIndex j, StorageIndex k, StorageIndex *head, const StorageIndex *next, StorageIndex *post, StorageIndex *stack)
+{
+  StorageIndex i, p, top = 0;
+  if(!head || !next || !post || !stack) return (-1);    /* check inputs */
+  stack[0] = j;                 /* place j on the stack */
+  while (top >= 0)                /* while (stack is not empty) */
+  {
+    p = stack[top];           /* p = top of stack */
+    i = head[p];              /* i = youngest child of p */
+    if(i == -1)
+    {
+      top--;                 /* p has no unordered children left */
+      post[k++] = p;        /* node p is the kth postordered node */
+    }
+    else
+    {
+      head[p] = next[i];   /* remove i from children of p */
+      stack[++top] = i;     /* start dfs on child node i */
+    }
+  }
+  return k;
+}
+
+
+/** \internal
+  * \ingroup OrderingMethods_Module 
+  * Approximate minimum degree ordering algorithm.
+  *
+  * \param[in] C the input selfadjoint matrix stored in compressed column major format.
+  * \param[out] perm the permutation P reducing the fill-in of the input matrix \a C
+  *
+  * Note that the input matrix \a C must be complete, that is both the upper and lower parts have to be stored, as well as the diagonal entries.
+  * On exit the values of C are destroyed */
+template<typename Scalar, typename StorageIndex>
+void minimum_degree_ordering(SparseMatrix<Scalar,ColMajor,StorageIndex>& C, PermutationMatrix<Dynamic,Dynamic,StorageIndex>& perm)
+{
+  using std::sqrt;
+  
+  StorageIndex d, dk, dext, lemax = 0, e, elenk, eln, i, j, k, k1,
+                k2, k3, jlast, ln, dense, nzmax, mindeg = 0, nvi, nvj, nvk, mark, wnvi,
+                ok, nel = 0, p, p1, p2, p3, p4, pj, pk, pk1, pk2, pn, q, t, h;
+  
+  StorageIndex n = StorageIndex(C.cols());
+  dense = std::max<StorageIndex> (16, StorageIndex(10 * sqrt(double(n))));   /* find dense threshold */
+  dense = (std::min)(n-2, dense);
+  
+  StorageIndex cnz = StorageIndex(C.nonZeros());
+  perm.resize(n+1);
+  t = cnz + cnz/5 + 2*n;                 /* add elbow room to C */
+  C.resizeNonZeros(t);
+  
+  // get workspace
+  ei_declare_aligned_stack_constructed_variable(StorageIndex,W,8*(n+1),0);
+  StorageIndex* len     = W;
+  StorageIndex* nv      = W +   (n+1);
+  StorageIndex* next    = W + 2*(n+1);
+  StorageIndex* head    = W + 3*(n+1);
+  StorageIndex* elen    = W + 4*(n+1);
+  StorageIndex* degree  = W + 5*(n+1);
+  StorageIndex* w       = W + 6*(n+1);
+  StorageIndex* hhead   = W + 7*(n+1);
+  StorageIndex* last    = perm.indices().data();                              /* use P as workspace for last */
+  
+  /* --- Initialize quotient graph ---------------------------------------- */
+  StorageIndex* Cp = C.outerIndexPtr();
+  StorageIndex* Ci = C.innerIndexPtr();
+  for(k = 0; k < n; k++)
+    len[k] = Cp[k+1] - Cp[k];
+  len[n] = 0;
+  nzmax = t;
+  
+  for(i = 0; i <= n; i++)
+  {
+    head[i]   = -1;                     // degree list i is empty
+    last[i]   = -1;
+    next[i]   = -1;
+    hhead[i]  = -1;                     // hash list i is empty 
+    nv[i]     = 1;                      // node i is just one node
+    w[i]      = 1;                      // node i is alive
+    elen[i]   = 0;                      // Ek of node i is empty
+    degree[i] = len[i];                 // degree of node i
+  }
+  mark = internal::cs_wclear<StorageIndex>(0, 0, w, n);         /* clear w */
+  
+  /* --- Initialize degree lists ------------------------------------------ */
+  for(i = 0; i < n; i++)
+  {
+    bool has_diag = false;
+    for(p = Cp[i]; p<Cp[i+1]; ++p)
+      if(Ci[p]==i)
+      {
+        has_diag = true;
+        break;
+      }
+   
+    d = degree[i];
+    if(d == 1 && has_diag)           /* node i is empty */
+    {
+      elen[i] = -2;                 /* element i is dead */
+      nel++;
+      Cp[i] = -1;                   /* i is a root of assembly tree */
+      w[i] = 0;
+    }
+    else if(d > dense || !has_diag)  /* node i is dense or has no structural diagonal element */
+    {
+      nv[i] = 0;                    /* absorb i into element n */
+      elen[i] = -1;                 /* node i is dead */
+      nel++;
+      Cp[i] = amd_flip (n);
+      nv[n]++;
+    }
+    else
+    {
+      if(head[d] != -1) last[head[d]] = i;
+      next[i] = head[d];           /* put node i in degree list d */
+      head[d] = i;
+    }
+  }
+  
+  elen[n] = -2;                         /* n is a dead element */
+  Cp[n] = -1;                           /* n is a root of assembly tree */
+  w[n] = 0;                             /* n is a dead element */
+  
+  while (nel < n)                         /* while (selecting pivots) do */
+  {
+    /* --- Select node of minimum approximate degree -------------------- */
+    for(k = -1; mindeg < n && (k = head[mindeg]) == -1; mindeg++) {}
+    if(next[k] != -1) last[next[k]] = -1;
+    head[mindeg] = next[k];          /* remove k from degree list */
+    elenk = elen[k];                  /* elenk = |Ek| */
+    nvk = nv[k];                      /* # of nodes k represents */
+    nel += nvk;                        /* nv[k] nodes of A eliminated */
+    
+    /* --- Garbage collection ------------------------------------------- */
+    if(elenk > 0 && cnz + mindeg >= nzmax)
+    {
+      for(j = 0; j < n; j++)
+      {
+        if((p = Cp[j]) >= 0)      /* j is a live node or element */
+        {
+          Cp[j] = Ci[p];          /* save first entry of object */
+          Ci[p] = amd_flip (j);    /* first entry is now amd_flip(j) */
+        }
+      }
+      for(q = 0, p = 0; p < cnz; ) /* scan all of memory */
+      {
+        if((j = amd_flip (Ci[p++])) >= 0)  /* found object j */
+        {
+          Ci[q] = Cp[j];       /* restore first entry of object */
+          Cp[j] = q++;          /* new pointer to object j */
+          for(k3 = 0; k3 < len[j]-1; k3++) Ci[q++] = Ci[p++];
+        }
+      }
+      cnz = q;                       /* Ci[cnz...nzmax-1] now free */
+    }
+    
+    /* --- Construct new element ---------------------------------------- */
+    dk = 0;
+    nv[k] = -nvk;                     /* flag k as in Lk */
+    p = Cp[k];
+    pk1 = (elenk == 0) ? p : cnz;      /* do in place if elen[k] == 0 */
+    pk2 = pk1;
+    for(k1 = 1; k1 <= elenk + 1; k1++)
+    {
+      if(k1 > elenk)
+      {
+        e = k;                     /* search the nodes in k */
+        pj = p;                    /* list of nodes starts at Ci[pj]*/
+        ln = len[k] - elenk;      /* length of list of nodes in k */
+      }
+      else
+      {
+        e = Ci[p++];              /* search the nodes in e */
+        pj = Cp[e];
+        ln = len[e];              /* length of list of nodes in e */
+      }
+      for(k2 = 1; k2 <= ln; k2++)
+      {
+        i = Ci[pj++];
+        if((nvi = nv[i]) <= 0) continue; /* node i dead, or seen */
+        dk += nvi;                 /* degree[Lk] += size of node i */
+        nv[i] = -nvi;             /* negate nv[i] to denote i in Lk*/
+        Ci[pk2++] = i;            /* place i in Lk */
+        if(next[i] != -1) last[next[i]] = last[i];
+        if(last[i] != -1)         /* remove i from degree list */
+        {
+          next[last[i]] = next[i];
+        }
+        else
+        {
+          head[degree[i]] = next[i];
+        }
+      }
+      if(e != k)
+      {
+        Cp[e] = amd_flip (k);      /* absorb e into k */
+        w[e] = 0;                 /* e is now a dead element */
+      }
+    }
+    if(elenk != 0) cnz = pk2;         /* Ci[cnz...nzmax] is free */
+    degree[k] = dk;                   /* external degree of k - |Lk\i| */
+    Cp[k] = pk1;                      /* element k is in Ci[pk1..pk2-1] */
+    len[k] = pk2 - pk1;
+    elen[k] = -2;                     /* k is now an element */
+    
+    /* --- Find set differences ----------------------------------------- */
+    mark = internal::cs_wclear<StorageIndex>(mark, lemax, w, n);  /* clear w if necessary */
+    for(pk = pk1; pk < pk2; pk++)    /* scan 1: find |Le\Lk| */
+    {
+      i = Ci[pk];
+      if((eln = elen[i]) <= 0) continue;/* skip if elen[i] empty */
+      nvi = -nv[i];                      /* nv[i] was negated */
+      wnvi = mark - nvi;
+      for(p = Cp[i]; p <= Cp[i] + eln - 1; p++)  /* scan Ei */
+      {
+        e = Ci[p];
+        if(w[e] >= mark)
+        {
+          w[e] -= nvi;          /* decrement |Le\Lk| */
+        }
+        else if(w[e] != 0)        /* ensure e is a live element */
+        {
+          w[e] = degree[e] + wnvi; /* 1st time e seen in scan 1 */
+        }
+      }
+    }
+    
+    /* --- Degree update ------------------------------------------------ */
+    for(pk = pk1; pk < pk2; pk++)    /* scan2: degree update */
+    {
+      i = Ci[pk];                   /* consider node i in Lk */
+      p1 = Cp[i];
+      p2 = p1 + elen[i] - 1;
+      pn = p1;
+      for(h = 0, d = 0, p = p1; p <= p2; p++)    /* scan Ei */
+      {
+        e = Ci[p];
+        if(w[e] != 0)             /* e is an unabsorbed element */
+        {
+          dext = w[e] - mark;   /* dext = |Le\Lk| */
+          if(dext > 0)
+          {
+            d += dext;         /* sum up the set differences */
+            Ci[pn++] = e;     /* keep e in Ei */
+            h += e;            /* compute the hash of node i */
+          }
+          else
+          {
+            Cp[e] = amd_flip (k);  /* aggressive absorb. e->k */
+            w[e] = 0;             /* e is a dead element */
+          }
+        }
+      }
+      elen[i] = pn - p1 + 1;        /* elen[i] = |Ei| */
+      p3 = pn;
+      p4 = p1 + len[i];
+      for(p = p2 + 1; p < p4; p++) /* prune edges in Ai */
+      {
+        j = Ci[p];
+        if((nvj = nv[j]) <= 0) continue; /* node j dead or in Lk */
+        d += nvj;                  /* degree(i) += |j| */
+        Ci[pn++] = j;             /* place j in node list of i */
+        h += j;                    /* compute hash for node i */
+      }
+      if(d == 0)                     /* check for mass elimination */
+      {
+        Cp[i] = amd_flip (k);      /* absorb i into k */
+        nvi = -nv[i];
+        dk -= nvi;                 /* |Lk| -= |i| */
+        nvk += nvi;                /* |k| += nv[i] */
+        nel += nvi;
+        nv[i] = 0;
+        elen[i] = -1;             /* node i is dead */
+      }
+      else
+      {
+        degree[i] = std::min<StorageIndex> (degree[i], d);   /* update degree(i) */
+        Ci[pn] = Ci[p3];         /* move first node to end */
+        Ci[p3] = Ci[p1];         /* move 1st el. to end of Ei */
+        Ci[p1] = k;               /* add k as 1st element in of Ei */
+        len[i] = pn - p1 + 1;     /* new len of adj. list of node i */
+        h %= n;                    /* finalize hash of i */
+        next[i] = hhead[h];      /* place i in hash bucket */
+        hhead[h] = i;
+        last[i] = h;      /* save hash of i in last[i] */
+      }
+    }                                   /* scan2 is done */
+    degree[k] = dk;                   /* finalize |Lk| */
+    lemax = std::max<StorageIndex>(lemax, dk);
+    mark = internal::cs_wclear<StorageIndex>(mark+lemax, lemax, w, n);    /* clear w */
+    
+    /* --- Supernode detection ------------------------------------------ */
+    for(pk = pk1; pk < pk2; pk++)
+    {
+      i = Ci[pk];
+      if(nv[i] >= 0) continue;         /* skip if i is dead */
+      h = last[i];                      /* scan hash bucket of node i */
+      i = hhead[h];
+      hhead[h] = -1;                    /* hash bucket will be empty */
+      for(; i != -1 && next[i] != -1; i = next[i], mark++)
+      {
+        ln = len[i];
+        eln = elen[i];
+        for(p = Cp[i]+1; p <= Cp[i] + ln-1; p++) w[Ci[p]] = mark;
+        jlast = i;
+        for(j = next[i]; j != -1; ) /* compare i with all j */
+        {
+          ok = (len[j] == ln) && (elen[j] == eln);
+          for(p = Cp[j] + 1; ok && p <= Cp[j] + ln - 1; p++)
+          {
+            if(w[Ci[p]] != mark) ok = 0;    /* compare i and j*/
+          }
+          if(ok)                     /* i and j are identical */
+          {
+            Cp[j] = amd_flip (i);  /* absorb j into i */
+            nv[i] += nv[j];
+            nv[j] = 0;
+            elen[j] = -1;         /* node j is dead */
+            j = next[j];          /* delete j from hash bucket */
+            next[jlast] = j;
+          }
+          else
+          {
+            jlast = j;             /* j and i are different */
+            j = next[j];
+          }
+        }
+      }
+    }
+    
+    /* --- Finalize new element------------------------------------------ */
+    for(p = pk1, pk = pk1; pk < pk2; pk++)   /* finalize Lk */
+    {
+      i = Ci[pk];
+      if((nvi = -nv[i]) <= 0) continue;/* skip if i is dead */
+      nv[i] = nvi;                      /* restore nv[i] */
+      d = degree[i] + dk - nvi;         /* compute external degree(i) */
+      d = std::min<StorageIndex> (d, n - nel - nvi);
+      if(head[d] != -1) last[head[d]] = i;
+      next[i] = head[d];               /* put i back in degree list */
+      last[i] = -1;
+      head[d] = i;
+      mindeg = std::min<StorageIndex> (mindeg, d);       /* find new minimum degree */
+      degree[i] = d;
+      Ci[p++] = i;                      /* place i in Lk */
+    }
+    nv[k] = nvk;                      /* # nodes absorbed into k */
+    if((len[k] = p-pk1) == 0)         /* length of adj list of element k*/
+    {
+      Cp[k] = -1;                   /* k is a root of the tree */
+      w[k] = 0;                     /* k is now a dead element */
+    }
+    if(elenk != 0) cnz = p;           /* free unused space in Lk */
+  }
+  
+  /* --- Postordering ----------------------------------------------------- */
+  for(i = 0; i < n; i++) Cp[i] = amd_flip (Cp[i]);/* fix assembly tree */
+  for(j = 0; j <= n; j++) head[j] = -1;
+  for(j = n; j >= 0; j--)              /* place unordered nodes in lists */
+  {
+    if(nv[j] > 0) continue;          /* skip if j is an element */
+    next[j] = head[Cp[j]];          /* place j in list of its parent */
+    head[Cp[j]] = j;
+  }
+  for(e = n; e >= 0; e--)              /* place elements in lists */
+  {
+    if(nv[e] <= 0) continue;         /* skip unless e is an element */
+    if(Cp[e] != -1)
+    {
+      next[e] = head[Cp[e]];      /* place e in list of its parent */
+      head[Cp[e]] = e;
+    }
+  }
+  for(k = 0, i = 0; i <= n; i++)       /* postorder the assembly tree */
+  {
+    if(Cp[i] == -1) k = internal::cs_tdfs<StorageIndex>(i, k, head, next, perm.indices().data(), w);
+  }
+  
+  perm.indices().conservativeResize(n);
+}
+
+} // namespace internal
+
+} // end namespace Eigen
+
+#endif // EIGEN_SPARSE_AMD_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/OrderingMethods/Eigen_Colamd.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/OrderingMethods/Eigen_Colamd.h
new file mode 100644
index 0000000..8e339a7
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/OrderingMethods/Eigen_Colamd.h
@@ -0,0 +1,1863 @@
+// // This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2012 Desire Nuentsa Wakam <desire.nuentsa_wakam@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+// This file is modified from the colamd/symamd library. The copyright is below
+
+//   The authors of the code itself are Stefan I. Larimore and Timothy A.
+//   Davis (davis@cise.ufl.edu), University of Florida.  The algorithm was
+//   developed in collaboration with John Gilbert, Xerox PARC, and Esmond
+//   Ng, Oak Ridge National Laboratory.
+//
+//     Date:
+//
+//   September 8, 2003.  Version 2.3.
+//
+//     Acknowledgements:
+//
+//   This work was supported by the National Science Foundation, under
+//   grants DMS-9504974 and DMS-9803599.
+//
+//     Notice:
+//
+//   Copyright (c) 1998-2003 by the University of Florida.
+//   All Rights Reserved.
+//
+//   THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY
+//   EXPRESSED OR IMPLIED.  ANY USE IS AT YOUR OWN RISK.
+//
+//   Permission is hereby granted to use, copy, modify, and/or distribute
+//   this program, provided that the Copyright, this License, and the
+//   Availability of the original version is retained on all copies and made
+//   accessible to the end-user of any code or package that includes COLAMD
+//   or any modified version of COLAMD.
+//
+//     Availability:
+//
+//   The colamd/symamd library is available at
+//
+//       http://www.suitesparse.com
+
+
+#ifndef EIGEN_COLAMD_H
+#define EIGEN_COLAMD_H
+
+namespace internal {
+
+namespace Colamd {
+
+/* Ensure that debugging is turned off: */
+#ifndef COLAMD_NDEBUG
+#define COLAMD_NDEBUG
+#endif /* NDEBUG */
+
+
+/* ========================================================================== */
+/* === Knob and statistics definitions ====================================== */
+/* ========================================================================== */
+
+/* size of the knobs [ ] array.  Only knobs [0..1] are currently used. */
+const int NKnobs = 20;
+
+/* number of output statistics.  Only stats [0..6] are currently used. */
+const int NStats = 20;
+
+/* Indices into knobs and stats array. */
+enum KnobsStatsIndex {
+  /* knobs [0] and stats [0]: dense row knob and output statistic. */
+  DenseRow = 0,
+
+  /* knobs [1] and stats [1]: dense column knob and output statistic. */
+  DenseCol = 1,
+
+  /* stats [2]: memory defragmentation count output statistic */
+  DefragCount = 2,
+
+  /* stats [3]: colamd status:  zero OK, > 0 warning or notice, < 0 error */
+  Status = 3,
+
+  /* stats [4..6]: error info, or info on jumbled columns */
+  Info1 = 4,
+  Info2 = 5,
+  Info3 = 6
+};
+
+/* error codes returned in stats [3]: */
+enum Status {
+  Ok = 0,
+  OkButJumbled = 1,
+  ErrorANotPresent = -1,
+  ErrorPNotPresent = -2,
+  ErrorNrowNegative = -3,
+  ErrorNcolNegative = -4,
+  ErrorNnzNegative = -5,
+  ErrorP0Nonzero = -6,
+  ErrorATooSmall = -7,
+  ErrorColLengthNegative = -8,
+  ErrorRowIndexOutOfBounds = -9,
+  ErrorOutOfMemory = -10,
+  ErrorInternalError = -999
+};
+/* ========================================================================== */
+/* === Definitions ========================================================== */
+/* ========================================================================== */
+
+template <typename IndexType>
+IndexType ones_complement(const IndexType r) {
+  return (-(r)-1);
+}
+
+/* -------------------------------------------------------------------------- */
+const int Empty = -1;
+
+/* Row and column status */
+enum RowColumnStatus {
+  Alive = 0,
+  Dead = -1
+};
+
+/* Column status */
+enum ColumnStatus {
+  DeadPrincipal = -1,
+  DeadNonPrincipal = -2
+};
+
+/* ========================================================================== */
+/* === Colamd reporting mechanism =========================================== */
+/* ========================================================================== */
+
+// == Row and Column structures ==
+template <typename IndexType>
+struct ColStructure
+{
+  IndexType start ;   /* index for A of first row in this column, or Dead */
+  /* if column is dead */
+  IndexType length ;  /* number of rows in this column */
+  union
+  {
+    IndexType thickness ; /* number of original columns represented by this */
+    /* col, if the column is alive */
+    IndexType parent ;  /* parent in parent tree super-column structure, if */
+    /* the column is dead */
+  } shared1 ;
+  union
+  {
+    IndexType score ; /* the score used to maintain heap, if col is alive */
+    IndexType order ; /* pivot ordering of this column, if col is dead */
+  } shared2 ;
+  union
+  {
+    IndexType headhash ;  /* head of a hash bucket, if col is at the head of */
+    /* a degree list */
+    IndexType hash ;  /* hash value, if col is not in a degree list */
+    IndexType prev ;  /* previous column in degree list, if col is in a */
+    /* degree list (but not at the head of a degree list) */
+  } shared3 ;
+  union
+  {
+    IndexType degree_next ; /* next column, if col is in a degree list */
+    IndexType hash_next ;   /* next column, if col is in a hash list */
+  } shared4 ;
+
+  inline bool is_dead() const { return start < Alive; }
+
+  inline bool is_alive() const { return start >= Alive; }
+
+  inline bool is_dead_principal() const { return start == DeadPrincipal; }
+
+  inline void kill_principal() { start = DeadPrincipal; }
+
+  inline void kill_non_principal() { start = DeadNonPrincipal; }
+
+};
+
+template <typename IndexType>
+struct RowStructure
+{
+  IndexType start ;   /* index for A of first col in this row */
+  IndexType length ;  /* number of principal columns in this row */
+  union
+  {
+    IndexType degree ;  /* number of principal & non-principal columns in row */
+    IndexType p ;   /* used as a row pointer in init_rows_cols () */
+  } shared1 ;
+  union
+  {
+    IndexType mark ;  /* for computing set differences and marking dead rows*/
+    IndexType first_column ;/* first column in row (used in garbage collection) */
+  } shared2 ;
+
+  inline bool is_dead() const { return shared2.mark < Alive; }
+
+  inline bool is_alive() const { return shared2.mark >= Alive; }
+
+  inline void kill() { shared2.mark = Dead; }
+
+};
+
+/* ========================================================================== */
+/* === Colamd recommended memory size ======================================= */
+/* ========================================================================== */
+
+/*
+  The recommended length Alen of the array A passed to colamd is given by
+  the COLAMD_RECOMMENDED (nnz, n_row, n_col) macro.  It returns -1 if any
+  argument is negative.  2*nnz space is required for the row and column
+  indices of the matrix. colamd_c (n_col) + colamd_r (n_row) space is
+  required for the Col and Row arrays, respectively, which are internal to
+  colamd.  An additional n_col space is the minimal amount of "elbow room",
+  and nnz/5 more space is recommended for run time efficiency.
+
+  This macro is not needed when using symamd.
+
+  Explicit typecast to IndexType added Sept. 23, 2002, COLAMD version 2.2, to avoid
+  gcc -pedantic warning messages.
+*/
+template <typename IndexType>
+inline IndexType colamd_c(IndexType n_col)
+{ return IndexType( ((n_col) + 1) * sizeof (ColStructure<IndexType>) / sizeof (IndexType) ) ; }
+
+template <typename IndexType>
+inline IndexType  colamd_r(IndexType n_row)
+{ return IndexType(((n_row) + 1) * sizeof (RowStructure<IndexType>) / sizeof (IndexType)); }
+
+// Prototypes of non-user callable routines
+template <typename IndexType>
+static IndexType init_rows_cols (IndexType n_row, IndexType n_col, RowStructure<IndexType> Row [], ColStructure<IndexType> col [], IndexType A [], IndexType p [], IndexType stats[NStats] );
+
+template <typename IndexType>
+static void init_scoring (IndexType n_row, IndexType n_col, RowStructure<IndexType> Row [], ColStructure<IndexType> Col [], IndexType A [], IndexType head [], double knobs[NKnobs], IndexType *p_n_row2, IndexType *p_n_col2, IndexType *p_max_deg);
+
+template <typename IndexType>
+static IndexType find_ordering (IndexType n_row, IndexType n_col, IndexType Alen, RowStructure<IndexType> Row [], ColStructure<IndexType> Col [], IndexType A [], IndexType head [], IndexType n_col2, IndexType max_deg, IndexType pfree);
+
+template <typename IndexType>
+static void order_children (IndexType n_col, ColStructure<IndexType> Col [], IndexType p []);
+
+template <typename IndexType>
+static void detect_super_cols (ColStructure<IndexType> Col [], IndexType A [], IndexType head [], IndexType row_start, IndexType row_length ) ;
+
+template <typename IndexType>
+static IndexType garbage_collection (IndexType n_row, IndexType n_col, RowStructure<IndexType> Row [], ColStructure<IndexType> Col [], IndexType A [], IndexType *pfree) ;
+
+template <typename IndexType>
+static inline  IndexType clear_mark (IndexType n_row, RowStructure<IndexType> Row [] ) ;
+
+/* === No debugging ========================================================= */
+
+#define COLAMD_DEBUG0(params) ;
+#define COLAMD_DEBUG1(params) ;
+#define COLAMD_DEBUG2(params) ;
+#define COLAMD_DEBUG3(params) ;
+#define COLAMD_DEBUG4(params) ;
+
+#define COLAMD_ASSERT(expression) ((void) 0)
+
+
+/**
+ * \brief Returns the recommended value of Alen
+ *
+ * Returns recommended value of Alen for use by colamd.
+ * Returns -1 if any input argument is negative.
+ * The use of this routine or macro is optional.
+ * Note that the macro uses its arguments   more than once,
+ * so be careful for side effects, if you pass expressions as arguments to COLAMD_RECOMMENDED.
+ *
+ * \param nnz nonzeros in A
+ * \param n_row number of rows in A
+ * \param n_col number of columns in A
+ * \return recommended value of Alen for use by colamd
+ */
+template <typename IndexType>
+inline IndexType recommended ( IndexType nnz, IndexType n_row, IndexType n_col)
+{
+  if ((nnz) < 0 || (n_row) < 0 || (n_col) < 0)
+    return (-1);
+  else
+    return (2 * (nnz) + colamd_c (n_col) + colamd_r (n_row) + (n_col) + ((nnz) / 5));
+}
+
+/**
+ * \brief set default parameters  The use of this routine is optional.
+ *
+ * Colamd: rows with more than (knobs [DenseRow] * n_col)
+ * entries are removed prior to ordering.  Columns with more than
+ * (knobs [DenseCol] * n_row) entries are removed prior to
+ * ordering, and placed last in the output column ordering.
+ *
+ * DenseRow and DenseCol are defined as 0 and 1,
+ * respectively, in colamd.h.  Default values of these two knobs
+ * are both 0.5.  Currently, only knobs [0] and knobs [1] are
+ * used, but future versions may use more knobs.  If so, they will
+ * be properly set to their defaults by the future version of
+ * colamd_set_defaults, so that the code that calls colamd will
+ * not need to change, assuming that you either use
+ * colamd_set_defaults, or pass a (double *) NULL pointer as the
+ * knobs array to colamd or symamd.
+ *
+ * \param knobs parameter settings for colamd
+ */
+
+static inline void set_defaults(double knobs[NKnobs])
+{
+  /* === Local variables ================================================== */
+
+  int i ;
+
+  if (!knobs)
+  {
+    return ;      /* no knobs to initialize */
+  }
+  for (i = 0 ; i < NKnobs ; i++)
+  {
+    knobs [i] = 0 ;
+  }
+  knobs [Colamd::DenseRow] = 0.5 ;  /* ignore rows over 50% dense */
+  knobs [Colamd::DenseCol] = 0.5 ;  /* ignore columns over 50% dense */
+}
+
+/**
+ * \brief  Computes a column ordering using the column approximate minimum degree ordering
+ *
+ * Computes a column ordering (Q) of A such that P(AQ)=LU or
+ * (AQ)'AQ=LL' have less fill-in and require fewer floating point
+ * operations than factorizing the unpermuted matrix A or A'A,
+ * respectively.
+ *
+ *
+ * \param n_row number of rows in A
+ * \param n_col number of columns in A
+ * \param Alen, size of the array A
+ * \param A row indices of the matrix, of size ALen
+ * \param p column pointers of A, of size n_col+1
+ * \param knobs parameter settings for colamd
+ * \param stats colamd output statistics and error codes
+ */
+template <typename IndexType>
+static bool compute_ordering(IndexType n_row, IndexType n_col, IndexType Alen, IndexType *A, IndexType *p, double knobs[NKnobs], IndexType stats[NStats])
+{
+  /* === Local variables ================================================== */
+
+  IndexType i ;     /* loop index */
+  IndexType nnz ;     /* nonzeros in A */
+  IndexType Row_size ;    /* size of Row [], in integers */
+  IndexType Col_size ;    /* size of Col [], in integers */
+  IndexType need ;      /* minimum required length of A */
+  Colamd::RowStructure<IndexType> *Row ;   /* pointer into A of Row [0..n_row] array */
+  Colamd::ColStructure<IndexType> *Col ;   /* pointer into A of Col [0..n_col] array */
+  IndexType n_col2 ;    /* number of non-dense, non-empty columns */
+  IndexType n_row2 ;    /* number of non-dense, non-empty rows */
+  IndexType ngarbage ;    /* number of garbage collections performed */
+  IndexType max_deg ;   /* maximum row degree */
+  double default_knobs [NKnobs] ; /* default knobs array */
+
+
+  /* === Check the input arguments ======================================== */
+
+  if (!stats)
+  {
+    COLAMD_DEBUG0 (("colamd: stats not present\n")) ;
+    return (false) ;
+  }
+  for (i = 0 ; i < NStats ; i++)
+  {
+    stats [i] = 0 ;
+  }
+  stats [Colamd::Status] = Colamd::Ok ;
+  stats [Colamd::Info1] = -1 ;
+  stats [Colamd::Info2] = -1 ;
+
+  if (!A)   /* A is not present */
+  {
+    stats [Colamd::Status] = Colamd::ErrorANotPresent ;
+    COLAMD_DEBUG0 (("colamd: A not present\n")) ;
+    return (false) ;
+  }
+
+  if (!p)   /* p is not present */
+  {
+    stats [Colamd::Status] = Colamd::ErrorPNotPresent ;
+    COLAMD_DEBUG0 (("colamd: p not present\n")) ;
+    return (false) ;
+  }
+
+  if (n_row < 0)  /* n_row must be >= 0 */
+  {
+    stats [Colamd::Status] = Colamd::ErrorNrowNegative ;
+    stats [Colamd::Info1] = n_row ;
+    COLAMD_DEBUG0 (("colamd: nrow negative %d\n", n_row)) ;
+    return (false) ;
+  }
+
+  if (n_col < 0)  /* n_col must be >= 0 */
+  {
+    stats [Colamd::Status] = Colamd::ErrorNcolNegative ;
+    stats [Colamd::Info1] = n_col ;
+    COLAMD_DEBUG0 (("colamd: ncol negative %d\n", n_col)) ;
+    return (false) ;
+  }
+
+  nnz = p [n_col] ;
+  if (nnz < 0)  /* nnz must be >= 0 */
+  {
+    stats [Colamd::Status] = Colamd::ErrorNnzNegative ;
+    stats [Colamd::Info1] = nnz ;
+    COLAMD_DEBUG0 (("colamd: number of entries negative %d\n", nnz)) ;
+    return (false) ;
+  }
+
+  if (p [0] != 0)
+  {
+    stats [Colamd::Status] = Colamd::ErrorP0Nonzero ;
+    stats [Colamd::Info1] = p [0] ;
+    COLAMD_DEBUG0 (("colamd: p[0] not zero %d\n", p [0])) ;
+    return (false) ;
+  }
+
+  /* === If no knobs, set default knobs =================================== */
+
+  if (!knobs)
+  {
+    set_defaults (default_knobs) ;
+    knobs = default_knobs ;
+  }
+
+  /* === Allocate the Row and Col arrays from array A ===================== */
+
+  Col_size = colamd_c (n_col) ;
+  Row_size = colamd_r (n_row) ;
+  need = 2*nnz + n_col + Col_size + Row_size ;
+
+  if (need > Alen)
+  {
+    /* not enough space in array A to perform the ordering */
+    stats [Colamd::Status] = Colamd::ErrorATooSmall ;
+    stats [Colamd::Info1] = need ;
+    stats [Colamd::Info2] = Alen ;
+    COLAMD_DEBUG0 (("colamd: Need Alen >= %d, given only Alen = %d\n", need,Alen));
+    return (false) ;
+  }
+
+  Alen -= Col_size + Row_size ;
+  Col = (ColStructure<IndexType> *) &A [Alen] ;
+  Row = (RowStructure<IndexType> *) &A [Alen + Col_size] ;
+
+  /* === Construct the row and column data structures ===================== */
+
+  if (!Colamd::init_rows_cols (n_row, n_col, Row, Col, A, p, stats))
+  {
+    /* input matrix is invalid */
+    COLAMD_DEBUG0 (("colamd: Matrix invalid\n")) ;
+    return (false) ;
+  }
+
+  /* === Initialize scores, kill dense rows/columns ======================= */
+
+  Colamd::init_scoring (n_row, n_col, Row, Col, A, p, knobs,
+		&n_row2, &n_col2, &max_deg) ;
+
+  /* === Order the supercolumns =========================================== */
+
+  ngarbage = Colamd::find_ordering (n_row, n_col, Alen, Row, Col, A, p,
+			    n_col2, max_deg, 2*nnz) ;
+
+  /* === Order the non-principal columns ================================== */
+
+  Colamd::order_children (n_col, Col, p) ;
+
+  /* === Return statistics in stats ======================================= */
+
+  stats [Colamd::DenseRow] = n_row - n_row2 ;
+  stats [Colamd::DenseCol] = n_col - n_col2 ;
+  stats [Colamd::DefragCount] = ngarbage ;
+  COLAMD_DEBUG0 (("colamd: done.\n")) ;
+  return (true) ;
+}
+
+/* ========================================================================== */
+/* === NON-USER-CALLABLE ROUTINES: ========================================== */
+/* ========================================================================== */
+
+/* There are no user-callable routines beyond this point in the file */
+
+/* ========================================================================== */
+/* === init_rows_cols ======================================================= */
+/* ========================================================================== */
+
+/*
+  Takes the column form of the matrix in A and creates the row form of the
+  matrix.  Also, row and column attributes are stored in the Col and Row
+  structs.  If the columns are un-sorted or contain duplicate row indices,
+  this routine will also sort and remove duplicate row indices from the
+  column form of the matrix.  Returns false if the matrix is invalid,
+  true otherwise.  Not user-callable.
+*/
+template <typename IndexType>
+static IndexType init_rows_cols  /* returns true if OK, or false otherwise */
+  (
+    /* === Parameters ======================================================= */
+
+    IndexType n_row,      /* number of rows of A */
+    IndexType n_col,      /* number of columns of A */
+    RowStructure<IndexType> Row [],    /* of size n_row+1 */
+    ColStructure<IndexType> Col [],    /* of size n_col+1 */
+    IndexType A [],     /* row indices of A, of size Alen */
+    IndexType p [],     /* pointers to columns in A, of size n_col+1 */
+    IndexType stats [NStats]  /* colamd statistics */
+    )
+{
+  /* === Local variables ================================================== */
+
+  IndexType col ;     /* a column index */
+  IndexType row ;     /* a row index */
+  IndexType *cp ;     /* a column pointer */
+  IndexType *cp_end ;   /* a pointer to the end of a column */
+  IndexType *rp ;     /* a row pointer */
+  IndexType *rp_end ;   /* a pointer to the end of a row */
+  IndexType last_row ;    /* previous row */
+
+  /* === Initialize columns, and check column pointers ==================== */
+
+  for (col = 0 ; col < n_col ; col++)
+  {
+    Col [col].start = p [col] ;
+    Col [col].length = p [col+1] - p [col] ;
+
+    if ((Col [col].length) < 0) // extra parentheses to work-around gcc bug 10200
+    {
+      /* column pointers must be non-decreasing */
+      stats [Colamd::Status] = Colamd::ErrorColLengthNegative ;
+      stats [Colamd::Info1] = col ;
+      stats [Colamd::Info2] = Col [col].length ;
+      COLAMD_DEBUG0 (("colamd: col %d length %d < 0\n", col, Col [col].length)) ;
+      return (false) ;
+    }
+
+    Col [col].shared1.thickness = 1 ;
+    Col [col].shared2.score = 0 ;
+    Col [col].shared3.prev = Empty ;
+    Col [col].shared4.degree_next = Empty ;
+  }
+
+  /* p [0..n_col] no longer needed, used as "head" in subsequent routines */
+
+  /* === Scan columns, compute row degrees, and check row indices ========= */
+
+  stats [Info3] = 0 ;  /* number of duplicate or unsorted row indices*/
+
+  for (row = 0 ; row < n_row ; row++)
+  {
+    Row [row].length = 0 ;
+    Row [row].shared2.mark = -1 ;
+  }
+
+  for (col = 0 ; col < n_col ; col++)
+  {
+    last_row = -1 ;
+
+    cp = &A [p [col]] ;
+    cp_end = &A [p [col+1]] ;
+
+    while (cp < cp_end)
+    {
+      row = *cp++ ;
+
+      /* make sure row indices within range */
+      if (row < 0 || row >= n_row)
+      {
+	stats [Colamd::Status] = Colamd::ErrorRowIndexOutOfBounds ;
+	stats [Colamd::Info1] = col ;
+	stats [Colamd::Info2] = row ;
+	stats [Colamd::Info3] = n_row ;
+	COLAMD_DEBUG0 (("colamd: row %d col %d out of bounds\n", row, col)) ;
+	return (false) ;
+      }
+
+      if (row <= last_row || Row [row].shared2.mark == col)
+      {
+	/* row index are unsorted or repeated (or both), thus col */
+	/* is jumbled.  This is a notice, not an error condition. */
+	stats [Colamd::Status] = Colamd::OkButJumbled ;
+	stats [Colamd::Info1] = col ;
+	stats [Colamd::Info2] = row ;
+	(stats [Colamd::Info3]) ++ ;
+	COLAMD_DEBUG1 (("colamd: row %d col %d unsorted/duplicate\n",row,col));
+      }
+
+      if (Row [row].shared2.mark != col)
+      {
+	Row [row].length++ ;
+      }
+      else
+      {
+	/* this is a repeated entry in the column, */
+	/* it will be removed */
+	Col [col].length-- ;
+      }
+
+      /* mark the row as having been seen in this column */
+      Row [row].shared2.mark = col ;
+
+      last_row = row ;
+    }
+  }
+
+  /* === Compute row pointers ============================================= */
+
+  /* row form of the matrix starts directly after the column */
+  /* form of matrix in A */
+  Row [0].start = p [n_col] ;
+  Row [0].shared1.p = Row [0].start ;
+  Row [0].shared2.mark = -1 ;
+  for (row = 1 ; row < n_row ; row++)
+  {
+    Row [row].start = Row [row-1].start + Row [row-1].length ;
+    Row [row].shared1.p = Row [row].start ;
+    Row [row].shared2.mark = -1 ;
+  }
+
+  /* === Create row form ================================================== */
+
+  if (stats [Status] == OkButJumbled)
+  {
+    /* if cols jumbled, watch for repeated row indices */
+    for (col = 0 ; col < n_col ; col++)
+    {
+      cp = &A [p [col]] ;
+      cp_end = &A [p [col+1]] ;
+      while (cp < cp_end)
+      {
+	row = *cp++ ;
+	if (Row [row].shared2.mark != col)
+	{
+	  A [(Row [row].shared1.p)++] = col ;
+	  Row [row].shared2.mark = col ;
+	}
+      }
+    }
+  }
+  else
+  {
+    /* if cols not jumbled, we don't need the mark (this is faster) */
+    for (col = 0 ; col < n_col ; col++)
+    {
+      cp = &A [p [col]] ;
+      cp_end = &A [p [col+1]] ;
+      while (cp < cp_end)
+      {
+	A [(Row [*cp++].shared1.p)++] = col ;
+      }
+    }
+  }
+
+  /* === Clear the row marks and set row degrees ========================== */
+
+  for (row = 0 ; row < n_row ; row++)
+  {
+    Row [row].shared2.mark = 0 ;
+    Row [row].shared1.degree = Row [row].length ;
+  }
+
+  /* === See if we need to re-create columns ============================== */
+
+  if (stats [Status] == OkButJumbled)
+  {
+    COLAMD_DEBUG0 (("colamd: reconstructing column form, matrix jumbled\n")) ;
+
+
+    /* === Compute col pointers ========================================= */
+
+    /* col form of the matrix starts at A [0]. */
+    /* Note, we may have a gap between the col form and the row */
+    /* form if there were duplicate entries, if so, it will be */
+    /* removed upon the first garbage collection */
+    Col [0].start = 0 ;
+    p [0] = Col [0].start ;
+    for (col = 1 ; col < n_col ; col++)
+    {
+      /* note that the lengths here are for pruned columns, i.e. */
+      /* no duplicate row indices will exist for these columns */
+      Col [col].start = Col [col-1].start + Col [col-1].length ;
+      p [col] = Col [col].start ;
+    }
+
+    /* === Re-create col form =========================================== */
+
+    for (row = 0 ; row < n_row ; row++)
+    {
+      rp = &A [Row [row].start] ;
+      rp_end = rp + Row [row].length ;
+      while (rp < rp_end)
+      {
+	A [(p [*rp++])++] = row ;
+      }
+    }
+  }
+
+  /* === Done.  Matrix is not (or no longer) jumbled ====================== */
+
+  return (true) ;
+}
+
+
+/* ========================================================================== */
+/* === init_scoring ========================================================= */
+/* ========================================================================== */
+
+/*
+  Kills dense or empty columns and rows, calculates an initial score for
+  each column, and places all columns in the degree lists.  Not user-callable.
+*/
+template <typename IndexType>
+static void init_scoring
+  (
+    /* === Parameters ======================================================= */
+
+    IndexType n_row,      /* number of rows of A */
+    IndexType n_col,      /* number of columns of A */
+    RowStructure<IndexType> Row [],    /* of size n_row+1 */
+    ColStructure<IndexType> Col [],    /* of size n_col+1 */
+    IndexType A [],     /* column form and row form of A */
+    IndexType head [],    /* of size n_col+1 */
+    double knobs [NKnobs],/* parameters */
+    IndexType *p_n_row2,    /* number of non-dense, non-empty rows */
+    IndexType *p_n_col2,    /* number of non-dense, non-empty columns */
+    IndexType *p_max_deg    /* maximum row degree */
+    )
+{
+  /* === Local variables ================================================== */
+
+  IndexType c ;     /* a column index */
+  IndexType r, row ;    /* a row index */
+  IndexType *cp ;     /* a column pointer */
+  IndexType deg ;     /* degree of a row or column */
+  IndexType *cp_end ;   /* a pointer to the end of a column */
+  IndexType *new_cp ;   /* new column pointer */
+  IndexType col_length ;    /* length of pruned column */
+  IndexType score ;     /* current column score */
+  IndexType n_col2 ;    /* number of non-dense, non-empty columns */
+  IndexType n_row2 ;    /* number of non-dense, non-empty rows */
+  IndexType dense_row_count ; /* remove rows with more entries than this */
+  IndexType dense_col_count ; /* remove cols with more entries than this */
+  IndexType min_score ;   /* smallest column score */
+  IndexType max_deg ;   /* maximum row degree */
+  IndexType next_col ;    /* Used to add to degree list.*/
+
+
+  /* === Extract knobs ==================================================== */
+
+  dense_row_count = numext::maxi(IndexType(0), numext::mini(IndexType(knobs [Colamd::DenseRow] * n_col), n_col)) ;
+  dense_col_count = numext::maxi(IndexType(0), numext::mini(IndexType(knobs [Colamd::DenseCol] * n_row), n_row)) ;
+  COLAMD_DEBUG1 (("colamd: densecount: %d %d\n", dense_row_count, dense_col_count)) ;
+  max_deg = 0 ;
+  n_col2 = n_col ;
+  n_row2 = n_row ;
+
+  /* === Kill empty columns =============================================== */
+
+  /* Put the empty columns at the end in their natural order, so that LU */
+  /* factorization can proceed as far as possible. */
+  for (c = n_col-1 ; c >= 0 ; c--)
+  {
+    deg = Col [c].length ;
+    if (deg == 0)
+    {
+      /* this is a empty column, kill and order it last */
+      Col [c].shared2.order = --n_col2 ;
+      Col[c].kill_principal() ;
+    }
+  }
+  COLAMD_DEBUG1 (("colamd: null columns killed: %d\n", n_col - n_col2)) ;
+
+  /* === Kill dense columns =============================================== */
+
+  /* Put the dense columns at the end, in their natural order */
+  for (c = n_col-1 ; c >= 0 ; c--)
+  {
+    /* skip any dead columns */
+    if (Col[c].is_dead())
+    {
+      continue ;
+    }
+    deg = Col [c].length ;
+    if (deg > dense_col_count)
+    {
+      /* this is a dense column, kill and order it last */
+      Col [c].shared2.order = --n_col2 ;
+      /* decrement the row degrees */
+      cp = &A [Col [c].start] ;
+      cp_end = cp + Col [c].length ;
+      while (cp < cp_end)
+      {
+	Row [*cp++].shared1.degree-- ;
+      }
+      Col[c].kill_principal() ;
+    }
+  }
+  COLAMD_DEBUG1 (("colamd: Dense and null columns killed: %d\n", n_col - n_col2)) ;
+
+  /* === Kill dense and empty rows ======================================== */
+
+  for (r = 0 ; r < n_row ; r++)
+  {
+    deg = Row [r].shared1.degree ;
+    COLAMD_ASSERT (deg >= 0 && deg <= n_col) ;
+    if (deg > dense_row_count || deg == 0)
+    {
+      /* kill a dense or empty row */
+      Row[r].kill() ;
+      --n_row2 ;
+    }
+    else
+    {
+      /* keep track of max degree of remaining rows */
+      max_deg = numext::maxi(max_deg, deg) ;
+    }
+  }
+  COLAMD_DEBUG1 (("colamd: Dense and null rows killed: %d\n", n_row - n_row2)) ;
+
+  /* === Compute initial column scores ==================================== */
+
+  /* At this point the row degrees are accurate.  They reflect the number */
+  /* of "live" (non-dense) columns in each row.  No empty rows exist. */
+  /* Some "live" columns may contain only dead rows, however.  These are */
+  /* pruned in the code below. */
+
+  /* now find the initial matlab score for each column */
+  for (c = n_col-1 ; c >= 0 ; c--)
+  {
+    /* skip dead column */
+    if (Col[c].is_dead())
+    {
+      continue ;
+    }
+    score = 0 ;
+    cp = &A [Col [c].start] ;
+    new_cp = cp ;
+    cp_end = cp + Col [c].length ;
+    while (cp < cp_end)
+    {
+      /* get a row */
+      row = *cp++ ;
+      /* skip if dead */
+      if (Row[row].is_dead())
+      {
+	continue ;
+      }
+      /* compact the column */
+      *new_cp++ = row ;
+      /* add row's external degree */
+      score += Row [row].shared1.degree - 1 ;
+      /* guard against integer overflow */
+      score = numext::mini(score, n_col) ;
+    }
+    /* determine pruned column length */
+    col_length = (IndexType) (new_cp - &A [Col [c].start]) ;
+    if (col_length == 0)
+    {
+      /* a newly-made null column (all rows in this col are "dense" */
+      /* and have already been killed) */
+      COLAMD_DEBUG2 (("Newly null killed: %d\n", c)) ;
+      Col [c].shared2.order = --n_col2 ;
+      Col[c].kill_principal() ;
+    }
+    else
+    {
+      /* set column length and set score */
+      COLAMD_ASSERT (score >= 0) ;
+      COLAMD_ASSERT (score <= n_col) ;
+      Col [c].length = col_length ;
+      Col [c].shared2.score = score ;
+    }
+  }
+  COLAMD_DEBUG1 (("colamd: Dense, null, and newly-null columns killed: %d\n",
+		  n_col-n_col2)) ;
+
+  /* At this point, all empty rows and columns are dead.  All live columns */
+  /* are "clean" (containing no dead rows) and simplicial (no supercolumns */
+  /* yet).  Rows may contain dead columns, but all live rows contain at */
+  /* least one live column. */
+
+  /* === Initialize degree lists ========================================== */
+
+
+  /* clear the hash buckets */
+  for (c = 0 ; c <= n_col ; c++)
+  {
+    head [c] = Empty ;
+  }
+  min_score = n_col ;
+  /* place in reverse order, so low column indices are at the front */
+  /* of the lists.  This is to encourage natural tie-breaking */
+  for (c = n_col-1 ; c >= 0 ; c--)
+  {
+    /* only add principal columns to degree lists */
+    if (Col[c].is_alive())
+    {
+      COLAMD_DEBUG4 (("place %d score %d minscore %d ncol %d\n",
+		      c, Col [c].shared2.score, min_score, n_col)) ;
+
+      /* === Add columns score to DList =============================== */
+
+      score = Col [c].shared2.score ;
+
+      COLAMD_ASSERT (min_score >= 0) ;
+      COLAMD_ASSERT (min_score <= n_col) ;
+      COLAMD_ASSERT (score >= 0) ;
+      COLAMD_ASSERT (score <= n_col) ;
+      COLAMD_ASSERT (head [score] >= Empty) ;
+
+      /* now add this column to dList at proper score location */
+      next_col = head [score] ;
+      Col [c].shared3.prev = Empty ;
+      Col [c].shared4.degree_next = next_col ;
+
+      /* if there already was a column with the same score, set its */
+      /* previous pointer to this new column */
+      if (next_col != Empty)
+      {
+	Col [next_col].shared3.prev = c ;
+      }
+      head [score] = c ;
+
+      /* see if this score is less than current min */
+      min_score = numext::mini(min_score, score) ;
+
+
+    }
+  }
+
+
+  /* === Return number of remaining columns, and max row degree =========== */
+
+  *p_n_col2 = n_col2 ;
+  *p_n_row2 = n_row2 ;
+  *p_max_deg = max_deg ;
+}
+
+
+/* ========================================================================== */
+/* === find_ordering ======================================================== */
+/* ========================================================================== */
+
+/*
+  Order the principal columns of the supercolumn form of the matrix
+  (no supercolumns on input).  Uses a minimum approximate column minimum
+  degree ordering method.  Not user-callable.
+*/
+template <typename IndexType>
+static IndexType find_ordering /* return the number of garbage collections */
+  (
+    /* === Parameters ======================================================= */
+
+    IndexType n_row,      /* number of rows of A */
+    IndexType n_col,      /* number of columns of A */
+    IndexType Alen,     /* size of A, 2*nnz + n_col or larger */
+    RowStructure<IndexType> Row [],    /* of size n_row+1 */
+    ColStructure<IndexType> Col [],    /* of size n_col+1 */
+    IndexType A [],     /* column form and row form of A */
+    IndexType head [],    /* of size n_col+1 */
+    IndexType n_col2,     /* Remaining columns to order */
+    IndexType max_deg,    /* Maximum row degree */
+    IndexType pfree     /* index of first free slot (2*nnz on entry) */
+    )
+{
+  /* === Local variables ================================================== */
+
+  IndexType k ;     /* current pivot ordering step */
+  IndexType pivot_col ;   /* current pivot column */
+  IndexType *cp ;     /* a column pointer */
+  IndexType *rp ;     /* a row pointer */
+  IndexType pivot_row ;   /* current pivot row */
+  IndexType *new_cp ;   /* modified column pointer */
+  IndexType *new_rp ;   /* modified row pointer */
+  IndexType pivot_row_start ; /* pointer to start of pivot row */
+  IndexType pivot_row_degree ;  /* number of columns in pivot row */
+  IndexType pivot_row_length ;  /* number of supercolumns in pivot row */
+  IndexType pivot_col_score ; /* score of pivot column */
+  IndexType needed_memory ;   /* free space needed for pivot row */
+  IndexType *cp_end ;   /* pointer to the end of a column */
+  IndexType *rp_end ;   /* pointer to the end of a row */
+  IndexType row ;     /* a row index */
+  IndexType col ;     /* a column index */
+  IndexType max_score ;   /* maximum possible score */
+  IndexType cur_score ;   /* score of current column */
+  unsigned int hash ;   /* hash value for supernode detection */
+  IndexType head_column ;   /* head of hash bucket */
+  IndexType first_col ;   /* first column in hash bucket */
+  IndexType tag_mark ;    /* marker value for mark array */
+  IndexType row_mark ;    /* Row [row].shared2.mark */
+  IndexType set_difference ;  /* set difference size of row with pivot row */
+  IndexType min_score ;   /* smallest column score */
+  IndexType col_thickness ;   /* "thickness" (no. of columns in a supercol) */
+  IndexType max_mark ;    /* maximum value of tag_mark */
+  IndexType pivot_col_thickness ; /* number of columns represented by pivot col */
+  IndexType prev_col ;    /* Used by Dlist operations. */
+  IndexType next_col ;    /* Used by Dlist operations. */
+  IndexType ngarbage ;    /* number of garbage collections performed */
+
+
+  /* === Initialization and clear mark ==================================== */
+
+  max_mark = INT_MAX - n_col ;  /* INT_MAX defined in <limits.h> */
+  tag_mark = Colamd::clear_mark (n_row, Row) ;
+  min_score = 0 ;
+  ngarbage = 0 ;
+  COLAMD_DEBUG1 (("colamd: Ordering, n_col2=%d\n", n_col2)) ;
+
+  /* === Order the columns ================================================ */
+
+  for (k = 0 ; k < n_col2 ; /* 'k' is incremented below */)
+  {
+
+    /* === Select pivot column, and order it ============================ */
+
+    /* make sure degree list isn't empty */
+    COLAMD_ASSERT (min_score >= 0) ;
+    COLAMD_ASSERT (min_score <= n_col) ;
+    COLAMD_ASSERT (head [min_score] >= Empty) ;
+
+    /* get pivot column from head of minimum degree list */
+    while (min_score < n_col && head [min_score] == Empty)
+    {
+      min_score++ ;
+    }
+    pivot_col = head [min_score] ;
+    COLAMD_ASSERT (pivot_col >= 0 && pivot_col <= n_col) ;
+    next_col = Col [pivot_col].shared4.degree_next ;
+    head [min_score] = next_col ;
+    if (next_col != Empty)
+    {
+      Col [next_col].shared3.prev = Empty ;
+    }
+
+    COLAMD_ASSERT (Col[pivot_col].is_alive()) ;
+    COLAMD_DEBUG3 (("Pivot col: %d\n", pivot_col)) ;
+
+    /* remember score for defrag check */
+    pivot_col_score = Col [pivot_col].shared2.score ;
+
+    /* the pivot column is the kth column in the pivot order */
+    Col [pivot_col].shared2.order = k ;
+
+    /* increment order count by column thickness */
+    pivot_col_thickness = Col [pivot_col].shared1.thickness ;
+    k += pivot_col_thickness ;
+    COLAMD_ASSERT (pivot_col_thickness > 0) ;
+
+    /* === Garbage_collection, if necessary ============================= */
+
+    needed_memory = numext::mini(pivot_col_score, n_col - k) ;
+    if (pfree + needed_memory >= Alen)
+    {
+      pfree = Colamd::garbage_collection (n_row, n_col, Row, Col, A, &A [pfree]) ;
+      ngarbage++ ;
+      /* after garbage collection we will have enough */
+      COLAMD_ASSERT (pfree + needed_memory < Alen) ;
+      /* garbage collection has wiped out the Row[].shared2.mark array */
+      tag_mark = Colamd::clear_mark (n_row, Row) ;
+
+    }
+
+    /* === Compute pivot row pattern ==================================== */
+
+    /* get starting location for this new merged row */
+    pivot_row_start = pfree ;
+
+    /* initialize new row counts to zero */
+    pivot_row_degree = 0 ;
+
+    /* tag pivot column as having been visited so it isn't included */
+    /* in merged pivot row */
+    Col [pivot_col].shared1.thickness = -pivot_col_thickness ;
+
+    /* pivot row is the union of all rows in the pivot column pattern */
+    cp = &A [Col [pivot_col].start] ;
+    cp_end = cp + Col [pivot_col].length ;
+    while (cp < cp_end)
+    {
+      /* get a row */
+      row = *cp++ ;
+      COLAMD_DEBUG4 (("Pivot col pattern %d %d\n", Row[row].is_alive(), row)) ;
+      /* skip if row is dead */
+      if (Row[row].is_dead())
+      {
+	continue ;
+      }
+      rp = &A [Row [row].start] ;
+      rp_end = rp + Row [row].length ;
+      while (rp < rp_end)
+      {
+	/* get a column */
+	col = *rp++ ;
+	/* add the column, if alive and untagged */
+	col_thickness = Col [col].shared1.thickness ;
+	if (col_thickness > 0 && Col[col].is_alive())
+	{
+	  /* tag column in pivot row */
+	  Col [col].shared1.thickness = -col_thickness ;
+	  COLAMD_ASSERT (pfree < Alen) ;
+	  /* place column in pivot row */
+	  A [pfree++] = col ;
+	  pivot_row_degree += col_thickness ;
+	}
+      }
+    }
+
+    /* clear tag on pivot column */
+    Col [pivot_col].shared1.thickness = pivot_col_thickness ;
+    max_deg = numext::maxi(max_deg, pivot_row_degree) ;
+
+
+    /* === Kill all rows used to construct pivot row ==================== */
+
+    /* also kill pivot row, temporarily */
+    cp = &A [Col [pivot_col].start] ;
+    cp_end = cp + Col [pivot_col].length ;
+    while (cp < cp_end)
+    {
+      /* may be killing an already dead row */
+      row = *cp++ ;
+      COLAMD_DEBUG3 (("Kill row in pivot col: %d\n", row)) ;
+      Row[row].kill() ;
+    }
+
+    /* === Select a row index to use as the new pivot row =============== */
+
+    pivot_row_length = pfree - pivot_row_start ;
+    if (pivot_row_length > 0)
+    {
+      /* pick the "pivot" row arbitrarily (first row in col) */
+      pivot_row = A [Col [pivot_col].start] ;
+      COLAMD_DEBUG3 (("Pivotal row is %d\n", pivot_row)) ;
+    }
+    else
+    {
+      /* there is no pivot row, since it is of zero length */
+      pivot_row = Empty ;
+      COLAMD_ASSERT (pivot_row_length == 0) ;
+    }
+    COLAMD_ASSERT (Col [pivot_col].length > 0 || pivot_row_length == 0) ;
+
+    /* === Approximate degree computation =============================== */
+
+    /* Here begins the computation of the approximate degree.  The column */
+    /* score is the sum of the pivot row "length", plus the size of the */
+    /* set differences of each row in the column minus the pattern of the */
+    /* pivot row itself.  The column ("thickness") itself is also */
+    /* excluded from the column score (we thus use an approximate */
+    /* external degree). */
+
+    /* The time taken by the following code (compute set differences, and */
+    /* add them up) is proportional to the size of the data structure */
+    /* being scanned - that is, the sum of the sizes of each column in */
+    /* the pivot row.  Thus, the amortized time to compute a column score */
+    /* is proportional to the size of that column (where size, in this */
+    /* context, is the column "length", or the number of row indices */
+    /* in that column).  The number of row indices in a column is */
+    /* monotonically non-decreasing, from the length of the original */
+    /* column on input to colamd. */
+
+    /* === Compute set differences ====================================== */
+
+    COLAMD_DEBUG3 (("** Computing set differences phase. **\n")) ;
+
+    /* pivot row is currently dead - it will be revived later. */
+
+    COLAMD_DEBUG3 (("Pivot row: ")) ;
+    /* for each column in pivot row */
+    rp = &A [pivot_row_start] ;
+    rp_end = rp + pivot_row_length ;
+    while (rp < rp_end)
+    {
+      col = *rp++ ;
+      COLAMD_ASSERT (Col[col].is_alive() && col != pivot_col) ;
+      COLAMD_DEBUG3 (("Col: %d\n", col)) ;
+
+      /* clear tags used to construct pivot row pattern */
+      col_thickness = -Col [col].shared1.thickness ;
+      COLAMD_ASSERT (col_thickness > 0) ;
+      Col [col].shared1.thickness = col_thickness ;
+
+      /* === Remove column from degree list =========================== */
+
+      cur_score = Col [col].shared2.score ;
+      prev_col = Col [col].shared3.prev ;
+      next_col = Col [col].shared4.degree_next ;
+      COLAMD_ASSERT (cur_score >= 0) ;
+      COLAMD_ASSERT (cur_score <= n_col) ;
+      COLAMD_ASSERT (cur_score >= Empty) ;
+      if (prev_col == Empty)
+      {
+	head [cur_score] = next_col ;
+      }
+      else
+      {
+	Col [prev_col].shared4.degree_next = next_col ;
+      }
+      if (next_col != Empty)
+      {
+	Col [next_col].shared3.prev = prev_col ;
+      }
+
+      /* === Scan the column ========================================== */
+
+      cp = &A [Col [col].start] ;
+      cp_end = cp + Col [col].length ;
+      while (cp < cp_end)
+      {
+	/* get a row */
+	row = *cp++ ;
+	/* skip if dead */
+	if (Row[row].is_dead())
+	{
+	  continue ;
+	}
+  row_mark = Row [row].shared2.mark ;
+	COLAMD_ASSERT (row != pivot_row) ;
+	set_difference = row_mark - tag_mark ;
+	/* check if the row has been seen yet */
+	if (set_difference < 0)
+	{
+	  COLAMD_ASSERT (Row [row].shared1.degree <= max_deg) ;
+	  set_difference = Row [row].shared1.degree ;
+	}
+	/* subtract column thickness from this row's set difference */
+	set_difference -= col_thickness ;
+	COLAMD_ASSERT (set_difference >= 0) ;
+	/* absorb this row if the set difference becomes zero */
+	if (set_difference == 0)
+	{
+	  COLAMD_DEBUG3 (("aggressive absorption. Row: %d\n", row)) ;
+	  Row[row].kill() ;
+	}
+	else
+	{
+	  /* save the new mark */
+	  Row [row].shared2.mark = set_difference + tag_mark ;
+	}
+      }
+    }
+
+
+    /* === Add up set differences for each column ======================= */
+
+    COLAMD_DEBUG3 (("** Adding set differences phase. **\n")) ;
+
+    /* for each column in pivot row */
+    rp = &A [pivot_row_start] ;
+    rp_end = rp + pivot_row_length ;
+    while (rp < rp_end)
+    {
+      /* get a column */
+      col = *rp++ ;
+      COLAMD_ASSERT (Col[col].is_alive() && col != pivot_col) ;
+      hash = 0 ;
+      cur_score = 0 ;
+      cp = &A [Col [col].start] ;
+      /* compact the column */
+      new_cp = cp ;
+      cp_end = cp + Col [col].length ;
+
+      COLAMD_DEBUG4 (("Adding set diffs for Col: %d.\n", col)) ;
+
+      while (cp < cp_end)
+      {
+	/* get a row */
+	row = *cp++ ;
+	COLAMD_ASSERT(row >= 0 && row < n_row) ;
+	/* skip if dead */
+	if (Row [row].is_dead())
+	{
+	  continue ;
+	}
+  row_mark = Row [row].shared2.mark ;
+	COLAMD_ASSERT (row_mark > tag_mark) ;
+	/* compact the column */
+	*new_cp++ = row ;
+	/* compute hash function */
+	hash += row ;
+	/* add set difference */
+	cur_score += row_mark - tag_mark ;
+	/* integer overflow... */
+	cur_score = numext::mini(cur_score, n_col) ;
+      }
+
+      /* recompute the column's length */
+      Col [col].length = (IndexType) (new_cp - &A [Col [col].start]) ;
+
+      /* === Further mass elimination ================================= */
+
+      if (Col [col].length == 0)
+      {
+	COLAMD_DEBUG4 (("further mass elimination. Col: %d\n", col)) ;
+	/* nothing left but the pivot row in this column */
+	Col[col].kill_principal() ;
+	pivot_row_degree -= Col [col].shared1.thickness ;
+	COLAMD_ASSERT (pivot_row_degree >= 0) ;
+	/* order it */
+	Col [col].shared2.order = k ;
+	/* increment order count by column thickness */
+	k += Col [col].shared1.thickness ;
+      }
+      else
+      {
+	/* === Prepare for supercolumn detection ==================== */
+
+	COLAMD_DEBUG4 (("Preparing supercol detection for Col: %d.\n", col)) ;
+
+	/* save score so far */
+	Col [col].shared2.score = cur_score ;
+
+	/* add column to hash table, for supercolumn detection */
+	hash %= n_col + 1 ;
+
+	COLAMD_DEBUG4 ((" Hash = %d, n_col = %d.\n", hash, n_col)) ;
+	COLAMD_ASSERT (hash <= n_col) ;
+
+	head_column = head [hash] ;
+	if (head_column > Empty)
+	{
+	  /* degree list "hash" is non-empty, use prev (shared3) of */
+	  /* first column in degree list as head of hash bucket */
+	  first_col = Col [head_column].shared3.headhash ;
+	  Col [head_column].shared3.headhash = col ;
+	}
+	else
+	{
+	  /* degree list "hash" is empty, use head as hash bucket */
+	  first_col = - (head_column + 2) ;
+	  head [hash] = - (col + 2) ;
+	}
+	Col [col].shared4.hash_next = first_col ;
+
+	/* save hash function in Col [col].shared3.hash */
+	Col [col].shared3.hash = (IndexType) hash ;
+	COLAMD_ASSERT (Col[col].is_alive()) ;
+      }
+    }
+
+    /* The approximate external column degree is now computed.  */
+
+    /* === Supercolumn detection ======================================== */
+
+    COLAMD_DEBUG3 (("** Supercolumn detection phase. **\n")) ;
+
+    Colamd::detect_super_cols (Col, A, head, pivot_row_start, pivot_row_length) ;
+
+    /* === Kill the pivotal column ====================================== */
+
+    Col[pivot_col].kill_principal() ;
+
+    /* === Clear mark =================================================== */
+
+    tag_mark += (max_deg + 1) ;
+    if (tag_mark >= max_mark)
+    {
+      COLAMD_DEBUG2 (("clearing tag_mark\n")) ;
+      tag_mark = Colamd::clear_mark (n_row, Row) ;
+    }
+
+    /* === Finalize the new pivot row, and column scores ================ */
+
+    COLAMD_DEBUG3 (("** Finalize scores phase. **\n")) ;
+
+    /* for each column in pivot row */
+    rp = &A [pivot_row_start] ;
+    /* compact the pivot row */
+    new_rp = rp ;
+    rp_end = rp + pivot_row_length ;
+    while (rp < rp_end)
+    {
+      col = *rp++ ;
+      /* skip dead columns */
+      if (Col[col].is_dead())
+      {
+	continue ;
+      }
+      *new_rp++ = col ;
+      /* add new pivot row to column */
+      A [Col [col].start + (Col [col].length++)] = pivot_row ;
+
+      /* retrieve score so far and add on pivot row's degree. */
+      /* (we wait until here for this in case the pivot */
+      /* row's degree was reduced due to mass elimination). */
+      cur_score = Col [col].shared2.score + pivot_row_degree ;
+
+      /* calculate the max possible score as the number of */
+      /* external columns minus the 'k' value minus the */
+      /* columns thickness */
+      max_score = n_col - k - Col [col].shared1.thickness ;
+
+      /* make the score the external degree of the union-of-rows */
+      cur_score -= Col [col].shared1.thickness ;
+
+      /* make sure score is less or equal than the max score */
+      cur_score = numext::mini(cur_score, max_score) ;
+      COLAMD_ASSERT (cur_score >= 0) ;
+
+      /* store updated score */
+      Col [col].shared2.score = cur_score ;
+
+      /* === Place column back in degree list ========================= */
+
+      COLAMD_ASSERT (min_score >= 0) ;
+      COLAMD_ASSERT (min_score <= n_col) ;
+      COLAMD_ASSERT (cur_score >= 0) ;
+      COLAMD_ASSERT (cur_score <= n_col) ;
+      COLAMD_ASSERT (head [cur_score] >= Empty) ;
+      next_col = head [cur_score] ;
+      Col [col].shared4.degree_next = next_col ;
+      Col [col].shared3.prev = Empty ;
+      if (next_col != Empty)
+      {
+	Col [next_col].shared3.prev = col ;
+      }
+      head [cur_score] = col ;
+
+      /* see if this score is less than current min */
+      min_score = numext::mini(min_score, cur_score) ;
+
+    }
+
+    /* === Resurrect the new pivot row ================================== */
+
+    if (pivot_row_degree > 0)
+    {
+      /* update pivot row length to reflect any cols that were killed */
+      /* during super-col detection and mass elimination */
+      Row [pivot_row].start  = pivot_row_start ;
+      Row [pivot_row].length = (IndexType) (new_rp - &A[pivot_row_start]) ;
+      Row [pivot_row].shared1.degree = pivot_row_degree ;
+      Row [pivot_row].shared2.mark = 0 ;
+      /* pivot row is no longer dead */
+    }
+  }
+
+  /* === All principal columns have now been ordered ====================== */
+
+  return (ngarbage) ;
+}
+
+
+/* ========================================================================== */
+/* === order_children ======================================================= */
+/* ========================================================================== */
+
+/*
+  The find_ordering routine has ordered all of the principal columns (the
+  representatives of the supercolumns).  The non-principal columns have not
+  yet been ordered.  This routine orders those columns by walking up the
+  parent tree (a column is a child of the column which absorbed it).  The
+  final permutation vector is then placed in p [0 ... n_col-1], with p [0]
+  being the first column, and p [n_col-1] being the last.  It doesn't look
+  like it at first glance, but be assured that this routine takes time linear
+  in the number of columns.  Although not immediately obvious, the time
+  taken by this routine is O (n_col), that is, linear in the number of
+  columns.  Not user-callable.
+*/
+template <typename IndexType>
+static inline  void order_children
+(
+  /* === Parameters ======================================================= */
+
+  IndexType n_col,      /* number of columns of A */
+  ColStructure<IndexType> Col [],    /* of size n_col+1 */
+  IndexType p []      /* p [0 ... n_col-1] is the column permutation*/
+  )
+{
+  /* === Local variables ================================================== */
+
+  IndexType i ;     /* loop counter for all columns */
+  IndexType c ;     /* column index */
+  IndexType parent ;    /* index of column's parent */
+  IndexType order ;     /* column's order */
+
+  /* === Order each non-principal column ================================== */
+
+  for (i = 0 ; i < n_col ; i++)
+  {
+    /* find an un-ordered non-principal column */
+    COLAMD_ASSERT (col_is_dead(Col, i)) ;
+    if (!Col[i].is_dead_principal() && Col [i].shared2.order == Empty)
+    {
+      parent = i ;
+      /* once found, find its principal parent */
+      do
+      {
+	parent = Col [parent].shared1.parent ;
+      } while (!Col[parent].is_dead_principal()) ;
+
+      /* now, order all un-ordered non-principal columns along path */
+      /* to this parent.  collapse tree at the same time */
+      c = i ;
+      /* get order of parent */
+      order = Col [parent].shared2.order ;
+
+      do
+      {
+	COLAMD_ASSERT (Col [c].shared2.order == Empty) ;
+
+	/* order this column */
+	Col [c].shared2.order = order++ ;
+	/* collaps tree */
+	Col [c].shared1.parent = parent ;
+
+	/* get immediate parent of this column */
+	c = Col [c].shared1.parent ;
+
+	/* continue until we hit an ordered column.  There are */
+	/* guaranteed not to be anymore unordered columns */
+	/* above an ordered column */
+      } while (Col [c].shared2.order == Empty) ;
+
+      /* re-order the super_col parent to largest order for this group */
+      Col [parent].shared2.order = order ;
+    }
+  }
+
+  /* === Generate the permutation ========================================= */
+
+  for (c = 0 ; c < n_col ; c++)
+  {
+    p [Col [c].shared2.order] = c ;
+  }
+}
+
+
+/* ========================================================================== */
+/* === detect_super_cols ==================================================== */
+/* ========================================================================== */
+
+/*
+  Detects supercolumns by finding matches between columns in the hash buckets.
+  Check amongst columns in the set A [row_start ... row_start + row_length-1].
+  The columns under consideration are currently *not* in the degree lists,
+  and have already been placed in the hash buckets.
+
+  The hash bucket for columns whose hash function is equal to h is stored
+  as follows:
+
+  if head [h] is >= 0, then head [h] contains a degree list, so:
+
+  head [h] is the first column in degree bucket h.
+  Col [head [h]].headhash gives the first column in hash bucket h.
+
+  otherwise, the degree list is empty, and:
+
+  -(head [h] + 2) is the first column in hash bucket h.
+
+  For a column c in a hash bucket, Col [c].shared3.prev is NOT a "previous
+  column" pointer.  Col [c].shared3.hash is used instead as the hash number
+  for that column.  The value of Col [c].shared4.hash_next is the next column
+  in the same hash bucket.
+
+  Assuming no, or "few" hash collisions, the time taken by this routine is
+  linear in the sum of the sizes (lengths) of each column whose score has
+  just been computed in the approximate degree computation.
+  Not user-callable.
+*/
+template <typename IndexType>
+static void detect_super_cols
+(
+  /* === Parameters ======================================================= */
+
+  ColStructure<IndexType> Col [],    /* of size n_col+1 */
+  IndexType A [],     /* row indices of A */
+  IndexType head [],    /* head of degree lists and hash buckets */
+  IndexType row_start,    /* pointer to set of columns to check */
+  IndexType row_length    /* number of columns to check */
+)
+{
+  /* === Local variables ================================================== */
+
+  IndexType hash ;      /* hash value for a column */
+  IndexType *rp ;     /* pointer to a row */
+  IndexType c ;     /* a column index */
+  IndexType super_c ;   /* column index of the column to absorb into */
+  IndexType *cp1 ;      /* column pointer for column super_c */
+  IndexType *cp2 ;      /* column pointer for column c */
+  IndexType length ;    /* length of column super_c */
+  IndexType prev_c ;    /* column preceding c in hash bucket */
+  IndexType i ;     /* loop counter */
+  IndexType *rp_end ;   /* pointer to the end of the row */
+  IndexType col ;     /* a column index in the row to check */
+  IndexType head_column ;   /* first column in hash bucket or degree list */
+  IndexType first_col ;   /* first column in hash bucket */
+
+  /* === Consider each column in the row ================================== */
+
+  rp = &A [row_start] ;
+  rp_end = rp + row_length ;
+  while (rp < rp_end)
+  {
+    col = *rp++ ;
+    if (Col[col].is_dead())
+    {
+      continue ;
+    }
+
+    /* get hash number for this column */
+    hash = Col [col].shared3.hash ;
+    COLAMD_ASSERT (hash <= n_col) ;
+
+    /* === Get the first column in this hash bucket ===================== */
+
+    head_column = head [hash] ;
+    if (head_column > Empty)
+    {
+      first_col = Col [head_column].shared3.headhash ;
+    }
+    else
+    {
+      first_col = - (head_column + 2) ;
+    }
+
+    /* === Consider each column in the hash bucket ====================== */
+
+    for (super_c = first_col ; super_c != Empty ;
+	 super_c = Col [super_c].shared4.hash_next)
+    {
+      COLAMD_ASSERT (Col [super_c].is_alive()) ;
+      COLAMD_ASSERT (Col [super_c].shared3.hash == hash) ;
+      length = Col [super_c].length ;
+
+      /* prev_c is the column preceding column c in the hash bucket */
+      prev_c = super_c ;
+
+      /* === Compare super_c with all columns after it ================ */
+
+      for (c = Col [super_c].shared4.hash_next ;
+	   c != Empty ; c = Col [c].shared4.hash_next)
+      {
+	COLAMD_ASSERT (c != super_c) ;
+	COLAMD_ASSERT (Col[c].is_alive()) ;
+	COLAMD_ASSERT (Col [c].shared3.hash == hash) ;
+
+	/* not identical if lengths or scores are different */
+	if (Col [c].length != length ||
+	    Col [c].shared2.score != Col [super_c].shared2.score)
+	{
+	  prev_c = c ;
+	  continue ;
+	}
+
+	/* compare the two columns */
+	cp1 = &A [Col [super_c].start] ;
+	cp2 = &A [Col [c].start] ;
+
+	for (i = 0 ; i < length ; i++)
+	{
+	  /* the columns are "clean" (no dead rows) */
+	  COLAMD_ASSERT ( cp1->is_alive() );
+	  COLAMD_ASSERT ( cp2->is_alive() );
+	  /* row indices will same order for both supercols, */
+	  /* no gather scatter necessary */
+	  if (*cp1++ != *cp2++)
+	  {
+	    break ;
+	  }
+	}
+
+	/* the two columns are different if the for-loop "broke" */
+	if (i != length)
+	{
+	  prev_c = c ;
+	  continue ;
+	}
+
+	/* === Got it!  two columns are identical =================== */
+
+	COLAMD_ASSERT (Col [c].shared2.score == Col [super_c].shared2.score) ;
+
+	Col [super_c].shared1.thickness += Col [c].shared1.thickness ;
+	Col [c].shared1.parent = super_c ;
+	Col[c].kill_non_principal() ;
+	/* order c later, in order_children() */
+	Col [c].shared2.order = Empty ;
+	/* remove c from hash bucket */
+	Col [prev_c].shared4.hash_next = Col [c].shared4.hash_next ;
+      }
+    }
+
+    /* === Empty this hash bucket ======================================= */
+
+    if (head_column > Empty)
+    {
+      /* corresponding degree list "hash" is not empty */
+      Col [head_column].shared3.headhash = Empty ;
+    }
+    else
+    {
+      /* corresponding degree list "hash" is empty */
+      head [hash] = Empty ;
+    }
+  }
+}
+
+
+/* ========================================================================== */
+/* === garbage_collection =================================================== */
+/* ========================================================================== */
+
+/*
+  Defragments and compacts columns and rows in the workspace A.  Used when
+  all available memory has been used while performing row merging.  Returns
+  the index of the first free position in A, after garbage collection.  The
+  time taken by this routine is linear is the size of the array A, which is
+  itself linear in the number of nonzeros in the input matrix.
+  Not user-callable.
+*/
+template <typename IndexType>
+static IndexType garbage_collection  /* returns the new value of pfree */
+  (
+    /* === Parameters ======================================================= */
+
+    IndexType n_row,      /* number of rows */
+    IndexType n_col,      /* number of columns */
+    RowStructure<IndexType> Row [],    /* row info */
+    ColStructure<IndexType> Col [],    /* column info */
+    IndexType A [],     /* A [0 ... Alen-1] holds the matrix */
+    IndexType *pfree      /* &A [0] ... pfree is in use */
+    )
+{
+  /* === Local variables ================================================== */
+
+  IndexType *psrc ;     /* source pointer */
+  IndexType *pdest ;    /* destination pointer */
+  IndexType j ;     /* counter */
+  IndexType r ;     /* a row index */
+  IndexType c ;     /* a column index */
+  IndexType length ;    /* length of a row or column */
+
+  /* === Defragment the columns =========================================== */
+
+  pdest = &A[0] ;
+  for (c = 0 ; c < n_col ; c++)
+  {
+    if (Col[c].is_alive())
+    {
+      psrc = &A [Col [c].start] ;
+
+      /* move and compact the column */
+      COLAMD_ASSERT (pdest <= psrc) ;
+      Col [c].start = (IndexType) (pdest - &A [0]) ;
+      length = Col [c].length ;
+      for (j = 0 ; j < length ; j++)
+      {
+	r = *psrc++ ;
+	if (Row[r].is_alive())
+	{
+	  *pdest++ = r ;
+	}
+      }
+      Col [c].length = (IndexType) (pdest - &A [Col [c].start]) ;
+    }
+  }
+
+  /* === Prepare to defragment the rows =================================== */
+
+  for (r = 0 ; r < n_row ; r++)
+  {
+    if (Row[r].is_alive())
+    {
+      if (Row [r].length == 0)
+      {
+        /* this row is of zero length.  cannot compact it, so kill it */
+        COLAMD_DEBUG3 (("Defrag row kill\n")) ;
+        Row[r].kill() ;
+      }
+      else
+      {
+        /* save first column index in Row [r].shared2.first_column */
+        psrc = &A [Row [r].start] ;
+        Row [r].shared2.first_column = *psrc ;
+        COLAMD_ASSERT (Row[r].is_alive()) ;
+        /* flag the start of the row with the one's complement of row */
+        *psrc = ones_complement(r) ;
+
+      }
+    }
+  }
+
+  /* === Defragment the rows ============================================== */
+
+  psrc = pdest ;
+  while (psrc < pfree)
+  {
+    /* find a negative number ... the start of a row */
+    if (*psrc++ < 0)
+    {
+      psrc-- ;
+      /* get the row index */
+      r = ones_complement(*psrc) ;
+      COLAMD_ASSERT (r >= 0 && r < n_row) ;
+      /* restore first column index */
+      *psrc = Row [r].shared2.first_column ;
+      COLAMD_ASSERT (Row[r].is_alive()) ;
+
+      /* move and compact the row */
+      COLAMD_ASSERT (pdest <= psrc) ;
+      Row [r].start = (IndexType) (pdest - &A [0]) ;
+      length = Row [r].length ;
+      for (j = 0 ; j < length ; j++)
+      {
+	c = *psrc++ ;
+	if (Col[c].is_alive())
+	{
+	  *pdest++ = c ;
+	}
+      }
+      Row [r].length = (IndexType) (pdest - &A [Row [r].start]) ;
+
+    }
+  }
+  /* ensure we found all the rows */
+  COLAMD_ASSERT (debug_rows == 0) ;
+
+  /* === Return the new value of pfree ==================================== */
+
+  return ((IndexType) (pdest - &A [0])) ;
+}
+
+
+/* ========================================================================== */
+/* === clear_mark =========================================================== */
+/* ========================================================================== */
+
+/*
+  Clears the Row [].shared2.mark array, and returns the new tag_mark.
+  Return value is the new tag_mark.  Not user-callable.
+*/
+template <typename IndexType>
+static inline  IndexType clear_mark  /* return the new value for tag_mark */
+  (
+      /* === Parameters ======================================================= */
+
+    IndexType n_row,    /* number of rows in A */
+    RowStructure<IndexType> Row [] /* Row [0 ... n_row-1].shared2.mark is set to zero */
+    )
+{
+  /* === Local variables ================================================== */
+
+  IndexType r ;
+
+  for (r = 0 ; r < n_row ; r++)
+  {
+    if (Row[r].is_alive())
+    {
+      Row [r].shared2.mark = 0 ;
+    }
+  }
+  return (1) ;
+}
+
+} // namespace Colamd
+
+} // namespace internal
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/OrderingMethods/Ordering.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/OrderingMethods/Ordering.h
new file mode 100644
index 0000000..c578970
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/OrderingMethods/Ordering.h
@@ -0,0 +1,153 @@
+ 
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2012  Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_ORDERING_H
+#define EIGEN_ORDERING_H
+
+namespace Eigen {
+  
+#include "Eigen_Colamd.h"
+
+namespace internal {
+    
+/** \internal
+  * \ingroup OrderingMethods_Module
+  * \param[in] A the input non-symmetric matrix
+  * \param[out] symmat the symmetric pattern A^T+A from the input matrix \a A.
+  * FIXME: The values should not be considered here
+  */
+template<typename MatrixType> 
+void ordering_helper_at_plus_a(const MatrixType& A, MatrixType& symmat)
+{
+  MatrixType C;
+  C = A.transpose(); // NOTE: Could be  costly
+  for (int i = 0; i < C.rows(); i++) 
+  {
+      for (typename MatrixType::InnerIterator it(C, i); it; ++it)
+        it.valueRef() = typename MatrixType::Scalar(0);
+  }
+  symmat = C + A;
+}
+    
+}
+
+/** \ingroup OrderingMethods_Module
+  * \class AMDOrdering
+  *
+  * Functor computing the \em approximate \em minimum \em degree ordering
+  * If the matrix is not structurally symmetric, an ordering of A^T+A is computed
+  * \tparam  StorageIndex The type of indices of the matrix 
+  * \sa COLAMDOrdering
+  */
+template <typename StorageIndex>
+class AMDOrdering
+{
+  public:
+    typedef PermutationMatrix<Dynamic, Dynamic, StorageIndex> PermutationType;
+    
+    /** Compute the permutation vector from a sparse matrix
+     * This routine is much faster if the input matrix is column-major     
+     */
+    template <typename MatrixType>
+    void operator()(const MatrixType& mat, PermutationType& perm)
+    {
+      // Compute the symmetric pattern
+      SparseMatrix<typename MatrixType::Scalar, ColMajor, StorageIndex> symm;
+      internal::ordering_helper_at_plus_a(mat,symm); 
+    
+      // Call the AMD routine 
+      //m_mat.prune(keep_diag());
+      internal::minimum_degree_ordering(symm, perm);
+    }
+    
+    /** Compute the permutation with a selfadjoint matrix */
+    template <typename SrcType, unsigned int SrcUpLo> 
+    void operator()(const SparseSelfAdjointView<SrcType, SrcUpLo>& mat, PermutationType& perm)
+    { 
+      SparseMatrix<typename SrcType::Scalar, ColMajor, StorageIndex> C; C = mat;
+      
+      // Call the AMD routine 
+      // m_mat.prune(keep_diag()); //Remove the diagonal elements 
+      internal::minimum_degree_ordering(C, perm);
+    }
+};
+
+/** \ingroup OrderingMethods_Module
+  * \class NaturalOrdering
+  *
+  * Functor computing the natural ordering (identity)
+  * 
+  * \note Returns an empty permutation matrix
+  * \tparam  StorageIndex The type of indices of the matrix 
+  */
+template <typename StorageIndex>
+class NaturalOrdering
+{
+  public:
+    typedef PermutationMatrix<Dynamic, Dynamic, StorageIndex> PermutationType;
+    
+    /** Compute the permutation vector from a column-major sparse matrix */
+    template <typename MatrixType>
+    void operator()(const MatrixType& /*mat*/, PermutationType& perm)
+    {
+      perm.resize(0); 
+    }
+    
+};
+
+/** \ingroup OrderingMethods_Module
+  * \class COLAMDOrdering
+  *
+  * \tparam  StorageIndex The type of indices of the matrix 
+  * 
+  * Functor computing the \em column \em approximate \em minimum \em degree ordering 
+  * The matrix should be in column-major and \b compressed format (see SparseMatrix::makeCompressed()).
+  */
+template<typename StorageIndex>
+class COLAMDOrdering
+{
+  public:
+    typedef PermutationMatrix<Dynamic, Dynamic, StorageIndex> PermutationType; 
+    typedef Matrix<StorageIndex, Dynamic, 1> IndexVector;
+    
+    /** Compute the permutation vector \a perm form the sparse matrix \a mat
+      * \warning The input sparse matrix \a mat must be in compressed mode (see SparseMatrix::makeCompressed()).
+      */
+    template <typename MatrixType>
+    void operator() (const MatrixType& mat, PermutationType& perm)
+    {
+      eigen_assert(mat.isCompressed() && "COLAMDOrdering requires a sparse matrix in compressed mode. Call .makeCompressed() before passing it to COLAMDOrdering");
+      
+      StorageIndex m = StorageIndex(mat.rows());
+      StorageIndex n = StorageIndex(mat.cols());
+      StorageIndex nnz = StorageIndex(mat.nonZeros());
+      // Get the recommended value of Alen to be used by colamd
+      StorageIndex Alen = internal::Colamd::recommended(nnz, m, n); 
+      // Set the default parameters
+      double knobs [internal::Colamd::NKnobs]; 
+      StorageIndex stats [internal::Colamd::NStats];
+      internal::Colamd::set_defaults(knobs);
+      
+      IndexVector p(n+1), A(Alen); 
+      for(StorageIndex i=0; i <= n; i++)   p(i) = mat.outerIndexPtr()[i];
+      for(StorageIndex i=0; i < nnz; i++)  A(i) = mat.innerIndexPtr()[i];
+      // Call Colamd routine to compute the ordering 
+      StorageIndex info = internal::Colamd::compute_ordering(m, n, Alen, A.data(), p.data(), knobs, stats); 
+      EIGEN_UNUSED_VARIABLE(info);
+      eigen_assert( info && "COLAMD failed " );
+      
+      perm.resize(n);
+      for (StorageIndex i = 0; i < n; i++) perm.indices()(p(i)) = i;
+    }
+};
+
+} // end namespace Eigen
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/QR/ColPivHouseholderQR.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/QR/ColPivHouseholderQR.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/QR/ColPivHouseholderQR.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/QR/ColPivHouseholderQR.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/QR/CompleteOrthogonalDecomposition.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/QR/CompleteOrthogonalDecomposition.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/QR/CompleteOrthogonalDecomposition.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/QR/CompleteOrthogonalDecomposition.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/QR/FullPivHouseholderQR.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/QR/FullPivHouseholderQR.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/QR/FullPivHouseholderQR.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/QR/FullPivHouseholderQR.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/QR/HouseholderQR.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/QR/HouseholderQR.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/QR/HouseholderQR.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/QR/HouseholderQR.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/SVD/BDCSVD.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SVD/BDCSVD.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/SVD/BDCSVD.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SVD/BDCSVD.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/SVD/JacobiSVD.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SVD/JacobiSVD.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/SVD/JacobiSVD.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SVD/JacobiSVD.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/SVD/SVDBase.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SVD/SVDBase.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/SVD/SVDBase.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SVD/SVDBase.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/SVD/UpperBidiagonalization.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SVD/UpperBidiagonalization.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/SVD/UpperBidiagonalization.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SVD/UpperBidiagonalization.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCholesky/SimplicialCholesky.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCholesky/SimplicialCholesky.h
new file mode 100644
index 0000000..9f93e32
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCholesky/SimplicialCholesky.h
@@ -0,0 +1,697 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2008-2012 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_SIMPLICIAL_CHOLESKY_H
+#define EIGEN_SIMPLICIAL_CHOLESKY_H
+
+namespace Eigen { 
+
+enum SimplicialCholeskyMode {
+  SimplicialCholeskyLLT,
+  SimplicialCholeskyLDLT
+};
+
+namespace internal {
+  template<typename CholMatrixType, typename InputMatrixType>
+  struct simplicial_cholesky_grab_input {
+    typedef CholMatrixType const * ConstCholMatrixPtr;
+    static void run(const InputMatrixType& input, ConstCholMatrixPtr &pmat, CholMatrixType &tmp)
+    {
+      tmp = input;
+      pmat = &tmp;
+    }
+  };
+  
+  template<typename MatrixType>
+  struct simplicial_cholesky_grab_input<MatrixType,MatrixType> {
+    typedef MatrixType const * ConstMatrixPtr;
+    static void run(const MatrixType& input, ConstMatrixPtr &pmat, MatrixType &/*tmp*/)
+    {
+      pmat = &input;
+    }
+  };
+} // end namespace internal
+
+/** \ingroup SparseCholesky_Module
+  * \brief A base class for direct sparse Cholesky factorizations
+  *
+  * This is a base class for LL^T and LDL^T Cholesky factorizations of sparse matrices that are
+  * selfadjoint and positive definite. These factorizations allow for solving A.X = B where
+  * X and B can be either dense or sparse.
+  * 
+  * In order to reduce the fill-in, a symmetric permutation P is applied prior to the factorization
+  * such that the factorized matrix is P A P^-1.
+  *
+  * \tparam Derived the type of the derived class, that is the actual factorization type.
+  *
+  */
+template<typename Derived>
+class SimplicialCholeskyBase : public SparseSolverBase<Derived>
+{
+    typedef SparseSolverBase<Derived> Base;
+    using Base::m_isInitialized;
+    
+  public:
+    typedef typename internal::traits<Derived>::MatrixType MatrixType;
+    typedef typename internal::traits<Derived>::OrderingType OrderingType;
+    enum { UpLo = internal::traits<Derived>::UpLo };
+    typedef typename MatrixType::Scalar Scalar;
+    typedef typename MatrixType::RealScalar RealScalar;
+    typedef typename MatrixType::StorageIndex StorageIndex;
+    typedef SparseMatrix<Scalar,ColMajor,StorageIndex> CholMatrixType;
+    typedef CholMatrixType const * ConstCholMatrixPtr;
+    typedef Matrix<Scalar,Dynamic,1> VectorType;
+    typedef Matrix<StorageIndex,Dynamic,1> VectorI;
+
+    enum {
+      ColsAtCompileTime = MatrixType::ColsAtCompileTime,
+      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime
+    };
+
+  public:
+    
+    using Base::derived;
+
+    /** Default constructor */
+    SimplicialCholeskyBase()
+      : m_info(Success),
+        m_factorizationIsOk(false),
+        m_analysisIsOk(false),
+        m_shiftOffset(0),
+        m_shiftScale(1)
+    {}
+
+    explicit SimplicialCholeskyBase(const MatrixType& matrix)
+      : m_info(Success),
+        m_factorizationIsOk(false),
+        m_analysisIsOk(false),
+        m_shiftOffset(0),
+        m_shiftScale(1)
+    {
+      derived().compute(matrix);
+    }
+
+    ~SimplicialCholeskyBase()
+    {
+    }
+
+    Derived& derived() { return *static_cast<Derived*>(this); }
+    const Derived& derived() const { return *static_cast<const Derived*>(this); }
+    
+    inline Index cols() const { return m_matrix.cols(); }
+    inline Index rows() const { return m_matrix.rows(); }
+    
+    /** \brief Reports whether previous computation was successful.
+      *
+      * \returns \c Success if computation was successful,
+      *          \c NumericalIssue if the matrix.appears to be negative.
+      */
+    ComputationInfo info() const
+    {
+      eigen_assert(m_isInitialized && "Decomposition is not initialized.");
+      return m_info;
+    }
+    
+    /** \returns the permutation P
+      * \sa permutationPinv() */
+    const PermutationMatrix<Dynamic,Dynamic,StorageIndex>& permutationP() const
+    { return m_P; }
+    
+    /** \returns the inverse P^-1 of the permutation P
+      * \sa permutationP() */
+    const PermutationMatrix<Dynamic,Dynamic,StorageIndex>& permutationPinv() const
+    { return m_Pinv; }
+
+    /** Sets the shift parameters that will be used to adjust the diagonal coefficients during the numerical factorization.
+      *
+      * During the numerical factorization, the diagonal coefficients are transformed by the following linear model:\n
+      * \c d_ii = \a offset + \a scale * \c d_ii
+      *
+      * The default is the identity transformation with \a offset=0, and \a scale=1.
+      *
+      * \returns a reference to \c *this.
+      */
+    Derived& setShift(const RealScalar& offset, const RealScalar& scale = 1)
+    {
+      m_shiftOffset = offset;
+      m_shiftScale = scale;
+      return derived();
+    }
+
+#ifndef EIGEN_PARSED_BY_DOXYGEN
+    /** \internal */
+    template<typename Stream>
+    void dumpMemory(Stream& s)
+    {
+      int total = 0;
+      s << "  L:        " << ((total+=(m_matrix.cols()+1) * sizeof(int) + m_matrix.nonZeros()*(sizeof(int)+sizeof(Scalar))) >> 20) << "Mb" << "\n";
+      s << "  diag:     " << ((total+=m_diag.size() * sizeof(Scalar)) >> 20) << "Mb" << "\n";
+      s << "  tree:     " << ((total+=m_parent.size() * sizeof(int)) >> 20) << "Mb" << "\n";
+      s << "  nonzeros: " << ((total+=m_nonZerosPerCol.size() * sizeof(int)) >> 20) << "Mb" << "\n";
+      s << "  perm:     " << ((total+=m_P.size() * sizeof(int)) >> 20) << "Mb" << "\n";
+      s << "  perm^-1:  " << ((total+=m_Pinv.size() * sizeof(int)) >> 20) << "Mb" << "\n";
+      s << "  TOTAL:    " << (total>> 20) << "Mb" << "\n";
+    }
+
+    /** \internal */
+    template<typename Rhs,typename Dest>
+    void _solve_impl(const MatrixBase<Rhs> &b, MatrixBase<Dest> &dest) const
+    {
+      eigen_assert(m_factorizationIsOk && "The decomposition is not in a valid state for solving, you must first call either compute() or symbolic()/numeric()");
+      eigen_assert(m_matrix.rows()==b.rows());
+
+      if(m_info!=Success)
+        return;
+
+      if(m_P.size()>0)
+        dest = m_P * b;
+      else
+        dest = b;
+
+      if(m_matrix.nonZeros()>0) // otherwise L==I
+        derived().matrixL().solveInPlace(dest);
+
+      if(m_diag.size()>0)
+        dest = m_diag.asDiagonal().inverse() * dest;
+
+      if (m_matrix.nonZeros()>0) // otherwise U==I
+        derived().matrixU().solveInPlace(dest);
+
+      if(m_P.size()>0)
+        dest = m_Pinv * dest;
+    }
+    
+    template<typename Rhs,typename Dest>
+    void _solve_impl(const SparseMatrixBase<Rhs> &b, SparseMatrixBase<Dest> &dest) const
+    {
+      internal::solve_sparse_through_dense_panels(derived(), b, dest);
+    }
+
+#endif // EIGEN_PARSED_BY_DOXYGEN
+
+  protected:
+    
+    /** Computes the sparse Cholesky decomposition of \a matrix */
+    template<bool DoLDLT>
+    void compute(const MatrixType& matrix)
+    {
+      eigen_assert(matrix.rows()==matrix.cols());
+      Index size = matrix.cols();
+      CholMatrixType tmp(size,size);
+      ConstCholMatrixPtr pmat;
+      ordering(matrix, pmat, tmp);
+      analyzePattern_preordered(*pmat, DoLDLT);
+      factorize_preordered<DoLDLT>(*pmat);
+    }
+    
+    template<bool DoLDLT>
+    void factorize(const MatrixType& a)
+    {
+      eigen_assert(a.rows()==a.cols());
+      Index size = a.cols();
+      CholMatrixType tmp(size,size);
+      ConstCholMatrixPtr pmat;
+      
+      if(m_P.size() == 0 && (int(UpLo) & int(Upper)) == Upper)
+      {
+        // If there is no ordering, try to directly use the input matrix without any copy
+        internal::simplicial_cholesky_grab_input<CholMatrixType,MatrixType>::run(a, pmat, tmp);
+      }
+      else
+      {
+        tmp.template selfadjointView<Upper>() = a.template selfadjointView<UpLo>().twistedBy(m_P);
+        pmat = &tmp;
+      }
+      
+      factorize_preordered<DoLDLT>(*pmat);
+    }
+
+    template<bool DoLDLT>
+    void factorize_preordered(const CholMatrixType& a);
+
+    void analyzePattern(const MatrixType& a, bool doLDLT)
+    {
+      eigen_assert(a.rows()==a.cols());
+      Index size = a.cols();
+      CholMatrixType tmp(size,size);
+      ConstCholMatrixPtr pmat;
+      ordering(a, pmat, tmp);
+      analyzePattern_preordered(*pmat,doLDLT);
+    }
+    void analyzePattern_preordered(const CholMatrixType& a, bool doLDLT);
+    
+    void ordering(const MatrixType& a, ConstCholMatrixPtr &pmat, CholMatrixType& ap);
+
+    /** keeps off-diagonal entries; drops diagonal entries */
+    struct keep_diag {
+      inline bool operator() (const Index& row, const Index& col, const Scalar&) const
+      {
+        return row!=col;
+      }
+    };
+
+    mutable ComputationInfo m_info;
+    bool m_factorizationIsOk;
+    bool m_analysisIsOk;
+    
+    CholMatrixType m_matrix;
+    VectorType m_diag;                                // the diagonal coefficients (LDLT mode)
+    VectorI m_parent;                                 // elimination tree
+    VectorI m_nonZerosPerCol;
+    PermutationMatrix<Dynamic,Dynamic,StorageIndex> m_P;     // the permutation
+    PermutationMatrix<Dynamic,Dynamic,StorageIndex> m_Pinv;  // the inverse permutation
+
+    RealScalar m_shiftOffset;
+    RealScalar m_shiftScale;
+};
+
+template<typename _MatrixType, int _UpLo = Lower, typename _Ordering = AMDOrdering<typename _MatrixType::StorageIndex> > class SimplicialLLT;
+template<typename _MatrixType, int _UpLo = Lower, typename _Ordering = AMDOrdering<typename _MatrixType::StorageIndex> > class SimplicialLDLT;
+template<typename _MatrixType, int _UpLo = Lower, typename _Ordering = AMDOrdering<typename _MatrixType::StorageIndex> > class SimplicialCholesky;
+
+namespace internal {
+
+template<typename _MatrixType, int _UpLo, typename _Ordering> struct traits<SimplicialLLT<_MatrixType,_UpLo,_Ordering> >
+{
+  typedef _MatrixType MatrixType;
+  typedef _Ordering OrderingType;
+  enum { UpLo = _UpLo };
+  typedef typename MatrixType::Scalar                         Scalar;
+  typedef typename MatrixType::StorageIndex                   StorageIndex;
+  typedef SparseMatrix<Scalar, ColMajor, StorageIndex>        CholMatrixType;
+  typedef TriangularView<const CholMatrixType, Eigen::Lower>  MatrixL;
+  typedef TriangularView<const typename CholMatrixType::AdjointReturnType, Eigen::Upper>   MatrixU;
+  static inline MatrixL getL(const CholMatrixType& m) { return MatrixL(m); }
+  static inline MatrixU getU(const CholMatrixType& m) { return MatrixU(m.adjoint()); }
+};
+
+template<typename _MatrixType,int _UpLo, typename _Ordering> struct traits<SimplicialLDLT<_MatrixType,_UpLo,_Ordering> >
+{
+  typedef _MatrixType MatrixType;
+  typedef _Ordering OrderingType;
+  enum { UpLo = _UpLo };
+  typedef typename MatrixType::Scalar                             Scalar;
+  typedef typename MatrixType::StorageIndex                       StorageIndex;
+  typedef SparseMatrix<Scalar, ColMajor, StorageIndex>            CholMatrixType;
+  typedef TriangularView<const CholMatrixType, Eigen::UnitLower>  MatrixL;
+  typedef TriangularView<const typename CholMatrixType::AdjointReturnType, Eigen::UnitUpper> MatrixU;
+  static inline MatrixL getL(const CholMatrixType& m) { return MatrixL(m); }
+  static inline MatrixU getU(const CholMatrixType& m) { return MatrixU(m.adjoint()); }
+};
+
+template<typename _MatrixType, int _UpLo, typename _Ordering> struct traits<SimplicialCholesky<_MatrixType,_UpLo,_Ordering> >
+{
+  typedef _MatrixType MatrixType;
+  typedef _Ordering OrderingType;
+  enum { UpLo = _UpLo };
+};
+
+}
+
+/** \ingroup SparseCholesky_Module
+  * \class SimplicialLLT
+  * \brief A direct sparse LLT Cholesky factorizations
+  *
+  * This class provides a LL^T Cholesky factorizations of sparse matrices that are
+  * selfadjoint and positive definite. The factorization allows for solving A.X = B where
+  * X and B can be either dense or sparse.
+  * 
+  * In order to reduce the fill-in, a symmetric permutation P is applied prior to the factorization
+  * such that the factorized matrix is P A P^-1.
+  *
+  * \tparam _MatrixType the type of the sparse matrix A, it must be a SparseMatrix<>
+  * \tparam _UpLo the triangular part that will be used for the computations. It can be Lower
+  *               or Upper. Default is Lower.
+  * \tparam _Ordering The ordering method to use, either AMDOrdering<> or NaturalOrdering<>. Default is AMDOrdering<>
+  *
+  * \implsparsesolverconcept
+  *
+  * \sa class SimplicialLDLT, class AMDOrdering, class NaturalOrdering
+  */
+template<typename _MatrixType, int _UpLo, typename _Ordering>
+    class SimplicialLLT : public SimplicialCholeskyBase<SimplicialLLT<_MatrixType,_UpLo,_Ordering> >
+{
+public:
+    typedef _MatrixType MatrixType;
+    enum { UpLo = _UpLo };
+    typedef SimplicialCholeskyBase<SimplicialLLT> Base;
+    typedef typename MatrixType::Scalar Scalar;
+    typedef typename MatrixType::RealScalar RealScalar;
+    typedef typename MatrixType::StorageIndex StorageIndex;
+    typedef SparseMatrix<Scalar,ColMajor,Index> CholMatrixType;
+    typedef Matrix<Scalar,Dynamic,1> VectorType;
+    typedef internal::traits<SimplicialLLT> Traits;
+    typedef typename Traits::MatrixL  MatrixL;
+    typedef typename Traits::MatrixU  MatrixU;
+public:
+    /** Default constructor */
+    SimplicialLLT() : Base() {}
+    /** Constructs and performs the LLT factorization of \a matrix */
+    explicit SimplicialLLT(const MatrixType& matrix)
+        : Base(matrix) {}
+
+    /** \returns an expression of the factor L */
+    inline const MatrixL matrixL() const {
+        eigen_assert(Base::m_factorizationIsOk && "Simplicial LLT not factorized");
+        return Traits::getL(Base::m_matrix);
+    }
+
+    /** \returns an expression of the factor U (= L^*) */
+    inline const MatrixU matrixU() const {
+        eigen_assert(Base::m_factorizationIsOk && "Simplicial LLT not factorized");
+        return Traits::getU(Base::m_matrix);
+    }
+    
+    /** Computes the sparse Cholesky decomposition of \a matrix */
+    SimplicialLLT& compute(const MatrixType& matrix)
+    {
+      Base::template compute<false>(matrix);
+      return *this;
+    }
+
+    /** Performs a symbolic decomposition on the sparcity of \a matrix.
+      *
+      * This function is particularly useful when solving for several problems having the same structure.
+      *
+      * \sa factorize()
+      */
+    void analyzePattern(const MatrixType& a)
+    {
+      Base::analyzePattern(a, false);
+    }
+
+    /** Performs a numeric decomposition of \a matrix
+      *
+      * The given matrix must has the same sparcity than the matrix on which the symbolic decomposition has been performed.
+      *
+      * \sa analyzePattern()
+      */
+    void factorize(const MatrixType& a)
+    {
+      Base::template factorize<false>(a);
+    }
+
+    /** \returns the determinant of the underlying matrix from the current factorization */
+    Scalar determinant() const
+    {
+      Scalar detL = Base::m_matrix.diagonal().prod();
+      return numext::abs2(detL);
+    }
+};
+
+/** \ingroup SparseCholesky_Module
+  * \class SimplicialLDLT
+  * \brief A direct sparse LDLT Cholesky factorizations without square root.
+  *
+  * This class provides a LDL^T Cholesky factorizations without square root of sparse matrices that are
+  * selfadjoint and positive definite. The factorization allows for solving A.X = B where
+  * X and B can be either dense or sparse.
+  * 
+  * In order to reduce the fill-in, a symmetric permutation P is applied prior to the factorization
+  * such that the factorized matrix is P A P^-1.
+  *
+  * \tparam _MatrixType the type of the sparse matrix A, it must be a SparseMatrix<>
+  * \tparam _UpLo the triangular part that will be used for the computations. It can be Lower
+  *               or Upper. Default is Lower.
+  * \tparam _Ordering The ordering method to use, either AMDOrdering<> or NaturalOrdering<>. Default is AMDOrdering<>
+  *
+  * \implsparsesolverconcept
+  *
+  * \sa class SimplicialLLT, class AMDOrdering, class NaturalOrdering
+  */
+template<typename _MatrixType, int _UpLo, typename _Ordering>
+    class SimplicialLDLT : public SimplicialCholeskyBase<SimplicialLDLT<_MatrixType,_UpLo,_Ordering> >
+{
+public:
+    typedef _MatrixType MatrixType;
+    enum { UpLo = _UpLo };
+    typedef SimplicialCholeskyBase<SimplicialLDLT> Base;
+    typedef typename MatrixType::Scalar Scalar;
+    typedef typename MatrixType::RealScalar RealScalar;
+    typedef typename MatrixType::StorageIndex StorageIndex;
+    typedef SparseMatrix<Scalar,ColMajor,StorageIndex> CholMatrixType;
+    typedef Matrix<Scalar,Dynamic,1> VectorType;
+    typedef internal::traits<SimplicialLDLT> Traits;
+    typedef typename Traits::MatrixL  MatrixL;
+    typedef typename Traits::MatrixU  MatrixU;
+public:
+    /** Default constructor */
+    SimplicialLDLT() : Base() {}
+
+    /** Constructs and performs the LLT factorization of \a matrix */
+    explicit SimplicialLDLT(const MatrixType& matrix)
+        : Base(matrix) {}
+
+    /** \returns a vector expression of the diagonal D */
+    inline const VectorType vectorD() const {
+        eigen_assert(Base::m_factorizationIsOk && "Simplicial LDLT not factorized");
+        return Base::m_diag;
+    }
+    /** \returns an expression of the factor L */
+    inline const MatrixL matrixL() const {
+        eigen_assert(Base::m_factorizationIsOk && "Simplicial LDLT not factorized");
+        return Traits::getL(Base::m_matrix);
+    }
+
+    /** \returns an expression of the factor U (= L^*) */
+    inline const MatrixU matrixU() const {
+        eigen_assert(Base::m_factorizationIsOk && "Simplicial LDLT not factorized");
+        return Traits::getU(Base::m_matrix);
+    }
+
+    /** Computes the sparse Cholesky decomposition of \a matrix */
+    SimplicialLDLT& compute(const MatrixType& matrix)
+    {
+      Base::template compute<true>(matrix);
+      return *this;
+    }
+    
+    /** Performs a symbolic decomposition on the sparcity of \a matrix.
+      *
+      * This function is particularly useful when solving for several problems having the same structure.
+      *
+      * \sa factorize()
+      */
+    void analyzePattern(const MatrixType& a)
+    {
+      Base::analyzePattern(a, true);
+    }
+
+    /** Performs a numeric decomposition of \a matrix
+      *
+      * The given matrix must has the same sparcity than the matrix on which the symbolic decomposition has been performed.
+      *
+      * \sa analyzePattern()
+      */
+    void factorize(const MatrixType& a)
+    {
+      Base::template factorize<true>(a);
+    }
+
+    /** \returns the determinant of the underlying matrix from the current factorization */
+    Scalar determinant() const
+    {
+      return Base::m_diag.prod();
+    }
+};
+
+/** \deprecated use SimplicialLDLT or class SimplicialLLT
+  * \ingroup SparseCholesky_Module
+  * \class SimplicialCholesky
+  *
+  * \sa class SimplicialLDLT, class SimplicialLLT
+  */
+template<typename _MatrixType, int _UpLo, typename _Ordering>
+    class SimplicialCholesky : public SimplicialCholeskyBase<SimplicialCholesky<_MatrixType,_UpLo,_Ordering> >
+{
+public:
+    typedef _MatrixType MatrixType;
+    enum { UpLo = _UpLo };
+    typedef SimplicialCholeskyBase<SimplicialCholesky> Base;
+    typedef typename MatrixType::Scalar Scalar;
+    typedef typename MatrixType::RealScalar RealScalar;
+    typedef typename MatrixType::StorageIndex StorageIndex;
+    typedef SparseMatrix<Scalar,ColMajor,StorageIndex> CholMatrixType;
+    typedef Matrix<Scalar,Dynamic,1> VectorType;
+    typedef internal::traits<SimplicialCholesky> Traits;
+    typedef internal::traits<SimplicialLDLT<MatrixType,UpLo> > LDLTTraits;
+    typedef internal::traits<SimplicialLLT<MatrixType,UpLo>  > LLTTraits;
+  public:
+    SimplicialCholesky() : Base(), m_LDLT(true) {}
+
+    explicit SimplicialCholesky(const MatrixType& matrix)
+      : Base(), m_LDLT(true)
+    {
+      compute(matrix);
+    }
+
+    SimplicialCholesky& setMode(SimplicialCholeskyMode mode)
+    {
+      switch(mode)
+      {
+      case SimplicialCholeskyLLT:
+        m_LDLT = false;
+        break;
+      case SimplicialCholeskyLDLT:
+        m_LDLT = true;
+        break;
+      default:
+        break;
+      }
+
+      return *this;
+    }
+
+    inline const VectorType vectorD() const {
+        eigen_assert(Base::m_factorizationIsOk && "Simplicial Cholesky not factorized");
+        return Base::m_diag;
+    }
+    inline const CholMatrixType rawMatrix() const {
+        eigen_assert(Base::m_factorizationIsOk && "Simplicial Cholesky not factorized");
+        return Base::m_matrix;
+    }
+    
+    /** Computes the sparse Cholesky decomposition of \a matrix */
+    SimplicialCholesky& compute(const MatrixType& matrix)
+    {
+      if(m_LDLT)
+        Base::template compute<true>(matrix);
+      else
+        Base::template compute<false>(matrix);
+      return *this;
+    }
+
+    /** Performs a symbolic decomposition on the sparcity of \a matrix.
+      *
+      * This function is particularly useful when solving for several problems having the same structure.
+      *
+      * \sa factorize()
+      */
+    void analyzePattern(const MatrixType& a)
+    {
+      Base::analyzePattern(a, m_LDLT);
+    }
+
+    /** Performs a numeric decomposition of \a matrix
+      *
+      * The given matrix must has the same sparcity than the matrix on which the symbolic decomposition has been performed.
+      *
+      * \sa analyzePattern()
+      */
+    void factorize(const MatrixType& a)
+    {
+      if(m_LDLT)
+        Base::template factorize<true>(a);
+      else
+        Base::template factorize<false>(a);
+    }
+
+    /** \internal */
+    template<typename Rhs,typename Dest>
+    void _solve_impl(const MatrixBase<Rhs> &b, MatrixBase<Dest> &dest) const
+    {
+      eigen_assert(Base::m_factorizationIsOk && "The decomposition is not in a valid state for solving, you must first call either compute() or symbolic()/numeric()");
+      eigen_assert(Base::m_matrix.rows()==b.rows());
+
+      if(Base::m_info!=Success)
+        return;
+
+      if(Base::m_P.size()>0)
+        dest = Base::m_P * b;
+      else
+        dest = b;
+
+      if(Base::m_matrix.nonZeros()>0) // otherwise L==I
+      {
+        if(m_LDLT)
+          LDLTTraits::getL(Base::m_matrix).solveInPlace(dest);
+        else
+          LLTTraits::getL(Base::m_matrix).solveInPlace(dest);
+      }
+
+      if(Base::m_diag.size()>0)
+        dest = Base::m_diag.real().asDiagonal().inverse() * dest;
+
+      if (Base::m_matrix.nonZeros()>0) // otherwise I==I
+      {
+        if(m_LDLT)
+          LDLTTraits::getU(Base::m_matrix).solveInPlace(dest);
+        else
+          LLTTraits::getU(Base::m_matrix).solveInPlace(dest);
+      }
+
+      if(Base::m_P.size()>0)
+        dest = Base::m_Pinv * dest;
+    }
+    
+    /** \internal */
+    template<typename Rhs,typename Dest>
+    void _solve_impl(const SparseMatrixBase<Rhs> &b, SparseMatrixBase<Dest> &dest) const
+    {
+      internal::solve_sparse_through_dense_panels(*this, b, dest);
+    }
+    
+    Scalar determinant() const
+    {
+      if(m_LDLT)
+      {
+        return Base::m_diag.prod();
+      }
+      else
+      {
+        Scalar detL = Diagonal<const CholMatrixType>(Base::m_matrix).prod();
+        return numext::abs2(detL);
+      }
+    }
+    
+  protected:
+    bool m_LDLT;
+};
+
+template<typename Derived>
+void SimplicialCholeskyBase<Derived>::ordering(const MatrixType& a, ConstCholMatrixPtr &pmat, CholMatrixType& ap)
+{
+  eigen_assert(a.rows()==a.cols());
+  const Index size = a.rows();
+  pmat = &ap;
+  // Note that ordering methods compute the inverse permutation
+  if(!internal::is_same<OrderingType,NaturalOrdering<Index> >::value)
+  {
+    {
+      CholMatrixType C;
+      C = a.template selfadjointView<UpLo>();
+      
+      OrderingType ordering;
+      ordering(C,m_Pinv);
+    }
+
+    if(m_Pinv.size()>0) m_P = m_Pinv.inverse();
+    else                m_P.resize(0);
+    
+    ap.resize(size,size);
+    ap.template selfadjointView<Upper>() = a.template selfadjointView<UpLo>().twistedBy(m_P);
+  }
+  else
+  {
+    m_Pinv.resize(0);
+    m_P.resize(0);
+    if(int(UpLo)==int(Lower) || MatrixType::IsRowMajor)
+    {
+      // we have to transpose the lower part to to the upper one
+      ap.resize(size,size);
+      ap.template selfadjointView<Upper>() = a.template selfadjointView<UpLo>();
+    }
+    else
+      internal::simplicial_cholesky_grab_input<CholMatrixType,MatrixType>::run(a, pmat, ap);
+  }  
+}
+
+} // end namespace Eigen
+
+#endif // EIGEN_SIMPLICIAL_CHOLESKY_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCholesky/SimplicialCholesky_impl.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCholesky/SimplicialCholesky_impl.h
new file mode 100644
index 0000000..72e1740
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCholesky/SimplicialCholesky_impl.h
@@ -0,0 +1,174 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2008-2012 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+/*
+NOTE: these functions have been adapted from the LDL library:
+
+LDL Copyright (c) 2005 by Timothy A. Davis.  All Rights Reserved.
+
+The author of LDL, Timothy A. Davis., has executed a license with Google LLC
+to permit distribution of this code and derivative works as part of Eigen under
+the Mozilla Public License v. 2.0, as stated at the top of this file.
+ */
+
+#ifndef EIGEN_SIMPLICIAL_CHOLESKY_IMPL_H
+#define EIGEN_SIMPLICIAL_CHOLESKY_IMPL_H
+
+namespace Eigen {
+
+template<typename Derived>
+void SimplicialCholeskyBase<Derived>::analyzePattern_preordered(const CholMatrixType& ap, bool doLDLT)
+{
+  const StorageIndex size = StorageIndex(ap.rows());
+  m_matrix.resize(size, size);
+  m_parent.resize(size);
+  m_nonZerosPerCol.resize(size);
+
+  ei_declare_aligned_stack_constructed_variable(StorageIndex, tags, size, 0);
+
+  for(StorageIndex k = 0; k < size; ++k)
+  {
+    /* L(k,:) pattern: all nodes reachable in etree from nz in A(0:k-1,k) */
+    m_parent[k] = -1;             /* parent of k is not yet known */
+    tags[k] = k;                  /* mark node k as visited */
+    m_nonZerosPerCol[k] = 0;      /* count of nonzeros in column k of L */
+    for(typename CholMatrixType::InnerIterator it(ap,k); it; ++it)
+    {
+      StorageIndex i = it.index();
+      if(i < k)
+      {
+        /* follow path from i to root of etree, stop at flagged node */
+        for(; tags[i] != k; i = m_parent[i])
+        {
+          /* find parent of i if not yet determined */
+          if (m_parent[i] == -1)
+            m_parent[i] = k;
+          m_nonZerosPerCol[i]++;        /* L (k,i) is nonzero */
+          tags[i] = k;                  /* mark i as visited */
+        }
+      }
+    }
+  }
+
+  /* construct Lp index array from m_nonZerosPerCol column counts */
+  StorageIndex* Lp = m_matrix.outerIndexPtr();
+  Lp[0] = 0;
+  for(StorageIndex k = 0; k < size; ++k)
+    Lp[k+1] = Lp[k] + m_nonZerosPerCol[k] + (doLDLT ? 0 : 1);
+
+  m_matrix.resizeNonZeros(Lp[size]);
+
+  m_isInitialized     = true;
+  m_info              = Success;
+  m_analysisIsOk      = true;
+  m_factorizationIsOk = false;
+}
+
+
+template<typename Derived>
+template<bool DoLDLT>
+void SimplicialCholeskyBase<Derived>::factorize_preordered(const CholMatrixType& ap)
+{
+  using std::sqrt;
+
+  eigen_assert(m_analysisIsOk && "You must first call analyzePattern()");
+  eigen_assert(ap.rows()==ap.cols());
+  eigen_assert(m_parent.size()==ap.rows());
+  eigen_assert(m_nonZerosPerCol.size()==ap.rows());
+
+  const StorageIndex size = StorageIndex(ap.rows());
+  const StorageIndex* Lp = m_matrix.outerIndexPtr();
+  StorageIndex* Li = m_matrix.innerIndexPtr();
+  Scalar* Lx = m_matrix.valuePtr();
+
+  ei_declare_aligned_stack_constructed_variable(Scalar, y, size, 0);
+  ei_declare_aligned_stack_constructed_variable(StorageIndex,  pattern, size, 0);
+  ei_declare_aligned_stack_constructed_variable(StorageIndex,  tags, size, 0);
+
+  bool ok = true;
+  m_diag.resize(DoLDLT ? size : 0);
+
+  for(StorageIndex k = 0; k < size; ++k)
+  {
+    // compute nonzero pattern of kth row of L, in topological order
+    y[k] = Scalar(0);                     // Y(0:k) is now all zero
+    StorageIndex top = size;               // stack for pattern is empty
+    tags[k] = k;                    // mark node k as visited
+    m_nonZerosPerCol[k] = 0;        // count of nonzeros in column k of L
+    for(typename CholMatrixType::InnerIterator it(ap,k); it; ++it)
+    {
+      StorageIndex i = it.index();
+      if(i <= k)
+      {
+        y[i] += numext::conj(it.value());            /* scatter A(i,k) into Y (sum duplicates) */
+        Index len;
+        for(len = 0; tags[i] != k; i = m_parent[i])
+        {
+          pattern[len++] = i;     /* L(k,i) is nonzero */
+          tags[i] = k;            /* mark i as visited */
+        }
+        while(len > 0)
+          pattern[--top] = pattern[--len];
+      }
+    }
+
+    /* compute numerical values kth row of L (a sparse triangular solve) */
+
+    RealScalar d = numext::real(y[k]) * m_shiftScale + m_shiftOffset;    // get D(k,k), apply the shift function, and clear Y(k)
+    y[k] = Scalar(0);
+    for(; top < size; ++top)
+    {
+      Index i = pattern[top];       /* pattern[top:n-1] is pattern of L(:,k) */
+      Scalar yi = y[i];             /* get and clear Y(i) */
+      y[i] = Scalar(0);
+
+      /* the nonzero entry L(k,i) */
+      Scalar l_ki;
+      if(DoLDLT)
+        l_ki = yi / numext::real(m_diag[i]);
+      else
+        yi = l_ki = yi / Lx[Lp[i]];
+
+      Index p2 = Lp[i] + m_nonZerosPerCol[i];
+      Index p;
+      for(p = Lp[i] + (DoLDLT ? 0 : 1); p < p2; ++p)
+        y[Li[p]] -= numext::conj(Lx[p]) * yi;
+      d -= numext::real(l_ki * numext::conj(yi));
+      Li[p] = k;                          /* store L(k,i) in column form of L */
+      Lx[p] = l_ki;
+      ++m_nonZerosPerCol[i];              /* increment count of nonzeros in col i */
+    }
+    if(DoLDLT)
+    {
+      m_diag[k] = d;
+      if(d == RealScalar(0))
+      {
+        ok = false;                         /* failure, D(k,k) is zero */
+        break;
+      }
+    }
+    else
+    {
+      Index p = Lp[k] + m_nonZerosPerCol[k]++;
+      Li[p] = k ;                /* store L(k,k) = sqrt (d) in column k */
+      if(d <= RealScalar(0)) {
+        ok = false;              /* failure, matrix is not positive definite */
+        break;
+      }
+      Lx[p] = sqrt(d) ;
+    }
+  }
+
+  m_info = ok ? Success : NumericalIssue;
+  m_factorizationIsOk = true;
+}
+
+} // end namespace Eigen
+
+#endif // EIGEN_SIMPLICIAL_CHOLESKY_IMPL_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/AmbiVector.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/AmbiVector.h
new file mode 100644
index 0000000..2cb7747
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/AmbiVector.h
@@ -0,0 +1,378 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_AMBIVECTOR_H
+#define EIGEN_AMBIVECTOR_H
+
+namespace Eigen { 
+
+namespace internal {
+
+/** \internal
+  * Hybrid sparse/dense vector class designed for intensive read-write operations.
+  *
+  * See BasicSparseLLT and SparseProduct for usage examples.
+  */
+template<typename _Scalar, typename _StorageIndex>
+class AmbiVector
+{
+  public:
+    typedef _Scalar Scalar;
+    typedef _StorageIndex StorageIndex;
+    typedef typename NumTraits<Scalar>::Real RealScalar;
+
+    explicit AmbiVector(Index size)
+      : m_buffer(0), m_zero(0), m_size(0), m_end(0), m_allocatedSize(0), m_allocatedElements(0), m_mode(-1)
+    {
+      resize(size);
+    }
+
+    void init(double estimatedDensity);
+    void init(int mode);
+
+    Index nonZeros() const;
+
+    /** Specifies a sub-vector to work on */
+    void setBounds(Index start, Index end) { m_start = convert_index(start); m_end = convert_index(end); }
+
+    void setZero();
+
+    void restart();
+    Scalar& coeffRef(Index i);
+    Scalar& coeff(Index i);
+
+    class Iterator;
+
+    ~AmbiVector() { delete[] m_buffer; }
+
+    void resize(Index size)
+    {
+      if (m_allocatedSize < size)
+        reallocate(size);
+      m_size = convert_index(size);
+    }
+
+    StorageIndex size() const { return m_size; }
+
+  protected:
+    StorageIndex convert_index(Index idx)
+    {
+      return internal::convert_index<StorageIndex>(idx);
+    }
+
+    void reallocate(Index size)
+    {
+      // if the size of the matrix is not too large, let's allocate a bit more than needed such
+      // that we can handle dense vector even in sparse mode.
+      delete[] m_buffer;
+      if (size<1000)
+      {
+        Index allocSize = (size * sizeof(ListEl) + sizeof(Scalar) - 1)/sizeof(Scalar);
+        m_allocatedElements = convert_index((allocSize*sizeof(Scalar))/sizeof(ListEl));
+        m_buffer = new Scalar[allocSize];
+      }
+      else
+      {
+        m_allocatedElements = convert_index((size*sizeof(Scalar))/sizeof(ListEl));
+        m_buffer = new Scalar[size];
+      }
+      m_size = convert_index(size);
+      m_start = 0;
+      m_end = m_size;
+    }
+
+    void reallocateSparse()
+    {
+      Index copyElements = m_allocatedElements;
+      m_allocatedElements = (std::min)(StorageIndex(m_allocatedElements*1.5),m_size);
+      Index allocSize = m_allocatedElements * sizeof(ListEl);
+      allocSize = (allocSize + sizeof(Scalar) - 1)/sizeof(Scalar);
+      Scalar* newBuffer = new Scalar[allocSize];
+      std::memcpy(newBuffer,  m_buffer,  copyElements * sizeof(ListEl));
+      delete[] m_buffer;
+      m_buffer = newBuffer;
+    }
+
+  protected:
+    // element type of the linked list
+    struct ListEl
+    {
+      StorageIndex next;
+      StorageIndex index;
+      Scalar value;
+    };
+
+    // used to store data in both mode
+    Scalar* m_buffer;
+    Scalar m_zero;
+    StorageIndex m_size;
+    StorageIndex m_start;
+    StorageIndex m_end;
+    StorageIndex m_allocatedSize;
+    StorageIndex m_allocatedElements;
+    StorageIndex m_mode;
+
+    // linked list mode
+    StorageIndex m_llStart;
+    StorageIndex m_llCurrent;
+    StorageIndex m_llSize;
+};
+
+/** \returns the number of non zeros in the current sub vector */
+template<typename _Scalar,typename _StorageIndex>
+Index AmbiVector<_Scalar,_StorageIndex>::nonZeros() const
+{
+  if (m_mode==IsSparse)
+    return m_llSize;
+  else
+    return m_end - m_start;
+}
+
+template<typename _Scalar,typename _StorageIndex>
+void AmbiVector<_Scalar,_StorageIndex>::init(double estimatedDensity)
+{
+  if (estimatedDensity>0.1)
+    init(IsDense);
+  else
+    init(IsSparse);
+}
+
+template<typename _Scalar,typename _StorageIndex>
+void AmbiVector<_Scalar,_StorageIndex>::init(int mode)
+{
+  m_mode = mode;
+  // This is only necessary in sparse mode, but we set these unconditionally to avoid some maybe-uninitialized warnings
+  // if (m_mode==IsSparse)
+  {
+    m_llSize = 0;
+    m_llStart = -1;
+  }
+}
+
+/** Must be called whenever we might perform a write access
+  * with an index smaller than the previous one.
+  *
+  * Don't worry, this function is extremely cheap.
+  */
+template<typename _Scalar,typename _StorageIndex>
+void AmbiVector<_Scalar,_StorageIndex>::restart()
+{
+  m_llCurrent = m_llStart;
+}
+
+/** Set all coefficients of current subvector to zero */
+template<typename _Scalar,typename _StorageIndex>
+void AmbiVector<_Scalar,_StorageIndex>::setZero()
+{
+  if (m_mode==IsDense)
+  {
+    for (Index i=m_start; i<m_end; ++i)
+      m_buffer[i] = Scalar(0);
+  }
+  else
+  {
+    eigen_assert(m_mode==IsSparse);
+    m_llSize = 0;
+    m_llStart = -1;
+  }
+}
+
+template<typename _Scalar,typename _StorageIndex>
+_Scalar& AmbiVector<_Scalar,_StorageIndex>::coeffRef(Index i)
+{
+  if (m_mode==IsDense)
+    return m_buffer[i];
+  else
+  {
+    ListEl* EIGEN_RESTRICT llElements = reinterpret_cast<ListEl*>(m_buffer);
+    // TODO factorize the following code to reduce code generation
+    eigen_assert(m_mode==IsSparse);
+    if (m_llSize==0)
+    {
+      // this is the first element
+      m_llStart = 0;
+      m_llCurrent = 0;
+      ++m_llSize;
+      llElements[0].value = Scalar(0);
+      llElements[0].index = convert_index(i);
+      llElements[0].next = -1;
+      return llElements[0].value;
+    }
+    else if (i<llElements[m_llStart].index)
+    {
+      // this is going to be the new first element of the list
+      ListEl& el = llElements[m_llSize];
+      el.value = Scalar(0);
+      el.index = convert_index(i);
+      el.next = m_llStart;
+      m_llStart = m_llSize;
+      ++m_llSize;
+      m_llCurrent = m_llStart;
+      return el.value;
+    }
+    else
+    {
+      StorageIndex nextel = llElements[m_llCurrent].next;
+      eigen_assert(i>=llElements[m_llCurrent].index && "you must call restart() before inserting an element with lower or equal index");
+      while (nextel >= 0 && llElements[nextel].index<=i)
+      {
+        m_llCurrent = nextel;
+        nextel = llElements[nextel].next;
+      }
+
+      if (llElements[m_llCurrent].index==i)
+      {
+        // the coefficient already exists and we found it !
+        return llElements[m_llCurrent].value;
+      }
+      else
+      {
+        if (m_llSize>=m_allocatedElements)
+        {
+          reallocateSparse();
+          llElements = reinterpret_cast<ListEl*>(m_buffer);
+        }
+        eigen_internal_assert(m_llSize<m_allocatedElements && "internal error: overflow in sparse mode");
+        // let's insert a new coefficient
+        ListEl& el = llElements[m_llSize];
+        el.value = Scalar(0);
+        el.index = convert_index(i);
+        el.next = llElements[m_llCurrent].next;
+        llElements[m_llCurrent].next = m_llSize;
+        ++m_llSize;
+        return el.value;
+      }
+    }
+  }
+}
+
+template<typename _Scalar,typename _StorageIndex>
+_Scalar& AmbiVector<_Scalar,_StorageIndex>::coeff(Index i)
+{
+  if (m_mode==IsDense)
+    return m_buffer[i];
+  else
+  {
+    ListEl* EIGEN_RESTRICT llElements = reinterpret_cast<ListEl*>(m_buffer);
+    eigen_assert(m_mode==IsSparse);
+    if ((m_llSize==0) || (i<llElements[m_llStart].index))
+    {
+      return m_zero;
+    }
+    else
+    {
+      Index elid = m_llStart;
+      while (elid >= 0 && llElements[elid].index<i)
+        elid = llElements[elid].next;
+
+      if (llElements[elid].index==i)
+        return llElements[m_llCurrent].value;
+      else
+        return m_zero;
+    }
+  }
+}
+
+/** Iterator over the nonzero coefficients */
+template<typename _Scalar,typename _StorageIndex>
+class AmbiVector<_Scalar,_StorageIndex>::Iterator
+{
+  public:
+    typedef _Scalar Scalar;
+    typedef typename NumTraits<Scalar>::Real RealScalar;
+
+    /** Default constructor
+      * \param vec the vector on which we iterate
+      * \param epsilon the minimal value used to prune zero coefficients.
+      * In practice, all coefficients having a magnitude smaller than \a epsilon
+      * are skipped.
+      */
+    explicit Iterator(const AmbiVector& vec, const RealScalar& epsilon = 0)
+      : m_vector(vec)
+    {
+      using std::abs;
+      m_epsilon = epsilon;
+      m_isDense = m_vector.m_mode==IsDense;
+      if (m_isDense)
+      {
+        m_currentEl = 0;   // this is to avoid a compilation warning
+        m_cachedValue = 0; // this is to avoid a compilation warning
+        m_cachedIndex = m_vector.m_start-1;
+        ++(*this);
+      }
+      else
+      {
+        ListEl* EIGEN_RESTRICT llElements = reinterpret_cast<ListEl*>(m_vector.m_buffer);
+        m_currentEl = m_vector.m_llStart;
+        while (m_currentEl>=0 && abs(llElements[m_currentEl].value)<=m_epsilon)
+          m_currentEl = llElements[m_currentEl].next;
+        if (m_currentEl<0)
+        {
+          m_cachedValue = 0; // this is to avoid a compilation warning
+          m_cachedIndex = -1;
+        }
+        else
+        {
+          m_cachedIndex = llElements[m_currentEl].index;
+          m_cachedValue = llElements[m_currentEl].value;
+        }
+      }
+    }
+
+    StorageIndex index() const { return m_cachedIndex; }
+    Scalar value() const { return m_cachedValue; }
+
+    operator bool() const { return m_cachedIndex>=0; }
+
+    Iterator& operator++()
+    {
+      using std::abs;
+      if (m_isDense)
+      {
+        do {
+          ++m_cachedIndex;
+        } while (m_cachedIndex<m_vector.m_end && abs(m_vector.m_buffer[m_cachedIndex])<=m_epsilon);
+        if (m_cachedIndex<m_vector.m_end)
+          m_cachedValue = m_vector.m_buffer[m_cachedIndex];
+        else
+          m_cachedIndex=-1;
+      }
+      else
+      {
+        ListEl* EIGEN_RESTRICT llElements = reinterpret_cast<ListEl*>(m_vector.m_buffer);
+        do {
+          m_currentEl = llElements[m_currentEl].next;
+        } while (m_currentEl>=0 && abs(llElements[m_currentEl].value)<=m_epsilon);
+        if (m_currentEl<0)
+        {
+          m_cachedIndex = -1;
+        }
+        else
+        {
+          m_cachedIndex = llElements[m_currentEl].index;
+          m_cachedValue = llElements[m_currentEl].value;
+        }
+      }
+      return *this;
+    }
+
+  protected:
+    const AmbiVector& m_vector; // the target vector
+    StorageIndex m_currentEl;   // the current element in sparse/linked-list mode
+    RealScalar m_epsilon;       // epsilon used to prune zero coefficients
+    StorageIndex m_cachedIndex; // current coordinate
+    Scalar m_cachedValue;       // current value
+    bool m_isDense;             // mode of the vector
+};
+
+} // end namespace internal
+
+} // end namespace Eigen
+
+#endif // EIGEN_AMBIVECTOR_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/CompressedStorage.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/CompressedStorage.h
new file mode 100644
index 0000000..acd986f
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/CompressedStorage.h
@@ -0,0 +1,274 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2008-2014 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_COMPRESSED_STORAGE_H
+#define EIGEN_COMPRESSED_STORAGE_H
+
+namespace Eigen { 
+
+namespace internal {
+
+/** \internal
+  * Stores a sparse set of values as a list of values and a list of indices.
+  *
+  */
+template<typename _Scalar,typename _StorageIndex>
+class CompressedStorage
+{
+  public:
+
+    typedef _Scalar Scalar;
+    typedef _StorageIndex StorageIndex;
+
+  protected:
+
+    typedef typename NumTraits<Scalar>::Real RealScalar;
+
+  public:
+
+    CompressedStorage()
+      : m_values(0), m_indices(0), m_size(0), m_allocatedSize(0)
+    {}
+
+    explicit CompressedStorage(Index size)
+      : m_values(0), m_indices(0), m_size(0), m_allocatedSize(0)
+    {
+      resize(size);
+    }
+
+    CompressedStorage(const CompressedStorage& other)
+      : m_values(0), m_indices(0), m_size(0), m_allocatedSize(0)
+    {
+      *this = other;
+    }
+
+    CompressedStorage& operator=(const CompressedStorage& other)
+    {
+      resize(other.size());
+      if(other.size()>0)
+      {
+        internal::smart_copy(other.m_values,  other.m_values  + m_size, m_values);
+        internal::smart_copy(other.m_indices, other.m_indices + m_size, m_indices);
+      }
+      return *this;
+    }
+
+    void swap(CompressedStorage& other)
+    {
+      std::swap(m_values, other.m_values);
+      std::swap(m_indices, other.m_indices);
+      std::swap(m_size, other.m_size);
+      std::swap(m_allocatedSize, other.m_allocatedSize);
+    }
+
+    ~CompressedStorage()
+    {
+      delete[] m_values;
+      delete[] m_indices;
+    }
+
+    void reserve(Index size)
+    {
+      Index newAllocatedSize = m_size + size;
+      if (newAllocatedSize > m_allocatedSize)
+        reallocate(newAllocatedSize);
+    }
+
+    void squeeze()
+    {
+      if (m_allocatedSize>m_size)
+        reallocate(m_size);
+    }
+
+    void resize(Index size, double reserveSizeFactor = 0)
+    {
+      if (m_allocatedSize<size)
+      {
+        Index realloc_size = (std::min<Index>)(NumTraits<StorageIndex>::highest(),  size + Index(reserveSizeFactor*double(size)));
+        if(realloc_size<size)
+          internal::throw_std_bad_alloc();
+        reallocate(realloc_size);
+      }
+      m_size = size;
+    }
+
+    void append(const Scalar& v, Index i)
+    {
+      Index id = m_size;
+      resize(m_size+1, 1);
+      m_values[id] = v;
+      m_indices[id] = internal::convert_index<StorageIndex>(i);
+    }
+
+    inline Index size() const { return m_size; }
+    inline Index allocatedSize() const { return m_allocatedSize; }
+    inline void clear() { m_size = 0; }
+
+    const Scalar* valuePtr() const { return m_values; }
+    Scalar* valuePtr() { return m_values; }
+    const StorageIndex* indexPtr() const { return m_indices; }
+    StorageIndex* indexPtr() { return m_indices; }
+
+    inline Scalar& value(Index i) { eigen_internal_assert(m_values!=0); return m_values[i]; }
+    inline const Scalar& value(Index i) const { eigen_internal_assert(m_values!=0); return m_values[i]; }
+
+    inline StorageIndex& index(Index i) { eigen_internal_assert(m_indices!=0); return m_indices[i]; }
+    inline const StorageIndex& index(Index i) const { eigen_internal_assert(m_indices!=0); return m_indices[i]; }
+
+    /** \returns the largest \c k such that for all \c j in [0,k) index[\c j]\<\a key */
+    inline Index searchLowerIndex(Index key) const
+    {
+      return searchLowerIndex(0, m_size, key);
+    }
+
+    /** \returns the largest \c k in [start,end) such that for all \c j in [start,k) index[\c j]\<\a key */
+    inline Index searchLowerIndex(Index start, Index end, Index key) const
+    {
+      while(end>start)
+      {
+        Index mid = (end+start)>>1;
+        if (m_indices[mid]<key)
+          start = mid+1;
+        else
+          end = mid;
+      }
+      return start;
+    }
+
+    /** \returns the stored value at index \a key
+      * If the value does not exist, then the value \a defaultValue is returned without any insertion. */
+    inline Scalar at(Index key, const Scalar& defaultValue = Scalar(0)) const
+    {
+      if (m_size==0)
+        return defaultValue;
+      else if (key==m_indices[m_size-1])
+        return m_values[m_size-1];
+      // ^^  optimization: let's first check if it is the last coefficient
+      // (very common in high level algorithms)
+      const Index id = searchLowerIndex(0,m_size-1,key);
+      return ((id<m_size) && (m_indices[id]==key)) ? m_values[id] : defaultValue;
+    }
+
+    /** Like at(), but the search is performed in the range [start,end) */
+    inline Scalar atInRange(Index start, Index end, Index key, const Scalar &defaultValue = Scalar(0)) const
+    {
+      if (start>=end)
+        return defaultValue;
+      else if (end>start && key==m_indices[end-1])
+        return m_values[end-1];
+      // ^^  optimization: let's first check if it is the last coefficient
+      // (very common in high level algorithms)
+      const Index id = searchLowerIndex(start,end-1,key);
+      return ((id<end) && (m_indices[id]==key)) ? m_values[id] : defaultValue;
+    }
+
+    /** \returns a reference to the value at index \a key
+      * If the value does not exist, then the value \a defaultValue is inserted
+      * such that the keys are sorted. */
+    inline Scalar& atWithInsertion(Index key, const Scalar& defaultValue = Scalar(0))
+    {
+      Index id = searchLowerIndex(0,m_size,key);
+      if (id>=m_size || m_indices[id]!=key)
+      {
+        if (m_allocatedSize<m_size+1)
+        {
+          m_allocatedSize = 2*(m_size+1);
+          internal::scoped_array<Scalar> newValues(m_allocatedSize);
+          internal::scoped_array<StorageIndex> newIndices(m_allocatedSize);
+
+          // copy first chunk
+          internal::smart_copy(m_values,  m_values +id, newValues.ptr());
+          internal::smart_copy(m_indices, m_indices+id, newIndices.ptr());
+
+          // copy the rest
+          if(m_size>id)
+          {
+            internal::smart_copy(m_values +id,  m_values +m_size, newValues.ptr() +id+1);
+            internal::smart_copy(m_indices+id,  m_indices+m_size, newIndices.ptr()+id+1);
+          }
+          std::swap(m_values,newValues.ptr());
+          std::swap(m_indices,newIndices.ptr());
+        }
+        else if(m_size>id)
+        {
+          internal::smart_memmove(m_values +id, m_values +m_size, m_values +id+1);
+          internal::smart_memmove(m_indices+id, m_indices+m_size, m_indices+id+1);
+        }
+        m_size++;
+        m_indices[id] = internal::convert_index<StorageIndex>(key);
+        m_values[id] = defaultValue;
+      }
+      return m_values[id];
+    }
+
+    void moveChunk(Index from, Index to, Index chunkSize)
+    {
+      eigen_internal_assert(to+chunkSize <= m_size);
+      if(to>from && from+chunkSize>to)
+      {
+        // move backward
+        internal::smart_memmove(m_values+from,  m_values+from+chunkSize,  m_values+to);
+        internal::smart_memmove(m_indices+from, m_indices+from+chunkSize, m_indices+to);
+      }
+      else
+      {
+        internal::smart_copy(m_values+from,  m_values+from+chunkSize,  m_values+to);
+        internal::smart_copy(m_indices+from, m_indices+from+chunkSize, m_indices+to);
+      }
+    }
+
+    void prune(const Scalar& reference, const RealScalar& epsilon = NumTraits<RealScalar>::dummy_precision())
+    {
+      Index k = 0;
+      Index n = size();
+      for (Index i=0; i<n; ++i)
+      {
+        if (!internal::isMuchSmallerThan(value(i), reference, epsilon))
+        {
+          value(k) = value(i);
+          index(k) = index(i);
+          ++k;
+        }
+      }
+      resize(k,0);
+    }
+
+  protected:
+
+    inline void reallocate(Index size)
+    {
+      #ifdef EIGEN_SPARSE_COMPRESSED_STORAGE_REALLOCATE_PLUGIN
+        EIGEN_SPARSE_COMPRESSED_STORAGE_REALLOCATE_PLUGIN
+      #endif
+      eigen_internal_assert(size!=m_allocatedSize);
+      internal::scoped_array<Scalar> newValues(size);
+      internal::scoped_array<StorageIndex> newIndices(size);
+      Index copySize = (std::min)(size, m_size);
+      if (copySize>0) {
+        internal::smart_copy(m_values, m_values+copySize, newValues.ptr());
+        internal::smart_copy(m_indices, m_indices+copySize, newIndices.ptr());
+      }
+      std::swap(m_values,newValues.ptr());
+      std::swap(m_indices,newIndices.ptr());
+      m_allocatedSize = size;
+    }
+
+  protected:
+    Scalar* m_values;
+    StorageIndex* m_indices;
+    Index m_size;
+    Index m_allocatedSize;
+
+};
+
+} // end namespace internal
+
+} // end namespace Eigen
+
+#endif // EIGEN_COMPRESSED_STORAGE_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/ConservativeSparseSparseProduct.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/ConservativeSparseSparseProduct.h
new file mode 100644
index 0000000..9486502
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/ConservativeSparseSparseProduct.h
@@ -0,0 +1,352 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2008-2015 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_CONSERVATIVESPARSESPARSEPRODUCT_H
+#define EIGEN_CONSERVATIVESPARSESPARSEPRODUCT_H
+
+namespace Eigen {
+
+namespace internal {
+
+template<typename Lhs, typename Rhs, typename ResultType>
+static void conservative_sparse_sparse_product_impl(const Lhs& lhs, const Rhs& rhs, ResultType& res, bool sortedInsertion = false)
+{
+  typedef typename remove_all<Lhs>::type::Scalar LhsScalar;
+  typedef typename remove_all<Rhs>::type::Scalar RhsScalar;
+  typedef typename remove_all<ResultType>::type::Scalar ResScalar;
+
+  // make sure to call innerSize/outerSize since we fake the storage order.
+  Index rows = lhs.innerSize();
+  Index cols = rhs.outerSize();
+  eigen_assert(lhs.outerSize() == rhs.innerSize());
+
+  ei_declare_aligned_stack_constructed_variable(bool,   mask,     rows, 0);
+  ei_declare_aligned_stack_constructed_variable(ResScalar, values,   rows, 0);
+  ei_declare_aligned_stack_constructed_variable(Index,  indices,  rows, 0);
+
+  std::memset(mask,0,sizeof(bool)*rows);
+
+  evaluator<Lhs> lhsEval(lhs);
+  evaluator<Rhs> rhsEval(rhs);
+
+  // estimate the number of non zero entries
+  // given a rhs column containing Y non zeros, we assume that the respective Y columns
+  // of the lhs differs in average of one non zeros, thus the number of non zeros for
+  // the product of a rhs column with the lhs is X+Y where X is the average number of non zero
+  // per column of the lhs.
+  // Therefore, we have nnz(lhs*rhs) = nnz(lhs) + nnz(rhs)
+  Index estimated_nnz_prod = lhsEval.nonZerosEstimate() + rhsEval.nonZerosEstimate();
+
+  res.setZero();
+  res.reserve(Index(estimated_nnz_prod));
+  // we compute each column of the result, one after the other
+  for (Index j=0; j<cols; ++j)
+  {
+
+    res.startVec(j);
+    Index nnz = 0;
+    for (typename evaluator<Rhs>::InnerIterator rhsIt(rhsEval, j); rhsIt; ++rhsIt)
+    {
+      RhsScalar y = rhsIt.value();
+      Index k = rhsIt.index();
+      for (typename evaluator<Lhs>::InnerIterator lhsIt(lhsEval, k); lhsIt; ++lhsIt)
+      {
+        Index i = lhsIt.index();
+        LhsScalar x = lhsIt.value();
+        if(!mask[i])
+        {
+          mask[i] = true;
+          values[i] = x * y;
+          indices[nnz] = i;
+          ++nnz;
+        }
+        else
+          values[i] += x * y;
+      }
+    }
+    if(!sortedInsertion)
+    {
+      // unordered insertion
+      for(Index k=0; k<nnz; ++k)
+      {
+        Index i = indices[k];
+        res.insertBackByOuterInnerUnordered(j,i) = values[i];
+        mask[i] = false;
+      }
+    }
+    else
+    {
+      // alternative ordered insertion code:
+      const Index t200 = rows/11; // 11 == (log2(200)*1.39)
+      const Index t = (rows*100)/139;
+
+      // FIXME reserve nnz non zeros
+      // FIXME implement faster sorting algorithms for very small nnz
+      // if the result is sparse enough => use a quick sort
+      // otherwise => loop through the entire vector
+      // In order to avoid to perform an expensive log2 when the
+      // result is clearly very sparse we use a linear bound up to 200.
+      if((nnz<200 && nnz<t200) || nnz * numext::log2(int(nnz)) < t)
+      {
+        if(nnz>1) std::sort(indices,indices+nnz);
+        for(Index k=0; k<nnz; ++k)
+        {
+          Index i = indices[k];
+          res.insertBackByOuterInner(j,i) = values[i];
+          mask[i] = false;
+        }
+      }
+      else
+      {
+        // dense path
+        for(Index i=0; i<rows; ++i)
+        {
+          if(mask[i])
+          {
+            mask[i] = false;
+            res.insertBackByOuterInner(j,i) = values[i];
+          }
+        }
+      }
+    }
+  }
+  res.finalize();
+}
+
+
+} // end namespace internal
+
+namespace internal {
+
+template<typename Lhs, typename Rhs, typename ResultType,
+  int LhsStorageOrder = (traits<Lhs>::Flags&RowMajorBit) ? RowMajor : ColMajor,
+  int RhsStorageOrder = (traits<Rhs>::Flags&RowMajorBit) ? RowMajor : ColMajor,
+  int ResStorageOrder = (traits<ResultType>::Flags&RowMajorBit) ? RowMajor : ColMajor>
+struct conservative_sparse_sparse_product_selector;
+
+template<typename Lhs, typename Rhs, typename ResultType>
+struct conservative_sparse_sparse_product_selector<Lhs,Rhs,ResultType,ColMajor,ColMajor,ColMajor>
+{
+  typedef typename remove_all<Lhs>::type LhsCleaned;
+  typedef typename LhsCleaned::Scalar Scalar;
+
+  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res)
+  {
+    typedef SparseMatrix<typename ResultType::Scalar,RowMajor,typename ResultType::StorageIndex> RowMajorMatrix;
+    typedef SparseMatrix<typename ResultType::Scalar,ColMajor,typename ResultType::StorageIndex> ColMajorMatrixAux;
+    typedef typename sparse_eval<ColMajorMatrixAux,ResultType::RowsAtCompileTime,ResultType::ColsAtCompileTime,ColMajorMatrixAux::Flags>::type ColMajorMatrix;
+
+    // If the result is tall and thin (in the extreme case a column vector)
+    // then it is faster to sort the coefficients inplace instead of transposing twice.
+    // FIXME, the following heuristic is probably not very good.
+    if(lhs.rows()>rhs.cols())
+    {
+      ColMajorMatrix resCol(lhs.rows(),rhs.cols());
+      // perform sorted insertion
+      internal::conservative_sparse_sparse_product_impl<Lhs,Rhs,ColMajorMatrix>(lhs, rhs, resCol, true);
+      res = resCol.markAsRValue();
+    }
+    else
+    {
+      ColMajorMatrixAux resCol(lhs.rows(),rhs.cols());
+      // resort to transpose to sort the entries
+      internal::conservative_sparse_sparse_product_impl<Lhs,Rhs,ColMajorMatrixAux>(lhs, rhs, resCol, false);
+      RowMajorMatrix resRow(resCol);
+      res = resRow.markAsRValue();
+    }
+  }
+};
+
+template<typename Lhs, typename Rhs, typename ResultType>
+struct conservative_sparse_sparse_product_selector<Lhs,Rhs,ResultType,RowMajor,ColMajor,ColMajor>
+{
+  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res)
+  {
+    typedef SparseMatrix<typename Rhs::Scalar,RowMajor,typename ResultType::StorageIndex> RowMajorRhs;
+    typedef SparseMatrix<typename ResultType::Scalar,RowMajor,typename ResultType::StorageIndex> RowMajorRes;
+    RowMajorRhs rhsRow = rhs;
+    RowMajorRes resRow(lhs.rows(), rhs.cols());
+    internal::conservative_sparse_sparse_product_impl<RowMajorRhs,Lhs,RowMajorRes>(rhsRow, lhs, resRow);
+    res = resRow;
+  }
+};
+
+template<typename Lhs, typename Rhs, typename ResultType>
+struct conservative_sparse_sparse_product_selector<Lhs,Rhs,ResultType,ColMajor,RowMajor,ColMajor>
+{
+  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res)
+  {
+    typedef SparseMatrix<typename Lhs::Scalar,RowMajor,typename ResultType::StorageIndex> RowMajorLhs;
+    typedef SparseMatrix<typename ResultType::Scalar,RowMajor,typename ResultType::StorageIndex> RowMajorRes;
+    RowMajorLhs lhsRow = lhs;
+    RowMajorRes resRow(lhs.rows(), rhs.cols());
+    internal::conservative_sparse_sparse_product_impl<Rhs,RowMajorLhs,RowMajorRes>(rhs, lhsRow, resRow);
+    res = resRow;
+  }
+};
+
+template<typename Lhs, typename Rhs, typename ResultType>
+struct conservative_sparse_sparse_product_selector<Lhs,Rhs,ResultType,RowMajor,RowMajor,ColMajor>
+{
+  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res)
+  {
+    typedef SparseMatrix<typename ResultType::Scalar,RowMajor,typename ResultType::StorageIndex> RowMajorMatrix;
+    RowMajorMatrix resRow(lhs.rows(), rhs.cols());
+    internal::conservative_sparse_sparse_product_impl<Rhs,Lhs,RowMajorMatrix>(rhs, lhs, resRow);
+    res = resRow;
+  }
+};
+
+
+template<typename Lhs, typename Rhs, typename ResultType>
+struct conservative_sparse_sparse_product_selector<Lhs,Rhs,ResultType,ColMajor,ColMajor,RowMajor>
+{
+  typedef typename traits<typename remove_all<Lhs>::type>::Scalar Scalar;
+
+  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res)
+  {
+    typedef SparseMatrix<typename ResultType::Scalar,ColMajor,typename ResultType::StorageIndex> ColMajorMatrix;
+    ColMajorMatrix resCol(lhs.rows(), rhs.cols());
+    internal::conservative_sparse_sparse_product_impl<Lhs,Rhs,ColMajorMatrix>(lhs, rhs, resCol);
+    res = resCol;
+  }
+};
+
+template<typename Lhs, typename Rhs, typename ResultType>
+struct conservative_sparse_sparse_product_selector<Lhs,Rhs,ResultType,RowMajor,ColMajor,RowMajor>
+{
+  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res)
+  {
+    typedef SparseMatrix<typename Lhs::Scalar,ColMajor,typename ResultType::StorageIndex> ColMajorLhs;
+    typedef SparseMatrix<typename ResultType::Scalar,ColMajor,typename ResultType::StorageIndex> ColMajorRes;
+    ColMajorLhs lhsCol = lhs;
+    ColMajorRes resCol(lhs.rows(), rhs.cols());
+    internal::conservative_sparse_sparse_product_impl<ColMajorLhs,Rhs,ColMajorRes>(lhsCol, rhs, resCol);
+    res = resCol;
+  }
+};
+
+template<typename Lhs, typename Rhs, typename ResultType>
+struct conservative_sparse_sparse_product_selector<Lhs,Rhs,ResultType,ColMajor,RowMajor,RowMajor>
+{
+  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res)
+  {
+    typedef SparseMatrix<typename Rhs::Scalar,ColMajor,typename ResultType::StorageIndex> ColMajorRhs;
+    typedef SparseMatrix<typename ResultType::Scalar,ColMajor,typename ResultType::StorageIndex> ColMajorRes;
+    ColMajorRhs rhsCol = rhs;
+    ColMajorRes resCol(lhs.rows(), rhs.cols());
+    internal::conservative_sparse_sparse_product_impl<Lhs,ColMajorRhs,ColMajorRes>(lhs, rhsCol, resCol);
+    res = resCol;
+  }
+};
+
+template<typename Lhs, typename Rhs, typename ResultType>
+struct conservative_sparse_sparse_product_selector<Lhs,Rhs,ResultType,RowMajor,RowMajor,RowMajor>
+{
+  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res)
+  {
+    typedef SparseMatrix<typename ResultType::Scalar,RowMajor,typename ResultType::StorageIndex> RowMajorMatrix;
+    typedef SparseMatrix<typename ResultType::Scalar,ColMajor,typename ResultType::StorageIndex> ColMajorMatrix;
+    RowMajorMatrix resRow(lhs.rows(),rhs.cols());
+    internal::conservative_sparse_sparse_product_impl<Rhs,Lhs,RowMajorMatrix>(rhs, lhs, resRow);
+    // sort the non zeros:
+    ColMajorMatrix resCol(resRow);
+    res = resCol;
+  }
+};
+
+} // end namespace internal
+
+
+namespace internal {
+
+template<typename Lhs, typename Rhs, typename ResultType>
+static void sparse_sparse_to_dense_product_impl(const Lhs& lhs, const Rhs& rhs, ResultType& res)
+{
+  typedef typename remove_all<Lhs>::type::Scalar LhsScalar;
+  typedef typename remove_all<Rhs>::type::Scalar RhsScalar;
+  Index cols = rhs.outerSize();
+  eigen_assert(lhs.outerSize() == rhs.innerSize());
+
+  evaluator<Lhs> lhsEval(lhs);
+  evaluator<Rhs> rhsEval(rhs);
+
+  for (Index j=0; j<cols; ++j)
+  {
+    for (typename evaluator<Rhs>::InnerIterator rhsIt(rhsEval, j); rhsIt; ++rhsIt)
+    {
+      RhsScalar y = rhsIt.value();
+      Index k = rhsIt.index();
+      for (typename evaluator<Lhs>::InnerIterator lhsIt(lhsEval, k); lhsIt; ++lhsIt)
+      {
+        Index i = lhsIt.index();
+        LhsScalar x = lhsIt.value();
+        res.coeffRef(i,j) += x * y;
+      }
+    }
+  }
+}
+
+
+} // end namespace internal
+
+namespace internal {
+
+template<typename Lhs, typename Rhs, typename ResultType,
+  int LhsStorageOrder = (traits<Lhs>::Flags&RowMajorBit) ? RowMajor : ColMajor,
+  int RhsStorageOrder = (traits<Rhs>::Flags&RowMajorBit) ? RowMajor : ColMajor>
+struct sparse_sparse_to_dense_product_selector;
+
+template<typename Lhs, typename Rhs, typename ResultType>
+struct sparse_sparse_to_dense_product_selector<Lhs,Rhs,ResultType,ColMajor,ColMajor>
+{
+  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res)
+  {
+    internal::sparse_sparse_to_dense_product_impl<Lhs,Rhs,ResultType>(lhs, rhs, res);
+  }
+};
+
+template<typename Lhs, typename Rhs, typename ResultType>
+struct sparse_sparse_to_dense_product_selector<Lhs,Rhs,ResultType,RowMajor,ColMajor>
+{
+  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res)
+  {
+    typedef SparseMatrix<typename Lhs::Scalar,ColMajor,typename ResultType::StorageIndex> ColMajorLhs;
+    ColMajorLhs lhsCol(lhs);
+    internal::sparse_sparse_to_dense_product_impl<ColMajorLhs,Rhs,ResultType>(lhsCol, rhs, res);
+  }
+};
+
+template<typename Lhs, typename Rhs, typename ResultType>
+struct sparse_sparse_to_dense_product_selector<Lhs,Rhs,ResultType,ColMajor,RowMajor>
+{
+  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res)
+  {
+    typedef SparseMatrix<typename Rhs::Scalar,ColMajor,typename ResultType::StorageIndex> ColMajorRhs;
+    ColMajorRhs rhsCol(rhs);
+    internal::sparse_sparse_to_dense_product_impl<Lhs,ColMajorRhs,ResultType>(lhs, rhsCol, res);
+  }
+};
+
+template<typename Lhs, typename Rhs, typename ResultType>
+struct sparse_sparse_to_dense_product_selector<Lhs,Rhs,ResultType,RowMajor,RowMajor>
+{
+  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res)
+  {
+    Transpose<ResultType> trRes(res);
+    internal::sparse_sparse_to_dense_product_impl<Rhs,Lhs,Transpose<ResultType> >(rhs, lhs, trRes);
+  }
+};
+
+
+} // end namespace internal
+
+} // end namespace Eigen
+
+#endif // EIGEN_CONSERVATIVESPARSESPARSEPRODUCT_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/MappedSparseMatrix.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/MappedSparseMatrix.h
new file mode 100644
index 0000000..67718c8
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/MappedSparseMatrix.h
@@ -0,0 +1,67 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2008-2014 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_MAPPED_SPARSEMATRIX_H
+#define EIGEN_MAPPED_SPARSEMATRIX_H
+
+namespace Eigen {
+
+/** \deprecated Use Map<SparseMatrix<> >
+  * \class MappedSparseMatrix
+  *
+  * \brief Sparse matrix
+  *
+  * \param _Scalar the scalar type, i.e. the type of the coefficients
+  *
+  * See http://www.netlib.org/linalg/html_templates/node91.html for details on the storage scheme.
+  *
+  */
+namespace internal {
+template<typename _Scalar, int _Flags, typename _StorageIndex>
+struct traits<MappedSparseMatrix<_Scalar, _Flags, _StorageIndex> > : traits<SparseMatrix<_Scalar, _Flags, _StorageIndex> >
+{};
+} // end namespace internal
+
+template<typename _Scalar, int _Flags, typename _StorageIndex>
+class MappedSparseMatrix
+  : public Map<SparseMatrix<_Scalar, _Flags, _StorageIndex> >
+{
+    typedef Map<SparseMatrix<_Scalar, _Flags, _StorageIndex> > Base;
+
+  public:
+    
+    typedef typename Base::StorageIndex StorageIndex;
+    typedef typename Base::Scalar Scalar;
+
+    inline MappedSparseMatrix(Index rows, Index cols, Index nnz, StorageIndex* outerIndexPtr, StorageIndex* innerIndexPtr, Scalar* valuePtr, StorageIndex* innerNonZeroPtr = 0)
+      : Base(rows, cols, nnz, outerIndexPtr, innerIndexPtr, valuePtr, innerNonZeroPtr)
+    {}
+
+    /** Empty destructor */
+    inline ~MappedSparseMatrix() {}
+};
+
+namespace internal {
+
+template<typename _Scalar, int _Options, typename _StorageIndex>
+struct evaluator<MappedSparseMatrix<_Scalar,_Options,_StorageIndex> >
+  : evaluator<SparseCompressedBase<MappedSparseMatrix<_Scalar,_Options,_StorageIndex> > >
+{
+  typedef MappedSparseMatrix<_Scalar,_Options,_StorageIndex> XprType;
+  typedef evaluator<SparseCompressedBase<XprType> > Base;
+  
+  evaluator() : Base() {}
+  explicit evaluator(const XprType &mat) : Base(mat) {}
+};
+
+}
+
+} // end namespace Eigen
+
+#endif // EIGEN_MAPPED_SPARSEMATRIX_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseAssign.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseAssign.h
new file mode 100644
index 0000000..905485c
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseAssign.h
@@ -0,0 +1,270 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2008-2014 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_SPARSEASSIGN_H
+#define EIGEN_SPARSEASSIGN_H
+
+namespace Eigen { 
+
+template<typename Derived>    
+template<typename OtherDerived>
+Derived& SparseMatrixBase<Derived>::operator=(const EigenBase<OtherDerived> &other)
+{
+  internal::call_assignment_no_alias(derived(), other.derived());
+  return derived();
+}
+
+template<typename Derived>
+template<typename OtherDerived>
+Derived& SparseMatrixBase<Derived>::operator=(const ReturnByValue<OtherDerived>& other)
+{
+  // TODO use the evaluator mechanism
+  other.evalTo(derived());
+  return derived();
+}
+
+template<typename Derived>
+template<typename OtherDerived>
+inline Derived& SparseMatrixBase<Derived>::operator=(const SparseMatrixBase<OtherDerived>& other)
+{
+  // by default sparse evaluation do not alias, so we can safely bypass the generic call_assignment routine
+  internal::Assignment<Derived,OtherDerived,internal::assign_op<Scalar,typename OtherDerived::Scalar> >
+          ::run(derived(), other.derived(), internal::assign_op<Scalar,typename OtherDerived::Scalar>());
+  return derived();
+}
+
+template<typename Derived>
+inline Derived& SparseMatrixBase<Derived>::operator=(const Derived& other)
+{
+  internal::call_assignment_no_alias(derived(), other.derived());
+  return derived();
+}
+
+namespace internal {
+
+template<>
+struct storage_kind_to_evaluator_kind<Sparse> {
+  typedef IteratorBased Kind;
+};
+
+template<>
+struct storage_kind_to_shape<Sparse> {
+  typedef SparseShape Shape;
+};
+
+struct Sparse2Sparse {};
+struct Sparse2Dense  {};
+
+template<> struct AssignmentKind<SparseShape, SparseShape>           { typedef Sparse2Sparse Kind; };
+template<> struct AssignmentKind<SparseShape, SparseTriangularShape> { typedef Sparse2Sparse Kind; };
+template<> struct AssignmentKind<DenseShape,  SparseShape>           { typedef Sparse2Dense  Kind; };
+template<> struct AssignmentKind<DenseShape,  SparseTriangularShape> { typedef Sparse2Dense  Kind; };
+
+
+template<typename DstXprType, typename SrcXprType>
+void assign_sparse_to_sparse(DstXprType &dst, const SrcXprType &src)
+{
+  typedef typename DstXprType::Scalar Scalar;
+  typedef internal::evaluator<DstXprType> DstEvaluatorType;
+  typedef internal::evaluator<SrcXprType> SrcEvaluatorType;
+
+  SrcEvaluatorType srcEvaluator(src);
+
+  const bool transpose = (DstEvaluatorType::Flags & RowMajorBit) != (SrcEvaluatorType::Flags & RowMajorBit);
+  const Index outerEvaluationSize = (SrcEvaluatorType::Flags&RowMajorBit) ? src.rows() : src.cols();
+  if ((!transpose) && src.isRValue())
+  {
+    // eval without temporary
+    dst.resize(src.rows(), src.cols());
+    dst.setZero();
+    dst.reserve((std::min)(src.rows()*src.cols(), (std::max)(src.rows(),src.cols())*2));
+    for (Index j=0; j<outerEvaluationSize; ++j)
+    {
+      dst.startVec(j);
+      for (typename SrcEvaluatorType::InnerIterator it(srcEvaluator, j); it; ++it)
+      {
+        Scalar v = it.value();
+        dst.insertBackByOuterInner(j,it.index()) = v;
+      }
+    }
+    dst.finalize();
+  }
+  else
+  {
+    // eval through a temporary
+    eigen_assert(( ((internal::traits<DstXprType>::SupportedAccessPatterns & OuterRandomAccessPattern)==OuterRandomAccessPattern) ||
+              (!((DstEvaluatorType::Flags & RowMajorBit) != (SrcEvaluatorType::Flags & RowMajorBit)))) &&
+              "the transpose operation is supposed to be handled in SparseMatrix::operator=");
+
+    enum { Flip = (DstEvaluatorType::Flags & RowMajorBit) != (SrcEvaluatorType::Flags & RowMajorBit) };
+
+    
+    DstXprType temp(src.rows(), src.cols());
+
+    temp.reserve((std::min)(src.rows()*src.cols(), (std::max)(src.rows(),src.cols())*2));
+    for (Index j=0; j<outerEvaluationSize; ++j)
+    {
+      temp.startVec(j);
+      for (typename SrcEvaluatorType::InnerIterator it(srcEvaluator, j); it; ++it)
+      {
+        Scalar v = it.value();
+        temp.insertBackByOuterInner(Flip?it.index():j,Flip?j:it.index()) = v;
+      }
+    }
+    temp.finalize();
+
+    dst = temp.markAsRValue();
+  }
+}
+
+// Generic Sparse to Sparse assignment
+template< typename DstXprType, typename SrcXprType, typename Functor>
+struct Assignment<DstXprType, SrcXprType, Functor, Sparse2Sparse>
+{
+  static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar> &/*func*/)
+  {
+    assign_sparse_to_sparse(dst.derived(), src.derived());
+  }
+};
+
+// Generic Sparse to Dense assignment
+template< typename DstXprType, typename SrcXprType, typename Functor, typename Weak>
+struct Assignment<DstXprType, SrcXprType, Functor, Sparse2Dense, Weak>
+{
+  static void run(DstXprType &dst, const SrcXprType &src, const Functor &func)
+  {
+    if(internal::is_same<Functor,internal::assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar> >::value)
+      dst.setZero();
+    
+    internal::evaluator<SrcXprType> srcEval(src);
+    resize_if_allowed(dst, src, func);
+    internal::evaluator<DstXprType> dstEval(dst);
+    
+    const Index outerEvaluationSize = (internal::evaluator<SrcXprType>::Flags&RowMajorBit) ? src.rows() : src.cols();
+    for (Index j=0; j<outerEvaluationSize; ++j)
+      for (typename internal::evaluator<SrcXprType>::InnerIterator i(srcEval,j); i; ++i)
+        func.assignCoeff(dstEval.coeffRef(i.row(),i.col()), i.value());
+  }
+};
+
+// Specialization for dense ?= dense +/- sparse and dense ?= sparse +/- dense
+template<typename DstXprType, typename Func1, typename Func2>
+struct assignment_from_dense_op_sparse
+{
+  template<typename SrcXprType, typename InitialFunc>
+  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE
+  void run(DstXprType &dst, const SrcXprType &src, const InitialFunc& /*func*/)
+  {
+    #ifdef EIGEN_SPARSE_ASSIGNMENT_FROM_DENSE_OP_SPARSE_PLUGIN
+    EIGEN_SPARSE_ASSIGNMENT_FROM_DENSE_OP_SPARSE_PLUGIN
+    #endif
+
+    call_assignment_no_alias(dst, src.lhs(), Func1());
+    call_assignment_no_alias(dst, src.rhs(), Func2());
+  }
+
+  // Specialization for dense1 = sparse + dense2; -> dense1 = dense2; dense1 += sparse;
+  template<typename Lhs, typename Rhs, typename Scalar>
+  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE
+  typename internal::enable_if<internal::is_same<typename internal::evaluator_traits<Rhs>::Shape,DenseShape>::value>::type
+  run(DstXprType &dst, const CwiseBinaryOp<internal::scalar_sum_op<Scalar,Scalar>, const Lhs, const Rhs> &src,
+      const internal::assign_op<typename DstXprType::Scalar,Scalar>& /*func*/)
+  {
+    #ifdef EIGEN_SPARSE_ASSIGNMENT_FROM_SPARSE_ADD_DENSE_PLUGIN
+    EIGEN_SPARSE_ASSIGNMENT_FROM_SPARSE_ADD_DENSE_PLUGIN
+    #endif
+
+    // Apply the dense matrix first, then the sparse one.
+    call_assignment_no_alias(dst, src.rhs(), Func1());
+    call_assignment_no_alias(dst, src.lhs(), Func2());
+  }
+
+  // Specialization for dense1 = sparse - dense2; -> dense1 = -dense2; dense1 += sparse;
+  template<typename Lhs, typename Rhs, typename Scalar>
+  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE
+  typename internal::enable_if<internal::is_same<typename internal::evaluator_traits<Rhs>::Shape,DenseShape>::value>::type
+  run(DstXprType &dst, const CwiseBinaryOp<internal::scalar_difference_op<Scalar,Scalar>, const Lhs, const Rhs> &src,
+      const internal::assign_op<typename DstXprType::Scalar,Scalar>& /*func*/)
+  {
+    #ifdef EIGEN_SPARSE_ASSIGNMENT_FROM_SPARSE_SUB_DENSE_PLUGIN
+    EIGEN_SPARSE_ASSIGNMENT_FROM_SPARSE_SUB_DENSE_PLUGIN
+    #endif
+
+    // Apply the dense matrix first, then the sparse one.
+    call_assignment_no_alias(dst, -src.rhs(), Func1());
+    call_assignment_no_alias(dst,  src.lhs(), add_assign_op<typename DstXprType::Scalar,typename Lhs::Scalar>());
+  }
+};
+
+#define EIGEN_CATCH_ASSIGN_DENSE_OP_SPARSE(ASSIGN_OP,BINOP,ASSIGN_OP2) \
+  template< typename DstXprType, typename Lhs, typename Rhs, typename Scalar> \
+  struct Assignment<DstXprType, CwiseBinaryOp<internal::BINOP<Scalar,Scalar>, const Lhs, const Rhs>, internal::ASSIGN_OP<typename DstXprType::Scalar,Scalar>, \
+                    Sparse2Dense, \
+                    typename internal::enable_if<   internal::is_same<typename internal::evaluator_traits<Lhs>::Shape,DenseShape>::value \
+                                                 || internal::is_same<typename internal::evaluator_traits<Rhs>::Shape,DenseShape>::value>::type> \
+    : assignment_from_dense_op_sparse<DstXprType, internal::ASSIGN_OP<typename DstXprType::Scalar,typename Lhs::Scalar>, internal::ASSIGN_OP2<typename DstXprType::Scalar,typename Rhs::Scalar> > \
+  {}
+
+EIGEN_CATCH_ASSIGN_DENSE_OP_SPARSE(assign_op,    scalar_sum_op,add_assign_op);
+EIGEN_CATCH_ASSIGN_DENSE_OP_SPARSE(add_assign_op,scalar_sum_op,add_assign_op);
+EIGEN_CATCH_ASSIGN_DENSE_OP_SPARSE(sub_assign_op,scalar_sum_op,sub_assign_op);
+
+EIGEN_CATCH_ASSIGN_DENSE_OP_SPARSE(assign_op,    scalar_difference_op,sub_assign_op);
+EIGEN_CATCH_ASSIGN_DENSE_OP_SPARSE(add_assign_op,scalar_difference_op,sub_assign_op);
+EIGEN_CATCH_ASSIGN_DENSE_OP_SPARSE(sub_assign_op,scalar_difference_op,add_assign_op);
+
+
+// Specialization for "dst = dec.solve(rhs)"
+// NOTE we need to specialize it for Sparse2Sparse to avoid ambiguous specialization error
+template<typename DstXprType, typename DecType, typename RhsType, typename Scalar>
+struct Assignment<DstXprType, Solve<DecType,RhsType>, internal::assign_op<Scalar,Scalar>, Sparse2Sparse>
+{
+  typedef Solve<DecType,RhsType> SrcXprType;
+  static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op<Scalar,Scalar> &)
+  {
+    Index dstRows = src.rows();
+    Index dstCols = src.cols();
+    if((dst.rows()!=dstRows) || (dst.cols()!=dstCols))
+      dst.resize(dstRows, dstCols);
+
+    src.dec()._solve_impl(src.rhs(), dst);
+  }
+};
+
+struct Diagonal2Sparse {};
+
+template<> struct AssignmentKind<SparseShape,DiagonalShape> { typedef Diagonal2Sparse Kind; };
+
+template< typename DstXprType, typename SrcXprType, typename Functor>
+struct Assignment<DstXprType, SrcXprType, Functor, Diagonal2Sparse>
+{
+  typedef typename DstXprType::StorageIndex StorageIndex;
+  typedef typename DstXprType::Scalar Scalar;
+
+  template<int Options, typename AssignFunc>
+  static void run(SparseMatrix<Scalar,Options,StorageIndex> &dst, const SrcXprType &src, const AssignFunc &func)
+  { dst.assignDiagonal(src.diagonal(), func); }
+  
+  template<typename DstDerived>
+  static void run(SparseMatrixBase<DstDerived> &dst, const SrcXprType &src, const internal::assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar> &/*func*/)
+  { dst.derived().diagonal() = src.diagonal(); }
+  
+  template<typename DstDerived>
+  static void run(SparseMatrixBase<DstDerived> &dst, const SrcXprType &src, const internal::add_assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar> &/*func*/)
+  { dst.derived().diagonal() += src.diagonal(); }
+  
+  template<typename DstDerived>
+  static void run(SparseMatrixBase<DstDerived> &dst, const SrcXprType &src, const internal::sub_assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar> &/*func*/)
+  { dst.derived().diagonal() -= src.diagonal(); }
+};
+} // end namespace internal
+
+} // end namespace Eigen
+
+#endif // EIGEN_SPARSEASSIGN_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseBlock.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseBlock.h
new file mode 100644
index 0000000..5b4f6cc
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseBlock.h
@@ -0,0 +1,571 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2008-2014 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_SPARSE_BLOCK_H
+#define EIGEN_SPARSE_BLOCK_H
+
+namespace Eigen {
+
+// Subset of columns or rows
+template<typename XprType, int BlockRows, int BlockCols>
+class BlockImpl<XprType,BlockRows,BlockCols,true,Sparse>
+  : public SparseMatrixBase<Block<XprType,BlockRows,BlockCols,true> >
+{
+    typedef typename internal::remove_all<typename XprType::Nested>::type _MatrixTypeNested;
+    typedef Block<XprType, BlockRows, BlockCols, true> BlockType;
+public:
+    enum { IsRowMajor = internal::traits<BlockType>::IsRowMajor };
+protected:
+    enum { OuterSize = IsRowMajor ? BlockRows : BlockCols };
+    typedef SparseMatrixBase<BlockType> Base;
+    using Base::convert_index;
+public:
+    EIGEN_SPARSE_PUBLIC_INTERFACE(BlockType)
+
+    inline BlockImpl(XprType& xpr, Index i)
+      : m_matrix(xpr), m_outerStart(convert_index(i)), m_outerSize(OuterSize)
+    {}
+
+    inline BlockImpl(XprType& xpr, Index startRow, Index startCol, Index blockRows, Index blockCols)
+      : m_matrix(xpr), m_outerStart(convert_index(IsRowMajor ? startRow : startCol)), m_outerSize(convert_index(IsRowMajor ? blockRows : blockCols))
+    {}
+
+    EIGEN_STRONG_INLINE Index rows() const { return IsRowMajor ? m_outerSize.value() : m_matrix.rows(); }
+    EIGEN_STRONG_INLINE Index cols() const { return IsRowMajor ? m_matrix.cols() : m_outerSize.value(); }
+
+    Index nonZeros() const
+    {
+      typedef internal::evaluator<XprType> EvaluatorType;
+      EvaluatorType matEval(m_matrix);
+      Index nnz = 0;
+      Index end = m_outerStart + m_outerSize.value();
+      for(Index j=m_outerStart; j<end; ++j)
+        for(typename EvaluatorType::InnerIterator it(matEval, j); it; ++it)
+          ++nnz;
+      return nnz;
+    }
+
+    inline const Scalar coeff(Index row, Index col) const
+    {
+      return m_matrix.coeff(row + (IsRowMajor ? m_outerStart : 0), col + (IsRowMajor ? 0 :  m_outerStart));
+    }
+
+    inline const Scalar coeff(Index index) const
+    {
+      return m_matrix.coeff(IsRowMajor ? m_outerStart : index, IsRowMajor ? index :  m_outerStart);
+    }
+
+    inline const XprType& nestedExpression() const { return m_matrix; }
+    inline XprType& nestedExpression() { return m_matrix; }
+    Index startRow() const { return IsRowMajor ? m_outerStart : 0; }
+    Index startCol() const { return IsRowMajor ? 0 : m_outerStart; }
+    Index blockRows() const { return IsRowMajor ? m_outerSize.value() : m_matrix.rows(); }
+    Index blockCols() const { return IsRowMajor ? m_matrix.cols() : m_outerSize.value(); }
+
+  protected:
+
+    typename internal::ref_selector<XprType>::non_const_type m_matrix;
+    Index m_outerStart;
+    const internal::variable_if_dynamic<Index, OuterSize> m_outerSize;
+
+  protected:
+    // Disable assignment with clear error message.
+    // Note that simply removing operator= yields compilation errors with ICC+MSVC
+    template<typename T>
+    BlockImpl& operator=(const T&)
+    {
+      EIGEN_STATIC_ASSERT(sizeof(T)==0, THIS_SPARSE_BLOCK_SUBEXPRESSION_IS_READ_ONLY);
+      return *this;
+    }
+};
+
+
+/***************************************************************************
+* specialization for SparseMatrix
+***************************************************************************/
+
+namespace internal {
+
+template<typename SparseMatrixType, int BlockRows, int BlockCols>
+class sparse_matrix_block_impl
+  : public SparseCompressedBase<Block<SparseMatrixType,BlockRows,BlockCols,true> >
+{
+    typedef typename internal::remove_all<typename SparseMatrixType::Nested>::type _MatrixTypeNested;
+    typedef Block<SparseMatrixType, BlockRows, BlockCols, true> BlockType;
+    typedef SparseCompressedBase<Block<SparseMatrixType,BlockRows,BlockCols,true> > Base;
+    using Base::convert_index;
+public:
+    enum { IsRowMajor = internal::traits<BlockType>::IsRowMajor };
+    EIGEN_SPARSE_PUBLIC_INTERFACE(BlockType)
+protected:
+    typedef typename Base::IndexVector IndexVector;
+    enum { OuterSize = IsRowMajor ? BlockRows : BlockCols };
+public:
+
+    inline sparse_matrix_block_impl(SparseMatrixType& xpr, Index i)
+      : m_matrix(xpr), m_outerStart(convert_index(i)), m_outerSize(OuterSize)
+    {}
+
+    inline sparse_matrix_block_impl(SparseMatrixType& xpr, Index startRow, Index startCol, Index blockRows, Index blockCols)
+      : m_matrix(xpr), m_outerStart(convert_index(IsRowMajor ? startRow : startCol)), m_outerSize(convert_index(IsRowMajor ? blockRows : blockCols))
+    {}
+
+    template<typename OtherDerived>
+    inline BlockType& operator=(const SparseMatrixBase<OtherDerived>& other)
+    {
+      typedef typename internal::remove_all<typename SparseMatrixType::Nested>::type _NestedMatrixType;
+      _NestedMatrixType& matrix = m_matrix;
+      // This assignment is slow if this vector set is not empty
+      // and/or it is not at the end of the nonzeros of the underlying matrix.
+
+      // 1 - eval to a temporary to avoid transposition and/or aliasing issues
+      Ref<const SparseMatrix<Scalar, IsRowMajor ? RowMajor : ColMajor, StorageIndex> > tmp(other.derived());
+      eigen_internal_assert(tmp.outerSize()==m_outerSize.value());
+
+      // 2 - let's check whether there is enough allocated memory
+      Index nnz           = tmp.nonZeros();
+      Index start         = m_outerStart==0 ? 0 : m_matrix.outerIndexPtr()[m_outerStart]; // starting position of the current block
+      Index end           = m_matrix.outerIndexPtr()[m_outerStart+m_outerSize.value()]; // ending position of the current block
+      Index block_size    = end - start;                                                // available room in the current block
+      Index tail_size     = m_matrix.outerIndexPtr()[m_matrix.outerSize()] - end;
+
+      Index free_size     = m_matrix.isCompressed()
+                          ? Index(matrix.data().allocatedSize()) + block_size
+                          : block_size;
+
+      Index tmp_start = tmp.outerIndexPtr()[0];
+
+      bool update_trailing_pointers = false;
+      if(nnz>free_size)
+      {
+        // realloc manually to reduce copies
+        typename SparseMatrixType::Storage newdata(m_matrix.data().allocatedSize() - block_size + nnz);
+
+        internal::smart_copy(m_matrix.valuePtr(),       m_matrix.valuePtr() + start,      newdata.valuePtr());
+        internal::smart_copy(m_matrix.innerIndexPtr(),  m_matrix.innerIndexPtr() + start, newdata.indexPtr());
+
+        internal::smart_copy(tmp.valuePtr() + tmp_start,      tmp.valuePtr() + tmp_start + nnz,       newdata.valuePtr() + start);
+        internal::smart_copy(tmp.innerIndexPtr() + tmp_start, tmp.innerIndexPtr() + tmp_start + nnz,  newdata.indexPtr() + start);
+
+        internal::smart_copy(matrix.valuePtr()+end,       matrix.valuePtr()+end + tail_size,      newdata.valuePtr()+start+nnz);
+        internal::smart_copy(matrix.innerIndexPtr()+end,  matrix.innerIndexPtr()+end + tail_size, newdata.indexPtr()+start+nnz);
+
+        newdata.resize(m_matrix.outerIndexPtr()[m_matrix.outerSize()] - block_size + nnz);
+
+        matrix.data().swap(newdata);
+
+        update_trailing_pointers = true;
+      }
+      else
+      {
+        if(m_matrix.isCompressed() && nnz!=block_size)
+        {
+          // no need to realloc, simply copy the tail at its respective position and insert tmp
+          matrix.data().resize(start + nnz + tail_size);
+
+          internal::smart_memmove(matrix.valuePtr()+end,      matrix.valuePtr() + end+tail_size,      matrix.valuePtr() + start+nnz);
+          internal::smart_memmove(matrix.innerIndexPtr()+end, matrix.innerIndexPtr() + end+tail_size, matrix.innerIndexPtr() + start+nnz);
+
+          update_trailing_pointers = true;
+        }
+
+        internal::smart_copy(tmp.valuePtr() + tmp_start,      tmp.valuePtr() + tmp_start + nnz,       matrix.valuePtr() + start);
+        internal::smart_copy(tmp.innerIndexPtr() + tmp_start, tmp.innerIndexPtr() + tmp_start + nnz,  matrix.innerIndexPtr() + start);
+      }
+
+      // update outer index pointers and innerNonZeros
+      if(IsVectorAtCompileTime)
+      {
+        if(!m_matrix.isCompressed())
+          matrix.innerNonZeroPtr()[m_outerStart] = StorageIndex(nnz);
+        matrix.outerIndexPtr()[m_outerStart] = StorageIndex(start);
+      }
+      else
+      {
+        StorageIndex p = StorageIndex(start);
+        for(Index k=0; k<m_outerSize.value(); ++k)
+        {
+          StorageIndex nnz_k = internal::convert_index<StorageIndex>(tmp.innerVector(k).nonZeros());
+          if(!m_matrix.isCompressed())
+            matrix.innerNonZeroPtr()[m_outerStart+k] = nnz_k;
+          matrix.outerIndexPtr()[m_outerStart+k] = p;
+          p += nnz_k;
+        }
+      }
+
+      if(update_trailing_pointers)
+      {
+        StorageIndex offset = internal::convert_index<StorageIndex>(nnz - block_size);
+        for(Index k = m_outerStart + m_outerSize.value(); k<=matrix.outerSize(); ++k)
+        {
+          matrix.outerIndexPtr()[k] += offset;
+        }
+      }
+
+      return derived();
+    }
+
+    inline BlockType& operator=(const BlockType& other)
+    {
+      return operator=<BlockType>(other);
+    }
+
+    inline const Scalar* valuePtr() const
+    { return m_matrix.valuePtr(); }
+    inline Scalar* valuePtr()
+    { return m_matrix.valuePtr(); }
+
+    inline const StorageIndex* innerIndexPtr() const
+    { return m_matrix.innerIndexPtr(); }
+    inline StorageIndex* innerIndexPtr()
+    { return m_matrix.innerIndexPtr(); }
+
+    inline const StorageIndex* outerIndexPtr() const
+    { return m_matrix.outerIndexPtr() + m_outerStart; }
+    inline StorageIndex* outerIndexPtr()
+    { return m_matrix.outerIndexPtr() + m_outerStart; }
+
+    inline const StorageIndex* innerNonZeroPtr() const
+    { return isCompressed() ? 0 : (m_matrix.innerNonZeroPtr()+m_outerStart); }
+    inline StorageIndex* innerNonZeroPtr()
+    { return isCompressed() ? 0 : (m_matrix.innerNonZeroPtr()+m_outerStart); }
+
+    bool isCompressed() const { return m_matrix.innerNonZeroPtr()==0; }
+
+    inline Scalar& coeffRef(Index row, Index col)
+    {
+      return m_matrix.coeffRef(row + (IsRowMajor ? m_outerStart : 0), col + (IsRowMajor ? 0 :  m_outerStart));
+    }
+
+    inline const Scalar coeff(Index row, Index col) const
+    {
+      return m_matrix.coeff(row + (IsRowMajor ? m_outerStart : 0), col + (IsRowMajor ? 0 :  m_outerStart));
+    }
+
+    inline const Scalar coeff(Index index) const
+    {
+      return m_matrix.coeff(IsRowMajor ? m_outerStart : index, IsRowMajor ? index :  m_outerStart);
+    }
+
+    const Scalar& lastCoeff() const
+    {
+      EIGEN_STATIC_ASSERT_VECTOR_ONLY(sparse_matrix_block_impl);
+      eigen_assert(Base::nonZeros()>0);
+      if(m_matrix.isCompressed())
+        return m_matrix.valuePtr()[m_matrix.outerIndexPtr()[m_outerStart+1]-1];
+      else
+        return m_matrix.valuePtr()[m_matrix.outerIndexPtr()[m_outerStart]+m_matrix.innerNonZeroPtr()[m_outerStart]-1];
+    }
+
+    EIGEN_STRONG_INLINE Index rows() const { return IsRowMajor ? m_outerSize.value() : m_matrix.rows(); }
+    EIGEN_STRONG_INLINE Index cols() const { return IsRowMajor ? m_matrix.cols() : m_outerSize.value(); }
+
+    inline const SparseMatrixType& nestedExpression() const { return m_matrix; }
+    inline SparseMatrixType& nestedExpression() { return m_matrix; }
+    Index startRow() const { return IsRowMajor ? m_outerStart : 0; }
+    Index startCol() const { return IsRowMajor ? 0 : m_outerStart; }
+    Index blockRows() const { return IsRowMajor ? m_outerSize.value() : m_matrix.rows(); }
+    Index blockCols() const { return IsRowMajor ? m_matrix.cols() : m_outerSize.value(); }
+
+  protected:
+
+    typename internal::ref_selector<SparseMatrixType>::non_const_type m_matrix;
+    Index m_outerStart;
+    const internal::variable_if_dynamic<Index, OuterSize> m_outerSize;
+
+};
+
+} // namespace internal
+
+template<typename _Scalar, int _Options, typename _StorageIndex, int BlockRows, int BlockCols>
+class BlockImpl<SparseMatrix<_Scalar, _Options, _StorageIndex>,BlockRows,BlockCols,true,Sparse>
+  : public internal::sparse_matrix_block_impl<SparseMatrix<_Scalar, _Options, _StorageIndex>,BlockRows,BlockCols>
+{
+public:
+  typedef _StorageIndex StorageIndex;
+  typedef SparseMatrix<_Scalar, _Options, _StorageIndex> SparseMatrixType;
+  typedef internal::sparse_matrix_block_impl<SparseMatrixType,BlockRows,BlockCols> Base;
+  inline BlockImpl(SparseMatrixType& xpr, Index i)
+    : Base(xpr, i)
+  {}
+
+  inline BlockImpl(SparseMatrixType& xpr, Index startRow, Index startCol, Index blockRows, Index blockCols)
+    : Base(xpr, startRow, startCol, blockRows, blockCols)
+  {}
+
+  using Base::operator=;
+};
+
+template<typename _Scalar, int _Options, typename _StorageIndex, int BlockRows, int BlockCols>
+class BlockImpl<const SparseMatrix<_Scalar, _Options, _StorageIndex>,BlockRows,BlockCols,true,Sparse>
+  : public internal::sparse_matrix_block_impl<const SparseMatrix<_Scalar, _Options, _StorageIndex>,BlockRows,BlockCols>
+{
+public:
+  typedef _StorageIndex StorageIndex;
+  typedef const SparseMatrix<_Scalar, _Options, _StorageIndex> SparseMatrixType;
+  typedef internal::sparse_matrix_block_impl<SparseMatrixType,BlockRows,BlockCols> Base;
+  inline BlockImpl(SparseMatrixType& xpr, Index i)
+    : Base(xpr, i)
+  {}
+
+  inline BlockImpl(SparseMatrixType& xpr, Index startRow, Index startCol, Index blockRows, Index blockCols)
+    : Base(xpr, startRow, startCol, blockRows, blockCols)
+  {}
+
+  using Base::operator=;
+private:
+  template<typename Derived> BlockImpl(const SparseMatrixBase<Derived>& xpr, Index i);
+  template<typename Derived> BlockImpl(const SparseMatrixBase<Derived>& xpr);
+};
+
+//----------
+
+/** Generic implementation of sparse Block expression.
+  * Real-only.
+  */
+template<typename XprType, int BlockRows, int BlockCols, bool InnerPanel>
+class BlockImpl<XprType,BlockRows,BlockCols,InnerPanel,Sparse>
+  : public SparseMatrixBase<Block<XprType,BlockRows,BlockCols,InnerPanel> >, internal::no_assignment_operator
+{
+    typedef Block<XprType, BlockRows, BlockCols, InnerPanel> BlockType;
+    typedef SparseMatrixBase<BlockType> Base;
+    using Base::convert_index;
+public:
+    enum { IsRowMajor = internal::traits<BlockType>::IsRowMajor };
+    EIGEN_SPARSE_PUBLIC_INTERFACE(BlockType)
+
+    typedef typename internal::remove_all<typename XprType::Nested>::type _MatrixTypeNested;
+
+    /** Column or Row constructor
+      */
+    inline BlockImpl(XprType& xpr, Index i)
+      : m_matrix(xpr),
+        m_startRow( (BlockRows==1) && (BlockCols==XprType::ColsAtCompileTime) ? convert_index(i) : 0),
+        m_startCol( (BlockRows==XprType::RowsAtCompileTime) && (BlockCols==1) ? convert_index(i) : 0),
+        m_blockRows(BlockRows==1 ? 1 : xpr.rows()),
+        m_blockCols(BlockCols==1 ? 1 : xpr.cols())
+    {}
+
+    /** Dynamic-size constructor
+      */
+    inline BlockImpl(XprType& xpr, Index startRow, Index startCol, Index blockRows, Index blockCols)
+      : m_matrix(xpr), m_startRow(convert_index(startRow)), m_startCol(convert_index(startCol)), m_blockRows(convert_index(blockRows)), m_blockCols(convert_index(blockCols))
+    {}
+
+    inline Index rows() const { return m_blockRows.value(); }
+    inline Index cols() const { return m_blockCols.value(); }
+
+    inline Scalar& coeffRef(Index row, Index col)
+    {
+      return m_matrix.coeffRef(row + m_startRow.value(), col + m_startCol.value());
+    }
+
+    inline const Scalar coeff(Index row, Index col) const
+    {
+      return m_matrix.coeff(row + m_startRow.value(), col + m_startCol.value());
+    }
+
+    inline Scalar& coeffRef(Index index)
+    {
+      return m_matrix.coeffRef(m_startRow.value() + (RowsAtCompileTime == 1 ? 0 : index),
+                               m_startCol.value() + (RowsAtCompileTime == 1 ? index : 0));
+    }
+
+    inline const Scalar coeff(Index index) const
+    {
+      return m_matrix.coeff(m_startRow.value() + (RowsAtCompileTime == 1 ? 0 : index),
+                            m_startCol.value() + (RowsAtCompileTime == 1 ? index : 0));
+    }
+
+    inline const XprType& nestedExpression() const { return m_matrix; }
+    inline XprType& nestedExpression() { return m_matrix; }
+    Index startRow() const { return m_startRow.value(); }
+    Index startCol() const { return m_startCol.value(); }
+    Index blockRows() const { return m_blockRows.value(); }
+    Index blockCols() const { return m_blockCols.value(); }
+
+  protected:
+//     friend class internal::GenericSparseBlockInnerIteratorImpl<XprType,BlockRows,BlockCols,InnerPanel>;
+    friend struct internal::unary_evaluator<Block<XprType,BlockRows,BlockCols,InnerPanel>, internal::IteratorBased, Scalar >;
+
+    Index nonZeros() const { return Dynamic; }
+
+    typename internal::ref_selector<XprType>::non_const_type m_matrix;
+    const internal::variable_if_dynamic<Index, XprType::RowsAtCompileTime == 1 ? 0 : Dynamic> m_startRow;
+    const internal::variable_if_dynamic<Index, XprType::ColsAtCompileTime == 1 ? 0 : Dynamic> m_startCol;
+    const internal::variable_if_dynamic<Index, RowsAtCompileTime> m_blockRows;
+    const internal::variable_if_dynamic<Index, ColsAtCompileTime> m_blockCols;
+
+  protected:
+    // Disable assignment with clear error message.
+    // Note that simply removing operator= yields compilation errors with ICC+MSVC
+    template<typename T>
+    BlockImpl& operator=(const T&)
+    {
+      EIGEN_STATIC_ASSERT(sizeof(T)==0, THIS_SPARSE_BLOCK_SUBEXPRESSION_IS_READ_ONLY);
+      return *this;
+    }
+
+};
+
+namespace internal {
+
+template<typename ArgType, int BlockRows, int BlockCols, bool InnerPanel>
+struct unary_evaluator<Block<ArgType,BlockRows,BlockCols,InnerPanel>, IteratorBased >
+ : public evaluator_base<Block<ArgType,BlockRows,BlockCols,InnerPanel> >
+{
+    class InnerVectorInnerIterator;
+    class OuterVectorInnerIterator;
+  public:
+    typedef Block<ArgType,BlockRows,BlockCols,InnerPanel> XprType;
+    typedef typename XprType::StorageIndex StorageIndex;
+    typedef typename XprType::Scalar Scalar;
+
+    enum {
+      IsRowMajor = XprType::IsRowMajor,
+
+      OuterVector =  (BlockCols==1 && ArgType::IsRowMajor)
+                    | // FIXME | instead of || to please GCC 4.4.0 stupid warning "suggest parentheses around &&".
+                      // revert to || as soon as not needed anymore.
+                     (BlockRows==1 && !ArgType::IsRowMajor),
+
+      CoeffReadCost = evaluator<ArgType>::CoeffReadCost,
+      Flags = XprType::Flags
+    };
+
+    typedef typename internal::conditional<OuterVector,OuterVectorInnerIterator,InnerVectorInnerIterator>::type InnerIterator;
+
+    explicit unary_evaluator(const XprType& op)
+      : m_argImpl(op.nestedExpression()), m_block(op)
+    {}
+
+    inline Index nonZerosEstimate() const {
+      const Index nnz = m_block.nonZeros();
+      if(nnz < 0) {
+        // Scale the non-zero estimate for the underlying expression linearly with block size.
+        // Return zero if the underlying block is empty.
+        const Index nested_sz = m_block.nestedExpression().size();        
+        return nested_sz == 0 ? 0 : m_argImpl.nonZerosEstimate() * m_block.size() / nested_sz;
+      }
+      return nnz;
+    }
+
+  protected:
+    typedef typename evaluator<ArgType>::InnerIterator EvalIterator;
+
+    evaluator<ArgType> m_argImpl;
+    const XprType &m_block;
+};
+
+template<typename ArgType, int BlockRows, int BlockCols, bool InnerPanel>
+class unary_evaluator<Block<ArgType,BlockRows,BlockCols,InnerPanel>, IteratorBased>::InnerVectorInnerIterator
+ : public EvalIterator
+{
+  // NOTE MSVC fails to compile if we don't explicitely "import" IsRowMajor from unary_evaluator
+  //      because the base class EvalIterator has a private IsRowMajor enum too. (bug #1786)
+  // NOTE We cannot call it IsRowMajor because it would shadow unary_evaluator::IsRowMajor
+  enum { XprIsRowMajor = unary_evaluator::IsRowMajor };
+  const XprType& m_block;
+  Index m_end;
+public:
+
+  EIGEN_STRONG_INLINE InnerVectorInnerIterator(const unary_evaluator& aEval, Index outer)
+    : EvalIterator(aEval.m_argImpl, outer + (XprIsRowMajor ? aEval.m_block.startRow() : aEval.m_block.startCol())),
+      m_block(aEval.m_block),
+      m_end(XprIsRowMajor ? aEval.m_block.startCol()+aEval.m_block.blockCols() : aEval.m_block.startRow()+aEval.m_block.blockRows())
+  {
+    while( (EvalIterator::operator bool()) && (EvalIterator::index() < (XprIsRowMajor ? m_block.startCol() : m_block.startRow())) )
+      EvalIterator::operator++();
+  }
+
+  inline StorageIndex index() const { return EvalIterator::index() - convert_index<StorageIndex>(XprIsRowMajor ? m_block.startCol() : m_block.startRow()); }
+  inline Index outer()  const { return EvalIterator::outer() - (XprIsRowMajor ? m_block.startRow() : m_block.startCol()); }
+  inline Index row()    const { return EvalIterator::row()   - m_block.startRow(); }
+  inline Index col()    const { return EvalIterator::col()   - m_block.startCol(); }
+
+  inline operator bool() const { return EvalIterator::operator bool() && EvalIterator::index() < m_end; }
+};
+
+template<typename ArgType, int BlockRows, int BlockCols, bool InnerPanel>
+class unary_evaluator<Block<ArgType,BlockRows,BlockCols,InnerPanel>, IteratorBased>::OuterVectorInnerIterator
+{
+  // NOTE see above
+  enum { XprIsRowMajor = unary_evaluator::IsRowMajor };
+  const unary_evaluator& m_eval;
+  Index m_outerPos;
+  const Index m_innerIndex;
+  Index m_end;
+  EvalIterator m_it;
+public:
+
+  EIGEN_STRONG_INLINE OuterVectorInnerIterator(const unary_evaluator& aEval, Index outer)
+    : m_eval(aEval),
+      m_outerPos( (XprIsRowMajor ? aEval.m_block.startCol() : aEval.m_block.startRow()) ),
+      m_innerIndex(XprIsRowMajor ? aEval.m_block.startRow() : aEval.m_block.startCol()),
+      m_end(XprIsRowMajor ? aEval.m_block.startCol()+aEval.m_block.blockCols() : aEval.m_block.startRow()+aEval.m_block.blockRows()),
+      m_it(m_eval.m_argImpl, m_outerPos)
+  {
+    EIGEN_UNUSED_VARIABLE(outer);
+    eigen_assert(outer==0);
+
+    while(m_it && m_it.index() < m_innerIndex) ++m_it;
+    if((!m_it) || (m_it.index()!=m_innerIndex))
+      ++(*this);
+  }
+
+  inline StorageIndex index() const { return convert_index<StorageIndex>(m_outerPos - (XprIsRowMajor ? m_eval.m_block.startCol() : m_eval.m_block.startRow())); }
+  inline Index outer()  const { return 0; }
+  inline Index row()    const { return XprIsRowMajor ? 0 : index(); }
+  inline Index col()    const { return XprIsRowMajor ? index() : 0; }
+
+  inline Scalar value() const { return m_it.value(); }
+  inline Scalar& valueRef() { return m_it.valueRef(); }
+
+  inline OuterVectorInnerIterator& operator++()
+  {
+    // search next non-zero entry
+    while(++m_outerPos<m_end)
+    {
+      // Restart iterator at the next inner-vector:
+      m_it.~EvalIterator();
+      ::new (&m_it) EvalIterator(m_eval.m_argImpl, m_outerPos);
+      // search for the key m_innerIndex in the current outer-vector
+      while(m_it && m_it.index() < m_innerIndex) ++m_it;
+      if(m_it && m_it.index()==m_innerIndex) break;
+    }
+    return *this;
+  }
+
+  inline operator bool() const { return m_outerPos < m_end; }
+};
+
+template<typename _Scalar, int _Options, typename _StorageIndex, int BlockRows, int BlockCols>
+struct unary_evaluator<Block<SparseMatrix<_Scalar, _Options, _StorageIndex>,BlockRows,BlockCols,true>, IteratorBased>
+  : evaluator<SparseCompressedBase<Block<SparseMatrix<_Scalar, _Options, _StorageIndex>,BlockRows,BlockCols,true> > >
+{
+  typedef Block<SparseMatrix<_Scalar, _Options, _StorageIndex>,BlockRows,BlockCols,true> XprType;
+  typedef evaluator<SparseCompressedBase<XprType> > Base;
+  explicit unary_evaluator(const XprType &xpr) : Base(xpr) {}
+};
+
+template<typename _Scalar, int _Options, typename _StorageIndex, int BlockRows, int BlockCols>
+struct unary_evaluator<Block<const SparseMatrix<_Scalar, _Options, _StorageIndex>,BlockRows,BlockCols,true>, IteratorBased>
+  : evaluator<SparseCompressedBase<Block<const SparseMatrix<_Scalar, _Options, _StorageIndex>,BlockRows,BlockCols,true> > >
+{
+  typedef Block<const SparseMatrix<_Scalar, _Options, _StorageIndex>,BlockRows,BlockCols,true> XprType;
+  typedef evaluator<SparseCompressedBase<XprType> > Base;
+  explicit unary_evaluator(const XprType &xpr) : Base(xpr) {}
+};
+
+} // end namespace internal
+
+
+} // end namespace Eigen
+
+#endif // EIGEN_SPARSE_BLOCK_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseColEtree.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseColEtree.h
new file mode 100644
index 0000000..ebe02d1
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseColEtree.h
@@ -0,0 +1,206 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+
+/* 
+ 
+ * NOTE: This file is the modified version of sp_coletree.c file in SuperLU 
+ 
+ * -- SuperLU routine (version 3.1) --
+ * Univ. of California Berkeley, Xerox Palo Alto Research Center,
+ * and Lawrence Berkeley National Lab.
+ * August 1, 2008
+ *
+ * Copyright (c) 1994 by Xerox Corporation.  All rights reserved.
+ *
+ * THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY
+ * EXPRESSED OR IMPLIED.  ANY USE IS AT YOUR OWN RISK.
+ *
+ * Permission is hereby granted to use or copy this program for any
+ * purpose, provided the above notices are retained on all copies.
+ * Permission to modify the code and to distribute modified code is
+ * granted, provided the above notices are retained, and a notice that
+ * the code was modified is included with the above copyright notice.
+ */
+#ifndef SPARSE_COLETREE_H
+#define SPARSE_COLETREE_H
+
+namespace Eigen {
+
+namespace internal {
+
+/** Find the root of the tree/set containing the vertex i : Use Path halving */ 
+template<typename Index, typename IndexVector>
+Index etree_find (Index i, IndexVector& pp)
+{
+  Index p = pp(i); // Parent 
+  Index gp = pp(p); // Grand parent 
+  while (gp != p) 
+  {
+    pp(i) = gp; // Parent pointer on find path is changed to former grand parent
+    i = gp; 
+    p = pp(i);
+    gp = pp(p);
+  }
+  return p; 
+}
+
+/** Compute the column elimination tree of a sparse matrix
+  * \param mat The matrix in column-major format. 
+  * \param parent The elimination tree
+  * \param firstRowElt The column index of the first element in each row
+  * \param perm The permutation to apply to the column of \b mat
+  */
+template <typename MatrixType, typename IndexVector>
+int coletree(const MatrixType& mat, IndexVector& parent, IndexVector& firstRowElt, typename MatrixType::StorageIndex *perm=0)
+{
+  typedef typename MatrixType::StorageIndex StorageIndex;
+  StorageIndex nc = convert_index<StorageIndex>(mat.cols()); // Number of columns
+  StorageIndex m = convert_index<StorageIndex>(mat.rows());
+  StorageIndex diagSize = (std::min)(nc,m);
+  IndexVector root(nc); // root of subtree of etree 
+  root.setZero();
+  IndexVector pp(nc); // disjoint sets 
+  pp.setZero(); // Initialize disjoint sets 
+  parent.resize(mat.cols());
+  //Compute first nonzero column in each row 
+  firstRowElt.resize(m);
+  firstRowElt.setConstant(nc);
+  firstRowElt.segment(0, diagSize).setLinSpaced(diagSize, 0, diagSize-1);
+  bool found_diag;
+  for (StorageIndex col = 0; col < nc; col++)
+  {
+    StorageIndex pcol = col;
+    if(perm) pcol  = perm[col];
+    for (typename MatrixType::InnerIterator it(mat, pcol); it; ++it)
+    { 
+      Index row = it.row();
+      firstRowElt(row) = (std::min)(firstRowElt(row), col);
+    }
+  }
+  /* Compute etree by Liu's algorithm for symmetric matrices,
+          except use (firstRowElt[r],c) in place of an edge (r,c) of A.
+    Thus each row clique in A'*A is replaced by a star
+    centered at its first vertex, which has the same fill. */
+  StorageIndex rset, cset, rroot;
+  for (StorageIndex col = 0; col < nc; col++) 
+  {
+    found_diag = col>=m;
+    pp(col) = col; 
+    cset = col; 
+    root(cset) = col; 
+    parent(col) = nc; 
+    /* The diagonal element is treated here even if it does not exist in the matrix
+     * hence the loop is executed once more */ 
+    StorageIndex pcol = col;
+    if(perm) pcol  = perm[col];
+    for (typename MatrixType::InnerIterator it(mat, pcol); it||!found_diag; ++it)
+    { //  A sequence of interleaved find and union is performed 
+      Index i = col;
+      if(it) i = it.index();
+      if (i == col) found_diag = true;
+      
+      StorageIndex row = firstRowElt(i);
+      if (row >= col) continue; 
+      rset = internal::etree_find(row, pp); // Find the name of the set containing row
+      rroot = root(rset);
+      if (rroot != col) 
+      {
+        parent(rroot) = col; 
+        pp(cset) = rset; 
+        cset = rset; 
+        root(cset) = col; 
+      }
+    }
+  }
+  return 0;  
+}
+
+/** 
+  * Depth-first search from vertex n.  No recursion.
+  * This routine was contributed by Cédric Doucet, CEDRAT Group, Meylan, France.
+*/
+template <typename IndexVector>
+void nr_etdfs (typename IndexVector::Scalar n, IndexVector& parent, IndexVector& first_kid, IndexVector& next_kid, IndexVector& post, typename IndexVector::Scalar postnum)
+{
+  typedef typename IndexVector::Scalar StorageIndex;
+  StorageIndex current = n, first, next;
+  while (postnum != n) 
+  {
+    // No kid for the current node
+    first = first_kid(current);
+    
+    // no kid for the current node
+    if (first == -1) 
+    {
+      // Numbering this node because it has no kid 
+      post(current) = postnum++;
+      
+      // looking for the next kid 
+      next = next_kid(current); 
+      while (next == -1) 
+      {
+        // No more kids : back to the parent node
+        current = parent(current); 
+        // numbering the parent node 
+        post(current) = postnum++;
+        
+        // Get the next kid 
+        next = next_kid(current); 
+      }
+      // stopping criterion 
+      if (postnum == n+1) return; 
+      
+      // Updating current node 
+      current = next; 
+    }
+    else 
+    {
+      current = first; 
+    }
+  }
+}
+
+
+/**
+  * \brief Post order a tree 
+  * \param n the number of nodes
+  * \param parent Input tree
+  * \param post postordered tree
+  */
+template <typename IndexVector>
+void treePostorder(typename IndexVector::Scalar n, IndexVector& parent, IndexVector& post)
+{
+  typedef typename IndexVector::Scalar StorageIndex;
+  IndexVector first_kid, next_kid; // Linked list of children 
+  StorageIndex postnum; 
+  // Allocate storage for working arrays and results 
+  first_kid.resize(n+1); 
+  next_kid.setZero(n+1);
+  post.setZero(n+1);
+  
+  // Set up structure describing children
+  first_kid.setConstant(-1); 
+  for (StorageIndex v = n-1; v >= 0; v--) 
+  {
+    StorageIndex dad = parent(v);
+    next_kid(v) = first_kid(dad); 
+    first_kid(dad) = v; 
+  }
+  
+  // Depth-first search from dummy root vertex #n
+  postnum = 0; 
+  internal::nr_etdfs(n, parent, first_kid, next_kid, post, postnum);
+}
+
+} // end namespace internal
+
+} // end namespace Eigen
+
+#endif // SPARSE_COLETREE_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseCompressedBase.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseCompressedBase.h
new file mode 100644
index 0000000..6a2c7a8
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseCompressedBase.h
@@ -0,0 +1,370 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2015 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_SPARSE_COMPRESSED_BASE_H
+#define EIGEN_SPARSE_COMPRESSED_BASE_H
+
+namespace Eigen { 
+
+template<typename Derived> class SparseCompressedBase;
+  
+namespace internal {
+
+template<typename Derived>
+struct traits<SparseCompressedBase<Derived> > : traits<Derived>
+{};
+
+} // end namespace internal
+
+/** \ingroup SparseCore_Module
+  * \class SparseCompressedBase
+  * \brief Common base class for sparse [compressed]-{row|column}-storage format.
+  *
+  * This class defines the common interface for all derived classes implementing the compressed sparse storage format, such as:
+  *  - SparseMatrix
+  *  - Ref<SparseMatrixType,Options>
+  *  - Map<SparseMatrixType>
+  *
+  */
+template<typename Derived>
+class SparseCompressedBase
+  : public SparseMatrixBase<Derived>
+{
+  public:
+    typedef SparseMatrixBase<Derived> Base;
+    EIGEN_SPARSE_PUBLIC_INTERFACE(SparseCompressedBase)
+    using Base::operator=;
+    using Base::IsRowMajor;
+    
+    class InnerIterator;
+    class ReverseInnerIterator;
+    
+  protected:
+    typedef typename Base::IndexVector IndexVector;
+    Eigen::Map<IndexVector> innerNonZeros() { return Eigen::Map<IndexVector>(innerNonZeroPtr(), isCompressed()?0:derived().outerSize()); }
+    const  Eigen::Map<const IndexVector> innerNonZeros() const { return Eigen::Map<const IndexVector>(innerNonZeroPtr(), isCompressed()?0:derived().outerSize()); }
+        
+  public:
+    
+    /** \returns the number of non zero coefficients */
+    inline Index nonZeros() const
+    {
+      if(Derived::IsVectorAtCompileTime && outerIndexPtr()==0)
+        return derived().nonZeros();
+      else if(isCompressed())
+        return outerIndexPtr()[derived().outerSize()]-outerIndexPtr()[0];
+      else if(derived().outerSize()==0)
+        return 0;
+      else
+        return innerNonZeros().sum();
+    }
+    
+    /** \returns a const pointer to the array of values.
+      * This function is aimed at interoperability with other libraries.
+      * \sa innerIndexPtr(), outerIndexPtr() */
+    inline const Scalar* valuePtr() const { return derived().valuePtr(); }
+    /** \returns a non-const pointer to the array of values.
+      * This function is aimed at interoperability with other libraries.
+      * \sa innerIndexPtr(), outerIndexPtr() */
+    inline Scalar* valuePtr() { return derived().valuePtr(); }
+
+    /** \returns a const pointer to the array of inner indices.
+      * This function is aimed at interoperability with other libraries.
+      * \sa valuePtr(), outerIndexPtr() */
+    inline const StorageIndex* innerIndexPtr() const { return derived().innerIndexPtr(); }
+    /** \returns a non-const pointer to the array of inner indices.
+      * This function is aimed at interoperability with other libraries.
+      * \sa valuePtr(), outerIndexPtr() */
+    inline StorageIndex* innerIndexPtr() { return derived().innerIndexPtr(); }
+
+    /** \returns a const pointer to the array of the starting positions of the inner vectors.
+      * This function is aimed at interoperability with other libraries.
+      * \warning it returns the null pointer 0 for SparseVector
+      * \sa valuePtr(), innerIndexPtr() */
+    inline const StorageIndex* outerIndexPtr() const { return derived().outerIndexPtr(); }
+    /** \returns a non-const pointer to the array of the starting positions of the inner vectors.
+      * This function is aimed at interoperability with other libraries.
+      * \warning it returns the null pointer 0 for SparseVector
+      * \sa valuePtr(), innerIndexPtr() */
+    inline StorageIndex* outerIndexPtr() { return derived().outerIndexPtr(); }
+
+    /** \returns a const pointer to the array of the number of non zeros of the inner vectors.
+      * This function is aimed at interoperability with other libraries.
+      * \warning it returns the null pointer 0 in compressed mode */
+    inline const StorageIndex* innerNonZeroPtr() const { return derived().innerNonZeroPtr(); }
+    /** \returns a non-const pointer to the array of the number of non zeros of the inner vectors.
+      * This function is aimed at interoperability with other libraries.
+      * \warning it returns the null pointer 0 in compressed mode */
+    inline StorageIndex* innerNonZeroPtr() { return derived().innerNonZeroPtr(); }
+    
+    /** \returns whether \c *this is in compressed form. */
+    inline bool isCompressed() const { return innerNonZeroPtr()==0; }
+
+    /** \returns a read-only view of the stored coefficients as a 1D array expression.
+      *
+      * \warning this method is for \b compressed \b storage \b only, and it will trigger an assertion otherwise.
+      *
+      * \sa valuePtr(), isCompressed() */
+    const Map<const Array<Scalar,Dynamic,1> > coeffs() const { eigen_assert(isCompressed()); return Array<Scalar,Dynamic,1>::Map(valuePtr(),nonZeros()); }
+
+    /** \returns a read-write view of the stored coefficients as a 1D array expression
+      *
+      * \warning this method is for \b compressed \b storage \b only, and it will trigger an assertion otherwise.
+      *
+      * Here is an example:
+      * \include SparseMatrix_coeffs.cpp
+      * and the output is:
+      * \include SparseMatrix_coeffs.out
+      *
+      * \sa valuePtr(), isCompressed() */
+    Map<Array<Scalar,Dynamic,1> > coeffs() { eigen_assert(isCompressed()); return Array<Scalar,Dynamic,1>::Map(valuePtr(),nonZeros()); }
+
+  protected:
+    /** Default constructor. Do nothing. */
+    SparseCompressedBase() {}
+
+    /** \internal return the index of the coeff at (row,col) or just before if it does not exist.
+      * This is an analogue of std::lower_bound.
+      */
+    internal::LowerBoundIndex lower_bound(Index row, Index col) const
+    {
+      eigen_internal_assert(row>=0 && row<this->rows() && col>=0 && col<this->cols());
+
+      const Index outer = Derived::IsRowMajor ? row : col;
+      const Index inner = Derived::IsRowMajor ? col : row;
+
+      Index start = this->outerIndexPtr()[outer];
+      Index end = this->isCompressed() ? this->outerIndexPtr()[outer+1] : this->outerIndexPtr()[outer] + this->innerNonZeroPtr()[outer];
+      eigen_assert(end>=start && "you are using a non finalized sparse matrix or written coefficient does not exist");
+      internal::LowerBoundIndex p;
+      p.value = std::lower_bound(this->innerIndexPtr()+start, this->innerIndexPtr()+end,inner) - this->innerIndexPtr();
+      p.found = (p.value<end) && (this->innerIndexPtr()[p.value]==inner);
+      return p;
+    }
+
+    friend struct internal::evaluator<SparseCompressedBase<Derived> >;
+
+  private:
+    template<typename OtherDerived> explicit SparseCompressedBase(const SparseCompressedBase<OtherDerived>&);
+};
+
+template<typename Derived>
+class SparseCompressedBase<Derived>::InnerIterator
+{
+  public:
+    InnerIterator()
+      : m_values(0), m_indices(0), m_outer(0), m_id(0), m_end(0)
+    {}
+
+    InnerIterator(const InnerIterator& other)
+      : m_values(other.m_values), m_indices(other.m_indices), m_outer(other.m_outer), m_id(other.m_id), m_end(other.m_end)
+    {}
+
+    InnerIterator& operator=(const InnerIterator& other)
+    {
+      m_values = other.m_values;
+      m_indices = other.m_indices;
+      const_cast<OuterType&>(m_outer).setValue(other.m_outer.value());
+      m_id = other.m_id;
+      m_end = other.m_end;
+      return *this;
+    }
+
+    InnerIterator(const SparseCompressedBase& mat, Index outer)
+      : m_values(mat.valuePtr()), m_indices(mat.innerIndexPtr()), m_outer(outer)
+    {
+      if(Derived::IsVectorAtCompileTime && mat.outerIndexPtr()==0)
+      {
+        m_id = 0;
+        m_end = mat.nonZeros();
+      }
+      else
+      {
+        m_id = mat.outerIndexPtr()[outer];
+        if(mat.isCompressed())
+          m_end = mat.outerIndexPtr()[outer+1];
+        else
+          m_end = m_id + mat.innerNonZeroPtr()[outer];
+      }
+    }
+
+    explicit InnerIterator(const SparseCompressedBase& mat)
+      : m_values(mat.valuePtr()), m_indices(mat.innerIndexPtr()), m_outer(0), m_id(0), m_end(mat.nonZeros())
+    {
+      EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived);
+    }
+
+    explicit InnerIterator(const internal::CompressedStorage<Scalar,StorageIndex>& data)
+      : m_values(data.valuePtr()), m_indices(data.indexPtr()), m_outer(0), m_id(0), m_end(data.size())
+    {
+      EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived);
+    }
+
+    inline InnerIterator& operator++() { m_id++; return *this; }
+    inline InnerIterator& operator+=(Index i) { m_id += i ; return *this; }
+
+    inline InnerIterator operator+(Index i) 
+    { 
+        InnerIterator result = *this;
+        result += i;
+        return result;
+    }
+
+    inline const Scalar& value() const { return m_values[m_id]; }
+    inline Scalar& valueRef() { return const_cast<Scalar&>(m_values[m_id]); }
+
+    inline StorageIndex index() const { return m_indices[m_id]; }
+    inline Index outer() const { return m_outer.value(); }
+    inline Index row() const { return IsRowMajor ? m_outer.value() : index(); }
+    inline Index col() const { return IsRowMajor ? index() : m_outer.value(); }
+
+    inline operator bool() const { return (m_id < m_end); }
+
+  protected:
+    const Scalar* m_values;
+    const StorageIndex* m_indices;
+    typedef internal::variable_if_dynamic<Index,Derived::IsVectorAtCompileTime?0:Dynamic> OuterType;
+    const OuterType m_outer;
+    Index m_id;
+    Index m_end;
+  private:
+    // If you get here, then you're not using the right InnerIterator type, e.g.:
+    //   SparseMatrix<double,RowMajor> A;
+    //   SparseMatrix<double>::InnerIterator it(A,0);
+    template<typename T> InnerIterator(const SparseMatrixBase<T>&, Index outer);
+};
+
+template<typename Derived>
+class SparseCompressedBase<Derived>::ReverseInnerIterator
+{
+  public:
+    ReverseInnerIterator(const SparseCompressedBase& mat, Index outer)
+      : m_values(mat.valuePtr()), m_indices(mat.innerIndexPtr()), m_outer(outer)
+    {
+      if(Derived::IsVectorAtCompileTime && mat.outerIndexPtr()==0)
+      {
+        m_start = 0;
+        m_id = mat.nonZeros();
+      }
+      else
+      {
+        m_start = mat.outerIndexPtr()[outer];
+        if(mat.isCompressed())
+          m_id = mat.outerIndexPtr()[outer+1];
+        else
+          m_id = m_start + mat.innerNonZeroPtr()[outer];
+      }
+    }
+
+    explicit ReverseInnerIterator(const SparseCompressedBase& mat)
+      : m_values(mat.valuePtr()), m_indices(mat.innerIndexPtr()), m_outer(0), m_start(0), m_id(mat.nonZeros())
+    {
+      EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived);
+    }
+
+    explicit ReverseInnerIterator(const internal::CompressedStorage<Scalar,StorageIndex>& data)
+      : m_values(data.valuePtr()), m_indices(data.indexPtr()), m_outer(0), m_start(0), m_id(data.size())
+    {
+      EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived);
+    }
+
+    inline ReverseInnerIterator& operator--() { --m_id; return *this; }
+    inline ReverseInnerIterator& operator-=(Index i) { m_id -= i; return *this; }
+
+    inline ReverseInnerIterator operator-(Index i) 
+    {
+        ReverseInnerIterator result = *this;
+        result -= i;
+        return result;
+    }
+
+    inline const Scalar& value() const { return m_values[m_id-1]; }
+    inline Scalar& valueRef() { return const_cast<Scalar&>(m_values[m_id-1]); }
+
+    inline StorageIndex index() const { return m_indices[m_id-1]; }
+    inline Index outer() const { return m_outer.value(); }
+    inline Index row() const { return IsRowMajor ? m_outer.value() : index(); }
+    inline Index col() const { return IsRowMajor ? index() : m_outer.value(); }
+
+    inline operator bool() const { return (m_id > m_start); }
+
+  protected:
+    const Scalar* m_values;
+    const StorageIndex* m_indices;
+    typedef internal::variable_if_dynamic<Index,Derived::IsVectorAtCompileTime?0:Dynamic> OuterType;
+    const OuterType m_outer;
+    Index m_start;
+    Index m_id;
+};
+
+namespace internal {
+
+template<typename Derived>
+struct evaluator<SparseCompressedBase<Derived> >
+  : evaluator_base<Derived>
+{
+  typedef typename Derived::Scalar Scalar;
+  typedef typename Derived::InnerIterator InnerIterator;
+  
+  enum {
+    CoeffReadCost = NumTraits<Scalar>::ReadCost,
+    Flags = Derived::Flags
+  };
+  
+  evaluator() : m_matrix(0), m_zero(0)
+  {
+    EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);
+  }
+  explicit evaluator(const Derived &mat) : m_matrix(&mat), m_zero(0)
+  {
+    EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);
+  }
+  
+  inline Index nonZerosEstimate() const {
+    return m_matrix->nonZeros();
+  }
+  
+  operator Derived&() { return m_matrix->const_cast_derived(); }
+  operator const Derived&() const { return *m_matrix; }
+  
+  typedef typename DenseCoeffsBase<Derived,ReadOnlyAccessors>::CoeffReturnType CoeffReturnType;
+  const Scalar& coeff(Index row, Index col) const
+  {
+    Index p = find(row,col);
+
+    if(p==Dynamic)
+      return m_zero;
+    else
+      return m_matrix->const_cast_derived().valuePtr()[p];
+  }
+
+  Scalar& coeffRef(Index row, Index col)
+  {
+    Index p = find(row,col);
+    eigen_assert(p!=Dynamic && "written coefficient does not exist");
+    return m_matrix->const_cast_derived().valuePtr()[p];
+  }
+
+protected:
+
+  Index find(Index row, Index col) const
+  {
+    internal::LowerBoundIndex p = m_matrix->lower_bound(row,col);
+    return p.found ? p.value : Dynamic;
+  }
+
+  const Derived *m_matrix;
+  const Scalar m_zero;
+};
+
+}
+
+} // end namespace Eigen
+
+#endif // EIGEN_SPARSE_COMPRESSED_BASE_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseCwiseBinaryOp.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseCwiseBinaryOp.h
new file mode 100644
index 0000000..9b0d3f9
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseCwiseBinaryOp.h
@@ -0,0 +1,722 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2008-2014 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_SPARSE_CWISE_BINARY_OP_H
+#define EIGEN_SPARSE_CWISE_BINARY_OP_H
+
+namespace Eigen { 
+
+// Here we have to handle 3 cases:
+//  1 - sparse op dense
+//  2 - dense op sparse
+//  3 - sparse op sparse
+// We also need to implement a 4th iterator for:
+//  4 - dense op dense
+// Finally, we also need to distinguish between the product and other operations :
+//                configuration      returned mode
+//  1 - sparse op dense    product      sparse
+//                         generic      dense
+//  2 - dense op sparse    product      sparse
+//                         generic      dense
+//  3 - sparse op sparse   product      sparse
+//                         generic      sparse
+//  4 - dense op dense     product      dense
+//                         generic      dense
+//
+// TODO to ease compiler job, we could specialize product/quotient with a scalar
+//      and fallback to cwise-unary evaluator using bind1st_op and bind2nd_op.
+
+template<typename BinaryOp, typename Lhs, typename Rhs>
+class CwiseBinaryOpImpl<BinaryOp, Lhs, Rhs, Sparse>
+  : public SparseMatrixBase<CwiseBinaryOp<BinaryOp, Lhs, Rhs> >
+{
+  public:
+    typedef CwiseBinaryOp<BinaryOp, Lhs, Rhs> Derived;
+    typedef SparseMatrixBase<Derived> Base;
+    EIGEN_SPARSE_PUBLIC_INTERFACE(Derived)
+    CwiseBinaryOpImpl()
+    {
+      EIGEN_STATIC_ASSERT((
+                (!internal::is_same<typename internal::traits<Lhs>::StorageKind,
+                                    typename internal::traits<Rhs>::StorageKind>::value)
+            ||  ((internal::evaluator<Lhs>::Flags&RowMajorBit) == (internal::evaluator<Rhs>::Flags&RowMajorBit))),
+            THE_STORAGE_ORDER_OF_BOTH_SIDES_MUST_MATCH);
+    }
+};
+
+namespace internal {
+
+  
+// Generic "sparse OP sparse"
+template<typename XprType> struct binary_sparse_evaluator;
+
+template<typename BinaryOp, typename Lhs, typename Rhs>
+struct binary_evaluator<CwiseBinaryOp<BinaryOp, Lhs, Rhs>, IteratorBased, IteratorBased>
+  : evaluator_base<CwiseBinaryOp<BinaryOp, Lhs, Rhs> >
+{
+protected:
+  typedef typename evaluator<Lhs>::InnerIterator  LhsIterator;
+  typedef typename evaluator<Rhs>::InnerIterator  RhsIterator;
+  typedef CwiseBinaryOp<BinaryOp, Lhs, Rhs> XprType;
+  typedef typename traits<XprType>::Scalar Scalar;
+  typedef typename XprType::StorageIndex StorageIndex;
+public:
+
+  class InnerIterator
+  {
+  public:
+    
+    EIGEN_STRONG_INLINE InnerIterator(const binary_evaluator& aEval, Index outer)
+      : m_lhsIter(aEval.m_lhsImpl,outer), m_rhsIter(aEval.m_rhsImpl,outer), m_functor(aEval.m_functor)
+    {
+      this->operator++();
+    }
+
+    EIGEN_STRONG_INLINE InnerIterator& operator++()
+    {
+      if (m_lhsIter && m_rhsIter && (m_lhsIter.index() == m_rhsIter.index()))
+      {
+        m_id = m_lhsIter.index();
+        m_value = m_functor(m_lhsIter.value(), m_rhsIter.value());
+        ++m_lhsIter;
+        ++m_rhsIter;
+      }
+      else if (m_lhsIter && (!m_rhsIter || (m_lhsIter.index() < m_rhsIter.index())))
+      {
+        m_id = m_lhsIter.index();
+        m_value = m_functor(m_lhsIter.value(), Scalar(0));
+        ++m_lhsIter;
+      }
+      else if (m_rhsIter && (!m_lhsIter || (m_lhsIter.index() > m_rhsIter.index())))
+      {
+        m_id = m_rhsIter.index();
+        m_value = m_functor(Scalar(0), m_rhsIter.value());
+        ++m_rhsIter;
+      }
+      else
+      {
+        m_value = Scalar(0); // this is to avoid a compilation warning
+        m_id = -1;
+      }
+      return *this;
+    }
+
+    EIGEN_STRONG_INLINE Scalar value() const { return m_value; }
+
+    EIGEN_STRONG_INLINE StorageIndex index() const { return m_id; }
+    EIGEN_STRONG_INLINE Index outer() const { return m_lhsIter.outer(); }
+    EIGEN_STRONG_INLINE Index row() const { return Lhs::IsRowMajor ? m_lhsIter.row() : index(); }
+    EIGEN_STRONG_INLINE Index col() const { return Lhs::IsRowMajor ? index() : m_lhsIter.col(); }
+
+    EIGEN_STRONG_INLINE operator bool() const { return m_id>=0; }
+
+  protected:
+    LhsIterator m_lhsIter;
+    RhsIterator m_rhsIter;
+    const BinaryOp& m_functor;
+    Scalar m_value;
+    StorageIndex m_id;
+  };
+  
+  
+  enum {
+    CoeffReadCost = int(evaluator<Lhs>::CoeffReadCost) + int(evaluator<Rhs>::CoeffReadCost) + int(functor_traits<BinaryOp>::Cost),
+    Flags = XprType::Flags
+  };
+  
+  explicit binary_evaluator(const XprType& xpr)
+    : m_functor(xpr.functor()),
+      m_lhsImpl(xpr.lhs()), 
+      m_rhsImpl(xpr.rhs())  
+  {
+    EIGEN_INTERNAL_CHECK_COST_VALUE(functor_traits<BinaryOp>::Cost);
+    EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);
+  }
+  
+  inline Index nonZerosEstimate() const {
+    return m_lhsImpl.nonZerosEstimate() + m_rhsImpl.nonZerosEstimate();
+  }
+
+protected:
+  const BinaryOp m_functor;
+  evaluator<Lhs> m_lhsImpl;
+  evaluator<Rhs> m_rhsImpl;
+};
+
+// dense op sparse
+template<typename BinaryOp, typename Lhs, typename Rhs>
+struct binary_evaluator<CwiseBinaryOp<BinaryOp, Lhs, Rhs>, IndexBased, IteratorBased>
+  : evaluator_base<CwiseBinaryOp<BinaryOp, Lhs, Rhs> >
+{
+protected:
+  typedef typename evaluator<Rhs>::InnerIterator  RhsIterator;
+  typedef CwiseBinaryOp<BinaryOp, Lhs, Rhs> XprType;
+  typedef typename traits<XprType>::Scalar Scalar;
+  typedef typename XprType::StorageIndex StorageIndex;
+public:
+
+  class InnerIterator
+  {
+    enum { IsRowMajor = (int(Rhs::Flags)&RowMajorBit)==RowMajorBit };
+  public:
+
+    EIGEN_STRONG_INLINE InnerIterator(const binary_evaluator& aEval, Index outer)
+      : m_lhsEval(aEval.m_lhsImpl), m_rhsIter(aEval.m_rhsImpl,outer), m_functor(aEval.m_functor), m_value(0), m_id(-1), m_innerSize(aEval.m_expr.rhs().innerSize())
+    {
+      this->operator++();
+    }
+
+    EIGEN_STRONG_INLINE InnerIterator& operator++()
+    {
+      ++m_id;
+      if(m_id<m_innerSize)
+      {
+        Scalar lhsVal = m_lhsEval.coeff(IsRowMajor?m_rhsIter.outer():m_id,
+                                        IsRowMajor?m_id:m_rhsIter.outer());
+        if(m_rhsIter && m_rhsIter.index()==m_id)
+        {
+          m_value = m_functor(lhsVal, m_rhsIter.value());
+          ++m_rhsIter;
+        }
+        else
+          m_value = m_functor(lhsVal, Scalar(0));
+      }
+
+      return *this;
+    }
+
+    EIGEN_STRONG_INLINE Scalar value() const { eigen_internal_assert(m_id<m_innerSize); return m_value; }
+
+    EIGEN_STRONG_INLINE StorageIndex index() const { return m_id; }
+    EIGEN_STRONG_INLINE Index outer() const { return m_rhsIter.outer(); }
+    EIGEN_STRONG_INLINE Index row() const { return IsRowMajor ? m_rhsIter.outer() : m_id; }
+    EIGEN_STRONG_INLINE Index col() const { return IsRowMajor ? m_id : m_rhsIter.outer(); }
+
+    EIGEN_STRONG_INLINE operator bool() const { return m_id<m_innerSize; }
+
+  protected:
+    const evaluator<Lhs> &m_lhsEval;
+    RhsIterator m_rhsIter;
+    const BinaryOp& m_functor;
+    Scalar m_value;
+    StorageIndex m_id;
+    StorageIndex m_innerSize;
+  };
+
+
+  enum {
+    CoeffReadCost = int(evaluator<Lhs>::CoeffReadCost) + int(evaluator<Rhs>::CoeffReadCost) + int(functor_traits<BinaryOp>::Cost),
+    Flags = XprType::Flags
+  };
+
+  explicit binary_evaluator(const XprType& xpr)
+    : m_functor(xpr.functor()),
+      m_lhsImpl(xpr.lhs()),
+      m_rhsImpl(xpr.rhs()),
+      m_expr(xpr)
+  {
+    EIGEN_INTERNAL_CHECK_COST_VALUE(functor_traits<BinaryOp>::Cost);
+    EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);
+  }
+
+  inline Index nonZerosEstimate() const {
+    return m_expr.size();
+  }
+
+protected:
+  const BinaryOp m_functor;
+  evaluator<Lhs> m_lhsImpl;
+  evaluator<Rhs> m_rhsImpl;
+  const XprType &m_expr;
+};
+
+// sparse op dense
+template<typename BinaryOp, typename Lhs, typename Rhs>
+struct binary_evaluator<CwiseBinaryOp<BinaryOp, Lhs, Rhs>, IteratorBased, IndexBased>
+  : evaluator_base<CwiseBinaryOp<BinaryOp, Lhs, Rhs> >
+{
+protected:
+  typedef typename evaluator<Lhs>::InnerIterator  LhsIterator;
+  typedef CwiseBinaryOp<BinaryOp, Lhs, Rhs> XprType;
+  typedef typename traits<XprType>::Scalar Scalar;
+  typedef typename XprType::StorageIndex StorageIndex;
+public:
+
+  class InnerIterator
+  {
+    enum { IsRowMajor = (int(Lhs::Flags)&RowMajorBit)==RowMajorBit };
+  public:
+
+    EIGEN_STRONG_INLINE InnerIterator(const binary_evaluator& aEval, Index outer)
+      : m_lhsIter(aEval.m_lhsImpl,outer), m_rhsEval(aEval.m_rhsImpl), m_functor(aEval.m_functor), m_value(0), m_id(-1), m_innerSize(aEval.m_expr.lhs().innerSize())
+    {
+      this->operator++();
+    }
+
+    EIGEN_STRONG_INLINE InnerIterator& operator++()
+    {
+      ++m_id;
+      if(m_id<m_innerSize)
+      {
+        Scalar rhsVal = m_rhsEval.coeff(IsRowMajor?m_lhsIter.outer():m_id,
+                                        IsRowMajor?m_id:m_lhsIter.outer());
+        if(m_lhsIter && m_lhsIter.index()==m_id)
+        {
+          m_value = m_functor(m_lhsIter.value(), rhsVal);
+          ++m_lhsIter;
+        }
+        else
+          m_value = m_functor(Scalar(0),rhsVal);
+      }
+
+      return *this;
+    }
+
+    EIGEN_STRONG_INLINE Scalar value() const { eigen_internal_assert(m_id<m_innerSize); return m_value; }
+
+    EIGEN_STRONG_INLINE StorageIndex index() const { return m_id; }
+    EIGEN_STRONG_INLINE Index outer() const { return m_lhsIter.outer(); }
+    EIGEN_STRONG_INLINE Index row() const { return IsRowMajor ? m_lhsIter.outer() : m_id; }
+    EIGEN_STRONG_INLINE Index col() const { return IsRowMajor ? m_id : m_lhsIter.outer(); }
+
+    EIGEN_STRONG_INLINE operator bool() const { return m_id<m_innerSize; }
+
+  protected:
+    LhsIterator m_lhsIter;
+    const evaluator<Rhs> &m_rhsEval;
+    const BinaryOp& m_functor;
+    Scalar m_value;
+    StorageIndex m_id;
+    StorageIndex m_innerSize;
+  };
+
+
+  enum {
+    CoeffReadCost = int(evaluator<Lhs>::CoeffReadCost) + int(evaluator<Rhs>::CoeffReadCost) + int(functor_traits<BinaryOp>::Cost),
+    Flags = XprType::Flags
+  };
+
+  explicit binary_evaluator(const XprType& xpr)
+    : m_functor(xpr.functor()),
+      m_lhsImpl(xpr.lhs()),
+      m_rhsImpl(xpr.rhs()),
+      m_expr(xpr)
+  {
+    EIGEN_INTERNAL_CHECK_COST_VALUE(functor_traits<BinaryOp>::Cost);
+    EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);
+  }
+
+  inline Index nonZerosEstimate() const {
+    return m_expr.size();
+  }
+
+protected:
+  const BinaryOp m_functor;
+  evaluator<Lhs> m_lhsImpl;
+  evaluator<Rhs> m_rhsImpl;
+  const XprType &m_expr;
+};
+
+template<typename T,
+         typename LhsKind   = typename evaluator_traits<typename T::Lhs>::Kind,
+         typename RhsKind   = typename evaluator_traits<typename T::Rhs>::Kind,
+         typename LhsScalar = typename traits<typename T::Lhs>::Scalar,
+         typename RhsScalar = typename traits<typename T::Rhs>::Scalar> struct sparse_conjunction_evaluator;
+
+// "sparse .* sparse"
+template<typename T1, typename T2, typename Lhs, typename Rhs>
+struct binary_evaluator<CwiseBinaryOp<scalar_product_op<T1,T2>, Lhs, Rhs>, IteratorBased, IteratorBased>
+  : sparse_conjunction_evaluator<CwiseBinaryOp<scalar_product_op<T1,T2>, Lhs, Rhs> >
+{
+  typedef CwiseBinaryOp<scalar_product_op<T1,T2>, Lhs, Rhs> XprType;
+  typedef sparse_conjunction_evaluator<XprType> Base;
+  explicit binary_evaluator(const XprType& xpr) : Base(xpr) {}
+};
+// "dense .* sparse"
+template<typename T1, typename T2, typename Lhs, typename Rhs>
+struct binary_evaluator<CwiseBinaryOp<scalar_product_op<T1,T2>, Lhs, Rhs>, IndexBased, IteratorBased>
+  : sparse_conjunction_evaluator<CwiseBinaryOp<scalar_product_op<T1,T2>, Lhs, Rhs> >
+{
+  typedef CwiseBinaryOp<scalar_product_op<T1,T2>, Lhs, Rhs> XprType;
+  typedef sparse_conjunction_evaluator<XprType> Base;
+  explicit binary_evaluator(const XprType& xpr) : Base(xpr) {}
+};
+// "sparse .* dense"
+template<typename T1, typename T2, typename Lhs, typename Rhs>
+struct binary_evaluator<CwiseBinaryOp<scalar_product_op<T1,T2>, Lhs, Rhs>, IteratorBased, IndexBased>
+  : sparse_conjunction_evaluator<CwiseBinaryOp<scalar_product_op<T1,T2>, Lhs, Rhs> >
+{
+  typedef CwiseBinaryOp<scalar_product_op<T1,T2>, Lhs, Rhs> XprType;
+  typedef sparse_conjunction_evaluator<XprType> Base;
+  explicit binary_evaluator(const XprType& xpr) : Base(xpr) {}
+};
+
+// "sparse ./ dense"
+template<typename T1, typename T2, typename Lhs, typename Rhs>
+struct binary_evaluator<CwiseBinaryOp<scalar_quotient_op<T1,T2>, Lhs, Rhs>, IteratorBased, IndexBased>
+  : sparse_conjunction_evaluator<CwiseBinaryOp<scalar_quotient_op<T1,T2>, Lhs, Rhs> >
+{
+  typedef CwiseBinaryOp<scalar_quotient_op<T1,T2>, Lhs, Rhs> XprType;
+  typedef sparse_conjunction_evaluator<XprType> Base;
+  explicit binary_evaluator(const XprType& xpr) : Base(xpr) {}
+};
+
+// "sparse && sparse"
+template<typename Lhs, typename Rhs>
+struct binary_evaluator<CwiseBinaryOp<scalar_boolean_and_op, Lhs, Rhs>, IteratorBased, IteratorBased>
+  : sparse_conjunction_evaluator<CwiseBinaryOp<scalar_boolean_and_op, Lhs, Rhs> >
+{
+  typedef CwiseBinaryOp<scalar_boolean_and_op, Lhs, Rhs> XprType;
+  typedef sparse_conjunction_evaluator<XprType> Base;
+  explicit binary_evaluator(const XprType& xpr) : Base(xpr) {}
+};
+// "dense && sparse"
+template<typename Lhs, typename Rhs>
+struct binary_evaluator<CwiseBinaryOp<scalar_boolean_and_op, Lhs, Rhs>, IndexBased, IteratorBased>
+  : sparse_conjunction_evaluator<CwiseBinaryOp<scalar_boolean_and_op, Lhs, Rhs> >
+{
+  typedef CwiseBinaryOp<scalar_boolean_and_op, Lhs, Rhs> XprType;
+  typedef sparse_conjunction_evaluator<XprType> Base;
+  explicit binary_evaluator(const XprType& xpr) : Base(xpr) {}
+};
+// "sparse && dense"
+template<typename Lhs, typename Rhs>
+struct binary_evaluator<CwiseBinaryOp<scalar_boolean_and_op, Lhs, Rhs>, IteratorBased, IndexBased>
+  : sparse_conjunction_evaluator<CwiseBinaryOp<scalar_boolean_and_op, Lhs, Rhs> >
+{
+  typedef CwiseBinaryOp<scalar_boolean_and_op, Lhs, Rhs> XprType;
+  typedef sparse_conjunction_evaluator<XprType> Base;
+  explicit binary_evaluator(const XprType& xpr) : Base(xpr) {}
+};
+
+// "sparse ^ sparse"
+template<typename XprType>
+struct sparse_conjunction_evaluator<XprType, IteratorBased, IteratorBased>
+  : evaluator_base<XprType>
+{
+protected:
+  typedef typename XprType::Functor BinaryOp;
+  typedef typename XprType::Lhs LhsArg;
+  typedef typename XprType::Rhs RhsArg;
+  typedef typename evaluator<LhsArg>::InnerIterator  LhsIterator;
+  typedef typename evaluator<RhsArg>::InnerIterator  RhsIterator;
+  typedef typename XprType::StorageIndex StorageIndex;
+  typedef typename traits<XprType>::Scalar Scalar;
+public:
+
+  class InnerIterator
+  {
+  public:
+    
+    EIGEN_STRONG_INLINE InnerIterator(const sparse_conjunction_evaluator& aEval, Index outer)
+      : m_lhsIter(aEval.m_lhsImpl,outer), m_rhsIter(aEval.m_rhsImpl,outer), m_functor(aEval.m_functor)
+    {
+      while (m_lhsIter && m_rhsIter && (m_lhsIter.index() != m_rhsIter.index()))
+      {
+        if (m_lhsIter.index() < m_rhsIter.index())
+          ++m_lhsIter;
+        else
+          ++m_rhsIter;
+      }
+    }
+
+    EIGEN_STRONG_INLINE InnerIterator& operator++()
+    {
+      ++m_lhsIter;
+      ++m_rhsIter;
+      while (m_lhsIter && m_rhsIter && (m_lhsIter.index() != m_rhsIter.index()))
+      {
+        if (m_lhsIter.index() < m_rhsIter.index())
+          ++m_lhsIter;
+        else
+          ++m_rhsIter;
+      }
+      return *this;
+    }
+    
+    EIGEN_STRONG_INLINE Scalar value() const { return m_functor(m_lhsIter.value(), m_rhsIter.value()); }
+
+    EIGEN_STRONG_INLINE StorageIndex index() const { return m_lhsIter.index(); }
+    EIGEN_STRONG_INLINE Index outer() const { return m_lhsIter.outer(); }
+    EIGEN_STRONG_INLINE Index row() const { return m_lhsIter.row(); }
+    EIGEN_STRONG_INLINE Index col() const { return m_lhsIter.col(); }
+
+    EIGEN_STRONG_INLINE operator bool() const { return (m_lhsIter && m_rhsIter); }
+
+  protected:
+    LhsIterator m_lhsIter;
+    RhsIterator m_rhsIter;
+    const BinaryOp& m_functor;
+  };
+  
+  
+  enum {
+    CoeffReadCost = int(evaluator<LhsArg>::CoeffReadCost) + int(evaluator<RhsArg>::CoeffReadCost) + int(functor_traits<BinaryOp>::Cost),
+    Flags = XprType::Flags
+  };
+  
+  explicit sparse_conjunction_evaluator(const XprType& xpr)
+    : m_functor(xpr.functor()),
+      m_lhsImpl(xpr.lhs()), 
+      m_rhsImpl(xpr.rhs())  
+  {
+    EIGEN_INTERNAL_CHECK_COST_VALUE(functor_traits<BinaryOp>::Cost);
+    EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);
+  }
+  
+  inline Index nonZerosEstimate() const {
+    return (std::min)(m_lhsImpl.nonZerosEstimate(), m_rhsImpl.nonZerosEstimate());
+  }
+
+protected:
+  const BinaryOp m_functor;
+  evaluator<LhsArg> m_lhsImpl;
+  evaluator<RhsArg> m_rhsImpl;
+};
+
+// "dense ^ sparse"
+template<typename XprType>
+struct sparse_conjunction_evaluator<XprType, IndexBased, IteratorBased>
+  : evaluator_base<XprType>
+{
+protected:
+  typedef typename XprType::Functor BinaryOp;
+  typedef typename XprType::Lhs LhsArg;
+  typedef typename XprType::Rhs RhsArg;
+  typedef evaluator<LhsArg> LhsEvaluator;
+  typedef typename evaluator<RhsArg>::InnerIterator  RhsIterator;
+  typedef typename XprType::StorageIndex StorageIndex;
+  typedef typename traits<XprType>::Scalar Scalar;
+public:
+
+  class InnerIterator
+  {
+    enum { IsRowMajor = (int(RhsArg::Flags)&RowMajorBit)==RowMajorBit };
+
+  public:
+    
+    EIGEN_STRONG_INLINE InnerIterator(const sparse_conjunction_evaluator& aEval, Index outer)
+      : m_lhsEval(aEval.m_lhsImpl), m_rhsIter(aEval.m_rhsImpl,outer), m_functor(aEval.m_functor), m_outer(outer)
+    {}
+
+    EIGEN_STRONG_INLINE InnerIterator& operator++()
+    {
+      ++m_rhsIter;
+      return *this;
+    }
+
+    EIGEN_STRONG_INLINE Scalar value() const
+    { return m_functor(m_lhsEval.coeff(IsRowMajor?m_outer:m_rhsIter.index(),IsRowMajor?m_rhsIter.index():m_outer), m_rhsIter.value()); }
+
+    EIGEN_STRONG_INLINE StorageIndex index() const { return m_rhsIter.index(); }
+    EIGEN_STRONG_INLINE Index outer() const { return m_rhsIter.outer(); }
+    EIGEN_STRONG_INLINE Index row() const { return m_rhsIter.row(); }
+    EIGEN_STRONG_INLINE Index col() const { return m_rhsIter.col(); }
+
+    EIGEN_STRONG_INLINE operator bool() const { return m_rhsIter; }
+    
+  protected:
+    const LhsEvaluator &m_lhsEval;
+    RhsIterator m_rhsIter;
+    const BinaryOp& m_functor;
+    const Index m_outer;
+  };
+  
+  
+  enum {
+    CoeffReadCost = int(evaluator<LhsArg>::CoeffReadCost) + int(evaluator<RhsArg>::CoeffReadCost) + int(functor_traits<BinaryOp>::Cost),
+    Flags = XprType::Flags
+  };
+  
+  explicit sparse_conjunction_evaluator(const XprType& xpr)
+    : m_functor(xpr.functor()),
+      m_lhsImpl(xpr.lhs()), 
+      m_rhsImpl(xpr.rhs())  
+  {
+    EIGEN_INTERNAL_CHECK_COST_VALUE(functor_traits<BinaryOp>::Cost);
+    EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);
+  }
+  
+  inline Index nonZerosEstimate() const {
+    return m_rhsImpl.nonZerosEstimate();
+  }
+
+protected:
+  const BinaryOp m_functor;
+  evaluator<LhsArg> m_lhsImpl;
+  evaluator<RhsArg> m_rhsImpl;
+};
+
+// "sparse ^ dense"
+template<typename XprType>
+struct sparse_conjunction_evaluator<XprType, IteratorBased, IndexBased>
+  : evaluator_base<XprType>
+{
+protected:
+  typedef typename XprType::Functor BinaryOp;
+  typedef typename XprType::Lhs LhsArg;
+  typedef typename XprType::Rhs RhsArg;
+  typedef typename evaluator<LhsArg>::InnerIterator LhsIterator;
+  typedef evaluator<RhsArg> RhsEvaluator;
+  typedef typename XprType::StorageIndex StorageIndex;
+  typedef typename traits<XprType>::Scalar Scalar;
+public:
+
+  class InnerIterator
+  {
+    enum { IsRowMajor = (int(LhsArg::Flags)&RowMajorBit)==RowMajorBit };
+
+  public:
+    
+    EIGEN_STRONG_INLINE InnerIterator(const sparse_conjunction_evaluator& aEval, Index outer)
+      : m_lhsIter(aEval.m_lhsImpl,outer), m_rhsEval(aEval.m_rhsImpl), m_functor(aEval.m_functor), m_outer(outer)
+    {}
+
+    EIGEN_STRONG_INLINE InnerIterator& operator++()
+    {
+      ++m_lhsIter;
+      return *this;
+    }
+
+    EIGEN_STRONG_INLINE Scalar value() const
+    { return m_functor(m_lhsIter.value(),
+                       m_rhsEval.coeff(IsRowMajor?m_outer:m_lhsIter.index(),IsRowMajor?m_lhsIter.index():m_outer)); }
+
+    EIGEN_STRONG_INLINE StorageIndex index() const { return m_lhsIter.index(); }
+    EIGEN_STRONG_INLINE Index outer() const { return m_lhsIter.outer(); }
+    EIGEN_STRONG_INLINE Index row() const { return m_lhsIter.row(); }
+    EIGEN_STRONG_INLINE Index col() const { return m_lhsIter.col(); }
+
+    EIGEN_STRONG_INLINE operator bool() const { return m_lhsIter; }
+    
+  protected:
+    LhsIterator m_lhsIter;
+    const evaluator<RhsArg> &m_rhsEval;
+    const BinaryOp& m_functor;
+    const Index m_outer;
+  };
+  
+  
+  enum {
+    CoeffReadCost = int(evaluator<LhsArg>::CoeffReadCost) + int(evaluator<RhsArg>::CoeffReadCost) + int(functor_traits<BinaryOp>::Cost),
+    Flags = XprType::Flags
+  };
+  
+  explicit sparse_conjunction_evaluator(const XprType& xpr)
+    : m_functor(xpr.functor()),
+      m_lhsImpl(xpr.lhs()), 
+      m_rhsImpl(xpr.rhs())  
+  {
+    EIGEN_INTERNAL_CHECK_COST_VALUE(functor_traits<BinaryOp>::Cost);
+    EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);
+  }
+  
+  inline Index nonZerosEstimate() const {
+    return m_lhsImpl.nonZerosEstimate();
+  }
+
+protected:
+  const BinaryOp m_functor;
+  evaluator<LhsArg> m_lhsImpl;
+  evaluator<RhsArg> m_rhsImpl;
+};
+
+}
+
+/***************************************************************************
+* Implementation of SparseMatrixBase and SparseCwise functions/operators
+***************************************************************************/
+
+template<typename Derived>
+template<typename OtherDerived>
+Derived& SparseMatrixBase<Derived>::operator+=(const EigenBase<OtherDerived> &other)
+{
+  call_assignment(derived(), other.derived(), internal::add_assign_op<Scalar,typename OtherDerived::Scalar>());
+  return derived();
+}
+
+template<typename Derived>
+template<typename OtherDerived>
+Derived& SparseMatrixBase<Derived>::operator-=(const EigenBase<OtherDerived> &other)
+{
+  call_assignment(derived(), other.derived(), internal::assign_op<Scalar,typename OtherDerived::Scalar>());
+  return derived();
+}
+
+template<typename Derived>
+template<typename OtherDerived>
+EIGEN_STRONG_INLINE Derived &
+SparseMatrixBase<Derived>::operator-=(const SparseMatrixBase<OtherDerived> &other)
+{
+  return derived() = derived() - other.derived();
+}
+
+template<typename Derived>
+template<typename OtherDerived>
+EIGEN_STRONG_INLINE Derived &
+SparseMatrixBase<Derived>::operator+=(const SparseMatrixBase<OtherDerived>& other)
+{
+  return derived() = derived() + other.derived();
+}
+
+template<typename Derived>
+template<typename OtherDerived>
+Derived& SparseMatrixBase<Derived>::operator+=(const DiagonalBase<OtherDerived>& other)
+{
+  call_assignment_no_alias(derived(), other.derived(), internal::add_assign_op<Scalar,typename OtherDerived::Scalar>());
+  return derived();
+}
+
+template<typename Derived>
+template<typename OtherDerived>
+Derived& SparseMatrixBase<Derived>::operator-=(const DiagonalBase<OtherDerived>& other)
+{
+  call_assignment_no_alias(derived(), other.derived(), internal::sub_assign_op<Scalar,typename OtherDerived::Scalar>());
+  return derived();
+}
+    
+template<typename Derived>
+template<typename OtherDerived>
+EIGEN_STRONG_INLINE const typename SparseMatrixBase<Derived>::template CwiseProductDenseReturnType<OtherDerived>::Type
+SparseMatrixBase<Derived>::cwiseProduct(const MatrixBase<OtherDerived> &other) const
+{
+  return typename CwiseProductDenseReturnType<OtherDerived>::Type(derived(), other.derived());
+}
+
+template<typename DenseDerived, typename SparseDerived>
+EIGEN_STRONG_INLINE const CwiseBinaryOp<internal::scalar_sum_op<typename DenseDerived::Scalar,typename SparseDerived::Scalar>, const DenseDerived, const SparseDerived>
+operator+(const MatrixBase<DenseDerived> &a, const SparseMatrixBase<SparseDerived> &b)
+{
+  return CwiseBinaryOp<internal::scalar_sum_op<typename DenseDerived::Scalar,typename SparseDerived::Scalar>, const DenseDerived, const SparseDerived>(a.derived(), b.derived());
+}
+
+template<typename SparseDerived, typename DenseDerived>
+EIGEN_STRONG_INLINE const CwiseBinaryOp<internal::scalar_sum_op<typename SparseDerived::Scalar,typename DenseDerived::Scalar>, const SparseDerived, const DenseDerived>
+operator+(const SparseMatrixBase<SparseDerived> &a, const MatrixBase<DenseDerived> &b)
+{
+  return CwiseBinaryOp<internal::scalar_sum_op<typename SparseDerived::Scalar,typename DenseDerived::Scalar>, const SparseDerived, const DenseDerived>(a.derived(), b.derived());
+}
+
+template<typename DenseDerived, typename SparseDerived>
+EIGEN_STRONG_INLINE const CwiseBinaryOp<internal::scalar_difference_op<typename DenseDerived::Scalar,typename SparseDerived::Scalar>, const DenseDerived, const SparseDerived>
+operator-(const MatrixBase<DenseDerived> &a, const SparseMatrixBase<SparseDerived> &b)
+{
+  return CwiseBinaryOp<internal::scalar_difference_op<typename DenseDerived::Scalar,typename SparseDerived::Scalar>, const DenseDerived, const SparseDerived>(a.derived(), b.derived());
+}
+
+template<typename SparseDerived, typename DenseDerived>
+EIGEN_STRONG_INLINE const CwiseBinaryOp<internal::scalar_difference_op<typename SparseDerived::Scalar,typename DenseDerived::Scalar>, const SparseDerived, const DenseDerived>
+operator-(const SparseMatrixBase<SparseDerived> &a, const MatrixBase<DenseDerived> &b)
+{
+  return CwiseBinaryOp<internal::scalar_difference_op<typename SparseDerived::Scalar,typename DenseDerived::Scalar>, const SparseDerived, const DenseDerived>(a.derived(), b.derived());
+}
+
+} // end namespace Eigen
+
+#endif // EIGEN_SPARSE_CWISE_BINARY_OP_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseCwiseUnaryOp.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseCwiseUnaryOp.h
new file mode 100644
index 0000000..32dac0f
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseCwiseUnaryOp.h
@@ -0,0 +1,150 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2008-2015 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_SPARSE_CWISE_UNARY_OP_H
+#define EIGEN_SPARSE_CWISE_UNARY_OP_H
+
+namespace Eigen { 
+
+namespace internal {
+  
+template<typename UnaryOp, typename ArgType>
+struct unary_evaluator<CwiseUnaryOp<UnaryOp,ArgType>, IteratorBased>
+  : public evaluator_base<CwiseUnaryOp<UnaryOp,ArgType> >
+{
+  public:
+    typedef CwiseUnaryOp<UnaryOp, ArgType> XprType;
+
+    class InnerIterator;
+    
+    enum {
+      CoeffReadCost = int(evaluator<ArgType>::CoeffReadCost) + int(functor_traits<UnaryOp>::Cost),
+      Flags = XprType::Flags
+    };
+    
+    explicit unary_evaluator(const XprType& op) : m_functor(op.functor()), m_argImpl(op.nestedExpression())
+    {
+      EIGEN_INTERNAL_CHECK_COST_VALUE(functor_traits<UnaryOp>::Cost);
+      EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);
+    }
+    
+    inline Index nonZerosEstimate() const {
+      return m_argImpl.nonZerosEstimate();
+    }
+
+  protected:
+    typedef typename evaluator<ArgType>::InnerIterator        EvalIterator;
+    
+    const UnaryOp m_functor;
+    evaluator<ArgType> m_argImpl;
+};
+
+template<typename UnaryOp, typename ArgType>
+class unary_evaluator<CwiseUnaryOp<UnaryOp,ArgType>, IteratorBased>::InnerIterator
+    : public unary_evaluator<CwiseUnaryOp<UnaryOp,ArgType>, IteratorBased>::EvalIterator
+{
+  protected:
+    typedef typename XprType::Scalar Scalar;
+    typedef typename unary_evaluator<CwiseUnaryOp<UnaryOp,ArgType>, IteratorBased>::EvalIterator Base;
+  public:
+
+    EIGEN_STRONG_INLINE InnerIterator(const unary_evaluator& unaryOp, Index outer)
+      : Base(unaryOp.m_argImpl,outer), m_functor(unaryOp.m_functor)
+    {}
+
+    EIGEN_STRONG_INLINE InnerIterator& operator++()
+    { Base::operator++(); return *this; }
+
+    EIGEN_STRONG_INLINE Scalar value() const { return m_functor(Base::value()); }
+
+  protected:
+    const UnaryOp m_functor;
+  private:
+    Scalar& valueRef();
+};
+
+template<typename ViewOp, typename ArgType>
+struct unary_evaluator<CwiseUnaryView<ViewOp,ArgType>, IteratorBased>
+  : public evaluator_base<CwiseUnaryView<ViewOp,ArgType> >
+{
+  public:
+    typedef CwiseUnaryView<ViewOp, ArgType> XprType;
+
+    class InnerIterator;
+    
+    enum {
+      CoeffReadCost = int(evaluator<ArgType>::CoeffReadCost) + int(functor_traits<ViewOp>::Cost),
+      Flags = XprType::Flags
+    };
+    
+    explicit unary_evaluator(const XprType& op) : m_functor(op.functor()), m_argImpl(op.nestedExpression())
+    {
+      EIGEN_INTERNAL_CHECK_COST_VALUE(functor_traits<ViewOp>::Cost);
+      EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);
+    }
+
+  protected:
+    typedef typename evaluator<ArgType>::InnerIterator        EvalIterator;
+    
+    const ViewOp m_functor;
+    evaluator<ArgType> m_argImpl;
+};
+
+template<typename ViewOp, typename ArgType>
+class unary_evaluator<CwiseUnaryView<ViewOp,ArgType>, IteratorBased>::InnerIterator
+    : public unary_evaluator<CwiseUnaryView<ViewOp,ArgType>, IteratorBased>::EvalIterator
+{
+  protected:
+    typedef typename XprType::Scalar Scalar;
+    typedef typename unary_evaluator<CwiseUnaryView<ViewOp,ArgType>, IteratorBased>::EvalIterator Base;
+  public:
+
+    EIGEN_STRONG_INLINE InnerIterator(const unary_evaluator& unaryOp, Index outer)
+      : Base(unaryOp.m_argImpl,outer), m_functor(unaryOp.m_functor)
+    {}
+
+    EIGEN_STRONG_INLINE InnerIterator& operator++()
+    { Base::operator++(); return *this; }
+
+    EIGEN_STRONG_INLINE Scalar value() const { return m_functor(Base::value()); }
+    EIGEN_STRONG_INLINE Scalar& valueRef() { return m_functor(Base::valueRef()); }
+
+  protected:
+    const ViewOp m_functor;
+};
+
+} // end namespace internal
+
+template<typename Derived>
+EIGEN_STRONG_INLINE Derived&
+SparseMatrixBase<Derived>::operator*=(const Scalar& other)
+{
+  typedef typename internal::evaluator<Derived>::InnerIterator EvalIterator;
+  internal::evaluator<Derived> thisEval(derived());
+  for (Index j=0; j<outerSize(); ++j)
+    for (EvalIterator i(thisEval,j); i; ++i)
+      i.valueRef() *= other;
+  return derived();
+}
+
+template<typename Derived>
+EIGEN_STRONG_INLINE Derived&
+SparseMatrixBase<Derived>::operator/=(const Scalar& other)
+{
+  typedef typename internal::evaluator<Derived>::InnerIterator EvalIterator;
+  internal::evaluator<Derived> thisEval(derived());
+  for (Index j=0; j<outerSize(); ++j)
+    for (EvalIterator i(thisEval,j); i; ++i)
+      i.valueRef() /= other;
+  return derived();
+}
+
+} // end namespace Eigen
+
+#endif // EIGEN_SPARSE_CWISE_UNARY_OP_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseDenseProduct.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseDenseProduct.h
new file mode 100644
index 0000000..f005a18
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseDenseProduct.h
@@ -0,0 +1,342 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2008-2015 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_SPARSEDENSEPRODUCT_H
+#define EIGEN_SPARSEDENSEPRODUCT_H
+
+namespace Eigen { 
+
+namespace internal {
+
+template <> struct product_promote_storage_type<Sparse,Dense, OuterProduct> { typedef Sparse ret; };
+template <> struct product_promote_storage_type<Dense,Sparse, OuterProduct> { typedef Sparse ret; };
+
+template<typename SparseLhsType, typename DenseRhsType, typename DenseResType,
+         typename AlphaType,
+         int LhsStorageOrder = ((SparseLhsType::Flags&RowMajorBit)==RowMajorBit) ? RowMajor : ColMajor,
+         bool ColPerCol = ((DenseRhsType::Flags&RowMajorBit)==0) || DenseRhsType::ColsAtCompileTime==1>
+struct sparse_time_dense_product_impl;
+
+template<typename SparseLhsType, typename DenseRhsType, typename DenseResType>
+struct sparse_time_dense_product_impl<SparseLhsType,DenseRhsType,DenseResType, typename DenseResType::Scalar, RowMajor, true>
+{
+  typedef typename internal::remove_all<SparseLhsType>::type Lhs;
+  typedef typename internal::remove_all<DenseRhsType>::type Rhs;
+  typedef typename internal::remove_all<DenseResType>::type Res;
+  typedef typename evaluator<Lhs>::InnerIterator LhsInnerIterator;
+  typedef evaluator<Lhs> LhsEval;
+  static void run(const SparseLhsType& lhs, const DenseRhsType& rhs, DenseResType& res, const typename Res::Scalar& alpha)
+  {
+    LhsEval lhsEval(lhs);
+    
+    Index n = lhs.outerSize();
+#ifdef EIGEN_HAS_OPENMP
+    Eigen::initParallel();
+    Index threads = Eigen::nbThreads();
+#endif
+    
+    for(Index c=0; c<rhs.cols(); ++c)
+    {
+#ifdef EIGEN_HAS_OPENMP
+      // This 20000 threshold has been found experimentally on 2D and 3D Poisson problems.
+      // It basically represents the minimal amount of work to be done to be worth it.
+      if(threads>1 && lhsEval.nonZerosEstimate() > 20000)
+      {
+        #pragma omp parallel for schedule(dynamic,(n+threads*4-1)/(threads*4)) num_threads(threads)
+        for(Index i=0; i<n; ++i)
+          processRow(lhsEval,rhs,res,alpha,i,c);
+      }
+      else
+#endif
+      {
+        for(Index i=0; i<n; ++i)
+          processRow(lhsEval,rhs,res,alpha,i,c);
+      }
+    }
+  }
+  
+  static void processRow(const LhsEval& lhsEval, const DenseRhsType& rhs, DenseResType& res, const typename Res::Scalar& alpha, Index i, Index col)
+  {
+    typename Res::Scalar tmp(0);
+    for(LhsInnerIterator it(lhsEval,i); it ;++it)
+      tmp += it.value() * rhs.coeff(it.index(),col);
+    res.coeffRef(i,col) += alpha * tmp;
+  }
+  
+};
+
+// FIXME: what is the purpose of the following specialization? Is it for the BlockedSparse format?
+// -> let's disable it for now as it is conflicting with generic scalar*matrix and matrix*scalar operators
+// template<typename T1, typename T2/*, int _Options, typename _StrideType*/>
+// struct ScalarBinaryOpTraits<T1, Ref<T2/*, _Options, _StrideType*/> >
+// {
+//   enum {
+//     Defined = 1
+//   };
+//   typedef typename CwiseUnaryOp<scalar_multiple2_op<T1, typename T2::Scalar>, T2>::PlainObject ReturnType;
+// };
+
+template<typename SparseLhsType, typename DenseRhsType, typename DenseResType, typename AlphaType>
+struct sparse_time_dense_product_impl<SparseLhsType,DenseRhsType,DenseResType, AlphaType, ColMajor, true>
+{
+  typedef typename internal::remove_all<SparseLhsType>::type Lhs;
+  typedef typename internal::remove_all<DenseRhsType>::type Rhs;
+  typedef typename internal::remove_all<DenseResType>::type Res;
+  typedef evaluator<Lhs> LhsEval;
+  typedef typename LhsEval::InnerIterator LhsInnerIterator;
+  static void run(const SparseLhsType& lhs, const DenseRhsType& rhs, DenseResType& res, const AlphaType& alpha)
+  {
+    LhsEval lhsEval(lhs);
+    for(Index c=0; c<rhs.cols(); ++c)
+    {
+      for(Index j=0; j<lhs.outerSize(); ++j)
+      {
+//        typename Res::Scalar rhs_j = alpha * rhs.coeff(j,c);
+        typename ScalarBinaryOpTraits<AlphaType, typename Rhs::Scalar>::ReturnType rhs_j(alpha * rhs.coeff(j,c));
+        for(LhsInnerIterator it(lhsEval,j); it ;++it)
+          res.coeffRef(it.index(),c) += it.value() * rhs_j;
+      }
+    }
+  }
+};
+
+template<typename SparseLhsType, typename DenseRhsType, typename DenseResType>
+struct sparse_time_dense_product_impl<SparseLhsType,DenseRhsType,DenseResType, typename DenseResType::Scalar, RowMajor, false>
+{
+  typedef typename internal::remove_all<SparseLhsType>::type Lhs;
+  typedef typename internal::remove_all<DenseRhsType>::type Rhs;
+  typedef typename internal::remove_all<DenseResType>::type Res;
+  typedef evaluator<Lhs> LhsEval;
+  typedef typename LhsEval::InnerIterator LhsInnerIterator;
+  static void run(const SparseLhsType& lhs, const DenseRhsType& rhs, DenseResType& res, const typename Res::Scalar& alpha)
+  {
+    Index n = lhs.rows();
+    LhsEval lhsEval(lhs);
+
+#ifdef EIGEN_HAS_OPENMP
+    Eigen::initParallel();
+    Index threads = Eigen::nbThreads();
+    // This 20000 threshold has been found experimentally on 2D and 3D Poisson problems.
+    // It basically represents the minimal amount of work to be done to be worth it.
+    if(threads>1 && lhsEval.nonZerosEstimate()*rhs.cols() > 20000)
+    {
+      #pragma omp parallel for schedule(dynamic,(n+threads*4-1)/(threads*4)) num_threads(threads)
+      for(Index i=0; i<n; ++i)
+        processRow(lhsEval,rhs,res,alpha,i);
+    }
+    else
+#endif
+    {
+      for(Index i=0; i<n; ++i)
+        processRow(lhsEval, rhs, res, alpha, i);
+    }
+  }
+
+  static void processRow(const LhsEval& lhsEval, const DenseRhsType& rhs, Res& res, const typename Res::Scalar& alpha, Index i)
+  {
+    typename Res::RowXpr res_i(res.row(i));
+    for(LhsInnerIterator it(lhsEval,i); it ;++it)
+      res_i += (alpha*it.value()) * rhs.row(it.index());
+  }
+};
+
+template<typename SparseLhsType, typename DenseRhsType, typename DenseResType>
+struct sparse_time_dense_product_impl<SparseLhsType,DenseRhsType,DenseResType, typename DenseResType::Scalar, ColMajor, false>
+{
+  typedef typename internal::remove_all<SparseLhsType>::type Lhs;
+  typedef typename internal::remove_all<DenseRhsType>::type Rhs;
+  typedef typename internal::remove_all<DenseResType>::type Res;
+  typedef typename evaluator<Lhs>::InnerIterator LhsInnerIterator;
+  static void run(const SparseLhsType& lhs, const DenseRhsType& rhs, DenseResType& res, const typename Res::Scalar& alpha)
+  {
+    evaluator<Lhs> lhsEval(lhs);
+    for(Index j=0; j<lhs.outerSize(); ++j)
+    {
+      typename Rhs::ConstRowXpr rhs_j(rhs.row(j));
+      for(LhsInnerIterator it(lhsEval,j); it ;++it)
+        res.row(it.index()) += (alpha*it.value()) * rhs_j;
+    }
+  }
+};
+
+template<typename SparseLhsType, typename DenseRhsType, typename DenseResType,typename AlphaType>
+inline void sparse_time_dense_product(const SparseLhsType& lhs, const DenseRhsType& rhs, DenseResType& res, const AlphaType& alpha)
+{
+  sparse_time_dense_product_impl<SparseLhsType,DenseRhsType,DenseResType, AlphaType>::run(lhs, rhs, res, alpha);
+}
+
+} // end namespace internal
+
+namespace internal {
+
+template<typename Lhs, typename Rhs, int ProductType>
+struct generic_product_impl<Lhs, Rhs, SparseShape, DenseShape, ProductType>
+ : generic_product_impl_base<Lhs,Rhs,generic_product_impl<Lhs,Rhs,SparseShape,DenseShape,ProductType> >
+{
+  typedef typename Product<Lhs,Rhs>::Scalar Scalar;
+  
+  template<typename Dest>
+  static void scaleAndAddTo(Dest& dst, const Lhs& lhs, const Rhs& rhs, const Scalar& alpha)
+  {
+    typedef typename nested_eval<Lhs,((Rhs::Flags&RowMajorBit)==0) ? 1 : Rhs::ColsAtCompileTime>::type LhsNested;
+    typedef typename nested_eval<Rhs,((Lhs::Flags&RowMajorBit)==0) ? 1 : Dynamic>::type RhsNested;
+    LhsNested lhsNested(lhs);
+    RhsNested rhsNested(rhs);
+    internal::sparse_time_dense_product(lhsNested, rhsNested, dst, alpha);
+  }
+};
+
+template<typename Lhs, typename Rhs, int ProductType>
+struct generic_product_impl<Lhs, Rhs, SparseTriangularShape, DenseShape, ProductType>
+  : generic_product_impl<Lhs, Rhs, SparseShape, DenseShape, ProductType>
+{};
+
+template<typename Lhs, typename Rhs, int ProductType>
+struct generic_product_impl<Lhs, Rhs, DenseShape, SparseShape, ProductType>
+  : generic_product_impl_base<Lhs,Rhs,generic_product_impl<Lhs,Rhs,DenseShape,SparseShape,ProductType> >
+{
+  typedef typename Product<Lhs,Rhs>::Scalar Scalar;
+  
+  template<typename Dst>
+  static void scaleAndAddTo(Dst& dst, const Lhs& lhs, const Rhs& rhs, const Scalar& alpha)
+  {
+    typedef typename nested_eval<Lhs,((Rhs::Flags&RowMajorBit)==0) ? Dynamic : 1>::type LhsNested;
+    typedef typename nested_eval<Rhs,((Lhs::Flags&RowMajorBit)==RowMajorBit) ? 1 : Lhs::RowsAtCompileTime>::type RhsNested;
+    LhsNested lhsNested(lhs);
+    RhsNested rhsNested(rhs);
+    
+    // transpose everything
+    Transpose<Dst> dstT(dst);
+    internal::sparse_time_dense_product(rhsNested.transpose(), lhsNested.transpose(), dstT, alpha);
+  }
+};
+
+template<typename Lhs, typename Rhs, int ProductType>
+struct generic_product_impl<Lhs, Rhs, DenseShape, SparseTriangularShape, ProductType>
+  : generic_product_impl<Lhs, Rhs, DenseShape, SparseShape, ProductType>
+{};
+
+template<typename LhsT, typename RhsT, bool NeedToTranspose>
+struct sparse_dense_outer_product_evaluator
+{
+protected:
+  typedef typename conditional<NeedToTranspose,RhsT,LhsT>::type Lhs1;
+  typedef typename conditional<NeedToTranspose,LhsT,RhsT>::type ActualRhs;
+  typedef Product<LhsT,RhsT,DefaultProduct> ProdXprType;
+  
+  // if the actual left-hand side is a dense vector,
+  // then build a sparse-view so that we can seamlessly iterate over it.
+  typedef typename conditional<is_same<typename internal::traits<Lhs1>::StorageKind,Sparse>::value,
+            Lhs1, SparseView<Lhs1> >::type ActualLhs;
+  typedef typename conditional<is_same<typename internal::traits<Lhs1>::StorageKind,Sparse>::value,
+            Lhs1 const&, SparseView<Lhs1> >::type LhsArg;
+            
+  typedef evaluator<ActualLhs> LhsEval;
+  typedef evaluator<ActualRhs> RhsEval;
+  typedef typename evaluator<ActualLhs>::InnerIterator LhsIterator;
+  typedef typename ProdXprType::Scalar Scalar;
+  
+public:
+  enum {
+    Flags = NeedToTranspose ? RowMajorBit : 0,
+    CoeffReadCost = HugeCost
+  };
+  
+  class InnerIterator : public LhsIterator
+  {
+  public:
+    InnerIterator(const sparse_dense_outer_product_evaluator &xprEval, Index outer)
+      : LhsIterator(xprEval.m_lhsXprImpl, 0),
+        m_outer(outer),
+        m_empty(false),
+        m_factor(get(xprEval.m_rhsXprImpl, outer, typename internal::traits<ActualRhs>::StorageKind() ))
+    {}
+    
+    EIGEN_STRONG_INLINE Index outer() const { return m_outer; }
+    EIGEN_STRONG_INLINE Index row()   const { return NeedToTranspose ? m_outer : LhsIterator::index(); }
+    EIGEN_STRONG_INLINE Index col()   const { return NeedToTranspose ? LhsIterator::index() : m_outer; }
+
+    EIGEN_STRONG_INLINE Scalar value() const { return LhsIterator::value() * m_factor; }
+    EIGEN_STRONG_INLINE operator bool() const { return LhsIterator::operator bool() && (!m_empty); }
+    
+  protected:
+    Scalar get(const RhsEval &rhs, Index outer, Dense = Dense()) const
+    {
+      return rhs.coeff(outer);
+    }
+    
+    Scalar get(const RhsEval &rhs, Index outer, Sparse = Sparse())
+    {
+      typename RhsEval::InnerIterator it(rhs, outer);
+      if (it && it.index()==0 && it.value()!=Scalar(0))
+        return it.value();
+      m_empty = true;
+      return Scalar(0);
+    }
+    
+    Index m_outer;
+    bool m_empty;
+    Scalar m_factor;
+  };
+  
+  sparse_dense_outer_product_evaluator(const Lhs1 &lhs, const ActualRhs &rhs)
+     : m_lhs(lhs), m_lhsXprImpl(m_lhs), m_rhsXprImpl(rhs)
+  {
+    EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);
+  }
+  
+  // transpose case
+  sparse_dense_outer_product_evaluator(const ActualRhs &rhs, const Lhs1 &lhs)
+     : m_lhs(lhs), m_lhsXprImpl(m_lhs), m_rhsXprImpl(rhs)
+  {
+    EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);
+  }
+    
+protected:
+  const LhsArg m_lhs;
+  evaluator<ActualLhs> m_lhsXprImpl;
+  evaluator<ActualRhs> m_rhsXprImpl;
+};
+
+// sparse * dense outer product
+template<typename Lhs, typename Rhs>
+struct product_evaluator<Product<Lhs, Rhs, DefaultProduct>, OuterProduct, SparseShape, DenseShape>
+  : sparse_dense_outer_product_evaluator<Lhs,Rhs, Lhs::IsRowMajor>
+{
+  typedef sparse_dense_outer_product_evaluator<Lhs,Rhs, Lhs::IsRowMajor> Base;
+  
+  typedef Product<Lhs, Rhs> XprType;
+  typedef typename XprType::PlainObject PlainObject;
+
+  explicit product_evaluator(const XprType& xpr)
+    : Base(xpr.lhs(), xpr.rhs())
+  {}
+  
+};
+
+template<typename Lhs, typename Rhs>
+struct product_evaluator<Product<Lhs, Rhs, DefaultProduct>, OuterProduct, DenseShape, SparseShape>
+  : sparse_dense_outer_product_evaluator<Lhs,Rhs, Rhs::IsRowMajor>
+{
+  typedef sparse_dense_outer_product_evaluator<Lhs,Rhs, Rhs::IsRowMajor> Base;
+  
+  typedef Product<Lhs, Rhs> XprType;
+  typedef typename XprType::PlainObject PlainObject;
+
+  explicit product_evaluator(const XprType& xpr)
+    : Base(xpr.lhs(), xpr.rhs())
+  {}
+  
+};
+
+} // end namespace internal
+
+} // end namespace Eigen
+
+#endif // EIGEN_SPARSEDENSEPRODUCT_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseDiagonalProduct.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseDiagonalProduct.h
new file mode 100644
index 0000000..941c03b
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseDiagonalProduct.h
@@ -0,0 +1,138 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2009-2015 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_SPARSE_DIAGONAL_PRODUCT_H
+#define EIGEN_SPARSE_DIAGONAL_PRODUCT_H
+
+namespace Eigen { 
+
+// The product of a diagonal matrix with a sparse matrix can be easily
+// implemented using expression template.
+// We have two consider very different cases:
+// 1 - diag * row-major sparse
+//     => each inner vector <=> scalar * sparse vector product
+//     => so we can reuse CwiseUnaryOp::InnerIterator
+// 2 - diag * col-major sparse
+//     => each inner vector <=> densevector * sparse vector cwise product
+//     => again, we can reuse specialization of CwiseBinaryOp::InnerIterator
+//        for that particular case
+// The two other cases are symmetric.
+
+namespace internal {
+
+enum {
+  SDP_AsScalarProduct,
+  SDP_AsCwiseProduct
+};
+  
+template<typename SparseXprType, typename DiagonalCoeffType, int SDP_Tag>
+struct sparse_diagonal_product_evaluator;
+
+template<typename Lhs, typename Rhs, int ProductTag>
+struct product_evaluator<Product<Lhs, Rhs, DefaultProduct>, ProductTag, DiagonalShape, SparseShape>
+  : public sparse_diagonal_product_evaluator<Rhs, typename Lhs::DiagonalVectorType, Rhs::Flags&RowMajorBit?SDP_AsScalarProduct:SDP_AsCwiseProduct>
+{
+  typedef Product<Lhs, Rhs, DefaultProduct> XprType;
+  enum { CoeffReadCost = HugeCost, Flags = Rhs::Flags&RowMajorBit, Alignment = 0 }; // FIXME CoeffReadCost & Flags
+  
+  typedef sparse_diagonal_product_evaluator<Rhs, typename Lhs::DiagonalVectorType, Rhs::Flags&RowMajorBit?SDP_AsScalarProduct:SDP_AsCwiseProduct> Base;
+  explicit product_evaluator(const XprType& xpr) : Base(xpr.rhs(), xpr.lhs().diagonal()) {}
+};
+
+template<typename Lhs, typename Rhs, int ProductTag>
+struct product_evaluator<Product<Lhs, Rhs, DefaultProduct>, ProductTag, SparseShape, DiagonalShape>
+  : public sparse_diagonal_product_evaluator<Lhs, Transpose<const typename Rhs::DiagonalVectorType>, Lhs::Flags&RowMajorBit?SDP_AsCwiseProduct:SDP_AsScalarProduct>
+{
+  typedef Product<Lhs, Rhs, DefaultProduct> XprType;
+  enum { CoeffReadCost = HugeCost, Flags = Lhs::Flags&RowMajorBit, Alignment = 0 }; // FIXME CoeffReadCost & Flags
+  
+  typedef sparse_diagonal_product_evaluator<Lhs, Transpose<const typename Rhs::DiagonalVectorType>, Lhs::Flags&RowMajorBit?SDP_AsCwiseProduct:SDP_AsScalarProduct> Base;
+  explicit product_evaluator(const XprType& xpr) : Base(xpr.lhs(), xpr.rhs().diagonal().transpose()) {}
+};
+
+template<typename SparseXprType, typename DiagonalCoeffType>
+struct sparse_diagonal_product_evaluator<SparseXprType, DiagonalCoeffType, SDP_AsScalarProduct>
+{
+protected:
+  typedef typename evaluator<SparseXprType>::InnerIterator SparseXprInnerIterator;
+  typedef typename SparseXprType::Scalar Scalar;
+  
+public:
+  class InnerIterator : public SparseXprInnerIterator
+  {
+  public:
+    InnerIterator(const sparse_diagonal_product_evaluator &xprEval, Index outer)
+      : SparseXprInnerIterator(xprEval.m_sparseXprImpl, outer),
+        m_coeff(xprEval.m_diagCoeffImpl.coeff(outer))
+    {}
+    
+    EIGEN_STRONG_INLINE Scalar value() const { return m_coeff * SparseXprInnerIterator::value(); }
+  protected:
+    typename DiagonalCoeffType::Scalar m_coeff;
+  };
+  
+  sparse_diagonal_product_evaluator(const SparseXprType &sparseXpr, const DiagonalCoeffType &diagCoeff)
+    : m_sparseXprImpl(sparseXpr), m_diagCoeffImpl(diagCoeff)
+  {}
+
+  Index nonZerosEstimate() const { return m_sparseXprImpl.nonZerosEstimate(); }
+    
+protected:
+  evaluator<SparseXprType> m_sparseXprImpl;
+  evaluator<DiagonalCoeffType> m_diagCoeffImpl;
+};
+
+
+template<typename SparseXprType, typename DiagCoeffType>
+struct sparse_diagonal_product_evaluator<SparseXprType, DiagCoeffType, SDP_AsCwiseProduct>
+{
+  typedef typename SparseXprType::Scalar Scalar;
+  typedef typename SparseXprType::StorageIndex StorageIndex;
+  
+  typedef typename nested_eval<DiagCoeffType,SparseXprType::IsRowMajor ? SparseXprType::RowsAtCompileTime
+                                                                       : SparseXprType::ColsAtCompileTime>::type DiagCoeffNested;
+  
+  class InnerIterator
+  {
+    typedef typename evaluator<SparseXprType>::InnerIterator SparseXprIter;
+  public:
+    InnerIterator(const sparse_diagonal_product_evaluator &xprEval, Index outer)
+      : m_sparseIter(xprEval.m_sparseXprEval, outer), m_diagCoeffNested(xprEval.m_diagCoeffNested)
+    {}
+    
+    inline Scalar value() const { return m_sparseIter.value() * m_diagCoeffNested.coeff(index()); }
+    inline StorageIndex index() const  { return m_sparseIter.index(); }
+    inline Index outer() const  { return m_sparseIter.outer(); }
+    inline Index col() const    { return SparseXprType::IsRowMajor ? m_sparseIter.index() : m_sparseIter.outer(); }
+    inline Index row() const    { return SparseXprType::IsRowMajor ? m_sparseIter.outer() : m_sparseIter.index(); }
+    
+    EIGEN_STRONG_INLINE InnerIterator& operator++() { ++m_sparseIter; return *this; }
+    inline operator bool() const  { return m_sparseIter; }
+    
+  protected:
+    SparseXprIter m_sparseIter;
+    DiagCoeffNested m_diagCoeffNested;
+  };
+  
+  sparse_diagonal_product_evaluator(const SparseXprType &sparseXpr, const DiagCoeffType &diagCoeff)
+    : m_sparseXprEval(sparseXpr), m_diagCoeffNested(diagCoeff)
+  {}
+
+  Index nonZerosEstimate() const { return m_sparseXprEval.nonZerosEstimate(); }
+    
+protected:
+  evaluator<SparseXprType> m_sparseXprEval;
+  DiagCoeffNested m_diagCoeffNested;
+};
+
+} // end namespace internal
+
+} // end namespace Eigen
+
+#endif // EIGEN_SPARSE_DIAGONAL_PRODUCT_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseDot.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseDot.h
new file mode 100644
index 0000000..38bc4aa
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseDot.h
@@ -0,0 +1,98 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_SPARSE_DOT_H
+#define EIGEN_SPARSE_DOT_H
+
+namespace Eigen { 
+
+template<typename Derived>
+template<typename OtherDerived>
+typename internal::traits<Derived>::Scalar
+SparseMatrixBase<Derived>::dot(const MatrixBase<OtherDerived>& other) const
+{
+  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)
+  EIGEN_STATIC_ASSERT_VECTOR_ONLY(OtherDerived)
+  EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(Derived,OtherDerived)
+  EIGEN_STATIC_ASSERT((internal::is_same<Scalar, typename OtherDerived::Scalar>::value),
+    YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)
+
+  eigen_assert(size() == other.size());
+  eigen_assert(other.size()>0 && "you are using a non initialized vector");
+
+  internal::evaluator<Derived> thisEval(derived());
+  typename internal::evaluator<Derived>::InnerIterator i(thisEval, 0);
+  Scalar res(0);
+  while (i)
+  {
+    res += numext::conj(i.value()) * other.coeff(i.index());
+    ++i;
+  }
+  return res;
+}
+
+template<typename Derived>
+template<typename OtherDerived>
+typename internal::traits<Derived>::Scalar
+SparseMatrixBase<Derived>::dot(const SparseMatrixBase<OtherDerived>& other) const
+{
+  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)
+  EIGEN_STATIC_ASSERT_VECTOR_ONLY(OtherDerived)
+  EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(Derived,OtherDerived)
+  EIGEN_STATIC_ASSERT((internal::is_same<Scalar, typename OtherDerived::Scalar>::value),
+    YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)
+
+  eigen_assert(size() == other.size());
+
+  internal::evaluator<Derived> thisEval(derived());
+  typename internal::evaluator<Derived>::InnerIterator i(thisEval, 0);
+  
+  internal::evaluator<OtherDerived>  otherEval(other.derived());
+  typename internal::evaluator<OtherDerived>::InnerIterator j(otherEval, 0);
+
+  Scalar res(0);
+  while (i && j)
+  {
+    if (i.index()==j.index())
+    {
+      res += numext::conj(i.value()) * j.value();
+      ++i; ++j;
+    }
+    else if (i.index()<j.index())
+      ++i;
+    else
+      ++j;
+  }
+  return res;
+}
+
+template<typename Derived>
+inline typename NumTraits<typename internal::traits<Derived>::Scalar>::Real
+SparseMatrixBase<Derived>::squaredNorm() const
+{
+  return numext::real((*this).cwiseAbs2().sum());
+}
+
+template<typename Derived>
+inline typename NumTraits<typename internal::traits<Derived>::Scalar>::Real
+SparseMatrixBase<Derived>::norm() const
+{
+  using std::sqrt;
+  return sqrt(squaredNorm());
+}
+
+template<typename Derived>
+inline typename NumTraits<typename internal::traits<Derived>::Scalar>::Real
+SparseMatrixBase<Derived>::blueNorm() const
+{
+  return internal::blueNorm_impl(*this);
+}
+} // end namespace Eigen
+
+#endif // EIGEN_SPARSE_DOT_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseFuzzy.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseFuzzy.h
new file mode 100644
index 0000000..7d47eb9
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseFuzzy.h
@@ -0,0 +1,29 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2008-2014 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_SPARSE_FUZZY_H
+#define EIGEN_SPARSE_FUZZY_H
+
+namespace Eigen {
+  
+template<typename Derived>
+template<typename OtherDerived>
+bool SparseMatrixBase<Derived>::isApprox(const SparseMatrixBase<OtherDerived>& other, const RealScalar &prec) const
+{
+  const typename internal::nested_eval<Derived,2,PlainObject>::type actualA(derived());
+  typename internal::conditional<bool(IsRowMajor)==bool(OtherDerived::IsRowMajor),
+    const typename internal::nested_eval<OtherDerived,2,PlainObject>::type,
+    const PlainObject>::type actualB(other.derived());
+
+  return (actualA - actualB).squaredNorm() <= prec * prec * numext::mini(actualA.squaredNorm(), actualB.squaredNorm());
+}
+
+} // end namespace Eigen
+
+#endif // EIGEN_SPARSE_FUZZY_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseMap.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseMap.h
new file mode 100644
index 0000000..f99be33
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseMap.h
@@ -0,0 +1,305 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2015 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_SPARSE_MAP_H
+#define EIGEN_SPARSE_MAP_H
+
+namespace Eigen {
+
+namespace internal {
+
+template<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>
+struct traits<Map<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> >
+  : public traits<SparseMatrix<MatScalar,MatOptions,MatIndex> >
+{
+  typedef SparseMatrix<MatScalar,MatOptions,MatIndex> PlainObjectType;
+  typedef traits<PlainObjectType> TraitsBase;
+  enum {
+    Flags = TraitsBase::Flags & (~NestByRefBit)
+  };
+};
+
+template<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>
+struct traits<Map<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> >
+  : public traits<SparseMatrix<MatScalar,MatOptions,MatIndex> >
+{
+  typedef SparseMatrix<MatScalar,MatOptions,MatIndex> PlainObjectType;
+  typedef traits<PlainObjectType> TraitsBase;
+  enum {
+    Flags = TraitsBase::Flags & (~ (NestByRefBit | LvalueBit))
+  };
+};
+
+} // end namespace internal
+
+template<typename Derived,
+         int Level = internal::accessors_level<Derived>::has_write_access ? WriteAccessors : ReadOnlyAccessors
+> class SparseMapBase;
+
+/** \ingroup SparseCore_Module
+  * class SparseMapBase
+  * \brief Common base class for Map and Ref instance of sparse matrix and vector.
+  */
+template<typename Derived>
+class SparseMapBase<Derived,ReadOnlyAccessors>
+  : public SparseCompressedBase<Derived>
+{
+  public:
+    typedef SparseCompressedBase<Derived> Base;
+    typedef typename Base::Scalar Scalar;
+    typedef typename Base::StorageIndex StorageIndex;
+    enum { IsRowMajor = Base::IsRowMajor };
+    using Base::operator=;
+  protected:
+    
+    typedef typename internal::conditional<
+                         bool(internal::is_lvalue<Derived>::value),
+                         Scalar *, const Scalar *>::type ScalarPointer;
+    typedef typename internal::conditional<
+                         bool(internal::is_lvalue<Derived>::value),
+                         StorageIndex *, const StorageIndex *>::type IndexPointer;
+
+    Index   m_outerSize;
+    Index   m_innerSize;
+    Array<StorageIndex,2,1>  m_zero_nnz;
+    IndexPointer  m_outerIndex;
+    IndexPointer  m_innerIndices;
+    ScalarPointer m_values;
+    IndexPointer  m_innerNonZeros;
+
+  public:
+
+    /** \copydoc SparseMatrixBase::rows() */
+    inline Index rows() const { return IsRowMajor ? m_outerSize : m_innerSize; }
+    /** \copydoc SparseMatrixBase::cols() */
+    inline Index cols() const { return IsRowMajor ? m_innerSize : m_outerSize; }
+    /** \copydoc SparseMatrixBase::innerSize() */
+    inline Index innerSize() const { return m_innerSize; }
+    /** \copydoc SparseMatrixBase::outerSize() */
+    inline Index outerSize() const { return m_outerSize; }
+    /** \copydoc SparseCompressedBase::nonZeros */
+    inline Index nonZeros() const { return m_zero_nnz[1]; }
+    
+    /** \copydoc SparseCompressedBase::isCompressed */
+    bool isCompressed() const { return m_innerNonZeros==0; }
+
+    //----------------------------------------
+    // direct access interface
+    /** \copydoc SparseMatrix::valuePtr */
+    inline const Scalar* valuePtr() const { return m_values; }
+    /** \copydoc SparseMatrix::innerIndexPtr */
+    inline const StorageIndex* innerIndexPtr() const { return m_innerIndices; }
+    /** \copydoc SparseMatrix::outerIndexPtr */
+    inline const StorageIndex* outerIndexPtr() const { return m_outerIndex; }
+    /** \copydoc SparseMatrix::innerNonZeroPtr */
+    inline const StorageIndex* innerNonZeroPtr() const { return m_innerNonZeros; }
+    //----------------------------------------
+
+    /** \copydoc SparseMatrix::coeff */
+    inline Scalar coeff(Index row, Index col) const
+    {
+      const Index outer = IsRowMajor ? row : col;
+      const Index inner = IsRowMajor ? col : row;
+
+      Index start = m_outerIndex[outer];
+      Index end = isCompressed() ? m_outerIndex[outer+1] : start + m_innerNonZeros[outer];
+      if (start==end)
+        return Scalar(0);
+      else if (end>0 && inner==m_innerIndices[end-1])
+        return m_values[end-1];
+      // ^^  optimization: let's first check if it is the last coefficient
+      // (very common in high level algorithms)
+
+      const StorageIndex* r = std::lower_bound(&m_innerIndices[start],&m_innerIndices[end-1],inner);
+      const Index id = r-&m_innerIndices[0];
+      return ((*r==inner) && (id<end)) ? m_values[id] : Scalar(0);
+    }
+
+    inline SparseMapBase(Index rows, Index cols, Index nnz, IndexPointer outerIndexPtr, IndexPointer innerIndexPtr,
+                              ScalarPointer valuePtr, IndexPointer innerNonZerosPtr = 0)
+      : m_outerSize(IsRowMajor?rows:cols), m_innerSize(IsRowMajor?cols:rows), m_zero_nnz(0,internal::convert_index<StorageIndex>(nnz)), m_outerIndex(outerIndexPtr),
+        m_innerIndices(innerIndexPtr), m_values(valuePtr), m_innerNonZeros(innerNonZerosPtr)
+    {}
+
+    // for vectors
+    inline SparseMapBase(Index size, Index nnz, IndexPointer innerIndexPtr, ScalarPointer valuePtr)
+      : m_outerSize(1), m_innerSize(size), m_zero_nnz(0,internal::convert_index<StorageIndex>(nnz)), m_outerIndex(m_zero_nnz.data()),
+        m_innerIndices(innerIndexPtr), m_values(valuePtr), m_innerNonZeros(0)
+    {}
+
+    /** Empty destructor */
+    inline ~SparseMapBase() {}
+
+  protected:
+    inline SparseMapBase() {}
+};
+
+/** \ingroup SparseCore_Module
+  * class SparseMapBase
+  * \brief Common base class for writable Map and Ref instance of sparse matrix and vector.
+  */
+template<typename Derived>
+class SparseMapBase<Derived,WriteAccessors>
+  : public SparseMapBase<Derived,ReadOnlyAccessors>
+{
+    typedef MapBase<Derived, ReadOnlyAccessors> ReadOnlyMapBase;
+    
+  public:
+    typedef SparseMapBase<Derived, ReadOnlyAccessors> Base;
+    typedef typename Base::Scalar Scalar;
+    typedef typename Base::StorageIndex StorageIndex;
+    enum { IsRowMajor = Base::IsRowMajor };
+    
+    using Base::operator=;
+
+  public:
+    
+    //----------------------------------------
+    // direct access interface
+    using Base::valuePtr;
+    using Base::innerIndexPtr;
+    using Base::outerIndexPtr;
+    using Base::innerNonZeroPtr;
+    /** \copydoc SparseMatrix::valuePtr */
+    inline Scalar* valuePtr()              { return Base::m_values; }
+    /** \copydoc SparseMatrix::innerIndexPtr */
+    inline StorageIndex* innerIndexPtr()   { return Base::m_innerIndices; }
+    /** \copydoc SparseMatrix::outerIndexPtr */
+    inline StorageIndex* outerIndexPtr()   { return Base::m_outerIndex; }
+    /** \copydoc SparseMatrix::innerNonZeroPtr */
+    inline StorageIndex* innerNonZeroPtr() { return Base::m_innerNonZeros; }
+    //----------------------------------------
+
+    /** \copydoc SparseMatrix::coeffRef */
+    inline Scalar& coeffRef(Index row, Index col)
+    {
+      const Index outer = IsRowMajor ? row : col;
+      const Index inner = IsRowMajor ? col : row;
+
+      Index start = Base::m_outerIndex[outer];
+      Index end = Base::isCompressed() ? Base::m_outerIndex[outer+1] : start + Base::m_innerNonZeros[outer];
+      eigen_assert(end>=start && "you probably called coeffRef on a non finalized matrix");
+      eigen_assert(end>start && "coeffRef cannot be called on a zero coefficient");
+      StorageIndex* r = std::lower_bound(&Base::m_innerIndices[start],&Base::m_innerIndices[end],inner);
+      const Index id = r - &Base::m_innerIndices[0];
+      eigen_assert((*r==inner) && (id<end) && "coeffRef cannot be called on a zero coefficient");
+      return const_cast<Scalar*>(Base::m_values)[id];
+    }
+    
+    inline SparseMapBase(Index rows, Index cols, Index nnz, StorageIndex* outerIndexPtr, StorageIndex* innerIndexPtr,
+                         Scalar* valuePtr, StorageIndex* innerNonZerosPtr = 0)
+      : Base(rows, cols, nnz, outerIndexPtr, innerIndexPtr, valuePtr, innerNonZerosPtr)
+    {}
+
+    // for vectors
+    inline SparseMapBase(Index size, Index nnz, StorageIndex* innerIndexPtr, Scalar* valuePtr)
+      : Base(size, nnz, innerIndexPtr, valuePtr)
+    {}
+
+    /** Empty destructor */
+    inline ~SparseMapBase() {}
+
+  protected:
+    inline SparseMapBase() {}
+};
+
+/** \ingroup SparseCore_Module
+  *
+  * \brief Specialization of class Map for SparseMatrix-like storage.
+  *
+  * \tparam SparseMatrixType the equivalent sparse matrix type of the referenced data, it must be a template instance of class SparseMatrix.
+  *
+  * \sa class Map, class SparseMatrix, class Ref<SparseMatrixType,Options>
+  */
+#ifndef EIGEN_PARSED_BY_DOXYGEN
+template<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>
+class Map<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType>
+  : public SparseMapBase<Map<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> >
+#else
+template<typename SparseMatrixType>
+class Map<SparseMatrixType>
+  : public SparseMapBase<Derived,WriteAccessors>
+#endif
+{
+  public:
+    typedef SparseMapBase<Map> Base;
+    EIGEN_SPARSE_PUBLIC_INTERFACE(Map)
+    enum { IsRowMajor = Base::IsRowMajor };
+
+  public:
+
+    /** Constructs a read-write Map to a sparse matrix of size \a rows x \a cols, containing \a nnz non-zero coefficients,
+      * stored as a sparse format as defined by the pointers \a outerIndexPtr, \a innerIndexPtr, and \a valuePtr.
+      * If the optional parameter \a innerNonZerosPtr is the null pointer, then a standard compressed format is assumed.
+      *
+      * This constructor is available only if \c SparseMatrixType is non-const.
+      *
+      * More details on the expected storage schemes are given in the \ref TutorialSparse "manual pages".
+      */
+    inline Map(Index rows, Index cols, Index nnz, StorageIndex* outerIndexPtr,
+               StorageIndex* innerIndexPtr, Scalar* valuePtr, StorageIndex* innerNonZerosPtr = 0)
+      : Base(rows, cols, nnz, outerIndexPtr, innerIndexPtr, valuePtr, innerNonZerosPtr)
+    {}
+#ifndef EIGEN_PARSED_BY_DOXYGEN
+    /** Empty destructor */
+    inline ~Map() {}
+};
+
+template<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>
+class Map<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType>
+  : public SparseMapBase<Map<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> >
+{
+  public:
+    typedef SparseMapBase<Map> Base;
+    EIGEN_SPARSE_PUBLIC_INTERFACE(Map)
+    enum { IsRowMajor = Base::IsRowMajor };
+
+  public:
+#endif
+    /** This is the const version of the above constructor.
+      *
+      * This constructor is available only if \c SparseMatrixType is const, e.g.:
+      * \code Map<const SparseMatrix<double> >  \endcode
+      */
+    inline Map(Index rows, Index cols, Index nnz, const StorageIndex* outerIndexPtr,
+               const StorageIndex* innerIndexPtr, const Scalar* valuePtr, const StorageIndex* innerNonZerosPtr = 0)
+      : Base(rows, cols, nnz, outerIndexPtr, innerIndexPtr, valuePtr, innerNonZerosPtr)
+    {}
+
+    /** Empty destructor */
+    inline ~Map() {}
+};
+
+namespace internal {
+
+template<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>
+struct evaluator<Map<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> >
+  : evaluator<SparseCompressedBase<Map<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> > >
+{
+  typedef evaluator<SparseCompressedBase<Map<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> > > Base;
+  typedef Map<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> XprType;  
+  evaluator() : Base() {}
+  explicit evaluator(const XprType &mat) : Base(mat) {}
+};
+
+template<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>
+struct evaluator<Map<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> >
+  : evaluator<SparseCompressedBase<Map<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> > >
+{
+  typedef evaluator<SparseCompressedBase<Map<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> > > Base;
+  typedef Map<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> XprType;  
+  evaluator() : Base() {}
+  explicit evaluator(const XprType &mat) : Base(mat) {}
+};
+
+}
+
+} // end namespace Eigen
+
+#endif // EIGEN_SPARSE_MAP_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseMatrix.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseMatrix.h
new file mode 100644
index 0000000..616b4a0
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseMatrix.h
@@ -0,0 +1,1518 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2008-2014 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_SPARSEMATRIX_H
+#define EIGEN_SPARSEMATRIX_H
+
+namespace Eigen { 
+
+/** \ingroup SparseCore_Module
+  *
+  * \class SparseMatrix
+  *
+  * \brief A versatible sparse matrix representation
+  *
+  * This class implements a more versatile variants of the common \em compressed row/column storage format.
+  * Each colmun's (resp. row) non zeros are stored as a pair of value with associated row (resp. colmiun) index.
+  * All the non zeros are stored in a single large buffer. Unlike the \em compressed format, there might be extra
+  * space in between the nonzeros of two successive colmuns (resp. rows) such that insertion of new non-zero
+  * can be done with limited memory reallocation and copies.
+  *
+  * A call to the function makeCompressed() turns the matrix into the standard \em compressed format
+  * compatible with many library.
+  *
+  * More details on this storage sceheme are given in the \ref TutorialSparse "manual pages".
+  *
+  * \tparam _Scalar the scalar type, i.e. the type of the coefficients
+  * \tparam _Options Union of bit flags controlling the storage scheme. Currently the only possibility
+  *                 is ColMajor or RowMajor. The default is 0 which means column-major.
+  * \tparam _StorageIndex the type of the indices. It has to be a \b signed type (e.g., short, int, std::ptrdiff_t). Default is \c int.
+  *
+  * \warning In %Eigen 3.2, the undocumented type \c SparseMatrix::Index was improperly defined as the storage index type (e.g., int),
+  *          whereas it is now (starting from %Eigen 3.3) deprecated and always defined as Eigen::Index.
+  *          Codes making use of \c SparseMatrix::Index, might thus likely have to be changed to use \c SparseMatrix::StorageIndex instead.
+  *
+  * This class can be extended with the help of the plugin mechanism described on the page
+  * \ref TopicCustomizing_Plugins by defining the preprocessor symbol \c EIGEN_SPARSEMATRIX_PLUGIN.
+  */
+
+namespace internal {
+template<typename _Scalar, int _Options, typename _StorageIndex>
+struct traits<SparseMatrix<_Scalar, _Options, _StorageIndex> >
+{
+  typedef _Scalar Scalar;
+  typedef _StorageIndex StorageIndex;
+  typedef Sparse StorageKind;
+  typedef MatrixXpr XprKind;
+  enum {
+    RowsAtCompileTime = Dynamic,
+    ColsAtCompileTime = Dynamic,
+    MaxRowsAtCompileTime = Dynamic,
+    MaxColsAtCompileTime = Dynamic,
+    Flags = _Options | NestByRefBit | LvalueBit | CompressedAccessBit,
+    SupportedAccessPatterns = InnerRandomAccessPattern
+  };
+};
+
+template<typename _Scalar, int _Options, typename _StorageIndex, int DiagIndex>
+struct traits<Diagonal<SparseMatrix<_Scalar, _Options, _StorageIndex>, DiagIndex> >
+{
+  typedef SparseMatrix<_Scalar, _Options, _StorageIndex> MatrixType;
+  typedef typename ref_selector<MatrixType>::type MatrixTypeNested;
+  typedef typename remove_reference<MatrixTypeNested>::type _MatrixTypeNested;
+
+  typedef _Scalar Scalar;
+  typedef Dense StorageKind;
+  typedef _StorageIndex StorageIndex;
+  typedef MatrixXpr XprKind;
+
+  enum {
+    RowsAtCompileTime = Dynamic,
+    ColsAtCompileTime = 1,
+    MaxRowsAtCompileTime = Dynamic,
+    MaxColsAtCompileTime = 1,
+    Flags = LvalueBit
+  };
+};
+
+template<typename _Scalar, int _Options, typename _StorageIndex, int DiagIndex>
+struct traits<Diagonal<const SparseMatrix<_Scalar, _Options, _StorageIndex>, DiagIndex> >
+ : public traits<Diagonal<SparseMatrix<_Scalar, _Options, _StorageIndex>, DiagIndex> >
+{
+  enum {
+    Flags = 0
+  };
+};
+
+} // end namespace internal
+
+template<typename _Scalar, int _Options, typename _StorageIndex>
+class SparseMatrix
+  : public SparseCompressedBase<SparseMatrix<_Scalar, _Options, _StorageIndex> >
+{
+    typedef SparseCompressedBase<SparseMatrix> Base;
+    using Base::convert_index;
+    friend class SparseVector<_Scalar,0,_StorageIndex>;
+    template<typename, typename, typename, typename, typename>
+    friend struct internal::Assignment;
+  public:
+    using Base::isCompressed;
+    using Base::nonZeros;
+    EIGEN_SPARSE_PUBLIC_INTERFACE(SparseMatrix)
+    using Base::operator+=;
+    using Base::operator-=;
+
+    typedef MappedSparseMatrix<Scalar,Flags> Map;
+    typedef Diagonal<SparseMatrix> DiagonalReturnType;
+    typedef Diagonal<const SparseMatrix> ConstDiagonalReturnType;
+    typedef typename Base::InnerIterator InnerIterator;
+    typedef typename Base::ReverseInnerIterator ReverseInnerIterator;
+    
+
+    using Base::IsRowMajor;
+    typedef internal::CompressedStorage<Scalar,StorageIndex> Storage;
+    enum {
+      Options = _Options
+    };
+
+    typedef typename Base::IndexVector IndexVector;
+    typedef typename Base::ScalarVector ScalarVector;
+  protected:
+    typedef SparseMatrix<Scalar,(Flags&~RowMajorBit)|(IsRowMajor?RowMajorBit:0)> TransposedSparseMatrix;
+
+    Index m_outerSize;
+    Index m_innerSize;
+    StorageIndex* m_outerIndex;
+    StorageIndex* m_innerNonZeros;     // optional, if null then the data is compressed
+    Storage m_data;
+
+  public:
+    
+    /** \returns the number of rows of the matrix */
+    inline Index rows() const { return IsRowMajor ? m_outerSize : m_innerSize; }
+    /** \returns the number of columns of the matrix */
+    inline Index cols() const { return IsRowMajor ? m_innerSize : m_outerSize; }
+
+    /** \returns the number of rows (resp. columns) of the matrix if the storage order column major (resp. row major) */
+    inline Index innerSize() const { return m_innerSize; }
+    /** \returns the number of columns (resp. rows) of the matrix if the storage order column major (resp. row major) */
+    inline Index outerSize() const { return m_outerSize; }
+    
+    /** \returns a const pointer to the array of values.
+      * This function is aimed at interoperability with other libraries.
+      * \sa innerIndexPtr(), outerIndexPtr() */
+    inline const Scalar* valuePtr() const { return m_data.valuePtr(); }
+    /** \returns a non-const pointer to the array of values.
+      * This function is aimed at interoperability with other libraries.
+      * \sa innerIndexPtr(), outerIndexPtr() */
+    inline Scalar* valuePtr() { return m_data.valuePtr(); }
+
+    /** \returns a const pointer to the array of inner indices.
+      * This function is aimed at interoperability with other libraries.
+      * \sa valuePtr(), outerIndexPtr() */
+    inline const StorageIndex* innerIndexPtr() const { return m_data.indexPtr(); }
+    /** \returns a non-const pointer to the array of inner indices.
+      * This function is aimed at interoperability with other libraries.
+      * \sa valuePtr(), outerIndexPtr() */
+    inline StorageIndex* innerIndexPtr() { return m_data.indexPtr(); }
+
+    /** \returns a const pointer to the array of the starting positions of the inner vectors.
+      * This function is aimed at interoperability with other libraries.
+      * \sa valuePtr(), innerIndexPtr() */
+    inline const StorageIndex* outerIndexPtr() const { return m_outerIndex; }
+    /** \returns a non-const pointer to the array of the starting positions of the inner vectors.
+      * This function is aimed at interoperability with other libraries.
+      * \sa valuePtr(), innerIndexPtr() */
+    inline StorageIndex* outerIndexPtr() { return m_outerIndex; }
+
+    /** \returns a const pointer to the array of the number of non zeros of the inner vectors.
+      * This function is aimed at interoperability with other libraries.
+      * \warning it returns the null pointer 0 in compressed mode */
+    inline const StorageIndex* innerNonZeroPtr() const { return m_innerNonZeros; }
+    /** \returns a non-const pointer to the array of the number of non zeros of the inner vectors.
+      * This function is aimed at interoperability with other libraries.
+      * \warning it returns the null pointer 0 in compressed mode */
+    inline StorageIndex* innerNonZeroPtr() { return m_innerNonZeros; }
+
+    /** \internal */
+    inline Storage& data() { return m_data; }
+    /** \internal */
+    inline const Storage& data() const { return m_data; }
+
+    /** \returns the value of the matrix at position \a i, \a j
+      * This function returns Scalar(0) if the element is an explicit \em zero */
+    inline Scalar coeff(Index row, Index col) const
+    {
+      eigen_assert(row>=0 && row<rows() && col>=0 && col<cols());
+      
+      const Index outer = IsRowMajor ? row : col;
+      const Index inner = IsRowMajor ? col : row;
+      Index end = m_innerNonZeros ? m_outerIndex[outer] + m_innerNonZeros[outer] : m_outerIndex[outer+1];
+      return m_data.atInRange(m_outerIndex[outer], end, StorageIndex(inner));
+    }
+
+    /** \returns a non-const reference to the value of the matrix at position \a i, \a j
+      *
+      * If the element does not exist then it is inserted via the insert(Index,Index) function
+      * which itself turns the matrix into a non compressed form if that was not the case.
+      *
+      * This is a O(log(nnz_j)) operation (binary search) plus the cost of insert(Index,Index)
+      * function if the element does not already exist.
+      */
+    inline Scalar& coeffRef(Index row, Index col)
+    {
+      eigen_assert(row>=0 && row<rows() && col>=0 && col<cols());
+      
+      const Index outer = IsRowMajor ? row : col;
+      const Index inner = IsRowMajor ? col : row;
+
+      Index start = m_outerIndex[outer];
+      Index end = m_innerNonZeros ? m_outerIndex[outer] + m_innerNonZeros[outer] : m_outerIndex[outer+1];
+      eigen_assert(end>=start && "you probably called coeffRef on a non finalized matrix");
+      if(end<=start)
+        return insert(row,col);
+      const Index p = m_data.searchLowerIndex(start,end-1,StorageIndex(inner));
+      if((p<end) && (m_data.index(p)==inner))
+        return m_data.value(p);
+      else
+        return insert(row,col);
+    }
+
+    /** \returns a reference to a novel non zero coefficient with coordinates \a row x \a col.
+      * The non zero coefficient must \b not already exist.
+      *
+      * If the matrix \c *this is in compressed mode, then \c *this is turned into uncompressed
+      * mode while reserving room for 2 x this->innerSize() non zeros if reserve(Index) has not been called earlier.
+      * In this case, the insertion procedure is optimized for a \e sequential insertion mode where elements are assumed to be
+      * inserted by increasing outer-indices.
+      * 
+      * If that's not the case, then it is strongly recommended to either use a triplet-list to assemble the matrix, or to first
+      * call reserve(const SizesType &) to reserve the appropriate number of non-zero elements per inner vector.
+      *
+      * Assuming memory has been appropriately reserved, this function performs a sorted insertion in O(1)
+      * if the elements of each inner vector are inserted in increasing inner index order, and in O(nnz_j) for a random insertion.
+      *
+      */
+    Scalar& insert(Index row, Index col);
+
+  public:
+
+    /** Removes all non zeros but keep allocated memory
+      *
+      * This function does not free the currently allocated memory. To release as much as memory as possible,
+      * call \code mat.data().squeeze(); \endcode after resizing it.
+      * 
+      * \sa resize(Index,Index), data()
+      */
+    inline void setZero()
+    {
+      m_data.clear();
+      memset(m_outerIndex, 0, (m_outerSize+1)*sizeof(StorageIndex));
+      if(m_innerNonZeros)
+        memset(m_innerNonZeros, 0, (m_outerSize)*sizeof(StorageIndex));
+    }
+
+    /** Preallocates \a reserveSize non zeros.
+      *
+      * Precondition: the matrix must be in compressed mode. */
+    inline void reserve(Index reserveSize)
+    {
+      eigen_assert(isCompressed() && "This function does not make sense in non compressed mode.");
+      m_data.reserve(reserveSize);
+    }
+    
+    #ifdef EIGEN_PARSED_BY_DOXYGEN
+    /** Preallocates \a reserveSize[\c j] non zeros for each column (resp. row) \c j.
+      *
+      * This function turns the matrix in non-compressed mode.
+      * 
+      * The type \c SizesType must expose the following interface:
+        \code
+        typedef value_type;
+        const value_type& operator[](i) const;
+        \endcode
+      * for \c i in the [0,this->outerSize()[ range.
+      * Typical choices include std::vector<int>, Eigen::VectorXi, Eigen::VectorXi::Constant, etc.
+      */
+    template<class SizesType>
+    inline void reserve(const SizesType& reserveSizes);
+    #else
+    template<class SizesType>
+    inline void reserve(const SizesType& reserveSizes, const typename SizesType::value_type& enableif =
+    #if (!EIGEN_COMP_MSVC) || (EIGEN_COMP_MSVC>=1500) // MSVC 2005 fails to compile with this typename
+        typename
+    #endif
+        SizesType::value_type())
+    {
+      EIGEN_UNUSED_VARIABLE(enableif);
+      reserveInnerVectors(reserveSizes);
+    }
+    #endif // EIGEN_PARSED_BY_DOXYGEN
+  protected:
+    template<class SizesType>
+    inline void reserveInnerVectors(const SizesType& reserveSizes)
+    {
+      if(isCompressed())
+      {
+        Index totalReserveSize = 0;
+        // turn the matrix into non-compressed mode
+        m_innerNonZeros = static_cast<StorageIndex*>(std::malloc(m_outerSize * sizeof(StorageIndex)));
+        if (!m_innerNonZeros) internal::throw_std_bad_alloc();
+        
+        // temporarily use m_innerSizes to hold the new starting points.
+        StorageIndex* newOuterIndex = m_innerNonZeros;
+        
+        StorageIndex count = 0;
+        for(Index j=0; j<m_outerSize; ++j)
+        {
+          newOuterIndex[j] = count;
+          count += reserveSizes[j] + (m_outerIndex[j+1]-m_outerIndex[j]);
+          totalReserveSize += reserveSizes[j];
+        }
+        m_data.reserve(totalReserveSize);
+        StorageIndex previousOuterIndex = m_outerIndex[m_outerSize];
+        for(Index j=m_outerSize-1; j>=0; --j)
+        {
+          StorageIndex innerNNZ = previousOuterIndex - m_outerIndex[j];
+          for(Index i=innerNNZ-1; i>=0; --i)
+          {
+            m_data.index(newOuterIndex[j]+i) = m_data.index(m_outerIndex[j]+i);
+            m_data.value(newOuterIndex[j]+i) = m_data.value(m_outerIndex[j]+i);
+          }
+          previousOuterIndex = m_outerIndex[j];
+          m_outerIndex[j] = newOuterIndex[j];
+          m_innerNonZeros[j] = innerNNZ;
+        }
+        if(m_outerSize>0)
+          m_outerIndex[m_outerSize] = m_outerIndex[m_outerSize-1] + m_innerNonZeros[m_outerSize-1] + reserveSizes[m_outerSize-1];
+        
+        m_data.resize(m_outerIndex[m_outerSize]);
+      }
+      else
+      {
+        StorageIndex* newOuterIndex = static_cast<StorageIndex*>(std::malloc((m_outerSize+1)*sizeof(StorageIndex)));
+        if (!newOuterIndex) internal::throw_std_bad_alloc();
+        
+        StorageIndex count = 0;
+        for(Index j=0; j<m_outerSize; ++j)
+        {
+          newOuterIndex[j] = count;
+          StorageIndex alreadyReserved = (m_outerIndex[j+1]-m_outerIndex[j]) - m_innerNonZeros[j];
+          StorageIndex toReserve = std::max<StorageIndex>(reserveSizes[j], alreadyReserved);
+          count += toReserve + m_innerNonZeros[j];
+        }
+        newOuterIndex[m_outerSize] = count;
+        
+        m_data.resize(count);
+        for(Index j=m_outerSize-1; j>=0; --j)
+        {
+          Index offset = newOuterIndex[j] - m_outerIndex[j];
+          if(offset>0)
+          {
+            StorageIndex innerNNZ = m_innerNonZeros[j];
+            for(Index i=innerNNZ-1; i>=0; --i)
+            {
+              m_data.index(newOuterIndex[j]+i) = m_data.index(m_outerIndex[j]+i);
+              m_data.value(newOuterIndex[j]+i) = m_data.value(m_outerIndex[j]+i);
+            }
+          }
+        }
+        
+        std::swap(m_outerIndex, newOuterIndex);
+        std::free(newOuterIndex);
+      }
+      
+    }
+  public:
+
+    //--- low level purely coherent filling ---
+
+    /** \internal
+      * \returns a reference to the non zero coefficient at position \a row, \a col assuming that:
+      * - the nonzero does not already exist
+      * - the new coefficient is the last one according to the storage order
+      *
+      * Before filling a given inner vector you must call the statVec(Index) function.
+      *
+      * After an insertion session, you should call the finalize() function.
+      *
+      * \sa insert, insertBackByOuterInner, startVec */
+    inline Scalar& insertBack(Index row, Index col)
+    {
+      return insertBackByOuterInner(IsRowMajor?row:col, IsRowMajor?col:row);
+    }
+
+    /** \internal
+      * \sa insertBack, startVec */
+    inline Scalar& insertBackByOuterInner(Index outer, Index inner)
+    {
+      eigen_assert(Index(m_outerIndex[outer+1]) == m_data.size() && "Invalid ordered insertion (invalid outer index)");
+      eigen_assert( (m_outerIndex[outer+1]-m_outerIndex[outer]==0 || m_data.index(m_data.size()-1)<inner) && "Invalid ordered insertion (invalid inner index)");
+      Index p = m_outerIndex[outer+1];
+      ++m_outerIndex[outer+1];
+      m_data.append(Scalar(0), inner);
+      return m_data.value(p);
+    }
+
+    /** \internal
+      * \warning use it only if you know what you are doing */
+    inline Scalar& insertBackByOuterInnerUnordered(Index outer, Index inner)
+    {
+      Index p = m_outerIndex[outer+1];
+      ++m_outerIndex[outer+1];
+      m_data.append(Scalar(0), inner);
+      return m_data.value(p);
+    }
+
+    /** \internal
+      * \sa insertBack, insertBackByOuterInner */
+    inline void startVec(Index outer)
+    {
+      eigen_assert(m_outerIndex[outer]==Index(m_data.size()) && "You must call startVec for each inner vector sequentially");
+      eigen_assert(m_outerIndex[outer+1]==0 && "You must call startVec for each inner vector sequentially");
+      m_outerIndex[outer+1] = m_outerIndex[outer];
+    }
+
+    /** \internal
+      * Must be called after inserting a set of non zero entries using the low level compressed API.
+      */
+    inline void finalize()
+    {
+      if(isCompressed())
+      {
+        StorageIndex size = internal::convert_index<StorageIndex>(m_data.size());
+        Index i = m_outerSize;
+        // find the last filled column
+        while (i>=0 && m_outerIndex[i]==0)
+          --i;
+        ++i;
+        while (i<=m_outerSize)
+        {
+          m_outerIndex[i] = size;
+          ++i;
+        }
+      }
+    }
+
+    //---
+
+    template<typename InputIterators>
+    void setFromTriplets(const InputIterators& begin, const InputIterators& end);
+
+    template<typename InputIterators,typename DupFunctor>
+    void setFromTriplets(const InputIterators& begin, const InputIterators& end, DupFunctor dup_func);
+
+    void sumupDuplicates() { collapseDuplicates(internal::scalar_sum_op<Scalar,Scalar>()); }
+
+    template<typename DupFunctor>
+    void collapseDuplicates(DupFunctor dup_func = DupFunctor());
+
+    //---
+    
+    /** \internal
+      * same as insert(Index,Index) except that the indices are given relative to the storage order */
+    Scalar& insertByOuterInner(Index j, Index i)
+    {
+      return insert(IsRowMajor ? j : i, IsRowMajor ? i : j);
+    }
+
+    /** Turns the matrix into the \em compressed format.
+      */
+    void makeCompressed()
+    {
+      if(isCompressed())
+        return;
+      
+      eigen_internal_assert(m_outerIndex!=0 && m_outerSize>0);
+      
+      Index oldStart = m_outerIndex[1];
+      m_outerIndex[1] = m_innerNonZeros[0];
+      for(Index j=1; j<m_outerSize; ++j)
+      {
+        Index nextOldStart = m_outerIndex[j+1];
+        Index offset = oldStart - m_outerIndex[j];
+        if(offset>0)
+        {
+          for(Index k=0; k<m_innerNonZeros[j]; ++k)
+          {
+            m_data.index(m_outerIndex[j]+k) = m_data.index(oldStart+k);
+            m_data.value(m_outerIndex[j]+k) = m_data.value(oldStart+k);
+          }
+        }
+        m_outerIndex[j+1] = m_outerIndex[j] + m_innerNonZeros[j];
+        oldStart = nextOldStart;
+      }
+      std::free(m_innerNonZeros);
+      m_innerNonZeros = 0;
+      m_data.resize(m_outerIndex[m_outerSize]);
+      m_data.squeeze();
+    }
+
+    /** Turns the matrix into the uncompressed mode */
+    void uncompress()
+    {
+      if(m_innerNonZeros != 0)
+        return; 
+      m_innerNonZeros = static_cast<StorageIndex*>(std::malloc(m_outerSize * sizeof(StorageIndex)));
+      for (Index i = 0; i < m_outerSize; i++)
+      {
+        m_innerNonZeros[i] = m_outerIndex[i+1] - m_outerIndex[i]; 
+      }
+    }
+
+    /** Suppresses all nonzeros which are \b much \b smaller \b than \a reference under the tolerance \a epsilon */
+    void prune(const Scalar& reference, const RealScalar& epsilon = NumTraits<RealScalar>::dummy_precision())
+    {
+      prune(default_prunning_func(reference,epsilon));
+    }
+    
+    /** Turns the matrix into compressed format, and suppresses all nonzeros which do not satisfy the predicate \a keep.
+      * The functor type \a KeepFunc must implement the following function:
+      * \code
+      * bool operator() (const Index& row, const Index& col, const Scalar& value) const;
+      * \endcode
+      * \sa prune(Scalar,RealScalar)
+      */
+    template<typename KeepFunc>
+    void prune(const KeepFunc& keep = KeepFunc())
+    {
+      // TODO optimize the uncompressed mode to avoid moving and allocating the data twice
+      makeCompressed();
+
+      StorageIndex k = 0;
+      for(Index j=0; j<m_outerSize; ++j)
+      {
+        Index previousStart = m_outerIndex[j];
+        m_outerIndex[j] = k;
+        Index end = m_outerIndex[j+1];
+        for(Index i=previousStart; i<end; ++i)
+        {
+          if(keep(IsRowMajor?j:m_data.index(i), IsRowMajor?m_data.index(i):j, m_data.value(i)))
+          {
+            m_data.value(k) = m_data.value(i);
+            m_data.index(k) = m_data.index(i);
+            ++k;
+          }
+        }
+      }
+      m_outerIndex[m_outerSize] = k;
+      m_data.resize(k,0);
+    }
+
+    /** Resizes the matrix to a \a rows x \a cols matrix leaving old values untouched.
+      *
+      * If the sizes of the matrix are decreased, then the matrix is turned to \b uncompressed-mode
+      * and the storage of the out of bounds coefficients is kept and reserved.
+      * Call makeCompressed() to pack the entries and squeeze extra memory.
+      *
+      * \sa reserve(), setZero(), makeCompressed()
+      */
+    void conservativeResize(Index rows, Index cols) 
+    {
+      // No change
+      if (this->rows() == rows && this->cols() == cols) return;
+      
+      // If one dimension is null, then there is nothing to be preserved
+      if(rows==0 || cols==0) return resize(rows,cols);
+
+      Index innerChange = IsRowMajor ? cols - this->cols() : rows - this->rows();
+      Index outerChange = IsRowMajor ? rows - this->rows() : cols - this->cols();
+      StorageIndex newInnerSize = convert_index(IsRowMajor ? cols : rows);
+
+      // Deals with inner non zeros
+      if (m_innerNonZeros)
+      {
+        // Resize m_innerNonZeros
+        StorageIndex *newInnerNonZeros = static_cast<StorageIndex*>(std::realloc(m_innerNonZeros, (m_outerSize + outerChange) * sizeof(StorageIndex)));
+        if (!newInnerNonZeros) internal::throw_std_bad_alloc();
+        m_innerNonZeros = newInnerNonZeros;
+        
+        for(Index i=m_outerSize; i<m_outerSize+outerChange; i++)          
+          m_innerNonZeros[i] = 0;
+      } 
+      else if (innerChange < 0) 
+      {
+        // Inner size decreased: allocate a new m_innerNonZeros
+        m_innerNonZeros = static_cast<StorageIndex*>(std::malloc((m_outerSize + outerChange) * sizeof(StorageIndex)));
+        if (!m_innerNonZeros) internal::throw_std_bad_alloc();
+        for(Index i = 0; i < m_outerSize + (std::min)(outerChange, Index(0)); i++)
+          m_innerNonZeros[i] = m_outerIndex[i+1] - m_outerIndex[i];
+        for(Index i = m_outerSize; i < m_outerSize + outerChange; i++)
+          m_innerNonZeros[i] = 0;
+      }
+      
+      // Change the m_innerNonZeros in case of a decrease of inner size
+      if (m_innerNonZeros && innerChange < 0)
+      {
+        for(Index i = 0; i < m_outerSize + (std::min)(outerChange, Index(0)); i++)
+        {
+          StorageIndex &n = m_innerNonZeros[i];
+          StorageIndex start = m_outerIndex[i];
+          while (n > 0 && m_data.index(start+n-1) >= newInnerSize) --n; 
+        }
+      }
+      
+      m_innerSize = newInnerSize;
+
+      // Re-allocate outer index structure if necessary
+      if (outerChange == 0)
+        return;
+          
+      StorageIndex *newOuterIndex = static_cast<StorageIndex*>(std::realloc(m_outerIndex, (m_outerSize + outerChange + 1) * sizeof(StorageIndex)));
+      if (!newOuterIndex) internal::throw_std_bad_alloc();
+      m_outerIndex = newOuterIndex;
+      if (outerChange > 0)
+      {
+        StorageIndex lastIdx = m_outerSize == 0 ? 0 : m_outerIndex[m_outerSize];
+        for(Index i=m_outerSize; i<m_outerSize+outerChange+1; i++)          
+          m_outerIndex[i] = lastIdx; 
+      }
+      m_outerSize += outerChange;
+    }
+    
+    /** Resizes the matrix to a \a rows x \a cols matrix and initializes it to zero.
+      * 
+      * This function does not free the currently allocated memory. To release as much as memory as possible,
+      * call \code mat.data().squeeze(); \endcode after resizing it.
+      * 
+      * \sa reserve(), setZero()
+      */
+    void resize(Index rows, Index cols)
+    {
+      const Index outerSize = IsRowMajor ? rows : cols;
+      m_innerSize = IsRowMajor ? cols : rows;
+      m_data.clear();
+      if (m_outerSize != outerSize || m_outerSize==0)
+      {
+        std::free(m_outerIndex);
+        m_outerIndex = static_cast<StorageIndex*>(std::malloc((outerSize + 1) * sizeof(StorageIndex)));
+        if (!m_outerIndex) internal::throw_std_bad_alloc();
+        
+        m_outerSize = outerSize;
+      }
+      if(m_innerNonZeros)
+      {
+        std::free(m_innerNonZeros);
+        m_innerNonZeros = 0;
+      }
+      memset(m_outerIndex, 0, (m_outerSize+1)*sizeof(StorageIndex));
+    }
+
+    /** \internal
+      * Resize the nonzero vector to \a size */
+    void resizeNonZeros(Index size)
+    {
+      m_data.resize(size);
+    }
+
+    /** \returns a const expression of the diagonal coefficients. */
+    const ConstDiagonalReturnType diagonal() const { return ConstDiagonalReturnType(*this); }
+    
+    /** \returns a read-write expression of the diagonal coefficients.
+      * \warning If the diagonal entries are written, then all diagonal
+      * entries \b must already exist, otherwise an assertion will be raised.
+      */
+    DiagonalReturnType diagonal() { return DiagonalReturnType(*this); }
+
+    /** Default constructor yielding an empty \c 0 \c x \c 0 matrix */
+    inline SparseMatrix()
+      : m_outerSize(-1), m_innerSize(0), m_outerIndex(0), m_innerNonZeros(0)
+    {
+      check_template_parameters();
+      resize(0, 0);
+    }
+
+    /** Constructs a \a rows \c x \a cols empty matrix */
+    inline SparseMatrix(Index rows, Index cols)
+      : m_outerSize(0), m_innerSize(0), m_outerIndex(0), m_innerNonZeros(0)
+    {
+      check_template_parameters();
+      resize(rows, cols);
+    }
+
+    /** Constructs a sparse matrix from the sparse expression \a other */
+    template<typename OtherDerived>
+    inline SparseMatrix(const SparseMatrixBase<OtherDerived>& other)
+      : m_outerSize(0), m_innerSize(0), m_outerIndex(0), m_innerNonZeros(0)
+    {
+      EIGEN_STATIC_ASSERT((internal::is_same<Scalar, typename OtherDerived::Scalar>::value),
+        YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)
+      check_template_parameters();
+      const bool needToTranspose = (Flags & RowMajorBit) != (internal::evaluator<OtherDerived>::Flags & RowMajorBit);
+      if (needToTranspose)
+        *this = other.derived();
+      else
+      {
+        #ifdef EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN
+          EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN
+        #endif
+        internal::call_assignment_no_alias(*this, other.derived());
+      }
+    }
+    
+    /** Constructs a sparse matrix from the sparse selfadjoint view \a other */
+    template<typename OtherDerived, unsigned int UpLo>
+    inline SparseMatrix(const SparseSelfAdjointView<OtherDerived, UpLo>& other)
+      : m_outerSize(0), m_innerSize(0), m_outerIndex(0), m_innerNonZeros(0)
+    {
+      check_template_parameters();
+      Base::operator=(other);
+    }
+
+    /** Copy constructor (it performs a deep copy) */
+    inline SparseMatrix(const SparseMatrix& other)
+      : Base(), m_outerSize(0), m_innerSize(0), m_outerIndex(0), m_innerNonZeros(0)
+    {
+      check_template_parameters();
+      *this = other.derived();
+    }
+
+    /** \brief Copy constructor with in-place evaluation */
+    template<typename OtherDerived>
+    SparseMatrix(const ReturnByValue<OtherDerived>& other)
+      : Base(), m_outerSize(0), m_innerSize(0), m_outerIndex(0), m_innerNonZeros(0)
+    {
+      check_template_parameters();
+      initAssignment(other);
+      other.evalTo(*this);
+    }
+    
+    /** \brief Copy constructor with in-place evaluation */
+    template<typename OtherDerived>
+    explicit SparseMatrix(const DiagonalBase<OtherDerived>& other)
+      : Base(), m_outerSize(0), m_innerSize(0), m_outerIndex(0), m_innerNonZeros(0)
+    {
+      check_template_parameters();
+      *this = other.derived();
+    }
+
+    /** Swaps the content of two sparse matrices of the same type.
+      * This is a fast operation that simply swaps the underlying pointers and parameters. */
+    inline void swap(SparseMatrix& other)
+    {
+      //EIGEN_DBG_SPARSE(std::cout << "SparseMatrix:: swap\n");
+      std::swap(m_outerIndex, other.m_outerIndex);
+      std::swap(m_innerSize, other.m_innerSize);
+      std::swap(m_outerSize, other.m_outerSize);
+      std::swap(m_innerNonZeros, other.m_innerNonZeros);
+      m_data.swap(other.m_data);
+    }
+
+    /** Sets *this to the identity matrix.
+      * This function also turns the matrix into compressed mode, and drop any reserved memory. */
+    inline void setIdentity()
+    {
+      eigen_assert(rows() == cols() && "ONLY FOR SQUARED MATRICES");
+      this->m_data.resize(rows());
+      Eigen::Map<IndexVector>(this->m_data.indexPtr(), rows()).setLinSpaced(0, StorageIndex(rows()-1));
+      Eigen::Map<ScalarVector>(this->m_data.valuePtr(), rows()).setOnes();
+      Eigen::Map<IndexVector>(this->m_outerIndex, rows()+1).setLinSpaced(0, StorageIndex(rows()));
+      std::free(m_innerNonZeros);
+      m_innerNonZeros = 0;
+    }
+    inline SparseMatrix& operator=(const SparseMatrix& other)
+    {
+      if (other.isRValue())
+      {
+        swap(other.const_cast_derived());
+      }
+      else if(this!=&other)
+      {
+        #ifdef EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN
+          EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN
+        #endif
+        initAssignment(other);
+        if(other.isCompressed())
+        {
+          internal::smart_copy(other.m_outerIndex, other.m_outerIndex + m_outerSize + 1, m_outerIndex);
+          m_data = other.m_data;
+        }
+        else
+        {
+          Base::operator=(other);
+        }
+      }
+      return *this;
+    }
+
+#ifndef EIGEN_PARSED_BY_DOXYGEN
+    template<typename OtherDerived>
+    inline SparseMatrix& operator=(const EigenBase<OtherDerived>& other)
+    { return Base::operator=(other.derived()); }
+
+    template<typename Lhs, typename Rhs>
+    inline SparseMatrix& operator=(const Product<Lhs,Rhs,AliasFreeProduct>& other);
+#endif // EIGEN_PARSED_BY_DOXYGEN
+
+    template<typename OtherDerived>
+    EIGEN_DONT_INLINE SparseMatrix& operator=(const SparseMatrixBase<OtherDerived>& other);
+
+    friend std::ostream & operator << (std::ostream & s, const SparseMatrix& m)
+    {
+      EIGEN_DBG_SPARSE(
+        s << "Nonzero entries:\n";
+        if(m.isCompressed())
+        {
+          for (Index i=0; i<m.nonZeros(); ++i)
+            s << "(" << m.m_data.value(i) << "," << m.m_data.index(i) << ") ";
+        }
+        else
+        {
+          for (Index i=0; i<m.outerSize(); ++i)
+          {
+            Index p = m.m_outerIndex[i];
+            Index pe = m.m_outerIndex[i]+m.m_innerNonZeros[i];
+            Index k=p;
+            for (; k<pe; ++k) {
+              s << "(" << m.m_data.value(k) << "," << m.m_data.index(k) << ") ";
+            }
+            for (; k<m.m_outerIndex[i+1]; ++k) {
+              s << "(_,_) ";
+            }
+          }
+        }
+        s << std::endl;
+        s << std::endl;
+        s << "Outer pointers:\n";
+        for (Index i=0; i<m.outerSize(); ++i) {
+          s << m.m_outerIndex[i] << " ";
+        }
+        s << " $" << std::endl;
+        if(!m.isCompressed())
+        {
+          s << "Inner non zeros:\n";
+          for (Index i=0; i<m.outerSize(); ++i) {
+            s << m.m_innerNonZeros[i] << " ";
+          }
+          s << " $" << std::endl;
+        }
+        s << std::endl;
+      );
+      s << static_cast<const SparseMatrixBase<SparseMatrix>&>(m);
+      return s;
+    }
+
+    /** Destructor */
+    inline ~SparseMatrix()
+    {
+      std::free(m_outerIndex);
+      std::free(m_innerNonZeros);
+    }
+
+    /** Overloaded for performance */
+    Scalar sum() const;
+    
+#   ifdef EIGEN_SPARSEMATRIX_PLUGIN
+#     include EIGEN_SPARSEMATRIX_PLUGIN
+#   endif
+
+protected:
+
+    template<typename Other>
+    void initAssignment(const Other& other)
+    {
+      resize(other.rows(), other.cols());
+      if(m_innerNonZeros)
+      {
+        std::free(m_innerNonZeros);
+        m_innerNonZeros = 0;
+      }
+    }
+
+    /** \internal
+      * \sa insert(Index,Index) */
+    EIGEN_DONT_INLINE Scalar& insertCompressed(Index row, Index col);
+
+    /** \internal
+      * A vector object that is equal to 0 everywhere but v at the position i */
+    class SingletonVector
+    {
+        StorageIndex m_index;
+        StorageIndex m_value;
+      public:
+        typedef StorageIndex value_type;
+        SingletonVector(Index i, Index v)
+          : m_index(convert_index(i)), m_value(convert_index(v))
+        {}
+
+        StorageIndex operator[](Index i) const { return i==m_index ? m_value : 0; }
+    };
+
+    /** \internal
+      * \sa insert(Index,Index) */
+    EIGEN_DONT_INLINE Scalar& insertUncompressed(Index row, Index col);
+
+public:
+    /** \internal
+      * \sa insert(Index,Index) */
+    EIGEN_STRONG_INLINE Scalar& insertBackUncompressed(Index row, Index col)
+    {
+      const Index outer = IsRowMajor ? row : col;
+      const Index inner = IsRowMajor ? col : row;
+
+      eigen_assert(!isCompressed());
+      eigen_assert(m_innerNonZeros[outer]<=(m_outerIndex[outer+1] - m_outerIndex[outer]));
+
+      Index p = m_outerIndex[outer] + m_innerNonZeros[outer]++;
+      m_data.index(p) = convert_index(inner);
+      return (m_data.value(p) = Scalar(0));
+    }
+protected:
+    struct IndexPosPair {
+      IndexPosPair(Index a_i, Index a_p) : i(a_i), p(a_p) {}
+      Index i;
+      Index p;
+    };
+
+    /** \internal assign \a diagXpr to the diagonal of \c *this
+      * There are different strategies:
+      *   1 - if *this is overwritten (Func==assign_op) or *this is empty, then we can work treat *this as a dense vector expression.
+      *   2 - otherwise, for each diagonal coeff,
+      *     2.a - if it already exists, then we update it,
+      *     2.b - otherwise, if *this is uncompressed and that the current inner-vector has empty room for at least 1 element, then we perform an in-place insertion.
+      *     2.c - otherwise, we'll have to reallocate and copy everything, so instead of doing so for each new element, it is recorded in a std::vector.
+      *   3 - at the end, if some entries failed to be inserted in-place, then we alloc a new buffer, copy each chunk at the right position, and insert the new elements.
+      * 
+      * TODO: some piece of code could be isolated and reused for a general in-place update strategy.
+      * TODO: if we start to defer the insertion of some elements (i.e., case 2.c executed once),
+      *       then it *might* be better to disable case 2.b since they will have to be copied anyway.
+      */
+    template<typename DiagXpr, typename Func>
+    void assignDiagonal(const DiagXpr diagXpr, const Func& assignFunc)
+    {
+      Index n = diagXpr.size();
+
+      const bool overwrite = internal::is_same<Func, internal::assign_op<Scalar,Scalar> >::value;
+      if(overwrite)
+      {
+        if((this->rows()!=n) || (this->cols()!=n))
+          this->resize(n, n);
+      }
+
+      if(m_data.size()==0 || overwrite)
+      {
+        typedef Array<StorageIndex,Dynamic,1> ArrayXI;  
+        this->makeCompressed();
+        this->resizeNonZeros(n);
+        Eigen::Map<ArrayXI>(this->innerIndexPtr(), n).setLinSpaced(0,StorageIndex(n)-1);
+        Eigen::Map<ArrayXI>(this->outerIndexPtr(), n+1).setLinSpaced(0,StorageIndex(n));
+        Eigen::Map<Array<Scalar,Dynamic,1> > values = this->coeffs();
+        values.setZero();
+        internal::call_assignment_no_alias(values, diagXpr, assignFunc);
+      }
+      else
+      {
+        bool isComp = isCompressed();
+        internal::evaluator<DiagXpr> diaEval(diagXpr);
+        std::vector<IndexPosPair> newEntries;
+
+        // 1 - try in-place update and record insertion failures
+        for(Index i = 0; i<n; ++i)
+        {
+          internal::LowerBoundIndex lb = this->lower_bound(i,i);
+          Index p = lb.value;
+          if(lb.found)
+          {
+            // the coeff already exists
+            assignFunc.assignCoeff(m_data.value(p), diaEval.coeff(i));
+          }
+          else if((!isComp) && m_innerNonZeros[i] < (m_outerIndex[i+1]-m_outerIndex[i]))
+          {
+            // non compressed mode with local room for inserting one element
+            m_data.moveChunk(p, p+1, m_outerIndex[i]+m_innerNonZeros[i]-p);
+            m_innerNonZeros[i]++;
+            m_data.value(p) = Scalar(0);
+            m_data.index(p) = StorageIndex(i);
+            assignFunc.assignCoeff(m_data.value(p), diaEval.coeff(i));
+          }
+          else
+          {
+            // defer insertion
+            newEntries.push_back(IndexPosPair(i,p));
+          }
+        }
+        // 2 - insert deferred entries
+        Index n_entries = Index(newEntries.size());
+        if(n_entries>0)
+        {
+          Storage newData(m_data.size()+n_entries);
+          Index prev_p = 0;
+          Index prev_i = 0;
+          for(Index k=0; k<n_entries;++k)
+          {
+            Index i = newEntries[k].i;
+            Index p = newEntries[k].p;
+            internal::smart_copy(m_data.valuePtr()+prev_p, m_data.valuePtr()+p, newData.valuePtr()+prev_p+k);
+            internal::smart_copy(m_data.indexPtr()+prev_p, m_data.indexPtr()+p, newData.indexPtr()+prev_p+k);
+            for(Index j=prev_i;j<i;++j)
+              m_outerIndex[j+1] += k;
+            if(!isComp)
+              m_innerNonZeros[i]++;
+            prev_p = p;
+            prev_i = i;
+            newData.value(p+k) = Scalar(0);
+            newData.index(p+k) = StorageIndex(i);
+            assignFunc.assignCoeff(newData.value(p+k), diaEval.coeff(i));
+          }
+          {
+            internal::smart_copy(m_data.valuePtr()+prev_p, m_data.valuePtr()+m_data.size(), newData.valuePtr()+prev_p+n_entries);
+            internal::smart_copy(m_data.indexPtr()+prev_p, m_data.indexPtr()+m_data.size(), newData.indexPtr()+prev_p+n_entries);
+            for(Index j=prev_i+1;j<=m_outerSize;++j)
+              m_outerIndex[j] += n_entries;
+          }
+          m_data.swap(newData);
+        }
+      }
+    }
+
+private:
+  static void check_template_parameters()
+  {
+    EIGEN_STATIC_ASSERT(NumTraits<StorageIndex>::IsSigned,THE_INDEX_TYPE_MUST_BE_A_SIGNED_TYPE);
+    EIGEN_STATIC_ASSERT((Options&(ColMajor|RowMajor))==Options,INVALID_MATRIX_TEMPLATE_PARAMETERS);
+  }
+
+  struct default_prunning_func {
+    default_prunning_func(const Scalar& ref, const RealScalar& eps) : reference(ref), epsilon(eps) {}
+    inline bool operator() (const Index&, const Index&, const Scalar& value) const
+    {
+      return !internal::isMuchSmallerThan(value, reference, epsilon);
+    }
+    Scalar reference;
+    RealScalar epsilon;
+  };
+};
+
+namespace internal {
+
+template<typename InputIterator, typename SparseMatrixType, typename DupFunctor>
+void set_from_triplets(const InputIterator& begin, const InputIterator& end, SparseMatrixType& mat, DupFunctor dup_func)
+{
+  enum { IsRowMajor = SparseMatrixType::IsRowMajor };
+  typedef typename SparseMatrixType::Scalar Scalar;
+  typedef typename SparseMatrixType::StorageIndex StorageIndex;
+  SparseMatrix<Scalar,IsRowMajor?ColMajor:RowMajor,StorageIndex> trMat(mat.rows(),mat.cols());
+
+  if(begin!=end)
+  {
+    // pass 1: count the nnz per inner-vector
+    typename SparseMatrixType::IndexVector wi(trMat.outerSize());
+    wi.setZero();
+    for(InputIterator it(begin); it!=end; ++it)
+    {
+      eigen_assert(it->row()>=0 && it->row()<mat.rows() && it->col()>=0 && it->col()<mat.cols());
+      wi(IsRowMajor ? it->col() : it->row())++;
+    }
+
+    // pass 2: insert all the elements into trMat
+    trMat.reserve(wi);
+    for(InputIterator it(begin); it!=end; ++it)
+      trMat.insertBackUncompressed(it->row(),it->col()) = it->value();
+
+    // pass 3:
+    trMat.collapseDuplicates(dup_func);
+  }
+
+  // pass 4: transposed copy -> implicit sorting
+  mat = trMat;
+}
+
+}
+
+
+/** Fill the matrix \c *this with the list of \em triplets defined by the iterator range \a begin - \a end.
+  *
+  * A \em triplet is a tuple (i,j,value) defining a non-zero element.
+  * The input list of triplets does not have to be sorted, and can contains duplicated elements.
+  * In any case, the result is a \b sorted and \b compressed sparse matrix where the duplicates have been summed up.
+  * This is a \em O(n) operation, with \em n the number of triplet elements.
+  * The initial contents of \c *this is destroyed.
+  * The matrix \c *this must be properly resized beforehand using the SparseMatrix(Index,Index) constructor,
+  * or the resize(Index,Index) method. The sizes are not extracted from the triplet list.
+  *
+  * The \a InputIterators value_type must provide the following interface:
+  * \code
+  * Scalar value() const; // the value
+  * Scalar row() const;   // the row index i
+  * Scalar col() const;   // the column index j
+  * \endcode
+  * See for instance the Eigen::Triplet template class.
+  *
+  * Here is a typical usage example:
+  * \code
+    typedef Triplet<double> T;
+    std::vector<T> tripletList;
+    tripletList.reserve(estimation_of_entries);
+    for(...)
+    {
+      // ...
+      tripletList.push_back(T(i,j,v_ij));
+    }
+    SparseMatrixType m(rows,cols);
+    m.setFromTriplets(tripletList.begin(), tripletList.end());
+    // m is ready to go!
+  * \endcode
+  *
+  * \warning The list of triplets is read multiple times (at least twice). Therefore, it is not recommended to define
+  * an abstract iterator over a complex data-structure that would be expensive to evaluate. The triplets should rather
+  * be explicitly stored into a std::vector for instance.
+  */
+template<typename Scalar, int _Options, typename _StorageIndex>
+template<typename InputIterators>
+void SparseMatrix<Scalar,_Options,_StorageIndex>::setFromTriplets(const InputIterators& begin, const InputIterators& end)
+{
+  internal::set_from_triplets<InputIterators, SparseMatrix<Scalar,_Options,_StorageIndex> >(begin, end, *this, internal::scalar_sum_op<Scalar,Scalar>());
+}
+
+/** The same as setFromTriplets but when duplicates are met the functor \a dup_func is applied:
+  * \code
+  * value = dup_func(OldValue, NewValue)
+  * \endcode 
+  * Here is a C++11 example keeping the latest entry only:
+  * \code
+  * mat.setFromTriplets(triplets.begin(), triplets.end(), [] (const Scalar&,const Scalar &b) { return b; });
+  * \endcode
+  */
+template<typename Scalar, int _Options, typename _StorageIndex>
+template<typename InputIterators,typename DupFunctor>
+void SparseMatrix<Scalar,_Options,_StorageIndex>::setFromTriplets(const InputIterators& begin, const InputIterators& end, DupFunctor dup_func)
+{
+  internal::set_from_triplets<InputIterators, SparseMatrix<Scalar,_Options,_StorageIndex>, DupFunctor>(begin, end, *this, dup_func);
+}
+
+/** \internal */
+template<typename Scalar, int _Options, typename _StorageIndex>
+template<typename DupFunctor>
+void SparseMatrix<Scalar,_Options,_StorageIndex>::collapseDuplicates(DupFunctor dup_func)
+{
+  eigen_assert(!isCompressed());
+  // TODO, in practice we should be able to use m_innerNonZeros for that task
+  IndexVector wi(innerSize());
+  wi.fill(-1);
+  StorageIndex count = 0;
+  // for each inner-vector, wi[inner_index] will hold the position of first element into the index/value buffers
+  for(Index j=0; j<outerSize(); ++j)
+  {
+    StorageIndex start   = count;
+    Index oldEnd  = m_outerIndex[j]+m_innerNonZeros[j];
+    for(Index k=m_outerIndex[j]; k<oldEnd; ++k)
+    {
+      Index i = m_data.index(k);
+      if(wi(i)>=start)
+      {
+        // we already meet this entry => accumulate it
+        m_data.value(wi(i)) = dup_func(m_data.value(wi(i)), m_data.value(k));
+      }
+      else
+      {
+        m_data.value(count) = m_data.value(k);
+        m_data.index(count) = m_data.index(k);
+        wi(i) = count;
+        ++count;
+      }
+    }
+    m_outerIndex[j] = start;
+  }
+  m_outerIndex[m_outerSize] = count;
+
+  // turn the matrix into compressed form
+  std::free(m_innerNonZeros);
+  m_innerNonZeros = 0;
+  m_data.resize(m_outerIndex[m_outerSize]);
+}
+
+template<typename Scalar, int _Options, typename _StorageIndex>
+template<typename OtherDerived>
+EIGEN_DONT_INLINE SparseMatrix<Scalar,_Options,_StorageIndex>& SparseMatrix<Scalar,_Options,_StorageIndex>::operator=(const SparseMatrixBase<OtherDerived>& other)
+{
+  EIGEN_STATIC_ASSERT((internal::is_same<Scalar, typename OtherDerived::Scalar>::value),
+        YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)
+
+  #ifdef EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN
+    EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN
+  #endif
+      
+  const bool needToTranspose = (Flags & RowMajorBit) != (internal::evaluator<OtherDerived>::Flags & RowMajorBit);
+  if (needToTranspose)
+  {
+    #ifdef EIGEN_SPARSE_TRANSPOSED_COPY_PLUGIN
+      EIGEN_SPARSE_TRANSPOSED_COPY_PLUGIN
+    #endif
+    // two passes algorithm:
+    //  1 - compute the number of coeffs per dest inner vector
+    //  2 - do the actual copy/eval
+    // Since each coeff of the rhs has to be evaluated twice, let's evaluate it if needed
+    typedef typename internal::nested_eval<OtherDerived,2,typename internal::plain_matrix_type<OtherDerived>::type >::type OtherCopy;
+    typedef typename internal::remove_all<OtherCopy>::type _OtherCopy;
+    typedef internal::evaluator<_OtherCopy> OtherCopyEval;
+    OtherCopy otherCopy(other.derived());
+    OtherCopyEval otherCopyEval(otherCopy);
+
+    SparseMatrix dest(other.rows(),other.cols());
+    Eigen::Map<IndexVector> (dest.m_outerIndex,dest.outerSize()).setZero();
+
+    // pass 1
+    // FIXME the above copy could be merged with that pass
+    for (Index j=0; j<otherCopy.outerSize(); ++j)
+      for (typename OtherCopyEval::InnerIterator it(otherCopyEval, j); it; ++it)
+        ++dest.m_outerIndex[it.index()];
+
+    // prefix sum
+    StorageIndex count = 0;
+    IndexVector positions(dest.outerSize());
+    for (Index j=0; j<dest.outerSize(); ++j)
+    {
+      StorageIndex tmp = dest.m_outerIndex[j];
+      dest.m_outerIndex[j] = count;
+      positions[j] = count;
+      count += tmp;
+    }
+    dest.m_outerIndex[dest.outerSize()] = count;
+    // alloc
+    dest.m_data.resize(count);
+    // pass 2
+    for (StorageIndex j=0; j<otherCopy.outerSize(); ++j)
+    {
+      for (typename OtherCopyEval::InnerIterator it(otherCopyEval, j); it; ++it)
+      {
+        Index pos = positions[it.index()]++;
+        dest.m_data.index(pos) = j;
+        dest.m_data.value(pos) = it.value();
+      }
+    }
+    this->swap(dest);
+    return *this;
+  }
+  else
+  {
+    if(other.isRValue())
+    {
+      initAssignment(other.derived());
+    }
+    // there is no special optimization
+    return Base::operator=(other.derived());
+  }
+}
+
+template<typename _Scalar, int _Options, typename _StorageIndex>
+typename SparseMatrix<_Scalar,_Options,_StorageIndex>::Scalar& SparseMatrix<_Scalar,_Options,_StorageIndex>::insert(Index row, Index col)
+{
+  eigen_assert(row>=0 && row<rows() && col>=0 && col<cols());
+  
+  const Index outer = IsRowMajor ? row : col;
+  const Index inner = IsRowMajor ? col : row;
+  
+  if(isCompressed())
+  {
+    if(nonZeros()==0)
+    {
+      // reserve space if not already done
+      if(m_data.allocatedSize()==0)
+        m_data.reserve(2*m_innerSize);
+      
+      // turn the matrix into non-compressed mode
+      m_innerNonZeros = static_cast<StorageIndex*>(std::malloc(m_outerSize * sizeof(StorageIndex)));
+      if(!m_innerNonZeros) internal::throw_std_bad_alloc();
+      
+      memset(m_innerNonZeros, 0, (m_outerSize)*sizeof(StorageIndex));
+      
+      // pack all inner-vectors to the end of the pre-allocated space
+      // and allocate the entire free-space to the first inner-vector
+      StorageIndex end = convert_index(m_data.allocatedSize());
+      for(Index j=1; j<=m_outerSize; ++j)
+        m_outerIndex[j] = end;
+    }
+    else
+    {
+      // turn the matrix into non-compressed mode
+      m_innerNonZeros = static_cast<StorageIndex*>(std::malloc(m_outerSize * sizeof(StorageIndex)));
+      if(!m_innerNonZeros) internal::throw_std_bad_alloc();
+      for(Index j=0; j<m_outerSize; ++j)
+        m_innerNonZeros[j] = m_outerIndex[j+1]-m_outerIndex[j];
+    }
+  }
+  
+  // check whether we can do a fast "push back" insertion
+  Index data_end = m_data.allocatedSize();
+  
+  // First case: we are filling a new inner vector which is packed at the end.
+  // We assume that all remaining inner-vectors are also empty and packed to the end.
+  if(m_outerIndex[outer]==data_end)
+  {
+    eigen_internal_assert(m_innerNonZeros[outer]==0);
+    
+    // pack previous empty inner-vectors to end of the used-space
+    // and allocate the entire free-space to the current inner-vector.
+    StorageIndex p = convert_index(m_data.size());
+    Index j = outer;
+    while(j>=0 && m_innerNonZeros[j]==0)
+      m_outerIndex[j--] = p;
+    
+    // push back the new element
+    ++m_innerNonZeros[outer];
+    m_data.append(Scalar(0), inner);
+    
+    // check for reallocation
+    if(data_end != m_data.allocatedSize())
+    {
+      // m_data has been reallocated
+      //  -> move remaining inner-vectors back to the end of the free-space
+      //     so that the entire free-space is allocated to the current inner-vector.
+      eigen_internal_assert(data_end < m_data.allocatedSize());
+      StorageIndex new_end = convert_index(m_data.allocatedSize());
+      for(Index k=outer+1; k<=m_outerSize; ++k)
+        if(m_outerIndex[k]==data_end)
+          m_outerIndex[k] = new_end;
+    }
+    return m_data.value(p);
+  }
+  
+  // Second case: the next inner-vector is packed to the end
+  // and the current inner-vector end match the used-space.
+  if(m_outerIndex[outer+1]==data_end && m_outerIndex[outer]+m_innerNonZeros[outer]==m_data.size())
+  {
+    eigen_internal_assert(outer+1==m_outerSize || m_innerNonZeros[outer+1]==0);
+    
+    // add space for the new element
+    ++m_innerNonZeros[outer];
+    m_data.resize(m_data.size()+1);
+    
+    // check for reallocation
+    if(data_end != m_data.allocatedSize())
+    {
+      // m_data has been reallocated
+      //  -> move remaining inner-vectors back to the end of the free-space
+      //     so that the entire free-space is allocated to the current inner-vector.
+      eigen_internal_assert(data_end < m_data.allocatedSize());
+      StorageIndex new_end = convert_index(m_data.allocatedSize());
+      for(Index k=outer+1; k<=m_outerSize; ++k)
+        if(m_outerIndex[k]==data_end)
+          m_outerIndex[k] = new_end;
+    }
+    
+    // and insert it at the right position (sorted insertion)
+    Index startId = m_outerIndex[outer];
+    Index p = m_outerIndex[outer]+m_innerNonZeros[outer]-1;
+    while ( (p > startId) && (m_data.index(p-1) > inner) )
+    {
+      m_data.index(p) = m_data.index(p-1);
+      m_data.value(p) = m_data.value(p-1);
+      --p;
+    }
+    
+    m_data.index(p) = convert_index(inner);
+    return (m_data.value(p) = Scalar(0));
+  }
+  
+  if(m_data.size() != m_data.allocatedSize())
+  {
+    // make sure the matrix is compatible to random un-compressed insertion:
+    m_data.resize(m_data.allocatedSize());
+    this->reserveInnerVectors(Array<StorageIndex,Dynamic,1>::Constant(m_outerSize, 2));
+  }
+  
+  return insertUncompressed(row,col);
+}
+    
+template<typename _Scalar, int _Options, typename _StorageIndex>
+EIGEN_DONT_INLINE typename SparseMatrix<_Scalar,_Options,_StorageIndex>::Scalar& SparseMatrix<_Scalar,_Options,_StorageIndex>::insertUncompressed(Index row, Index col)
+{
+  eigen_assert(!isCompressed());
+
+  const Index outer = IsRowMajor ? row : col;
+  const StorageIndex inner = convert_index(IsRowMajor ? col : row);
+
+  Index room = m_outerIndex[outer+1] - m_outerIndex[outer];
+  StorageIndex innerNNZ = m_innerNonZeros[outer];
+  if(innerNNZ>=room)
+  {
+    // this inner vector is full, we need to reallocate the whole buffer :(
+    reserve(SingletonVector(outer,std::max<StorageIndex>(2,innerNNZ)));
+  }
+
+  Index startId = m_outerIndex[outer];
+  Index p = startId + m_innerNonZeros[outer];
+  while ( (p > startId) && (m_data.index(p-1) > inner) )
+  {
+    m_data.index(p) = m_data.index(p-1);
+    m_data.value(p) = m_data.value(p-1);
+    --p;
+  }
+  eigen_assert((p<=startId || m_data.index(p-1)!=inner) && "you cannot insert an element that already exists, you must call coeffRef to this end");
+
+  m_innerNonZeros[outer]++;
+
+  m_data.index(p) = inner;
+  return (m_data.value(p) = Scalar(0));
+}
+
+template<typename _Scalar, int _Options, typename _StorageIndex>
+EIGEN_DONT_INLINE typename SparseMatrix<_Scalar,_Options,_StorageIndex>::Scalar& SparseMatrix<_Scalar,_Options,_StorageIndex>::insertCompressed(Index row, Index col)
+{
+  eigen_assert(isCompressed());
+
+  const Index outer = IsRowMajor ? row : col;
+  const Index inner = IsRowMajor ? col : row;
+
+  Index previousOuter = outer;
+  if (m_outerIndex[outer+1]==0)
+  {
+    // we start a new inner vector
+    while (previousOuter>=0 && m_outerIndex[previousOuter]==0)
+    {
+      m_outerIndex[previousOuter] = convert_index(m_data.size());
+      --previousOuter;
+    }
+    m_outerIndex[outer+1] = m_outerIndex[outer];
+  }
+
+  // here we have to handle the tricky case where the outerIndex array
+  // starts with: [ 0 0 0 0 0 1 ...] and we are inserted in, e.g.,
+  // the 2nd inner vector...
+  bool isLastVec = (!(previousOuter==-1 && m_data.size()!=0))
+                && (std::size_t(m_outerIndex[outer+1]) == m_data.size());
+
+  std::size_t startId = m_outerIndex[outer];
+  // FIXME let's make sure sizeof(long int) == sizeof(std::size_t)
+  std::size_t p = m_outerIndex[outer+1];
+  ++m_outerIndex[outer+1];
+
+  double reallocRatio = 1;
+  if (m_data.allocatedSize()<=m_data.size())
+  {
+    // if there is no preallocated memory, let's reserve a minimum of 32 elements
+    if (m_data.size()==0)
+    {
+      m_data.reserve(32);
+    }
+    else
+    {
+      // we need to reallocate the data, to reduce multiple reallocations
+      // we use a smart resize algorithm based on the current filling ratio
+      // in addition, we use double to avoid integers overflows
+      double nnzEstimate = double(m_outerIndex[outer])*double(m_outerSize)/double(outer+1);
+      reallocRatio = (nnzEstimate-double(m_data.size()))/double(m_data.size());
+      // furthermore we bound the realloc ratio to:
+      //   1) reduce multiple minor realloc when the matrix is almost filled
+      //   2) avoid to allocate too much memory when the matrix is almost empty
+      reallocRatio = (std::min)((std::max)(reallocRatio,1.5),8.);
+    }
+  }
+  m_data.resize(m_data.size()+1,reallocRatio);
+
+  if (!isLastVec)
+  {
+    if (previousOuter==-1)
+    {
+      // oops wrong guess.
+      // let's correct the outer offsets
+      for (Index k=0; k<=(outer+1); ++k)
+        m_outerIndex[k] = 0;
+      Index k=outer+1;
+      while(m_outerIndex[k]==0)
+        m_outerIndex[k++] = 1;
+      while (k<=m_outerSize && m_outerIndex[k]!=0)
+        m_outerIndex[k++]++;
+      p = 0;
+      --k;
+      k = m_outerIndex[k]-1;
+      while (k>0)
+      {
+        m_data.index(k) = m_data.index(k-1);
+        m_data.value(k) = m_data.value(k-1);
+        k--;
+      }
+    }
+    else
+    {
+      // we are not inserting into the last inner vec
+      // update outer indices:
+      Index j = outer+2;
+      while (j<=m_outerSize && m_outerIndex[j]!=0)
+        m_outerIndex[j++]++;
+      --j;
+      // shift data of last vecs:
+      Index k = m_outerIndex[j]-1;
+      while (k>=Index(p))
+      {
+        m_data.index(k) = m_data.index(k-1);
+        m_data.value(k) = m_data.value(k-1);
+        k--;
+      }
+    }
+  }
+
+  while ( (p > startId) && (m_data.index(p-1) > inner) )
+  {
+    m_data.index(p) = m_data.index(p-1);
+    m_data.value(p) = m_data.value(p-1);
+    --p;
+  }
+
+  m_data.index(p) = inner;
+  return (m_data.value(p) = Scalar(0));
+}
+
+namespace internal {
+
+template<typename _Scalar, int _Options, typename _StorageIndex>
+struct evaluator<SparseMatrix<_Scalar,_Options,_StorageIndex> >
+  : evaluator<SparseCompressedBase<SparseMatrix<_Scalar,_Options,_StorageIndex> > >
+{
+  typedef evaluator<SparseCompressedBase<SparseMatrix<_Scalar,_Options,_StorageIndex> > > Base;
+  typedef SparseMatrix<_Scalar,_Options,_StorageIndex> SparseMatrixType;
+  evaluator() : Base() {}
+  explicit evaluator(const SparseMatrixType &mat) : Base(mat) {}
+};
+
+}
+
+} // end namespace Eigen
+
+#endif // EIGEN_SPARSEMATRIX_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseMatrixBase.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseMatrixBase.h
new file mode 100644
index 0000000..229449f
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseMatrixBase.h
@@ -0,0 +1,398 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2008-2014 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_SPARSEMATRIXBASE_H
+#define EIGEN_SPARSEMATRIXBASE_H
+
+namespace Eigen { 
+
+/** \ingroup SparseCore_Module
+  *
+  * \class SparseMatrixBase
+  *
+  * \brief Base class of any sparse matrices or sparse expressions
+  *
+  * \tparam Derived is the derived type, e.g. a sparse matrix type, or an expression, etc.
+  *
+  * This class can be extended with the help of the plugin mechanism described on the page
+  * \ref TopicCustomizing_Plugins by defining the preprocessor symbol \c EIGEN_SPARSEMATRIXBASE_PLUGIN.
+  */
+template<typename Derived> class SparseMatrixBase
+  : public EigenBase<Derived>
+{
+  public:
+
+    typedef typename internal::traits<Derived>::Scalar Scalar;
+    
+    /** The numeric type of the expression' coefficients, e.g. float, double, int or std::complex<float>, etc.
+      *
+      * It is an alias for the Scalar type */
+    typedef Scalar value_type;
+    
+    typedef typename internal::packet_traits<Scalar>::type PacketScalar;
+    typedef typename internal::traits<Derived>::StorageKind StorageKind;
+
+    /** The integer type used to \b store indices within a SparseMatrix.
+      * For a \c SparseMatrix<Scalar,Options,IndexType> it an alias of the third template parameter \c IndexType. */
+    typedef typename internal::traits<Derived>::StorageIndex StorageIndex;
+
+    typedef typename internal::add_const_on_value_type_if_arithmetic<
+                         typename internal::packet_traits<Scalar>::type
+                     >::type PacketReturnType;
+
+    typedef SparseMatrixBase StorageBaseType;
+
+    typedef Matrix<StorageIndex,Dynamic,1> IndexVector;
+    typedef Matrix<Scalar,Dynamic,1> ScalarVector;
+    
+    template<typename OtherDerived>
+    Derived& operator=(const EigenBase<OtherDerived> &other);
+
+    enum {
+
+      RowsAtCompileTime = internal::traits<Derived>::RowsAtCompileTime,
+        /**< The number of rows at compile-time. This is just a copy of the value provided
+          * by the \a Derived type. If a value is not known at compile-time,
+          * it is set to the \a Dynamic constant.
+          * \sa MatrixBase::rows(), MatrixBase::cols(), ColsAtCompileTime, SizeAtCompileTime */
+
+      ColsAtCompileTime = internal::traits<Derived>::ColsAtCompileTime,
+        /**< The number of columns at compile-time. This is just a copy of the value provided
+          * by the \a Derived type. If a value is not known at compile-time,
+          * it is set to the \a Dynamic constant.
+          * \sa MatrixBase::rows(), MatrixBase::cols(), RowsAtCompileTime, SizeAtCompileTime */
+
+
+      SizeAtCompileTime = (internal::size_at_compile_time<internal::traits<Derived>::RowsAtCompileTime,
+                                                   internal::traits<Derived>::ColsAtCompileTime>::ret),
+        /**< This is equal to the number of coefficients, i.e. the number of
+          * rows times the number of columns, or to \a Dynamic if this is not
+          * known at compile-time. \sa RowsAtCompileTime, ColsAtCompileTime */
+
+      MaxRowsAtCompileTime = RowsAtCompileTime,
+      MaxColsAtCompileTime = ColsAtCompileTime,
+
+      MaxSizeAtCompileTime = (internal::size_at_compile_time<MaxRowsAtCompileTime,
+                                                      MaxColsAtCompileTime>::ret),
+
+      IsVectorAtCompileTime = RowsAtCompileTime == 1 || ColsAtCompileTime == 1,
+        /**< This is set to true if either the number of rows or the number of
+          * columns is known at compile-time to be equal to 1. Indeed, in that case,
+          * we are dealing with a column-vector (if there is only one column) or with
+          * a row-vector (if there is only one row). */
+
+      NumDimensions = int(MaxSizeAtCompileTime) == 1 ? 0 : bool(IsVectorAtCompileTime) ? 1 : 2,
+        /**< This value is equal to Tensor::NumDimensions, i.e. 0 for scalars, 1 for vectors,
+         * and 2 for matrices.
+         */
+
+      Flags = internal::traits<Derived>::Flags,
+        /**< This stores expression \ref flags flags which may or may not be inherited by new expressions
+          * constructed from this one. See the \ref flags "list of flags".
+          */
+
+      IsRowMajor = Flags&RowMajorBit ? 1 : 0,
+      
+      InnerSizeAtCompileTime = int(IsVectorAtCompileTime) ? int(SizeAtCompileTime)
+                             : int(IsRowMajor) ? int(ColsAtCompileTime) : int(RowsAtCompileTime),
+
+      #ifndef EIGEN_PARSED_BY_DOXYGEN
+      _HasDirectAccess = (int(Flags)&DirectAccessBit) ? 1 : 0 // workaround sunCC
+      #endif
+    };
+
+    /** \internal the return type of MatrixBase::adjoint() */
+    typedef typename internal::conditional<NumTraits<Scalar>::IsComplex,
+                        CwiseUnaryOp<internal::scalar_conjugate_op<Scalar>, Eigen::Transpose<const Derived> >,
+                        Transpose<const Derived>
+                     >::type AdjointReturnType;
+    typedef Transpose<Derived> TransposeReturnType;
+    typedef typename internal::add_const<Transpose<const Derived> >::type ConstTransposeReturnType;
+
+    // FIXME storage order do not match evaluator storage order
+    typedef SparseMatrix<Scalar, Flags&RowMajorBit ? RowMajor : ColMajor, StorageIndex> PlainObject;
+
+#ifndef EIGEN_PARSED_BY_DOXYGEN
+    /** This is the "real scalar" type; if the \a Scalar type is already real numbers
+      * (e.g. int, float or double) then \a RealScalar is just the same as \a Scalar. If
+      * \a Scalar is \a std::complex<T> then RealScalar is \a T.
+      *
+      * \sa class NumTraits
+      */
+    typedef typename NumTraits<Scalar>::Real RealScalar;
+
+    /** \internal the return type of coeff()
+      */
+    typedef typename internal::conditional<_HasDirectAccess, const Scalar&, Scalar>::type CoeffReturnType;
+
+    /** \internal Represents a matrix with all coefficients equal to one another*/
+    typedef CwiseNullaryOp<internal::scalar_constant_op<Scalar>,Matrix<Scalar,Dynamic,Dynamic> > ConstantReturnType;
+
+    /** type of the equivalent dense matrix */
+    typedef Matrix<Scalar,RowsAtCompileTime,ColsAtCompileTime> DenseMatrixType;
+    /** type of the equivalent square matrix */
+    typedef Matrix<Scalar,EIGEN_SIZE_MAX(RowsAtCompileTime,ColsAtCompileTime),
+                          EIGEN_SIZE_MAX(RowsAtCompileTime,ColsAtCompileTime)> SquareMatrixType;
+
+    inline const Derived& derived() const { return *static_cast<const Derived*>(this); }
+    inline Derived& derived() { return *static_cast<Derived*>(this); }
+    inline Derived& const_cast_derived() const
+    { return *static_cast<Derived*>(const_cast<SparseMatrixBase*>(this)); }
+
+    typedef EigenBase<Derived> Base;
+
+#endif // not EIGEN_PARSED_BY_DOXYGEN
+
+#define EIGEN_CURRENT_STORAGE_BASE_CLASS Eigen::SparseMatrixBase
+#ifdef EIGEN_PARSED_BY_DOXYGEN
+#define EIGEN_DOC_UNARY_ADDONS(METHOD,OP)           /** <p>This method does not change the sparsity of \c *this: the OP is applied to explicitly stored coefficients only. \sa SparseCompressedBase::coeffs() </p> */
+#define EIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL      /** <p> \warning This method returns a read-only expression for any sparse matrices. \sa \ref TutorialSparse_SubMatrices "Sparse block operations" </p> */
+#define EIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(COND) /** <p> \warning This method returns a read-write expression for COND sparse matrices only. Otherwise, the returned expression is read-only. \sa \ref TutorialSparse_SubMatrices "Sparse block operations" </p> */
+#else
+#define EIGEN_DOC_UNARY_ADDONS(X,Y)
+#define EIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL
+#define EIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(COND)
+#endif
+#   include "../plugins/CommonCwiseUnaryOps.h"
+#   include "../plugins/CommonCwiseBinaryOps.h"
+#   include "../plugins/MatrixCwiseUnaryOps.h"
+#   include "../plugins/MatrixCwiseBinaryOps.h"
+#   include "../plugins/BlockMethods.h"
+#   ifdef EIGEN_SPARSEMATRIXBASE_PLUGIN
+#     include EIGEN_SPARSEMATRIXBASE_PLUGIN
+#   endif
+#undef EIGEN_CURRENT_STORAGE_BASE_CLASS
+#undef EIGEN_DOC_UNARY_ADDONS
+#undef EIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL
+#undef EIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF
+
+    /** \returns the number of rows. \sa cols() */
+    inline Index rows() const { return derived().rows(); }
+    /** \returns the number of columns. \sa rows() */
+    inline Index cols() const { return derived().cols(); }
+    /** \returns the number of coefficients, which is \a rows()*cols().
+      * \sa rows(), cols(). */
+    inline Index size() const { return rows() * cols(); }
+    /** \returns true if either the number of rows or the number of columns is equal to 1.
+      * In other words, this function returns
+      * \code rows()==1 || cols()==1 \endcode
+      * \sa rows(), cols(), IsVectorAtCompileTime. */
+    inline bool isVector() const { return rows()==1 || cols()==1; }
+    /** \returns the size of the storage major dimension,
+      * i.e., the number of columns for a columns major matrix, and the number of rows otherwise */
+    Index outerSize() const { return (int(Flags)&RowMajorBit) ? this->rows() : this->cols(); }
+    /** \returns the size of the inner dimension according to the storage order,
+      * i.e., the number of rows for a columns major matrix, and the number of cols otherwise */
+    Index innerSize() const { return (int(Flags)&RowMajorBit) ? this->cols() : this->rows(); }
+
+    bool isRValue() const { return m_isRValue; }
+    Derived& markAsRValue() { m_isRValue = true; return derived(); }
+
+    SparseMatrixBase() : m_isRValue(false) { /* TODO check flags */ }
+
+    
+    template<typename OtherDerived>
+    Derived& operator=(const ReturnByValue<OtherDerived>& other);
+
+    template<typename OtherDerived>
+    inline Derived& operator=(const SparseMatrixBase<OtherDerived>& other);
+
+    inline Derived& operator=(const Derived& other);
+
+  protected:
+
+    template<typename OtherDerived>
+    inline Derived& assign(const OtherDerived& other);
+
+    template<typename OtherDerived>
+    inline void assignGeneric(const OtherDerived& other);
+
+  public:
+
+    friend std::ostream & operator << (std::ostream & s, const SparseMatrixBase& m)
+    {
+      typedef typename Derived::Nested Nested;
+      typedef typename internal::remove_all<Nested>::type NestedCleaned;
+
+      if (Flags&RowMajorBit)
+      {
+        Nested nm(m.derived());
+        internal::evaluator<NestedCleaned> thisEval(nm);
+        for (Index row=0; row<nm.outerSize(); ++row)
+        {
+          Index col = 0;
+          for (typename internal::evaluator<NestedCleaned>::InnerIterator it(thisEval, row); it; ++it)
+          {
+            for ( ; col<it.index(); ++col)
+              s << "0 ";
+            s << it.value() << " ";
+            ++col;
+          }
+          for ( ; col<m.cols(); ++col)
+            s << "0 ";
+          s << std::endl;
+        }
+      }
+      else
+      {
+        Nested nm(m.derived());
+        internal::evaluator<NestedCleaned> thisEval(nm);
+        if (m.cols() == 1) {
+          Index row = 0;
+          for (typename internal::evaluator<NestedCleaned>::InnerIterator it(thisEval, 0); it; ++it)
+          {
+            for ( ; row<it.index(); ++row)
+              s << "0" << std::endl;
+            s << it.value() << std::endl;
+            ++row;
+          }
+          for ( ; row<m.rows(); ++row)
+            s << "0" << std::endl;
+        }
+        else
+        {
+          SparseMatrix<Scalar, RowMajorBit, StorageIndex> trans = m;
+          s << static_cast<const SparseMatrixBase<SparseMatrix<Scalar, RowMajorBit, StorageIndex> >&>(trans);
+        }
+      }
+      return s;
+    }
+
+    template<typename OtherDerived>
+    Derived& operator+=(const SparseMatrixBase<OtherDerived>& other);
+    template<typename OtherDerived>
+    Derived& operator-=(const SparseMatrixBase<OtherDerived>& other);
+    
+    template<typename OtherDerived>
+    Derived& operator+=(const DiagonalBase<OtherDerived>& other);
+    template<typename OtherDerived>
+    Derived& operator-=(const DiagonalBase<OtherDerived>& other);
+
+    template<typename OtherDerived>
+    Derived& operator+=(const EigenBase<OtherDerived> &other);
+    template<typename OtherDerived>
+    Derived& operator-=(const EigenBase<OtherDerived> &other);
+
+    Derived& operator*=(const Scalar& other);
+    Derived& operator/=(const Scalar& other);
+
+    template<typename OtherDerived> struct CwiseProductDenseReturnType {
+      typedef CwiseBinaryOp<internal::scalar_product_op<typename ScalarBinaryOpTraits<
+                                                          typename internal::traits<Derived>::Scalar,
+                                                          typename internal::traits<OtherDerived>::Scalar
+                                                        >::ReturnType>,
+                            const Derived,
+                            const OtherDerived
+                          > Type;
+    };
+
+    template<typename OtherDerived>
+    EIGEN_STRONG_INLINE const typename CwiseProductDenseReturnType<OtherDerived>::Type
+    cwiseProduct(const MatrixBase<OtherDerived> &other) const;
+
+    // sparse * diagonal
+    template<typename OtherDerived>
+    const Product<Derived,OtherDerived>
+    operator*(const DiagonalBase<OtherDerived> &other) const
+    { return Product<Derived,OtherDerived>(derived(), other.derived()); }
+
+    // diagonal * sparse
+    template<typename OtherDerived> friend
+    const Product<OtherDerived,Derived>
+    operator*(const DiagonalBase<OtherDerived> &lhs, const SparseMatrixBase& rhs)
+    { return Product<OtherDerived,Derived>(lhs.derived(), rhs.derived()); }
+    
+    // sparse * sparse
+    template<typename OtherDerived>
+    const Product<Derived,OtherDerived,AliasFreeProduct>
+    operator*(const SparseMatrixBase<OtherDerived> &other) const;
+    
+    // sparse * dense
+    template<typename OtherDerived>
+    const Product<Derived,OtherDerived>
+    operator*(const MatrixBase<OtherDerived> &other) const
+    { return Product<Derived,OtherDerived>(derived(), other.derived()); }
+    
+    // dense * sparse
+    template<typename OtherDerived> friend
+    const Product<OtherDerived,Derived>
+    operator*(const MatrixBase<OtherDerived> &lhs, const SparseMatrixBase& rhs)
+    { return Product<OtherDerived,Derived>(lhs.derived(), rhs.derived()); }
+    
+     /** \returns an expression of P H P^-1 where H is the matrix represented by \c *this */
+    SparseSymmetricPermutationProduct<Derived,Upper|Lower> twistedBy(const PermutationMatrix<Dynamic,Dynamic,StorageIndex>& perm) const
+    {
+      return SparseSymmetricPermutationProduct<Derived,Upper|Lower>(derived(), perm);
+    }
+
+    template<typename OtherDerived>
+    Derived& operator*=(const SparseMatrixBase<OtherDerived>& other);
+
+    template<int Mode>
+    inline const TriangularView<const Derived, Mode> triangularView() const;
+    
+    template<unsigned int UpLo> struct SelfAdjointViewReturnType { typedef SparseSelfAdjointView<Derived, UpLo> Type; };
+    template<unsigned int UpLo> struct ConstSelfAdjointViewReturnType { typedef const SparseSelfAdjointView<const Derived, UpLo> Type; };
+
+    template<unsigned int UpLo> inline 
+    typename ConstSelfAdjointViewReturnType<UpLo>::Type selfadjointView() const;
+    template<unsigned int UpLo> inline
+    typename SelfAdjointViewReturnType<UpLo>::Type selfadjointView();
+
+    template<typename OtherDerived> Scalar dot(const MatrixBase<OtherDerived>& other) const;
+    template<typename OtherDerived> Scalar dot(const SparseMatrixBase<OtherDerived>& other) const;
+    RealScalar squaredNorm() const;
+    RealScalar norm()  const;
+    RealScalar blueNorm() const;
+
+    TransposeReturnType transpose() { return TransposeReturnType(derived()); }
+    const ConstTransposeReturnType transpose() const { return ConstTransposeReturnType(derived()); }
+    const AdjointReturnType adjoint() const { return AdjointReturnType(transpose()); }
+
+    DenseMatrixType toDense() const
+    {
+      return DenseMatrixType(derived());
+    }
+
+    template<typename OtherDerived>
+    bool isApprox(const SparseMatrixBase<OtherDerived>& other,
+                  const RealScalar& prec = NumTraits<Scalar>::dummy_precision()) const;
+
+    template<typename OtherDerived>
+    bool isApprox(const MatrixBase<OtherDerived>& other,
+                  const RealScalar& prec = NumTraits<Scalar>::dummy_precision()) const
+    { return toDense().isApprox(other,prec); }
+
+    /** \returns the matrix or vector obtained by evaluating this expression.
+      *
+      * Notice that in the case of a plain matrix or vector (not an expression) this function just returns
+      * a const reference, in order to avoid a useless copy.
+      */
+    inline const typename internal::eval<Derived>::type eval() const
+    { return typename internal::eval<Derived>::type(derived()); }
+
+    Scalar sum() const;
+    
+    inline const SparseView<Derived>
+    pruned(const Scalar& reference = Scalar(0), const RealScalar& epsilon = NumTraits<Scalar>::dummy_precision()) const;
+
+  protected:
+
+    bool m_isRValue;
+
+    static inline StorageIndex convert_index(const Index idx) {
+      return internal::convert_index<StorageIndex>(idx);
+    }
+  private:
+    template<typename Dest> void evalTo(Dest &) const;
+};
+
+} // end namespace Eigen
+
+#endif // EIGEN_SPARSEMATRIXBASE_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparsePermutation.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparsePermutation.h
new file mode 100644
index 0000000..ef38357
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparsePermutation.h
@@ -0,0 +1,178 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2012 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_SPARSE_PERMUTATION_H
+#define EIGEN_SPARSE_PERMUTATION_H
+
+// This file implements sparse * permutation products
+
+namespace Eigen { 
+
+namespace internal {
+
+template<typename ExpressionType, int Side, bool Transposed>
+struct permutation_matrix_product<ExpressionType, Side, Transposed, SparseShape>
+{
+    typedef typename nested_eval<ExpressionType, 1>::type MatrixType;
+    typedef typename remove_all<MatrixType>::type MatrixTypeCleaned;
+
+    typedef typename MatrixTypeCleaned::Scalar Scalar;
+    typedef typename MatrixTypeCleaned::StorageIndex StorageIndex;
+
+    enum {
+      SrcStorageOrder = MatrixTypeCleaned::Flags&RowMajorBit ? RowMajor : ColMajor,
+      MoveOuter = SrcStorageOrder==RowMajor ? Side==OnTheLeft : Side==OnTheRight
+    };
+    
+    typedef typename internal::conditional<MoveOuter,
+        SparseMatrix<Scalar,SrcStorageOrder,StorageIndex>,
+        SparseMatrix<Scalar,int(SrcStorageOrder)==RowMajor?ColMajor:RowMajor,StorageIndex> >::type ReturnType;
+
+    template<typename Dest,typename PermutationType>
+    static inline void run(Dest& dst, const PermutationType& perm, const ExpressionType& xpr)
+    {
+      MatrixType mat(xpr);
+      if(MoveOuter)
+      {
+        SparseMatrix<Scalar,SrcStorageOrder,StorageIndex> tmp(mat.rows(), mat.cols());
+        Matrix<StorageIndex,Dynamic,1> sizes(mat.outerSize());
+        for(Index j=0; j<mat.outerSize(); ++j)
+        {
+          Index jp = perm.indices().coeff(j);
+          sizes[((Side==OnTheLeft) ^ Transposed) ? jp : j] = StorageIndex(mat.innerVector(((Side==OnTheRight) ^ Transposed) ? jp : j).nonZeros());
+        }
+        tmp.reserve(sizes);
+        for(Index j=0; j<mat.outerSize(); ++j)
+        {
+          Index jp = perm.indices().coeff(j);
+          Index jsrc = ((Side==OnTheRight) ^ Transposed) ? jp : j;
+          Index jdst = ((Side==OnTheLeft) ^ Transposed) ? jp : j;
+          for(typename MatrixTypeCleaned::InnerIterator it(mat,jsrc); it; ++it)
+            tmp.insertByOuterInner(jdst,it.index()) = it.value();
+        }
+        dst = tmp;
+      }
+      else
+      {
+        SparseMatrix<Scalar,int(SrcStorageOrder)==RowMajor?ColMajor:RowMajor,StorageIndex> tmp(mat.rows(), mat.cols());
+        Matrix<StorageIndex,Dynamic,1> sizes(tmp.outerSize());
+        sizes.setZero();
+        PermutationMatrix<Dynamic,Dynamic,StorageIndex> perm_cpy;
+        if((Side==OnTheLeft) ^ Transposed)
+          perm_cpy = perm;
+        else
+          perm_cpy = perm.transpose();
+
+        for(Index j=0; j<mat.outerSize(); ++j)
+          for(typename MatrixTypeCleaned::InnerIterator it(mat,j); it; ++it)
+            sizes[perm_cpy.indices().coeff(it.index())]++;
+        tmp.reserve(sizes);
+        for(Index j=0; j<mat.outerSize(); ++j)
+          for(typename MatrixTypeCleaned::InnerIterator it(mat,j); it; ++it)
+            tmp.insertByOuterInner(perm_cpy.indices().coeff(it.index()),j) = it.value();
+        dst = tmp;
+      }
+    }
+};
+
+}
+
+namespace internal {
+
+template <int ProductTag> struct product_promote_storage_type<Sparse,             PermutationStorage, ProductTag> { typedef Sparse ret; };
+template <int ProductTag> struct product_promote_storage_type<PermutationStorage, Sparse,             ProductTag> { typedef Sparse ret; };
+
+// TODO, the following two overloads are only needed to define the right temporary type through 
+// typename traits<permutation_sparse_matrix_product<Rhs,Lhs,OnTheRight,false> >::ReturnType
+// whereas it should be correctly handled by traits<Product<> >::PlainObject
+
+template<typename Lhs, typename Rhs, int ProductTag>
+struct product_evaluator<Product<Lhs, Rhs, AliasFreeProduct>, ProductTag, PermutationShape, SparseShape>
+  : public evaluator<typename permutation_matrix_product<Rhs,OnTheLeft,false,SparseShape>::ReturnType>
+{
+  typedef Product<Lhs, Rhs, AliasFreeProduct> XprType;
+  typedef typename permutation_matrix_product<Rhs,OnTheLeft,false,SparseShape>::ReturnType PlainObject;
+  typedef evaluator<PlainObject> Base;
+
+  enum {
+    Flags = Base::Flags | EvalBeforeNestingBit
+  };
+
+  explicit product_evaluator(const XprType& xpr)
+    : m_result(xpr.rows(), xpr.cols())
+  {
+    ::new (static_cast<Base*>(this)) Base(m_result);
+    generic_product_impl<Lhs, Rhs, PermutationShape, SparseShape, ProductTag>::evalTo(m_result, xpr.lhs(), xpr.rhs());
+  }
+
+protected:
+  PlainObject m_result;
+};
+
+template<typename Lhs, typename Rhs, int ProductTag>
+struct product_evaluator<Product<Lhs, Rhs, AliasFreeProduct>, ProductTag, SparseShape, PermutationShape >
+  : public evaluator<typename permutation_matrix_product<Lhs,OnTheRight,false,SparseShape>::ReturnType>
+{
+  typedef Product<Lhs, Rhs, AliasFreeProduct> XprType;
+  typedef typename permutation_matrix_product<Lhs,OnTheRight,false,SparseShape>::ReturnType PlainObject;
+  typedef evaluator<PlainObject> Base;
+
+  enum {
+    Flags = Base::Flags | EvalBeforeNestingBit
+  };
+
+  explicit product_evaluator(const XprType& xpr)
+    : m_result(xpr.rows(), xpr.cols())
+  {
+    ::new (static_cast<Base*>(this)) Base(m_result);
+    generic_product_impl<Lhs, Rhs, SparseShape, PermutationShape, ProductTag>::evalTo(m_result, xpr.lhs(), xpr.rhs());
+  }
+
+protected:
+  PlainObject m_result;
+};
+
+} // end namespace internal
+
+/** \returns the matrix with the permutation applied to the columns
+  */
+template<typename SparseDerived, typename PermDerived>
+inline const Product<SparseDerived, PermDerived, AliasFreeProduct>
+operator*(const SparseMatrixBase<SparseDerived>& matrix, const PermutationBase<PermDerived>& perm)
+{ return Product<SparseDerived, PermDerived, AliasFreeProduct>(matrix.derived(), perm.derived()); }
+
+/** \returns the matrix with the permutation applied to the rows
+  */
+template<typename SparseDerived, typename PermDerived>
+inline const Product<PermDerived, SparseDerived, AliasFreeProduct>
+operator*( const PermutationBase<PermDerived>& perm, const SparseMatrixBase<SparseDerived>& matrix)
+{ return  Product<PermDerived, SparseDerived, AliasFreeProduct>(perm.derived(), matrix.derived()); }
+
+
+/** \returns the matrix with the inverse permutation applied to the columns.
+  */
+template<typename SparseDerived, typename PermutationType>
+inline const Product<SparseDerived, Inverse<PermutationType>, AliasFreeProduct>
+operator*(const SparseMatrixBase<SparseDerived>& matrix, const InverseImpl<PermutationType, PermutationStorage>& tperm)
+{
+  return Product<SparseDerived, Inverse<PermutationType>, AliasFreeProduct>(matrix.derived(), tperm.derived());
+}
+
+/** \returns the matrix with the inverse permutation applied to the rows.
+  */
+template<typename SparseDerived, typename PermutationType>
+inline const Product<Inverse<PermutationType>, SparseDerived, AliasFreeProduct>
+operator*(const InverseImpl<PermutationType,PermutationStorage>& tperm, const SparseMatrixBase<SparseDerived>& matrix)
+{
+  return Product<Inverse<PermutationType>, SparseDerived, AliasFreeProduct>(tperm.derived(), matrix.derived());
+}
+
+} // end namespace Eigen
+
+#endif // EIGEN_SPARSE_SELFADJOINTVIEW_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseProduct.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseProduct.h
new file mode 100644
index 0000000..af8a774
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseProduct.h
@@ -0,0 +1,181 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2008-2015 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_SPARSEPRODUCT_H
+#define EIGEN_SPARSEPRODUCT_H
+
+namespace Eigen { 
+
+/** \returns an expression of the product of two sparse matrices.
+  * By default a conservative product preserving the symbolic non zeros is performed.
+  * The automatic pruning of the small values can be achieved by calling the pruned() function
+  * in which case a totally different product algorithm is employed:
+  * \code
+  * C = (A*B).pruned();             // suppress numerical zeros (exact)
+  * C = (A*B).pruned(ref);
+  * C = (A*B).pruned(ref,epsilon);
+  * \endcode
+  * where \c ref is a meaningful non zero reference value.
+  * */
+template<typename Derived>
+template<typename OtherDerived>
+inline const Product<Derived,OtherDerived,AliasFreeProduct>
+SparseMatrixBase<Derived>::operator*(const SparseMatrixBase<OtherDerived> &other) const
+{
+  return Product<Derived,OtherDerived,AliasFreeProduct>(derived(), other.derived());
+}
+
+namespace internal {
+
+// sparse * sparse
+template<typename Lhs, typename Rhs, int ProductType>
+struct generic_product_impl<Lhs, Rhs, SparseShape, SparseShape, ProductType>
+{
+  template<typename Dest>
+  static void evalTo(Dest& dst, const Lhs& lhs, const Rhs& rhs)
+  {
+    evalTo(dst, lhs, rhs, typename evaluator_traits<Dest>::Shape());
+  }
+
+  // dense += sparse * sparse
+  template<typename Dest,typename ActualLhs>
+  static void addTo(Dest& dst, const ActualLhs& lhs, const Rhs& rhs, typename enable_if<is_same<typename evaluator_traits<Dest>::Shape,DenseShape>::value,int*>::type* = 0)
+  {
+    typedef typename nested_eval<ActualLhs,Dynamic>::type LhsNested;
+    typedef typename nested_eval<Rhs,Dynamic>::type RhsNested;
+    LhsNested lhsNested(lhs);
+    RhsNested rhsNested(rhs);
+    internal::sparse_sparse_to_dense_product_selector<typename remove_all<LhsNested>::type,
+                                                      typename remove_all<RhsNested>::type, Dest>::run(lhsNested,rhsNested,dst);
+  }
+
+  // dense -= sparse * sparse
+  template<typename Dest>
+  static void subTo(Dest& dst, const Lhs& lhs, const Rhs& rhs, typename enable_if<is_same<typename evaluator_traits<Dest>::Shape,DenseShape>::value,int*>::type* = 0)
+  {
+    addTo(dst, -lhs, rhs);
+  }
+
+protected:
+
+  // sparse = sparse * sparse
+  template<typename Dest>
+  static void evalTo(Dest& dst, const Lhs& lhs, const Rhs& rhs, SparseShape)
+  {
+    typedef typename nested_eval<Lhs,Dynamic>::type LhsNested;
+    typedef typename nested_eval<Rhs,Dynamic>::type RhsNested;
+    LhsNested lhsNested(lhs);
+    RhsNested rhsNested(rhs);
+    internal::conservative_sparse_sparse_product_selector<typename remove_all<LhsNested>::type,
+                                                          typename remove_all<RhsNested>::type, Dest>::run(lhsNested,rhsNested,dst);
+  }
+
+  // dense = sparse * sparse
+  template<typename Dest>
+  static void evalTo(Dest& dst, const Lhs& lhs, const Rhs& rhs, DenseShape)
+  {
+    dst.setZero();
+    addTo(dst, lhs, rhs);
+  }
+};
+
+// sparse * sparse-triangular
+template<typename Lhs, typename Rhs, int ProductType>
+struct generic_product_impl<Lhs, Rhs, SparseShape, SparseTriangularShape, ProductType>
+ : public generic_product_impl<Lhs, Rhs, SparseShape, SparseShape, ProductType>
+{};
+
+// sparse-triangular * sparse
+template<typename Lhs, typename Rhs, int ProductType>
+struct generic_product_impl<Lhs, Rhs, SparseTriangularShape, SparseShape, ProductType>
+ : public generic_product_impl<Lhs, Rhs, SparseShape, SparseShape, ProductType>
+{};
+
+// dense = sparse-product (can be sparse*sparse, sparse*perm, etc.)
+template< typename DstXprType, typename Lhs, typename Rhs>
+struct Assignment<DstXprType, Product<Lhs,Rhs,AliasFreeProduct>, internal::assign_op<typename DstXprType::Scalar,typename Product<Lhs,Rhs,AliasFreeProduct>::Scalar>, Sparse2Dense>
+{
+  typedef Product<Lhs,Rhs,AliasFreeProduct> SrcXprType;
+  static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar> &)
+  {
+    Index dstRows = src.rows();
+    Index dstCols = src.cols();
+    if((dst.rows()!=dstRows) || (dst.cols()!=dstCols))
+      dst.resize(dstRows, dstCols);
+    
+    generic_product_impl<Lhs, Rhs>::evalTo(dst,src.lhs(),src.rhs());
+  }
+};
+
+// dense += sparse-product (can be sparse*sparse, sparse*perm, etc.)
+template< typename DstXprType, typename Lhs, typename Rhs>
+struct Assignment<DstXprType, Product<Lhs,Rhs,AliasFreeProduct>, internal::add_assign_op<typename DstXprType::Scalar,typename Product<Lhs,Rhs,AliasFreeProduct>::Scalar>, Sparse2Dense>
+{
+  typedef Product<Lhs,Rhs,AliasFreeProduct> SrcXprType;
+  static void run(DstXprType &dst, const SrcXprType &src, const internal::add_assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar> &)
+  {
+    generic_product_impl<Lhs, Rhs>::addTo(dst,src.lhs(),src.rhs());
+  }
+};
+
+// dense -= sparse-product (can be sparse*sparse, sparse*perm, etc.)
+template< typename DstXprType, typename Lhs, typename Rhs>
+struct Assignment<DstXprType, Product<Lhs,Rhs,AliasFreeProduct>, internal::sub_assign_op<typename DstXprType::Scalar,typename Product<Lhs,Rhs,AliasFreeProduct>::Scalar>, Sparse2Dense>
+{
+  typedef Product<Lhs,Rhs,AliasFreeProduct> SrcXprType;
+  static void run(DstXprType &dst, const SrcXprType &src, const internal::sub_assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar> &)
+  {
+    generic_product_impl<Lhs, Rhs>::subTo(dst,src.lhs(),src.rhs());
+  }
+};
+
+template<typename Lhs, typename Rhs, int Options>
+struct unary_evaluator<SparseView<Product<Lhs, Rhs, Options> >, IteratorBased>
+ : public evaluator<typename Product<Lhs, Rhs, DefaultProduct>::PlainObject>
+{
+  typedef SparseView<Product<Lhs, Rhs, Options> > XprType;
+  typedef typename XprType::PlainObject PlainObject;
+  typedef evaluator<PlainObject> Base;
+
+  explicit unary_evaluator(const XprType& xpr)
+    : m_result(xpr.rows(), xpr.cols())
+  {
+    using std::abs;
+    ::new (static_cast<Base*>(this)) Base(m_result);
+    typedef typename nested_eval<Lhs,Dynamic>::type LhsNested;
+    typedef typename nested_eval<Rhs,Dynamic>::type RhsNested;
+    LhsNested lhsNested(xpr.nestedExpression().lhs());
+    RhsNested rhsNested(xpr.nestedExpression().rhs());
+
+    internal::sparse_sparse_product_with_pruning_selector<typename remove_all<LhsNested>::type,
+                                                          typename remove_all<RhsNested>::type, PlainObject>::run(lhsNested,rhsNested,m_result,
+                                                                                                                  abs(xpr.reference())*xpr.epsilon());
+  }
+
+protected:
+  PlainObject m_result;
+};
+
+} // end namespace internal
+
+// sparse matrix = sparse-product (can be sparse*sparse, sparse*perm, etc.)
+template<typename Scalar, int _Options, typename _StorageIndex>
+template<typename Lhs, typename Rhs>
+SparseMatrix<Scalar,_Options,_StorageIndex>& SparseMatrix<Scalar,_Options,_StorageIndex>::operator=(const Product<Lhs,Rhs,AliasFreeProduct>& src)
+{
+  // std::cout << "in Assignment : " << DstOptions << "\n";
+  SparseMatrix dst(src.rows(),src.cols());
+  internal::generic_product_impl<Lhs, Rhs>::evalTo(dst,src.lhs(),src.rhs());
+  this->swap(dst);
+  return *this;
+}
+
+} // end namespace Eigen
+
+#endif // EIGEN_SPARSEPRODUCT_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseRedux.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseRedux.h
new file mode 100644
index 0000000..4587749
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseRedux.h
@@ -0,0 +1,49 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2008-2014 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_SPARSEREDUX_H
+#define EIGEN_SPARSEREDUX_H
+
+namespace Eigen { 
+
+template<typename Derived>
+typename internal::traits<Derived>::Scalar
+SparseMatrixBase<Derived>::sum() const
+{
+  eigen_assert(rows()>0 && cols()>0 && "you are using a non initialized matrix");
+  Scalar res(0);
+  internal::evaluator<Derived> thisEval(derived());
+  for (Index j=0; j<outerSize(); ++j)
+    for (typename internal::evaluator<Derived>::InnerIterator iter(thisEval,j); iter; ++iter)
+      res += iter.value();
+  return res;
+}
+
+template<typename _Scalar, int _Options, typename _Index>
+typename internal::traits<SparseMatrix<_Scalar,_Options,_Index> >::Scalar
+SparseMatrix<_Scalar,_Options,_Index>::sum() const
+{
+  eigen_assert(rows()>0 && cols()>0 && "you are using a non initialized matrix");
+  if(this->isCompressed())
+    return Matrix<Scalar,1,Dynamic>::Map(m_data.valuePtr(), m_data.size()).sum();
+  else
+    return Base::sum();
+}
+
+template<typename _Scalar, int _Options, typename _Index>
+typename internal::traits<SparseVector<_Scalar,_Options, _Index> >::Scalar
+SparseVector<_Scalar,_Options,_Index>::sum() const
+{
+  eigen_assert(rows()>0 && cols()>0 && "you are using a non initialized matrix");
+  return Matrix<Scalar,1,Dynamic>::Map(m_data.valuePtr(), m_data.size()).sum();
+}
+
+} // end namespace Eigen
+
+#endif // EIGEN_SPARSEREDUX_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseRef.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseRef.h
new file mode 100644
index 0000000..748f87d
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseRef.h
@@ -0,0 +1,397 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2015 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_SPARSE_REF_H
+#define EIGEN_SPARSE_REF_H
+
+namespace Eigen {
+
+enum {
+  StandardCompressedFormat = 2 /**< used by Ref<SparseMatrix> to specify whether the input storage must be in standard compressed form */
+};
+  
+namespace internal {
+
+template<typename Derived> class SparseRefBase;
+
+template<typename MatScalar, int MatOptions, typename MatIndex, int _Options, typename _StrideType>
+struct traits<Ref<SparseMatrix<MatScalar,MatOptions,MatIndex>, _Options, _StrideType> >
+  : public traits<SparseMatrix<MatScalar,MatOptions,MatIndex> >
+{
+  typedef SparseMatrix<MatScalar,MatOptions,MatIndex> PlainObjectType;
+  enum {
+    Options = _Options,
+    Flags = traits<PlainObjectType>::Flags | CompressedAccessBit | NestByRefBit
+  };
+
+  template<typename Derived> struct match {
+    enum {
+      StorageOrderMatch = PlainObjectType::IsVectorAtCompileTime || Derived::IsVectorAtCompileTime || ((PlainObjectType::Flags&RowMajorBit)==(Derived::Flags&RowMajorBit)),
+      MatchAtCompileTime = (Derived::Flags&CompressedAccessBit) && StorageOrderMatch
+    };
+    typedef typename internal::conditional<MatchAtCompileTime,internal::true_type,internal::false_type>::type type;
+  };
+  
+};
+
+template<typename MatScalar, int MatOptions, typename MatIndex, int _Options, typename _StrideType>
+struct traits<Ref<const SparseMatrix<MatScalar,MatOptions,MatIndex>, _Options, _StrideType> >
+  : public traits<Ref<SparseMatrix<MatScalar,MatOptions,MatIndex>, _Options, _StrideType> >
+{
+  enum {
+    Flags = (traits<SparseMatrix<MatScalar,MatOptions,MatIndex> >::Flags | CompressedAccessBit | NestByRefBit) & ~LvalueBit
+  };
+};
+
+template<typename MatScalar, int MatOptions, typename MatIndex, int _Options, typename _StrideType>
+struct traits<Ref<SparseVector<MatScalar,MatOptions,MatIndex>, _Options, _StrideType> >
+  : public traits<SparseVector<MatScalar,MatOptions,MatIndex> >
+{
+  typedef SparseVector<MatScalar,MatOptions,MatIndex> PlainObjectType;
+  enum {
+    Options = _Options,
+    Flags = traits<PlainObjectType>::Flags | CompressedAccessBit | NestByRefBit
+  };
+
+  template<typename Derived> struct match {
+    enum {
+      MatchAtCompileTime = (Derived::Flags&CompressedAccessBit) && Derived::IsVectorAtCompileTime
+    };
+    typedef typename internal::conditional<MatchAtCompileTime,internal::true_type,internal::false_type>::type type;
+  };
+
+};
+
+template<typename MatScalar, int MatOptions, typename MatIndex, int _Options, typename _StrideType>
+struct traits<Ref<const SparseVector<MatScalar,MatOptions,MatIndex>, _Options, _StrideType> >
+  : public traits<Ref<SparseVector<MatScalar,MatOptions,MatIndex>, _Options, _StrideType> >
+{
+  enum {
+    Flags = (traits<SparseVector<MatScalar,MatOptions,MatIndex> >::Flags | CompressedAccessBit | NestByRefBit) & ~LvalueBit
+  };
+};
+
+template<typename Derived>
+struct traits<SparseRefBase<Derived> > : public traits<Derived> {};
+
+template<typename Derived> class SparseRefBase
+  : public SparseMapBase<Derived>
+{
+public:
+
+  typedef SparseMapBase<Derived> Base;
+  EIGEN_SPARSE_PUBLIC_INTERFACE(SparseRefBase)
+
+  SparseRefBase()
+    : Base(RowsAtCompileTime==Dynamic?0:RowsAtCompileTime,ColsAtCompileTime==Dynamic?0:ColsAtCompileTime, 0, 0, 0, 0, 0)
+  {}
+  
+protected:
+
+  template<typename Expression>
+  void construct(Expression& expr)
+  {
+    if(expr.outerIndexPtr()==0)
+      ::new (static_cast<Base*>(this)) Base(expr.size(), expr.nonZeros(), expr.innerIndexPtr(), expr.valuePtr());
+    else
+      ::new (static_cast<Base*>(this)) Base(expr.rows(), expr.cols(), expr.nonZeros(), expr.outerIndexPtr(), expr.innerIndexPtr(), expr.valuePtr(), expr.innerNonZeroPtr());
+  }
+};
+
+} // namespace internal
+
+
+/** 
+  * \ingroup SparseCore_Module
+  *
+  * \brief A sparse matrix expression referencing an existing sparse expression
+  *
+  * \tparam SparseMatrixType the equivalent sparse matrix type of the referenced data, it must be a template instance of class SparseMatrix.
+  * \tparam Options specifies whether the a standard compressed format is required \c Options is  \c #StandardCompressedFormat, or \c 0.
+  *                The default is \c 0.
+  *
+  * \sa class Ref
+  */
+#ifndef EIGEN_PARSED_BY_DOXYGEN
+template<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>
+class Ref<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType >
+  : public internal::SparseRefBase<Ref<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType > >
+#else
+template<typename SparseMatrixType, int Options>
+class Ref<SparseMatrixType, Options>
+  : public SparseMapBase<Derived,WriteAccessors> // yes, that's weird to use Derived here, but that works!
+#endif
+{
+    typedef SparseMatrix<MatScalar,MatOptions,MatIndex> PlainObjectType;
+    typedef internal::traits<Ref> Traits;
+    template<int OtherOptions>
+    inline Ref(const SparseMatrix<MatScalar,OtherOptions,MatIndex>& expr);
+    template<int OtherOptions>
+    inline Ref(const MappedSparseMatrix<MatScalar,OtherOptions,MatIndex>& expr);
+  public:
+
+    typedef internal::SparseRefBase<Ref> Base;
+    EIGEN_SPARSE_PUBLIC_INTERFACE(Ref)
+
+
+    #ifndef EIGEN_PARSED_BY_DOXYGEN
+    template<int OtherOptions>
+    inline Ref(SparseMatrix<MatScalar,OtherOptions,MatIndex>& expr)
+    {
+      EIGEN_STATIC_ASSERT(bool(Traits::template match<SparseMatrix<MatScalar,OtherOptions,MatIndex> >::MatchAtCompileTime), STORAGE_LAYOUT_DOES_NOT_MATCH);
+      eigen_assert( ((Options & int(StandardCompressedFormat))==0) || (expr.isCompressed()) );
+      Base::construct(expr.derived());
+    }
+    
+    template<int OtherOptions>
+    inline Ref(MappedSparseMatrix<MatScalar,OtherOptions,MatIndex>& expr)
+    {
+      EIGEN_STATIC_ASSERT(bool(Traits::template match<SparseMatrix<MatScalar,OtherOptions,MatIndex> >::MatchAtCompileTime), STORAGE_LAYOUT_DOES_NOT_MATCH);
+      eigen_assert( ((Options & int(StandardCompressedFormat))==0) || (expr.isCompressed()) );
+      Base::construct(expr.derived());
+    }
+    
+    template<typename Derived>
+    inline Ref(const SparseCompressedBase<Derived>& expr)
+    #else
+    /** Implicit constructor from any sparse expression (2D matrix or 1D vector) */
+    template<typename Derived>
+    inline Ref(SparseCompressedBase<Derived>& expr)
+    #endif
+    {
+      EIGEN_STATIC_ASSERT(bool(internal::is_lvalue<Derived>::value), THIS_EXPRESSION_IS_NOT_A_LVALUE__IT_IS_READ_ONLY);
+      EIGEN_STATIC_ASSERT(bool(Traits::template match<Derived>::MatchAtCompileTime), STORAGE_LAYOUT_DOES_NOT_MATCH);
+      eigen_assert( ((Options & int(StandardCompressedFormat))==0) || (expr.isCompressed()) );
+      Base::construct(expr.const_cast_derived());
+    }
+};
+
+// this is the const ref version
+template<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>
+class Ref<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType>
+  : public internal::SparseRefBase<Ref<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> >
+{
+    typedef SparseMatrix<MatScalar,MatOptions,MatIndex> TPlainObjectType;
+    typedef internal::traits<Ref> Traits;
+  public:
+
+    typedef internal::SparseRefBase<Ref> Base;
+    EIGEN_SPARSE_PUBLIC_INTERFACE(Ref)
+
+    template<typename Derived>
+    inline Ref(const SparseMatrixBase<Derived>& expr) : m_hasCopy(false)
+    {
+      construct(expr.derived(), typename Traits::template match<Derived>::type());
+    }
+
+    inline Ref(const Ref& other) : Base(other), m_hasCopy(false) {
+      // copy constructor shall not copy the m_object, to avoid unnecessary malloc and copy
+    }
+
+    template<typename OtherRef>
+    inline Ref(const RefBase<OtherRef>& other) : m_hasCopy(false) {
+      construct(other.derived(), typename Traits::template match<OtherRef>::type());
+    }
+
+    ~Ref() {
+      if(m_hasCopy) {
+        TPlainObjectType* obj = reinterpret_cast<TPlainObjectType*>(&m_storage);
+        obj->~TPlainObjectType();
+      }
+    }
+
+  protected:
+
+    template<typename Expression>
+    void construct(const Expression& expr,internal::true_type)
+    {
+      if((Options & int(StandardCompressedFormat)) && (!expr.isCompressed()))
+      {
+        TPlainObjectType* obj = reinterpret_cast<TPlainObjectType*>(&m_storage);
+        ::new (obj) TPlainObjectType(expr);
+        m_hasCopy = true;
+        Base::construct(*obj);
+      }
+      else
+      {
+        Base::construct(expr);
+      }
+    }
+
+    template<typename Expression>
+    void construct(const Expression& expr, internal::false_type)
+    {
+      TPlainObjectType* obj = reinterpret_cast<TPlainObjectType*>(&m_storage);
+      ::new (obj) TPlainObjectType(expr);
+      m_hasCopy = true;
+      Base::construct(*obj);
+    }
+
+  protected:
+    typename internal::aligned_storage<sizeof(TPlainObjectType), EIGEN_ALIGNOF(TPlainObjectType)>::type m_storage;
+    bool m_hasCopy;
+};
+
+
+
+/**
+  * \ingroup SparseCore_Module
+  *
+  * \brief A sparse vector expression referencing an existing sparse vector expression
+  *
+  * \tparam SparseVectorType the equivalent sparse vector type of the referenced data, it must be a template instance of class SparseVector.
+  *
+  * \sa class Ref
+  */
+#ifndef EIGEN_PARSED_BY_DOXYGEN
+template<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>
+class Ref<SparseVector<MatScalar,MatOptions,MatIndex>, Options, StrideType >
+  : public internal::SparseRefBase<Ref<SparseVector<MatScalar,MatOptions,MatIndex>, Options, StrideType > >
+#else
+template<typename SparseVectorType>
+class Ref<SparseVectorType>
+  : public SparseMapBase<Derived,WriteAccessors>
+#endif
+{
+    typedef SparseVector<MatScalar,MatOptions,MatIndex> PlainObjectType;
+    typedef internal::traits<Ref> Traits;
+    template<int OtherOptions>
+    inline Ref(const SparseVector<MatScalar,OtherOptions,MatIndex>& expr);
+  public:
+
+    typedef internal::SparseRefBase<Ref> Base;
+    EIGEN_SPARSE_PUBLIC_INTERFACE(Ref)
+
+    #ifndef EIGEN_PARSED_BY_DOXYGEN
+    template<int OtherOptions>
+    inline Ref(SparseVector<MatScalar,OtherOptions,MatIndex>& expr)
+    {
+      EIGEN_STATIC_ASSERT(bool(Traits::template match<SparseVector<MatScalar,OtherOptions,MatIndex> >::MatchAtCompileTime), STORAGE_LAYOUT_DOES_NOT_MATCH);
+      Base::construct(expr.derived());
+    }
+
+    template<typename Derived>
+    inline Ref(const SparseCompressedBase<Derived>& expr)
+    #else
+    /** Implicit constructor from any 1D sparse vector expression */
+    template<typename Derived>
+    inline Ref(SparseCompressedBase<Derived>& expr)
+    #endif
+    {
+      EIGEN_STATIC_ASSERT(bool(internal::is_lvalue<Derived>::value), THIS_EXPRESSION_IS_NOT_A_LVALUE__IT_IS_READ_ONLY);
+      EIGEN_STATIC_ASSERT(bool(Traits::template match<Derived>::MatchAtCompileTime), STORAGE_LAYOUT_DOES_NOT_MATCH);
+      Base::construct(expr.const_cast_derived());
+    }
+};
+
+// this is the const ref version
+template<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>
+class Ref<const SparseVector<MatScalar,MatOptions,MatIndex>, Options, StrideType>
+  : public internal::SparseRefBase<Ref<const SparseVector<MatScalar,MatOptions,MatIndex>, Options, StrideType> >
+{
+    typedef SparseVector<MatScalar,MatOptions,MatIndex> TPlainObjectType;
+    typedef internal::traits<Ref> Traits;
+  public:
+
+    typedef internal::SparseRefBase<Ref> Base;
+    EIGEN_SPARSE_PUBLIC_INTERFACE(Ref)
+
+    template<typename Derived>
+    inline Ref(const SparseMatrixBase<Derived>& expr) : m_hasCopy(false)
+    {
+      construct(expr.derived(), typename Traits::template match<Derived>::type());
+    }
+
+    inline Ref(const Ref& other) : Base(other), m_hasCopy(false) {
+      // copy constructor shall not copy the m_object, to avoid unnecessary malloc and copy
+    }
+
+    template<typename OtherRef>
+    inline Ref(const RefBase<OtherRef>& other) : m_hasCopy(false) {
+      construct(other.derived(), typename Traits::template match<OtherRef>::type());
+    }
+
+    ~Ref() {
+      if(m_hasCopy) {
+        TPlainObjectType* obj = reinterpret_cast<TPlainObjectType*>(&m_storage);
+        obj->~TPlainObjectType();
+      }
+    }
+
+  protected:
+
+    template<typename Expression>
+    void construct(const Expression& expr,internal::true_type)
+    {
+      Base::construct(expr);
+    }
+
+    template<typename Expression>
+    void construct(const Expression& expr, internal::false_type)
+    {
+      TPlainObjectType* obj = reinterpret_cast<TPlainObjectType*>(&m_storage);
+      ::new (obj) TPlainObjectType(expr);
+      m_hasCopy = true;
+      Base::construct(*obj);
+    }
+
+  protected:
+    typename internal::aligned_storage<sizeof(TPlainObjectType), EIGEN_ALIGNOF(TPlainObjectType)>::type m_storage;
+    bool m_hasCopy;
+};
+
+namespace internal {
+
+// FIXME shall we introduce a general evaluatior_ref that we can specialize for any sparse object once, and thus remove this copy-pasta thing...
+
+template<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>
+struct evaluator<Ref<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> >
+  : evaluator<SparseCompressedBase<Ref<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> > >
+{
+  typedef evaluator<SparseCompressedBase<Ref<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> > > Base;
+  typedef Ref<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> XprType;  
+  evaluator() : Base() {}
+  explicit evaluator(const XprType &mat) : Base(mat) {}
+};
+
+template<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>
+struct evaluator<Ref<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> >
+  : evaluator<SparseCompressedBase<Ref<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> > >
+{
+  typedef evaluator<SparseCompressedBase<Ref<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> > > Base;
+  typedef Ref<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> XprType;  
+  evaluator() : Base() {}
+  explicit evaluator(const XprType &mat) : Base(mat) {}
+};
+
+template<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>
+struct evaluator<Ref<SparseVector<MatScalar,MatOptions,MatIndex>, Options, StrideType> >
+  : evaluator<SparseCompressedBase<Ref<SparseVector<MatScalar,MatOptions,MatIndex>, Options, StrideType> > >
+{
+  typedef evaluator<SparseCompressedBase<Ref<SparseVector<MatScalar,MatOptions,MatIndex>, Options, StrideType> > > Base;
+  typedef Ref<SparseVector<MatScalar,MatOptions,MatIndex>, Options, StrideType> XprType;
+  evaluator() : Base() {}
+  explicit evaluator(const XprType &mat) : Base(mat) {}
+};
+
+template<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>
+struct evaluator<Ref<const SparseVector<MatScalar,MatOptions,MatIndex>, Options, StrideType> >
+  : evaluator<SparseCompressedBase<Ref<const SparseVector<MatScalar,MatOptions,MatIndex>, Options, StrideType> > >
+{
+  typedef evaluator<SparseCompressedBase<Ref<const SparseVector<MatScalar,MatOptions,MatIndex>, Options, StrideType> > > Base;
+  typedef Ref<const SparseVector<MatScalar,MatOptions,MatIndex>, Options, StrideType> XprType;
+  evaluator() : Base() {}
+  explicit evaluator(const XprType &mat) : Base(mat) {}
+};
+
+}
+
+} // end namespace Eigen
+
+#endif // EIGEN_SPARSE_REF_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseSelfAdjointView.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseSelfAdjointView.h
new file mode 100644
index 0000000..85b00e1
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseSelfAdjointView.h
@@ -0,0 +1,659 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2009-2014 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_SPARSE_SELFADJOINTVIEW_H
+#define EIGEN_SPARSE_SELFADJOINTVIEW_H
+
+namespace Eigen { 
+  
+/** \ingroup SparseCore_Module
+  * \class SparseSelfAdjointView
+  *
+  * \brief Pseudo expression to manipulate a triangular sparse matrix as a selfadjoint matrix.
+  *
+  * \param MatrixType the type of the dense matrix storing the coefficients
+  * \param Mode can be either \c #Lower or \c #Upper
+  *
+  * This class is an expression of a sefladjoint matrix from a triangular part of a matrix
+  * with given dense storage of the coefficients. It is the return type of MatrixBase::selfadjointView()
+  * and most of the time this is the only way that it is used.
+  *
+  * \sa SparseMatrixBase::selfadjointView()
+  */
+namespace internal {
+  
+template<typename MatrixType, unsigned int Mode>
+struct traits<SparseSelfAdjointView<MatrixType,Mode> > : traits<MatrixType> {
+};
+
+template<int SrcMode,int DstMode,typename MatrixType,int DestOrder>
+void permute_symm_to_symm(const MatrixType& mat, SparseMatrix<typename MatrixType::Scalar,DestOrder,typename MatrixType::StorageIndex>& _dest, const typename MatrixType::StorageIndex* perm = 0);
+
+template<int Mode,typename MatrixType,int DestOrder>
+void permute_symm_to_fullsymm(const MatrixType& mat, SparseMatrix<typename MatrixType::Scalar,DestOrder,typename MatrixType::StorageIndex>& _dest, const typename MatrixType::StorageIndex* perm = 0);
+
+}
+
+template<typename MatrixType, unsigned int _Mode> class SparseSelfAdjointView
+  : public EigenBase<SparseSelfAdjointView<MatrixType,_Mode> >
+{
+  public:
+    
+    enum {
+      Mode = _Mode,
+      TransposeMode = ((Mode & Upper) ? Lower : 0) | ((Mode & Lower) ? Upper : 0),
+      RowsAtCompileTime = internal::traits<SparseSelfAdjointView>::RowsAtCompileTime,
+      ColsAtCompileTime = internal::traits<SparseSelfAdjointView>::ColsAtCompileTime
+    };
+
+    typedef EigenBase<SparseSelfAdjointView> Base;
+    typedef typename MatrixType::Scalar Scalar;
+    typedef typename MatrixType::StorageIndex StorageIndex;
+    typedef Matrix<StorageIndex,Dynamic,1> VectorI;
+    typedef typename internal::ref_selector<MatrixType>::non_const_type MatrixTypeNested;
+    typedef typename internal::remove_all<MatrixTypeNested>::type _MatrixTypeNested;
+    
+    explicit inline SparseSelfAdjointView(MatrixType& matrix) : m_matrix(matrix)
+    {
+      eigen_assert(rows()==cols() && "SelfAdjointView is only for squared matrices");
+    }
+
+    inline Index rows() const { return m_matrix.rows(); }
+    inline Index cols() const { return m_matrix.cols(); }
+
+    /** \internal \returns a reference to the nested matrix */
+    const _MatrixTypeNested& matrix() const { return m_matrix; }
+    typename internal::remove_reference<MatrixTypeNested>::type& matrix() { return m_matrix; }
+
+    /** \returns an expression of the matrix product between a sparse self-adjoint matrix \c *this and a sparse matrix \a rhs.
+      *
+      * Note that there is no algorithmic advantage of performing such a product compared to a general sparse-sparse matrix product.
+      * Indeed, the SparseSelfadjointView operand is first copied into a temporary SparseMatrix before computing the product.
+      */
+    template<typename OtherDerived>
+    Product<SparseSelfAdjointView, OtherDerived>
+    operator*(const SparseMatrixBase<OtherDerived>& rhs) const
+    {
+      return Product<SparseSelfAdjointView, OtherDerived>(*this, rhs.derived());
+    }
+
+    /** \returns an expression of the matrix product between a sparse matrix \a lhs and a sparse self-adjoint matrix \a rhs.
+      *
+      * Note that there is no algorithmic advantage of performing such a product compared to a general sparse-sparse matrix product.
+      * Indeed, the SparseSelfadjointView operand is first copied into a temporary SparseMatrix before computing the product.
+      */
+    template<typename OtherDerived> friend
+    Product<OtherDerived, SparseSelfAdjointView>
+    operator*(const SparseMatrixBase<OtherDerived>& lhs, const SparseSelfAdjointView& rhs)
+    {
+      return Product<OtherDerived, SparseSelfAdjointView>(lhs.derived(), rhs);
+    }
+    
+    /** Efficient sparse self-adjoint matrix times dense vector/matrix product */
+    template<typename OtherDerived>
+    Product<SparseSelfAdjointView,OtherDerived>
+    operator*(const MatrixBase<OtherDerived>& rhs) const
+    {
+      return Product<SparseSelfAdjointView,OtherDerived>(*this, rhs.derived());
+    }
+
+    /** Efficient dense vector/matrix times sparse self-adjoint matrix product */
+    template<typename OtherDerived> friend
+    Product<OtherDerived,SparseSelfAdjointView>
+    operator*(const MatrixBase<OtherDerived>& lhs, const SparseSelfAdjointView& rhs)
+    {
+      return Product<OtherDerived,SparseSelfAdjointView>(lhs.derived(), rhs);
+    }
+
+    /** Perform a symmetric rank K update of the selfadjoint matrix \c *this:
+      * \f$ this = this + \alpha ( u u^* ) \f$ where \a u is a vector or matrix.
+      *
+      * \returns a reference to \c *this
+      *
+      * To perform \f$ this = this + \alpha ( u^* u ) \f$ you can simply
+      * call this function with u.adjoint().
+      */
+    template<typename DerivedU>
+    SparseSelfAdjointView& rankUpdate(const SparseMatrixBase<DerivedU>& u, const Scalar& alpha = Scalar(1));
+    
+    /** \returns an expression of P H P^-1 */
+    // TODO implement twists in a more evaluator friendly fashion
+    SparseSymmetricPermutationProduct<_MatrixTypeNested,Mode> twistedBy(const PermutationMatrix<Dynamic,Dynamic,StorageIndex>& perm) const
+    {
+      return SparseSymmetricPermutationProduct<_MatrixTypeNested,Mode>(m_matrix, perm);
+    }
+
+    template<typename SrcMatrixType,int SrcMode>
+    SparseSelfAdjointView& operator=(const SparseSymmetricPermutationProduct<SrcMatrixType,SrcMode>& permutedMatrix)
+    {
+      internal::call_assignment_no_alias_no_transpose(*this, permutedMatrix);
+      return *this;
+    }
+
+    SparseSelfAdjointView& operator=(const SparseSelfAdjointView& src)
+    {
+      PermutationMatrix<Dynamic,Dynamic,StorageIndex> pnull;
+      return *this = src.twistedBy(pnull);
+    }
+
+    // Since we override the copy-assignment operator, we need to explicitly re-declare the copy-constructor
+    EIGEN_DEFAULT_COPY_CONSTRUCTOR(SparseSelfAdjointView)
+
+    template<typename SrcMatrixType,unsigned int SrcMode>
+    SparseSelfAdjointView& operator=(const SparseSelfAdjointView<SrcMatrixType,SrcMode>& src)
+    {
+      PermutationMatrix<Dynamic,Dynamic,StorageIndex> pnull;
+      return *this = src.twistedBy(pnull);
+    }
+    
+    void resize(Index rows, Index cols)
+    {
+      EIGEN_ONLY_USED_FOR_DEBUG(rows);
+      EIGEN_ONLY_USED_FOR_DEBUG(cols);
+      eigen_assert(rows == this->rows() && cols == this->cols()
+                && "SparseSelfadjointView::resize() does not actually allow to resize.");
+    }
+    
+  protected:
+
+    MatrixTypeNested m_matrix;
+    //mutable VectorI m_countPerRow;
+    //mutable VectorI m_countPerCol;
+  private:
+    template<typename Dest> void evalTo(Dest &) const;
+};
+
+/***************************************************************************
+* Implementation of SparseMatrixBase methods
+***************************************************************************/
+
+template<typename Derived>
+template<unsigned int UpLo>
+typename SparseMatrixBase<Derived>::template ConstSelfAdjointViewReturnType<UpLo>::Type SparseMatrixBase<Derived>::selfadjointView() const
+{
+  return SparseSelfAdjointView<const Derived, UpLo>(derived());
+}
+
+template<typename Derived>
+template<unsigned int UpLo>
+typename SparseMatrixBase<Derived>::template SelfAdjointViewReturnType<UpLo>::Type SparseMatrixBase<Derived>::selfadjointView()
+{
+  return SparseSelfAdjointView<Derived, UpLo>(derived());
+}
+
+/***************************************************************************
+* Implementation of SparseSelfAdjointView methods
+***************************************************************************/
+
+template<typename MatrixType, unsigned int Mode>
+template<typename DerivedU>
+SparseSelfAdjointView<MatrixType,Mode>&
+SparseSelfAdjointView<MatrixType,Mode>::rankUpdate(const SparseMatrixBase<DerivedU>& u, const Scalar& alpha)
+{
+  SparseMatrix<Scalar,(MatrixType::Flags&RowMajorBit)?RowMajor:ColMajor> tmp = u * u.adjoint();
+  if(alpha==Scalar(0))
+    m_matrix = tmp.template triangularView<Mode>();
+  else
+    m_matrix += alpha * tmp.template triangularView<Mode>();
+
+  return *this;
+}
+
+namespace internal {
+  
+// TODO currently a selfadjoint expression has the form SelfAdjointView<.,.>
+//      in the future selfadjoint-ness should be defined by the expression traits
+//      such that Transpose<SelfAdjointView<.,.> > is valid. (currently TriangularBase::transpose() is overloaded to make it work)
+template<typename MatrixType, unsigned int Mode>
+struct evaluator_traits<SparseSelfAdjointView<MatrixType,Mode> >
+{
+  typedef typename storage_kind_to_evaluator_kind<typename MatrixType::StorageKind>::Kind Kind;
+  typedef SparseSelfAdjointShape Shape;
+};
+
+struct SparseSelfAdjoint2Sparse {};
+
+template<> struct AssignmentKind<SparseShape,SparseSelfAdjointShape> { typedef SparseSelfAdjoint2Sparse Kind; };
+template<> struct AssignmentKind<SparseSelfAdjointShape,SparseShape> { typedef Sparse2Sparse Kind; };
+
+template< typename DstXprType, typename SrcXprType, typename Functor>
+struct Assignment<DstXprType, SrcXprType, Functor, SparseSelfAdjoint2Sparse>
+{
+  typedef typename DstXprType::StorageIndex StorageIndex;
+  typedef internal::assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar> AssignOpType;
+
+  template<typename DestScalar,int StorageOrder>
+  static void run(SparseMatrix<DestScalar,StorageOrder,StorageIndex> &dst, const SrcXprType &src, const AssignOpType&/*func*/)
+  {
+    internal::permute_symm_to_fullsymm<SrcXprType::Mode>(src.matrix(), dst);
+  }
+
+  // FIXME: the handling of += and -= in sparse matrices should be cleanup so that next two overloads could be reduced to:
+  template<typename DestScalar,int StorageOrder,typename AssignFunc>
+  static void run(SparseMatrix<DestScalar,StorageOrder,StorageIndex> &dst, const SrcXprType &src, const AssignFunc& func)
+  {
+    SparseMatrix<DestScalar,StorageOrder,StorageIndex> tmp(src.rows(),src.cols());
+    run(tmp, src, AssignOpType());
+    call_assignment_no_alias_no_transpose(dst, tmp, func);
+  }
+
+  template<typename DestScalar,int StorageOrder>
+  static void run(SparseMatrix<DestScalar,StorageOrder,StorageIndex> &dst, const SrcXprType &src,
+                  const internal::add_assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar>& /* func */)
+  {
+    SparseMatrix<DestScalar,StorageOrder,StorageIndex> tmp(src.rows(),src.cols());
+    run(tmp, src, AssignOpType());
+    dst += tmp;
+  }
+
+  template<typename DestScalar,int StorageOrder>
+  static void run(SparseMatrix<DestScalar,StorageOrder,StorageIndex> &dst, const SrcXprType &src,
+                  const internal::sub_assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar>& /* func */)
+  {
+    SparseMatrix<DestScalar,StorageOrder,StorageIndex> tmp(src.rows(),src.cols());
+    run(tmp, src, AssignOpType());
+    dst -= tmp;
+  }
+  
+  template<typename DestScalar>
+  static void run(DynamicSparseMatrix<DestScalar,ColMajor,StorageIndex>& dst, const SrcXprType &src, const AssignOpType&/*func*/)
+  {
+    // TODO directly evaluate into dst;
+    SparseMatrix<DestScalar,ColMajor,StorageIndex> tmp(dst.rows(),dst.cols());
+    internal::permute_symm_to_fullsymm<SrcXprType::Mode>(src.matrix(), tmp);
+    dst = tmp;
+  }
+};
+
+} // end namespace internal
+
+/***************************************************************************
+* Implementation of sparse self-adjoint time dense matrix
+***************************************************************************/
+
+namespace internal {
+
+template<int Mode, typename SparseLhsType, typename DenseRhsType, typename DenseResType, typename AlphaType>
+inline void sparse_selfadjoint_time_dense_product(const SparseLhsType& lhs, const DenseRhsType& rhs, DenseResType& res, const AlphaType& alpha)
+{
+  EIGEN_ONLY_USED_FOR_DEBUG(alpha);
+  
+  typedef typename internal::nested_eval<SparseLhsType,DenseRhsType::MaxColsAtCompileTime>::type SparseLhsTypeNested;
+  typedef typename internal::remove_all<SparseLhsTypeNested>::type SparseLhsTypeNestedCleaned;
+  typedef evaluator<SparseLhsTypeNestedCleaned> LhsEval;
+  typedef typename LhsEval::InnerIterator LhsIterator;
+  typedef typename SparseLhsType::Scalar LhsScalar;
+  
+  enum {
+    LhsIsRowMajor = (LhsEval::Flags&RowMajorBit)==RowMajorBit,
+    ProcessFirstHalf =
+              ((Mode&(Upper|Lower))==(Upper|Lower))
+          || ( (Mode&Upper) && !LhsIsRowMajor)
+          || ( (Mode&Lower) && LhsIsRowMajor),
+    ProcessSecondHalf = !ProcessFirstHalf
+  };
+  
+  SparseLhsTypeNested lhs_nested(lhs);
+  LhsEval lhsEval(lhs_nested);
+
+  // work on one column at once
+  for (Index k=0; k<rhs.cols(); ++k)
+  {
+    for (Index j=0; j<lhs.outerSize(); ++j)
+    {
+      LhsIterator i(lhsEval,j);
+      // handle diagonal coeff
+      if (ProcessSecondHalf)
+      {
+        while (i && i.index()<j) ++i;
+        if(i && i.index()==j)
+        {
+          res.coeffRef(j,k) += alpha * i.value() * rhs.coeff(j,k);
+          ++i;
+        }
+      }
+
+      // premultiplied rhs for scatters
+      typename ScalarBinaryOpTraits<AlphaType, typename DenseRhsType::Scalar>::ReturnType rhs_j(alpha*rhs(j,k));
+      // accumulator for partial scalar product
+      typename DenseResType::Scalar res_j(0);
+      for(; (ProcessFirstHalf ? i && i.index() < j : i) ; ++i)
+      {
+        LhsScalar lhs_ij = i.value();
+        if(!LhsIsRowMajor) lhs_ij = numext::conj(lhs_ij);
+        res_j += lhs_ij * rhs.coeff(i.index(),k);
+        res(i.index(),k) += numext::conj(lhs_ij) * rhs_j;
+      }
+      res.coeffRef(j,k) += alpha * res_j;
+
+      // handle diagonal coeff
+      if (ProcessFirstHalf && i && (i.index()==j))
+        res.coeffRef(j,k) += alpha * i.value() * rhs.coeff(j,k);
+    }
+  }
+}
+
+
+template<typename LhsView, typename Rhs, int ProductType>
+struct generic_product_impl<LhsView, Rhs, SparseSelfAdjointShape, DenseShape, ProductType>
+: generic_product_impl_base<LhsView, Rhs, generic_product_impl<LhsView, Rhs, SparseSelfAdjointShape, DenseShape, ProductType> >
+{
+  template<typename Dest>
+  static void scaleAndAddTo(Dest& dst, const LhsView& lhsView, const Rhs& rhs, const typename Dest::Scalar& alpha)
+  {
+    typedef typename LhsView::_MatrixTypeNested Lhs;
+    typedef typename nested_eval<Lhs,Dynamic>::type LhsNested;
+    typedef typename nested_eval<Rhs,Dynamic>::type RhsNested;
+    LhsNested lhsNested(lhsView.matrix());
+    RhsNested rhsNested(rhs);
+    
+    internal::sparse_selfadjoint_time_dense_product<LhsView::Mode>(lhsNested, rhsNested, dst, alpha);
+  }
+};
+
+template<typename Lhs, typename RhsView, int ProductType>
+struct generic_product_impl<Lhs, RhsView, DenseShape, SparseSelfAdjointShape, ProductType>
+: generic_product_impl_base<Lhs, RhsView, generic_product_impl<Lhs, RhsView, DenseShape, SparseSelfAdjointShape, ProductType> >
+{
+  template<typename Dest>
+  static void scaleAndAddTo(Dest& dst, const Lhs& lhs, const RhsView& rhsView, const typename Dest::Scalar& alpha)
+  {
+    typedef typename RhsView::_MatrixTypeNested Rhs;
+    typedef typename nested_eval<Lhs,Dynamic>::type LhsNested;
+    typedef typename nested_eval<Rhs,Dynamic>::type RhsNested;
+    LhsNested lhsNested(lhs);
+    RhsNested rhsNested(rhsView.matrix());
+    
+    // transpose everything
+    Transpose<Dest> dstT(dst);
+    internal::sparse_selfadjoint_time_dense_product<RhsView::TransposeMode>(rhsNested.transpose(), lhsNested.transpose(), dstT, alpha);
+  }
+};
+
+// NOTE: these two overloads are needed to evaluate the sparse selfadjoint view into a full sparse matrix
+// TODO: maybe the copy could be handled by generic_product_impl so that these overloads would not be needed anymore
+
+template<typename LhsView, typename Rhs, int ProductTag>
+struct product_evaluator<Product<LhsView, Rhs, DefaultProduct>, ProductTag, SparseSelfAdjointShape, SparseShape>
+  : public evaluator<typename Product<typename Rhs::PlainObject, Rhs, DefaultProduct>::PlainObject>
+{
+  typedef Product<LhsView, Rhs, DefaultProduct> XprType;
+  typedef typename XprType::PlainObject PlainObject;
+  typedef evaluator<PlainObject> Base;
+
+  product_evaluator(const XprType& xpr)
+    : m_lhs(xpr.lhs()), m_result(xpr.rows(), xpr.cols())
+  {
+    ::new (static_cast<Base*>(this)) Base(m_result);
+    generic_product_impl<typename Rhs::PlainObject, Rhs, SparseShape, SparseShape, ProductTag>::evalTo(m_result, m_lhs, xpr.rhs());
+  }
+  
+protected:
+  typename Rhs::PlainObject m_lhs;
+  PlainObject m_result;
+};
+
+template<typename Lhs, typename RhsView, int ProductTag>
+struct product_evaluator<Product<Lhs, RhsView, DefaultProduct>, ProductTag, SparseShape, SparseSelfAdjointShape>
+  : public evaluator<typename Product<Lhs, typename Lhs::PlainObject, DefaultProduct>::PlainObject>
+{
+  typedef Product<Lhs, RhsView, DefaultProduct> XprType;
+  typedef typename XprType::PlainObject PlainObject;
+  typedef evaluator<PlainObject> Base;
+
+  product_evaluator(const XprType& xpr)
+    : m_rhs(xpr.rhs()), m_result(xpr.rows(), xpr.cols())
+  {
+    ::new (static_cast<Base*>(this)) Base(m_result);
+    generic_product_impl<Lhs, typename Lhs::PlainObject, SparseShape, SparseShape, ProductTag>::evalTo(m_result, xpr.lhs(), m_rhs);
+  }
+  
+protected:
+  typename Lhs::PlainObject m_rhs;
+  PlainObject m_result;
+};
+
+} // namespace internal
+
+/***************************************************************************
+* Implementation of symmetric copies and permutations
+***************************************************************************/
+namespace internal {
+
+template<int Mode,typename MatrixType,int DestOrder>
+void permute_symm_to_fullsymm(const MatrixType& mat, SparseMatrix<typename MatrixType::Scalar,DestOrder,typename MatrixType::StorageIndex>& _dest, const typename MatrixType::StorageIndex* perm)
+{
+  typedef typename MatrixType::StorageIndex StorageIndex;
+  typedef typename MatrixType::Scalar Scalar;
+  typedef SparseMatrix<Scalar,DestOrder,StorageIndex> Dest;
+  typedef Matrix<StorageIndex,Dynamic,1> VectorI;
+  typedef evaluator<MatrixType> MatEval;
+  typedef typename evaluator<MatrixType>::InnerIterator MatIterator;
+  
+  MatEval matEval(mat);
+  Dest& dest(_dest.derived());
+  enum {
+    StorageOrderMatch = int(Dest::IsRowMajor) == int(MatrixType::IsRowMajor)
+  };
+  
+  Index size = mat.rows();
+  VectorI count;
+  count.resize(size);
+  count.setZero();
+  dest.resize(size,size);
+  for(Index j = 0; j<size; ++j)
+  {
+    Index jp = perm ? perm[j] : j;
+    for(MatIterator it(matEval,j); it; ++it)
+    {
+      Index i = it.index();
+      Index r = it.row();
+      Index c = it.col();
+      Index ip = perm ? perm[i] : i;
+      if(Mode==int(Upper|Lower))
+        count[StorageOrderMatch ? jp : ip]++;
+      else if(r==c)
+        count[ip]++;
+      else if(( Mode==Lower && r>c) || ( Mode==Upper && r<c))
+      {
+        count[ip]++;
+        count[jp]++;
+      }
+    }
+  }
+  Index nnz = count.sum();
+  
+  // reserve space
+  dest.resizeNonZeros(nnz);
+  dest.outerIndexPtr()[0] = 0;
+  for(Index j=0; j<size; ++j)
+    dest.outerIndexPtr()[j+1] = dest.outerIndexPtr()[j] + count[j];
+  for(Index j=0; j<size; ++j)
+    count[j] = dest.outerIndexPtr()[j];
+  
+  // copy data
+  for(StorageIndex j = 0; j<size; ++j)
+  {
+    for(MatIterator it(matEval,j); it; ++it)
+    {
+      StorageIndex i = internal::convert_index<StorageIndex>(it.index());
+      Index r = it.row();
+      Index c = it.col();
+      
+      StorageIndex jp = perm ? perm[j] : j;
+      StorageIndex ip = perm ? perm[i] : i;
+      
+      if(Mode==int(Upper|Lower))
+      {
+        Index k = count[StorageOrderMatch ? jp : ip]++;
+        dest.innerIndexPtr()[k] = StorageOrderMatch ? ip : jp;
+        dest.valuePtr()[k] = it.value();
+      }
+      else if(r==c)
+      {
+        Index k = count[ip]++;
+        dest.innerIndexPtr()[k] = ip;
+        dest.valuePtr()[k] = it.value();
+      }
+      else if(( (Mode&Lower)==Lower && r>c) || ( (Mode&Upper)==Upper && r<c))
+      {
+        if(!StorageOrderMatch)
+          std::swap(ip,jp);
+        Index k = count[jp]++;
+        dest.innerIndexPtr()[k] = ip;
+        dest.valuePtr()[k] = it.value();
+        k = count[ip]++;
+        dest.innerIndexPtr()[k] = jp;
+        dest.valuePtr()[k] = numext::conj(it.value());
+      }
+    }
+  }
+}
+
+template<int _SrcMode,int _DstMode,typename MatrixType,int DstOrder>
+void permute_symm_to_symm(const MatrixType& mat, SparseMatrix<typename MatrixType::Scalar,DstOrder,typename MatrixType::StorageIndex>& _dest, const typename MatrixType::StorageIndex* perm)
+{
+  typedef typename MatrixType::StorageIndex StorageIndex;
+  typedef typename MatrixType::Scalar Scalar;
+  SparseMatrix<Scalar,DstOrder,StorageIndex>& dest(_dest.derived());
+  typedef Matrix<StorageIndex,Dynamic,1> VectorI;
+  typedef evaluator<MatrixType> MatEval;
+  typedef typename evaluator<MatrixType>::InnerIterator MatIterator;
+
+  enum {
+    SrcOrder = MatrixType::IsRowMajor ? RowMajor : ColMajor,
+    StorageOrderMatch = int(SrcOrder) == int(DstOrder),
+    DstMode = DstOrder==RowMajor ? (_DstMode==Upper ? Lower : Upper) : _DstMode,
+    SrcMode = SrcOrder==RowMajor ? (_SrcMode==Upper ? Lower : Upper) : _SrcMode
+  };
+
+  MatEval matEval(mat);
+  
+  Index size = mat.rows();
+  VectorI count(size);
+  count.setZero();
+  dest.resize(size,size);
+  for(StorageIndex j = 0; j<size; ++j)
+  {
+    StorageIndex jp = perm ? perm[j] : j;
+    for(MatIterator it(matEval,j); it; ++it)
+    {
+      StorageIndex i = it.index();
+      if((int(SrcMode)==int(Lower) && i<j) || (int(SrcMode)==int(Upper) && i>j))
+        continue;
+                  
+      StorageIndex ip = perm ? perm[i] : i;
+      count[int(DstMode)==int(Lower) ? (std::min)(ip,jp) : (std::max)(ip,jp)]++;
+    }
+  }
+  dest.outerIndexPtr()[0] = 0;
+  for(Index j=0; j<size; ++j)
+    dest.outerIndexPtr()[j+1] = dest.outerIndexPtr()[j] + count[j];
+  dest.resizeNonZeros(dest.outerIndexPtr()[size]);
+  for(Index j=0; j<size; ++j)
+    count[j] = dest.outerIndexPtr()[j];
+  
+  for(StorageIndex j = 0; j<size; ++j)
+  {
+    
+    for(MatIterator it(matEval,j); it; ++it)
+    {
+      StorageIndex i = it.index();
+      if((int(SrcMode)==int(Lower) && i<j) || (int(SrcMode)==int(Upper) && i>j))
+        continue;
+                  
+      StorageIndex jp = perm ? perm[j] : j;
+      StorageIndex ip = perm? perm[i] : i;
+      
+      Index k = count[int(DstMode)==int(Lower) ? (std::min)(ip,jp) : (std::max)(ip,jp)]++;
+      dest.innerIndexPtr()[k] = int(DstMode)==int(Lower) ? (std::max)(ip,jp) : (std::min)(ip,jp);
+      
+      if(!StorageOrderMatch) std::swap(ip,jp);
+      if( ((int(DstMode)==int(Lower) && ip<jp) || (int(DstMode)==int(Upper) && ip>jp)))
+        dest.valuePtr()[k] = numext::conj(it.value());
+      else
+        dest.valuePtr()[k] = it.value();
+    }
+  }
+}
+
+}
+
+// TODO implement twists in a more evaluator friendly fashion
+
+namespace internal {
+
+template<typename MatrixType, int Mode>
+struct traits<SparseSymmetricPermutationProduct<MatrixType,Mode> > : traits<MatrixType> {
+};
+
+}
+
+template<typename MatrixType,int Mode>
+class SparseSymmetricPermutationProduct
+  : public EigenBase<SparseSymmetricPermutationProduct<MatrixType,Mode> >
+{
+  public:
+    typedef typename MatrixType::Scalar Scalar;
+    typedef typename MatrixType::StorageIndex StorageIndex;
+    enum {
+      RowsAtCompileTime = internal::traits<SparseSymmetricPermutationProduct>::RowsAtCompileTime,
+      ColsAtCompileTime = internal::traits<SparseSymmetricPermutationProduct>::ColsAtCompileTime
+    };
+  protected:
+    typedef PermutationMatrix<Dynamic,Dynamic,StorageIndex> Perm;
+  public:
+    typedef Matrix<StorageIndex,Dynamic,1> VectorI;
+    typedef typename MatrixType::Nested MatrixTypeNested;
+    typedef typename internal::remove_all<MatrixTypeNested>::type NestedExpression;
+    
+    SparseSymmetricPermutationProduct(const MatrixType& mat, const Perm& perm)
+      : m_matrix(mat), m_perm(perm)
+    {}
+    
+    inline Index rows() const { return m_matrix.rows(); }
+    inline Index cols() const { return m_matrix.cols(); }
+        
+    const NestedExpression& matrix() const { return m_matrix; }
+    const Perm& perm() const { return m_perm; }
+    
+  protected:
+    MatrixTypeNested m_matrix;
+    const Perm& m_perm;
+
+};
+
+namespace internal {
+  
+template<typename DstXprType, typename MatrixType, int Mode, typename Scalar>
+struct Assignment<DstXprType, SparseSymmetricPermutationProduct<MatrixType,Mode>, internal::assign_op<Scalar,typename MatrixType::Scalar>, Sparse2Sparse>
+{
+  typedef SparseSymmetricPermutationProduct<MatrixType,Mode> SrcXprType;
+  typedef typename DstXprType::StorageIndex DstIndex;
+  template<int Options>
+  static void run(SparseMatrix<Scalar,Options,DstIndex> &dst, const SrcXprType &src, const internal::assign_op<Scalar,typename MatrixType::Scalar> &)
+  {
+    // internal::permute_symm_to_fullsymm<Mode>(m_matrix,_dest,m_perm.indices().data());
+    SparseMatrix<Scalar,(Options&RowMajor)==RowMajor ? ColMajor : RowMajor, DstIndex> tmp;
+    internal::permute_symm_to_fullsymm<Mode>(src.matrix(),tmp,src.perm().indices().data());
+    dst = tmp;
+  }
+  
+  template<typename DestType,unsigned int DestMode>
+  static void run(SparseSelfAdjointView<DestType,DestMode>& dst, const SrcXprType &src, const internal::assign_op<Scalar,typename MatrixType::Scalar> &)
+  {
+    internal::permute_symm_to_symm<Mode,DestMode>(src.matrix(),dst.matrix(),src.perm().indices().data());
+  }
+};
+
+} // end namespace internal
+
+} // end namespace Eigen
+
+#endif // EIGEN_SPARSE_SELFADJOINTVIEW_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseSolverBase.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseSolverBase.h
new file mode 100644
index 0000000..b4c9a42
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseSolverBase.h
@@ -0,0 +1,124 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2014 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_SPARSESOLVERBASE_H
+#define EIGEN_SPARSESOLVERBASE_H
+
+namespace Eigen { 
+
+namespace internal {
+
+  /** \internal
+  * Helper functions to solve with a sparse right-hand-side and result.
+  * The rhs is decomposed into small vertical panels which are solved through dense temporaries.
+  */
+template<typename Decomposition, typename Rhs, typename Dest>
+typename enable_if<Rhs::ColsAtCompileTime!=1 && Dest::ColsAtCompileTime!=1>::type
+solve_sparse_through_dense_panels(const Decomposition &dec, const Rhs& rhs, Dest &dest)
+{
+  EIGEN_STATIC_ASSERT((Dest::Flags&RowMajorBit)==0,THIS_METHOD_IS_ONLY_FOR_COLUMN_MAJOR_MATRICES);
+  typedef typename Dest::Scalar DestScalar;
+  // we process the sparse rhs per block of NbColsAtOnce columns temporarily stored into a dense matrix.
+  static const Index NbColsAtOnce = 4;
+  Index rhsCols = rhs.cols();
+  Index size = rhs.rows();
+  // the temporary matrices do not need more columns than NbColsAtOnce:
+  Index tmpCols = (std::min)(rhsCols, NbColsAtOnce); 
+  Eigen::Matrix<DestScalar,Dynamic,Dynamic> tmp(size,tmpCols);
+  Eigen::Matrix<DestScalar,Dynamic,Dynamic> tmpX(size,tmpCols);
+  for(Index k=0; k<rhsCols; k+=NbColsAtOnce)
+  {
+    Index actualCols = std::min<Index>(rhsCols-k, NbColsAtOnce);
+    tmp.leftCols(actualCols) = rhs.middleCols(k,actualCols);
+    tmpX.leftCols(actualCols) = dec.solve(tmp.leftCols(actualCols));
+    dest.middleCols(k,actualCols) = tmpX.leftCols(actualCols).sparseView();
+  }
+}
+
+// Overload for vector as rhs
+template<typename Decomposition, typename Rhs, typename Dest>
+typename enable_if<Rhs::ColsAtCompileTime==1 || Dest::ColsAtCompileTime==1>::type
+solve_sparse_through_dense_panels(const Decomposition &dec, const Rhs& rhs, Dest &dest)
+{
+  typedef typename Dest::Scalar DestScalar;
+  Index size = rhs.rows();
+  Eigen::Matrix<DestScalar,Dynamic,1> rhs_dense(rhs);
+  Eigen::Matrix<DestScalar,Dynamic,1> dest_dense(size);
+  dest_dense = dec.solve(rhs_dense);
+  dest = dest_dense.sparseView();
+}
+
+} // end namespace internal
+
+/** \class SparseSolverBase
+  * \ingroup SparseCore_Module
+  * \brief A base class for sparse solvers
+  *
+  * \tparam Derived the actual type of the solver.
+  *
+  */
+template<typename Derived>
+class SparseSolverBase : internal::noncopyable
+{
+  public:
+
+    /** Default constructor */
+    SparseSolverBase()
+      : m_isInitialized(false)
+    {}
+
+    ~SparseSolverBase()
+    {}
+
+    Derived& derived() { return *static_cast<Derived*>(this); }
+    const Derived& derived() const { return *static_cast<const Derived*>(this); }
+    
+    /** \returns an expression of the solution x of \f$ A x = b \f$ using the current decomposition of A.
+      *
+      * \sa compute()
+      */
+    template<typename Rhs>
+    inline const Solve<Derived, Rhs>
+    solve(const MatrixBase<Rhs>& b) const
+    {
+      eigen_assert(m_isInitialized && "Solver is not initialized.");
+      eigen_assert(derived().rows()==b.rows() && "solve(): invalid number of rows of the right hand side matrix b");
+      return Solve<Derived, Rhs>(derived(), b.derived());
+    }
+    
+    /** \returns an expression of the solution x of \f$ A x = b \f$ using the current decomposition of A.
+      *
+      * \sa compute()
+      */
+    template<typename Rhs>
+    inline const Solve<Derived, Rhs>
+    solve(const SparseMatrixBase<Rhs>& b) const
+    {
+      eigen_assert(m_isInitialized && "Solver is not initialized.");
+      eigen_assert(derived().rows()==b.rows() && "solve(): invalid number of rows of the right hand side matrix b");
+      return Solve<Derived, Rhs>(derived(), b.derived());
+    }
+    
+    #ifndef EIGEN_PARSED_BY_DOXYGEN
+    /** \internal default implementation of solving with a sparse rhs */
+    template<typename Rhs,typename Dest>
+    void _solve_impl(const SparseMatrixBase<Rhs> &b, SparseMatrixBase<Dest> &dest) const
+    {
+      internal::solve_sparse_through_dense_panels(derived(), b.derived(), dest.derived());
+    }
+    #endif // EIGEN_PARSED_BY_DOXYGEN
+
+  protected:
+    
+    mutable bool m_isInitialized;
+};
+
+} // end namespace Eigen
+
+#endif // EIGEN_SPARSESOLVERBASE_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseSparseProductWithPruning.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseSparseProductWithPruning.h
new file mode 100644
index 0000000..88820a4
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseSparseProductWithPruning.h
@@ -0,0 +1,198 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2008-2014 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_SPARSESPARSEPRODUCTWITHPRUNING_H
+#define EIGEN_SPARSESPARSEPRODUCTWITHPRUNING_H
+
+namespace Eigen { 
+
+namespace internal {
+
+
+// perform a pseudo in-place sparse * sparse product assuming all matrices are col major
+template<typename Lhs, typename Rhs, typename ResultType>
+static void sparse_sparse_product_with_pruning_impl(const Lhs& lhs, const Rhs& rhs, ResultType& res, const typename ResultType::RealScalar& tolerance)
+{
+  // return sparse_sparse_product_with_pruning_impl2(lhs,rhs,res);
+
+  typedef typename remove_all<Rhs>::type::Scalar RhsScalar;
+  typedef typename remove_all<ResultType>::type::Scalar ResScalar;
+  typedef typename remove_all<Lhs>::type::StorageIndex StorageIndex;
+
+  // make sure to call innerSize/outerSize since we fake the storage order.
+  Index rows = lhs.innerSize();
+  Index cols = rhs.outerSize();
+  //Index size = lhs.outerSize();
+  eigen_assert(lhs.outerSize() == rhs.innerSize());
+
+  // allocate a temporary buffer
+  AmbiVector<ResScalar,StorageIndex> tempVector(rows);
+
+  // mimics a resizeByInnerOuter:
+  if(ResultType::IsRowMajor)
+    res.resize(cols, rows);
+  else
+    res.resize(rows, cols);
+  
+  evaluator<Lhs> lhsEval(lhs);
+  evaluator<Rhs> rhsEval(rhs);
+  
+  // estimate the number of non zero entries
+  // given a rhs column containing Y non zeros, we assume that the respective Y columns
+  // of the lhs differs in average of one non zeros, thus the number of non zeros for
+  // the product of a rhs column with the lhs is X+Y where X is the average number of non zero
+  // per column of the lhs.
+  // Therefore, we have nnz(lhs*rhs) = nnz(lhs) + nnz(rhs)
+  Index estimated_nnz_prod = lhsEval.nonZerosEstimate() + rhsEval.nonZerosEstimate();
+
+  res.reserve(estimated_nnz_prod);
+  double ratioColRes = double(estimated_nnz_prod)/(double(lhs.rows())*double(rhs.cols()));
+  for (Index j=0; j<cols; ++j)
+  {
+    // FIXME:
+    //double ratioColRes = (double(rhs.innerVector(j).nonZeros()) + double(lhs.nonZeros())/double(lhs.cols()))/double(lhs.rows());
+    // let's do a more accurate determination of the nnz ratio for the current column j of res
+    tempVector.init(ratioColRes);
+    tempVector.setZero();
+    for (typename evaluator<Rhs>::InnerIterator rhsIt(rhsEval, j); rhsIt; ++rhsIt)
+    {
+      // FIXME should be written like this: tmp += rhsIt.value() * lhs.col(rhsIt.index())
+      tempVector.restart();
+      RhsScalar x = rhsIt.value();
+      for (typename evaluator<Lhs>::InnerIterator lhsIt(lhsEval, rhsIt.index()); lhsIt; ++lhsIt)
+      {
+        tempVector.coeffRef(lhsIt.index()) += lhsIt.value() * x;
+      }
+    }
+    res.startVec(j);
+    for (typename AmbiVector<ResScalar,StorageIndex>::Iterator it(tempVector,tolerance); it; ++it)
+      res.insertBackByOuterInner(j,it.index()) = it.value();
+  }
+  res.finalize();
+}
+
+template<typename Lhs, typename Rhs, typename ResultType,
+  int LhsStorageOrder = traits<Lhs>::Flags&RowMajorBit,
+  int RhsStorageOrder = traits<Rhs>::Flags&RowMajorBit,
+  int ResStorageOrder = traits<ResultType>::Flags&RowMajorBit>
+struct sparse_sparse_product_with_pruning_selector;
+
+template<typename Lhs, typename Rhs, typename ResultType>
+struct sparse_sparse_product_with_pruning_selector<Lhs,Rhs,ResultType,ColMajor,ColMajor,ColMajor>
+{
+  typedef typename ResultType::RealScalar RealScalar;
+
+  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res, const RealScalar& tolerance)
+  {
+    typename remove_all<ResultType>::type _res(res.rows(), res.cols());
+    internal::sparse_sparse_product_with_pruning_impl<Lhs,Rhs,ResultType>(lhs, rhs, _res, tolerance);
+    res.swap(_res);
+  }
+};
+
+template<typename Lhs, typename Rhs, typename ResultType>
+struct sparse_sparse_product_with_pruning_selector<Lhs,Rhs,ResultType,ColMajor,ColMajor,RowMajor>
+{
+  typedef typename ResultType::RealScalar RealScalar;
+  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res, const RealScalar& tolerance)
+  {
+    // we need a col-major matrix to hold the result
+    typedef SparseMatrix<typename ResultType::Scalar,ColMajor,typename ResultType::StorageIndex> SparseTemporaryType;
+    SparseTemporaryType _res(res.rows(), res.cols());
+    internal::sparse_sparse_product_with_pruning_impl<Lhs,Rhs,SparseTemporaryType>(lhs, rhs, _res, tolerance);
+    res = _res;
+  }
+};
+
+template<typename Lhs, typename Rhs, typename ResultType>
+struct sparse_sparse_product_with_pruning_selector<Lhs,Rhs,ResultType,RowMajor,RowMajor,RowMajor>
+{
+  typedef typename ResultType::RealScalar RealScalar;
+  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res, const RealScalar& tolerance)
+  {
+    // let's transpose the product to get a column x column product
+    typename remove_all<ResultType>::type _res(res.rows(), res.cols());
+    internal::sparse_sparse_product_with_pruning_impl<Rhs,Lhs,ResultType>(rhs, lhs, _res, tolerance);
+    res.swap(_res);
+  }
+};
+
+template<typename Lhs, typename Rhs, typename ResultType>
+struct sparse_sparse_product_with_pruning_selector<Lhs,Rhs,ResultType,RowMajor,RowMajor,ColMajor>
+{
+  typedef typename ResultType::RealScalar RealScalar;
+  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res, const RealScalar& tolerance)
+  {
+    typedef SparseMatrix<typename Lhs::Scalar,ColMajor,typename Lhs::StorageIndex> ColMajorMatrixLhs;
+    typedef SparseMatrix<typename Rhs::Scalar,ColMajor,typename Lhs::StorageIndex> ColMajorMatrixRhs;
+    ColMajorMatrixLhs colLhs(lhs);
+    ColMajorMatrixRhs colRhs(rhs);
+    internal::sparse_sparse_product_with_pruning_impl<ColMajorMatrixLhs,ColMajorMatrixRhs,ResultType>(colLhs, colRhs, res, tolerance);
+
+    // let's transpose the product to get a column x column product
+//     typedef SparseMatrix<typename ResultType::Scalar> SparseTemporaryType;
+//     SparseTemporaryType _res(res.cols(), res.rows());
+//     sparse_sparse_product_with_pruning_impl<Rhs,Lhs,SparseTemporaryType>(rhs, lhs, _res);
+//     res = _res.transpose();
+  }
+};
+
+template<typename Lhs, typename Rhs, typename ResultType>
+struct sparse_sparse_product_with_pruning_selector<Lhs,Rhs,ResultType,ColMajor,RowMajor,RowMajor>
+{
+  typedef typename ResultType::RealScalar RealScalar;
+  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res, const RealScalar& tolerance)
+  {
+    typedef SparseMatrix<typename Lhs::Scalar,RowMajor,typename Lhs::StorageIndex> RowMajorMatrixLhs;
+    RowMajorMatrixLhs rowLhs(lhs);
+    sparse_sparse_product_with_pruning_selector<RowMajorMatrixLhs,Rhs,ResultType,RowMajor,RowMajor>(rowLhs,rhs,res,tolerance);
+  }
+};
+
+template<typename Lhs, typename Rhs, typename ResultType>
+struct sparse_sparse_product_with_pruning_selector<Lhs,Rhs,ResultType,RowMajor,ColMajor,RowMajor>
+{
+  typedef typename ResultType::RealScalar RealScalar;
+  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res, const RealScalar& tolerance)
+  {
+    typedef SparseMatrix<typename Rhs::Scalar,RowMajor,typename Lhs::StorageIndex> RowMajorMatrixRhs;
+    RowMajorMatrixRhs rowRhs(rhs);
+    sparse_sparse_product_with_pruning_selector<Lhs,RowMajorMatrixRhs,ResultType,RowMajor,RowMajor,RowMajor>(lhs,rowRhs,res,tolerance);
+  }
+};
+
+template<typename Lhs, typename Rhs, typename ResultType>
+struct sparse_sparse_product_with_pruning_selector<Lhs,Rhs,ResultType,ColMajor,RowMajor,ColMajor>
+{
+  typedef typename ResultType::RealScalar RealScalar;
+  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res, const RealScalar& tolerance)
+  {
+    typedef SparseMatrix<typename Rhs::Scalar,ColMajor,typename Lhs::StorageIndex> ColMajorMatrixRhs;
+    ColMajorMatrixRhs colRhs(rhs);
+    internal::sparse_sparse_product_with_pruning_impl<Lhs,ColMajorMatrixRhs,ResultType>(lhs, colRhs, res, tolerance);
+  }
+};
+
+template<typename Lhs, typename Rhs, typename ResultType>
+struct sparse_sparse_product_with_pruning_selector<Lhs,Rhs,ResultType,RowMajor,ColMajor,ColMajor>
+{
+  typedef typename ResultType::RealScalar RealScalar;
+  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res, const RealScalar& tolerance)
+  {
+    typedef SparseMatrix<typename Lhs::Scalar,ColMajor,typename Lhs::StorageIndex> ColMajorMatrixLhs;
+    ColMajorMatrixLhs colLhs(lhs);
+    internal::sparse_sparse_product_with_pruning_impl<ColMajorMatrixLhs,Rhs,ResultType>(colLhs, rhs, res, tolerance);
+  }
+};
+
+} // end namespace internal
+
+} // end namespace Eigen
+
+#endif // EIGEN_SPARSESPARSEPRODUCTWITHPRUNING_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseTranspose.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseTranspose.h
new file mode 100644
index 0000000..3757d4c
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseTranspose.h
@@ -0,0 +1,92 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2008-2015 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_SPARSETRANSPOSE_H
+#define EIGEN_SPARSETRANSPOSE_H
+
+namespace Eigen { 
+
+namespace internal {
+  template<typename MatrixType,int CompressedAccess=int(MatrixType::Flags&CompressedAccessBit)>
+  class SparseTransposeImpl
+    : public SparseMatrixBase<Transpose<MatrixType> >
+  {};
+  
+  template<typename MatrixType>
+  class SparseTransposeImpl<MatrixType,CompressedAccessBit>
+    : public SparseCompressedBase<Transpose<MatrixType> >
+  {
+    typedef SparseCompressedBase<Transpose<MatrixType> > Base;
+  public:
+    using Base::derived;
+    typedef typename Base::Scalar Scalar;
+    typedef typename Base::StorageIndex StorageIndex;
+
+    inline Index nonZeros() const { return derived().nestedExpression().nonZeros(); }
+    
+    inline const Scalar* valuePtr() const { return derived().nestedExpression().valuePtr(); }
+    inline const StorageIndex* innerIndexPtr() const { return derived().nestedExpression().innerIndexPtr(); }
+    inline const StorageIndex* outerIndexPtr() const { return derived().nestedExpression().outerIndexPtr(); }
+    inline const StorageIndex* innerNonZeroPtr() const { return derived().nestedExpression().innerNonZeroPtr(); }
+
+    inline Scalar* valuePtr() { return derived().nestedExpression().valuePtr(); }
+    inline StorageIndex* innerIndexPtr() { return derived().nestedExpression().innerIndexPtr(); }
+    inline StorageIndex* outerIndexPtr() { return derived().nestedExpression().outerIndexPtr(); }
+    inline StorageIndex* innerNonZeroPtr() { return derived().nestedExpression().innerNonZeroPtr(); }
+  };
+}
+  
+template<typename MatrixType> class TransposeImpl<MatrixType,Sparse>
+  : public internal::SparseTransposeImpl<MatrixType>
+{
+  protected:
+    typedef internal::SparseTransposeImpl<MatrixType> Base;
+};
+
+namespace internal {
+  
+template<typename ArgType>
+struct unary_evaluator<Transpose<ArgType>, IteratorBased>
+  : public evaluator_base<Transpose<ArgType> >
+{
+    typedef typename evaluator<ArgType>::InnerIterator        EvalIterator;
+  public:
+    typedef Transpose<ArgType> XprType;
+    
+    inline Index nonZerosEstimate() const {
+      return m_argImpl.nonZerosEstimate();
+    }
+
+    class InnerIterator : public EvalIterator
+    {
+    public:
+      EIGEN_STRONG_INLINE InnerIterator(const unary_evaluator& unaryOp, Index outer)
+        : EvalIterator(unaryOp.m_argImpl,outer)
+      {}
+      
+      Index row() const { return EvalIterator::col(); }
+      Index col() const { return EvalIterator::row(); }
+    };
+    
+    enum {
+      CoeffReadCost = evaluator<ArgType>::CoeffReadCost,
+      Flags = XprType::Flags
+    };
+    
+    explicit unary_evaluator(const XprType& op) :m_argImpl(op.nestedExpression()) {}
+
+  protected:
+    evaluator<ArgType> m_argImpl;
+};
+
+} // end namespace internal
+
+} // end namespace Eigen
+
+#endif // EIGEN_SPARSETRANSPOSE_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseTriangularView.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseTriangularView.h
new file mode 100644
index 0000000..9ac1202
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseTriangularView.h
@@ -0,0 +1,189 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2009-2015 Gael Guennebaud <gael.guennebaud@inria.fr>
+// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_SPARSE_TRIANGULARVIEW_H
+#define EIGEN_SPARSE_TRIANGULARVIEW_H
+
+namespace Eigen {
+
+/** \ingroup SparseCore_Module
+  *
+  * \brief Base class for a triangular part in a \b sparse matrix
+  *
+  * This class is an abstract base class of class TriangularView, and objects of type TriangularViewImpl cannot be instantiated.
+  * It extends class TriangularView with additional methods which are available for sparse expressions only.
+  *
+  * \sa class TriangularView, SparseMatrixBase::triangularView()
+  */
+template<typename MatrixType, unsigned int Mode> class TriangularViewImpl<MatrixType,Mode,Sparse>
+  : public SparseMatrixBase<TriangularView<MatrixType,Mode> >
+{
+    enum { SkipFirst = ((Mode&Lower) && !(MatrixType::Flags&RowMajorBit))
+                    || ((Mode&Upper) &&  (MatrixType::Flags&RowMajorBit)),
+           SkipLast = !SkipFirst,
+           SkipDiag = (Mode&ZeroDiag) ? 1 : 0,
+           HasUnitDiag = (Mode&UnitDiag) ? 1 : 0
+    };
+    
+    typedef TriangularView<MatrixType,Mode> TriangularViewType;
+    
+  protected:
+    // dummy solve function to make TriangularView happy.
+    void solve() const;
+
+    typedef SparseMatrixBase<TriangularViewType> Base;
+  public:
+    
+    EIGEN_SPARSE_PUBLIC_INTERFACE(TriangularViewType)
+    
+    typedef typename MatrixType::Nested MatrixTypeNested;
+    typedef typename internal::remove_reference<MatrixTypeNested>::type MatrixTypeNestedNonRef;
+    typedef typename internal::remove_all<MatrixTypeNested>::type MatrixTypeNestedCleaned;
+
+    template<typename RhsType, typename DstType>
+    EIGEN_DEVICE_FUNC
+    EIGEN_STRONG_INLINE void _solve_impl(const RhsType &rhs, DstType &dst) const {
+      if(!(internal::is_same<RhsType,DstType>::value && internal::extract_data(dst) == internal::extract_data(rhs)))
+        dst = rhs;
+      this->solveInPlace(dst);
+    }
+
+    /** Applies the inverse of \c *this to the dense vector or matrix \a other, "in-place" */
+    template<typename OtherDerived> void solveInPlace(MatrixBase<OtherDerived>& other) const;
+
+    /** Applies the inverse of \c *this to the sparse vector or matrix \a other, "in-place" */
+    template<typename OtherDerived> void solveInPlace(SparseMatrixBase<OtherDerived>& other) const;
+  
+};
+
+namespace internal {
+
+template<typename ArgType, unsigned int Mode>
+struct unary_evaluator<TriangularView<ArgType,Mode>, IteratorBased>
+ : evaluator_base<TriangularView<ArgType,Mode> >
+{
+  typedef TriangularView<ArgType,Mode> XprType;
+  
+protected:
+  
+  typedef typename XprType::Scalar Scalar;
+  typedef typename XprType::StorageIndex StorageIndex;
+  typedef typename evaluator<ArgType>::InnerIterator EvalIterator;
+  
+  enum { SkipFirst = ((Mode&Lower) && !(ArgType::Flags&RowMajorBit))
+                    || ((Mode&Upper) &&  (ArgType::Flags&RowMajorBit)),
+         SkipLast = !SkipFirst,
+         SkipDiag = (Mode&ZeroDiag) ? 1 : 0,
+         HasUnitDiag = (Mode&UnitDiag) ? 1 : 0
+  };
+  
+public:
+  
+  enum {
+    CoeffReadCost = evaluator<ArgType>::CoeffReadCost,
+    Flags = XprType::Flags
+  };
+    
+  explicit unary_evaluator(const XprType &xpr) : m_argImpl(xpr.nestedExpression()), m_arg(xpr.nestedExpression()) {}
+  
+  inline Index nonZerosEstimate() const {
+    return m_argImpl.nonZerosEstimate();
+  }
+  
+  class InnerIterator : public EvalIterator
+  {
+      typedef EvalIterator Base;
+    public:
+
+      EIGEN_STRONG_INLINE InnerIterator(const unary_evaluator& xprEval, Index outer)
+        : Base(xprEval.m_argImpl,outer), m_returnOne(false), m_containsDiag(Base::outer()<xprEval.m_arg.innerSize())
+      {
+        if(SkipFirst)
+        {
+          while((*this) && ((HasUnitDiag||SkipDiag)  ? this->index()<=outer : this->index()<outer))
+            Base::operator++();
+          if(HasUnitDiag)
+            m_returnOne = m_containsDiag;
+        }
+        else if(HasUnitDiag && ((!Base::operator bool()) || Base::index()>=Base::outer()))
+        {
+          if((!SkipFirst) && Base::operator bool())
+            Base::operator++();
+          m_returnOne = m_containsDiag;
+        }
+      }
+
+      EIGEN_STRONG_INLINE InnerIterator& operator++()
+      {
+        if(HasUnitDiag && m_returnOne)
+          m_returnOne = false;
+        else
+        {
+          Base::operator++();
+          if(HasUnitDiag && (!SkipFirst) && ((!Base::operator bool()) || Base::index()>=Base::outer()))
+          {
+            if((!SkipFirst) && Base::operator bool())
+              Base::operator++();
+            m_returnOne = m_containsDiag;
+          }
+        }
+        return *this;
+      }
+      
+      EIGEN_STRONG_INLINE operator bool() const
+      {
+        if(HasUnitDiag && m_returnOne)
+          return true;
+        if(SkipFirst) return  Base::operator bool();
+        else
+        {
+          if (SkipDiag) return (Base::operator bool() && this->index() < this->outer());
+          else return (Base::operator bool() && this->index() <= this->outer());
+        }
+      }
+
+//       inline Index row() const { return (ArgType::Flags&RowMajorBit ? Base::outer() : this->index()); }
+//       inline Index col() const { return (ArgType::Flags&RowMajorBit ? this->index() : Base::outer()); }
+      inline StorageIndex index() const
+      {
+        if(HasUnitDiag && m_returnOne)  return internal::convert_index<StorageIndex>(Base::outer());
+        else                            return Base::index();
+      }
+      inline Scalar value() const
+      {
+        if(HasUnitDiag && m_returnOne)  return Scalar(1);
+        else                            return Base::value();
+      }
+
+    protected:
+      bool m_returnOne;
+      bool m_containsDiag;
+    private:
+      Scalar& valueRef();
+  };
+  
+protected:
+  evaluator<ArgType> m_argImpl;
+  const ArgType& m_arg;
+};
+
+} // end namespace internal
+
+template<typename Derived>
+template<int Mode>
+inline const TriangularView<const Derived, Mode>
+SparseMatrixBase<Derived>::triangularView() const
+{
+  return TriangularView<const Derived, Mode>(derived());
+}
+
+} // end namespace Eigen
+
+#endif // EIGEN_SPARSE_TRIANGULARVIEW_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseUtil.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseUtil.h
new file mode 100644
index 0000000..ceb9368
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseUtil.h
@@ -0,0 +1,186 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2008-2014 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_SPARSEUTIL_H
+#define EIGEN_SPARSEUTIL_H
+
+namespace Eigen { 
+
+#ifdef NDEBUG
+#define EIGEN_DBG_SPARSE(X)
+#else
+#define EIGEN_DBG_SPARSE(X) X
+#endif
+
+#define EIGEN_SPARSE_INHERIT_ASSIGNMENT_OPERATOR(Derived, Op) \
+template<typename OtherDerived> \
+EIGEN_STRONG_INLINE Derived& operator Op(const Eigen::SparseMatrixBase<OtherDerived>& other) \
+{ \
+  return Base::operator Op(other.derived()); \
+} \
+EIGEN_STRONG_INLINE Derived& operator Op(const Derived& other) \
+{ \
+  return Base::operator Op(other); \
+}
+
+#define EIGEN_SPARSE_INHERIT_SCALAR_ASSIGNMENT_OPERATOR(Derived, Op) \
+template<typename Other> \
+EIGEN_STRONG_INLINE Derived& operator Op(const Other& scalar) \
+{ \
+  return Base::operator Op(scalar); \
+}
+
+#define EIGEN_SPARSE_INHERIT_ASSIGNMENT_OPERATORS(Derived) \
+EIGEN_SPARSE_INHERIT_ASSIGNMENT_OPERATOR(Derived, =)
+
+
+#define EIGEN_SPARSE_PUBLIC_INTERFACE(Derived) \
+  EIGEN_GENERIC_PUBLIC_INTERFACE(Derived)
+
+  
+const int CoherentAccessPattern     = 0x1;
+const int InnerRandomAccessPattern  = 0x2 | CoherentAccessPattern;
+const int OuterRandomAccessPattern  = 0x4 | CoherentAccessPattern;
+const int RandomAccessPattern       = 0x8 | OuterRandomAccessPattern | InnerRandomAccessPattern;
+
+template<typename _Scalar, int _Flags = 0, typename _StorageIndex = int>  class SparseMatrix;
+template<typename _Scalar, int _Flags = 0, typename _StorageIndex = int>  class DynamicSparseMatrix;
+template<typename _Scalar, int _Flags = 0, typename _StorageIndex = int>  class SparseVector;
+template<typename _Scalar, int _Flags = 0, typename _StorageIndex = int>  class MappedSparseMatrix;
+
+template<typename MatrixType, unsigned int UpLo>  class SparseSelfAdjointView;
+template<typename Lhs, typename Rhs>              class SparseDiagonalProduct;
+template<typename MatrixType> class SparseView;
+
+template<typename Lhs, typename Rhs>        class SparseSparseProduct;
+template<typename Lhs, typename Rhs>        class SparseTimeDenseProduct;
+template<typename Lhs, typename Rhs>        class DenseTimeSparseProduct;
+template<typename Lhs, typename Rhs, bool Transpose> class SparseDenseOuterProduct;
+
+template<typename Lhs, typename Rhs> struct SparseSparseProductReturnType;
+template<typename Lhs, typename Rhs,
+         int InnerSize = EIGEN_SIZE_MIN_PREFER_FIXED(internal::traits<Lhs>::ColsAtCompileTime,internal::traits<Rhs>::RowsAtCompileTime)> struct DenseSparseProductReturnType;
+         
+template<typename Lhs, typename Rhs,
+         int InnerSize = EIGEN_SIZE_MIN_PREFER_FIXED(internal::traits<Lhs>::ColsAtCompileTime,internal::traits<Rhs>::RowsAtCompileTime)> struct SparseDenseProductReturnType;
+template<typename MatrixType,int UpLo> class SparseSymmetricPermutationProduct;
+
+namespace internal {
+
+template<typename T,int Rows,int Cols,int Flags> struct sparse_eval;
+
+template<typename T> struct eval<T,Sparse>
+  : sparse_eval<T, traits<T>::RowsAtCompileTime,traits<T>::ColsAtCompileTime,traits<T>::Flags>
+{};
+
+template<typename T,int Cols,int Flags> struct sparse_eval<T,1,Cols,Flags> {
+    typedef typename traits<T>::Scalar _Scalar;
+    typedef typename traits<T>::StorageIndex _StorageIndex;
+  public:
+    typedef SparseVector<_Scalar, RowMajor, _StorageIndex> type;
+};
+
+template<typename T,int Rows,int Flags> struct sparse_eval<T,Rows,1,Flags> {
+    typedef typename traits<T>::Scalar _Scalar;
+    typedef typename traits<T>::StorageIndex _StorageIndex;
+  public:
+    typedef SparseVector<_Scalar, ColMajor, _StorageIndex> type;
+};
+
+// TODO this seems almost identical to plain_matrix_type<T, Sparse>
+template<typename T,int Rows,int Cols,int Flags> struct sparse_eval {
+    typedef typename traits<T>::Scalar _Scalar;
+    typedef typename traits<T>::StorageIndex _StorageIndex;
+    enum { _Options = ((Flags&RowMajorBit)==RowMajorBit) ? RowMajor : ColMajor };
+  public:
+    typedef SparseMatrix<_Scalar, _Options, _StorageIndex> type;
+};
+
+template<typename T,int Flags> struct sparse_eval<T,1,1,Flags> {
+    typedef typename traits<T>::Scalar _Scalar;
+  public:
+    typedef Matrix<_Scalar, 1, 1> type;
+};
+
+template<typename T> struct plain_matrix_type<T,Sparse>
+{
+  typedef typename traits<T>::Scalar _Scalar;
+  typedef typename traits<T>::StorageIndex _StorageIndex;
+  enum { _Options = ((evaluator<T>::Flags&RowMajorBit)==RowMajorBit) ? RowMajor : ColMajor };
+  public:
+    typedef SparseMatrix<_Scalar, _Options, _StorageIndex> type;
+};
+
+template<typename T>
+struct plain_object_eval<T,Sparse>
+  : sparse_eval<T, traits<T>::RowsAtCompileTime,traits<T>::ColsAtCompileTime, evaluator<T>::Flags>
+{};
+
+template<typename Decomposition, typename RhsType>
+struct solve_traits<Decomposition,RhsType,Sparse>
+{
+  typedef typename sparse_eval<RhsType, RhsType::RowsAtCompileTime, RhsType::ColsAtCompileTime,traits<RhsType>::Flags>::type PlainObject;
+};
+
+template<typename Derived>
+struct generic_xpr_base<Derived, MatrixXpr, Sparse>
+{
+  typedef SparseMatrixBase<Derived> type;
+};
+
+struct SparseTriangularShape  { static std::string debugName() { return "SparseTriangularShape"; } };
+struct SparseSelfAdjointShape { static std::string debugName() { return "SparseSelfAdjointShape"; } };
+
+template<> struct glue_shapes<SparseShape,SelfAdjointShape> { typedef SparseSelfAdjointShape type;  };
+template<> struct glue_shapes<SparseShape,TriangularShape > { typedef SparseTriangularShape  type;  };
+
+// return type of SparseCompressedBase::lower_bound;
+struct LowerBoundIndex {
+  LowerBoundIndex() : value(-1), found(false) {}
+  LowerBoundIndex(Index val, bool ok) : value(val), found(ok) {}
+  Index value;
+  bool found;
+};
+
+} // end namespace internal
+
+/** \ingroup SparseCore_Module
+  *
+  * \class Triplet
+  *
+  * \brief A small structure to hold a non zero as a triplet (i,j,value).
+  *
+  * \sa SparseMatrix::setFromTriplets()
+  */
+template<typename Scalar, typename StorageIndex=typename SparseMatrix<Scalar>::StorageIndex >
+class Triplet
+{
+public:
+  Triplet() : m_row(0), m_col(0), m_value(0) {}
+
+  Triplet(const StorageIndex& i, const StorageIndex& j, const Scalar& v = Scalar(0))
+    : m_row(i), m_col(j), m_value(v)
+  {}
+
+  /** \returns the row index of the element */
+  const StorageIndex& row() const { return m_row; }
+
+  /** \returns the column index of the element */
+  const StorageIndex& col() const { return m_col; }
+
+  /** \returns the value of the element */
+  const Scalar& value() const { return m_value; }
+protected:
+  StorageIndex m_row, m_col;
+  Scalar m_value;
+};
+
+} // end namespace Eigen
+
+#endif // EIGEN_SPARSEUTIL_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseVector.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseVector.h
new file mode 100644
index 0000000..05779be
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseVector.h
@@ -0,0 +1,478 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2008-2015 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_SPARSEVECTOR_H
+#define EIGEN_SPARSEVECTOR_H
+
+namespace Eigen { 
+
+/** \ingroup SparseCore_Module
+  * \class SparseVector
+  *
+  * \brief a sparse vector class
+  *
+  * \tparam _Scalar the scalar type, i.e. the type of the coefficients
+  *
+  * See http://www.netlib.org/linalg/html_templates/node91.html for details on the storage scheme.
+  *
+  * This class can be extended with the help of the plugin mechanism described on the page
+  * \ref TopicCustomizing_Plugins by defining the preprocessor symbol \c EIGEN_SPARSEVECTOR_PLUGIN.
+  */
+
+namespace internal {
+template<typename _Scalar, int _Options, typename _StorageIndex>
+struct traits<SparseVector<_Scalar, _Options, _StorageIndex> >
+{
+  typedef _Scalar Scalar;
+  typedef _StorageIndex StorageIndex;
+  typedef Sparse StorageKind;
+  typedef MatrixXpr XprKind;
+  enum {
+    IsColVector = (_Options & RowMajorBit) ? 0 : 1,
+
+    RowsAtCompileTime = IsColVector ? Dynamic : 1,
+    ColsAtCompileTime = IsColVector ? 1 : Dynamic,
+    MaxRowsAtCompileTime = RowsAtCompileTime,
+    MaxColsAtCompileTime = ColsAtCompileTime,
+    Flags = _Options | NestByRefBit | LvalueBit | (IsColVector ? 0 : RowMajorBit) | CompressedAccessBit,
+    SupportedAccessPatterns = InnerRandomAccessPattern
+  };
+};
+
+// Sparse-Vector-Assignment kinds:
+enum {
+  SVA_RuntimeSwitch,
+  SVA_Inner,
+  SVA_Outer
+};
+
+template< typename Dest, typename Src,
+          int AssignmentKind = !bool(Src::IsVectorAtCompileTime) ? SVA_RuntimeSwitch
+                             : Src::InnerSizeAtCompileTime==1 ? SVA_Outer
+                             : SVA_Inner>
+struct sparse_vector_assign_selector;
+
+}
+
+template<typename _Scalar, int _Options, typename _StorageIndex>
+class SparseVector
+  : public SparseCompressedBase<SparseVector<_Scalar, _Options, _StorageIndex> >
+{
+    typedef SparseCompressedBase<SparseVector> Base;
+    using Base::convert_index;
+  public:
+    EIGEN_SPARSE_PUBLIC_INTERFACE(SparseVector)
+    EIGEN_SPARSE_INHERIT_ASSIGNMENT_OPERATOR(SparseVector, +=)
+    EIGEN_SPARSE_INHERIT_ASSIGNMENT_OPERATOR(SparseVector, -=)
+    
+    typedef internal::CompressedStorage<Scalar,StorageIndex> Storage;
+    enum { IsColVector = internal::traits<SparseVector>::IsColVector };
+    
+    enum {
+      Options = _Options
+    };
+    
+    EIGEN_STRONG_INLINE Index rows() const { return IsColVector ? m_size : 1; }
+    EIGEN_STRONG_INLINE Index cols() const { return IsColVector ? 1 : m_size; }
+    EIGEN_STRONG_INLINE Index innerSize() const { return m_size; }
+    EIGEN_STRONG_INLINE Index outerSize() const { return 1; }
+
+    EIGEN_STRONG_INLINE const Scalar* valuePtr() const { return m_data.valuePtr(); }
+    EIGEN_STRONG_INLINE Scalar* valuePtr() { return m_data.valuePtr(); }
+
+    EIGEN_STRONG_INLINE const StorageIndex* innerIndexPtr() const { return m_data.indexPtr(); }
+    EIGEN_STRONG_INLINE StorageIndex* innerIndexPtr() { return m_data.indexPtr(); }
+
+    inline const StorageIndex* outerIndexPtr() const { return 0; }
+    inline StorageIndex* outerIndexPtr() { return 0; }
+    inline const StorageIndex* innerNonZeroPtr() const { return 0; }
+    inline StorageIndex* innerNonZeroPtr() { return 0; }
+    
+    /** \internal */
+    inline Storage& data() { return m_data; }
+    /** \internal */
+    inline const Storage& data() const { return m_data; }
+
+    inline Scalar coeff(Index row, Index col) const
+    {
+      eigen_assert(IsColVector ? (col==0 && row>=0 && row<m_size) : (row==0 && col>=0 && col<m_size));
+      return coeff(IsColVector ? row : col);
+    }
+    inline Scalar coeff(Index i) const
+    {
+      eigen_assert(i>=0 && i<m_size);
+      return m_data.at(StorageIndex(i));
+    }
+
+    inline Scalar& coeffRef(Index row, Index col)
+    {
+      eigen_assert(IsColVector ? (col==0 && row>=0 && row<m_size) : (row==0 && col>=0 && col<m_size));
+      return coeffRef(IsColVector ? row : col);
+    }
+
+    /** \returns a reference to the coefficient value at given index \a i
+      * This operation involes a log(rho*size) binary search. If the coefficient does not
+      * exist yet, then a sorted insertion into a sequential buffer is performed.
+      *
+      * This insertion might be very costly if the number of nonzeros above \a i is large.
+      */
+    inline Scalar& coeffRef(Index i)
+    {
+      eigen_assert(i>=0 && i<m_size);
+
+      return m_data.atWithInsertion(StorageIndex(i));
+    }
+
+  public:
+
+    typedef typename Base::InnerIterator InnerIterator;
+    typedef typename Base::ReverseInnerIterator ReverseInnerIterator;
+
+    inline void setZero() { m_data.clear(); }
+
+    /** \returns the number of non zero coefficients */
+    inline Index nonZeros() const  { return m_data.size(); }
+
+    inline void startVec(Index outer)
+    {
+      EIGEN_UNUSED_VARIABLE(outer);
+      eigen_assert(outer==0);
+    }
+
+    inline Scalar& insertBackByOuterInner(Index outer, Index inner)
+    {
+      EIGEN_UNUSED_VARIABLE(outer);
+      eigen_assert(outer==0);
+      return insertBack(inner);
+    }
+    inline Scalar& insertBack(Index i)
+    {
+      m_data.append(0, i);
+      return m_data.value(m_data.size()-1);
+    }
+    
+    Scalar& insertBackByOuterInnerUnordered(Index outer, Index inner)
+    {
+      EIGEN_UNUSED_VARIABLE(outer);
+      eigen_assert(outer==0);
+      return insertBackUnordered(inner);
+    }
+    inline Scalar& insertBackUnordered(Index i)
+    {
+      m_data.append(0, i);
+      return m_data.value(m_data.size()-1);
+    }
+
+    inline Scalar& insert(Index row, Index col)
+    {
+      eigen_assert(IsColVector ? (col==0 && row>=0 && row<m_size) : (row==0 && col>=0 && col<m_size));
+      
+      Index inner = IsColVector ? row : col;
+      Index outer = IsColVector ? col : row;
+      EIGEN_ONLY_USED_FOR_DEBUG(outer);
+      eigen_assert(outer==0);
+      return insert(inner);
+    }
+    Scalar& insert(Index i)
+    {
+      eigen_assert(i>=0 && i<m_size);
+      
+      Index startId = 0;
+      Index p = Index(m_data.size()) - 1;
+      // TODO smart realloc
+      m_data.resize(p+2,1);
+
+      while ( (p >= startId) && (m_data.index(p) > i) )
+      {
+        m_data.index(p+1) = m_data.index(p);
+        m_data.value(p+1) = m_data.value(p);
+        --p;
+      }
+      m_data.index(p+1) = convert_index(i);
+      m_data.value(p+1) = 0;
+      return m_data.value(p+1);
+    }
+
+    /**
+      */
+    inline void reserve(Index reserveSize) { m_data.reserve(reserveSize); }
+
+
+    inline void finalize() {}
+
+    /** \copydoc SparseMatrix::prune(const Scalar&,const RealScalar&) */
+    void prune(const Scalar& reference, const RealScalar& epsilon = NumTraits<RealScalar>::dummy_precision())
+    {
+      m_data.prune(reference,epsilon);
+    }
+
+    /** Resizes the sparse vector to \a rows x \a cols
+      *
+      * This method is provided for compatibility with matrices.
+      * For a column vector, \a cols must be equal to 1.
+      * For a row vector, \a rows must be equal to 1.
+      *
+      * \sa resize(Index)
+      */
+    void resize(Index rows, Index cols)
+    {
+      eigen_assert((IsColVector ? cols : rows)==1 && "Outer dimension must equal 1");
+      resize(IsColVector ? rows : cols);
+    }
+
+    /** Resizes the sparse vector to \a newSize
+      * This method deletes all entries, thus leaving an empty sparse vector
+      *
+      * \sa  conservativeResize(), setZero() */
+    void resize(Index newSize)
+    {
+      m_size = newSize;
+      m_data.clear();
+    }
+
+    /** Resizes the sparse vector to \a newSize, while leaving old values untouched.
+      *
+      * If the size of the vector is decreased, then the storage of the out-of bounds coefficients is kept and reserved.
+      * Call .data().squeeze() to free extra memory.
+      *
+      * \sa reserve(), setZero()
+      */
+    void conservativeResize(Index newSize)
+    {
+      if (newSize < m_size)
+      {
+        Index i = 0;
+        while (i<m_data.size() && m_data.index(i)<newSize) ++i;
+        m_data.resize(i);
+      }
+      m_size = newSize;
+    }
+
+    void resizeNonZeros(Index size) { m_data.resize(size); }
+
+    inline SparseVector() : m_size(0) { check_template_parameters(); resize(0); }
+
+    explicit inline SparseVector(Index size) : m_size(0) { check_template_parameters(); resize(size); }
+
+    inline SparseVector(Index rows, Index cols) : m_size(0) { check_template_parameters(); resize(rows,cols); }
+
+    template<typename OtherDerived>
+    inline SparseVector(const SparseMatrixBase<OtherDerived>& other)
+      : m_size(0)
+    {
+      #ifdef EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN
+        EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN
+      #endif
+      check_template_parameters();
+      *this = other.derived();
+    }
+
+    inline SparseVector(const SparseVector& other)
+      : Base(other), m_size(0)
+    {
+      check_template_parameters();
+      *this = other.derived();
+    }
+
+    /** Swaps the values of \c *this and \a other.
+      * Overloaded for performance: this version performs a \em shallow swap by swapping pointers and attributes only.
+      * \sa SparseMatrixBase::swap()
+      */
+    inline void swap(SparseVector& other)
+    {
+      std::swap(m_size, other.m_size);
+      m_data.swap(other.m_data);
+    }
+
+    template<int OtherOptions>
+    inline void swap(SparseMatrix<Scalar,OtherOptions,StorageIndex>& other)
+    {
+      eigen_assert(other.outerSize()==1);
+      std::swap(m_size, other.m_innerSize);
+      m_data.swap(other.m_data);
+    }
+
+    inline SparseVector& operator=(const SparseVector& other)
+    {
+      if (other.isRValue())
+      {
+        swap(other.const_cast_derived());
+      }
+      else
+      {
+        resize(other.size());
+        m_data = other.m_data;
+      }
+      return *this;
+    }
+
+    template<typename OtherDerived>
+    inline SparseVector& operator=(const SparseMatrixBase<OtherDerived>& other)
+    {
+      SparseVector tmp(other.size());
+      internal::sparse_vector_assign_selector<SparseVector,OtherDerived>::run(tmp,other.derived());
+      this->swap(tmp);
+      return *this;
+    }
+
+    #ifndef EIGEN_PARSED_BY_DOXYGEN
+    template<typename Lhs, typename Rhs>
+    inline SparseVector& operator=(const SparseSparseProduct<Lhs,Rhs>& product)
+    {
+      return Base::operator=(product);
+    }
+    #endif
+
+    friend std::ostream & operator << (std::ostream & s, const SparseVector& m)
+    {
+      for (Index i=0; i<m.nonZeros(); ++i)
+        s << "(" << m.m_data.value(i) << "," << m.m_data.index(i) << ") ";
+      s << std::endl;
+      return s;
+    }
+
+    /** Destructor */
+    inline ~SparseVector() {}
+
+    /** Overloaded for performance */
+    Scalar sum() const;
+
+  public:
+
+    /** \internal \deprecated use setZero() and reserve() */
+    EIGEN_DEPRECATED void startFill(Index reserve)
+    {
+      setZero();
+      m_data.reserve(reserve);
+    }
+
+    /** \internal \deprecated use insertBack(Index,Index) */
+    EIGEN_DEPRECATED Scalar& fill(Index r, Index c)
+    {
+      eigen_assert(r==0 || c==0);
+      return fill(IsColVector ? r : c);
+    }
+
+    /** \internal \deprecated use insertBack(Index) */
+    EIGEN_DEPRECATED Scalar& fill(Index i)
+    {
+      m_data.append(0, i);
+      return m_data.value(m_data.size()-1);
+    }
+
+    /** \internal \deprecated use insert(Index,Index) */
+    EIGEN_DEPRECATED Scalar& fillrand(Index r, Index c)
+    {
+      eigen_assert(r==0 || c==0);
+      return fillrand(IsColVector ? r : c);
+    }
+
+    /** \internal \deprecated use insert(Index) */
+    EIGEN_DEPRECATED Scalar& fillrand(Index i)
+    {
+      return insert(i);
+    }
+
+    /** \internal \deprecated use finalize() */
+    EIGEN_DEPRECATED void endFill() {}
+    
+    // These two functions were here in the 3.1 release, so let's keep them in case some code rely on them.
+    /** \internal \deprecated use data() */
+    EIGEN_DEPRECATED Storage& _data() { return m_data; }
+    /** \internal \deprecated use data() */
+    EIGEN_DEPRECATED const Storage& _data() const { return m_data; }
+    
+#   ifdef EIGEN_SPARSEVECTOR_PLUGIN
+#     include EIGEN_SPARSEVECTOR_PLUGIN
+#   endif
+
+protected:
+  
+    static void check_template_parameters()
+    {
+      EIGEN_STATIC_ASSERT(NumTraits<StorageIndex>::IsSigned,THE_INDEX_TYPE_MUST_BE_A_SIGNED_TYPE);
+      EIGEN_STATIC_ASSERT((_Options&(ColMajor|RowMajor))==Options,INVALID_MATRIX_TEMPLATE_PARAMETERS);
+    }
+    
+    Storage m_data;
+    Index m_size;
+};
+
+namespace internal {
+
+template<typename _Scalar, int _Options, typename _Index>
+struct evaluator<SparseVector<_Scalar,_Options,_Index> >
+  : evaluator_base<SparseVector<_Scalar,_Options,_Index> >
+{
+  typedef SparseVector<_Scalar,_Options,_Index> SparseVectorType;
+  typedef evaluator_base<SparseVectorType> Base;
+  typedef typename SparseVectorType::InnerIterator InnerIterator;
+  typedef typename SparseVectorType::ReverseInnerIterator ReverseInnerIterator;
+  
+  enum {
+    CoeffReadCost = NumTraits<_Scalar>::ReadCost,
+    Flags = SparseVectorType::Flags
+  };
+
+  evaluator() : Base() {}
+  
+  explicit evaluator(const SparseVectorType &mat) : m_matrix(&mat)
+  {
+    EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);
+  }
+  
+  inline Index nonZerosEstimate() const {
+    return m_matrix->nonZeros();
+  }
+  
+  operator SparseVectorType&() { return m_matrix->const_cast_derived(); }
+  operator const SparseVectorType&() const { return *m_matrix; }
+  
+  const SparseVectorType *m_matrix;
+};
+
+template< typename Dest, typename Src>
+struct sparse_vector_assign_selector<Dest,Src,SVA_Inner> {
+  static void run(Dest& dst, const Src& src) {
+    eigen_internal_assert(src.innerSize()==src.size());
+    typedef internal::evaluator<Src> SrcEvaluatorType;
+    SrcEvaluatorType srcEval(src);
+    for(typename SrcEvaluatorType::InnerIterator it(srcEval, 0); it; ++it)
+      dst.insert(it.index()) = it.value();
+  }
+};
+
+template< typename Dest, typename Src>
+struct sparse_vector_assign_selector<Dest,Src,SVA_Outer> {
+  static void run(Dest& dst, const Src& src) {
+    eigen_internal_assert(src.outerSize()==src.size());
+    typedef internal::evaluator<Src> SrcEvaluatorType;
+    SrcEvaluatorType srcEval(src);
+    for(Index i=0; i<src.size(); ++i)
+    {
+      typename SrcEvaluatorType::InnerIterator it(srcEval, i);
+      if(it)
+        dst.insert(i) = it.value();
+    }
+  }
+};
+
+template< typename Dest, typename Src>
+struct sparse_vector_assign_selector<Dest,Src,SVA_RuntimeSwitch> {
+  static void run(Dest& dst, const Src& src) {
+    if(src.outerSize()==1)  sparse_vector_assign_selector<Dest,Src,SVA_Inner>::run(dst, src);
+    else                    sparse_vector_assign_selector<Dest,Src,SVA_Outer>::run(dst, src);
+  }
+};
+
+}
+
+} // end namespace Eigen
+
+#endif // EIGEN_SPARSEVECTOR_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseView.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseView.h
new file mode 100644
index 0000000..92b3d1f
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/SparseView.h
@@ -0,0 +1,254 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2011-2014 Gael Guennebaud <gael.guennebaud@inria.fr>
+// Copyright (C) 2010 Daniel Lowengrub <lowdanie@gmail.com>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_SPARSEVIEW_H
+#define EIGEN_SPARSEVIEW_H
+
+namespace Eigen { 
+
+namespace internal {
+
+template<typename MatrixType>
+struct traits<SparseView<MatrixType> > : traits<MatrixType>
+{
+  typedef typename MatrixType::StorageIndex StorageIndex;
+  typedef Sparse StorageKind;
+  enum {
+    Flags = int(traits<MatrixType>::Flags) & (RowMajorBit)
+  };
+};
+
+} // end namespace internal
+
+/** \ingroup SparseCore_Module
+  * \class SparseView
+  *
+  * \brief Expression of a dense or sparse matrix with zero or too small values removed
+  *
+  * \tparam MatrixType the type of the object of which we are removing the small entries
+  *
+  * This class represents an expression of a given dense or sparse matrix with
+  * entries smaller than \c reference * \c epsilon are removed.
+  * It is the return type of MatrixBase::sparseView() and SparseMatrixBase::pruned()
+  * and most of the time this is the only way it is used.
+  *
+  * \sa MatrixBase::sparseView(), SparseMatrixBase::pruned()
+  */
+template<typename MatrixType>
+class SparseView : public SparseMatrixBase<SparseView<MatrixType> >
+{
+  typedef typename MatrixType::Nested MatrixTypeNested;
+  typedef typename internal::remove_all<MatrixTypeNested>::type _MatrixTypeNested;
+  typedef SparseMatrixBase<SparseView > Base;
+public:
+  EIGEN_SPARSE_PUBLIC_INTERFACE(SparseView)
+  typedef typename internal::remove_all<MatrixType>::type NestedExpression;
+
+  explicit SparseView(const MatrixType& mat, const Scalar& reference = Scalar(0),
+                      const RealScalar &epsilon = NumTraits<Scalar>::dummy_precision())
+    : m_matrix(mat), m_reference(reference), m_epsilon(epsilon) {}
+
+  inline Index rows() const { return m_matrix.rows(); }
+  inline Index cols() const { return m_matrix.cols(); }
+
+  inline Index innerSize() const { return m_matrix.innerSize(); }
+  inline Index outerSize() const { return m_matrix.outerSize(); }
+  
+  /** \returns the nested expression */
+  const typename internal::remove_all<MatrixTypeNested>::type&
+  nestedExpression() const { return m_matrix; }
+  
+  Scalar reference() const { return m_reference; }
+  RealScalar epsilon() const { return m_epsilon; }
+  
+protected:
+  MatrixTypeNested m_matrix;
+  Scalar m_reference;
+  RealScalar m_epsilon;
+};
+
+namespace internal {
+
+// TODO find a way to unify the two following variants
+// This is tricky because implementing an inner iterator on top of an IndexBased evaluator is
+// not easy because the evaluators do not expose the sizes of the underlying expression.
+  
+template<typename ArgType>
+struct unary_evaluator<SparseView<ArgType>, IteratorBased>
+  : public evaluator_base<SparseView<ArgType> >
+{
+    typedef typename evaluator<ArgType>::InnerIterator EvalIterator;
+  public:
+    typedef SparseView<ArgType> XprType;
+    
+    class InnerIterator : public EvalIterator
+    {
+      protected:
+        typedef typename XprType::Scalar Scalar;
+      public:
+
+        EIGEN_STRONG_INLINE InnerIterator(const unary_evaluator& sve, Index outer)
+          : EvalIterator(sve.m_argImpl,outer), m_view(sve.m_view)
+        {
+          incrementToNonZero();
+        }
+
+        EIGEN_STRONG_INLINE InnerIterator& operator++()
+        {
+          EvalIterator::operator++();
+          incrementToNonZero();
+          return *this;
+        }
+
+        using EvalIterator::value;
+
+      protected:
+        const XprType &m_view;
+
+      private:
+        void incrementToNonZero()
+        {
+          while((bool(*this)) && internal::isMuchSmallerThan(value(), m_view.reference(), m_view.epsilon()))
+          {
+            EvalIterator::operator++();
+          }
+        }
+    };
+    
+    enum {
+      CoeffReadCost = evaluator<ArgType>::CoeffReadCost,
+      Flags = XprType::Flags
+    };
+    
+    explicit unary_evaluator(const XprType& xpr) : m_argImpl(xpr.nestedExpression()), m_view(xpr) {}
+
+  protected:
+    evaluator<ArgType> m_argImpl;
+    const XprType &m_view;
+};
+
+template<typename ArgType>
+struct unary_evaluator<SparseView<ArgType>, IndexBased>
+  : public evaluator_base<SparseView<ArgType> >
+{
+  public:
+    typedef SparseView<ArgType> XprType;
+  protected:
+    enum { IsRowMajor = (XprType::Flags&RowMajorBit)==RowMajorBit };
+    typedef typename XprType::Scalar Scalar;
+    typedef typename XprType::StorageIndex StorageIndex;
+  public:
+    
+    class InnerIterator
+    {
+      public:
+
+        EIGEN_STRONG_INLINE InnerIterator(const unary_evaluator& sve, Index outer)
+          : m_sve(sve), m_inner(0), m_outer(outer), m_end(sve.m_view.innerSize())
+        {
+          incrementToNonZero();
+        }
+
+        EIGEN_STRONG_INLINE InnerIterator& operator++()
+        {
+          m_inner++;
+          incrementToNonZero();
+          return *this;
+        }
+
+        EIGEN_STRONG_INLINE Scalar value() const
+        {
+          return (IsRowMajor) ? m_sve.m_argImpl.coeff(m_outer, m_inner)
+                              : m_sve.m_argImpl.coeff(m_inner, m_outer);
+        }
+
+        EIGEN_STRONG_INLINE StorageIndex index() const { return m_inner; }
+        inline Index row() const { return IsRowMajor ? m_outer : index(); }
+        inline Index col() const { return IsRowMajor ? index() : m_outer; }
+
+        EIGEN_STRONG_INLINE operator bool() const { return m_inner < m_end && m_inner>=0; }
+
+      protected:
+        const unary_evaluator &m_sve;
+        Index m_inner;
+        const Index m_outer;
+        const Index m_end;
+
+      private:
+        void incrementToNonZero()
+        {
+          while((bool(*this)) && internal::isMuchSmallerThan(value(), m_sve.m_view.reference(), m_sve.m_view.epsilon()))
+          {
+            m_inner++;
+          }
+        }
+    };
+    
+    enum {
+      CoeffReadCost = evaluator<ArgType>::CoeffReadCost,
+      Flags = XprType::Flags
+    };
+    
+    explicit unary_evaluator(const XprType& xpr) : m_argImpl(xpr.nestedExpression()), m_view(xpr) {}
+
+  protected:
+    evaluator<ArgType> m_argImpl;
+    const XprType &m_view;
+};
+
+} // end namespace internal
+
+/** \ingroup SparseCore_Module
+  *
+  * \returns a sparse expression of the dense expression \c *this with values smaller than
+  * \a reference * \a epsilon removed.
+  *
+  * This method is typically used when prototyping to convert a quickly assembled dense Matrix \c D to a SparseMatrix \c S:
+  * \code
+  * MatrixXd D(n,m);
+  * SparseMatrix<double> S;
+  * S = D.sparseView();             // suppress numerical zeros (exact)
+  * S = D.sparseView(reference);
+  * S = D.sparseView(reference,epsilon);
+  * \endcode
+  * where \a reference is a meaningful non zero reference value,
+  * and \a epsilon is a tolerance factor defaulting to NumTraits<Scalar>::dummy_precision().
+  *
+  * \sa SparseMatrixBase::pruned(), class SparseView */
+template<typename Derived>
+const SparseView<Derived> MatrixBase<Derived>::sparseView(const Scalar& reference,
+                                                          const typename NumTraits<Scalar>::Real& epsilon) const
+{
+  return SparseView<Derived>(derived(), reference, epsilon);
+}
+
+/** \returns an expression of \c *this with values smaller than
+  * \a reference * \a epsilon removed.
+  *
+  * This method is typically used in conjunction with the product of two sparse matrices
+  * to automatically prune the smallest values as follows:
+  * \code
+  * C = (A*B).pruned();             // suppress numerical zeros (exact)
+  * C = (A*B).pruned(ref);
+  * C = (A*B).pruned(ref,epsilon);
+  * \endcode
+  * where \c ref is a meaningful non zero reference value.
+  * */
+template<typename Derived>
+const SparseView<Derived>
+SparseMatrixBase<Derived>::pruned(const Scalar& reference,
+                                  const RealScalar& epsilon) const
+{
+  return SparseView<Derived>(derived(), reference, epsilon);
+}
+
+} // end namespace Eigen
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/TriangularSolver.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/TriangularSolver.h
new file mode 100644
index 0000000..f9c56ba
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseCore/TriangularSolver.h
@@ -0,0 +1,315 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_SPARSETRIANGULARSOLVER_H
+#define EIGEN_SPARSETRIANGULARSOLVER_H
+
+namespace Eigen { 
+
+namespace internal {
+
+template<typename Lhs, typename Rhs, int Mode,
+  int UpLo = (Mode & Lower)
+           ? Lower
+           : (Mode & Upper)
+           ? Upper
+           : -1,
+  int StorageOrder = int(traits<Lhs>::Flags) & RowMajorBit>
+struct sparse_solve_triangular_selector;
+
+// forward substitution, row-major
+template<typename Lhs, typename Rhs, int Mode>
+struct sparse_solve_triangular_selector<Lhs,Rhs,Mode,Lower,RowMajor>
+{
+  typedef typename Rhs::Scalar Scalar;
+  typedef evaluator<Lhs> LhsEval;
+  typedef typename evaluator<Lhs>::InnerIterator LhsIterator;
+  static void run(const Lhs& lhs, Rhs& other)
+  {
+    LhsEval lhsEval(lhs);
+    for(Index col=0 ; col<other.cols() ; ++col)
+    {
+      for(Index i=0; i<lhs.rows(); ++i)
+      {
+        Scalar tmp = other.coeff(i,col);
+        Scalar lastVal(0);
+        Index lastIndex = 0;
+        for(LhsIterator it(lhsEval, i); it; ++it)
+        {
+          lastVal = it.value();
+          lastIndex = it.index();
+          if(lastIndex==i)
+            break;
+          tmp -= lastVal * other.coeff(lastIndex,col);
+        }
+        if (Mode & UnitDiag)
+          other.coeffRef(i,col) = tmp;
+        else
+        {
+          eigen_assert(lastIndex==i);
+          other.coeffRef(i,col) = tmp/lastVal;
+        }
+      }
+    }
+  }
+};
+
+// backward substitution, row-major
+template<typename Lhs, typename Rhs, int Mode>
+struct sparse_solve_triangular_selector<Lhs,Rhs,Mode,Upper,RowMajor>
+{
+  typedef typename Rhs::Scalar Scalar;
+  typedef evaluator<Lhs> LhsEval;
+  typedef typename evaluator<Lhs>::InnerIterator LhsIterator;
+  static void run(const Lhs& lhs, Rhs& other)
+  {
+    LhsEval lhsEval(lhs);
+    for(Index col=0 ; col<other.cols() ; ++col)
+    {
+      for(Index i=lhs.rows()-1 ; i>=0 ; --i)
+      {
+        Scalar tmp = other.coeff(i,col);
+        Scalar l_ii(0);
+        LhsIterator it(lhsEval, i);
+        while(it && it.index()<i)
+          ++it;
+        if(!(Mode & UnitDiag))
+        {
+          eigen_assert(it && it.index()==i);
+          l_ii = it.value();
+          ++it;
+        }
+        else if (it && it.index() == i)
+          ++it;
+        for(; it; ++it)
+        {
+          tmp -= it.value() * other.coeff(it.index(),col);
+        }
+
+        if (Mode & UnitDiag)  other.coeffRef(i,col) = tmp;
+        else                  other.coeffRef(i,col) = tmp/l_ii;
+      }
+    }
+  }
+};
+
+// forward substitution, col-major
+template<typename Lhs, typename Rhs, int Mode>
+struct sparse_solve_triangular_selector<Lhs,Rhs,Mode,Lower,ColMajor>
+{
+  typedef typename Rhs::Scalar Scalar;
+  typedef evaluator<Lhs> LhsEval;
+  typedef typename evaluator<Lhs>::InnerIterator LhsIterator;
+  static void run(const Lhs& lhs, Rhs& other)
+  {
+    LhsEval lhsEval(lhs);
+    for(Index col=0 ; col<other.cols() ; ++col)
+    {
+      for(Index i=0; i<lhs.cols(); ++i)
+      {
+        Scalar& tmp = other.coeffRef(i,col);
+        if (tmp!=Scalar(0)) // optimization when other is actually sparse
+        {
+          LhsIterator it(lhsEval, i);
+          while(it && it.index()<i)
+            ++it;
+          if(!(Mode & UnitDiag))
+          {
+            eigen_assert(it && it.index()==i);
+            tmp /= it.value();
+          }
+          if (it && it.index()==i)
+            ++it;
+          for(; it; ++it)
+            other.coeffRef(it.index(), col) -= tmp * it.value();
+        }
+      }
+    }
+  }
+};
+
+// backward substitution, col-major
+template<typename Lhs, typename Rhs, int Mode>
+struct sparse_solve_triangular_selector<Lhs,Rhs,Mode,Upper,ColMajor>
+{
+  typedef typename Rhs::Scalar Scalar;
+  typedef evaluator<Lhs> LhsEval;
+  typedef typename evaluator<Lhs>::InnerIterator LhsIterator;
+  static void run(const Lhs& lhs, Rhs& other)
+  {
+    LhsEval lhsEval(lhs);
+    for(Index col=0 ; col<other.cols() ; ++col)
+    {
+      for(Index i=lhs.cols()-1; i>=0; --i)
+      {
+        Scalar& tmp = other.coeffRef(i,col);
+        if (tmp!=Scalar(0)) // optimization when other is actually sparse
+        {
+          if(!(Mode & UnitDiag))
+          {
+            // TODO replace this by a binary search. make sure the binary search is safe for partially sorted elements
+            LhsIterator it(lhsEval, i);
+            while(it && it.index()!=i)
+              ++it;
+            eigen_assert(it && it.index()==i);
+            other.coeffRef(i,col) /= it.value();
+          }
+          LhsIterator it(lhsEval, i);
+          for(; it && it.index()<i; ++it)
+            other.coeffRef(it.index(), col) -= tmp * it.value();
+        }
+      }
+    }
+  }
+};
+
+} // end namespace internal
+
+#ifndef EIGEN_PARSED_BY_DOXYGEN
+
+template<typename ExpressionType,unsigned int Mode>
+template<typename OtherDerived>
+void TriangularViewImpl<ExpressionType,Mode,Sparse>::solveInPlace(MatrixBase<OtherDerived>& other) const
+{
+  eigen_assert(derived().cols() == derived().rows() && derived().cols() == other.rows());
+  eigen_assert((!(Mode & ZeroDiag)) && bool(Mode & (Upper|Lower)));
+
+  enum { copy = internal::traits<OtherDerived>::Flags & RowMajorBit };
+
+  typedef typename internal::conditional<copy,
+    typename internal::plain_matrix_type_column_major<OtherDerived>::type, OtherDerived&>::type OtherCopy;
+  OtherCopy otherCopy(other.derived());
+
+  internal::sparse_solve_triangular_selector<ExpressionType, typename internal::remove_reference<OtherCopy>::type, Mode>::run(derived().nestedExpression(), otherCopy);
+
+  if (copy)
+    other = otherCopy;
+}
+#endif
+
+// pure sparse path
+
+namespace internal {
+
+template<typename Lhs, typename Rhs, int Mode,
+  int UpLo = (Mode & Lower)
+           ? Lower
+           : (Mode & Upper)
+           ? Upper
+           : -1,
+  int StorageOrder = int(Lhs::Flags) & (RowMajorBit)>
+struct sparse_solve_triangular_sparse_selector;
+
+// forward substitution, col-major
+template<typename Lhs, typename Rhs, int Mode, int UpLo>
+struct sparse_solve_triangular_sparse_selector<Lhs,Rhs,Mode,UpLo,ColMajor>
+{
+  typedef typename Rhs::Scalar Scalar;
+  typedef typename promote_index_type<typename traits<Lhs>::StorageIndex,
+                                      typename traits<Rhs>::StorageIndex>::type StorageIndex;
+  static void run(const Lhs& lhs, Rhs& other)
+  {
+    const bool IsLower = (UpLo==Lower);
+    AmbiVector<Scalar,StorageIndex> tempVector(other.rows()*2);
+    tempVector.setBounds(0,other.rows());
+
+    Rhs res(other.rows(), other.cols());
+    res.reserve(other.nonZeros());
+
+    for(Index col=0 ; col<other.cols() ; ++col)
+    {
+      // FIXME estimate number of non zeros
+      tempVector.init(.99/*float(other.col(col).nonZeros())/float(other.rows())*/);
+      tempVector.setZero();
+      tempVector.restart();
+      for (typename Rhs::InnerIterator rhsIt(other, col); rhsIt; ++rhsIt)
+      {
+        tempVector.coeffRef(rhsIt.index()) = rhsIt.value();
+      }
+
+      for(Index i=IsLower?0:lhs.cols()-1;
+          IsLower?i<lhs.cols():i>=0;
+          i+=IsLower?1:-1)
+      {
+        tempVector.restart();
+        Scalar& ci = tempVector.coeffRef(i);
+        if (ci!=Scalar(0))
+        {
+          // find
+          typename Lhs::InnerIterator it(lhs, i);
+          if(!(Mode & UnitDiag))
+          {
+            if (IsLower)
+            {
+              eigen_assert(it.index()==i);
+              ci /= it.value();
+            }
+            else
+              ci /= lhs.coeff(i,i);
+          }
+          tempVector.restart();
+          if (IsLower)
+          {
+            if (it.index()==i)
+              ++it;
+            for(; it; ++it)
+              tempVector.coeffRef(it.index()) -= ci * it.value();
+          }
+          else
+          {
+            for(; it && it.index()<i; ++it)
+              tempVector.coeffRef(it.index()) -= ci * it.value();
+          }
+        }
+      }
+
+
+      Index count = 0;
+      // FIXME compute a reference value to filter zeros
+      for (typename AmbiVector<Scalar,StorageIndex>::Iterator it(tempVector/*,1e-12*/); it; ++it)
+      {
+        ++ count;
+//         std::cerr << "fill " << it.index() << ", " << col << "\n";
+//         std::cout << it.value() << "  ";
+        // FIXME use insertBack
+        res.insert(it.index(), col) = it.value();
+      }
+//       std::cout << "tempVector.nonZeros() == " << int(count) << " / " << (other.rows()) << "\n";
+    }
+    res.finalize();
+    other = res.markAsRValue();
+  }
+};
+
+} // end namespace internal
+
+#ifndef EIGEN_PARSED_BY_DOXYGEN
+template<typename ExpressionType,unsigned int Mode>
+template<typename OtherDerived>
+void TriangularViewImpl<ExpressionType,Mode,Sparse>::solveInPlace(SparseMatrixBase<OtherDerived>& other) const
+{
+  eigen_assert(derived().cols() == derived().rows() && derived().cols() == other.rows());
+  eigen_assert( (!(Mode & ZeroDiag)) && bool(Mode & (Upper|Lower)));
+
+//   enum { copy = internal::traits<OtherDerived>::Flags & RowMajorBit };
+
+//   typedef typename internal::conditional<copy,
+//     typename internal::plain_matrix_type_column_major<OtherDerived>::type, OtherDerived&>::type OtherCopy;
+//   OtherCopy otherCopy(other.derived());
+
+  internal::sparse_solve_triangular_sparse_selector<ExpressionType, OtherDerived, Mode>::run(derived().nestedExpression(), other.derived());
+
+//   if (copy)
+//     other = otherCopy;
+}
+#endif
+
+} // end namespace Eigen
+
+#endif // EIGEN_SPARSETRIANGULARSOLVER_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU.h
new file mode 100644
index 0000000..0c8d893
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU.h
@@ -0,0 +1,923 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>
+// Copyright (C) 2012-2014 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+
+#ifndef EIGEN_SPARSE_LU_H
+#define EIGEN_SPARSE_LU_H
+
+namespace Eigen {
+
+template <typename _MatrixType, typename _OrderingType = COLAMDOrdering<typename _MatrixType::StorageIndex> > class SparseLU;
+template <typename MappedSparseMatrixType> struct SparseLUMatrixLReturnType;
+template <typename MatrixLType, typename MatrixUType> struct SparseLUMatrixUReturnType;
+
+template <bool Conjugate,class SparseLUType>
+class SparseLUTransposeView : public SparseSolverBase<SparseLUTransposeView<Conjugate,SparseLUType> >
+{
+protected:
+  typedef SparseSolverBase<SparseLUTransposeView<Conjugate,SparseLUType> > APIBase;
+  using APIBase::m_isInitialized;
+public:
+  typedef typename SparseLUType::Scalar Scalar;
+  typedef typename SparseLUType::StorageIndex StorageIndex;
+  typedef typename SparseLUType::MatrixType MatrixType;
+  typedef typename SparseLUType::OrderingType OrderingType;
+
+  enum {
+    ColsAtCompileTime = MatrixType::ColsAtCompileTime,
+    MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime
+  };
+
+  SparseLUTransposeView() : m_sparseLU(NULL) {}
+  SparseLUTransposeView(const SparseLUTransposeView& view) {
+    this->m_sparseLU = view.m_sparseLU;
+  }
+  void setIsInitialized(const bool isInitialized) {this->m_isInitialized = isInitialized;}
+  void setSparseLU(SparseLUType* sparseLU) {m_sparseLU = sparseLU;}
+  using APIBase::_solve_impl;
+  template<typename Rhs, typename Dest>
+  bool _solve_impl(const MatrixBase<Rhs> &B, MatrixBase<Dest> &X_base) const
+  {
+    Dest& X(X_base.derived());
+    eigen_assert(m_sparseLU->info() == Success && "The matrix should be factorized first");
+    EIGEN_STATIC_ASSERT((Dest::Flags&RowMajorBit)==0,
+                        THIS_METHOD_IS_ONLY_FOR_COLUMN_MAJOR_MATRICES);
+
+
+    // this ugly const_cast_derived() helps to detect aliasing when applying the permutations
+    for(Index j = 0; j < B.cols(); ++j){
+      X.col(j) = m_sparseLU->colsPermutation() * B.const_cast_derived().col(j);
+    }
+    //Forward substitution with transposed or adjoint of U
+    m_sparseLU->matrixU().template solveTransposedInPlace<Conjugate>(X);
+
+    //Backward substitution with transposed or adjoint of L
+    m_sparseLU->matrixL().template solveTransposedInPlace<Conjugate>(X);
+
+    // Permute back the solution
+    for (Index j = 0; j < B.cols(); ++j)
+      X.col(j) = m_sparseLU->rowsPermutation().transpose() * X.col(j);
+    return true;
+  }
+  inline Index rows() const { return m_sparseLU->rows(); }
+  inline Index cols() const { return m_sparseLU->cols(); }
+
+private:
+  SparseLUType *m_sparseLU;
+  SparseLUTransposeView& operator=(const SparseLUTransposeView&);
+};
+
+
+/** \ingroup SparseLU_Module
+  * \class SparseLU
+  * 
+  * \brief Sparse supernodal LU factorization for general matrices
+  * 
+  * This class implements the supernodal LU factorization for general matrices.
+  * It uses the main techniques from the sequential SuperLU package 
+  * (http://crd-legacy.lbl.gov/~xiaoye/SuperLU/). It handles transparently real 
+  * and complex arithmetic with single and double precision, depending on the 
+  * scalar type of your input matrix. 
+  * The code has been optimized to provide BLAS-3 operations during supernode-panel updates. 
+  * It benefits directly from the built-in high-performant Eigen BLAS routines. 
+  * Moreover, when the size of a supernode is very small, the BLAS calls are avoided to 
+  * enable a better optimization from the compiler. For best performance, 
+  * you should compile it with NDEBUG flag to avoid the numerous bounds checking on vectors. 
+  * 
+  * An important parameter of this class is the ordering method. It is used to reorder the columns 
+  * (and eventually the rows) of the matrix to reduce the number of new elements that are created during 
+  * numerical factorization. The cheapest method available is COLAMD. 
+  * See  \link OrderingMethods_Module the OrderingMethods module \endlink for the list of 
+  * built-in and external ordering methods. 
+  *
+  * Simple example with key steps 
+  * \code
+  * VectorXd x(n), b(n);
+  * SparseMatrix<double> A;
+  * SparseLU<SparseMatrix<double>, COLAMDOrdering<int> >   solver;
+  * // fill A and b;
+  * // Compute the ordering permutation vector from the structural pattern of A
+  * solver.analyzePattern(A); 
+  * // Compute the numerical factorization 
+  * solver.factorize(A); 
+  * //Use the factors to solve the linear system 
+  * x = solver.solve(b); 
+  * \endcode
+  * 
+  * \warning The input matrix A should be in a \b compressed and \b column-major form.
+  * Otherwise an expensive copy will be made. You can call the inexpensive makeCompressed() to get a compressed matrix.
+  * 
+  * \note Unlike the initial SuperLU implementation, there is no step to equilibrate the matrix. 
+  * For badly scaled matrices, this step can be useful to reduce the pivoting during factorization. 
+  * If this is the case for your matrices, you can try the basic scaling method at
+  *  "unsupported/Eigen/src/IterativeSolvers/Scaling.h"
+  * 
+  * \tparam _MatrixType The type of the sparse matrix. It must be a column-major SparseMatrix<>
+  * \tparam _OrderingType The ordering method to use, either AMD, COLAMD or METIS. Default is COLMAD
+  *
+  * \implsparsesolverconcept
+  * 
+  * \sa \ref TutorialSparseSolverConcept
+  * \sa \ref OrderingMethods_Module
+  */
+template <typename _MatrixType, typename _OrderingType>
+class SparseLU : public SparseSolverBase<SparseLU<_MatrixType,_OrderingType> >, public internal::SparseLUImpl<typename _MatrixType::Scalar, typename _MatrixType::StorageIndex>
+{
+  protected:
+    typedef SparseSolverBase<SparseLU<_MatrixType,_OrderingType> > APIBase;
+    using APIBase::m_isInitialized;
+  public:
+    using APIBase::_solve_impl;
+    
+    typedef _MatrixType MatrixType; 
+    typedef _OrderingType OrderingType;
+    typedef typename MatrixType::Scalar Scalar; 
+    typedef typename MatrixType::RealScalar RealScalar; 
+    typedef typename MatrixType::StorageIndex StorageIndex;
+    typedef SparseMatrix<Scalar,ColMajor,StorageIndex> NCMatrix;
+    typedef internal::MappedSuperNodalMatrix<Scalar, StorageIndex> SCMatrix;
+    typedef Matrix<Scalar,Dynamic,1> ScalarVector;
+    typedef Matrix<StorageIndex,Dynamic,1> IndexVector;
+    typedef PermutationMatrix<Dynamic, Dynamic, StorageIndex> PermutationType;
+    typedef internal::SparseLUImpl<Scalar, StorageIndex> Base;
+
+    enum {
+      ColsAtCompileTime = MatrixType::ColsAtCompileTime,
+      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime
+    };
+    
+  public:
+
+    SparseLU():m_lastError(""),m_Ustore(0,0,0,0,0,0),m_symmetricmode(false),m_diagpivotthresh(1.0),m_detPermR(1)
+    {
+      initperfvalues(); 
+    }
+    explicit SparseLU(const MatrixType& matrix)
+      : m_lastError(""),m_Ustore(0,0,0,0,0,0),m_symmetricmode(false),m_diagpivotthresh(1.0),m_detPermR(1)
+    {
+      initperfvalues(); 
+      compute(matrix);
+    }
+    
+    ~SparseLU()
+    {
+      // Free all explicit dynamic pointers 
+    }
+    
+    void analyzePattern (const MatrixType& matrix);
+    void factorize (const MatrixType& matrix);
+    void simplicialfactorize(const MatrixType& matrix);
+    
+    /**
+      * Compute the symbolic and numeric factorization of the input sparse matrix.
+      * The input matrix should be in column-major storage. 
+      */
+    void compute (const MatrixType& matrix)
+    {
+      // Analyze 
+      analyzePattern(matrix); 
+      //Factorize
+      factorize(matrix);
+    } 
+
+    /** \returns an expression of the transposed of the factored matrix.
+      *
+      * A typical usage is to solve for the transposed problem A^T x = b:
+      * \code
+      * solver.compute(A);
+      * x = solver.transpose().solve(b);
+      * \endcode
+      *
+      * \sa adjoint(), solve()
+      */
+    const SparseLUTransposeView<false,SparseLU<_MatrixType,_OrderingType> > transpose()
+    {
+      SparseLUTransposeView<false,  SparseLU<_MatrixType,_OrderingType> > transposeView;
+      transposeView.setSparseLU(this);
+      transposeView.setIsInitialized(this->m_isInitialized);
+      return transposeView;
+    }
+
+
+    /** \returns an expression of the adjoint of the factored matrix
+      *
+      * A typical usage is to solve for the adjoint problem A' x = b:
+      * \code
+      * solver.compute(A);
+      * x = solver.adjoint().solve(b);
+      * \endcode
+      *
+      * For real scalar types, this function is equivalent to transpose().
+      *
+      * \sa transpose(), solve()
+      */
+    const SparseLUTransposeView<true, SparseLU<_MatrixType,_OrderingType> > adjoint()
+    {
+      SparseLUTransposeView<true,  SparseLU<_MatrixType,_OrderingType> > adjointView;
+      adjointView.setSparseLU(this);
+      adjointView.setIsInitialized(this->m_isInitialized);
+      return adjointView;
+    }
+    
+    inline Index rows() const { return m_mat.rows(); }
+    inline Index cols() const { return m_mat.cols(); }
+    /** Indicate that the pattern of the input matrix is symmetric */
+    void isSymmetric(bool sym)
+    {
+      m_symmetricmode = sym;
+    }
+    
+    /** \returns an expression of the matrix L, internally stored as supernodes
+      * The only operation available with this expression is the triangular solve
+      * \code
+      * y = b; matrixL().solveInPlace(y);
+      * \endcode
+      */
+    SparseLUMatrixLReturnType<SCMatrix> matrixL() const
+    {
+      return SparseLUMatrixLReturnType<SCMatrix>(m_Lstore);
+    }
+    /** \returns an expression of the matrix U,
+      * The only operation available with this expression is the triangular solve
+      * \code
+      * y = b; matrixU().solveInPlace(y);
+      * \endcode
+      */
+    SparseLUMatrixUReturnType<SCMatrix,MappedSparseMatrix<Scalar,ColMajor,StorageIndex> > matrixU() const
+    {
+      return SparseLUMatrixUReturnType<SCMatrix, MappedSparseMatrix<Scalar,ColMajor,StorageIndex> >(m_Lstore, m_Ustore);
+    }
+
+    /**
+      * \returns a reference to the row matrix permutation \f$ P_r \f$ such that \f$P_r A P_c^T = L U\f$
+      * \sa colsPermutation()
+      */
+    inline const PermutationType& rowsPermutation() const
+    {
+      return m_perm_r;
+    }
+    /**
+      * \returns a reference to the column matrix permutation\f$ P_c^T \f$ such that \f$P_r A P_c^T = L U\f$
+      * \sa rowsPermutation()
+      */
+    inline const PermutationType& colsPermutation() const
+    {
+      return m_perm_c;
+    }
+    /** Set the threshold used for a diagonal entry to be an acceptable pivot. */
+    void setPivotThreshold(const RealScalar& thresh)
+    {
+      m_diagpivotthresh = thresh; 
+    }
+
+#ifdef EIGEN_PARSED_BY_DOXYGEN
+    /** \returns the solution X of \f$ A X = B \f$ using the current decomposition of A.
+      *
+      * \warning the destination matrix X in X = this->solve(B) must be colmun-major.
+      *
+      * \sa compute()
+      */
+    template<typename Rhs>
+    inline const Solve<SparseLU, Rhs> solve(const MatrixBase<Rhs>& B) const;
+#endif // EIGEN_PARSED_BY_DOXYGEN
+    
+    /** \brief Reports whether previous computation was successful.
+      *
+      * \returns \c Success if computation was successful,
+      *          \c NumericalIssue if the LU factorization reports a problem, zero diagonal for instance
+      *          \c InvalidInput if the input matrix is invalid
+      *
+      * \sa iparm()          
+      */
+    ComputationInfo info() const
+    {
+      eigen_assert(m_isInitialized && "Decomposition is not initialized.");
+      return m_info;
+    }
+    
+    /**
+      * \returns A string describing the type of error
+      */
+    std::string lastErrorMessage() const
+    {
+      return m_lastError; 
+    }
+
+    template<typename Rhs, typename Dest>
+    bool _solve_impl(const MatrixBase<Rhs> &B, MatrixBase<Dest> &X_base) const
+    {
+      Dest& X(X_base.derived());
+      eigen_assert(m_factorizationIsOk && "The matrix should be factorized first");
+      EIGEN_STATIC_ASSERT((Dest::Flags&RowMajorBit)==0,
+                        THIS_METHOD_IS_ONLY_FOR_COLUMN_MAJOR_MATRICES);
+      
+      // Permute the right hand side to form X = Pr*B
+      // on return, X is overwritten by the computed solution
+      X.resize(B.rows(),B.cols());
+
+      // this ugly const_cast_derived() helps to detect aliasing when applying the permutations
+      for(Index j = 0; j < B.cols(); ++j)
+        X.col(j) = rowsPermutation() * B.const_cast_derived().col(j);
+      
+      //Forward substitution with L
+      this->matrixL().solveInPlace(X);
+      this->matrixU().solveInPlace(X);
+      
+      // Permute back the solution 
+      for (Index j = 0; j < B.cols(); ++j)
+        X.col(j) = colsPermutation().inverse() * X.col(j);
+      
+      return true; 
+    }
+    
+    /**
+      * \returns the absolute value of the determinant of the matrix of which
+      * *this is the QR decomposition.
+      *
+      * \warning a determinant can be very big or small, so for matrices
+      * of large enough dimension, there is a risk of overflow/underflow.
+      * One way to work around that is to use logAbsDeterminant() instead.
+      *
+      * \sa logAbsDeterminant(), signDeterminant()
+      */
+    Scalar absDeterminant()
+    {
+      using std::abs;
+      eigen_assert(m_factorizationIsOk && "The matrix should be factorized first.");
+      // Initialize with the determinant of the row matrix
+      Scalar det = Scalar(1.);
+      // Note that the diagonal blocks of U are stored in supernodes,
+      // which are available in the  L part :)
+      for (Index j = 0; j < this->cols(); ++j)
+      {
+        for (typename SCMatrix::InnerIterator it(m_Lstore, j); it; ++it)
+        {
+          if(it.index() == j)
+          {
+            det *= abs(it.value());
+            break;
+          }
+        }
+      }
+      return det;
+    }
+
+    /** \returns the natural log of the absolute value of the determinant of the matrix
+      * of which **this is the QR decomposition
+      *
+      * \note This method is useful to work around the risk of overflow/underflow that's
+      * inherent to the determinant computation.
+      *
+      * \sa absDeterminant(), signDeterminant()
+      */
+    Scalar logAbsDeterminant() const
+    {
+      using std::log;
+      using std::abs;
+
+      eigen_assert(m_factorizationIsOk && "The matrix should be factorized first.");
+      Scalar det = Scalar(0.);
+      for (Index j = 0; j < this->cols(); ++j)
+      {
+        for (typename SCMatrix::InnerIterator it(m_Lstore, j); it; ++it)
+        {
+          if(it.row() < j) continue;
+          if(it.row() == j)
+          {
+            det += log(abs(it.value()));
+            break;
+          }
+        }
+      }
+      return det;
+    }
+
+    /** \returns A number representing the sign of the determinant
+      *
+      * \sa absDeterminant(), logAbsDeterminant()
+      */
+    Scalar signDeterminant()
+    {
+      eigen_assert(m_factorizationIsOk && "The matrix should be factorized first.");
+      // Initialize with the determinant of the row matrix
+      Index det = 1;
+      // Note that the diagonal blocks of U are stored in supernodes,
+      // which are available in the  L part :)
+      for (Index j = 0; j < this->cols(); ++j)
+      {
+        for (typename SCMatrix::InnerIterator it(m_Lstore, j); it; ++it)
+        {
+          if(it.index() == j)
+          {
+            if(it.value()<0)
+              det = -det;
+            else if(it.value()==0)
+              return 0;
+            break;
+          }
+        }
+      }
+      return det * m_detPermR * m_detPermC;
+    }
+    
+    /** \returns The determinant of the matrix.
+      *
+      * \sa absDeterminant(), logAbsDeterminant()
+      */
+    Scalar determinant()
+    {
+      eigen_assert(m_factorizationIsOk && "The matrix should be factorized first.");
+      // Initialize with the determinant of the row matrix
+      Scalar det = Scalar(1.);
+      // Note that the diagonal blocks of U are stored in supernodes,
+      // which are available in the  L part :)
+      for (Index j = 0; j < this->cols(); ++j)
+      {
+        for (typename SCMatrix::InnerIterator it(m_Lstore, j); it; ++it)
+        {
+          if(it.index() == j)
+          {
+            det *= it.value();
+            break;
+          }
+        }
+      }
+      return (m_detPermR * m_detPermC) > 0 ? det : -det;
+    }
+
+    Index nnzL() const { return m_nnzL; };
+    Index nnzU() const { return m_nnzU; };
+
+  protected:
+    // Functions 
+    void initperfvalues()
+    {
+      m_perfv.panel_size = 16;
+      m_perfv.relax = 1; 
+      m_perfv.maxsuper = 128; 
+      m_perfv.rowblk = 16; 
+      m_perfv.colblk = 8; 
+      m_perfv.fillfactor = 20;  
+    }
+      
+    // Variables 
+    mutable ComputationInfo m_info;
+    bool m_factorizationIsOk;
+    bool m_analysisIsOk;
+    std::string m_lastError;
+    NCMatrix m_mat; // The input (permuted ) matrix 
+    SCMatrix m_Lstore; // The lower triangular matrix (supernodal)
+    MappedSparseMatrix<Scalar,ColMajor,StorageIndex> m_Ustore; // The upper triangular matrix
+    PermutationType m_perm_c; // Column permutation 
+    PermutationType m_perm_r ; // Row permutation
+    IndexVector m_etree; // Column elimination tree 
+    
+    typename Base::GlobalLU_t m_glu; 
+                               
+    // SparseLU options 
+    bool m_symmetricmode;
+    // values for performance 
+    internal::perfvalues m_perfv;
+    RealScalar m_diagpivotthresh; // Specifies the threshold used for a diagonal entry to be an acceptable pivot
+    Index m_nnzL, m_nnzU; // Nonzeros in L and U factors
+    Index m_detPermR, m_detPermC; // Determinants of the permutation matrices
+  private:
+    // Disable copy constructor 
+    SparseLU (const SparseLU& );
+}; // End class SparseLU
+
+
+
+// Functions needed by the anaysis phase
+/** 
+  * Compute the column permutation to minimize the fill-in
+  * 
+  *  - Apply this permutation to the input matrix - 
+  * 
+  *  - Compute the column elimination tree on the permuted matrix 
+  * 
+  *  - Postorder the elimination tree and the column permutation
+  * 
+  */
+template <typename MatrixType, typename OrderingType>
+void SparseLU<MatrixType, OrderingType>::analyzePattern(const MatrixType& mat)
+{
+  
+  //TODO  It is possible as in SuperLU to compute row and columns scaling vectors to equilibrate the matrix mat.
+  
+  // Firstly, copy the whole input matrix. 
+  m_mat = mat;
+  
+  // Compute fill-in ordering
+  OrderingType ord; 
+  ord(m_mat,m_perm_c);
+  
+  // Apply the permutation to the column of the input  matrix
+  if (m_perm_c.size())
+  {
+    m_mat.uncompress(); //NOTE: The effect of this command is only to create the InnerNonzeros pointers. FIXME : This vector is filled but not subsequently used.  
+    // Then, permute only the column pointers
+    ei_declare_aligned_stack_constructed_variable(StorageIndex,outerIndexPtr,mat.cols()+1,mat.isCompressed()?const_cast<StorageIndex*>(mat.outerIndexPtr()):0);
+    
+    // If the input matrix 'mat' is uncompressed, then the outer-indices do not match the ones of m_mat, and a copy is thus needed.
+    if(!mat.isCompressed()) 
+      IndexVector::Map(outerIndexPtr, mat.cols()+1) = IndexVector::Map(m_mat.outerIndexPtr(),mat.cols()+1);
+    
+    // Apply the permutation and compute the nnz per column.
+    for (Index i = 0; i < mat.cols(); i++)
+    {
+      m_mat.outerIndexPtr()[m_perm_c.indices()(i)] = outerIndexPtr[i];
+      m_mat.innerNonZeroPtr()[m_perm_c.indices()(i)] = outerIndexPtr[i+1] - outerIndexPtr[i];
+    }
+  }
+  
+  // Compute the column elimination tree of the permuted matrix 
+  IndexVector firstRowElt;
+  internal::coletree(m_mat, m_etree,firstRowElt); 
+     
+  // In symmetric mode, do not do postorder here
+  if (!m_symmetricmode) {
+    IndexVector post, iwork; 
+    // Post order etree
+    internal::treePostorder(StorageIndex(m_mat.cols()), m_etree, post); 
+      
+   
+    // Renumber etree in postorder 
+    Index m = m_mat.cols(); 
+    iwork.resize(m+1);
+    for (Index i = 0; i < m; ++i) iwork(post(i)) = post(m_etree(i));
+    m_etree = iwork;
+    
+    // Postmultiply A*Pc by post, i.e reorder the matrix according to the postorder of the etree
+    PermutationType post_perm(m); 
+    for (Index i = 0; i < m; i++) 
+      post_perm.indices()(i) = post(i); 
+        
+    // Combine the two permutations : postorder the permutation for future use
+    if(m_perm_c.size()) {
+      m_perm_c = post_perm * m_perm_c;
+    }
+    
+  } // end postordering 
+  
+  m_analysisIsOk = true; 
+}
+
+// Functions needed by the numerical factorization phase
+
+
+/** 
+  *  - Numerical factorization 
+  *  - Interleaved with the symbolic factorization 
+  * On exit,  info is 
+  * 
+  *    = 0: successful factorization
+  * 
+  *    > 0: if info = i, and i is
+  * 
+  *       <= A->ncol: U(i,i) is exactly zero. The factorization has
+  *          been completed, but the factor U is exactly singular,
+  *          and division by zero will occur if it is used to solve a
+  *          system of equations.
+  * 
+  *       > A->ncol: number of bytes allocated when memory allocation
+  *         failure occurred, plus A->ncol. If lwork = -1, it is
+  *         the estimated amount of space needed, plus A->ncol.  
+  */
+template <typename MatrixType, typename OrderingType>
+void SparseLU<MatrixType, OrderingType>::factorize(const MatrixType& matrix)
+{
+  using internal::emptyIdxLU;
+  eigen_assert(m_analysisIsOk && "analyzePattern() should be called first"); 
+  eigen_assert((matrix.rows() == matrix.cols()) && "Only for squared matrices");
+  
+  m_isInitialized = true;
+  
+  // Apply the column permutation computed in analyzepattern()
+  //   m_mat = matrix * m_perm_c.inverse(); 
+  m_mat = matrix;
+  if (m_perm_c.size()) 
+  {
+    m_mat.uncompress(); //NOTE: The effect of this command is only to create the InnerNonzeros pointers.
+    //Then, permute only the column pointers
+    const StorageIndex * outerIndexPtr;
+    if (matrix.isCompressed()) outerIndexPtr = matrix.outerIndexPtr();
+    else
+    {
+      StorageIndex* outerIndexPtr_t = new StorageIndex[matrix.cols()+1];
+      for(Index i = 0; i <= matrix.cols(); i++) outerIndexPtr_t[i] = m_mat.outerIndexPtr()[i];
+      outerIndexPtr = outerIndexPtr_t;
+    }
+    for (Index i = 0; i < matrix.cols(); i++)
+    {
+      m_mat.outerIndexPtr()[m_perm_c.indices()(i)] = outerIndexPtr[i];
+      m_mat.innerNonZeroPtr()[m_perm_c.indices()(i)] = outerIndexPtr[i+1] - outerIndexPtr[i];
+    }
+    if(!matrix.isCompressed()) delete[] outerIndexPtr;
+  } 
+  else 
+  { //FIXME This should not be needed if the empty permutation is handled transparently
+    m_perm_c.resize(matrix.cols());
+    for(StorageIndex i = 0; i < matrix.cols(); ++i) m_perm_c.indices()(i) = i;
+  }
+  
+  Index m = m_mat.rows();
+  Index n = m_mat.cols();
+  Index nnz = m_mat.nonZeros();
+  Index maxpanel = m_perfv.panel_size * m;
+  // Allocate working storage common to the factor routines
+  Index lwork = 0;
+  Index info = Base::memInit(m, n, nnz, lwork, m_perfv.fillfactor, m_perfv.panel_size, m_glu); 
+  if (info) 
+  {
+    m_lastError = "UNABLE TO ALLOCATE WORKING MEMORY\n\n" ;
+    m_factorizationIsOk = false;
+    return ; 
+  }
+  
+  // Set up pointers for integer working arrays 
+  IndexVector segrep(m); segrep.setZero();
+  IndexVector parent(m); parent.setZero();
+  IndexVector xplore(m); xplore.setZero();
+  IndexVector repfnz(maxpanel);
+  IndexVector panel_lsub(maxpanel);
+  IndexVector xprune(n); xprune.setZero();
+  IndexVector marker(m*internal::LUNoMarker); marker.setZero();
+  
+  repfnz.setConstant(-1); 
+  panel_lsub.setConstant(-1);
+  
+  // Set up pointers for scalar working arrays 
+  ScalarVector dense; 
+  dense.setZero(maxpanel);
+  ScalarVector tempv; 
+  tempv.setZero(internal::LUnumTempV(m, m_perfv.panel_size, m_perfv.maxsuper, /*m_perfv.rowblk*/m) );
+  
+  // Compute the inverse of perm_c
+  PermutationType iperm_c(m_perm_c.inverse()); 
+  
+  // Identify initial relaxed snodes
+  IndexVector relax_end(n);
+  if ( m_symmetricmode == true ) 
+    Base::heap_relax_snode(n, m_etree, m_perfv.relax, marker, relax_end);
+  else
+    Base::relax_snode(n, m_etree, m_perfv.relax, marker, relax_end);
+  
+  
+  m_perm_r.resize(m); 
+  m_perm_r.indices().setConstant(-1);
+  marker.setConstant(-1);
+  m_detPermR = 1; // Record the determinant of the row permutation
+  
+  m_glu.supno(0) = emptyIdxLU; m_glu.xsup.setConstant(0);
+  m_glu.xsup(0) = m_glu.xlsub(0) = m_glu.xusub(0) = m_glu.xlusup(0) = Index(0);
+  
+  // Work on one 'panel' at a time. A panel is one of the following :
+  //  (a) a relaxed supernode at the bottom of the etree, or
+  //  (b) panel_size contiguous columns, <panel_size> defined by the user
+  Index jcol; 
+  Index pivrow; // Pivotal row number in the original row matrix
+  Index nseg1; // Number of segments in U-column above panel row jcol
+  Index nseg; // Number of segments in each U-column 
+  Index irep; 
+  Index i, k, jj; 
+  for (jcol = 0; jcol < n; )
+  {
+    // Adjust panel size so that a panel won't overlap with the next relaxed snode. 
+    Index panel_size = m_perfv.panel_size; // upper bound on panel width
+    for (k = jcol + 1; k < (std::min)(jcol+panel_size, n); k++)
+    {
+      if (relax_end(k) != emptyIdxLU) 
+      {
+        panel_size = k - jcol; 
+        break; 
+      }
+    }
+    if (k == n) 
+      panel_size = n - jcol; 
+      
+    // Symbolic outer factorization on a panel of columns 
+    Base::panel_dfs(m, panel_size, jcol, m_mat, m_perm_r.indices(), nseg1, dense, panel_lsub, segrep, repfnz, xprune, marker, parent, xplore, m_glu); 
+    
+    // Numeric sup-panel updates in topological order 
+    Base::panel_bmod(m, panel_size, jcol, nseg1, dense, tempv, segrep, repfnz, m_glu); 
+    
+    // Sparse LU within the panel, and below the panel diagonal 
+    for ( jj = jcol; jj< jcol + panel_size; jj++) 
+    {
+      k = (jj - jcol) * m; // Column index for w-wide arrays 
+      
+      nseg = nseg1; // begin after all the panel segments
+      //Depth-first-search for the current column
+      VectorBlock<IndexVector> panel_lsubk(panel_lsub, k, m);
+      VectorBlock<IndexVector> repfnz_k(repfnz, k, m); 
+      info = Base::column_dfs(m, jj, m_perm_r.indices(), m_perfv.maxsuper, nseg, panel_lsubk, segrep, repfnz_k, xprune, marker, parent, xplore, m_glu); 
+      if ( info ) 
+      {
+        m_lastError =  "UNABLE TO EXPAND MEMORY IN COLUMN_DFS() ";
+        m_info = NumericalIssue; 
+        m_factorizationIsOk = false; 
+        return; 
+      }
+      // Numeric updates to this column 
+      VectorBlock<ScalarVector> dense_k(dense, k, m); 
+      VectorBlock<IndexVector> segrep_k(segrep, nseg1, m-nseg1); 
+      info = Base::column_bmod(jj, (nseg - nseg1), dense_k, tempv, segrep_k, repfnz_k, jcol, m_glu); 
+      if ( info ) 
+      {
+        m_lastError = "UNABLE TO EXPAND MEMORY IN COLUMN_BMOD() ";
+        m_info = NumericalIssue; 
+        m_factorizationIsOk = false; 
+        return; 
+      }
+      
+      // Copy the U-segments to ucol(*)
+      info = Base::copy_to_ucol(jj, nseg, segrep, repfnz_k ,m_perm_r.indices(), dense_k, m_glu); 
+      if ( info ) 
+      {
+        m_lastError = "UNABLE TO EXPAND MEMORY IN COPY_TO_UCOL() ";
+        m_info = NumericalIssue; 
+        m_factorizationIsOk = false; 
+        return; 
+      }
+      
+      // Form the L-segment 
+      info = Base::pivotL(jj, m_diagpivotthresh, m_perm_r.indices(), iperm_c.indices(), pivrow, m_glu);
+      if ( info ) 
+      {
+        m_lastError = "THE MATRIX IS STRUCTURALLY SINGULAR ... ZERO COLUMN AT ";
+        std::ostringstream returnInfo;
+        returnInfo << info; 
+        m_lastError += returnInfo.str();
+        m_info = NumericalIssue; 
+        m_factorizationIsOk = false; 
+        return; 
+      }
+      
+      // Update the determinant of the row permutation matrix
+      // FIXME: the following test is not correct, we should probably take iperm_c into account and pivrow is not directly the row pivot.
+      if (pivrow != jj) m_detPermR = -m_detPermR;
+
+      // Prune columns (0:jj-1) using column jj
+      Base::pruneL(jj, m_perm_r.indices(), pivrow, nseg, segrep, repfnz_k, xprune, m_glu); 
+      
+      // Reset repfnz for this column 
+      for (i = 0; i < nseg; i++)
+      {
+        irep = segrep(i); 
+        repfnz_k(irep) = emptyIdxLU; 
+      }
+    } // end SparseLU within the panel  
+    jcol += panel_size;  // Move to the next panel
+  } // end for -- end elimination 
+  
+  m_detPermR = m_perm_r.determinant();
+  m_detPermC = m_perm_c.determinant();
+  
+  // Count the number of nonzeros in factors 
+  Base::countnz(n, m_nnzL, m_nnzU, m_glu); 
+  // Apply permutation  to the L subscripts 
+  Base::fixupL(n, m_perm_r.indices(), m_glu);
+  
+  // Create supernode matrix L 
+  m_Lstore.setInfos(m, n, m_glu.lusup, m_glu.xlusup, m_glu.lsub, m_glu.xlsub, m_glu.supno, m_glu.xsup); 
+  // Create the column major upper sparse matrix  U; 
+  new (&m_Ustore) MappedSparseMatrix<Scalar, ColMajor, StorageIndex> ( m, n, m_nnzU, m_glu.xusub.data(), m_glu.usub.data(), m_glu.ucol.data() );
+  
+  m_info = Success;
+  m_factorizationIsOk = true;
+}
+
+template<typename MappedSupernodalType>
+struct SparseLUMatrixLReturnType : internal::no_assignment_operator
+{
+  typedef typename MappedSupernodalType::Scalar Scalar;
+  explicit SparseLUMatrixLReturnType(const MappedSupernodalType& mapL) : m_mapL(mapL)
+  { }
+  Index rows() const { return m_mapL.rows(); }
+  Index cols() const { return m_mapL.cols(); }
+  template<typename Dest>
+  void solveInPlace( MatrixBase<Dest> &X) const
+  {
+    m_mapL.solveInPlace(X);
+  }
+  template<bool Conjugate, typename Dest>
+  void solveTransposedInPlace( MatrixBase<Dest> &X) const
+  {
+    m_mapL.template solveTransposedInPlace<Conjugate>(X);
+  }
+
+  const MappedSupernodalType& m_mapL;
+};
+
+template<typename MatrixLType, typename MatrixUType>
+struct SparseLUMatrixUReturnType : internal::no_assignment_operator
+{
+  typedef typename MatrixLType::Scalar Scalar;
+  SparseLUMatrixUReturnType(const MatrixLType& mapL, const MatrixUType& mapU)
+  : m_mapL(mapL),m_mapU(mapU)
+  { }
+  Index rows() const { return m_mapL.rows(); }
+  Index cols() const { return m_mapL.cols(); }
+
+  template<typename Dest>   void solveInPlace(MatrixBase<Dest> &X) const
+  {
+    Index nrhs = X.cols();
+    Index n    = X.rows();
+    // Backward solve with U
+    for (Index k = m_mapL.nsuper(); k >= 0; k--)
+    {
+      Index fsupc = m_mapL.supToCol()[k];
+      Index lda = m_mapL.colIndexPtr()[fsupc+1] - m_mapL.colIndexPtr()[fsupc]; // leading dimension
+      Index nsupc = m_mapL.supToCol()[k+1] - fsupc;
+      Index luptr = m_mapL.colIndexPtr()[fsupc];
+
+      if (nsupc == 1)
+      {
+        for (Index j = 0; j < nrhs; j++)
+        {
+          X(fsupc, j) /= m_mapL.valuePtr()[luptr];
+        }
+      }
+      else
+      {
+        // FIXME: the following lines should use Block expressions and not Map!
+        Map<const Matrix<Scalar,Dynamic,Dynamic, ColMajor>, 0, OuterStride<> > A( &(m_mapL.valuePtr()[luptr]), nsupc, nsupc, OuterStride<>(lda) );
+        Map< Matrix<Scalar,Dynamic,Dest::ColsAtCompileTime, ColMajor>, 0, OuterStride<> > U (&(X.coeffRef(fsupc,0)), nsupc, nrhs, OuterStride<>(n) );
+        U = A.template triangularView<Upper>().solve(U);
+      }
+
+      for (Index j = 0; j < nrhs; ++j)
+      {
+        for (Index jcol = fsupc; jcol < fsupc + nsupc; jcol++)
+        {
+          typename MatrixUType::InnerIterator it(m_mapU, jcol);
+          for ( ; it; ++it)
+          {
+            Index irow = it.index();
+            X(irow, j) -= X(jcol, j) * it.value();
+          }
+        }
+      }
+    } // End For U-solve
+  }
+
+  template<bool Conjugate, typename Dest>   void solveTransposedInPlace(MatrixBase<Dest> &X) const
+  {
+    using numext::conj;
+    Index nrhs = X.cols();
+    Index n    = X.rows();
+    // Forward solve with U
+    for (Index k = 0; k <=  m_mapL.nsuper(); k++)
+    {
+      Index fsupc = m_mapL.supToCol()[k];
+      Index lda = m_mapL.colIndexPtr()[fsupc+1] - m_mapL.colIndexPtr()[fsupc]; // leading dimension
+      Index nsupc = m_mapL.supToCol()[k+1] - fsupc;
+      Index luptr = m_mapL.colIndexPtr()[fsupc];
+
+      for (Index j = 0; j < nrhs; ++j)
+      {
+        for (Index jcol = fsupc; jcol < fsupc + nsupc; jcol++)
+        {
+          typename MatrixUType::InnerIterator it(m_mapU, jcol);
+          for ( ; it; ++it)
+          {
+            Index irow = it.index();
+            X(jcol, j) -= X(irow, j) * (Conjugate? conj(it.value()): it.value());
+          }
+        }
+      }
+      if (nsupc == 1)
+      {
+        for (Index j = 0; j < nrhs; j++)
+        {
+          X(fsupc, j) /= (Conjugate? conj(m_mapL.valuePtr()[luptr]) : m_mapL.valuePtr()[luptr]);
+        }
+      }
+      else
+      {
+        Map<const Matrix<Scalar,Dynamic,Dynamic, ColMajor>, 0, OuterStride<> > A( &(m_mapL.valuePtr()[luptr]), nsupc, nsupc, OuterStride<>(lda) );
+        Map< Matrix<Scalar,Dynamic,Dest::ColsAtCompileTime, ColMajor>, 0, OuterStride<> > U (&(X(fsupc,0)), nsupc, nrhs, OuterStride<>(n) );
+        if(Conjugate)
+          U = A.adjoint().template triangularView<Lower>().solve(U);
+        else
+          U = A.transpose().template triangularView<Lower>().solve(U);
+      }
+    }// End For U-solve
+  }
+
+
+  const MatrixLType& m_mapL;
+  const MatrixUType& m_mapU;
+};
+
+} // End namespace Eigen 
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLUImpl.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLUImpl.h
new file mode 100644
index 0000000..fc0cfc4
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLUImpl.h
@@ -0,0 +1,66 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+#ifndef SPARSELU_IMPL_H
+#define SPARSELU_IMPL_H
+
+namespace Eigen {
+namespace internal {
+  
+/** \ingroup SparseLU_Module
+  * \class SparseLUImpl
+  * Base class for sparseLU
+  */
+template <typename Scalar, typename StorageIndex>
+class SparseLUImpl
+{
+  public:
+    typedef Matrix<Scalar,Dynamic,1> ScalarVector;
+    typedef Matrix<StorageIndex,Dynamic,1> IndexVector; 
+    typedef Matrix<Scalar,Dynamic,Dynamic,ColMajor> ScalarMatrix;
+    typedef Map<ScalarMatrix, 0,  OuterStride<> > MappedMatrixBlock;
+    typedef typename ScalarVector::RealScalar RealScalar; 
+    typedef Ref<Matrix<Scalar,Dynamic,1> > BlockScalarVector;
+    typedef Ref<Matrix<StorageIndex,Dynamic,1> > BlockIndexVector;
+    typedef LU_GlobalLU_t<IndexVector, ScalarVector> GlobalLU_t; 
+    typedef SparseMatrix<Scalar,ColMajor,StorageIndex> MatrixType; 
+    
+  protected:
+     template <typename VectorType>
+     Index expand(VectorType& vec, Index& length, Index nbElts, Index keep_prev, Index& num_expansions);
+     Index memInit(Index m, Index n, Index annz, Index lwork, Index fillratio, Index panel_size,  GlobalLU_t& glu); 
+     template <typename VectorType>
+     Index memXpand(VectorType& vec, Index& maxlen, Index nbElts, MemType memtype, Index& num_expansions);
+     void heap_relax_snode (const Index n, IndexVector& et, const Index relax_columns, IndexVector& descendants, IndexVector& relax_end); 
+     void relax_snode (const Index n, IndexVector& et, const Index relax_columns, IndexVector& descendants, IndexVector& relax_end); 
+     Index snode_dfs(const Index jcol, const Index kcol,const MatrixType& mat,  IndexVector& xprune, IndexVector& marker, GlobalLU_t& glu); 
+     Index snode_bmod (const Index jcol, const Index fsupc, ScalarVector& dense, GlobalLU_t& glu);
+     Index pivotL(const Index jcol, const RealScalar& diagpivotthresh, IndexVector& perm_r, IndexVector& iperm_c, Index& pivrow, GlobalLU_t& glu);
+     template <typename Traits>
+     void dfs_kernel(const StorageIndex jj, IndexVector& perm_r,
+                    Index& nseg, IndexVector& panel_lsub, IndexVector& segrep,
+                    Ref<IndexVector> repfnz_col, IndexVector& xprune, Ref<IndexVector> marker, IndexVector& parent,
+                    IndexVector& xplore, GlobalLU_t& glu, Index& nextl_col, Index krow, Traits& traits);
+     void panel_dfs(const Index m, const Index w, const Index jcol, MatrixType& A, IndexVector& perm_r, Index& nseg, ScalarVector& dense, IndexVector& panel_lsub, IndexVector& segrep, IndexVector& repfnz, IndexVector& xprune, IndexVector& marker, IndexVector& parent, IndexVector& xplore, GlobalLU_t& glu);
+    
+     void panel_bmod(const Index m, const Index w, const Index jcol, const Index nseg, ScalarVector& dense, ScalarVector& tempv, IndexVector& segrep, IndexVector& repfnz, GlobalLU_t& glu);
+     Index column_dfs(const Index m, const Index jcol, IndexVector& perm_r, Index maxsuper, Index& nseg,  BlockIndexVector lsub_col, IndexVector& segrep, BlockIndexVector repfnz, IndexVector& xprune, IndexVector& marker, IndexVector& parent, IndexVector& xplore, GlobalLU_t& glu);
+     Index column_bmod(const Index jcol, const Index nseg, BlockScalarVector dense, ScalarVector& tempv, BlockIndexVector segrep, BlockIndexVector repfnz, Index fpanelc, GlobalLU_t& glu); 
+     Index copy_to_ucol(const Index jcol, const Index nseg, IndexVector& segrep, BlockIndexVector repfnz ,IndexVector& perm_r, BlockScalarVector dense, GlobalLU_t& glu); 
+     void pruneL(const Index jcol, const IndexVector& perm_r, const Index pivrow, const Index nseg, const IndexVector& segrep, BlockIndexVector repfnz, IndexVector& xprune, GlobalLU_t& glu);
+     void countnz(const Index n, Index& nnzL, Index& nnzU, GlobalLU_t& glu); 
+     void fixupL(const Index n, const IndexVector& perm_r, GlobalLU_t& glu); 
+     
+     template<typename , typename >
+     friend struct column_dfs_traits;
+}; 
+
+} // end namespace internal
+} // namespace Eigen
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_Memory.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_Memory.h
new file mode 100644
index 0000000..349bfd5
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_Memory.h
@@ -0,0 +1,226 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+/* 
+ 
+ * NOTE: This file is the modified version of [s,d,c,z]memory.c files in SuperLU 
+ 
+ * -- SuperLU routine (version 3.1) --
+ * Univ. of California Berkeley, Xerox Palo Alto Research Center,
+ * and Lawrence Berkeley National Lab.
+ * August 1, 2008
+ *
+ * Copyright (c) 1994 by Xerox Corporation.  All rights reserved.
+ *
+ * THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY
+ * EXPRESSED OR IMPLIED.  ANY USE IS AT YOUR OWN RISK.
+ *
+ * Permission is hereby granted to use or copy this program for any
+ * purpose, provided the above notices are retained on all copies.
+ * Permission to modify the code and to distribute modified code is
+ * granted, provided the above notices are retained, and a notice that
+ * the code was modified is included with the above copyright notice.
+ */
+
+#ifndef EIGEN_SPARSELU_MEMORY
+#define EIGEN_SPARSELU_MEMORY
+
+namespace Eigen {
+namespace internal {
+  
+enum { LUNoMarker = 3 };
+enum {emptyIdxLU = -1};
+inline Index LUnumTempV(Index& m, Index& w, Index& t, Index& b)
+{
+  return (std::max)(m, (t+b)*w);
+}
+
+template< typename Scalar>
+inline Index LUTempSpace(Index&m, Index& w)
+{
+  return (2*w + 4 + LUNoMarker) * m * sizeof(Index) + (w + 1) * m * sizeof(Scalar);
+}
+
+
+
+
+/** 
+  * Expand the existing storage to accommodate more fill-ins
+  * \param vec Valid pointer to the vector to allocate or expand
+  * \param[in,out] length  At input, contain the current length of the vector that is to be increased. At output, length of the newly allocated vector
+  * \param[in] nbElts Current number of elements in the factors
+  * \param keep_prev  1: use length  and do not expand the vector; 0: compute new_len and expand
+  * \param[in,out] num_expansions Number of times the memory has been expanded
+  */
+template <typename Scalar, typename StorageIndex>
+template <typename VectorType>
+Index  SparseLUImpl<Scalar,StorageIndex>::expand(VectorType& vec, Index& length, Index nbElts, Index keep_prev, Index& num_expansions) 
+{
+  
+  float alpha = 1.5; // Ratio of the memory increase 
+  Index new_len; // New size of the allocated memory
+  
+  if(num_expansions == 0 || keep_prev) 
+    new_len = length ; // First time allocate requested
+  else 
+    new_len = (std::max)(length+1,Index(alpha * length));
+  
+  VectorType old_vec; // Temporary vector to hold the previous values   
+  if (nbElts > 0 )
+    old_vec = vec.segment(0,nbElts); 
+  
+  //Allocate or expand the current vector
+#ifdef EIGEN_EXCEPTIONS
+  try
+#endif
+  {
+    vec.resize(new_len); 
+  }
+#ifdef EIGEN_EXCEPTIONS
+  catch(std::bad_alloc& )
+#else
+  if(!vec.size())
+#endif
+  {
+    if (!num_expansions)
+    {
+      // First time to allocate from LUMemInit()
+      // Let LUMemInit() deals with it.
+      return -1;
+    }
+    if (keep_prev)
+    {
+      // In this case, the memory length should not not be reduced
+      return new_len;
+    }
+    else 
+    {
+      // Reduce the size and increase again 
+      Index tries = 0; // Number of attempts
+      do 
+      {
+        alpha = (alpha + 1)/2;
+        new_len = (std::max)(length+1,Index(alpha * length));
+#ifdef EIGEN_EXCEPTIONS
+        try
+#endif
+        {
+          vec.resize(new_len); 
+        }
+#ifdef EIGEN_EXCEPTIONS
+        catch(std::bad_alloc& )
+#else
+        if (!vec.size())
+#endif
+        {
+          tries += 1; 
+          if ( tries > 10) return new_len; 
+        }
+      } while (!vec.size());
+    }
+  }
+  //Copy the previous values to the newly allocated space 
+  if (nbElts > 0)
+    vec.segment(0, nbElts) = old_vec;   
+   
+  
+  length  = new_len;
+  if(num_expansions) ++num_expansions;
+  return 0; 
+}
+
+/**
+ * \brief  Allocate various working space for the numerical factorization phase.
+ * \param m number of rows of the input matrix 
+ * \param n number of columns 
+ * \param annz number of initial nonzeros in the matrix 
+ * \param lwork  if lwork=-1, this routine returns an estimated size of the required memory
+ * \param glu persistent data to facilitate multiple factors : will be deleted later ??
+ * \param fillratio estimated ratio of fill in the factors
+ * \param panel_size Size of a panel
+ * \return an estimated size of the required memory if lwork = -1; otherwise, return the size of actually allocated memory when allocation failed, and 0 on success
+ * \note Unlike SuperLU, this routine does not support successive factorization with the same pattern and the same row permutation
+ */
+template <typename Scalar, typename StorageIndex>
+Index SparseLUImpl<Scalar,StorageIndex>::memInit(Index m, Index n, Index annz, Index lwork, Index fillratio, Index panel_size,  GlobalLU_t& glu)
+{
+  Index& num_expansions = glu.num_expansions; //No memory expansions so far
+  num_expansions = 0;
+  glu.nzumax = glu.nzlumax = (std::min)(fillratio * (annz+1) / n, m) * n; // estimated number of nonzeros in U 
+  glu.nzlmax = (std::max)(Index(4), fillratio) * (annz+1) / 4; // estimated  nnz in L factor
+  // Return the estimated size to the user if necessary
+  Index tempSpace;
+  tempSpace = (2*panel_size + 4 + LUNoMarker) * m * sizeof(Index) + (panel_size + 1) * m * sizeof(Scalar);
+  if (lwork == emptyIdxLU) 
+  {
+    Index estimated_size;
+    estimated_size = (5 * n + 5) * sizeof(Index)  + tempSpace
+                    + (glu.nzlmax + glu.nzumax) * sizeof(Index) + (glu.nzlumax+glu.nzumax) *  sizeof(Scalar) + n; 
+    return estimated_size;
+  }
+  
+  // Setup the required space 
+  
+  // First allocate Integer pointers for L\U factors
+  glu.xsup.resize(n+1);
+  glu.supno.resize(n+1);
+  glu.xlsub.resize(n+1);
+  glu.xlusup.resize(n+1);
+  glu.xusub.resize(n+1);
+
+  // Reserve memory for L/U factors
+  do 
+  {
+    if(     (expand<ScalarVector>(glu.lusup, glu.nzlumax, 0, 0, num_expansions)<0)
+        ||  (expand<ScalarVector>(glu.ucol,  glu.nzumax,  0, 0, num_expansions)<0)
+        ||  (expand<IndexVector> (glu.lsub,  glu.nzlmax,  0, 0, num_expansions)<0)
+        ||  (expand<IndexVector> (glu.usub,  glu.nzumax,  0, 1, num_expansions)<0) )
+    {
+      //Reduce the estimated size and retry
+      glu.nzlumax /= 2;
+      glu.nzumax /= 2;
+      glu.nzlmax /= 2;
+      if (glu.nzlumax < annz ) return glu.nzlumax; 
+    }
+  } while (!glu.lusup.size() || !glu.ucol.size() || !glu.lsub.size() || !glu.usub.size());
+  
+  ++num_expansions;
+  return 0;
+  
+} // end LuMemInit
+
+/** 
+ * \brief Expand the existing storage 
+ * \param vec vector to expand 
+ * \param[in,out] maxlen On input, previous size of vec (Number of elements to copy ). on output, new size
+ * \param nbElts current number of elements in the vector.
+ * \param memtype Type of the element to expand
+ * \param num_expansions Number of expansions 
+ * \return 0 on success, > 0 size of the memory allocated so far
+ */
+template <typename Scalar, typename StorageIndex>
+template <typename VectorType>
+Index SparseLUImpl<Scalar,StorageIndex>::memXpand(VectorType& vec, Index& maxlen, Index nbElts, MemType memtype, Index& num_expansions)
+{
+  Index failed_size; 
+  if (memtype == USUB)
+     failed_size = this->expand<VectorType>(vec, maxlen, nbElts, 1, num_expansions);
+  else
+    failed_size = this->expand<VectorType>(vec, maxlen, nbElts, 0, num_expansions);
+
+  if (failed_size)
+    return failed_size; 
+  
+  return 0 ;  
+}
+
+} // end namespace internal
+
+} // end namespace Eigen
+#endif // EIGEN_SPARSELU_MEMORY
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_Structs.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_Structs.h
new file mode 100644
index 0000000..cf5ec44
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_Structs.h
@@ -0,0 +1,110 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+/* 
+ * NOTE: This file comes from a partly modified version of files slu_[s,d,c,z]defs.h
+ * -- SuperLU routine (version 4.1) --
+ * Univ. of California Berkeley, Xerox Palo Alto Research Center,
+ * and Lawrence Berkeley National Lab.
+ * November, 2010
+ * 
+ * Global data structures used in LU factorization -
+ * 
+ *   nsuper: #supernodes = nsuper + 1, numbered [0, nsuper].
+ *   (xsup,supno): supno[i] is the supernode no to which i belongs;
+ *  xsup(s) points to the beginning of the s-th supernode.
+ *  e.g.   supno 0 1 2 2 3 3 3 4 4 4 4 4   (n=12)
+ *          xsup 0 1 2 4 7 12
+ *  Note: dfs will be performed on supernode rep. relative to the new 
+ *        row pivoting ordering
+ *
+ *   (xlsub,lsub): lsub[*] contains the compressed subscript of
+ *  rectangular supernodes; xlsub[j] points to the starting
+ *  location of the j-th column in lsub[*]. Note that xlsub 
+ *  is indexed by column.
+ *  Storage: original row subscripts
+ *
+ *      During the course of sparse LU factorization, we also use
+ *  (xlsub,lsub) for the purpose of symmetric pruning. For each
+ *  supernode {s,s+1,...,t=s+r} with first column s and last
+ *  column t, the subscript set
+ *    lsub[j], j=xlsub[s], .., xlsub[s+1]-1
+ *  is the structure of column s (i.e. structure of this supernode).
+ *  It is used for the storage of numerical values.
+ *  Furthermore,
+ *    lsub[j], j=xlsub[t], .., xlsub[t+1]-1
+ *  is the structure of the last column t of this supernode.
+ *  It is for the purpose of symmetric pruning. Therefore, the
+ *  structural subscripts can be rearranged without making physical
+ *  interchanges among the numerical values.
+ *
+ *  However, if the supernode has only one column, then we
+ *  only keep one set of subscripts. For any subscript interchange
+ *  performed, similar interchange must be done on the numerical
+ *  values.
+ *
+ *  The last column structures (for pruning) will be removed
+ *  after the numercial LU factorization phase.
+ *
+ *   (xlusup,lusup): lusup[*] contains the numerical values of the
+ *  rectangular supernodes; xlusup[j] points to the starting
+ *  location of the j-th column in storage vector lusup[*]
+ *  Note: xlusup is indexed by column.
+ *  Each rectangular supernode is stored by column-major
+ *  scheme, consistent with Fortran 2-dim array storage.
+ *
+ *   (xusub,ucol,usub): ucol[*] stores the numerical values of
+ *  U-columns outside the rectangular supernodes. The row
+ *  subscript of nonzero ucol[k] is stored in usub[k].
+ *  xusub[i] points to the starting location of column i in ucol.
+ *  Storage: new row subscripts; that is subscripts of PA.
+ */
+
+#ifndef EIGEN_LU_STRUCTS
+#define EIGEN_LU_STRUCTS
+namespace Eigen {
+namespace internal {
+  
+typedef enum {LUSUP, UCOL, LSUB, USUB, LLVL, ULVL} MemType; 
+
+template <typename IndexVector, typename ScalarVector>
+struct LU_GlobalLU_t {
+  typedef typename IndexVector::Scalar StorageIndex; 
+  IndexVector xsup; //First supernode column ... xsup(s) points to the beginning of the s-th supernode
+  IndexVector supno; // Supernode number corresponding to this column (column to supernode mapping)
+  ScalarVector  lusup; // nonzero values of L ordered by columns 
+  IndexVector lsub; // Compressed row indices of L rectangular supernodes. 
+  IndexVector xlusup; // pointers to the beginning of each column in lusup
+  IndexVector xlsub; // pointers to the beginning of each column in lsub
+  Index   nzlmax; // Current max size of lsub
+  Index   nzlumax; // Current max size of lusup
+  ScalarVector  ucol; // nonzero values of U ordered by columns 
+  IndexVector usub; // row indices of U columns in ucol
+  IndexVector xusub; // Pointers to the beginning of each column of U in ucol 
+  Index   nzumax; // Current max size of ucol
+  Index   n; // Number of columns in the matrix  
+  Index   num_expansions; 
+};
+
+// Values to set for performance
+struct perfvalues {
+  Index panel_size; // a panel consists of at most <panel_size> consecutive columns
+  Index relax; // To control degree of relaxing supernodes. If the number of nodes (columns) 
+                // in a subtree of the elimination tree is less than relax, this subtree is considered 
+                // as one supernode regardless of the row structures of those columns
+  Index maxsuper; // The maximum size for a supernode in complete LU
+  Index rowblk; // The minimum row dimension for 2-D blocking to be used;
+  Index colblk; // The minimum column dimension for 2-D blocking to be used;
+  Index fillfactor; // The estimated fills factors for L and U, compared with A
+}; 
+
+} // end namespace internal
+
+} // end namespace Eigen
+#endif // EIGEN_LU_STRUCTS
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_SupernodalMatrix.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_SupernodalMatrix.h
new file mode 100644
index 0000000..0be293d
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_SupernodalMatrix.h
@@ -0,0 +1,375 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>
+// Copyright (C) 2012 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_SPARSELU_SUPERNODAL_MATRIX_H
+#define EIGEN_SPARSELU_SUPERNODAL_MATRIX_H
+
+namespace Eigen {
+namespace internal {
+
+/** \ingroup SparseLU_Module
+ * \brief a class to manipulate the L supernodal factor from the SparseLU factorization
+ * 
+ * This class  contain the data to easily store 
+ * and manipulate the supernodes during the factorization and solution phase of Sparse LU. 
+ * Only the lower triangular matrix has supernodes.
+ * 
+ * NOTE : This class corresponds to the SCformat structure in SuperLU
+ * 
+ */
+/* TODO
+ * InnerIterator as for sparsematrix 
+ * SuperInnerIterator to iterate through all supernodes 
+ * Function for triangular solve
+ */
+template <typename _Scalar, typename _StorageIndex>
+class MappedSuperNodalMatrix
+{
+  public:
+    typedef _Scalar Scalar; 
+    typedef _StorageIndex StorageIndex;
+    typedef Matrix<StorageIndex,Dynamic,1> IndexVector;
+    typedef Matrix<Scalar,Dynamic,1> ScalarVector;
+  public:
+    MappedSuperNodalMatrix()
+    {
+      
+    }
+    MappedSuperNodalMatrix(Index m, Index n,  ScalarVector& nzval, IndexVector& nzval_colptr, IndexVector& rowind,
+             IndexVector& rowind_colptr, IndexVector& col_to_sup, IndexVector& sup_to_col )
+    {
+      setInfos(m, n, nzval, nzval_colptr, rowind, rowind_colptr, col_to_sup, sup_to_col);
+    }
+    
+    ~MappedSuperNodalMatrix()
+    {
+      
+    }
+    /**
+     * Set appropriate pointers for the lower triangular supernodal matrix
+     * These infos are available at the end of the numerical factorization
+     * FIXME This class will be modified such that it can be use in the course 
+     * of the factorization.
+     */
+    void setInfos(Index m, Index n, ScalarVector& nzval, IndexVector& nzval_colptr, IndexVector& rowind,
+             IndexVector& rowind_colptr, IndexVector& col_to_sup, IndexVector& sup_to_col )
+    {
+      m_row = m;
+      m_col = n; 
+      m_nzval = nzval.data(); 
+      m_nzval_colptr = nzval_colptr.data(); 
+      m_rowind = rowind.data(); 
+      m_rowind_colptr = rowind_colptr.data(); 
+      m_nsuper = col_to_sup(n); 
+      m_col_to_sup = col_to_sup.data(); 
+      m_sup_to_col = sup_to_col.data(); 
+    }
+    
+    /**
+     * Number of rows
+     */
+    Index rows() const { return m_row; }
+    
+    /**
+     * Number of columns
+     */
+    Index cols() const { return m_col; }
+    
+    /**
+     * Return the array of nonzero values packed by column
+     * 
+     * The size is nnz
+     */
+    Scalar* valuePtr() {  return m_nzval; }
+    
+    const Scalar* valuePtr() const 
+    {
+      return m_nzval; 
+    }
+    /**
+     * Return the pointers to the beginning of each column in \ref valuePtr()
+     */
+    StorageIndex* colIndexPtr()
+    {
+      return m_nzval_colptr; 
+    }
+    
+    const StorageIndex* colIndexPtr() const
+    {
+      return m_nzval_colptr; 
+    }
+    
+    /**
+     * Return the array of compressed row indices of all supernodes
+     */
+    StorageIndex* rowIndex()  { return m_rowind; }
+    
+    const StorageIndex* rowIndex() const
+    {
+      return m_rowind; 
+    }
+    
+    /**
+     * Return the location in \em rowvaluePtr() which starts each column
+     */
+    StorageIndex* rowIndexPtr() { return m_rowind_colptr; }
+    
+    const StorageIndex* rowIndexPtr() const
+    {
+      return m_rowind_colptr; 
+    }
+    
+    /** 
+     * Return the array of column-to-supernode mapping 
+     */
+    StorageIndex* colToSup()  { return m_col_to_sup; }
+    
+    const StorageIndex* colToSup() const
+    {
+      return m_col_to_sup;       
+    }
+    /**
+     * Return the array of supernode-to-column mapping
+     */
+    StorageIndex* supToCol() { return m_sup_to_col; }
+    
+    const StorageIndex* supToCol() const
+    {
+      return m_sup_to_col;
+    }
+    
+    /**
+     * Return the number of supernodes
+     */
+    Index nsuper() const
+    {
+      return m_nsuper; 
+    }
+    
+    class InnerIterator; 
+    template<typename Dest>
+    void solveInPlace( MatrixBase<Dest>&X) const;
+    template<bool Conjugate, typename Dest>
+    void solveTransposedInPlace( MatrixBase<Dest>&X) const;
+
+    
+      
+      
+    
+  protected:
+    Index m_row; // Number of rows
+    Index m_col; // Number of columns
+    Index m_nsuper; // Number of supernodes
+    Scalar* m_nzval; //array of nonzero values packed by column
+    StorageIndex* m_nzval_colptr; //nzval_colptr[j] Stores the location in nzval[] which starts column j
+    StorageIndex* m_rowind; // Array of compressed row indices of rectangular supernodes
+    StorageIndex* m_rowind_colptr; //rowind_colptr[j] stores the location in rowind[] which starts column j
+    StorageIndex* m_col_to_sup; // col_to_sup[j] is the supernode number to which column j belongs
+    StorageIndex* m_sup_to_col; //sup_to_col[s] points to the starting column of the s-th supernode
+    
+  private :
+};
+
+/**
+  * \brief InnerIterator class to iterate over nonzero values of the current column in the supernodal matrix L
+  * 
+  */
+template<typename Scalar, typename StorageIndex>
+class MappedSuperNodalMatrix<Scalar,StorageIndex>::InnerIterator
+{
+  public:
+     InnerIterator(const MappedSuperNodalMatrix& mat, Index outer)
+      : m_matrix(mat),
+        m_outer(outer),
+        m_supno(mat.colToSup()[outer]),
+        m_idval(mat.colIndexPtr()[outer]),
+        m_startidval(m_idval),
+        m_endidval(mat.colIndexPtr()[outer+1]),
+        m_idrow(mat.rowIndexPtr()[mat.supToCol()[mat.colToSup()[outer]]]),
+        m_endidrow(mat.rowIndexPtr()[mat.supToCol()[mat.colToSup()[outer]]+1])
+    {}
+    inline InnerIterator& operator++()
+    { 
+      m_idval++; 
+      m_idrow++;
+      return *this;
+    }
+    inline Scalar value() const { return m_matrix.valuePtr()[m_idval]; }
+    
+    inline Scalar& valueRef() { return const_cast<Scalar&>(m_matrix.valuePtr()[m_idval]); }
+    
+    inline Index index() const { return m_matrix.rowIndex()[m_idrow]; }
+    inline Index row() const { return index(); }
+    inline Index col() const { return m_outer; }
+    
+    inline Index supIndex() const { return m_supno; }
+    
+    inline operator bool() const 
+    { 
+      return ( (m_idval < m_endidval) && (m_idval >= m_startidval)
+                && (m_idrow < m_endidrow) );
+    }
+    
+  protected:
+    const MappedSuperNodalMatrix& m_matrix; // Supernodal lower triangular matrix 
+    const Index m_outer;                    // Current column 
+    const Index m_supno;                    // Current SuperNode number
+    Index m_idval;                          // Index to browse the values in the current column
+    const Index m_startidval;               // Start of the column value
+    const Index m_endidval;                 // End of the column value
+    Index m_idrow;                          // Index to browse the row indices 
+    Index m_endidrow;                       // End index of row indices of the current column
+};
+
+/**
+ * \brief Solve with the supernode triangular matrix
+ * 
+ */
+template<typename Scalar, typename Index_>
+template<typename Dest>
+void MappedSuperNodalMatrix<Scalar,Index_>::solveInPlace( MatrixBase<Dest>&X) const
+{
+    /* Explicit type conversion as the Index type of MatrixBase<Dest> may be wider than Index */
+//    eigen_assert(X.rows() <= NumTraits<Index>::highest());
+//    eigen_assert(X.cols() <= NumTraits<Index>::highest());
+    Index n    = int(X.rows());
+    Index nrhs = Index(X.cols());
+    const Scalar * Lval = valuePtr();                 // Nonzero values 
+    Matrix<Scalar,Dynamic,Dest::ColsAtCompileTime, ColMajor> work(n, nrhs);     // working vector
+    work.setZero();
+    for (Index k = 0; k <= nsuper(); k ++)
+    {
+      Index fsupc = supToCol()[k];                    // First column of the current supernode 
+      Index istart = rowIndexPtr()[fsupc];            // Pointer index to the subscript of the current column
+      Index nsupr = rowIndexPtr()[fsupc+1] - istart;  // Number of rows in the current supernode
+      Index nsupc = supToCol()[k+1] - fsupc;          // Number of columns in the current supernode
+      Index nrow = nsupr - nsupc;                     // Number of rows in the non-diagonal part of the supernode
+      Index irow;                                     //Current index row
+      
+      if (nsupc == 1 )
+      {
+        for (Index j = 0; j < nrhs; j++)
+        {
+          InnerIterator it(*this, fsupc);
+          ++it; // Skip the diagonal element
+          for (; it; ++it)
+          {
+            irow = it.row();
+            X(irow, j) -= X(fsupc, j) * it.value();
+          }
+        }
+      }
+      else
+      {
+        // The supernode has more than one column 
+        Index luptr = colIndexPtr()[fsupc]; 
+        Index lda = colIndexPtr()[fsupc+1] - luptr;
+        
+        // Triangular solve 
+        Map<const Matrix<Scalar,Dynamic,Dynamic, ColMajor>, 0, OuterStride<> > A( &(Lval[luptr]), nsupc, nsupc, OuterStride<>(lda) );
+        Map< Matrix<Scalar,Dynamic,Dest::ColsAtCompileTime, ColMajor>, 0, OuterStride<> > U (&(X(fsupc,0)), nsupc, nrhs, OuterStride<>(n) );
+        U = A.template triangularView<UnitLower>().solve(U); 
+        
+        // Matrix-vector product 
+        new (&A) Map<const Matrix<Scalar,Dynamic,Dynamic, ColMajor>, 0, OuterStride<> > ( &(Lval[luptr+nsupc]), nrow, nsupc, OuterStride<>(lda) );
+        work.topRows(nrow).noalias() = A * U;
+        
+        //Begin Scatter 
+        for (Index j = 0; j < nrhs; j++)
+        {
+          Index iptr = istart + nsupc; 
+          for (Index i = 0; i < nrow; i++)
+          {
+            irow = rowIndex()[iptr]; 
+            X(irow, j) -= work(i, j); // Scatter operation
+            work(i, j) = Scalar(0); 
+            iptr++;
+          }
+        }
+      }
+    } 
+}
+
+template<typename Scalar, typename Index_>
+template<bool Conjugate, typename Dest>
+void MappedSuperNodalMatrix<Scalar,Index_>::solveTransposedInPlace( MatrixBase<Dest>&X) const
+{
+    using numext::conj;
+  Index n    = int(X.rows());
+  Index nrhs = Index(X.cols());
+  const Scalar * Lval = valuePtr();                 // Nonzero values
+  Matrix<Scalar,Dynamic,Dest::ColsAtCompileTime, ColMajor> work(n, nrhs);     // working vector
+  work.setZero();
+  for (Index k = nsuper(); k >= 0; k--)
+  {
+    Index fsupc = supToCol()[k];                    // First column of the current supernode
+    Index istart = rowIndexPtr()[fsupc];            // Pointer index to the subscript of the current column
+    Index nsupr = rowIndexPtr()[fsupc+1] - istart;  // Number of rows in the current supernode
+    Index nsupc = supToCol()[k+1] - fsupc;          // Number of columns in the current supernode
+    Index nrow = nsupr - nsupc;                     // Number of rows in the non-diagonal part of the supernode
+    Index irow;                                     //Current index row
+
+    if (nsupc == 1 )
+    {
+      for (Index j = 0; j < nrhs; j++)
+      {
+        InnerIterator it(*this, fsupc);
+        ++it; // Skip the diagonal element
+        for (; it; ++it)
+        {
+          irow = it.row();
+          X(fsupc,j) -= X(irow, j) * (Conjugate?conj(it.value()):it.value());
+        }
+      }
+    }
+    else
+    {
+      // The supernode has more than one column
+      Index luptr = colIndexPtr()[fsupc];
+      Index lda = colIndexPtr()[fsupc+1] - luptr;
+
+      //Begin Gather
+      for (Index j = 0; j < nrhs; j++)
+      {
+        Index iptr = istart + nsupc;
+        for (Index i = 0; i < nrow; i++)
+        {
+          irow = rowIndex()[iptr];
+          work.topRows(nrow)(i,j)= X(irow,j); // Gather operation
+          iptr++;
+        }
+      }
+
+      // Matrix-vector product with transposed submatrix
+      Map<const Matrix<Scalar,Dynamic,Dynamic, ColMajor>, 0, OuterStride<> > A( &(Lval[luptr+nsupc]), nrow, nsupc, OuterStride<>(lda) );
+      Map< Matrix<Scalar,Dynamic,Dest::ColsAtCompileTime, ColMajor>, 0, OuterStride<> > U (&(X(fsupc,0)), nsupc, nrhs, OuterStride<>(n) );
+      if(Conjugate)
+        U = U - A.adjoint() * work.topRows(nrow);
+      else
+        U = U - A.transpose() * work.topRows(nrow);
+
+      // Triangular solve (of transposed diagonal block)
+      new (&A) Map<const Matrix<Scalar,Dynamic,Dynamic, ColMajor>, 0, OuterStride<> > ( &(Lval[luptr]), nsupc, nsupc, OuterStride<>(lda) );
+      if(Conjugate)
+        U = A.adjoint().template triangularView<UnitUpper>().solve(U);
+      else
+        U = A.transpose().template triangularView<UnitUpper>().solve(U);
+
+    }
+
+  }
+}
+
+
+} // end namespace internal
+
+} // end namespace Eigen
+
+#endif // EIGEN_SPARSELU_MATRIX_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_Utils.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_Utils.h
new file mode 100644
index 0000000..9e3dab4
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_Utils.h
@@ -0,0 +1,80 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+
+#ifndef EIGEN_SPARSELU_UTILS_H
+#define EIGEN_SPARSELU_UTILS_H
+
+namespace Eigen {
+namespace internal {
+
+/**
+ * \brief Count Nonzero elements in the factors
+ */
+template <typename Scalar, typename StorageIndex>
+void SparseLUImpl<Scalar,StorageIndex>::countnz(const Index n, Index& nnzL, Index& nnzU, GlobalLU_t& glu)
+{
+ nnzL = 0; 
+ nnzU = (glu.xusub)(n); 
+ Index nsuper = (glu.supno)(n); 
+ Index jlen; 
+ Index i, j, fsupc;
+ if (n <= 0 ) return; 
+ // For each supernode
+ for (i = 0; i <= nsuper; i++)
+ {
+   fsupc = glu.xsup(i); 
+   jlen = glu.xlsub(fsupc+1) - glu.xlsub(fsupc); 
+   
+   for (j = fsupc; j < glu.xsup(i+1); j++)
+   {
+     nnzL += jlen; 
+     nnzU += j - fsupc + 1; 
+     jlen--; 
+   }
+ }
+}
+
+/**
+ * \brief Fix up the data storage lsub for L-subscripts. 
+ * 
+ * It removes the subscripts sets for structural pruning, 
+ * and applies permutation to the remaining subscripts
+ * 
+ */
+template <typename Scalar, typename StorageIndex>
+void SparseLUImpl<Scalar,StorageIndex>::fixupL(const Index n, const IndexVector& perm_r, GlobalLU_t& glu)
+{
+  Index fsupc, i, j, k, jstart; 
+  
+  StorageIndex nextl = 0; 
+  Index nsuper = (glu.supno)(n); 
+  
+  // For each supernode 
+  for (i = 0; i <= nsuper; i++)
+  {
+    fsupc = glu.xsup(i); 
+    jstart = glu.xlsub(fsupc); 
+    glu.xlsub(fsupc) = nextl; 
+    for (j = jstart; j < glu.xlsub(fsupc + 1); j++)
+    {
+      glu.lsub(nextl) = perm_r(glu.lsub(j)); // Now indexed into P*A
+      nextl++;
+    }
+    for (k = fsupc+1; k < glu.xsup(i+1); k++)
+      glu.xlsub(k) = nextl; // other columns in supernode i
+  }
+  
+  glu.xlsub(n) = nextl; 
+}
+
+} // end namespace internal
+
+} // end namespace Eigen
+#endif // EIGEN_SPARSELU_UTILS_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_column_bmod.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_column_bmod.h
new file mode 100644
index 0000000..b57f068
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_column_bmod.h
@@ -0,0 +1,181 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>
+// Copyright (C) 2012 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+/* 
+ 
+ * NOTE: This file is the modified version of xcolumn_bmod.c file in SuperLU 
+ 
+ * -- SuperLU routine (version 3.0) --
+ * Univ. of California Berkeley, Xerox Palo Alto Research Center,
+ * and Lawrence Berkeley National Lab.
+ * October 15, 2003
+ *
+ * Copyright (c) 1994 by Xerox Corporation.  All rights reserved.
+ *
+ * THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY
+ * EXPRESSED OR IMPLIED.  ANY USE IS AT YOUR OWN RISK.
+ *
+ * Permission is hereby granted to use or copy this program for any
+ * purpose, provided the above notices are retained on all copies.
+ * Permission to modify the code and to distribute modified code is
+ * granted, provided the above notices are retained, and a notice that
+ * the code was modified is included with the above copyright notice.
+ */
+#ifndef SPARSELU_COLUMN_BMOD_H
+#define SPARSELU_COLUMN_BMOD_H
+
+namespace Eigen {
+
+namespace internal {
+/**
+ * \brief Performs numeric block updates (sup-col) in topological order
+ * 
+ * \param jcol current column to update
+ * \param nseg Number of segments in the U part
+ * \param dense Store the full representation of the column
+ * \param tempv working array 
+ * \param segrep segment representative ...
+ * \param repfnz ??? First nonzero column in each row ???  ...
+ * \param fpanelc First column in the current panel
+ * \param glu Global LU data. 
+ * \return 0 - successful return 
+ *         > 0 - number of bytes allocated when run out of space
+ * 
+ */
+template <typename Scalar, typename StorageIndex>
+Index SparseLUImpl<Scalar,StorageIndex>::column_bmod(const Index jcol, const Index nseg, BlockScalarVector dense, ScalarVector& tempv,
+                                                     BlockIndexVector segrep, BlockIndexVector repfnz, Index fpanelc, GlobalLU_t& glu)
+{
+  Index  jsupno, k, ksub, krep, ksupno; 
+  Index lptr, nrow, isub, irow, nextlu, new_next, ufirst; 
+  Index fsupc, nsupc, nsupr, luptr, kfnz, no_zeros; 
+  /* krep = representative of current k-th supernode
+    * fsupc =  first supernodal column
+    * nsupc = number of columns in a supernode
+    * nsupr = number of rows in a supernode
+    * luptr = location of supernodal LU-block in storage
+    * kfnz = first nonz in the k-th supernodal segment
+    * no_zeros = no lf leading zeros in a supernodal U-segment
+    */
+  
+  jsupno = glu.supno(jcol);
+  // For each nonzero supernode segment of U[*,j] in topological order 
+  k = nseg - 1; 
+  Index d_fsupc; // distance between the first column of the current panel and the 
+               // first column of the current snode
+  Index fst_col; // First column within small LU update
+  Index segsize; 
+  for (ksub = 0; ksub < nseg; ksub++)
+  {
+    krep = segrep(k); k--; 
+    ksupno = glu.supno(krep); 
+    if (jsupno != ksupno )
+    {
+      // outside the rectangular supernode 
+      fsupc = glu.xsup(ksupno); 
+      fst_col = (std::max)(fsupc, fpanelc); 
+      
+      // Distance from the current supernode to the current panel; 
+      // d_fsupc = 0 if fsupc > fpanelc
+      d_fsupc = fst_col - fsupc; 
+      
+      luptr = glu.xlusup(fst_col) + d_fsupc; 
+      lptr = glu.xlsub(fsupc) + d_fsupc; 
+      
+      kfnz = repfnz(krep); 
+      kfnz = (std::max)(kfnz, fpanelc); 
+      
+      segsize = krep - kfnz + 1; 
+      nsupc = krep - fst_col + 1; 
+      nsupr = glu.xlsub(fsupc+1) - glu.xlsub(fsupc); 
+      nrow = nsupr - d_fsupc - nsupc;
+      Index lda = glu.xlusup(fst_col+1) - glu.xlusup(fst_col);
+      
+      
+      // Perform a triangular solver and block update, 
+      // then scatter the result of sup-col update to dense
+      no_zeros = kfnz - fst_col; 
+      if(segsize==1)
+        LU_kernel_bmod<1>::run(segsize, dense, tempv, glu.lusup, luptr, lda, nrow, glu.lsub, lptr, no_zeros);
+      else
+        LU_kernel_bmod<Dynamic>::run(segsize, dense, tempv, glu.lusup, luptr, lda, nrow, glu.lsub, lptr, no_zeros);
+    } // end if jsupno 
+  } // end for each segment
+  
+  // Process the supernodal portion of  L\U[*,j]
+  nextlu = glu.xlusup(jcol); 
+  fsupc = glu.xsup(jsupno);
+  
+  // copy the SPA dense into L\U[*,j]
+  Index mem; 
+  new_next = nextlu + glu.xlsub(fsupc + 1) - glu.xlsub(fsupc); 
+  Index offset = internal::first_multiple<Index>(new_next, internal::packet_traits<Scalar>::size) - new_next;
+  if(offset)
+    new_next += offset;
+  while (new_next > glu.nzlumax )
+  {
+    mem = memXpand<ScalarVector>(glu.lusup, glu.nzlumax, nextlu, LUSUP, glu.num_expansions);  
+    if (mem) return mem; 
+  }
+  
+  for (isub = glu.xlsub(fsupc); isub < glu.xlsub(fsupc+1); isub++)
+  {
+    irow = glu.lsub(isub);
+    glu.lusup(nextlu) = dense(irow);
+    dense(irow) = Scalar(0.0); 
+    ++nextlu; 
+  }
+  
+  if(offset)
+  {
+    glu.lusup.segment(nextlu,offset).setZero();
+    nextlu += offset;
+  }
+  glu.xlusup(jcol + 1) = StorageIndex(nextlu);  // close L\U(*,jcol); 
+  
+  /* For more updates within the panel (also within the current supernode),
+   * should start from the first column of the panel, or the first column
+   * of the supernode, whichever is bigger. There are two cases:
+   *  1) fsupc < fpanelc, then fst_col <-- fpanelc
+   *  2) fsupc >= fpanelc, then fst_col <-- fsupc
+   */
+  fst_col = (std::max)(fsupc, fpanelc); 
+  
+  if (fst_col  < jcol)
+  {
+    // Distance between the current supernode and the current panel
+    // d_fsupc = 0 if fsupc >= fpanelc
+    d_fsupc = fst_col - fsupc; 
+    
+    lptr = glu.xlsub(fsupc) + d_fsupc; 
+    luptr = glu.xlusup(fst_col) + d_fsupc; 
+    nsupr = glu.xlsub(fsupc+1) - glu.xlsub(fsupc); // leading dimension
+    nsupc = jcol - fst_col; // excluding jcol 
+    nrow = nsupr - d_fsupc - nsupc; 
+    
+    // points to the beginning of jcol in snode L\U(jsupno) 
+    ufirst = glu.xlusup(jcol) + d_fsupc; 
+    Index lda = glu.xlusup(jcol+1) - glu.xlusup(jcol);
+    MappedMatrixBlock A( &(glu.lusup.data()[luptr]), nsupc, nsupc, OuterStride<>(lda) );
+    VectorBlock<ScalarVector> u(glu.lusup, ufirst, nsupc); 
+    u = A.template triangularView<UnitLower>().solve(u); 
+    
+    new (&A) MappedMatrixBlock ( &(glu.lusup.data()[luptr+nsupc]), nrow, nsupc, OuterStride<>(lda) );
+    VectorBlock<ScalarVector> l(glu.lusup, ufirst+nsupc, nrow); 
+    l.noalias() -= A * u;
+    
+  } // End if fst_col
+  return 0; 
+}
+
+} // end namespace internal
+} // end namespace Eigen
+
+#endif // SPARSELU_COLUMN_BMOD_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_column_dfs.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_column_dfs.h
new file mode 100644
index 0000000..5a2c941
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_column_dfs.h
@@ -0,0 +1,179 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+/* 
+ 
+ * NOTE: This file is the modified version of [s,d,c,z]column_dfs.c file in SuperLU 
+ 
+ * -- SuperLU routine (version 2.0) --
+ * Univ. of California Berkeley, Xerox Palo Alto Research Center,
+ * and Lawrence Berkeley National Lab.
+ * November 15, 1997
+ *
+ * Copyright (c) 1994 by Xerox Corporation.  All rights reserved.
+ *
+ * THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY
+ * EXPRESSED OR IMPLIED.  ANY USE IS AT YOUR OWN RISK.
+ *
+ * Permission is hereby granted to use or copy this program for any
+ * purpose, provided the above notices are retained on all copies.
+ * Permission to modify the code and to distribute modified code is
+ * granted, provided the above notices are retained, and a notice that
+ * the code was modified is included with the above copyright notice.
+ */
+#ifndef SPARSELU_COLUMN_DFS_H
+#define SPARSELU_COLUMN_DFS_H
+
+template <typename Scalar, typename StorageIndex> class SparseLUImpl;
+namespace Eigen {
+
+namespace internal {
+
+template<typename IndexVector, typename ScalarVector>
+struct column_dfs_traits : no_assignment_operator
+{
+  typedef typename ScalarVector::Scalar Scalar;
+  typedef typename IndexVector::Scalar StorageIndex;
+  column_dfs_traits(Index jcol, Index& jsuper, typename SparseLUImpl<Scalar, StorageIndex>::GlobalLU_t& glu, SparseLUImpl<Scalar, StorageIndex>& luImpl)
+   : m_jcol(jcol), m_jsuper_ref(jsuper), m_glu(glu), m_luImpl(luImpl)
+ {}
+  bool update_segrep(Index /*krep*/, Index /*jj*/)
+  {
+    return true;
+  }
+  void mem_expand(IndexVector& lsub, Index& nextl, Index chmark)
+  {
+    if (nextl >= m_glu.nzlmax)
+      m_luImpl.memXpand(lsub, m_glu.nzlmax, nextl, LSUB, m_glu.num_expansions); 
+    if (chmark != (m_jcol-1)) m_jsuper_ref = emptyIdxLU;
+  }
+  enum { ExpandMem = true };
+  
+  Index m_jcol;
+  Index& m_jsuper_ref;
+  typename SparseLUImpl<Scalar, StorageIndex>::GlobalLU_t& m_glu;
+  SparseLUImpl<Scalar, StorageIndex>& m_luImpl;
+};
+
+
+/**
+ * \brief Performs a symbolic factorization on column jcol and decide the supernode boundary
+ * 
+ * A supernode representative is the last column of a supernode.
+ * The nonzeros in U[*,j] are segments that end at supernodes representatives. 
+ * The routine returns a list of the supernodal representatives 
+ * in topological order of the dfs that generates them. 
+ * The location of the first nonzero in each supernodal segment 
+ * (supernodal entry location) is also returned. 
+ * 
+ * \param m number of rows in the matrix
+ * \param jcol Current column 
+ * \param perm_r Row permutation
+ * \param maxsuper  Maximum number of column allowed in a supernode
+ * \param [in,out] nseg Number of segments in current U[*,j] - new segments appended
+ * \param lsub_col defines the rhs vector to start the dfs
+ * \param [in,out] segrep Segment representatives - new segments appended 
+ * \param repfnz  First nonzero location in each row
+ * \param xprune 
+ * \param marker  marker[i] == jj, if i was visited during dfs of current column jj;
+ * \param parent
+ * \param xplore working array
+ * \param glu global LU data 
+ * \return 0 success
+ *         > 0 number of bytes allocated when run out of space
+ * 
+ */
+template <typename Scalar, typename StorageIndex>
+Index SparseLUImpl<Scalar,StorageIndex>::column_dfs(const Index m, const Index jcol, IndexVector& perm_r, Index maxsuper, Index& nseg,
+                                                    BlockIndexVector lsub_col, IndexVector& segrep, BlockIndexVector repfnz, IndexVector& xprune,
+                                                    IndexVector& marker, IndexVector& parent, IndexVector& xplore, GlobalLU_t& glu)
+{
+  
+  Index jsuper = glu.supno(jcol); 
+  Index nextl = glu.xlsub(jcol); 
+  VectorBlock<IndexVector> marker2(marker, 2*m, m); 
+  
+  
+  column_dfs_traits<IndexVector, ScalarVector> traits(jcol, jsuper, glu, *this);
+  
+  // For each nonzero in A(*,jcol) do dfs 
+  for (Index k = 0; ((k < m) ? lsub_col[k] != emptyIdxLU : false) ; k++)
+  {
+    Index krow = lsub_col(k); 
+    lsub_col(k) = emptyIdxLU; 
+    Index kmark = marker2(krow); 
+    
+    // krow was visited before, go to the next nonz; 
+    if (kmark == jcol) continue;
+    
+    dfs_kernel(StorageIndex(jcol), perm_r, nseg, glu.lsub, segrep, repfnz, xprune, marker2, parent,
+                   xplore, glu, nextl, krow, traits);
+  } // for each nonzero ... 
+  
+  Index fsupc;
+  StorageIndex nsuper = glu.supno(jcol);
+  StorageIndex jcolp1 = StorageIndex(jcol) + 1;
+  Index jcolm1 = jcol - 1;
+  
+  // check to see if j belongs in the same supernode as j-1
+  if ( jcol == 0 )
+  { // Do nothing for column 0 
+    nsuper = glu.supno(0) = 0 ;
+  }
+  else 
+  {
+    fsupc = glu.xsup(nsuper); 
+    StorageIndex jptr = glu.xlsub(jcol); // Not yet compressed
+    StorageIndex jm1ptr = glu.xlsub(jcolm1); 
+    
+    // Use supernodes of type T2 : see SuperLU paper
+    if ( (nextl-jptr != jptr-jm1ptr-1) ) jsuper = emptyIdxLU;
+    
+    // Make sure the number of columns in a supernode doesn't
+    // exceed threshold
+    if ( (jcol - fsupc) >= maxsuper) jsuper = emptyIdxLU; 
+    
+    /* If jcol starts a new supernode, reclaim storage space in
+     * glu.lsub from previous supernode. Note we only store 
+     * the subscript set of the first and last columns of 
+     * a supernode. (first for num values, last for pruning)
+     */
+    if (jsuper == emptyIdxLU)
+    { // starts a new supernode 
+      if ( (fsupc < jcolm1-1) ) 
+      { // >= 3 columns in nsuper
+        StorageIndex ito = glu.xlsub(fsupc+1);
+        glu.xlsub(jcolm1) = ito; 
+        StorageIndex istop = ito + jptr - jm1ptr; 
+        xprune(jcolm1) = istop; // initialize xprune(jcol-1)
+        glu.xlsub(jcol) = istop; 
+        
+        for (StorageIndex ifrom = jm1ptr; ifrom < nextl; ++ifrom, ++ito)
+          glu.lsub(ito) = glu.lsub(ifrom); 
+        nextl = ito;  // = istop + length(jcol)
+      }
+      nsuper++; 
+      glu.supno(jcol) = nsuper; 
+    } // if a new supernode 
+  } // end else:  jcol > 0
+  
+  // Tidy up the pointers before exit
+  glu.xsup(nsuper+1) = jcolp1; 
+  glu.supno(jcolp1) = nsuper; 
+  xprune(jcol) = StorageIndex(nextl);  // Initialize upper bound for pruning
+  glu.xlsub(jcolp1) = StorageIndex(nextl); 
+  
+  return 0; 
+}
+
+} // end namespace internal
+
+} // end namespace Eigen
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_copy_to_ucol.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_copy_to_ucol.h
new file mode 100644
index 0000000..c32d8d8
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_copy_to_ucol.h
@@ -0,0 +1,107 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+/* 
+ 
+ * NOTE: This file is the modified version of [s,d,c,z]copy_to_ucol.c file in SuperLU 
+ 
+ * -- SuperLU routine (version 2.0) --
+ * Univ. of California Berkeley, Xerox Palo Alto Research Center,
+ * and Lawrence Berkeley National Lab.
+ * November 15, 1997
+ *
+ * Copyright (c) 1994 by Xerox Corporation.  All rights reserved.
+ *
+ * THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY
+ * EXPRESSED OR IMPLIED.  ANY USE IS AT YOUR OWN RISK.
+ *
+ * Permission is hereby granted to use or copy this program for any
+ * purpose, provided the above notices are retained on all copies.
+ * Permission to modify the code and to distribute modified code is
+ * granted, provided the above notices are retained, and a notice that
+ * the code was modified is included with the above copyright notice.
+ */
+#ifndef SPARSELU_COPY_TO_UCOL_H
+#define SPARSELU_COPY_TO_UCOL_H
+
+namespace Eigen {
+namespace internal {
+
+/**
+ * \brief Performs numeric block updates (sup-col) in topological order
+ * 
+ * \param jcol current column to update
+ * \param nseg Number of segments in the U part
+ * \param segrep segment representative ...
+ * \param repfnz First nonzero column in each row  ...
+ * \param perm_r Row permutation 
+ * \param dense Store the full representation of the column
+ * \param glu Global LU data. 
+ * \return 0 - successful return 
+ *         > 0 - number of bytes allocated when run out of space
+ * 
+ */
+template <typename Scalar, typename StorageIndex>
+Index SparseLUImpl<Scalar,StorageIndex>::copy_to_ucol(const Index jcol, const Index nseg, IndexVector& segrep,
+                                                      BlockIndexVector repfnz ,IndexVector& perm_r, BlockScalarVector dense, GlobalLU_t& glu)
+{  
+  Index ksub, krep, ksupno; 
+    
+  Index jsupno = glu.supno(jcol);
+  
+  // For each nonzero supernode segment of U[*,j] in topological order 
+  Index k = nseg - 1, i; 
+  StorageIndex nextu = glu.xusub(jcol); 
+  Index kfnz, isub, segsize; 
+  Index new_next,irow; 
+  Index fsupc, mem; 
+  for (ksub = 0; ksub < nseg; ksub++)
+  {
+    krep = segrep(k); k--; 
+    ksupno = glu.supno(krep); 
+    if (jsupno != ksupno ) // should go into ucol(); 
+    {
+      kfnz = repfnz(krep); 
+      if (kfnz != emptyIdxLU)
+      { // Nonzero U-segment 
+        fsupc = glu.xsup(ksupno); 
+        isub = glu.xlsub(fsupc) + kfnz - fsupc; 
+        segsize = krep - kfnz + 1; 
+        new_next = nextu + segsize; 
+        while (new_next > glu.nzumax) 
+        {
+          mem = memXpand<ScalarVector>(glu.ucol, glu.nzumax, nextu, UCOL, glu.num_expansions); 
+          if (mem) return mem; 
+          mem = memXpand<IndexVector>(glu.usub, glu.nzumax, nextu, USUB, glu.num_expansions); 
+          if (mem) return mem; 
+          
+        }
+        
+        for (i = 0; i < segsize; i++)
+        {
+          irow = glu.lsub(isub); 
+          glu.usub(nextu) = perm_r(irow); // Unlike the L part, the U part is stored in its final order
+          glu.ucol(nextu) = dense(irow); 
+          dense(irow) = Scalar(0.0); 
+          nextu++;
+          isub++;
+        }
+        
+      } // end nonzero U-segment 
+      
+    } // end if jsupno 
+    
+  } // end for each segment
+  glu.xusub(jcol + 1) = nextu; // close U(*,jcol)
+  return 0; 
+}
+
+} // namespace internal
+} // end namespace Eigen
+
+#endif // SPARSELU_COPY_TO_UCOL_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_gemm_kernel.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_gemm_kernel.h
new file mode 100644
index 0000000..e37c2fe
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_gemm_kernel.h
@@ -0,0 +1,280 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2012 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_SPARSELU_GEMM_KERNEL_H
+#define EIGEN_SPARSELU_GEMM_KERNEL_H
+
+namespace Eigen {
+
+namespace internal {
+
+
+/** \internal
+  * A general matrix-matrix product kernel optimized for the SparseLU factorization.
+  *  - A, B, and C must be column major
+  *  - lda and ldc must be multiples of the respective packet size
+  *  - C must have the same alignment as A
+  */
+template<typename Scalar>
+EIGEN_DONT_INLINE
+void sparselu_gemm(Index m, Index n, Index d, const Scalar* A, Index lda, const Scalar* B, Index ldb, Scalar* C, Index ldc)
+{
+  using namespace Eigen::internal;
+  
+  typedef typename packet_traits<Scalar>::type Packet;
+  enum {
+    NumberOfRegisters = EIGEN_ARCH_DEFAULT_NUMBER_OF_REGISTERS,
+    PacketSize = packet_traits<Scalar>::size,
+    PM = 8,                             // peeling in M
+    RN = 2,                             // register blocking
+    RK = NumberOfRegisters>=16 ? 4 : 2, // register blocking
+    BM = 4096/sizeof(Scalar),           // number of rows of A-C per chunk
+    SM = PM*PacketSize                  // step along M
+  };
+  Index d_end = (d/RK)*RK;    // number of columns of A (rows of B) suitable for full register blocking
+  Index n_end = (n/RN)*RN;    // number of columns of B-C suitable for processing RN columns at once
+  Index i0 = internal::first_default_aligned(A,m);
+  
+  eigen_internal_assert(((lda%PacketSize)==0) && ((ldc%PacketSize)==0) && (i0==internal::first_default_aligned(C,m)));
+  
+  // handle the non aligned rows of A and C without any optimization:
+  for(Index i=0; i<i0; ++i)
+  {
+    for(Index j=0; j<n; ++j)
+    {
+      Scalar c = C[i+j*ldc];
+      for(Index k=0; k<d; ++k)
+        c += B[k+j*ldb] * A[i+k*lda];
+      C[i+j*ldc] = c;
+    }
+  }
+  // process the remaining rows per chunk of BM rows
+  for(Index ib=i0; ib<m; ib+=BM)
+  {
+    Index actual_b = std::min<Index>(BM, m-ib);                 // actual number of rows
+    Index actual_b_end1 = (actual_b/SM)*SM;                   // actual number of rows suitable for peeling
+    Index actual_b_end2 = (actual_b/PacketSize)*PacketSize;   // actual number of rows suitable for vectorization
+    
+    // Let's process two columns of B-C at once
+    for(Index j=0; j<n_end; j+=RN)
+    {
+      const Scalar* Bc0 = B+(j+0)*ldb;
+      const Scalar* Bc1 = B+(j+1)*ldb;
+      
+      for(Index k=0; k<d_end; k+=RK)
+      {
+        
+        // load and expand a RN x RK block of B
+        Packet b00, b10, b20, b30, b01, b11, b21, b31;
+                  { b00 = pset1<Packet>(Bc0[0]); }
+                  { b10 = pset1<Packet>(Bc0[1]); }
+        if(RK==4) { b20 = pset1<Packet>(Bc0[2]); }
+        if(RK==4) { b30 = pset1<Packet>(Bc0[3]); }
+                  { b01 = pset1<Packet>(Bc1[0]); }
+                  { b11 = pset1<Packet>(Bc1[1]); }
+        if(RK==4) { b21 = pset1<Packet>(Bc1[2]); }
+        if(RK==4) { b31 = pset1<Packet>(Bc1[3]); }
+        
+        Packet a0, a1, a2, a3, c0, c1, t0, t1;
+        
+        const Scalar* A0 = A+ib+(k+0)*lda;
+        const Scalar* A1 = A+ib+(k+1)*lda;
+        const Scalar* A2 = A+ib+(k+2)*lda;
+        const Scalar* A3 = A+ib+(k+3)*lda;
+        
+        Scalar* C0 = C+ib+(j+0)*ldc;
+        Scalar* C1 = C+ib+(j+1)*ldc;
+        
+                  a0 = pload<Packet>(A0);
+                  a1 = pload<Packet>(A1);
+        if(RK==4)
+        {
+          a2 = pload<Packet>(A2);
+          a3 = pload<Packet>(A3);
+        }
+        else
+        {
+          // workaround "may be used uninitialized in this function" warning
+          a2 = a3 = a0;
+        }
+        
+#define KMADD(c, a, b, tmp) {tmp = b; tmp = pmul(a,tmp); c = padd(c,tmp);}
+#define WORK(I)  \
+                     c0 = pload<Packet>(C0+i+(I)*PacketSize);    \
+                     c1 = pload<Packet>(C1+i+(I)*PacketSize);    \
+                     KMADD(c0, a0, b00, t0)                      \
+                     KMADD(c1, a0, b01, t1)                      \
+                     a0 = pload<Packet>(A0+i+(I+1)*PacketSize);  \
+                     KMADD(c0, a1, b10, t0)                      \
+                     KMADD(c1, a1, b11, t1)                      \
+                     a1 = pload<Packet>(A1+i+(I+1)*PacketSize);  \
+          if(RK==4){ KMADD(c0, a2, b20, t0)                     }\
+          if(RK==4){ KMADD(c1, a2, b21, t1)                     }\
+          if(RK==4){ a2 = pload<Packet>(A2+i+(I+1)*PacketSize); }\
+          if(RK==4){ KMADD(c0, a3, b30, t0)                     }\
+          if(RK==4){ KMADD(c1, a3, b31, t1)                     }\
+          if(RK==4){ a3 = pload<Packet>(A3+i+(I+1)*PacketSize); }\
+                     pstore(C0+i+(I)*PacketSize, c0);            \
+                     pstore(C1+i+(I)*PacketSize, c1)
+        
+        // process rows of A' - C' with aggressive vectorization and peeling 
+        for(Index i=0; i<actual_b_end1; i+=PacketSize*8)
+        {
+          EIGEN_ASM_COMMENT("SPARSELU_GEMML_KERNEL1");
+                    prefetch((A0+i+(5)*PacketSize));
+                    prefetch((A1+i+(5)*PacketSize));
+          if(RK==4) prefetch((A2+i+(5)*PacketSize));
+          if(RK==4) prefetch((A3+i+(5)*PacketSize));
+
+          WORK(0);
+          WORK(1);
+          WORK(2);
+          WORK(3);
+          WORK(4);
+          WORK(5);
+          WORK(6);
+          WORK(7);
+        }
+        // process the remaining rows with vectorization only
+        for(Index i=actual_b_end1; i<actual_b_end2; i+=PacketSize)
+        {
+          WORK(0);
+        }
+#undef WORK
+        // process the remaining rows without vectorization
+        for(Index i=actual_b_end2; i<actual_b; ++i)
+        {
+          if(RK==4)
+          {
+            C0[i] += A0[i]*Bc0[0]+A1[i]*Bc0[1]+A2[i]*Bc0[2]+A3[i]*Bc0[3];
+            C1[i] += A0[i]*Bc1[0]+A1[i]*Bc1[1]+A2[i]*Bc1[2]+A3[i]*Bc1[3];
+          }
+          else
+          {
+            C0[i] += A0[i]*Bc0[0]+A1[i]*Bc0[1];
+            C1[i] += A0[i]*Bc1[0]+A1[i]*Bc1[1];
+          }
+        }
+        
+        Bc0 += RK;
+        Bc1 += RK;
+      } // peeled loop on k
+    } // peeled loop on the columns j
+    // process the last column (we now perform a matrix-vector product)
+    if((n-n_end)>0)
+    {
+      const Scalar* Bc0 = B+(n-1)*ldb;
+      
+      for(Index k=0; k<d_end; k+=RK)
+      {
+        
+        // load and expand a 1 x RK block of B
+        Packet b00, b10, b20, b30;
+                  b00 = pset1<Packet>(Bc0[0]);
+                  b10 = pset1<Packet>(Bc0[1]);
+        if(RK==4) b20 = pset1<Packet>(Bc0[2]);
+        if(RK==4) b30 = pset1<Packet>(Bc0[3]);
+        
+        Packet a0, a1, a2, a3, c0, t0/*, t1*/;
+        
+        const Scalar* A0 = A+ib+(k+0)*lda;
+        const Scalar* A1 = A+ib+(k+1)*lda;
+        const Scalar* A2 = A+ib+(k+2)*lda;
+        const Scalar* A3 = A+ib+(k+3)*lda;
+        
+        Scalar* C0 = C+ib+(n_end)*ldc;
+        
+                  a0 = pload<Packet>(A0);
+                  a1 = pload<Packet>(A1);
+        if(RK==4)
+        {
+          a2 = pload<Packet>(A2);
+          a3 = pload<Packet>(A3);
+        }
+        else
+        {
+          // workaround "may be used uninitialized in this function" warning
+          a2 = a3 = a0;
+        }
+        
+#define WORK(I) \
+                   c0 = pload<Packet>(C0+i+(I)*PacketSize);     \
+                   KMADD(c0, a0, b00, t0)                       \
+                   a0 = pload<Packet>(A0+i+(I+1)*PacketSize);   \
+                   KMADD(c0, a1, b10, t0)                       \
+                   a1 = pload<Packet>(A1+i+(I+1)*PacketSize);   \
+        if(RK==4){ KMADD(c0, a2, b20, t0)                      }\
+        if(RK==4){ a2 = pload<Packet>(A2+i+(I+1)*PacketSize);  }\
+        if(RK==4){ KMADD(c0, a3, b30, t0)                      }\
+        if(RK==4){ a3 = pload<Packet>(A3+i+(I+1)*PacketSize);  }\
+                   pstore(C0+i+(I)*PacketSize, c0);
+        
+        // aggressive vectorization and peeling
+        for(Index i=0; i<actual_b_end1; i+=PacketSize*8)
+        {
+          EIGEN_ASM_COMMENT("SPARSELU_GEMML_KERNEL2");
+          WORK(0);
+          WORK(1);
+          WORK(2);
+          WORK(3);
+          WORK(4);
+          WORK(5);
+          WORK(6);
+          WORK(7);
+        }
+        // vectorization only
+        for(Index i=actual_b_end1; i<actual_b_end2; i+=PacketSize)
+        {
+          WORK(0);
+        }
+        // remaining scalars
+        for(Index i=actual_b_end2; i<actual_b; ++i)
+        {
+          if(RK==4) 
+            C0[i] += A0[i]*Bc0[0]+A1[i]*Bc0[1]+A2[i]*Bc0[2]+A3[i]*Bc0[3];
+          else
+            C0[i] += A0[i]*Bc0[0]+A1[i]*Bc0[1];
+        }
+        
+        Bc0 += RK;
+#undef WORK
+      }
+    }
+    
+    // process the last columns of A, corresponding to the last rows of B
+    Index rd = d-d_end;
+    if(rd>0)
+    {
+      for(Index j=0; j<n; ++j)
+      {
+        enum {
+          Alignment = PacketSize>1 ? Aligned : 0
+        };
+        typedef Map<Matrix<Scalar,Dynamic,1>, Alignment > MapVector;
+        typedef Map<const Matrix<Scalar,Dynamic,1>, Alignment > ConstMapVector;
+        if(rd==1)       MapVector(C+j*ldc+ib,actual_b) += B[0+d_end+j*ldb] * ConstMapVector(A+(d_end+0)*lda+ib, actual_b);
+        
+        else if(rd==2)  MapVector(C+j*ldc+ib,actual_b) += B[0+d_end+j*ldb] * ConstMapVector(A+(d_end+0)*lda+ib, actual_b)
+                                                        + B[1+d_end+j*ldb] * ConstMapVector(A+(d_end+1)*lda+ib, actual_b);
+        
+        else            MapVector(C+j*ldc+ib,actual_b) += B[0+d_end+j*ldb] * ConstMapVector(A+(d_end+0)*lda+ib, actual_b)
+                                                        + B[1+d_end+j*ldb] * ConstMapVector(A+(d_end+1)*lda+ib, actual_b)
+                                                        + B[2+d_end+j*ldb] * ConstMapVector(A+(d_end+2)*lda+ib, actual_b);
+      }
+    }
+  
+  } // blocking on the rows of A and C
+}
+#undef KMADD
+
+} // namespace internal
+
+} // namespace Eigen
+
+#endif // EIGEN_SPARSELU_GEMM_KERNEL_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_heap_relax_snode.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_heap_relax_snode.h
new file mode 100644
index 0000000..6f75d50
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_heap_relax_snode.h
@@ -0,0 +1,126 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+/* This file is a modified version of heap_relax_snode.c file in SuperLU
+ * -- SuperLU routine (version 3.0) --
+ * Univ. of California Berkeley, Xerox Palo Alto Research Center,
+ * and Lawrence Berkeley National Lab.
+ * October 15, 2003
+ *
+ * Copyright (c) 1994 by Xerox Corporation.  All rights reserved.
+ *
+ * THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY
+ * EXPRESSED OR IMPLIED.  ANY USE IS AT YOUR OWN RISK.
+ *
+ * Permission is hereby granted to use or copy this program for any
+ * purpose, provided the above notices are retained on all copies.
+ * Permission to modify the code and to distribute modified code is
+ * granted, provided the above notices are retained, and a notice that
+ * the code was modified is included with the above copyright notice.
+ */
+
+#ifndef SPARSELU_HEAP_RELAX_SNODE_H
+#define SPARSELU_HEAP_RELAX_SNODE_H
+
+namespace Eigen {
+namespace internal {
+
+/** 
+ * \brief Identify the initial relaxed supernodes
+ * 
+ * This routine applied to a symmetric elimination tree. 
+ * It assumes that the matrix has been reordered according to the postorder of the etree
+ * \param n The number of columns
+ * \param et elimination tree 
+ * \param relax_columns Maximum number of columns allowed in a relaxed snode 
+ * \param descendants Number of descendants of each node in the etree
+ * \param relax_end last column in a supernode
+ */
+template <typename Scalar, typename StorageIndex>
+void SparseLUImpl<Scalar,StorageIndex>::heap_relax_snode (const Index n, IndexVector& et, const Index relax_columns, IndexVector& descendants, IndexVector& relax_end)
+{
+  
+  // The etree may not be postordered, but its heap ordered  
+  IndexVector post;
+  internal::treePostorder(StorageIndex(n), et, post); // Post order etree
+  IndexVector inv_post(n+1); 
+  for (StorageIndex i = 0; i < n+1; ++i) inv_post(post(i)) = i; // inv_post = post.inverse()???
+  
+  // Renumber etree in postorder 
+  IndexVector iwork(n);
+  IndexVector et_save(n+1);
+  for (Index i = 0; i < n; ++i)
+  {
+    iwork(post(i)) = post(et(i));
+  }
+  et_save = et; // Save the original etree
+  et = iwork; 
+  
+  // compute the number of descendants of each node in the etree
+  relax_end.setConstant(emptyIdxLU);
+  Index j, parent; 
+  descendants.setZero();
+  for (j = 0; j < n; j++) 
+  {
+    parent = et(j);
+    if (parent != n) // not the dummy root
+      descendants(parent) += descendants(j) + 1;
+  }
+  // Identify the relaxed supernodes by postorder traversal of the etree
+  Index snode_start; // beginning of a snode 
+  StorageIndex k;
+  Index nsuper_et_post = 0; // Number of relaxed snodes in postordered etree 
+  Index nsuper_et = 0; // Number of relaxed snodes in the original etree 
+  StorageIndex l; 
+  for (j = 0; j < n; )
+  {
+    parent = et(j);
+    snode_start = j; 
+    while ( parent != n && descendants(parent) < relax_columns ) 
+    {
+      j = parent; 
+      parent = et(j);
+    }
+    // Found a supernode in postordered etree, j is the last column 
+    ++nsuper_et_post;
+    k = StorageIndex(n);
+    for (Index i = snode_start; i <= j; ++i)
+      k = (std::min)(k, inv_post(i));
+    l = inv_post(j);
+    if ( (l - k) == (j - snode_start) )  // Same number of columns in the snode
+    {
+      // This is also a supernode in the original etree
+      relax_end(k) = l; // Record last column 
+      ++nsuper_et; 
+    }
+    else 
+    {
+      for (Index i = snode_start; i <= j; ++i) 
+      {
+        l = inv_post(i);
+        if (descendants(i) == 0) 
+        {
+          relax_end(l) = l;
+          ++nsuper_et;
+        }
+      }
+    }
+    j++;
+    // Search for a new leaf
+    while (descendants(j) != 0 && j < n) j++;
+  } // End postorder traversal of the etree
+  
+  // Recover the original etree
+  et = et_save; 
+}
+
+} // end namespace internal
+
+} // end namespace Eigen
+#endif // SPARSELU_HEAP_RELAX_SNODE_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_kernel_bmod.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_kernel_bmod.h
new file mode 100644
index 0000000..8c1b3e8
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_kernel_bmod.h
@@ -0,0 +1,130 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>
+// Copyright (C) 2012 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef SPARSELU_KERNEL_BMOD_H
+#define SPARSELU_KERNEL_BMOD_H
+
+namespace Eigen {
+namespace internal {
+  
+template <int SegSizeAtCompileTime> struct LU_kernel_bmod
+{
+  /** \internal
+    * \brief Performs numeric block updates from a given supernode to a single column
+    *
+    * \param segsize Size of the segment (and blocks ) to use for updates
+    * \param[in,out] dense Packed values of the original matrix
+    * \param tempv temporary vector to use for updates
+    * \param lusup array containing the supernodes
+    * \param lda Leading dimension in the supernode
+    * \param nrow Number of rows in the rectangular part of the supernode
+    * \param lsub compressed row subscripts of supernodes
+    * \param lptr pointer to the first column of the current supernode in lsub
+    * \param no_zeros Number of nonzeros elements before the diagonal part of the supernode
+    */
+  template <typename BlockScalarVector, typename ScalarVector, typename IndexVector>
+  static EIGEN_DONT_INLINE void run(const Index segsize, BlockScalarVector& dense, ScalarVector& tempv, ScalarVector& lusup, Index& luptr, const Index lda,
+                                    const Index nrow, IndexVector& lsub, const Index lptr, const Index no_zeros);
+};
+
+template <int SegSizeAtCompileTime>
+template <typename BlockScalarVector, typename ScalarVector, typename IndexVector>
+EIGEN_DONT_INLINE void LU_kernel_bmod<SegSizeAtCompileTime>::run(const Index segsize, BlockScalarVector& dense, ScalarVector& tempv, ScalarVector& lusup, Index& luptr, const Index lda,
+                                                                  const Index nrow, IndexVector& lsub, const Index lptr, const Index no_zeros)
+{
+  typedef typename ScalarVector::Scalar Scalar;
+  // First, copy U[*,j] segment from dense(*) to tempv(*)
+  // The result of triangular solve is in tempv[*]; 
+    // The result of matric-vector update is in dense[*]
+  Index isub = lptr + no_zeros; 
+  Index i;
+  Index irow;
+  for (i = 0; i < ((SegSizeAtCompileTime==Dynamic)?segsize:SegSizeAtCompileTime); i++)
+  {
+    irow = lsub(isub); 
+    tempv(i) = dense(irow); 
+    ++isub; 
+  }
+  // Dense triangular solve -- start effective triangle
+  luptr += lda * no_zeros + no_zeros; 
+  // Form Eigen matrix and vector 
+  Map<Matrix<Scalar,SegSizeAtCompileTime,SegSizeAtCompileTime, ColMajor>, 0, OuterStride<> > A( &(lusup.data()[luptr]), segsize, segsize, OuterStride<>(lda) );
+  Map<Matrix<Scalar,SegSizeAtCompileTime,1> > u(tempv.data(), segsize);
+  
+  u = A.template triangularView<UnitLower>().solve(u); 
+  
+  // Dense matrix-vector product y <-- B*x 
+  luptr += segsize;
+  const Index PacketSize = internal::packet_traits<Scalar>::size;
+  Index ldl = internal::first_multiple(nrow, PacketSize);
+  Map<Matrix<Scalar,Dynamic,SegSizeAtCompileTime, ColMajor>, 0, OuterStride<> > B( &(lusup.data()[luptr]), nrow, segsize, OuterStride<>(lda) );
+  Index aligned_offset = internal::first_default_aligned(tempv.data()+segsize, PacketSize);
+  Index aligned_with_B_offset = (PacketSize-internal::first_default_aligned(B.data(), PacketSize))%PacketSize;
+  Map<Matrix<Scalar,Dynamic,1>, 0, OuterStride<> > l(tempv.data()+segsize+aligned_offset+aligned_with_B_offset, nrow, OuterStride<>(ldl) );
+  
+  l.setZero();
+  internal::sparselu_gemm<Scalar>(l.rows(), l.cols(), B.cols(), B.data(), B.outerStride(), u.data(), u.outerStride(), l.data(), l.outerStride());
+  
+  // Scatter tempv[] into SPA dense[] as a temporary storage 
+  isub = lptr + no_zeros;
+  for (i = 0; i < ((SegSizeAtCompileTime==Dynamic)?segsize:SegSizeAtCompileTime); i++)
+  {
+    irow = lsub(isub++); 
+    dense(irow) = tempv(i);
+  }
+  
+  // Scatter l into SPA dense[]
+  for (i = 0; i < nrow; i++)
+  {
+    irow = lsub(isub++); 
+    dense(irow) -= l(i);
+  } 
+}
+
+template <> struct LU_kernel_bmod<1>
+{
+  template <typename BlockScalarVector, typename ScalarVector, typename IndexVector>
+  static EIGEN_DONT_INLINE void run(const Index /*segsize*/, BlockScalarVector& dense, ScalarVector& /*tempv*/, ScalarVector& lusup, Index& luptr,
+                                    const Index lda, const Index nrow, IndexVector& lsub, const Index lptr, const Index no_zeros);
+};
+
+
+template <typename BlockScalarVector, typename ScalarVector, typename IndexVector>
+EIGEN_DONT_INLINE void LU_kernel_bmod<1>::run(const Index /*segsize*/, BlockScalarVector& dense, ScalarVector& /*tempv*/, ScalarVector& lusup, Index& luptr,
+                                              const Index lda, const Index nrow, IndexVector& lsub, const Index lptr, const Index no_zeros)
+{
+  typedef typename ScalarVector::Scalar Scalar;
+  typedef typename IndexVector::Scalar StorageIndex;
+  Scalar f = dense(lsub(lptr + no_zeros));
+  luptr += lda * no_zeros + no_zeros + 1;
+  const Scalar* a(lusup.data() + luptr);
+  const StorageIndex*  irow(lsub.data()+lptr + no_zeros + 1);
+  Index i = 0;
+  for (; i+1 < nrow; i+=2)
+  {
+    Index i0 = *(irow++);
+    Index i1 = *(irow++);
+    Scalar a0 = *(a++);
+    Scalar a1 = *(a++);
+    Scalar d0 = dense.coeff(i0);
+    Scalar d1 = dense.coeff(i1);
+    d0 -= f*a0;
+    d1 -= f*a1;
+    dense.coeffRef(i0) = d0;
+    dense.coeffRef(i1) = d1;
+  }
+  if(i<nrow)
+    dense.coeffRef(*(irow++)) -= f * *(a++);
+}
+
+} // end namespace internal
+
+} // end namespace Eigen
+#endif // SPARSELU_KERNEL_BMOD_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_panel_bmod.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_panel_bmod.h
new file mode 100644
index 0000000..f052001
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_panel_bmod.h
@@ -0,0 +1,223 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>
+// Copyright (C) 2012 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+/* 
+ 
+ * NOTE: This file is the modified version of [s,d,c,z]panel_bmod.c file in SuperLU 
+ 
+ * -- SuperLU routine (version 3.0) --
+ * Univ. of California Berkeley, Xerox Palo Alto Research Center,
+ * and Lawrence Berkeley National Lab.
+ * October 15, 2003
+ *
+ * Copyright (c) 1994 by Xerox Corporation.  All rights reserved.
+ *
+ * THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY
+ * EXPRESSED OR IMPLIED.  ANY USE IS AT YOUR OWN RISK.
+ *
+ * Permission is hereby granted to use or copy this program for any
+ * purpose, provided the above notices are retained on all copies.
+ * Permission to modify the code and to distribute modified code is
+ * granted, provided the above notices are retained, and a notice that
+ * the code was modified is included with the above copyright notice.
+ */
+#ifndef SPARSELU_PANEL_BMOD_H
+#define SPARSELU_PANEL_BMOD_H
+
+namespace Eigen {
+namespace internal {
+
+/**
+ * \brief Performs numeric block updates (sup-panel) in topological order.
+ * 
+ * Before entering this routine, the original nonzeros in the panel
+ * were already copied into the spa[m,w]
+ * 
+ * \param m number of rows in the matrix
+ * \param w Panel size
+ * \param jcol Starting  column of the panel
+ * \param nseg Number of segments in the U part
+ * \param dense Store the full representation of the panel 
+ * \param tempv working array 
+ * \param segrep segment representative... first row in the segment
+ * \param repfnz First nonzero rows
+ * \param glu Global LU data. 
+ * 
+ * 
+ */
+template <typename Scalar, typename StorageIndex>
+void SparseLUImpl<Scalar,StorageIndex>::panel_bmod(const Index m, const Index w, const Index jcol, 
+                                            const Index nseg, ScalarVector& dense, ScalarVector& tempv,
+                                            IndexVector& segrep, IndexVector& repfnz, GlobalLU_t& glu)
+{
+  
+  Index ksub,jj,nextl_col; 
+  Index fsupc, nsupc, nsupr, nrow; 
+  Index krep, kfnz; 
+  Index lptr; // points to the row subscripts of a supernode 
+  Index luptr; // ...
+  Index segsize,no_zeros ; 
+  // For each nonz supernode segment of U[*,j] in topological order
+  Index k = nseg - 1; 
+  const Index PacketSize = internal::packet_traits<Scalar>::size;
+  
+  for (ksub = 0; ksub < nseg; ksub++)
+  { // For each updating supernode
+    /* krep = representative of current k-th supernode
+     * fsupc =  first supernodal column
+     * nsupc = number of columns in a supernode
+     * nsupr = number of rows in a supernode
+     */
+    krep = segrep(k); k--; 
+    fsupc = glu.xsup(glu.supno(krep)); 
+    nsupc = krep - fsupc + 1; 
+    nsupr = glu.xlsub(fsupc+1) - glu.xlsub(fsupc); 
+    nrow = nsupr - nsupc; 
+    lptr = glu.xlsub(fsupc); 
+    
+    // loop over the panel columns to detect the actual number of columns and rows
+    Index u_rows = 0;
+    Index u_cols = 0;
+    for (jj = jcol; jj < jcol + w; jj++)
+    {
+      nextl_col = (jj-jcol) * m; 
+      VectorBlock<IndexVector> repfnz_col(repfnz, nextl_col, m); // First nonzero column index for each row
+      
+      kfnz = repfnz_col(krep); 
+      if ( kfnz == emptyIdxLU ) 
+        continue; // skip any zero segment
+      
+      segsize = krep - kfnz + 1;
+      u_cols++;
+      u_rows = (std::max)(segsize,u_rows);
+    }
+    
+    if(nsupc >= 2)
+    { 
+      Index ldu = internal::first_multiple<Index>(u_rows, PacketSize);
+      Map<ScalarMatrix, Aligned,  OuterStride<> > U(tempv.data(), u_rows, u_cols, OuterStride<>(ldu));
+      
+      // gather U
+      Index u_col = 0;
+      for (jj = jcol; jj < jcol + w; jj++)
+      {
+        nextl_col = (jj-jcol) * m; 
+        VectorBlock<IndexVector> repfnz_col(repfnz, nextl_col, m); // First nonzero column index for each row
+        VectorBlock<ScalarVector> dense_col(dense, nextl_col, m); // Scatter/gather entire matrix column from/to here
+        
+        kfnz = repfnz_col(krep); 
+        if ( kfnz == emptyIdxLU ) 
+          continue; // skip any zero segment
+        
+        segsize = krep - kfnz + 1;
+        luptr = glu.xlusup(fsupc);    
+        no_zeros = kfnz - fsupc; 
+        
+        Index isub = lptr + no_zeros;
+        Index off = u_rows-segsize;
+        for (Index i = 0; i < off; i++) U(i,u_col) = 0;
+        for (Index i = 0; i < segsize; i++)
+        {
+          Index irow = glu.lsub(isub); 
+          U(i+off,u_col) = dense_col(irow); 
+          ++isub; 
+        }
+        u_col++;
+      }
+      // solve U = A^-1 U
+      luptr = glu.xlusup(fsupc);
+      Index lda = glu.xlusup(fsupc+1) - glu.xlusup(fsupc);
+      no_zeros = (krep - u_rows + 1) - fsupc;
+      luptr += lda * no_zeros + no_zeros;
+      MappedMatrixBlock A(glu.lusup.data()+luptr, u_rows, u_rows, OuterStride<>(lda) );
+      U = A.template triangularView<UnitLower>().solve(U);
+      
+      // update
+      luptr += u_rows;
+      MappedMatrixBlock B(glu.lusup.data()+luptr, nrow, u_rows, OuterStride<>(lda) );
+      eigen_assert(tempv.size()>w*ldu + nrow*w + 1);
+      
+      Index ldl = internal::first_multiple<Index>(nrow, PacketSize);
+      Index offset = (PacketSize-internal::first_default_aligned(B.data(), PacketSize)) % PacketSize;
+      MappedMatrixBlock L(tempv.data()+w*ldu+offset, nrow, u_cols, OuterStride<>(ldl));
+      
+      L.setZero();
+      internal::sparselu_gemm<Scalar>(L.rows(), L.cols(), B.cols(), B.data(), B.outerStride(), U.data(), U.outerStride(), L.data(), L.outerStride());
+      
+      // scatter U and L
+      u_col = 0;
+      for (jj = jcol; jj < jcol + w; jj++)
+      {
+        nextl_col = (jj-jcol) * m; 
+        VectorBlock<IndexVector> repfnz_col(repfnz, nextl_col, m); // First nonzero column index for each row
+        VectorBlock<ScalarVector> dense_col(dense, nextl_col, m); // Scatter/gather entire matrix column from/to here
+        
+        kfnz = repfnz_col(krep); 
+        if ( kfnz == emptyIdxLU ) 
+          continue; // skip any zero segment
+        
+        segsize = krep - kfnz + 1;
+        no_zeros = kfnz - fsupc; 
+        Index isub = lptr + no_zeros;
+        
+        Index off = u_rows-segsize;
+        for (Index i = 0; i < segsize; i++)
+        {
+          Index irow = glu.lsub(isub++); 
+          dense_col(irow) = U.coeff(i+off,u_col);
+          U.coeffRef(i+off,u_col) = 0;
+        }
+        
+        // Scatter l into SPA dense[]
+        for (Index i = 0; i < nrow; i++)
+        {
+          Index irow = glu.lsub(isub++); 
+          dense_col(irow) -= L.coeff(i,u_col);
+          L.coeffRef(i,u_col) = 0;
+        }
+        u_col++;
+      }
+    }
+    else // level 2 only
+    {
+      // Sequence through each column in the panel
+      for (jj = jcol; jj < jcol + w; jj++)
+      {
+        nextl_col = (jj-jcol) * m; 
+        VectorBlock<IndexVector> repfnz_col(repfnz, nextl_col, m); // First nonzero column index for each row
+        VectorBlock<ScalarVector> dense_col(dense, nextl_col, m); // Scatter/gather entire matrix column from/to here
+        
+        kfnz = repfnz_col(krep); 
+        if ( kfnz == emptyIdxLU ) 
+          continue; // skip any zero segment
+        
+        segsize = krep - kfnz + 1;
+        luptr = glu.xlusup(fsupc);
+        
+        Index lda = glu.xlusup(fsupc+1)-glu.xlusup(fsupc);// nsupr
+        
+        // Perform a trianglar solve and block update, 
+        // then scatter the result of sup-col update to dense[]
+        no_zeros = kfnz - fsupc; 
+              if(segsize==1)  LU_kernel_bmod<1>::run(segsize, dense_col, tempv, glu.lusup, luptr, lda, nrow, glu.lsub, lptr, no_zeros);
+        else  if(segsize==2)  LU_kernel_bmod<2>::run(segsize, dense_col, tempv, glu.lusup, luptr, lda, nrow, glu.lsub, lptr, no_zeros);
+        else  if(segsize==3)  LU_kernel_bmod<3>::run(segsize, dense_col, tempv, glu.lusup, luptr, lda, nrow, glu.lsub, lptr, no_zeros);
+        else                  LU_kernel_bmod<Dynamic>::run(segsize, dense_col, tempv, glu.lusup, luptr, lda, nrow, glu.lsub, lptr, no_zeros); 
+      } // End for each column in the panel 
+    }
+    
+  } // End for each updating supernode
+} // end panel bmod
+
+} // end namespace internal
+
+} // end namespace Eigen
+
+#endif // SPARSELU_PANEL_BMOD_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_panel_dfs.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_panel_dfs.h
new file mode 100644
index 0000000..155df73
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_panel_dfs.h
@@ -0,0 +1,258 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+/* 
+ 
+ * NOTE: This file is the modified version of [s,d,c,z]panel_dfs.c file in SuperLU 
+ 
+ * -- SuperLU routine (version 2.0) --
+ * Univ. of California Berkeley, Xerox Palo Alto Research Center,
+ * and Lawrence Berkeley National Lab.
+ * November 15, 1997
+ *
+ * Copyright (c) 1994 by Xerox Corporation.  All rights reserved.
+ *
+ * THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY
+ * EXPRESSED OR IMPLIED.  ANY USE IS AT YOUR OWN RISK.
+ *
+ * Permission is hereby granted to use or copy this program for any
+ * purpose, provided the above notices are retained on all copies.
+ * Permission to modify the code and to distribute modified code is
+ * granted, provided the above notices are retained, and a notice that
+ * the code was modified is included with the above copyright notice.
+ */
+#ifndef SPARSELU_PANEL_DFS_H
+#define SPARSELU_PANEL_DFS_H
+
+namespace Eigen {
+
+namespace internal {
+  
+template<typename IndexVector>
+struct panel_dfs_traits
+{
+  typedef typename IndexVector::Scalar StorageIndex;
+  panel_dfs_traits(Index jcol, StorageIndex* marker)
+    : m_jcol(jcol), m_marker(marker)
+  {}
+  bool update_segrep(Index krep, StorageIndex jj)
+  {
+    if(m_marker[krep]<m_jcol)
+    {
+      m_marker[krep] = jj; 
+      return true;
+    }
+    return false;
+  }
+  void mem_expand(IndexVector& /*glu.lsub*/, Index /*nextl*/, Index /*chmark*/) {}
+  enum { ExpandMem = false };
+  Index m_jcol;
+  StorageIndex* m_marker;
+};
+
+
+template <typename Scalar, typename StorageIndex>
+template <typename Traits>
+void SparseLUImpl<Scalar,StorageIndex>::dfs_kernel(const StorageIndex jj, IndexVector& perm_r,
+                   Index& nseg, IndexVector& panel_lsub, IndexVector& segrep,
+                   Ref<IndexVector> repfnz_col, IndexVector& xprune, Ref<IndexVector> marker, IndexVector& parent,
+                   IndexVector& xplore, GlobalLU_t& glu,
+                   Index& nextl_col, Index krow, Traits& traits
+                  )
+{
+  
+  StorageIndex kmark = marker(krow);
+      
+  // For each unmarked krow of jj
+  marker(krow) = jj; 
+  StorageIndex kperm = perm_r(krow); 
+  if (kperm == emptyIdxLU ) {
+    // krow is in L : place it in structure of L(*, jj)
+    panel_lsub(nextl_col++) = StorageIndex(krow);  // krow is indexed into A
+    
+    traits.mem_expand(panel_lsub, nextl_col, kmark);
+  }
+  else 
+  {
+    // krow is in U : if its supernode-representative krep
+    // has been explored, update repfnz(*)
+    // krep = supernode representative of the current row
+    StorageIndex krep = glu.xsup(glu.supno(kperm)+1) - 1; 
+    // First nonzero element in the current column:
+    StorageIndex myfnz = repfnz_col(krep); 
+    
+    if (myfnz != emptyIdxLU )
+    {
+      // Representative visited before
+      if (myfnz > kperm ) repfnz_col(krep) = kperm; 
+      
+    }
+    else 
+    {
+      // Otherwise, perform dfs starting at krep
+      StorageIndex oldrep = emptyIdxLU; 
+      parent(krep) = oldrep; 
+      repfnz_col(krep) = kperm; 
+      StorageIndex xdfs =  glu.xlsub(krep); 
+      Index maxdfs = xprune(krep); 
+      
+      StorageIndex kpar;
+      do 
+      {
+        // For each unmarked kchild of krep
+        while (xdfs < maxdfs) 
+        {
+          StorageIndex kchild = glu.lsub(xdfs); 
+          xdfs++; 
+          StorageIndex chmark = marker(kchild); 
+          
+          if (chmark != jj ) 
+          {
+            marker(kchild) = jj; 
+            StorageIndex chperm = perm_r(kchild); 
+            
+            if (chperm == emptyIdxLU) 
+            {
+              // case kchild is in L: place it in L(*, j)
+              panel_lsub(nextl_col++) = kchild;
+              traits.mem_expand(panel_lsub, nextl_col, chmark);
+            }
+            else
+            {
+              // case kchild is in U :
+              // chrep = its supernode-rep. If its rep has been explored, 
+              // update its repfnz(*)
+              StorageIndex chrep = glu.xsup(glu.supno(chperm)+1) - 1; 
+              myfnz = repfnz_col(chrep); 
+              
+              if (myfnz != emptyIdxLU) 
+              { // Visited before 
+                if (myfnz > chperm) 
+                  repfnz_col(chrep) = chperm; 
+              }
+              else 
+              { // Cont. dfs at snode-rep of kchild
+                xplore(krep) = xdfs; 
+                oldrep = krep; 
+                krep = chrep; // Go deeper down G(L)
+                parent(krep) = oldrep; 
+                repfnz_col(krep) = chperm; 
+                xdfs = glu.xlsub(krep); 
+                maxdfs = xprune(krep); 
+                
+              } // end if myfnz != -1
+            } // end if chperm == -1 
+                
+          } // end if chmark !=jj
+        } // end while xdfs < maxdfs
+        
+        // krow has no more unexplored nbrs :
+        //    Place snode-rep krep in postorder DFS, if this 
+        //    segment is seen for the first time. (Note that 
+        //    "repfnz(krep)" may change later.)
+        //    Baktrack dfs to its parent
+        if(traits.update_segrep(krep,jj))
+        //if (marker1(krep) < jcol )
+        {
+          segrep(nseg) = krep; 
+          ++nseg; 
+          //marker1(krep) = jj; 
+        }
+        
+        kpar = parent(krep); // Pop recursion, mimic recursion 
+        if (kpar == emptyIdxLU) 
+          break; // dfs done 
+        krep = kpar; 
+        xdfs = xplore(krep); 
+        maxdfs = xprune(krep); 
+
+      } while (kpar != emptyIdxLU); // Do until empty stack 
+      
+    } // end if (myfnz = -1)
+
+  } // end if (kperm == -1)   
+}
+
+/**
+ * \brief Performs a symbolic factorization on a panel of columns [jcol, jcol+w)
+ * 
+ * A supernode representative is the last column of a supernode.
+ * The nonzeros in U[*,j] are segments that end at supernodes representatives
+ * 
+ * The routine returns a list of the supernodal representatives 
+ * in topological order of the dfs that generates them. This list is 
+ * a superset of the topological order of each individual column within 
+ * the panel.
+ * The location of the first nonzero in each supernodal segment 
+ * (supernodal entry location) is also returned. Each column has 
+ * a separate list for this purpose. 
+ * 
+ * Two markers arrays are used for dfs :
+ *    marker[i] == jj, if i was visited during dfs of current column jj;
+ *    marker1[i] >= jcol, if i was visited by earlier columns in this panel; 
+ * 
+ * \param[in] m number of rows in the matrix
+ * \param[in] w Panel size
+ * \param[in] jcol Starting  column of the panel
+ * \param[in] A Input matrix in column-major storage
+ * \param[in] perm_r Row permutation
+ * \param[out] nseg Number of U segments
+ * \param[out] dense Accumulate the column vectors of the panel
+ * \param[out] panel_lsub Subscripts of the row in the panel 
+ * \param[out] segrep Segment representative i.e first nonzero row of each segment
+ * \param[out] repfnz First nonzero location in each row
+ * \param[out] xprune The pruned elimination tree
+ * \param[out] marker work vector
+ * \param  parent The elimination tree
+ * \param xplore work vector
+ * \param glu The global data structure
+ * 
+ */
+
+template <typename Scalar, typename StorageIndex>
+void SparseLUImpl<Scalar,StorageIndex>::panel_dfs(const Index m, const Index w, const Index jcol, MatrixType& A, IndexVector& perm_r, Index& nseg, ScalarVector& dense, IndexVector& panel_lsub, IndexVector& segrep, IndexVector& repfnz, IndexVector& xprune, IndexVector& marker, IndexVector& parent, IndexVector& xplore, GlobalLU_t& glu)
+{
+  Index nextl_col; // Next available position in panel_lsub[*,jj] 
+  
+  // Initialize pointers 
+  VectorBlock<IndexVector> marker1(marker, m, m); 
+  nseg = 0; 
+  
+  panel_dfs_traits<IndexVector> traits(jcol, marker1.data());
+  
+  // For each column in the panel 
+  for (StorageIndex jj = StorageIndex(jcol); jj < jcol + w; jj++) 
+  {
+    nextl_col = (jj - jcol) * m; 
+    
+    VectorBlock<IndexVector> repfnz_col(repfnz, nextl_col, m); // First nonzero location in each row
+    VectorBlock<ScalarVector> dense_col(dense,nextl_col, m); // Accumulate a column vector here
+    
+    
+    // For each nnz in A[*, jj] do depth first search
+    for (typename MatrixType::InnerIterator it(A, jj); it; ++it)
+    {
+      Index krow = it.row(); 
+      dense_col(krow) = it.value();
+      
+      StorageIndex kmark = marker(krow); 
+      if (kmark == jj) 
+        continue; // krow visited before, go to the next nonzero
+      
+      dfs_kernel(jj, perm_r, nseg, panel_lsub, segrep, repfnz_col, xprune, marker, parent,
+                   xplore, glu, nextl_col, krow, traits);
+    }// end for nonzeros in column jj
+    
+  } // end for column jj
+}
+
+} // end namespace internal
+} // end namespace Eigen
+
+#endif // SPARSELU_PANEL_DFS_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_pivotL.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_pivotL.h
new file mode 100644
index 0000000..a86dac9
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_pivotL.h
@@ -0,0 +1,137 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+/* 
+ 
+ * NOTE: This file is the modified version of xpivotL.c file in SuperLU 
+ 
+ * -- SuperLU routine (version 3.0) --
+ * Univ. of California Berkeley, Xerox Palo Alto Research Center,
+ * and Lawrence Berkeley National Lab.
+ * October 15, 2003
+ *
+ * Copyright (c) 1994 by Xerox Corporation.  All rights reserved.
+ *
+ * THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY
+ * EXPRESSED OR IMPLIED.  ANY USE IS AT YOUR OWN RISK.
+ *
+ * Permission is hereby granted to use or copy this program for any
+ * purpose, provided the above notices are retained on all copies.
+ * Permission to modify the code and to distribute modified code is
+ * granted, provided the above notices are retained, and a notice that
+ * the code was modified is included with the above copyright notice.
+ */
+#ifndef SPARSELU_PIVOTL_H
+#define SPARSELU_PIVOTL_H
+
+namespace Eigen {
+namespace internal {
+  
+/**
+ * \brief Performs the numerical pivotin on the current column of L, and the CDIV operation.
+ * 
+ * Pivot policy :
+ * (1) Compute thresh = u * max_(i>=j) abs(A_ij);
+ * (2) IF user specifies pivot row k and abs(A_kj) >= thresh THEN
+ *           pivot row = k;
+ *       ELSE IF abs(A_jj) >= thresh THEN
+ *           pivot row = j;
+ *       ELSE
+ *           pivot row = m;
+ * 
+ *   Note: If you absolutely want to use a given pivot order, then set u=0.0.
+ * 
+ * \param jcol The current column of L
+ * \param diagpivotthresh diagonal pivoting threshold
+ * \param[in,out] perm_r Row permutation (threshold pivoting)
+ * \param[in] iperm_c column permutation - used to finf diagonal of Pc*A*Pc'
+ * \param[out] pivrow  The pivot row
+ * \param glu Global LU data
+ * \return 0 if success, i > 0 if U(i,i) is exactly zero 
+ * 
+ */
+template <typename Scalar, typename StorageIndex>
+Index SparseLUImpl<Scalar,StorageIndex>::pivotL(const Index jcol, const RealScalar& diagpivotthresh, IndexVector& perm_r, IndexVector& iperm_c, Index& pivrow, GlobalLU_t& glu)
+{
+  
+  Index fsupc = (glu.xsup)((glu.supno)(jcol)); // First column in the supernode containing the column jcol
+  Index nsupc = jcol - fsupc; // Number of columns in the supernode portion, excluding jcol; nsupc >=0
+  Index lptr = glu.xlsub(fsupc); // pointer to the starting location of the row subscripts for this supernode portion
+  Index nsupr = glu.xlsub(fsupc+1) - lptr; // Number of rows in the supernode
+  Index lda = glu.xlusup(fsupc+1) - glu.xlusup(fsupc); // leading dimension
+  Scalar* lu_sup_ptr = &(glu.lusup.data()[glu.xlusup(fsupc)]); // Start of the current supernode
+  Scalar* lu_col_ptr = &(glu.lusup.data()[glu.xlusup(jcol)]); // Start of jcol in the supernode
+  StorageIndex* lsub_ptr = &(glu.lsub.data()[lptr]); // Start of row indices of the supernode
+  
+  // Determine the largest abs numerical value for partial pivoting 
+  Index diagind = iperm_c(jcol); // diagonal index 
+  RealScalar pivmax(-1.0);
+  Index pivptr = nsupc; 
+  Index diag = emptyIdxLU; 
+  RealScalar rtemp;
+  Index isub, icol, itemp, k; 
+  for (isub = nsupc; isub < nsupr; ++isub) {
+    using std::abs;
+    rtemp = abs(lu_col_ptr[isub]);
+    if (rtemp > pivmax) {
+      pivmax = rtemp; 
+      pivptr = isub;
+    } 
+    if (lsub_ptr[isub] == diagind) diag = isub;
+  }
+  
+  // Test for singularity
+  if ( pivmax <= RealScalar(0.0) ) {
+    // if pivmax == -1, the column is structurally empty, otherwise it is only numerically zero
+    pivrow = pivmax < RealScalar(0.0) ? diagind : lsub_ptr[pivptr];
+    perm_r(pivrow) = StorageIndex(jcol);
+    return (jcol+1);
+  }
+  
+  RealScalar thresh = diagpivotthresh * pivmax; 
+  
+  // Choose appropriate pivotal element 
+  
+  {
+    // Test if the diagonal element can be used as a pivot (given the threshold value)
+    if (diag >= 0 ) 
+    {
+      // Diagonal element exists
+      using std::abs;
+      rtemp = abs(lu_col_ptr[diag]);
+      if (rtemp != RealScalar(0.0) && rtemp >= thresh) pivptr = diag;
+    }
+    pivrow = lsub_ptr[pivptr];
+  }
+  
+  // Record pivot row
+  perm_r(pivrow) = StorageIndex(jcol);
+  // Interchange row subscripts
+  if (pivptr != nsupc )
+  {
+    std::swap( lsub_ptr[pivptr], lsub_ptr[nsupc] );
+    // Interchange numerical values as well, for the two rows in the whole snode
+    // such that L is indexed the same way as A
+    for (icol = 0; icol <= nsupc; icol++)
+    {
+      itemp = pivptr + icol * lda; 
+      std::swap(lu_sup_ptr[itemp], lu_sup_ptr[nsupc + icol * lda]);
+    }
+  }
+  // cdiv operations
+  Scalar temp = Scalar(1.0) / lu_col_ptr[nsupc];
+  for (k = nsupc+1; k < nsupr; k++)
+    lu_col_ptr[k] *= temp; 
+  return 0;
+}
+
+} // end namespace internal
+} // end namespace Eigen
+
+#endif // SPARSELU_PIVOTL_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_pruneL.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_pruneL.h
new file mode 100644
index 0000000..ad32fed
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_pruneL.h
@@ -0,0 +1,136 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+/* 
+ 
+ * NOTE: This file is the modified version of [s,d,c,z]pruneL.c file in SuperLU 
+ 
+ * -- SuperLU routine (version 2.0) --
+ * Univ. of California Berkeley, Xerox Palo Alto Research Center,
+ * and Lawrence Berkeley National Lab.
+ * November 15, 1997
+ *
+ * Copyright (c) 1994 by Xerox Corporation.  All rights reserved.
+ *
+ * THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY
+ * EXPRESSED OR IMPLIED.  ANY USE IS AT YOUR OWN RISK.
+ *
+ * Permission is hereby granted to use or copy this program for any
+ * purpose, provided the above notices are retained on all copies.
+ * Permission to modify the code and to distribute modified code is
+ * granted, provided the above notices are retained, and a notice that
+ * the code was modified is included with the above copyright notice.
+ */
+#ifndef SPARSELU_PRUNEL_H
+#define SPARSELU_PRUNEL_H
+
+namespace Eigen {
+namespace internal {
+
+/**
+ * \brief Prunes the L-structure.
+ *
+ * It prunes the L-structure  of supernodes whose L-structure contains the current pivot row "pivrow"
+ * 
+ * 
+ * \param jcol The current column of L
+ * \param[in] perm_r Row permutation
+ * \param[out] pivrow  The pivot row
+ * \param nseg Number of segments
+ * \param segrep 
+ * \param repfnz
+ * \param[out] xprune 
+ * \param glu Global LU data
+ * 
+ */
+template <typename Scalar, typename StorageIndex>
+void SparseLUImpl<Scalar,StorageIndex>::pruneL(const Index jcol, const IndexVector& perm_r, const Index pivrow, const Index nseg,
+                                               const IndexVector& segrep, BlockIndexVector repfnz, IndexVector& xprune, GlobalLU_t& glu)
+{
+  // For each supernode-rep irep in U(*,j]
+  Index jsupno = glu.supno(jcol); 
+  Index i,irep,irep1; 
+  bool movnum, do_prune = false; 
+  Index kmin = 0, kmax = 0, minloc, maxloc,krow; 
+  for (i = 0; i < nseg; i++)
+  {
+    irep = segrep(i); 
+    irep1 = irep + 1; 
+    do_prune = false; 
+    
+    // Don't prune with a zero U-segment 
+    if (repfnz(irep) == emptyIdxLU) continue; 
+    
+    // If a snode overlaps with the next panel, then the U-segment
+    // is fragmented into two parts -- irep and irep1. We should let 
+    // pruning occur at the rep-column in irep1s snode. 
+    if (glu.supno(irep) == glu.supno(irep1) ) continue; // don't prune 
+    
+    // If it has not been pruned & it has a nonz in row L(pivrow,i)
+    if (glu.supno(irep) != jsupno )
+    {
+      if ( xprune (irep) >= glu.xlsub(irep1) )
+      {
+        kmin = glu.xlsub(irep);
+        kmax = glu.xlsub(irep1) - 1; 
+        for (krow = kmin; krow <= kmax; krow++)
+        {
+          if (glu.lsub(krow) == pivrow) 
+          {
+            do_prune = true; 
+            break; 
+          }
+        }
+      }
+      
+      if (do_prune) 
+      {
+        // do a quicksort-type partition
+        // movnum=true means that the num values have to be exchanged
+        movnum = false; 
+        if (irep == glu.xsup(glu.supno(irep)) ) // Snode of size 1 
+          movnum = true; 
+        
+        while (kmin <= kmax)
+        {
+          if (perm_r(glu.lsub(kmax)) == emptyIdxLU)
+            kmax--; 
+          else if ( perm_r(glu.lsub(kmin)) != emptyIdxLU)
+            kmin++;
+          else 
+          {
+            // kmin below pivrow (not yet pivoted), and kmax
+            // above pivrow: interchange the two suscripts
+            std::swap(glu.lsub(kmin), glu.lsub(kmax)); 
+            
+            // If the supernode has only one column, then we 
+            // only keep one set of subscripts. For any subscript
+            // intercnahge performed, similar interchange must be 
+            // done on the numerical values. 
+            if (movnum) 
+            {
+              minloc = glu.xlusup(irep) + ( kmin - glu.xlsub(irep) ); 
+              maxloc = glu.xlusup(irep) + ( kmax - glu.xlsub(irep) ); 
+              std::swap(glu.lusup(minloc), glu.lusup(maxloc)); 
+            }
+            kmin++;
+            kmax--;
+          }
+        } // end while 
+        
+        xprune(irep) = StorageIndex(kmin);  //Pruning 
+      } // end if do_prune 
+    } // end pruning 
+  } // End for each U-segment
+}
+
+} // end namespace internal
+} // end namespace Eigen
+
+#endif // SPARSELU_PRUNEL_H
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_relax_snode.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_relax_snode.h
new file mode 100644
index 0000000..c408d01
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseLU/SparseLU_relax_snode.h
@@ -0,0 +1,83 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+/* This file is a modified version of heap_relax_snode.c file in SuperLU
+ * -- SuperLU routine (version 3.0) --
+ * Univ. of California Berkeley, Xerox Palo Alto Research Center,
+ * and Lawrence Berkeley National Lab.
+ * October 15, 2003
+ *
+ * Copyright (c) 1994 by Xerox Corporation.  All rights reserved.
+ *
+ * THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY
+ * EXPRESSED OR IMPLIED.  ANY USE IS AT YOUR OWN RISK.
+ *
+ * Permission is hereby granted to use or copy this program for any
+ * purpose, provided the above notices are retained on all copies.
+ * Permission to modify the code and to distribute modified code is
+ * granted, provided the above notices are retained, and a notice that
+ * the code was modified is included with the above copyright notice.
+ */
+
+#ifndef SPARSELU_RELAX_SNODE_H
+#define SPARSELU_RELAX_SNODE_H
+
+namespace Eigen {
+
+namespace internal {
+ 
+/** 
+ * \brief Identify the initial relaxed supernodes
+ * 
+ * This routine is applied to a column elimination tree. 
+ * It assumes that the matrix has been reordered according to the postorder of the etree
+ * \param n  the number of columns
+ * \param et elimination tree 
+ * \param relax_columns Maximum number of columns allowed in a relaxed snode 
+ * \param descendants Number of descendants of each node in the etree
+ * \param relax_end last column in a supernode
+ */
+template <typename Scalar, typename StorageIndex>
+void SparseLUImpl<Scalar,StorageIndex>::relax_snode (const Index n, IndexVector& et, const Index relax_columns, IndexVector& descendants, IndexVector& relax_end)
+{
+  
+  // compute the number of descendants of each node in the etree
+  Index parent; 
+  relax_end.setConstant(emptyIdxLU);
+  descendants.setZero();
+  for (Index j = 0; j < n; j++) 
+  {
+    parent = et(j);
+    if (parent != n) // not the dummy root
+      descendants(parent) += descendants(j) + 1;
+  }
+  // Identify the relaxed supernodes by postorder traversal of the etree
+  Index snode_start; // beginning of a snode 
+  for (Index j = 0; j < n; )
+  {
+    parent = et(j);
+    snode_start = j; 
+    while ( parent != n && descendants(parent) < relax_columns ) 
+    {
+      j = parent; 
+      parent = et(j);
+    }
+    // Found a supernode in postordered etree, j is the last column 
+    relax_end(snode_start) = StorageIndex(j); // Record last column
+    j++;
+    // Search for a new leaf
+    while (descendants(j) != 0 && j < n) j++;
+  } // End postorder traversal of the etree
+  
+}
+
+} // end namespace internal
+
+} // end namespace Eigen
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseQR/SparseQR.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseQR/SparseQR.h
new file mode 100644
index 0000000..d1fb96f
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/SparseQR/SparseQR.h
@@ -0,0 +1,758 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2012-2013 Desire Nuentsa <desire.nuentsa_wakam@inria.fr>
+// Copyright (C) 2012-2014 Gael Guennebaud <gael.guennebaud@inria.fr>
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_SPARSE_QR_H
+#define EIGEN_SPARSE_QR_H
+
+namespace Eigen {
+
+template<typename MatrixType, typename OrderingType> class SparseQR;
+template<typename SparseQRType> struct SparseQRMatrixQReturnType;
+template<typename SparseQRType> struct SparseQRMatrixQTransposeReturnType;
+template<typename SparseQRType, typename Derived> struct SparseQR_QProduct;
+namespace internal {
+  template <typename SparseQRType> struct traits<SparseQRMatrixQReturnType<SparseQRType> >
+  {
+    typedef typename SparseQRType::MatrixType ReturnType;
+    typedef typename ReturnType::StorageIndex StorageIndex;
+    typedef typename ReturnType::StorageKind StorageKind;
+    enum {
+      RowsAtCompileTime = Dynamic,
+      ColsAtCompileTime = Dynamic
+    };
+  };
+  template <typename SparseQRType> struct traits<SparseQRMatrixQTransposeReturnType<SparseQRType> >
+  {
+    typedef typename SparseQRType::MatrixType ReturnType;
+  };
+  template <typename SparseQRType, typename Derived> struct traits<SparseQR_QProduct<SparseQRType, Derived> >
+  {
+    typedef typename Derived::PlainObject ReturnType;
+  };
+} // End namespace internal
+
+/**
+  * \ingroup SparseQR_Module
+  * \class SparseQR
+  * \brief Sparse left-looking QR factorization with numerical column pivoting
+  * 
+  * This class implements a left-looking QR decomposition of sparse matrices
+  * with numerical column pivoting.
+  * When a column has a norm less than a given tolerance
+  * it is implicitly permuted to the end. The QR factorization thus obtained is 
+  * given by A*P = Q*R where R is upper triangular or trapezoidal. 
+  * 
+  * P is the column permutation which is the product of the fill-reducing and the
+  * numerical permutations. Use colsPermutation() to get it.
+  * 
+  * Q is the orthogonal matrix represented as products of Householder reflectors. 
+  * Use matrixQ() to get an expression and matrixQ().adjoint() to get the adjoint.
+  * You can then apply it to a vector.
+  * 
+  * R is the sparse triangular or trapezoidal matrix. The later occurs when A is rank-deficient.
+  * matrixR().topLeftCorner(rank(), rank()) always returns a triangular factor of full rank.
+  * 
+  * \tparam _MatrixType The type of the sparse matrix A, must be a column-major SparseMatrix<>
+  * \tparam _OrderingType The fill-reducing ordering method. See the \link OrderingMethods_Module 
+  *  OrderingMethods \endlink module for the list of built-in and external ordering methods.
+  * 
+  * \implsparsesolverconcept
+  *
+  * The numerical pivoting strategy and default threshold are the same as in SuiteSparse QR, and
+  * detailed in the following paper:
+  * <i>
+  * Tim Davis, "Algorithm 915, SuiteSparseQR: Multifrontal Multithreaded Rank-Revealing
+  * Sparse QR Factorization, ACM Trans. on Math. Soft. 38(1), 2011.
+  * </i>
+  * Even though it is qualified as "rank-revealing", this strategy might fail for some 
+  * rank deficient problems. When this class is used to solve linear or least-square problems
+  * it is thus strongly recommended to check the accuracy of the computed solution. If it
+  * failed, it usually helps to increase the threshold with setPivotThreshold.
+  * 
+  * \warning The input sparse matrix A must be in compressed mode (see SparseMatrix::makeCompressed()).
+  * \warning For complex matrices matrixQ().transpose() will actually return the adjoint matrix.
+  * 
+  */
+template<typename _MatrixType, typename _OrderingType>
+class SparseQR : public SparseSolverBase<SparseQR<_MatrixType,_OrderingType> >
+{
+  protected:
+    typedef SparseSolverBase<SparseQR<_MatrixType,_OrderingType> > Base;
+    using Base::m_isInitialized;
+  public:
+    using Base::_solve_impl;
+    typedef _MatrixType MatrixType;
+    typedef _OrderingType OrderingType;
+    typedef typename MatrixType::Scalar Scalar;
+    typedef typename MatrixType::RealScalar RealScalar;
+    typedef typename MatrixType::StorageIndex StorageIndex;
+    typedef SparseMatrix<Scalar,ColMajor,StorageIndex> QRMatrixType;
+    typedef Matrix<StorageIndex, Dynamic, 1> IndexVector;
+    typedef Matrix<Scalar, Dynamic, 1> ScalarVector;
+    typedef PermutationMatrix<Dynamic, Dynamic, StorageIndex> PermutationType;
+
+    enum {
+      ColsAtCompileTime = MatrixType::ColsAtCompileTime,
+      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime
+    };
+    
+  public:
+    SparseQR () :  m_analysisIsok(false), m_lastError(""), m_useDefaultThreshold(true),m_isQSorted(false),m_isEtreeOk(false)
+    { }
+    
+    /** Construct a QR factorization of the matrix \a mat.
+      * 
+      * \warning The matrix \a mat must be in compressed mode (see SparseMatrix::makeCompressed()).
+      * 
+      * \sa compute()
+      */
+    explicit SparseQR(const MatrixType& mat) : m_analysisIsok(false), m_lastError(""), m_useDefaultThreshold(true),m_isQSorted(false),m_isEtreeOk(false)
+    {
+      compute(mat);
+    }
+    
+    /** Computes the QR factorization of the sparse matrix \a mat.
+      * 
+      * \warning The matrix \a mat must be in compressed mode (see SparseMatrix::makeCompressed()).
+      * 
+      * \sa analyzePattern(), factorize()
+      */
+    void compute(const MatrixType& mat)
+    {
+      analyzePattern(mat);
+      factorize(mat);
+    }
+    void analyzePattern(const MatrixType& mat);
+    void factorize(const MatrixType& mat);
+    
+    /** \returns the number of rows of the represented matrix. 
+      */
+    inline Index rows() const { return m_pmat.rows(); }
+    
+    /** \returns the number of columns of the represented matrix. 
+      */
+    inline Index cols() const { return m_pmat.cols();}
+    
+    /** \returns a const reference to the \b sparse upper triangular matrix R of the QR factorization.
+      * \warning The entries of the returned matrix are not sorted. This means that using it in algorithms
+      *          expecting sorted entries will fail. This include random coefficient accesses (SpaseMatrix::coeff()),
+      *          and coefficient-wise operations. Matrix products and triangular solves are fine though.
+      *
+      * To sort the entries, you can assign it to a row-major matrix, and if a column-major matrix
+      * is required, you can copy it again:
+      * \code
+      * SparseMatrix<double>          R  = qr.matrixR();  // column-major, not sorted!
+      * SparseMatrix<double,RowMajor> Rr = qr.matrixR();  // row-major, sorted
+      * SparseMatrix<double>          Rc = Rr;            // column-major, sorted
+      * \endcode
+      */
+    const QRMatrixType& matrixR() const { return m_R; }
+    
+    /** \returns the number of non linearly dependent columns as determined by the pivoting threshold.
+      *
+      * \sa setPivotThreshold()
+      */
+    Index rank() const
+    {
+      eigen_assert(m_isInitialized && "The factorization should be called first, use compute()");
+      return m_nonzeropivots; 
+    }
+    
+    /** \returns an expression of the matrix Q as products of sparse Householder reflectors.
+    * The common usage of this function is to apply it to a dense matrix or vector
+    * \code
+    * VectorXd B1, B2;
+    * // Initialize B1
+    * B2 = matrixQ() * B1;
+    * \endcode
+    *
+    * To get a plain SparseMatrix representation of Q:
+    * \code
+    * SparseMatrix<double> Q;
+    * Q = SparseQR<SparseMatrix<double> >(A).matrixQ();
+    * \endcode
+    * Internally, this call simply performs a sparse product between the matrix Q
+    * and a sparse identity matrix. However, due to the fact that the sparse
+    * reflectors are stored unsorted, two transpositions are needed to sort
+    * them before performing the product.
+    */
+    SparseQRMatrixQReturnType<SparseQR> matrixQ() const 
+    { return SparseQRMatrixQReturnType<SparseQR>(*this); }
+    
+    /** \returns a const reference to the column permutation P that was applied to A such that A*P = Q*R
+      * It is the combination of the fill-in reducing permutation and numerical column pivoting.
+      */
+    const PermutationType& colsPermutation() const
+    { 
+      eigen_assert(m_isInitialized && "Decomposition is not initialized.");
+      return m_outputPerm_c;
+    }
+    
+    /** \returns A string describing the type of error.
+      * This method is provided to ease debugging, not to handle errors.
+      */
+    std::string lastErrorMessage() const { return m_lastError; }
+    
+    /** \internal */
+    template<typename Rhs, typename Dest>
+    bool _solve_impl(const MatrixBase<Rhs> &B, MatrixBase<Dest> &dest) const
+    {
+      eigen_assert(m_isInitialized && "The factorization should be called first, use compute()");
+      eigen_assert(this->rows() == B.rows() && "SparseQR::solve() : invalid number of rows in the right hand side matrix");
+
+      Index rank = this->rank();
+      
+      // Compute Q^* * b;
+      typename Dest::PlainObject y, b;
+      y = this->matrixQ().adjoint() * B;
+      b = y;
+      
+      // Solve with the triangular matrix R
+      y.resize((std::max<Index>)(cols(),y.rows()),y.cols());
+      y.topRows(rank) = this->matrixR().topLeftCorner(rank, rank).template triangularView<Upper>().solve(b.topRows(rank));
+      y.bottomRows(y.rows()-rank).setZero();
+      
+      // Apply the column permutation
+      if (m_perm_c.size())  dest = colsPermutation() * y.topRows(cols());
+      else                  dest = y.topRows(cols());
+      
+      m_info = Success;
+      return true;
+    }
+
+    /** Sets the threshold that is used to determine linearly dependent columns during the factorization.
+      *
+      * In practice, if during the factorization the norm of the column that has to be eliminated is below
+      * this threshold, then the entire column is treated as zero, and it is moved at the end.
+      */
+    void setPivotThreshold(const RealScalar& threshold)
+    {
+      m_useDefaultThreshold = false;
+      m_threshold = threshold;
+    }
+    
+    /** \returns the solution X of \f$ A X = B \f$ using the current decomposition of A.
+      *
+      * \sa compute()
+      */
+    template<typename Rhs>
+    inline const Solve<SparseQR, Rhs> solve(const MatrixBase<Rhs>& B) const 
+    {
+      eigen_assert(m_isInitialized && "The factorization should be called first, use compute()");
+      eigen_assert(this->rows() == B.rows() && "SparseQR::solve() : invalid number of rows in the right hand side matrix");
+      return Solve<SparseQR, Rhs>(*this, B.derived());
+    }
+    template<typename Rhs>
+    inline const Solve<SparseQR, Rhs> solve(const SparseMatrixBase<Rhs>& B) const
+    {
+          eigen_assert(m_isInitialized && "The factorization should be called first, use compute()");
+          eigen_assert(this->rows() == B.rows() && "SparseQR::solve() : invalid number of rows in the right hand side matrix");
+          return Solve<SparseQR, Rhs>(*this, B.derived());
+    }
+    
+    /** \brief Reports whether previous computation was successful.
+      *
+      * \returns \c Success if computation was successful,
+      *          \c NumericalIssue if the QR factorization reports a numerical problem
+      *          \c InvalidInput if the input matrix is invalid
+      *
+      * \sa iparm()          
+      */
+    ComputationInfo info() const
+    {
+      eigen_assert(m_isInitialized && "Decomposition is not initialized.");
+      return m_info;
+    }
+
+
+    /** \internal */
+    inline void _sort_matrix_Q()
+    {
+      if(this->m_isQSorted) return;
+      // The matrix Q is sorted during the transposition
+      SparseMatrix<Scalar, RowMajor, Index> mQrm(this->m_Q);
+      this->m_Q = mQrm;
+      this->m_isQSorted = true;
+    }
+
+    
+  protected:
+    bool m_analysisIsok;
+    bool m_factorizationIsok;
+    mutable ComputationInfo m_info;
+    std::string m_lastError;
+    QRMatrixType m_pmat;            // Temporary matrix
+    QRMatrixType m_R;               // The triangular factor matrix
+    QRMatrixType m_Q;               // The orthogonal reflectors
+    ScalarVector m_hcoeffs;         // The Householder coefficients
+    PermutationType m_perm_c;       // Fill-reducing  Column  permutation
+    PermutationType m_pivotperm;    // The permutation for rank revealing
+    PermutationType m_outputPerm_c; // The final column permutation
+    RealScalar m_threshold;         // Threshold to determine null Householder reflections
+    bool m_useDefaultThreshold;     // Use default threshold
+    Index m_nonzeropivots;          // Number of non zero pivots found
+    IndexVector m_etree;            // Column elimination tree
+    IndexVector m_firstRowElt;      // First element in each row
+    bool m_isQSorted;               // whether Q is sorted or not
+    bool m_isEtreeOk;               // whether the elimination tree match the initial input matrix
+    
+    template <typename, typename > friend struct SparseQR_QProduct;
+    
+};
+
+/** \brief Preprocessing step of a QR factorization 
+  * 
+  * \warning The matrix \a mat must be in compressed mode (see SparseMatrix::makeCompressed()).
+  * 
+  * In this step, the fill-reducing permutation is computed and applied to the columns of A
+  * and the column elimination tree is computed as well. Only the sparsity pattern of \a mat is exploited.
+  * 
+  * \note In this step it is assumed that there is no empty row in the matrix \a mat.
+  */
+template <typename MatrixType, typename OrderingType>
+void SparseQR<MatrixType,OrderingType>::analyzePattern(const MatrixType& mat)
+{
+  eigen_assert(mat.isCompressed() && "SparseQR requires a sparse matrix in compressed mode. Call .makeCompressed() before passing it to SparseQR");
+  // Copy to a column major matrix if the input is rowmajor
+  typename internal::conditional<MatrixType::IsRowMajor,QRMatrixType,const MatrixType&>::type matCpy(mat);
+  // Compute the column fill reducing ordering
+  OrderingType ord; 
+  ord(matCpy, m_perm_c); 
+  Index n = mat.cols();
+  Index m = mat.rows();
+  Index diagSize = (std::min)(m,n);
+  
+  if (!m_perm_c.size())
+  {
+    m_perm_c.resize(n);
+    m_perm_c.indices().setLinSpaced(n, 0,StorageIndex(n-1));
+  }
+  
+  // Compute the column elimination tree of the permuted matrix
+  m_outputPerm_c = m_perm_c.inverse();
+  internal::coletree(matCpy, m_etree, m_firstRowElt, m_outputPerm_c.indices().data());
+  m_isEtreeOk = true;
+  
+  m_R.resize(m, n);
+  m_Q.resize(m, diagSize);
+  
+  // Allocate space for nonzero elements: rough estimation
+  m_R.reserve(2*mat.nonZeros()); //FIXME Get a more accurate estimation through symbolic factorization with the etree
+  m_Q.reserve(2*mat.nonZeros());
+  m_hcoeffs.resize(diagSize);
+  m_analysisIsok = true;
+}
+
+/** \brief Performs the numerical QR factorization of the input matrix
+  * 
+  * The function SparseQR::analyzePattern(const MatrixType&) must have been called beforehand with
+  * a matrix having the same sparsity pattern than \a mat.
+  * 
+  * \param mat The sparse column-major matrix
+  */
+template <typename MatrixType, typename OrderingType>
+void SparseQR<MatrixType,OrderingType>::factorize(const MatrixType& mat)
+{
+  using std::abs;
+  
+  eigen_assert(m_analysisIsok && "analyzePattern() should be called before this step");
+  StorageIndex m = StorageIndex(mat.rows());
+  StorageIndex n = StorageIndex(mat.cols());
+  StorageIndex diagSize = (std::min)(m,n);
+  IndexVector mark((std::max)(m,n)); mark.setConstant(-1);  // Record the visited nodes
+  IndexVector Ridx(n), Qidx(m);                             // Store temporarily the row indexes for the current column of R and Q
+  Index nzcolR, nzcolQ;                                     // Number of nonzero for the current column of R and Q
+  ScalarVector tval(m);                                     // The dense vector used to compute the current column
+  RealScalar pivotThreshold = m_threshold;
+  
+  m_R.setZero();
+  m_Q.setZero();
+  m_pmat = mat;
+  if(!m_isEtreeOk)
+  {
+    m_outputPerm_c = m_perm_c.inverse();
+    internal::coletree(m_pmat, m_etree, m_firstRowElt, m_outputPerm_c.indices().data());
+    m_isEtreeOk = true;
+  }
+
+  m_pmat.uncompress(); // To have the innerNonZeroPtr allocated
+  
+  // Apply the fill-in reducing permutation lazily:
+  {
+    // If the input is row major, copy the original column indices,
+    // otherwise directly use the input matrix
+    // 
+    IndexVector originalOuterIndicesCpy;
+    const StorageIndex *originalOuterIndices = mat.outerIndexPtr();
+    if(MatrixType::IsRowMajor)
+    {
+      originalOuterIndicesCpy = IndexVector::Map(m_pmat.outerIndexPtr(),n+1);
+      originalOuterIndices = originalOuterIndicesCpy.data();
+    }
+    
+    for (int i = 0; i < n; i++)
+    {
+      Index p = m_perm_c.size() ? m_perm_c.indices()(i) : i;
+      m_pmat.outerIndexPtr()[p] = originalOuterIndices[i]; 
+      m_pmat.innerNonZeroPtr()[p] = originalOuterIndices[i+1] - originalOuterIndices[i]; 
+    }
+  }
+  
+  /* Compute the default threshold as in MatLab, see:
+   * Tim Davis, "Algorithm 915, SuiteSparseQR: Multifrontal Multithreaded Rank-Revealing
+   * Sparse QR Factorization, ACM Trans. on Math. Soft. 38(1), 2011, Page 8:3 
+   */
+  if(m_useDefaultThreshold) 
+  {
+    RealScalar max2Norm = 0.0;
+    for (int j = 0; j < n; j++) max2Norm = numext::maxi(max2Norm, m_pmat.col(j).norm());
+    if(max2Norm==RealScalar(0))
+      max2Norm = RealScalar(1);
+    pivotThreshold = 20 * (m + n) * max2Norm * NumTraits<RealScalar>::epsilon();
+  }
+  
+  // Initialize the numerical permutation
+  m_pivotperm.setIdentity(n);
+  
+  StorageIndex nonzeroCol = 0; // Record the number of valid pivots
+  m_Q.startVec(0);
+
+  // Left looking rank-revealing QR factorization: compute a column of R and Q at a time
+  for (StorageIndex col = 0; col < n; ++col)
+  {
+    mark.setConstant(-1);
+    m_R.startVec(col);
+    mark(nonzeroCol) = col;
+    Qidx(0) = nonzeroCol;
+    nzcolR = 0; nzcolQ = 1;
+    bool found_diag = nonzeroCol>=m;
+    tval.setZero(); 
+    
+    // Symbolic factorization: find the nonzero locations of the column k of the factors R and Q, i.e.,
+    // all the nodes (with indexes lower than rank) reachable through the column elimination tree (etree) rooted at node k.
+    // Note: if the diagonal entry does not exist, then its contribution must be explicitly added,
+    // thus the trick with found_diag that permits to do one more iteration on the diagonal element if this one has not been found.
+    for (typename QRMatrixType::InnerIterator itp(m_pmat, col); itp || !found_diag; ++itp)
+    {
+      StorageIndex curIdx = nonzeroCol;
+      if(itp) curIdx = StorageIndex(itp.row());
+      if(curIdx == nonzeroCol) found_diag = true;
+      
+      // Get the nonzeros indexes of the current column of R
+      StorageIndex st = m_firstRowElt(curIdx); // The traversal of the etree starts here
+      if (st < 0 )
+      {
+        m_lastError = "Empty row found during numerical factorization";
+        m_info = InvalidInput;
+        return;
+      }
+
+      // Traverse the etree 
+      Index bi = nzcolR;
+      for (; mark(st) != col; st = m_etree(st))
+      {
+        Ridx(nzcolR) = st;  // Add this row to the list,
+        mark(st) = col;     // and mark this row as visited
+        nzcolR++;
+      }
+
+      // Reverse the list to get the topological ordering
+      Index nt = nzcolR-bi;
+      for(Index i = 0; i < nt/2; i++) std::swap(Ridx(bi+i), Ridx(nzcolR-i-1));
+       
+      // Copy the current (curIdx,pcol) value of the input matrix
+      if(itp) tval(curIdx) = itp.value();
+      else    tval(curIdx) = Scalar(0);
+      
+      // Compute the pattern of Q(:,k)
+      if(curIdx > nonzeroCol && mark(curIdx) != col ) 
+      {
+        Qidx(nzcolQ) = curIdx;  // Add this row to the pattern of Q,
+        mark(curIdx) = col;     // and mark it as visited
+        nzcolQ++;
+      }
+    }
+
+    // Browse all the indexes of R(:,col) in reverse order
+    for (Index i = nzcolR-1; i >= 0; i--)
+    {
+      Index curIdx = Ridx(i);
+      
+      // Apply the curIdx-th householder vector to the current column (temporarily stored into tval)
+      Scalar tdot(0);
+      
+      // First compute q' * tval
+      tdot = m_Q.col(curIdx).dot(tval);
+
+      tdot *= m_hcoeffs(curIdx);
+      
+      // Then update tval = tval - q * tau
+      // FIXME: tval -= tdot * m_Q.col(curIdx) should amount to the same (need to check/add support for efficient "dense ?= sparse")
+      for (typename QRMatrixType::InnerIterator itq(m_Q, curIdx); itq; ++itq)
+        tval(itq.row()) -= itq.value() * tdot;
+
+      // Detect fill-in for the current column of Q
+      if(m_etree(Ridx(i)) == nonzeroCol)
+      {
+        for (typename QRMatrixType::InnerIterator itq(m_Q, curIdx); itq; ++itq)
+        {
+          StorageIndex iQ = StorageIndex(itq.row());
+          if (mark(iQ) != col)
+          {
+            Qidx(nzcolQ++) = iQ;  // Add this row to the pattern of Q,
+            mark(iQ) = col;       // and mark it as visited
+          }
+        }
+      }
+    } // End update current column
+    
+    Scalar tau = RealScalar(0);
+    RealScalar beta = 0;
+    
+    if(nonzeroCol < diagSize)
+    {
+      // Compute the Householder reflection that eliminate the current column
+      // FIXME this step should call the Householder module.
+      Scalar c0 = nzcolQ ? tval(Qidx(0)) : Scalar(0);
+      
+      // First, the squared norm of Q((col+1):m, col)
+      RealScalar sqrNorm = 0.;
+      for (Index itq = 1; itq < nzcolQ; ++itq) sqrNorm += numext::abs2(tval(Qidx(itq)));
+      if(sqrNorm == RealScalar(0) && numext::imag(c0) == RealScalar(0))
+      {
+        beta = numext::real(c0);
+        tval(Qidx(0)) = 1;
+      }
+      else
+      {
+        using std::sqrt;
+        beta = sqrt(numext::abs2(c0) + sqrNorm);
+        if(numext::real(c0) >= RealScalar(0))
+          beta = -beta;
+        tval(Qidx(0)) = 1;
+        for (Index itq = 1; itq < nzcolQ; ++itq)
+          tval(Qidx(itq)) /= (c0 - beta);
+        tau = numext::conj((beta-c0) / beta);
+          
+      }
+    }
+
+    // Insert values in R
+    for (Index  i = nzcolR-1; i >= 0; i--)
+    {
+      Index curIdx = Ridx(i);
+      if(curIdx < nonzeroCol) 
+      {
+        m_R.insertBackByOuterInnerUnordered(col, curIdx) = tval(curIdx);
+        tval(curIdx) = Scalar(0.);
+      }
+    }
+
+    if(nonzeroCol < diagSize && abs(beta) >= pivotThreshold)
+    {
+      m_R.insertBackByOuterInner(col, nonzeroCol) = beta;
+      // The householder coefficient
+      m_hcoeffs(nonzeroCol) = tau;
+      // Record the householder reflections
+      for (Index itq = 0; itq < nzcolQ; ++itq)
+      {
+        Index iQ = Qidx(itq);
+        m_Q.insertBackByOuterInnerUnordered(nonzeroCol,iQ) = tval(iQ);
+        tval(iQ) = Scalar(0.);
+      }
+      nonzeroCol++;
+      if(nonzeroCol<diagSize)
+        m_Q.startVec(nonzeroCol);
+    }
+    else
+    {
+      // Zero pivot found: move implicitly this column to the end
+      for (Index j = nonzeroCol; j < n-1; j++) 
+        std::swap(m_pivotperm.indices()(j), m_pivotperm.indices()[j+1]);
+      
+      // Recompute the column elimination tree
+      internal::coletree(m_pmat, m_etree, m_firstRowElt, m_pivotperm.indices().data());
+      m_isEtreeOk = false;
+    }
+  }
+  
+  m_hcoeffs.tail(diagSize-nonzeroCol).setZero();
+  
+  // Finalize the column pointers of the sparse matrices R and Q
+  m_Q.finalize();
+  m_Q.makeCompressed();
+  m_R.finalize();
+  m_R.makeCompressed();
+  m_isQSorted = false;
+
+  m_nonzeropivots = nonzeroCol;
+  
+  if(nonzeroCol<n)
+  {
+    // Permute the triangular factor to put the 'dead' columns to the end
+    QRMatrixType tempR(m_R);
+    m_R = tempR * m_pivotperm;
+    
+    // Update the column permutation
+    m_outputPerm_c = m_outputPerm_c * m_pivotperm;
+  }
+  
+  m_isInitialized = true; 
+  m_factorizationIsok = true;
+  m_info = Success;
+}
+
+template <typename SparseQRType, typename Derived>
+struct SparseQR_QProduct : ReturnByValue<SparseQR_QProduct<SparseQRType, Derived> >
+{
+  typedef typename SparseQRType::QRMatrixType MatrixType;
+  typedef typename SparseQRType::Scalar Scalar;
+  // Get the references 
+  SparseQR_QProduct(const SparseQRType& qr, const Derived& other, bool transpose) : 
+  m_qr(qr),m_other(other),m_transpose(transpose) {}
+  inline Index rows() const { return m_qr.matrixQ().rows(); }
+  inline Index cols() const { return m_other.cols(); }
+  
+  // Assign to a vector
+  template<typename DesType>
+  void evalTo(DesType& res) const
+  {
+    Index m = m_qr.rows();
+    Index n = m_qr.cols();
+    Index diagSize = (std::min)(m,n);
+    res = m_other;
+    if (m_transpose)
+    {
+      eigen_assert(m_qr.m_Q.rows() == m_other.rows() && "Non conforming object sizes");
+      //Compute res = Q' * other column by column
+      for(Index j = 0; j < res.cols(); j++){
+        for (Index k = 0; k < diagSize; k++)
+        {
+          Scalar tau = Scalar(0);
+          tau = m_qr.m_Q.col(k).dot(res.col(j));
+          if(tau==Scalar(0)) continue;
+          tau = tau * m_qr.m_hcoeffs(k);
+          res.col(j) -= tau * m_qr.m_Q.col(k);
+        }
+      }
+    }
+    else
+    {
+      eigen_assert(m_qr.matrixQ().cols() == m_other.rows() && "Non conforming object sizes");
+
+      res.conservativeResize(rows(), cols());
+
+      // Compute res = Q * other column by column
+      for(Index j = 0; j < res.cols(); j++)
+      {
+        Index start_k = internal::is_identity<Derived>::value ? numext::mini(j,diagSize-1) : diagSize-1;
+        for (Index k = start_k; k >=0; k--)
+        {
+          Scalar tau = Scalar(0);
+          tau = m_qr.m_Q.col(k).dot(res.col(j));
+          if(tau==Scalar(0)) continue;
+          tau = tau * numext::conj(m_qr.m_hcoeffs(k));
+          res.col(j) -= tau * m_qr.m_Q.col(k);
+        }
+      }
+    }
+  }
+  
+  const SparseQRType& m_qr;
+  const Derived& m_other;
+  bool m_transpose; // TODO this actually means adjoint
+};
+
+template<typename SparseQRType>
+struct SparseQRMatrixQReturnType : public EigenBase<SparseQRMatrixQReturnType<SparseQRType> >
+{  
+  typedef typename SparseQRType::Scalar Scalar;
+  typedef Matrix<Scalar,Dynamic,Dynamic> DenseMatrix;
+  enum {
+    RowsAtCompileTime = Dynamic,
+    ColsAtCompileTime = Dynamic
+  };
+  explicit SparseQRMatrixQReturnType(const SparseQRType& qr) : m_qr(qr) {}
+  template<typename Derived>
+  SparseQR_QProduct<SparseQRType, Derived> operator*(const MatrixBase<Derived>& other)
+  {
+    return SparseQR_QProduct<SparseQRType,Derived>(m_qr,other.derived(),false);
+  }
+  // To use for operations with the adjoint of Q
+  SparseQRMatrixQTransposeReturnType<SparseQRType> adjoint() const
+  {
+    return SparseQRMatrixQTransposeReturnType<SparseQRType>(m_qr);
+  }
+  inline Index rows() const { return m_qr.rows(); }
+  inline Index cols() const { return m_qr.rows(); }
+  // To use for operations with the transpose of Q FIXME this is the same as adjoint at the moment
+  SparseQRMatrixQTransposeReturnType<SparseQRType> transpose() const
+  {
+    return SparseQRMatrixQTransposeReturnType<SparseQRType>(m_qr);
+  }
+  const SparseQRType& m_qr;
+};
+
+// TODO this actually represents the adjoint of Q
+template<typename SparseQRType>
+struct SparseQRMatrixQTransposeReturnType
+{
+  explicit SparseQRMatrixQTransposeReturnType(const SparseQRType& qr) : m_qr(qr) {}
+  template<typename Derived>
+  SparseQR_QProduct<SparseQRType,Derived> operator*(const MatrixBase<Derived>& other)
+  {
+    return SparseQR_QProduct<SparseQRType,Derived>(m_qr,other.derived(), true);
+  }
+  const SparseQRType& m_qr;
+};
+
+namespace internal {
+  
+template<typename SparseQRType>
+struct evaluator_traits<SparseQRMatrixQReturnType<SparseQRType> >
+{
+  typedef typename SparseQRType::MatrixType MatrixType;
+  typedef typename storage_kind_to_evaluator_kind<typename MatrixType::StorageKind>::Kind Kind;
+  typedef SparseShape Shape;
+};
+
+template< typename DstXprType, typename SparseQRType>
+struct Assignment<DstXprType, SparseQRMatrixQReturnType<SparseQRType>, internal::assign_op<typename DstXprType::Scalar,typename DstXprType::Scalar>, Sparse2Sparse>
+{
+  typedef SparseQRMatrixQReturnType<SparseQRType> SrcXprType;
+  typedef typename DstXprType::Scalar Scalar;
+  typedef typename DstXprType::StorageIndex StorageIndex;
+  static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op<Scalar,Scalar> &/*func*/)
+  {
+    typename DstXprType::PlainObject idMat(src.rows(), src.cols());
+    idMat.setIdentity();
+    // Sort the sparse householder reflectors if needed
+    const_cast<SparseQRType *>(&src.m_qr)->_sort_matrix_Q();
+    dst = SparseQR_QProduct<SparseQRType, DstXprType>(src.m_qr, idMat, false);
+  }
+};
+
+template< typename DstXprType, typename SparseQRType>
+struct Assignment<DstXprType, SparseQRMatrixQReturnType<SparseQRType>, internal::assign_op<typename DstXprType::Scalar,typename DstXprType::Scalar>, Sparse2Dense>
+{
+  typedef SparseQRMatrixQReturnType<SparseQRType> SrcXprType;
+  typedef typename DstXprType::Scalar Scalar;
+  typedef typename DstXprType::StorageIndex StorageIndex;
+  static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op<Scalar,Scalar> &/*func*/)
+  {
+    dst = src.m_qr.matrixQ() * DstXprType::Identity(src.m_qr.rows(), src.m_qr.rows());
+  }
+};
+
+} // end namespace internal
+
+} // end namespace Eigen
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/StlSupport/StdDeque.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/StlSupport/StdDeque.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/StlSupport/StdDeque.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/StlSupport/StdDeque.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/StlSupport/StdList.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/StlSupport/StdList.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/StlSupport/StdList.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/StlSupport/StdList.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/StlSupport/StdVector.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/StlSupport/StdVector.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/StlSupport/StdVector.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/StlSupport/StdVector.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/StlSupport/details.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/StlSupport/details.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/StlSupport/details.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/StlSupport/details.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/misc/Image.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/misc/Image.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/misc/Image.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/misc/Image.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/misc/Kernel.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/misc/Kernel.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/misc/Kernel.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/misc/Kernel.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/misc/RealSvd2x2.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/misc/RealSvd2x2.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/misc/RealSvd2x2.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/misc/RealSvd2x2.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/plugins/ArrayCwiseBinaryOps.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/plugins/ArrayCwiseBinaryOps.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/plugins/ArrayCwiseBinaryOps.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/plugins/ArrayCwiseBinaryOps.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/plugins/ArrayCwiseUnaryOps.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/plugins/ArrayCwiseUnaryOps.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/plugins/ArrayCwiseUnaryOps.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/plugins/ArrayCwiseUnaryOps.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/plugins/BlockMethods.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/plugins/BlockMethods.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/plugins/BlockMethods.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/plugins/BlockMethods.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/plugins/CommonCwiseBinaryOps.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/plugins/CommonCwiseBinaryOps.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/plugins/CommonCwiseBinaryOps.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/plugins/CommonCwiseBinaryOps.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/plugins/CommonCwiseUnaryOps.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/plugins/CommonCwiseUnaryOps.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/plugins/CommonCwiseUnaryOps.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/plugins/CommonCwiseUnaryOps.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/plugins/IndexedViewMethods.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/plugins/IndexedViewMethods.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/plugins/IndexedViewMethods.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/plugins/IndexedViewMethods.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/plugins/MatrixCwiseBinaryOps.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/plugins/MatrixCwiseBinaryOps.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/plugins/MatrixCwiseBinaryOps.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/plugins/MatrixCwiseBinaryOps.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/plugins/MatrixCwiseUnaryOps.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/plugins/MatrixCwiseUnaryOps.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/plugins/MatrixCwiseUnaryOps.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/plugins/MatrixCwiseUnaryOps.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/plugins/ReshapedMethods.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/plugins/ReshapedMethods.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/Eigen/src/plugins/ReshapedMethods.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/Eigen/src/plugins/ReshapedMethods.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/unsupported/Eigen/MatrixFunctions b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/unsupported/Eigen/MatrixFunctions
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/unsupported/Eigen/MatrixFunctions
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/unsupported/Eigen/MatrixFunctions
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/unsupported/Eigen/src/MatrixFunctions/MatrixExponential.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/unsupported/Eigen/src/MatrixFunctions/MatrixExponential.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/unsupported/Eigen/src/MatrixFunctions/MatrixExponential.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/unsupported/Eigen/src/MatrixFunctions/MatrixExponential.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/unsupported/Eigen/src/MatrixFunctions/MatrixFunction.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/unsupported/Eigen/src/MatrixFunctions/MatrixFunction.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/unsupported/Eigen/src/MatrixFunctions/MatrixFunction.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/unsupported/Eigen/src/MatrixFunctions/MatrixFunction.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/unsupported/Eigen/src/MatrixFunctions/MatrixLogarithm.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/unsupported/Eigen/src/MatrixFunctions/MatrixLogarithm.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/unsupported/Eigen/src/MatrixFunctions/MatrixLogarithm.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/unsupported/Eigen/src/MatrixFunctions/MatrixLogarithm.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/unsupported/Eigen/src/MatrixFunctions/MatrixPower.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/unsupported/Eigen/src/MatrixFunctions/MatrixPower.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/unsupported/Eigen/src/MatrixFunctions/MatrixPower.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/unsupported/Eigen/src/MatrixFunctions/MatrixPower.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/unsupported/Eigen/src/MatrixFunctions/MatrixSquareRoot.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/unsupported/Eigen/src/MatrixFunctions/MatrixSquareRoot.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/unsupported/Eigen/src/MatrixFunctions/MatrixSquareRoot.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/unsupported/Eigen/src/MatrixFunctions/MatrixSquareRoot.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/eigeninclude/unsupported/Eigen/src/MatrixFunctions/StemFunction.h b/third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/unsupported/Eigen/src/MatrixFunctions/StemFunction.h
similarity index 100%
rename from third_party/allwpilib/wpimath/src/main/native/eigeninclude/unsupported/Eigen/src/MatrixFunctions/StemFunction.h
rename to third_party/allwpilib/wpimath/src/main/native/thirdparty/eigen/include/unsupported/Eigen/src/MatrixFunctions/StemFunction.h
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem.hpp
new file mode 100644
index 0000000..cb28ff0
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem.hpp
@@ -0,0 +1,104 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+#ifndef _gcem_HPP
+#define _gcem_HPP
+
+#include "gcem_incl/gcem_options.hpp"
+
+namespace gcem
+{
+    #include "gcem_incl/quadrature/gauss_legendre_50.hpp"
+
+    #include "gcem_incl/is_inf.hpp"
+    #include "gcem_incl/is_nan.hpp"
+    #include "gcem_incl/is_finite.hpp"
+    
+    #include "gcem_incl/signbit.hpp"
+    #include "gcem_incl/copysign.hpp"
+    #include "gcem_incl/neg_zero.hpp"
+    #include "gcem_incl/sgn.hpp"
+
+    #include "gcem_incl/abs.hpp"
+    #include "gcem_incl/ceil.hpp"
+    #include "gcem_incl/floor.hpp"
+    #include "gcem_incl/trunc.hpp"
+    #include "gcem_incl/is_odd.hpp"
+    #include "gcem_incl/is_even.hpp"
+    #include "gcem_incl/max.hpp"
+    #include "gcem_incl/min.hpp"
+    #include "gcem_incl/sqrt.hpp"
+    #include "gcem_incl/inv_sqrt.hpp"
+    #include "gcem_incl/hypot.hpp"
+
+    #include "gcem_incl/find_exponent.hpp"
+    #include "gcem_incl/find_fraction.hpp"
+    #include "gcem_incl/find_whole.hpp"
+    #include "gcem_incl/mantissa.hpp"
+    #include "gcem_incl/round.hpp"
+    #include "gcem_incl/fmod.hpp"
+
+    #include "gcem_incl/pow_integral.hpp"
+    #include "gcem_incl/exp.hpp"
+    #include "gcem_incl/expm1.hpp"
+    #include "gcem_incl/log.hpp"
+    #include "gcem_incl/log1p.hpp"
+    #include "gcem_incl/log2.hpp"
+    #include "gcem_incl/log10.hpp"
+    #include "gcem_incl/pow.hpp"
+
+    #include "gcem_incl/gcd.hpp"
+    #include "gcem_incl/lcm.hpp"
+
+    #include "gcem_incl/tan.hpp"
+    #include "gcem_incl/cos.hpp"
+    #include "gcem_incl/sin.hpp"
+
+    #include "gcem_incl/atan.hpp"
+    #include "gcem_incl/atan2.hpp"
+    #include "gcem_incl/acos.hpp"
+    #include "gcem_incl/asin.hpp"
+
+    #include "gcem_incl/tanh.hpp"
+    #include "gcem_incl/cosh.hpp"
+    #include "gcem_incl/sinh.hpp"
+
+    #include "gcem_incl/atanh.hpp"
+    #include "gcem_incl/acosh.hpp"
+    #include "gcem_incl/asinh.hpp"
+
+    #include "gcem_incl/binomial_coef.hpp"
+    #include "gcem_incl/lgamma.hpp"
+    #include "gcem_incl/tgamma.hpp"
+    #include "gcem_incl/factorial.hpp"
+    #include "gcem_incl/lbeta.hpp"
+    #include "gcem_incl/beta.hpp"
+    #include "gcem_incl/lmgamma.hpp"
+    #include "gcem_incl/log_binomial_coef.hpp"
+
+    #include "gcem_incl/erf.hpp"
+    #include "gcem_incl/erf_inv.hpp"
+    #include "gcem_incl/incomplete_beta.hpp"
+    #include "gcem_incl/incomplete_beta_inv.hpp"
+    #include "gcem_incl/incomplete_gamma.hpp"
+    #include "gcem_incl/incomplete_gamma_inv.hpp"
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/abs.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/abs.hpp
new file mode 100644
index 0000000..0a3ada6
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/abs.hpp
@@ -0,0 +1,45 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+#ifndef _gcem_abs_HPP
+#define _gcem_abs_HPP
+
+/**
+ * Compile-time absolute value function
+ *
+ * @param x a real-valued input.
+ * @return the absolute value of \c x, \f$ |x| \f$.
+ */
+
+template<typename T>
+constexpr
+T
+abs(const T x)
+noexcept
+{
+    return( // deal with signed-zeros
+            x == T(0) ? \
+                T(0) :
+            // else
+            x < T(0) ? \
+                - x : x );
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/acos.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/acos.hpp
new file mode 100644
index 0000000..9d3bc07
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/acos.hpp
@@ -0,0 +1,84 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * compile-time arccosine function
+ */
+
+#ifndef _gcem_acos_HPP
+#define _gcem_acos_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr
+T
+acos_compute(const T x)
+noexcept
+{
+    return( // only defined on [-1,1]
+            abs(x) > T(1) ? \
+                GCLIM<T>::quiet_NaN() :
+            // indistinguishable from one or zero
+            GCLIM<T>::min() > abs(x -  T(1)) ? \
+                T(0) :
+            GCLIM<T>::min() > abs(x) ? \
+                T(GCEM_HALF_PI) :
+            // else
+                atan( sqrt(T(1) - x*x)/x ) );
+}
+
+template<typename T>
+constexpr
+T
+acos_check(const T x)
+noexcept
+{
+    return( // NaN check
+            is_nan(x) ? \
+                GCLIM<T>::quiet_NaN() :
+            //
+            x > T(0) ? \
+            // if
+                acos_compute(x) :
+            // else 
+                T(GCEM_PI) - acos_compute(-x) );
+}
+
+}
+
+/**
+ * Compile-time arccosine function
+ *
+ * @param x a real-valued input, where \f$ x \in [-1,1] \f$.
+ * @return the inverse cosine function using \f[ \text{acos}(x) = \text{atan} \left( \frac{\sqrt{1-x^2}}{x} \right) \f]
+ */
+
+template<typename T>
+constexpr
+return_t<T>
+acos(const T x)
+noexcept
+{
+    return internal::acos_check( static_cast<return_t<T>>(x) );
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/acosh.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/acosh.hpp
new file mode 100644
index 0000000..79579d7
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/acosh.hpp
@@ -0,0 +1,68 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * compile-time inverse hyperbolic cosine function
+ */
+
+#ifndef _gcem_acosh_HPP
+#define _gcem_acosh_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr
+T
+acosh_compute(const T x)
+noexcept
+{
+    return( // NaN check
+            is_nan(x) ? \
+                GCLIM<T>::quiet_NaN() :
+            // function defined for x >= 1
+            x < T(1) ? \
+                GCLIM<T>::quiet_NaN() :
+            // indistinguishable from 1
+            GCLIM<T>::min() > abs(x - T(1)) ? \
+                T(0) :
+            // else
+                log( x + sqrt(x*x - T(1)) ) );
+}
+
+}
+
+/**
+ * Compile-time inverse hyperbolic cosine function
+ *
+ * @param x a real-valued input.
+ * @return the inverse hyperbolic cosine function using \f[ \text{acosh}(x) = \ln \left( x + \sqrt{x^2 - 1} \right) \f]
+ */
+
+template<typename T>
+constexpr
+return_t<T>
+acosh(const T x)
+noexcept
+{
+    return internal::acosh_compute( static_cast<return_t<T>>(x) );
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/asin.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/asin.hpp
new file mode 100644
index 0000000..210d9fc
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/asin.hpp
@@ -0,0 +1,82 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * compile-time arcsine function
+ */
+
+#ifndef _gcem_asin_HPP
+#define _gcem_asin_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr
+T
+asin_compute(const T x)
+noexcept
+{
+    return( // only defined on [-1,1]
+            x > T(1) ? \
+                GCLIM<T>::quiet_NaN() :
+            // indistinguishable from one or zero
+            GCLIM<T>::min() > abs(x -  T(1)) ? \
+                T(GCEM_HALF_PI) :
+            GCLIM<T>::min() > abs(x) ? \
+                T(0) :
+            // else
+                atan( x/sqrt(T(1) - x*x) ) );
+}
+
+template<typename T>
+constexpr
+T
+asin_check(const T x)
+noexcept
+{
+    return( // NaN check
+            is_nan(x) ? \
+                GCLIM<T>::quiet_NaN() :
+            //
+            x < T(0) ? \
+                - asin_compute(-x) : 
+                  asin_compute(x) );
+}
+
+}
+
+/**
+ * Compile-time arcsine function
+ *
+ * @param x a real-valued input, where \f$ x \in [-1,1] \f$.
+ * @return the inverse sine function using \f[ \text{asin}(x) = \text{atan} \left( \frac{x}{\sqrt{1-x^2}} \right) \f]
+ */
+
+template<typename T>
+constexpr
+return_t<T>
+asin(const T x)
+noexcept
+{
+    return internal::asin_check( static_cast<return_t<T>>(x) );
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/asinh.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/asinh.hpp
new file mode 100644
index 0000000..dfad57e
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/asinh.hpp
@@ -0,0 +1,66 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * compile-time inverse hyperbolic sine function
+ */
+
+#ifndef _gcem_asinh_HPP
+#define _gcem_asinh_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr
+T
+asinh_compute(const T x)
+noexcept
+{
+    return( // NaN check
+            is_nan(x) ? \
+                GCLIM<T>::quiet_NaN() :
+            // indistinguishable from zero
+            GCLIM<T>::min() > abs(x) ? \
+                T(0) :
+            // else
+                log( x + sqrt(x*x + T(1)) ) );
+}
+
+}
+
+/**
+ * Compile-time inverse hyperbolic sine function
+ *
+ * @param x a real-valued input.
+ * @return the inverse hyperbolic sine function using \f[ \text{asinh}(x) = \ln \left( x + \sqrt{x^2 + 1} \right) \f]
+ */
+
+template<typename T>
+constexpr
+return_t<T>
+asinh(const T x)
+noexcept
+{
+    return internal::asinh_compute( static_cast<return_t<T>>(x) );
+}
+
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/atan.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/atan.hpp
new file mode 100644
index 0000000..9aea85b
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/atan.hpp
@@ -0,0 +1,155 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * compile-time arctangent function
+ */
+
+// see
+// http://functions.wolfram.com/ElementaryFunctions/ArcTan/10/0001/
+// http://functions.wolfram.com/ElementaryFunctions/ArcTan/06/01/06/01/0002/
+
+#ifndef _gcem_atan_HPP
+#define _gcem_atan_HPP
+
+namespace internal
+{
+
+// Series
+
+template<typename T>
+constexpr
+T
+atan_series_order_calc(const T x, const T x_pow, const uint_t order)
+noexcept
+{
+    return( T(1)/( T((order-1)*4 - 1) * x_pow ) \
+              - T(1)/( T((order-1)*4 + 1) * x_pow*x) );
+}
+
+template<typename T>
+constexpr
+T
+atan_series_order(const T x, const T x_pow, const uint_t order, const uint_t max_order)
+noexcept
+{
+    return( order == 1 ? \
+                GCEM_HALF_PI - T(1)/x + atan_series_order(x*x,pow(x,3),order+1,max_order) :
+            // NOTE: x changes to x*x for order > 1
+            order < max_order ? \
+                atan_series_order_calc(x,x_pow,order) \
+                    + atan_series_order(x,x_pow*x*x,order+1,max_order) :
+            // order == max_order
+                atan_series_order_calc(x,x_pow,order) );
+}
+
+template<typename T>
+constexpr
+T
+atan_series_main(const T x)
+noexcept
+{
+    return( x < T(3)    ? atan_series_order(x,x,1U,10U) :  // O(1/x^39)
+            x < T(4)    ? atan_series_order(x,x,1U,9U)  :  // O(1/x^35)
+            x < T(5)    ? atan_series_order(x,x,1U,8U)  :  // O(1/x^31)
+            x < T(7)    ? atan_series_order(x,x,1U,7U)  :  // O(1/x^27)
+            x < T(11)   ? atan_series_order(x,x,1U,6U)  :  // O(1/x^23)
+            x < T(25)   ? atan_series_order(x,x,1U,5U)  :  // O(1/x^19)
+            x < T(100)  ? atan_series_order(x,x,1U,4U)  :  // O(1/x^15)
+            x < T(1000) ? atan_series_order(x,x,1U,3U)  :  // O(1/x^11)
+                          atan_series_order(x,x,1U,2U) );  // O(1/x^7)
+}
+
+// CF
+
+template<typename T>
+constexpr
+T
+atan_cf_recur(const T xx, const uint_t depth, const uint_t max_depth)
+noexcept
+{
+    return( depth < max_depth ? \
+            // if
+                T(2*depth - 1) + depth*depth*xx/atan_cf_recur(xx,depth+1,max_depth) :
+            // else
+                T(2*depth - 1) );
+}
+
+template<typename T>
+constexpr
+T
+atan_cf_main(const T x)
+noexcept
+{
+    return( x < T(0.5) ? x/atan_cf_recur(x*x,1U, 15U ) : 
+            x < T(1)   ? x/atan_cf_recur(x*x,1U, 25U ) : 
+            x < T(1.5) ? x/atan_cf_recur(x*x,1U, 35U ) : 
+            x < T(2)   ? x/atan_cf_recur(x*x,1U, 45U ) : 
+                         x/atan_cf_recur(x*x,1U, 52U ) );
+}
+
+//
+
+template<typename T>
+constexpr
+T
+atan_begin(const T x)
+noexcept
+{
+    return( x > T(2.5) ? atan_series_main(x) : atan_cf_main(x) );
+}
+
+template<typename T>
+constexpr
+T
+atan_check(const T x)
+noexcept
+{
+    return( // NaN check
+            is_nan(x) ? \
+                GCLIM<T>::quiet_NaN() :
+            // indistinguishable from zero
+            GCLIM<T>::min() > abs(x) ? \
+                T(0) :
+            // negative or positive
+            x < T(0) ? \
+                - atan_begin(-x) :
+                  atan_begin( x) );
+}
+
+}
+
+/**
+ * Compile-time arctangent function
+ *
+ * @param x a real-valued input.
+ * @return the inverse tangent function using \f[ \text{atan}(x) = \dfrac{x}{1 + \dfrac{x^2}{3 + \dfrac{4x^2}{5 + \dfrac{9x^2}{7 + \ddots}}}} \f]
+ */
+
+template<typename T>
+constexpr
+return_t<T>
+atan(const T x)
+noexcept
+{
+    return internal::atan_check( static_cast<return_t<T>>(x) );
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/atan2.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/atan2.hpp
new file mode 100644
index 0000000..97c8d6a
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/atan2.hpp
@@ -0,0 +1,88 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * compile-time two-argument arctangent function
+ */
+
+#ifndef _gcem_atan2_HPP
+#define _gcem_atan2_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr
+T
+atan2_compute(const T y, const T x)
+noexcept
+{
+    return( // NaN check
+            any_nan(y,x) ? \
+                GCLIM<T>::quiet_NaN() :
+            //
+            GCLIM<T>::min() > abs(x) ? \
+            //
+                GCLIM<T>::min() > abs(y) ? \
+                    neg_zero(y) ? \
+                        neg_zero(x) ? - T(GCEM_PI) : - T(0) :
+                        neg_zero(x) ?   T(GCEM_PI) :   T(0) :
+                y > T(0) ? \
+                    T(GCEM_HALF_PI) : - T(GCEM_HALF_PI) :
+            //
+            x < T(0) ? \
+                y < T(0) ? \
+                    atan(y/x) - T(GCEM_PI) : 
+                    atan(y/x) + T(GCEM_PI) :
+            //
+                atan(y/x) );
+}
+
+template<typename T1, typename T2, typename TC = common_return_t<T1,T2>>
+constexpr
+TC
+atan2_type_check(const T1 y, const T2 x)
+noexcept
+{
+    return atan2_compute(static_cast<TC>(x),static_cast<TC>(y));
+}
+
+}
+
+/**
+ * Compile-time two-argument arctangent function
+ *
+ * @param y a real-valued input.
+ * @param x a real-valued input.
+ * @return \f[ \text{atan2}(y,x) = \begin{cases} \text{atan}(y/x) & \text{ if } x > 0 \\ \text{atan}(y/x) + \pi & \text{ if } x < 0 \text{ and } y \geq 0 \\ \text{atan}(y/x) - \pi & \text{ if } x < 0 \text{ and } y < 0 \\ + \pi/2 & \text{ if } x = 0 \text{ and } y > 0 \\ - \pi/2 & \text{ if } x = 0 \text{ and } y < 0 \end{cases} \f]
+ * The function is undefined at the origin, however the following conventions are used.
+ * \f[ \text{atan2}(y,x) = \begin{cases} +0 & \text{ if } x = +0 \text{ and } y = +0 \\ -0 & \text{ if } x = +0 \text{ and } y = -0 \\ +\pi & \text{ if } x = -0 \text{ and } y = +0 \\ - \pi & \text{ if } x = -0 \text{ and } y = -0 \end{cases} \f]
+ */
+
+template<typename T1, typename T2>
+constexpr
+common_return_t<T1,T2>
+atan2(const T1 y, const T2 x)
+noexcept
+{
+    return internal::atan2_type_check(x,y);
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/atanh.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/atanh.hpp
new file mode 100644
index 0000000..2e1cb76
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/atanh.hpp
@@ -0,0 +1,79 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * compile-time inverse hyperbolic tangent function
+ */
+
+#ifndef _gcem_atanh_HPP
+#define _gcem_atanh_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr
+T
+atanh_compute(const T x)
+noexcept
+{
+    return( log( (T(1) + x)/(T(1) - x) ) / T(2) );
+}
+
+template<typename T>
+constexpr
+T
+atanh_check(const T x)
+noexcept
+{
+    return( // NaN check
+            is_nan(x) ? \
+                GCLIM<T>::quiet_NaN() :
+            // function is defined for |x| < 1
+            T(1) < abs(x) ? \
+                GCLIM<T>::quiet_NaN() :
+            GCLIM<T>::min() > (T(1) - abs(x)) ? \
+                sgn(x)*GCLIM<T>::infinity() :
+            // indistinguishable from zero
+            GCLIM<T>::min() > abs(x) ? \
+                T(0) :
+            // else
+                atanh_compute(x) );
+}
+
+}
+
+/**
+ * Compile-time inverse hyperbolic tangent function
+ *
+ * @param x a real-valued input.
+ * @return the inverse hyperbolic tangent function using \f[ \text{atanh}(x) = \frac{1}{2} \ln \left( \frac{1+x}{1-x} \right) \f]
+ */
+
+template<typename T>
+constexpr
+return_t<T>
+atanh(const T x)
+noexcept
+{
+    return internal::atanh_check( static_cast<return_t<T>>(x) );
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/beta.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/beta.hpp
new file mode 100644
index 0000000..e888e47
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/beta.hpp
@@ -0,0 +1,42 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+#ifndef _gcem_beta_HPP
+#define _gcem_beta_HPP
+
+/**
+ * Compile-time beta function
+ *
+ * @param a a real-valued input.
+ * @param b a real-valued input.
+ * @return the beta function using \f[ \text{B}(\alpha,\beta) := \int_0^1 t^{\alpha - 1} (1-t)^{\beta - 1} dt = \frac{\Gamma(\alpha)\Gamma(\beta)}{\Gamma(\alpha + \beta)} \f]
+ * where \f$ \Gamma \f$ denotes the gamma function.
+ */
+
+template<typename T1, typename T2>
+constexpr
+common_return_t<T1,T2>
+beta(const T1 a, const T2 b)
+noexcept
+{
+    return exp( lbeta(a,b) );
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/binomial_coef.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/binomial_coef.hpp
new file mode 100644
index 0000000..fb050a2
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/binomial_coef.hpp
@@ -0,0 +1,91 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+#ifndef _gcem_binomial_coef_HPP
+#define _gcem_binomial_coef_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr
+T
+binomial_coef_recur(const T n, const T k)
+noexcept
+{
+    return( // edge cases
+                (k == T(0) || n == k) ? T(1) : // deals with 0 choose 0 case
+                n == T(0) ? T(0) :
+            // else
+                binomial_coef_recur(n-1,k-1) + binomial_coef_recur(n-1,k) );
+}
+
+template<typename T, typename std::enable_if<std::is_integral<T>::value>::type* = nullptr>
+constexpr
+T
+binomial_coef_check(const T n, const T k)
+noexcept
+{
+    return binomial_coef_recur(n,k);
+}
+
+template<typename T, typename std::enable_if<!std::is_integral<T>::value>::type* = nullptr>
+constexpr
+T
+binomial_coef_check(const T n, const T k)
+noexcept
+{
+    return( // NaN check; removed due to MSVC problems; template not being ignored in <int> cases
+            // (is_nan(n) || is_nan(k)) ? GCLIM<T>::quiet_NaN() :
+            //
+            static_cast<T>(binomial_coef_recur(static_cast<ullint_t>(n),static_cast<ullint_t>(k))) );
+}
+
+template<typename T1, typename T2, typename TC = common_t<T1,T2>>
+constexpr
+TC
+binomial_coef_type_check(const T1 n, const T2 k)
+noexcept
+{
+    return binomial_coef_check(static_cast<TC>(n),static_cast<TC>(k));
+}
+
+}
+
+/**
+ * Compile-time binomial coefficient
+ *
+ * @param n integral-valued input.
+ * @param k integral-valued input.
+ * @return computes the Binomial coefficient
+ * \f[ \binom{n}{k} = \frac{n!}{k!(n-k)!} \f]
+ * also known as '\c n choose \c k '.
+ */
+
+template<typename T1, typename T2>
+constexpr
+common_t<T1,T2>
+binomial_coef(const T1 n, const T2 k)
+noexcept
+{
+    return internal::binomial_coef_type_check(n,k);
+}
+
+#endif
\ No newline at end of file
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/ceil.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/ceil.hpp
new file mode 100644
index 0000000..e8570ab
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/ceil.hpp
@@ -0,0 +1,130 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+#ifndef _gcem_ceil_HPP
+#define _gcem_ceil_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr
+int
+ceil_resid(const T x, const T x_whole)
+noexcept
+{
+    return( (x > T(0)) && (x > x_whole) );
+}
+
+template<typename T>
+constexpr
+T
+ceil_int(const T x, const T x_whole)
+noexcept
+{
+    return( x_whole + static_cast<T>(ceil_resid(x,x_whole)) );
+}
+
+template<typename T>
+constexpr
+T
+ceil_check_internal(const T x)
+noexcept
+{
+    return x;
+}
+
+template<>
+constexpr
+float
+ceil_check_internal<float>(const float x)
+noexcept
+{
+    return( abs(x) >= 8388608.f ? \
+            // if
+                x : \
+            // else
+                ceil_int(x, float(static_cast<int>(x))) );
+}
+
+template<>
+constexpr
+double
+ceil_check_internal<double>(const double x)
+noexcept
+{
+    return( abs(x) >= 4503599627370496. ? \
+            // if
+                x : \
+            // else
+                ceil_int(x, double(static_cast<llint_t>(x))) );
+}
+
+template<>
+constexpr
+long double
+ceil_check_internal<long double>(const long double x)
+noexcept
+{
+    return( abs(x) >= 9223372036854775808.l ? \
+            // if
+                x : \
+            // else
+                ceil_int(x, ((long double)static_cast<ullint_t>(abs(x))) * sgn(x)) );
+}
+
+template<typename T>
+constexpr
+T
+ceil_check(const T x)
+noexcept
+{
+    return( // NaN check
+            is_nan(x) ? \
+                GCLIM<T>::quiet_NaN() :
+            // +/- infinite
+            !is_finite(x) ? \
+                x :
+            // signed-zero cases
+            GCLIM<T>::min() > abs(x) ? \
+                x :
+            // else
+                ceil_check_internal(x) );
+}
+
+}
+
+/**
+ * Compile-time ceil function
+ *
+ * @param x a real-valued input.
+ * @return computes the ceiling-value of the input.
+ */
+
+template<typename T>
+constexpr
+return_t<T>
+ceil(const T x)
+noexcept
+{
+    return internal::ceil_check( static_cast<return_t<T>>(x) );
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/copysign.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/copysign.hpp
new file mode 100644
index 0000000..a3bab74
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/copysign.hpp
@@ -0,0 +1,41 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+#ifndef _gcem_copysign_HPP
+#define _gcem_copysign_HPP
+
+/**
+ * Compile-time copy sign function
+ *
+ * @param x a real-valued input
+ * @param y a real-valued input
+ * @return replace the signbit of \c x with the signbit of \c y.
+ */
+
+template <typename T1, typename T2>
+constexpr
+T1
+copysign(const T1 x, const T2 y)
+noexcept
+{
+    return( signbit(x) != signbit(y) ? -x : x );
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/cos.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/cos.hpp
new file mode 100644
index 0000000..0e98012
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/cos.hpp
@@ -0,0 +1,83 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * compile-time cosine function using tan(x/2)
+ */
+
+#ifndef _gcem_cos_HPP
+#define _gcem_cos_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr
+T
+cos_compute(const T x)
+noexcept
+{
+    return( T(1) - x*x)/(T(1) + x*x );
+}
+
+template<typename T>
+constexpr
+T
+cos_check(const T x)
+noexcept
+{
+    return( // NaN check
+            is_nan(x) ? \
+                GCLIM<T>::quiet_NaN() :
+            // indistinguishable from 0
+            GCLIM<T>::min() > abs(x) ? 
+                T(1) :
+            // special cases: pi/2 and pi
+            GCLIM<T>::min() > abs(x - T(GCEM_HALF_PI)) ? \
+                T(0) :
+            GCLIM<T>::min() > abs(x + T(GCEM_HALF_PI)) ? \
+                T(0) :
+            GCLIM<T>::min() > abs(x - T(GCEM_PI)) ? \
+                - T(1) :
+            GCLIM<T>::min() > abs(x + T(GCEM_PI)) ? \
+                - T(1) :
+            // else
+                cos_compute( tan(x/T(2)) ) );
+}
+
+}
+
+/**
+ * Compile-time cosine function
+ *
+ * @param x a real-valued input.
+ * @return the cosine function using \f[ \cos(x) = \frac{1-\tan^2(x/2)}{1+\tan^2(x/2)} \f]
+ */
+
+template<typename T>
+constexpr
+return_t<T>
+cos(const T x)
+noexcept
+{
+    return internal::cos_check( static_cast<return_t<T>>(x) );
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/cosh.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/cosh.hpp
new file mode 100644
index 0000000..b3cebb8
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/cosh.hpp
@@ -0,0 +1,65 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * compile-time hyperbolic cosine function
+ */
+
+#ifndef _gcem_cosh_HPP
+#define _gcem_cosh_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr
+T
+cosh_compute(const T x)
+noexcept
+{
+    return( // NaN check
+            is_nan(x) ? \
+                GCLIM<T>::quiet_NaN() :
+            // indistinguishable from zero
+            GCLIM<T>::min() > abs(x) ? \
+                T(1) : 
+            // else
+                (exp(x) + exp(-x)) / T(2) );
+}
+
+}
+
+/**
+ * Compile-time hyperbolic cosine function
+ *
+ * @param x a real-valued input.
+ * @return the hyperbolic cosine function using \f[ \cosh(x) = \frac{\exp(x) + \exp(-x)}{2} \f]
+ */
+
+template<typename T>
+constexpr
+return_t<T>
+cosh(const T x)
+noexcept
+{
+    return internal::cosh_compute( static_cast<return_t<T>>(x) );
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/erf.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/erf.hpp
new file mode 100644
index 0000000..afec09e
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/erf.hpp
@@ -0,0 +1,143 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * compile-time error function
+ */
+
+#ifndef _gcem_erf_HPP
+#define _gcem_erf_HPP
+
+namespace internal
+{
+
+// see
+// http://functions.wolfram.com/GammaBetaErf/Erf/10/01/0007/
+
+template<typename T>
+constexpr
+T
+erf_cf_large_recur(const T x, const int depth)
+noexcept
+{
+    return( depth < GCEM_ERF_MAX_ITER ? \
+            // if
+                x + 2*depth/erf_cf_large_recur(x,depth+1) :
+            // else
+                x );
+}
+
+template<typename T>
+constexpr
+T
+erf_cf_large_main(const T x)
+noexcept
+{
+    return( T(1) - T(2) * ( exp(-x*x) / T(GCEM_SQRT_PI) ) \
+                / erf_cf_large_recur(T(2)*x,1) );
+}
+
+// see
+// http://functions.wolfram.com/GammaBetaErf/Erf/10/01/0005/
+
+template<typename T>
+constexpr
+T
+erf_cf_small_recur(const T xx, const int depth)
+noexcept
+{
+    return( depth < GCEM_ERF_MAX_ITER ? \
+            // if
+                (2*depth - T(1)) - 2*xx \
+                    + 4*depth*xx / erf_cf_small_recur(xx,depth+1) :
+            // else
+                (2*depth - T(1)) - 2*xx );
+}
+
+template<typename T>
+constexpr
+T
+erf_cf_small_main(const T x)
+noexcept
+{
+    return( T(2) * x * ( exp(-x*x) / T(GCEM_SQRT_PI) ) \
+                / erf_cf_small_recur(x*x,1) );
+}
+
+//
+
+template<typename T>
+constexpr
+T
+erf_begin(const T x)
+noexcept
+{
+    return( x > T(2.1) ? \
+            // if
+                erf_cf_large_main(x) :
+            // else
+                erf_cf_small_main(x) );
+}
+
+template<typename T>
+constexpr
+T
+erf_check(const T x)
+noexcept
+{
+    return( // NaN check
+            is_nan(x) ? \
+                GCLIM<T>::quiet_NaN() :
+            // +/-Inf
+            is_posinf(x) ? \
+                T(1) :
+            is_neginf(x) ? \
+                - T(1) :
+            // indistinguishable from zero
+            GCLIM<T>::min() > abs(x) ? \
+                T(0) :
+            // else
+                x < T(0) ? \
+                    - erf_begin(-x) : 
+                      erf_begin( x) );
+}
+
+}
+
+/**
+ * Compile-time Gaussian error function
+ *
+ * @param x a real-valued input.
+ * @return computes the Gaussian error function
+ * \f[ \text{erf}(x) = \frac{2}{\sqrt{\pi}} \int_0^x \exp( - t^2) dt \f]
+ * using a continued fraction representation:
+ * \f[ \text{erf}(x) = \frac{2x}{\sqrt{\pi}} \exp(-x^2) \dfrac{1}{1 - 2x^2 + \dfrac{4x^2}{3 - 2x^2 + \dfrac{8x^2}{5 - 2x^2 + \dfrac{12x^2}{7 - 2x^2 + \ddots}}}} \f]
+ */
+
+template<typename T>
+constexpr
+return_t<T>
+erf(const T x)
+noexcept
+{
+    return internal::erf_check( static_cast<return_t<T>>(x) );
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/erf_inv.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/erf_inv.hpp
new file mode 100644
index 0000000..a93f8db
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/erf_inv.hpp
@@ -0,0 +1,264 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/* 
+ * compile-time inverse error function
+ *
+ * Initial approximation based on:
+ * 'Approximating the erfinv function' by Mike Giles
+ */
+
+#ifndef _gcem_erf_inv_HPP
+#define _gcem_erf_inv_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr T erf_inv_decision(const T value, const T p, const T direc, const int iter_count) noexcept;
+
+//
+// initial value
+
+// two cases: (1) a < 5; and (2) otherwise
+
+template<typename T>
+constexpr
+T
+erf_inv_initial_val_coef_2(const T a, const T p_term, const int order)
+noexcept
+{
+    return( order == 1 ? T(-0.000200214257L) :
+            order == 2 ? T( 0.000100950558L) + a*p_term :
+            order == 3 ? T( 0.00134934322L)  + a*p_term :
+            order == 4 ? T(-0.003673428440L) + a*p_term :
+            order == 5 ? T( 0.005739507730L) + a*p_term :
+            order == 6 ? T(-0.00762246130L)  + a*p_term :
+            order == 7 ? T( 0.009438870470L) + a*p_term :
+            order == 8 ? T( 1.001674060000L) + a*p_term :
+            order == 9 ? T( 2.83297682000L)  + a*p_term :
+                         p_term );
+}
+
+template<typename T>
+constexpr
+T
+erf_inv_initial_val_case_2(const T a, const T p_term, const int order)
+noexcept
+{
+    return( order == 9 ? \
+            // if
+                erf_inv_initial_val_coef_2(a,p_term,order) :
+            // else
+                erf_inv_initial_val_case_2(a,erf_inv_initial_val_coef_2(a,p_term,order),order+1) );
+}
+
+template<typename T>
+constexpr
+T
+erf_inv_initial_val_coef_1(const T a, const T p_term, const int order)
+noexcept
+{
+    return( order == 1 ? T( 2.81022636e-08L) : 
+            order == 2 ? T( 3.43273939e-07L) + a*p_term :
+            order == 3 ? T(-3.5233877e-06L)  + a*p_term :
+            order == 4 ? T(-4.39150654e-06L) + a*p_term :
+            order == 5 ? T( 0.00021858087L)  + a*p_term :
+            order == 6 ? T(-0.00125372503L)  + a*p_term :
+            order == 7 ? T(-0.004177681640L) + a*p_term :
+            order == 8 ? T( 0.24664072700L)  + a*p_term :
+            order == 9 ? T( 1.50140941000L)  + a*p_term :
+                         p_term );
+}
+
+template<typename T>
+constexpr
+T
+erf_inv_initial_val_case_1(const T a, const T p_term, const int order)
+noexcept
+{
+    return( order == 9 ? \
+            // if
+                erf_inv_initial_val_coef_1(a,p_term,order) :
+            // else
+                erf_inv_initial_val_case_1(a,erf_inv_initial_val_coef_1(a,p_term,order),order+1) );
+}
+
+template<typename T>
+constexpr
+T
+erf_inv_initial_val_int(const T a)
+noexcept
+{
+    return( a < T(5) ? \
+            // if
+                erf_inv_initial_val_case_1(a-T(2.5),T(0),1) :
+            // else
+                erf_inv_initial_val_case_2(sqrt(a)-T(3),T(0),1) );
+}
+
+template<typename T>
+constexpr
+T
+erf_inv_initial_val(const T x)
+noexcept
+{
+    return x*erf_inv_initial_val_int( -log( (T(1) - x)*(T(1) + x) ) );
+}
+
+//
+// Halley recursion
+
+template<typename T>
+constexpr
+T
+erf_inv_err_val(const T value, const T p)
+noexcept
+{   // err_val = f(x)
+    return( erf(value) - p );
+}
+
+template<typename T>
+constexpr
+T
+erf_inv_deriv_1(const T value)
+noexcept
+{   // derivative of the error function w.r.t. x
+    return( exp( -value*value ) );
+}
+
+template<typename T>
+constexpr
+T
+erf_inv_deriv_2(const T value, const T deriv_1)
+noexcept
+{   // second derivative of the error function w.r.t. x
+    return( deriv_1*( -T(2)*value ) );
+}
+
+template<typename T>
+constexpr
+T
+erf_inv_ratio_val_1(const T value, const T p, const T deriv_1)
+noexcept
+{
+    return( erf_inv_err_val(value,p) / deriv_1 );
+}
+
+template<typename T>
+constexpr
+T
+erf_inv_ratio_val_2(const T value, const T deriv_1)
+noexcept
+{
+    return( erf_inv_deriv_2(value,deriv_1) / deriv_1 );
+}
+
+template<typename T>
+constexpr
+T
+erf_inv_halley(const T ratio_val_1, const T ratio_val_2)
+noexcept
+{
+    return( ratio_val_1 / max( T(0.8), min( T(1.2), T(1) - T(0.5)*ratio_val_1*ratio_val_2 ) ) );
+}
+
+template<typename T>
+constexpr
+T
+erf_inv_recur(const T value, const T p, const T deriv_1, const int iter_count)
+noexcept
+{
+    return erf_inv_decision( value, p, 
+                             erf_inv_halley(erf_inv_ratio_val_1(value,p,deriv_1), 
+                                            erf_inv_ratio_val_2(value,deriv_1)),
+                             iter_count );
+}
+
+template<typename T>
+constexpr
+T
+erf_inv_decision(const T value, const T p, const T direc, const int iter_count)
+noexcept
+{
+    return( iter_count < GCEM_ERF_INV_MAX_ITER ? \
+            // if
+                erf_inv_recur(value-direc,p, erf_inv_deriv_1(value), iter_count+1) :
+            // else
+                value - direc );
+}
+
+template<typename T>
+constexpr
+T
+erf_inv_recur_begin(const T initial_val, const T p)
+noexcept
+{
+    return erf_inv_recur(initial_val,p,erf_inv_deriv_1(initial_val),1);
+}
+
+template<typename T>
+constexpr
+T
+erf_inv_begin(const T p)
+noexcept
+{
+    return( // NaN check
+            is_nan(p) ? \
+                GCLIM<T>::quiet_NaN() :
+            // bad values
+            abs(p) > T(1) ? \
+                GCLIM<T>::quiet_NaN() :
+            // indistinguishable from 1
+            GCLIM<T>::min() > abs(T(1) - p) ? \
+                GCLIM<T>::infinity() :
+            // indistinguishable from - 1
+            GCLIM<T>::min() > abs(T(1) + p) ? \
+                - GCLIM<T>::infinity() :
+            // else
+            erf_inv_recur_begin(erf_inv_initial_val(p),p) );
+}
+
+}
+
+/**
+ * Compile-time inverse Gaussian error function
+ *
+ * @param p a real-valued input with values in the unit-interval.
+ * @return Computes the inverse Gaussian error function, a value \f$ x \f$ such that 
+ * \f[ f(x) := \text{erf}(x) - p \f]
+ * is equal to zero, for a given \c p. 
+ * GCE-Math finds this root using Halley's method:
+ * \f[ x_{n+1} = x_n - \frac{f(x_n)/f'(x_n)}{1 - 0.5 \frac{f(x_n)}{f'(x_n)} \frac{f''(x_n)}{f'(x_n)} } \f]
+ * where
+ * \f[ \frac{\partial}{\partial x} \text{erf}(x) = \exp(-x^2), \ \ \frac{\partial^2}{\partial x^2} \text{erf}(x) = -2x\exp(-x^2) \f]
+ */
+
+template<typename T>
+constexpr
+return_t<T>
+erf_inv(const T p)
+noexcept
+{
+    return internal::erf_inv_begin( static_cast<return_t<T>>(p) );
+}
+
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/exp.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/exp.hpp
new file mode 100644
index 0000000..0c66829
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/exp.hpp
@@ -0,0 +1,106 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * compile-time exponential function
+ */
+
+#ifndef _gcem_exp_HPP
+#define _gcem_exp_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr
+T
+exp_cf_recur(const T x, const int depth)
+noexcept
+{
+    return( depth < GCEM_EXP_MAX_ITER_SMALL ? \
+            // if
+                depth == 1 ? \
+                    T(1) - x/exp_cf_recur(x,depth+1) : 
+                    T(1) + x/T(depth - 1) - x/depth/exp_cf_recur(x,depth+1) : 
+             // else
+                T(1) );
+}
+
+template<typename T>
+constexpr
+T
+exp_cf(const T x)
+noexcept
+{
+    return( T(1)/exp_cf_recur(x,1) );
+}
+
+template<typename T>
+constexpr
+T
+exp_split(const T x)
+noexcept
+{
+    return( static_cast<T>(pow_integral(GCEM_E,find_whole(x))) * exp_cf(find_fraction(x)) );
+}
+
+template<typename T>
+constexpr
+T
+exp_check(const T x)
+noexcept
+{
+    return( is_nan(x) ? \
+                GCLIM<T>::quiet_NaN() :
+            //
+            is_neginf(x) ? \
+                T(0) :
+            //
+            GCLIM<T>::min() > abs(x) ? \
+                T(1) : 
+            //
+            is_posinf(x) ? \
+                GCLIM<T>::infinity() :
+            //
+            abs(x) < T(2) ? \
+                exp_cf(x) : \
+                exp_split(x) );
+}
+
+}
+
+/**
+ * Compile-time exponential function
+ *
+ * @param x a real-valued input.
+ * @return \f$ \exp(x) \f$ using \f[ \exp(x) = \dfrac{1}{1-\dfrac{x}{1+x-\dfrac{\frac{1}{2}x}{1 + \frac{1}{2}x - \dfrac{\frac{1}{3}x}{1 + \frac{1}{3}x - \ddots}}}} \f] 
+ * The continued fraction argument is split into two parts: \f$ x = n + r \f$, where \f$ n \f$ is an integer and \f$ r \in [-0.5,0.5] \f$.
+ */
+
+template<typename T>
+constexpr
+return_t<T>
+exp(const T x)
+noexcept
+{
+    return internal::exp_check( static_cast<return_t<T>>(x) );
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/expm1.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/expm1.hpp
new file mode 100644
index 0000000..11b2eb9
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/expm1.hpp
@@ -0,0 +1,76 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * compile-time exponential function
+ */
+
+#ifndef _gcem_expm1_HPP
+#define _gcem_expm1_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr
+T
+expm1_compute(const T x)
+noexcept
+{
+    // return x * ( T(1) + x * ( T(1)/T(2) + x * ( T(1)/T(6) + x * ( T(1)/T(24) +  x/T(120) ) ) ) ); // O(x^6)
+    return x + x * ( x/T(2) + x * ( x/T(6) + x * ( x/T(24) +  x*x/T(120) ) ) ); // O(x^6)
+}
+
+template<typename T>
+constexpr
+T
+expm1_check(const T x)
+noexcept
+{
+    return( // NaN check
+            is_nan(x) ? \
+                GCLIM<T>::quiet_NaN() :
+            //
+            abs(x) > T(1e-04) ? \
+            // if
+                exp(x) - T(1) :
+            // else    
+                expm1_compute(x) );
+}
+
+}
+
+/**
+ * Compile-time exponential-minus-1 function
+ *
+ * @param x a real-valued input.
+ * @return \f$ \exp(x) - 1 \f$ using \f[ \exp(x) = \sum_{k=0}^\infty \dfrac{x^k}{k!} \f] 
+ */
+
+template<typename T>
+constexpr
+return_t<T>
+expm1(const T x)
+noexcept
+{
+    return internal::expm1_check( static_cast<return_t<T>>(x) );
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/factorial.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/factorial.hpp
new file mode 100644
index 0000000..539c3f3
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/factorial.hpp
@@ -0,0 +1,98 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * compile-time factorial function
+ */
+
+#ifndef _gcem_factorial_HPP
+#define _gcem_factorial_HPP
+
+namespace internal
+{
+
+// T should be int, long int, unsigned int, etc.
+
+template<typename T>
+constexpr
+T
+factorial_table(const T x)
+noexcept
+{   // table for x! when x = {2,...,16}
+    return( x == T(2)  ? T(2)     : x == T(3)  ? T(6)      :
+            x == T(4)  ? T(24)    : x == T(5)  ? T(120)    :
+            x == T(6)  ? T(720)   : x == T(7)  ? T(5040)   :
+            x == T(8)  ? T(40320) : x == T(9)  ? T(362880) :
+            //
+            x == T(10) ? T(3628800)       : 
+            x == T(11) ? T(39916800)      :
+            x == T(12) ? T(479001600)     :
+            x == T(13) ? T(6227020800)    : 
+            x == T(14) ? T(87178291200)   : 
+            x == T(15) ? T(1307674368000) : 
+                         T(20922789888000) );
+}
+
+template<typename T, typename std::enable_if<std::is_integral<T>::value>::type* = nullptr>
+constexpr
+T
+factorial_recur(const T x)
+noexcept
+{
+    return( x == T(0) ? T(1) :
+            x == T(1) ? x :
+            //
+            x < T(17) ? \
+                // if
+                factorial_table(x) :
+                // else
+                x*factorial_recur(x-1) );
+}
+
+template<typename T, typename std::enable_if<!std::is_integral<T>::value>::type* = nullptr>
+constexpr
+T
+factorial_recur(const T x)
+noexcept
+{
+    return tgamma(x + 1);
+}
+
+}
+
+/**
+ * Compile-time factorial function
+ *
+ * @param x a real-valued input.
+ * @return Computes the factorial value \f$ x! \f$. 
+ * When \c x is an integral type (\c int, <tt>long int</tt>, etc.), a simple recursion method is used, along with table values.
+ * When \c x is real-valued, <tt>factorial(x) = tgamma(x+1)</tt>.
+ */
+
+template<typename T>
+constexpr
+T
+factorial(const T x)
+noexcept
+{
+    return internal::factorial_recur(x);
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/find_exponent.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/find_exponent.hpp
new file mode 100644
index 0000000..710adce
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/find_exponent.hpp
@@ -0,0 +1,47 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * compile-time find_exponent function
+ */
+
+#ifndef _gcem_find_exponent_HPP
+#define _gcem_find_exponent_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr
+llint_t
+find_exponent(const T x, const llint_t exponent)
+noexcept
+{
+    return( x < T(1)  ? \
+                find_exponent(x*T(10),exponent - llint_t(1)) :
+            x > T(10) ? \
+                find_exponent(x/T(10),exponent + llint_t(1)) :
+            // else
+                exponent );
+}
+
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/find_fraction.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/find_fraction.hpp
new file mode 100644
index 0000000..d9769e6
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/find_fraction.hpp
@@ -0,0 +1,46 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * find the fraction part of x = n + r, where -0.5 <= r <= 0.5
+ */
+
+#ifndef _gcem_find_fraction_HPP
+#define _gcem_find_fraction_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr
+T
+find_fraction(const T x)
+noexcept
+{
+    return( abs(x - internal::floor_check(x)) >= T(0.5) ? \
+            // if 
+                x - internal::floor_check(x) - sgn(x) : 
+            //else 
+                x - internal::floor_check(x) );
+}
+
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/find_whole.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/find_whole.hpp
new file mode 100644
index 0000000..bd5e0b9
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/find_whole.hpp
@@ -0,0 +1,46 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * find the whole number part of x = n + r, where -0.5 <= r <= 0.5
+ */
+
+#ifndef _gcem_find_whole_HPP
+#define _gcem_find_whole_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr
+llint_t
+find_whole(const T x)
+noexcept
+{
+    return( abs(x - internal::floor_check(x)) >= T(0.5) ? \
+            // if 
+                static_cast<llint_t>(internal::floor_check(x) + sgn(x)) :
+            // else 
+                static_cast<llint_t>(internal::floor_check(x)) );
+}
+
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/floor.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/floor.hpp
new file mode 100644
index 0000000..c60ff6a
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/floor.hpp
@@ -0,0 +1,130 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+#ifndef _gcem_floor_HPP
+#define _gcem_floor_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr
+int
+floor_resid(const T x, const T x_whole)
+noexcept
+{
+    return( (x < T(0)) && (x < x_whole) );
+}
+
+template<typename T>
+constexpr
+T
+floor_int(const T x, const T x_whole)
+noexcept
+{
+    return( x_whole - static_cast<T>(floor_resid(x,x_whole)) );
+}
+
+template<typename T>
+constexpr
+T
+floor_check_internal(const T x)
+noexcept
+{
+    return x;
+}
+
+template<>
+constexpr
+float
+floor_check_internal<float>(const float x)
+noexcept
+{
+    return( abs(x) >= 8388608.f ? \
+            // if
+                x : \
+            // else
+                floor_int(x, float(static_cast<int>(x))) );
+}
+
+template<>
+constexpr
+double
+floor_check_internal<double>(const double x)
+noexcept
+{
+    return( abs(x) >= 4503599627370496. ? \
+            // if
+                x : \
+            // else
+                floor_int(x, double(static_cast<llint_t>(x))) );
+}
+
+template<>
+constexpr
+long double
+floor_check_internal<long double>(const long double x)
+noexcept
+{
+    return( abs(x) >= 9223372036854775808.l ? \
+            // if
+                x : \
+            // else
+                floor_int(x, ((long double)static_cast<ullint_t>(abs(x))) * sgn(x)) );
+}
+
+template<typename T>
+constexpr
+T
+floor_check(const T x)
+noexcept
+{
+    return( // NaN check
+            is_nan(x) ? \
+                GCLIM<T>::quiet_NaN() :
+            // +/- infinite
+            !is_finite(x) ? \
+                x :
+            // signed-zero cases
+            GCLIM<T>::min() > abs(x) ? \
+                x :
+            // else
+                floor_check_internal(x) );
+}
+
+}
+
+/**
+ * Compile-time floor function
+ *
+ * @param x a real-valued input.
+ * @return computes the floor-value of the input.
+ */
+
+template<typename T>
+constexpr
+return_t<T>
+floor(const T x)
+noexcept
+{
+    return internal::floor_check( static_cast<return_t<T>>(x) );
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/fmod.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/fmod.hpp
new file mode 100644
index 0000000..c804ce6
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/fmod.hpp
@@ -0,0 +1,70 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+#ifndef _gcem_fmod_HPP
+#define _gcem_fmod_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr
+T
+fmod_check(const T x, const T y)
+noexcept
+{
+    return( // NaN check
+            any_nan(x, y) ? \
+                GCLIM<T>::quiet_NaN() :
+            // +/- infinite
+            !all_finite(x, y) ? \
+                GCLIM<T>::quiet_NaN() :
+            // else
+                x - trunc(x/y)*y );
+}
+
+template<typename T1, typename T2, typename TC = common_return_t<T1,T2>>
+constexpr
+TC
+fmod_type_check(const T1 x, const T2 y)
+noexcept
+{
+    return fmod_check(static_cast<TC>(x),static_cast<TC>(y));
+}
+
+}
+
+/**
+ * Compile-time remainder of division function
+ * @param x a real-valued input.
+ * @param y a real-valued input.
+ * @return computes the floating-point remainder of \f$ x / y \f$ (rounded towards zero) using \f[ \text{fmod}(x,y) = x - \text{trunc}(x/y) \times y \f] 
+ */
+
+template<typename T1, typename T2>
+constexpr
+common_return_t<T1,T2>
+fmod(const T1 x, const T2 y)
+noexcept
+{
+    return internal::fmod_type_check(x,y);
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/gcd.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/gcd.hpp
new file mode 100644
index 0000000..4a10bbe
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/gcd.hpp
@@ -0,0 +1,82 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+#ifndef _gcem_gcd_HPP
+#define _gcem_gcd_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr
+T
+gcd_recur(const T a, const T b)
+noexcept
+{
+    return( b == T(0) ? a : gcd_recur(b, a % b) );
+}
+
+template<typename T, typename std::enable_if<std::is_integral<T>::value>::type* = nullptr>
+constexpr
+T
+gcd_int_check(const T a, const T b)
+noexcept
+{
+    return gcd_recur(a,b);
+}
+
+template<typename T, typename std::enable_if<!std::is_integral<T>::value>::type* = nullptr>
+constexpr
+T
+gcd_int_check(const T a, const T b)
+noexcept
+{
+    return gcd_recur( static_cast<ullint_t>(a), static_cast<ullint_t>(b) );
+}
+
+template<typename T1, typename T2, typename TC = common_t<T1,T2>>
+constexpr
+TC
+gcd_type_check(const T1 a, const T2 b)
+noexcept
+{
+    return gcd_int_check( static_cast<TC>(abs(a)), static_cast<TC>(abs(b)) );
+}
+
+}
+
+/**
+ * Compile-time greatest common divisor (GCD) function
+ *
+ * @param a integral-valued input.
+ * @param b integral-valued input.
+ * @return the greatest common divisor between integers \c a and \c b using a Euclidean algorithm.
+ */
+
+template<typename T1, typename T2>
+constexpr
+common_t<T1,T2>
+gcd(const T1 a, const T2 b)
+noexcept
+{
+    return internal::gcd_type_check(a,b);
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/gcem_options.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/gcem_options.hpp
new file mode 100644
index 0000000..cd2747c
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/gcem_options.hpp
@@ -0,0 +1,213 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+#include <cstddef>      // size_t
+#include <limits>
+#include <type_traits>
+
+// undef some functions from math.h
+// see issue #29
+
+#ifdef abs
+    #undef abs
+#endif
+
+#ifdef min
+    #undef min
+#endif
+
+#ifdef max
+    #undef max
+#endif
+
+#ifdef round
+    #undef round
+#endif
+
+#ifdef signbit
+    #undef signbit
+#endif
+
+//
+// version
+
+#ifndef GCEM_VERSION_MAJOR
+    #define GCEM_VERSION_MAJOR 1
+#endif
+
+#ifndef GCEM_VERSION_MINOR
+    #define GCEM_VERSION_MINOR 16
+#endif
+
+#ifndef GCEM_VERSION_PATCH
+    #define GCEM_VERSION_PATCH 0
+#endif
+
+//
+// types
+
+namespace gcem
+{
+    using uint_t = unsigned int;
+    using ullint_t = unsigned long long int;
+
+    using llint_t = long long int;
+
+    template<class T>
+    using GCLIM = std::numeric_limits<T>;
+
+    template<typename T>
+    using return_t = typename std::conditional<std::is_integral<T>::value,double,T>::type;
+
+    template<typename ...T>
+    using common_t = typename std::common_type<T...>::type;
+
+    template<typename ...T>
+    using common_return_t = return_t<common_t<T...>>;
+}
+
+//
+// constants
+
+#ifndef GCEM_LOG_2
+    #define GCEM_LOG_2 0.6931471805599453094172321214581765680755L
+#endif
+
+#ifndef GCEM_LOG_10
+    #define GCEM_LOG_10 2.3025850929940456840179914546843642076011L
+#endif
+
+#ifndef GCEM_PI
+    #define GCEM_PI 3.1415926535897932384626433832795028841972L
+#endif
+
+#ifndef GCEM_LOG_PI
+    #define GCEM_LOG_PI 1.1447298858494001741434273513530587116473L
+#endif
+
+#ifndef GCEM_LOG_2PI
+    #define GCEM_LOG_2PI 1.8378770664093454835606594728112352797228L
+#endif
+
+#ifndef GCEM_LOG_SQRT_2PI
+    #define GCEM_LOG_SQRT_2PI 0.9189385332046727417803297364056176398614L
+#endif
+
+#ifndef GCEM_SQRT_2
+    #define GCEM_SQRT_2 1.4142135623730950488016887242096980785697L
+#endif
+
+#ifndef GCEM_HALF_PI
+    #define GCEM_HALF_PI 1.5707963267948966192313216916397514420986L
+#endif
+
+#ifndef GCEM_SQRT_PI
+    #define GCEM_SQRT_PI 1.7724538509055160272981674833411451827975L
+#endif
+
+#ifndef GCEM_SQRT_HALF_PI
+    #define GCEM_SQRT_HALF_PI 1.2533141373155002512078826424055226265035L
+#endif
+
+#ifndef GCEM_E
+    #define GCEM_E 2.7182818284590452353602874713526624977572L
+#endif
+
+//
+// convergence settings
+
+#ifndef GCEM_ERF_MAX_ITER
+    #define GCEM_ERF_MAX_ITER 60
+#endif
+
+#ifndef GCEM_ERF_INV_MAX_ITER
+    #define GCEM_ERF_INV_MAX_ITER 60
+#endif
+
+#ifndef GCEM_EXP_MAX_ITER_SMALL
+    #define GCEM_EXP_MAX_ITER_SMALL 25
+#endif
+
+// #ifndef GCEM_LOG_TOL
+//     #define GCEM_LOG_TOL 1E-14
+// #endif
+
+#ifndef GCEM_LOG_MAX_ITER_SMALL
+    #define GCEM_LOG_MAX_ITER_SMALL 25
+#endif
+
+#ifndef GCEM_LOG_MAX_ITER_BIG
+    #define GCEM_LOG_MAX_ITER_BIG 255
+#endif
+
+#ifndef GCEM_INCML_BETA_TOL
+    #define GCEM_INCML_BETA_TOL 1E-15
+#endif
+
+#ifndef GCEM_INCML_BETA_MAX_ITER
+    #define GCEM_INCML_BETA_MAX_ITER 205
+#endif
+
+#ifndef GCEM_INCML_BETA_INV_MAX_ITER
+    #define GCEM_INCML_BETA_INV_MAX_ITER 35
+#endif
+
+#ifndef GCEM_INCML_GAMMA_MAX_ITER
+    #define GCEM_INCML_GAMMA_MAX_ITER 55
+#endif
+
+#ifndef GCEM_INCML_GAMMA_INV_MAX_ITER
+    #define GCEM_INCML_GAMMA_INV_MAX_ITER 35
+#endif
+
+#ifndef GCEM_SQRT_MAX_ITER
+    #define GCEM_SQRT_MAX_ITER 100
+#endif
+
+#ifndef GCEM_INV_SQRT_MAX_ITER
+    #define GCEM_INV_SQRT_MAX_ITER 100
+#endif
+
+#ifndef GCEM_TAN_MAX_ITER
+    #define GCEM_TAN_MAX_ITER 35
+#endif
+
+#ifndef GCEM_TANH_MAX_ITER
+    #define GCEM_TANH_MAX_ITER 35
+#endif
+
+//
+// Macros
+
+#ifdef _MSC_VER
+    #ifndef GCEM_SIGNBIT
+        #define GCEM_SIGNBIT(x) _signbit(x)
+    #endif
+    #ifndef GCEM_COPYSIGN
+        #define GCEM_COPYSIGN(x,y) _copysign(x,y)
+    #endif
+#else
+    #ifndef GCEM_SIGNBIT
+        #define GCEM_SIGNBIT(x) __builtin_signbit(x)
+    #endif
+    #ifndef GCEM_COPYSIGN
+        #define GCEM_COPYSIGN(x,y) __builtin_copysign(x,y)
+    #endif  
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/hypot.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/hypot.hpp
new file mode 100644
index 0000000..5a805ed
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/hypot.hpp
@@ -0,0 +1,90 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * compile-time Pythagorean addition function
+ */
+
+// see: https://en.wikipedia.org/wiki/Pythagorean_addition
+
+#ifndef _gcem_hypot_HPP
+#define _gcem_hypot_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr
+T
+hypot_compute(const T x, const T ydx)
+noexcept
+{
+    return abs(x) * sqrt( T(1) + (ydx * ydx) );
+}
+
+template<typename T>
+constexpr
+T
+hypot_vals_check(const T x, const T y)
+noexcept
+{
+    return( any_nan(x, y) ? \
+                GCLIM<T>::quiet_NaN() :
+            //
+            any_inf(x,y) ? \
+                GCLIM<T>::infinity() :
+            // indistinguishable from zero or one
+            GCLIM<T>::min() > abs(x) ? \
+                abs(y) :
+            GCLIM<T>::min() > abs(y) ? \
+                abs(x) :
+            // else
+            hypot_compute(x, y/x) );
+}
+
+template<typename T1, typename T2, typename TC = common_return_t<T1,T2>>
+constexpr
+TC
+hypot_type_check(const T1 x, const T2 y)
+noexcept
+{
+    return hypot_vals_check(static_cast<TC>(x),static_cast<TC>(y));
+}
+
+}
+
+/**
+ * Compile-time Pythagorean addition function
+ *
+ * @param x a real-valued input.
+ * @param y a real-valued input.
+ * @return Computes \f$ x \oplus y = \sqrt{x^2 + y^2} \f$.
+ */
+
+template<typename T1, typename T2>
+constexpr
+common_return_t<T1,T2>
+hypot(const T1 x, const T2 y)
+noexcept
+{
+    return internal::hypot_type_check(x,y);
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/incomplete_beta.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/incomplete_beta.hpp
new file mode 100644
index 0000000..5645dbe
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/incomplete_beta.hpp
@@ -0,0 +1,194 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * compile-time incomplete beta function
+ *
+ * see eq. 18.5.17a in the Handbook of Continued Fractions for Special Functions
+ */
+
+#ifndef _gcem_incomplete_beta_HPP
+#define _gcem_incomplete_beta_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr T incomplete_beta_cf(const T a, const T b, const T z, const T c_j, const T d_j, const T f_j, const int depth) noexcept;
+
+//
+// coefficients; see eq. 18.5.17b
+
+template<typename T>
+constexpr
+T
+incomplete_beta_coef_even(const T a, const T b, const T z, const int k)
+noexcept
+{
+    return( -z*(a + k)*(a + b + k)/( (a + 2*k)*(a + 2*k + T(1)) ) );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_beta_coef_odd(const T a, const T b, const T z, const int k)
+noexcept
+{
+    return( z*k*(b - k)/((a + 2*k - T(1))*(a + 2*k)) );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_beta_coef(const T a, const T b, const T z, const int depth)
+noexcept
+{
+    return( !is_odd(depth) ? incomplete_beta_coef_even(a,b,z,depth/2) :
+                             incomplete_beta_coef_odd(a,b,z,(depth+1)/2) );
+}
+
+//
+// update formulae for the modified Lentz method
+
+template<typename T>
+constexpr
+T
+incomplete_beta_c_update(const T a, const T b, const T z, const T c_j, const int depth)
+noexcept
+{
+    return( T(1) + incomplete_beta_coef(a,b,z,depth)/c_j );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_beta_d_update(const T a, const T b, const T z, const T d_j, const int depth)
+noexcept
+{
+    return( T(1) / (T(1) + incomplete_beta_coef(a,b,z,depth)*d_j) );
+}
+
+//
+// convergence-type condition
+
+template<typename T>
+constexpr
+T
+incomplete_beta_decision(const T a, const T b, const T z, const T c_j, const T d_j, const T f_j, const int depth)
+noexcept
+{
+    return( // tolerance check
+                abs(c_j*d_j - T(1)) < GCEM_INCML_BETA_TOL ? f_j*c_j*d_j :
+            // max_iter check
+                depth < GCEM_INCML_BETA_MAX_ITER ? \
+                    // if
+                        incomplete_beta_cf(a,b,z,c_j,d_j,f_j*c_j*d_j,depth+1) :
+                    // else 
+                        f_j*c_j*d_j );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_beta_cf(const T a, const T b, const T z, const T c_j, const T d_j, const T f_j, const int depth)
+noexcept
+{
+    return  incomplete_beta_decision(a,b,z,
+                incomplete_beta_c_update(a,b,z,c_j,depth),
+                incomplete_beta_d_update(a,b,z,d_j,depth),
+                f_j,depth);
+}
+
+//
+// x^a (1-x)^{b} / (a beta(a,b)) * cf
+
+template<typename T>
+constexpr
+T
+incomplete_beta_begin(const T a, const T b, const T z)
+noexcept
+{
+    return  ( (exp(a*log(z) + b*log(T(1)-z) - lbeta(a,b)) / a) * \
+                incomplete_beta_cf(a,b,z,T(1), 
+                    incomplete_beta_d_update(a,b,z,T(1),0),
+                    incomplete_beta_d_update(a,b,z,T(1),0),1)
+            );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_beta_check(const T a, const T b, const T z)
+noexcept
+{
+    return( // NaN check
+            any_nan(a, b, z) ? \
+                GCLIM<T>::quiet_NaN() :
+            // indistinguishable from zero
+            GCLIM<T>::min() > z ? \
+                T(0) :
+            // parameter check for performance
+            (a + T(1))/(a + b + T(2)) > z ? \
+                incomplete_beta_begin(a,b,z) :
+                T(1) - incomplete_beta_begin(b,a,T(1) - z) );
+}
+
+template<typename T1, typename T2, typename T3, typename TC = common_return_t<T1,T2,T3>>
+constexpr
+TC
+incomplete_beta_type_check(const T1 a, const T2 b, const T3 p)
+noexcept
+{
+    return incomplete_beta_check(static_cast<TC>(a),
+                                 static_cast<TC>(b),
+                                 static_cast<TC>(p));
+}
+
+}
+
+/**
+ * Compile-time regularized incomplete beta function
+ *
+ * @param a a real-valued, non-negative input.
+ * @param b a real-valued, non-negative input.
+ * @param z a real-valued, non-negative input.
+ *
+ * @return computes the regularized incomplete beta function,
+ * \f[ \frac{\text{B}(z;\alpha,\beta)}{\text{B}(\alpha,\beta)} = \frac{1}{\text{B}(\alpha,\beta)}\int_0^z t^{a-1} (1-t)^{\beta-1} dt \f]
+ * using a continued fraction representation, found in the Handbook of Continued Fractions for Special Functions, and a modified Lentz method.
+ * \f[ \frac{\text{B}(z;\alpha,\beta)}{\text{B}(\alpha,\beta)} = \frac{z^{\alpha} (1-t)^{\beta}}{\alpha \text{B}(\alpha,\beta)} \dfrac{a_1}{1 + \dfrac{a_2}{1 + \dfrac{a_3}{1 + \dfrac{a_4}{1 + \ddots}}}} \f]
+ * where \f$ a_1 = 1 \f$ and
+ * \f[ a_{2m+2} = - \frac{(\alpha + m)(\alpha + \beta + m)}{(\alpha + 2m)(\alpha + 2m + 1)}, \ m \geq 0 \f]
+ * \f[ a_{2m+1} = \frac{m(\beta - m)}{(\alpha + 2m - 1)(\alpha + 2m)}, \ m \geq 1 \f]
+ * The Lentz method works as follows: let \f$ f_j \f$ denote the value of the continued fraction up to the first \f$ j \f$ terms; \f$ f_j \f$ is updated as follows:
+ * \f[ c_j = 1 + a_j / c_{j-1}, \ \ d_j = 1 / (1 + a_j d_{j-1}) \f]
+ * \f[ f_j = c_j d_j f_{j-1} \f]
+ */
+
+template<typename T1, typename T2, typename T3>
+constexpr
+common_return_t<T1,T2,T3>
+incomplete_beta(const T1 a, const T2 b, const T3 z)
+noexcept
+{
+    return internal::incomplete_beta_type_check(a,b,z);
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/incomplete_beta_inv.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/incomplete_beta_inv.hpp
new file mode 100644
index 0000000..f7fdfa0
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/incomplete_beta_inv.hpp
@@ -0,0 +1,352 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * inverse of the incomplete beta function
+ */
+
+#ifndef _gcem_incomplete_beta_inv_HPP
+#define _gcem_incomplete_beta_inv_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr T incomplete_beta_inv_decision(const T value, const T alpha_par, const T beta_par, const T p,
+                                         const T direc, const T lb_val, const int iter_count) noexcept;
+
+//
+// initial value for Halley
+
+//
+// a,b > 1 case
+
+template<typename T>
+constexpr
+T
+incomplete_beta_inv_initial_val_1_tval(const T p)
+noexcept
+{   // a > 1.0
+    return( p > T(0.5) ? \
+            // if
+                sqrt(-T(2)*log(T(1) - p)) :
+            // else
+                sqrt(-T(2)*log(p)) );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_beta_inv_initial_val_1_int_begin(const T t_val)
+noexcept
+{   // internal for a > 1.0
+    return( t_val - ( T(2.515517) + T(0.802853)*t_val + T(0.010328)*t_val*t_val ) \
+                / ( T(1) + T(1.432788)*t_val + T(0.189269)*t_val*t_val + T(0.001308)*t_val*t_val*t_val ) );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_beta_inv_initial_val_1_int_ab1(const T alpha_par, const T beta_par)
+noexcept
+{
+    return( T(1)/(2*alpha_par - T(1)) + T(1)/(2*beta_par - T(1)) );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_beta_inv_initial_val_1_int_ab2(const T alpha_par, const T beta_par)
+noexcept
+{
+    return( T(1)/(2*beta_par - T(1)) - T(1)/(2*alpha_par - T(1)) );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_beta_inv_initial_val_1_int_h(const T ab_term_1)
+noexcept
+{
+    return( T(2) / ab_term_1 );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_beta_inv_initial_val_1_int_w(const T value, const T ab_term_2, const T h_term)
+noexcept
+{
+    // return( value * sqrt(h_term + lambda)/h_term - ab_term_2*(lambda + 5.0/6.0 -2.0/(3.0*h_term)) );
+    return( value * sqrt(h_term + (value*value - T(3))/T(6))/h_term \
+                - ab_term_2*((value*value - T(3))/T(6) + T(5)/T(6) - T(2)/(T(3)*h_term)) );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_beta_inv_initial_val_1_int_end(const T alpha_par, const T beta_par, const T w_term)
+noexcept
+{
+    return( alpha_par / (alpha_par + beta_par*exp(2*w_term)) );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_beta_inv_initial_val_1(const T alpha_par, const T beta_par, const T t_val, const T sgn_term)
+noexcept
+{   // a > 1.0
+    return  incomplete_beta_inv_initial_val_1_int_end( alpha_par, beta_par,
+                incomplete_beta_inv_initial_val_1_int_w(
+                    sgn_term*incomplete_beta_inv_initial_val_1_int_begin(t_val),
+                    incomplete_beta_inv_initial_val_1_int_ab2(alpha_par,beta_par),
+                    incomplete_beta_inv_initial_val_1_int_h(
+                        incomplete_beta_inv_initial_val_1_int_ab1(alpha_par,beta_par)
+                    )
+                )
+            );
+}
+
+//
+// a,b else
+
+template<typename T>
+constexpr
+T
+incomplete_beta_inv_initial_val_2_s1(const T alpha_par, const T beta_par)
+noexcept
+{
+    return( pow(alpha_par/(alpha_par+beta_par),alpha_par) / alpha_par );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_beta_inv_initial_val_2_s2(const T alpha_par, const T beta_par)
+noexcept
+{
+    return( pow(beta_par/(alpha_par+beta_par),beta_par) / beta_par );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_beta_inv_initial_val_2(const T alpha_par, const T beta_par, const T p, const T s_1, const T s_2)
+noexcept
+{
+    return( p <= s_1/(s_1 + s_2) ? pow(p*(s_1+s_2)*alpha_par,T(1)/alpha_par) :
+                                    T(1) - pow(p*(s_1+s_2)*beta_par,T(1)/beta_par) );
+}
+
+// initial value
+
+template<typename T>
+constexpr
+T
+incomplete_beta_inv_initial_val(const T alpha_par, const T beta_par, const T p)
+noexcept
+{
+    return( (alpha_par > T(1) && beta_par > T(1)) ?
+            // if
+                incomplete_beta_inv_initial_val_1(alpha_par,beta_par,
+                    incomplete_beta_inv_initial_val_1_tval(p),
+                    p < T(0.5) ? T(1) : T(-1) ) :
+            // else
+                p > T(0.5) ?
+                    // if
+                       T(1) - incomplete_beta_inv_initial_val_2(beta_par,alpha_par,T(1) - p,
+                                    incomplete_beta_inv_initial_val_2_s1(beta_par,alpha_par),
+                                    incomplete_beta_inv_initial_val_2_s2(beta_par,alpha_par)) :
+                    // else
+                       incomplete_beta_inv_initial_val_2(alpha_par,beta_par,p,
+                            incomplete_beta_inv_initial_val_2_s1(alpha_par,beta_par),
+                            incomplete_beta_inv_initial_val_2_s2(alpha_par,beta_par))
+            );
+}
+
+//
+// Halley recursion
+
+template<typename T>
+constexpr
+T
+incomplete_beta_inv_err_val(const T value, const T alpha_par, const T beta_par, const T p)
+noexcept
+{   // err_val = f(x)
+    return( incomplete_beta(alpha_par,beta_par,value) - p );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_beta_inv_deriv_1(const T value, const T alpha_par, const T beta_par, const T lb_val)
+noexcept
+{   // derivative of the incomplete beta function w.r.t. x
+    return( // indistinguishable from zero or one
+            GCLIM<T>::min() > abs(value) ? \
+                T(0) :
+            GCLIM<T>::min() > abs(T(1) - value) ? \
+                T(0) :
+            // else
+                exp( (alpha_par - T(1))*log(value) + (beta_par - T(1))*log(T(1) - value) - lb_val ) );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_beta_inv_deriv_2(const T value, const T alpha_par, const T beta_par, const T deriv_1)
+noexcept
+{ // second derivative of the incomplete beta function w.r.t. x
+    return( deriv_1*((alpha_par - T(1))/value - (beta_par - T(1))/(T(1) - value)) );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_beta_inv_ratio_val_1(const T value, const T alpha_par, const T beta_par, const T p, const T deriv_1)
+noexcept
+{
+    return( incomplete_beta_inv_err_val(value,alpha_par,beta_par,p) / deriv_1 );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_beta_inv_ratio_val_2(const T value, const T alpha_par, const T beta_par, const T deriv_1)
+noexcept
+{
+    return( incomplete_beta_inv_deriv_2(value,alpha_par,beta_par,deriv_1) / deriv_1 );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_beta_inv_halley(const T ratio_val_1, const T ratio_val_2)
+noexcept
+{
+    return( ratio_val_1 / max( T(0.8), min( T(1.2), T(1) - T(0.5)*ratio_val_1*ratio_val_2 ) ) );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_beta_inv_recur(const T value, const T alpha_par, const T beta_par, const T p, const T deriv_1,
+                          const T lb_val, const int iter_count)
+noexcept
+{
+    return( // derivative = 0
+            GCLIM<T>::min() > abs(deriv_1) ? \
+                incomplete_beta_inv_decision( value, alpha_par, beta_par, p, T(0), lb_val,
+                    GCEM_INCML_BETA_INV_MAX_ITER+1) :
+            // else
+            incomplete_beta_inv_decision( value, alpha_par, beta_par, p,
+               incomplete_beta_inv_halley(
+                   incomplete_beta_inv_ratio_val_1(value,alpha_par,beta_par,p,deriv_1),
+                   incomplete_beta_inv_ratio_val_2(value,alpha_par,beta_par,deriv_1)
+               ), lb_val, iter_count) );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_beta_inv_decision(const T value, const T alpha_par, const T beta_par, const T p, const T direc,
+                             const T lb_val, const int iter_count)
+noexcept
+{
+    return( iter_count <= GCEM_INCML_BETA_INV_MAX_ITER ?
+            // if
+                incomplete_beta_inv_recur(value-direc,alpha_par,beta_par,p,
+                    incomplete_beta_inv_deriv_1(value,alpha_par,beta_par,lb_val),
+                    lb_val, iter_count+1) :
+            // else
+                value - direc );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_beta_inv_begin(const T initial_val, const T alpha_par, const T beta_par, const T p, const T lb_val)
+noexcept
+{
+    return incomplete_beta_inv_recur(initial_val,alpha_par,beta_par,p,
+               incomplete_beta_inv_deriv_1(initial_val,alpha_par,beta_par,lb_val),
+               lb_val,1);
+}
+
+template<typename T>
+constexpr
+T
+incomplete_beta_inv_check(const T alpha_par, const T beta_par, const T p)
+noexcept
+{
+    return( // NaN check
+            any_nan(alpha_par, beta_par, p) ? \
+                GCLIM<T>::quiet_NaN() :
+            // indistinguishable from zero or one
+            GCLIM<T>::min() > p ? \
+                T(0) :
+            GCLIM<T>::min() > abs(T(1) - p) ? \
+                T(1) :
+            // else
+                incomplete_beta_inv_begin(incomplete_beta_inv_initial_val(alpha_par,beta_par,p),
+                    alpha_par,beta_par,p,lbeta(alpha_par,beta_par)) );
+}
+
+template<typename T1, typename T2, typename T3, typename TC = common_t<T1,T2,T3>>
+constexpr
+TC
+incomplete_beta_inv_type_check(const T1 a, const T2 b, const T3 p)
+noexcept
+{
+    return incomplete_beta_inv_check(static_cast<TC>(a),
+                                     static_cast<TC>(b),
+                                     static_cast<TC>(p));
+}
+
+}
+
+/**
+ * Compile-time inverse incomplete beta function
+ *
+ * @param a a real-valued, non-negative input.
+ * @param b a real-valued, non-negative input.
+ * @param p a real-valued input with values in the unit-interval.
+ *
+ * @return Computes the inverse incomplete beta function, a value \f$ x \f$ such that 
+ * \f[ f(x) := \frac{\text{B}(x;\alpha,\beta)}{\text{B}(\alpha,\beta)} - p \f]
+ * equal to zero, for a given \c p.
+ * GCE-Math finds this root using Halley's method:
+ * \f[ x_{n+1} = x_n - \frac{f(x_n)/f'(x_n)}{1 - 0.5 \frac{f(x_n)}{f'(x_n)} \frac{f''(x_n)}{f'(x_n)} } \f]
+ * where
+ * \f[ \frac{\partial}{\partial x} \left(\frac{\text{B}(x;\alpha,\beta)}{\text{B}(\alpha,\beta)}\right) = \frac{1}{\text{B}(\alpha,\beta)} x^{\alpha-1} (1-x)^{\beta-1} \f]
+ * \f[ \frac{\partial^2}{\partial x^2} \left(\frac{\text{B}(x;\alpha,\beta)}{\text{B}(\alpha,\beta)}\right) = \frac{1}{\text{B}(\alpha,\beta)} x^{\alpha-1} (1-x)^{\beta-1} \left( \frac{\alpha-1}{x} - \frac{\beta-1}{1 - x} \right) \f]
+ */
+
+template<typename T1, typename T2, typename T3>
+constexpr
+common_t<T1,T2,T3>
+incomplete_beta_inv(const T1 a, const T2 b, const T3 p)
+noexcept
+{
+    return internal::incomplete_beta_inv_type_check(a,b,p);
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/incomplete_gamma.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/incomplete_gamma.hpp
new file mode 100644
index 0000000..38734a5
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/incomplete_gamma.hpp
@@ -0,0 +1,247 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/* 
+ * compile-time (regularized) incomplete gamma function
+ */
+
+#ifndef _gcem_incomplete_gamma_HPP
+#define _gcem_incomplete_gamma_HPP
+
+namespace internal
+{
+
+// 50 point Gauss-Legendre quadrature
+
+template<typename T>
+constexpr
+T
+incomplete_gamma_quad_inp_vals(const T lb, const T ub, const int counter)
+noexcept
+{
+    return (ub-lb) * gauss_legendre_50_points[counter] / T(2) + (ub + lb) / T(2);
+}
+
+template<typename T>
+constexpr
+T
+incomplete_gamma_quad_weight_vals(const T lb, const T ub, const int counter)
+noexcept
+{
+    return (ub-lb) * gauss_legendre_50_weights[counter] / T(2);
+}
+
+template<typename T>
+constexpr
+T
+incomplete_gamma_quad_fn(const T x, const T a, const T lg_term)
+noexcept
+{
+    return exp( -x + (a-T(1))*log(x) - lg_term );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_gamma_quad_recur(const T lb, const T ub, const T a, const T lg_term, const int counter)
+noexcept
+{
+    return( counter < 49 ? \
+            // if 
+                incomplete_gamma_quad_fn(incomplete_gamma_quad_inp_vals(lb,ub,counter),a,lg_term) \
+                    * incomplete_gamma_quad_weight_vals(lb,ub,counter) \
+                    + incomplete_gamma_quad_recur(lb,ub,a,lg_term,counter+1) :
+            // else
+                incomplete_gamma_quad_fn(incomplete_gamma_quad_inp_vals(lb,ub,counter),a,lg_term) \
+                    * incomplete_gamma_quad_weight_vals(lb,ub,counter) );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_gamma_quad_lb(const T a, const T z)
+noexcept
+{
+    return( a > T(1000) ? max(T(0),min(z,a) - 11*sqrt(a)) : // break integration into ranges
+            a > T(800)  ? max(T(0),min(z,a) - 11*sqrt(a)) :
+            a > T(500)  ? max(T(0),min(z,a) - 10*sqrt(a)) :
+            a > T(300)  ? max(T(0),min(z,a) - 10*sqrt(a)) : 
+            a > T(100)  ? max(T(0),min(z,a) -  9*sqrt(a)) :
+            a > T(90)   ? max(T(0),min(z,a) -  9*sqrt(a)) :
+            a > T(70)   ? max(T(0),min(z,a) -  8*sqrt(a)) :
+            a > T(50)   ? max(T(0),min(z,a) -  7*sqrt(a)) :
+            a > T(40)   ? max(T(0),min(z,a) -  6*sqrt(a)) :
+            a > T(30)   ? max(T(0),min(z,a) -  5*sqrt(a)) :
+            // else
+                max(T(0),min(z,a)-4*sqrt(a)) );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_gamma_quad_ub(const T a, const T z)
+noexcept
+{
+    return( a > T(1000) ? min(z, a + 10*sqrt(a)) :
+            a > T(800)  ? min(z, a + 10*sqrt(a)) :
+            a > T(500)  ? min(z, a + 9*sqrt(a))  :
+            a > T(300)  ? min(z, a + 9*sqrt(a))  : 
+            a > T(100)  ? min(z, a + 8*sqrt(a))  :
+            a > T(90)   ? min(z, a + 8*sqrt(a))  :
+            a > T(70)   ? min(z, a + 7*sqrt(a))  :
+            a > T(50)   ? min(z, a + 6*sqrt(a))  :
+            // else
+                min(z, a + 5*sqrt(a)) );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_gamma_quad(const T a, const T z)
+noexcept
+{
+    return incomplete_gamma_quad_recur(incomplete_gamma_quad_lb(a,z), incomplete_gamma_quad_ub(a,z), a,lgamma(a),0);
+}
+
+// reverse cf expansion
+// see: https://functions.wolfram.com/GammaBetaErf/Gamma2/10/0003/
+
+template<typename T>
+constexpr
+T
+incomplete_gamma_cf_2_recur(const T a, const T z, const int depth)
+noexcept
+{
+    return( depth < 100 ? \
+            // if
+                (1 + (depth-1)*2 - a + z) + depth*(a - depth)/incomplete_gamma_cf_2_recur(a,z,depth+1) :
+            // else
+                (1 + (depth-1)*2 - a + z) );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_gamma_cf_2(const T a, const T z)
+noexcept
+{   // lower (regularized) incomplete gamma function
+    return( T(1.0) - exp(a*log(z) - z - lgamma(a)) / incomplete_gamma_cf_2_recur(a,z,1) );
+}
+
+// cf expansion
+// see: http://functions.wolfram.com/GammaBetaErf/Gamma2/10/0009/
+
+template<typename T>
+constexpr
+T
+incomplete_gamma_cf_1_coef(const T a, const T z, const int depth)
+noexcept
+{
+    return( is_odd(depth) ? - (a - 1 + T(depth+1)/T(2)) * z : T(depth)/T(2) * z );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_gamma_cf_1_recur(const T a, const T z, const int depth)
+noexcept
+{
+    return( depth < GCEM_INCML_GAMMA_MAX_ITER ? \
+            // if
+                (a + depth - 1) + incomplete_gamma_cf_1_coef(a,z,depth)/incomplete_gamma_cf_1_recur(a,z,depth+1) :
+            // else
+                (a + depth - 1) );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_gamma_cf_1(const T a, const T z)
+noexcept
+{   // lower (regularized) incomplete gamma function
+    return( exp(a*log(z) - z - lgamma(a)) / incomplete_gamma_cf_1_recur(a,z,1) );
+}
+
+//
+
+template<typename T>
+constexpr
+T
+incomplete_gamma_check(const T a, const T z)
+noexcept
+{
+    return( // NaN check
+            any_nan(a, z) ? \
+                GCLIM<T>::quiet_NaN() :
+            //
+            a < T(0) ? \
+                GCLIM<T>::quiet_NaN() :
+            //
+            GCLIM<T>::min() > z ? \
+                T(0) : 
+            //
+            GCLIM<T>::min() > a ? \
+                T(1) : 
+            // cf or quadrature
+            (a < T(10)) && (z - a < T(10)) ?
+                incomplete_gamma_cf_1(a,z) :
+            (a < T(10)) || (z/a > T(3)) ?
+                incomplete_gamma_cf_2(a,z) :
+            // else
+                incomplete_gamma_quad(a,z) );
+}
+
+template<typename T1, typename T2, typename TC = common_return_t<T1,T2>>
+constexpr
+TC
+incomplete_gamma_type_check(const T1 a, const T2 p)
+noexcept
+{
+    return incomplete_gamma_check(static_cast<TC>(a),
+                                  static_cast<TC>(p));
+}
+
+}
+
+/**
+ * Compile-time regularized lower incomplete gamma function
+ *
+ * @param a a real-valued, non-negative input.
+ * @param x a real-valued, non-negative input.
+ *
+ * @return the regularized lower incomplete gamma function evaluated at (\c a, \c x),
+ * \f[ \frac{\gamma(a,x)}{\Gamma(a)} = \frac{1}{\Gamma(a)} \int_0^x t^{a-1} \exp(-t) dt \f]
+ * When \c a is not too large, the value is computed using the continued fraction representation of the upper incomplete gamma function, \f$ \Gamma(a,x) \f$, using
+ * \f[ \Gamma(a,x) = \Gamma(a) - \dfrac{x^a\exp(-x)}{a - \dfrac{ax}{a + 1 + \dfrac{x}{a + 2 - \dfrac{(a+1)x}{a + 3 + \dfrac{2x}{a + 4 - \ddots}}}}} \f]
+ * where \f$ \gamma(a,x) \f$ and \f$ \Gamma(a,x) \f$ are connected via
+ * \f[ \frac{\gamma(a,x)}{\Gamma(a)} + \frac{\Gamma(a,x)}{\Gamma(a)} = 1 \f]
+ * When \f$ a > 10 \f$, a 50-point Gauss-Legendre quadrature scheme is employed.
+ */
+
+template<typename T1, typename T2>
+constexpr
+common_return_t<T1,T2>
+incomplete_gamma(const T1 a, const T2 x)
+noexcept
+{
+    return internal::incomplete_gamma_type_check(a,x);
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/incomplete_gamma_inv.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/incomplete_gamma_inv.hpp
new file mode 100644
index 0000000..1e57fc1
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/incomplete_gamma_inv.hpp
@@ -0,0 +1,271 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/* 
+ * inverse of the incomplete gamma function
+ */
+
+#ifndef _gcem_incomplete_gamma_inv_HPP
+#define _gcem_incomplete_gamma_inv_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr T incomplete_gamma_inv_decision(const T value, const T a, const T p, const T direc, const T lg_val, const int iter_count) noexcept;
+
+//
+// initial value for Halley
+
+template<typename T>
+constexpr
+T
+incomplete_gamma_inv_t_val_1(const T p)
+noexcept
+{   // a > 1.0
+    return( p > T(0.5) ? sqrt(-2*log(T(1) - p)) : sqrt(-2*log(p)) );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_gamma_inv_t_val_2(const T a)
+noexcept
+{   // a <= 1.0
+    return( T(1) - T(0.253) * a - T(0.12) * a*a );
+}
+
+//
+
+template<typename T>
+constexpr
+T
+incomplete_gamma_inv_initial_val_1_int_begin(const T t_val)
+noexcept
+{   // internal for a > 1.0
+    return( t_val - (T(2.515517L) + T(0.802853L)*t_val + T(0.010328L)*t_val*t_val) \
+                / (T(1) + T(1.432788L)*t_val + T(0.189269L)*t_val*t_val + T(0.001308L)*t_val*t_val*t_val) );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_gamma_inv_initial_val_1_int_end(const T value_inp, const T a)
+noexcept
+{   // internal for a > 1.0
+    return max( T(1E-04), a*pow(T(1) - T(1)/(9*a) - value_inp/(3*sqrt(a)), 3) );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_gamma_inv_initial_val_1(const T a, const T t_val, const T sgn_term)
+noexcept
+{   // a > 1.0
+    return incomplete_gamma_inv_initial_val_1_int_end(sgn_term*incomplete_gamma_inv_initial_val_1_int_begin(t_val), a);
+}
+
+template<typename T>
+constexpr
+T
+incomplete_gamma_inv_initial_val_2(const T a, const T p, const T t_val)
+noexcept
+{   // a <= 1.0
+    return( p < t_val ? \
+             // if 
+                pow(p/t_val,T(1)/a) : 
+             // else
+                T(1) - log(T(1) - (p - t_val)/(T(1) - t_val)) );
+}
+
+// initial value
+
+template<typename T>
+constexpr
+T
+incomplete_gamma_inv_initial_val(const T a, const T p)
+noexcept
+{
+    return( a > T(1) ? \
+             // if
+                incomplete_gamma_inv_initial_val_1(a,
+                    incomplete_gamma_inv_t_val_1(p),
+                    p > T(0.5) ? T(-1) : T(1)) :
+             // else
+                incomplete_gamma_inv_initial_val_2(a,p,
+                    incomplete_gamma_inv_t_val_2(a)));
+}
+
+//
+// Halley recursion
+
+template<typename T>
+constexpr
+T
+incomplete_gamma_inv_err_val(const T value, const T a, const T p)
+noexcept
+{ // err_val = f(x)
+    return( incomplete_gamma(a,value) - p );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_gamma_inv_deriv_1(const T value, const T a, const T lg_val)
+noexcept
+{ // derivative of the incomplete gamma function w.r.t. x
+    return( exp( - value + (a - T(1))*log(value) - lg_val ) );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_gamma_inv_deriv_2(const T value, const T a, const T deriv_1)
+noexcept
+{ // second derivative of the incomplete gamma function w.r.t. x
+    return( deriv_1*((a - T(1))/value - T(1)) );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_gamma_inv_ratio_val_1(const T value, const T a, const T p, const T deriv_1)
+noexcept
+{
+    return( incomplete_gamma_inv_err_val(value,a,p) / deriv_1 );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_gamma_inv_ratio_val_2(const T value, const T a, const T deriv_1)
+noexcept
+{
+    return( incomplete_gamma_inv_deriv_2(value,a,deriv_1) / deriv_1 );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_gamma_inv_halley(const T ratio_val_1, const T ratio_val_2)
+noexcept
+{
+    return( ratio_val_1 / max( T(0.8), min( T(1.2), T(1) - T(0.5)*ratio_val_1*ratio_val_2 ) ) );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_gamma_inv_recur(const T value, const T a, const T p, const T deriv_1, const T lg_val, const int iter_count)
+noexcept
+{
+    return incomplete_gamma_inv_decision(value, a, p,
+                incomplete_gamma_inv_halley(incomplete_gamma_inv_ratio_val_1(value,a,p,deriv_1), 
+                incomplete_gamma_inv_ratio_val_2(value,a,deriv_1)),
+                lg_val, iter_count);
+}
+
+template<typename T>
+constexpr
+T
+incomplete_gamma_inv_decision(const T value, const T a, const T p, const T direc, const T lg_val, const int iter_count)
+noexcept
+{
+    // return( abs(direc) > GCEM_INCML_GAMMA_INV_TOL ? incomplete_gamma_inv_recur(value - direc, a, p, incomplete_gamma_inv_deriv_1(value,a,lg_val), lg_val) : value - direc );
+    return( iter_count <= GCEM_INCML_GAMMA_INV_MAX_ITER ? \
+            // if
+                incomplete_gamma_inv_recur(value-direc,a,p,
+                    incomplete_gamma_inv_deriv_1(value,a,lg_val),
+                    lg_val,iter_count+1) :
+            // else 
+                value - direc );
+}
+
+template<typename T>
+constexpr
+T
+incomplete_gamma_inv_begin(const T initial_val, const T a, const T p, const T lg_val)
+noexcept
+{
+    return incomplete_gamma_inv_recur(initial_val,a,p,
+                incomplete_gamma_inv_deriv_1(initial_val,a,lg_val), lg_val,1);
+}
+
+template<typename T>
+constexpr
+T
+incomplete_gamma_inv_check(const T a, const T p)
+noexcept
+{
+    return( // NaN check
+            any_nan(a, p) ? \
+                GCLIM<T>::quiet_NaN() :
+            //
+            GCLIM<T>::min() > p ? \
+                T(0) :
+            p > T(1) ? \
+                GCLIM<T>::quiet_NaN() :
+            GCLIM<T>::min() > abs(T(1) - p) ? \
+                GCLIM<T>::infinity() :
+            //
+            GCLIM<T>::min() > a ? \
+                T(0) :
+            // else
+                incomplete_gamma_inv_begin(incomplete_gamma_inv_initial_val(a,p),a,p,lgamma(a)) );
+}
+
+template<typename T1, typename T2, typename TC = common_return_t<T1,T2>>
+constexpr
+TC
+incomplete_gamma_inv_type_check(const T1 a, const T2 p)
+noexcept
+{
+    return incomplete_gamma_inv_check(static_cast<TC>(a),
+                                      static_cast<TC>(p));
+}
+
+}
+
+/**
+ * Compile-time inverse incomplete gamma function
+ *
+ * @param a a real-valued, non-negative input.
+ * @param p a real-valued input with values in the unit-interval.
+ *
+ * @return Computes the inverse incomplete gamma function, a value \f$ x \f$ such that 
+ * \f[ f(x) := \frac{\gamma(a,x)}{\Gamma(a)} - p \f]
+ * equal to zero, for a given \c p.
+ * GCE-Math finds this root using Halley's method:
+ * \f[ x_{n+1} = x_n - \frac{f(x_n)/f'(x_n)}{1 - 0.5 \frac{f(x_n)}{f'(x_n)} \frac{f''(x_n)}{f'(x_n)} } \f]
+ * where
+ * \f[ \frac{\partial}{\partial x} \left(\frac{\gamma(a,x)}{\Gamma(a)}\right) = \frac{1}{\Gamma(a)} x^{a-1} \exp(-x) \f]
+ * \f[ \frac{\partial^2}{\partial x^2} \left(\frac{\gamma(a,x)}{\Gamma(a)}\right) = \frac{1}{\Gamma(a)} x^{a-1} \exp(-x) \left( \frac{a-1}{x} - 1 \right) \f]
+ */
+
+template<typename T1, typename T2>
+constexpr
+common_return_t<T1,T2>
+incomplete_gamma_inv(const T1 a, const T2 p)
+noexcept
+{
+    return internal::incomplete_gamma_inv_type_check(a,p);
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/inv_sqrt.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/inv_sqrt.hpp
new file mode 100644
index 0000000..0200f11
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/inv_sqrt.hpp
@@ -0,0 +1,88 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * compile-time inverse-square-root function
+ */
+
+#ifndef _gcem_inv_sqrt_HPP
+#define _gcem_inv_sqrt_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr
+T
+inv_sqrt_recur(const T x, const T xn, const int count)
+noexcept
+{
+    return( abs( xn - T(1)/(x*xn) ) / (T(1) + xn) < GCLIM<T>::min() ? \
+            // if
+                xn :
+            count < GCEM_INV_SQRT_MAX_ITER ? \
+            // else
+                inv_sqrt_recur(x, T(0.5)*(xn + T(1)/(x*xn)), count+1) :
+                xn );
+}
+
+template<typename T>
+constexpr
+T
+inv_sqrt_check(const T x)
+noexcept
+{
+    return( is_nan(x) ? \
+                GCLIM<T>::quiet_NaN() :
+            //
+            x < T(0) ? \
+                GCLIM<T>::quiet_NaN() :
+            //
+            is_posinf(x) ? \
+                T(0) :
+            // indistinguishable from zero or one
+            GCLIM<T>::min() > abs(x) ? \
+                GCLIM<T>::infinity() :
+            GCLIM<T>::min() > abs(T(1) - x) ? \
+                x :
+            // else
+            inv_sqrt_recur(x, x/T(2), 0) );
+}
+
+}
+
+
+/**
+ * Compile-time inverse-square-root function
+ *
+ * @param x a real-valued input.
+ * @return Computes \f$ 1 / \sqrt{x} \f$ using a Newton-Raphson approach.
+ */
+
+template<typename T>
+constexpr
+return_t<T>
+inv_sqrt(const T x)
+noexcept
+{
+    return internal::inv_sqrt_check( static_cast<return_t<T>>(x) );
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/is_even.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/is_even.hpp
new file mode 100644
index 0000000..fa925bb
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/is_even.hpp
@@ -0,0 +1,41 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * compile-time check if integer is even
+ */
+
+#ifndef _gcem_is_even_HPP
+#define _gcem_is_even_HPP
+
+namespace internal
+{
+
+constexpr
+bool
+is_even(const llint_t x)
+noexcept
+{
+    return !is_odd(x);
+}
+
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/is_finite.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/is_finite.hpp
new file mode 100644
index 0000000..25f2e3c
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/is_finite.hpp
@@ -0,0 +1,78 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * compile-time check if a float is not NaN-valued or +/-Inf
+ */
+
+#ifndef _gcem_is_finite_HPP
+#define _gcem_is_finite_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr
+bool
+is_finite(const T x)
+noexcept
+{
+    return (!is_nan(x)) && (!is_inf(x));
+}
+
+template<typename T1, typename T2>
+constexpr
+bool
+any_finite(const T1 x, const T2 y)
+noexcept
+{
+    return( is_finite(x) || is_finite(y) );
+}
+
+template<typename T1, typename T2>
+constexpr
+bool
+all_finite(const T1 x, const T2 y)
+noexcept
+{
+    return( is_finite(x) && is_finite(y) );
+}
+
+template<typename T1, typename T2, typename T3>
+constexpr
+bool
+any_finite(const T1 x, const T2 y, const T3 z)
+noexcept
+{
+    return( is_finite(x) || is_finite(y) || is_finite(z) );
+}
+
+template<typename T1, typename T2, typename T3>
+constexpr
+bool
+all_finite(const T1 x, const T2 y, const T3 z)
+noexcept
+{
+    return( is_finite(x) && is_finite(y) && is_finite(z) );
+}
+
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/is_inf.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/is_inf.hpp
new file mode 100644
index 0000000..627c509
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/is_inf.hpp
@@ -0,0 +1,172 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * compile-time check if a float is +/-Inf
+ */
+
+#ifndef _gcem_is_inf_HPP
+#define _gcem_is_inf_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr
+bool
+is_neginf(const T x)
+noexcept
+{
+    return x == - GCLIM<T>::infinity();
+}
+
+template<typename T1, typename T2>
+constexpr
+bool
+any_neginf(const T1 x, const T2 y)
+noexcept
+{
+    return( is_neginf(x) || is_neginf(y) );
+}
+
+template<typename T1, typename T2>
+constexpr
+bool
+all_neginf(const T1 x, const T2 y)
+noexcept
+{
+    return( is_neginf(x) && is_neginf(y) );
+}
+
+template<typename T1, typename T2, typename T3>
+constexpr
+bool
+any_neginf(const T1 x, const T2 y, const T3 z)
+noexcept
+{
+    return( is_neginf(x) || is_neginf(y) || is_neginf(z) );
+}
+
+template<typename T1, typename T2, typename T3>
+constexpr
+bool
+all_neginf(const T1 x, const T2 y, const T3 z)
+noexcept
+{
+    return( is_neginf(x) && is_neginf(y) && is_neginf(z) );
+}
+
+//
+
+template<typename T>
+constexpr
+bool
+is_posinf(const T x)
+noexcept
+{
+    return x == GCLIM<T>::infinity();
+}
+
+template<typename T1, typename T2>
+constexpr
+bool
+any_posinf(const T1 x, const T2 y)
+noexcept
+{
+    return( is_posinf(x) || is_posinf(y) );
+}
+
+template<typename T1, typename T2>
+constexpr
+bool
+all_posinf(const T1 x, const T2 y)
+noexcept
+{
+    return( is_posinf(x) && is_posinf(y) );
+}
+
+template<typename T1, typename T2, typename T3>
+constexpr
+bool
+any_posinf(const T1 x, const T2 y, const T3 z)
+noexcept
+{
+    return( is_posinf(x) || is_posinf(y) || is_posinf(z) );
+}
+
+template<typename T1, typename T2, typename T3>
+constexpr
+bool
+all_posinf(const T1 x, const T2 y, const T3 z)
+noexcept
+{
+    return( is_posinf(x) && is_posinf(y) && is_posinf(z) );
+}
+
+//
+
+template<typename T>
+constexpr
+bool
+is_inf(const T x)
+noexcept
+{
+    return( is_neginf(x) || is_posinf(x) );
+}
+
+template<typename T1, typename T2>
+constexpr
+bool
+any_inf(const T1 x, const T2 y)
+noexcept
+{
+    return( is_inf(x) || is_inf(y) );
+}
+
+template<typename T1, typename T2>
+constexpr
+bool
+all_inf(const T1 x, const T2 y)
+noexcept
+{
+    return( is_inf(x) && is_inf(y) );
+}
+
+template<typename T1, typename T2, typename T3>
+constexpr
+bool
+any_inf(const T1 x, const T2 y, const T3 z)
+noexcept
+{
+    return( is_inf(x) || is_inf(y) || is_inf(z) );
+}
+
+template<typename T1, typename T2, typename T3>
+constexpr
+bool
+all_inf(const T1 x, const T2 y, const T3 z)
+noexcept
+{
+    return( is_inf(x) && is_inf(y) && is_inf(z) );
+}
+
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/is_nan.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/is_nan.hpp
new file mode 100644
index 0000000..a7a1af3
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/is_nan.hpp
@@ -0,0 +1,80 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * compile-time check if a float is NaN-valued
+ */
+
+#ifndef _gcem_is_nan_HPP
+#define _gcem_is_nan_HPP
+
+namespace internal
+{
+
+// future: consider using __builtin_isnan(__x)
+
+template<typename T>
+constexpr
+bool
+is_nan(const T x)
+noexcept
+{
+    return x != x;
+}
+
+template<typename T1, typename T2>
+constexpr
+bool
+any_nan(const T1 x, const T2 y)
+noexcept
+{
+    return( is_nan(x) || is_nan(y) );
+}
+
+template<typename T1, typename T2>
+constexpr
+bool
+all_nan(const T1 x, const T2 y)
+noexcept
+{
+    return( is_nan(x) && is_nan(y) );
+}
+
+template<typename T1, typename T2, typename T3>
+constexpr
+bool
+any_nan(const T1 x, const T2 y, const T3 z)
+noexcept
+{
+    return( is_nan(x) || is_nan(y) || is_nan(z) );
+}
+
+template<typename T1, typename T2, typename T3>
+constexpr
+bool
+all_nan(const T1 x, const T2 y, const T3 z)
+noexcept
+{
+    return( is_nan(x) && is_nan(y) && is_nan(z) );
+}
+
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/is_odd.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/is_odd.hpp
new file mode 100644
index 0000000..e6da720
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/is_odd.hpp
@@ -0,0 +1,42 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * compile-time check if integer is odd
+ */
+
+#ifndef _gcem_is_odd_HPP
+#define _gcem_is_odd_HPP
+
+namespace internal
+{
+
+constexpr
+bool
+is_odd(const llint_t x)
+noexcept
+{
+    // return( x % llint_t(2) == llint_t(0) ? false : true );
+    return (x & 1U) != 0;
+}
+
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/lbeta.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/lbeta.hpp
new file mode 100644
index 0000000..2213849
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/lbeta.hpp
@@ -0,0 +1,42 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+#ifndef _gcem_lbeta_HPP
+#define _gcem_lbeta_HPP
+
+/**
+ * Compile-time log-beta function
+ *
+ * @param a a real-valued input.
+ * @param b a real-valued input.
+ * @return the log-beta function using \f[ \ln \text{B}(\alpha,\beta) := \ln \int_0^1 t^{\alpha - 1} (1-t)^{\beta - 1} dt = \ln \Gamma(\alpha) + \ln \Gamma(\beta) - \ln \Gamma(\alpha + \beta) \f]
+ * where \f$ \Gamma \f$ denotes the gamma function.
+ */
+
+template<typename T1, typename T2>
+constexpr
+common_return_t<T1,T2>
+lbeta(const T1 a, const T2 b)
+noexcept
+{
+    return( (lgamma(a) + lgamma(b)) - lgamma(a+b) );
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/lcm.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/lcm.hpp
new file mode 100644
index 0000000..b0d8fb4
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/lcm.hpp
@@ -0,0 +1,65 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+#ifndef _gcem_lcm_HPP
+#define _gcem_lcm_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr
+T
+lcm_compute(const T a, const T b)
+noexcept
+{
+    return abs(a * (b / gcd(a,b)));
+}
+
+template<typename T1, typename T2, typename TC = common_t<T1,T2>>
+constexpr
+TC
+lcm_type_check(const T1 a, const T2 b)
+noexcept
+{
+    return lcm_compute(static_cast<TC>(a),static_cast<TC>(b));
+}
+
+}
+
+/**
+ * Compile-time least common multiple (LCM) function
+ *
+ * @param a integral-valued input.
+ * @param b integral-valued input.
+ * @return the least common multiple between integers \c a and \c b using the representation \f[ \text{lcm}(a,b) = \dfrac{| a b |}{\text{gcd}(a,b)} \f]
+ * where \f$ \text{gcd}(a,b) \f$ denotes the greatest common divisor between \f$ a \f$ and \f$ b \f$.
+ */
+
+template<typename T1, typename T2>
+constexpr
+common_t<T1,T2>
+lcm(const T1 a, const T2 b)
+noexcept
+{
+    return internal::lcm_type_check(a,b);
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/lgamma.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/lgamma.hpp
new file mode 100644
index 0000000..5d78eb3
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/lgamma.hpp
@@ -0,0 +1,135 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * compile-time log-gamma function
+ * 
+ * for coefficient values, see:
+ * http://my.fit.edu/~gabdo/gamma.txt
+ */
+
+#ifndef _gcem_lgamma_HPP
+#define _gcem_lgamma_HPP
+
+namespace internal
+{
+
+// P. Godfrey's coefficients:
+//
+//  0.99999999999999709182
+//  57.156235665862923517
+// -59.597960355475491248
+//  14.136097974741747174
+//  -0.49191381609762019978
+//    .33994649984811888699e-4
+//    .46523628927048575665e-4
+//   -.98374475304879564677e-4
+//    .15808870322491248884e-3
+//   -.21026444172410488319e-3
+//    .21743961811521264320e-3
+//   -.16431810653676389022e-3
+//    .84418223983852743293e-4
+//   -.26190838401581408670e-4
+//    .36899182659531622704e-5
+
+constexpr
+long double
+lgamma_coef_term(const long double x)
+noexcept
+{
+    return(     0.99999999999999709182L             + 57.156235665862923517L      / (x+1)  \
+             - 59.597960355475491248L      / (x+2)  + 14.136097974741747174L      / (x+3)  \
+             -  0.49191381609762019978L    / (x+4)  +   .33994649984811888699e-4L / (x+5)  \
+             +   .46523628927048575665e-4L / (x+6)  -   .98374475304879564677e-4L / (x+7)  \
+             +   .15808870322491248884e-3L / (x+8)  -   .21026444172410488319e-3L / (x+9)  \
+             +   .21743961811521264320e-3L / (x+10) -   .16431810653676389022e-3L / (x+11) \
+             +   .84418223983852743293e-4L / (x+12) -   .26190838401581408670e-4L / (x+13) \
+             +   .36899182659531622704e-5L / (x+14) );
+}
+
+template<typename T>
+constexpr
+T
+lgamma_term_2(const T x)
+noexcept
+{ //
+    return( T(GCEM_LOG_SQRT_2PI) + log(T(lgamma_coef_term(x))) );
+}
+
+template<typename T>
+constexpr
+T
+lgamma_term_1(const T x)
+noexcept
+{   // note: 607/128 + 0.5 = 5.2421875
+    return( (x + T(0.5))*log(x + T(5.2421875L)) - (x + T(5.2421875L)) );
+}
+
+template<typename T>
+constexpr
+T
+lgamma_begin(const T x)
+noexcept
+{   // returns lngamma(x+1)
+    return( lgamma_term_1(x) + lgamma_term_2(x) );
+}
+
+template<typename T>
+constexpr
+T
+lgamma_check(const T x)
+noexcept
+{
+    return( // NaN check
+            is_nan(x) ? \
+                GCLIM<T>::quiet_NaN() :
+            // indistinguishable from one or <= zero
+            GCLIM<T>::min() > abs(x - T(1)) ? \
+                T(0) :
+            GCLIM<T>::min() > x ? \
+                GCLIM<T>::infinity() :
+            // else
+                lgamma_begin(x - T(1)) );
+}
+
+}
+
+/**
+ * Compile-time log-gamma function
+ *
+ * @param x a real-valued input.
+ * @return computes the log-gamma function
+ * \f[ \ln \Gamma(x) = \ln \int_0^\infty y^{x-1} \exp(-y) dy \f]
+ * using a polynomial form:
+ * \f[ \Gamma(x+1) \approx (x+g+0.5)^{x+0.5} \exp(-x-g-0.5) \sqrt{2 \pi} \left[ c_0 + \frac{c_1}{x+1} + \frac{c_2}{x+2} + \cdots + \frac{c_n}{x+n} \right] \f]
+ * where the value \f$ g \f$ and the coefficients \f$ (c_0, c_1, \ldots, c_n) \f$
+ * are taken from Paul Godfrey, whose note can be found here: http://my.fit.edu/~gabdo/gamma.txt
+ */
+
+template<typename T>
+constexpr
+return_t<T>
+lgamma(const T x)
+noexcept
+{
+    return internal::lgamma_check( static_cast<return_t<T>>(x) );
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/lmgamma.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/lmgamma.hpp
new file mode 100644
index 0000000..76bf833
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/lmgamma.hpp
@@ -0,0 +1,73 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/* 
+ * log multivariate gamma function
+ */
+
+#ifndef _gcem_lmgamma_HPP
+#define _gcem_lmgamma_HPP
+
+namespace internal
+{
+
+// see https://en.wikipedia.org/wiki/Multivariate_gamma_function
+
+template<typename T1, typename T2>
+constexpr
+T1
+lmgamma_recur(const T1 a, const T2 p)
+noexcept
+{
+    return( // NaN check
+            is_nan(a) ? \
+                GCLIM<T1>::quiet_NaN() :
+            //
+            p == T2(1) ? \
+                lgamma(a) :
+            p <  T2(1) ? \
+                GCLIM<T1>::quiet_NaN() :
+            // else
+                T1(GCEM_LOG_PI) * (p - T1(1))/T1(2) \
+                    + lgamma(a) + lmgamma_recur(a - T1(0.5),p-T2(1)) );
+}
+
+}
+
+/**
+ * Compile-time log multivariate gamma function
+ *
+ * @param a a real-valued input.
+ * @param p integral-valued input.
+ * @return computes log-multivariate gamma function via recursion
+ * \f[ \Gamma_p(a) = \pi^{(p-1)/2} \Gamma(a) \Gamma_{p-1}(a-0.5) \f]
+ * where \f$ \Gamma_1(a) = \Gamma(a) \f$.
+ */
+
+template<typename T1, typename T2>
+constexpr
+return_t<T1>
+lmgamma(const T1 a, const T2 p)
+noexcept
+{
+    return internal::lmgamma_recur(static_cast<return_t<T1>>(a),p);
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/log.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/log.hpp
new file mode 100644
index 0000000..0d83e97
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/log.hpp
@@ -0,0 +1,162 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * compile-time natural logarithm function
+ */
+
+#ifndef _gcem_log_HPP
+#define _gcem_log_HPP
+
+namespace internal
+{
+
+// continued fraction seems to be a better approximation for small x
+// see http://functions.wolfram.com/ElementaryFunctions/Log/10/0005/
+
+template<typename T>
+constexpr
+T
+log_cf_main(const T xx, const int depth)
+noexcept
+{
+    return( depth < GCEM_LOG_MAX_ITER_SMALL ? \
+            // if 
+                T(2*depth - 1) - T(depth*depth)*xx/log_cf_main(xx,depth+1) :
+            // else 
+                T(2*depth - 1) );
+}
+
+template<typename T>
+constexpr
+T
+log_cf_begin(const T x)
+noexcept
+{ 
+    return( T(2)*x/log_cf_main(x*x,1) );
+}
+
+template<typename T>
+constexpr
+T
+log_main(const T x)
+noexcept
+{ 
+    return( log_cf_begin((x - T(1))/(x + T(1))) );
+}
+
+constexpr
+long double
+log_mantissa_integer(const int x)
+noexcept
+{
+    return( x == 2  ? 0.6931471805599453094172321214581765680755L :
+            x == 3  ? 1.0986122886681096913952452369225257046475L :
+            x == 4  ? 1.3862943611198906188344642429163531361510L :
+            x == 5  ? 1.6094379124341003746007593332261876395256L :
+            x == 6  ? 1.7917594692280550008124773583807022727230L :
+            x == 7  ? 1.9459101490553133051053527434431797296371L :
+            x == 8  ? 2.0794415416798359282516963643745297042265L :
+            x == 9  ? 2.1972245773362193827904904738450514092950L :
+            x == 10 ? 2.3025850929940456840179914546843642076011L :
+                      0.0L );
+}
+
+template<typename T>
+constexpr
+T
+log_mantissa(const T x)
+noexcept
+{   // divide by the integer part of x, which will be in [1,10], then adjust using tables
+    return( log_main(x/T(static_cast<int>(x))) + T(log_mantissa_integer(static_cast<int>(x))) );
+}
+
+template<typename T>
+constexpr
+T
+log_breakup(const T x)
+noexcept
+{   // x = a*b, where b = 10^c
+    return( log_mantissa(mantissa(x)) + T(GCEM_LOG_10)*T(find_exponent(x,0)) );
+}
+
+template<typename T>
+constexpr
+T
+log_check(const T x)
+noexcept
+{
+    return( is_nan(x) ? \
+                GCLIM<T>::quiet_NaN() :
+            // x < 0
+            x < T(0) ? \
+                GCLIM<T>::quiet_NaN() :
+            // x ~= 0
+            GCLIM<T>::min() > x ? \
+                - GCLIM<T>::infinity() :
+            // indistinguishable from 1
+            GCLIM<T>::min() > abs(x - T(1)) ? \
+                T(0) : 
+            // 
+            x == GCLIM<T>::infinity() ? \
+                GCLIM<T>::infinity() :
+            // else
+                (x < T(0.5) || x > T(1.5)) ?
+                // if 
+                    log_breakup(x) :
+                // else
+                    log_main(x) );
+}
+
+template<typename T>
+constexpr
+return_t<T>
+log_integral_check(const T x)
+noexcept
+{
+    return( std::is_integral<T>::value ? \
+                x == T(0) ? \
+                    - GCLIM<return_t<T>>::infinity() :
+                x > T(1) ? \
+                    log_check( static_cast<return_t<T>>(x) ) :
+                    static_cast<return_t<T>>(0) :
+            log_check( static_cast<return_t<T>>(x) ) );
+}
+
+}
+
+/**
+ * Compile-time natural logarithm function
+ *
+ * @param x a real-valued input.
+ * @return \f$ \log_e(x) \f$ using \f[ \log\left(\frac{1+x}{1-x}\right) = \dfrac{2x}{1-\dfrac{x^2}{3-\dfrac{4x^2}{5 - \dfrac{9x^3}{7 - \ddots}}}}, \ \ x \in [-1,1] \f] 
+ * The continued fraction argument is split into two parts: \f$ x = a \times 10^c \f$, where \f$ c \f$ is an integer.
+ */
+
+template<typename T>
+constexpr
+return_t<T>
+log(const T x)
+noexcept
+{
+    return internal::log_integral_check( x );
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/log10.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/log10.hpp
new file mode 100644
index 0000000..4a3c37d
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/log10.hpp
@@ -0,0 +1,59 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * compile-time common logarithm function
+ */
+
+#ifndef _gcem_log10_HPP
+#define _gcem_log10_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr
+return_t<T>
+log10_check(const T x)
+noexcept
+{
+    // log_10(x) = ln(x) / ln(10)
+    return return_t<T>(log(x) / GCEM_LOG_10);
+}
+
+}
+
+/**
+ * Compile-time common logarithm function
+ *
+ * @param x a real-valued input.
+ * @return \f$ \log_{10}(x) \f$ using \f[ \log_{10}(x) = \frac{\log_e(x)}{\log_e(10)} \f] 
+ */
+
+template<typename T>
+constexpr
+return_t<T>
+log10(const T x)
+noexcept
+{
+    return internal::log10_check( x );
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/log1p.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/log1p.hpp
new file mode 100644
index 0000000..3883b22
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/log1p.hpp
@@ -0,0 +1,80 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * compile-time natural logarithm(x+1) function
+ */
+
+#ifndef _gcem_log1p_HPP
+#define _gcem_log1p_HPP
+
+namespace internal
+{
+
+// see:
+// http://functions.wolfram.com/ElementaryFunctions/Log/06/01/04/01/0003/
+
+
+template<typename T>
+constexpr
+T
+log1p_compute(const T x)
+noexcept
+{
+    // return x * ( T(1) + x * ( -T(1)/T(2) +  x * ( T(1)/T(3) +  x * ( -T(1)/T(4) + x/T(5) ) ) ) ); // O(x^6)
+    return x + x * ( - x/T(2) +  x * ( x/T(3) +  x * ( -x/T(4) + x*x/T(5) ) ) ); // O(x^6)
+}
+
+template<typename T>
+constexpr
+T
+log1p_check(const T x)
+noexcept
+{
+    return( // NaN check
+            is_nan(x) ? \
+                GCLIM<T>::quiet_NaN() :
+            //
+            abs(x) > T(1e-04) ? \
+            // if
+                log(T(1) + x) :
+            // else    
+                log1p_compute(x) );
+}
+
+}
+
+/**
+ * Compile-time natural-logarithm-plus-1 function
+ *
+ * @param x a real-valued input.
+ * @return \f$ \log_e(x+1) \f$ using \f[ \log(x+1) = \sum_{k=1}^\infty \dfrac{(-1)^{k-1}x^k}{k}, \ \ |x| < 1 \f] 
+ */
+
+template<typename T>
+constexpr
+return_t<T>
+log1p(const T x)
+noexcept
+{
+    return internal::log1p_check( static_cast<return_t<T>>(x) );
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/log2.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/log2.hpp
new file mode 100644
index 0000000..56b7f8e
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/log2.hpp
@@ -0,0 +1,59 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * compile-time binary logarithm function
+ */
+
+#ifndef _gcem_log2_HPP
+#define _gcem_log2_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr
+return_t<T>
+log2_check(const T x)
+noexcept
+{
+    // log_2(x) = ln(x) / ln(2)
+    return return_t<T>(log(x) / GCEM_LOG_2);
+}
+
+}
+
+/**
+ * Compile-time binary logarithm function
+ *
+ * @param x a real-valued input.
+ * @return \f$ \log_2(x) \f$ using \f[ \log_{2}(x) = \frac{\log_e(x)}{\log_e(2)} \f] 
+ */
+
+template<typename T>
+constexpr
+return_t<T>
+log2(const T x)
+noexcept
+{
+    return internal::log2_check( x );
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/log_binomial_coef.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/log_binomial_coef.hpp
new file mode 100644
index 0000000..7aa9a2b
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/log_binomial_coef.hpp
@@ -0,0 +1,65 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+#ifndef _gcem_log_binomial_coef_HPP
+#define _gcem_log_binomial_coef_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr
+T
+log_binomial_coef_compute(const T n, const T k)
+noexcept
+{
+    return( lgamma(n+1) - (lgamma(k+1) + lgamma(n-k+1)) );
+}
+
+template<typename T1, typename T2, typename TC = common_return_t<T1,T2>>
+constexpr
+TC
+log_binomial_coef_type_check(const T1 n, const T2 k)
+noexcept
+{
+    return log_binomial_coef_compute(static_cast<TC>(n),static_cast<TC>(k));
+}
+
+}
+
+/**
+ * Compile-time log binomial coefficient
+ *
+ * @param n integral-valued input.
+ * @param k integral-valued input.
+ * @return computes the log Binomial coefficient
+ * \f[ \ln \frac{n!}{k!(n-k)!} = \ln \Gamma(n+1) - [ \ln \Gamma(k+1) + \ln \Gamma(n-k+1) ] \f]
+ */
+
+template<typename T1, typename T2>
+constexpr
+common_return_t<T1,T2>
+log_binomial_coef(const T1 n, const T2 k)
+noexcept
+{
+    return internal::log_binomial_coef_type_check(n,k);
+}
+
+#endif
\ No newline at end of file
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/mantissa.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/mantissa.hpp
new file mode 100644
index 0000000..df6152b
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/mantissa.hpp
@@ -0,0 +1,47 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * compile-time mantissa function
+ */
+
+#ifndef _gcem_mantissa_HPP
+#define _gcem_mantissa_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr
+T
+mantissa(const T x)
+noexcept
+{
+    return( x < T(1) ? \
+                mantissa(x*T(10)) : 
+            x > T(10) ? \
+                mantissa(x/T(10)) :
+            // else
+                x );
+}
+
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/max.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/max.hpp
new file mode 100644
index 0000000..4aed84f
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/max.hpp
@@ -0,0 +1,41 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+#ifndef _gcem_max_HPP
+#define _gcem_max_HPP
+
+/**
+ * Compile-time pairwise maximum function
+ *
+ * @param x a real-valued input.
+ * @param y a real-valued input.
+ * @return Computes the maximum between \c x and \c y, where \c x and \c y have the same type (e.g., \c int, \c double, etc.)
+ */
+
+template<typename T1, typename T2>
+constexpr
+common_t<T1,T2>
+max(const T1 x, const T2 y)
+noexcept
+{
+    return( y < x ? x : y );
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/min.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/min.hpp
new file mode 100644
index 0000000..d593dbc
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/min.hpp
@@ -0,0 +1,41 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+#ifndef _gcem_min_HPP
+#define _gcem_min_HPP
+
+/**
+ * Compile-time pairwise minimum function
+ *
+ * @param x a real-valued input.
+ * @param y a real-valued input.
+ * @return Computes the minimum between \c x and \c y, where \c x and \c y have the same type (e.g., \c int, \c double, etc.)
+ */
+
+template<typename T1, typename T2>
+constexpr
+common_t<T1,T2>
+min(const T1 x, const T2 y)
+noexcept
+{
+    return( y > x ? x : y );
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/neg_zero.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/neg_zero.hpp
new file mode 100644
index 0000000..db33f87
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/neg_zero.hpp
@@ -0,0 +1,37 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * extract signbit for signed zeros
+ */
+
+namespace internal
+{
+
+template<typename T>
+constexpr 
+bool 
+neg_zero(const T x)
+noexcept
+{
+    return( (x == T(0.0)) && (copysign(T(1.0), x) == T(-1.0)) );
+}
+
+}
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/pow.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/pow.hpp
new file mode 100644
index 0000000..166a8c1
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/pow.hpp
@@ -0,0 +1,82 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * compile-time power function
+ */
+
+#ifndef _gcem_pow_HPP
+#define _gcem_pow_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr
+T
+pow_dbl(const T base, const T exp_term)
+noexcept
+{
+    return exp(exp_term*log(base));
+}
+
+template<typename T1, typename T2, typename TC = common_t<T1,T2>, 
+         typename std::enable_if<!std::is_integral<T2>::value>::type* = nullptr>
+constexpr
+TC
+pow_check(const T1 base, const T2 exp_term)
+noexcept
+{
+    return( base < T1(0) ? \
+                GCLIM<TC>::quiet_NaN() :
+            //
+            pow_dbl(static_cast<TC>(base),static_cast<TC>(exp_term)) );
+}
+
+template<typename T1, typename T2, typename TC = common_t<T1,T2>, 
+         typename std::enable_if<std::is_integral<T2>::value>::type* = nullptr>
+constexpr
+TC
+pow_check(const T1 base, const T2 exp_term)
+noexcept
+{
+    return pow_integral(base,exp_term);
+}
+
+}
+
+/**
+ * Compile-time power function
+ *
+ * @param base a real-valued input. 
+ * @param exp_term a real-valued input.
+ * @return Computes \c base raised to the power \c exp_term. In the case where \c exp_term is integral-valued, recursion by squaring is used, otherwise \f$ \text{base}^{\text{exp\_term}} = e^{\text{exp\_term} \log(\text{base})} \f$
+ */
+
+template<typename T1, typename T2>
+constexpr
+common_t<T1,T2>
+pow(const T1 base, const T2 exp_term)
+noexcept
+{
+    return internal::pow_check(base,exp_term);
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/pow_integral.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/pow_integral.hpp
new file mode 100644
index 0000000..3a902ca
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/pow_integral.hpp
@@ -0,0 +1,128 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * compile-time power function
+ */
+
+#ifndef _gcem_pow_integral_HPP
+#define _gcem_pow_integral_HPP
+
+namespace internal
+{
+
+template<typename T1, typename T2>
+constexpr T1 pow_integral_compute(const T1 base, const T2 exp_term) noexcept;
+
+// integral-valued powers using method described in 
+// https://en.wikipedia.org/wiki/Exponentiation_by_squaring
+
+template<typename T1, typename T2>
+constexpr
+T1
+pow_integral_compute_recur(const T1 base, const T1 val, const T2 exp_term)
+noexcept
+{
+    return( exp_term > T2(1) ? \
+                (is_odd(exp_term) ? \
+                    pow_integral_compute_recur(base*base,val*base,exp_term/2) :
+                    pow_integral_compute_recur(base*base,val,exp_term/2)) :
+                (exp_term == T2(1) ? val*base : val) );
+}
+
+template<typename T1, typename T2, typename std::enable_if<std::is_signed<T2>::value>::type* = nullptr>
+constexpr
+T1
+pow_integral_sgn_check(const T1 base, const T2 exp_term)
+noexcept
+{
+    return( exp_term < T2(0) ? \
+            //
+                T1(1) / pow_integral_compute(base, - exp_term) : 
+            //
+                pow_integral_compute_recur(base,T1(1),exp_term) );
+}
+
+template<typename T1, typename T2, typename std::enable_if<!std::is_signed<T2>::value>::type* = nullptr>
+constexpr
+T1
+pow_integral_sgn_check(const T1 base, const T2 exp_term)
+noexcept
+{
+    return( pow_integral_compute_recur(base,T1(1),exp_term) );
+}
+
+template<typename T1, typename T2>
+constexpr
+T1
+pow_integral_compute(const T1 base, const T2 exp_term)
+noexcept
+{
+    return( exp_term == T2(3) ? \
+                base*base*base :
+            exp_term == T2(2) ? \
+                base*base :
+            exp_term == T2(1) ? \
+                base :
+            exp_term == T2(0) ? \
+                T1(1) :
+            // check for overflow
+            exp_term == GCLIM<T2>::min() ? \
+                T1(0) :
+            exp_term == GCLIM<T2>::max() ? \
+                GCLIM<T1>::infinity() :
+            // else
+            pow_integral_sgn_check(base,exp_term) );
+}
+
+template<typename T1, typename T2, typename std::enable_if<std::is_integral<T2>::value>::type* = nullptr>
+constexpr
+T1
+pow_integral_type_check(const T1 base, const T2 exp_term)
+noexcept
+{
+    return pow_integral_compute(base,exp_term);
+}
+
+template<typename T1, typename T2, typename std::enable_if<!std::is_integral<T2>::value>::type* = nullptr>
+constexpr
+T1
+pow_integral_type_check(const T1 base, const T2 exp_term)
+noexcept
+{
+    // return GCLIM<return_t<T1>>::quiet_NaN();
+    return pow_integral_compute(base,static_cast<llint_t>(exp_term));
+}
+
+//
+// main function
+
+template<typename T1, typename T2>
+constexpr
+T1
+pow_integral(const T1 base, const T2 exp_term)
+noexcept
+{
+    return internal::pow_integral_type_check(base,exp_term);
+}
+
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/quadrature/gauss_legendre_30.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/quadrature/gauss_legendre_30.hpp
new file mode 100644
index 0000000..e609b89
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/quadrature/gauss_legendre_30.hpp
@@ -0,0 +1,91 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * Gauss-Legendre quadrature: 30 points
+ */
+
+static const long double gauss_legendre_30_points[30] = \
+{
+    -0.05147184255531769583302521316672L,
+     0.05147184255531769583302521316672L,
+    -0.15386991360858354696379467274326L,
+     0.15386991360858354696379467274326L,
+    -0.25463692616788984643980512981781L,
+     0.25463692616788984643980512981781L,
+    -0.35270472553087811347103720708937L,
+     0.35270472553087811347103720708937L,
+    -0.44703376953808917678060990032285L,
+     0.44703376953808917678060990032285L,
+    -0.53662414814201989926416979331107L,
+     0.53662414814201989926416979331107L,
+    -0.62052618298924286114047755643119L,
+     0.62052618298924286114047755643119L,
+    -0.69785049479331579693229238802664L,
+     0.69785049479331579693229238802664L,
+    -0.76777743210482619491797734097450L,
+     0.76777743210482619491797734097450L,
+    -0.82956576238276839744289811973250L,
+     0.82956576238276839744289811973250L,
+    -0.88256053579205268154311646253023L,
+     0.88256053579205268154311646253023L,
+    -0.92620004742927432587932427708047L,
+     0.92620004742927432587932427708047L,
+    -0.96002186496830751221687102558180L,
+     0.96002186496830751221687102558180L,
+    -0.98366812327974720997003258160566L,
+     0.98366812327974720997003258160566L,
+    -0.99689348407464954027163005091870L,
+     0.99689348407464954027163005091870L\
+};
+
+static const long double gauss_legendre_30_weights[30] = \
+{
+    0.10285265289355884034128563670542L,
+    0.10285265289355884034128563670542L,
+    0.10176238974840550459642895216855L,
+    0.10176238974840550459642895216855L,
+    0.09959342058679526706278028210357L,
+    0.09959342058679526706278028210357L,
+    0.09636873717464425963946862635181L,
+    0.09636873717464425963946862635181L,
+    0.09212252223778612871763270708762L,
+    0.09212252223778612871763270708762L,
+    0.08689978720108297980238753071513L,
+    0.08689978720108297980238753071513L,
+    0.08075589522942021535469493846053L,
+    0.08075589522942021535469493846053L,
+    0.07375597473770520626824385002219L,
+    0.07375597473770520626824385002219L,
+    0.06597422988218049512812851511596L,
+    0.06597422988218049512812851511596L,
+    0.05749315621761906648172168940206L,
+    0.05749315621761906648172168940206L,
+    0.04840267283059405290293814042281L,
+    0.04840267283059405290293814042281L,
+    0.03879919256962704959680193644635L,
+    0.03879919256962704959680193644635L,
+    0.02878470788332336934971917961129L,
+    0.02878470788332336934971917961129L,
+    0.01846646831109095914230213191205L,
+    0.01846646831109095914230213191205L,
+    0.00796819249616660561546588347467L,
+    0.00796819249616660561546588347467L\
+};
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/quadrature/gauss_legendre_50.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/quadrature/gauss_legendre_50.hpp
new file mode 100644
index 0000000..44281f9
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/quadrature/gauss_legendre_50.hpp
@@ -0,0 +1,131 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * Gauss-Legendre quadrature: 50 points
+ */
+
+static const long double gauss_legendre_50_points[50] = \
+{
+    -0.03109833832718887611232898966595L,
+     0.03109833832718887611232898966595L,
+    -0.09317470156008614085445037763960L,
+     0.09317470156008614085445037763960L,
+    -0.15489058999814590207162862094111L,
+     0.15489058999814590207162862094111L,
+    -0.21600723687604175684728453261710L,
+     0.21600723687604175684728453261710L,
+    -0.27628819377953199032764527852113L,
+     0.27628819377953199032764527852113L,
+    -0.33550024541943735683698825729107L,
+     0.33550024541943735683698825729107L,
+    -0.39341431189756512739422925382382L,
+     0.39341431189756512739422925382382L,
+    -0.44980633497403878914713146777838L,
+     0.44980633497403878914713146777838L,
+    -0.50445814490746420165145913184914L,
+     0.50445814490746420165145913184914L,
+    -0.55715830451465005431552290962580L,
+     0.55715830451465005431552290962580L,
+    -0.60770292718495023918038179639183L,
+     0.60770292718495023918038179639183L,
+    -0.65589646568543936078162486400368L,
+     0.65589646568543936078162486400368L,
+    -0.70155246870682225108954625788366L,
+     0.70155246870682225108954625788366L,
+    -0.74449430222606853826053625268219L,
+     0.74449430222606853826053625268219L,
+    -0.78455583290039926390530519634099L,
+     0.78455583290039926390530519634099L,
+    -0.82158207085933594835625411087394L,
+     0.82158207085933594835625411087394L,
+    -0.85542976942994608461136264393476L,
+     0.85542976942994608461136264393476L,
+    -0.88596797952361304863754098246675L,
+     0.88596797952361304863754098246675L,
+    -0.91307855665579189308973564277166L,
+     0.91307855665579189308973564277166L,
+    -0.93665661894487793378087494727250L,
+     0.93665661894487793378087494727250L,
+    -0.95661095524280794299774564415662L,
+     0.95661095524280794299774564415662L,
+    -0.97286438510669207371334410460625L,
+     0.97286438510669207371334410460625L,
+    -0.98535408404800588230900962563249L,
+     0.98535408404800588230900962563249L,
+    -0.99403196943209071258510820042069L,
+     0.99403196943209071258510820042069L,
+    -0.99886640442007105018545944497422L,
+     0.99886640442007105018545944497422L\
+};
+
+static const long double gauss_legendre_50_weights[50] = \
+{
+    0.06217661665534726232103310736061L,
+    0.06217661665534726232103310736061L,
+    0.06193606742068324338408750978083L,
+    0.06193606742068324338408750978083L,
+    0.06145589959031666375640678608392L,
+    0.06145589959031666375640678608392L,
+    0.06073797084177021603175001538481L,
+    0.06073797084177021603175001538481L,
+    0.05978505870426545750957640531259L,
+    0.05978505870426545750957640531259L,
+    0.05860084981322244583512243663085L,
+    0.05860084981322244583512243663085L,
+    0.05718992564772838372302931506599L,
+    0.05718992564772838372302931506599L,
+    0.05555774480621251762356742561227L,
+    0.05555774480621251762356742561227L,
+    0.05371062188899624652345879725566L,
+    0.05371062188899624652345879725566L,
+    0.05165570306958113848990529584010L,
+    0.05165570306958113848990529584010L,
+    0.04940093844946631492124358075143L,
+    0.04940093844946631492124358075143L,
+    0.04695505130394843296563301363499L,
+    0.04695505130394843296563301363499L,
+    0.04432750433880327549202228683039L,
+    0.04432750433880327549202228683039L,
+    0.04152846309014769742241197896407L,
+    0.04152846309014769742241197896407L,
+    0.03856875661258767524477015023639L,
+    0.03856875661258767524477015023639L,
+    0.03545983561514615416073461100098L,
+    0.03545983561514615416073461100098L,
+    0.03221372822357801664816582732300L,
+    0.03221372822357801664816582732300L,
+    0.02884299358053519802990637311323L,
+    0.02884299358053519802990637311323L,
+    0.02536067357001239044019487838544L,
+    0.02536067357001239044019487838544L,
+    0.02178024317012479298159206906269L,
+    0.02178024317012479298159206906269L,
+    0.01811556071348939035125994342235L,
+    0.01811556071348939035125994342235L,
+    0.01438082276148557441937890892732L,
+    0.01438082276148557441937890892732L,
+    0.01059054838365096926356968149924L,
+    0.01059054838365096926356968149924L,
+    0.00675979919574540150277887817799L,
+    0.00675979919574540150277887817799L,
+    0.00290862255315514095840072434286L,
+    0.00290862255315514095840072434286L\
+};
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/round.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/round.hpp
new file mode 100644
index 0000000..43d7a5e
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/round.hpp
@@ -0,0 +1,125 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+#ifndef _gcem_round_HPP
+#define _gcem_round_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr
+T
+round_int(const T x)
+noexcept
+{
+    return( abs(x - internal::floor_check(x)) >= T(0.5) ? \
+            // if 
+                internal::floor_check(x) + sgn(x) : \
+            // else 
+                internal::floor_check(x) );
+}
+
+template<typename T>
+constexpr
+T
+round_check_internal(const T x)
+noexcept
+{
+    return x;
+}
+
+template<>
+constexpr
+float
+round_check_internal<float>(const float x)
+noexcept
+{
+    return( abs(x) >= 8388608.f ? \
+            // if
+                x : \
+            //else
+                round_int(x) );
+}
+
+template<>
+constexpr
+double
+round_check_internal<double>(const double x)
+noexcept
+{
+    return( abs(x) >= 4503599627370496. ? \
+            // if
+                x : \
+            // else
+                round_int(x) );
+}
+
+template<>
+constexpr
+long double
+round_check_internal<long double>(const long double x)
+noexcept
+{
+    return( abs(x) >= 9223372036854775808.l ? \
+            // if
+                x : \
+            // else
+                round_int(x) );
+}
+
+template<typename T>
+constexpr
+T
+round_check(const T x)
+noexcept
+{
+    return( // NaN check
+            is_nan(x) ? \
+                GCLIM<T>::quiet_NaN() :
+            // +/- infinite
+            !is_finite(x) ? \
+                x :
+            // signed-zero cases
+            GCLIM<T>::min() > abs(x) ? \
+                x :
+            // else
+                sgn(x) * round_check_internal(abs(x)) );
+}
+
+}
+
+/**
+ * Compile-time round function
+ *
+ * @param x a real-valued input.
+ * @return computes the rounding value of the input.
+ */
+
+template<typename T>
+constexpr
+return_t<T>
+round(const T x)
+noexcept
+{
+    return internal::round_check( static_cast<return_t<T>>(x) );
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/sgn.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/sgn.hpp
new file mode 100644
index 0000000..605a35a
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/sgn.hpp
@@ -0,0 +1,45 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+#ifndef _gcem_sgn_HPP
+#define _gcem_sgn_HPP
+
+/**
+ * Compile-time sign function
+ *
+ * @param x a real-valued input
+ * @return a value \f$ y \f$ such that \f[ y = \begin{cases} 1 \ &\text{ if } x > 0 \\ 0 \ &\text{ if } x = 0 \\ -1 \ &\text{ if } x < 0 \end{cases} \f]
+ */
+
+template<typename T>
+constexpr
+int
+sgn(const T x)
+noexcept
+{
+    return( // positive
+            x > T(0) ?  1 :
+            // negative
+            x < T(0) ? -1 :
+            // else
+                0 );
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/signbit.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/signbit.hpp
new file mode 100644
index 0000000..e207a5a
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/signbit.hpp
@@ -0,0 +1,44 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+#ifndef _gcem_signbit_HPP
+#define _gcem_signbit_HPP
+
+/**
+ * Compile-time sign bit detection function
+ *
+ * @param x a real-valued input
+ * @return return true if \c x is negative, otherwise return false.
+ */
+
+template <typename T>
+constexpr 
+bool
+signbit(const T x)
+noexcept
+{
+#ifdef _MSC_VER
+    return( (x == T(0)) ? (_fpclass(x) == _FPCLASS_NZ) : (x < T(0)) );
+#else
+    return GCEM_SIGNBIT(x);
+#endif
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/sin.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/sin.hpp
new file mode 100644
index 0000000..128cd32
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/sin.hpp
@@ -0,0 +1,85 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * compile-time sine function using tan(x/2)
+ * 
+ * see eq. 5.4.8 in Numerical Recipes
+ */
+
+#ifndef _gcem_sin_HPP
+#define _gcem_sin_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr
+T
+sin_compute(const T x)
+noexcept
+{
+    return T(2)*x/(T(1) + x*x);
+}
+
+template<typename T>
+constexpr
+T
+sin_check(const T x)
+noexcept
+{
+    return( // NaN check
+            is_nan(x) ? \
+                GCLIM<T>::quiet_NaN() :
+            // indistinguishable from zero
+            GCLIM<T>::min() > abs(x) ? \
+                T(0) :
+            // special cases: pi/2 and pi
+            GCLIM<T>::min() > abs(x - T(GCEM_HALF_PI)) ? \
+                T(1) :
+            GCLIM<T>::min() > abs(x + T(GCEM_HALF_PI)) ? \
+                - T(1) :
+            GCLIM<T>::min() > abs(x - T(GCEM_PI)) ? \
+                T(0) :
+            GCLIM<T>::min() > abs(x + T(GCEM_PI)) ? \
+                - T(0) :
+            // else
+                sin_compute( tan(x/T(2)) ) );
+}
+
+}
+
+/**
+ * Compile-time sine function
+ *
+ * @param x a real-valued input.
+ * @return the sine function using \f[ \sin(x) = \frac{2\tan(x/2)}{1+\tan^2(x/2)} \f]
+ */
+
+template<typename T>
+constexpr
+return_t<T>
+sin(const T x)
+noexcept
+{
+    return internal::sin_check( static_cast<return_t<T>>(x) );
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/sinh.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/sinh.hpp
new file mode 100644
index 0000000..5355301
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/sinh.hpp
@@ -0,0 +1,65 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * compile-time hyperbolic sine function
+ */
+
+#ifndef _gcem_sinh_HPP
+#define _gcem_sinh_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr
+T
+sinh_check(const T x)
+noexcept
+{
+    return( // NaN check
+            is_nan(x) ? \
+                GCLIM<T>::quiet_NaN() :
+            // indistinguishable from zero
+            GCLIM<T>::min() > abs(x) ? \
+                T(0) :
+            // else
+                (exp(x) - exp(-x))/T(2) );
+}
+
+}
+
+/**
+ * Compile-time hyperbolic sine function
+ *
+ * @param x a real-valued input.
+ * @return the hyperbolic sine function using \f[ \sinh(x) = \frac{\exp(x) - \exp(-x)}{2} \f]
+ */
+
+template<typename T>
+constexpr
+return_t<T>
+sinh(const T x)
+noexcept
+{
+    return internal::sinh_check( static_cast<return_t<T>>(x) );
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/sqrt.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/sqrt.hpp
new file mode 100644
index 0000000..0fd559d
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/sqrt.hpp
@@ -0,0 +1,90 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * compile-time square-root function
+ */
+
+#ifndef _gcem_sqrt_HPP
+#define _gcem_sqrt_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr
+T
+sqrt_recur(const T x, const T xn, const int count)
+noexcept
+{
+    return( abs(xn - x/xn) / (T(1) + xn) < GCLIM<T>::min() ? \
+            // if
+                xn :
+            count < GCEM_SQRT_MAX_ITER ? \
+            // else
+                sqrt_recur(x, T(0.5)*(xn + x/xn), count+1) :
+                xn );
+}
+
+template<typename T>
+constexpr
+T
+sqrt_check(const T x, const T m_val)
+noexcept
+{
+    return( is_nan(x) ? \
+                GCLIM<T>::quiet_NaN() :
+            //
+            x < T(0) ? \
+                GCLIM<T>::quiet_NaN() :
+            //
+            is_posinf(x) ? \
+                x :
+            // indistinguishable from zero or one
+            GCLIM<T>::min() > abs(x) ? \
+                T(0) :
+            GCLIM<T>::min() > abs(T(1) - x) ? \
+                x :
+            // else
+            x > T(4) ? \
+                sqrt_check(x/T(4), T(2)*m_val) :
+                m_val * sqrt_recur(x, x/T(2), 0) );
+}
+
+}
+
+
+/**
+ * Compile-time square-root function
+ *
+ * @param x a real-valued input.
+ * @return Computes \f$ \sqrt{x} \f$ using a Newton-Raphson approach.
+ */
+
+template<typename T>
+constexpr
+return_t<T>
+sqrt(const T x)
+noexcept
+{
+    return internal::sqrt_check( static_cast<return_t<T>>(x), return_t<T>(1) );
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/tan.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/tan.hpp
new file mode 100644
index 0000000..e53f5c8
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/tan.hpp
@@ -0,0 +1,140 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * compile-time tangent function
+ */
+
+#ifndef _gcem_tan_HPP
+#define _gcem_tan_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr
+T
+tan_series_exp_long(const T z)
+noexcept
+{   // this is based on a fourth-order expansion of tan(z) using Bernoulli numbers
+    return( - 1/z + (z/3 + (pow_integral(z,3)/45 + (2*pow_integral(z,5)/945 + pow_integral(z,7)/4725))) );
+}
+
+template<typename T>
+constexpr
+T
+tan_series_exp(const T x)
+noexcept
+{
+    return( GCLIM<T>::min() > abs(x - T(GCEM_HALF_PI)) ? \
+            // the value tan(pi/2) is somewhat of a convention;
+            // technically the function is not defined at EXACTLY pi/2,
+            // but this is floating point pi/2
+                T(1.633124e+16) :
+            // otherwise we use an expansion around pi/2
+                tan_series_exp_long(x - T(GCEM_HALF_PI))
+            );
+}
+
+template<typename T>
+constexpr
+T
+tan_cf_recur(const T xx, const int depth, const int max_depth)
+noexcept
+{
+    return( depth < max_depth ? \
+            // if
+                T(2*depth - 1) - xx/tan_cf_recur(xx,depth+1,max_depth) :
+            // else
+                T(2*depth - 1) );
+}
+
+template<typename T>
+constexpr
+T
+tan_cf_main(const T x)
+noexcept
+{
+    return( (x > T(1.55) && x < T(1.60)) ? \
+                tan_series_exp(x) : // deals with a singularity at tan(pi/2)
+            //
+            x > T(1.4) ? \
+                x/tan_cf_recur(x*x,1,45) :
+            x > T(1)   ? \
+                x/tan_cf_recur(x*x,1,35) :
+            // else
+                x/tan_cf_recur(x*x,1,25) );
+}
+
+template<typename T>
+constexpr
+T
+tan_begin(const T x, const int count = 0)
+noexcept
+{   // tan(x) = tan(x + pi)
+    return( x > T(GCEM_PI) ? \
+            // if
+                count > 1 ? GCLIM<T>::quiet_NaN() : // protect against undefined behavior
+                tan_begin( x - T(GCEM_PI) * internal::floor_check(x/T(GCEM_PI)), count+1 ) :
+            // else 
+                tan_cf_main(x) );
+}
+
+template<typename T>
+constexpr
+T
+tan_check(const T x)
+noexcept
+{
+    return( // NaN check
+            is_nan(x) ? \
+                GCLIM<T>::quiet_NaN() :
+            // indistinguishable from zero 
+            GCLIM<T>::min() > abs(x) ? \
+                T(0) :
+            // else
+                x < T(0) ? \
+                    - tan_begin(-x) : 
+                      tan_begin( x) );
+}
+
+}
+
+/**
+ * Compile-time tangent function
+ *
+ * @param x a real-valued input.
+ * @return the tangent function using
+ * \f[ \tan(x) = \dfrac{x}{1 - \dfrac{x^2}{3 - \dfrac{x^2}{5 - \ddots}}} \f]
+ * To deal with a singularity at \f$ \pi / 2 \f$, the following expansion is employed:
+ * \f[ \tan(x) = - \frac{1}{x-\pi/2} - \sum_{k=1}^\infty \frac{(-1)^k 2^{2k} B_{2k}}{(2k)!} (x - \pi/2)^{2k - 1} \f]
+ * where \f$ B_n \f$ is the n-th Bernoulli number.
+ */
+
+template<typename T>
+constexpr
+return_t<T>
+tan(const T x)
+noexcept
+{
+    return internal::tan_check( static_cast<return_t<T>>(x) );
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/tanh.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/tanh.hpp
new file mode 100644
index 0000000..109d751
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/tanh.hpp
@@ -0,0 +1,89 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * compile-time hyperbolic tangent function
+ */
+
+#ifndef _gcem_tanh_HPP
+#define _gcem_tanh_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr
+T
+tanh_cf(const T xx, const int depth)
+noexcept
+{
+    return( depth < GCEM_TANH_MAX_ITER ? \
+            // if
+                (2*depth - 1) + xx/tanh_cf(xx,depth+1) :
+            // else
+                T(2*depth - 1) );
+}
+
+template<typename T>
+constexpr
+T
+tanh_begin(const T x)
+noexcept
+{
+    return( x/tanh_cf(x*x,1) );
+}
+
+template<typename T>
+constexpr
+T
+tanh_check(const T x)
+noexcept
+{
+    return( // NaN check
+            is_nan(x) ? \
+                GCLIM<T>::quiet_NaN() :
+            // indistinguishable from zero
+             GCLIM<T>::min() > abs(x) ? \
+                T(0) :
+             // else
+                x < T(0) ? \
+                    - tanh_begin(-x) : 
+                      tanh_begin( x) );
+}
+
+}
+
+/**
+ * Compile-time hyperbolic tangent function
+ *
+ * @param x a real-valued input.
+ * @return the hyperbolic tangent function using \f[ \tanh(x) = \dfrac{x}{1 + \dfrac{x^2}{3 + \dfrac{x^2}{5 + \dfrac{x^2}{7 + \ddots}}}} \f]
+ */
+
+template<typename T>
+constexpr
+return_t<T>
+tanh(const T x)
+noexcept
+{
+    return internal::tanh_check( static_cast<return_t<T>>(x) );
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/tgamma.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/tgamma.hpp
new file mode 100644
index 0000000..5a9ae97
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/tgamma.hpp
@@ -0,0 +1,80 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+/*
+ * the ('true') gamma function
+ */
+
+#ifndef _gcem_tgamma_HPP
+#define _gcem_tgamma_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr
+T
+tgamma_check(const T x)
+noexcept
+{
+    return( // NaN check
+            is_nan(x) ? \
+                GCLIM<T>::quiet_NaN() :
+            // indistinguishable from one or zero
+            GCLIM<T>::min() > abs(x - T(1)) ? \
+                T(1) :
+            GCLIM<T>::min() > abs(x) ? \
+                GCLIM<T>::infinity() :
+            // negative numbers
+            x < T(0) ? \
+                // check for integer
+                GCLIM<T>::min() > abs(x - find_whole(x)) ? \
+                    GCLIM<T>::quiet_NaN() :
+                // else
+                tgamma_check(x+T(1)) / x :
+
+            // else
+                exp(lgamma(x)) );
+}
+
+}
+
+/**
+ * Compile-time gamma function
+ *
+ * @param x a real-valued input.
+ * @return computes the `true' gamma function
+ * \f[ \Gamma(x) = \int_0^\infty y^{x-1} \exp(-y) dy \f]
+ * using a polynomial form:
+ * \f[ \Gamma(x+1) \approx (x+g+0.5)^{x+0.5} \exp(-x-g-0.5) \sqrt{2 \pi} \left[ c_0 + \frac{c_1}{x+1} + \frac{c_2}{x+2} + \cdots + \frac{c_n}{x+n} \right] \f]
+ * where the value \f$ g \f$ and the coefficients \f$ (c_0, c_1, \ldots, c_n) \f$
+ * are taken from Paul Godfrey, whose note can be found here: http://my.fit.edu/~gabdo/gamma.txt
+ */
+
+template<typename T>
+constexpr
+return_t<T>
+tgamma(const T x)
+noexcept
+{
+    return internal::tgamma_check( static_cast<return_t<T>>(x) );
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/trunc.hpp b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/trunc.hpp
new file mode 100644
index 0000000..4e19ef9
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/main/native/thirdparty/gcem/include/gcem_incl/trunc.hpp
@@ -0,0 +1,121 @@
+/*################################################################################
+  ##
+  ##   Copyright (C) 2016-2022 Keith O'Hara
+  ##
+  ##   This file is part of the GCE-Math C++ library.
+  ##
+  ##   Licensed under the Apache License, Version 2.0 (the "License");
+  ##   you may not use this file except in compliance with the License.
+  ##   You may obtain a copy of the License at
+  ##
+  ##       http://www.apache.org/licenses/LICENSE-2.0
+  ##
+  ##   Unless required by applicable law or agreed to in writing, software
+  ##   distributed under the License is distributed on an "AS IS" BASIS,
+  ##   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  ##   See the License for the specific language governing permissions and
+  ##   limitations under the License.
+  ##
+  ################################################################################*/
+
+#ifndef _gcem_trunc_HPP
+#define _gcem_trunc_HPP
+
+namespace internal
+{
+
+template<typename T>
+constexpr
+T
+trunc_int(const T x)
+noexcept
+{
+    return( T(static_cast<llint_t>(x)) );
+}
+
+template<typename T>
+constexpr
+T
+trunc_check_internal(const T x)
+noexcept
+{
+    return x;
+}
+
+template<>
+constexpr
+float
+trunc_check_internal<float>(const float x)
+noexcept
+{
+    return( abs(x) >= 8388608.f ? \
+            // if
+                x : \
+            // else
+                trunc_int(x) );
+}
+
+template<>
+constexpr
+double
+trunc_check_internal<double>(const double x)
+noexcept
+{
+    return( abs(x) >= 4503599627370496. ? \
+            // if
+                x : \
+            // else
+                trunc_int(x) );
+}
+
+template<>
+constexpr
+long double
+trunc_check_internal<long double>(const long double x)
+noexcept
+{
+    return( abs(x) >= 9223372036854775808.l ? \
+            // if
+                x : \
+            // else
+                ((long double)static_cast<ullint_t>(abs(x))) * sgn(x) );
+}
+
+template<typename T>
+constexpr
+T
+trunc_check(const T x)
+noexcept
+{
+    return( // NaN check
+            is_nan(x) ? \
+                GCLIM<T>::quiet_NaN() :
+            // +/- infinite
+            !is_finite(x) ? \
+                x :
+            // signed-zero cases
+            GCLIM<T>::min() > abs(x) ? \
+                x :
+            // else
+                trunc_check_internal(x) );
+}
+
+}
+
+/**
+ * Compile-time trunc function
+ *
+ * @param x a real-valued input.
+ * @return computes the trunc-value of the input, essentially returning the integer part of the input.
+ */
+
+template<typename T>
+constexpr
+return_t<T>
+trunc(const T x)
+noexcept
+{
+    return internal::trunc_check( static_cast<return_t<T>>(x) );
+}
+
+#endif
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/ComputerVisionUtilTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/ComputerVisionUtilTest.java
new file mode 100644
index 0000000..2927847
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/ComputerVisionUtilTest.java
@@ -0,0 +1,33 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.math;
+
+import static org.junit.jupiter.api.Assertions.assertEquals;
+
+import edu.wpi.first.math.geometry.Pose3d;
+import edu.wpi.first.math.geometry.Rotation3d;
+import edu.wpi.first.math.geometry.Transform3d;
+import edu.wpi.first.math.geometry.Translation3d;
+import edu.wpi.first.math.util.Units;
+import org.junit.jupiter.api.Test;
+
+class ComputerVisionUtilTest {
+  @Test
+  void testObjectToRobotPose() {
+    var robot = new Pose3d(1.0, 2.0, 0.0, new Rotation3d(0.0, 0.0, Units.degreesToRadians(30.0)));
+    var cameraToObject =
+        new Transform3d(
+            new Translation3d(1.0, 1.0, 1.0),
+            new Rotation3d(0.0, Units.degreesToRadians(-20.0), Units.degreesToRadians(45.0)));
+    var robotToCamera =
+        new Transform3d(
+            new Translation3d(1.0, 0.0, 2.0),
+            new Rotation3d(0.0, 0.0, Units.degreesToRadians(25.0)));
+    Pose3d object = robot.plus(robotToCamera).plus(cameraToObject);
+
+    assertEquals(
+        robot, ComputerVisionUtil.objectToRobotPose(object, cameraToObject, robotToCamera));
+  }
+}
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/DrakeTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/DrakeTest.java
index 66daf3d..3050867 100644
--- a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/DrakeTest.java
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/DrakeTest.java
@@ -10,7 +10,6 @@
 import org.ejml.simple.SimpleMatrix;
 import org.junit.jupiter.api.Test;
 
-@SuppressWarnings({"ParameterName", "LocalVariableName"})
 class DrakeTest {
   public static void assertMatrixEqual(SimpleMatrix A, SimpleMatrix B) {
     for (int i = 0; i < A.numRows(); i++) {
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/MathUtilTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/MathUtilTest.java
index bb116ce..a3de9cc 100644
--- a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/MathUtilTest.java
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/MathUtilTest.java
@@ -10,7 +10,7 @@
 
 class MathUtilTest {
   @Test
-  void testApplyDeadband() {
+  void testApplyDeadbandUnityScale() {
     // < 0
     assertEquals(-1.0, MathUtil.applyDeadband(-1.0, 0.02));
     assertEquals((-0.03 + 0.02) / (1.0 - 0.02), MathUtil.applyDeadband(-0.03, 0.02));
@@ -28,6 +28,27 @@
   }
 
   @Test
+  void testApplyDeadbandArbitraryScale() {
+    // < 0
+    assertEquals(-2.5, MathUtil.applyDeadband(-2.5, 0.02, 2.5));
+    assertEquals(0.0, MathUtil.applyDeadband(-0.02, 0.02, 2.5));
+    assertEquals(0.0, MathUtil.applyDeadband(-0.01, 0.02, 2.5));
+
+    // == 0
+    assertEquals(0.0, MathUtil.applyDeadband(0.0, 0.02, 2.5));
+
+    // > 0
+    assertEquals(0.0, MathUtil.applyDeadband(0.01, 0.02, 2.5));
+    assertEquals(0.0, MathUtil.applyDeadband(0.02, 0.02, 2.5));
+    assertEquals(2.5, MathUtil.applyDeadband(2.5, 0.02, 2.5));
+  }
+
+  @Test
+  void testApplyDeadbandLargeMaxMagnitude() {
+    assertEquals(80.0, MathUtil.applyDeadband(100.0, 20, Double.POSITIVE_INFINITY));
+  }
+
+  @Test
   void testInputModulus() {
     // These tests check error wrapping. That is, the result of wrapping the
     // result of an angle reference minus the measurement.
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/StateSpaceUtilTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/StateSpaceUtilTest.java
index 8cd1e5a..054c29a 100644
--- a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/StateSpaceUtilTest.java
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/StateSpaceUtilTest.java
@@ -50,7 +50,6 @@
   }
 
   @Test
-  @SuppressWarnings("LocalVariableName")
   void testIsStabilizable() {
     Matrix<N2, N2> A;
     Matrix<N2, N1> B = VecBuilder.fill(0, 1);
@@ -77,7 +76,6 @@
   }
 
   @Test
-  @SuppressWarnings("LocalVariableName")
   void testIsDetectable() {
     Matrix<N2, N2> A;
     Matrix<N1, N2> C = Matrix.mat(Nat.N1(), Nat.N2()).fill(0, 1);
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/VectorTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/VectorTest.java
new file mode 100644
index 0000000..5488b68
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/VectorTest.java
@@ -0,0 +1,30 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.math;
+
+import static org.junit.jupiter.api.Assertions.assertEquals;
+
+import org.junit.jupiter.api.Test;
+
+class VectorTest {
+  @Test
+  void testVectorDot() {
+    var vec1 = VecBuilder.fill(1.0, 2.0, 3.0);
+    var vec2 = VecBuilder.fill(4.0, 5.0, 6.0);
+
+    assertEquals(32.0, vec1.dot(vec2));
+
+    var vec3 = VecBuilder.fill(-1.0, 2.0, -3.0);
+    var vec4 = VecBuilder.fill(4.0, -5.0, 6.0);
+
+    assertEquals(-32.0, vec3.dot(vec4));
+  }
+
+  @Test
+  void testVectorNorm() {
+    assertEquals(Math.sqrt(14.0), VecBuilder.fill(1.0, 2.0, 3.0).norm());
+    assertEquals(Math.sqrt(14.0), VecBuilder.fill(1.0, -2.0, 3.0).norm());
+  }
+}
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/controller/ControlAffinePlantInversionFeedforwardTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/controller/ControlAffinePlantInversionFeedforwardTest.java
index f64608e..fcd9de1 100644
--- a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/controller/ControlAffinePlantInversionFeedforwardTest.java
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/controller/ControlAffinePlantInversionFeedforwardTest.java
@@ -14,7 +14,6 @@
 import org.junit.jupiter.api.Test;
 
 class ControlAffinePlantInversionFeedforwardTest {
-  @SuppressWarnings("LocalVariableName")
   @Test
   void testCalculate() {
     ControlAffinePlantInversionFeedforward<N2, N1> feedforward =
@@ -25,7 +24,6 @@
         48.0, feedforward.calculate(VecBuilder.fill(2, 2), VecBuilder.fill(3, 3)).get(0, 0), 1e-6);
   }
 
-  @SuppressWarnings("LocalVariableName")
   @Test
   void testCalculateState() {
     ControlAffinePlantInversionFeedforward<N2, N1> feedforward =
@@ -36,7 +34,6 @@
         48.0, feedforward.calculate(VecBuilder.fill(2, 2), VecBuilder.fill(3, 3)).get(0, 0), 1e-6);
   }
 
-  @SuppressWarnings("ParameterName")
   protected Matrix<N2, N1> getDynamics(Matrix<N2, N1> x, Matrix<N1, N1> u) {
     return Matrix.mat(Nat.N2(), Nat.N2())
         .fill(1.000, 0, 0, 1.000)
@@ -44,7 +41,6 @@
         .plus(VecBuilder.fill(0, 1).times(u));
   }
 
-  @SuppressWarnings("ParameterName")
   protected Matrix<N2, N1> getStateDynamics(Matrix<N2, N1> x) {
     return Matrix.mat(Nat.N2(), Nat.N2()).fill(1.000, 0, 0, 1.000).times(x);
   }
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/controller/DifferentialDriveAccelerationLimiterTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/controller/DifferentialDriveAccelerationLimiterTest.java
new file mode 100644
index 0000000..b23ee1e
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/controller/DifferentialDriveAccelerationLimiterTest.java
@@ -0,0 +1,303 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.math.controller;
+
+import static org.junit.jupiter.api.Assertions.assertDoesNotThrow;
+import static org.junit.jupiter.api.Assertions.assertEquals;
+import static org.junit.jupiter.api.Assertions.assertThrows;
+import static org.junit.jupiter.api.Assertions.assertTrue;
+
+import edu.wpi.first.math.MatBuilder;
+import edu.wpi.first.math.Nat;
+import edu.wpi.first.math.system.plant.LinearSystemId;
+import org.junit.jupiter.api.Test;
+
+class DifferentialDriveAccelerationLimiterTest {
+  @Test
+  void testLowLimits() {
+    final double trackwidth = 0.9;
+    final double dt = 0.005;
+    final double maxA = 2.0;
+    final double maxAlpha = 2.0;
+
+    var plant = LinearSystemId.identifyDrivetrainSystem(1.0, 1.0, 1.0, 1.0);
+
+    var accelLimiter = new DifferentialDriveAccelerationLimiter(plant, trackwidth, maxA, maxAlpha);
+
+    var x = new MatBuilder<>(Nat.N2(), Nat.N1()).fill(0.0, 0.0);
+    var xAccelLimiter = new MatBuilder<>(Nat.N2(), Nat.N1()).fill(0.0, 0.0);
+
+    // Ensure voltage exceeds acceleration before limiting
+    {
+      final var accels =
+          plant
+              .getA()
+              .times(xAccelLimiter)
+              .plus(plant.getB().times(new MatBuilder<>(Nat.N2(), Nat.N1()).fill(12.0, 12.0)));
+      final double a = (accels.get(0, 0) + accels.get(1, 0)) / 2.0;
+      assertTrue(Math.abs(a) > maxA);
+    }
+    {
+      final var accels =
+          plant
+              .getA()
+              .times(xAccelLimiter)
+              .plus(plant.getB().times(new MatBuilder<>(Nat.N2(), Nat.N1()).fill(-12.0, 12.0)));
+      final double alpha = (accels.get(1, 0) - accels.get(0, 0)) / trackwidth;
+      assertTrue(Math.abs(alpha) > maxAlpha);
+    }
+
+    // Forward
+    var u = new MatBuilder<>(Nat.N2(), Nat.N1()).fill(12.0, 12.0);
+    for (double t = 0.0; t < 3.0; t += dt) {
+      x = plant.calculateX(x, u, dt);
+      final var voltages =
+          accelLimiter.calculate(
+              xAccelLimiter.get(0, 0), xAccelLimiter.get(1, 0), u.get(0, 0), u.get(1, 0));
+      xAccelLimiter =
+          plant.calculateX(
+              xAccelLimiter,
+              new MatBuilder<>(Nat.N2(), Nat.N1()).fill(voltages.left, voltages.right),
+              dt);
+
+      final var accels =
+          plant
+              .getA()
+              .times(xAccelLimiter)
+              .plus(
+                  plant
+                      .getB()
+                      .times(
+                          new MatBuilder<>(Nat.N2(), Nat.N1())
+                              .fill(voltages.left, voltages.right)));
+      final double a = (accels.get(0, 0) + accels.get(1, 0)) / 2.0;
+      final double alpha = (accels.get(1, 0) - accels.get(0, 0)) / trackwidth;
+      assertTrue(Math.abs(a) <= maxA);
+      assertTrue(Math.abs(alpha) <= maxAlpha);
+    }
+
+    // Backward
+    u = new MatBuilder<>(Nat.N2(), Nat.N1()).fill(-12.0, -12.0);
+    for (double t = 0.0; t < 3.0; t += dt) {
+      x = plant.calculateX(x, u, dt);
+      final var voltages =
+          accelLimiter.calculate(
+              xAccelLimiter.get(0, 0), xAccelLimiter.get(1, 0), u.get(0, 0), u.get(1, 0));
+      xAccelLimiter =
+          plant.calculateX(
+              xAccelLimiter,
+              new MatBuilder<>(Nat.N2(), Nat.N1()).fill(voltages.left, voltages.right),
+              dt);
+
+      final var accels =
+          plant
+              .getA()
+              .times(xAccelLimiter)
+              .plus(
+                  plant
+                      .getB()
+                      .times(
+                          new MatBuilder<>(Nat.N2(), Nat.N1())
+                              .fill(voltages.left, voltages.right)));
+      final double a = (accels.get(0, 0) + accels.get(1, 0)) / 2.0;
+      final double alpha = (accels.get(1, 0) - accels.get(0, 0)) / trackwidth;
+      assertTrue(Math.abs(a) <= maxA);
+      assertTrue(Math.abs(alpha) <= maxAlpha);
+    }
+
+    // Rotate CCW
+    u = new MatBuilder<>(Nat.N2(), Nat.N1()).fill(-12.0, 12.0);
+    for (double t = 0.0; t < 3.0; t += dt) {
+      x = plant.calculateX(x, u, dt);
+      final var voltages =
+          accelLimiter.calculate(
+              xAccelLimiter.get(0, 0), xAccelLimiter.get(1, 0), u.get(0, 0), u.get(1, 0));
+      xAccelLimiter =
+          plant.calculateX(
+              xAccelLimiter,
+              new MatBuilder<>(Nat.N2(), Nat.N1()).fill(voltages.left, voltages.right),
+              dt);
+
+      final var accels =
+          plant
+              .getA()
+              .times(xAccelLimiter)
+              .plus(
+                  plant
+                      .getB()
+                      .times(
+                          new MatBuilder<>(Nat.N2(), Nat.N1())
+                              .fill(voltages.left, voltages.right)));
+      final double a = (accels.get(0, 0) + accels.get(1, 0)) / 2.0;
+      final double alpha = (accels.get(1, 0) - accels.get(0, 0)) / trackwidth;
+      assertTrue(Math.abs(a) <= maxA);
+      assertTrue(Math.abs(alpha) <= maxAlpha);
+    }
+  }
+
+  @Test
+  void testHighLimits() {
+    final double trackwidth = 0.9;
+    final double dt = 0.005;
+
+    var plant = LinearSystemId.identifyDrivetrainSystem(1.0, 1.0, 1.0, 1.0);
+
+    // Limits are so high, they don't get hit, so states of constrained and
+    // unconstrained systems should match
+    var accelLimiter = new DifferentialDriveAccelerationLimiter(plant, trackwidth, 1e3, 1e3);
+
+    var x = new MatBuilder<>(Nat.N2(), Nat.N1()).fill(0.0, 0.0);
+    var xAccelLimiter = new MatBuilder<>(Nat.N2(), Nat.N1()).fill(0.0, 0.0);
+
+    // Forward
+    var u = new MatBuilder<>(Nat.N2(), Nat.N1()).fill(12.0, 12.0);
+    for (double t = 0.0; t < 3.0; t += dt) {
+      x = plant.calculateX(x, u, dt);
+      final var voltages =
+          accelLimiter.calculate(
+              xAccelLimiter.get(0, 0), xAccelLimiter.get(1, 0), u.get(0, 0), u.get(1, 0));
+      xAccelLimiter =
+          plant.calculateX(
+              xAccelLimiter,
+              new MatBuilder<>(Nat.N2(), Nat.N1()).fill(voltages.left, voltages.right),
+              dt);
+
+      assertEquals(x.get(0, 0), xAccelLimiter.get(0, 0), 1e-5);
+      assertEquals(x.get(1, 0), xAccelLimiter.get(1, 0), 1e-5);
+    }
+
+    // Backward
+    x.fill(0.0);
+    xAccelLimiter.fill(0.0);
+    u = new MatBuilder<>(Nat.N2(), Nat.N1()).fill(-12.0, -12.0);
+    for (double t = 0.0; t < 3.0; t += dt) {
+      x = plant.calculateX(x, u, dt);
+      final var voltages =
+          accelLimiter.calculate(
+              xAccelLimiter.get(0, 0), xAccelLimiter.get(1, 0), u.get(0, 0), u.get(1, 0));
+      xAccelLimiter =
+          plant.calculateX(
+              xAccelLimiter,
+              new MatBuilder<>(Nat.N2(), Nat.N1()).fill(voltages.left, voltages.right),
+              dt);
+
+      assertEquals(x.get(0, 0), xAccelLimiter.get(0, 0), 1e-5);
+      assertEquals(x.get(1, 0), xAccelLimiter.get(1, 0), 1e-5);
+    }
+
+    // Rotate CCW
+    x.fill(0.0);
+    xAccelLimiter.fill(0.0);
+    u = new MatBuilder<>(Nat.N2(), Nat.N1()).fill(-12.0, 12.0);
+    for (double t = 0.0; t < 3.0; t += dt) {
+      x = plant.calculateX(x, u, dt);
+      final var voltages =
+          accelLimiter.calculate(
+              xAccelLimiter.get(0, 0), xAccelLimiter.get(1, 0), u.get(0, 0), u.get(1, 0));
+      xAccelLimiter =
+          plant.calculateX(
+              xAccelLimiter,
+              new MatBuilder<>(Nat.N2(), Nat.N1()).fill(voltages.left, voltages.right),
+              dt);
+
+      assertEquals(x.get(0, 0), xAccelLimiter.get(0, 0), 1e-5);
+      assertEquals(x.get(1, 0), xAccelLimiter.get(1, 0), 1e-5);
+    }
+  }
+
+  @Test
+  void testSeperateMinMaxLowLimits() {
+    final double trackwidth = 0.9;
+    final double dt = 0.005;
+    final double minA = -1.0;
+    final double maxA = 2.0;
+    final double maxAlpha = 2.0;
+
+    var plant = LinearSystemId.identifyDrivetrainSystem(1.0, 1.0, 1.0, 1.0);
+
+    var accelLimiter =
+        new DifferentialDriveAccelerationLimiter(plant, trackwidth, minA, maxA, maxAlpha);
+
+    var x = new MatBuilder<>(Nat.N2(), Nat.N1()).fill(0.0, 0.0);
+    var xAccelLimiter = new MatBuilder<>(Nat.N2(), Nat.N1()).fill(0.0, 0.0);
+
+    // Ensure voltage exceeds acceleration before limiting
+    {
+      final var accels =
+          plant
+              .getA()
+              .times(xAccelLimiter)
+              .plus(plant.getB().times(new MatBuilder<>(Nat.N2(), Nat.N1()).fill(12.0, 12.0)));
+      final double a = (accels.get(0, 0) + accels.get(1, 0)) / 2.0;
+      System.out.println(a);
+      assertTrue(Math.abs(a) > maxA);
+      assertTrue(Math.abs(a) > -minA);
+    }
+
+    // a should always be within [minA, maxA]
+    // Forward
+    var u = new MatBuilder<>(Nat.N2(), Nat.N1()).fill(12.0, 12.0);
+    for (double t = 0.0; t < 3.0; t += dt) {
+      x = plant.calculateX(x, u, dt);
+      final var voltages =
+          accelLimiter.calculate(
+              xAccelLimiter.get(0, 0), xAccelLimiter.get(1, 0), u.get(0, 0), u.get(1, 0));
+      xAccelLimiter =
+          plant.calculateX(
+              xAccelLimiter,
+              new MatBuilder<>(Nat.N2(), Nat.N1()).fill(voltages.left, voltages.right),
+              dt);
+
+      final var accels =
+          plant
+              .getA()
+              .times(xAccelLimiter)
+              .plus(
+                  plant
+                      .getB()
+                      .times(
+                          new MatBuilder<>(Nat.N2(), Nat.N1())
+                              .fill(voltages.left, voltages.right)));
+      final double a = (accels.get(0, 0) + accels.get(1, 0)) / 2.0;
+      assertTrue(minA <= a && a <= maxA);
+    }
+
+    // Backward
+    u = new MatBuilder<>(Nat.N2(), Nat.N1()).fill(-12.0, -12.0);
+    for (double t = 0.0; t < 3.0; t += dt) {
+      x = plant.calculateX(x, u, dt);
+      final var voltages =
+          accelLimiter.calculate(
+              xAccelLimiter.get(0, 0), xAccelLimiter.get(1, 0), u.get(0, 0), u.get(1, 0));
+      xAccelLimiter =
+          plant.calculateX(
+              xAccelLimiter,
+              new MatBuilder<>(Nat.N2(), Nat.N1()).fill(voltages.left, voltages.right),
+              dt);
+
+      final var accels =
+          plant
+              .getA()
+              .times(xAccelLimiter)
+              .plus(
+                  plant
+                      .getB()
+                      .times(
+                          new MatBuilder<>(Nat.N2(), Nat.N1())
+                              .fill(voltages.left, voltages.right)));
+      final double a = (accels.get(0, 0) + accels.get(1, 0)) / 2.0;
+      assertTrue(minA <= a && a <= maxA);
+    }
+  }
+
+  @Test
+  void testMinAccelGreaterThanMaxAccel() {
+    var plant = LinearSystemId.identifyDrivetrainSystem(1.0, 1.0, 1.0, 1.0);
+    assertDoesNotThrow(() -> new DifferentialDriveAccelerationLimiter(plant, 1, -1, 1, 1e3));
+    assertThrows(
+        IllegalArgumentException.class,
+        () -> new DifferentialDriveAccelerationLimiter(plant, 1, 1, -1, 1e3));
+  }
+}
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/controller/DifferentialDriveFeedforwardTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/controller/DifferentialDriveFeedforwardTest.java
new file mode 100644
index 0000000..fdf53ea
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/controller/DifferentialDriveFeedforwardTest.java
@@ -0,0 +1,85 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.math.controller;
+
+import static org.junit.jupiter.api.Assertions.assertEquals;
+
+import edu.wpi.first.math.Matrix;
+import edu.wpi.first.math.VecBuilder;
+import edu.wpi.first.math.numbers.N1;
+import edu.wpi.first.math.numbers.N2;
+import edu.wpi.first.math.system.LinearSystem;
+import edu.wpi.first.math.system.plant.LinearSystemId;
+import org.junit.jupiter.api.Test;
+
+class DifferentialDriveFeedforwardTest {
+  private static final double kVLinear = 1.0;
+  private static final double kALinear = 1.0;
+  private static final double kVAngular = 1.0;
+  private static final double kAAngular = 1.0;
+  private static final double trackwidth = 1.0;
+  private static final double dtSeconds = 0.02;
+
+  @Test
+  void testCalculateWithTrackwidth() {
+    DifferentialDriveFeedforward differentialDriveFeedforward =
+        new DifferentialDriveFeedforward(kVLinear, kALinear, kVAngular, kAAngular, trackwidth);
+    LinearSystem<N2, N2, N2> plant =
+        LinearSystemId.identifyDrivetrainSystem(
+            kVLinear, kALinear, kVAngular, kAAngular, trackwidth);
+    for (int currentLeftVelocity = -4; currentLeftVelocity <= 4; currentLeftVelocity += 2) {
+      for (int currentRightVelocity = -4; currentRightVelocity <= 4; currentRightVelocity += 2) {
+        for (int nextLeftVelocity = -4; nextLeftVelocity <= 4; nextLeftVelocity += 2) {
+          for (int nextRightVelocity = -4; nextRightVelocity <= 4; nextRightVelocity += 2) {
+            DifferentialDriveWheelVoltages u =
+                differentialDriveFeedforward.calculate(
+                    currentLeftVelocity,
+                    nextLeftVelocity,
+                    currentRightVelocity,
+                    nextRightVelocity,
+                    dtSeconds);
+            Matrix<N2, N1> nextX =
+                plant.calculateX(
+                    VecBuilder.fill(currentLeftVelocity, currentRightVelocity),
+                    VecBuilder.fill(u.left, u.right),
+                    dtSeconds);
+            assertEquals(nextX.get(0, 0), nextLeftVelocity, 1e-6);
+            assertEquals(nextX.get(1, 0), nextRightVelocity, 1e-6);
+          }
+        }
+      }
+    }
+  }
+
+  @Test
+  void testCalculateWithoutTrackwidth() {
+    DifferentialDriveFeedforward differentialDriveFeedforward =
+        new DifferentialDriveFeedforward(kVLinear, kALinear, kVAngular, kAAngular);
+    LinearSystem<N2, N2, N2> plant =
+        LinearSystemId.identifyDrivetrainSystem(kVLinear, kALinear, kVAngular, kAAngular);
+    for (int currentLeftVelocity = -4; currentLeftVelocity <= 4; currentLeftVelocity += 2) {
+      for (int currentRightVelocity = -4; currentRightVelocity <= 4; currentRightVelocity += 2) {
+        for (int nextLeftVelocity = -4; nextLeftVelocity <= 4; nextLeftVelocity += 2) {
+          for (int nextRightVelocity = -4; nextRightVelocity <= 4; nextRightVelocity += 2) {
+            DifferentialDriveWheelVoltages u =
+                differentialDriveFeedforward.calculate(
+                    currentLeftVelocity,
+                    nextLeftVelocity,
+                    currentRightVelocity,
+                    nextRightVelocity,
+                    dtSeconds);
+            Matrix<N2, N1> nextX =
+                plant.calculateX(
+                    VecBuilder.fill(currentLeftVelocity, currentRightVelocity),
+                    VecBuilder.fill(u.left, u.right),
+                    dtSeconds);
+            assertEquals(nextX.get(0, 0), nextLeftVelocity, 1e-6);
+            assertEquals(nextX.get(1, 0), nextRightVelocity, 1e-6);
+          }
+        }
+      }
+    }
+  }
+}
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/controller/ImplicitModelFollowerTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/controller/ImplicitModelFollowerTest.java
new file mode 100644
index 0000000..674cba3
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/controller/ImplicitModelFollowerTest.java
@@ -0,0 +1,107 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.math.controller;
+
+import static org.junit.jupiter.api.Assertions.assertEquals;
+import static org.junit.jupiter.api.Assertions.assertTrue;
+
+import edu.wpi.first.math.MatBuilder;
+import edu.wpi.first.math.Nat;
+import edu.wpi.first.math.numbers.N2;
+import edu.wpi.first.math.system.plant.LinearSystemId;
+import org.junit.jupiter.api.Test;
+
+class ImplicitModelFollowerTest {
+  @Test
+  void testSameModel() {
+    final double dt = 0.005;
+
+    var plant = LinearSystemId.identifyDrivetrainSystem(1.0, 1.0, 1.0, 1.0);
+
+    var imf = new ImplicitModelFollower<N2, N2, N2>(plant, plant);
+
+    var x = new MatBuilder<>(Nat.N2(), Nat.N1()).fill(0.0, 0.0);
+    var xImf = new MatBuilder<>(Nat.N2(), Nat.N1()).fill(0.0, 0.0);
+
+    // Forward
+    var u = new MatBuilder<>(Nat.N2(), Nat.N1()).fill(12.0, 12.0);
+    for (double t = 0.0; t < 3.0; t += dt) {
+      x = plant.calculateX(x, u, dt);
+      xImf = plant.calculateX(xImf, imf.calculate(xImf, u), dt);
+
+      assertEquals(x.get(0, 0), xImf.get(0, 0));
+      assertEquals(x.get(1, 0), xImf.get(1, 0));
+    }
+
+    // Backward
+    u = new MatBuilder<>(Nat.N2(), Nat.N1()).fill(-12.0, -12.0);
+    for (double t = 0.0; t < 3.0; t += dt) {
+      x = plant.calculateX(x, u, dt);
+      xImf = plant.calculateX(xImf, imf.calculate(xImf, u), dt);
+
+      assertEquals(x.get(0, 0), xImf.get(0, 0));
+      assertEquals(x.get(1, 0), xImf.get(1, 0));
+    }
+
+    // Rotate CCW
+    u = new MatBuilder<>(Nat.N2(), Nat.N1()).fill(-12.0, 12.0);
+    for (double t = 0.0; t < 3.0; t += dt) {
+      x = plant.calculateX(x, u, dt);
+      xImf = plant.calculateX(xImf, imf.calculate(xImf, u), dt);
+
+      assertEquals(x.get(0, 0), xImf.get(0, 0));
+      assertEquals(x.get(1, 0), xImf.get(1, 0));
+    }
+  }
+
+  @Test
+  void testSlowerRefModel() {
+    final double dt = 0.005;
+
+    var plant = LinearSystemId.identifyDrivetrainSystem(1.0, 1.0, 1.0, 1.0);
+
+    // Linear acceleration is slower, but angular acceleration is the same
+    var plantRef = LinearSystemId.identifyDrivetrainSystem(1.0, 2.0, 1.0, 1.0);
+
+    var imf = new ImplicitModelFollower<N2, N2, N2>(plant, plantRef);
+
+    var x = new MatBuilder<>(Nat.N2(), Nat.N1()).fill(0.0, 0.0);
+    var xImf = new MatBuilder<>(Nat.N2(), Nat.N1()).fill(0.0, 0.0);
+
+    // Forward
+    var u = new MatBuilder<>(Nat.N2(), Nat.N1()).fill(12.0, 12.0);
+    for (double t = 0.0; t < 3.0; t += dt) {
+      x = plant.calculateX(x, u, dt);
+      xImf = plant.calculateX(xImf, imf.calculate(xImf, u), dt);
+
+      assertTrue(x.get(0, 0) >= xImf.get(0, 0));
+      assertTrue(x.get(1, 0) >= xImf.get(1, 0));
+    }
+
+    // Backward
+    x.fill(0.0);
+    xImf.fill(0.0);
+    u = new MatBuilder<>(Nat.N2(), Nat.N1()).fill(-12.0, -12.0);
+    for (double t = 0.0; t < 3.0; t += dt) {
+      x = plant.calculateX(x, u, dt);
+      xImf = plant.calculateX(xImf, imf.calculate(xImf, u), dt);
+
+      assertTrue(x.get(0, 0) <= xImf.get(0, 0));
+      assertTrue(x.get(1, 0) <= xImf.get(1, 0));
+    }
+
+    // Rotate CCW
+    x.fill(0.0);
+    xImf.fill(0.0);
+    u = new MatBuilder<>(Nat.N2(), Nat.N1()).fill(-12.0, 12.0);
+    for (double t = 0.0; t < 3.0; t += dt) {
+      x = plant.calculateX(x, u, dt);
+      xImf = plant.calculateX(xImf, imf.calculate(xImf, u), dt);
+
+      assertEquals(x.get(0, 0), xImf.get(0, 0), 1e-5);
+      assertEquals(x.get(1, 0), xImf.get(1, 0), 1e-5);
+    }
+  }
+}
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/controller/LTVDifferentialDriveControllerTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/controller/LTVDifferentialDriveControllerTest.java
new file mode 100644
index 0000000..efb9c5e
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/controller/LTVDifferentialDriveControllerTest.java
@@ -0,0 +1,128 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.math.controller;
+
+import static org.junit.jupiter.api.Assertions.assertAll;
+import static org.junit.jupiter.api.Assertions.assertEquals;
+
+import edu.wpi.first.math.MatBuilder;
+import edu.wpi.first.math.MathUtil;
+import edu.wpi.first.math.Matrix;
+import edu.wpi.first.math.Nat;
+import edu.wpi.first.math.VecBuilder;
+import edu.wpi.first.math.geometry.Pose2d;
+import edu.wpi.first.math.geometry.Rotation2d;
+import edu.wpi.first.math.numbers.N1;
+import edu.wpi.first.math.numbers.N2;
+import edu.wpi.first.math.numbers.N5;
+import edu.wpi.first.math.system.LinearSystem;
+import edu.wpi.first.math.system.NumericalIntegration;
+import edu.wpi.first.math.system.plant.LinearSystemId;
+import edu.wpi.first.math.trajectory.TrajectoryConfig;
+import edu.wpi.first.math.trajectory.TrajectoryGenerator;
+import java.util.ArrayList;
+import org.junit.jupiter.api.Test;
+
+class LTVDifferentialDriveControllerTest {
+  private static final double kTolerance = 1 / 12.0;
+  private static final double kAngularTolerance = Math.toRadians(2);
+
+  /** States of the drivetrain system. */
+  static class State {
+    /// X position in global coordinate frame.
+    public static final int kX = 0;
+
+    /// Y position in global coordinate frame.
+    public static final int kY = 1;
+
+    /// Heading in global coordinate frame.
+    public static final int kHeading = 2;
+
+    /// Left encoder velocity.
+    public static final int kLeftVelocity = 3;
+
+    /// Right encoder velocity.
+    public static final int kRightVelocity = 4;
+  }
+
+  private static final double kLinearV = 3.02; // V/(m/s)
+  private static final double kLinearA = 0.642; // V/(m/s²)
+  private static final double kAngularV = 1.382; // V/(m/s)
+  private static final double kAngularA = 0.08495; // V/(m/s²)
+  private static final LinearSystem<N2, N2, N2> plant =
+      LinearSystemId.identifyDrivetrainSystem(kLinearV, kLinearA, kAngularV, kAngularA);
+  private static final double kTrackwidth = 0.9;
+
+  private static Matrix<N5, N1> dynamics(Matrix<N5, N1> x, Matrix<N2, N1> u) {
+    double v = (x.get(State.kLeftVelocity, 0) + x.get(State.kRightVelocity, 0)) / 2.0;
+
+    var xdot = new Matrix<>(Nat.N5(), Nat.N1());
+    xdot.set(0, 0, v * Math.cos(x.get(State.kHeading, 0)));
+    xdot.set(1, 0, v * Math.sin(x.get(State.kHeading, 0)));
+    xdot.set(2, 0, (x.get(State.kRightVelocity, 0) - x.get(State.kLeftVelocity, 0)) / kTrackwidth);
+    xdot.assignBlock(
+        3, 0, plant.getA().times(x.block(Nat.N2(), Nat.N1(), 3, 0)).plus(plant.getB().times(u)));
+    return xdot;
+  }
+
+  @Test
+  void testReachesReference() {
+    final double kDt = 0.02;
+
+    final var controller =
+        new LTVDifferentialDriveController(
+            plant,
+            kTrackwidth,
+            VecBuilder.fill(0.0625, 0.125, 2.5, 0.95, 0.95),
+            VecBuilder.fill(12.0, 12.0),
+            kDt);
+    var robotPose = new Pose2d(2.7, 23.0, Rotation2d.fromDegrees(0.0));
+
+    final var waypoints = new ArrayList<Pose2d>();
+    waypoints.add(new Pose2d(2.75, 22.521, new Rotation2d(0)));
+    waypoints.add(new Pose2d(24.73, 19.68, new Rotation2d(5.846)));
+    var config = new TrajectoryConfig(8.8, 0.1);
+    final var trajectory = TrajectoryGenerator.generateTrajectory(waypoints, config);
+
+    var x =
+        new MatBuilder<>(Nat.N5(), Nat.N1())
+            .fill(
+                robotPose.getX(), robotPose.getY(), robotPose.getRotation().getRadians(), 0.0, 0.0);
+
+    final var totalTime = trajectory.getTotalTimeSeconds();
+    for (int i = 0; i < (totalTime / kDt); ++i) {
+      var state = trajectory.sample(kDt * i);
+      robotPose =
+          new Pose2d(
+              x.get(State.kX, 0), x.get(State.kY, 0), new Rotation2d(x.get(State.kHeading, 0)));
+      final var output =
+          controller.calculate(
+              robotPose, x.get(State.kLeftVelocity, 0), x.get(State.kRightVelocity, 0), state);
+
+      x =
+          NumericalIntegration.rkdp(
+              LTVDifferentialDriveControllerTest::dynamics,
+              x,
+              new MatBuilder<>(Nat.N2(), Nat.N1()).fill(output.left, output.right),
+              kDt);
+    }
+
+    final var states = trajectory.getStates();
+    final var endPose = states.get(states.size() - 1).poseMeters;
+
+    // Java lambdas require local variables referenced from a lambda expression
+    // must be final or effectively final.
+    final var finalRobotPose = robotPose;
+    assertAll(
+        () -> assertEquals(endPose.getX(), finalRobotPose.getX(), kTolerance),
+        () -> assertEquals(endPose.getY(), finalRobotPose.getY(), kTolerance),
+        () ->
+            assertEquals(
+                0.0,
+                MathUtil.angleModulus(
+                    endPose.getRotation().getRadians() - finalRobotPose.getRotation().getRadians()),
+                kAngularTolerance));
+  }
+}
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/controller/LTVUnicycleControllerTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/controller/LTVUnicycleControllerTest.java
new file mode 100644
index 0000000..463e1ce
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/controller/LTVUnicycleControllerTest.java
@@ -0,0 +1,65 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.math.controller;
+
+import static org.junit.jupiter.api.Assertions.assertAll;
+import static org.junit.jupiter.api.Assertions.assertEquals;
+
+import edu.wpi.first.math.MathUtil;
+import edu.wpi.first.math.VecBuilder;
+import edu.wpi.first.math.geometry.Pose2d;
+import edu.wpi.first.math.geometry.Rotation2d;
+import edu.wpi.first.math.geometry.Twist2d;
+import edu.wpi.first.math.trajectory.TrajectoryConfig;
+import edu.wpi.first.math.trajectory.TrajectoryGenerator;
+import java.util.ArrayList;
+import org.junit.jupiter.api.Test;
+
+class LTVUnicycleControllerTest {
+  private static final double kTolerance = 1 / 12.0;
+  private static final double kAngularTolerance = Math.toRadians(2);
+
+  @Test
+  void testReachesReference() {
+    final double kDt = 0.02;
+
+    final var controller =
+        new LTVUnicycleController(
+            VecBuilder.fill(0.0625, 0.125, 2.5), VecBuilder.fill(4.0, 4.0), kDt);
+    var robotPose = new Pose2d(2.7, 23.0, Rotation2d.fromDegrees(0.0));
+
+    final var waypoints = new ArrayList<Pose2d>();
+    waypoints.add(new Pose2d(2.75, 22.521, new Rotation2d(0)));
+    waypoints.add(new Pose2d(24.73, 19.68, new Rotation2d(5.846)));
+    var config = new TrajectoryConfig(8.8, 0.1);
+    final var trajectory = TrajectoryGenerator.generateTrajectory(waypoints, config);
+
+    final var totalTime = trajectory.getTotalTimeSeconds();
+    for (int i = 0; i < (totalTime / kDt); ++i) {
+      var state = trajectory.sample(kDt * i);
+
+      var output = controller.calculate(robotPose, state);
+      robotPose =
+          robotPose.exp(
+              new Twist2d(output.vxMetersPerSecond * kDt, 0, output.omegaRadiansPerSecond * kDt));
+    }
+
+    final var states = trajectory.getStates();
+    final var endPose = states.get(states.size() - 1).poseMeters;
+
+    // Java lambdas require local variables referenced from a lambda expression
+    // must be final or effectively final.
+    final var finalRobotPose = robotPose;
+    assertAll(
+        () -> assertEquals(endPose.getX(), finalRobotPose.getX(), kTolerance),
+        () -> assertEquals(endPose.getY(), finalRobotPose.getY(), kTolerance),
+        () ->
+            assertEquals(
+                0.0,
+                MathUtil.angleModulus(
+                    endPose.getRotation().getRadians() - finalRobotPose.getRotation().getRadians()),
+                kAngularTolerance));
+  }
+}
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/controller/LinearPlantInversionFeedforwardTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/controller/LinearPlantInversionFeedforwardTest.java
index 98b0e6c..1aba6d7 100644
--- a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/controller/LinearPlantInversionFeedforwardTest.java
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/controller/LinearPlantInversionFeedforwardTest.java
@@ -14,7 +14,6 @@
 import org.junit.jupiter.api.Test;
 
 class LinearPlantInversionFeedforwardTest {
-  @SuppressWarnings("LocalVariableName")
   @Test
   void testCalculate() {
     Matrix<N2, N2> A = Matrix.mat(Nat.N2(), Nat.N2()).fill(1, 0, 0, 1);
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/controller/LinearQuadraticRegulatorTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/controller/LinearQuadraticRegulatorTest.java
index 93b89c8..31213f6 100644
--- a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/controller/LinearQuadraticRegulatorTest.java
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/controller/LinearQuadraticRegulatorTest.java
@@ -17,7 +17,6 @@
 
 class LinearQuadraticRegulatorTest {
   @Test
-  @SuppressWarnings("LocalVariableName")
   void testLQROnElevator() {
     var motors = DCMotor.getVex775Pro(2);
 
@@ -38,7 +37,6 @@
   }
 
   @Test
-  @SuppressWarnings("LocalVariableName")
   void testFourMotorElevator() {
     var dt = 0.020;
 
@@ -55,7 +53,6 @@
   }
 
   @Test
-  @SuppressWarnings("LocalVariableName")
   void testLQROnArm() {
     var motors = DCMotor.getVex775Pro(2);
 
@@ -89,7 +86,6 @@
    * @param Aref Desired state matrix.
    * @param dtSeconds Discretization timestep in seconds.
    */
-  @SuppressWarnings({"LocalVariableName", "MethodTypeParameterName", "ParameterName"})
   <States extends Num, Inputs extends Num> Matrix<Inputs, States> getImplicitModelFollowingK(
       Matrix<States, States> A,
       Matrix<States, Inputs> B,
@@ -114,7 +110,6 @@
   }
 
   @Test
-  @SuppressWarnings("LocalVariableName")
   void testMatrixOverloadsWithSingleIntegrator() {
     var A = Matrix.mat(Nat.N2(), Nat.N2()).fill(0, 0, 0, 0);
     var B = Matrix.mat(Nat.N2(), Nat.N2()).fill(1, 0, 0, 1);
@@ -138,7 +133,6 @@
   }
 
   @Test
-  @SuppressWarnings("LocalVariableName")
   void testMatrixOverloadsWithDoubleIntegrator() {
     double Kv = 3.02;
     double Ka = 0.642;
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/controller/LinearSystemLoopTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/controller/LinearSystemLoopTest.java
index 5fa4939..7b8484d 100644
--- a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/controller/LinearSystemLoopTest.java
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/controller/LinearSystemLoopTest.java
@@ -40,7 +40,6 @@
   private final LinearSystemLoop<N2, N1, N1> m_loop =
       new LinearSystemLoop<>(m_plant, m_controller, m_observer, 12, 0.00505);
 
-  @SuppressWarnings("LocalVariableName")
   private static void updateTwoState(
       LinearSystem<N2, N1, N1> plant, LinearSystemLoop<N2, N1, N1> loop, double noise) {
     Matrix<N1, N1> y = plant.calculateY(loop.getXHat(), loop.getU()).plus(VecBuilder.fill(noise));
@@ -50,7 +49,6 @@
   }
 
   @Test
-  @SuppressWarnings("LocalVariableName")
   void testStateSpaceEnabled() {
     m_loop.reset(VecBuilder.fill(0, 0));
     Matrix<N2, N1> references = VecBuilder.fill(2.0, 0.0);
@@ -79,7 +77,6 @@
   }
 
   @Test
-  @SuppressWarnings("LocalVariableName")
   void testFlywheelEnabled() {
     LinearSystem<N1, N1, N1> plant =
         LinearSystemId.createFlywheelSystem(DCMotor.getNEO(2), 0.00289, 1.0);
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/controller/SimpleMotorFeedforwardTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/controller/SimpleMotorFeedforwardTest.java
index 83fced2..fd4e428 100644
--- a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/controller/SimpleMotorFeedforwardTest.java
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/controller/SimpleMotorFeedforwardTest.java
@@ -13,7 +13,6 @@
 import org.junit.jupiter.api.Test;
 
 class SimpleMotorFeedforwardTest {
-  @SuppressWarnings("LocalVariableName")
   @Test
   void testCalculate() {
     double Ks = 0.5;
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/estimator/DifferentialDrivePoseEstimatorTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/estimator/DifferentialDrivePoseEstimatorTest.java
index 78908e4..c3906d4 100644
--- a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/estimator/DifferentialDrivePoseEstimatorTest.java
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/estimator/DifferentialDrivePoseEstimatorTest.java
@@ -6,34 +6,37 @@
 
 import static org.junit.jupiter.api.Assertions.assertEquals;
 
-import edu.wpi.first.math.MatBuilder;
-import edu.wpi.first.math.Nat;
+import edu.wpi.first.math.VecBuilder;
 import edu.wpi.first.math.geometry.Pose2d;
 import edu.wpi.first.math.geometry.Rotation2d;
+import edu.wpi.first.math.geometry.Transform2d;
 import edu.wpi.first.math.geometry.Translation2d;
 import edu.wpi.first.math.kinematics.ChassisSpeeds;
 import edu.wpi.first.math.kinematics.DifferentialDriveKinematics;
-import edu.wpi.first.math.kinematics.DifferentialDriveWheelSpeeds;
 import edu.wpi.first.math.trajectory.Trajectory;
 import edu.wpi.first.math.trajectory.TrajectoryConfig;
 import edu.wpi.first.math.trajectory.TrajectoryGenerator;
 import java.util.List;
 import java.util.Random;
+import java.util.TreeMap;
+import java.util.function.Function;
 import org.junit.jupiter.api.Test;
 
 class DifferentialDrivePoseEstimatorTest {
-  @SuppressWarnings("LocalVariableName")
   @Test
   void testAccuracy() {
+    var kinematics = new DifferentialDriveKinematics(1);
+
     var estimator =
         new DifferentialDrivePoseEstimator(
+            kinematics,
             new Rotation2d(),
+            0,
+            0,
             new Pose2d(),
-            new MatBuilder<>(Nat.N5(), Nat.N1()).fill(0.02, 0.02, 0.01, 0.02, 0.02),
-            new MatBuilder<>(Nat.N3(), Nat.N1()).fill(0.01, 0.01, 0.001),
-            new MatBuilder<>(Nat.N3(), Nat.N1()).fill(0.1, 0.1, 0.01));
-
-    var traj =
+            VecBuilder.fill(0.02, 0.02, 0.01),
+            VecBuilder.fill(0.1, 0.1, 0.1));
+    var trajectory =
         TrajectoryGenerator.generateTrajectory(
             List.of(
                 new Pose2d(0, 0, Rotation2d.fromDegrees(45)),
@@ -41,67 +44,165 @@
                 new Pose2d(0, 0, Rotation2d.fromDegrees(135)),
                 new Pose2d(-3, 0, Rotation2d.fromDegrees(-90)),
                 new Pose2d(0, 0, Rotation2d.fromDegrees(45))),
-            new TrajectoryConfig(10, 5));
+            new TrajectoryConfig(2, 2));
 
+    testFollowTrajectory(
+        kinematics,
+        estimator,
+        trajectory,
+        state ->
+            new ChassisSpeeds(
+                state.velocityMetersPerSecond,
+                0,
+                state.velocityMetersPerSecond * state.curvatureRadPerMeter),
+        state -> state.poseMeters,
+        trajectory.getInitialPose(),
+        new Pose2d(0, 0, Rotation2d.fromDegrees(45)),
+        0.02,
+        0.1,
+        0.25,
+        true);
+  }
+
+  @Test
+  void testBadInitialPose() {
     var kinematics = new DifferentialDriveKinematics(1);
-    var rand = new Random(4915);
 
-    final double dt = 0.02;
+    var estimator =
+        new DifferentialDrivePoseEstimator(
+            kinematics,
+            new Rotation2d(),
+            0,
+            0,
+            new Pose2d(),
+            VecBuilder.fill(0.02, 0.02, 0.01),
+            VecBuilder.fill(0.1, 0.1, 0.1));
+
+    var trajectory =
+        TrajectoryGenerator.generateTrajectory(
+            List.of(
+                new Pose2d(0, 0, Rotation2d.fromDegrees(45)),
+                new Pose2d(3, 0, Rotation2d.fromDegrees(-90)),
+                new Pose2d(0, 0, Rotation2d.fromDegrees(135)),
+                new Pose2d(-3, 0, Rotation2d.fromDegrees(-90)),
+                new Pose2d(0, 0, Rotation2d.fromDegrees(45))),
+            new TrajectoryConfig(2, 2));
+
+    for (int offset_direction_degs = 0; offset_direction_degs < 360; offset_direction_degs += 45) {
+      for (int offset_heading_degs = 0; offset_heading_degs < 360; offset_heading_degs += 45) {
+        var pose_offset = Rotation2d.fromDegrees(offset_direction_degs);
+        var heading_offset = Rotation2d.fromDegrees(offset_heading_degs);
+
+        var initial_pose =
+            trajectory
+                .getInitialPose()
+                .plus(
+                    new Transform2d(
+                        new Translation2d(pose_offset.getCos(), pose_offset.getSin()),
+                        heading_offset));
+
+        testFollowTrajectory(
+            kinematics,
+            estimator,
+            trajectory,
+            state ->
+                new ChassisSpeeds(
+                    state.velocityMetersPerSecond,
+                    0,
+                    state.velocityMetersPerSecond * state.curvatureRadPerMeter),
+            state -> state.poseMeters,
+            initial_pose,
+            new Pose2d(0, 0, Rotation2d.fromDegrees(45)),
+            0.02,
+            0.1,
+            0.25,
+            false);
+      }
+    }
+  }
+
+  void testFollowTrajectory(
+      final DifferentialDriveKinematics kinematics,
+      final DifferentialDrivePoseEstimator estimator,
+      final Trajectory trajectory,
+      final Function<Trajectory.State, ChassisSpeeds> chassisSpeedsGenerator,
+      final Function<Trajectory.State, Pose2d> visionMeasurementGenerator,
+      final Pose2d startingPose,
+      final Pose2d endingPose,
+      final double dt,
+      final double visionUpdateRate,
+      final double visionUpdateDelay,
+      final boolean checkError) {
+    double leftDistanceMeters = 0;
+    double rightDistanceMeters = 0;
+
+    estimator.resetPosition(
+        new Rotation2d(), leftDistanceMeters, rightDistanceMeters, startingPose);
+
+    var rand = new Random(3538);
+
     double t = 0.0;
 
-    final double visionUpdateRate = 0.1;
-    Pose2d lastVisionPose = null;
-    double lastVisionUpdateTime = Double.NEGATIVE_INFINITY;
+    System.out.print("time, est_x, est_y, est_theta, true_x, true_y, true_theta\n");
 
-    double distanceLeft = 0.0;
-    double distanceRight = 0.0;
+    final TreeMap<Double, Pose2d> visionUpdateQueue = new TreeMap<>();
 
     double maxError = Double.NEGATIVE_INFINITY;
     double errorSum = 0;
-    Trajectory.State groundtruthState;
-    DifferentialDriveWheelSpeeds input;
-    while (t <= traj.getTotalTimeSeconds()) {
-      groundtruthState = traj.sample(t);
-      input =
-          kinematics.toWheelSpeeds(
-              new ChassisSpeeds(
-                  groundtruthState.velocityMetersPerSecond,
-                  0.0,
-                  // ds/dt * dtheta/ds = dtheta/dt
-                  groundtruthState.velocityMetersPerSecond
-                      * groundtruthState.curvatureRadPerMeter));
+    while (t <= trajectory.getTotalTimeSeconds()) {
+      var groundTruthState = trajectory.sample(t);
 
-      if (lastVisionUpdateTime + visionUpdateRate + rand.nextGaussian() * 0.4 < t) {
-        if (lastVisionPose != null) {
-          estimator.addVisionMeasurement(lastVisionPose, lastVisionUpdateTime);
-        }
-        var groundPose = groundtruthState.poseMeters;
-        lastVisionPose =
-            new Pose2d(
-                new Translation2d(
-                    groundPose.getTranslation().getX() + rand.nextGaussian() * 0.1,
-                    groundPose.getTranslation().getY() + rand.nextGaussian() * 0.1),
-                new Rotation2d(rand.nextGaussian() * 0.01).plus(groundPose.getRotation()));
-        lastVisionUpdateTime = t;
+      // We are due for a new vision measurement if it's been `visionUpdateRate` seconds since the
+      // last vision measurement
+      if (visionUpdateQueue.isEmpty() || visionUpdateQueue.lastKey() + visionUpdateRate < t) {
+        Pose2d newVisionPose =
+            visionMeasurementGenerator
+                .apply(groundTruthState)
+                .plus(
+                    new Transform2d(
+                        new Translation2d(rand.nextGaussian() * 0.1, rand.nextGaussian() * 0.1),
+                        new Rotation2d(rand.nextGaussian() * 0.05)));
+
+        visionUpdateQueue.put(t, newVisionPose);
       }
 
-      input.leftMetersPerSecond += rand.nextGaussian() * 0.01;
-      input.rightMetersPerSecond += rand.nextGaussian() * 0.01;
+      // We should apply the oldest vision measurement if it has been `visionUpdateDelay` seconds
+      // since it was measured
+      if (!visionUpdateQueue.isEmpty() && visionUpdateQueue.firstKey() + visionUpdateDelay < t) {
+        var visionEntry = visionUpdateQueue.pollFirstEntry();
+        estimator.addVisionMeasurement(visionEntry.getValue(), visionEntry.getKey());
+      }
 
-      distanceLeft += input.leftMetersPerSecond * dt;
-      distanceRight += input.rightMetersPerSecond * dt;
+      var chassisSpeeds = chassisSpeedsGenerator.apply(groundTruthState);
 
-      var rotNoise = new Rotation2d(rand.nextGaussian() * 0.001);
+      var wheelSpeeds = kinematics.toWheelSpeeds(chassisSpeeds);
+
+      leftDistanceMeters += wheelSpeeds.leftMetersPerSecond * dt;
+      rightDistanceMeters += wheelSpeeds.rightMetersPerSecond * dt;
+
       var xHat =
           estimator.updateWithTime(
               t,
-              groundtruthState.poseMeters.getRotation().plus(rotNoise),
-              input,
-              distanceLeft,
-              distanceRight);
+              groundTruthState
+                  .poseMeters
+                  .getRotation()
+                  .plus(new Rotation2d(rand.nextGaussian() * 0.05))
+                  .minus(trajectory.getInitialPose().getRotation()),
+              leftDistanceMeters,
+              rightDistanceMeters);
+
+      System.out.printf(
+          "%f, %f, %f, %f, %f, %f, %f\n",
+          t,
+          xHat.getX(),
+          xHat.getY(),
+          xHat.getRotation().getRadians(),
+          groundTruthState.poseMeters.getX(),
+          groundTruthState.poseMeters.getY(),
+          groundTruthState.poseMeters.getRotation().getRadians());
 
       double error =
-          groundtruthState.poseMeters.getTranslation().getDistance(xHat.getTranslation());
+          groundTruthState.poseMeters.getTranslation().getDistance(xHat.getTranslation());
       if (error > maxError) {
         maxError = error;
       }
@@ -110,7 +211,20 @@
       t += dt;
     }
 
-    assertEquals(0.0, errorSum / (traj.getTotalTimeSeconds() / dt), 0.035, "Incorrect mean error");
-    assertEquals(0.0, maxError, 0.055, "Incorrect max error");
+    assertEquals(
+        endingPose.getX(), estimator.getEstimatedPosition().getX(), 0.08, "Incorrect Final X");
+    assertEquals(
+        endingPose.getY(), estimator.getEstimatedPosition().getY(), 0.08, "Incorrect Final Y");
+    assertEquals(
+        endingPose.getRotation().getRadians(),
+        estimator.getEstimatedPosition().getRotation().getRadians(),
+        0.15,
+        "Incorrect Final Theta");
+
+    if (checkError) {
+      assertEquals(
+          0.0, errorSum / (trajectory.getTotalTimeSeconds() / dt), 0.07, "Incorrect mean error");
+      assertEquals(0.0, maxError, 0.2, "Incorrect max error");
+    }
   }
 }
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/estimator/ExtendedKalmanFilterTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/estimator/ExtendedKalmanFilterTest.java
index 5b07ebc..112ef90 100644
--- a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/estimator/ExtendedKalmanFilterTest.java
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/estimator/ExtendedKalmanFilterTest.java
@@ -26,7 +26,6 @@
 import java.util.List;
 import org.junit.jupiter.api.Test;
 
-@SuppressWarnings("ParameterName")
 class ExtendedKalmanFilterTest {
   private static Matrix<N5, N1> getDynamics(final Matrix<N5, N1> x, final Matrix<N2, N1> u) {
     final var motors = DCMotor.getCIM(2);
@@ -68,7 +67,6 @@
     return VecBuilder.fill(x.get(0, 0), x.get(1, 0), x.get(2, 0), x.get(3, 0), x.get(4, 0));
   }
 
-  @SuppressWarnings("LocalVariableName")
   @Test
   void testInit() {
     double dtSeconds = 0.00505;
@@ -99,7 +97,6 @@
         });
   }
 
-  @SuppressWarnings("LocalVariableName")
   @Test
   void testConvergence() {
     double dtSeconds = 0.00505;
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/estimator/KalmanFilterTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/estimator/KalmanFilterTest.java
index 4d709be..848fe93 100644
--- a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/estimator/KalmanFilterTest.java
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/estimator/KalmanFilterTest.java
@@ -34,7 +34,6 @@
     createElevator();
   }
 
-  @SuppressWarnings("LocalVariableName")
   private static void createElevator() {
     var motors = DCMotor.getVex775Pro(2);
 
@@ -61,7 +60,6 @@
           new Matrix<>(Nat.N3(), Nat.N3())); // D
 
   @Test
-  @SuppressWarnings("LocalVariableName")
   void testElevatorKalmanFilter() {
     var Q = VecBuilder.fill(0.05, 1.0);
     var R = VecBuilder.fill(0.0001);
@@ -136,7 +134,6 @@
   }
 
   @Test
-  @SuppressWarnings("LocalVariableName")
   void testSwerveKFMovingOverTrajectory() {
     var random = new Random();
 
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/estimator/MecanumDrivePoseEstimatorTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/estimator/MecanumDrivePoseEstimatorTest.java
index d8756f0..02d2d52 100644
--- a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/estimator/MecanumDrivePoseEstimatorTest.java
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/estimator/MecanumDrivePoseEstimatorTest.java
@@ -9,87 +9,186 @@
 import edu.wpi.first.math.VecBuilder;
 import edu.wpi.first.math.geometry.Pose2d;
 import edu.wpi.first.math.geometry.Rotation2d;
+import edu.wpi.first.math.geometry.Transform2d;
 import edu.wpi.first.math.geometry.Translation2d;
 import edu.wpi.first.math.kinematics.ChassisSpeeds;
 import edu.wpi.first.math.kinematics.MecanumDriveKinematics;
+import edu.wpi.first.math.kinematics.MecanumDriveWheelPositions;
+import edu.wpi.first.math.trajectory.Trajectory;
 import edu.wpi.first.math.trajectory.TrajectoryConfig;
 import edu.wpi.first.math.trajectory.TrajectoryGenerator;
 import java.util.List;
 import java.util.Random;
+import java.util.TreeMap;
+import java.util.function.Function;
 import org.junit.jupiter.api.Test;
 
 class MecanumDrivePoseEstimatorTest {
   @Test
-  @SuppressWarnings("LocalVariableName")
-  void testAccuracy() {
+  void testAccuracyFacingTrajectory() {
     var kinematics =
         new MecanumDriveKinematics(
             new Translation2d(1, 1), new Translation2d(1, -1),
             new Translation2d(-1, -1), new Translation2d(-1, 1));
 
+    var wheelPositions = new MecanumDriveWheelPositions();
+
     var estimator =
         new MecanumDrivePoseEstimator(
-            new Rotation2d(),
-            new Pose2d(),
             kinematics,
+            new Rotation2d(),
+            wheelPositions,
+            new Pose2d(),
             VecBuilder.fill(0.1, 0.1, 0.1),
-            VecBuilder.fill(0.05),
-            VecBuilder.fill(0.1, 0.1, 0.1));
+            VecBuilder.fill(0.45, 0.45, 0.1));
 
     var trajectory =
         TrajectoryGenerator.generateTrajectory(
             List.of(
-                new Pose2d(),
-                new Pose2d(20, 20, Rotation2d.fromDegrees(0)),
-                new Pose2d(10, 10, Rotation2d.fromDegrees(180)),
-                new Pose2d(30, 30, Rotation2d.fromDegrees(0)),
-                new Pose2d(20, 20, Rotation2d.fromDegrees(180)),
-                new Pose2d(10, 10, Rotation2d.fromDegrees(0))),
-            new TrajectoryConfig(0.5, 2));
+                new Pose2d(0, 0, Rotation2d.fromDegrees(45)),
+                new Pose2d(3, 0, Rotation2d.fromDegrees(-90)),
+                new Pose2d(0, 0, Rotation2d.fromDegrees(135)),
+                new Pose2d(-3, 0, Rotation2d.fromDegrees(-90)),
+                new Pose2d(0, 0, Rotation2d.fromDegrees(45))),
+            new TrajectoryConfig(2, 2));
 
-    var rand = new Random(5190);
+    testFollowTrajectory(
+        kinematics,
+        estimator,
+        trajectory,
+        state ->
+            new ChassisSpeeds(
+                state.velocityMetersPerSecond,
+                0,
+                state.velocityMetersPerSecond * state.curvatureRadPerMeter),
+        state -> state.poseMeters,
+        trajectory.getInitialPose(),
+        new Pose2d(0, 0, Rotation2d.fromDegrees(45)),
+        0.02,
+        0.1,
+        0.25,
+        true);
+  }
 
-    final double dt = 0.02;
+  @Test
+  void testBadInitialPose() {
+    var kinematics =
+        new MecanumDriveKinematics(
+            new Translation2d(1, 1), new Translation2d(1, -1),
+            new Translation2d(-1, -1), new Translation2d(-1, 1));
+
+    var wheelPositions = new MecanumDriveWheelPositions();
+
+    var estimator =
+        new MecanumDrivePoseEstimator(
+            kinematics,
+            new Rotation2d(),
+            wheelPositions,
+            new Pose2d(),
+            VecBuilder.fill(0.1, 0.1, 0.1),
+            VecBuilder.fill(0.45, 0.45, 0.1));
+
+    var trajectory =
+        TrajectoryGenerator.generateTrajectory(
+            List.of(
+                new Pose2d(0, 0, Rotation2d.fromDegrees(45)),
+                new Pose2d(3, 0, Rotation2d.fromDegrees(-90)),
+                new Pose2d(0, 0, Rotation2d.fromDegrees(135)),
+                new Pose2d(-3, 0, Rotation2d.fromDegrees(-90)),
+                new Pose2d(0, 0, Rotation2d.fromDegrees(45))),
+            new TrajectoryConfig(2, 2));
+
+    for (int offset_direction_degs = 0; offset_direction_degs < 360; offset_direction_degs += 45) {
+      for (int offset_heading_degs = 0; offset_heading_degs < 360; offset_heading_degs += 45) {
+        var pose_offset = Rotation2d.fromDegrees(offset_direction_degs);
+        var heading_offset = Rotation2d.fromDegrees(offset_heading_degs);
+
+        var initial_pose =
+            trajectory
+                .getInitialPose()
+                .plus(
+                    new Transform2d(
+                        new Translation2d(pose_offset.getCos(), pose_offset.getSin()),
+                        heading_offset));
+
+        testFollowTrajectory(
+            kinematics,
+            estimator,
+            trajectory,
+            state ->
+                new ChassisSpeeds(
+                    state.velocityMetersPerSecond,
+                    0,
+                    state.velocityMetersPerSecond * state.curvatureRadPerMeter),
+            state -> state.poseMeters,
+            initial_pose,
+            new Pose2d(0, 0, Rotation2d.fromDegrees(45)),
+            0.02,
+            0.1,
+            0.25,
+            false);
+      }
+    }
+  }
+
+  void testFollowTrajectory(
+      final MecanumDriveKinematics kinematics,
+      final MecanumDrivePoseEstimator estimator,
+      final Trajectory trajectory,
+      final Function<Trajectory.State, ChassisSpeeds> chassisSpeedsGenerator,
+      final Function<Trajectory.State, Pose2d> visionMeasurementGenerator,
+      final Pose2d startingPose,
+      final Pose2d endingPose,
+      final double dt,
+      final double visionUpdateRate,
+      final double visionUpdateDelay,
+      final boolean checkError) {
+    var wheelPositions = new MecanumDriveWheelPositions();
+
+    estimator.resetPosition(new Rotation2d(), wheelPositions, startingPose);
+
+    var rand = new Random(3538);
+
     double t = 0.0;
 
-    final double visionUpdateRate = 0.1;
-    Pose2d lastVisionPose = null;
-    double lastVisionUpdateTime = Double.NEGATIVE_INFINITY;
+    System.out.print("time, est_x, est_y, est_theta, true_x, true_y, true_theta\n");
+
+    final TreeMap<Double, Pose2d> visionUpdateQueue = new TreeMap<>();
 
     double maxError = Double.NEGATIVE_INFINITY;
     double errorSum = 0;
     while (t <= trajectory.getTotalTimeSeconds()) {
       var groundTruthState = trajectory.sample(t);
 
-      if (lastVisionUpdateTime + visionUpdateRate < t) {
-        if (lastVisionPose != null) {
-          estimator.addVisionMeasurement(lastVisionPose, lastVisionUpdateTime);
-        }
+      // We are due for a new vision measurement if it's been `visionUpdateRate` seconds since the
+      // last vision measurement
+      if (visionUpdateQueue.isEmpty() || visionUpdateQueue.lastKey() + visionUpdateRate < t) {
+        Pose2d newVisionPose =
+            visionMeasurementGenerator
+                .apply(groundTruthState)
+                .plus(
+                    new Transform2d(
+                        new Translation2d(rand.nextGaussian() * 0.1, rand.nextGaussian() * 0.1),
+                        new Rotation2d(rand.nextGaussian() * 0.05)));
 
-        lastVisionPose =
-            new Pose2d(
-                new Translation2d(
-                    groundTruthState.poseMeters.getTranslation().getX() + rand.nextGaussian() * 0.1,
-                    groundTruthState.poseMeters.getTranslation().getY()
-                        + rand.nextGaussian() * 0.1),
-                new Rotation2d(rand.nextGaussian() * 0.1)
-                    .plus(groundTruthState.poseMeters.getRotation()));
-
-        lastVisionUpdateTime = t;
+        visionUpdateQueue.put(t, newVisionPose);
       }
 
-      var wheelSpeeds =
-          kinematics.toWheelSpeeds(
-              new ChassisSpeeds(
-                  groundTruthState.velocityMetersPerSecond,
-                  0,
-                  groundTruthState.velocityMetersPerSecond
-                      * groundTruthState.curvatureRadPerMeter));
+      // We should apply the oldest vision measurement if it has been `visionUpdateDelay` seconds
+      // since it was measured
+      if (!visionUpdateQueue.isEmpty() && visionUpdateQueue.firstKey() + visionUpdateDelay < t) {
+        var visionEntry = visionUpdateQueue.pollFirstEntry();
+        estimator.addVisionMeasurement(visionEntry.getValue(), visionEntry.getKey());
+      }
 
-      wheelSpeeds.frontLeftMetersPerSecond += rand.nextGaussian() * 0.1;
-      wheelSpeeds.frontRightMetersPerSecond += rand.nextGaussian() * 0.1;
-      wheelSpeeds.rearLeftMetersPerSecond += rand.nextGaussian() * 0.1;
-      wheelSpeeds.rearRightMetersPerSecond += rand.nextGaussian() * 0.1;
+      var chassisSpeeds = chassisSpeedsGenerator.apply(groundTruthState);
+
+      var wheelSpeeds = kinematics.toWheelSpeeds(chassisSpeeds);
+
+      wheelPositions.frontLeftMeters += wheelSpeeds.frontLeftMetersPerSecond * dt;
+      wheelPositions.frontRightMeters += wheelSpeeds.frontRightMetersPerSecond * dt;
+      wheelPositions.rearLeftMeters += wheelSpeeds.rearLeftMetersPerSecond * dt;
+      wheelPositions.rearRightMeters += wheelSpeeds.rearRightMetersPerSecond * dt;
 
       var xHat =
           estimator.updateWithTime(
@@ -97,8 +196,19 @@
               groundTruthState
                   .poseMeters
                   .getRotation()
-                  .plus(new Rotation2d(rand.nextGaussian() * 0.05)),
-              wheelSpeeds);
+                  .plus(new Rotation2d(rand.nextGaussian() * 0.05))
+                  .minus(trajectory.getInitialPose().getRotation()),
+              wheelPositions);
+
+      System.out.printf(
+          "%f, %f, %f, %f, %f, %f, %f\n",
+          t,
+          xHat.getX(),
+          xHat.getY(),
+          xHat.getRotation().getRadians(),
+          groundTruthState.poseMeters.getX(),
+          groundTruthState.poseMeters.getY(),
+          groundTruthState.poseMeters.getRotation().getRadians());
 
       double error =
           groundTruthState.poseMeters.getTranslation().getDistance(xHat.getTranslation());
@@ -111,7 +221,19 @@
     }
 
     assertEquals(
-        0.0, errorSum / (trajectory.getTotalTimeSeconds() / dt), 0.25, "Incorrect mean error");
-    assertEquals(0.0, maxError, 0.42, "Incorrect max error");
+        endingPose.getX(), estimator.getEstimatedPosition().getX(), 0.08, "Incorrect Final X");
+    assertEquals(
+        endingPose.getY(), estimator.getEstimatedPosition().getY(), 0.08, "Incorrect Final Y");
+    assertEquals(
+        endingPose.getRotation().getRadians(),
+        estimator.getEstimatedPosition().getRotation().getRadians(),
+        0.15,
+        "Incorrect Final Theta");
+
+    if (checkError) {
+      assertEquals(
+          0.0, errorSum / (trajectory.getTotalTimeSeconds() / dt), 0.07, "Incorrect mean error");
+      assertEquals(0.0, maxError, 0.2, "Incorrect max error");
+    }
   }
 }
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/estimator/MerweScaledSigmaPointsTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/estimator/MerweScaledSigmaPointsTest.java
index 3c51d6c..2131c35 100644
--- a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/estimator/MerweScaledSigmaPointsTest.java
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/estimator/MerweScaledSigmaPointsTest.java
@@ -16,7 +16,7 @@
   void testZeroMeanPoints() {
     var merweScaledSigmaPoints = new MerweScaledSigmaPoints<>(Nat.N2());
     var points =
-        merweScaledSigmaPoints.sigmaPoints(
+        merweScaledSigmaPoints.squareRootSigmaPoints(
             VecBuilder.fill(0, 0), Matrix.mat(Nat.N2(), Nat.N2()).fill(1, 0, 0, 1));
 
     assertTrue(
@@ -31,8 +31,8 @@
   void testNonzeroMeanPoints() {
     var merweScaledSigmaPoints = new MerweScaledSigmaPoints<>(Nat.N2());
     var points =
-        merweScaledSigmaPoints.sigmaPoints(
-            VecBuilder.fill(1, 2), Matrix.mat(Nat.N2(), Nat.N2()).fill(1, 0, 0, 10));
+        merweScaledSigmaPoints.squareRootSigmaPoints(
+            VecBuilder.fill(1, 2), Matrix.mat(Nat.N2(), Nat.N2()).fill(1, 0, 0, Math.sqrt(10)));
 
     assertTrue(
         points.isEqual(
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/estimator/SwerveDrivePoseEstimatorTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/estimator/SwerveDrivePoseEstimatorTest.java
index c6126c6..fde2c39 100644
--- a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/estimator/SwerveDrivePoseEstimatorTest.java
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/estimator/SwerveDrivePoseEstimatorTest.java
@@ -9,33 +9,43 @@
 import edu.wpi.first.math.VecBuilder;
 import edu.wpi.first.math.geometry.Pose2d;
 import edu.wpi.first.math.geometry.Rotation2d;
+import edu.wpi.first.math.geometry.Transform2d;
 import edu.wpi.first.math.geometry.Translation2d;
 import edu.wpi.first.math.kinematics.ChassisSpeeds;
 import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
+import edu.wpi.first.math.kinematics.SwerveModulePosition;
+import edu.wpi.first.math.trajectory.Trajectory;
 import edu.wpi.first.math.trajectory.TrajectoryConfig;
 import edu.wpi.first.math.trajectory.TrajectoryGenerator;
 import java.util.List;
 import java.util.Random;
+import java.util.TreeMap;
+import java.util.function.Function;
 import org.junit.jupiter.api.Test;
 
 class SwerveDrivePoseEstimatorTest {
   @Test
-  @SuppressWarnings("LocalVariableName")
-  void testAccuracy() {
+  void testAccuracyFacingTrajectory() {
     var kinematics =
         new SwerveDriveKinematics(
             new Translation2d(1, 1),
             new Translation2d(1, -1),
             new Translation2d(-1, -1),
             new Translation2d(-1, 1));
+
+    var fl = new SwerveModulePosition();
+    var fr = new SwerveModulePosition();
+    var bl = new SwerveModulePosition();
+    var br = new SwerveModulePosition();
+
     var estimator =
         new SwerveDrivePoseEstimator(
-            new Rotation2d(),
-            new Pose2d(),
             kinematics,
+            new Rotation2d(),
+            new SwerveModulePosition[] {fl, fr, bl, br},
+            new Pose2d(),
             VecBuilder.fill(0.1, 0.1, 0.1),
-            VecBuilder.fill(0.005),
-            VecBuilder.fill(0.1, 0.1, 0.1));
+            VecBuilder.fill(0.5, 0.5, 0.5));
 
     var trajectory =
         TrajectoryGenerator.generateTrajectory(
@@ -45,49 +55,158 @@
                 new Pose2d(0, 0, Rotation2d.fromDegrees(135)),
                 new Pose2d(-3, 0, Rotation2d.fromDegrees(-90)),
                 new Pose2d(0, 0, Rotation2d.fromDegrees(45))),
-            new TrajectoryConfig(0.5, 2));
+            new TrajectoryConfig(2, 2));
 
-    var rand = new Random(4915);
+    testFollowTrajectory(
+        kinematics,
+        estimator,
+        trajectory,
+        state ->
+            new ChassisSpeeds(
+                state.velocityMetersPerSecond,
+                0,
+                state.velocityMetersPerSecond * state.curvatureRadPerMeter),
+        state -> state.poseMeters,
+        trajectory.getInitialPose(),
+        new Pose2d(0, 0, Rotation2d.fromDegrees(45)),
+        0.02,
+        0.1,
+        0.25,
+        true);
+  }
 
-    final double dt = 0.02;
+  @Test
+  void testBadInitialPose() {
+    var kinematics =
+        new SwerveDriveKinematics(
+            new Translation2d(1, 1),
+            new Translation2d(1, -1),
+            new Translation2d(-1, -1),
+            new Translation2d(-1, 1));
+
+    var fl = new SwerveModulePosition();
+    var fr = new SwerveModulePosition();
+    var bl = new SwerveModulePosition();
+    var br = new SwerveModulePosition();
+
+    var estimator =
+        new SwerveDrivePoseEstimator(
+            kinematics,
+            new Rotation2d(),
+            new SwerveModulePosition[] {fl, fr, bl, br},
+            new Pose2d(-1, -1, Rotation2d.fromRadians(-1)),
+            VecBuilder.fill(0.1, 0.1, 0.1),
+            VecBuilder.fill(0.9, 0.9, 0.9));
+    var trajectory =
+        TrajectoryGenerator.generateTrajectory(
+            List.of(
+                new Pose2d(0, 0, Rotation2d.fromDegrees(45)),
+                new Pose2d(3, 0, Rotation2d.fromDegrees(-90)),
+                new Pose2d(0, 0, Rotation2d.fromDegrees(135)),
+                new Pose2d(-3, 0, Rotation2d.fromDegrees(-90)),
+                new Pose2d(0, 0, Rotation2d.fromDegrees(45))),
+            new TrajectoryConfig(2, 2));
+
+    for (int offset_direction_degs = 0; offset_direction_degs < 360; offset_direction_degs += 45) {
+      for (int offset_heading_degs = 0; offset_heading_degs < 360; offset_heading_degs += 45) {
+        var pose_offset = Rotation2d.fromDegrees(offset_direction_degs);
+        var heading_offset = Rotation2d.fromDegrees(offset_heading_degs);
+
+        var initial_pose =
+            trajectory
+                .getInitialPose()
+                .plus(
+                    new Transform2d(
+                        new Translation2d(pose_offset.getCos(), pose_offset.getSin()),
+                        heading_offset));
+
+        testFollowTrajectory(
+            kinematics,
+            estimator,
+            trajectory,
+            state ->
+                new ChassisSpeeds(
+                    state.velocityMetersPerSecond,
+                    0,
+                    state.velocityMetersPerSecond * state.curvatureRadPerMeter),
+            state -> state.poseMeters,
+            initial_pose,
+            new Pose2d(0, 0, Rotation2d.fromDegrees(45)),
+            0.02,
+            0.1,
+            1.0,
+            false);
+      }
+    }
+  }
+
+  void testFollowTrajectory(
+      final SwerveDriveKinematics kinematics,
+      final SwerveDrivePoseEstimator estimator,
+      final Trajectory trajectory,
+      final Function<Trajectory.State, ChassisSpeeds> chassisSpeedsGenerator,
+      final Function<Trajectory.State, Pose2d> visionMeasurementGenerator,
+      final Pose2d startingPose,
+      final Pose2d endingPose,
+      final double dt,
+      final double visionUpdateRate,
+      final double visionUpdateDelay,
+      final boolean checkError) {
+    SwerveModulePosition[] positions = {
+      new SwerveModulePosition(),
+      new SwerveModulePosition(),
+      new SwerveModulePosition(),
+      new SwerveModulePosition()
+    };
+
+    estimator.resetPosition(new Rotation2d(), positions, startingPose);
+
+    var rand = new Random(3538);
+
     double t = 0.0;
 
-    final double visionUpdateRate = 0.1;
-    Pose2d lastVisionPose = null;
-    double lastVisionUpdateTime = Double.NEGATIVE_INFINITY;
+    System.out.print(
+        "time, est_x, est_y, est_theta, true_x, true_y, true_theta, "
+            + "distance_1, distance_2, distance_3, distance_4, "
+            + "angle_1, angle_2, angle_3, angle_4\n");
+
+    final TreeMap<Double, Pose2d> visionUpdateQueue = new TreeMap<>();
 
     double maxError = Double.NEGATIVE_INFINITY;
     double errorSum = 0;
     while (t <= trajectory.getTotalTimeSeconds()) {
       var groundTruthState = trajectory.sample(t);
 
-      if (lastVisionUpdateTime + visionUpdateRate < t) {
-        if (lastVisionPose != null) {
-          estimator.addVisionMeasurement(lastVisionPose, lastVisionUpdateTime);
-        }
+      // We are due for a new vision measurement if it's been `visionUpdateRate` seconds since the
+      // last vision measurement
+      if (visionUpdateQueue.isEmpty() || visionUpdateQueue.lastKey() + visionUpdateRate < t) {
+        Pose2d newVisionPose =
+            visionMeasurementGenerator
+                .apply(groundTruthState)
+                .plus(
+                    new Transform2d(
+                        new Translation2d(rand.nextGaussian() * 0.1, rand.nextGaussian() * 0.1),
+                        new Rotation2d(rand.nextGaussian() * 0.05)));
 
-        lastVisionPose =
-            new Pose2d(
-                new Translation2d(
-                    groundTruthState.poseMeters.getTranslation().getX() + rand.nextGaussian() * 0.1,
-                    groundTruthState.poseMeters.getTranslation().getY()
-                        + rand.nextGaussian() * 0.1),
-                new Rotation2d(rand.nextGaussian() * 0.1)
-                    .plus(groundTruthState.poseMeters.getRotation()));
-
-        lastVisionUpdateTime = t;
+        visionUpdateQueue.put(t, newVisionPose);
       }
 
-      var moduleStates =
-          kinematics.toSwerveModuleStates(
-              new ChassisSpeeds(
-                  groundTruthState.velocityMetersPerSecond,
-                  0.0,
-                  groundTruthState.velocityMetersPerSecond
-                      * groundTruthState.curvatureRadPerMeter));
-      for (var moduleState : moduleStates) {
-        moduleState.angle = moduleState.angle.plus(new Rotation2d(rand.nextGaussian() * 0.005));
-        moduleState.speedMetersPerSecond += rand.nextGaussian() * 0.1;
+      // We should apply the oldest vision measurement if it has been `visionUpdateDelay` seconds
+      // since it was measured
+      if (!visionUpdateQueue.isEmpty() && visionUpdateQueue.firstKey() + visionUpdateDelay < t) {
+        var visionEntry = visionUpdateQueue.pollFirstEntry();
+        estimator.addVisionMeasurement(visionEntry.getValue(), visionEntry.getKey());
+      }
+
+      var chassisSpeeds = chassisSpeedsGenerator.apply(groundTruthState);
+
+      var moduleStates = kinematics.toSwerveModuleStates(chassisSpeeds);
+
+      for (int i = 0; i < moduleStates.length; i++) {
+        positions[i].distanceMeters +=
+            moduleStates[i].speedMetersPerSecond * (1 - rand.nextGaussian() * 0.05) * dt;
+        positions[i].angle =
+            moduleStates[i].angle.plus(new Rotation2d(rand.nextGaussian() * 0.005));
       }
 
       var xHat =
@@ -96,8 +215,27 @@
               groundTruthState
                   .poseMeters
                   .getRotation()
-                  .plus(new Rotation2d(rand.nextGaussian() * 0.05)),
-              moduleStates);
+                  .plus(new Rotation2d(rand.nextGaussian() * 0.05))
+                  .minus(trajectory.getInitialPose().getRotation()),
+              positions);
+
+      System.out.printf(
+          "%f, %f, %f, %f, %f, %f, %f, %f, %f, %f, %f, %f, %f, %f, %f\n",
+          t,
+          xHat.getX(),
+          xHat.getY(),
+          xHat.getRotation().getRadians(),
+          groundTruthState.poseMeters.getX(),
+          groundTruthState.poseMeters.getY(),
+          groundTruthState.poseMeters.getRotation().getRadians(),
+          positions[0].distanceMeters,
+          positions[1].distanceMeters,
+          positions[2].distanceMeters,
+          positions[3].distanceMeters,
+          positions[0].angle.getRadians(),
+          positions[1].angle.getRadians(),
+          positions[2].angle.getRadians(),
+          positions[3].angle.getRadians());
 
       double error =
           groundTruthState.poseMeters.getTranslation().getDistance(xHat.getTranslation());
@@ -110,7 +248,19 @@
     }
 
     assertEquals(
-        0.0, errorSum / (trajectory.getTotalTimeSeconds() / dt), 0.25, "Incorrect mean error");
-    assertEquals(0.0, maxError, 0.42, "Incorrect max error");
+        endingPose.getX(), estimator.getEstimatedPosition().getX(), 0.08, "Incorrect Final X");
+    assertEquals(
+        endingPose.getY(), estimator.getEstimatedPosition().getY(), 0.08, "Incorrect Final Y");
+    assertEquals(
+        endingPose.getRotation().getRadians(),
+        estimator.getEstimatedPosition().getRotation().getRadians(),
+        0.15,
+        "Incorrect Final Theta");
+
+    if (checkError) {
+      assertEquals(
+          0.0, errorSum / (trajectory.getTotalTimeSeconds() / dt), 0.07, "Incorrect mean error");
+      assertEquals(0.0, maxError, 0.2, "Incorrect max error");
+    }
   }
 }
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/estimator/UnscentedKalmanFilterTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/estimator/UnscentedKalmanFilterTest.java
index 25def49..a8e4d3b 100644
--- a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/estimator/UnscentedKalmanFilterTest.java
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/estimator/UnscentedKalmanFilterTest.java
@@ -16,8 +16,8 @@
 import edu.wpi.first.math.geometry.Rotation2d;
 import edu.wpi.first.math.numbers.N1;
 import edu.wpi.first.math.numbers.N2;
-import edu.wpi.first.math.numbers.N4;
-import edu.wpi.first.math.numbers.N6;
+import edu.wpi.first.math.numbers.N3;
+import edu.wpi.first.math.numbers.N5;
 import edu.wpi.first.math.system.Discretization;
 import edu.wpi.first.math.system.NumericalIntegration;
 import edu.wpi.first.math.system.NumericalJacobian;
@@ -30,92 +30,109 @@
 import org.junit.jupiter.api.Test;
 
 class UnscentedKalmanFilterTest {
-  @SuppressWarnings({"LocalVariableName", "ParameterName"})
-  private static Matrix<N6, N1> getDynamics(Matrix<N6, N1> x, Matrix<N2, N1> u) {
+  private static Matrix<N5, N1> getDynamics(Matrix<N5, N1> x, Matrix<N2, N1> u) {
     var motors = DCMotor.getCIM(2);
 
-    var gHigh = 7.08;
-    var rb = 0.8382 / 2.0;
-    var r = 0.0746125;
-    var m = 63.503;
-    var J = 5.6;
+    // var gLow = 15.32;    // Low gear ratio
+    var gHigh = 7.08; // High gear ratio
+    var rb = 0.8382 / 2.0; // Robot radius
+    var r = 0.0746125; // Wheel radius
+    var m = 63.503; // Robot mass
+    var J = 5.6; // Robot moment of inertia
 
     var C1 =
         -Math.pow(gHigh, 2)
             * motors.KtNMPerAmp
             / (motors.KvRadPerSecPerVolt * motors.rOhms * r * r);
     var C2 = gHigh * motors.KtNMPerAmp / (motors.rOhms * r);
+    var k1 = 1.0 / m + Math.pow(rb, 2) / J;
+    var k2 = 1.0 / m - Math.pow(rb, 2) / J;
 
-    var c = x.get(2, 0);
-    var s = x.get(3, 0);
-    var vl = x.get(4, 0);
-    var vr = x.get(5, 0);
-
+    var vl = x.get(3, 0);
+    var vr = x.get(4, 0);
     var Vl = u.get(0, 0);
     var Vr = u.get(1, 0);
 
-    var k1 = 1.0 / m + rb * rb / J;
-    var k2 = 1.0 / m - rb * rb / J;
-
-    var xvel = (vl + vr) / 2;
-    var w = (vr - vl) / (2.0 * rb);
-
+    var v = 0.5 * (vl + vr);
     return VecBuilder.fill(
-        xvel * c,
-        xvel * s,
-        -s * w,
-        c * w,
-        k1 * ((C1 * vl) + (C2 * Vl)) + k2 * ((C1 * vr) + (C2 * Vr)),
-        k2 * ((C1 * vl) + (C2 * Vl)) + k1 * ((C1 * vr) + (C2 * Vr)));
+        v * Math.cos(x.get(2, 0)),
+        v * Math.sin(x.get(2, 0)),
+        (vr - vl) / (2.0 * rb),
+        k1 * (C1 * vl + C2 * Vl) + k2 * (C1 * vr + C2 * Vr),
+        k2 * (C1 * vl + C2 * Vl) + k1 * (C1 * vr + C2 * Vr));
   }
 
-  @SuppressWarnings({"PMD.UnusedFormalParameter", "ParameterName"})
-  private static Matrix<N4, N1> getLocalMeasurementModel(Matrix<N6, N1> x, Matrix<N2, N1> u) {
-    return VecBuilder.fill(x.get(2, 0), x.get(3, 0), x.get(4, 0), x.get(5, 0));
+  @SuppressWarnings("PMD.UnusedFormalParameter")
+  private static Matrix<N3, N1> getLocalMeasurementModel(Matrix<N5, N1> x, Matrix<N2, N1> u) {
+    return VecBuilder.fill(x.get(2, 0), x.get(3, 0), x.get(4, 0));
   }
 
-  @SuppressWarnings({"PMD.UnusedFormalParameter", "ParameterName"})
-  private static Matrix<N6, N1> getGlobalMeasurementModel(Matrix<N6, N1> x, Matrix<N2, N1> u) {
+  @SuppressWarnings("PMD.UnusedFormalParameter")
+  private static Matrix<N5, N1> getGlobalMeasurementModel(Matrix<N5, N1> x, Matrix<N2, N1> u) {
     return x.copy();
   }
 
   @Test
-  @SuppressWarnings("LocalVariableName")
   void testInit() {
+    var dtSeconds = 0.005;
     assertDoesNotThrow(
         () -> {
-          UnscentedKalmanFilter<N6, N2, N4> observer =
+          UnscentedKalmanFilter<N5, N2, N3> observer =
               new UnscentedKalmanFilter<>(
-                  Nat.N6(),
-                  Nat.N4(),
+                  Nat.N5(),
+                  Nat.N3(),
                   UnscentedKalmanFilterTest::getDynamics,
                   UnscentedKalmanFilterTest::getLocalMeasurementModel,
-                  VecBuilder.fill(0.5, 0.5, 0.7, 0.7, 1.0, 1.0),
-                  VecBuilder.fill(0.001, 0.001, 0.5, 0.5),
-                  0.00505);
+                  VecBuilder.fill(0.5, 0.5, 10.0, 1.0, 1.0),
+                  VecBuilder.fill(0.0001, 0.01, 0.01),
+                  AngleStatistics.angleMean(2),
+                  AngleStatistics.angleMean(0),
+                  AngleStatistics.angleResidual(2),
+                  AngleStatistics.angleResidual(0),
+                  AngleStatistics.angleAdd(2),
+                  dtSeconds);
 
           var u = VecBuilder.fill(12.0, 12.0);
-          observer.predict(u, 0.00505);
+          observer.predict(u, dtSeconds);
 
           var localY = getLocalMeasurementModel(observer.getXhat(), u);
           observer.correct(u, localY);
+
+          var globalY = getGlobalMeasurementModel(observer.getXhat(), u);
+          var R =
+              StateSpaceUtil.makeCovarianceMatrix(
+                  Nat.N5(), VecBuilder.fill(0.01, 0.01, 0.0001, 0.01, 0.01));
+          observer.correct(
+              Nat.N5(),
+              u,
+              globalY,
+              UnscentedKalmanFilterTest::getGlobalMeasurementModel,
+              R,
+              AngleStatistics.angleMean(2),
+              AngleStatistics.angleResidual(2),
+              AngleStatistics.angleResidual(2),
+              AngleStatistics.angleAdd(2));
         });
   }
 
-  @SuppressWarnings("LocalVariableName")
   @Test
   void testConvergence() {
-    double dtSeconds = 0.00505;
+    double dtSeconds = 0.005;
     double rbMeters = 0.8382 / 2.0; // Robot radius
 
-    UnscentedKalmanFilter<N6, N2, N4> observer =
+    UnscentedKalmanFilter<N5, N2, N3> observer =
         new UnscentedKalmanFilter<>(
-            Nat.N6(),
-            Nat.N4(),
+            Nat.N5(),
+            Nat.N3(),
             UnscentedKalmanFilterTest::getDynamics,
             UnscentedKalmanFilterTest::getLocalMeasurementModel,
-            VecBuilder.fill(0.5, 0.5, 0.7, 0.7, 1.0, 1.0),
-            VecBuilder.fill(0.001, 0.001, 0.5, 0.5),
+            VecBuilder.fill(0.5, 0.5, 10.0, 1.0, 1.0),
+            VecBuilder.fill(0.0001, 0.5, 0.5),
+            AngleStatistics.angleMean(2),
+            AngleStatistics.angleMean(0),
+            AngleStatistics.angleResidual(2),
+            AngleStatistics.angleResidual(0),
+            AngleStatistics.angleAdd(2),
             dtSeconds);
 
     List<Pose2d> waypoints =
@@ -125,56 +142,52 @@
     var trajectory =
         TrajectoryGenerator.generateTrajectory(waypoints, new TrajectoryConfig(8.8, 0.1));
 
-    Matrix<N6, N1> nextR;
+    Matrix<N5, N1> r = new Matrix<>(Nat.N5(), Nat.N1());
     Matrix<N2, N1> u = new Matrix<>(Nat.N2(), Nat.N1());
 
     var B =
         NumericalJacobian.numericalJacobianU(
-            Nat.N6(),
+            Nat.N5(),
             Nat.N2(),
             UnscentedKalmanFilterTest::getDynamics,
-            new Matrix<>(Nat.N6(), Nat.N1()),
-            u);
+            new Matrix<>(Nat.N5(), Nat.N1()),
+            new Matrix<>(Nat.N2(), Nat.N1()));
 
-    observer.setXhat(VecBuilder.fill(2.75, 22.521, 1.0, 0.0, 0.0, 0.0)); // TODO not hard code this
-
-    var ref = trajectory.sample(0.0);
-
-    Matrix<N6, N1> r =
+    observer.setXhat(
         VecBuilder.fill(
-            ref.poseMeters.getTranslation().getX(),
-            ref.poseMeters.getTranslation().getY(),
-            ref.poseMeters.getRotation().getCos(),
-            ref.poseMeters.getRotation().getSin(),
-            ref.velocityMetersPerSecond * (1 - (ref.curvatureRadPerMeter * rbMeters)),
-            ref.velocityMetersPerSecond * (1 + (ref.curvatureRadPerMeter * rbMeters)));
-    nextR = r.copy();
+            trajectory.getInitialPose().getTranslation().getX(),
+            trajectory.getInitialPose().getTranslation().getY(),
+            trajectory.getInitialPose().getRotation().getRadians(),
+            0.0,
+            0.0));
 
     var trueXhat = observer.getXhat();
 
     double totalTime = trajectory.getTotalTimeSeconds();
     for (int i = 0; i < (totalTime / dtSeconds); i++) {
-      ref = trajectory.sample(dtSeconds * i);
+      var ref = trajectory.sample(dtSeconds * i);
       double vl = ref.velocityMetersPerSecond * (1 - (ref.curvatureRadPerMeter * rbMeters));
       double vr = ref.velocityMetersPerSecond * (1 + (ref.curvatureRadPerMeter * rbMeters));
 
-      nextR.set(0, 0, ref.poseMeters.getTranslation().getX());
-      nextR.set(1, 0, ref.poseMeters.getTranslation().getY());
-      nextR.set(2, 0, ref.poseMeters.getRotation().getCos());
-      nextR.set(3, 0, ref.poseMeters.getRotation().getSin());
-      nextR.set(4, 0, vl);
-      nextR.set(5, 0, vr);
+      var nextR =
+          VecBuilder.fill(
+              ref.poseMeters.getTranslation().getX(),
+              ref.poseMeters.getTranslation().getY(),
+              ref.poseMeters.getRotation().getRadians(),
+              vl,
+              vr);
 
-      Matrix<N4, N1> localY = getLocalMeasurementModel(trueXhat, new Matrix<>(Nat.N2(), Nat.N1()));
-      var noiseStdDev = VecBuilder.fill(0.001, 0.001, 0.5, 0.5);
+      Matrix<N3, N1> localY = getLocalMeasurementModel(trueXhat, new Matrix<>(Nat.N2(), Nat.N1()));
+      var noiseStdDev = VecBuilder.fill(0.0001, 0.5, 0.5);
 
       observer.correct(u, localY.plus(StateSpaceUtil.makeWhiteNoiseVector(noiseStdDev)));
 
       var rdot = nextR.minus(r).div(dtSeconds);
       u = new Matrix<>(B.solve(rdot.minus(getDynamics(r, new Matrix<>(Nat.N2(), Nat.N1())))));
 
-      r = nextR;
       observer.predict(u, dtSeconds);
+
+      r = nextR;
       trueXhat =
           NumericalIntegration.rk4(UnscentedKalmanFilterTest::getDynamics, trueXhat, u, dtSeconds);
     }
@@ -183,29 +196,31 @@
     observer.correct(u, localY);
 
     var globalY = getGlobalMeasurementModel(trueXhat, u);
-    var R = StateSpaceUtil.makeCostMatrix(VecBuilder.fill(0.01, 0.01, 0.0001, 0.0001, 0.5, 0.5));
+    var R =
+        StateSpaceUtil.makeCovarianceMatrix(
+            Nat.N5(), VecBuilder.fill(0.01, 0.01, 0.0001, 0.5, 0.5));
     observer.correct(
-        Nat.N6(),
+        Nat.N5(),
         u,
         globalY,
         UnscentedKalmanFilterTest::getGlobalMeasurementModel,
         R,
-        (sigmas, weights) -> sigmas.times(Matrix.changeBoundsUnchecked(weights)),
-        Matrix::minus,
-        Matrix::minus,
-        Matrix::plus);
+        AngleStatistics.angleMean(2),
+        AngleStatistics.angleResidual(2),
+        AngleStatistics.angleResidual(2),
+        AngleStatistics.angleAdd(2));
 
     final var finalPosition = trajectory.sample(trajectory.getTotalTimeSeconds());
 
-    assertEquals(finalPosition.poseMeters.getTranslation().getX(), observer.getXhat(0), 0.25);
-    assertEquals(finalPosition.poseMeters.getTranslation().getY(), observer.getXhat(1), 0.25);
-    assertEquals(finalPosition.poseMeters.getRotation().getRadians(), observer.getXhat(2), 1.0);
-    assertEquals(0.0, observer.getXhat(3), 1.0);
-    assertEquals(0.0, observer.getXhat(4), 1.0);
+    assertEquals(finalPosition.poseMeters.getTranslation().getX(), observer.getXhat(0), 0.055);
+    assertEquals(finalPosition.poseMeters.getTranslation().getY(), observer.getXhat(1), 0.15);
+    assertEquals(
+        finalPosition.poseMeters.getRotation().getRadians(), observer.getXhat(2), 0.000005);
+    assertEquals(0.0, observer.getXhat(3), 0.1);
+    assertEquals(0.0, observer.getXhat(4), 0.1);
   }
 
   @Test
-  @SuppressWarnings({"LocalVariableName", "ParameterName"})
   void testLinearUKF() {
     var dt = 0.020;
     var plant = LinearSystemId.identifyVelocitySystem(0.02, 0.006);
@@ -236,94 +251,22 @@
   }
 
   @Test
-  void testUnscentedTransform() {
-    // From FilterPy
-    var ret =
-        UnscentedKalmanFilter.unscentedTransform(
-            Nat.N4(),
-            Nat.N4(),
-            Matrix.mat(Nat.N4(), Nat.N9())
-                .fill(
-                    -0.9,
-                    -0.822540333075852,
-                    -0.8922540333075852,
-                    -0.9,
-                    -0.9,
-                    -0.9774596669241481,
-                    -0.9077459666924148,
-                    -0.9,
-                    -0.9,
-                    1.0,
-                    1.0,
-                    1.077459666924148,
-                    1.0,
-                    1.0,
-                    1.0,
-                    0.9225403330758519,
-                    1.0,
-                    1.0,
-                    -0.9,
-                    -0.9,
-                    -0.9,
-                    -0.822540333075852,
-                    -0.8922540333075852,
-                    -0.9,
-                    -0.9,
-                    -0.9774596669241481,
-                    -0.9077459666924148,
-                    1.0,
-                    1.0,
-                    1.0,
-                    1.0,
-                    1.077459666924148,
-                    1.0,
-                    1.0,
-                    1.0,
-                    0.9225403330758519),
-            VecBuilder.fill(
-                -132.33333333,
-                16.66666667,
-                16.66666667,
-                16.66666667,
-                16.66666667,
-                16.66666667,
-                16.66666667,
-                16.66666667,
-                16.66666667),
-            VecBuilder.fill(
-                -129.34333333,
-                16.66666667,
-                16.66666667,
-                16.66666667,
-                16.66666667,
-                16.66666667,
-                16.66666667,
-                16.66666667,
-                16.66666667),
-            (sigmas, weights) -> sigmas.times(Matrix.changeBoundsUnchecked(weights)),
-            Matrix::minus);
+  void testRoundTripP() {
+    var dtSeconds = 0.005;
 
-    assertTrue(VecBuilder.fill(-0.9, 1, -0.9, 1).isEqual(ret.getFirst(), 1E-5));
+    var observer =
+        new UnscentedKalmanFilter<>(
+            Nat.N2(),
+            Nat.N2(),
+            (x, u) -> x,
+            (x, u) -> x,
+            VecBuilder.fill(0.0, 0.0),
+            VecBuilder.fill(0.0, 0.0),
+            dtSeconds);
 
-    assertTrue(
-        Matrix.mat(Nat.N4(), Nat.N4())
-            .fill(
-                2.02000002e-01,
-                2.00000500e-02,
-                -2.69044710e-29,
-                -4.59511477e-29,
-                2.00000500e-02,
-                2.00001000e-01,
-                -2.98781068e-29,
-                -5.12759588e-29,
-                -2.73372625e-29,
-                -3.09882635e-29,
-                2.02000002e-01,
-                2.00000500e-02,
-                -4.67065917e-29,
-                -5.10705197e-29,
-                2.00000500e-02,
-                2.00001000e-01)
-            .isEqual(ret.getSecond(), 1E-5));
+    var P = Matrix.mat(Nat.N2(), Nat.N2()).fill(2.0, 1.0, 1.0, 2.0);
+    observer.setP(P);
+
+    assertTrue(observer.getP().isEqual(P, 1e-9));
   }
 }
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/filter/LinearFilterTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/filter/LinearFilterTest.java
index f0b39c6..ec43cd5 100644
--- a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/filter/LinearFilterTest.java
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/filter/LinearFilterTest.java
@@ -141,7 +141,7 @@
         3,
         // f(x) = ln(x)
         (double x) -> Math.log(x),
-        // df/dx = 1 / x
+        // df/dx = 1/x
         (double x) -> 1.0 / x,
         h,
         1.0,
@@ -174,7 +174,7 @@
         5,
         // f(x) = ln(x)
         (double x) -> Math.log(x),
-        // d²f/dx² = -1 / x²
+        // d²f/dx² = -1/x²
         (double x) -> -1.0 / (x * x),
         h,
         1.0,
@@ -213,7 +213,7 @@
         2,
         // f(x) = ln(x)
         (double x) -> Math.log(x),
-        // df/dx = 1 / x
+        // df/dx = 1/x
         (double x) -> 1.0 / x,
         h,
         1.0,
@@ -246,7 +246,7 @@
         4,
         // f(x) = ln(x)
         (double x) -> Math.log(x),
-        // d²f/dx² = -1 / x²
+        // d²f/dx² = -1/x²
         (double x) -> -1.0 / (x * x),
         h,
         1.0,
@@ -282,7 +282,7 @@
       stencil[i] = -(samples - 1) / 2 + i;
     }
 
-    var filter = LinearFilter.finiteDifference(derivative, samples, stencil, h);
+    var filter = LinearFilter.finiteDifference(derivative, stencil, h);
 
     for (int i = (int) (min / h); i < (int) (max / h); ++i) {
       // Let filter initialize
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/filter/SlewRateLimiterTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/filter/SlewRateLimiterTest.java
index e7ec644..6e94b3c 100644
--- a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/filter/SlewRateLimiterTest.java
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/filter/SlewRateLimiterTest.java
@@ -38,4 +38,13 @@
     WPIUtilJNI.setMockTime(1000000L);
     assertEquals(limiter.calculate(0.5), 0.5);
   }
+
+  @Test
+  void slewRatePositiveNegativeTest() {
+    var limiter = new SlewRateLimiter(1, -0.5, 0);
+    WPIUtilJNI.setMockTime(1000000L);
+    assertEquals(limiter.calculate(2), 1);
+    WPIUtilJNI.setMockTime(2000000L);
+    assertEquals(limiter.calculate(0), 0.5);
+  }
 }
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/CoordinateSystemTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/CoordinateSystemTest.java
new file mode 100644
index 0000000..68babdd
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/CoordinateSystemTest.java
@@ -0,0 +1,251 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.math.geometry;
+
+import static org.junit.jupiter.api.Assertions.assertEquals;
+
+import edu.wpi.first.math.util.Units;
+import org.junit.jupiter.api.Test;
+
+class CoordinateSystemTest {
+  private void checkPose3dConvert(
+      Pose3d poseFrom, Pose3d poseTo, CoordinateSystem coordFrom, CoordinateSystem coordTo) {
+    // "from" to "to"
+    assertEquals(
+        poseTo.getTranslation(),
+        CoordinateSystem.convert(poseFrom.getTranslation(), coordFrom, coordTo));
+    assertEquals(
+        poseTo.getRotation(), CoordinateSystem.convert(poseFrom.getRotation(), coordFrom, coordTo));
+    assertEquals(poseTo, CoordinateSystem.convert(poseFrom, coordFrom, coordTo));
+
+    // "to" to "from"
+    assertEquals(
+        poseFrom.getTranslation(),
+        CoordinateSystem.convert(poseTo.getTranslation(), coordTo, coordFrom));
+    assertEquals(
+        poseFrom.getRotation(), CoordinateSystem.convert(poseTo.getRotation(), coordTo, coordFrom));
+    assertEquals(poseFrom, CoordinateSystem.convert(poseTo, coordTo, coordFrom));
+  }
+
+  private void checkTransform3dConvert(
+      Transform3d transformFrom,
+      Transform3d transformTo,
+      CoordinateSystem coordFrom,
+      CoordinateSystem coordTo) {
+    // "from" to "to"
+    assertEquals(
+        transformTo.getTranslation(),
+        CoordinateSystem.convert(transformFrom.getTranslation(), coordFrom, coordTo));
+    assertEquals(
+        transformTo.getRotation(),
+        CoordinateSystem.convert(transformFrom.getRotation(), coordFrom, coordTo));
+    assertEquals(transformTo, CoordinateSystem.convert(transformFrom, coordFrom, coordTo));
+
+    // "to" to "from"
+    assertEquals(
+        transformFrom.getTranslation(),
+        CoordinateSystem.convert(transformTo.getTranslation(), coordTo, coordFrom));
+    assertEquals(
+        transformFrom.getRotation(),
+        CoordinateSystem.convert(transformTo.getRotation(), coordTo, coordFrom));
+    assertEquals(transformFrom, CoordinateSystem.convert(transformTo, coordTo, coordFrom));
+  }
+
+  @Test
+  void testPose3dEDNtoNWU() {
+    // No rotation from EDN to NWU
+    checkPose3dConvert(
+        new Pose3d(1.0, 2.0, 3.0, new Rotation3d()),
+        new Pose3d(
+            3.0,
+            -1.0,
+            -2.0,
+            new Rotation3d(Units.degreesToRadians(-90.0), 0.0, Units.degreesToRadians(-90.0))),
+        CoordinateSystem.EDN(),
+        CoordinateSystem.NWU());
+
+    // 45° roll from EDN to NWU
+    checkPose3dConvert(
+        new Pose3d(1.0, 2.0, 3.0, new Rotation3d(Units.degreesToRadians(45.0), 0.0, 0.0)),
+        new Pose3d(
+            3.0,
+            -1.0,
+            -2.0,
+            new Rotation3d(Units.degreesToRadians(-45.0), 0.0, Units.degreesToRadians(-90.0))),
+        CoordinateSystem.EDN(),
+        CoordinateSystem.NWU());
+
+    // 45° pitch from EDN to NWU
+    checkPose3dConvert(
+        new Pose3d(1.0, 2.0, 3.0, new Rotation3d(0.0, Units.degreesToRadians(45.0), 0.0)),
+        new Pose3d(
+            3.0,
+            -1.0,
+            -2.0,
+            new Rotation3d(Units.degreesToRadians(-90.0), 0.0, Units.degreesToRadians(-135.0))),
+        CoordinateSystem.EDN(),
+        CoordinateSystem.NWU());
+
+    // 45° yaw from EDN to NWU
+    checkPose3dConvert(
+        new Pose3d(1.0, 2.0, 3.0, new Rotation3d(0.0, 0.0, Units.degreesToRadians(45.0))),
+        new Pose3d(
+            3.0,
+            -1.0,
+            -2.0,
+            new Rotation3d(
+                Units.degreesToRadians(-90.0),
+                Units.degreesToRadians(45.0),
+                Units.degreesToRadians(-90.0))),
+        CoordinateSystem.EDN(),
+        CoordinateSystem.NWU());
+  }
+
+  @Test
+  void testPose3dEDNtoNED() {
+    // No rotation from EDN to NED
+    checkPose3dConvert(
+        new Pose3d(1.0, 2.0, 3.0, new Rotation3d()),
+        new Pose3d(
+            3.0,
+            1.0,
+            2.0,
+            new Rotation3d(Units.degreesToRadians(90.0), 0.0, Units.degreesToRadians(90.0))),
+        CoordinateSystem.EDN(),
+        CoordinateSystem.NED());
+
+    // 45° roll from EDN to NED
+    checkPose3dConvert(
+        new Pose3d(1.0, 2.0, 3.0, new Rotation3d(Units.degreesToRadians(45.0), 0.0, 0.0)),
+        new Pose3d(
+            3.0,
+            1.0,
+            2.0,
+            new Rotation3d(Units.degreesToRadians(135.0), 0.0, Units.degreesToRadians(90.0))),
+        CoordinateSystem.EDN(),
+        CoordinateSystem.NED());
+
+    // 45° pitch from EDN to NED
+    checkPose3dConvert(
+        new Pose3d(1.0, 2.0, 3.0, new Rotation3d(0.0, Units.degreesToRadians(45.0), 0.0)),
+        new Pose3d(
+            3.0,
+            1.0,
+            2.0,
+            new Rotation3d(Units.degreesToRadians(90.0), 0.0, Units.degreesToRadians(135.0))),
+        CoordinateSystem.EDN(),
+        CoordinateSystem.NED());
+
+    // 45° yaw from EDN to NED
+    checkPose3dConvert(
+        new Pose3d(1.0, 2.0, 3.0, new Rotation3d(0.0, 0.0, Units.degreesToRadians(45.0))),
+        new Pose3d(
+            3.0,
+            1.0,
+            2.0,
+            new Rotation3d(
+                Units.degreesToRadians(90.0),
+                Units.degreesToRadians(-45.0),
+                Units.degreesToRadians(90.0))),
+        CoordinateSystem.EDN(),
+        CoordinateSystem.NED());
+  }
+
+  @Test
+  void testTransform3dEDNtoNWU() {
+    // No rotation from EDN to NWU
+    checkTransform3dConvert(
+        new Transform3d(new Translation3d(1.0, 2.0, 3.0), new Rotation3d()),
+        new Transform3d(
+            new Translation3d(3.0, -1.0, -2.0),
+            new Rotation3d(Units.degreesToRadians(-90.0), 0.0, Units.degreesToRadians(-90.0))),
+        CoordinateSystem.EDN(),
+        CoordinateSystem.NWU());
+
+    // 45° roll from EDN to NWU
+    checkTransform3dConvert(
+        new Transform3d(
+            new Translation3d(1.0, 2.0, 3.0),
+            new Rotation3d(Units.degreesToRadians(45.0), 0.0, 0.0)),
+        new Transform3d(
+            new Translation3d(3.0, -1.0, -2.0),
+            new Rotation3d(Units.degreesToRadians(-45.0), 0.0, Units.degreesToRadians(-90.0))),
+        CoordinateSystem.EDN(),
+        CoordinateSystem.NWU());
+
+    // 45° pitch from EDN to NWU
+    checkTransform3dConvert(
+        new Transform3d(
+            new Translation3d(1.0, 2.0, 3.0),
+            new Rotation3d(0.0, Units.degreesToRadians(45.0), 0.0)),
+        new Transform3d(
+            new Translation3d(3.0, -1.0, -2.0),
+            new Rotation3d(Units.degreesToRadians(-90.0), 0.0, Units.degreesToRadians(-135.0))),
+        CoordinateSystem.EDN(),
+        CoordinateSystem.NWU());
+
+    // 45° yaw from EDN to NWU
+    checkTransform3dConvert(
+        new Transform3d(
+            new Translation3d(1.0, 2.0, 3.0),
+            new Rotation3d(0.0, 0.0, Units.degreesToRadians(45.0))),
+        new Transform3d(
+            new Translation3d(3.0, -1.0, -2.0),
+            new Rotation3d(
+                Units.degreesToRadians(-90.0),
+                Units.degreesToRadians(45.0),
+                Units.degreesToRadians(-90.0))),
+        CoordinateSystem.EDN(),
+        CoordinateSystem.NWU());
+  }
+
+  @Test
+  void testTransform3dEDNtoNED() {
+    // No rotation from EDN to NED
+    checkTransform3dConvert(
+        new Transform3d(new Translation3d(1.0, 2.0, 3.0), new Rotation3d()),
+        new Transform3d(
+            new Translation3d(3.0, 1.0, 2.0),
+            new Rotation3d(Units.degreesToRadians(90.0), 0.0, Units.degreesToRadians(90.0))),
+        CoordinateSystem.EDN(),
+        CoordinateSystem.NED());
+
+    // 45° roll from EDN to NED
+    checkTransform3dConvert(
+        new Transform3d(
+            new Translation3d(1.0, 2.0, 3.0),
+            new Rotation3d(Units.degreesToRadians(45.0), 0.0, 0.0)),
+        new Transform3d(
+            new Translation3d(3.0, 1.0, 2.0),
+            new Rotation3d(Units.degreesToRadians(135.0), 0.0, Units.degreesToRadians(90.0))),
+        CoordinateSystem.EDN(),
+        CoordinateSystem.NED());
+
+    // 45° pitch from EDN to NED
+    checkTransform3dConvert(
+        new Transform3d(
+            new Translation3d(1.0, 2.0, 3.0),
+            new Rotation3d(0.0, Units.degreesToRadians(45.0), 0.0)),
+        new Transform3d(
+            new Translation3d(3.0, 1.0, 2.0),
+            new Rotation3d(Units.degreesToRadians(90.0), 0.0, Units.degreesToRadians(135.0))),
+        CoordinateSystem.EDN(),
+        CoordinateSystem.NED());
+
+    // 45° yaw from EDN to NED
+    checkTransform3dConvert(
+        new Transform3d(
+            new Translation3d(1.0, 2.0, 3.0),
+            new Rotation3d(0.0, 0.0, Units.degreesToRadians(45.0))),
+        new Transform3d(
+            new Translation3d(3.0, 1.0, 2.0),
+            new Rotation3d(
+                Units.degreesToRadians(90.0),
+                Units.degreesToRadians(-45.0),
+                Units.degreesToRadians(90.0))),
+        CoordinateSystem.EDN(),
+        CoordinateSystem.NED());
+  }
+}
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/Pose2dTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/Pose2dTest.java
index 5a314b1..780c816 100644
--- a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/Pose2dTest.java
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/Pose2dTest.java
@@ -21,9 +21,9 @@
     var transformed = initial.plus(transformation);
 
     assertAll(
-        () -> assertEquals(transformed.getX(), 1 + 5.0 / Math.sqrt(2.0), kEpsilon),
-        () -> assertEquals(transformed.getY(), 2 + 5.0 / Math.sqrt(2.0), kEpsilon),
-        () -> assertEquals(transformed.getRotation().getDegrees(), 50.0, kEpsilon));
+        () -> assertEquals(1.0 + 5.0 / Math.sqrt(2.0), transformed.getX(), kEpsilon),
+        () -> assertEquals(2.0 + 5.0 / Math.sqrt(2.0), transformed.getY(), kEpsilon),
+        () -> assertEquals(50.0, transformed.getRotation().getDegrees(), kEpsilon));
   }
 
   @Test
@@ -34,9 +34,9 @@
     var finalRelativeToInitial = last.relativeTo(initial);
 
     assertAll(
-        () -> assertEquals(finalRelativeToInitial.getX(), 5.0 * Math.sqrt(2.0), kEpsilon),
-        () -> assertEquals(finalRelativeToInitial.getY(), 0.0, kEpsilon),
-        () -> assertEquals(finalRelativeToInitial.getRotation().getDegrees(), 0.0, kEpsilon));
+        () -> assertEquals(5.0 * Math.sqrt(2.0), finalRelativeToInitial.getX(), kEpsilon),
+        () -> assertEquals(0.0, finalRelativeToInitial.getY(), kEpsilon),
+        () -> assertEquals(0.0, finalRelativeToInitial.getRotation().getDegrees(), kEpsilon));
   }
 
   @Test
@@ -61,8 +61,8 @@
     final var transform = last.minus(initial);
 
     assertAll(
-        () -> assertEquals(transform.getX(), 5.0 * Math.sqrt(2.0), kEpsilon),
-        () -> assertEquals(transform.getY(), 0.0, kEpsilon),
-        () -> assertEquals(transform.getRotation().getDegrees(), 0.0, kEpsilon));
+        () -> assertEquals(5.0 * Math.sqrt(2.0), transform.getX(), kEpsilon),
+        () -> assertEquals(0.0, transform.getY(), kEpsilon),
+        () -> assertEquals(0.0, transform.getRotation().getDegrees(), kEpsilon));
   }
 }
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/Pose3dTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/Pose3dTest.java
new file mode 100644
index 0000000..f13819f
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/Pose3dTest.java
@@ -0,0 +1,156 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.math.geometry;
+
+import static org.junit.jupiter.api.Assertions.assertAll;
+import static org.junit.jupiter.api.Assertions.assertEquals;
+import static org.junit.jupiter.api.Assertions.assertNotEquals;
+
+import edu.wpi.first.math.VecBuilder;
+import edu.wpi.first.math.util.Units;
+import org.junit.jupiter.api.Test;
+
+class Pose3dTest {
+  private static final double kEpsilon = 1E-9;
+
+  @Test
+  void testTransformByRotations() {
+    var initialPose =
+        new Pose3d(
+            new Translation3d(0.0, 0.0, 0.0),
+            new Rotation3d(
+                Units.degreesToRadians(0.0),
+                Units.degreesToRadians(0.0),
+                Units.degreesToRadians(0.0)));
+
+    var transform1 =
+        new Transform3d(
+            new Translation3d(0.0, 0.0, 0.0),
+            new Rotation3d(
+                Units.degreesToRadians(90.0),
+                Units.degreesToRadians(45.0),
+                Units.degreesToRadians(0.0)));
+
+    var transform2 =
+        new Transform3d(
+            new Translation3d(0.0, 0.0, 0.0),
+            new Rotation3d(
+                Units.degreesToRadians(-90.0),
+                Units.degreesToRadians(0.0),
+                Units.degreesToRadians(0.0)));
+
+    var transform3 =
+        new Transform3d(
+            new Translation3d(0.0, 0.0, 0.0),
+            new Rotation3d(
+                Units.degreesToRadians(0.0),
+                Units.degreesToRadians(-45.0),
+                Units.degreesToRadians(0.0)));
+
+    // This sequence of rotations should diverge from the origin and eventually return to it. When
+    // each rotation occurs, it should be performed intrinsicly, i.e. 'from the viewpoint' of and
+    // with
+    // the axes of the pose that is being transformed, just like how the translation is done 'from
+    // the
+    // viewpoint' of the pose that is being transformed.
+    var finalPose =
+        initialPose.transformBy(transform1).transformBy(transform2).transformBy(transform3);
+
+    assertAll(
+        () ->
+            assertEquals(
+                finalPose.getRotation().getX(), initialPose.getRotation().getX(), kEpsilon),
+        () ->
+            assertEquals(
+                finalPose.getRotation().getY(), initialPose.getRotation().getY(), kEpsilon),
+        () ->
+            assertEquals(
+                finalPose.getRotation().getZ(), initialPose.getRotation().getZ(), kEpsilon));
+  }
+
+  @Test
+  void testTransformBy() {
+    var zAxis = VecBuilder.fill(0.0, 0.0, 1.0);
+
+    var initial =
+        new Pose3d(
+            new Translation3d(1.0, 2.0, 0.0), new Rotation3d(zAxis, Units.degreesToRadians(45.0)));
+    var transformation =
+        new Transform3d(
+            new Translation3d(5.0, 0.0, 0.0), new Rotation3d(zAxis, Units.degreesToRadians(5.0)));
+
+    var transformed = initial.plus(transformation);
+
+    assertAll(
+        () -> assertEquals(1.0 + 5.0 / Math.sqrt(2.0), transformed.getX(), kEpsilon),
+        () -> assertEquals(2.0 + 5.0 / Math.sqrt(2.0), transformed.getY(), kEpsilon),
+        () ->
+            assertEquals(Units.degreesToRadians(50.0), transformed.getRotation().getZ(), kEpsilon));
+  }
+
+  @Test
+  void testRelativeTo() {
+    var zAxis = VecBuilder.fill(0.0, 0.0, 1.0);
+
+    var initial = new Pose3d(0.0, 0.0, 0.0, new Rotation3d(zAxis, Units.degreesToRadians(45.0)));
+    var last = new Pose3d(5.0, 5.0, 0.0, new Rotation3d(zAxis, Units.degreesToRadians(45.0)));
+
+    var finalRelativeToInitial = last.relativeTo(initial);
+
+    assertAll(
+        () -> assertEquals(5.0 * Math.sqrt(2.0), finalRelativeToInitial.getX(), kEpsilon),
+        () -> assertEquals(0.0, finalRelativeToInitial.getY(), kEpsilon),
+        () -> assertEquals(0.0, finalRelativeToInitial.getRotation().getZ(), kEpsilon));
+  }
+
+  @Test
+  void testEquality() {
+    var zAxis = VecBuilder.fill(0.0, 0.0, 1.0);
+
+    var one = new Pose3d(0.0, 5.0, 0.0, new Rotation3d(zAxis, Units.degreesToRadians(43.0)));
+    var two = new Pose3d(0.0, 5.0, 0.0, new Rotation3d(zAxis, Units.degreesToRadians(43.0)));
+    assertEquals(one, two);
+  }
+
+  @Test
+  void testInequality() {
+    var zAxis = VecBuilder.fill(0.0, 0.0, 1.0);
+
+    var one = new Pose3d(0.0, 5.0, 0.0, new Rotation3d(zAxis, Units.degreesToRadians(43.0)));
+    var two = new Pose3d(0.0, 1.524, 0.0, new Rotation3d(zAxis, Units.degreesToRadians(43.0)));
+    assertNotEquals(one, two);
+  }
+
+  @Test
+  void testMinus() {
+    var zAxis = VecBuilder.fill(0.0, 0.0, 1.0);
+
+    var initial = new Pose3d(0.0, 0.0, 0.0, new Rotation3d(zAxis, Units.degreesToRadians(45.0)));
+    var last = new Pose3d(5.0, 5.0, 0.0, new Rotation3d(zAxis, Units.degreesToRadians(45.0)));
+
+    final var transform = last.minus(initial);
+
+    assertAll(
+        () -> assertEquals(5.0 * Math.sqrt(2.0), transform.getX(), kEpsilon),
+        () -> assertEquals(0.0, transform.getY(), kEpsilon),
+        () -> assertEquals(0.0, transform.getRotation().getZ(), kEpsilon));
+  }
+
+  @Test
+  void testToPose2d() {
+    var pose =
+        new Pose3d(
+            1.0,
+            2.0,
+            3.0,
+            new Rotation3d(
+                Units.degreesToRadians(20.0),
+                Units.degreesToRadians(30.0),
+                Units.degreesToRadians(40.0)));
+    var expected = new Pose2d(1.0, 2.0, new Rotation2d(Units.degreesToRadians(40.0)));
+
+    assertEquals(expected, pose.toPose2d());
+  }
+}
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/QuaternionTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/QuaternionTest.java
new file mode 100644
index 0000000..7c7e103
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/QuaternionTest.java
@@ -0,0 +1,89 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.math.geometry;
+
+import static org.junit.jupiter.api.Assertions.assertEquals;
+
+import edu.wpi.first.math.util.Units;
+import org.junit.jupiter.api.Test;
+
+class QuaternionTest {
+  @Test
+  void testInit() {
+    // Identity
+    var q1 = new Quaternion();
+    assertEquals(1.0, q1.getW());
+    assertEquals(0.0, q1.getX());
+    assertEquals(0.0, q1.getY());
+    assertEquals(0.0, q1.getZ());
+
+    // Normalized
+    var q2 = new Quaternion(0.5, 0.5, 0.5, 0.5);
+    assertEquals(0.5, q2.getW());
+    assertEquals(0.5, q2.getX());
+    assertEquals(0.5, q2.getY());
+    assertEquals(0.5, q2.getZ());
+
+    // Unnormalized
+    var q3 = new Quaternion(0.75, 0.3, 0.4, 0.5);
+    assertEquals(0.75, q3.getW());
+    assertEquals(0.3, q3.getX());
+    assertEquals(0.4, q3.getY());
+    assertEquals(0.5, q3.getZ());
+
+    q3 = q3.normalize();
+    double norm = Math.sqrt(0.75 * 0.75 + 0.3 * 0.3 + 0.4 * 0.4 + 0.5 * 0.5);
+    assertEquals(0.75 / norm, q3.getW());
+    assertEquals(0.3 / norm, q3.getX());
+    assertEquals(0.4 / norm, q3.getY());
+    assertEquals(0.5 / norm, q3.getZ());
+    assertEquals(
+        1.0,
+        q3.getW() * q3.getW()
+            + q3.getX() * q3.getX()
+            + q3.getY() * q3.getY()
+            + q3.getZ() * q3.getZ());
+  }
+
+  @Test
+  void testTimes() {
+    // 90° CCW rotations around each axis
+    double c = Math.cos(Units.degreesToRadians(90.0) / 2.0);
+    double s = Math.sin(Units.degreesToRadians(90.0) / 2.0);
+    var xRot = new Quaternion(c, s, 0.0, 0.0);
+    var yRot = new Quaternion(c, 0.0, s, 0.0);
+    var zRot = new Quaternion(c, 0.0, 0.0, s);
+
+    // 90° CCW X rotation, 90° CCW Y rotation, and 90° CCW Z rotation should
+    // produce a 90° CCW Y rotation
+    var expected = yRot;
+    var actual = zRot.times(yRot).times(xRot);
+    assertEquals(expected.getW(), actual.getW(), 1e-9);
+    assertEquals(expected.getX(), actual.getX(), 1e-9);
+    assertEquals(expected.getY(), actual.getY(), 1e-9);
+    assertEquals(expected.getZ(), actual.getZ(), 1e-9);
+
+    // Identity
+    var q =
+        new Quaternion(
+            0.72760687510899891, 0.29104275004359953, 0.38805700005813276, 0.48507125007266594);
+    actual = q.times(q.inverse());
+    assertEquals(1.0, actual.getW());
+    assertEquals(0.0, actual.getX());
+    assertEquals(0.0, actual.getY());
+    assertEquals(0.0, actual.getZ());
+  }
+
+  @Test
+  void testInverse() {
+    var q = new Quaternion(0.75, 0.3, 0.4, 0.5);
+    var inv = q.inverse();
+
+    assertEquals(q.getW(), inv.getW());
+    assertEquals(-q.getX(), inv.getX());
+    assertEquals(-q.getY(), inv.getY());
+    assertEquals(-q.getZ(), inv.getZ());
+  }
+}
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/Rotation2dTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/Rotation2dTest.java
index cb3f0f3..6702f1d 100644
--- a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/Rotation2dTest.java
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/Rotation2dTest.java
@@ -15,12 +15,12 @@
 
   @Test
   void testRadiansToDegrees() {
-    var rot1 = new Rotation2d(Math.PI / 3);
-    var rot2 = new Rotation2d(Math.PI / 4);
+    var rot1 = Rotation2d.fromRadians(Math.PI / 3);
+    var rot2 = Rotation2d.fromRadians(Math.PI / 4);
 
     assertAll(
-        () -> assertEquals(rot1.getDegrees(), 60.0, kEpsilon),
-        () -> assertEquals(rot2.getDegrees(), 45.0, kEpsilon));
+        () -> assertEquals(60.0, rot1.getDegrees(), kEpsilon),
+        () -> assertEquals(45.0, rot2.getDegrees(), kEpsilon));
   }
 
   @Test
@@ -29,8 +29,8 @@
     var rot2 = Rotation2d.fromDegrees(30.0);
 
     assertAll(
-        () -> assertEquals(rot1.getRadians(), Math.PI / 4, kEpsilon),
-        () -> assertEquals(rot2.getRadians(), Math.PI / 6, kEpsilon));
+        () -> assertEquals(Math.PI / 4.0, rot1.getRadians(), kEpsilon),
+        () -> assertEquals(Math.PI / 6.0, rot2.getRadians(), kEpsilon));
   }
 
   @Test
@@ -39,8 +39,8 @@
     var rotated = zero.rotateBy(Rotation2d.fromDegrees(90.0));
 
     assertAll(
-        () -> assertEquals(rotated.getRadians(), Math.PI / 2.0, kEpsilon),
-        () -> assertEquals(rotated.getDegrees(), 90.0, kEpsilon));
+        () -> assertEquals(Math.PI / 2.0, rotated.getRadians(), kEpsilon),
+        () -> assertEquals(90.0, rotated.getDegrees(), kEpsilon));
   }
 
   @Test
@@ -48,7 +48,7 @@
     var rot = Rotation2d.fromDegrees(90.0);
     rot = rot.plus(Rotation2d.fromDegrees(30.0));
 
-    assertEquals(rot.getDegrees(), 120.0, kEpsilon);
+    assertEquals(120.0, rot.getDegrees(), kEpsilon);
   }
 
   @Test
@@ -56,7 +56,22 @@
     var rot1 = Rotation2d.fromDegrees(70.0);
     var rot2 = Rotation2d.fromDegrees(30.0);
 
-    assertEquals(rot1.minus(rot2).getDegrees(), 40.0, kEpsilon);
+    assertEquals(40.0, rot1.minus(rot2).getDegrees(), kEpsilon);
+  }
+
+  @Test
+  void testUnaryMinus() {
+    var rot = Rotation2d.fromDegrees(20.0);
+
+    assertEquals(-20.0, rot.unaryMinus().getDegrees(), kEpsilon);
+  }
+
+  @Test
+  void testMultiply() {
+    var rot = Rotation2d.fromDegrees(10.0);
+
+    assertEquals(30.0, rot.times(3.0).getDegrees(), kEpsilon);
+    assertEquals(410.0, rot.times(41.0).getDegrees(), kEpsilon);
   }
 
   @Test
@@ -65,9 +80,9 @@
     var rot2 = Rotation2d.fromDegrees(43.0);
     assertEquals(rot1, rot2);
 
-    var rot3 = Rotation2d.fromDegrees(-180.0);
-    var rot4 = Rotation2d.fromDegrees(180.0);
-    assertEquals(rot3, rot4);
+    rot1 = Rotation2d.fromDegrees(-180.0);
+    rot2 = Rotation2d.fromDegrees(180.0);
+    assertEquals(rot1, rot2);
   }
 
   @Test
@@ -76,4 +91,19 @@
     var rot2 = Rotation2d.fromDegrees(43.5);
     assertNotEquals(rot1, rot2);
   }
+
+  @Test
+  void testInterpolate() {
+    // 50 + (70 - 50) * 0.5 = 60
+    var rot1 = Rotation2d.fromDegrees(50);
+    var rot2 = Rotation2d.fromDegrees(70);
+    var interpolated = rot1.interpolate(rot2, 0.5);
+    assertEquals(60.0, interpolated.getDegrees(), kEpsilon);
+
+    // -160 minus half distance between 170 and -160 (15) = -175
+    rot1 = Rotation2d.fromDegrees(170);
+    rot2 = Rotation2d.fromDegrees(-160);
+    interpolated = rot1.interpolate(rot2, 0.5);
+    assertEquals(-175.0, interpolated.getDegrees());
+  }
 }
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/Rotation3dTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/Rotation3dTest.java
new file mode 100644
index 0000000..072a2e6
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/Rotation3dTest.java
@@ -0,0 +1,363 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.math.geometry;
+
+import static org.junit.jupiter.api.Assertions.assertAll;
+import static org.junit.jupiter.api.Assertions.assertEquals;
+import static org.junit.jupiter.api.Assertions.assertNotEquals;
+import static org.junit.jupiter.api.Assertions.assertThrows;
+
+import edu.wpi.first.math.MatBuilder;
+import edu.wpi.first.math.Matrix;
+import edu.wpi.first.math.Nat;
+import edu.wpi.first.math.VecBuilder;
+import edu.wpi.first.math.util.Units;
+import org.junit.jupiter.api.Test;
+
+class Rotation3dTest {
+  private static final double kEpsilon = 1E-9;
+
+  @Test
+  void testInitAxisAngleAndRollPitchYaw() {
+    final var xAxis = VecBuilder.fill(1.0, 0.0, 0.0);
+    final var rot1 = new Rotation3d(xAxis, Math.PI / 3);
+    final var rot2 = new Rotation3d(Math.PI / 3, 0.0, 0.0);
+    assertEquals(rot1, rot2);
+
+    final var yAxis = VecBuilder.fill(0.0, 1.0, 0.0);
+    final var rot3 = new Rotation3d(yAxis, Math.PI / 3);
+    final var rot4 = new Rotation3d(0.0, Math.PI / 3, 0.0);
+    assertEquals(rot3, rot4);
+
+    final var zAxis = VecBuilder.fill(0.0, 0.0, 1.0);
+    final var rot5 = new Rotation3d(zAxis, Math.PI / 3);
+    final var rot6 = new Rotation3d(0.0, 0.0, Math.PI / 3);
+    assertEquals(rot5, rot6);
+  }
+
+  @Test
+  void testInitRotationMatrix() {
+    // No rotation
+    final var R1 = Matrix.eye(Nat.N3());
+    final var rot1 = new Rotation3d(R1);
+    assertEquals(new Rotation3d(), rot1);
+
+    // 90 degree CCW rotation around z-axis
+    final var R2 = new Matrix<>(Nat.N3(), Nat.N3());
+    R2.assignBlock(0, 0, VecBuilder.fill(0.0, 1.0, 0.0));
+    R2.assignBlock(0, 1, VecBuilder.fill(-1.0, 0.0, 0.0));
+    R2.assignBlock(0, 2, VecBuilder.fill(0.0, 0.0, 1.0));
+    final var rot2 = new Rotation3d(R2);
+    final var expected2 = new Rotation3d(0.0, 0.0, Units.degreesToRadians(90.0));
+    assertEquals(expected2, rot2);
+
+    // Matrix that isn't orthogonal
+    final var R3 =
+        new MatBuilder<>(Nat.N3(), Nat.N3()).fill(1.0, 0.0, 0.0, 1.0, 0.0, 0.0, 1.0, 0.0, 0.0);
+    assertThrows(IllegalArgumentException.class, () -> new Rotation3d(R3));
+
+    // Matrix that's orthogonal but not special orthogonal
+    final var R4 = Matrix.eye(Nat.N3()).times(2.0);
+    assertThrows(IllegalArgumentException.class, () -> new Rotation3d(R4));
+  }
+
+  @Test
+  void testInitTwoVector() {
+    final var xAxis = VecBuilder.fill(1.0, 0.0, 0.0);
+    final var yAxis = VecBuilder.fill(0.0, 1.0, 0.0);
+    final var zAxis = VecBuilder.fill(0.0, 0.0, 1.0);
+
+    // 90 degree CW rotation around y-axis
+    final var rot1 = new Rotation3d(xAxis, zAxis);
+    final var expected1 = new Rotation3d(yAxis, -Math.PI / 2.0);
+    assertEquals(expected1, rot1);
+
+    // 45 degree CCW rotation around z-axis
+    final var rot2 = new Rotation3d(xAxis, VecBuilder.fill(1.0, 1.0, 0.0));
+    final var expected2 = new Rotation3d(zAxis, Math.PI / 4.0);
+    assertEquals(expected2, rot2);
+
+    // 0 degree rotation of x-axes
+    final var rot3 = new Rotation3d(xAxis, xAxis);
+    assertEquals(new Rotation3d(), rot3);
+
+    // 0 degree rotation of y-axes
+    final var rot4 = new Rotation3d(yAxis, yAxis);
+    assertEquals(new Rotation3d(), rot4);
+
+    // 0 degree rotation of z-axes
+    final var rot5 = new Rotation3d(zAxis, zAxis);
+    assertEquals(new Rotation3d(), rot5);
+
+    // 180 degree rotation tests. For 180 degree rotations, any quaternion with
+    // an orthogonal rotation axis is acceptable. The rotation axis and initial
+    // vector are orthogonal if their dot product is zero.
+
+    // 180 degree rotation of x-axes
+    final var rot6 = new Rotation3d(xAxis, xAxis.times(-1.0));
+    final var q6 = rot6.getQuaternion();
+    assertEquals(0.0, q6.getW());
+    assertEquals(
+        0.0,
+        q6.getX() * xAxis.get(0, 0) + q6.getY() * xAxis.get(1, 0) + q6.getZ() * xAxis.get(2, 0));
+
+    // 180 degree rotation of y-axes
+    final var rot7 = new Rotation3d(yAxis, yAxis.times(-1.0));
+    final var q7 = rot7.getQuaternion();
+    assertEquals(0.0, q7.getW());
+    assertEquals(
+        0.0,
+        q7.getX() * yAxis.get(0, 0) + q7.getY() * yAxis.get(1, 0) + q7.getZ() * yAxis.get(2, 0));
+
+    // 180 degree rotation of z-axes
+    final var rot8 = new Rotation3d(zAxis, zAxis.times(-1.0));
+    final var q8 = rot8.getQuaternion();
+    assertEquals(0.0, q8.getW());
+    assertEquals(
+        0.0,
+        q8.getX() * zAxis.get(0, 0) + q8.getY() * zAxis.get(1, 0) + q8.getZ() * zAxis.get(2, 0));
+  }
+
+  @Test
+  void testRadiansToDegrees() {
+    final var zAxis = VecBuilder.fill(0.0, 0.0, 1.0);
+
+    var rot1 = new Rotation3d(zAxis, Math.PI / 3);
+    assertAll(
+        () -> assertEquals(Units.degreesToRadians(0.0), rot1.getX(), kEpsilon),
+        () -> assertEquals(Units.degreesToRadians(0.0), rot1.getY(), kEpsilon),
+        () -> assertEquals(Units.degreesToRadians(60.0), rot1.getZ(), kEpsilon));
+
+    var rot2 = new Rotation3d(zAxis, Math.PI / 4);
+    assertAll(
+        () -> assertEquals(Units.degreesToRadians(0.0), rot2.getX(), kEpsilon),
+        () -> assertEquals(Units.degreesToRadians(0.0), rot2.getY(), kEpsilon),
+        () -> assertEquals(Units.degreesToRadians(45.0), rot2.getZ(), kEpsilon));
+  }
+
+  @Test
+  void testRadiansAndDegrees() {
+    final var zAxis = VecBuilder.fill(0.0, 0.0, 1.0);
+
+    var rot1 = new Rotation3d(zAxis, Units.degreesToRadians(45.0));
+    assertAll(
+        () -> assertEquals(0.0, rot1.getX(), kEpsilon),
+        () -> assertEquals(0.0, rot1.getY(), kEpsilon),
+        () -> assertEquals(Math.PI / 4.0, rot1.getZ(), kEpsilon));
+
+    var rot2 = new Rotation3d(zAxis, Units.degreesToRadians(30.0));
+    assertAll(
+        () -> assertEquals(0.0, rot2.getX(), kEpsilon),
+        () -> assertEquals(0.0, rot2.getY(), kEpsilon),
+        () -> assertEquals(Math.PI / 6.0, rot2.getZ(), kEpsilon));
+  }
+
+  @Test
+  void testRotationLoop() {
+    var rot = new Rotation3d();
+
+    rot = rot.plus(new Rotation3d(Units.degreesToRadians(90.0), 0.0, 0.0));
+    var expected = new Rotation3d(Units.degreesToRadians(90.0), 0.0, 0.0);
+    assertEquals(expected, rot);
+
+    rot = rot.plus(new Rotation3d(0.0, Units.degreesToRadians(90.0), 0.0));
+    expected =
+        new Rotation3d(
+            VecBuilder.fill(1.0 / Math.sqrt(3), 1.0 / Math.sqrt(3), -1.0 / Math.sqrt(3)),
+            Units.degreesToRadians(120.0));
+    assertEquals(expected, rot);
+
+    rot = rot.plus(new Rotation3d(0.0, 0.0, Units.degreesToRadians(90.0)));
+    expected = new Rotation3d(0.0, Units.degreesToRadians(90.0), 0.0);
+    assertEquals(expected, rot);
+
+    rot = rot.plus(new Rotation3d(0.0, Units.degreesToRadians(-90.0), 0.0));
+    assertEquals(new Rotation3d(), rot);
+  }
+
+  @Test
+  void testRotateByFromZeroX() {
+    final var xAxis = VecBuilder.fill(1.0, 0.0, 0.0);
+
+    final var zero = new Rotation3d();
+    var rotated = zero.rotateBy(new Rotation3d(xAxis, Units.degreesToRadians(90.0)));
+
+    var expected = new Rotation3d(xAxis, Units.degreesToRadians(90.0));
+    assertEquals(expected, rotated);
+  }
+
+  @Test
+  void testRotateByFromZeroY() {
+    final var yAxis = VecBuilder.fill(0.0, 1.0, 0.0);
+
+    final var zero = new Rotation3d();
+    var rotated = zero.rotateBy(new Rotation3d(yAxis, Units.degreesToRadians(90.0)));
+
+    var expected = new Rotation3d(yAxis, Units.degreesToRadians(90.0));
+    assertEquals(expected, rotated);
+  }
+
+  @Test
+  void testRotateByFromZeroZ() {
+    final var zAxis = VecBuilder.fill(0.0, 0.0, 1.0);
+
+    final var zero = new Rotation3d();
+    var rotated = zero.rotateBy(new Rotation3d(zAxis, Units.degreesToRadians(90.0)));
+
+    var expected = new Rotation3d(zAxis, Units.degreesToRadians(90.0));
+    assertEquals(expected, rotated);
+  }
+
+  @Test
+  void testRotateByNonZeroX() {
+    final var xAxis = VecBuilder.fill(1.0, 0.0, 0.0);
+
+    var rot = new Rotation3d(xAxis, Units.degreesToRadians(90.0));
+    rot = rot.plus(new Rotation3d(xAxis, Units.degreesToRadians(30.0)));
+
+    var expected = new Rotation3d(xAxis, Units.degreesToRadians(120.0));
+    assertEquals(expected, rot);
+  }
+
+  @Test
+  void testRotateByNonZeroY() {
+    final var yAxis = VecBuilder.fill(0.0, 1.0, 0.0);
+
+    var rot = new Rotation3d(yAxis, Units.degreesToRadians(90.0));
+    rot = rot.plus(new Rotation3d(yAxis, Units.degreesToRadians(30.0)));
+
+    var expected = new Rotation3d(yAxis, Units.degreesToRadians(120.0));
+    assertEquals(expected, rot);
+  }
+
+  @Test
+  void testRotateByNonZeroZ() {
+    final var zAxis = VecBuilder.fill(0.0, 0.0, 1.0);
+
+    var rot = new Rotation3d(zAxis, Units.degreesToRadians(90.0));
+    rot = rot.plus(new Rotation3d(zAxis, Units.degreesToRadians(30.0)));
+
+    var expected = new Rotation3d(zAxis, Units.degreesToRadians(120.0));
+    assertEquals(expected, rot);
+  }
+
+  @Test
+  void testMinus() {
+    final var zAxis = VecBuilder.fill(0.0, 0.0, 1.0);
+
+    var rot1 = new Rotation3d(zAxis, Units.degreesToRadians(70.0));
+    var rot2 = new Rotation3d(zAxis, Units.degreesToRadians(30.0));
+
+    assertEquals(rot1.minus(rot2).getZ(), Units.degreesToRadians(40.0), kEpsilon);
+  }
+
+  @Test
+  void testEquality() {
+    final var zAxis = VecBuilder.fill(0.0, 0.0, 1.0);
+
+    var rot1 = new Rotation3d(zAxis, Units.degreesToRadians(43.0));
+    var rot2 = new Rotation3d(zAxis, Units.degreesToRadians(43.0));
+    assertEquals(rot1, rot2);
+
+    rot1 = new Rotation3d(zAxis, Units.degreesToRadians(-180.0));
+    rot2 = new Rotation3d(zAxis, Units.degreesToRadians(180.0));
+    assertEquals(rot1, rot2);
+  }
+
+  @Test
+  void testAxisAngle() {
+    final var xAxis = VecBuilder.fill(1.0, 0.0, 0.0);
+    final var yAxis = VecBuilder.fill(0.0, 1.0, 0.0);
+    final var zAxis = VecBuilder.fill(0.0, 0.0, 1.0);
+
+    var rot1 = new Rotation3d(xAxis, Units.degreesToRadians(90.0));
+    assertEquals(xAxis, rot1.getAxis());
+    assertEquals(Math.PI / 2.0, rot1.getAngle(), 1e-9);
+
+    var rot2 = new Rotation3d(yAxis, Units.degreesToRadians(45.0));
+    assertEquals(yAxis, rot2.getAxis());
+    assertEquals(Math.PI / 4.0, rot2.getAngle(), 1e-9);
+
+    var rot3 = new Rotation3d(zAxis, Units.degreesToRadians(60.0));
+    assertEquals(zAxis, rot3.getAxis());
+    assertEquals(Math.PI / 3.0, rot3.getAngle(), 1e-9);
+  }
+
+  @Test
+  void testToRotation2d() {
+    var rotation =
+        new Rotation3d(
+            Units.degreesToRadians(20.0),
+            Units.degreesToRadians(30.0),
+            Units.degreesToRadians(40.0));
+    var expected = new Rotation2d(Units.degreesToRadians(40.0));
+
+    assertEquals(expected, rotation.toRotation2d());
+  }
+
+  @Test
+  void testInequality() {
+    final var zAxis = VecBuilder.fill(0.0, 0.0, 1.0);
+
+    var rot1 = new Rotation3d(zAxis, Units.degreesToRadians(43.0));
+    var rot2 = new Rotation3d(zAxis, Units.degreesToRadians(43.5));
+    assertNotEquals(rot1, rot2);
+  }
+
+  @Test
+  void testInterpolate() {
+    final var xAxis = VecBuilder.fill(1.0, 0.0, 0.0);
+    final var yAxis = VecBuilder.fill(0.0, 1.0, 0.0);
+    final var zAxis = VecBuilder.fill(0.0, 0.0, 1.0);
+
+    // 50 + (70 - 50) * 0.5 = 60
+    var rot1 = new Rotation3d(xAxis, Units.degreesToRadians(50));
+    var rot2 = new Rotation3d(xAxis, Units.degreesToRadians(70));
+    var interpolated = rot1.interpolate(rot2, 0.5);
+    assertEquals(Units.degreesToRadians(60.0), interpolated.getX(), kEpsilon);
+    assertEquals(Units.degreesToRadians(0.0), interpolated.getY(), kEpsilon);
+    assertEquals(Units.degreesToRadians(0.0), interpolated.getZ(), kEpsilon);
+
+    // -160 minus half distance between 170 and -160 (15) = -175
+    rot1 = new Rotation3d(xAxis, Units.degreesToRadians(170));
+    rot2 = new Rotation3d(xAxis, Units.degreesToRadians(-160));
+    interpolated = rot1.interpolate(rot2, 0.5);
+    assertEquals(Units.degreesToRadians(-175.0), interpolated.getX());
+    assertEquals(Units.degreesToRadians(0.0), interpolated.getY(), kEpsilon);
+    assertEquals(Units.degreesToRadians(0.0), interpolated.getZ());
+
+    // 50 + (70 - 50) * 0.5 = 60
+    rot1 = new Rotation3d(yAxis, Units.degreesToRadians(50));
+    rot2 = new Rotation3d(yAxis, Units.degreesToRadians(70));
+    interpolated = rot1.interpolate(rot2, 0.5);
+    assertEquals(Units.degreesToRadians(0.0), interpolated.getX(), kEpsilon);
+    assertEquals(Units.degreesToRadians(60.0), interpolated.getY(), kEpsilon);
+    assertEquals(Units.degreesToRadians(0.0), interpolated.getZ(), kEpsilon);
+
+    // -160 minus half distance between 170 and -160 (165) = 5
+    rot1 = new Rotation3d(yAxis, Units.degreesToRadians(170));
+    rot2 = new Rotation3d(yAxis, Units.degreesToRadians(-160));
+    interpolated = rot1.interpolate(rot2, 0.5);
+    assertEquals(Units.degreesToRadians(180.0), interpolated.getX(), kEpsilon);
+    assertEquals(Units.degreesToRadians(-5.0), interpolated.getY(), kEpsilon);
+    assertEquals(Units.degreesToRadians(180.0), interpolated.getZ(), kEpsilon);
+
+    // 50 + (70 - 50) * 0.5 = 60
+    rot1 = new Rotation3d(zAxis, Units.degreesToRadians(50));
+    rot2 = new Rotation3d(zAxis, Units.degreesToRadians(70));
+    interpolated = rot1.interpolate(rot2, 0.5);
+    assertEquals(Units.degreesToRadians(0.0), interpolated.getX(), kEpsilon);
+    assertEquals(Units.degreesToRadians(0.0), interpolated.getY(), kEpsilon);
+    assertEquals(Units.degreesToRadians(60.0), interpolated.getZ(), kEpsilon);
+
+    // -160 minus half distance between 170 and -160 (15) = -175
+    rot1 = new Rotation3d(zAxis, Units.degreesToRadians(170));
+    rot2 = new Rotation3d(zAxis, Units.degreesToRadians(-160));
+    interpolated = rot1.interpolate(rot2, 0.5);
+    assertEquals(Units.degreesToRadians(0.0), interpolated.getX(), kEpsilon);
+    assertEquals(Units.degreesToRadians(0.0), interpolated.getY(), kEpsilon);
+    assertEquals(Units.degreesToRadians(-175.0), interpolated.getZ(), kEpsilon);
+  }
+}
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/Transform2dTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/Transform2dTest.java
index 7265e25..93d8a0e 100644
--- a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/Transform2dTest.java
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/Transform2dTest.java
@@ -4,14 +4,11 @@
 
 package edu.wpi.first.math.geometry;
 
-import static org.junit.jupiter.api.Assertions.assertAll;
 import static org.junit.jupiter.api.Assertions.assertEquals;
 
 import org.junit.jupiter.api.Test;
 
 class Transform2dTest {
-  private static final double kEpsilon = 1E-9;
-
   @Test
   void testInverse() {
     var initial = new Pose2d(new Translation2d(1.0, 2.0), Rotation2d.fromDegrees(45.0));
@@ -20,14 +17,7 @@
     var transformed = initial.plus(transform);
     var untransformed = transformed.plus(transform.inverse());
 
-    assertAll(
-        () -> assertEquals(initial.getX(), untransformed.getX(), kEpsilon),
-        () -> assertEquals(initial.getY(), untransformed.getY(), kEpsilon),
-        () ->
-            assertEquals(
-                initial.getRotation().getDegrees(),
-                untransformed.getRotation().getDegrees(),
-                kEpsilon));
+    assertEquals(initial, untransformed);
   }
 
   @Test
@@ -39,13 +29,6 @@
     var transformedSeparate = initial.plus(transform1).plus(transform2);
     var transformedCombined = initial.plus(transform1.plus(transform2));
 
-    assertAll(
-        () -> assertEquals(transformedSeparate.getX(), transformedCombined.getX(), kEpsilon),
-        () -> assertEquals(transformedSeparate.getY(), transformedCombined.getY(), kEpsilon),
-        () ->
-            assertEquals(
-                transformedSeparate.getRotation().getDegrees(),
-                transformedCombined.getRotation().getDegrees(),
-                kEpsilon));
+    assertEquals(transformedSeparate, transformedCombined);
   }
 }
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/Transform3dTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/Transform3dTest.java
new file mode 100644
index 0000000..51d5f07
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/Transform3dTest.java
@@ -0,0 +1,50 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.math.geometry;
+
+import static org.junit.jupiter.api.Assertions.assertEquals;
+
+import edu.wpi.first.math.VecBuilder;
+import edu.wpi.first.math.util.Units;
+import org.junit.jupiter.api.Test;
+
+class Transform3dTest {
+  @Test
+  void testInverse() {
+    var zAxis = VecBuilder.fill(0.0, 0.0, 1.0);
+
+    var initial =
+        new Pose3d(
+            new Translation3d(1.0, 2.0, 3.0), new Rotation3d(zAxis, Units.degreesToRadians(45.0)));
+    var transform =
+        new Transform3d(
+            new Translation3d(5.0, 4.0, 3.0), new Rotation3d(zAxis, Units.degreesToRadians(5.0)));
+
+    var transformed = initial.plus(transform);
+    var untransformed = transformed.plus(transform.inverse());
+
+    assertEquals(initial, untransformed);
+  }
+
+  @Test
+  void testComposition() {
+    var zAxis = VecBuilder.fill(0.0, 0.0, 1.0);
+
+    var initial =
+        new Pose3d(
+            new Translation3d(1.0, 2.0, 3.0), new Rotation3d(zAxis, Units.degreesToRadians(45.0)));
+    var transform1 =
+        new Transform3d(
+            new Translation3d(5.0, 0.0, 0.0), new Rotation3d(zAxis, Units.degreesToRadians(5.0)));
+    var transform2 =
+        new Transform3d(
+            new Translation3d(0.0, 2.0, 0.0), new Rotation3d(zAxis, Units.degreesToRadians(5.0)));
+
+    var transformedSeparate = initial.plus(transform1).plus(transform2);
+    var transformedCombined = initial.plus(transform1.plus(transform2));
+
+    assertEquals(transformedSeparate, transformedCombined);
+  }
+}
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/Translation2dTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/Translation2dTest.java
index 2d8eeaa..c8f5690 100644
--- a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/Translation2dTest.java
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/Translation2dTest.java
@@ -21,8 +21,8 @@
     var sum = one.plus(two);
 
     assertAll(
-        () -> assertEquals(sum.getX(), 3.0, kEpsilon),
-        () -> assertEquals(sum.getY(), 8.0, kEpsilon));
+        () -> assertEquals(3.0, sum.getX(), kEpsilon),
+        () -> assertEquals(8.0, sum.getY(), kEpsilon));
   }
 
   @Test
@@ -33,8 +33,8 @@
     var difference = one.minus(two);
 
     assertAll(
-        () -> assertEquals(difference.getX(), -1.0, kEpsilon),
-        () -> assertEquals(difference.getY(), -2.0, kEpsilon));
+        () -> assertEquals(-1.0, difference.getX(), kEpsilon),
+        () -> assertEquals(-2.0, difference.getY(), kEpsilon));
   }
 
   @Test
@@ -43,8 +43,8 @@
     var rotated = another.rotateBy(Rotation2d.fromDegrees(90.0));
 
     assertAll(
-        () -> assertEquals(rotated.getX(), 0.0, kEpsilon),
-        () -> assertEquals(rotated.getY(), 3.0, kEpsilon));
+        () -> assertEquals(0.0, rotated.getX(), kEpsilon),
+        () -> assertEquals(3.0, rotated.getY(), kEpsilon));
   }
 
   @Test
@@ -53,8 +53,8 @@
     var mult = original.times(3);
 
     assertAll(
-        () -> assertEquals(mult.getX(), 9.0, kEpsilon),
-        () -> assertEquals(mult.getY(), 15.0, kEpsilon));
+        () -> assertEquals(9.0, mult.getX(), kEpsilon),
+        () -> assertEquals(15.0, mult.getY(), kEpsilon));
   }
 
   @Test
@@ -63,21 +63,21 @@
     var div = original.div(2);
 
     assertAll(
-        () -> assertEquals(div.getX(), 1.5, kEpsilon),
-        () -> assertEquals(div.getY(), 2.5, kEpsilon));
+        () -> assertEquals(1.5, div.getX(), kEpsilon),
+        () -> assertEquals(2.5, div.getY(), kEpsilon));
   }
 
   @Test
   void testNorm() {
     var one = new Translation2d(3.0, 5.0);
-    assertEquals(one.getNorm(), Math.hypot(3.0, 5.0), kEpsilon);
+    assertEquals(Math.hypot(3.0, 5.0), one.getNorm(), kEpsilon);
   }
 
   @Test
   void testDistance() {
     var one = new Translation2d(1, 1);
     var two = new Translation2d(6, 6);
-    assertEquals(one.getDistance(two), 5 * Math.sqrt(2), kEpsilon);
+    assertEquals(5.0 * Math.sqrt(2.0), one.getDistance(two), kEpsilon);
   }
 
   @Test
@@ -86,8 +86,8 @@
     var inverted = original.unaryMinus();
 
     assertAll(
-        () -> assertEquals(inverted.getX(), 4.5, kEpsilon),
-        () -> assertEquals(inverted.getY(), -7, kEpsilon));
+        () -> assertEquals(4.5, inverted.getX(), kEpsilon),
+        () -> assertEquals(-7.0, inverted.getY(), kEpsilon));
   }
 
   @Test
@@ -109,9 +109,9 @@
     var one = new Translation2d(Math.sqrt(2), Rotation2d.fromDegrees(45.0));
     var two = new Translation2d(2, Rotation2d.fromDegrees(60.0));
     assertAll(
-        () -> assertEquals(one.getX(), 1.0, kEpsilon),
-        () -> assertEquals(one.getY(), 1.0, kEpsilon),
-        () -> assertEquals(two.getX(), 1.0, kEpsilon),
-        () -> assertEquals(two.getY(), Math.sqrt(3), kEpsilon));
+        () -> assertEquals(1.0, one.getX(), kEpsilon),
+        () -> assertEquals(1.0, one.getY(), kEpsilon),
+        () -> assertEquals(1.0, two.getX(), kEpsilon),
+        () -> assertEquals(Math.sqrt(3.0), two.getY(), kEpsilon));
   }
 }
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/Translation3dTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/Translation3dTest.java
new file mode 100644
index 0000000..762425b
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/Translation3dTest.java
@@ -0,0 +1,153 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.math.geometry;
+
+import static org.junit.jupiter.api.Assertions.assertAll;
+import static org.junit.jupiter.api.Assertions.assertEquals;
+import static org.junit.jupiter.api.Assertions.assertNotEquals;
+
+import edu.wpi.first.math.VecBuilder;
+import edu.wpi.first.math.util.Units;
+import org.junit.jupiter.api.Test;
+
+class Translation3dTest {
+  private static final double kEpsilon = 1E-9;
+
+  @Test
+  void testSum() {
+    var one = new Translation3d(1.0, 3.0, 5.0);
+    var two = new Translation3d(2.0, 5.0, 8.0);
+
+    var sum = one.plus(two);
+
+    assertAll(
+        () -> assertEquals(3.0, sum.getX(), kEpsilon),
+        () -> assertEquals(8.0, sum.getY(), kEpsilon),
+        () -> assertEquals(13.0, sum.getZ(), kEpsilon));
+  }
+
+  @Test
+  void testDifference() {
+    var one = new Translation3d(1.0, 3.0, 5.0);
+    var two = new Translation3d(2.0, 5.0, 8.0);
+
+    var difference = one.minus(two);
+
+    assertAll(
+        () -> assertEquals(-1.0, difference.getX(), kEpsilon),
+        () -> assertEquals(-2.0, difference.getY(), kEpsilon),
+        () -> assertEquals(-3.0, difference.getZ(), kEpsilon));
+  }
+
+  @Test
+  void testRotateBy() {
+    var xAxis = VecBuilder.fill(1.0, 0.0, 0.0);
+    var yAxis = VecBuilder.fill(0.0, 1.0, 0.0);
+    var zAxis = VecBuilder.fill(0.0, 0.0, 1.0);
+
+    var translation = new Translation3d(1.0, 2.0, 3.0);
+
+    var rotated1 = translation.rotateBy(new Rotation3d(xAxis, Units.degreesToRadians(90.0)));
+    assertAll(
+        () -> assertEquals(1.0, rotated1.getX(), kEpsilon),
+        () -> assertEquals(-3.0, rotated1.getY(), kEpsilon),
+        () -> assertEquals(2.0, rotated1.getZ(), kEpsilon));
+
+    var rotated2 = translation.rotateBy(new Rotation3d(yAxis, Units.degreesToRadians(90.0)));
+    assertAll(
+        () -> assertEquals(3.0, rotated2.getX(), kEpsilon),
+        () -> assertEquals(2.0, rotated2.getY(), kEpsilon),
+        () -> assertEquals(-1.0, rotated2.getZ(), kEpsilon));
+
+    var rotated3 = translation.rotateBy(new Rotation3d(zAxis, Units.degreesToRadians(90.0)));
+    assertAll(
+        () -> assertEquals(-2.0, rotated3.getX(), kEpsilon),
+        () -> assertEquals(1.0, rotated3.getY(), kEpsilon),
+        () -> assertEquals(3.0, rotated3.getZ(), kEpsilon));
+  }
+
+  @Test
+  void testToTranslation2d() {
+    var translation = new Translation3d(1.0, 2.0, 3.0);
+    var expected = new Translation2d(1.0, 2.0);
+
+    assertEquals(expected, translation.toTranslation2d());
+  }
+
+  @Test
+  void testMultiplication() {
+    var original = new Translation3d(3.0, 5.0, 7.0);
+    var mult = original.times(3);
+
+    assertAll(
+        () -> assertEquals(9.0, mult.getX(), kEpsilon),
+        () -> assertEquals(15.0, mult.getY(), kEpsilon),
+        () -> assertEquals(21.0, mult.getZ(), kEpsilon));
+  }
+
+  @Test
+  void testDivision() {
+    var original = new Translation3d(3.0, 5.0, 7.0);
+    var div = original.div(2);
+
+    assertAll(
+        () -> assertEquals(1.5, div.getX(), kEpsilon),
+        () -> assertEquals(2.5, div.getY(), kEpsilon),
+        () -> assertEquals(3.5, div.getZ(), kEpsilon));
+  }
+
+  @Test
+  void testNorm() {
+    var one = new Translation3d(3.0, 5.0, 7.0);
+    assertEquals(Math.sqrt(83.0), one.getNorm(), kEpsilon);
+  }
+
+  @Test
+  void testDistance() {
+    var one = new Translation3d(1.0, 1.0, 1.0);
+    var two = new Translation3d(6.0, 6.0, 6.0);
+    assertEquals(5.0 * Math.sqrt(3.0), one.getDistance(two), kEpsilon);
+  }
+
+  @Test
+  void testUnaryMinus() {
+    var original = new Translation3d(-4.5, 7.0, 9.0);
+    var inverted = original.unaryMinus();
+
+    assertAll(
+        () -> assertEquals(4.5, inverted.getX(), kEpsilon),
+        () -> assertEquals(-7.0, inverted.getY(), kEpsilon),
+        () -> assertEquals(-9.0, inverted.getZ(), kEpsilon));
+  }
+
+  @Test
+  void testEquality() {
+    var one = new Translation3d(9, 5.5, 3.5);
+    var two = new Translation3d(9, 5.5, 3.5);
+    assertEquals(one, two);
+  }
+
+  @Test
+  void testInequality() {
+    var one = new Translation3d(9, 5.5, 3.5);
+    var two = new Translation3d(9, 5.7, 3.5);
+    assertNotEquals(one, two);
+  }
+
+  @Test
+  void testPolarConstructor() {
+    var zAxis = VecBuilder.fill(0.0, 0.0, 1.0);
+
+    var one = new Translation3d(Math.sqrt(2), new Rotation3d(zAxis, Units.degreesToRadians(45.0)));
+    var two = new Translation3d(2, new Rotation3d(zAxis, Units.degreesToRadians(60.0)));
+    assertAll(
+        () -> assertEquals(1.0, one.getX(), kEpsilon),
+        () -> assertEquals(1.0, one.getY(), kEpsilon),
+        () -> assertEquals(0.0, one.getZ(), kEpsilon),
+        () -> assertEquals(1.0, two.getX(), kEpsilon),
+        () -> assertEquals(Math.sqrt(3.0), two.getY(), kEpsilon),
+        () -> assertEquals(0.0, two.getZ(), kEpsilon));
+  }
+}
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/Twist2dTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/Twist2dTest.java
index 69a4c86..4108a62 100644
--- a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/Twist2dTest.java
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/Twist2dTest.java
@@ -4,35 +4,28 @@
 
 package edu.wpi.first.math.geometry;
 
-import static org.junit.jupiter.api.Assertions.assertAll;
 import static org.junit.jupiter.api.Assertions.assertEquals;
 import static org.junit.jupiter.api.Assertions.assertNotEquals;
 
 import org.junit.jupiter.api.Test;
 
 class Twist2dTest {
-  private static final double kEpsilon = 1E-9;
-
   @Test
-  void testStraightLineTwist() {
+  void testStraight() {
     var straight = new Twist2d(5.0, 0.0, 0.0);
     var straightPose = new Pose2d().exp(straight);
 
-    assertAll(
-        () -> assertEquals(straightPose.getX(), 5.0, kEpsilon),
-        () -> assertEquals(straightPose.getY(), 0.0, kEpsilon),
-        () -> assertEquals(straightPose.getRotation().getRadians(), 0.0, kEpsilon));
+    var expected = new Pose2d(5.0, 0.0, new Rotation2d());
+    assertEquals(expected, straightPose);
   }
 
   @Test
-  void testQuarterCirleTwist() {
+  void testQuarterCirle() {
     var quarterCircle = new Twist2d(5.0 / 2.0 * Math.PI, 0, Math.PI / 2.0);
     var quarterCirclePose = new Pose2d().exp(quarterCircle);
 
-    assertAll(
-        () -> assertEquals(quarterCirclePose.getX(), 5.0, kEpsilon),
-        () -> assertEquals(quarterCirclePose.getY(), 5.0, kEpsilon),
-        () -> assertEquals(quarterCirclePose.getRotation().getDegrees(), 90.0, kEpsilon));
+    var expected = new Pose2d(5.0, 5.0, Rotation2d.fromDegrees(90.0));
+    assertEquals(expected, quarterCirclePose);
   }
 
   @Test
@@ -40,10 +33,8 @@
     var diagonal = new Twist2d(2.0, 2.0, 0.0);
     var diagonalPose = new Pose2d().exp(diagonal);
 
-    assertAll(
-        () -> assertEquals(diagonalPose.getX(), 2.0, kEpsilon),
-        () -> assertEquals(diagonalPose.getY(), 2.0, kEpsilon),
-        () -> assertEquals(diagonalPose.getRotation().getDegrees(), 0.0, kEpsilon));
+    var expected = new Pose2d(2.0, 2.0, new Rotation2d());
+    assertEquals(expected, diagonalPose);
   }
 
   @Test
@@ -67,9 +58,11 @@
 
     final var twist = start.log(end);
 
-    assertAll(
-        () -> assertEquals(twist.dx, 5.0 / 2.0 * Math.PI, kEpsilon),
-        () -> assertEquals(twist.dy, 0.0, kEpsilon),
-        () -> assertEquals(twist.dtheta, Math.PI / 2.0, kEpsilon));
+    var expected = new Twist2d(5.0 / 2.0 * Math.PI, 0.0, Math.PI / 2.0);
+    assertEquals(expected, twist);
+
+    // Make sure computed twist gives back original end pose
+    final var reapplied = start.exp(twist);
+    assertEquals(end, reapplied);
   }
 }
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/Twist3dTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/Twist3dTest.java
new file mode 100644
index 0000000..bb3bbb7
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/geometry/Twist3dTest.java
@@ -0,0 +1,124 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.math.geometry;
+
+import static org.junit.jupiter.api.Assertions.assertEquals;
+import static org.junit.jupiter.api.Assertions.assertNotEquals;
+
+import edu.wpi.first.math.VecBuilder;
+import edu.wpi.first.math.util.Units;
+import org.junit.jupiter.api.Test;
+
+class Twist3dTest {
+  @Test
+  void testStraightX() {
+    var straight = new Twist3d(5.0, 0.0, 0.0, 0.0, 0.0, 0.0);
+    var straightPose = new Pose3d().exp(straight);
+
+    var expected = new Pose3d(5.0, 0.0, 0.0, new Rotation3d());
+    assertEquals(expected, straightPose);
+  }
+
+  @Test
+  void testStraightY() {
+    var straight = new Twist3d(0.0, 5.0, 0.0, 0.0, 0.0, 0.0);
+    var straightPose = new Pose3d().exp(straight);
+
+    var expected = new Pose3d(0.0, 5.0, 0.0, new Rotation3d());
+    assertEquals(expected, straightPose);
+  }
+
+  @Test
+  void testStraightZ() {
+    var straight = new Twist3d(0.0, 0.0, 5.0, 0.0, 0.0, 0.0);
+    var straightPose = new Pose3d().exp(straight);
+
+    var expected = new Pose3d(0.0, 0.0, 5.0, new Rotation3d());
+    assertEquals(expected, straightPose);
+  }
+
+  @Test
+  void testQuarterCirle() {
+    var zAxis = VecBuilder.fill(0.0, 0.0, 1.0);
+
+    var quarterCircle = new Twist3d(5.0 / 2.0 * Math.PI, 0.0, 0.0, 0.0, 0.0, Math.PI / 2.0);
+    var quarterCirclePose = new Pose3d().exp(quarterCircle);
+
+    var expected = new Pose3d(5.0, 5.0, 0.0, new Rotation3d(zAxis, Units.degreesToRadians(90.0)));
+    assertEquals(expected, quarterCirclePose);
+  }
+
+  @Test
+  void testDiagonalNoDtheta() {
+    var diagonal = new Twist3d(2.0, 2.0, 0.0, 0.0, 0.0, 0.0);
+    var diagonalPose = new Pose3d().exp(diagonal);
+
+    var expected = new Pose3d(2.0, 2.0, 0.0, new Rotation3d());
+    assertEquals(expected, diagonalPose);
+  }
+
+  @Test
+  void testEquality() {
+    var one = new Twist3d(5, 1, 0, 0.0, 0.0, 3.0);
+    var two = new Twist3d(5, 1, 0, 0.0, 0.0, 3.0);
+    assertEquals(one, two);
+  }
+
+  @Test
+  void testInequality() {
+    var one = new Twist3d(5, 1, 0, 0.0, 0.0, 3.0);
+    var two = new Twist3d(5, 1.2, 0, 0.0, 0.0, 3.0);
+    assertNotEquals(one, two);
+  }
+
+  @Test
+  void testPose3dLogX() {
+    final var start = new Pose3d();
+    final var end =
+        new Pose3d(0.0, 5.0, 5.0, new Rotation3d(Units.degreesToRadians(90.0), 0.0, 0.0));
+
+    final var twist = start.log(end);
+
+    var expected =
+        new Twist3d(0.0, 5.0 / 2.0 * Math.PI, 0.0, Units.degreesToRadians(90.0), 0.0, 0.0);
+    assertEquals(expected, twist);
+
+    // Make sure computed twist gives back original end pose
+    final var reapplied = start.exp(twist);
+    assertEquals(end, reapplied);
+  }
+
+  @Test
+  void testPose3dLogY() {
+    final var start = new Pose3d();
+    final var end =
+        new Pose3d(5.0, 0.0, 5.0, new Rotation3d(0.0, Units.degreesToRadians(90.0), 0.0));
+
+    final var twist = start.log(end);
+
+    var expected = new Twist3d(0.0, 0.0, 5.0 / 2.0 * Math.PI, 0.0, Math.PI / 2.0, 0.0);
+    assertEquals(expected, twist);
+
+    // Make sure computed twist gives back original end pose
+    final var reapplied = start.exp(twist);
+    assertEquals(end, reapplied);
+  }
+
+  @Test
+  void testPose3dLogZ() {
+    final var start = new Pose3d();
+    final var end =
+        new Pose3d(5.0, 5.0, 0.0, new Rotation3d(0.0, 0.0, Units.degreesToRadians(90.0)));
+
+    final var twist = start.log(end);
+
+    var expected = new Twist3d(5.0 / 2.0 * Math.PI, 0.0, 0.0, 0.0, 0.0, Math.PI / 2.0);
+    assertEquals(expected, twist);
+
+    // Make sure computed twist gives back original end pose
+    final var reapplied = start.exp(twist);
+    assertEquals(end, reapplied);
+  }
+}
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/interpolation/TimeInterpolatableBufferTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/interpolation/TimeInterpolatableBufferTest.java
index 7b0e334..e65d27f 100644
--- a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/interpolation/TimeInterpolatableBufferTest.java
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/interpolation/TimeInterpolatableBufferTest.java
@@ -16,15 +16,15 @@
     TimeInterpolatableBuffer<Rotation2d> buffer = TimeInterpolatableBuffer.createBuffer(10);
 
     buffer.addSample(0, new Rotation2d());
-    assertEquals(0, buffer.getSample(0).getRadians(), 0.001);
+    assertEquals(0, buffer.getSample(0).get().getRadians(), 0.001);
     buffer.addSample(1, new Rotation2d(1));
-    assertEquals(0.5, buffer.getSample(0.5).getRadians(), 0.001);
-    assertEquals(1.0, buffer.getSample(1.0).getRadians(), 0.001);
+    assertEquals(0.5, buffer.getSample(0.5).get().getRadians(), 0.001);
+    assertEquals(1.0, buffer.getSample(1.0).get().getRadians(), 0.001);
     buffer.addSample(3, new Rotation2d(2));
-    assertEquals(1.5, buffer.getSample(2).getRadians(), 0.001);
+    assertEquals(1.5, buffer.getSample(2).get().getRadians(), 0.001);
 
     buffer.addSample(10.5, new Rotation2d(2));
-    assertEquals(new Rotation2d(1), buffer.getSample(0));
+    assertEquals(new Rotation2d(1), buffer.getSample(0).get());
   }
 
   @Test
@@ -34,7 +34,7 @@
     // We expect to be at (1 - 1/Math.sqrt(2), 1/Math.sqrt(2), 45deg) at t=0.5
     buffer.addSample(0, new Pose2d(0, 0, Rotation2d.fromDegrees(90)));
     buffer.addSample(1, new Pose2d(1, 1, Rotation2d.fromDegrees(0)));
-    Pose2d sample = buffer.getSample(0.5);
+    Pose2d sample = buffer.getSample(0.5).get();
 
     assertEquals(1 - 1 / Math.sqrt(2), sample.getTranslation().getX(), 0.01);
     assertEquals(1 / Math.sqrt(2), sample.getTranslation().getY(), 0.01);
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/kinematics/DifferentialDriveOdometryTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/kinematics/DifferentialDriveOdometryTest.java
index f85e8fb..6d15f64 100644
--- a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/kinematics/DifferentialDriveOdometryTest.java
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/kinematics/DifferentialDriveOdometryTest.java
@@ -14,11 +14,11 @@
 class DifferentialDriveOdometryTest {
   private static final double kEpsilon = 1E-9;
   private final DifferentialDriveOdometry m_odometry =
-      new DifferentialDriveOdometry(new Rotation2d());
+      new DifferentialDriveOdometry(new Rotation2d(), 0, 0);
 
   @Test
   void testOdometryWithEncoderDistances() {
-    m_odometry.resetPosition(new Pose2d(), Rotation2d.fromDegrees(45));
+    m_odometry.resetPosition(Rotation2d.fromDegrees(45), 0, 0, new Pose2d());
     var pose = m_odometry.update(Rotation2d.fromDegrees(135.0), 0.0, 5 * Math.PI);
 
     assertAll(
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/kinematics/MecanumDriveKinematicsTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/kinematics/MecanumDriveKinematicsTest.java
index b3546f5..18d3ec7 100644
--- a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/kinematics/MecanumDriveKinematicsTest.java
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/kinematics/MecanumDriveKinematicsTest.java
@@ -45,6 +45,17 @@
   }
 
   @Test
+  void testStraightLineForwardKinematicsKinematicsWithDeltas() {
+    var wheelDeltas = new MecanumDriveWheelPositions(3.536, 3.536, 3.536, 3.536);
+    var twist = m_kinematics.toTwist2d(wheelDeltas);
+
+    assertAll(
+        () -> assertEquals(3.536, twist.dx, 0.1),
+        () -> assertEquals(0, twist.dy, 0.1),
+        () -> assertEquals(0, twist.dtheta, 0.1));
+  }
+
+  @Test
   void testStrafeInverseKinematics() {
     ChassisSpeeds speeds = new ChassisSpeeds(0, 4, 0);
     var moduleStates = m_kinematics.toWheelSpeeds(speeds);
@@ -68,6 +79,17 @@
   }
 
   @Test
+  void testStrafeForwardKinematicsKinematicsWithDeltas() {
+    var wheelDeltas = new MecanumDriveWheelPositions(-2.828427, 2.828427, 2.828427, -2.828427);
+    var twist = m_kinematics.toTwist2d(wheelDeltas);
+
+    assertAll(
+        () -> assertEquals(0, twist.dx, 0.1),
+        () -> assertEquals(2.8284, twist.dy, 0.1),
+        () -> assertEquals(0, twist.dtheta, 0.1));
+  }
+
+  @Test
   void testRotationInverseKinematics() {
     ChassisSpeeds speeds = new ChassisSpeeds(0, 0, 2 * Math.PI);
     var moduleStates = m_kinematics.toWheelSpeeds(speeds);
@@ -91,6 +113,17 @@
   }
 
   @Test
+  void testRotationForwardKinematicsKinematicsWithDeltas() {
+    var wheelDeltas = new MecanumDriveWheelPositions(-150.79645, 150.79645, -150.79645, 150.79645);
+    var twist = m_kinematics.toTwist2d(wheelDeltas);
+
+    assertAll(
+        () -> assertEquals(0, twist.dx, 0.1),
+        () -> assertEquals(0, twist.dy, 0.1),
+        () -> assertEquals(2 * Math.PI, twist.dtheta, 0.1));
+  }
+
+  @Test
   void testMixedTranslationRotationInverseKinematics() {
     ChassisSpeeds speeds = new ChassisSpeeds(2, 3, 1);
     var moduleStates = m_kinematics.toWheelSpeeds(speeds);
@@ -114,6 +147,17 @@
   }
 
   @Test
+  void testMixedTranslationRotationForwardKinematicsKinematicsWithDeltas() {
+    var wheelDeltas = new MecanumDriveWheelPositions(-17.677670, 20.51, -13.44, 16.26);
+    var twist = m_kinematics.toTwist2d(wheelDeltas);
+
+    assertAll(
+        () -> assertEquals(1.413, twist.dx, 0.1),
+        () -> assertEquals(2.122, twist.dy, 0.1),
+        () -> assertEquals(0.707, twist.dtheta, 0.1));
+  }
+
+  @Test
   void testOffCenterRotationInverseKinematics() {
     ChassisSpeeds speeds = new ChassisSpeeds(0, 0, 1);
     var moduleStates = m_kinematics.toWheelSpeeds(speeds, m_fl);
@@ -137,6 +181,17 @@
   }
 
   @Test
+  void testOffCenterRotationForwardKinematicsKinematicsWithDeltas() {
+    var wheelDeltas = new MecanumDriveWheelPositions(0, 16.971, -16.971, 33.941);
+    var twist = m_kinematics.toTwist2d(wheelDeltas);
+
+    assertAll(
+        () -> assertEquals(8.48525, twist.dx, 0.1),
+        () -> assertEquals(-8.48525, twist.dy, 0.1),
+        () -> assertEquals(0.707, twist.dtheta, 0.1));
+  }
+
+  @Test
   void testOffCenterTranslationRotationInverseKinematics() {
     ChassisSpeeds speeds = new ChassisSpeeds(5, 2, 1);
     var moduleStates = m_kinematics.toWheelSpeeds(speeds, m_fl);
@@ -160,6 +215,17 @@
   }
 
   @Test
+  void testOffCenterRotationTranslationForwardKinematicsKinematicsWithDeltas() {
+    var wheelDeltas = new MecanumDriveWheelPositions(2.12, 21.92, -12.02, 36.06);
+    var twist = m_kinematics.toTwist2d(wheelDeltas);
+
+    assertAll(
+        () -> assertEquals(12.02, twist.dx, 0.1),
+        () -> assertEquals(-7.07, twist.dy, 0.1),
+        () -> assertEquals(0.707, twist.dtheta, 0.1));
+  }
+
+  @Test
   void testDesaturate() {
     var wheelSpeeds = new MecanumDriveWheelSpeeds(5, 6, 4, 7);
     wheelSpeeds.desaturate(5.5);
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/kinematics/MecanumDriveOdometryTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/kinematics/MecanumDriveOdometryTest.java
index 3f43109..cf6a439 100644
--- a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/kinematics/MecanumDriveOdometryTest.java
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/kinematics/MecanumDriveOdometryTest.java
@@ -10,6 +10,10 @@
 import edu.wpi.first.math.geometry.Pose2d;
 import edu.wpi.first.math.geometry.Rotation2d;
 import edu.wpi.first.math.geometry.Translation2d;
+import edu.wpi.first.math.trajectory.TrajectoryConfig;
+import edu.wpi.first.math.trajectory.TrajectoryGenerator;
+import java.util.List;
+import java.util.Random;
 import org.junit.jupiter.api.Test;
 
 class MecanumDriveOdometryTest {
@@ -21,15 +25,19 @@
   private final MecanumDriveKinematics m_kinematics =
       new MecanumDriveKinematics(m_fl, m_fr, m_bl, m_br);
 
+  private final MecanumDriveWheelPositions zero = new MecanumDriveWheelPositions();
+
   private final MecanumDriveOdometry m_odometry =
-      new MecanumDriveOdometry(m_kinematics, new Rotation2d());
+      new MecanumDriveOdometry(m_kinematics, new Rotation2d(), zero);
 
   @Test
   void testMultipleConsecutiveUpdates() {
-    var wheelSpeeds = new MecanumDriveWheelSpeeds(3.536, 3.536, 3.536, 3.536);
+    var wheelPositions = new MecanumDriveWheelPositions(3.536, 3.536, 3.536, 3.536);
 
-    m_odometry.updateWithTime(0.0, new Rotation2d(), wheelSpeeds);
-    var secondPose = m_odometry.updateWithTime(0.0, new Rotation2d(), wheelSpeeds);
+    m_odometry.resetPosition(new Rotation2d(), wheelPositions, new Pose2d());
+
+    m_odometry.update(new Rotation2d(), wheelPositions);
+    var secondPose = m_odometry.update(new Rotation2d(), wheelPositions);
 
     assertAll(
         () -> assertEquals(secondPose.getX(), 0.0, 0.01),
@@ -39,11 +47,12 @@
 
   @Test
   void testTwoIterations() {
-    // 5 units/sec  in the x axis (forward)
-    final var wheelSpeeds = new MecanumDriveWheelSpeeds(3.536, 3.536, 3.536, 3.536);
+    // 5 units/sec  in the x-axis (forward)
+    final var wheelPositions = new MecanumDriveWheelPositions(0.3536, 0.3536, 0.3536, 0.3536);
+    m_odometry.resetPosition(new Rotation2d(), new MecanumDriveWheelPositions(), new Pose2d());
 
-    m_odometry.updateWithTime(0.0, new Rotation2d(), new MecanumDriveWheelSpeeds());
-    var pose = m_odometry.updateWithTime(0.10, new Rotation2d(), wheelSpeeds);
+    m_odometry.update(new Rotation2d(), new MecanumDriveWheelPositions());
+    var pose = m_odometry.update(new Rotation2d(), wheelPositions);
 
     assertAll(
         () -> assertEquals(0.3536, pose.getX(), 0.01),
@@ -55,10 +64,11 @@
   void test90degreeTurn() {
     // This is a 90 degree turn about the point between front left and rear left wheels
     // fl -13.328649 fr 39.985946 rl -13.328649 rr 39.985946
-    final var wheelSpeeds = new MecanumDriveWheelSpeeds(-13.328, 39.986, -13.329, 39.986);
+    final var wheelPositions = new MecanumDriveWheelPositions(-13.328, 39.986, -13.329, 39.986);
+    m_odometry.resetPosition(new Rotation2d(), new MecanumDriveWheelPositions(), new Pose2d());
 
-    m_odometry.updateWithTime(0.0, new Rotation2d(), new MecanumDriveWheelSpeeds());
-    final var pose = m_odometry.updateWithTime(1.0, Rotation2d.fromDegrees(90.0), wheelSpeeds);
+    m_odometry.update(new Rotation2d(), new MecanumDriveWheelPositions());
+    final var pose = m_odometry.update(Rotation2d.fromDegrees(90.0), wheelPositions);
 
     assertAll(
         () -> assertEquals(8.4855, pose.getX(), 0.01),
@@ -70,14 +80,188 @@
   void testGyroAngleReset() {
     var gyro = Rotation2d.fromDegrees(90.0);
     var fieldAngle = Rotation2d.fromDegrees(0.0);
-    m_odometry.resetPosition(new Pose2d(new Translation2d(), fieldAngle), gyro);
-    var speeds = new MecanumDriveWheelSpeeds(3.536, 3.536, 3.536, 3.536);
-    m_odometry.updateWithTime(0.0, gyro, new MecanumDriveWheelSpeeds());
-    var pose = m_odometry.updateWithTime(1.0, gyro, speeds);
+    m_odometry.resetPosition(
+        gyro, new MecanumDriveWheelPositions(), new Pose2d(new Translation2d(), fieldAngle));
+    var speeds = new MecanumDriveWheelPositions(3.536, 3.536, 3.536, 3.536);
+    m_odometry.update(gyro, new MecanumDriveWheelPositions());
+    var pose = m_odometry.update(gyro, speeds);
 
     assertAll(
         () -> assertEquals(3.536, pose.getX(), 0.1),
         () -> assertEquals(0.0, pose.getY(), 0.1),
         () -> assertEquals(0.0, pose.getRotation().getRadians(), 0.1));
   }
+
+  @Test
+  void testAccuracyFacingTrajectory() {
+    var kinematics =
+        new MecanumDriveKinematics(
+            new Translation2d(1, 1), new Translation2d(1, -1),
+            new Translation2d(-1, -1), new Translation2d(-1, 1));
+
+    var wheelPositions = new MecanumDriveWheelPositions();
+
+    var odometry =
+        new MecanumDriveOdometry(kinematics, new Rotation2d(), wheelPositions, new Pose2d());
+
+    var trajectory =
+        TrajectoryGenerator.generateTrajectory(
+            List.of(
+                new Pose2d(),
+                new Pose2d(20, 20, Rotation2d.fromDegrees(0)),
+                new Pose2d(10, 10, Rotation2d.fromDegrees(180)),
+                new Pose2d(30, 30, Rotation2d.fromDegrees(0)),
+                new Pose2d(20, 20, Rotation2d.fromDegrees(180)),
+                new Pose2d(10, 10, Rotation2d.fromDegrees(0))),
+            new TrajectoryConfig(0.5, 2));
+
+    var rand = new Random(5190);
+
+    final double dt = 0.02;
+    double t = 0.0;
+
+    double maxError = Double.NEGATIVE_INFINITY;
+    double errorSum = 0;
+    double odometryDistanceTravelled = 0;
+    double trajectoryDistanceTravelled = 0;
+    while (t <= trajectory.getTotalTimeSeconds()) {
+      var groundTruthState = trajectory.sample(t);
+
+      trajectoryDistanceTravelled +=
+          groundTruthState.velocityMetersPerSecond * dt
+              + 0.5 * groundTruthState.accelerationMetersPerSecondSq * dt * dt;
+
+      var wheelSpeeds =
+          kinematics.toWheelSpeeds(
+              new ChassisSpeeds(
+                  groundTruthState.velocityMetersPerSecond,
+                  0,
+                  groundTruthState.velocityMetersPerSecond
+                      * groundTruthState.curvatureRadPerMeter));
+
+      wheelSpeeds.frontLeftMetersPerSecond += rand.nextGaussian() * 0.1;
+      wheelSpeeds.frontRightMetersPerSecond += rand.nextGaussian() * 0.1;
+      wheelSpeeds.rearLeftMetersPerSecond += rand.nextGaussian() * 0.1;
+      wheelSpeeds.rearRightMetersPerSecond += rand.nextGaussian() * 0.1;
+
+      wheelPositions.frontLeftMeters += wheelSpeeds.frontLeftMetersPerSecond * dt;
+      wheelPositions.frontRightMeters += wheelSpeeds.frontRightMetersPerSecond * dt;
+      wheelPositions.rearLeftMeters += wheelSpeeds.rearLeftMetersPerSecond * dt;
+      wheelPositions.rearRightMeters += wheelSpeeds.rearRightMetersPerSecond * dt;
+
+      var lastPose = odometry.getPoseMeters();
+
+      var xHat =
+          odometry.update(
+              groundTruthState
+                  .poseMeters
+                  .getRotation()
+                  .plus(new Rotation2d(rand.nextGaussian() * 0.05)),
+              wheelPositions);
+
+      odometryDistanceTravelled += lastPose.getTranslation().getDistance(xHat.getTranslation());
+
+      double error =
+          groundTruthState.poseMeters.getTranslation().getDistance(xHat.getTranslation());
+      if (error > maxError) {
+        maxError = error;
+      }
+      errorSum += error;
+
+      t += dt;
+    }
+
+    assertEquals(
+        0.0, errorSum / (trajectory.getTotalTimeSeconds() / dt), 0.15, "Incorrect mean error");
+    assertEquals(0.0, maxError, 0.3, "Incorrect max error");
+    assertEquals(
+        1.0,
+        odometryDistanceTravelled / trajectoryDistanceTravelled,
+        0.05,
+        "Incorrect distance travelled");
+  }
+
+  @Test
+  void testAccuracyFacingXAxis() {
+    var kinematics =
+        new MecanumDriveKinematics(
+            new Translation2d(1, 1), new Translation2d(1, -1),
+            new Translation2d(-1, -1), new Translation2d(-1, 1));
+
+    var wheelPositions = new MecanumDriveWheelPositions();
+
+    var odometry =
+        new MecanumDriveOdometry(kinematics, new Rotation2d(), wheelPositions, new Pose2d());
+
+    var trajectory =
+        TrajectoryGenerator.generateTrajectory(
+            List.of(
+                new Pose2d(),
+                new Pose2d(20, 20, Rotation2d.fromDegrees(0)),
+                new Pose2d(10, 10, Rotation2d.fromDegrees(180)),
+                new Pose2d(30, 30, Rotation2d.fromDegrees(0)),
+                new Pose2d(20, 20, Rotation2d.fromDegrees(180)),
+                new Pose2d(10, 10, Rotation2d.fromDegrees(0))),
+            new TrajectoryConfig(0.5, 2));
+
+    var rand = new Random(5190);
+
+    final double dt = 0.02;
+    double t = 0.0;
+
+    double maxError = Double.NEGATIVE_INFINITY;
+    double errorSum = 0;
+    double odometryDistanceTravelled = 0;
+    double trajectoryDistanceTravelled = 0;
+    while (t <= trajectory.getTotalTimeSeconds()) {
+      var groundTruthState = trajectory.sample(t);
+
+      trajectoryDistanceTravelled +=
+          groundTruthState.velocityMetersPerSecond * dt
+              + 0.5 * groundTruthState.accelerationMetersPerSecondSq * dt * dt;
+
+      var wheelSpeeds =
+          kinematics.toWheelSpeeds(
+              new ChassisSpeeds(
+                  groundTruthState.velocityMetersPerSecond
+                      * groundTruthState.poseMeters.getRotation().getCos(),
+                  groundTruthState.velocityMetersPerSecond
+                      * groundTruthState.poseMeters.getRotation().getSin(),
+                  0));
+
+      wheelSpeeds.frontLeftMetersPerSecond += rand.nextGaussian() * 0.1;
+      wheelSpeeds.frontRightMetersPerSecond += rand.nextGaussian() * 0.1;
+      wheelSpeeds.rearLeftMetersPerSecond += rand.nextGaussian() * 0.1;
+      wheelSpeeds.rearRightMetersPerSecond += rand.nextGaussian() * 0.1;
+
+      wheelPositions.frontLeftMeters += wheelSpeeds.frontLeftMetersPerSecond * dt;
+      wheelPositions.frontRightMeters += wheelSpeeds.frontRightMetersPerSecond * dt;
+      wheelPositions.rearLeftMeters += wheelSpeeds.rearLeftMetersPerSecond * dt;
+      wheelPositions.rearRightMeters += wheelSpeeds.rearRightMetersPerSecond * dt;
+
+      var lastPose = odometry.getPoseMeters();
+
+      var xHat = odometry.update(new Rotation2d(rand.nextGaussian() * 0.05), wheelPositions);
+
+      odometryDistanceTravelled += lastPose.getTranslation().getDistance(xHat.getTranslation());
+
+      double error =
+          groundTruthState.poseMeters.getTranslation().getDistance(xHat.getTranslation());
+      if (error > maxError) {
+        maxError = error;
+      }
+      errorSum += error;
+
+      t += dt;
+    }
+
+    assertEquals(
+        0.0, errorSum / (trajectory.getTotalTimeSeconds() / dt), 0.15, "Incorrect mean error");
+    assertEquals(0.0, maxError, 0.3, "Incorrect max error");
+    assertEquals(
+        1.0,
+        odometryDistanceTravelled / trajectoryDistanceTravelled,
+        0.05,
+        "Incorrect distance travelled");
+  }
 }
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/kinematics/SwerveDriveKinematicsTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/kinematics/SwerveDriveKinematicsTest.java
index 574e086..43dd02a 100644
--- a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/kinematics/SwerveDriveKinematicsTest.java
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/kinematics/SwerveDriveKinematicsTest.java
@@ -41,16 +41,28 @@
 
   @Test
   void testStraightLineForwardKinematics() { // test forward kinematics going in a straight line
-    SwerveModuleState state = new SwerveModuleState(5.0, Rotation2d.fromDegrees(90.0));
+    SwerveModuleState state = new SwerveModuleState(5.0, Rotation2d.fromDegrees(0.0));
     var chassisSpeeds = m_kinematics.toChassisSpeeds(state, state, state, state);
 
     assertAll(
-        () -> assertEquals(0.0, chassisSpeeds.vxMetersPerSecond, kEpsilon),
-        () -> assertEquals(5.0, chassisSpeeds.vyMetersPerSecond, kEpsilon),
+        () -> assertEquals(5.0, chassisSpeeds.vxMetersPerSecond, kEpsilon),
+        () -> assertEquals(0.0, chassisSpeeds.vyMetersPerSecond, kEpsilon),
         () -> assertEquals(0.0, chassisSpeeds.omegaRadiansPerSecond, kEpsilon));
   }
 
   @Test
+  void testStraightLineForwardKinematicsWithDeltas() {
+    // test forward kinematics going in a straight line
+    SwerveModulePosition delta = new SwerveModulePosition(5.0, Rotation2d.fromDegrees(0.0));
+    var twist = m_kinematics.toTwist2d(delta, delta, delta, delta);
+
+    assertAll(
+        () -> assertEquals(5.0, twist.dx, kEpsilon),
+        () -> assertEquals(0.0, twist.dy, kEpsilon),
+        () -> assertEquals(0.0, twist.dtheta, kEpsilon));
+  }
+
+  @Test
   void testStraightStrafeInverseKinematics() {
     ChassisSpeeds speeds = new ChassisSpeeds(0, 5, 0);
     var moduleStates = m_kinematics.toSwerveModuleStates(speeds);
@@ -78,13 +90,43 @@
   }
 
   @Test
+  void testStraightStrafeForwardKinematicsWithDeltas() {
+    SwerveModulePosition delta = new SwerveModulePosition(5.0, Rotation2d.fromDegrees(90.0));
+    var twist = m_kinematics.toTwist2d(delta, delta, delta, delta);
+
+    assertAll(
+        () -> assertEquals(0.0, twist.dx, kEpsilon),
+        () -> assertEquals(5.0, twist.dy, kEpsilon),
+        () -> assertEquals(0.0, twist.dtheta, kEpsilon));
+  }
+
+  @Test
+  void testConserveWheelAngle() {
+    ChassisSpeeds speeds = new ChassisSpeeds(0, 0, 2 * Math.PI);
+    m_kinematics.toSwerveModuleStates(speeds);
+    var moduleStates = m_kinematics.toSwerveModuleStates(new ChassisSpeeds());
+
+    // Robot is stationary, but module angles are preserved.
+
+    assertAll(
+        () -> assertEquals(0.0, moduleStates[0].speedMetersPerSecond, kEpsilon),
+        () -> assertEquals(0.0, moduleStates[1].speedMetersPerSecond, kEpsilon),
+        () -> assertEquals(0.0, moduleStates[2].speedMetersPerSecond, kEpsilon),
+        () -> assertEquals(0.0, moduleStates[3].speedMetersPerSecond, kEpsilon),
+        () -> assertEquals(135.0, moduleStates[0].angle.getDegrees(), kEpsilon),
+        () -> assertEquals(45.0, moduleStates[1].angle.getDegrees(), kEpsilon),
+        () -> assertEquals(-135.0, moduleStates[2].angle.getDegrees(), kEpsilon),
+        () -> assertEquals(-45.0, moduleStates[3].angle.getDegrees(), kEpsilon));
+  }
+
+  @Test
   void testTurnInPlaceInverseKinematics() {
     ChassisSpeeds speeds = new ChassisSpeeds(0, 0, 2 * Math.PI);
     var moduleStates = m_kinematics.toSwerveModuleStates(speeds);
 
     /*
-    The circumference of the wheels about the COR is pi * diameter, or 2 * pi * radius
-    the radius is the sqrt(12^2in + 12^2in), or 16.9706in, so the circumference the wheels
+    The circumference of the wheels about the COR is π * diameter, or 2π * radius
+    the radius is the √(12²in + 12²in), or 16.9706in, so the circumference the wheels
     trace out is 106.629190516in. since we want our robot to rotate at 1 rotation per second,
     our wheels must trace out 1 rotation (or 106.63 inches) per second.
       */
@@ -116,6 +158,21 @@
   }
 
   @Test
+  void testTurnInPlaceForwardKinematicsWithDeltas() {
+    SwerveModulePosition flDelta = new SwerveModulePosition(106.629, Rotation2d.fromDegrees(135));
+    SwerveModulePosition frDelta = new SwerveModulePosition(106.629, Rotation2d.fromDegrees(45));
+    SwerveModulePosition blDelta = new SwerveModulePosition(106.629, Rotation2d.fromDegrees(-135));
+    SwerveModulePosition brDelta = new SwerveModulePosition(106.629, Rotation2d.fromDegrees(-45));
+
+    var twist = m_kinematics.toTwist2d(flDelta, frDelta, blDelta, brDelta);
+
+    assertAll(
+        () -> assertEquals(0.0, twist.dx, kEpsilon),
+        () -> assertEquals(0.0, twist.dy, kEpsilon),
+        () -> assertEquals(2 * Math.PI, twist.dtheta, 0.1));
+  }
+
+  @Test
   void testOffCenterCORRotationInverseKinematics() {
     ChassisSpeeds speeds = new ChassisSpeeds(0, 0, 2 * Math.PI);
     var moduleStates = m_kinematics.toSwerveModuleStates(speeds, m_fl);
@@ -124,7 +181,7 @@
     This one is a bit trickier. Because we are rotating about the front-left wheel,
     it should be parked at 0 degrees and 0 speed. The front-right and back-left wheels both travel
     an arc with radius 24 (and circumference 150.796), and the back-right wheel travels an arc with
-    radius sqrt(24^2 + 24^2) and circumference 213.2584. As for angles, the front-right wheel
+    radius √(24² + 24²) and circumference 213.2584. As for angles, the front-right wheel
     should be pointing straight forward, the back-left wheel should be pointing straight right,
     and the back-right wheel should be at a -45 degree angle
     */
@@ -150,12 +207,12 @@
     var chassisSpeeds = m_kinematics.toChassisSpeeds(flState, frState, blState, brState);
 
     /*
-    We already know that our omega should be 2pi from the previous test. Next, we need to determine
+    We already know that our omega should be 2π from the previous test. Next, we need to determine
     the vx and vy of our chassis center. Because our COR is at a 45 degree angle from the center,
     we know that vx and vy must be the same. Furthermore, we know that the center of mass makes
     a full revolution about the center of revolution once every second. Therefore, the center of
-    mass must be moving at 106.629in/sec. Recalling that the ratios of a 45/45/90 triagle are
-    1:sqrt(2)/2:sqrt(2)/2, we find that the COM vx is -75.398, and vy is 75.398.
+    mass must be moving at 106.629in/sec. Recalling that the ratios of a 45/45/90 triangle are
+    1:√(2)/2:√(2)/2, we find that the COM vx is -75.398, and vy is 75.398.
     */
 
     assertAll(
@@ -164,6 +221,30 @@
         () -> assertEquals(2 * Math.PI, chassisSpeeds.omegaRadiansPerSecond, 0.1));
   }
 
+  @Test
+  void testOffCenterCORRotationForwardKinematicsWithDeltas() {
+    SwerveModulePosition flDelta = new SwerveModulePosition(0.0, Rotation2d.fromDegrees(0.0));
+    SwerveModulePosition frDelta = new SwerveModulePosition(150.796, Rotation2d.fromDegrees(0.0));
+    SwerveModulePosition blDelta = new SwerveModulePosition(150.796, Rotation2d.fromDegrees(-90));
+    SwerveModulePosition brDelta = new SwerveModulePosition(213.258, Rotation2d.fromDegrees(-45));
+
+    var twist = m_kinematics.toTwist2d(flDelta, frDelta, blDelta, brDelta);
+
+    /*
+    We already know that our omega should be 2π from the previous test. Next, we need to determine
+    the vx and vy of our chassis center. Because our COR is at a 45 degree angle from the center,
+    we know that vx and vy must be the same. Furthermore, we know that the center of mass makes
+    a full revolution about the center of revolution once every second. Therefore, the center of
+    mass must be moving at 106.629in/sec. Recalling that the ratios of a 45/45/90 triangle are
+    1:√(2)/2:√(2)/2, we find that the COM vx is -75.398, and vy is 75.398.
+    */
+
+    assertAll(
+        () -> assertEquals(75.398, twist.dx, 0.1),
+        () -> assertEquals(-75.398, twist.dy, 0.1),
+        () -> assertEquals(2 * Math.PI, twist.dtheta, 0.1));
+  }
+
   private void assertModuleState(
       SwerveModuleState expected, SwerveModuleState actual, SwerveModuleState tolerance) {
     assertAll(
@@ -229,6 +310,30 @@
   }
 
   @Test
+  void testOffCenterCORRotationAndTranslationForwardKinematicsWithDeltas() {
+    SwerveModulePosition flDelta = new SwerveModulePosition(23.43, Rotation2d.fromDegrees(-140.19));
+    SwerveModulePosition frDelta = new SwerveModulePosition(23.43, Rotation2d.fromDegrees(-39.81));
+    SwerveModulePosition blDelta = new SwerveModulePosition(54.08, Rotation2d.fromDegrees(-109.44));
+    SwerveModulePosition brDelta = new SwerveModulePosition(54.08, Rotation2d.fromDegrees(-70.56));
+
+    var twist = m_kinematics.toTwist2d(flDelta, frDelta, blDelta, brDelta);
+
+    /*
+    From equation (13.17), we know that chassis motion is th dot product of the
+    pseudoinverse of the inverseKinematics matrix (with the center of rotation at
+    (0,0) -- we don't want the motion of the center of rotation, we want it of
+    the center of the robot). These above SwerveModuleStates are known to be from
+    a velocity of [[0][3][1.5]] about (0, 24), and the expected numbers have been
+    calculated using Numpy's linalg.pinv function.
+    */
+
+    assertAll(
+        () -> assertEquals(0.0, twist.dx, 0.1),
+        () -> assertEquals(-33.0, twist.dy, 0.1),
+        () -> assertEquals(1.5, twist.dtheta, 0.1));
+  }
+
+  @Test
   void testDesaturate() {
     SwerveModuleState fl = new SwerveModuleState(5, new Rotation2d());
     SwerveModuleState fr = new SwerveModuleState(6, new Rotation2d());
@@ -246,4 +351,24 @@
         () -> assertEquals(4.0 * factor, arr[2].speedMetersPerSecond, kEpsilon),
         () -> assertEquals(7.0 * factor, arr[3].speedMetersPerSecond, kEpsilon));
   }
+
+  @Test
+  void testDesaturateSmooth() {
+    SwerveModuleState fl = new SwerveModuleState(5, new Rotation2d());
+    SwerveModuleState fr = new SwerveModuleState(6, new Rotation2d());
+    SwerveModuleState bl = new SwerveModuleState(4, new Rotation2d());
+    SwerveModuleState br = new SwerveModuleState(7, new Rotation2d());
+
+    SwerveModuleState[] arr = {fl, fr, bl, br};
+    SwerveDriveKinematics.desaturateWheelSpeeds(
+        arr, m_kinematics.toChassisSpeeds(arr), 5.5, 5.5, 3.5);
+
+    double factor = 5.5 / 7.0;
+
+    assertAll(
+        () -> assertEquals(5.0 * factor, arr[0].speedMetersPerSecond, kEpsilon),
+        () -> assertEquals(6.0 * factor, arr[1].speedMetersPerSecond, kEpsilon),
+        () -> assertEquals(4.0 * factor, arr[2].speedMetersPerSecond, kEpsilon),
+        () -> assertEquals(7.0 * factor, arr[3].speedMetersPerSecond, kEpsilon));
+  }
 }
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/kinematics/SwerveDriveOdometryTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/kinematics/SwerveDriveOdometryTest.java
index cb6dfdf..716da03 100644
--- a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/kinematics/SwerveDriveOdometryTest.java
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/kinematics/SwerveDriveOdometryTest.java
@@ -10,6 +10,10 @@
 import edu.wpi.first.math.geometry.Pose2d;
 import edu.wpi.first.math.geometry.Rotation2d;
 import edu.wpi.first.math.geometry.Translation2d;
+import edu.wpi.first.math.trajectory.TrajectoryConfig;
+import edu.wpi.first.math.trajectory.TrajectoryGenerator;
+import java.util.List;
+import java.util.Random;
 import org.junit.jupiter.api.Test;
 
 class SwerveDriveOdometryTest {
@@ -18,30 +22,34 @@
   private final Translation2d m_bl = new Translation2d(-12, 12);
   private final Translation2d m_br = new Translation2d(-12, -12);
 
+  private final SwerveModulePosition zero = new SwerveModulePosition();
+
   private final SwerveDriveKinematics m_kinematics =
       new SwerveDriveKinematics(m_fl, m_fr, m_bl, m_br);
 
   private final SwerveDriveOdometry m_odometry =
-      new SwerveDriveOdometry(m_kinematics, new Rotation2d());
+      new SwerveDriveOdometry(
+          m_kinematics, new Rotation2d(), new SwerveModulePosition[] {zero, zero, zero, zero});
 
   @Test
   void testTwoIterations() {
-    // 5 units/sec  in the x axis (forward)
-    final SwerveModuleState[] wheelSpeeds = {
-      new SwerveModuleState(5, Rotation2d.fromDegrees(0)),
-      new SwerveModuleState(5, Rotation2d.fromDegrees(0)),
-      new SwerveModuleState(5, Rotation2d.fromDegrees(0)),
-      new SwerveModuleState(5, Rotation2d.fromDegrees(0))
+    // 5 units/sec  in the x-axis (forward)
+    final SwerveModulePosition[] wheelDeltas = {
+      new SwerveModulePosition(0.5, Rotation2d.fromDegrees(0)),
+      new SwerveModulePosition(0.5, Rotation2d.fromDegrees(0)),
+      new SwerveModulePosition(0.5, Rotation2d.fromDegrees(0)),
+      new SwerveModulePosition(0.5, Rotation2d.fromDegrees(0))
     };
 
-    m_odometry.updateWithTime(
-        0.0,
+    m_odometry.update(
         new Rotation2d(),
-        new SwerveModuleState(),
-        new SwerveModuleState(),
-        new SwerveModuleState(),
-        new SwerveModuleState());
-    var pose = m_odometry.updateWithTime(0.10, new Rotation2d(), wheelSpeeds);
+        new SwerveModulePosition[] {
+          new SwerveModulePosition(),
+          new SwerveModulePosition(),
+          new SwerveModulePosition(),
+          new SwerveModulePosition()
+        });
+    var pose = m_odometry.update(new Rotation2d(), wheelDeltas);
 
     assertAll(
         () -> assertEquals(5.0 / 10.0, pose.getX(), 0.01),
@@ -57,16 +65,16 @@
     //        Module 2: speed 18.84955592153876 angle -90.0
     //        Module 3: speed 42.14888838624436 angle -26.565051177077986
 
-    final SwerveModuleState[] wheelSpeeds = {
-      new SwerveModuleState(18.85, Rotation2d.fromDegrees(90.0)),
-      new SwerveModuleState(42.15, Rotation2d.fromDegrees(26.565)),
-      new SwerveModuleState(18.85, Rotation2d.fromDegrees(-90)),
-      new SwerveModuleState(42.15, Rotation2d.fromDegrees(-26.565))
+    final SwerveModulePosition[] wheelDeltas = {
+      new SwerveModulePosition(18.85, Rotation2d.fromDegrees(90.0)),
+      new SwerveModulePosition(42.15, Rotation2d.fromDegrees(26.565)),
+      new SwerveModulePosition(18.85, Rotation2d.fromDegrees(-90)),
+      new SwerveModulePosition(42.15, Rotation2d.fromDegrees(-26.565))
     };
-    final var zero = new SwerveModuleState();
+    final var zero = new SwerveModulePosition();
 
-    m_odometry.updateWithTime(0.0, new Rotation2d(), zero, zero, zero, zero);
-    final var pose = m_odometry.updateWithTime(1.0, Rotation2d.fromDegrees(90.0), wheelSpeeds);
+    m_odometry.update(new Rotation2d(), new SwerveModulePosition[] {zero, zero, zero, zero});
+    final var pose = m_odometry.update(Rotation2d.fromDegrees(90.0), wheelDeltas);
 
     assertAll(
         () -> assertEquals(12.0, pose.getX(), 0.01),
@@ -78,15 +86,191 @@
   void testGyroAngleReset() {
     var gyro = Rotation2d.fromDegrees(90.0);
     var fieldAngle = Rotation2d.fromDegrees(0.0);
-    m_odometry.resetPosition(new Pose2d(new Translation2d(), fieldAngle), gyro);
-    var state = new SwerveModuleState();
-    m_odometry.updateWithTime(0.0, gyro, state, state, state, state);
-    state = new SwerveModuleState(1.0, Rotation2d.fromDegrees(0));
-    var pose = m_odometry.updateWithTime(1.0, gyro, state, state, state, state);
+    m_odometry.resetPosition(
+        gyro,
+        new SwerveModulePosition[] {zero, zero, zero, zero},
+        new Pose2d(new Translation2d(), fieldAngle));
+    var delta = new SwerveModulePosition();
+    m_odometry.update(gyro, new SwerveModulePosition[] {delta, delta, delta, delta});
+    delta = new SwerveModulePosition(1.0, Rotation2d.fromDegrees(0));
+    var pose = m_odometry.update(gyro, new SwerveModulePosition[] {delta, delta, delta, delta});
 
     assertAll(
         () -> assertEquals(1.0, pose.getX(), 0.1),
         () -> assertEquals(0.00, pose.getY(), 0.1),
         () -> assertEquals(0.00, pose.getRotation().getRadians(), 0.1));
   }
+
+  @Test
+  void testAccuracyFacingTrajectory() {
+    var kinematics =
+        new SwerveDriveKinematics(
+            new Translation2d(1, 1),
+            new Translation2d(1, -1),
+            new Translation2d(-1, -1),
+            new Translation2d(-1, 1));
+    var odometry =
+        new SwerveDriveOdometry(
+            kinematics, new Rotation2d(), new SwerveModulePosition[] {zero, zero, zero, zero});
+
+    SwerveModulePosition fl = new SwerveModulePosition();
+    SwerveModulePosition fr = new SwerveModulePosition();
+    SwerveModulePosition bl = new SwerveModulePosition();
+    SwerveModulePosition br = new SwerveModulePosition();
+
+    var trajectory =
+        TrajectoryGenerator.generateTrajectory(
+            List.of(
+                new Pose2d(0, 0, Rotation2d.fromDegrees(45)),
+                new Pose2d(3, 0, Rotation2d.fromDegrees(-90)),
+                new Pose2d(0, 0, Rotation2d.fromDegrees(135)),
+                new Pose2d(-3, 0, Rotation2d.fromDegrees(-90)),
+                new Pose2d(0, 0, Rotation2d.fromDegrees(45))),
+            new TrajectoryConfig(0.5, 2));
+
+    var rand = new Random(4915);
+
+    final double dt = 0.02;
+    double t = 0.0;
+
+    double maxError = Double.NEGATIVE_INFINITY;
+    double errorSum = 0;
+    while (t <= trajectory.getTotalTimeSeconds()) {
+      var groundTruthState = trajectory.sample(t);
+
+      var moduleStates =
+          kinematics.toSwerveModuleStates(
+              new ChassisSpeeds(
+                  groundTruthState.velocityMetersPerSecond,
+                  0.0,
+                  groundTruthState.velocityMetersPerSecond
+                      * groundTruthState.curvatureRadPerMeter));
+      for (var moduleState : moduleStates) {
+        moduleState.angle = moduleState.angle.plus(new Rotation2d(rand.nextGaussian() * 0.005));
+        moduleState.speedMetersPerSecond += rand.nextGaussian() * 0.1;
+      }
+
+      fl.distanceMeters += moduleStates[0].speedMetersPerSecond * dt;
+      fr.distanceMeters += moduleStates[1].speedMetersPerSecond * dt;
+      bl.distanceMeters += moduleStates[2].speedMetersPerSecond * dt;
+      br.distanceMeters += moduleStates[3].speedMetersPerSecond * dt;
+
+      fl.angle = moduleStates[0].angle;
+      fr.angle = moduleStates[1].angle;
+      bl.angle = moduleStates[2].angle;
+      br.angle = moduleStates[3].angle;
+
+      var xHat =
+          odometry.update(
+              groundTruthState
+                  .poseMeters
+                  .getRotation()
+                  .plus(new Rotation2d(rand.nextGaussian() * 0.05)),
+              new SwerveModulePosition[] {fl, fr, bl, br});
+
+      double error =
+          groundTruthState.poseMeters.getTranslation().getDistance(xHat.getTranslation());
+      if (error > maxError) {
+        maxError = error;
+      }
+      errorSum += error;
+
+      t += dt;
+    }
+
+    assertEquals(0.0, odometry.getPoseMeters().getX(), 1e-1, "Incorrect Final X");
+    assertEquals(0.0, odometry.getPoseMeters().getY(), 1e-1, "Incorrect Final Y");
+    assertEquals(
+        Math.PI / 4,
+        odometry.getPoseMeters().getRotation().getRadians(),
+        10 * Math.PI / 180,
+        "Incorrect Final Theta");
+
+    assertEquals(
+        0.0, errorSum / (trajectory.getTotalTimeSeconds() / dt), 0.05, "Incorrect mean error");
+    assertEquals(0.0, maxError, 0.125, "Incorrect max error");
+  }
+
+  @Test
+  void testAccuracyFacingXAxis() {
+    var kinematics =
+        new SwerveDriveKinematics(
+            new Translation2d(1, 1),
+            new Translation2d(1, -1),
+            new Translation2d(-1, -1),
+            new Translation2d(-1, 1));
+    var odometry =
+        new SwerveDriveOdometry(
+            kinematics, new Rotation2d(), new SwerveModulePosition[] {zero, zero, zero, zero});
+
+    SwerveModulePosition fl = new SwerveModulePosition();
+    SwerveModulePosition fr = new SwerveModulePosition();
+    SwerveModulePosition bl = new SwerveModulePosition();
+    SwerveModulePosition br = new SwerveModulePosition();
+
+    var trajectory =
+        TrajectoryGenerator.generateTrajectory(
+            List.of(
+                new Pose2d(0, 0, Rotation2d.fromDegrees(45)),
+                new Pose2d(3, 0, Rotation2d.fromDegrees(-90)),
+                new Pose2d(0, 0, Rotation2d.fromDegrees(135)),
+                new Pose2d(-3, 0, Rotation2d.fromDegrees(-90)),
+                new Pose2d(0, 0, Rotation2d.fromDegrees(45))),
+            new TrajectoryConfig(0.5, 2));
+
+    var rand = new Random(4915);
+
+    final double dt = 0.02;
+    double t = 0.0;
+
+    double maxError = Double.NEGATIVE_INFINITY;
+    double errorSum = 0;
+    while (t <= trajectory.getTotalTimeSeconds()) {
+      var groundTruthState = trajectory.sample(t);
+
+      fl.distanceMeters +=
+          groundTruthState.velocityMetersPerSecond * dt
+              + 0.5 * groundTruthState.accelerationMetersPerSecondSq * dt * dt;
+      fr.distanceMeters +=
+          groundTruthState.velocityMetersPerSecond * dt
+              + 0.5 * groundTruthState.accelerationMetersPerSecondSq * dt * dt;
+      bl.distanceMeters +=
+          groundTruthState.velocityMetersPerSecond * dt
+              + 0.5 * groundTruthState.accelerationMetersPerSecondSq * dt * dt;
+      br.distanceMeters +=
+          groundTruthState.velocityMetersPerSecond * dt
+              + 0.5 * groundTruthState.accelerationMetersPerSecondSq * dt * dt;
+
+      fl.angle = groundTruthState.poseMeters.getRotation();
+      fr.angle = groundTruthState.poseMeters.getRotation();
+      bl.angle = groundTruthState.poseMeters.getRotation();
+      br.angle = groundTruthState.poseMeters.getRotation();
+
+      var xHat =
+          odometry.update(
+              new Rotation2d(rand.nextGaussian() * 0.05),
+              new SwerveModulePosition[] {fl, fr, bl, br});
+
+      double error =
+          groundTruthState.poseMeters.getTranslation().getDistance(xHat.getTranslation());
+      if (error > maxError) {
+        maxError = error;
+      }
+      errorSum += error;
+
+      t += dt;
+    }
+
+    assertEquals(0.0, odometry.getPoseMeters().getX(), 1e-1, "Incorrect Final X");
+    assertEquals(0.0, odometry.getPoseMeters().getY(), 1e-1, "Incorrect Final Y");
+    assertEquals(
+        0.0,
+        odometry.getPoseMeters().getRotation().getRadians(),
+        10 * Math.PI / 180,
+        "Incorrect Final Theta");
+
+    assertEquals(
+        0.0, errorSum / (trajectory.getTotalTimeSeconds() / dt), 0.06, "Incorrect mean error");
+    assertEquals(0.0, maxError, 0.125, "Incorrect max error");
+  }
 }
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/spline/CubicHermiteSplineTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/spline/CubicHermiteSplineTest.java
index dd08e45..8e3d02b 100644
--- a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/spline/CubicHermiteSplineTest.java
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/spline/CubicHermiteSplineTest.java
@@ -23,7 +23,6 @@
   private static final double kMaxDy = 0.00127;
   private static final double kMaxDtheta = 0.0872;
 
-  @SuppressWarnings("ParameterName")
   private void run(Pose2d a, List<Translation2d> waypoints, Pose2d b) {
     // Start the timer.
     // var start = System.nanoTime();
@@ -97,13 +96,11 @@
                 1E-9));
   }
 
-  @SuppressWarnings("PMD.JUnitTestsShouldIncludeAssert")
   @Test
   void testStraightLine() {
     run(new Pose2d(), new ArrayList<>(), new Pose2d(3, 0, new Rotation2d()));
   }
 
-  @SuppressWarnings("PMD.JUnitTestsShouldIncludeAssert")
   @Test
   void testSCurve() {
     var start = new Pose2d(0, 0, Rotation2d.fromDegrees(90.0));
@@ -115,7 +112,6 @@
     run(start, waypoints, end);
   }
 
-  @SuppressWarnings("PMD.JUnitTestsShouldIncludeAssert")
   @Test
   void testOneInterior() {
     var start = new Pose2d(0, 0, Rotation2d.fromDegrees(0.0));
@@ -126,7 +122,6 @@
     run(start, waypoints, end);
   }
 
-  @SuppressWarnings("PMD.JUnitTestsShouldIncludeAssert")
   @Test
   void testWindyPath() {
     final var start = new Pose2d(0, 0, Rotation2d.fromDegrees(0.0));
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/spline/QuinticHermiteSplineTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/spline/QuinticHermiteSplineTest.java
index 8367070..6435dd5 100644
--- a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/spline/QuinticHermiteSplineTest.java
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/spline/QuinticHermiteSplineTest.java
@@ -20,7 +20,6 @@
   private static final double kMaxDy = 0.00127;
   private static final double kMaxDtheta = 0.0872;
 
-  @SuppressWarnings("ParameterName")
   private void run(Pose2d a, Pose2d b) {
     // Start the timer.
     // var start = System.nanoTime();
@@ -68,19 +67,16 @@
                 1E-9));
   }
 
-  @SuppressWarnings("PMD.JUnitTestsShouldIncludeAssert")
   @Test
   void testStraightLine() {
     run(new Pose2d(), new Pose2d(3, 0, new Rotation2d()));
   }
 
-  @SuppressWarnings("PMD.JUnitTestsShouldIncludeAssert")
   @Test
   void testSimpleSCurve() {
     run(new Pose2d(), new Pose2d(1, 1, new Rotation2d()));
   }
 
-  @SuppressWarnings("PMD.JUnitTestsShouldIncludeAssert")
   @Test
   void testSquiggly() {
     run(
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/system/DiscretizationTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/system/DiscretizationTest.java
index 3dff90b..2182674 100644
--- a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/system/DiscretizationTest.java
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/system/DiscretizationTest.java
@@ -58,9 +58,9 @@
     assertEquals(x1Truth, x1Discrete);
   }
 
-  //                                             dt
-  // Test that the discrete approximation of Q ≈ ∫ e^(Aτ) Q e^(Aᵀτ) dτ
-  //                                             0
+  //                                               T
+  // Test that the discrete approximation of Q_d ≈ ∫ e^(Aτ) Q e^(Aᵀτ) dτ
+  //                                               0
   @Test
   void testDiscretizeSlowModelAQ() {
     final var contA = new MatBuilder<>(Nat.N2(), Nat.N2()).fill(0, 1, 0, 0);
@@ -68,6 +68,9 @@
 
     final double dt = 1.0;
 
+    //       T
+    // Q_d = ∫ e^(Aτ) Q e^(Aᵀτ) dτ
+    //       0
     final var discQIntegrated =
         RungeKuttaTimeVarying.rungeKuttaTimeVarying(
             (Double t, Matrix<N2, N2> x) ->
@@ -87,9 +90,9 @@
             + discQIntegrated);
   }
 
-  //                                             dt
-  // Test that the discrete approximation of Q ≈ ∫ e^(Aτ) Q e^(Aᵀτ) dτ
-  //                                             0
+  //                                               T
+  // Test that the discrete approximation of Q_d ≈ ∫ e^(Aτ) Q e^(Aᵀτ) dτ
+  //                                               0
   @Test
   void testDiscretizeFastModelAQ() {
     final var contA = new MatBuilder<>(Nat.N2(), Nat.N2()).fill(0, 1, 0, -1406.29);
@@ -97,6 +100,9 @@
 
     final var dt = 0.005;
 
+    //       T
+    // Q_d = ∫ e^(Aτ) Q e^(Aᵀτ) dτ
+    //       0
     final var discQIntegrated =
         RungeKuttaTimeVarying.rungeKuttaTimeVarying(
             (Double t, Matrix<N2, N2> x) ->
@@ -130,6 +136,9 @@
       assertTrue(esCont.getEigenvalue(i).real >= 0);
     }
 
+    //       T
+    // Q_d = ∫ e^(Aτ) Q e^(Aᵀτ) dτ
+    //       0
     final var discQIntegrated =
         RungeKuttaTimeVarying.rungeKuttaTimeVarying(
             (Double t, Matrix<N2, N2> x) ->
@@ -173,6 +182,9 @@
       assertTrue(esCont.getEigenvalue(i).real >= 0);
     }
 
+    //       T
+    // Q_d = ∫ e^(Aτ) Q e^(Aᵀτ) dτ
+    //       0
     final var discQIntegrated =
         RungeKuttaTimeVarying.rungeKuttaTimeVarying(
             (Double t, Matrix<N2, N2> x) ->
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/system/NumericalIntegrationTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/system/NumericalIntegrationTest.java
index 6671963..72fb5ea 100644
--- a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/system/NumericalIntegrationTest.java
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/system/NumericalIntegrationTest.java
@@ -31,24 +31,6 @@
   }
 
   @Test
-  void testExponentialRKF45() {
-    Matrix<N1, N1> y0 = VecBuilder.fill(0.0);
-
-    var y1 =
-        NumericalIntegration.rkf45(
-            (x, u) -> {
-              var y = new Matrix<>(Nat.N1(), Nat.N1());
-              y.set(0, 0, Math.exp(x.get(0, 0)));
-              return y;
-            },
-            y0,
-            VecBuilder.fill(0),
-            0.1);
-
-    assertEquals(Math.exp(0.1) - Math.exp(0.0), y1.get(0, 0), 1e-3);
-  }
-
-  @Test
   void testExponentialRKDP() {
     Matrix<N1, N1> y0 = VecBuilder.fill(0.0);
 
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/system/RungeKuttaTimeVarying.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/system/RungeKuttaTimeVarying.java
index 7b5e844..d0e6c12 100644
--- a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/system/RungeKuttaTimeVarying.java
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/system/RungeKuttaTimeVarying.java
@@ -23,7 +23,6 @@
    * @param y The initial value of y.
    * @param dtSeconds The time over which to integrate.
    */
-  @SuppressWarnings("MethodTypeParameterName")
   public static <Rows extends Num, Cols extends Num> Matrix<Rows, Cols> rungeKuttaTimeVarying(
       BiFunction<Double, Matrix<Rows, Cols>, Matrix<Rows, Cols>> f,
       double t,
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/system/RungeKuttaTimeVaryingTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/system/RungeKuttaTimeVaryingTest.java
index e4df93f..3db878e 100644
--- a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/system/RungeKuttaTimeVaryingTest.java
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/system/RungeKuttaTimeVaryingTest.java
@@ -15,16 +15,16 @@
 class RungeKuttaTimeVaryingTest {
   private static Matrix<N1, N1> rungeKuttaTimeVaryingSolution(double t) {
     return new MatBuilder<>(Nat.N1(), Nat.N1())
-        .fill(12.0 * Math.exp(t) / (Math.pow(Math.exp(t) + 1.0, 2.0)));
+        .fill(12.0 * Math.exp(t) / Math.pow(Math.exp(t) + 1.0, 2.0));
   }
 
   // Tests RK4 with a time varying solution. From
   // http://www2.hawaii.edu/~jmcfatri/math407/RungeKuttaTest.html:
-  //   x' = x (2 / (e^t + 1) - 1)
+  //   x' = x (2/(eᵗ + 1) - 1)
   //
   // The true (analytical) solution is:
   //
-  // x(t) = 12 * e^t / ((e^t + 1)^2)
+  // x(t) = 12eᵗ/(eᵗ + 1)²
   @Test
   void rungeKuttaTimeVaryingTest() {
     final var y0 = rungeKuttaTimeVaryingSolution(5.0);
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/trajectory/CentripetalAccelerationConstraintTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/trajectory/CentripetalAccelerationConstraintTest.java
index 1805589..fa2314e 100644
--- a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/trajectory/CentripetalAccelerationConstraintTest.java
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/trajectory/CentripetalAccelerationConstraintTest.java
@@ -12,7 +12,6 @@
 import org.junit.jupiter.api.Test;
 
 class CentripetalAccelerationConstraintTest {
-  @SuppressWarnings("LocalVariableName")
   @Test
   void testCentripetalAccelerationConstraint() {
     double maxCentripetalAcceleration = Units.feetToMeters(7.0); // 7 feet per second squared
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/trajectory/DifferentialDriveKinematicsConstraintTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/trajectory/DifferentialDriveKinematicsConstraintTest.java
index 4c8a8ba..bcc3c16 100644
--- a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/trajectory/DifferentialDriveKinematicsConstraintTest.java
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/trajectory/DifferentialDriveKinematicsConstraintTest.java
@@ -15,7 +15,6 @@
 import org.junit.jupiter.api.Test;
 
 class DifferentialDriveKinematicsConstraintTest {
-  @SuppressWarnings("LocalVariableName")
   @Test
   void testDifferentialDriveKinematicsConstraint() {
     double maxVelocity = Units.feetToMeters(12.0); // 12 feet per second
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/trajectory/DifferentialDriveVoltageConstraintTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/trajectory/DifferentialDriveVoltageConstraintTest.java
index 87c1bd9..917edb4 100644
--- a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/trajectory/DifferentialDriveVoltageConstraintTest.java
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/trajectory/DifferentialDriveVoltageConstraintTest.java
@@ -20,7 +20,6 @@
 import org.junit.jupiter.api.Test;
 
 class DifferentialDriveVoltageConstraintTest {
-  @SuppressWarnings("LocalVariableName")
   @Test
   void testDifferentialDriveVoltageConstraint() {
     // Pick an unreasonably large kA to ensure the constraint has to do some work
diff --git a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/trajectory/TrajectoryGeneratorTest.java b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/trajectory/TrajectoryGeneratorTest.java
index 97c1858..45ee1d3 100644
--- a/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/trajectory/TrajectoryGeneratorTest.java
+++ b/third_party/allwpilib/wpimath/src/test/java/edu/wpi/first/math/trajectory/TrajectoryGeneratorTest.java
@@ -50,7 +50,6 @@
   }
 
   @Test
-  @SuppressWarnings("LocalVariableName")
   void testGenerationAndConstraints() {
     Trajectory trajectory = getTrajectory(new ArrayList<>());
 
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/ComputerVisionUtilTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/ComputerVisionUtilTest.cpp
new file mode 100644
index 0000000..e397af1
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/ComputerVisionUtilTest.cpp
@@ -0,0 +1,18 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/ComputerVisionUtil.h"
+#include "gtest/gtest.h"
+
+TEST(ComputerVisionUtilTest, ObjectToRobotPose) {
+  frc::Pose3d robot{1_m, 2_m, 0_m, frc::Rotation3d{0_deg, 0_deg, 30_deg}};
+  frc::Transform3d cameraToObject{frc::Translation3d{1_m, 1_m, 1_m},
+                                  frc::Rotation3d{0_deg, -20_deg, 45_deg}};
+  frc::Transform3d robotToCamera{frc::Translation3d{1_m, 0_m, 2_m},
+                                 frc::Rotation3d{0_deg, 0_deg, 25_deg}};
+  frc::Pose3d object = robot + robotToCamera + cameraToObject;
+
+  EXPECT_EQ(robot,
+            frc::ObjectToRobotPose(object, cameraToObject, robotToCamera));
+}
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/EigenTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/EigenTest.cpp
index c1786c3..03be9b3 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/EigenTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/EigenTest.cpp
@@ -2,34 +2,34 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
-#include "Eigen/Core"
 #include "Eigen/LU"
+#include "frc/EigenCore.h"
 #include "gtest/gtest.h"
 
 TEST(EigenTest, Multiplication) {
-  Eigen::Matrix<double, 2, 2> m1{{2, 1}, {0, 1}};
-  Eigen::Matrix<double, 2, 2> m2{{3, 0}, {0, 2.5}};
+  frc::Matrixd<2, 2> m1{{2, 1}, {0, 1}};
+  frc::Matrixd<2, 2> m2{{3, 0}, {0, 2.5}};
 
   const auto result = m1 * m2;
 
-  Eigen::Matrix<double, 2, 2> expectedResult{{6.0, 2.5}, {0.0, 2.5}};
+  frc::Matrixd<2, 2> expectedResult{{6.0, 2.5}, {0.0, 2.5}};
 
   EXPECT_TRUE(expectedResult.isApprox(result));
 
-  Eigen::Matrix<double, 2, 3> m3{{1.0, 3.0, 0.5}, {2.0, 4.3, 1.2}};
-  Eigen::Matrix<double, 3, 4> m4{
+  frc::Matrixd<2, 3> m3{{1.0, 3.0, 0.5}, {2.0, 4.3, 1.2}};
+  frc::Matrixd<3, 4> m4{
       {3.0, 1.5, 2.0, 4.5}, {2.3, 1.0, 1.6, 3.1}, {5.2, 2.1, 2.0, 1.0}};
 
   const auto result2 = m3 * m4;
 
-  Eigen::Matrix<double, 2, 4> expectedResult2{{12.5, 5.55, 7.8, 14.3},
-                                              {22.13, 9.82, 13.28, 23.53}};
+  frc::Matrixd<2, 4> expectedResult2{{12.5, 5.55, 7.8, 14.3},
+                                     {22.13, 9.82, 13.28, 23.53}};
 
   EXPECT_TRUE(expectedResult2.isApprox(result2));
 }
 
 TEST(EigenTest, Transpose) {
-  Eigen::Vector<double, 3> vec{1, 2, 3};
+  frc::Vectord<3> vec{1, 2, 3};
 
   const auto transpose = vec.transpose();
 
@@ -39,8 +39,7 @@
 }
 
 TEST(EigenTest, Inverse) {
-  Eigen::Matrix<double, 3, 3> mat{
-      {1.0, 3.0, 2.0}, {5.0, 2.0, 1.5}, {0.0, 1.3, 2.5}};
+  frc::Matrixd<3, 3> mat{{1.0, 3.0, 2.0}, {5.0, 2.0, 1.5}, {0.0, 1.3, 2.5}};
 
   const auto inverse = mat.inverse();
   const auto identity = Eigen::MatrixXd::Identity(3, 3);
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/FormatterTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/FormatterTest.cpp
index cd7ef5c..0e2f77c 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/FormatterTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/FormatterTest.cpp
@@ -2,6 +2,8 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
+#include <vector>
+
 #include <fmt/format.h>
 
 #include "frc/fmt/Eigen.h"
@@ -10,12 +12,33 @@
 #include "units/velocity.h"
 
 TEST(FormatterTest, Eigen) {
-  Eigen::Matrix<double, 3, 2> A{{1.0, 2.0}, {3.0, 4.0}, {5.0, 6.0}};
+  Eigen::Matrix<double, 3, 2> A{{0.0, 1.0}, {2.0, 3.0}, {4.0, 5.0}};
   EXPECT_EQ(
-      "  1.000000  2.000000\n"
-      "  3.000000  4.000000\n"
-      "  5.000000  6.000000",
+      "  0.000000  1.000000\n"
+      "  2.000000  3.000000\n"
+      "  4.000000  5.000000",
       fmt::format("{}", A));
+
+  Eigen::MatrixXd B{{0.0, 1.0}, {2.0, 3.0}, {4.0, 5.0}};
+  EXPECT_EQ(
+      "  0.000000  1.000000\n"
+      "  2.000000  3.000000\n"
+      "  4.000000  5.000000",
+      fmt::format("{}", B));
+
+  Eigen::SparseMatrix<double> C{3, 2};
+  std::vector<Eigen::Triplet<double>> triplets;
+  triplets.emplace_back(0, 1, 1.0);
+  triplets.emplace_back(1, 0, 2.0);
+  triplets.emplace_back(1, 1, 3.0);
+  triplets.emplace_back(2, 0, 4.0);
+  triplets.emplace_back(2, 1, 5.0);
+  C.setFromTriplets(triplets.begin(), triplets.end());
+  EXPECT_EQ(
+      "  0.000000  1.000000\n"
+      "  2.000000  3.000000\n"
+      "  4.000000  5.000000",
+      fmt::format("{}", C));
 }
 
 TEST(FormatterTest, Units) {
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/MathUtilTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/MathUtilTest.cpp
index 6b5af2b..a836a77 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/MathUtilTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/MathUtilTest.cpp
@@ -2,6 +2,8 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
+#include <limits>
+
 #include "frc/MathUtil.h"
 #include "gtest/gtest.h"
 #include "units/angle.h"
@@ -10,7 +12,7 @@
 
 #define EXPECT_UNITS_NEAR(a, b, c) EXPECT_NEAR((a).value(), (b).value(), c)
 
-TEST(MathUtilTest, ApplyDeadband) {
+TEST(MathUtilTest, ApplyDeadbandUnityScale) {
   // < 0
   EXPECT_DOUBLE_EQ(-1.0, frc::ApplyDeadband(-1.0, 0.02));
   EXPECT_DOUBLE_EQ((-0.03 + 0.02) / (1.0 - 0.02),
@@ -29,6 +31,33 @@
   EXPECT_DOUBLE_EQ(1.0, frc::ApplyDeadband(1.0, 0.02));
 }
 
+TEST(MathUtilTest, ApplyDeadbandArbitraryScale) {
+  // < 0
+  EXPECT_DOUBLE_EQ(-2.5, frc::ApplyDeadband(-2.5, 0.02, 2.5));
+  EXPECT_DOUBLE_EQ(0.0, frc::ApplyDeadband(-0.02, 0.02, 2.5));
+  EXPECT_DOUBLE_EQ(0.0, frc::ApplyDeadband(-0.01, 0.02, 2.5));
+
+  // == 0
+  EXPECT_DOUBLE_EQ(0.0, frc::ApplyDeadband(0.0, 0.02, 2.5));
+
+  // > 0
+  EXPECT_DOUBLE_EQ(0.0, frc::ApplyDeadband(0.01, 0.02, 2.5));
+  EXPECT_DOUBLE_EQ(0.0, frc::ApplyDeadband(0.02, 0.02, 2.5));
+  EXPECT_DOUBLE_EQ(2.5, frc::ApplyDeadband(2.5, 0.02, 2.5));
+}
+
+TEST(MathUtilTest, ApplyDeadbandUnits) {
+  // < 0
+  EXPECT_DOUBLE_EQ(
+      -20, frc::ApplyDeadband<units::radian_t>(-20_rad, 1_rad, 20_rad).value());
+}
+
+TEST(MathUtilTest, ApplyDeadbandLargeMaxMagnitude) {
+  EXPECT_DOUBLE_EQ(
+      80.0,
+      frc::ApplyDeadband(100.0, 20.0, std::numeric_limits<double>::infinity()));
+}
+
 TEST(MathUtilTest, InputModulus) {
   // These tests check error wrapping. That is, the result of wrapping the
   // result of an angle reference minus the measurement.
@@ -71,20 +100,20 @@
 
 TEST(MathUtilTest, AngleModulus) {
   EXPECT_UNITS_NEAR(
-      frc::AngleModulus(units::radian_t{-2000 * wpi::numbers::pi / 180}),
-      units::radian_t{160 * wpi::numbers::pi / 180}, 1e-10);
+      frc::AngleModulus(units::radian_t{-2000 * std::numbers::pi / 180}),
+      units::radian_t{160 * std::numbers::pi / 180}, 1e-10);
   EXPECT_UNITS_NEAR(
-      frc::AngleModulus(units::radian_t{358 * wpi::numbers::pi / 180}),
-      units::radian_t{-2 * wpi::numbers::pi / 180}, 1e-10);
-  EXPECT_UNITS_NEAR(frc::AngleModulus(units::radian_t{2.0 * wpi::numbers::pi}),
+      frc::AngleModulus(units::radian_t{358 * std::numbers::pi / 180}),
+      units::radian_t{-2 * std::numbers::pi / 180}, 1e-10);
+  EXPECT_UNITS_NEAR(frc::AngleModulus(units::radian_t{2.0 * std::numbers::pi}),
                     0_rad, 1e-10);
 
-  EXPECT_UNITS_EQ(frc::AngleModulus(units::radian_t(5 * wpi::numbers::pi)),
-                  units::radian_t(wpi::numbers::pi));
-  EXPECT_UNITS_EQ(frc::AngleModulus(units::radian_t(-5 * wpi::numbers::pi)),
-                  units::radian_t(wpi::numbers::pi));
-  EXPECT_UNITS_EQ(frc::AngleModulus(units::radian_t(wpi::numbers::pi / 2)),
-                  units::radian_t(wpi::numbers::pi / 2));
-  EXPECT_UNITS_EQ(frc::AngleModulus(units::radian_t(-wpi::numbers::pi / 2)),
-                  units::radian_t(-wpi::numbers::pi / 2));
+  EXPECT_UNITS_EQ(frc::AngleModulus(units::radian_t{5 * std::numbers::pi}),
+                  units::radian_t{std::numbers::pi});
+  EXPECT_UNITS_EQ(frc::AngleModulus(units::radian_t{-5 * std::numbers::pi}),
+                  units::radian_t{std::numbers::pi});
+  EXPECT_UNITS_EQ(frc::AngleModulus(units::radian_t{std::numbers::pi / 2}),
+                  units::radian_t{std::numbers::pi / 2});
+  EXPECT_UNITS_EQ(frc::AngleModulus(units::radian_t{-std::numbers::pi / 2}),
+                  units::radian_t{-std::numbers::pi / 2});
 }
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/StateSpaceTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/StateSpaceTest.cpp
index 0dc3978..ee7842c 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/StateSpaceTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/StateSpaceTest.cpp
@@ -7,7 +7,7 @@
 #include <cmath>
 #include <random>
 
-#include "Eigen/Core"
+#include "frc/EigenCore.h"
 #include "frc/controller/LinearPlantInversionFeedforward.h"
 #include "frc/controller/LinearQuadraticRegulator.h"
 #include "frc/estimator/KalmanFilter.h"
@@ -45,8 +45,7 @@
 
 void Update(const LinearSystem<2, 1, 1>& plant, LinearSystemLoop<2, 1, 1>& loop,
             double noise) {
-  Eigen::Vector<double, 1> y =
-      plant.CalculateY(loop.Xhat(), loop.U()) + Eigen::Vector<double, 1>{noise};
+  Vectord<1> y = plant.CalculateY(loop.Xhat(), loop.U()) + Vectord<1>{noise};
   loop.Correct(y);
   loop.Predict(kDt);
 }
@@ -55,7 +54,7 @@
   std::default_random_engine generator;
   std::normal_distribution<double> dist{0.0, kPositionStddev};
 
-  Eigen::Vector<double, 2> references{2.0, 0.0};
+  Vectord<2> references{2.0, 0.0};
   loop.SetNextR(references);
 
   for (int i = 0; i < 1000; i++) {
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/StateSpaceUtilTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/StateSpaceUtilTest.cpp
index 57b93bb..105a434 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/StateSpaceUtilTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/StateSpaceUtilTest.cpp
@@ -6,51 +6,12 @@
 
 #include <array>
 
-#include "Eigen/Core"
+#include "frc/EigenCore.h"
 #include "frc/StateSpaceUtil.h"
 #include "frc/system/NumericalIntegration.h"
 
-TEST(StateSpaceUtilTest, MakeMatrix) {
-  // Column vector
-  Eigen::Vector<double, 2> mat1 = frc::MakeMatrix<2, 1>(1.0, 2.0);
-  EXPECT_NEAR(mat1(0), 1.0, 1e-3);
-  EXPECT_NEAR(mat1(1), 2.0, 1e-3);
-
-  // Row vector
-  Eigen::RowVector<double, 2> mat2 = frc::MakeMatrix<1, 2>(1.0, 2.0);
-  EXPECT_NEAR(mat2(0), 1.0, 1e-3);
-  EXPECT_NEAR(mat2(1), 2.0, 1e-3);
-
-  // Square matrix
-  Eigen::Matrix<double, 2, 2> mat3 = frc::MakeMatrix<2, 2>(1.0, 2.0, 3.0, 4.0);
-  EXPECT_NEAR(mat3(0, 0), 1.0, 1e-3);
-  EXPECT_NEAR(mat3(0, 1), 2.0, 1e-3);
-  EXPECT_NEAR(mat3(1, 0), 3.0, 1e-3);
-  EXPECT_NEAR(mat3(1, 1), 4.0, 1e-3);
-
-  // Nonsquare matrix with more rows than columns
-  Eigen::Matrix<double, 3, 2> mat4 =
-      frc::MakeMatrix<3, 2>(1.0, 2.0, 3.0, 4.0, 5.0, 6.0);
-  EXPECT_NEAR(mat4(0, 0), 1.0, 1e-3);
-  EXPECT_NEAR(mat4(0, 1), 2.0, 1e-3);
-  EXPECT_NEAR(mat4(1, 0), 3.0, 1e-3);
-  EXPECT_NEAR(mat4(1, 1), 4.0, 1e-3);
-  EXPECT_NEAR(mat4(2, 0), 5.0, 1e-3);
-  EXPECT_NEAR(mat4(2, 1), 6.0, 1e-3);
-
-  // Nonsquare matrix with more columns than rows
-  Eigen::Matrix<double, 2, 3> mat5 =
-      frc::MakeMatrix<2, 3>(1.0, 2.0, 3.0, 4.0, 5.0, 6.0);
-  EXPECT_NEAR(mat5(0, 0), 1.0, 1e-3);
-  EXPECT_NEAR(mat5(0, 1), 2.0, 1e-3);
-  EXPECT_NEAR(mat5(0, 2), 3.0, 1e-3);
-  EXPECT_NEAR(mat5(1, 0), 4.0, 1e-3);
-  EXPECT_NEAR(mat5(1, 1), 5.0, 1e-3);
-  EXPECT_NEAR(mat5(1, 2), 6.0, 1e-3);
-}
-
 TEST(StateSpaceUtilTest, CostParameterPack) {
-  Eigen::Matrix<double, 3, 3> mat = frc::MakeCostMatrix(1.0, 2.0, 3.0);
+  frc::Matrixd<3, 3> mat = frc::MakeCostMatrix(1.0, 2.0, 3.0);
   EXPECT_NEAR(mat(0, 0), 1.0, 1e-3);
   EXPECT_NEAR(mat(0, 1), 0.0, 1e-3);
   EXPECT_NEAR(mat(0, 2), 0.0, 1e-3);
@@ -63,7 +24,7 @@
 }
 
 TEST(StateSpaceUtilTest, CostArray) {
-  Eigen::Matrix<double, 3, 3> mat = frc::MakeCostMatrix<3>({1.0, 2.0, 3.0});
+  frc::Matrixd<3, 3> mat = frc::MakeCostMatrix<3>({1.0, 2.0, 3.0});
   EXPECT_NEAR(mat(0, 0), 1.0, 1e-3);
   EXPECT_NEAR(mat(0, 1), 0.0, 1e-3);
   EXPECT_NEAR(mat(0, 2), 0.0, 1e-3);
@@ -76,7 +37,7 @@
 }
 
 TEST(StateSpaceUtilTest, CovParameterPack) {
-  Eigen::Matrix<double, 3, 3> mat = frc::MakeCovMatrix(1.0, 2.0, 3.0);
+  frc::Matrixd<3, 3> mat = frc::MakeCovMatrix(1.0, 2.0, 3.0);
   EXPECT_NEAR(mat(0, 0), 1.0, 1e-3);
   EXPECT_NEAR(mat(0, 1), 0.0, 1e-3);
   EXPECT_NEAR(mat(0, 2), 0.0, 1e-3);
@@ -89,7 +50,7 @@
 }
 
 TEST(StateSpaceUtilTest, CovArray) {
-  Eigen::Matrix<double, 3, 3> mat = frc::MakeCovMatrix<3>({1.0, 2.0, 3.0});
+  frc::Matrixd<3, 3> mat = frc::MakeCovMatrix<3>({1.0, 2.0, 3.0});
   EXPECT_NEAR(mat(0, 0), 1.0, 1e-3);
   EXPECT_NEAR(mat(0, 1), 0.0, 1e-3);
   EXPECT_NEAR(mat(0, 2), 0.0, 1e-3);
@@ -102,59 +63,59 @@
 }
 
 TEST(StateSpaceUtilTest, WhiteNoiseVectorParameterPack) {
-  Eigen::Vector<double, 2> vec = frc::MakeWhiteNoiseVector(2.0, 3.0);
+  frc::Vectord<2> vec = frc::MakeWhiteNoiseVector(2.0, 3.0);
   static_cast<void>(vec);
 }
 
 TEST(StateSpaceUtilTest, WhiteNoiseVectorArray) {
-  Eigen::Vector<double, 2> vec = frc::MakeWhiteNoiseVector<2>({2.0, 3.0});
+  frc::Vectord<2> vec = frc::MakeWhiteNoiseVector<2>({2.0, 3.0});
   static_cast<void>(vec);
 }
 
 TEST(StateSpaceUtilTest, IsStabilizable) {
-  Eigen::Matrix<double, 2, 1> B{0, 1};
+  frc::Matrixd<2, 1> B{0, 1};
 
   // First eigenvalue is uncontrollable and unstable.
   // Second eigenvalue is controllable and stable.
-  EXPECT_FALSE((frc::IsStabilizable<2, 1>(
-      Eigen::Matrix<double, 2, 2>{{1.2, 0}, {0, 0.5}}, B)));
+  EXPECT_FALSE(
+      (frc::IsStabilizable<2, 1>(frc::Matrixd<2, 2>{{1.2, 0}, {0, 0.5}}, B)));
 
   // First eigenvalue is uncontrollable and marginally stable.
   // Second eigenvalue is controllable and stable.
-  EXPECT_FALSE((frc::IsStabilizable<2, 1>(
-      Eigen::Matrix<double, 2, 2>{{1, 0}, {0, 0.5}}, B)));
+  EXPECT_FALSE(
+      (frc::IsStabilizable<2, 1>(frc::Matrixd<2, 2>{{1, 0}, {0, 0.5}}, B)));
 
   // First eigenvalue is uncontrollable and stable.
   // Second eigenvalue is controllable and stable.
-  EXPECT_TRUE((frc::IsStabilizable<2, 1>(
-      Eigen::Matrix<double, 2, 2>{{0.2, 0}, {0, 0.5}}, B)));
+  EXPECT_TRUE(
+      (frc::IsStabilizable<2, 1>(frc::Matrixd<2, 2>{{0.2, 0}, {0, 0.5}}, B)));
 
   // First eigenvalue is uncontrollable and stable.
   // Second eigenvalue is controllable and unstable.
-  EXPECT_TRUE((frc::IsStabilizable<2, 1>(
-      Eigen::Matrix<double, 2, 2>{{0.2, 0}, {0, 1.2}}, B)));
+  EXPECT_TRUE(
+      (frc::IsStabilizable<2, 1>(frc::Matrixd<2, 2>{{0.2, 0}, {0, 1.2}}, B)));
 }
 
 TEST(StateSpaceUtilTest, IsDetectable) {
-  Eigen::Matrix<double, 1, 2> C{0, 1};
+  frc::Matrixd<1, 2> C{0, 1};
 
   // First eigenvalue is unobservable and unstable.
   // Second eigenvalue is observable and stable.
-  EXPECT_FALSE((frc::IsDetectable<2, 1>(
-      Eigen::Matrix<double, 2, 2>{{1.2, 0}, {0, 0.5}}, C)));
+  EXPECT_FALSE(
+      (frc::IsDetectable<2, 1>(frc::Matrixd<2, 2>{{1.2, 0}, {0, 0.5}}, C)));
 
   // First eigenvalue is unobservable and marginally stable.
   // Second eigenvalue is observable and stable.
-  EXPECT_FALSE((frc::IsDetectable<2, 1>(
-      Eigen::Matrix<double, 2, 2>{{1, 0}, {0, 0.5}}, C)));
+  EXPECT_FALSE(
+      (frc::IsDetectable<2, 1>(frc::Matrixd<2, 2>{{1, 0}, {0, 0.5}}, C)));
 
   // First eigenvalue is unobservable and stable.
   // Second eigenvalue is observable and stable.
-  EXPECT_TRUE((frc::IsDetectable<2, 1>(
-      Eigen::Matrix<double, 2, 2>{{0.2, 0}, {0, 0.5}}, C)));
+  EXPECT_TRUE(
+      (frc::IsDetectable<2, 1>(frc::Matrixd<2, 2>{{0.2, 0}, {0, 0.5}}, C)));
 
   // First eigenvalue is unobservable and stable.
   // Second eigenvalue is observable and unstable.
-  EXPECT_TRUE((frc::IsDetectable<2, 1>(
-      Eigen::Matrix<double, 2, 2>{{0.2, 0}, {0, 1.2}}, C)));
+  EXPECT_TRUE(
+      (frc::IsDetectable<2, 1>(frc::Matrixd<2, 2>{{0.2, 0}, {0, 1.2}}, C)));
 }
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/UnitsTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/UnitsTest.cpp
index d5ba717..1059260 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/UnitsTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/UnitsTest.cpp
@@ -1420,6 +1420,7 @@
 }
 #endif
 
+#if !defined(UNIT_LIB_DISABLE_FMT)
 TEST_F(UnitContainer, fmtlib) {
   testing::internal::CaptureStdout();
   fmt::print("{}", degree_t(349.87));
@@ -1500,6 +1501,7 @@
   EXPECT_STREQ("5.670367e-08 kg s^-3 K^-4", output.c_str());
 #endif
 }
+#endif
 
 TEST_F(UnitContainer, to_string) {
   foot_t a(3.5);
@@ -3063,14 +3065,17 @@
   constexpr meter_t result0(0);
   constexpr auto result1 = make_unit<meter_t>(1);
   constexpr auto result2 = meter_t(2);
+  constexpr auto result3 = -3_m;
 
   EXPECT_EQ(meter_t(0), result0);
   EXPECT_EQ(meter_t(1), result1);
   EXPECT_EQ(meter_t(2), result2);
+  EXPECT_EQ(meter_t(-3), result3);
 
   EXPECT_TRUE(noexcept(result0));
   EXPECT_TRUE(noexcept(result1));
   EXPECT_TRUE(noexcept(result2));
+  EXPECT_TRUE(noexcept(result3));
 }
 
 TEST_F(Constexpr, constants) {
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/controller/ControlAffinePlantInversionFeedforwardTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/controller/ControlAffinePlantInversionFeedforwardTest.cpp
index 354ed18..b2bcee6 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/controller/ControlAffinePlantInversionFeedforwardTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/controller/ControlAffinePlantInversionFeedforwardTest.cpp
@@ -6,47 +6,46 @@
 
 #include <cmath>
 
-#include "Eigen/Core"
+#include "frc/EigenCore.h"
 #include "frc/controller/ControlAffinePlantInversionFeedforward.h"
 #include "units/time.h"
 
 namespace frc {
 
-Eigen::Vector<double, 2> Dynamics(const Eigen::Vector<double, 2>& x,
-                                  const Eigen::Vector<double, 1>& u) {
-  return Eigen::Matrix<double, 2, 2>{{1.0, 0.0}, {0.0, 1.0}} * x +
-         Eigen::Matrix<double, 2, 1>{0.0, 1.0} * u;
+Vectord<2> Dynamics(const Vectord<2>& x, const Vectord<1>& u) {
+  return Matrixd<2, 2>{{1.0, 0.0}, {0.0, 1.0}} * x +
+         Matrixd<2, 1>{0.0, 1.0} * u;
 }
 
-Eigen::Vector<double, 2> StateDynamics(const Eigen::Vector<double, 2>& x) {
-  return Eigen::Matrix<double, 2, 2>{{1.0, 0.0}, {0.0, 1.0}} * x;
+Vectord<2> StateDynamics(const Vectord<2>& x) {
+  return Matrixd<2, 2>{{1.0, 0.0}, {0.0, 1.0}} * x;
 }
 
 TEST(ControlAffinePlantInversionFeedforwardTest, Calculate) {
-  std::function<Eigen::Vector<double, 2>(const Eigen::Vector<double, 2>&,
-                                         const Eigen::Vector<double, 1>&)>
+  std::function<Vectord<2>(const Vectord<2>&, const Vectord<1>&)>
       modelDynamics = [](auto& x, auto& u) { return Dynamics(x, u); };
 
   frc::ControlAffinePlantInversionFeedforward<2, 1> feedforward{
       modelDynamics, units::second_t{0.02}};
 
-  Eigen::Vector<double, 2> r{2, 2};
-  Eigen::Vector<double, 2> nextR{3, 3};
+  Vectord<2> r{2, 2};
+  Vectord<2> nextR{3, 3};
 
   EXPECT_NEAR(48, feedforward.Calculate(r, nextR)(0, 0), 1e-6);
 }
 
 TEST(ControlAffinePlantInversionFeedforwardTest, CalculateState) {
-  std::function<Eigen::Vector<double, 2>(const Eigen::Vector<double, 2>&)>
-      modelDynamics = [](auto& x) { return StateDynamics(x); };
+  std::function<Vectord<2>(const Vectord<2>&)> modelDynamics = [](auto& x) {
+    return StateDynamics(x);
+  };
 
-  Eigen::Matrix<double, 2, 1> B{0, 1};
+  Matrixd<2, 1> B{0, 1};
 
-  frc::ControlAffinePlantInversionFeedforward<2, 1> feedforward{
-      modelDynamics, B, units::second_t(0.02)};
+  frc::ControlAffinePlantInversionFeedforward<2, 1> feedforward{modelDynamics,
+                                                                B, 20_ms};
 
-  Eigen::Vector<double, 2> r{2, 2};
-  Eigen::Vector<double, 2> nextR{3, 3};
+  Vectord<2> r{2, 2};
+  Vectord<2> nextR{3, 3};
 
   EXPECT_NEAR(48, feedforward.Calculate(r, nextR)(0, 0), 1e-6);
 }
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/controller/DifferentialDriveAccelerationLimiterTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/controller/DifferentialDriveAccelerationLimiterTest.cpp
new file mode 100644
index 0000000..ab8359c
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/controller/DifferentialDriveAccelerationLimiterTest.cpp
@@ -0,0 +1,257 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <gtest/gtest.h>
+
+#include "frc/controller/DifferentialDriveAccelerationLimiter.h"
+#include "frc/system/plant/LinearSystemId.h"
+#include "units/math.h"
+
+namespace frc {
+
+TEST(DifferentialDriveAccelerationLimiterTest, LowLimits) {
+  constexpr auto trackwidth = 0.9_m;
+  constexpr auto dt = 5_ms;
+  constexpr auto maxA = 2_mps_sq;
+  constexpr auto maxAlpha = 2_rad_per_s_sq;
+
+  using Kv_t = decltype(1_V / 1_mps);
+  using Ka_t = decltype(1_V / 1_mps_sq);
+  auto plant = LinearSystemId::IdentifyDrivetrainSystem(Kv_t{1.0}, Ka_t{1.0},
+                                                        Kv_t{1.0}, Ka_t{1.0});
+
+  DifferentialDriveAccelerationLimiter accelLimiter{plant, trackwidth, maxA,
+                                                    maxAlpha};
+
+  Vectord<2> x{0.0, 0.0};
+  Vectord<2> xAccelLimiter{0.0, 0.0};
+
+  // Ensure voltage exceeds acceleration before limiting
+  {
+    Vectord<2> accels =
+        plant.A() * xAccelLimiter + plant.B() * Vectord<2>{12.0, 12.0};
+    units::meters_per_second_squared_t a{(accels(0) + accels(1)) / 2.0};
+    EXPECT_GT(units::math::abs(a), maxA);
+  }
+  {
+    Vectord<2> accels =
+        plant.A() * xAccelLimiter + plant.B() * Vectord<2>{-12.0, 12.0};
+    units::radians_per_second_squared_t alpha{(accels(1) - accels(0)) /
+                                              trackwidth.value()};
+    EXPECT_GT(units::math::abs(alpha), maxAlpha);
+  }
+
+  // Forward
+  Vectord<2> u{12.0, 12.0};
+  for (auto t = 0_s; t < 3_s; t += dt) {
+    x = plant.CalculateX(x, u, dt);
+    auto [left, right] =
+        accelLimiter.Calculate(units::meters_per_second_t{xAccelLimiter(0)},
+                               units::meters_per_second_t{xAccelLimiter(1)},
+                               units::volt_t{u(0)}, units::volt_t{u(1)});
+    xAccelLimiter =
+        plant.CalculateX(xAccelLimiter, Vectord<2>{left, right}, dt);
+
+    Vectord<2> accels =
+        plant.A() * xAccelLimiter + plant.B() * Vectord<2>{left, right};
+    units::meters_per_second_squared_t a{(accels(0) + accels(1)) / 2.0};
+    units::radians_per_second_squared_t alpha{(accels(1) - accels(0)) /
+                                              trackwidth.value()};
+    EXPECT_LE(units::math::abs(a), maxA);
+    EXPECT_LE(units::math::abs(alpha), maxAlpha);
+  }
+
+  // Backward
+  u = Vectord<2>{-12.0, -12.0};
+  for (auto t = 0_s; t < 3_s; t += dt) {
+    x = plant.CalculateX(x, u, dt);
+    auto [left, right] =
+        accelLimiter.Calculate(units::meters_per_second_t{xAccelLimiter(0)},
+                               units::meters_per_second_t{xAccelLimiter(1)},
+                               units::volt_t{u(0)}, units::volt_t{u(1)});
+    xAccelLimiter =
+        plant.CalculateX(xAccelLimiter, Vectord<2>{left, right}, dt);
+
+    Vectord<2> accels =
+        plant.A() * xAccelLimiter + plant.B() * Vectord<2>{left, right};
+    units::meters_per_second_squared_t a{(accels(0) + accels(1)) / 2.0};
+    units::radians_per_second_squared_t alpha{(accels(1) - accels(0)) /
+                                              trackwidth.value()};
+    EXPECT_LE(units::math::abs(a), maxA);
+    EXPECT_LE(units::math::abs(alpha), maxAlpha);
+  }
+
+  // Rotate CCW
+  u = Vectord<2>{-12.0, 12.0};
+  for (auto t = 0_s; t < 3_s; t += dt) {
+    x = plant.CalculateX(x, u, dt);
+    auto [left, right] =
+        accelLimiter.Calculate(units::meters_per_second_t{xAccelLimiter(0)},
+                               units::meters_per_second_t{xAccelLimiter(1)},
+                               units::volt_t{u(0)}, units::volt_t{u(1)});
+    xAccelLimiter =
+        plant.CalculateX(xAccelLimiter, Vectord<2>{left, right}, dt);
+
+    Vectord<2> accels =
+        plant.A() * xAccelLimiter + plant.B() * Vectord<2>{left, right};
+    units::meters_per_second_squared_t a{(accels(0) + accels(1)) / 2.0};
+    units::radians_per_second_squared_t alpha{(accels(1) - accels(0)) /
+                                              trackwidth.value()};
+    EXPECT_LE(units::math::abs(a), maxA);
+    EXPECT_LE(units::math::abs(alpha), maxAlpha);
+  }
+}
+
+TEST(DifferentialDriveAccelerationLimiterTest, HighLimits) {
+  constexpr auto trackwidth = 0.9_m;
+  constexpr auto dt = 5_ms;
+
+  using Kv_t = decltype(1_V / 1_mps);
+  using Ka_t = decltype(1_V / 1_mps_sq);
+
+  auto plant = LinearSystemId::IdentifyDrivetrainSystem(Kv_t{1.0}, Ka_t{1.0},
+                                                        Kv_t{1.0}, Ka_t{1.0});
+
+  // Limits are so high, they don't get hit, so states of constrained and
+  // unconstrained systems should match
+  DifferentialDriveAccelerationLimiter accelLimiter{
+      plant, trackwidth, 1e3_mps_sq, 1e3_rad_per_s_sq};
+
+  Vectord<2> x{0.0, 0.0};
+  Vectord<2> xAccelLimiter{0.0, 0.0};
+
+  // Forward
+  Vectord<2> u{12.0, 12.0};
+  for (auto t = 0_s; t < 3_s; t += dt) {
+    x = plant.CalculateX(x, u, dt);
+    auto [left, right] =
+        accelLimiter.Calculate(units::meters_per_second_t{xAccelLimiter(0)},
+                               units::meters_per_second_t{xAccelLimiter(1)},
+                               units::volt_t{u(0)}, units::volt_t{u(1)});
+    xAccelLimiter =
+        plant.CalculateX(xAccelLimiter, Vectord<2>{left, right}, dt);
+
+    EXPECT_DOUBLE_EQ(x(0), xAccelLimiter(0));
+    EXPECT_DOUBLE_EQ(x(1), xAccelLimiter(1));
+  }
+
+  // Backward
+  x.setZero();
+  xAccelLimiter.setZero();
+  u = Vectord<2>{-12.0, -12.0};
+  for (auto t = 0_s; t < 3_s; t += dt) {
+    x = plant.CalculateX(x, u, dt);
+    auto [left, right] =
+        accelLimiter.Calculate(units::meters_per_second_t{xAccelLimiter(0)},
+                               units::meters_per_second_t{xAccelLimiter(1)},
+                               units::volt_t{u(0)}, units::volt_t{u(1)});
+    xAccelLimiter =
+        plant.CalculateX(xAccelLimiter, Vectord<2>{left, right}, dt);
+
+    EXPECT_DOUBLE_EQ(x(0), xAccelLimiter(0));
+    EXPECT_DOUBLE_EQ(x(1), xAccelLimiter(1));
+  }
+
+  // Rotate CCW
+  x.setZero();
+  xAccelLimiter.setZero();
+  u = Vectord<2>{-12.0, 12.0};
+  for (auto t = 0_s; t < 3_s; t += dt) {
+    x = plant.CalculateX(x, u, dt);
+    auto [left, right] =
+        accelLimiter.Calculate(units::meters_per_second_t{xAccelLimiter(0)},
+                               units::meters_per_second_t{xAccelLimiter(1)},
+                               units::volt_t{u(0)}, units::volt_t{u(1)});
+    xAccelLimiter =
+        plant.CalculateX(xAccelLimiter, Vectord<2>{left, right}, dt);
+
+    EXPECT_DOUBLE_EQ(x(0), xAccelLimiter(0));
+    EXPECT_DOUBLE_EQ(x(1), xAccelLimiter(1));
+  }
+}
+
+TEST(DifferentialDriveAccelerationLimiterTest, SeperateMinMaxLowLimits) {
+  constexpr auto trackwidth = 0.9_m;
+  constexpr auto dt = 5_ms;
+  constexpr auto minA = -1_mps_sq;
+  constexpr auto maxA = 2_mps_sq;
+  constexpr auto maxAlpha = 2_rad_per_s_sq;
+
+  using Kv_t = decltype(1_V / 1_mps);
+  using Ka_t = decltype(1_V / 1_mps_sq);
+  auto plant = LinearSystemId::IdentifyDrivetrainSystem(Kv_t{1.0}, Ka_t{1.0},
+                                                        Kv_t{1.0}, Ka_t{1.0});
+
+  DifferentialDriveAccelerationLimiter accelLimiter{plant, trackwidth, minA,
+                                                    maxA, maxAlpha};
+
+  Vectord<2> x{0.0, 0.0};
+  Vectord<2> xAccelLimiter{0.0, 0.0};
+
+  // Ensure voltage exceeds acceleration before limiting
+  {
+    Vectord<2> accels =
+        plant.A() * xAccelLimiter + plant.B() * Vectord<2>{12.0, 12.0};
+    units::meters_per_second_squared_t a{(accels(0) + accels(1)) / 2.0};
+    EXPECT_GT(units::math::abs(a), maxA);
+    EXPECT_GT(units::math::abs(a), -minA);
+  }
+
+  // a should always be within [minA, maxA]
+  // Forward
+  Vectord<2> u{12.0, 12.0};
+  for (auto t = 0_s; t < 3_s; t += dt) {
+    x = plant.CalculateX(x, u, dt);
+    auto [left, right] =
+        accelLimiter.Calculate(units::meters_per_second_t{xAccelLimiter(0)},
+                               units::meters_per_second_t{xAccelLimiter(1)},
+                               units::volt_t{u(0)}, units::volt_t{u(1)});
+    xAccelLimiter =
+        plant.CalculateX(xAccelLimiter, Vectord<2>{left, right}, dt);
+
+    Vectord<2> accels =
+        plant.A() * xAccelLimiter + plant.B() * Vectord<2>{left, right};
+    units::meters_per_second_squared_t a{(accels(0) + accels(1)) / 2.0};
+    EXPECT_GE(a, minA);
+    EXPECT_LE(a, maxA);
+  }
+
+  // Backward
+  u = Vectord<2>{-12.0, -12.0};
+  for (auto t = 0_s; t < 3_s; t += dt) {
+    x = plant.CalculateX(x, u, dt);
+    auto [left, right] =
+        accelLimiter.Calculate(units::meters_per_second_t{xAccelLimiter(0)},
+                               units::meters_per_second_t{xAccelLimiter(1)},
+                               units::volt_t{u(0)}, units::volt_t{u(1)});
+    xAccelLimiter =
+        plant.CalculateX(xAccelLimiter, Vectord<2>{left, right}, dt);
+
+    Vectord<2> accels =
+        plant.A() * xAccelLimiter + plant.B() * Vectord<2>{left, right};
+    units::meters_per_second_squared_t a{(accels(0) + accels(1)) / 2.0};
+    EXPECT_GE(a, minA);
+    EXPECT_LE(a, maxA);
+  }
+}
+
+TEST(DifferentialDriveAccelerationLimiterTest, MinAccelGreaterThanMaxAccel) {
+  using Kv_t = decltype(1_V / 1_mps);
+  using Ka_t = decltype(1_V / 1_mps_sq);
+  auto plant = LinearSystemId::IdentifyDrivetrainSystem(Kv_t{1.0}, Ka_t{1.0},
+                                                        Kv_t{1.0}, Ka_t{1.0});
+  EXPECT_NO_THROW({
+    DifferentialDriveAccelerationLimiter accelLimiter(plant, 1_m, 1_mps_sq,
+                                                      1_rad_per_s_sq);
+  });
+
+  EXPECT_THROW(
+      {
+        DifferentialDriveAccelerationLimiter accelLimiter(
+            plant, 1_m, 1_mps_sq, -1_mps_sq, 1_rad_per_s_sq);
+      },
+      std::invalid_argument);
+}
+
+}  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/controller/DifferentialDriveFeedforwardTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/controller/DifferentialDriveFeedforwardTest.cpp
new file mode 100644
index 0000000..74d945c
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/controller/DifferentialDriveFeedforwardTest.cpp
@@ -0,0 +1,84 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <gtest/gtest.h>
+
+#include <cmath>
+
+#include "frc/EigenCore.h"
+#include "frc/controller/DifferentialDriveFeedforward.h"
+#include "frc/controller/LinearPlantInversionFeedforward.h"
+#include "frc/system/plant/LinearSystemId.h"
+#include "units/acceleration.h"
+#include "units/length.h"
+#include "units/time.h"
+
+TEST(DifferentialDriveFeedforwardTest, CalculateWithTrackwidth) {
+  constexpr auto kVLinear = 1_V / 1_mps;
+  constexpr auto kALinear = 1_V / 1_mps_sq;
+  constexpr auto kVAngular = 1_V / 1_rad_per_s;
+  constexpr auto kAAngular = 1_V / 1_rad_per_s_sq;
+  constexpr auto trackwidth = 1_m;
+  constexpr auto dt = 20_ms;
+
+  frc::DifferentialDriveFeedforward differentialDriveFeedforward{
+      kVLinear, kALinear, kVAngular, kAAngular, trackwidth};
+  frc::LinearSystem<2, 2, 2> plant =
+      frc::LinearSystemId::IdentifyDrivetrainSystem(
+          kVLinear, kALinear, kVAngular, kAAngular, trackwidth);
+  for (auto currentLeftVelocity = -4_mps; currentLeftVelocity <= 4_mps;
+       currentLeftVelocity += 2_mps) {
+    for (auto currentRightVelocity = -4_mps; currentRightVelocity <= 4_mps;
+         currentRightVelocity += 2_mps) {
+      for (auto nextLeftVelocity = -4_mps; nextLeftVelocity <= 4_mps;
+           nextLeftVelocity += 2_mps) {
+        for (auto nextRightVelocity = -4_mps; nextRightVelocity <= 4_mps;
+             nextRightVelocity += 2_mps) {
+          auto [left, right] = differentialDriveFeedforward.Calculate(
+              currentLeftVelocity, nextLeftVelocity, currentRightVelocity,
+              nextRightVelocity, dt);
+          frc::Matrixd<2, 1> nextX = plant.CalculateX(
+              frc::Vectord<2>{currentLeftVelocity, currentRightVelocity},
+              frc::Vectord<2>{left, right}, dt);
+          EXPECT_NEAR(nextX(0), nextLeftVelocity.value(), 1e-6);
+          EXPECT_NEAR(nextX(1), nextRightVelocity.value(), 1e-6);
+        }
+      }
+    }
+  }
+}
+
+TEST(DifferentialDriveFeedforwardTest, CalculateWithoutTrackwidth) {
+  constexpr auto kVLinear = 1_V / 1_mps;
+  constexpr auto kALinear = 1_V / 1_mps_sq;
+  constexpr auto kVAngular = 1_V / 1_mps;
+  constexpr auto kAAngular = 1_V / 1_mps_sq;
+  constexpr auto dt = 20_ms;
+
+  frc::DifferentialDriveFeedforward differentialDriveFeedforward{
+      kVLinear, kALinear, kVAngular, kAAngular};
+  frc::LinearSystem<2, 2, 2> plant =
+      frc::LinearSystemId::IdentifyDrivetrainSystem(kVLinear, kALinear,
+                                                    kVAngular, kAAngular);
+  for (auto currentLeftVelocity = -4_mps; currentLeftVelocity <= 4_mps;
+       currentLeftVelocity += 2_mps) {
+    for (auto currentRightVelocity = -4_mps; currentRightVelocity <= 4_mps;
+         currentRightVelocity += 2_mps) {
+      for (auto nextLeftVelocity = -4_mps; nextLeftVelocity <= 4_mps;
+           nextLeftVelocity += 2_mps) {
+        for (auto nextRightVelocity = -4_mps; nextRightVelocity <= 4_mps;
+             nextRightVelocity += 2_mps) {
+          auto [left, right] = differentialDriveFeedforward.Calculate(
+              currentLeftVelocity, nextLeftVelocity, currentRightVelocity,
+              nextRightVelocity, dt);
+          frc::Matrixd<2, 1> nextX = plant.CalculateX(
+              frc::Vectord<2>{currentLeftVelocity, currentRightVelocity},
+              frc::Vectord<2>{left, right}, dt);
+          EXPECT_NEAR(nextX(0), nextLeftVelocity.value(), 1e-6);
+          EXPECT_NEAR(nextX(1), nextRightVelocity.value(), 1e-6);
+        }
+      }
+    }
+  }
+}
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/controller/HolonomicDriveControllerTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/controller/HolonomicDriveControllerTest.cpp
index c6b669c..134a4e0 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/controller/HolonomicDriveControllerTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/controller/HolonomicDriveControllerTest.cpp
@@ -2,7 +2,7 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
-#include <wpi/numbers>
+#include <numbers>
 
 #include "frc/MathUtil.h"
 #include "frc/controller/HolonomicDriveController.h"
@@ -16,7 +16,7 @@
   EXPECT_LE(units::math::abs(val1 - val2), eps)
 
 static constexpr units::meter_t kTolerance{1 / 12.0};
-static constexpr units::radian_t kAngularTolerance{2.0 * wpi::numbers::pi /
+static constexpr units::radian_t kAngularTolerance{2.0 * std::numbers::pi /
                                                    180.0};
 
 TEST(HolonomicDriveControllerTest, ReachesReference) {
@@ -25,10 +25,10 @@
       frc::ProfiledPIDController<units::radian>{
           1.0, 0.0, 0.0,
           frc::TrapezoidProfile<units::radian>::Constraints{
-              units::radians_per_second_t{2.0 * wpi::numbers::pi},
-              units::radians_per_second_squared_t{wpi::numbers::pi}}}};
+              units::radians_per_second_t{2.0 * std::numbers::pi},
+              units::radians_per_second_squared_t{std::numbers::pi}}}};
 
-  frc::Pose2d robotPose{2.7_m, 23_m, frc::Rotation2d{0_deg}};
+  frc::Pose2d robotPose{2.7_m, 23_m, 0_deg};
 
   auto waypoints = std::vector{frc::Pose2d{2.75_m, 22.521_m, 0_rad},
                                frc::Pose2d{24.73_m, 19.68_m, 5.846_rad}};
@@ -60,7 +60,7 @@
               4_rad_per_s, 2_rad_per_s / 1_s}}};
 
   frc::ChassisSpeeds speeds = controller.Calculate(
-      frc::Pose2d(0_m, 0_m, 1.57_rad), frc::Pose2d(), 0_mps, 1.57_rad);
+      frc::Pose2d{0_m, 0_m, 1.57_rad}, frc::Pose2d{}, 0_mps, 1.57_rad);
 
   EXPECT_EQ(0, speeds.omega.value());
 }
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/controller/ImplicitModelFollowerTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/controller/ImplicitModelFollowerTest.cpp
new file mode 100644
index 0000000..afa491a
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/controller/ImplicitModelFollowerTest.cpp
@@ -0,0 +1,109 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <gtest/gtest.h>
+
+#include "frc/controller/ImplicitModelFollower.h"
+#include "frc/system/plant/LinearSystemId.h"
+
+namespace frc {
+
+TEST(ImplicitModelFollowerTest, SameModel) {
+  constexpr auto dt = 5_ms;
+
+  using Kv_t = decltype(1_V / 1_mps);
+  using Ka_t = decltype(1_V / 1_mps_sq);
+  auto plant = LinearSystemId::IdentifyDrivetrainSystem(Kv_t{1.0}, Ka_t{1.0},
+                                                        Kv_t{1.0}, Ka_t{1.0});
+
+  ImplicitModelFollower<2, 2> imf{plant, plant};
+
+  Vectord<2> x{0.0, 0.0};
+  Vectord<2> xImf{0.0, 0.0};
+
+  // Forward
+  Vectord<2> u{12.0, 12.0};
+  for (auto t = 0_s; t < 3_s; t += dt) {
+    x = plant.CalculateX(x, u, dt);
+    xImf = plant.CalculateX(xImf, imf.Calculate(xImf, u), dt);
+
+    EXPECT_DOUBLE_EQ(x(0), xImf(0));
+    EXPECT_DOUBLE_EQ(x(1), xImf(1));
+  }
+
+  // Backward
+  u = Vectord<2>{-12.0, -12.0};
+  for (auto t = 0_s; t < 3_s; t += dt) {
+    x = plant.CalculateX(x, u, dt);
+    xImf = plant.CalculateX(xImf, imf.Calculate(xImf, u), dt);
+
+    EXPECT_DOUBLE_EQ(x(0), xImf(0));
+    EXPECT_DOUBLE_EQ(x(1), xImf(1));
+  }
+
+  // Rotate CCW
+  u = Vectord<2>{-12.0, 12.0};
+  for (auto t = 0_s; t < 3_s; t += dt) {
+    x = plant.CalculateX(x, u, dt);
+    xImf = plant.CalculateX(xImf, imf.Calculate(xImf, u), dt);
+
+    EXPECT_DOUBLE_EQ(x(0), xImf(0));
+    EXPECT_DOUBLE_EQ(x(1), xImf(1));
+  }
+}
+
+TEST(ImplicitModelFollowerTest, SlowerRefModel) {
+  constexpr auto dt = 5_ms;
+
+  using Kv_t = decltype(1_V / 1_mps);
+  using Ka_t = decltype(1_V / 1_mps_sq);
+
+  auto plant = LinearSystemId::IdentifyDrivetrainSystem(Kv_t{1.0}, Ka_t{1.0},
+                                                        Kv_t{1.0}, Ka_t{1.0});
+
+  // Linear acceleration is slower, but angular acceleration is the same
+  auto plantRef = LinearSystemId::IdentifyDrivetrainSystem(
+      Kv_t{1.0}, Ka_t{2.0}, Kv_t{1.0}, Ka_t{1.0});
+
+  ImplicitModelFollower<2, 2> imf{plant, plantRef};
+
+  Vectord<2> x{0.0, 0.0};
+  Vectord<2> xImf{0.0, 0.0};
+
+  // Forward
+  Vectord<2> u{12.0, 12.0};
+  for (auto t = 0_s; t < 3_s; t += dt) {
+    x = plant.CalculateX(x, u, dt);
+    xImf = plant.CalculateX(xImf, imf.Calculate(xImf, u), dt);
+
+    EXPECT_GE(x(0), xImf(0));
+    EXPECT_GE(x(1), xImf(1));
+  }
+
+  // Backward
+  x.setZero();
+  xImf.setZero();
+  u = Vectord<2>{-12.0, -12.0};
+  for (auto t = 0_s; t < 3_s; t += dt) {
+    x = plant.CalculateX(x, u, dt);
+    xImf = plant.CalculateX(xImf, imf.Calculate(xImf, u), dt);
+
+    EXPECT_LE(x(0), xImf(0));
+    EXPECT_LE(x(1), xImf(1));
+  }
+
+  // Rotate CCW
+  x.setZero();
+  xImf.setZero();
+  u = Vectord<2>{-12.0, 12.0};
+  for (auto t = 0_s; t < 3_s; t += dt) {
+    x = plant.CalculateX(x, u, dt);
+    xImf = plant.CalculateX(xImf, imf.Calculate(xImf, u), dt);
+
+    EXPECT_NEAR(x(0), xImf(0), 1e-5);
+    EXPECT_NEAR(x(1), xImf(1), 1e-5);
+  }
+}
+
+}  // namespace frc
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/controller/LTVDifferentialDriveControllerTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/controller/LTVDifferentialDriveControllerTest.cpp
new file mode 100644
index 0000000..753ea34
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/controller/LTVDifferentialDriveControllerTest.cpp
@@ -0,0 +1,101 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <cmath>
+
+#include "frc/MathUtil.h"
+#include "frc/controller/LTVDifferentialDriveController.h"
+#include "frc/system/NumericalIntegration.h"
+#include "frc/system/plant/LinearSystemId.h"
+#include "frc/trajectory/TrajectoryGenerator.h"
+#include "gtest/gtest.h"
+#include "units/math.h"
+
+#define EXPECT_NEAR_UNITS(val1, val2, eps) \
+  EXPECT_LE(units::math::abs(val1 - val2), eps)
+
+static constexpr units::meter_t kTolerance{1 / 12.0};
+static constexpr units::radian_t kAngularTolerance{2.0 * std::numbers::pi /
+                                                   180.0};
+
+/**
+ * States of the drivetrain system.
+ */
+class State {
+ public:
+  /// X position in global coordinate frame.
+  static constexpr int kX = 0;
+
+  /// Y position in global coordinate frame.
+  static constexpr int kY = 1;
+
+  /// Heading in global coordinate frame.
+  static constexpr int kHeading = 2;
+
+  /// Left encoder velocity.
+  static constexpr int kLeftVelocity = 3;
+
+  /// Right encoder velocity.
+  static constexpr int kRightVelocity = 4;
+};
+
+static constexpr auto kLinearV = 3.02_V / 1_mps;
+static constexpr auto kLinearA = 0.642_V / 1_mps_sq;
+static constexpr auto kAngularV = 1.382_V / 1_mps;
+static constexpr auto kAngularA = 0.08495_V / 1_mps_sq;
+static auto plant = frc::LinearSystemId::IdentifyDrivetrainSystem(
+    kLinearV, kLinearA, kAngularV, kAngularA);
+static constexpr auto kTrackwidth = 0.9_m;
+
+frc::Vectord<5> Dynamics(const frc::Vectord<5>& x, const frc::Vectord<2>& u) {
+  double v = (x(State::kLeftVelocity) + x(State::kRightVelocity)) / 2.0;
+
+  frc::Vectord<5> xdot;
+  xdot(0) = v * std::cos(x(State::kHeading));
+  xdot(1) = v * std::sin(x(State::kHeading));
+  xdot(2) = ((x(State::kRightVelocity) - x(State::kLeftVelocity)) / kTrackwidth)
+                .value();
+  xdot.block<2, 1>(3, 0) = plant.A() * x.block<2, 1>(3, 0) + plant.B() * u;
+  return xdot;
+}
+
+TEST(LTVDifferentialDriveControllerTest, ReachesReference) {
+  constexpr auto kDt = 0.02_s;
+
+  frc::LTVDifferentialDriveController controller{
+      plant, kTrackwidth, {0.0625, 0.125, 2.5, 0.95, 0.95}, {12.0, 12.0}, kDt};
+  frc::Pose2d robotPose{2.7_m, 23_m, 0_deg};
+
+  auto waypoints = std::vector{frc::Pose2d{2.75_m, 22.521_m, 0_rad},
+                               frc::Pose2d{24.73_m, 19.68_m, 5.846_rad}};
+  auto trajectory = frc::TrajectoryGenerator::GenerateTrajectory(
+      waypoints, {8.8_mps, 0.1_mps_sq});
+
+  frc::Vectord<5> x = frc::Vectord<5>::Zero();
+  x(State::kX) = robotPose.X().value();
+  x(State::kY) = robotPose.Y().value();
+  x(State::kHeading) = robotPose.Rotation().Radians().value();
+
+  auto totalTime = trajectory.TotalTime();
+  for (size_t i = 0; i < (totalTime / kDt).value(); ++i) {
+    auto state = trajectory.Sample(kDt * i);
+    robotPose =
+        frc::Pose2d{units::meter_t{x(State::kX)}, units::meter_t{x(State::kY)},
+                    units::radian_t{x(State::kHeading)}};
+    auto [leftVoltage, rightVoltage] = controller.Calculate(
+        robotPose, units::meters_per_second_t{x(State::kLeftVelocity)},
+        units::meters_per_second_t{x(State::kRightVelocity)}, state);
+
+    x = frc::RKDP(&Dynamics, x,
+                  frc::Vectord<2>{leftVoltage.value(), rightVoltage.value()},
+                  kDt);
+  }
+
+  auto& endPose = trajectory.States().back().pose;
+  EXPECT_NEAR_UNITS(endPose.X(), robotPose.X(), kTolerance);
+  EXPECT_NEAR_UNITS(endPose.Y(), robotPose.Y(), kTolerance);
+  EXPECT_NEAR_UNITS(frc::AngleModulus(endPose.Rotation().Radians() -
+                                      robotPose.Rotation().Radians()),
+                    0_rad, kAngularTolerance);
+}
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/controller/LTVUnicycleControllerTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/controller/LTVUnicycleControllerTest.cpp
new file mode 100644
index 0000000..56faf1d
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/controller/LTVUnicycleControllerTest.cpp
@@ -0,0 +1,44 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/MathUtil.h"
+#include "frc/controller/LTVUnicycleController.h"
+#include "frc/trajectory/TrajectoryGenerator.h"
+#include "gtest/gtest.h"
+#include "units/math.h"
+
+#define EXPECT_NEAR_UNITS(val1, val2, eps) \
+  EXPECT_LE(units::math::abs(val1 - val2), eps)
+
+static constexpr units::meter_t kTolerance{1 / 12.0};
+static constexpr units::radian_t kAngularTolerance{2.0 * std::numbers::pi /
+                                                   180.0};
+
+TEST(LTVUnicycleControllerTest, ReachesReference) {
+  constexpr auto kDt = 0.02_s;
+
+  frc::LTVUnicycleController controller{{0.0625, 0.125, 2.5}, {4.0, 4.0}, kDt};
+  frc::Pose2d robotPose{2.7_m, 23_m, 0_deg};
+
+  auto waypoints = std::vector{frc::Pose2d{2.75_m, 22.521_m, 0_rad},
+                               frc::Pose2d{24.73_m, 19.68_m, 5.846_rad}};
+  auto trajectory = frc::TrajectoryGenerator::GenerateTrajectory(
+      waypoints, {8.8_mps, 0.1_mps_sq});
+
+  auto totalTime = trajectory.TotalTime();
+  for (size_t i = 0; i < (totalTime / kDt).value(); ++i) {
+    auto state = trajectory.Sample(kDt * i);
+    auto [vx, vy, omega] = controller.Calculate(robotPose, state);
+    static_cast<void>(vy);
+
+    robotPose = robotPose.Exp(frc::Twist2d{vx * kDt, 0_m, omega * kDt});
+  }
+
+  auto& endPose = trajectory.States().back().pose;
+  EXPECT_NEAR_UNITS(endPose.X(), robotPose.X(), kTolerance);
+  EXPECT_NEAR_UNITS(endPose.Y(), robotPose.Y(), kTolerance);
+  EXPECT_NEAR_UNITS(frc::AngleModulus(endPose.Rotation().Radians() -
+                                      robotPose.Rotation().Radians()),
+                    0_rad, kAngularTolerance);
+}
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/controller/LinearPlantInversionFeedforwardTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/controller/LinearPlantInversionFeedforwardTest.cpp
index 6e61706..e7107d0 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/controller/LinearPlantInversionFeedforwardTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/controller/LinearPlantInversionFeedforwardTest.cpp
@@ -6,21 +6,20 @@
 
 #include <cmath>
 
-#include "Eigen/Core"
+#include "frc/EigenCore.h"
 #include "frc/controller/LinearPlantInversionFeedforward.h"
 #include "units/time.h"
 
 namespace frc {
 
 TEST(LinearPlantInversionFeedforwardTest, Calculate) {
-  Eigen::Matrix<double, 2, 2> A{{1, 0}, {0, 1}};
-  Eigen::Matrix<double, 2, 1> B{0, 1};
+  Matrixd<2, 2> A{{1, 0}, {0, 1}};
+  Matrixd<2, 1> B{0, 1};
 
-  frc::LinearPlantInversionFeedforward<2, 1> feedforward{A, B,
-                                                         units::second_t(0.02)};
+  frc::LinearPlantInversionFeedforward<2, 1> feedforward{A, B, 20_ms};
 
-  Eigen::Vector<double, 2> r{2, 2};
-  Eigen::Vector<double, 2> nextR{3, 3};
+  Vectord<2> r{2, 2};
+  Vectord<2> nextR{3, 3};
 
   EXPECT_NEAR(47.502599, feedforward.Calculate(r, nextR)(0, 0), 0.002);
 }
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/controller/LinearQuadraticRegulatorTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/controller/LinearQuadraticRegulatorTest.cpp
index 7055530..1127fc2 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/controller/LinearQuadraticRegulatorTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/controller/LinearQuadraticRegulatorTest.cpp
@@ -6,7 +6,7 @@
 
 #include <cmath>
 
-#include "Eigen/Core"
+#include "frc/EigenCore.h"
 #include "frc/controller/LinearQuadraticRegulator.h"
 #include "frc/system/LinearSystem.h"
 #include "frc/system/plant/DCMotor.h"
@@ -30,7 +30,7 @@
 
     return frc::LinearSystemId::ElevatorSystem(motors, m, r, G);
   }();
-  Eigen::Matrix<double, 1, 2> K =
+  Matrixd<1, 2> K =
       LinearQuadraticRegulator<2, 1>{plant, {0.02, 0.4}, {12.0}, 5.05_ms}.K();
 
   EXPECT_NEAR(522.15314269, K(0, 0), 1e-6);
@@ -54,7 +54,7 @@
         motors, 1.0 / 3.0 * m * r * r, G);
   }();
 
-  Eigen::Matrix<double, 1, 2> K =
+  Matrixd<1, 2> K =
       LinearQuadraticRegulator<2, 1>{plant, {0.01745, 0.08726}, {12.0}, 5.05_ms}
           .K();
 
@@ -77,7 +77,7 @@
 
     return frc::LinearSystemId::ElevatorSystem(motors, m, r, G);
   }();
-  Eigen::Matrix<double, 1, 2> K =
+  Matrixd<1, 2> K =
       LinearQuadraticRegulator<2, 1>{plant, {0.1, 0.2}, {12.0}, 20_ms}.K();
 
   EXPECT_NEAR(10.38, K(0, 0), 1e-1);
@@ -99,50 +99,44 @@
  * @param dt Discretization timestep.
  */
 template <int States, int Inputs>
-Eigen::Matrix<double, Inputs, States> GetImplicitModelFollowingK(
-    const Eigen::Matrix<double, States, States>& A,
-    const Eigen::Matrix<double, States, Inputs>& B,
-    const Eigen::Matrix<double, States, States>& Q,
-    const Eigen::Matrix<double, Inputs, Inputs>& R,
-    const Eigen::Matrix<double, States, States>& Aref, units::second_t dt) {
+Matrixd<Inputs, States> GetImplicitModelFollowingK(
+    const Matrixd<States, States>& A, const Matrixd<States, Inputs>& B,
+    const Matrixd<States, States>& Q, const Matrixd<Inputs, Inputs>& R,
+    const Matrixd<States, States>& Aref, units::second_t dt) {
   // Discretize real dynamics
-  Eigen::Matrix<double, States, States> discA;
-  Eigen::Matrix<double, States, Inputs> discB;
+  Matrixd<States, States> discA;
+  Matrixd<States, Inputs> discB;
   DiscretizeAB<States, Inputs>(A, B, dt, &discA, &discB);
 
   // Discretize desired dynamics
-  Eigen::Matrix<double, States, States> discAref;
+  Matrixd<States, States> discAref;
   DiscretizeA<States>(Aref, dt, &discAref);
 
-  Eigen::Matrix<double, States, States> Qimf =
+  Matrixd<States, States> Qimf =
       (discA - discAref).transpose() * Q * (discA - discAref);
-  Eigen::Matrix<double, Inputs, Inputs> Rimf =
-      discB.transpose() * Q * discB + R;
-  Eigen::Matrix<double, States, Inputs> Nimf =
-      (discA - discAref).transpose() * Q * discB;
+  Matrixd<Inputs, Inputs> Rimf = discB.transpose() * Q * discB + R;
+  Matrixd<States, Inputs> Nimf = (discA - discAref).transpose() * Q * discB;
 
   return LinearQuadraticRegulator<States, Inputs>{A, B, Qimf, Rimf, Nimf, dt}
       .K();
 }
 
 TEST(LinearQuadraticRegulatorTest, MatrixOverloadsWithSingleIntegrator) {
-  Eigen::Matrix<double, 2, 2> A{Eigen::Matrix<double, 2, 2>::Zero()};
-  Eigen::Matrix<double, 2, 2> B{Eigen::Matrix<double, 2, 2>::Identity()};
-  Eigen::Matrix<double, 2, 2> Q{Eigen::Matrix<double, 2, 2>::Identity()};
-  Eigen::Matrix<double, 2, 2> R{Eigen::Matrix<double, 2, 2>::Identity()};
+  Matrixd<2, 2> A{Matrixd<2, 2>::Zero()};
+  Matrixd<2, 2> B{Matrixd<2, 2>::Identity()};
+  Matrixd<2, 2> Q{Matrixd<2, 2>::Identity()};
+  Matrixd<2, 2> R{Matrixd<2, 2>::Identity()};
 
   // QR overload
-  Eigen::Matrix<double, 2, 2> K =
-      LinearQuadraticRegulator<2, 2>{A, B, Q, R, 5_ms}.K();
+  Matrixd<2, 2> K = LinearQuadraticRegulator<2, 2>{A, B, Q, R, 5_ms}.K();
   EXPECT_NEAR(0.99750312499512261, K(0, 0), 1e-10);
   EXPECT_NEAR(0.0, K(0, 1), 1e-10);
   EXPECT_NEAR(0.0, K(1, 0), 1e-10);
   EXPECT_NEAR(0.99750312499512261, K(1, 1), 1e-10);
 
   // QRN overload
-  Eigen::Matrix<double, 2, 2> N{Eigen::Matrix<double, 2, 2>::Identity()};
-  Eigen::Matrix<double, 2, 2> Kimf =
-      LinearQuadraticRegulator<2, 2>{A, B, Q, R, N, 5_ms}.K();
+  Matrixd<2, 2> N{Matrixd<2, 2>::Identity()};
+  Matrixd<2, 2> Kimf = LinearQuadraticRegulator<2, 2>{A, B, Q, R, N, 5_ms}.K();
   EXPECT_NEAR(1.0, Kimf(0, 0), 1e-10);
   EXPECT_NEAR(0.0, Kimf(0, 1), 1e-10);
   EXPECT_NEAR(0.0, Kimf(1, 0), 1e-10);
@@ -153,21 +147,19 @@
   double Kv = 3.02;
   double Ka = 0.642;
 
-  Eigen::Matrix<double, 2, 2> A{{0, 1}, {0, -Kv / Ka}};
-  Eigen::Matrix<double, 2, 1> B{{0}, {1.0 / Ka}};
-  Eigen::Matrix<double, 2, 2> Q{{1, 0}, {0, 0.2}};
-  Eigen::Matrix<double, 1, 1> R{0.25};
+  Matrixd<2, 2> A{{0, 1}, {0, -Kv / Ka}};
+  Matrixd<2, 1> B{{0}, {1.0 / Ka}};
+  Matrixd<2, 2> Q{{1, 0}, {0, 0.2}};
+  Matrixd<1, 1> R{0.25};
 
   // QR overload
-  Eigen::Matrix<double, 1, 2> K =
-      LinearQuadraticRegulator<2, 1>{A, B, Q, R, 5_ms}.K();
+  Matrixd<1, 2> K = LinearQuadraticRegulator<2, 1>{A, B, Q, R, 5_ms}.K();
   EXPECT_NEAR(1.9960017786537287, K(0, 0), 1e-10);
   EXPECT_NEAR(0.51182128351092726, K(0, 1), 1e-10);
 
   // QRN overload
-  Eigen::Matrix<double, 2, 2> Aref{{0, 1}, {0, -Kv / (Ka * 2.0)}};
-  Eigen::Matrix<double, 1, 2> Kimf =
-      GetImplicitModelFollowingK<2, 1>(A, B, Q, R, Aref, 5_ms);
+  Matrixd<2, 2> Aref{{0, 1}, {0, -Kv / (Ka * 2.0)}};
+  Matrixd<1, 2> Kimf = GetImplicitModelFollowingK<2, 1>(A, B, Q, R, Aref, 5_ms);
   EXPECT_NEAR(0.0, Kimf(0, 0), 1e-10);
   EXPECT_NEAR(-5.367540084534802e-05, Kimf(0, 1), 1e-10);
 }
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/controller/PIDInputOutputTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/controller/PIDInputOutputTest.cpp
index 379db9e..f1034f5 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/controller/PIDInputOutputTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/controller/PIDInputOutputTest.cpp
@@ -9,7 +9,7 @@
  protected:
   frc2::PIDController* controller;
 
-  void SetUp() override { controller = new frc2::PIDController(0, 0, 0); }
+  void SetUp() override { controller = new frc2::PIDController{0, 0, 0}; }
 
   void TearDown() override { delete controller; }
 };
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/controller/ProfiledPIDInputOutputTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/controller/ProfiledPIDInputOutputTest.cpp
index da402ae..44d1f41 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/controller/ProfiledPIDInputOutputTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/controller/ProfiledPIDInputOutputTest.cpp
@@ -2,7 +2,7 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
-#include <wpi/numbers>
+#include <numbers>
 
 #include "frc/controller/ProfiledPIDController.h"
 #include "gtest/gtest.h"
@@ -40,8 +40,8 @@
 
 TEST_F(ProfiledPIDInputOutputTest, ContinuousInput2) {
   controller->SetP(1);
-  controller->EnableContinuousInput(-units::radian_t{wpi::numbers::pi},
-                                    units::radian_t{wpi::numbers::pi});
+  controller->EnableContinuousInput(-units::radian_t{std::numbers::pi},
+                                    units::radian_t{std::numbers::pi});
 
   static constexpr units::radian_t kSetpoint{-3.4826633343199735};
   static constexpr units::radian_t kMeasurement{-3.1352207333939606};
@@ -52,13 +52,13 @@
 
   // Error must be less than half the input range at all times
   EXPECT_LT(units::math::abs(controller->GetSetpoint().position - kMeasurement),
-            units::radian_t{wpi::numbers::pi});
+            units::radian_t{std::numbers::pi});
 }
 
 TEST_F(ProfiledPIDInputOutputTest, ContinuousInput3) {
   controller->SetP(1);
-  controller->EnableContinuousInput(-units::radian_t{wpi::numbers::pi},
-                                    units::radian_t{wpi::numbers::pi});
+  controller->EnableContinuousInput(-units::radian_t{std::numbers::pi},
+                                    units::radian_t{std::numbers::pi});
 
   static constexpr units::radian_t kSetpoint{-3.5176604690006377};
   static constexpr units::radian_t kMeasurement{3.1191729343822456};
@@ -69,13 +69,13 @@
 
   // Error must be less than half the input range at all times
   EXPECT_LT(units::math::abs(controller->GetSetpoint().position - kMeasurement),
-            units::radian_t{wpi::numbers::pi});
+            units::radian_t{std::numbers::pi});
 }
 
 TEST_F(ProfiledPIDInputOutputTest, ContinuousInput4) {
   controller->SetP(1);
   controller->EnableContinuousInput(0_rad,
-                                    units::radian_t{2.0 * wpi::numbers::pi});
+                                    units::radian_t{2.0 * std::numbers::pi});
 
   static constexpr units::radian_t kSetpoint{2.78};
   static constexpr units::radian_t kMeasurement{3.12};
@@ -86,7 +86,7 @@
 
   // Error must be less than half the input range at all times
   EXPECT_LT(units::math::abs(controller->GetSetpoint().position - kMeasurement),
-            units::radian_t{wpi::numbers::pi});
+            units::radian_t{std::numbers::pi});
 }
 
 TEST_F(ProfiledPIDInputOutputTest, ProportionalGainOutput) {
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/controller/RamseteControllerTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/controller/RamseteControllerTest.cpp
index 8829deb..2fd26bb 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/controller/RamseteControllerTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/controller/RamseteControllerTest.cpp
@@ -12,13 +12,13 @@
   EXPECT_LE(units::math::abs(val1 - val2), eps)
 
 static constexpr units::meter_t kTolerance{1 / 12.0};
-static constexpr units::radian_t kAngularTolerance{2.0 * wpi::numbers::pi /
+static constexpr units::radian_t kAngularTolerance{2.0 * std::numbers::pi /
                                                    180.0};
 
 TEST(RamseteControllerTest, ReachesReference) {
   frc::RamseteController controller{2.0 * 1_rad * 1_rad / (1_m * 1_m),
                                     0.7 / 1_rad};
-  frc::Pose2d robotPose{2.7_m, 23_m, frc::Rotation2d{0_deg}};
+  frc::Pose2d robotPose{2.7_m, 23_m, 0_deg};
 
   auto waypoints = std::vector{frc::Pose2d{2.75_m, 22.521_m, 0_rad},
                                frc::Pose2d{24.73_m, 19.68_m, 5.846_rad}};
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/controller/SimpleMotorFeedforwardTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/controller/SimpleMotorFeedforwardTest.cpp
index 3cf944e..6d10e05 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/controller/SimpleMotorFeedforwardTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/controller/SimpleMotorFeedforwardTest.cpp
@@ -6,7 +6,7 @@
 
 #include <cmath>
 
-#include "Eigen/Core"
+#include "frc/EigenCore.h"
 #include "frc/controller/LinearPlantInversionFeedforward.h"
 #include "frc/controller/SimpleMotorFeedforward.h"
 #include "units/acceleration.h"
@@ -21,16 +21,16 @@
   double Ka = 0.6;
   auto dt = 0.02_s;
 
-  Eigen::Matrix<double, 1, 1> A{-Kv / Ka};
-  Eigen::Matrix<double, 1, 1> B{1.0 / Ka};
+  Matrixd<1, 1> A{-Kv / Ka};
+  Matrixd<1, 1> B{1.0 / Ka};
 
   frc::LinearPlantInversionFeedforward<1, 1> plantInversion{A, B, dt};
   frc::SimpleMotorFeedforward<units::meter> simpleMotor{
       units::volt_t{Ks}, units::volt_t{Kv} / 1_mps,
       units::volt_t{Ka} / 1_mps_sq};
 
-  Eigen::Vector<double, 1> r{2.0};
-  Eigen::Vector<double, 1> nextR{3.0};
+  Vectord<1> r{2.0};
+  Vectord<1> nextR{3.0};
 
   EXPECT_NEAR(37.524995834325161 + Ks,
               simpleMotor.Calculate(2_mps, 3_mps, dt).value(), 0.002);
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/estimator/AngleStatisticsTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/estimator/AngleStatisticsTest.cpp
index ee1da7f..b2ee87d 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/estimator/AngleStatisticsTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/estimator/AngleStatisticsTest.cpp
@@ -4,15 +4,15 @@
 
 #include <gtest/gtest.h>
 
-#include <wpi/numbers>
+#include <numbers>
 
-#include "Eigen/Core"
+#include "frc/EigenCore.h"
 #include "frc/estimator/AngleStatistics.h"
 
 TEST(AngleStatisticsTest, Mean) {
-  Eigen::Matrix<double, 3, 3> sigmas{
+  frc::Matrixd<3, 3> sigmas{
       {1, 1.2, 0},
-      {359 * wpi::numbers::pi / 180, 3 * wpi::numbers::pi / 180, 0},
+      {359 * std::numbers::pi / 180, 3 * std::numbers::pi / 180, 0},
       {1, 2, 0}};
   // Weights need to produce the mean of the sigmas
   Eigen::Vector3d weights;
@@ -23,16 +23,16 @@
 }
 
 TEST(AngleStatisticsTest, Residual) {
-  Eigen::Vector3d a{1, 1 * wpi::numbers::pi / 180, 2};
-  Eigen::Vector3d b{1, 359 * wpi::numbers::pi / 180, 1};
+  Eigen::Vector3d a{1, 1 * std::numbers::pi / 180, 2};
+  Eigen::Vector3d b{1, 359 * std::numbers::pi / 180, 1};
 
   EXPECT_TRUE(frc::AngleResidual<3>(a, b, 1).isApprox(
-      Eigen::Vector3d{0, 2 * wpi::numbers::pi / 180, 1}));
+      Eigen::Vector3d{0, 2 * std::numbers::pi / 180, 1}));
 }
 
 TEST(AngleStatisticsTest, Add) {
-  Eigen::Vector3d a{1, 1 * wpi::numbers::pi / 180, 2};
-  Eigen::Vector3d b{1, 359 * wpi::numbers::pi / 180, 1};
+  Eigen::Vector3d a{1, 1 * std::numbers::pi / 180, 2};
+  Eigen::Vector3d b{1, 359 * std::numbers::pi / 180, 1};
 
   EXPECT_TRUE(frc::AngleAdd<3>(a, b, 1).isApprox(Eigen::Vector3d{2, 0, 3}));
 }
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/estimator/DifferentialDrivePoseEstimatorTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/estimator/DifferentialDrivePoseEstimatorTest.cpp
index 4a854fd..1d623ca 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/estimator/DifferentialDrivePoseEstimatorTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/estimator/DifferentialDrivePoseEstimatorTest.cpp
@@ -4,81 +4,103 @@
 
 #include <limits>
 #include <random>
+#include <tuple>
+#include <utility>
 
 #include "frc/StateSpaceUtil.h"
 #include "frc/estimator/DifferentialDrivePoseEstimator.h"
 #include "frc/geometry/Pose2d.h"
 #include "frc/geometry/Rotation2d.h"
 #include "frc/kinematics/DifferentialDriveKinematics.h"
-#include "frc/kinematics/DifferentialDriveOdometry.h"
 #include "frc/trajectory/TrajectoryGenerator.h"
 #include "gtest/gtest.h"
 #include "units/angle.h"
 #include "units/length.h"
 #include "units/time.h"
 
-TEST(DifferentialDrivePoseEstimatorTest, Accuracy) {
-  frc::DifferentialDrivePoseEstimator estimator{frc::Rotation2d(),
-                                                frc::Pose2d(),
-                                                {0.02, 0.02, 0.01, 0.02, 0.02},
-                                                {0.01, 0.01, 0.001},
-                                                {0.1, 0.1, 0.01}};
+void testFollowTrajectory(
+    const frc::DifferentialDriveKinematics& kinematics,
+    frc::DifferentialDrivePoseEstimator& estimator,
+    const frc::Trajectory& trajectory,
+    std::function<frc::ChassisSpeeds(frc::Trajectory::State&)>
+        chassisSpeedsGenerator,
+    std::function<frc::Pose2d(frc::Trajectory::State&)>
+        visionMeasurementGenerator,
+    const frc::Pose2d& startingPose, const frc::Pose2d& endingPose,
+    const units::second_t dt, const units::second_t kVisionUpdateRate,
+    const units::second_t kVisionUpdateDelay, const bool checkError,
+    const bool debug) {
+  units::meter_t leftDistance = 0_m;
+  units::meter_t rightDistance = 0_m;
 
-  frc::Trajectory trajectory = frc::TrajectoryGenerator::GenerateTrajectory(
-      std::vector{frc::Pose2d(0_m, 0_m, frc::Rotation2d(45_deg)),
-                  frc::Pose2d(3_m, 0_m, frc::Rotation2d(-90_deg)),
-                  frc::Pose2d(0_m, 0_m, frc::Rotation2d(135_deg)),
-                  frc::Pose2d(-3_m, 0_m, frc::Rotation2d(-90_deg)),
-                  frc::Pose2d(0_m, 0_m, frc::Rotation2d(45_deg))},
-      frc::TrajectoryConfig(10_mps, 5.0_mps_sq));
-
-  frc::DifferentialDriveKinematics kinematics{1.0_m};
-  frc::DifferentialDriveOdometry odometry{frc::Rotation2d()};
+  estimator.ResetPosition(frc::Rotation2d{}, leftDistance, rightDistance,
+                          startingPose);
 
   std::default_random_engine generator;
   std::normal_distribution<double> distribution(0.0, 1.0);
 
-  units::second_t dt = 0.02_s;
-  units::second_t t = 0.0_s;
+  units::second_t t = 0_s;
 
-  units::meter_t leftDistance = 0_m;
-  units::meter_t rightDistance = 0_m;
-
-  units::second_t kVisionUpdateRate = 0.1_s;
-  frc::Pose2d lastVisionPose;
-  units::second_t lastVisionUpdateTime{-std::numeric_limits<double>::max()};
+  std::vector<std::pair<units::second_t, frc::Pose2d>> visionPoses;
+  std::vector<std::tuple<units::second_t, units::second_t, frc::Pose2d>>
+      visionLog;
 
   double maxError = -std::numeric_limits<double>::max();
   double errorSum = 0;
 
-  while (t <= trajectory.TotalTime()) {
-    auto groundTruthState = trajectory.Sample(t);
-    auto input = kinematics.ToWheelSpeeds(
-        {groundTruthState.velocity, 0_mps,
-         groundTruthState.velocity * groundTruthState.curvature});
+  if (debug) {
+    fmt::print(
+        "time, est_x, est_y, est_theta, true_x, true_y, true_theta, left, "
+        "right\n");
+  }
 
-    if (lastVisionUpdateTime + kVisionUpdateRate < t) {
-      if (lastVisionPose != frc::Pose2d()) {
-        estimator.AddVisionMeasurement(lastVisionPose, lastVisionUpdateTime);
-      }
-      lastVisionPose =
-          groundTruthState.pose +
-          frc::Transform2d(
-              frc::Translation2d(distribution(generator) * 0.1 * 1_m,
-                                 distribution(generator) * 0.1 * 1_m),
-              frc::Rotation2d(distribution(generator) * 0.01 * 1_rad));
+  while (t < trajectory.TotalTime()) {
+    frc::Trajectory::State groundTruthState = trajectory.Sample(t);
 
-      lastVisionUpdateTime = t;
+    // We are due for a new vision measurement if it's been `visionUpdateRate`
+    // seconds since the last vision measurement
+    if (visionPoses.empty() ||
+        visionPoses.back().first + kVisionUpdateRate < t) {
+      auto visionPose =
+          visionMeasurementGenerator(groundTruthState) +
+          frc::Transform2d{frc::Translation2d{distribution(generator) * 0.1_m,
+                                              distribution(generator) * 0.1_m},
+                           frc::Rotation2d{distribution(generator) * 0.05_rad}};
+      visionPoses.push_back({t, visionPose});
     }
 
-    leftDistance += input.left * distribution(generator) * 0.01 * dt;
-    rightDistance += input.right * distribution(generator) * 0.01 * dt;
+    // We should apply the oldest vision measurement if it has been
+    // `visionUpdateDelay` seconds since it was measured
+    if (!visionPoses.empty() &&
+        visionPoses.front().first + kVisionUpdateDelay < t) {
+      auto visionEntry = visionPoses.front();
+      estimator.AddVisionMeasurement(visionEntry.second, visionEntry.first);
+      visionPoses.erase(visionPoses.begin());
+      visionLog.push_back({t, visionEntry.first, visionEntry.second});
+    }
+
+    auto chassisSpeeds = chassisSpeedsGenerator(groundTruthState);
+
+    auto wheelSpeeds = kinematics.ToWheelSpeeds(chassisSpeeds);
+
+    leftDistance += wheelSpeeds.left * dt;
+    rightDistance += wheelSpeeds.right * dt;
 
     auto xhat = estimator.UpdateWithTime(
         t,
         groundTruthState.pose.Rotation() +
-            frc::Rotation2d(units::radian_t(distribution(generator) * 0.001)),
-        input, leftDistance, rightDistance);
+            frc::Rotation2d{distribution(generator) * 0.05_rad} -
+            trajectory.InitialPose().Rotation(),
+        leftDistance, rightDistance);
+
+    if (debug) {
+      fmt::print(
+          "{}, {}, {}, {}, {}, {}, {}, {}, {}\n", t.value(), xhat.X().value(),
+          xhat.Y().value(), xhat.Rotation().Radians().value(),
+          groundTruthState.pose.X().value(), groundTruthState.pose.Y().value(),
+          groundTruthState.pose.Rotation().Radians().value(),
+          leftDistance.value(), rightDistance.value());
+    }
 
     double error = groundTruthState.pose.Translation()
                        .Distance(xhat.Translation())
@@ -92,7 +114,96 @@
     t += dt;
   }
 
-  EXPECT_NEAR(0.0, errorSum / (trajectory.TotalTime().value() / dt.value()),
-              0.2);
-  EXPECT_NEAR(0.0, maxError, 0.4);
+  if (debug) {
+    fmt::print("apply_time, measured_time, vision_x, vision_y, vision_theta\n");
+
+    units::second_t apply_time;
+    units::second_t measure_time;
+    frc::Pose2d vision_pose;
+    for (auto record : visionLog) {
+      std::tie(apply_time, measure_time, vision_pose) = record;
+      fmt::print("{}, {}, {}, {}, {}\n", apply_time.value(),
+                 measure_time.value(), vision_pose.X().value(),
+                 vision_pose.Y().value(),
+                 vision_pose.Rotation().Radians().value());
+    }
+  }
+
+  EXPECT_NEAR(endingPose.X().value(),
+              estimator.GetEstimatedPosition().X().value(), 0.08);
+  EXPECT_NEAR(endingPose.Y().value(),
+              estimator.GetEstimatedPosition().Y().value(), 0.08);
+  EXPECT_NEAR(endingPose.Rotation().Radians().value(),
+              estimator.GetEstimatedPosition().Rotation().Radians().value(),
+              0.15);
+
+  if (checkError) {
+    EXPECT_LT(errorSum / (trajectory.TotalTime() / dt), 0.05);
+    EXPECT_LT(maxError, 0.2);
+  }
+}
+
+TEST(DifferentialDrivePoseEstimatorTest, Accuracy) {
+  frc::DifferentialDriveKinematics kinematics{1.0_m};
+
+  frc::DifferentialDrivePoseEstimator estimator{
+      kinematics,         frc::Rotation2d{}, 0_m, 0_m, frc::Pose2d{},
+      {0.02, 0.02, 0.01}, {0.1, 0.1, 0.1}};
+
+  frc::Trajectory trajectory = frc::TrajectoryGenerator::GenerateTrajectory(
+      std::vector{frc::Pose2d{0_m, 0_m, 45_deg}, frc::Pose2d{3_m, 0_m, -90_deg},
+                  frc::Pose2d{0_m, 0_m, 135_deg},
+                  frc::Pose2d{-3_m, 0_m, -90_deg},
+                  frc::Pose2d{0_m, 0_m, 45_deg}},
+      frc::TrajectoryConfig(2_mps, 2_mps_sq));
+
+  testFollowTrajectory(
+      kinematics, estimator, trajectory,
+      [&](frc::Trajectory::State& state) {
+        return frc::ChassisSpeeds{state.velocity, 0_mps,
+                                  state.velocity * state.curvature};
+      },
+      [&](frc::Trajectory::State& state) { return state.pose; },
+      trajectory.InitialPose(), {0_m, 0_m, frc::Rotation2d{45_deg}}, 0.02_s,
+      0.1_s, 0.25_s, true, false);
+}
+
+TEST(DifferentialDrivePoseEstimatorTest, BadInitialPose) {
+  frc::DifferentialDriveKinematics kinematics{1.0_m};
+
+  frc::DifferentialDrivePoseEstimator estimator{
+      kinematics,         frc::Rotation2d{}, 0_m, 0_m, frc::Pose2d{},
+      {0.02, 0.02, 0.01}, {0.1, 0.1, 0.1}};
+
+  frc::Trajectory trajectory = frc::TrajectoryGenerator::GenerateTrajectory(
+      std::vector{frc::Pose2d{0_m, 0_m, 45_deg}, frc::Pose2d{3_m, 0_m, -90_deg},
+                  frc::Pose2d{0_m, 0_m, 135_deg},
+                  frc::Pose2d{-3_m, 0_m, -90_deg},
+                  frc::Pose2d{0_m, 0_m, 45_deg}},
+      frc::TrajectoryConfig(2_mps, 2_mps_sq));
+
+  for (units::degree_t offset_direction_degs = 0_deg;
+       offset_direction_degs < 360_deg; offset_direction_degs += 45_deg) {
+    for (units::degree_t offset_heading_degs = 0_deg;
+         offset_heading_degs < 360_deg; offset_heading_degs += 45_deg) {
+      auto pose_offset = frc::Rotation2d{offset_direction_degs};
+      auto heading_offset = frc::Rotation2d{offset_heading_degs};
+
+      auto initial_pose =
+          trajectory.InitialPose() +
+          frc::Transform2d{frc::Translation2d{pose_offset.Cos() * 1_m,
+                                              pose_offset.Sin() * 1_m},
+                           heading_offset};
+
+      testFollowTrajectory(
+          kinematics, estimator, trajectory,
+          [&](frc::Trajectory::State& state) {
+            return frc::ChassisSpeeds{state.velocity, 0_mps,
+                                      state.velocity * state.curvature};
+          },
+          [&](frc::Trajectory::State& state) { return state.pose; },
+          initial_pose, {0_m, 0_m, frc::Rotation2d{45_deg}}, 0.02_s, 0.1_s,
+          0.25_s, false, false);
+    }
+  }
 }
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/estimator/ExtendedKalmanFilterTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/estimator/ExtendedKalmanFilterTest.cpp
index 6d51185..1924b73 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/estimator/ExtendedKalmanFilterTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/estimator/ExtendedKalmanFilterTest.cpp
@@ -7,8 +7,8 @@
 #include <array>
 #include <cmath>
 
-#include "Eigen/Core"
 #include "Eigen/QR"
+#include "frc/EigenCore.h"
 #include "frc/StateSpaceUtil.h"
 #include "frc/estimator/ExtendedKalmanFilter.h"
 #include "frc/system/NumericalJacobian.h"
@@ -18,8 +18,7 @@
 
 namespace {
 
-Eigen::Vector<double, 5> Dynamics(const Eigen::Vector<double, 5>& x,
-                                  const Eigen::Vector<double, 2>& u) {
+frc::Vectord<5> Dynamics(const frc::Vectord<5>& x, const frc::Vectord<2>& u) {
   auto motors = frc::DCMotor::CIM(2);
 
   // constexpr double Glow = 15.32;       // Low gear ratio
@@ -41,7 +40,7 @@
   units::volt_t Vr{u(1)};
 
   auto v = 0.5 * (vl + vr);
-  return Eigen::Vector<double, 5>{
+  return frc::Vectord<5>{
       v.value() * std::cos(x(2)), v.value() * std::sin(x(2)),
       ((vr - vl) / (2.0 * rb)).value(),
       k1.value() * ((C1 * vl).value() + (C2 * Vl).value()) +
@@ -50,16 +49,16 @@
           k1.value() * ((C1 * vr).value() + (C2 * Vr).value())};
 }
 
-Eigen::Vector<double, 3> LocalMeasurementModel(
-    const Eigen::Vector<double, 5>& x, const Eigen::Vector<double, 2>& u) {
+frc::Vectord<3> LocalMeasurementModel(const frc::Vectord<5>& x,
+                                      const frc::Vectord<2>& u) {
   static_cast<void>(u);
-  return Eigen::Vector<double, 3>{x(2), x(3), x(4)};
+  return frc::Vectord<3>{x(2), x(3), x(4)};
 }
 
-Eigen::Vector<double, 5> GlobalMeasurementModel(
-    const Eigen::Vector<double, 5>& x, const Eigen::Vector<double, 2>& u) {
+frc::Vectord<5> GlobalMeasurementModel(const frc::Vectord<5>& x,
+                                       const frc::Vectord<2>& u) {
   static_cast<void>(u);
-  return Eigen::Vector<double, 5>{x(0), x(1), x(2), x(3), x(4)};
+  return frc::Vectord<5>{x(0), x(1), x(2), x(3), x(4)};
 }
 }  // namespace
 
@@ -71,7 +70,7 @@
                                               {0.5, 0.5, 10.0, 1.0, 1.0},
                                               {0.0001, 0.01, 0.01},
                                               dt};
-  Eigen::Vector<double, 2> u{12.0, 12.0};
+  frc::Vectord<2> u{12.0, 12.0};
   observer.Predict(u, dt);
 
   auto localY = LocalMeasurementModel(observer.Xhat(), u);
@@ -98,14 +97,13 @@
   auto trajectory = frc::TrajectoryGenerator::GenerateTrajectory(
       waypoints, {8.8_mps, 0.1_mps_sq});
 
-  Eigen::Vector<double, 5> r = Eigen::Vector<double, 5>::Zero();
-  Eigen::Vector<double, 2> u = Eigen::Vector<double, 2>::Zero();
+  frc::Vectord<5> r = frc::Vectord<5>::Zero();
+  frc::Vectord<2> u = frc::Vectord<2>::Zero();
 
-  auto B = frc::NumericalJacobianU<5, 5, 2>(Dynamics,
-                                            Eigen::Vector<double, 5>::Zero(),
-                                            Eigen::Vector<double, 2>::Zero());
+  auto B = frc::NumericalJacobianU<5, 5, 2>(Dynamics, frc::Vectord<5>::Zero(),
+                                            frc::Vectord<2>::Zero());
 
-  observer.SetXhat(Eigen::Vector<double, 5>{
+  observer.SetXhat(frc::Vectord<5>{
       trajectory.InitialPose().Translation().X().value(),
       trajectory.InitialPose().Translation().Y().value(),
       trajectory.InitialPose().Rotation().Radians().value(), 0.0, 0.0});
@@ -118,17 +116,15 @@
     units::meters_per_second_t vr =
         ref.velocity * (1 + (ref.curvature * rb).value());
 
-    Eigen::Vector<double, 5> nextR{
+    frc::Vectord<5> nextR{
         ref.pose.Translation().X().value(), ref.pose.Translation().Y().value(),
         ref.pose.Rotation().Radians().value(), vl.value(), vr.value()};
 
-    auto localY =
-        LocalMeasurementModel(nextR, Eigen::Vector<double, 2>::Zero());
+    auto localY = LocalMeasurementModel(nextR, frc::Vectord<2>::Zero());
     observer.Correct(u, localY + frc::MakeWhiteNoiseVector(0.0001, 0.5, 0.5));
 
-    Eigen::Vector<double, 5> rdot = (nextR - r) / dt.value();
-    u = B.householderQr().solve(rdot -
-                                Dynamics(r, Eigen::Vector<double, 2>::Zero()));
+    frc::Vectord<5> rdot = (nextR - r) / dt.value();
+    u = B.householderQr().solve(rdot - Dynamics(r, frc::Vectord<2>::Zero()));
 
     observer.Predict(u, dt);
 
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/estimator/MecanumDrivePoseEstimatorTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/estimator/MecanumDrivePoseEstimatorTest.cpp
index 881d4e8..13dc5aa 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/estimator/MecanumDrivePoseEstimatorTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/estimator/MecanumDrivePoseEstimatorTest.cpp
@@ -4,74 +4,95 @@
 
 #include <limits>
 #include <random>
+#include <tuple>
 
 #include "frc/estimator/MecanumDrivePoseEstimator.h"
 #include "frc/geometry/Pose2d.h"
 #include "frc/kinematics/MecanumDriveKinematics.h"
-#include "frc/kinematics/MecanumDriveOdometry.h"
 #include "frc/trajectory/TrajectoryGenerator.h"
 #include "gtest/gtest.h"
 
-TEST(MecanumDrivePoseEstimatorTest, Accuracy) {
-  frc::MecanumDriveKinematics kinematics{
-      frc::Translation2d{1_m, 1_m}, frc::Translation2d{1_m, -1_m},
-      frc::Translation2d{-1_m, -1_m}, frc::Translation2d{-1_m, 1_m}};
+void testFollowTrajectory(
+    const frc::MecanumDriveKinematics& kinematics,
+    frc::MecanumDrivePoseEstimator& estimator,
+    const frc::Trajectory& trajectory,
+    std::function<frc::ChassisSpeeds(frc::Trajectory::State&)>
+        chassisSpeedsGenerator,
+    std::function<frc::Pose2d(frc::Trajectory::State&)>
+        visionMeasurementGenerator,
+    const frc::Pose2d& startingPose, const frc::Pose2d& endingPose,
+    const units::second_t dt, const units::second_t kVisionUpdateRate,
+    const units::second_t kVisionUpdateDelay, const bool checkError,
+    const bool debug) {
+  frc::MecanumDriveWheelPositions wheelPositions{};
 
-  frc::MecanumDrivePoseEstimator estimator{
-      frc::Rotation2d(), frc::Pose2d(), kinematics,
-      {0.1, 0.1, 0.1},   {0.05},        {0.1, 0.1, 0.1}};
-
-  frc::MecanumDriveOdometry odometry{kinematics, frc::Rotation2d()};
-
-  frc::Trajectory trajectory = frc::TrajectoryGenerator::GenerateTrajectory(
-      std::vector{frc::Pose2d(0_m, 0_m, frc::Rotation2d(45_deg)),
-                  frc::Pose2d(3_m, 0_m, frc::Rotation2d(-90_deg)),
-                  frc::Pose2d(0_m, 0_m, frc::Rotation2d(135_deg)),
-                  frc::Pose2d(-3_m, 0_m, frc::Rotation2d(-90_deg)),
-                  frc::Pose2d(0_m, 0_m, frc::Rotation2d(45_deg))},
-      frc::TrajectoryConfig(5.0_mps, 2.0_mps_sq));
+  estimator.ResetPosition(frc::Rotation2d{}, wheelPositions, startingPose);
 
   std::default_random_engine generator;
   std::normal_distribution<double> distribution(0.0, 1.0);
 
-  units::second_t dt = 0.02_s;
   units::second_t t = 0_s;
 
-  units::second_t kVisionUpdateRate = 0.1_s;
-  frc::Pose2d lastVisionPose;
-  units::second_t lastVisionUpdateTime{-std::numeric_limits<double>::max()};
-
-  std::vector<frc::Pose2d> visionPoses;
+  std::vector<std::pair<units::second_t, frc::Pose2d>> visionPoses;
+  std::vector<std::tuple<units::second_t, units::second_t, frc::Pose2d>>
+      visionLog;
 
   double maxError = -std::numeric_limits<double>::max();
   double errorSum = 0;
 
+  if (debug) {
+    fmt::print("time, est_x, est_y, est_theta, true_x, true_y, true_theta\n");
+  }
+
   while (t < trajectory.TotalTime()) {
     frc::Trajectory::State groundTruthState = trajectory.Sample(t);
 
-    if (lastVisionUpdateTime + kVisionUpdateRate < t) {
-      if (lastVisionPose != frc::Pose2d()) {
-        estimator.AddVisionMeasurement(lastVisionPose, lastVisionUpdateTime);
-      }
-      lastVisionPose =
-          groundTruthState.pose +
-          frc::Transform2d(
-              frc::Translation2d(distribution(generator) * 0.1_m,
-                                 distribution(generator) * 0.1_m),
-              frc::Rotation2d(distribution(generator) * 0.1 * 1_rad));
-      visionPoses.push_back(lastVisionPose);
-      lastVisionUpdateTime = t;
+    // We are due for a new vision measurement if it's been `visionUpdateRate`
+    // seconds since the last vision measurement
+    if (visionPoses.empty() ||
+        visionPoses.back().first + kVisionUpdateRate < t) {
+      auto visionPose =
+          visionMeasurementGenerator(groundTruthState) +
+          frc::Transform2d{frc::Translation2d{distribution(generator) * 0.1_m,
+                                              distribution(generator) * 0.1_m},
+                           frc::Rotation2d{distribution(generator) * 0.05_rad}};
+      visionPoses.push_back({t, visionPose});
     }
 
-    auto wheelSpeeds = kinematics.ToWheelSpeeds(
-        {groundTruthState.velocity, 0_mps,
-         groundTruthState.velocity * groundTruthState.curvature});
+    // We should apply the oldest vision measurement if it has been
+    // `visionUpdateDelay` seconds since it was measured
+    if (!visionPoses.empty() &&
+        visionPoses.front().first + kVisionUpdateDelay < t) {
+      auto visionEntry = visionPoses.front();
+      estimator.AddVisionMeasurement(visionEntry.second, visionEntry.first);
+      visionPoses.erase(visionPoses.begin());
+      visionLog.push_back({t, visionEntry.first, visionEntry.second});
+    }
+
+    auto chassisSpeeds = chassisSpeedsGenerator(groundTruthState);
+
+    auto wheelSpeeds = kinematics.ToWheelSpeeds(chassisSpeeds);
+
+    wheelPositions.frontLeft += wheelSpeeds.frontLeft * dt;
+    wheelPositions.frontRight += wheelSpeeds.frontRight * dt;
+    wheelPositions.rearLeft += wheelSpeeds.rearLeft * dt;
+    wheelPositions.rearRight += wheelSpeeds.rearRight * dt;
 
     auto xhat = estimator.UpdateWithTime(
         t,
         groundTruthState.pose.Rotation() +
-            frc::Rotation2d(distribution(generator) * 0.05_rad),
-        wheelSpeeds);
+            frc::Rotation2d{distribution(generator) * 0.05_rad} -
+            trajectory.InitialPose().Rotation(),
+        wheelPositions);
+
+    if (debug) {
+      fmt::print("{}, {}, {}, {}, {}, {}, {}\n", t.value(), xhat.X().value(),
+                 xhat.Y().value(), xhat.Rotation().Radians().value(),
+                 groundTruthState.pose.X().value(),
+                 groundTruthState.pose.Y().value(),
+                 groundTruthState.pose.Rotation().Radians().value());
+    }
+
     double error = groundTruthState.pose.Translation()
                        .Distance(xhat.Translation())
                        .value();
@@ -84,6 +105,104 @@
     t += dt;
   }
 
-  EXPECT_LT(errorSum / (trajectory.TotalTime().value() / dt.value()), 0.2);
-  EXPECT_LT(maxError, 0.4);
+  if (debug) {
+    fmt::print("apply_time, measured_time, vision_x, vision_y, vision_theta\n");
+
+    units::second_t apply_time;
+    units::second_t measure_time;
+    frc::Pose2d vision_pose;
+    for (auto record : visionLog) {
+      std::tie(apply_time, measure_time, vision_pose) = record;
+      fmt::print("{}, {}, {}, {}, {}\n", apply_time.value(),
+                 measure_time.value(), vision_pose.X().value(),
+                 vision_pose.Y().value(),
+                 vision_pose.Rotation().Radians().value());
+    }
+  }
+
+  EXPECT_NEAR(endingPose.X().value(),
+              estimator.GetEstimatedPosition().X().value(), 0.08);
+  EXPECT_NEAR(endingPose.Y().value(),
+              estimator.GetEstimatedPosition().Y().value(), 0.08);
+  EXPECT_NEAR(endingPose.Rotation().Radians().value(),
+              estimator.GetEstimatedPosition().Rotation().Radians().value(),
+              0.15);
+
+  if (checkError) {
+    EXPECT_LT(errorSum / (trajectory.TotalTime() / dt), 0.051);
+    EXPECT_LT(maxError, 0.2);
+  }
+}
+
+TEST(MecanumDrivePoseEstimatorTest, AccuracyFacingTrajectory) {
+  frc::MecanumDriveKinematics kinematics{
+      frc::Translation2d{1_m, 1_m}, frc::Translation2d{1_m, -1_m},
+      frc::Translation2d{-1_m, -1_m}, frc::Translation2d{-1_m, 1_m}};
+
+  frc::MecanumDriveWheelPositions wheelPositions;
+
+  frc::MecanumDrivePoseEstimator estimator{kinematics,      frc::Rotation2d{},
+                                           wheelPositions,  frc::Pose2d{},
+                                           {0.1, 0.1, 0.1}, {0.45, 0.45, 0.45}};
+
+  frc::Trajectory trajectory = frc::TrajectoryGenerator::GenerateTrajectory(
+      std::vector{frc::Pose2d{0_m, 0_m, 45_deg}, frc::Pose2d{3_m, 0_m, -90_deg},
+                  frc::Pose2d{0_m, 0_m, 135_deg},
+                  frc::Pose2d{-3_m, 0_m, -90_deg},
+                  frc::Pose2d{0_m, 0_m, 45_deg}},
+      frc::TrajectoryConfig(2.0_mps, 2.0_mps_sq));
+
+  testFollowTrajectory(
+      kinematics, estimator, trajectory,
+      [&](frc::Trajectory::State& state) {
+        return frc::ChassisSpeeds{state.velocity, 0_mps,
+                                  state.velocity * state.curvature};
+      },
+      [&](frc::Trajectory::State& state) { return state.pose; },
+      trajectory.InitialPose(), {0_m, 0_m, frc::Rotation2d{45_deg}}, 0.02_s,
+      0.1_s, 0.25_s, true, false);
+}
+
+TEST(MecanumDrivePoseEstimatorTest, BadInitialPose) {
+  frc::MecanumDriveKinematics kinematics{
+      frc::Translation2d{1_m, 1_m}, frc::Translation2d{1_m, -1_m},
+      frc::Translation2d{-1_m, -1_m}, frc::Translation2d{-1_m, 1_m}};
+
+  frc::MecanumDriveWheelPositions wheelPositions;
+
+  frc::MecanumDrivePoseEstimator estimator{kinematics,      frc::Rotation2d{},
+                                           wheelPositions,  frc::Pose2d{},
+                                           {0.1, 0.1, 0.1}, {0.45, 0.45, 0.1}};
+
+  frc::Trajectory trajectory = frc::TrajectoryGenerator::GenerateTrajectory(
+      std::vector{frc::Pose2d{0_m, 0_m, 45_deg}, frc::Pose2d{3_m, 0_m, -90_deg},
+                  frc::Pose2d{0_m, 0_m, 135_deg},
+                  frc::Pose2d{-3_m, 0_m, -90_deg},
+                  frc::Pose2d{0_m, 0_m, 45_deg}},
+      frc::TrajectoryConfig(2.0_mps, 2.0_mps_sq));
+
+  for (units::degree_t offset_direction_degs = 0_deg;
+       offset_direction_degs < 360_deg; offset_direction_degs += 45_deg) {
+    for (units::degree_t offset_heading_degs = 0_deg;
+         offset_heading_degs < 360_deg; offset_heading_degs += 45_deg) {
+      auto pose_offset = frc::Rotation2d{offset_direction_degs};
+      auto heading_offset = frc::Rotation2d{offset_heading_degs};
+
+      auto initial_pose =
+          trajectory.InitialPose() +
+          frc::Transform2d{frc::Translation2d{pose_offset.Cos() * 1_m,
+                                              pose_offset.Sin() * 1_m},
+                           heading_offset};
+
+      testFollowTrajectory(
+          kinematics, estimator, trajectory,
+          [&](frc::Trajectory::State& state) {
+            return frc::ChassisSpeeds{state.velocity, 0_mps,
+                                      state.velocity * state.curvature};
+          },
+          [&](frc::Trajectory::State& state) { return state.pose; },
+          initial_pose, {0_m, 0_m, frc::Rotation2d{45_deg}}, 0.02_s, 0.1_s,
+          0.25_s, false, false);
+    }
+  }
 }
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/estimator/MerweScaledSigmaPointsTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/estimator/MerweScaledSigmaPointsTest.cpp
index c012435..19a734b 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/estimator/MerweScaledSigmaPointsTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/estimator/MerweScaledSigmaPointsTest.cpp
@@ -10,26 +10,23 @@
 namespace {
 TEST(MerweScaledSigmaPointsTest, ZeroMean) {
   frc::MerweScaledSigmaPoints<2> sigmaPoints;
-  auto points = sigmaPoints.SigmaPoints(
-      Eigen::Vector<double, 2>{0.0, 0.0},
-      Eigen::Matrix<double, 2, 2>{{1.0, 0.0}, {0.0, 1.0}});
+  auto points = sigmaPoints.SquareRootSigmaPoints(
+      frc::Vectord<2>{0.0, 0.0}, frc::Matrixd<2, 2>{{1.0, 0.0}, {0.0, 1.0}});
 
   EXPECT_TRUE(
-      (points -
-       Eigen::Matrix<double, 2, 5>{{0.0, 0.00173205, 0.0, -0.00173205, 0.0},
+      (points - frc::Matrixd<2, 5>{{0.0, 0.00173205, 0.0, -0.00173205, 0.0},
                                    {0.0, 0.0, 0.00173205, 0.0, -0.00173205}})
           .norm() < 1e-3);
 }
 
 TEST(MerweScaledSigmaPointsTest, NonzeroMean) {
   frc::MerweScaledSigmaPoints<2> sigmaPoints;
-  auto points = sigmaPoints.SigmaPoints(
-      Eigen::Vector<double, 2>{1.0, 2.0},
-      Eigen::Matrix<double, 2, 2>{{1.0, 0.0}, {0.0, 10.0}});
+  auto points = sigmaPoints.SquareRootSigmaPoints(
+      frc::Vectord<2>{1.0, 2.0},
+      frc::Matrixd<2, 2>{{1.0, 0.0}, {0.0, std::sqrt(10.0)}});
 
   EXPECT_TRUE(
-      (points -
-       Eigen::Matrix<double, 2, 5>{{1.0, 1.00173205, 1.0, 0.998268, 1.0},
+      (points - frc::Matrixd<2, 5>{{1.0, 1.00173205, 1.0, 0.998268, 1.0},
                                    {2.0, 2.0, 2.00548, 2.0, 1.99452}})
           .norm() < 1e-3);
 }
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/estimator/SwerveDrivePoseEstimatorTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/estimator/SwerveDrivePoseEstimatorTest.cpp
index ee01f6f..554ca59 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/estimator/SwerveDrivePoseEstimatorTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/estimator/SwerveDrivePoseEstimatorTest.cpp
@@ -3,75 +3,99 @@
 // the WPILib BSD license file in the root directory of this project.
 
 #include <limits>
+#include <numbers>
 #include <random>
+#include <tuple>
+
+#include <fmt/format.h>
 
 #include "frc/estimator/SwerveDrivePoseEstimator.h"
 #include "frc/geometry/Pose2d.h"
 #include "frc/kinematics/SwerveDriveKinematics.h"
-#include "frc/kinematics/SwerveDriveOdometry.h"
 #include "frc/trajectory/TrajectoryGenerator.h"
 #include "gtest/gtest.h"
 
-TEST(SwerveDrivePoseEstimatorTest, Accuracy) {
-  frc::SwerveDriveKinematics<4> kinematics{
-      frc::Translation2d{1_m, 1_m}, frc::Translation2d{1_m, -1_m},
-      frc::Translation2d{-1_m, -1_m}, frc::Translation2d{-1_m, 1_m}};
+void testFollowTrajectory(
+    const frc::SwerveDriveKinematics<4>& kinematics,
+    frc::SwerveDrivePoseEstimator<4>& estimator,
+    const frc::Trajectory& trajectory,
+    std::function<frc::ChassisSpeeds(frc::Trajectory::State&)>
+        chassisSpeedsGenerator,
+    std::function<frc::Pose2d(frc::Trajectory::State&)>
+        visionMeasurementGenerator,
+    const frc::Pose2d& startingPose, const frc::Pose2d& endingPose,
+    const units::second_t dt, const units::second_t kVisionUpdateRate,
+    const units::second_t kVisionUpdateDelay, const bool checkError,
+    const bool debug) {
+  wpi::array<frc::SwerveModulePosition, 4> positions{wpi::empty_array};
 
-  frc::SwerveDrivePoseEstimator<4> estimator{
-      frc::Rotation2d(), frc::Pose2d(), kinematics,
-      {0.1, 0.1, 0.1},   {0.05},        {0.1, 0.1, 0.1}};
-
-  frc::SwerveDriveOdometry<4> odometry{kinematics, frc::Rotation2d()};
-
-  frc::Trajectory trajectory = frc::TrajectoryGenerator::GenerateTrajectory(
-      std::vector{frc::Pose2d(0_m, 0_m, frc::Rotation2d(45_deg)),
-                  frc::Pose2d(3_m, 0_m, frc::Rotation2d(-90_deg)),
-                  frc::Pose2d(0_m, 0_m, frc::Rotation2d(135_deg)),
-                  frc::Pose2d(-3_m, 0_m, frc::Rotation2d(-90_deg)),
-                  frc::Pose2d(0_m, 0_m, frc::Rotation2d(45_deg))},
-      frc::TrajectoryConfig(5.0_mps, 2.0_mps_sq));
+  estimator.ResetPosition(frc::Rotation2d{}, positions, startingPose);
 
   std::default_random_engine generator;
   std::normal_distribution<double> distribution(0.0, 1.0);
 
-  units::second_t dt = 0.02_s;
   units::second_t t = 0_s;
 
-  units::second_t kVisionUpdateRate = 0.1_s;
-  frc::Pose2d lastVisionPose;
-  units::second_t lastVisionUpdateTime{-std::numeric_limits<double>::max()};
-
-  std::vector<frc::Pose2d> visionPoses;
+  std::vector<std::pair<units::second_t, frc::Pose2d>> visionPoses;
+  std::vector<std::tuple<units::second_t, units::second_t, frc::Pose2d>>
+      visionLog;
 
   double maxError = -std::numeric_limits<double>::max();
   double errorSum = 0;
 
+  if (debug) {
+    fmt::print("time, est_x, est_y, est_theta, true_x, true_y, true_theta\n");
+  }
+
   while (t < trajectory.TotalTime()) {
     frc::Trajectory::State groundTruthState = trajectory.Sample(t);
 
-    if (lastVisionUpdateTime + kVisionUpdateRate < t) {
-      if (lastVisionPose != frc::Pose2d()) {
-        estimator.AddVisionMeasurement(lastVisionPose, lastVisionUpdateTime);
-      }
-      lastVisionPose =
-          groundTruthState.pose +
-          frc::Transform2d(
-              frc::Translation2d(distribution(generator) * 0.1_m,
-                                 distribution(generator) * 0.1_m),
-              frc::Rotation2d(distribution(generator) * 0.1 * 1_rad));
-      visionPoses.push_back(lastVisionPose);
-      lastVisionUpdateTime = t;
+    // We are due for a new vision measurement if it's been `visionUpdateRate`
+    // seconds since the last vision measurement
+    if (visionPoses.empty() ||
+        visionPoses.back().first + kVisionUpdateRate < t) {
+      auto visionPose =
+          visionMeasurementGenerator(groundTruthState) +
+          frc::Transform2d{frc::Translation2d{distribution(generator) * 0.1_m,
+                                              distribution(generator) * 0.1_m},
+                           frc::Rotation2d{distribution(generator) * 0.05_rad}};
+      visionPoses.push_back({t, visionPose});
     }
 
-    auto moduleStates = kinematics.ToSwerveModuleStates(
-        {groundTruthState.velocity, 0_mps,
-         groundTruthState.velocity * groundTruthState.curvature});
+    // We should apply the oldest vision measurement if it has been
+    // `visionUpdateDelay` seconds since it was measured
+    if (!visionPoses.empty() &&
+        visionPoses.front().first + kVisionUpdateDelay < t) {
+      auto visionEntry = visionPoses.front();
+      estimator.AddVisionMeasurement(visionEntry.second, visionEntry.first);
+      visionPoses.erase(visionPoses.begin());
+      visionLog.push_back({t, visionEntry.first, visionEntry.second});
+    }
+
+    auto chassisSpeeds = chassisSpeedsGenerator(groundTruthState);
+
+    auto moduleStates = kinematics.ToSwerveModuleStates(chassisSpeeds);
+
+    for (size_t i = 0; i < 4; i++) {
+      positions[i].distance += moduleStates[i].speed * dt;
+      positions[i].angle = moduleStates[i].angle;
+    }
 
     auto xhat = estimator.UpdateWithTime(
         t,
         groundTruthState.pose.Rotation() +
-            frc::Rotation2d(distribution(generator) * 0.05_rad),
-        moduleStates[0], moduleStates[1], moduleStates[2], moduleStates[3]);
+            frc::Rotation2d{distribution(generator) * 0.05_rad} -
+            trajectory.InitialPose().Rotation(),
+        positions);
+
+    if (debug) {
+      fmt::print("{}, {}, {}, {}, {}, {}, {}\n", t.value(), xhat.X().value(),
+                 xhat.Y().value(), xhat.Rotation().Radians().value(),
+                 groundTruthState.pose.X().value(),
+                 groundTruthState.pose.Y().value(),
+                 groundTruthState.pose.Rotation().Radians().value());
+    }
+
     double error = groundTruthState.pose.Translation()
                        .Distance(xhat.Translation())
                        .value();
@@ -84,6 +108,110 @@
     t += dt;
   }
 
-  EXPECT_LT(errorSum / (trajectory.TotalTime().value() / dt.value()), 0.2);
-  EXPECT_LT(maxError, 0.4);
+  if (debug) {
+    fmt::print("apply_time, measured_time, vision_x, vision_y, vision_theta\n");
+
+    units::second_t apply_time;
+    units::second_t measure_time;
+    frc::Pose2d vision_pose;
+    for (auto record : visionLog) {
+      std::tie(apply_time, measure_time, vision_pose) = record;
+      fmt::print("{}, {}, {}, {}, {}\n", apply_time.value(),
+                 measure_time.value(), vision_pose.X().value(),
+                 vision_pose.Y().value(),
+                 vision_pose.Rotation().Radians().value());
+    }
+  }
+
+  EXPECT_NEAR(endingPose.X().value(),
+              estimator.GetEstimatedPosition().X().value(), 0.08);
+  EXPECT_NEAR(endingPose.Y().value(),
+              estimator.GetEstimatedPosition().Y().value(), 0.08);
+  EXPECT_NEAR(endingPose.Rotation().Radians().value(),
+              estimator.GetEstimatedPosition().Rotation().Radians().value(),
+              0.15);
+
+  if (checkError) {
+    EXPECT_LT(errorSum / (trajectory.TotalTime() / dt), 0.058);
+    EXPECT_LT(maxError, 0.2);
+  }
+}
+
+TEST(SwerveDrivePoseEstimatorTest, AccuracyFacingTrajectory) {
+  frc::SwerveDriveKinematics<4> kinematics{
+      frc::Translation2d{1_m, 1_m}, frc::Translation2d{1_m, -1_m},
+      frc::Translation2d{-1_m, -1_m}, frc::Translation2d{-1_m, 1_m}};
+
+  frc::SwerveModulePosition fl;
+  frc::SwerveModulePosition fr;
+  frc::SwerveModulePosition bl;
+  frc::SwerveModulePosition br;
+
+  frc::SwerveDrivePoseEstimator<4> estimator{
+      kinematics,    frc::Rotation2d{}, {fl, fr, bl, br},
+      frc::Pose2d{}, {0.1, 0.1, 0.1},   {0.45, 0.45, 0.45}};
+
+  frc::Trajectory trajectory = frc::TrajectoryGenerator::GenerateTrajectory(
+      std::vector{frc::Pose2d{0_m, 0_m, 45_deg}, frc::Pose2d{3_m, 0_m, -90_deg},
+                  frc::Pose2d{0_m, 0_m, 135_deg},
+                  frc::Pose2d{-3_m, 0_m, -90_deg},
+                  frc::Pose2d{0_m, 0_m, 45_deg}},
+      frc::TrajectoryConfig(2_mps, 2.0_mps_sq));
+
+  testFollowTrajectory(
+      kinematics, estimator, trajectory,
+      [&](frc::Trajectory::State& state) {
+        return frc::ChassisSpeeds{state.velocity, 0_mps,
+                                  state.velocity * state.curvature};
+      },
+      [&](frc::Trajectory::State& state) { return state.pose; },
+      {0_m, 0_m, frc::Rotation2d{45_deg}}, {0_m, 0_m, frc::Rotation2d{45_deg}},
+      0.02_s, 0.1_s, 0.25_s, true, false);
+}
+
+TEST(SwerveDrivePoseEstimatorTest, BadInitialPose) {
+  frc::SwerveDriveKinematics<4> kinematics{
+      frc::Translation2d{1_m, 1_m}, frc::Translation2d{1_m, -1_m},
+      frc::Translation2d{-1_m, -1_m}, frc::Translation2d{-1_m, 1_m}};
+
+  frc::SwerveModulePosition fl;
+  frc::SwerveModulePosition fr;
+  frc::SwerveModulePosition bl;
+  frc::SwerveModulePosition br;
+
+  frc::SwerveDrivePoseEstimator<4> estimator{
+      kinematics,    frc::Rotation2d{}, {fl, fr, bl, br},
+      frc::Pose2d{}, {0.1, 0.1, 0.1},   {0.9, 0.9, 0.9}};
+
+  frc::Trajectory trajectory = frc::TrajectoryGenerator::GenerateTrajectory(
+      std::vector{frc::Pose2d{0_m, 0_m, 45_deg}, frc::Pose2d{3_m, 0_m, -90_deg},
+                  frc::Pose2d{0_m, 0_m, 135_deg},
+                  frc::Pose2d{-3_m, 0_m, -90_deg},
+                  frc::Pose2d{0_m, 0_m, 45_deg}},
+      frc::TrajectoryConfig(2_mps, 2.0_mps_sq));
+
+  for (units::degree_t offset_direction_degs = 0_deg;
+       offset_direction_degs < 360_deg; offset_direction_degs += 45_deg) {
+    for (units::degree_t offset_heading_degs = 0_deg;
+         offset_heading_degs < 360_deg; offset_heading_degs += 45_deg) {
+      auto pose_offset = frc::Rotation2d{offset_direction_degs};
+      auto heading_offset = frc::Rotation2d{offset_heading_degs};
+
+      auto initial_pose =
+          trajectory.InitialPose() +
+          frc::Transform2d{frc::Translation2d{pose_offset.Cos() * 1_m,
+                                              pose_offset.Sin() * 1_m},
+                           heading_offset};
+
+      testFollowTrajectory(
+          kinematics, estimator, trajectory,
+          [&](frc::Trajectory::State& state) {
+            return frc::ChassisSpeeds{state.velocity, 0_mps,
+                                      state.velocity * state.curvature};
+          },
+          [&](frc::Trajectory::State& state) { return state.pose; },
+          initial_pose, {0_m, 0_m, frc::Rotation2d{45_deg}}, 0.02_s, 0.1_s,
+          0.25_s, false, false);
+    }
+  }
 }
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/estimator/UnscentedKalmanFilterTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/estimator/UnscentedKalmanFilterTest.cpp
index 9665442..68f9c40 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/estimator/UnscentedKalmanFilterTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/estimator/UnscentedKalmanFilterTest.cpp
@@ -7,8 +7,8 @@
 #include <array>
 #include <cmath>
 
-#include "Eigen/Core"
 #include "Eigen/QR"
+#include "frc/EigenCore.h"
 #include "frc/StateSpaceUtil.h"
 #include "frc/estimator/AngleStatistics.h"
 #include "frc/estimator/UnscentedKalmanFilter.h"
@@ -20,11 +20,10 @@
 
 namespace {
 
-Eigen::Vector<double, 5> Dynamics(const Eigen::Vector<double, 5>& x,
-                                  const Eigen::Vector<double, 2>& u) {
+frc::Vectord<5> Dynamics(const frc::Vectord<5>& x, const frc::Vectord<2>& u) {
   auto motors = frc::DCMotor::CIM(2);
 
-  // constexpr double Glow = 15.32;       // Low gear ratio
+  // constexpr double Glow = 15.32;    // Low gear ratio
   constexpr double Ghigh = 7.08;       // High gear ratio
   constexpr auto rb = 0.8382_m / 2.0;  // Robot radius
   constexpr auto r = 0.0746125_m;      // Wheel radius
@@ -43,7 +42,7 @@
   units::volt_t Vr{u(1)};
 
   auto v = 0.5 * (vl + vr);
-  return Eigen::Vector<double, 5>{
+  return frc::Vectord<5>{
       v.value() * std::cos(x(2)), v.value() * std::sin(x(2)),
       ((vr - vl) / (2.0 * rb)).value(),
       k1.value() * ((C1 * vl).value() + (C2 * Vl).value()) +
@@ -52,16 +51,16 @@
           k1.value() * ((C1 * vr).value() + (C2 * Vr).value())};
 }
 
-Eigen::Vector<double, 3> LocalMeasurementModel(
-    const Eigen::Vector<double, 5>& x, const Eigen::Vector<double, 2>& u) {
+frc::Vectord<3> LocalMeasurementModel(const frc::Vectord<5>& x,
+                                      const frc::Vectord<2>& u) {
   static_cast<void>(u);
-  return Eigen::Vector<double, 3>{x(2), x(3), x(4)};
+  return frc::Vectord<3>{x(2), x(3), x(4)};
 }
 
-Eigen::Vector<double, 5> GlobalMeasurementModel(
-    const Eigen::Vector<double, 5>& x, const Eigen::Vector<double, 2>& u) {
+frc::Vectord<5> GlobalMeasurementModel(const frc::Vectord<5>& x,
+                                       const frc::Vectord<2>& u) {
   static_cast<void>(u);
-  return Eigen::Vector<double, 5>{x(0), x(1), x(2), x(3), x(4)};
+  return frc::Vectord<5>{x(0), x(1), x(2), x(3), x(4)};
 }
 }  // namespace
 
@@ -72,8 +71,13 @@
                                                LocalMeasurementModel,
                                                {0.5, 0.5, 10.0, 1.0, 1.0},
                                                {0.0001, 0.01, 0.01},
+                                               frc::AngleMean<5, 5>(2),
+                                               frc::AngleMean<3, 5>(0),
+                                               frc::AngleResidual<5>(2),
+                                               frc::AngleResidual<3>(0),
+                                               frc::AngleAdd<5>(2),
                                                dt};
-  Eigen::Vector<double, 2> u{12.0, 12.0};
+  frc::Vectord<2> u{12.0, 12.0};
   observer.Predict(u, dt);
 
   auto localY = LocalMeasurementModel(observer.Xhat(), u);
@@ -94,6 +98,11 @@
                                                LocalMeasurementModel,
                                                {0.5, 0.5, 10.0, 1.0, 1.0},
                                                {0.0001, 0.5, 0.5},
+                                               frc::AngleMean<5, 5>(2),
+                                               frc::AngleMean<3, 5>(0),
+                                               frc::AngleResidual<5>(2),
+                                               frc::AngleResidual<3>(0),
+                                               frc::AngleAdd<5>(2),
                                                dt};
 
   auto waypoints =
@@ -102,14 +111,13 @@
   auto trajectory = frc::TrajectoryGenerator::GenerateTrajectory(
       waypoints, {8.8_mps, 0.1_mps_sq});
 
-  Eigen::Vector<double, 5> r = Eigen::Vector<double, 5>::Zero();
-  Eigen::Vector<double, 2> u = Eigen::Vector<double, 2>::Zero();
+  frc::Vectord<5> r = frc::Vectord<5>::Zero();
+  frc::Vectord<2> u = frc::Vectord<2>::Zero();
 
-  auto B = frc::NumericalJacobianU<5, 5, 2>(Dynamics,
-                                            Eigen::Vector<double, 5>::Zero(),
-                                            Eigen::Vector<double, 2>::Zero());
+  auto B = frc::NumericalJacobianU<5, 5, 2>(Dynamics, frc::Vectord<5>::Zero(),
+                                            frc::Vectord<2>::Zero());
 
-  observer.SetXhat(Eigen::Vector<double, 5>{
+  observer.SetXhat(frc::Vectord<5>{
       trajectory.InitialPose().Translation().X().value(),
       trajectory.InitialPose().Translation().Y().value(),
       trajectory.InitialPose().Rotation().Radians().value(), 0.0, 0.0});
@@ -124,17 +132,15 @@
     units::meters_per_second_t vr =
         ref.velocity * (1 + (ref.curvature * rb).value());
 
-    Eigen::Vector<double, 5> nextR{
+    frc::Vectord<5> nextR{
         ref.pose.Translation().X().value(), ref.pose.Translation().Y().value(),
         ref.pose.Rotation().Radians().value(), vl.value(), vr.value()};
 
-    auto localY =
-        LocalMeasurementModel(trueXhat, Eigen::Vector<double, 2>::Zero());
+    auto localY = LocalMeasurementModel(trueXhat, frc::Vectord<2>::Zero());
     observer.Correct(u, localY + frc::MakeWhiteNoiseVector(0.0001, 0.5, 0.5));
 
-    Eigen::Vector<double, 5> rdot = (nextR - r) / dt.value();
-    u = B.householderQr().solve(rdot -
-                                Dynamics(r, Eigen::Vector<double, 2>::Zero()));
+    frc::Vectord<5> rdot = (nextR - r) / dt.value();
+    u = B.householderQr().solve(rdot - Dynamics(r, frc::Vectord<2>::Zero()));
 
     observer.Predict(u, dt);
 
@@ -154,12 +160,28 @@
   );
 
   auto finalPosition = trajectory.Sample(trajectory.TotalTime());
-  ASSERT_NEAR(finalPosition.pose.Translation().X().value(), observer.Xhat(0),
-              1.0);
-  ASSERT_NEAR(finalPosition.pose.Translation().Y().value(), observer.Xhat(1),
-              1.0);
-  ASSERT_NEAR(finalPosition.pose.Rotation().Radians().value(), observer.Xhat(2),
-              1.0);
-  ASSERT_NEAR(0.0, observer.Xhat(3), 1.0);
-  ASSERT_NEAR(0.0, observer.Xhat(4), 1.0);
+  EXPECT_NEAR(finalPosition.pose.Translation().X().value(), observer.Xhat(0),
+              0.055);
+  EXPECT_NEAR(finalPosition.pose.Translation().Y().value(), observer.Xhat(1),
+              0.15);
+  EXPECT_NEAR(finalPosition.pose.Rotation().Radians().value(), observer.Xhat(2),
+              0.000005);
+  EXPECT_NEAR(0.0, observer.Xhat(3), 0.1);
+  EXPECT_NEAR(0.0, observer.Xhat(4), 0.1);
+}
+
+TEST(UnscentedKalmanFilterTest, RoundTripP) {
+  constexpr auto dt = 5_ms;
+
+  frc::UnscentedKalmanFilter<2, 2, 2> observer{
+      [](const frc::Vectord<2>& x, const frc::Vectord<2>& u) { return x; },
+      [](const frc::Vectord<2>& x, const frc::Vectord<2>& u) { return x; },
+      {0.0, 0.0},
+      {0.0, 0.0},
+      dt};
+
+  frc::Matrixd<2, 2> P({{2, 1}, {1, 2}});
+  observer.SetP(P);
+
+  ASSERT_TRUE(observer.P().isApprox(P));
 }
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/filter/LinearFilterNoiseTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/filter/LinearFilterNoiseTest.cpp
index 5ccd829..8299a71 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/filter/LinearFilterNoiseTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/filter/LinearFilterNoiseTest.cpp
@@ -5,10 +5,9 @@
 #include "frc/filter/LinearFilter.h"  // NOLINT(build/include_order)
 
 #include <cmath>
+#include <numbers>
 #include <random>
 
-#include <wpi/numbers>
-
 #include "gtest/gtest.h"
 #include "units/time.h"
 
@@ -21,7 +20,7 @@
 enum LinearFilterNoiseTestType { kTestSinglePoleIIR, kTestMovAvg };
 
 static double GetData(double t) {
-  return 100.0 * std::sin(2.0 * wpi::numbers::pi * t);
+  return 100.0 * std::sin(2.0 * std::numbers::pi * t);
 }
 
 class LinearFilterNoiseTest
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/filter/LinearFilterOutputTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/filter/LinearFilterOutputTest.cpp
index 56121fa..152737d 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/filter/LinearFilterOutputTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/filter/LinearFilterOutputTest.cpp
@@ -7,10 +7,10 @@
 #include <cmath>
 #include <functional>
 #include <memory>
+#include <numbers>
 #include <random>
 
 #include <wpi/array.h>
-#include <wpi/numbers>
 
 #include "gtest/gtest.h"
 #include "units/time.h"
@@ -33,8 +33,8 @@
 };
 
 static double GetData(double t) {
-  return 100.0 * std::sin(2.0 * wpi::numbers::pi * t) +
-         20.0 * std::cos(50.0 * wpi::numbers::pi * t);
+  return 100.0 * std::sin(2.0 * std::numbers::pi * t) +
+         20.0 * std::cos(50.0 * std::numbers::pi * t);
 }
 
 static double GetPulseData(double t) {
@@ -207,14 +207,14 @@
         return std::log(x);
       },
       [](double x) {
-        // df/dx = 1 / x
+        // df/dx = 1/x
         return 1.0 / x;
       },
       h, 1.0, 20.0);
 
   AssertCentralResults<2, 5>(
       [](double x) {
-        // f(x) = x^2
+        // f(x) = x²
         return x * x;
       },
       [](double x) {
@@ -240,7 +240,7 @@
         return std::log(x);
       },
       [](double x) {
-        // d²f/dx² = -1 / x²
+        // d²f/dx² = -1/x²
         return -1.0 / (x * x);
       },
       h, 1.0, 20.0);
@@ -280,14 +280,14 @@
         return std::log(x);
       },
       [](double x) {
-        // df/dx = 1 / x
+        // df/dx = 1/x
         return 1.0 / x;
       },
       h, 1.0, 20.0);
 
   AssertBackwardResults<2, 4>(
       [](double x) {
-        // f(x) = x^2
+        // f(x) = x²
         return x * x;
       },
       [](double x) {
@@ -313,7 +313,7 @@
         return std::log(x);
       },
       [](double x) {
-        // d²f/dx² = -1 / x²
+        // d²f/dx² = -1/x²
         return -1.0 / (x * x);
       },
       h, 1.0, 20.0);
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/filter/SlewRateLimiterTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/filter/SlewRateLimiterTest.cpp
index 4896073..5dbe8c8 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/filter/SlewRateLimiterTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/filter/SlewRateLimiterTest.cpp
@@ -38,3 +38,15 @@
 
   EXPECT_EQ(limiter.Calculate(0.5_m), 0.5_m);
 }
+
+TEST_F(SlewRateLimiterTest, SlewRatePositveNegativeLimit) {
+  frc::SlewRateLimiter<units::meters> limiter(1_mps, -0.5_mps);
+
+  now += 1_s;
+
+  EXPECT_EQ(limiter.Calculate(2_m), 1_m);
+
+  now += 1_s;
+
+  EXPECT_EQ(limiter.Calculate(0_m), 0.5_m);
+}
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/CoordinateSystemTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/CoordinateSystemTest.cpp
new file mode 100644
index 0000000..fc44fa5
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/CoordinateSystemTest.cpp
@@ -0,0 +1,163 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "frc/geometry/CoordinateSystem.h"
+#include "frc/geometry/Pose3d.h"
+#include "frc/geometry/Transform3d.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+void CheckPose3dConvert(const Pose3d& poseFrom, const Pose3d& poseTo,
+                        const CoordinateSystem& coordFrom,
+                        const CoordinateSystem& coordTo) {
+  // "from" to "to"
+  EXPECT_EQ(
+      poseTo.Translation(),
+      CoordinateSystem::Convert(poseFrom.Translation(), coordFrom, coordTo));
+  EXPECT_EQ(poseTo.Rotation(),
+            CoordinateSystem::Convert(poseFrom.Rotation(), coordFrom, coordTo));
+  EXPECT_EQ(poseTo, CoordinateSystem::Convert(poseFrom, coordFrom, coordTo));
+
+  // "to" to "from"
+  EXPECT_EQ(
+      poseFrom.Translation(),
+      CoordinateSystem::Convert(poseTo.Translation(), coordTo, coordFrom));
+  EXPECT_EQ(poseFrom.Rotation(),
+            CoordinateSystem::Convert(poseTo.Rotation(), coordTo, coordFrom));
+  EXPECT_EQ(poseFrom, CoordinateSystem::Convert(poseTo, coordTo, coordFrom));
+}
+
+void CheckTransform3dConvert(const Transform3d& transformFrom,
+                             const Transform3d& transformTo,
+                             const CoordinateSystem& coordFrom,
+                             const CoordinateSystem& coordTo) {
+  // "from" to "to"
+  EXPECT_EQ(transformTo.Translation(),
+            CoordinateSystem::Convert(transformFrom.Translation(), coordFrom,
+                                      coordTo));
+  EXPECT_EQ(
+      transformTo.Rotation(),
+      CoordinateSystem::Convert(transformFrom.Rotation(), coordFrom, coordTo));
+  EXPECT_EQ(transformTo,
+            CoordinateSystem::Convert(transformFrom, coordFrom, coordTo));
+
+  // "to" to "from"
+  EXPECT_EQ(
+      transformFrom.Translation(),
+      CoordinateSystem::Convert(transformTo.Translation(), coordTo, coordFrom));
+  EXPECT_EQ(
+      transformFrom.Rotation(),
+      CoordinateSystem::Convert(transformTo.Rotation(), coordTo, coordFrom));
+  EXPECT_EQ(transformFrom,
+            CoordinateSystem::Convert(transformTo, coordTo, coordFrom));
+}
+
+TEST(CoordinateSystemTest, Pose3dEDNtoNWU) {
+  // No rotation from EDN to NWU
+  CheckPose3dConvert(
+      Pose3d{1_m, 2_m, 3_m, Rotation3d{}},
+      Pose3d{3_m, -1_m, -2_m, Rotation3d{-90_deg, 0_deg, -90_deg}},
+      CoordinateSystem::EDN(), CoordinateSystem::NWU());
+
+  // 45° roll from EDN to NWU
+  CheckPose3dConvert(
+      Pose3d{1_m, 2_m, 3_m, Rotation3d{45_deg, 0_deg, 0_deg}},
+      Pose3d{3_m, -1_m, -2_m, Rotation3d{-45_deg, 0_deg, -90_deg}},
+      CoordinateSystem::EDN(), CoordinateSystem::NWU());
+
+  // 45° pitch from EDN to NWU
+  CheckPose3dConvert(
+      Pose3d{1_m, 2_m, 3_m, Rotation3d{0_deg, 45_deg, 0_deg}},
+      Pose3d{3_m, -1_m, -2_m, Rotation3d{-90_deg, 0_deg, -135_deg}},
+      CoordinateSystem::EDN(), CoordinateSystem::NWU());
+
+  // 45° yaw from EDN to NWU
+  CheckPose3dConvert(
+      Pose3d{1_m, 2_m, 3_m, Rotation3d{0_deg, 0_deg, 45_deg}},
+      Pose3d{3_m, -1_m, -2_m, Rotation3d{-90_deg, 45_deg, -90_deg}},
+      CoordinateSystem::EDN(), CoordinateSystem::NWU());
+}
+
+TEST(CoordinateSystemTest, Pose3dEDNtoNED) {
+  // No rotation from EDN to NED
+  CheckPose3dConvert(Pose3d{1_m, 2_m, 3_m, Rotation3d{}},
+                     Pose3d{3_m, 1_m, 2_m, Rotation3d{90_deg, 0_deg, 90_deg}},
+                     CoordinateSystem::EDN(), CoordinateSystem::NED());
+
+  // 45° roll from EDN to NED
+  CheckPose3dConvert(Pose3d{1_m, 2_m, 3_m, Rotation3d{45_deg, 0_deg, 0_deg}},
+                     Pose3d{3_m, 1_m, 2_m, Rotation3d{135_deg, 0_deg, 90_deg}},
+                     CoordinateSystem::EDN(), CoordinateSystem::NED());
+
+  // 45° pitch from EDN to NED
+  CheckPose3dConvert(Pose3d{1_m, 2_m, 3_m, Rotation3d{0_deg, 45_deg, 0_deg}},
+                     Pose3d{3_m, 1_m, 2_m, Rotation3d{90_deg, 0_deg, 135_deg}},
+                     CoordinateSystem::EDN(), CoordinateSystem::NED());
+
+  // 45° yaw from EDN to NED
+  CheckPose3dConvert(Pose3d{1_m, 2_m, 3_m, Rotation3d{0_deg, 0_deg, 45_deg}},
+                     Pose3d{3_m, 1_m, 2_m, Rotation3d{90_deg, -45_deg, 90_deg}},
+                     CoordinateSystem::EDN(), CoordinateSystem::NED());
+}
+
+TEST(CoordinateSystemTest, Transform3dEDNtoNWU) {
+  // No rotation from EDN to NWU
+  CheckTransform3dConvert(
+      Transform3d{Translation3d{1_m, 2_m, 3_m}, Rotation3d{}},
+      Transform3d{Translation3d{3_m, -1_m, -2_m},
+                  Rotation3d{-90_deg, 0_deg, -90_deg}},
+      CoordinateSystem::EDN(), CoordinateSystem::NWU());
+
+  // 45° roll from EDN to NWU
+  CheckTransform3dConvert(Transform3d{Translation3d{1_m, 2_m, 3_m},
+                                      Rotation3d{45_deg, 0_deg, 0_deg}},
+                          Transform3d{Translation3d{3_m, -1_m, -2_m},
+                                      Rotation3d{-45_deg, 0_deg, -90_deg}},
+                          CoordinateSystem::EDN(), CoordinateSystem::NWU());
+
+  // 45° pitch from EDN to NWU
+  CheckTransform3dConvert(Transform3d{Translation3d{1_m, 2_m, 3_m},
+                                      Rotation3d{0_deg, 45_deg, 0_deg}},
+                          Transform3d{Translation3d{3_m, -1_m, -2_m},
+                                      Rotation3d{-90_deg, 0_deg, -135_deg}},
+                          CoordinateSystem::EDN(), CoordinateSystem::NWU());
+
+  // 45° yaw from EDN to NWU
+  CheckTransform3dConvert(Transform3d{Translation3d{1_m, 2_m, 3_m},
+                                      Rotation3d{0_deg, 0_deg, 45_deg}},
+                          Transform3d{Translation3d{3_m, -1_m, -2_m},
+                                      Rotation3d{-90_deg, 45_deg, -90_deg}},
+                          CoordinateSystem::EDN(), CoordinateSystem::NWU());
+}
+
+TEST(CoordinateSystemTest, Transform3dEDNtoNED) {
+  // No rotation from EDN to NED
+  CheckTransform3dConvert(
+      Transform3d{Translation3d{1_m, 2_m, 3_m}, Rotation3d{}},
+      Transform3d{Translation3d{3_m, 1_m, 2_m},
+                  Rotation3d{90_deg, 0_deg, 90_deg}},
+      CoordinateSystem::EDN(), CoordinateSystem::NED());
+
+  // 45° roll from EDN to NED
+  CheckTransform3dConvert(Transform3d{Translation3d{1_m, 2_m, 3_m},
+                                      Rotation3d{45_deg, 0_deg, 0_deg}},
+                          Transform3d{Translation3d{3_m, 1_m, 2_m},
+                                      Rotation3d{135_deg, 0_deg, 90_deg}},
+                          CoordinateSystem::EDN(), CoordinateSystem::NED());
+
+  // 45° pitch from EDN to NED
+  CheckTransform3dConvert(Transform3d{Translation3d{1_m, 2_m, 3_m},
+                                      Rotation3d{0_deg, 45_deg, 0_deg}},
+                          Transform3d{Translation3d{3_m, 1_m, 2_m},
+                                      Rotation3d{90_deg, 0_deg, 135_deg}},
+                          CoordinateSystem::EDN(), CoordinateSystem::NED());
+
+  // 45° yaw from EDN to NED
+  CheckTransform3dConvert(Transform3d{Translation3d{1_m, 2_m, 3_m},
+                                      Rotation3d{0_deg, 0_deg, 45_deg}},
+                          Transform3d{Translation3d{3_m, 1_m, 2_m},
+                                      Rotation3d{90_deg, -45_deg, 90_deg}},
+                          CoordinateSystem::EDN(), CoordinateSystem::NED());
+}
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/Pose2dTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/Pose2dTest.cpp
index cd5b127..5ce6819 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/Pose2dTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/Pose2dTest.cpp
@@ -9,51 +9,66 @@
 
 using namespace frc;
 
-static constexpr double kEpsilon = 1E-9;
-
 TEST(Pose2dTest, TransformBy) {
-  const Pose2d initial{1_m, 2_m, Rotation2d(45.0_deg)};
-  const Transform2d transform{Translation2d{5.0_m, 0.0_m}, Rotation2d(5.0_deg)};
+  const Pose2d initial{1_m, 2_m, 45_deg};
+  const Transform2d transform{Translation2d{5_m, 0_m}, 5_deg};
 
   const auto transformed = initial + transform;
 
-  EXPECT_NEAR(transformed.X().value(), 1 + 5 / std::sqrt(2.0), kEpsilon);
-  EXPECT_NEAR(transformed.Y().value(), 2 + 5 / std::sqrt(2.0), kEpsilon);
-  EXPECT_NEAR(transformed.Rotation().Degrees().value(), 50.0, kEpsilon);
+  EXPECT_DOUBLE_EQ(1.0 + 5.0 / std::sqrt(2.0), transformed.X().value());
+  EXPECT_DOUBLE_EQ(2.0 + 5.0 / std::sqrt(2.0), transformed.Y().value());
+  EXPECT_DOUBLE_EQ(50.0, transformed.Rotation().Degrees().value());
 }
 
 TEST(Pose2dTest, RelativeTo) {
-  const Pose2d initial{0_m, 0_m, Rotation2d(45.0_deg)};
-  const Pose2d final{5_m, 5_m, Rotation2d(45.0_deg)};
+  const Pose2d initial{0_m, 0_m, 45_deg};
+  const Pose2d final{5_m, 5_m, 45.0_deg};
 
   const auto finalRelativeToInitial = final.RelativeTo(initial);
 
-  EXPECT_NEAR(finalRelativeToInitial.X().value(), 5.0 * std::sqrt(2.0),
-              kEpsilon);
-  EXPECT_NEAR(finalRelativeToInitial.Y().value(), 0.0, kEpsilon);
-  EXPECT_NEAR(finalRelativeToInitial.Rotation().Degrees().value(), 0.0,
-              kEpsilon);
+  EXPECT_DOUBLE_EQ(5.0 * std::sqrt(2.0), finalRelativeToInitial.X().value());
+  EXPECT_NEAR(0.0, finalRelativeToInitial.Y().value(), 1e-9);
+  EXPECT_DOUBLE_EQ(0.0, finalRelativeToInitial.Rotation().Degrees().value());
 }
 
 TEST(Pose2dTest, Equality) {
-  const Pose2d a{0_m, 5_m, Rotation2d(43_deg)};
-  const Pose2d b{0_m, 5_m, Rotation2d(43_deg)};
+  const Pose2d a{0_m, 5_m, 43_deg};
+  const Pose2d b{0_m, 5_m, 43_deg};
   EXPECT_TRUE(a == b);
 }
 
 TEST(Pose2dTest, Inequality) {
-  const Pose2d a{0_m, 5_m, Rotation2d(43_deg)};
-  const Pose2d b{0_m, 5_ft, Rotation2d(43_deg)};
+  const Pose2d a{0_m, 5_m, 43_deg};
+  const Pose2d b{0_m, 5_ft, 43_deg};
   EXPECT_TRUE(a != b);
 }
 
 TEST(Pose2dTest, Minus) {
-  const Pose2d initial{0_m, 0_m, Rotation2d(45.0_deg)};
-  const Pose2d final{5_m, 5_m, Rotation2d(45.0_deg)};
+  const Pose2d initial{0_m, 0_m, 45_deg};
+  const Pose2d final{5_m, 5_m, 45_deg};
 
   const auto transform = final - initial;
 
-  EXPECT_NEAR(transform.X().value(), 5.0 * std::sqrt(2.0), kEpsilon);
-  EXPECT_NEAR(transform.Y().value(), 0.0, kEpsilon);
-  EXPECT_NEAR(transform.Rotation().Degrees().value(), 0.0, kEpsilon);
+  EXPECT_DOUBLE_EQ(5.0 * std::sqrt(2.0), transform.X().value());
+  EXPECT_NEAR(0.0, transform.Y().value(), 1e-9);
+  EXPECT_DOUBLE_EQ(0.0, transform.Rotation().Degrees().value());
+}
+
+TEST(Pose2dTest, Constexpr) {
+  constexpr Pose2d defaultConstructed;
+  constexpr Pose2d translationRotation{Translation2d{0_m, 1_m},
+                                       Rotation2d{0_deg}};
+  constexpr Pose2d coordRotation{0_m, 0_m, Rotation2d{45_deg}};
+
+  constexpr auto added =
+      translationRotation + Transform2d{Translation2d{}, Rotation2d{45_deg}};
+  constexpr auto multiplied = coordRotation * 2;
+
+  static_assert(defaultConstructed.X() == 0_m);
+  static_assert(translationRotation.Y() == 1_m);
+  static_assert(coordRotation.Rotation().Degrees() == 45_deg);
+  static_assert(added.X() == 0_m);
+  static_assert(added.Y() == 1_m);
+  static_assert(added.Rotation().Degrees() == 45_deg);
+  static_assert(multiplied.Rotation().Degrees() == 90_deg);
 }
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/Pose3dTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/Pose3dTest.cpp
new file mode 100644
index 0000000..8c4452c
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/Pose3dTest.cpp
@@ -0,0 +1,97 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <cmath>
+
+#include "frc/geometry/Pose3d.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+TEST(Pose3dTest, TestTransformByRotations) {
+  const double kEpsilon = 1E-9;
+
+  const Pose3d initialPose{0_m, 0_m, 0_m, Rotation3d{0_deg, 0_deg, 0_deg}};
+  const Transform3d transform1{Translation3d{0_m, 0_m, 0_m},
+                               Rotation3d{90_deg, 45_deg, 0_deg}};
+  const Transform3d transform2{Translation3d{0_m, 0_m, 0_m},
+                               Rotation3d{-90_deg, 0_deg, 0_deg}};
+  const Transform3d transform3{Translation3d{0_m, 0_m, 0_m},
+                               Rotation3d{0_deg, -45_deg, 0_deg}};
+
+  Pose3d finalPose = initialPose.TransformBy(transform1)
+                         .TransformBy(transform2)
+                         .TransformBy(transform3);
+
+  EXPECT_NEAR(finalPose.Rotation().X().value(),
+              initialPose.Rotation().X().value(), kEpsilon);
+  EXPECT_NEAR(finalPose.Rotation().Y().value(),
+              initialPose.Rotation().Y().value(), kEpsilon);
+  EXPECT_NEAR(finalPose.Rotation().Z().value(),
+              initialPose.Rotation().Z().value(), kEpsilon);
+}
+
+TEST(Pose3dTest, TransformBy) {
+  Eigen::Vector3d zAxis{0.0, 0.0, 1.0};
+
+  const Pose3d initial{1_m, 2_m, 0_m, Rotation3d{zAxis, 45.0_deg}};
+  const Transform3d transform{Translation3d{5_m, 0_m, 0_m},
+                              Rotation3d{zAxis, 5_deg}};
+
+  const auto transformed = initial + transform;
+
+  EXPECT_DOUBLE_EQ(1.0 + 5.0 / std::sqrt(2.0), transformed.X().value());
+  EXPECT_DOUBLE_EQ(2.0 + 5.0 / std::sqrt(2.0), transformed.Y().value());
+  EXPECT_DOUBLE_EQ(transformed.Rotation().Z().value(),
+                   units::radian_t{50_deg}.value());
+}
+
+TEST(Pose3dTest, RelativeTo) {
+  Eigen::Vector3d zAxis{0.0, 0.0, 1.0};
+
+  const Pose3d initial{0_m, 0_m, 0_m, Rotation3d{zAxis, 45_deg}};
+  const Pose3d final{5_m, 5_m, 0_m, Rotation3d{zAxis, 45_deg}};
+
+  const auto finalRelativeToInitial = final.RelativeTo(initial);
+
+  EXPECT_DOUBLE_EQ(5.0 * std::sqrt(2.0), finalRelativeToInitial.X().value());
+  EXPECT_DOUBLE_EQ(0.0, finalRelativeToInitial.Y().value());
+  EXPECT_DOUBLE_EQ(0.0, finalRelativeToInitial.Rotation().Z().value());
+}
+
+TEST(Pose3dTest, Equality) {
+  Eigen::Vector3d zAxis{0.0, 0.0, 1.0};
+
+  const Pose3d a{0_m, 5_m, 0_m, Rotation3d{zAxis, 43_deg}};
+  const Pose3d b{0_m, 5_m, 0_m, Rotation3d{zAxis, 43_deg}};
+  EXPECT_TRUE(a == b);
+}
+
+TEST(Pose3dTest, Inequality) {
+  Eigen::Vector3d zAxis{0.0, 0.0, 1.0};
+
+  const Pose3d a{0_m, 5_m, 0_m, Rotation3d{zAxis, 43_deg}};
+  const Pose3d b{0_m, 5_ft, 0_m, Rotation3d{zAxis, 43_deg}};
+  EXPECT_TRUE(a != b);
+}
+
+TEST(Pose3dTest, Minus) {
+  Eigen::Vector3d zAxis{0.0, 0.0, 1.0};
+
+  const Pose3d initial{0_m, 0_m, 0_m, Rotation3d{zAxis, 45_deg}};
+  const Pose3d final{5_m, 5_m, 0_m, Rotation3d{zAxis, 45_deg}};
+
+  const auto transform = final - initial;
+
+  EXPECT_DOUBLE_EQ(5.0 * std::sqrt(2.0), transform.X().value());
+  EXPECT_DOUBLE_EQ(0.0, transform.Y().value());
+  EXPECT_DOUBLE_EQ(0.0, transform.Rotation().Z().value());
+}
+
+TEST(Pose3dTest, ToPose2d) {
+  Pose3d pose{1_m, 2_m, 3_m, Rotation3d{20_deg, 30_deg, 40_deg}};
+  Pose2d expected{1_m, 2_m, 40_deg};
+
+  EXPECT_EQ(expected, pose.ToPose2d());
+}
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/QuaternionTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/QuaternionTest.cpp
new file mode 100644
index 0000000..5b95abb
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/QuaternionTest.cpp
@@ -0,0 +1,82 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <numbers>
+
+#include "frc/geometry/Quaternion.h"
+#include "gtest/gtest.h"
+#include "units/angle.h"
+#include "units/math.h"
+
+using namespace frc;
+
+TEST(QuaternionTest, Init) {
+  // Identity
+  Quaternion q1;
+  EXPECT_DOUBLE_EQ(1.0, q1.W());
+  EXPECT_DOUBLE_EQ(0.0, q1.X());
+  EXPECT_DOUBLE_EQ(0.0, q1.Y());
+  EXPECT_DOUBLE_EQ(0.0, q1.Z());
+
+  // Normalized
+  Quaternion q2{0.5, 0.5, 0.5, 0.5};
+  EXPECT_DOUBLE_EQ(0.5, q2.W());
+  EXPECT_DOUBLE_EQ(0.5, q2.X());
+  EXPECT_DOUBLE_EQ(0.5, q2.Y());
+  EXPECT_DOUBLE_EQ(0.5, q2.Z());
+
+  // Unnormalized
+  Quaternion q3{0.75, 0.3, 0.4, 0.5};
+  EXPECT_DOUBLE_EQ(0.75, q3.W());
+  EXPECT_DOUBLE_EQ(0.3, q3.X());
+  EXPECT_DOUBLE_EQ(0.4, q3.Y());
+  EXPECT_DOUBLE_EQ(0.5, q3.Z());
+
+  q3 = q3.Normalize();
+  double norm = std::sqrt(0.75 * 0.75 + 0.3 * 0.3 + 0.4 * 0.4 + 0.5 * 0.5);
+  EXPECT_DOUBLE_EQ(0.75 / norm, q3.W());
+  EXPECT_DOUBLE_EQ(0.3 / norm, q3.X());
+  EXPECT_DOUBLE_EQ(0.4 / norm, q3.Y());
+  EXPECT_DOUBLE_EQ(0.5 / norm, q3.Z());
+  EXPECT_DOUBLE_EQ(1.0, q3.W() * q3.W() + q3.X() * q3.X() + q3.Y() * q3.Y() +
+                            q3.Z() * q3.Z());
+}
+
+TEST(QuaternionTest, Multiply) {
+  // 90° CCW rotations around each axis
+  double c = units::math::cos(90_deg / 2.0);
+  double s = units::math::sin(90_deg / 2.0);
+  Quaternion xRot{c, s, 0.0, 0.0};
+  Quaternion yRot{c, 0.0, s, 0.0};
+  Quaternion zRot{c, 0.0, 0.0, s};
+
+  // 90° CCW X rotation, 90° CCW Y rotation, and 90° CCW Z rotation should
+  // produce a 90° CCW Y rotation
+  auto expected = yRot;
+  auto actual = zRot * yRot * xRot;
+  EXPECT_NEAR(expected.W(), actual.W(), 1e-9);
+  EXPECT_NEAR(expected.X(), actual.X(), 1e-9);
+  EXPECT_NEAR(expected.Y(), actual.Y(), 1e-9);
+  EXPECT_NEAR(expected.Z(), actual.Z(), 1e-9);
+
+  // Identity
+  Quaternion q{0.72760687510899891, 0.29104275004359953, 0.38805700005813276,
+               0.48507125007266594};
+  actual = q * q.Inverse();
+  EXPECT_DOUBLE_EQ(1.0, actual.W());
+  EXPECT_DOUBLE_EQ(0.0, actual.X());
+  EXPECT_DOUBLE_EQ(0.0, actual.Y());
+  EXPECT_DOUBLE_EQ(0.0, actual.Z());
+}
+
+TEST(QuaternionTest, Inverse) {
+  Quaternion q{0.72760687510899891, 0.29104275004359953, 0.38805700005813276,
+               0.48507125007266594};
+  auto inv = q.Inverse();
+
+  EXPECT_DOUBLE_EQ(q.W(), inv.W());
+  EXPECT_DOUBLE_EQ(-q.X(), inv.X());
+  EXPECT_DOUBLE_EQ(-q.Y(), inv.Y());
+  EXPECT_DOUBLE_EQ(-q.Z(), inv.Z());
+}
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/Rotation2dTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/Rotation2dTest.cpp
index ed3b6b5..4e2e683 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/Rotation2dTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/Rotation2dTest.cpp
@@ -3,66 +3,82 @@
 // the WPILib BSD license file in the root directory of this project.
 
 #include <cmath>
-
-#include <wpi/numbers>
+#include <numbers>
 
 #include "frc/geometry/Rotation2d.h"
 #include "gtest/gtest.h"
 
 using namespace frc;
 
-static constexpr double kEpsilon = 1E-9;
-
 TEST(Rotation2dTest, RadiansToDegrees) {
-  const Rotation2d rot1{units::radian_t(wpi::numbers::pi / 3)};
-  const Rotation2d rot2{units::radian_t(wpi::numbers::pi / 4)};
+  const Rotation2d rot1{units::radian_t{std::numbers::pi / 3.0}};
+  const Rotation2d rot2{units::radian_t{std::numbers::pi / 4.0}};
 
-  EXPECT_NEAR(rot1.Degrees().value(), 60.0, kEpsilon);
-  EXPECT_NEAR(rot2.Degrees().value(), 45.0, kEpsilon);
+  EXPECT_DOUBLE_EQ(60.0, rot1.Degrees().value());
+  EXPECT_DOUBLE_EQ(45.0, rot2.Degrees().value());
 }
 
 TEST(Rotation2dTest, DegreesToRadians) {
-  const auto rot1 = Rotation2d(45.0_deg);
-  const auto rot2 = Rotation2d(30.0_deg);
+  const auto rot1 = Rotation2d{45_deg};
+  const auto rot2 = Rotation2d{30_deg};
 
-  EXPECT_NEAR(rot1.Radians().value(), wpi::numbers::pi / 4.0, kEpsilon);
-  EXPECT_NEAR(rot2.Radians().value(), wpi::numbers::pi / 6.0, kEpsilon);
+  EXPECT_DOUBLE_EQ(std::numbers::pi / 4.0, rot1.Radians().value());
+  EXPECT_DOUBLE_EQ(std::numbers::pi / 6.0, rot2.Radians().value());
 }
 
 TEST(Rotation2dTest, RotateByFromZero) {
   const Rotation2d zero;
-  auto sum = zero + Rotation2d(90.0_deg);
+  auto rotated = zero + Rotation2d{90_deg};
 
-  EXPECT_NEAR(sum.Radians().value(), wpi::numbers::pi / 2.0, kEpsilon);
-  EXPECT_NEAR(sum.Degrees().value(), 90.0, kEpsilon);
+  EXPECT_DOUBLE_EQ(std::numbers::pi / 2.0, rotated.Radians().value());
+  EXPECT_DOUBLE_EQ(90.0, rotated.Degrees().value());
 }
 
 TEST(Rotation2dTest, RotateByNonZero) {
-  auto rot = Rotation2d(90.0_deg);
-  rot = rot + Rotation2d(30.0_deg);
+  auto rot = Rotation2d{90_deg};
+  rot = rot + Rotation2d{30_deg};
 
-  EXPECT_NEAR(rot.Degrees().value(), 120.0, kEpsilon);
+  EXPECT_DOUBLE_EQ(120.0, rot.Degrees().value());
 }
 
 TEST(Rotation2dTest, Minus) {
-  const auto rot1 = Rotation2d(70.0_deg);
-  const auto rot2 = Rotation2d(30.0_deg);
+  const auto rot1 = Rotation2d{70_deg};
+  const auto rot2 = Rotation2d{30_deg};
 
-  EXPECT_NEAR((rot1 - rot2).Degrees().value(), 40.0, kEpsilon);
+  EXPECT_DOUBLE_EQ(40.0, (rot1 - rot2).Degrees().value());
 }
 
 TEST(Rotation2dTest, Equality) {
-  const auto rot1 = Rotation2d(43_deg);
-  const auto rot2 = Rotation2d(43_deg);
+  auto rot1 = Rotation2d{43_deg};
+  auto rot2 = Rotation2d{43_deg};
   EXPECT_EQ(rot1, rot2);
 
-  const auto rot3 = Rotation2d(-180_deg);
-  const auto rot4 = Rotation2d(180_deg);
-  EXPECT_EQ(rot3, rot4);
+  rot1 = Rotation2d{-180_deg};
+  rot2 = Rotation2d{180_deg};
+  EXPECT_EQ(rot1, rot2);
 }
 
 TEST(Rotation2dTest, Inequality) {
-  const auto rot1 = Rotation2d(43_deg);
-  const auto rot2 = Rotation2d(43.5_deg);
+  const auto rot1 = Rotation2d{43_deg};
+  const auto rot2 = Rotation2d{43.5_deg};
   EXPECT_NE(rot1, rot2);
 }
+
+TEST(Rotation2dTest, Constexpr) {
+  constexpr Rotation2d defaultCtor;
+  constexpr Rotation2d radianCtor{5_rad};
+  constexpr Rotation2d degreeCtor{270_deg};
+  constexpr Rotation2d rotation45{45_deg};
+  constexpr Rotation2d cartesianCtor{3.5, -3.5};
+
+  constexpr auto negated = -radianCtor;
+  constexpr auto multiplied = radianCtor * 2;
+  constexpr auto subtracted = cartesianCtor - degreeCtor;
+
+  static_assert(defaultCtor.Radians() == 0_rad);
+  static_assert(degreeCtor.Degrees() == 270_deg);
+  static_assert(negated.Radians() == -5_rad);
+  static_assert(multiplied.Radians() == 10_rad);
+  static_assert(subtracted == rotation45);
+  static_assert(radianCtor != degreeCtor);
+}
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/Rotation3dTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/Rotation3dTest.cpp
new file mode 100644
index 0000000..4709ed0
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/Rotation3dTest.cpp
@@ -0,0 +1,321 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <cmath>
+#include <numbers>
+
+#include <wpi/MathExtras.h>
+
+#include "frc/EigenCore.h"
+#include "frc/geometry/Rotation3d.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+TEST(Rotation3dTest, InitAxisAngleAndRollPitchYaw) {
+  const Eigen::Vector3d xAxis{1.0, 0.0, 0.0};
+  const Rotation3d rot1{xAxis, units::radian_t{std::numbers::pi / 3}};
+  const Rotation3d rot2{units::radian_t{std::numbers::pi / 3}, 0_rad, 0_rad};
+  EXPECT_EQ(rot1, rot2);
+
+  const Eigen::Vector3d yAxis{0.0, 1.0, 0.0};
+  const Rotation3d rot3{yAxis, units::radian_t{std::numbers::pi / 3}};
+  const Rotation3d rot4{0_rad, units::radian_t{std::numbers::pi / 3}, 0_rad};
+  EXPECT_EQ(rot3, rot4);
+
+  const Eigen::Vector3d zAxis{0.0, 0.0, 1.0};
+  const Rotation3d rot5{zAxis, units::radian_t{std::numbers::pi / 3}};
+  const Rotation3d rot6{0_rad, 0_rad, units::radian_t{std::numbers::pi / 3}};
+  EXPECT_EQ(rot5, rot6);
+}
+
+TEST(Rotation3dTest, InitRotationMatrix) {
+  // No rotation
+  const Matrixd<3, 3> R1 = Matrixd<3, 3>::Identity();
+  const Rotation3d rot1{R1};
+  EXPECT_EQ(Rotation3d{}, rot1);
+
+  // 90 degree CCW rotation around z-axis
+  Matrixd<3, 3> R2;
+  R2.block<3, 1>(0, 0) = Vectord<3>{0.0, 1.0, 0.0};
+  R2.block<3, 1>(0, 1) = Vectord<3>{-1.0, 0.0, 0.0};
+  R2.block<3, 1>(0, 2) = Vectord<3>{0.0, 0.0, 1.0};
+  const Rotation3d rot2{R2};
+  const Rotation3d expected2{0_deg, 0_deg, 90_deg};
+  EXPECT_EQ(expected2, rot2);
+
+  // Matrix that isn't orthogonal
+  const Matrixd<3, 3> R3{{1.0, 0.0, 0.0}, {1.0, 0.0, 0.0}, {1.0, 0.0, 0.0}};
+  EXPECT_THROW(Rotation3d{R3}, std::domain_error);
+
+  // Matrix that's orthogonal but not special orthogonal
+  const Matrixd<3, 3> R4 = Matrixd<3, 3>::Identity() * 2.0;
+  EXPECT_THROW(Rotation3d{R4}, std::domain_error);
+}
+
+TEST(Rotation3dTest, InitTwoVector) {
+  const Eigen::Vector3d xAxis{1.0, 0.0, 0.0};
+  const Eigen::Vector3d yAxis{0.0, 1.0, 0.0};
+  const Eigen::Vector3d zAxis{0.0, 0.0, 1.0};
+
+  // 90 degree CW rotation around y-axis
+  const Rotation3d rot1{xAxis, zAxis};
+  const Rotation3d expected1{yAxis, units::radian_t{-std::numbers::pi / 2.0}};
+  EXPECT_EQ(expected1, rot1);
+
+  // 45 degree CCW rotation around z-axis
+  const Rotation3d rot2{xAxis, Eigen::Vector3d{1.0, 1.0, 0.0}};
+  const Rotation3d expected2{zAxis, units::radian_t{std::numbers::pi / 4.0}};
+  EXPECT_EQ(expected2, rot2);
+
+  // 0 degree rotation of x-axes
+  const Rotation3d rot3{xAxis, xAxis};
+  EXPECT_EQ(Rotation3d{}, rot3);
+
+  // 0 degree rotation of y-axes
+  const Rotation3d rot4{yAxis, yAxis};
+  EXPECT_EQ(Rotation3d{}, rot4);
+
+  // 0 degree rotation of z-axes
+  const Rotation3d rot5{zAxis, zAxis};
+  EXPECT_EQ(Rotation3d{}, rot5);
+
+  // 180 degree rotation tests. For 180 degree rotations, any quaternion with an
+  // orthogonal rotation axis is acceptable. The rotation axis and initial
+  // vector are orthogonal if their dot product is zero.
+
+  // 180 degree rotation of x-axes
+  const Rotation3d rot6{xAxis, -xAxis};
+  const auto q6 = rot6.GetQuaternion();
+  EXPECT_EQ(0.0, q6.W());
+  EXPECT_EQ(0.0, q6.X() * xAxis(0) + q6.Y() * xAxis(1) + q6.Z() * xAxis(2));
+
+  // 180 degree rotation of y-axes
+  const Rotation3d rot7{yAxis, -yAxis};
+  const auto q7 = rot7.GetQuaternion();
+  EXPECT_EQ(0.0, q7.W());
+  EXPECT_EQ(0.0, q7.X() * yAxis(0) + q7.Y() * yAxis(1) + q7.Z() * yAxis(2));
+
+  // 180 degree rotation of z-axes
+  const Rotation3d rot8{zAxis, -zAxis};
+  const auto q8 = rot8.GetQuaternion();
+  EXPECT_EQ(0.0, q8.W());
+  EXPECT_EQ(0.0, q8.X() * zAxis(0) + q8.Y() * zAxis(1) + q8.Z() * zAxis(2));
+}
+
+TEST(Rotation3dTest, RadiansToDegrees) {
+  const Eigen::Vector3d zAxis{0.0, 0.0, 1.0};
+
+  const Rotation3d rot1{zAxis, units::radian_t{std::numbers::pi / 3}};
+  EXPECT_DOUBLE_EQ(0.0, rot1.X().value());
+  EXPECT_DOUBLE_EQ(0.0, rot1.Y().value());
+  EXPECT_DOUBLE_EQ(units::radian_t{60_deg}.value(), rot1.Z().value());
+
+  const Rotation3d rot2{zAxis, units::radian_t{std::numbers::pi / 4}};
+  EXPECT_DOUBLE_EQ(0.0, rot2.X().value());
+  EXPECT_DOUBLE_EQ(0.0, rot2.Y().value());
+  EXPECT_DOUBLE_EQ(units::radian_t{45_deg}.value(), rot2.Z().value());
+}
+
+TEST(Rotation3dTest, DegreesToRadians) {
+  const Eigen::Vector3d zAxis{0.0, 0.0, 1.0};
+
+  const auto rot1 = Rotation3d{zAxis, 45_deg};
+  EXPECT_DOUBLE_EQ(0.0, rot1.X().value());
+  EXPECT_DOUBLE_EQ(0.0, rot1.Y().value());
+  EXPECT_DOUBLE_EQ(std::numbers::pi / 4.0, rot1.Z().value());
+
+  const auto rot2 = Rotation3d{zAxis, 30_deg};
+  EXPECT_DOUBLE_EQ(0.0, rot2.X().value());
+  EXPECT_DOUBLE_EQ(0.0, rot2.Y().value());
+  EXPECT_DOUBLE_EQ(std::numbers::pi / 6.0, rot2.Z().value());
+}
+
+TEST(Rotation3dTest, RotationLoop) {
+  Rotation3d rot;
+
+  rot = rot + Rotation3d{90_deg, 0_deg, 0_deg};
+  Rotation3d expected{90_deg, 0_deg, 0_deg};
+  EXPECT_EQ(expected, rot);
+
+  rot = rot + Rotation3d{0_deg, 90_deg, 0_deg};
+  expected = Rotation3d{
+      {1.0 / std::sqrt(3), 1.0 / std::sqrt(3), -1.0 / std::sqrt(3)}, 120_deg};
+  EXPECT_EQ(expected, rot);
+
+  rot = rot + Rotation3d{0_deg, 0_deg, 90_deg};
+  expected = Rotation3d{0_deg, 90_deg, 0_deg};
+  EXPECT_EQ(expected, rot);
+
+  rot = rot + Rotation3d{0_deg, -90_deg, 0_deg};
+  EXPECT_EQ(Rotation3d{}, rot);
+}
+
+TEST(Rotation3dTest, RotateByFromZeroX) {
+  const Eigen::Vector3d xAxis{1.0, 0.0, 0.0};
+
+  const Rotation3d zero;
+  auto rotated = zero + Rotation3d{xAxis, 90_deg};
+
+  Rotation3d expected{xAxis, 90_deg};
+  EXPECT_EQ(expected, rotated);
+}
+
+TEST(Rotation3dTest, RotateByFromZeroY) {
+  const Eigen::Vector3d yAxis{0.0, 1.0, 0.0};
+
+  const Rotation3d zero;
+  auto rotated = zero + Rotation3d{yAxis, 90_deg};
+
+  Rotation3d expected{yAxis, 90_deg};
+  EXPECT_EQ(expected, rotated);
+}
+
+TEST(Rotation3dTest, RotateByFromZeroZ) {
+  const Eigen::Vector3d zAxis{0.0, 0.0, 1.0};
+
+  const Rotation3d zero;
+  auto rotated = zero + Rotation3d{zAxis, 90_deg};
+
+  Rotation3d expected{zAxis, 90_deg};
+  EXPECT_EQ(expected, rotated);
+}
+
+TEST(Rotation3dTest, RotateByNonZeroX) {
+  const Eigen::Vector3d xAxis{1.0, 0.0, 0.0};
+
+  auto rot = Rotation3d{xAxis, 90_deg};
+  rot = rot + Rotation3d{xAxis, 30_deg};
+
+  Rotation3d expected{xAxis, 120_deg};
+  EXPECT_EQ(expected, rot);
+}
+
+TEST(Rotation3dTest, RotateByNonZeroY) {
+  const Eigen::Vector3d yAxis{0.0, 1.0, 0.0};
+
+  auto rot = Rotation3d{yAxis, 90_deg};
+  rot = rot + Rotation3d{yAxis, 30_deg};
+
+  Rotation3d expected{yAxis, 120_deg};
+  EXPECT_EQ(expected, rot);
+}
+
+TEST(Rotation3dTest, RotateByNonZeroZ) {
+  const Eigen::Vector3d zAxis{0.0, 0.0, 1.0};
+
+  auto rot = Rotation3d{zAxis, 90_deg};
+  rot = rot + Rotation3d{zAxis, 30_deg};
+
+  Rotation3d expected{zAxis, 120_deg};
+  EXPECT_EQ(expected, rot);
+}
+
+TEST(Rotation3dTest, Minus) {
+  const Eigen::Vector3d zAxis{0.0, 0.0, 1.0};
+
+  const auto rot1 = Rotation3d{zAxis, 70_deg};
+  const auto rot2 = Rotation3d{zAxis, 30_deg};
+
+  EXPECT_DOUBLE_EQ(40.0, units::degree_t{(rot1 - rot2).Z()}.value());
+}
+
+TEST(Rotation3dTest, AxisAngle) {
+  const Eigen::Vector3d xAxis{1.0, 0.0, 0.0};
+  const Eigen::Vector3d yAxis{0.0, 1.0, 0.0};
+  const Eigen::Vector3d zAxis{0.0, 0.0, 1.0};
+
+  Rotation3d rot1{xAxis, 90_deg};
+  EXPECT_EQ(xAxis, rot1.Axis());
+  EXPECT_DOUBLE_EQ(std::numbers::pi / 2.0, rot1.Angle().value());
+
+  Rotation3d rot2{yAxis, 45_deg};
+  EXPECT_EQ(yAxis, rot2.Axis());
+  EXPECT_DOUBLE_EQ(std::numbers::pi / 4.0, rot2.Angle().value());
+
+  Rotation3d rot3{zAxis, 60_deg};
+  EXPECT_EQ(zAxis, rot3.Axis());
+  EXPECT_DOUBLE_EQ(std::numbers::pi / 3.0, rot3.Angle().value());
+}
+
+TEST(Rotation3dTest, ToRotation2d) {
+  Rotation3d rotation{20_deg, 30_deg, 40_deg};
+  Rotation2d expected{40_deg};
+
+  EXPECT_EQ(expected, rotation.ToRotation2d());
+}
+
+TEST(Rotation3dTest, Equality) {
+  const Eigen::Vector3d zAxis{0.0, 0.0, 1.0};
+
+  const auto rot1 = Rotation3d{zAxis, 43_deg};
+  const auto rot2 = Rotation3d{zAxis, 43_deg};
+  EXPECT_EQ(rot1, rot2);
+
+  const auto rot3 = Rotation3d{zAxis, -180_deg};
+  const auto rot4 = Rotation3d{zAxis, 180_deg};
+  EXPECT_EQ(rot3, rot4);
+}
+
+TEST(Rotation3dTest, Inequality) {
+  const Eigen::Vector3d zAxis{0.0, 0.0, 1.0};
+
+  const auto rot1 = Rotation3d{zAxis, 43_deg};
+  const auto rot2 = Rotation3d{zAxis, 43.5_deg};
+  EXPECT_NE(rot1, rot2);
+}
+
+TEST(Rotation3dTest, Interpolate) {
+  const Eigen::Vector3d xAxis{1.0, 0.0, 0.0};
+  const Eigen::Vector3d yAxis{0.0, 1.0, 0.0};
+  const Eigen::Vector3d zAxis{0.0, 0.0, 1.0};
+
+  // 50 + (70 - 50) * 0.5 = 60
+  auto rot1 = Rotation3d{xAxis, 50_deg};
+  auto rot2 = Rotation3d{xAxis, 70_deg};
+  auto interpolated = wpi::Lerp(rot1, rot2, 0.5);
+  EXPECT_DOUBLE_EQ(60.0, units::degree_t{interpolated.X()}.value());
+  EXPECT_DOUBLE_EQ(0.0, units::degree_t{interpolated.Y()}.value());
+  EXPECT_DOUBLE_EQ(0.0, units::degree_t{interpolated.Z()}.value());
+
+  // -160 minus half distance between 170 and -160 (15) = -175
+  rot1 = Rotation3d{xAxis, 170_deg};
+  rot2 = Rotation3d{xAxis, -160_deg};
+  interpolated = wpi::Lerp(rot1, rot2, 0.5);
+  EXPECT_DOUBLE_EQ(-175.0, units::degree_t{interpolated.X()}.value());
+  EXPECT_DOUBLE_EQ(0.0, units::degree_t{interpolated.Y()}.value());
+  EXPECT_DOUBLE_EQ(0.0, units::degree_t{interpolated.Z()}.value());
+
+  // 50 + (70 - 50) * 0.5 = 60
+  rot1 = Rotation3d{yAxis, 50_deg};
+  rot2 = Rotation3d{yAxis, 70_deg};
+  interpolated = wpi::Lerp(rot1, rot2, 0.5);
+  EXPECT_DOUBLE_EQ(0.0, units::degree_t{interpolated.X()}.value());
+  EXPECT_DOUBLE_EQ(60.0, units::degree_t{interpolated.Y()}.value());
+  EXPECT_DOUBLE_EQ(0.0, units::degree_t{interpolated.Z()}.value());
+
+  // -160 plus half distance between 170 and -160 (165) = 5
+  rot1 = Rotation3d{yAxis, 170_deg};
+  rot2 = Rotation3d{yAxis, -160_deg};
+  interpolated = wpi::Lerp(rot1, rot2, 0.5);
+  EXPECT_DOUBLE_EQ(180.0, units::degree_t{interpolated.X()}.value());
+  EXPECT_DOUBLE_EQ(-5.0, units::degree_t{interpolated.Y()}.value());
+  EXPECT_DOUBLE_EQ(180.0, units::degree_t{interpolated.Z()}.value());
+
+  // 50 + (70 - 50) * 0.5 = 60
+  rot1 = Rotation3d{zAxis, 50_deg};
+  rot2 = Rotation3d{zAxis, 70_deg};
+  interpolated = wpi::Lerp(rot1, rot2, 0.5);
+  EXPECT_DOUBLE_EQ(0.0, units::degree_t{interpolated.X()}.value());
+  EXPECT_DOUBLE_EQ(0.0, units::degree_t{interpolated.Y()}.value());
+  EXPECT_DOUBLE_EQ(60.0, units::degree_t{interpolated.Z()}.value());
+
+  // -160 minus half distance between 170 and -160 (15) = -175
+  rot1 = Rotation3d{zAxis, 170_deg};
+  rot2 = Rotation3d{zAxis, -160_deg};
+  interpolated = wpi::Lerp(rot1, rot2, 0.5);
+  EXPECT_DOUBLE_EQ(0.0, units::degree_t{interpolated.X()}.value());
+  EXPECT_DOUBLE_EQ(0.0, units::degree_t{interpolated.Y()}.value());
+  EXPECT_DOUBLE_EQ(-175.0, units::degree_t{interpolated.Z()}.value());
+}
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/Transform2dTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/Transform2dTest.cpp
index 968ab29..1b0934d 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/Transform2dTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/Transform2dTest.cpp
@@ -12,8 +12,6 @@
 
 using namespace frc;
 
-static constexpr double kEpsilon = 1E-9;
-
 TEST(Transform2dTest, Inverse) {
   const Pose2d initial{1_m, 2_m, 45_deg};
   const Transform2d transform{{5_m, 0_m}, 5_deg};
@@ -21,10 +19,7 @@
   auto transformed = initial + transform;
   auto untransformed = transformed + transform.Inverse();
 
-  EXPECT_NEAR(initial.X().value(), untransformed.X().value(), kEpsilon);
-  EXPECT_NEAR(initial.Y().value(), untransformed.Y().value(), kEpsilon);
-  EXPECT_NEAR(initial.Rotation().Degrees().value(),
-              untransformed.Rotation().Degrees().value(), kEpsilon);
+  EXPECT_EQ(initial, untransformed);
 }
 
 TEST(Transform2dTest, Composition) {
@@ -35,10 +30,23 @@
   auto transformedSeparate = initial + transform1 + transform2;
   auto transformedCombined = initial + (transform1 + transform2);
 
-  EXPECT_NEAR(transformedSeparate.X().value(), transformedCombined.X().value(),
-              kEpsilon);
-  EXPECT_NEAR(transformedSeparate.Y().value(), transformedCombined.Y().value(),
-              kEpsilon);
-  EXPECT_NEAR(transformedSeparate.Rotation().Degrees().value(),
-              transformedCombined.Rotation().Degrees().value(), kEpsilon);
+  EXPECT_EQ(transformedSeparate, transformedCombined);
+}
+
+TEST(Transform2dTest, Constexpr) {
+  constexpr Transform2d defaultCtor;
+  constexpr Transform2d translationRotationCtor{Translation2d{},
+                                                Rotation2d{10_deg}};
+  constexpr auto multiplied = translationRotationCtor * 5;
+  constexpr auto divided = translationRotationCtor / 2;
+
+  static_assert(defaultCtor.Translation().X() == 0_m);
+  static_assert(translationRotationCtor.X() == 0_m);
+  static_assert(translationRotationCtor.Y() == 0_m);
+  static_assert(multiplied.Rotation().Degrees() == 50_deg);
+  static_assert(translationRotationCtor.Inverse().Rotation().Degrees() ==
+                (-10_deg));
+  static_assert(translationRotationCtor.Inverse().X() == 0_m);
+  static_assert(translationRotationCtor.Inverse().Y() == 0_m);
+  static_assert(divided.Rotation().Degrees() == 5_deg);
 }
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/Transform3dTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/Transform3dTest.cpp
new file mode 100644
index 0000000..904ec9c
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/Transform3dTest.cpp
@@ -0,0 +1,38 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <cmath>
+
+#include "frc/geometry/Pose3d.h"
+#include "frc/geometry/Rotation3d.h"
+#include "frc/geometry/Transform3d.h"
+#include "frc/geometry/Translation3d.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+TEST(Transform3dTest, Inverse) {
+  Eigen::Vector3d zAxis{0.0, 0.0, 1.0};
+
+  const Pose3d initial{1_m, 2_m, 3_m, Rotation3d{zAxis, 45_deg}};
+  const Transform3d transform{{5_m, 4_m, 3_m}, Rotation3d{zAxis, 5_deg}};
+
+  auto transformed = initial + transform;
+  auto untransformed = transformed + transform.Inverse();
+
+  EXPECT_EQ(initial, untransformed);
+}
+
+TEST(Transform3dTest, Composition) {
+  Eigen::Vector3d zAxis{0.0, 0.0, 1.0};
+
+  const Pose3d initial{1_m, 2_m, 3_m, Rotation3d{zAxis, 45_deg}};
+  const Transform3d transform1{{5_m, 0_m, 0_m}, Rotation3d{zAxis, 5_deg}};
+  const Transform3d transform2{{0_m, 2_m, 0_m}, Rotation3d{zAxis, 5_deg}};
+
+  auto transformedSeparate = initial + transform1 + transform2;
+  auto transformedCombined = initial + (transform1 + transform2);
+
+  EXPECT_EQ(transformedSeparate, transformedCombined);
+}
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/Translation2dTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/Translation2dTest.cpp
index efdcace..5493c43 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/Translation2dTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/Translation2dTest.cpp
@@ -9,69 +9,67 @@
 
 using namespace frc;
 
-static constexpr double kEpsilon = 1E-9;
-
 TEST(Translation2dTest, Sum) {
-  const Translation2d one{1.0_m, 3.0_m};
-  const Translation2d two{2.0_m, 5.0_m};
+  const Translation2d one{1_m, 3_m};
+  const Translation2d two{2_m, 5_m};
 
   const auto sum = one + two;
 
-  EXPECT_NEAR(sum.X().value(), 3.0, kEpsilon);
-  EXPECT_NEAR(sum.Y().value(), 8.0, kEpsilon);
+  EXPECT_DOUBLE_EQ(3.0, sum.X().value());
+  EXPECT_DOUBLE_EQ(8.0, sum.Y().value());
 }
 
 TEST(Translation2dTest, Difference) {
-  const Translation2d one{1.0_m, 3.0_m};
-  const Translation2d two{2.0_m, 5.0_m};
+  const Translation2d one{1_m, 3_m};
+  const Translation2d two{2_m, 5_m};
 
   const auto difference = one - two;
 
-  EXPECT_NEAR(difference.X().value(), -1.0, kEpsilon);
-  EXPECT_NEAR(difference.Y().value(), -2.0, kEpsilon);
+  EXPECT_DOUBLE_EQ(-1.0, difference.X().value());
+  EXPECT_DOUBLE_EQ(-2.0, difference.Y().value());
 }
 
 TEST(Translation2dTest, RotateBy) {
-  const Translation2d another{3.0_m, 0.0_m};
-  const auto rotated = another.RotateBy(Rotation2d(90.0_deg));
+  const Translation2d another{3_m, 0_m};
+  const auto rotated = another.RotateBy(90_deg);
 
-  EXPECT_NEAR(rotated.X().value(), 0.0, kEpsilon);
-  EXPECT_NEAR(rotated.Y().value(), 3.0, kEpsilon);
+  EXPECT_NEAR(0.0, rotated.X().value(), 1e-9);
+  EXPECT_DOUBLE_EQ(3.0, rotated.Y().value());
 }
 
 TEST(Translation2dTest, Multiplication) {
-  const Translation2d original{3.0_m, 5.0_m};
+  const Translation2d original{3_m, 5_m};
   const auto mult = original * 3;
 
-  EXPECT_NEAR(mult.X().value(), 9.0, kEpsilon);
-  EXPECT_NEAR(mult.Y().value(), 15.0, kEpsilon);
+  EXPECT_DOUBLE_EQ(9.0, mult.X().value());
+  EXPECT_DOUBLE_EQ(15.0, mult.Y().value());
 }
 
 TEST(Translation2dTest, Division) {
-  const Translation2d original{3.0_m, 5.0_m};
+  const Translation2d original{3_m, 5_m};
   const auto div = original / 2;
 
-  EXPECT_NEAR(div.X().value(), 1.5, kEpsilon);
-  EXPECT_NEAR(div.Y().value(), 2.5, kEpsilon);
+  EXPECT_DOUBLE_EQ(1.5, div.X().value());
+  EXPECT_DOUBLE_EQ(2.5, div.Y().value());
 }
 
 TEST(Translation2dTest, Norm) {
-  const Translation2d one{3.0_m, 5.0_m};
-  EXPECT_NEAR(one.Norm().value(), std::hypot(3, 5), kEpsilon);
+  const Translation2d one{3_m, 5_m};
+  EXPECT_DOUBLE_EQ(std::hypot(3.0, 5.0), one.Norm().value());
 }
 
 TEST(Translation2dTest, Distance) {
   const Translation2d one{1_m, 1_m};
   const Translation2d two{6_m, 6_m};
-  EXPECT_NEAR(one.Distance(two).value(), 5 * std::sqrt(2), kEpsilon);
+  EXPECT_DOUBLE_EQ(5.0 * std::sqrt(2.0), one.Distance(two).value());
 }
 
 TEST(Translation2dTest, UnaryMinus) {
   const Translation2d original{-4.5_m, 7_m};
   const auto inverted = -original;
 
-  EXPECT_NEAR(inverted.X().value(), 4.5, kEpsilon);
-  EXPECT_NEAR(inverted.Y().value(), -7, kEpsilon);
+  EXPECT_DOUBLE_EQ(4.5, inverted.X().value());
+  EXPECT_DOUBLE_EQ(-7.0, inverted.Y().value());
 }
 
 TEST(Translation2dTest, Equality) {
@@ -87,11 +85,29 @@
 }
 
 TEST(Translation2dTest, PolarConstructor) {
-  Translation2d one{std::sqrt(2) * 1_m, Rotation2d(45_deg)};
-  EXPECT_NEAR(one.X().value(), 1.0, kEpsilon);
-  EXPECT_NEAR(one.Y().value(), 1.0, kEpsilon);
+  Translation2d one{std::sqrt(2) * 1_m, Rotation2d{45_deg}};
+  EXPECT_DOUBLE_EQ(1.0, one.X().value());
+  EXPECT_DOUBLE_EQ(1.0, one.Y().value());
 
-  Translation2d two{2_m, Rotation2d(60_deg)};
-  EXPECT_NEAR(two.X().value(), 1.0, kEpsilon);
-  EXPECT_NEAR(two.Y().value(), std::sqrt(3.0), kEpsilon);
+  Translation2d two{2_m, Rotation2d{60_deg}};
+  EXPECT_DOUBLE_EQ(1.0, two.X().value());
+  EXPECT_DOUBLE_EQ(std::sqrt(3.0), two.Y().value());
+}
+
+TEST(Translation2dTest, Constexpr) {
+  constexpr Translation2d defaultCtor;
+  constexpr Translation2d componentCtor{1_m, 2_m};
+  constexpr auto added = defaultCtor + componentCtor;
+  constexpr auto subtracted = defaultCtor - componentCtor;
+  constexpr auto negated = -componentCtor;
+  constexpr auto multiplied = componentCtor * 2;
+  constexpr auto divided = componentCtor / 2;
+
+  static_assert(defaultCtor.X() == 0_m);
+  static_assert(componentCtor.Y() == 2_m);
+  static_assert(added.X() == 1_m);
+  static_assert(subtracted.Y() == (-2_m));
+  static_assert(negated.X() == (-1_m));
+  static_assert(multiplied.X() == 2_m);
+  static_assert(divided.Y() == 1_m);
 }
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/Translation3dTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/Translation3dTest.cpp
new file mode 100644
index 0000000..58c611e
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/Translation3dTest.cpp
@@ -0,0 +1,149 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <cmath>
+
+#include "frc/geometry/Translation3d.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+static constexpr double kEpsilon = 1E-9;
+
+TEST(Translation3dTest, Sum) {
+  const Translation3d one{1_m, 3_m, 5_m};
+  const Translation3d two{2_m, 5_m, 8_m};
+
+  const auto sum = one + two;
+
+  EXPECT_NEAR(3.0, sum.X().value(), kEpsilon);
+  EXPECT_NEAR(8.0, sum.Y().value(), kEpsilon);
+  EXPECT_NEAR(13.0, sum.Z().value(), kEpsilon);
+}
+
+TEST(Translation3dTest, Difference) {
+  const Translation3d one{1_m, 3_m, 5_m};
+  const Translation3d two{2_m, 5_m, 8_m};
+
+  const auto difference = one - two;
+
+  EXPECT_NEAR(difference.X().value(), -1.0, kEpsilon);
+  EXPECT_NEAR(difference.Y().value(), -2.0, kEpsilon);
+  EXPECT_NEAR(difference.Z().value(), -3.0, kEpsilon);
+}
+
+TEST(Translation3dTest, RotateBy) {
+  Eigen::Vector3d xAxis{1.0, 0.0, 0.0};
+  Eigen::Vector3d yAxis{0.0, 1.0, 0.0};
+  Eigen::Vector3d zAxis{0.0, 0.0, 1.0};
+
+  const Translation3d translation{1_m, 2_m, 3_m};
+
+  const auto rotated1 = translation.RotateBy(Rotation3d{xAxis, 90_deg});
+  EXPECT_NEAR(rotated1.X().value(), 1.0, kEpsilon);
+  EXPECT_NEAR(rotated1.Y().value(), -3.0, kEpsilon);
+  EXPECT_NEAR(rotated1.Z().value(), 2.0, kEpsilon);
+
+  const auto rotated2 = translation.RotateBy(Rotation3d{yAxis, 90_deg});
+  EXPECT_NEAR(rotated2.X().value(), 3.0, kEpsilon);
+  EXPECT_NEAR(rotated2.Y().value(), 2.0, kEpsilon);
+  EXPECT_NEAR(rotated2.Z().value(), -1.0, kEpsilon);
+
+  const auto rotated3 = translation.RotateBy(Rotation3d{zAxis, 90_deg});
+  EXPECT_NEAR(rotated3.X().value(), -2.0, kEpsilon);
+  EXPECT_NEAR(rotated3.Y().value(), 1.0, kEpsilon);
+  EXPECT_NEAR(rotated3.Z().value(), 3.0, kEpsilon);
+}
+
+TEST(Translation3dTest, ToTranslation2d) {
+  Translation3d translation{1_m, 2_m, 3_m};
+  Translation2d expected{1_m, 2_m};
+
+  EXPECT_EQ(expected, translation.ToTranslation2d());
+}
+
+TEST(Translation3dTest, Multiplication) {
+  const Translation3d original{3_m, 5_m, 7_m};
+  const auto mult = original * 3;
+
+  EXPECT_NEAR(mult.X().value(), 9.0, kEpsilon);
+  EXPECT_NEAR(mult.Y().value(), 15.0, kEpsilon);
+  EXPECT_NEAR(mult.Z().value(), 21.0, kEpsilon);
+}
+
+TEST(Translation3dTest, Division) {
+  const Translation3d original{3_m, 5_m, 7_m};
+  const auto div = original / 2;
+
+  EXPECT_NEAR(div.X().value(), 1.5, kEpsilon);
+  EXPECT_NEAR(div.Y().value(), 2.5, kEpsilon);
+  EXPECT_NEAR(div.Z().value(), 3.5, kEpsilon);
+}
+
+TEST(Translation3dTest, Norm) {
+  const Translation3d one{3_m, 5_m, 7_m};
+  EXPECT_NEAR(one.Norm().value(), std::hypot(3, 5, 7), kEpsilon);
+}
+
+TEST(Translation3dTest, Distance) {
+  const Translation3d one{1_m, 1_m, 1_m};
+  const Translation3d two{6_m, 6_m, 6_m};
+  EXPECT_NEAR(one.Distance(two).value(), 5 * std::sqrt(3), kEpsilon);
+}
+
+TEST(Translation3dTest, UnaryMinus) {
+  const Translation3d original{-4.5_m, 7_m, 9_m};
+  const auto inverted = -original;
+
+  EXPECT_NEAR(inverted.X().value(), 4.5, kEpsilon);
+  EXPECT_NEAR(inverted.Y().value(), -7, kEpsilon);
+  EXPECT_NEAR(inverted.Z().value(), -9, kEpsilon);
+}
+
+TEST(Translation3dTest, Equality) {
+  const Translation3d one{9_m, 5.5_m, 3.5_m};
+  const Translation3d two{9_m, 5.5_m, 3.5_m};
+  EXPECT_TRUE(one == two);
+}
+
+TEST(Translation3dTest, Inequality) {
+  const Translation3d one{9_m, 5.5_m, 3.5_m};
+  const Translation3d two{9_m, 5.7_m, 3.5_m};
+  EXPECT_TRUE(one != two);
+}
+
+TEST(Translation3dTest, PolarConstructor) {
+  Eigen::Vector3d zAxis{0.0, 0.0, 1.0};
+
+  Translation3d one{std::sqrt(2) * 1_m, Rotation3d{zAxis, 45_deg}};
+  EXPECT_NEAR(one.X().value(), 1.0, kEpsilon);
+  EXPECT_NEAR(one.Y().value(), 1.0, kEpsilon);
+  EXPECT_NEAR(one.Z().value(), 0.0, kEpsilon);
+
+  Translation3d two{2_m, Rotation3d{zAxis, 60_deg}};
+  EXPECT_NEAR(two.X().value(), 1.0, kEpsilon);
+  EXPECT_NEAR(two.Y().value(), std::sqrt(3.0), kEpsilon);
+  EXPECT_NEAR(two.Z().value(), 0.0, kEpsilon);
+}
+
+TEST(Translation3dTest, Constexpr) {
+  constexpr Translation3d defaultCtor;
+  constexpr Translation3d componentCtor{1_m, 2_m, 3_m};
+  constexpr auto added = defaultCtor + componentCtor;
+  constexpr auto subtracted = defaultCtor - componentCtor;
+  constexpr auto negated = -componentCtor;
+  constexpr auto multiplied = componentCtor * 2;
+  constexpr auto divided = componentCtor / 2;
+  constexpr Translation2d projected = componentCtor.ToTranslation2d();
+
+  static_assert(defaultCtor.X() == 0_m);
+  static_assert(componentCtor.Y() == 2_m);
+  static_assert(added.Z() == 3_m);
+  static_assert(subtracted.X() == (-1_m));
+  static_assert(negated.Y() == (-2_m));
+  static_assert(multiplied.Z() == 6_m);
+  static_assert(divided.Y() == 1_m);
+  static_assert(projected.X() == 1_m);
+  static_assert(projected.Y() == 2_m);
+}
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/Twist2dTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/Twist2dTest.cpp
index fa9eecc..33970cd 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/Twist2dTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/Twist2dTest.cpp
@@ -3,63 +3,74 @@
 // the WPILib BSD license file in the root directory of this project.
 
 #include <cmath>
-
-#include <wpi/numbers>
+#include <numbers>
 
 #include "frc/geometry/Pose2d.h"
 #include "gtest/gtest.h"
 
 using namespace frc;
 
-static constexpr double kEpsilon = 1E-9;
-
 TEST(Twist2dTest, Straight) {
-  const Twist2d straight{5.0_m, 0.0_m, 0.0_rad};
-  const auto straightPose = Pose2d().Exp(straight);
+  const Twist2d straight{5_m, 0_m, 0_rad};
+  const auto straightPose = Pose2d{}.Exp(straight);
 
-  EXPECT_NEAR(straightPose.X().value(), 5.0, kEpsilon);
-  EXPECT_NEAR(straightPose.Y().value(), 0.0, kEpsilon);
-  EXPECT_NEAR(straightPose.Rotation().Radians().value(), 0.0, kEpsilon);
+  EXPECT_DOUBLE_EQ(5.0, straightPose.X().value());
+  EXPECT_DOUBLE_EQ(0.0, straightPose.Y().value());
+  EXPECT_DOUBLE_EQ(0.0, straightPose.Rotation().Radians().value());
 }
 
 TEST(Twist2dTest, QuarterCircle) {
-  const Twist2d quarterCircle{5.0_m / 2.0 * wpi::numbers::pi, 0_m,
-                              units::radian_t(wpi::numbers::pi / 2.0)};
-  const auto quarterCirclePose = Pose2d().Exp(quarterCircle);
+  const Twist2d quarterCircle{5_m / 2.0 * std::numbers::pi, 0_m,
+                              units::radian_t{std::numbers::pi / 2.0}};
+  const auto quarterCirclePose = Pose2d{}.Exp(quarterCircle);
 
-  EXPECT_NEAR(quarterCirclePose.X().value(), 5.0, kEpsilon);
-  EXPECT_NEAR(quarterCirclePose.Y().value(), 5.0, kEpsilon);
-  EXPECT_NEAR(quarterCirclePose.Rotation().Degrees().value(), 90.0, kEpsilon);
+  EXPECT_DOUBLE_EQ(5.0, quarterCirclePose.X().value());
+  EXPECT_DOUBLE_EQ(5.0, quarterCirclePose.Y().value());
+  EXPECT_DOUBLE_EQ(90.0, quarterCirclePose.Rotation().Degrees().value());
 }
 
 TEST(Twist2dTest, DiagonalNoDtheta) {
-  const Twist2d diagonal{2.0_m, 2.0_m, 0.0_deg};
-  const auto diagonalPose = Pose2d().Exp(diagonal);
+  const Twist2d diagonal{2_m, 2_m, 0_deg};
+  const auto diagonalPose = Pose2d{}.Exp(diagonal);
 
-  EXPECT_NEAR(diagonalPose.X().value(), 2.0, kEpsilon);
-  EXPECT_NEAR(diagonalPose.Y().value(), 2.0, kEpsilon);
-  EXPECT_NEAR(diagonalPose.Rotation().Degrees().value(), 0.0, kEpsilon);
+  EXPECT_DOUBLE_EQ(2.0, diagonalPose.X().value());
+  EXPECT_DOUBLE_EQ(2.0, diagonalPose.Y().value());
+  EXPECT_DOUBLE_EQ(0.0, diagonalPose.Rotation().Degrees().value());
 }
 
 TEST(Twist2dTest, Equality) {
-  const Twist2d one{5.0_m, 1.0_m, 3.0_rad};
-  const Twist2d two{5.0_m, 1.0_m, 3.0_rad};
+  const Twist2d one{5_m, 1_m, 3_rad};
+  const Twist2d two{5_m, 1_m, 3_rad};
   EXPECT_TRUE(one == two);
 }
 
 TEST(Twist2dTest, Inequality) {
-  const Twist2d one{5.0_m, 1.0_m, 3.0_rad};
-  const Twist2d two{5.0_m, 1.2_m, 3.0_rad};
+  const Twist2d one{5_m, 1_m, 3_rad};
+  const Twist2d two{5_m, 1.2_m, 3_rad};
   EXPECT_TRUE(one != two);
 }
 
 TEST(Twist2dTest, Pose2dLog) {
-  const Pose2d end{5_m, 5_m, Rotation2d(90_deg)};
-  const Pose2d start{};
+  const Pose2d end{5_m, 5_m, 90_deg};
+  const Pose2d start;
 
   const auto twist = start.Log(end);
 
-  EXPECT_NEAR(twist.dx.value(), 5 / 2.0 * wpi::numbers::pi, kEpsilon);
-  EXPECT_NEAR(twist.dy.value(), 0.0, kEpsilon);
-  EXPECT_NEAR(twist.dtheta.value(), wpi::numbers::pi / 2.0, kEpsilon);
+  Twist2d expected{units::meter_t{5.0 / 2.0 * std::numbers::pi}, 0_m,
+                   units::radian_t{std::numbers::pi / 2.0}};
+  EXPECT_EQ(expected, twist);
+
+  // Make sure computed twist gives back original end pose
+  const auto reapplied = start.Exp(twist);
+  EXPECT_EQ(end, reapplied);
+}
+
+TEST(Twist2dTest, Constexpr) {
+  constexpr Twist2d defaultCtor;
+  constexpr Twist2d componentCtor{1_m, 2_m, 3_rad};
+  constexpr auto multiplied = componentCtor * 2;
+
+  static_assert(defaultCtor.dx == 0_m);
+  static_assert(componentCtor.dy == 2_m);
+  static_assert(multiplied.dtheta == 6_rad);
 }
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/Twist3dTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/Twist3dTest.cpp
new file mode 100644
index 0000000..0d8a8f4
--- /dev/null
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/geometry/Twist3dTest.cpp
@@ -0,0 +1,131 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <cmath>
+#include <numbers>
+
+#include "frc/geometry/Pose3d.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+TEST(Twist3dTest, StraightX) {
+  const Twist3d straight{5_m, 0_m, 0_m, 0_rad, 0_rad, 0_rad};
+  const auto straightPose = Pose3d{}.Exp(straight);
+
+  Pose3d expected{5_m, 0_m, 0_m, Rotation3d{}};
+  EXPECT_EQ(expected, straightPose);
+}
+
+TEST(Twist3dTest, StraightY) {
+  const Twist3d straight{0_m, 5_m, 0_m, 0_rad, 0_rad, 0_rad};
+  const auto straightPose = Pose3d{}.Exp(straight);
+
+  Pose3d expected{0_m, 5_m, 0_m, Rotation3d{}};
+  EXPECT_EQ(expected, straightPose);
+}
+
+TEST(Twist3dTest, StraightZ) {
+  const Twist3d straight{0_m, 0_m, 5_m, 0_rad, 0_rad, 0_rad};
+  const auto straightPose = Pose3d{}.Exp(straight);
+
+  Pose3d expected{0_m, 0_m, 5_m, Rotation3d{}};
+  EXPECT_EQ(expected, straightPose);
+}
+
+TEST(Twist3dTest, QuarterCircle) {
+  Eigen::Vector3d zAxis{0.0, 0.0, 1.0};
+
+  const Twist3d quarterCircle{
+      5_m / 2.0 * std::numbers::pi,           0_m, 0_m, 0_rad, 0_rad,
+      units::radian_t{std::numbers::pi / 2.0}};
+  const auto quarterCirclePose = Pose3d{}.Exp(quarterCircle);
+
+  Pose3d expected{5_m, 5_m, 0_m, Rotation3d{zAxis, 90_deg}};
+  EXPECT_EQ(expected, quarterCirclePose);
+}
+
+TEST(Twist3dTest, DiagonalNoDtheta) {
+  const Twist3d diagonal{2_m, 2_m, 0_m, 0_rad, 0_rad, 0_rad};
+  const auto diagonalPose = Pose3d{}.Exp(diagonal);
+
+  Pose3d expected{2_m, 2_m, 0_m, Rotation3d{}};
+  EXPECT_EQ(expected, diagonalPose);
+}
+
+TEST(Twist3dTest, Equality) {
+  const Twist3d one{5_m, 1_m, 0_m, 0_rad, 0_rad, 3_rad};
+  const Twist3d two{5_m, 1_m, 0_m, 0_rad, 0_rad, 3_rad};
+  EXPECT_TRUE(one == two);
+}
+
+TEST(Twist3dTest, Inequality) {
+  const Twist3d one{5_m, 1_m, 0_m, 0_rad, 0_rad, 3_rad};
+  const Twist3d two{5_m, 1.2_m, 0_m, 0_rad, 0_rad, 3_rad};
+  EXPECT_TRUE(one != two);
+}
+
+TEST(Twist3dTest, Pose3dLogX) {
+  const Pose3d end{0_m, 5_m, 5_m, Rotation3d{90_deg, 0_deg, 0_deg}};
+  const Pose3d start;
+
+  const auto twist = start.Log(end);
+
+  Twist3d expected{0_m,   units::meter_t{5.0 / 2.0 * std::numbers::pi},
+                   0_m,   90_deg,
+                   0_deg, 0_deg};
+  EXPECT_EQ(expected, twist);
+
+  // Make sure computed twist gives back original end pose
+  const auto reapplied = start.Exp(twist);
+  EXPECT_EQ(end, reapplied);
+}
+
+TEST(Twist3dTest, Pose3dLogY) {
+  const Pose3d end{5_m, 0_m, 5_m, Rotation3d{0_deg, 90_deg, 0_deg}};
+  const Pose3d start;
+
+  const auto twist = start.Log(end);
+
+  Twist3d expected{0_m,   0_m,    units::meter_t{5.0 / 2.0 * std::numbers::pi},
+                   0_deg, 90_deg, 0_deg};
+  EXPECT_EQ(expected, twist);
+
+  // Make sure computed twist gives back original end pose
+  const auto reapplied = start.Exp(twist);
+  EXPECT_EQ(end, reapplied);
+}
+
+TEST(Twist3dTest, Pose3dLogZ) {
+  const Pose3d end{5_m, 5_m, 0_m, Rotation3d{0_deg, 0_deg, 90_deg}};
+  const Pose3d start;
+
+  const auto twist = start.Log(end);
+
+  Twist3d expected{units::meter_t{5.0 / 2.0 * std::numbers::pi},
+                   0_m,
+                   0_m,
+                   0_deg,
+                   0_deg,
+                   90_deg};
+  EXPECT_EQ(expected, twist);
+
+  // Make sure computed twist gives back original end pose
+  const auto reapplied = start.Exp(twist);
+  EXPECT_EQ(end, reapplied);
+}
+
+TEST(Twist3dTest, Constexpr) {
+  constexpr Twist3d defaultCtor;
+  constexpr Twist3d componentCtor{1_m, 2_m, 3_m, 4_rad, 5_rad, 6_rad};
+  constexpr auto multiplied = componentCtor * 2;
+
+  static_assert(defaultCtor.dx == 0_m);
+  static_assert(componentCtor.dy == 2_m);
+  static_assert(componentCtor.dz == 3_m);
+  static_assert(multiplied.dx == 2_m);
+  static_assert(multiplied.rx == 8_rad);
+  static_assert(multiplied.ry == 10_rad);
+  static_assert(multiplied.rz == 12_rad);
+}
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/interpolation/TimeInterpolatableBufferTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/interpolation/TimeInterpolatableBufferTest.cpp
index ee2ec9b..8a920f6 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/interpolation/TimeInterpolatableBufferTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/interpolation/TimeInterpolatableBufferTest.cpp
@@ -13,16 +13,16 @@
 TEST(TimeInterpolatableBufferTest, Interpolation) {
   frc::TimeInterpolatableBuffer<frc::Rotation2d> buffer{10_s};
 
-  buffer.AddSample(0_s, frc::Rotation2d(0_rad));
-  EXPECT_TRUE(buffer.Sample(0_s) == frc::Rotation2d(0_rad));
-  buffer.AddSample(1_s, frc::Rotation2d(1_rad));
-  EXPECT_TRUE(buffer.Sample(0.5_s) == frc::Rotation2d(0.5_rad));
-  EXPECT_TRUE(buffer.Sample(1_s) == frc::Rotation2d(1_rad));
-  buffer.AddSample(3_s, frc::Rotation2d(2_rad));
-  EXPECT_TRUE(buffer.Sample(2_s) == frc::Rotation2d(1.5_rad));
+  buffer.AddSample(0_s, 0_rad);
+  EXPECT_TRUE(buffer.Sample(0_s).value() == 0_rad);
+  buffer.AddSample(1_s, 1_rad);
+  EXPECT_TRUE(buffer.Sample(0.5_s).value() == 0.5_rad);
+  EXPECT_TRUE(buffer.Sample(1_s).value() == 1_rad);
+  buffer.AddSample(3_s, 2_rad);
+  EXPECT_TRUE(buffer.Sample(2_s).value() == 1.5_rad);
 
-  buffer.AddSample(10.5_s, frc::Rotation2d(2_rad));
-  EXPECT_TRUE(buffer.Sample(0_s) == frc::Rotation2d(1_rad));
+  buffer.AddSample(10.5_s, 2_rad);
+  EXPECT_TRUE(buffer.Sample(0_s) == 1_rad);
 }
 
 TEST(TimeInterpolatableBufferTest, Pose2d) {
@@ -30,9 +30,8 @@
   // We expect to be at (1 - 1/std::sqrt(2), 1/std::sqrt(2), 45deg) at t=0.5
   buffer.AddSample(0_s, frc::Pose2d{0_m, 0_m, 90_deg});
   buffer.AddSample(1_s, frc::Pose2d{1_m, 1_m, 0_deg});
-  frc::Pose2d sample = buffer.Sample(0.5_s);
-  EXPECT_TRUE(std::abs(sample.X().to<double>() - (1 - 1 / std::sqrt(2))) <
-              0.01);
-  EXPECT_TRUE(std::abs(sample.Y().to<double>() - (1 / std::sqrt(2))) < 0.01);
-  EXPECT_TRUE(std::abs(sample.Rotation().Degrees().to<double>() - 45) < 0.01);
+  frc::Pose2d sample = buffer.Sample(0.5_s).value();
+  EXPECT_TRUE(std::abs(sample.X().value() - (1 - 1 / std::sqrt(2))) < 0.01);
+  EXPECT_TRUE(std::abs(sample.Y().value() - (1 / std::sqrt(2))) < 0.01);
+  EXPECT_TRUE(std::abs(sample.Rotation().Degrees().value() - 45) < 0.01);
 }
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/kinematics/ChassisSpeedsTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/kinematics/ChassisSpeedsTest.cpp
index 7665a97..4e0b3e5 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/kinematics/ChassisSpeedsTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/kinematics/ChassisSpeedsTest.cpp
@@ -9,7 +9,7 @@
 
 TEST(ChassisSpeedsTest, FieldRelativeConstruction) {
   const auto chassisSpeeds = frc::ChassisSpeeds::FromFieldRelativeSpeeds(
-      1.0_mps, 0.0_mps, 0.5_rad_per_s, frc::Rotation2d(-90.0_deg));
+      1.0_mps, 0.0_mps, 0.5_rad_per_s, -90.0_deg);
 
   EXPECT_NEAR(0.0, chassisSpeeds.vx.value(), kEpsilon);
   EXPECT_NEAR(1.0, chassisSpeeds.vy.value(), kEpsilon);
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/kinematics/DifferentialDriveKinematicsTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/kinematics/DifferentialDriveKinematicsTest.cpp
index 224e231..4af5ac8 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/kinematics/DifferentialDriveKinematicsTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/kinematics/DifferentialDriveKinematicsTest.cpp
@@ -2,7 +2,7 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
-#include <wpi/numbers>
+#include <numbers>
 
 #include "frc/kinematics/ChassisSpeeds.h"
 #include "frc/kinematics/DifferentialDriveKinematics.h"
@@ -56,21 +56,21 @@
 TEST(DifferentialDriveKinematicsTest, InverseKinematicsForRotateInPlace) {
   const DifferentialDriveKinematics kinematics{0.381_m * 2};
   const ChassisSpeeds chassisSpeeds{
-      0.0_mps, 0.0_mps, units::radians_per_second_t{wpi::numbers::pi}};
+      0.0_mps, 0.0_mps, units::radians_per_second_t{std::numbers::pi}};
   const auto wheelSpeeds = kinematics.ToWheelSpeeds(chassisSpeeds);
 
-  EXPECT_NEAR(wheelSpeeds.left.value(), -0.381 * wpi::numbers::pi, kEpsilon);
-  EXPECT_NEAR(wheelSpeeds.right.value(), +0.381 * wpi::numbers::pi, kEpsilon);
+  EXPECT_NEAR(wheelSpeeds.left.value(), -0.381 * std::numbers::pi, kEpsilon);
+  EXPECT_NEAR(wheelSpeeds.right.value(), +0.381 * std::numbers::pi, kEpsilon);
 }
 
 TEST(DifferentialDriveKinematicsTest, ForwardKinematicsForRotateInPlace) {
   const DifferentialDriveKinematics kinematics{0.381_m * 2};
   const DifferentialDriveWheelSpeeds wheelSpeeds{
-      units::meters_per_second_t(+0.381 * wpi::numbers::pi),
-      units::meters_per_second_t(-0.381 * wpi::numbers::pi)};
+      units::meters_per_second_t{+0.381 * std::numbers::pi},
+      units::meters_per_second_t{-0.381 * std::numbers::pi}};
   const auto chassisSpeeds = kinematics.ToChassisSpeeds(wheelSpeeds);
 
   EXPECT_NEAR(chassisSpeeds.vx.value(), 0, kEpsilon);
   EXPECT_NEAR(chassisSpeeds.vy.value(), 0, kEpsilon);
-  EXPECT_NEAR(chassisSpeeds.omega.value(), -wpi::numbers::pi, kEpsilon);
+  EXPECT_NEAR(chassisSpeeds.omega.value(), -std::numbers::pi, kEpsilon);
 }
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/kinematics/DifferentialDriveOdometryTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/kinematics/DifferentialDriveOdometryTest.cpp
index da16b28..e480941 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/kinematics/DifferentialDriveOdometryTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/kinematics/DifferentialDriveOdometryTest.cpp
@@ -2,7 +2,7 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
-#include <wpi/numbers>
+#include <numbers>
 
 #include "frc/kinematics/DifferentialDriveKinematics.h"
 #include "frc/kinematics/DifferentialDriveOdometry.h"
@@ -13,10 +13,10 @@
 using namespace frc;
 
 TEST(DifferentialDriveOdometryTest, EncoderDistances) {
-  DifferentialDriveOdometry odometry{Rotation2d(45_deg)};
+  DifferentialDriveOdometry odometry{45_deg, 0_m, 0_m};
 
-  const auto& pose = odometry.Update(Rotation2d(135_deg), 0_m,
-                                     units::meter_t(5 * wpi::numbers::pi));
+  const auto& pose =
+      odometry.Update(135_deg, 0_m, units::meter_t{5 * std::numbers::pi});
 
   EXPECT_NEAR(pose.X().value(), 5.0, kEpsilon);
   EXPECT_NEAR(pose.Y().value(), 5.0, kEpsilon);
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/kinematics/MecanumDriveKinematicsTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/kinematics/MecanumDriveKinematicsTest.cpp
index 8cc454e..364163e 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/kinematics/MecanumDriveKinematicsTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/kinematics/MecanumDriveKinematicsTest.cpp
@@ -2,7 +2,7 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
-#include <wpi/numbers>
+#include <numbers>
 
 #include "frc/geometry/Translation2d.h"
 #include "frc/kinematics/MecanumDriveKinematics.h"
@@ -40,6 +40,15 @@
   EXPECT_NEAR(0.0, chassisSpeeds.omega.value(), 0.1);
 }
 
+TEST_F(MecanumDriveKinematicsTest, StraightLineForwardKinematicsWithDeltas) {
+  MecanumDriveWheelPositions wheelDeltas{5_m, 5_m, 5_m, 5_m};
+  auto twist = kinematics.ToTwist2d(wheelDeltas);
+
+  EXPECT_NEAR(5.0, twist.dx.value(), 0.1);
+  EXPECT_NEAR(0.0, twist.dy.value(), 0.1);
+  EXPECT_NEAR(0.0, twist.dtheta.value(), 0.1);
+}
+
 TEST_F(MecanumDriveKinematicsTest, StrafeInverseKinematics) {
   ChassisSpeeds speeds{0_mps, 4_mps, 0_rad_per_s};
   auto moduleStates = kinematics.ToWheelSpeeds(speeds);
@@ -59,9 +68,18 @@
   EXPECT_NEAR(0.0, chassisSpeeds.omega.value(), 0.1);
 }
 
+TEST_F(MecanumDriveKinematicsTest, StrafeForwardKinematicsWithDeltas) {
+  MecanumDriveWheelPositions wheelDeltas{-5_m, 5_m, 5_m, -5_m};
+  auto twist = kinematics.ToTwist2d(wheelDeltas);
+
+  EXPECT_NEAR(0.0, twist.dx.value(), 0.1);
+  EXPECT_NEAR(5.0, twist.dy.value(), 0.1);
+  EXPECT_NEAR(0.0, twist.dtheta.value(), 0.1);
+}
+
 TEST_F(MecanumDriveKinematicsTest, RotationInverseKinematics) {
   ChassisSpeeds speeds{0_mps, 0_mps,
-                       units::radians_per_second_t(2 * wpi::numbers::pi)};
+                       units::radians_per_second_t{2 * std::numbers::pi}};
   auto moduleStates = kinematics.ToWheelSpeeds(speeds);
 
   EXPECT_NEAR(-150.79644737, moduleStates.frontLeft.value(), 0.1);
@@ -77,7 +95,17 @@
 
   EXPECT_NEAR(0.0, chassisSpeeds.vx.value(), 0.1);
   EXPECT_NEAR(0.0, chassisSpeeds.vy.value(), 0.1);
-  EXPECT_NEAR(2 * wpi::numbers::pi, chassisSpeeds.omega.value(), 0.1);
+  EXPECT_NEAR(2 * std::numbers::pi, chassisSpeeds.omega.value(), 0.1);
+}
+
+TEST_F(MecanumDriveKinematicsTest, RotationForwardKinematicsWithDeltas) {
+  MecanumDriveWheelPositions wheelDeltas{-150.79644737_m, 150.79644737_m,
+                                         -150.79644737_m, 150.79644737_m};
+  auto twist = kinematics.ToTwist2d(wheelDeltas);
+
+  EXPECT_NEAR(0.0, twist.dx.value(), 0.1);
+  EXPECT_NEAR(0.0, twist.dy.value(), 0.1);
+  EXPECT_NEAR(2 * std::numbers::pi, twist.dtheta.value(), 0.1);
 }
 
 TEST_F(MecanumDriveKinematicsTest, MixedRotationTranslationInverseKinematics) {
@@ -101,6 +129,18 @@
   EXPECT_NEAR(0.707, chassisSpeeds.omega.value(), 0.1);
 }
 
+TEST_F(MecanumDriveKinematicsTest,
+       MixedRotationTranslationForwardKinematicsWithDeltas) {
+  MecanumDriveWheelPositions wheelDeltas{-17.677670_m, 20.506097_m, -13.435_m,
+                                         16.26_m};
+
+  auto twist = kinematics.ToTwist2d(wheelDeltas);
+
+  EXPECT_NEAR(1.41335, twist.dx.value(), 0.1);
+  EXPECT_NEAR(2.1221, twist.dy.value(), 0.1);
+  EXPECT_NEAR(0.707, twist.dtheta.value(), 0.1);
+}
+
 TEST_F(MecanumDriveKinematicsTest, OffCenterRotationInverseKinematics) {
   ChassisSpeeds speeds{0_mps, 0_mps, 1_rad_per_s};
   auto moduleStates = kinematics.ToWheelSpeeds(speeds, m_fl);
@@ -122,6 +162,16 @@
 }
 
 TEST_F(MecanumDriveKinematicsTest,
+       OffCenterRotationForwardKinematicsWithDeltas) {
+  MecanumDriveWheelPositions wheelDeltas{0_m, 16.971_m, -16.971_m, 33.941_m};
+  auto twist = kinematics.ToTwist2d(wheelDeltas);
+
+  EXPECT_NEAR(8.48525, twist.dx.value(), 0.1);
+  EXPECT_NEAR(-8.48525, twist.dy.value(), 0.1);
+  EXPECT_NEAR(0.707, twist.dtheta.value(), 0.1);
+}
+
+TEST_F(MecanumDriveKinematicsTest,
        OffCenterTranslationRotationInverseKinematics) {
   ChassisSpeeds speeds{5_mps, 2_mps, 1_rad_per_s};
   auto moduleStates = kinematics.ToWheelSpeeds(speeds, m_fl);
@@ -143,6 +193,16 @@
   EXPECT_NEAR(0.707, chassisSpeeds.omega.value(), 0.1);
 }
 
+TEST_F(MecanumDriveKinematicsTest,
+       OffCenterTranslationRotationForwardKinematicsWithDeltas) {
+  MecanumDriveWheelPositions wheelDeltas{2.12_m, 21.92_m, -12.02_m, 36.06_m};
+  auto twist = kinematics.ToTwist2d(wheelDeltas);
+
+  EXPECT_NEAR(12.02, twist.dx.value(), 0.1);
+  EXPECT_NEAR(-7.07, twist.dy.value(), 0.1);
+  EXPECT_NEAR(0.707, twist.dtheta.value(), 0.1);
+}
+
 TEST_F(MecanumDriveKinematicsTest, Desaturate) {
   MecanumDriveWheelSpeeds wheelSpeeds{5_mps, 6_mps, 4_mps, 7_mps};
   wheelSpeeds.Desaturate(5.5_mps);
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/kinematics/MecanumDriveOdometryTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/kinematics/MecanumDriveOdometryTest.cpp
index 152506d..bfaf91b 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/kinematics/MecanumDriveOdometryTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/kinematics/MecanumDriveOdometryTest.cpp
@@ -2,7 +2,11 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
+#include <limits>
+#include <random>
+
 #include "frc/kinematics/MecanumDriveOdometry.h"
+#include "frc/trajectory/TrajectoryGenerator.h"
 #include "gtest/gtest.h"
 
 using namespace frc;
@@ -14,17 +18,19 @@
   Translation2d m_bl{-12_m, 12_m};
   Translation2d m_br{-12_m, -12_m};
 
+  MecanumDriveWheelPositions zero;
+
   MecanumDriveKinematics kinematics{m_fl, m_fr, m_bl, m_br};
-  MecanumDriveOdometry odometry{kinematics, 0_rad};
+  MecanumDriveOdometry odometry{kinematics, 0_rad, zero};
 };
 
 TEST_F(MecanumDriveOdometryTest, MultipleConsecutiveUpdates) {
-  odometry.ResetPosition(Pose2d(), 0_rad);
-  MecanumDriveWheelSpeeds wheelSpeeds{3.536_mps, 3.536_mps, 3.536_mps,
-                                      3.536_mps};
+  MecanumDriveWheelPositions wheelDeltas{3.536_m, 3.536_m, 3.536_m, 3.536_m};
 
-  odometry.UpdateWithTime(0_s, Rotation2d(), wheelSpeeds);
-  auto secondPose = odometry.UpdateWithTime(0.0_s, Rotation2d(), wheelSpeeds);
+  odometry.ResetPosition(0_rad, wheelDeltas, Pose2d{});
+
+  odometry.Update(0_deg, wheelDeltas);
+  auto secondPose = odometry.Update(0_deg, wheelDeltas);
 
   EXPECT_NEAR(secondPose.X().value(), 0.0, 0.01);
   EXPECT_NEAR(secondPose.Y().value(), 0.0, 0.01);
@@ -32,11 +38,12 @@
 }
 
 TEST_F(MecanumDriveOdometryTest, TwoIterations) {
-  odometry.ResetPosition(Pose2d(), 0_rad);
-  MecanumDriveWheelSpeeds speeds{3.536_mps, 3.536_mps, 3.536_mps, 3.536_mps};
+  odometry.ResetPosition(0_rad, zero, Pose2d{});
+  MecanumDriveWheelPositions wheelDeltas{0.3536_m, 0.3536_m, 0.3536_m,
+                                         0.3536_m};
 
-  odometry.UpdateWithTime(0_s, Rotation2d(), MecanumDriveWheelSpeeds{});
-  auto pose = odometry.UpdateWithTime(0.10_s, Rotation2d(), speeds);
+  odometry.Update(0_deg, MecanumDriveWheelPositions{});
+  auto pose = odometry.Update(0_deg, wheelDeltas);
 
   EXPECT_NEAR(pose.X().value(), 0.3536, 0.01);
   EXPECT_NEAR(pose.Y().value(), 0.0, 0.01);
@@ -44,11 +51,11 @@
 }
 
 TEST_F(MecanumDriveOdometryTest, 90DegreeTurn) {
-  odometry.ResetPosition(Pose2d(), 0_rad);
-  MecanumDriveWheelSpeeds speeds{-13.328_mps, 39.986_mps, -13.329_mps,
-                                 39.986_mps};
-  odometry.UpdateWithTime(0_s, Rotation2d(), MecanumDriveWheelSpeeds{});
-  auto pose = odometry.UpdateWithTime(1_s, Rotation2d(90_deg), speeds);
+  odometry.ResetPosition(0_rad, zero, Pose2d{});
+  MecanumDriveWheelPositions wheelDeltas{-13.328_m, 39.986_m, -13.329_m,
+                                         39.986_m};
+  odometry.Update(0_deg, MecanumDriveWheelPositions{});
+  auto pose = odometry.Update(90_deg, wheelDeltas);
 
   EXPECT_NEAR(pose.X().value(), 8.4855, 0.01);
   EXPECT_NEAR(pose.Y().value(), 8.4855, 0.01);
@@ -56,14 +63,140 @@
 }
 
 TEST_F(MecanumDriveOdometryTest, GyroAngleReset) {
-  odometry.ResetPosition(Pose2d(), Rotation2d(90_deg));
+  odometry.ResetPosition(90_deg, zero, Pose2d{});
 
-  MecanumDriveWheelSpeeds speeds{3.536_mps, 3.536_mps, 3.536_mps, 3.536_mps};
+  MecanumDriveWheelPositions wheelDeltas{0.3536_m, 0.3536_m, 0.3536_m,
+                                         0.3536_m};
 
-  odometry.UpdateWithTime(0_s, Rotation2d(90_deg), MecanumDriveWheelSpeeds{});
-  auto pose = odometry.UpdateWithTime(0.10_s, Rotation2d(90_deg), speeds);
+  odometry.Update(90_deg, MecanumDriveWheelPositions{});
+  auto pose = odometry.Update(90_deg, wheelDeltas);
 
   EXPECT_NEAR(pose.X().value(), 0.3536, 0.01);
   EXPECT_NEAR(pose.Y().value(), 0.0, 0.01);
   EXPECT_NEAR(pose.Rotation().Radians().value(), 0.0, 0.01);
 }
+
+TEST_F(MecanumDriveOdometryTest, AccuracyFacingTrajectory) {
+  frc::MecanumDriveKinematics kinematics{
+      frc::Translation2d{1_m, 1_m}, frc::Translation2d{1_m, -1_m},
+      frc::Translation2d{-1_m, -1_m}, frc::Translation2d{-1_m, 1_m}};
+
+  frc::MecanumDriveWheelPositions wheelPositions;
+
+  frc::MecanumDriveOdometry odometry{kinematics, frc::Rotation2d{},
+                                     wheelPositions, frc::Pose2d{}};
+
+  frc::Trajectory trajectory = frc::TrajectoryGenerator::GenerateTrajectory(
+      std::vector{frc::Pose2d{0_m, 0_m, 45_deg}, frc::Pose2d{3_m, 0_m, -90_deg},
+                  frc::Pose2d{0_m, 0_m, 135_deg},
+                  frc::Pose2d{-3_m, 0_m, -90_deg},
+                  frc::Pose2d{0_m, 0_m, 45_deg}},
+      frc::TrajectoryConfig(5.0_mps, 2.0_mps_sq));
+
+  std::default_random_engine generator;
+  std::normal_distribution<double> distribution(0.0, 1.0);
+
+  units::second_t dt = 0.02_s;
+  units::second_t t = 0_s;
+
+  double maxError = -std::numeric_limits<double>::max();
+  double errorSum = 0;
+
+  while (t < trajectory.TotalTime()) {
+    frc::Trajectory::State groundTruthState = trajectory.Sample(t);
+
+    auto wheelSpeeds = kinematics.ToWheelSpeeds(
+        {groundTruthState.velocity, 0_mps,
+         groundTruthState.velocity * groundTruthState.curvature});
+
+    wheelSpeeds.frontLeft += distribution(generator) * 0.1_mps;
+    wheelSpeeds.frontRight += distribution(generator) * 0.1_mps;
+    wheelSpeeds.rearLeft += distribution(generator) * 0.1_mps;
+    wheelSpeeds.rearRight += distribution(generator) * 0.1_mps;
+
+    wheelPositions.frontLeft += wheelSpeeds.frontLeft * dt;
+    wheelPositions.frontRight += wheelSpeeds.frontRight * dt;
+    wheelPositions.rearLeft += wheelSpeeds.rearLeft * dt;
+    wheelPositions.rearRight += wheelSpeeds.rearRight * dt;
+
+    auto xhat =
+        odometry.Update(groundTruthState.pose.Rotation() +
+                            frc::Rotation2d{distribution(generator) * 0.05_rad},
+                        wheelPositions);
+    double error = groundTruthState.pose.Translation()
+                       .Distance(xhat.Translation())
+                       .value();
+
+    if (error > maxError) {
+      maxError = error;
+    }
+    errorSum += error;
+
+    t += dt;
+  }
+
+  EXPECT_LT(errorSum / (trajectory.TotalTime().value() / dt.value()), 0.06);
+  EXPECT_LT(maxError, 0.125);
+}
+
+TEST_F(MecanumDriveOdometryTest, AccuracyFacingXAxis) {
+  frc::MecanumDriveKinematics kinematics{
+      frc::Translation2d{1_m, 1_m}, frc::Translation2d{1_m, -1_m},
+      frc::Translation2d{-1_m, -1_m}, frc::Translation2d{-1_m, 1_m}};
+
+  frc::MecanumDriveWheelPositions wheelPositions;
+
+  frc::MecanumDriveOdometry odometry{kinematics, frc::Rotation2d{},
+                                     wheelPositions, frc::Pose2d{}};
+
+  frc::Trajectory trajectory = frc::TrajectoryGenerator::GenerateTrajectory(
+      std::vector{frc::Pose2d{0_m, 0_m, 45_deg}, frc::Pose2d{3_m, 0_m, -90_deg},
+                  frc::Pose2d{0_m, 0_m, 135_deg},
+                  frc::Pose2d{-3_m, 0_m, -90_deg},
+                  frc::Pose2d{0_m, 0_m, 45_deg}},
+      frc::TrajectoryConfig(5.0_mps, 2.0_mps_sq));
+
+  std::default_random_engine generator;
+  std::normal_distribution<double> distribution(0.0, 1.0);
+
+  units::second_t dt = 0.02_s;
+  units::second_t t = 0_s;
+
+  double maxError = -std::numeric_limits<double>::max();
+  double errorSum = 0;
+
+  while (t < trajectory.TotalTime()) {
+    frc::Trajectory::State groundTruthState = trajectory.Sample(t);
+
+    auto wheelSpeeds = kinematics.ToWheelSpeeds(
+        {groundTruthState.velocity * groundTruthState.pose.Rotation().Cos(),
+         groundTruthState.velocity * groundTruthState.pose.Rotation().Sin(),
+         0_rad_per_s});
+
+    wheelSpeeds.frontLeft += distribution(generator) * 0.1_mps;
+    wheelSpeeds.frontRight += distribution(generator) * 0.1_mps;
+    wheelSpeeds.rearLeft += distribution(generator) * 0.1_mps;
+    wheelSpeeds.rearRight += distribution(generator) * 0.1_mps;
+
+    wheelPositions.frontLeft += wheelSpeeds.frontLeft * dt;
+    wheelPositions.frontRight += wheelSpeeds.frontRight * dt;
+    wheelPositions.rearLeft += wheelSpeeds.rearLeft * dt;
+    wheelPositions.rearRight += wheelSpeeds.rearRight * dt;
+
+    auto xhat = odometry.Update(
+        frc::Rotation2d{distribution(generator) * 0.05_rad}, wheelPositions);
+    double error = groundTruthState.pose.Translation()
+                       .Distance(xhat.Translation())
+                       .value();
+
+    if (error > maxError) {
+      maxError = error;
+    }
+    errorSum += error;
+
+    t += dt;
+  }
+
+  EXPECT_LT(errorSum / (trajectory.TotalTime().value() / dt.value()), 0.06);
+  EXPECT_LT(maxError, 0.125);
+}
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/kinematics/SwerveDriveKinematicsTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/kinematics/SwerveDriveKinematicsTest.cpp
index 55ebdcf..8e0dc8f 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/kinematics/SwerveDriveKinematicsTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/kinematics/SwerveDriveKinematicsTest.cpp
@@ -2,7 +2,7 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
-#include <wpi/numbers>
+#include <numbers>
 
 #include "frc/geometry/Translation2d.h"
 #include "frc/kinematics/SwerveDriveKinematics.h"
@@ -40,7 +40,7 @@
 }
 
 TEST_F(SwerveDriveKinematicsTest, StraightLineForwardKinematics) {
-  SwerveModuleState state{5.0_mps, Rotation2d()};
+  SwerveModuleState state{5.0_mps, 0_deg};
 
   auto chassisSpeeds = m_kinematics.ToChassisSpeeds(state, state, state, state);
 
@@ -49,6 +49,16 @@
   EXPECT_NEAR(chassisSpeeds.omega.value(), 0.0, kEpsilon);
 }
 
+TEST_F(SwerveDriveKinematicsTest, StraightLineForwardKinematicsWithDeltas) {
+  SwerveModulePosition delta{5.0_m, 0_deg};
+
+  auto twist = m_kinematics.ToTwist2d(delta, delta, delta, delta);
+
+  EXPECT_NEAR(twist.dx.value(), 5.0, kEpsilon);
+  EXPECT_NEAR(twist.dy.value(), 0.0, kEpsilon);
+  EXPECT_NEAR(twist.dtheta.value(), 0.0, kEpsilon);
+}
+
 TEST_F(SwerveDriveKinematicsTest, StraightStrafeInverseKinematics) {
   ChassisSpeeds speeds{0_mps, 5_mps, 0_rad_per_s};
   auto [fl, fr, bl, br] = m_kinematics.ToSwerveModuleStates(speeds);
@@ -65,7 +75,7 @@
 }
 
 TEST_F(SwerveDriveKinematicsTest, StraightStrafeForwardKinematics) {
-  SwerveModuleState state{5_mps, Rotation2d(90_deg)};
+  SwerveModuleState state{5_mps, 90_deg};
   auto chassisSpeeds = m_kinematics.ToChassisSpeeds(state, state, state, state);
 
   EXPECT_NEAR(chassisSpeeds.vx.value(), 0.0, kEpsilon);
@@ -73,9 +83,19 @@
   EXPECT_NEAR(chassisSpeeds.omega.value(), 0.0, kEpsilon);
 }
 
+TEST_F(SwerveDriveKinematicsTest, StraightStrafeForwardKinematicsWithDeltas) {
+  SwerveModulePosition delta{5_m, 90_deg};
+
+  auto twist = m_kinematics.ToTwist2d(delta, delta, delta, delta);
+
+  EXPECT_NEAR(twist.dx.value(), 0.0, kEpsilon);
+  EXPECT_NEAR(twist.dy.value(), 5.0, kEpsilon);
+  EXPECT_NEAR(twist.dtheta.value(), 0.0, kEpsilon);
+}
+
 TEST_F(SwerveDriveKinematicsTest, TurnInPlaceInverseKinematics) {
   ChassisSpeeds speeds{0_mps, 0_mps,
-                       units::radians_per_second_t(2 * wpi::numbers::pi)};
+                       units::radians_per_second_t{2 * std::numbers::pi}};
   auto [fl, fr, bl, br] = m_kinematics.ToSwerveModuleStates(speeds);
 
   EXPECT_NEAR(fl.speed.value(), 106.63, kEpsilon);
@@ -89,22 +109,52 @@
   EXPECT_NEAR(br.angle.Degrees().value(), -45.0, kEpsilon);
 }
 
+TEST_F(SwerveDriveKinematicsTest, ConserveWheelAngle) {
+  ChassisSpeeds speeds{0_mps, 0_mps,
+                       units::radians_per_second_t{2 * std::numbers::pi}};
+  m_kinematics.ToSwerveModuleStates(speeds);
+  auto [fl, fr, bl, br] = m_kinematics.ToSwerveModuleStates(ChassisSpeeds{});
+
+  EXPECT_NEAR(fl.speed.value(), 0.0, kEpsilon);
+  EXPECT_NEAR(fr.speed.value(), 0.0, kEpsilon);
+  EXPECT_NEAR(bl.speed.value(), 0.0, kEpsilon);
+  EXPECT_NEAR(br.speed.value(), 0.0, kEpsilon);
+
+  EXPECT_NEAR(fl.angle.Degrees().value(), 135.0, kEpsilon);
+  EXPECT_NEAR(fr.angle.Degrees().value(), 45.0, kEpsilon);
+  EXPECT_NEAR(bl.angle.Degrees().value(), -135.0, kEpsilon);
+  EXPECT_NEAR(br.angle.Degrees().value(), -45.0, kEpsilon);
+}
+
 TEST_F(SwerveDriveKinematicsTest, TurnInPlaceForwardKinematics) {
-  SwerveModuleState fl{106.629_mps, Rotation2d(135_deg)};
-  SwerveModuleState fr{106.629_mps, Rotation2d(45_deg)};
-  SwerveModuleState bl{106.629_mps, Rotation2d(-135_deg)};
-  SwerveModuleState br{106.629_mps, Rotation2d(-45_deg)};
+  SwerveModuleState fl{106.629_mps, 135_deg};
+  SwerveModuleState fr{106.629_mps, 45_deg};
+  SwerveModuleState bl{106.629_mps, -135_deg};
+  SwerveModuleState br{106.629_mps, -45_deg};
 
   auto chassisSpeeds = m_kinematics.ToChassisSpeeds(fl, fr, bl, br);
 
   EXPECT_NEAR(chassisSpeeds.vx.value(), 0.0, kEpsilon);
   EXPECT_NEAR(chassisSpeeds.vy.value(), 0.0, kEpsilon);
-  EXPECT_NEAR(chassisSpeeds.omega.value(), 2 * wpi::numbers::pi, kEpsilon);
+  EXPECT_NEAR(chassisSpeeds.omega.value(), 2 * std::numbers::pi, kEpsilon);
+}
+
+TEST_F(SwerveDriveKinematicsTest, TurnInPlaceForwardKinematicsWithDeltas) {
+  SwerveModulePosition fl{106.629_m, 135_deg};
+  SwerveModulePosition fr{106.629_m, 45_deg};
+  SwerveModulePosition bl{106.629_m, -135_deg};
+  SwerveModulePosition br{106.629_m, -45_deg};
+
+  auto twist = m_kinematics.ToTwist2d(fl, fr, bl, br);
+
+  EXPECT_NEAR(twist.dx.value(), 0.0, kEpsilon);
+  EXPECT_NEAR(twist.dy.value(), 0.0, kEpsilon);
+  EXPECT_NEAR(twist.dtheta.value(), 2 * std::numbers::pi, kEpsilon);
 }
 
 TEST_F(SwerveDriveKinematicsTest, OffCenterCORRotationInverseKinematics) {
   ChassisSpeeds speeds{0_mps, 0_mps,
-                       units::radians_per_second_t(2 * wpi::numbers::pi)};
+                       units::radians_per_second_t{2 * std::numbers::pi}};
   auto [fl, fr, bl, br] = m_kinematics.ToSwerveModuleStates(speeds, m_fl);
 
   EXPECT_NEAR(fl.speed.value(), 0.0, kEpsilon);
@@ -119,23 +169,37 @@
 }
 
 TEST_F(SwerveDriveKinematicsTest, OffCenterCORRotationForwardKinematics) {
-  SwerveModuleState fl{0.0_mps, Rotation2d(0_deg)};
-  SwerveModuleState fr{150.796_mps, Rotation2d(0_deg)};
-  SwerveModuleState bl{150.796_mps, Rotation2d(-90_deg)};
-  SwerveModuleState br{213.258_mps, Rotation2d(-45_deg)};
+  SwerveModuleState fl{0.0_mps, 0_deg};
+  SwerveModuleState fr{150.796_mps, 0_deg};
+  SwerveModuleState bl{150.796_mps, -90_deg};
+  SwerveModuleState br{213.258_mps, -45_deg};
 
   auto chassisSpeeds = m_kinematics.ToChassisSpeeds(fl, fr, bl, br);
 
   EXPECT_NEAR(chassisSpeeds.vx.value(), 75.398, kEpsilon);
   EXPECT_NEAR(chassisSpeeds.vy.value(), -75.398, kEpsilon);
-  EXPECT_NEAR(chassisSpeeds.omega.value(), 2 * wpi::numbers::pi, kEpsilon);
+  EXPECT_NEAR(chassisSpeeds.omega.value(), 2 * std::numbers::pi, kEpsilon);
+}
+
+TEST_F(SwerveDriveKinematicsTest,
+       OffCenterCORRotationForwardKinematicsWithDeltas) {
+  SwerveModulePosition fl{0.0_m, 0_deg};
+  SwerveModulePosition fr{150.796_m, 0_deg};
+  SwerveModulePosition bl{150.796_m, -90_deg};
+  SwerveModulePosition br{213.258_m, -45_deg};
+
+  auto twist = m_kinematics.ToTwist2d(fl, fr, bl, br);
+
+  EXPECT_NEAR(twist.dx.value(), 75.398, kEpsilon);
+  EXPECT_NEAR(twist.dy.value(), -75.398, kEpsilon);
+  EXPECT_NEAR(twist.dtheta.value(), 2 * std::numbers::pi, kEpsilon);
 }
 
 TEST_F(SwerveDriveKinematicsTest,
        OffCenterCORRotationAndTranslationInverseKinematics) {
   ChassisSpeeds speeds{0_mps, 3.0_mps, 1.5_rad_per_s};
   auto [fl, fr, bl, br] =
-      m_kinematics.ToSwerveModuleStates(speeds, Translation2d(24_m, 0_m));
+      m_kinematics.ToSwerveModuleStates(speeds, Translation2d{24_m, 0_m});
 
   EXPECT_NEAR(fl.speed.value(), 23.43, kEpsilon);
   EXPECT_NEAR(fr.speed.value(), 23.43, kEpsilon);
@@ -150,10 +214,10 @@
 
 TEST_F(SwerveDriveKinematicsTest,
        OffCenterCORRotationAndTranslationForwardKinematics) {
-  SwerveModuleState fl{23.43_mps, Rotation2d(-140.19_deg)};
-  SwerveModuleState fr{23.43_mps, Rotation2d(-39.81_deg)};
-  SwerveModuleState bl{54.08_mps, Rotation2d(-109.44_deg)};
-  SwerveModuleState br{54.08_mps, Rotation2d(-70.56_deg)};
+  SwerveModuleState fl{23.43_mps, -140.19_deg};
+  SwerveModuleState fr{23.43_mps, -39.81_deg};
+  SwerveModuleState bl{54.08_mps, -109.44_deg};
+  SwerveModuleState br{54.08_mps, -70.56_deg};
 
   auto chassisSpeeds = m_kinematics.ToChassisSpeeds(fl, fr, bl, br);
 
@@ -162,11 +226,25 @@
   EXPECT_NEAR(chassisSpeeds.omega.value(), 1.5, kEpsilon);
 }
 
+TEST_F(SwerveDriveKinematicsTest,
+       OffCenterCORRotationAndTranslationForwardKinematicsWithDeltas) {
+  SwerveModulePosition fl{23.43_m, -140.19_deg};
+  SwerveModulePosition fr{23.43_m, -39.81_deg};
+  SwerveModulePosition bl{54.08_m, -109.44_deg};
+  SwerveModulePosition br{54.08_m, -70.56_deg};
+
+  auto twist = m_kinematics.ToTwist2d(fl, fr, bl, br);
+
+  EXPECT_NEAR(twist.dx.value(), 0.0, kEpsilon);
+  EXPECT_NEAR(twist.dy.value(), -33.0, kEpsilon);
+  EXPECT_NEAR(twist.dtheta.value(), 1.5, kEpsilon);
+}
+
 TEST_F(SwerveDriveKinematicsTest, Desaturate) {
-  SwerveModuleState state1{5.0_mps, Rotation2d()};
-  SwerveModuleState state2{6.0_mps, Rotation2d()};
-  SwerveModuleState state3{4.0_mps, Rotation2d()};
-  SwerveModuleState state4{7.0_mps, Rotation2d()};
+  SwerveModuleState state1{5.0_mps, 0_deg};
+  SwerveModuleState state2{6.0_mps, 0_deg};
+  SwerveModuleState state3{4.0_mps, 0_deg};
+  SwerveModuleState state4{7.0_mps, 0_deg};
 
   wpi::array<SwerveModuleState, 4> arr{state1, state2, state3, state4};
   SwerveDriveKinematics<4>::DesaturateWheelSpeeds(&arr, 5.5_mps);
@@ -178,3 +256,21 @@
   EXPECT_NEAR(arr[2].speed.value(), 4.0 * kFactor, kEpsilon);
   EXPECT_NEAR(arr[3].speed.value(), 7.0 * kFactor, kEpsilon);
 }
+
+TEST_F(SwerveDriveKinematicsTest, DesaturateSmooth) {
+  SwerveModuleState state1{5.0_mps, 0_deg};
+  SwerveModuleState state2{6.0_mps, 0_deg};
+  SwerveModuleState state3{4.0_mps, 0_deg};
+  SwerveModuleState state4{7.0_mps, 0_deg};
+
+  wpi::array<SwerveModuleState, 4> arr{state1, state2, state3, state4};
+  SwerveDriveKinematics<4>::DesaturateWheelSpeeds(
+      &arr, m_kinematics.ToChassisSpeeds(arr), 5.5_mps, 5.5_mps, 3.5_rad_per_s);
+
+  double kFactor = 5.5 / 7.0;
+
+  EXPECT_NEAR(arr[0].speed.value(), 5.0 * kFactor, kEpsilon);
+  EXPECT_NEAR(arr[1].speed.value(), 6.0 * kFactor, kEpsilon);
+  EXPECT_NEAR(arr[2].speed.value(), 4.0 * kFactor, kEpsilon);
+  EXPECT_NEAR(arr[3].speed.value(), 7.0 * kFactor, kEpsilon);
+}
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/kinematics/SwerveDriveOdometryTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/kinematics/SwerveDriveOdometryTest.cpp
index 27d2a6e..8c67ab5 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/kinematics/SwerveDriveOdometryTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/kinematics/SwerveDriveOdometryTest.cpp
@@ -2,8 +2,14 @@
 // Open Source Software; you can modify and/or share it under the terms of
 // the WPILib BSD license file in the root directory of this project.
 
+#include <limits>
+#include <random>
+
 #include "frc/kinematics/SwerveDriveKinematics.h"
 #include "frc/kinematics/SwerveDriveOdometry.h"
+#include "frc/trajectory/Trajectory.h"
+#include "frc/trajectory/TrajectoryConfig.h"
+#include "frc/trajectory/TrajectoryGenerator.h"
 #include "gtest/gtest.h"
 
 using namespace frc;
@@ -18,18 +24,20 @@
   Translation2d m_br{-12_m, -12_m};
 
   SwerveDriveKinematics<4> m_kinematics{m_fl, m_fr, m_bl, m_br};
-  SwerveDriveOdometry<4> m_odometry{m_kinematics, 0_rad};
+  SwerveModulePosition zero;
+  SwerveDriveOdometry<4> m_odometry{
+      m_kinematics, 0_rad, {zero, zero, zero, zero}};
 };
 
 TEST_F(SwerveDriveOdometryTest, TwoIterations) {
-  SwerveModuleState state{5_mps, Rotation2d()};
+  SwerveModulePosition position{0.5_m, 0_deg};
 
-  m_odometry.ResetPosition(Pose2d(), 0_rad);
-  m_odometry.UpdateWithTime(0_s, Rotation2d(), SwerveModuleState(),
-                            SwerveModuleState(), SwerveModuleState(),
-                            SwerveModuleState());
-  auto pose = m_odometry.UpdateWithTime(0.1_s, Rotation2d(), state, state,
-                                        state, state);
+  m_odometry.ResetPosition(0_rad, {zero, zero, zero, zero}, Pose2d{});
+
+  m_odometry.Update(0_deg, {zero, zero, zero, zero});
+
+  auto pose =
+      m_odometry.Update(0_deg, {position, position, position, position});
 
   EXPECT_NEAR(0.5, pose.X().value(), kEpsilon);
   EXPECT_NEAR(0.0, pose.Y().value(), kEpsilon);
@@ -37,17 +45,13 @@
 }
 
 TEST_F(SwerveDriveOdometryTest, 90DegreeTurn) {
-  SwerveModuleState fl{18.85_mps, Rotation2d(90_deg)};
-  SwerveModuleState fr{42.15_mps, Rotation2d(26.565_deg)};
-  SwerveModuleState bl{18.85_mps, Rotation2d(-90_deg)};
-  SwerveModuleState br{42.15_mps, Rotation2d(-26.565_deg)};
+  SwerveModulePosition fl{18.85_m, 90_deg};
+  SwerveModulePosition fr{42.15_m, 26.565_deg};
+  SwerveModulePosition bl{18.85_m, -90_deg};
+  SwerveModulePosition br{42.15_m, -26.565_deg};
 
-  SwerveModuleState zero{0_mps, Rotation2d()};
-
-  m_odometry.ResetPosition(Pose2d(), 0_rad);
-  m_odometry.UpdateWithTime(0_s, Rotation2d(), zero, zero, zero, zero);
-  auto pose =
-      m_odometry.UpdateWithTime(1_s, Rotation2d(90_deg), fl, fr, bl, br);
+  m_odometry.ResetPosition(0_rad, {zero, zero, zero, zero}, Pose2d{});
+  auto pose = m_odometry.Update(90_deg, {fl, fr, bl, br});
 
   EXPECT_NEAR(12.0, pose.X().value(), kEpsilon);
   EXPECT_NEAR(12.0, pose.Y().value(), kEpsilon);
@@ -55,17 +59,140 @@
 }
 
 TEST_F(SwerveDriveOdometryTest, GyroAngleReset) {
-  m_odometry.ResetPosition(Pose2d(), Rotation2d(90_deg));
+  m_odometry.ResetPosition(90_deg, {zero, zero, zero, zero}, Pose2d{});
 
-  SwerveModuleState state{5_mps, Rotation2d()};
+  SwerveModulePosition position{0.5_m, 0_deg};
 
-  m_odometry.UpdateWithTime(0_s, Rotation2d(90_deg), SwerveModuleState(),
-                            SwerveModuleState(), SwerveModuleState(),
-                            SwerveModuleState());
-  auto pose = m_odometry.UpdateWithTime(0.1_s, Rotation2d(90_deg), state, state,
-                                        state, state);
+  auto pose =
+      m_odometry.Update(90_deg, {position, position, position, position});
 
   EXPECT_NEAR(0.5, pose.X().value(), kEpsilon);
   EXPECT_NEAR(0.0, pose.Y().value(), kEpsilon);
   EXPECT_NEAR(0.0, pose.Rotation().Degrees().value(), kEpsilon);
 }
+
+TEST_F(SwerveDriveOdometryTest, AccuracyFacingTrajectory) {
+  SwerveDriveKinematics<4> kinematics{
+      Translation2d{1_m, 1_m}, Translation2d{1_m, -1_m},
+      Translation2d{-1_m, -1_m}, Translation2d{-1_m, 1_m}};
+
+  SwerveDriveOdometry<4> odometry{kinematics, 0_rad, {zero, zero, zero, zero}};
+
+  SwerveModulePosition fl;
+  SwerveModulePosition fr;
+  SwerveModulePosition bl;
+  SwerveModulePosition br;
+
+  Trajectory trajectory = TrajectoryGenerator::GenerateTrajectory(
+      std::vector{Pose2d{0_m, 0_m, 45_deg}, Pose2d{3_m, 0_m, -90_deg},
+                  Pose2d{0_m, 0_m, 135_deg}, Pose2d{-3_m, 0_m, -90_deg},
+                  Pose2d{0_m, 0_m, 45_deg}},
+      TrajectoryConfig(5.0_mps, 2.0_mps_sq));
+
+  std::default_random_engine generator;
+  std::normal_distribution<double> distribution(0.0, 1.0);
+
+  units::second_t dt = 0.02_s;
+  units::second_t t = 0_s;
+
+  double maxError = -std::numeric_limits<double>::max();
+  double errorSum = 0;
+
+  while (t < trajectory.TotalTime()) {
+    Trajectory::State groundTruthState = trajectory.Sample(t);
+
+    auto moduleStates = kinematics.ToSwerveModuleStates(
+        {groundTruthState.velocity, 0_mps,
+         groundTruthState.velocity * groundTruthState.curvature});
+
+    fl.distance += moduleStates[0].speed * dt;
+    fr.distance += moduleStates[1].speed * dt;
+    bl.distance += moduleStates[2].speed * dt;
+    br.distance += moduleStates[3].speed * dt;
+
+    fl.angle = moduleStates[0].angle;
+    fr.angle = moduleStates[1].angle;
+    bl.angle = moduleStates[2].angle;
+    br.angle = moduleStates[3].angle;
+
+    auto xhat =
+        odometry.Update(groundTruthState.pose.Rotation() +
+                            frc::Rotation2d{distribution(generator) * 0.05_rad},
+                        {fl, fr, bl, br});
+    double error = groundTruthState.pose.Translation()
+                       .Distance(xhat.Translation())
+                       .value();
+
+    if (error > maxError) {
+      maxError = error;
+    }
+    errorSum += error;
+
+    t += dt;
+  }
+
+  EXPECT_LT(errorSum / (trajectory.TotalTime().value() / dt.value()), 0.05);
+  EXPECT_LT(maxError, 0.125);
+}
+
+TEST_F(SwerveDriveOdometryTest, AccuracyFacingXAxis) {
+  SwerveDriveKinematics<4> kinematics{
+      Translation2d{1_m, 1_m}, Translation2d{1_m, -1_m},
+      Translation2d{-1_m, -1_m}, Translation2d{-1_m, 1_m}};
+
+  SwerveDriveOdometry<4> odometry{kinematics, 0_rad, {zero, zero, zero, zero}};
+
+  SwerveModulePosition fl;
+  SwerveModulePosition fr;
+  SwerveModulePosition bl;
+  SwerveModulePosition br;
+
+  Trajectory trajectory = TrajectoryGenerator::GenerateTrajectory(
+      std::vector{Pose2d{0_m, 0_m, 45_deg}, Pose2d{3_m, 0_m, -90_deg},
+                  Pose2d{0_m, 0_m, 135_deg}, Pose2d{-3_m, 0_m, -90_deg},
+                  Pose2d{0_m, 0_m, 45_deg}},
+      TrajectoryConfig(5.0_mps, 2.0_mps_sq));
+
+  std::default_random_engine generator;
+  std::normal_distribution<double> distribution(0.0, 1.0);
+
+  units::second_t dt = 0.02_s;
+  units::second_t t = 0_s;
+
+  double maxError = -std::numeric_limits<double>::max();
+  double errorSum = 0;
+
+  while (t < trajectory.TotalTime()) {
+    Trajectory::State groundTruthState = trajectory.Sample(t);
+
+    fl.distance += groundTruthState.velocity * dt +
+                   0.5 * groundTruthState.acceleration * dt * dt;
+    fr.distance += groundTruthState.velocity * dt +
+                   0.5 * groundTruthState.acceleration * dt * dt;
+    bl.distance += groundTruthState.velocity * dt +
+                   0.5 * groundTruthState.acceleration * dt * dt;
+    br.distance += groundTruthState.velocity * dt +
+                   0.5 * groundTruthState.acceleration * dt * dt;
+
+    fl.angle = groundTruthState.pose.Rotation();
+    fr.angle = groundTruthState.pose.Rotation();
+    bl.angle = groundTruthState.pose.Rotation();
+    br.angle = groundTruthState.pose.Rotation();
+
+    auto xhat = odometry.Update(
+        frc::Rotation2d{distribution(generator) * 0.05_rad}, {fl, fr, bl, br});
+    double error = groundTruthState.pose.Translation()
+                       .Distance(xhat.Translation())
+                       .value();
+
+    if (error > maxError) {
+      maxError = error;
+    }
+    errorSum += error;
+
+    t += dt;
+  }
+
+  EXPECT_LT(errorSum / (trajectory.TotalTime().value() / dt.value()), 0.06);
+  EXPECT_LT(maxError, 0.125);
+}
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/spline/CubicHermiteSplineTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/spline/CubicHermiteSplineTest.cpp
index 41c34f9..7422a7f 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/spline/CubicHermiteSplineTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/spline/CubicHermiteSplineTest.cpp
@@ -93,31 +93,29 @@
 }  // namespace frc
 
 TEST_F(CubicHermiteSplineTest, StraightLine) {
-  Run(Pose2d(), std::vector<Translation2d>(), Pose2d(3_m, 0_m, Rotation2d()));
+  Run(Pose2d{}, std::vector<Translation2d>(), Pose2d{3_m, 0_m, 0_deg});
 }
 
 TEST_F(CubicHermiteSplineTest, SCurve) {
-  Pose2d start{0_m, 0_m, Rotation2d(90_deg)};
-  std::vector<Translation2d> waypoints{Translation2d(1_m, 1_m),
-                                       Translation2d(2_m, -1_m)};
-  Pose2d end{3_m, 0_m, Rotation2d{90_deg}};
+  Pose2d start{0_m, 0_m, 90_deg};
+  std::vector<Translation2d> waypoints{Translation2d{1_m, 1_m},
+                                       Translation2d{2_m, -1_m}};
+  Pose2d end{3_m, 0_m, 90_deg};
   Run(start, waypoints, end);
 }
 
 TEST_F(CubicHermiteSplineTest, OneInterior) {
   Pose2d start{0_m, 0_m, 0_rad};
-  std::vector<Translation2d> waypoints{Translation2d(2_m, 0_m)};
+  std::vector<Translation2d> waypoints{Translation2d{2_m, 0_m}};
   Pose2d end{4_m, 0_m, 0_rad};
   Run(start, waypoints, end);
 }
 
 TEST_F(CubicHermiteSplineTest, ThrowsOnMalformed) {
-  EXPECT_THROW(
-      Run(Pose2d{0_m, 0_m, Rotation2d(0_deg)}, std::vector<Translation2d>{},
-          Pose2d{1_m, 0_m, Rotation2d(180_deg)}),
-      SplineParameterizer::MalformedSplineException);
-  EXPECT_THROW(
-      Run(Pose2d{10_m, 10_m, Rotation2d(90_deg)}, std::vector<Translation2d>{},
-          Pose2d{10_m, 11_m, Rotation2d(-90_deg)}),
-      SplineParameterizer::MalformedSplineException);
+  EXPECT_THROW(Run(Pose2d{0_m, 0_m, 0_deg}, std::vector<Translation2d>{},
+                   Pose2d{1_m, 0_m, 180_deg}),
+               SplineParameterizer::MalformedSplineException);
+  EXPECT_THROW(Run(Pose2d{10_m, 10_m, 90_deg}, std::vector<Translation2d>{},
+                   Pose2d{10_m, 11_m, -90_deg}),
+               SplineParameterizer::MalformedSplineException);
 }
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/spline/QuinticHermiteSplineTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/spline/QuinticHermiteSplineTest.cpp
index e045622..e45df7b 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/spline/QuinticHermiteSplineTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/spline/QuinticHermiteSplineTest.cpp
@@ -65,23 +65,20 @@
 }  // namespace frc
 
 TEST_F(QuinticHermiteSplineTest, StraightLine) {
-  Run(Pose2d(), Pose2d(3_m, 0_m, Rotation2d()));
+  Run(Pose2d{}, Pose2d{3_m, 0_m, 0_deg});
 }
 
 TEST_F(QuinticHermiteSplineTest, SimpleSCurve) {
-  Run(Pose2d(), Pose2d(1_m, 1_m, Rotation2d()));
+  Run(Pose2d{}, Pose2d{1_m, 1_m, 0_deg});
 }
 
 TEST_F(QuinticHermiteSplineTest, SquigglyCurve) {
-  Run(Pose2d(0_m, 0_m, Rotation2d(90_deg)),
-      Pose2d(-1_m, 0_m, Rotation2d(90_deg)));
+  Run(Pose2d{0_m, 0_m, 90_deg}, Pose2d{-1_m, 0_m, 90_deg});
 }
 
 TEST_F(QuinticHermiteSplineTest, ThrowsOnMalformed) {
-  EXPECT_THROW(Run(Pose2d(0_m, 0_m, Rotation2d(0_deg)),
-                   Pose2d(1_m, 0_m, Rotation2d(180_deg))),
+  EXPECT_THROW(Run(Pose2d{0_m, 0_m, 0_deg}, Pose2d{1_m, 0_m, 180_deg}),
                SplineParameterizer::MalformedSplineException);
-  EXPECT_THROW(Run(Pose2d(10_m, 10_m, Rotation2d(90_deg)),
-                   Pose2d(10_m, 11_m, Rotation2d(-90_deg))),
+  EXPECT_THROW(Run(Pose2d{10_m, 10_m, 90_deg}, Pose2d{10_m, 11_m, -90_deg}),
                SplineParameterizer::MalformedSplineException);
 }
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/system/DiscretizationTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/system/DiscretizationTest.cpp
index b5a0fdc..d735338 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/system/DiscretizationTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/system/DiscretizationTest.cpp
@@ -6,8 +6,8 @@
 
 #include <functional>
 
-#include "Eigen/Core"
 #include "Eigen/Eigenvalues"
+#include "frc/EigenCore.h"
 #include "frc/system/Discretization.h"
 #include "frc/system/NumericalIntegration.h"
 #include "frc/system/RungeKuttaTimeVarying.h"
@@ -15,17 +15,16 @@
 // Check that for a simple second-order system that we can easily analyze
 // analytically,
 TEST(DiscretizationTest, DiscretizeA) {
-  Eigen::Matrix<double, 2, 2> contA{{0, 1}, {0, 0}};
+  frc::Matrixd<2, 2> contA{{0, 1}, {0, 0}};
 
-  Eigen::Vector<double, 2> x0{1, 1};
-  Eigen::Matrix<double, 2, 2> discA;
+  frc::Vectord<2> x0{1, 1};
+  frc::Matrixd<2, 2> discA;
 
   frc::DiscretizeA<2>(contA, 1_s, &discA);
-  Eigen::Vector<double, 2> x1Discrete = discA * x0;
+  frc::Vectord<2> x1Discrete = discA * x0;
 
   // We now have pos = vel = 1 and accel = 0, which should give us:
-  Eigen::Vector<double, 2> x1Truth{1.0 * x0(0) + 1.0 * x0(1),
-                                   0.0 * x0(0) + 1.0 * x0(1)};
+  frc::Vectord<2> x1Truth{1.0 * x0(0) + 1.0 * x0(1), 0.0 * x0(0) + 1.0 * x0(1)};
 
   EXPECT_EQ(x1Truth, x1Discrete);
 }
@@ -33,46 +32,48 @@
 // Check that for a simple second-order system that we can easily analyze
 // analytically,
 TEST(DiscretizationTest, DiscretizeAB) {
-  Eigen::Matrix<double, 2, 2> contA{{0, 1}, {0, 0}};
-  Eigen::Matrix<double, 2, 1> contB{0, 1};
+  frc::Matrixd<2, 2> contA{{0, 1}, {0, 0}};
+  frc::Matrixd<2, 1> contB{0, 1};
 
-  Eigen::Vector<double, 2> x0{1, 1};
-  Eigen::Vector<double, 1> u{1};
-  Eigen::Matrix<double, 2, 2> discA;
-  Eigen::Matrix<double, 2, 1> discB;
+  frc::Vectord<2> x0{1, 1};
+  frc::Vectord<1> u{1};
+  frc::Matrixd<2, 2> discA;
+  frc::Matrixd<2, 1> discB;
 
   frc::DiscretizeAB<2, 1>(contA, contB, 1_s, &discA, &discB);
-  Eigen::Vector<double, 2> x1Discrete = discA * x0 + discB * u;
+  frc::Vectord<2> x1Discrete = discA * x0 + discB * u;
 
   // We now have pos = vel = accel = 1, which should give us:
-  Eigen::Vector<double, 2> x1Truth{1.0 * x0(0) + 1.0 * x0(1) + 0.5 * u(0),
-                                   0.0 * x0(0) + 1.0 * x0(1) + 1.0 * u(0)};
+  frc::Vectord<2> x1Truth{1.0 * x0(0) + 1.0 * x0(1) + 0.5 * u(0),
+                          0.0 * x0(0) + 1.0 * x0(1) + 1.0 * u(0)};
 
   EXPECT_EQ(x1Truth, x1Discrete);
 }
 
-//                                             dt
-// Test that the discrete approximation of Q ≈ ∫ e^(Aτ) Q e^(Aᵀτ) dτ
-//                                             0
+//                                               T
+// Test that the discrete approximation of Q_d ≈ ∫ e^(Aτ) Q e^(Aᵀτ) dτ
+//                                               0
 TEST(DiscretizationTest, DiscretizeSlowModelAQ) {
-  Eigen::Matrix<double, 2, 2> contA{{0, 1}, {0, 0}};
-  Eigen::Matrix<double, 2, 2> contQ{{1, 0}, {0, 1}};
+  frc::Matrixd<2, 2> contA{{0, 1}, {0, 0}};
+  frc::Matrixd<2, 2> contQ{{1, 0}, {0, 1}};
 
   constexpr auto dt = 1_s;
 
-  Eigen::Matrix<double, 2, 2> discQIntegrated = frc::RungeKuttaTimeVarying<
-      std::function<Eigen::Matrix<double, 2, 2>(
-          units::second_t, const Eigen::Matrix<double, 2, 2>&)>,
-      Eigen::Matrix<double, 2, 2>>(
-      [&](units::second_t t, const Eigen::Matrix<double, 2, 2>&) {
-        return Eigen::Matrix<double, 2, 2>(
-            (contA * t.value()).exp() * contQ *
-            (contA.transpose() * t.value()).exp());
+  //       T
+  // Q_d ≈ ∫ e^(Aτ) Q e^(Aᵀτ) dτ
+  //       0
+  frc::Matrixd<2, 2> discQIntegrated = frc::RungeKuttaTimeVarying<
+      std::function<frc::Matrixd<2, 2>(units::second_t,
+                                       const frc::Matrixd<2, 2>&)>,
+      frc::Matrixd<2, 2>>(
+      [&](units::second_t t, const frc::Matrixd<2, 2>&) {
+        return frc::Matrixd<2, 2>((contA * t.value()).exp() * contQ *
+                                  (contA.transpose() * t.value()).exp());
       },
-      0_s, Eigen::Matrix<double, 2, 2>::Zero(), dt);
+      0_s, frc::Matrixd<2, 2>::Zero(), dt);
 
-  Eigen::Matrix<double, 2, 2> discA;
-  Eigen::Matrix<double, 2, 2> discQ;
+  frc::Matrixd<2, 2> discA;
+  frc::Matrixd<2, 2> discQ;
   frc::DiscretizeAQ<2>(contA, contQ, dt, &discA, &discQ);
 
   EXPECT_LT((discQIntegrated - discQ).norm(), 1e-10)
@@ -81,28 +82,30 @@
       << discQIntegrated;
 }
 
-//                                             dt
-// Test that the discrete approximation of Q ≈ ∫ e^(Aτ) Q e^(Aᵀτ) dτ
-//                                             0
+//                                               T
+// Test that the discrete approximation of Q_d ≈ ∫ e^(Aτ) Q e^(Aᵀτ) dτ
+//                                               0
 TEST(DiscretizationTest, DiscretizeFastModelAQ) {
-  Eigen::Matrix<double, 2, 2> contA{{0, 1}, {0, -1406.29}};
-  Eigen::Matrix<double, 2, 2> contQ{{0.0025, 0}, {0, 1}};
+  frc::Matrixd<2, 2> contA{{0, 1}, {0, -1406.29}};
+  frc::Matrixd<2, 2> contQ{{0.0025, 0}, {0, 1}};
 
   constexpr auto dt = 5_ms;
 
-  Eigen::Matrix<double, 2, 2> discQIntegrated = frc::RungeKuttaTimeVarying<
-      std::function<Eigen::Matrix<double, 2, 2>(
-          units::second_t, const Eigen::Matrix<double, 2, 2>&)>,
-      Eigen::Matrix<double, 2, 2>>(
-      [&](units::second_t t, const Eigen::Matrix<double, 2, 2>&) {
-        return Eigen::Matrix<double, 2, 2>(
-            (contA * t.value()).exp() * contQ *
-            (contA.transpose() * t.value()).exp());
+  //       T
+  // Q_d = ∫ e^(Aτ) Q e^(Aᵀτ) dτ
+  //       0
+  frc::Matrixd<2, 2> discQIntegrated = frc::RungeKuttaTimeVarying<
+      std::function<frc::Matrixd<2, 2>(units::second_t,
+                                       const frc::Matrixd<2, 2>&)>,
+      frc::Matrixd<2, 2>>(
+      [&](units::second_t t, const frc::Matrixd<2, 2>&) {
+        return frc::Matrixd<2, 2>((contA * t.value()).exp() * contQ *
+                                  (contA.transpose() * t.value()).exp());
       },
-      0_s, Eigen::Matrix<double, 2, 2>::Zero(), dt);
+      0_s, frc::Matrixd<2, 2>::Zero(), dt);
 
-  Eigen::Matrix<double, 2, 2> discA;
-  Eigen::Matrix<double, 2, 2> discQ;
+  frc::Matrixd<2, 2> discA;
+  frc::Matrixd<2, 2> discQ;
   frc::DiscretizeAQ<2>(contA, contQ, dt, &discA, &discQ);
 
   EXPECT_LT((discQIntegrated - discQ).norm(), 1e-3)
@@ -113,14 +116,14 @@
 
 // Test that the Taylor series discretization produces nearly identical results.
 TEST(DiscretizationTest, DiscretizeSlowModelAQTaylor) {
-  Eigen::Matrix<double, 2, 2> contA{{0, 1}, {0, 0}};
-  Eigen::Matrix<double, 2, 2> contQ{{1, 0}, {0, 1}};
+  frc::Matrixd<2, 2> contA{{0, 1}, {0, 0}};
+  frc::Matrixd<2, 2> contQ{{1, 0}, {0, 1}};
 
   constexpr auto dt = 1_s;
 
-  Eigen::Matrix<double, 2, 2> discQTaylor;
-  Eigen::Matrix<double, 2, 2> discA;
-  Eigen::Matrix<double, 2, 2> discATaylor;
+  frc::Matrixd<2, 2> discQTaylor;
+  frc::Matrixd<2, 2> discA;
+  frc::Matrixd<2, 2> discATaylor;
 
   // Continuous Q should be positive semidefinite
   Eigen::SelfAdjointEigenSolver<Eigen::MatrixXd> esCont{contQ};
@@ -128,16 +131,18 @@
     EXPECT_GE(esCont.eigenvalues()[i], 0);
   }
 
-  Eigen::Matrix<double, 2, 2> discQIntegrated = frc::RungeKuttaTimeVarying<
-      std::function<Eigen::Matrix<double, 2, 2>(
-          units::second_t, const Eigen::Matrix<double, 2, 2>&)>,
-      Eigen::Matrix<double, 2, 2>>(
-      [&](units::second_t t, const Eigen::Matrix<double, 2, 2>&) {
-        return Eigen::Matrix<double, 2, 2>(
-            (contA * t.value()).exp() * contQ *
-            (contA.transpose() * t.value()).exp());
+  //       T
+  // Q_d = ∫ e^(Aτ) Q e^(Aᵀτ) dτ
+  //       0
+  frc::Matrixd<2, 2> discQIntegrated = frc::RungeKuttaTimeVarying<
+      std::function<frc::Matrixd<2, 2>(units::second_t,
+                                       const frc::Matrixd<2, 2>&)>,
+      frc::Matrixd<2, 2>>(
+      [&](units::second_t t, const frc::Matrixd<2, 2>&) {
+        return frc::Matrixd<2, 2>((contA * t.value()).exp() * contQ *
+                                  (contA.transpose() * t.value()).exp());
       },
-      0_s, Eigen::Matrix<double, 2, 2>::Zero(), dt);
+      0_s, frc::Matrixd<2, 2>::Zero(), dt);
 
   frc::DiscretizeA<2>(contA, dt, &discA);
   frc::DiscretizeAQTaylor<2>(contA, contQ, dt, &discATaylor, &discQTaylor);
@@ -157,14 +162,14 @@
 
 // Test that the Taylor series discretization produces nearly identical results.
 TEST(DiscretizationTest, DiscretizeFastModelAQTaylor) {
-  Eigen::Matrix<double, 2, 2> contA{{0, 1}, {0, -1500}};
-  Eigen::Matrix<double, 2, 2> contQ{{0.0025, 0}, {0, 1}};
+  frc::Matrixd<2, 2> contA{{0, 1}, {0, -1500}};
+  frc::Matrixd<2, 2> contQ{{0.0025, 0}, {0, 1}};
 
   constexpr auto dt = 5_ms;
 
-  Eigen::Matrix<double, 2, 2> discQTaylor;
-  Eigen::Matrix<double, 2, 2> discA;
-  Eigen::Matrix<double, 2, 2> discATaylor;
+  frc::Matrixd<2, 2> discQTaylor;
+  frc::Matrixd<2, 2> discA;
+  frc::Matrixd<2, 2> discATaylor;
 
   // Continuous Q should be positive semidefinite
   Eigen::SelfAdjointEigenSolver<Eigen::MatrixXd> esCont(contQ);
@@ -172,16 +177,18 @@
     EXPECT_GE(esCont.eigenvalues()[i], 0);
   }
 
-  Eigen::Matrix<double, 2, 2> discQIntegrated = frc::RungeKuttaTimeVarying<
-      std::function<Eigen::Matrix<double, 2, 2>(
-          units::second_t, const Eigen::Matrix<double, 2, 2>&)>,
-      Eigen::Matrix<double, 2, 2>>(
-      [&](units::second_t t, const Eigen::Matrix<double, 2, 2>&) {
-        return Eigen::Matrix<double, 2, 2>(
-            (contA * t.value()).exp() * contQ *
-            (contA.transpose() * t.value()).exp());
+  //       T
+  // Q_d = ∫ e^(Aτ) Q e^(Aᵀτ) dτ
+  //       0
+  frc::Matrixd<2, 2> discQIntegrated = frc::RungeKuttaTimeVarying<
+      std::function<frc::Matrixd<2, 2>(units::second_t,
+                                       const frc::Matrixd<2, 2>&)>,
+      frc::Matrixd<2, 2>>(
+      [&](units::second_t t, const frc::Matrixd<2, 2>&) {
+        return frc::Matrixd<2, 2>((contA * t.value()).exp() * contQ *
+                                  (contA.transpose() * t.value()).exp());
       },
-      0_s, Eigen::Matrix<double, 2, 2>::Zero(), dt);
+      0_s, frc::Matrixd<2, 2>::Zero(), dt);
 
   frc::DiscretizeA<2>(contA, dt, &discA);
   frc::DiscretizeAQTaylor<2>(contA, contQ, dt, &discATaylor, &discQTaylor);
@@ -201,10 +208,10 @@
 
 // Test that DiscretizeR() works
 TEST(DiscretizationTest, DiscretizeR) {
-  Eigen::Matrix<double, 2, 2> contR{{2.0, 0.0}, {0.0, 1.0}};
-  Eigen::Matrix<double, 2, 2> discRTruth{{4.0, 0.0}, {0.0, 2.0}};
+  frc::Matrixd<2, 2> contR{{2.0, 0.0}, {0.0, 1.0}};
+  frc::Matrixd<2, 2> discRTruth{{4.0, 0.0}, {0.0, 2.0}};
 
-  Eigen::Matrix<double, 2, 2> discR = frc::DiscretizeR<2>(contR, 500_ms);
+  frc::Matrixd<2, 2> discR = frc::DiscretizeR<2>(contR, 500_ms);
 
   EXPECT_LT((discRTruth - discR).norm(), 1e-10)
       << "Expected these to be nearly equal:\ndiscR:\n"
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/system/LinearSystemIDTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/system/LinearSystemIDTest.cpp
index fbf86f1..dbc4284 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/system/LinearSystemIDTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/system/LinearSystemIDTest.cpp
@@ -16,49 +16,43 @@
       frc::DCMotor::NEO(4), 70_kg, 0.05_m, 0.4_m, 6.0_kg_sq_m, 6.0);
 
   ASSERT_TRUE(model.A().isApprox(
-      Eigen::Matrix<double, 2, 2>{{-10.14132, 3.06598}, {3.06598, -10.14132}},
-      0.001));
+      frc::Matrixd<2, 2>{{-10.14132, 3.06598}, {3.06598, -10.14132}}, 0.001));
   ASSERT_TRUE(model.B().isApprox(
-      Eigen::Matrix<double, 2, 2>{{4.2590, -1.28762}, {-1.2876, 4.2590}},
-      0.001));
-  ASSERT_TRUE(model.C().isApprox(
-      Eigen::Matrix<double, 2, 2>{{1.0, 0.0}, {0.0, 1.0}}, 0.001));
-  ASSERT_TRUE(model.D().isApprox(
-      Eigen::Matrix<double, 2, 2>{{0.0, 0.0}, {0.0, 0.0}}, 0.001));
+      frc::Matrixd<2, 2>{{4.2590, -1.28762}, {-1.2876, 4.2590}}, 0.001));
+  ASSERT_TRUE(
+      model.C().isApprox(frc::Matrixd<2, 2>{{1.0, 0.0}, {0.0, 1.0}}, 0.001));
+  ASSERT_TRUE(
+      model.D().isApprox(frc::Matrixd<2, 2>{{0.0, 0.0}, {0.0, 0.0}}, 0.001));
 }
 
 TEST(LinearSystemIDTest, ElevatorSystem) {
   auto model = frc::LinearSystemId::ElevatorSystem(frc::DCMotor::NEO(2), 5_kg,
                                                    0.05_m, 12);
   ASSERT_TRUE(model.A().isApprox(
-      Eigen::Matrix<double, 2, 2>{{0.0, 1.0}, {0.0, -99.05473}}, 0.001));
-  ASSERT_TRUE(
-      model.B().isApprox(Eigen::Matrix<double, 2, 1>{0.0, 20.8}, 0.001));
-  ASSERT_TRUE(model.C().isApprox(Eigen::Matrix<double, 1, 2>{1.0, 0.0}, 0.001));
-  ASSERT_TRUE(model.D().isApprox(Eigen::Matrix<double, 1, 1>{0.0}, 0.001));
+      frc::Matrixd<2, 2>{{0.0, 1.0}, {0.0, -99.05473}}, 0.001));
+  ASSERT_TRUE(model.B().isApprox(frc::Matrixd<2, 1>{0.0, 20.8}, 0.001));
+  ASSERT_TRUE(model.C().isApprox(frc::Matrixd<1, 2>{1.0, 0.0}, 0.001));
+  ASSERT_TRUE(model.D().isApprox(frc::Matrixd<1, 1>{0.0}, 0.001));
 }
 
 TEST(LinearSystemIDTest, FlywheelSystem) {
   auto model = frc::LinearSystemId::FlywheelSystem(frc::DCMotor::NEO(2),
                                                    0.00032_kg_sq_m, 1.0);
-  ASSERT_TRUE(
-      model.A().isApprox(Eigen::Matrix<double, 1, 1>{-26.87032}, 0.001));
-  ASSERT_TRUE(
-      model.B().isApprox(Eigen::Matrix<double, 1, 1>{1354.166667}, 0.001));
-  ASSERT_TRUE(model.C().isApprox(Eigen::Matrix<double, 1, 1>{1.0}, 0.001));
-  ASSERT_TRUE(model.D().isApprox(Eigen::Matrix<double, 1, 1>{0.0}, 0.001));
+  ASSERT_TRUE(model.A().isApprox(frc::Matrixd<1, 1>{-26.87032}, 0.001));
+  ASSERT_TRUE(model.B().isApprox(frc::Matrixd<1, 1>{1354.166667}, 0.001));
+  ASSERT_TRUE(model.C().isApprox(frc::Matrixd<1, 1>{1.0}, 0.001));
+  ASSERT_TRUE(model.D().isApprox(frc::Matrixd<1, 1>{0.0}, 0.001));
 }
 
 TEST(LinearSystemIDTest, DCMotorSystem) {
   auto model = frc::LinearSystemId::DCMotorSystem(frc::DCMotor::NEO(2),
                                                   0.00032_kg_sq_m, 1.0);
-  ASSERT_TRUE(model.A().isApprox(
-      Eigen::Matrix<double, 2, 2>{{0, 1}, {0, -26.87032}}, 0.001));
   ASSERT_TRUE(
-      model.B().isApprox(Eigen::Matrix<double, 2, 1>{0, 1354.166667}, 0.001));
-  ASSERT_TRUE(model.C().isApprox(
-      Eigen::Matrix<double, 2, 2>{{1.0, 0.0}, {0.0, 1.0}}, 0.001));
-  ASSERT_TRUE(model.D().isApprox(Eigen::Matrix<double, 2, 1>{0.0, 0.0}, 0.001));
+      model.A().isApprox(frc::Matrixd<2, 2>{{0, 1}, {0, -26.87032}}, 0.001));
+  ASSERT_TRUE(model.B().isApprox(frc::Matrixd<2, 1>{0, 1354.166667}, 0.001));
+  ASSERT_TRUE(
+      model.C().isApprox(frc::Matrixd<2, 2>{{1.0, 0.0}, {0.0, 1.0}}, 0.001));
+  ASSERT_TRUE(model.D().isApprox(frc::Matrixd<2, 1>{0.0, 0.0}, 0.001));
 }
 
 TEST(LinearSystemIDTest, IdentifyPositionSystem) {
@@ -70,9 +64,8 @@
       kv * 1_V / 1_mps, ka * 1_V / 1_mps_sq);
 
   ASSERT_TRUE(model.A().isApprox(
-      Eigen::Matrix<double, 2, 2>{{0.0, 1.0}, {0.0, -kv / ka}}, 0.001));
-  ASSERT_TRUE(
-      model.B().isApprox(Eigen::Matrix<double, 2, 1>{0.0, 1.0 / ka}, 0.001));
+      frc::Matrixd<2, 2>{{0.0, 1.0}, {0.0, -kv / ka}}, 0.001));
+  ASSERT_TRUE(model.B().isApprox(frc::Matrixd<2, 1>{0.0, 1.0 / ka}, 0.001));
 }
 
 TEST(LinearSystemIDTest, IdentifyVelocitySystem) {
@@ -84,6 +77,6 @@
   auto model = frc::LinearSystemId::IdentifyVelocitySystem<units::meter>(
       kv * 1_V / 1_mps, ka * 1_V / 1_mps_sq);
 
-  ASSERT_TRUE(model.A().isApprox(Eigen::Matrix<double, 1, 1>{-kv / ka}, 0.001));
-  ASSERT_TRUE(model.B().isApprox(Eigen::Matrix<double, 1, 1>{1.0 / ka}, 0.001));
+  ASSERT_TRUE(model.A().isApprox(frc::Matrixd<1, 1>{-kv / ka}, 0.001));
+  ASSERT_TRUE(model.B().isApprox(frc::Matrixd<1, 1>{1.0 / ka}, 0.001));
 }
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/system/NumericalIntegrationTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/system/NumericalIntegrationTest.cpp
index fd9c039..b1793ad 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/system/NumericalIntegrationTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/system/NumericalIntegrationTest.cpp
@@ -10,48 +10,34 @@
 
 // Tests that integrating dx/dt = e^x works.
 TEST(NumericalIntegrationTest, Exponential) {
-  Eigen::Vector<double, 1> y0{0.0};
+  frc::Vectord<1> y0{0.0};
 
-  Eigen::Vector<double, 1> y1 = frc::RK4(
-      [](const Eigen::Vector<double, 1>& x) {
-        return Eigen::Vector<double, 1>{std::exp(x(0))};
-      },
+  frc::Vectord<1> y1 = frc::RK4(
+      [](const frc::Vectord<1>& x) { return frc::Vectord<1>{std::exp(x(0))}; },
       y0, 0.1_s);
   EXPECT_NEAR(y1(0), std::exp(0.1) - std::exp(0), 1e-3);
 }
 
 // Tests that integrating dx/dt = e^x works when we provide a U.
 TEST(NumericalIntegrationTest, ExponentialWithU) {
-  Eigen::Vector<double, 1> y0{0.0};
+  frc::Vectord<1> y0{0.0};
 
-  Eigen::Vector<double, 1> y1 = frc::RK4(
-      [](const Eigen::Vector<double, 1>& x, const Eigen::Vector<double, 1>& u) {
-        return Eigen::Vector<double, 1>{std::exp(u(0) * x(0))};
+  frc::Vectord<1> y1 = frc::RK4(
+      [](const frc::Vectord<1>& x, const frc::Vectord<1>& u) {
+        return frc::Vectord<1>{std::exp(u(0) * x(0))};
       },
-      y0, Eigen::Vector<double, 1>{1.0}, 0.1_s);
-  EXPECT_NEAR(y1(0), std::exp(0.1) - std::exp(0), 1e-3);
-}
-
-// Tests that integrating dx/dt = e^x works with RKF45.
-TEST(NumericalIntegrationTest, ExponentialRKF45) {
-  Eigen::Vector<double, 1> y0{0.0};
-
-  Eigen::Vector<double, 1> y1 = frc::RKF45(
-      [](const Eigen::Vector<double, 1>& x, const Eigen::Vector<double, 1>& u) {
-        return Eigen::Vector<double, 1>{std::exp(x(0))};
-      },
-      y0, Eigen::Vector<double, 1>{0.0}, 0.1_s);
+      y0, frc::Vectord<1>{1.0}, 0.1_s);
   EXPECT_NEAR(y1(0), std::exp(0.1) - std::exp(0), 1e-3);
 }
 
 // Tests that integrating dx/dt = e^x works with RKDP
 TEST(NumericalIntegrationTest, ExponentialRKDP) {
-  Eigen::Vector<double, 1> y0{0.0};
+  frc::Vectord<1> y0{0.0};
 
-  Eigen::Vector<double, 1> y1 = frc::RKDP(
-      [](const Eigen::Vector<double, 1>& x, const Eigen::Vector<double, 1>& u) {
-        return Eigen::Vector<double, 1>{std::exp(x(0))};
+  frc::Vectord<1> y1 = frc::RKDP(
+      [](const frc::Vectord<1>& x, const frc::Vectord<1>& u) {
+        return frc::Vectord<1>{std::exp(x(0))};
       },
-      y0, Eigen::Vector<double, 1>{0.0}, 0.1_s);
+      y0, frc::Vectord<1>{0.0}, 0.1_s);
   EXPECT_NEAR(y1(0), std::exp(0.1) - std::exp(0), 1e-3);
 }
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/system/NumericalJacobianTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/system/NumericalJacobianTest.cpp
index 4e64825..513684b 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/system/NumericalJacobianTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/system/NumericalJacobianTest.cpp
@@ -6,53 +6,46 @@
 
 #include "frc/system/NumericalJacobian.h"
 
-Eigen::Matrix<double, 4, 4> A{
-    {1, 2, 4, 1}, {5, 2, 3, 4}, {5, 1, 3, 2}, {1, 1, 3, 7}};
-Eigen::Matrix<double, 4, 2> B{{1, 1}, {2, 1}, {3, 2}, {3, 7}};
+frc::Matrixd<4, 4> A{{1, 2, 4, 1}, {5, 2, 3, 4}, {5, 1, 3, 2}, {1, 1, 3, 7}};
+frc::Matrixd<4, 2> B{{1, 1}, {2, 1}, {3, 2}, {3, 7}};
 
 // Function from which to recover A and B
-Eigen::Vector<double, 4> AxBuFn(const Eigen::Vector<double, 4>& x,
-                                const Eigen::Vector<double, 2>& u) {
+frc::Vectord<4> AxBuFn(const frc::Vectord<4>& x, const frc::Vectord<2>& u) {
   return A * x + B * u;
 }
 
 // Test that we can recover A from AxBuFn() pretty accurately
 TEST(NumericalJacobianTest, Ax) {
-  Eigen::Matrix<double, 4, 4> newA =
-      frc::NumericalJacobianX<4, 4, 2>(AxBuFn, Eigen::Vector<double, 4>::Zero(),
-                                       Eigen::Vector<double, 2>::Zero());
+  frc::Matrixd<4, 4> newA = frc::NumericalJacobianX<4, 4, 2>(
+      AxBuFn, frc::Vectord<4>::Zero(), frc::Vectord<2>::Zero());
   EXPECT_TRUE(newA.isApprox(A));
 }
 
 // Test that we can recover B from AxBuFn() pretty accurately
 TEST(NumericalJacobianTest, Bu) {
-  Eigen::Matrix<double, 4, 2> newB =
-      frc::NumericalJacobianU<4, 4, 2>(AxBuFn, Eigen::Vector<double, 4>::Zero(),
-                                       Eigen::Vector<double, 2>::Zero());
+  frc::Matrixd<4, 2> newB = frc::NumericalJacobianU<4, 4, 2>(
+      AxBuFn, frc::Vectord<4>::Zero(), frc::Vectord<2>::Zero());
   EXPECT_TRUE(newB.isApprox(B));
 }
 
-Eigen::Matrix<double, 3, 4> C{{1, 2, 4, 1}, {5, 2, 3, 4}, {5, 1, 3, 2}};
-Eigen::Matrix<double, 3, 2> D{{1, 1}, {2, 1}, {3, 2}};
+frc::Matrixd<3, 4> C{{1, 2, 4, 1}, {5, 2, 3, 4}, {5, 1, 3, 2}};
+frc::Matrixd<3, 2> D{{1, 1}, {2, 1}, {3, 2}};
 
 // Function from which to recover C and D
-Eigen::Vector<double, 3> CxDuFn(const Eigen::Vector<double, 4>& x,
-                                const Eigen::Vector<double, 2>& u) {
+frc::Vectord<3> CxDuFn(const frc::Vectord<4>& x, const frc::Vectord<2>& u) {
   return C * x + D * u;
 }
 
 // Test that we can recover C from CxDuFn() pretty accurately
 TEST(NumericalJacobianTest, Cx) {
-  Eigen::Matrix<double, 3, 4> newC =
-      frc::NumericalJacobianX<3, 4, 2>(CxDuFn, Eigen::Vector<double, 4>::Zero(),
-                                       Eigen::Vector<double, 2>::Zero());
+  frc::Matrixd<3, 4> newC = frc::NumericalJacobianX<3, 4, 2>(
+      CxDuFn, frc::Vectord<4>::Zero(), frc::Vectord<2>::Zero());
   EXPECT_TRUE(newC.isApprox(C));
 }
 
 // Test that we can recover D from CxDuFn() pretty accurately
 TEST(NumericalJacobianTest, Du) {
-  Eigen::Matrix<double, 3, 2> newD =
-      frc::NumericalJacobianU<3, 4, 2>(CxDuFn, Eigen::Vector<double, 4>::Zero(),
-                                       Eigen::Vector<double, 2>::Zero());
+  frc::Matrixd<3, 2> newD = frc::NumericalJacobianU<3, 4, 2>(
+      CxDuFn, frc::Vectord<4>::Zero(), frc::Vectord<2>::Zero());
   EXPECT_TRUE(newD.isApprox(D));
 }
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/system/RungeKuttaTimeVaryingTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/system/RungeKuttaTimeVaryingTest.cpp
index f1be861..70f1938 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/system/RungeKuttaTimeVaryingTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/system/RungeKuttaTimeVaryingTest.cpp
@@ -9,26 +9,25 @@
 #include "frc/system/RungeKuttaTimeVarying.h"
 
 namespace {
-Eigen::Vector<double, 1> RungeKuttaTimeVaryingSolution(double t) {
-  return Eigen::Vector<double, 1>{12.0 * std::exp(t) /
-                                  (std::pow(std::exp(t) + 1.0, 2.0))};
+frc::Vectord<1> RungeKuttaTimeVaryingSolution(double t) {
+  return frc::Vectord<1>{12.0 * std::exp(t) / std::pow(std::exp(t) + 1.0, 2.0)};
 }
 }  // namespace
 
 // Tests RK4 with a time varying solution. From
 // http://www2.hawaii.edu/~jmcfatri/math407/RungeKuttaTest.html:
-//   x' = x (2 / (e^t + 1) - 1)
+//   x' = x (2/(eᵗ + 1) - 1)
 //
 // The true (analytical) solution is:
 //
-// x(t) = 12 * e^t / ((e^t + 1)^2)
+// x(t) = 12eᵗ/((eᵗ + 1)²)
 TEST(RungeKuttaTimeVaryingTest, RungeKuttaTimeVarying) {
-  Eigen::Vector<double, 1> y0 = RungeKuttaTimeVaryingSolution(5.0);
+  frc::Vectord<1> y0 = RungeKuttaTimeVaryingSolution(5.0);
 
-  Eigen::Vector<double, 1> y1 = frc::RungeKuttaTimeVarying(
-      [](units::second_t t, const Eigen::Vector<double, 1>& x) {
-        return Eigen::Vector<double, 1>{
-            x(0) * (2.0 / (std::exp(t.value()) + 1.0) - 1.0)};
+  frc::Vectord<1> y1 = frc::RungeKuttaTimeVarying(
+      [](units::second_t t, const frc::Vectord<1>& x) {
+        return frc::Vectord<1>{x(0) *
+                               (2.0 / (std::exp(t.value()) + 1.0) - 1.0)};
       },
       5_s, y0, 1_s);
   EXPECT_NEAR(y1(0), RungeKuttaTimeVaryingSolution(6.0)(0), 1e-3);
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/trajectory/DifferentialDriveVoltageTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/trajectory/DifferentialDriveVoltageTest.cpp
index b5f6406..e3d6b7f 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/trajectory/DifferentialDriveVoltageTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/trajectory/DifferentialDriveVoltageTest.cpp
@@ -72,12 +72,12 @@
       DifferentialDriveVoltageConstraint(feedforward, kinematics, maxVoltage));
 
   EXPECT_NO_FATAL_FAILURE(TrajectoryGenerator::GenerateTrajectory(
-      Pose2d{1_m, 0_m, Rotation2d{90_deg}}, std::vector<Translation2d>{},
-      Pose2d{0_m, 1_m, Rotation2d{180_deg}}, config));
+      Pose2d{1_m, 0_m, 90_deg}, std::vector<Translation2d>{},
+      Pose2d{0_m, 1_m, 180_deg}, config));
 
   config.SetReversed(true);
 
   EXPECT_NO_FATAL_FAILURE(TrajectoryGenerator::GenerateTrajectory(
-      Pose2d{0_m, 1_m, Rotation2d{180_deg}}, std::vector<Translation2d>{},
-      Pose2d{1_m, 0_m, Rotation2d{90_deg}}, config));
+      Pose2d{0_m, 1_m, 180_deg}, std::vector<Translation2d>{},
+      Pose2d{1_m, 0_m, 90_deg}, config));
 }
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/trajectory/EllipticalRegionConstraintTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/trajectory/EllipticalRegionConstraintTest.cpp
index 88dc2b8..8d9e221 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/trajectory/EllipticalRegionConstraintTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/trajectory/EllipticalRegionConstraintTest.cpp
@@ -21,9 +21,8 @@
 
   auto config = TrajectoryConfig(13_fps, 13_fps_sq);
   MaxVelocityConstraint maxVelConstraint(maxVelocity);
-  EllipticalRegionConstraint regionConstraint(frc::Translation2d{5_ft, 2.5_ft},
-                                              10_ft, 5_ft, Rotation2d(180_deg),
-                                              maxVelConstraint);
+  EllipticalRegionConstraint regionConstraint(
+      frc::Translation2d{5_ft, 2.5_ft}, 10_ft, 5_ft, 180_deg, maxVelConstraint);
   config.AddConstraint(regionConstraint);
 
   auto trajectory = TestTrajectory::GetTrajectory(config);
@@ -45,14 +44,12 @@
   constexpr auto maxVelocity = 2_fps;
   MaxVelocityConstraint maxVelConstraint(maxVelocity);
   EllipticalRegionConstraint regionConstraintNoRotation(
-      frc::Translation2d{1_ft, 1_ft}, 2_ft, 4_ft, Rotation2d(0_deg),
-      maxVelConstraint);
+      frc::Translation2d{1_ft, 1_ft}, 2_ft, 4_ft, 0_deg, maxVelConstraint);
   EXPECT_FALSE(regionConstraintNoRotation.IsPoseInRegion(
-      frc::Pose2d(2.1_ft, 1_ft, 0_rad)));
+      frc::Pose2d{2.1_ft, 1_ft, 0_rad}));
 
   EllipticalRegionConstraint regionConstraintWithRotation(
-      frc::Translation2d{1_ft, 1_ft}, 2_ft, 4_ft, Rotation2d(90_deg),
-      maxVelConstraint);
+      frc::Translation2d{1_ft, 1_ft}, 2_ft, 4_ft, 90_deg, maxVelConstraint);
   EXPECT_TRUE(regionConstraintWithRotation.IsPoseInRegion(
-      frc::Pose2d(2.1_ft, 1_ft, 0_rad)));
+      frc::Pose2d{2.1_ft, 1_ft, 0_rad}));
 }
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/trajectory/RectangularRegionConstraintTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/trajectory/RectangularRegionConstraintTest.cpp
index 77310ae..0bf6b1a 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/trajectory/RectangularRegionConstraintTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/trajectory/RectangularRegionConstraintTest.cpp
@@ -47,7 +47,6 @@
                                                frc::Translation2d{5_ft, 27_ft},
                                                maxVelConstraint);
 
-  EXPECT_FALSE(regionConstraint.IsPoseInRegion(Pose2d()));
-  EXPECT_TRUE(
-      regionConstraint.IsPoseInRegion(Pose2d(3_ft, 14.5_ft, Rotation2d())));
+  EXPECT_FALSE(regionConstraint.IsPoseInRegion(Pose2d{}));
+  EXPECT_TRUE(regionConstraint.IsPoseInRegion(Pose2d{3_ft, 14.5_ft, 0_deg}));
 }
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/trajectory/TrajectoryGeneratorTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/trajectory/TrajectoryGeneratorTest.cpp
index 175becf..5892461 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/trajectory/TrajectoryGeneratorTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/trajectory/TrajectoryGeneratorTest.cpp
@@ -34,8 +34,7 @@
 
 TEST(TrajectoryGenertionTest, ReturnsEmptyOnMalformed) {
   const auto t = TrajectoryGenerator::GenerateTrajectory(
-      std::vector<Pose2d>{Pose2d(0_m, 0_m, Rotation2d(0_deg)),
-                          Pose2d(1_m, 0_m, Rotation2d(180_deg))},
+      std::vector<Pose2d>{Pose2d{0_m, 0_m, 0_deg}, Pose2d{1_m, 0_m, 180_deg}},
       TrajectoryConfig(12_fps, 12_fps_sq));
 
   ASSERT_EQ(t.States().size(), 1u);
diff --git a/third_party/allwpilib/wpimath/src/test/native/cpp/trajectory/TrajectoryTransformTest.cpp b/third_party/allwpilib/wpimath/src/test/native/cpp/trajectory/TrajectoryTransformTest.cpp
index 0c6e07a..5c77a5b 100644
--- a/third_party/allwpilib/wpimath/src/test/native/cpp/trajectory/TrajectoryTransformTest.cpp
+++ b/third_party/allwpilib/wpimath/src/test/native/cpp/trajectory/TrajectoryTransformTest.cpp
@@ -31,11 +31,9 @@
 TEST(TrajectoryTransformsTest, TransformBy) {
   frc::TrajectoryConfig config{3_mps, 3_mps_sq};
   auto trajectory = frc::TrajectoryGenerator::GenerateTrajectory(
-      frc::Pose2d{}, {}, frc::Pose2d{1_m, 1_m, frc::Rotation2d(90_deg)},
-      config);
+      frc::Pose2d{}, {}, frc::Pose2d{1_m, 1_m, 90_deg}, config);
 
-  auto transformedTrajectory =
-      trajectory.TransformBy({{1_m, 2_m}, frc::Rotation2d(30_deg)});
+  auto transformedTrajectory = trajectory.TransformBy({{1_m, 2_m}, 30_deg});
 
   auto firstPose = transformedTrajectory.Sample(0_s).pose;
 
@@ -49,11 +47,9 @@
 TEST(TrajectoryTransformsTest, RelativeTo) {
   frc::TrajectoryConfig config{3_mps, 3_mps_sq};
   auto trajectory = frc::TrajectoryGenerator::GenerateTrajectory(
-      frc::Pose2d{1_m, 2_m, frc::Rotation2d(30_deg)}, {},
-      frc::Pose2d{5_m, 7_m, frc::Rotation2d(90_deg)}, config);
+      frc::Pose2d{1_m, 2_m, 30_deg}, {}, frc::Pose2d{5_m, 7_m, 90_deg}, config);
 
-  auto transformedTrajectory =
-      trajectory.RelativeTo({1_m, 2_m, frc::Rotation2d(30_deg)});
+  auto transformedTrajectory = trajectory.RelativeTo({1_m, 2_m, 30_deg});
 
   auto firstPose = transformedTrajectory.Sample(0_s).pose;
 
diff --git a/third_party/allwpilib/wpimath/src/test/native/include/frc/system/RungeKuttaTimeVarying.h b/third_party/allwpilib/wpimath/src/test/native/include/frc/system/RungeKuttaTimeVarying.h
index 23a20e8..5e7b165 100644
--- a/third_party/allwpilib/wpimath/src/test/native/include/frc/system/RungeKuttaTimeVarying.h
+++ b/third_party/allwpilib/wpimath/src/test/native/include/frc/system/RungeKuttaTimeVarying.h
@@ -6,7 +6,7 @@
 
 #include <array>
 
-#include "Eigen/Core"
+#include "frc/EigenCore.h"
 #include "units/time.h"
 
 namespace frc {
diff --git a/third_party/allwpilib/wpimath/src/test/native/include/trajectory/TestTrajectory.h b/third_party/allwpilib/wpimath/src/test/native/include/trajectory/TestTrajectory.h
index de7b8b8..89e735c 100644
--- a/third_party/allwpilib/wpimath/src/test/native/include/trajectory/TestTrajectory.h
+++ b/third_party/allwpilib/wpimath/src/test/native/include/trajectory/TestTrajectory.h
@@ -17,16 +17,15 @@
  public:
   static Trajectory GetTrajectory(TrajectoryConfig& config) {
     // 2018 cross scale auto waypoints
-    const Pose2d sideStart{1.54_ft, 23.23_ft, Rotation2d(180_deg)};
-    const Pose2d crossScale{23.7_ft, 6.8_ft, Rotation2d(-160_deg)};
+    const Pose2d sideStart{1.54_ft, 23.23_ft, 180_deg};
+    const Pose2d crossScale{23.7_ft, 6.8_ft, -160_deg};
 
     config.SetReversed(true);
 
     auto vector = std::vector<Translation2d>{
-        (sideStart + Transform2d{Translation2d(-13_ft, 0_ft), Rotation2d()})
+        (sideStart + Transform2d{Translation2d{-13_ft, 0_ft}, 0_deg})
             .Translation(),
-        (sideStart +
-         Transform2d{Translation2d(-19.5_ft, 5.0_ft), Rotation2d(-90_deg)})
+        (sideStart + Transform2d{Translation2d{-19.5_ft, 5.0_ft}, -90_deg})
             .Translation()};
 
     return TrajectoryGenerator::GenerateTrajectory(sideStart, vector,
diff --git a/third_party/allwpilib/wpinet/.styleguide b/third_party/allwpilib/wpinet/.styleguide
new file mode 100644
index 0000000..ab55757
--- /dev/null
+++ b/third_party/allwpilib/wpinet/.styleguide
@@ -0,0 +1,36 @@
+cppHeaderFileInclude {
+  \.h$
+  \.inc$
+  \.inl$
+}
+
+cppSrcFileInclude {
+  \.cpp$
+}
+
+generatedFileExclude {
+  src/main/native/thirdparty/
+
+  src/main/native/cpp/http_parser\.cpp$
+  src/main/native/include/wpinet/http_parser\.h$
+  src/main/native/resources/
+  src/main/native/linux/AvahiClient
+}
+
+licenseUpdateExclude {
+}
+
+repoRootNameOverride {
+  wpinet
+}
+
+includeGuardRoots {
+  wpinet/src/main/native/cpp/
+  wpinet/src/main/native/include/wpinet/
+  wpinet/src/test/native/cpp/
+}
+
+includeOtherLibs {
+  ^fmt/
+  ^wpi/
+}
diff --git a/third_party/allwpilib/wpinet/CMakeLists.txt b/third_party/allwpilib/wpinet/CMakeLists.txt
new file mode 100644
index 0000000..3da7bf0
--- /dev/null
+++ b/third_party/allwpilib/wpinet/CMakeLists.txt
@@ -0,0 +1,228 @@
+project(wpinet)
+
+include(SubDirList)
+include(GenResources)
+include(CompileWarnings)
+include(AddTest)
+
+file(GLOB wpinet_jni_src src/main/native/cpp/jni/WPINetJNI.cpp)
+
+# Java bindings
+if (WITH_JAVA)
+  find_package(Java REQUIRED)
+  find_package(JNI REQUIRED)
+  include(UseJava)
+  set(CMAKE_JAVA_COMPILE_FLAGS "-encoding" "UTF8" "-Xlint:unchecked")
+
+  set(CMAKE_JNI_TARGET true)
+
+  file(GLOB_RECURSE JAVA_SOURCES src/main/java/*.java)
+
+  if(${CMAKE_VERSION} VERSION_LESS "3.11.0")
+    set(CMAKE_JAVA_COMPILE_FLAGS "-h" "${CMAKE_CURRENT_BINARY_DIR}/jniheaders")
+    add_jar(wpinet_jar ${JAVA_SOURCES} INCLUDE_JARS wpiutil_jar OUTPUT_NAME wpinet)
+  else()
+    add_jar(wpinet_jar ${JAVA_SOURCES} INCLUDE_JARS wpiutil_jar OUTPUT_NAME wpinet GENERATE_NATIVE_HEADERS wpinet_jni_headers)
+  endif()
+
+  get_property(WPINET_JAR_FILE TARGET wpinet_jar PROPERTY JAR_FILE)
+  install(FILES ${WPINET_JAR_FILE} DESTINATION "${java_lib_dest}")
+
+  set_property(TARGET wpinet_jar PROPERTY FOLDER "java")
+
+  add_library(wpinetjni ${wpinet_jni_src})
+  wpilib_target_warnings(wpinetjni)
+  target_link_libraries(wpinetjni PUBLIC wpinet)
+
+  set_property(TARGET wpinetjni PROPERTY FOLDER "libraries")
+
+  if(${CMAKE_VERSION} VERSION_LESS "3.11.0")
+    target_include_directories(wpinetjni PRIVATE ${JNI_INCLUDE_DIRS})
+    target_include_directories(wpinetjni PRIVATE "${CMAKE_CURRENT_BINARY_DIR}/jniheaders")
+  else()
+    target_link_libraries(wpinetjni PRIVATE wpinet_jni_headers)
+  endif()
+  add_dependencies(wpinetjni wpinet_jar)
+
+  if (MSVC)
+    install(TARGETS wpinetjni RUNTIME DESTINATION "${jni_lib_dest}" COMPONENT Runtime)
+  endif()
+
+  install(TARGETS wpinetjni EXPORT wpinetjni DESTINATION "${main_lib_dest}")
+
+endif()
+
+set(THREADS_PREFER_PTHREAD_FLAG ON)
+find_package(Threads REQUIRED)
+
+if (NOT MSVC AND NOT APPLE)
+    find_library(ATOMIC NAMES atomic libatomic.so.1)
+    if (ATOMIC)
+        message(STATUS "Found libatomic: ${ATOMIC}")
+    endif()
+endif()
+
+GENERATE_RESOURCES(src/main/native/resources generated/main/cpp WPI wpi wpinet_resources_src)
+
+file(GLOB_RECURSE wpinet_native_src src/main/native/cpp/*.cpp src/main/native/thirdparty/tcpsockets/cpp/*.cpp)
+list(REMOVE_ITEM wpinet_native_src ${wpinet_jni_src})
+file(GLOB_RECURSE wpinet_unix_src src/main/native/unix/*.cpp)
+file(GLOB_RECURSE wpinet_linux_src src/main/native/linux/*.cpp)
+file(GLOB_RECURSE wpinet_macos_src src/main/native/macOS/*.cpp)
+file(GLOB_RECURSE wpinet_windows_src src/main/native/windows/*.cpp)
+
+file(GLOB uv_native_src src/main/native/thirdparty/libuv/src/*.cpp)
+
+file(GLOB uv_windows_src src/main/native/thirdparty/libuv/src/win/*.cpp)
+
+set(uv_unix_src
+    src/main/native/thirdparty/libuv/src/unix/async.cpp
+    src/main/native/thirdparty/libuv/src/unix/core.cpp
+    src/main/native/thirdparty/libuv/src/unix/dl.cpp
+    src/main/native/thirdparty/libuv/src/unix/fs.cpp
+    src/main/native/thirdparty/libuv/src/unix/getaddrinfo.cpp
+    src/main/native/thirdparty/libuv/src/unix/getnameinfo.cpp
+    src/main/native/thirdparty/libuv/src/unix/loop-watcher.cpp
+    src/main/native/thirdparty/libuv/src/unix/loop.cpp
+    src/main/native/thirdparty/libuv/src/unix/pipe.cpp
+    src/main/native/thirdparty/libuv/src/unix/poll.cpp
+    src/main/native/thirdparty/libuv/src/unix/process.cpp
+    src/main/native/thirdparty/libuv/src/unix/random-devurandom.cpp
+    src/main/native/thirdparty/libuv/src/unix/random-getentropy.cpp
+    src/main/native/thirdparty/libuv/src/unix/random-getrandom.cpp
+    src/main/native/thirdparty/libuv/src/unix/signal.cpp
+    src/main/native/thirdparty/libuv/src/unix/stream.cpp
+    src/main/native/thirdparty/libuv/src/unix/tcp.cpp
+    src/main/native/thirdparty/libuv/src/unix/thread.cpp
+    src/main/native/thirdparty/libuv/src/unix/tty.cpp
+    src/main/native/thirdparty/libuv/src/unix/udp.cpp
+)
+
+set(uv_darwin_src
+    src/main/native/thirdparty/libuv/src/unix/bsd-ifaddrs.cpp
+    src/main/native/thirdparty/libuv/src/unix/darwin.cpp
+    src/main/native/thirdparty/libuv/src/unix/darwin-proctitle.cpp
+    src/main/native/thirdparty/libuv/src/unix/fsevents.cpp
+    src/main/native/thirdparty/libuv/src/unix/kqueue.cpp
+    src/main/native/thirdparty/libuv/src/unix/proctitle.cpp
+)
+
+set(uv_linux_src
+    src/main/native/thirdparty/libuv/src/unix/epoll.cpp
+    src/main/native/thirdparty/libuv/src/unix/linux-core.cpp
+    src/main/native/thirdparty/libuv/src/unix/linux-inotify.cpp
+    src/main/native/thirdparty/libuv/src/unix/linux-syscalls.cpp
+    src/main/native/thirdparty/libuv/src/unix/procfs-exepath.cpp
+    src/main/native/thirdparty/libuv/src/unix/proctitle.cpp
+    src/main/native/thirdparty/libuv/src/unix/random-sysctl-linux.cpp
+)
+
+add_library(wpinet ${wpinet_native_src} ${wpinet_resources_src})
+set_target_properties(wpinet PROPERTIES DEBUG_POSTFIX "d")
+
+set_property(TARGET wpinet PROPERTY FOLDER "libraries")
+
+target_compile_features(wpinet PUBLIC cxx_std_20)
+wpilib_target_warnings(wpinet)
+target_link_libraries(wpinet PUBLIC wpiutil)
+
+if (NOT USE_SYSTEM_LIBUV)
+    target_sources(wpinet PRIVATE ${uv_native_src})
+    install(DIRECTORY src/main/native/thirdparty/libuv/include/ DESTINATION "${include_dest}/wpinet")
+    target_include_directories(wpinet PRIVATE
+        src/main/native/thirdparty/libuv/src)
+    target_include_directories(wpinet PUBLIC
+                            $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/src/main/native/thirdparty/libuv/include>
+                            $<INSTALL_INTERFACE:${include_dest}/wpinet>)
+    if(NOT MSVC)
+        target_sources(wpinet PRIVATE ${uv_unix_src})
+        if (APPLE)
+            target_sources(wpinet PRIVATE ${uv_darwin_src})
+        else()
+            target_sources(wpinet PRIVATE ${uv_linux_src})
+        endif()
+        target_compile_definitions(wpinet PRIVATE -D_GNU_SOURCE)
+    else()
+        target_sources(wpinet PRIVATE ${uv_windows_src})
+        if(BUILD_SHARED_LIBS)
+            target_compile_definitions(wpinet PRIVATE -DBUILDING_UV_SHARED)
+        endif()
+    endif()
+else()
+    find_package(PkgConfig REQUIRED)
+    pkg_check_modules(libuv REQUIRED IMPORTED_TARGET libuv)
+    target_link_libraries(wpinet PUBLIC PkgConfig::libuv)
+endif()
+
+if (MSVC)
+    target_sources(wpinet PRIVATE ${wpinet_windows_src})
+else ()
+    target_sources(wpinet PRIVATE ${wpinet_unix_src})
+    if (APPLE)
+        target_sources(wpinet PRIVATE ${wpinet_macos_src})
+    else()
+        target_sources(wpinet PRIVATE ${wpinet_linux_src})
+    endif()
+endif()
+
+install(DIRECTORY src/main/native/thirdparty/tcpsockets/include/ DESTINATION "${include_dest}/wpinet")
+target_include_directories(wpinet PUBLIC
+                            $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/src/main/native/thirdparty/tcpsockets/include>
+                            $<INSTALL_INTERFACE:${include_dest}/wpinet>)
+
+install(DIRECTORY src/main/native/include/ DESTINATION "${include_dest}/wpinet")
+target_include_directories(wpinet PUBLIC
+                            $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/src/main/native/include>
+                            $<INSTALL_INTERFACE:${include_dest}/wpinet>)
+
+install(TARGETS wpinet EXPORT wpinet DESTINATION "${main_lib_dest}")
+
+if (WITH_JAVA AND MSVC)
+    install(TARGETS wpinet RUNTIME DESTINATION "${jni_lib_dest}" COMPONENT Runtime)
+endif()
+
+if (WITH_FLAT_INSTALL)
+    set (wpinet_config_dir ${wpilib_dest})
+else()
+    set (wpinet_config_dir share/wpinet)
+endif()
+
+configure_file(wpinet-config.cmake.in ${WPILIB_BINARY_DIR}/wpinet-config.cmake )
+install(FILES ${WPILIB_BINARY_DIR}/wpinet-config.cmake DESTINATION ${wpinet_config_dir})
+install(EXPORT wpinet DESTINATION ${wpinet_config_dir})
+
+SUBDIR_LIST(wpinet_examples "${CMAKE_CURRENT_SOURCE_DIR}/examples")
+foreach(example ${wpinet_examples})
+    file(GLOB wpinet_example_src examples/${example}/*.cpp)
+    if(wpinet_example_src)
+        add_executable(wpinet_${example} ${wpinet_example_src})
+        wpilib_target_warnings(wpinet_${example})
+        target_link_libraries(wpinet_${example} wpinet)
+        set_property(TARGET wpinet_${example} PROPERTY FOLDER "examples")
+    endif()
+endforeach()
+
+if (UNIX AND NOT APPLE)
+    set (LIBUTIL -lutil)
+else()
+    set (LIBUTIL)
+endif()
+
+file(GLOB netconsoleServer_src src/netconsoleServer/native/cpp/*.cpp)
+add_executable(netconsoleServer ${netconsoleServer_src})
+wpilib_target_warnings(netconsoleServer)
+target_link_libraries(netconsoleServer wpinet ${LIBUTIL})
+
+file(GLOB netconsoleTee_src src/netconsoleTee/native/cpp/*.cpp)
+add_executable(netconsoleTee ${netconsoleTee_src})
+wpilib_target_warnings(netconsoleTee)
+target_link_libraries(netconsoleTee wpinet)
+
+set_property(TARGET netconsoleServer PROPERTY FOLDER "examples")
+set_property(TARGET netconsoleTee PROPERTY FOLDER "examples")
+
+if (WITH_TESTS)
+    wpilib_add_test(wpinet src/test/native/cpp)
+    target_include_directories(wpinet_test PRIVATE src/test/native/include)
+    target_link_libraries(wpinet_test wpinet ${LIBUTIL} gmock_main)
+endif()
diff --git a/third_party/allwpilib/wpinet/build.gradle b/third_party/allwpilib/wpinet/build.gradle
new file mode 100644
index 0000000..b149675
--- /dev/null
+++ b/third_party/allwpilib/wpinet/build.gradle
@@ -0,0 +1,284 @@
+apply from: "${rootDir}/shared/resources.gradle"
+
+ext {
+    baseId = 'wpinet'
+    groupId = 'edu.wpi.first.net'
+
+    nativeName = 'wpinet'
+    devMain = 'edu.wpi.first.net.DevMain'
+    def generateTask = createGenerateResourcesTask('main', 'WPI', 'wpi', project)
+
+    splitSetup = {
+        it.tasks.withType(CppCompile) {
+            dependsOn generateTask
+        }
+        it.sources {
+            libuvCpp(CppSourceSet) {
+                source {
+                    srcDirs 'src/main/native/thirdparty/libuv/src'
+                    include '*.cpp'
+                }
+                exportedHeaders {
+                    srcDirs 'src/main/native/include', 'src/main/native/thirdparty/libuv/include', 'src/main/native/thirdparty/libuv/src'
+                }
+            }
+            tcpsocketsCpp(CppSourceSet) {
+                source {
+                    srcDirs 'src/main/native/thirdparty/tcpsockets/cpp'
+                    include '*.cpp'
+                }
+                exportedHeaders {
+                    srcDirs 'src/main/native/include', 'src/main/native/thirdparty/tcpsockets/include'
+                }
+            }
+            resourcesCpp(CppSourceSet) {
+                source {
+                    srcDirs "$buildDir/generated/main/cpp", "$rootDir/shared/singlelib"
+                    include '*.cpp'
+                }
+                exportedHeaders {
+                    srcDirs 'src/main/native/include'
+                }
+            }
+        }
+        if (!it.targetPlatform.operatingSystem.isWindows()) {
+            it.cppCompiler.define '_GNU_SOURCE'
+            it.sources {
+                libuvUnixCpp(CppSourceSet) {
+                    source {
+                        srcDirs 'src/main/native/thirdparty/libuv/src/unix'
+                        includes = [
+                            'async.cpp',
+                            'core.cpp',
+                            'dl.cpp',
+                            'fs.cpp',
+                            'getaddrinfo.cpp',
+                            'getnameinfo.cpp',
+                            'loop-watcher.cpp',
+                            'loop.cpp',
+                            'pipe.cpp',
+                            'poll.cpp',
+                            'process.cpp',
+                            'random-devurandom.cpp',
+                            'random-getentropy.cpp',
+                            'random-getrandom.cpp',
+                            'signal.cpp',
+                            'stream.cpp',
+                            'tcp.cpp',
+                            'thread.cpp',
+                            'timer.cpp',
+                            'tty.cpp',
+                            'udp.cpp',
+                        ]
+                    }
+                    exportedHeaders {
+                        srcDirs 'src/main/native/include', 'src/main/native/thirdparty/libuv/include', 'src/main/native/thirdparty/libuv/src'
+                    }
+                }
+                wpinetUnixCpp(CppSourceSet) {
+                    source {
+                        srcDirs 'src/main/native/unix'
+                        include '**/*.cpp'
+                    }
+                    exportedHeaders {
+                        srcDirs 'src/main/native/include', 'src/main/native/cpp'
+                        include '**/*.h'
+                    }
+                }
+            }
+        }
+        if (it.targetPlatform.operatingSystem.isWindows()) {
+            if (it in SharedLibraryBinarySpec) {
+                it.cppCompiler.define 'BUILDING_UV_SHARED'
+            }
+            it.sources {
+                libuvWindowsCpp(CppSourceSet) {
+                    source {
+                        srcDirs 'src/main/native/thirdparty/libuv/src/win'
+                        include '*.cpp'
+                    }
+                    exportedHeaders {
+                        srcDirs 'src/main/native/include', 'src/main/native/thirdparty/libuv/include', 'src/main/native/thirdparty/libuv/src'
+                    }
+                }
+                wpinetWindowsCpp(CppSourceSet) {
+                    source {
+                        srcDirs 'src/main/native/windows'
+                        include '**/*.cpp'
+                    }
+                    exportedHeaders {
+                        srcDirs 'src/main/native/include', 'src/main/native/cpp'
+                        include '**/*.h'
+                    }
+                }
+            }
+        } else if (it.targetPlatform.operatingSystem.isMacOsX()) {
+            it.sources {
+                libuvMacCpp(CppSourceSet) {
+                    source {
+                        srcDirs 'src/main/native/thirdparty/libuv/src/unix'
+                        includes = [
+                            'bsd-ifaddrs.cpp',
+                            'darwin.cpp',
+                            'darwin-proctitle.cpp',
+                            'fsevents.cpp',
+                            'kqueue.cpp',
+                            'proctitle.cpp'
+                        ]
+                    }
+                    exportedHeaders {
+                        srcDirs 'src/main/native/include', 'src/main/native/thirdparty/libuv/include', 'src/main/native/thirdparty/libuv/src'
+                    }
+                }
+                wpinetmacOSCpp(CppSourceSet) {
+                    source {
+                        srcDirs 'src/main/native/macOS'
+                        include '**/*.cpp'
+                    }
+                    exportedHeaders {
+                        srcDirs 'src/main/native/include', 'src/main/native/cpp'
+                        include '**/*.h'
+                    }
+                }
+            }
+        } else {
+            it.sources {
+                libuvLinuxCpp(CppSourceSet) {
+                    source {
+                        srcDirs 'src/main/native/thirdparty/libuv/src/unix'
+                        includes = [
+                            'epoll.cpp',
+                            'linux-core.cpp',
+                            'linux-inotify.cpp',
+                            'linux-syscalls.cpp',
+                            'procfs-exepath.cpp',
+                            'proctitle.cpp',
+                            'random-sysctl-linux.cpp',
+                        ]
+                    }
+                    exportedHeaders {
+                        srcDirs 'src/main/native/include', 'src/main/native/thirdparty/libuv/include', 'src/main/native/thirdparty/libuv/src'
+                    }
+                }
+                wpinetLinuxCpp(CppSourceSet) {
+                    source {
+                        srcDirs 'src/main/native/linux'
+                        include '**/*.cpp'
+                    }
+                    exportedHeaders {
+                        srcDirs 'src/main/native/include', 'src/main/native/cpp', 'src/main/native/fmtlib/include'
+                        include '**/*.h'
+                    }
+                }
+            }
+        }
+    }
+}
+
+def examplesMap = [:];
+file("$projectDir/examples").list(new FilenameFilter() {
+            @Override
+            public boolean accept(File current, String name) {
+                return new File(current, name).isDirectory();
+            }
+        }).each {
+            examplesMap.put(it, [])
+        }
+
+apply from: "${rootDir}/shared/jni/setupBuild.gradle"
+
+nativeUtils.exportsConfigs {
+    wpinet {
+        x64ExcludeSymbols = [
+            '_CT??_R0?AV_System_error',
+            '_CT??_R0?AVexception',
+            '_CT??_R0?AVfailure',
+            '_CT??_R0?AVruntime_error',
+            '_CT??_R0?AVsystem_error',
+            '_CTA5?AVfailure',
+            '_TI5?AVfailure',
+            '_CT??_R0?AVout_of_range',
+            '_CTA3?AVout_of_range',
+            '_TI3?AVout_of_range',
+            '_CT??_R0?AVbad_cast'
+        ]
+    }
+}
+
+cppHeadersZip {
+    from('src/main/native/thirdparty/libuv/include') {
+        into '/'
+    }
+    from('src/main/native/third_party/tcpsockets/include') {
+        into '/'
+    }
+}
+
+model {
+    components {
+        all {
+            it.sources.each {
+                it.exportedHeaders {
+                    srcDirs 'src/main/native/include', 'src/main/native/thirdparty/libuv/include', 'src/main/native/thirdparty/tcpsockets/include', 'src/main/native/thirdparty/libuv/src'
+                }
+            }
+        }
+    }
+}
+
+model {
+    components {
+        examplesMap.each { key, value ->
+            "${key}"(NativeExecutableSpec) {
+                targetBuildTypes 'debug'
+                binaries.all {
+                    lib library: 'wpinet', linkage: 'shared'
+                    lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+                }
+                sources {
+                    cpp {
+                        source {
+                            srcDirs 'examples/' + "${key}"
+                            include '**/*.cpp'
+                        }
+                    }
+                }
+            }
+        }
+        netconsoleServer(NativeExecutableSpec) {
+            sources {
+                cpp {
+                    source {
+                        srcDirs = [
+                            'src/netconsoleServer/native/cpp'
+                        ]
+                        includes = ['**/*.cpp']
+                    }
+                }
+            }
+            binaries.all { binary ->
+                lib project: ':wpinet', library: 'wpinet', linkage: 'static'
+                lib project: ':wpiutil', library: 'wpiutil', linkage: 'static'
+                if (binary.targetPlatform.operatingSystem.isLinux()) {
+                    linker.args "-lutil"
+                }
+            }
+        }
+        netconsoleTee(NativeExecutableSpec) {
+            sources {
+                cpp {
+                    source {
+                        srcDirs = [
+                            'src/netconsoleTee/native/cpp'
+                        ]
+                        includes = ['**/*.cpp']
+                    }
+                }
+            }
+            binaries.all { binary ->
+                lib project: ':wpinet', library: 'wpinet', linkage: 'static'
+                lib project: ':wpiutil', library: 'wpiutil', linkage: 'static'
+            }
+        }
+    }
+}
diff --git a/third_party/allwpilib/wpinet/examples/dsclient/dsclient.cpp b/third_party/allwpilib/wpinet/examples/dsclient/dsclient.cpp
new file mode 100644
index 0000000..5135d70
--- /dev/null
+++ b/third_party/allwpilib/wpinet/examples/dsclient/dsclient.cpp
@@ -0,0 +1,36 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <cstdio>
+
+#include <fmt/format.h>
+#include <wpi/Logger.h>
+
+#include "wpinet/DsClient.h"
+#include "wpinet/EventLoopRunner.h"
+#include "wpinet/uv/Error.h"
+
+namespace uv = wpi::uv;
+
+static void logfunc(unsigned int level, const char* file, unsigned int line,
+                    const char* msg) {
+  std::fprintf(stderr, "(%d) %s:%d: %s\n", level, file, line, msg);
+}
+
+int main() {
+  wpi::Logger logger{logfunc, 0};
+
+  // Kick off the event loop on a separate thread
+  wpi::EventLoopRunner loop;
+  std::shared_ptr<wpi::DsClient> client;
+  loop.ExecAsync([&](uv::Loop& loop) {
+    client = wpi::DsClient::Create(loop, logger);
+    client->setIp.connect(
+        [](std::string_view ip) { fmt::print("got IP: {}\n", ip); });
+    client->clearIp.connect([] { std::fputs("cleared IP\n", stdout); });
+  });
+
+  // wait for a keypress to terminate
+  std::getchar();
+}
diff --git a/third_party/allwpilib/wpinet/examples/parallelconnect/parallelconnect.cpp b/third_party/allwpilib/wpinet/examples/parallelconnect/parallelconnect.cpp
new file mode 100644
index 0000000..fecdac8
--- /dev/null
+++ b/third_party/allwpilib/wpinet/examples/parallelconnect/parallelconnect.cpp
@@ -0,0 +1,51 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <cstdio>
+
+#include <wpi/Logger.h>
+
+#include "wpinet/EventLoopRunner.h"
+#include "wpinet/ParallelTcpConnector.h"
+#include "wpinet/uv/Error.h"
+#include "wpinet/uv/Tcp.h"
+
+namespace uv = wpi::uv;
+
+static void logfunc(unsigned int level, const char* file, unsigned int line,
+                    const char* msg) {
+  std::fprintf(stderr, "(%d) %s:%d: %s\n", level, file, line, msg);
+}
+
+int main() {
+  wpi::Logger logger{logfunc, 0};
+
+  // Kick off the event loop on a separate thread
+  wpi::EventLoopRunner loop;
+  std::shared_ptr<wpi::ParallelTcpConnector> connect;
+  loop.ExecAsync([&](uv::Loop& loop) {
+    connect = wpi::ParallelTcpConnector::Create(
+        loop, uv::Timer::Time{2000}, logger, [&](uv::Tcp& tcp) {
+          std::fputs("Got connection, accepting!\n", stdout);
+          tcp.StartRead();
+          connect->Succeeded(tcp);
+          tcp.end.connect([&] {
+            std::fputs("TCP connection ended, disconnecting!\n", stdout);
+            tcp.Close();
+            connect->Disconnected();
+          });
+          tcp.error.connect([&](uv::Error) {
+            std::fputs("TCP error, disconnecting!\n", stdout);
+            connect->Disconnected();
+          });
+        });
+    connect->SetServers({{{"roborio-294-frc.local", 8080},
+                          {"roborio-294-frc.frc-field.local", 8080},
+                          {"10.2.94.2", 8080},
+                          {"127.0.0.1", 8080}}});
+  });
+
+  // wait for a keypress to terminate
+  std::getchar();
+}
diff --git a/third_party/allwpilib/wpinet/examples/webserver/webserver.cpp b/third_party/allwpilib/wpinet/examples/webserver/webserver.cpp
new file mode 100644
index 0000000..0f1e5c4
--- /dev/null
+++ b/third_party/allwpilib/wpinet/examples/webserver/webserver.cpp
@@ -0,0 +1,88 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <cstdio>
+
+#include <fmt/format.h>
+
+#include "wpinet/EventLoopRunner.h"
+#include "wpinet/HttpServerConnection.h"
+#include "wpinet/UrlParser.h"
+#include "wpinet/uv/Loop.h"
+#include "wpinet/uv/Tcp.h"
+
+namespace uv = wpi::uv;
+
+class MyHttpServerConnection : public wpi::HttpServerConnection {
+ public:
+  explicit MyHttpServerConnection(std::shared_ptr<uv::Stream> stream)
+      : HttpServerConnection(stream) {}
+
+ protected:
+  void ProcessRequest() override;
+};
+
+void MyHttpServerConnection::ProcessRequest() {
+  fmt::print(stderr, "HTTP request: '{}'\n", m_request.GetUrl());
+  wpi::UrlParser url{m_request.GetUrl(),
+                     m_request.GetMethod() == wpi::HTTP_CONNECT};
+  if (!url.IsValid()) {
+    // failed to parse URL
+    SendError(400);
+    return;
+  }
+
+  std::string_view path;
+  if (url.HasPath()) {
+    path = url.GetPath();
+  }
+  fmt::print(stderr, "path: \"{}\"\n", path);
+
+  std::string_view query;
+  if (url.HasQuery()) {
+    query = url.GetQuery();
+  }
+  fmt::print(stderr, "query: \"{}\"\n", query);
+
+  const bool isGET = m_request.GetMethod() == wpi::HTTP_GET;
+  if (isGET && path == "/") {
+    // build HTML root page
+    SendResponse(200, "OK", "text/html",
+                 "<html><head><title>WebServer Example</title></head>"
+                 "<body><p>This is an example root page from the webserver."
+                 "</body></html>");
+  } else {
+    SendError(404, "Resource not found");
+  }
+}
+
+int main() {
+  // Kick off the event loop on a separate thread
+  wpi::EventLoopRunner loop;
+  loop.ExecAsync([](uv::Loop& loop) {
+    auto tcp = uv::Tcp::Create(loop);
+
+    // bind to listen address and port
+    tcp->Bind("", 8080);
+
+    // when we get a connection, accept it and start reading
+    tcp->connection.connect([srv = tcp.get()] {
+      auto tcp = srv->Accept();
+      if (!tcp) {
+        return;
+      }
+      std::fputs("Got a connection\n", stderr);
+      auto conn = std::make_shared<MyHttpServerConnection>(tcp);
+      tcp->SetData(conn);
+    });
+
+    // start listening for incoming connections
+    tcp->Listen();
+
+    std::fputs("Listening on port 8080\n", stderr);
+  });
+
+  // wait for a keypress to terminate
+  std::getchar();
+}
diff --git a/third_party/allwpilib/wpinet/src/dev/java/edu/wpi/first/net/DevMain.java b/third_party/allwpilib/wpinet/src/dev/java/edu/wpi/first/net/DevMain.java
new file mode 100644
index 0000000..7c71a45
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/dev/java/edu/wpi/first/net/DevMain.java
@@ -0,0 +1,17 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.net;
+
+import edu.wpi.first.util.RuntimeDetector;
+
+public final class DevMain {
+  /** Main entry point. */
+  public static void main(String[] args) {
+    System.out.println("Hello World!");
+    System.out.println(RuntimeDetector.getPlatformPath());
+  }
+
+  private DevMain() {}
+}
diff --git a/third_party/allwpilib/wpinet/src/dev/native/cpp/main.cpp b/third_party/allwpilib/wpinet/src/dev/native/cpp/main.cpp
new file mode 100644
index 0000000..d0e2f92
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/dev/native/cpp/main.cpp
@@ -0,0 +1,11 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <fmt/core.h>
+#include <wpi/SmallString.h>
+
+int main() {
+  wpi::SmallString<128> v1("Hello");
+  fmt::print("{}\n", v1.str());
+}
diff --git a/third_party/allwpilib/wpinet/src/main/java/edu/wpi/first/net/MulticastServiceAnnouncer.java b/third_party/allwpilib/wpinet/src/main/java/edu/wpi/first/net/MulticastServiceAnnouncer.java
new file mode 100644
index 0000000..6dff454
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/java/edu/wpi/first/net/MulticastServiceAnnouncer.java
@@ -0,0 +1,57 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.net;
+
+import java.util.Map;
+
+/** Class to announce over mDNS that a service is available. */
+public class MulticastServiceAnnouncer implements AutoCloseable {
+  private final int m_handle;
+
+  /**
+   * Creates a MulticastServiceAnnouncer.
+   *
+   * @param serviceName service name
+   * @param serviceType service type
+   * @param port port
+   * @param txt txt
+   */
+  public MulticastServiceAnnouncer(
+      String serviceName, String serviceType, int port, Map<String, String> txt) {
+    String[] keys = txt.keySet().toArray(String[]::new);
+    String[] values = txt.values().toArray(String[]::new);
+    m_handle =
+        WPINetJNI.createMulticastServiceAnnouncer(serviceName, serviceType, port, keys, values);
+  }
+
+  /**
+   * Creates a MulticastServiceAnnouncer.
+   *
+   * @param serviceName service name
+   * @param serviceType service type
+   * @param port port
+   */
+  public MulticastServiceAnnouncer(String serviceName, String serviceType, int port) {
+    m_handle =
+        WPINetJNI.createMulticastServiceAnnouncer(serviceName, serviceType, port, null, null);
+  }
+
+  @Override
+  public void close() {
+    WPINetJNI.freeMulticastServiceAnnouncer(m_handle);
+  }
+
+  public void start() {
+    WPINetJNI.startMulticastServiceAnnouncer(m_handle);
+  }
+
+  public void stop() {
+    WPINetJNI.stopMulticastServiceAnnouncer(m_handle);
+  }
+
+  public boolean hasImplementation() {
+    return WPINetJNI.getMulticastServiceAnnouncerHasImplementation(m_handle);
+  }
+}
diff --git a/third_party/allwpilib/wpinet/src/main/java/edu/wpi/first/net/MulticastServiceResolver.java b/third_party/allwpilib/wpinet/src/main/java/edu/wpi/first/net/MulticastServiceResolver.java
new file mode 100644
index 0000000..2426de2
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/java/edu/wpi/first/net/MulticastServiceResolver.java
@@ -0,0 +1,44 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.net;
+
+/** Class to resolve a service over mDNS. */
+public class MulticastServiceResolver implements AutoCloseable {
+  private final int m_handle;
+
+  /**
+   * Creates a MulticastServiceResolver.
+   *
+   * @param serviceType service type to look for
+   */
+  public MulticastServiceResolver(String serviceType) {
+    m_handle = WPINetJNI.createMulticastServiceResolver(serviceType);
+  }
+
+  @Override
+  public void close() {
+    WPINetJNI.freeMulticastServiceResolver(m_handle);
+  }
+
+  public void start() {
+    WPINetJNI.startMulticastServiceResolver(m_handle);
+  }
+
+  public void stop() {
+    WPINetJNI.stopMulticastServiceResolver(m_handle);
+  }
+
+  public boolean hasImplementation() {
+    return WPINetJNI.getMulticastServiceResolverHasImplementation(m_handle);
+  }
+
+  public int getEventHandle() {
+    return WPINetJNI.getMulticastServiceResolverEventHandle(m_handle);
+  }
+
+  public ServiceData[] getData() {
+    return WPINetJNI.getMulticastServiceResolverData(m_handle);
+  }
+}
diff --git a/third_party/allwpilib/wpinet/src/main/java/edu/wpi/first/net/PortForwarder.java b/third_party/allwpilib/wpinet/src/main/java/edu/wpi/first/net/PortForwarder.java
new file mode 100644
index 0000000..904e4f0
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/java/edu/wpi/first/net/PortForwarder.java
@@ -0,0 +1,36 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.net;
+
+/**
+ * Forward ports to another host. This is primarily useful for accessing Ethernet-connected devices
+ * from a computer tethered to the RoboRIO USB port.
+ */
+public final class PortForwarder {
+  private PortForwarder() {
+    throw new UnsupportedOperationException("This is a utility class!");
+  }
+
+  /**
+   * Forward a local TCP port to a remote host and port. Note that local ports less than 1024 won't
+   * work as a normal user.
+   *
+   * @param port local port number
+   * @param remoteHost remote IP address / DNS name
+   * @param remotePort remote port number
+   */
+  public static void add(int port, String remoteHost, int remotePort) {
+    WPINetJNI.addPortForwarder(port, remoteHost, remotePort);
+  }
+
+  /**
+   * Stop TCP forwarding on a port.
+   *
+   * @param port local port number
+   */
+  public static void remove(int port) {
+    WPINetJNI.removePortForwarder(port);
+  }
+}
diff --git a/third_party/allwpilib/wpinet/src/main/java/edu/wpi/first/net/ServiceData.java b/third_party/allwpilib/wpinet/src/main/java/edu/wpi/first/net/ServiceData.java
new file mode 100644
index 0000000..126526b
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/java/edu/wpi/first/net/ServiceData.java
@@ -0,0 +1,66 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.net;
+
+import java.util.HashMap;
+import java.util.Map;
+
+/** Service data for MulticastServiceResolver. */
+public class ServiceData {
+  /**
+   * Constructs a ServiceData.
+   *
+   * @param ipv4Address ipv4Address
+   * @param port port
+   * @param serviceName found service name
+   * @param hostName found host name
+   * @param keys txt keys
+   * @param values txt values
+   */
+  public ServiceData(
+      long ipv4Address,
+      int port,
+      String serviceName,
+      String hostName,
+      String[] keys,
+      String[] values) {
+    this.m_serviceName = serviceName;
+    this.m_hostName = hostName;
+    this.m_port = port;
+    this.m_ipv4Address = ipv4Address;
+
+    m_txt = new HashMap<>();
+
+    for (int i = 0; i < keys.length; i++) {
+      m_txt.put(keys[i], values[i]);
+    }
+  }
+
+  public Map<String, String> getTxt() {
+    return m_txt;
+  }
+
+  public String getHostName() {
+    return m_hostName;
+  }
+
+  public String getServiceName() {
+    return m_serviceName;
+  }
+
+  public int getPort() {
+    return m_port;
+  }
+
+  public long getIpv4Address() {
+    return m_ipv4Address;
+  }
+
+  private final Map<String, String> m_txt;
+  private final long m_ipv4Address;
+  private final int m_port;
+  private final String m_serviceName;
+  private final String m_hostName;
+}
diff --git a/third_party/allwpilib/wpinet/src/main/java/edu/wpi/first/net/WPINetJNI.java b/third_party/allwpilib/wpinet/src/main/java/edu/wpi/first/net/WPINetJNI.java
new file mode 100644
index 0000000..d0bcf7d
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/java/edu/wpi/first/net/WPINetJNI.java
@@ -0,0 +1,85 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.net;
+
+import edu.wpi.first.util.RuntimeLoader;
+import java.io.IOException;
+import java.util.concurrent.atomic.AtomicBoolean;
+
+public class WPINetJNI {
+  static boolean libraryLoaded = false;
+  static RuntimeLoader<WPINetJNI> loader = null;
+
+  public static class Helper {
+    private static AtomicBoolean extractOnStaticLoad = new AtomicBoolean(true);
+
+    public static boolean getExtractOnStaticLoad() {
+      return extractOnStaticLoad.get();
+    }
+
+    public static void setExtractOnStaticLoad(boolean load) {
+      extractOnStaticLoad.set(load);
+    }
+  }
+
+  static {
+    if (Helper.getExtractOnStaticLoad()) {
+      try {
+        loader =
+            new RuntimeLoader<>(
+                "wpinetjni", RuntimeLoader.getDefaultExtractionRoot(), WPINetJNI.class);
+        loader.loadLibrary();
+      } catch (IOException ex) {
+        ex.printStackTrace();
+        System.exit(1);
+      }
+      libraryLoaded = true;
+    }
+  }
+
+  /**
+   * Force load the library.
+   *
+   * @throws IOException if the library failed to load
+   */
+  public static synchronized void forceLoad() throws IOException {
+    if (libraryLoaded) {
+      return;
+    }
+    loader =
+        new RuntimeLoader<>("wpinetjni", RuntimeLoader.getDefaultExtractionRoot(), WPINetJNI.class);
+    loader.loadLibrary();
+    libraryLoaded = true;
+  }
+
+  public static native void addPortForwarder(int port, String remoteHost, int remotePort);
+
+  public static native void removePortForwarder(int port);
+
+  public static native int createMulticastServiceAnnouncer(
+      String serviceName, String serviceType, int port, String[] keys, String[] values);
+
+  public static native void freeMulticastServiceAnnouncer(int handle);
+
+  public static native void startMulticastServiceAnnouncer(int handle);
+
+  public static native void stopMulticastServiceAnnouncer(int handle);
+
+  public static native boolean getMulticastServiceAnnouncerHasImplementation(int handle);
+
+  public static native int createMulticastServiceResolver(String serviceType);
+
+  public static native void freeMulticastServiceResolver(int handle);
+
+  public static native void startMulticastServiceResolver(int handle);
+
+  public static native void stopMulticastServiceResolver(int handle);
+
+  public static native boolean getMulticastServiceResolverHasImplementation(int handle);
+
+  public static native int getMulticastServiceResolverEventHandle(int handle);
+
+  public static native ServiceData[] getMulticastServiceResolverData(int handle);
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/DsClient.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/DsClient.cpp
new file mode 100644
index 0000000..86f8f00
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/DsClient.cpp
@@ -0,0 +1,107 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/DsClient.h"
+
+#include <fmt/format.h>
+#include <wpi/Logger.h>
+#include <wpi/StringExtras.h>
+#include <wpi/json.h>
+
+#include "wpinet/uv/Tcp.h"
+#include "wpinet/uv/Timer.h"
+
+using namespace wpi;
+
+static constexpr uv::Timer::Time kReconnectTime{500};
+
+DsClient::DsClient(wpi::uv::Loop& loop, wpi::Logger& logger,
+                   const private_init&)
+    : m_logger{logger},
+      m_tcp{uv::Tcp::Create(loop)},
+      m_timer{uv::Timer::Create(loop)} {
+  m_tcp->end.connect([this] {
+    WPI_DEBUG4(m_logger, "DS connection closed");
+    clearIp();
+    // try to connect again
+    m_tcp->Reuse([this] { m_timer->Start(kReconnectTime); });
+  });
+  m_tcp->data.connect([this](wpi::uv::Buffer buf, size_t len) {
+    HandleIncoming({buf.base, len});
+  });
+  m_timer->timeout.connect([this] { Connect(); });
+  Connect();
+}
+
+DsClient::~DsClient() = default;
+
+void DsClient::Close() {
+  m_tcp->Close();
+  m_timer->Close();
+  clearIp();
+}
+
+void DsClient::Connect() {
+  auto connreq = std::make_shared<uv::TcpConnectReq>();
+  connreq->connected.connect([this] {
+    m_json.clear();
+    m_tcp->StopRead();
+    m_tcp->StartRead();
+  });
+
+  connreq->error = [this](uv::Error err) {
+    WPI_DEBUG4(m_logger, "DS connect failure: {}", err.str());
+    // try to connect again
+    m_tcp->Reuse([this] { m_timer->Start(kReconnectTime); });
+  };
+
+  WPI_DEBUG4(m_logger, "Starting DS connection attempt");
+  m_tcp->Connect("127.0.0.1", 1742, connreq);
+}
+
+void DsClient::HandleIncoming(std::string_view in) {
+  // this is very bare-bones, as there are never nested {} in these messages
+  while (!in.empty()) {
+    // if json is empty, look for the first { (and discard)
+    if (m_json.empty()) {
+      auto start = in.find('{');
+      in = wpi::slice(in, start, std::string_view::npos);
+    }
+
+    // look for the terminating } (and save)
+    auto end = in.find('}');
+    if (end == std::string_view::npos) {
+      m_json.append(in);
+      return;  // nothing left to read
+    }
+
+    // have complete json message
+    ++end;
+    m_json.append(wpi::slice(in, 0, end));
+    in = wpi::slice(in, end, std::string_view::npos);
+    ParseJson();
+    m_json.clear();
+  }
+}
+
+void DsClient::ParseJson() {
+  WPI_DEBUG4(m_logger, "DsClient JSON: {}", m_json);
+  unsigned int ip = 0;
+  try {
+    ip = wpi::json::parse(m_json).at("robotIP").get<unsigned int>();
+  } catch (wpi::json::exception& e) {
+    WPI_INFO(m_logger, "DsClient JSON error: {}", e.what());
+    return;
+  }
+
+  if (ip == 0) {
+    clearIp();
+  } else {
+    // Convert number into dotted quad
+    auto newip = fmt::format("{}.{}.{}.{}", (ip >> 24) & 0xff,
+                             (ip >> 16) & 0xff, (ip >> 8) & 0xff, ip & 0xff);
+    WPI_INFO(m_logger, "DS received server IP: {}", newip);
+    setIp(newip);
+  }
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/EventLoopRunner.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/EventLoopRunner.cpp
new file mode 100644
index 0000000..7c7e79c
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/EventLoopRunner.cpp
@@ -0,0 +1,91 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/EventLoopRunner.h"
+
+#include <wpi/SmallVector.h>
+#include <wpi/condition_variable.h>
+#include <wpi/mutex.h>
+
+#include "wpinet/uv/AsyncFunction.h"
+#include "wpinet/uv/Loop.h"
+
+using namespace wpi;
+
+class EventLoopRunner::Thread : public SafeThread {
+ public:
+  using UvExecFunc = uv::AsyncFunction<void(LoopFunc)>;
+
+  Thread() : m_loop(uv::Loop::Create()) {
+    // set up async handles
+    if (!m_loop) {
+      return;
+    }
+
+    // run function
+    m_doExec = UvExecFunc::Create(
+        m_loop, [loop = m_loop.get()](auto out, LoopFunc func) {
+          func(*loop);
+          out.set_value();
+        });
+  }
+
+  void Main() override {
+    if (m_loop) {
+      m_loop->Run();
+    }
+  }
+
+  // the loop
+  std::shared_ptr<uv::Loop> m_loop;
+
+  // run function
+  std::weak_ptr<UvExecFunc> m_doExec;
+};
+
+EventLoopRunner::EventLoopRunner() {
+  m_owner.Start();
+}
+
+EventLoopRunner::~EventLoopRunner() {
+  Stop();
+}
+
+void EventLoopRunner::Stop() {
+  ExecAsync([](uv::Loop& loop) {
+    // close all handles; this will (eventually) stop the loop
+    loop.Walk([](uv::Handle& h) {
+      h.SetLoopClosing(true);
+      h.Close();
+    });
+  });
+  m_owner.Join();
+}
+
+void EventLoopRunner::ExecAsync(LoopFunc func) {
+  if (auto thr = m_owner.GetThread()) {
+    if (auto doExec = thr->m_doExec.lock()) {
+      doExec->Call(std::move(func));
+    }
+  }
+}
+
+void EventLoopRunner::ExecSync(LoopFunc func) {
+  wpi::future<void> f;
+  if (auto thr = m_owner.GetThread()) {
+    if (auto doExec = thr->m_doExec.lock()) {
+      f = doExec->Call(std::move(func));
+    }
+  }
+  if (f.valid()) {
+    f.wait();
+  }
+}
+
+std::shared_ptr<uv::Loop> EventLoopRunner::GetLoop() {
+  if (auto thr = m_owner.GetThread()) {
+    return thr->m_loop;
+  }
+  return nullptr;
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/HttpParser.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/HttpParser.cpp
new file mode 100644
index 0000000..c428da2
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/HttpParser.cpp
@@ -0,0 +1,193 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/HttpParser.h"
+
+using namespace wpi;
+
+uint32_t HttpParser::GetParserVersion() {
+  return static_cast<uint32_t>(http_parser_version());
+}
+
+HttpParser::HttpParser(Type type) {
+  http_parser_init(&m_parser,
+                   static_cast<http_parser_type>(static_cast<int>(type)));
+  m_parser.data = this;
+
+  http_parser_settings_init(&m_settings);
+
+  // Unlike the underlying http_parser library, we don't perform callbacks
+  // (other than body) with partial data; instead we buffer and call the user
+  // callback only when the data is complete.
+
+  // on_message_begin: initialize our state, call user callback
+  m_settings.on_message_begin = [](http_parser* p) -> int {
+    auto& self = *static_cast<HttpParser*>(p->data);
+    self.m_urlBuf.clear();
+    self.m_state = kStart;
+    self.messageBegin();
+    return self.m_aborted;
+  };
+
+  // on_url: collect into buffer
+  m_settings.on_url = [](http_parser* p, const char* at, size_t length) -> int {
+    auto& self = *static_cast<HttpParser*>(p->data);
+    // append to buffer
+    if ((self.m_urlBuf.size() + length) > self.m_maxLength) {
+      return 1;
+    }
+    self.m_urlBuf += std::string_view{at, length};
+    self.m_state = kUrl;
+    return 0;
+  };
+
+  // on_status: collect into buffer, call user URL callback
+  m_settings.on_status = [](http_parser* p, const char* at,
+                            size_t length) -> int {
+    auto& self = *static_cast<HttpParser*>(p->data);
+    // use valueBuf for the status
+    if ((self.m_valueBuf.size() + length) > self.m_maxLength) {
+      return 1;
+    }
+    self.m_valueBuf += std::string_view{at, length};
+    self.m_state = kStatus;
+    return 0;
+  };
+
+  // on_header_field: collect into buffer, call user header/status callback
+  m_settings.on_header_field = [](http_parser* p, const char* at,
+                                  size_t length) -> int {
+    auto& self = *static_cast<HttpParser*>(p->data);
+
+    // once we're in header, we know the URL is complete
+    if (self.m_state == kUrl) {
+      self.url(self.m_urlBuf);
+      if (self.m_aborted) {
+        return 1;
+      }
+    }
+
+    // once we're in header, we know the status is complete
+    if (self.m_state == kStatus) {
+      self.status(self.m_valueBuf);
+      if (self.m_aborted) {
+        return 1;
+      }
+    }
+
+    // if we previously were in value state, that means we finished a header
+    if (self.m_state == kValue) {
+      self.header(self.m_fieldBuf, self.m_valueBuf);
+      if (self.m_aborted) {
+        return 1;
+      }
+    }
+
+    // clear field and value when we enter this state
+    if (self.m_state != kField) {
+      self.m_state = kField;
+      self.m_fieldBuf.clear();
+      self.m_valueBuf.clear();
+    }
+
+    // append data to field buffer
+    if ((self.m_fieldBuf.size() + length) > self.m_maxLength) {
+      return 1;
+    }
+    self.m_fieldBuf += std::string_view{at, length};
+    return 0;
+  };
+
+  // on_header_field: collect into buffer
+  m_settings.on_header_value = [](http_parser* p, const char* at,
+                                  size_t length) -> int {
+    auto& self = *static_cast<HttpParser*>(p->data);
+
+    // if we weren't previously in value state, clear the buffer
+    if (self.m_state != kValue) {
+      self.m_state = kValue;
+      self.m_valueBuf.clear();
+    }
+
+    // append data to value buffer
+    if ((self.m_valueBuf.size() + length) > self.m_maxLength) {
+      return 1;
+    }
+    self.m_valueBuf += std::string_view{at, length};
+    return 0;
+  };
+
+  // on_headers_complete: call user status/header/complete callback
+  m_settings.on_headers_complete = [](http_parser* p) -> int {
+    auto& self = *static_cast<HttpParser*>(p->data);
+
+    // if we previously were in url state, that means we finished the url
+    if (self.m_state == kUrl) {
+      self.url(self.m_urlBuf);
+      if (self.m_aborted) {
+        return 1;
+      }
+    }
+
+    // if we previously were in status state, that means we finished the status
+    if (self.m_state == kStatus) {
+      self.status(self.m_valueBuf);
+      if (self.m_aborted) {
+        return 1;
+      }
+    }
+
+    // if we previously were in value state, that means we finished a header
+    if (self.m_state == kValue) {
+      self.header(self.m_fieldBuf, self.m_valueBuf);
+      if (self.m_aborted) {
+        return 1;
+      }
+    }
+
+    self.headersComplete(self.ShouldKeepAlive());
+    return self.m_aborted;
+  };
+
+  // on_body: call user callback
+  m_settings.on_body = [](http_parser* p, const char* at,
+                          size_t length) -> int {
+    auto& self = *static_cast<HttpParser*>(p->data);
+    self.body(std::string_view{at, length}, self.IsBodyFinal());
+    return self.m_aborted;
+  };
+
+  // on_message_complete: call user callback
+  m_settings.on_message_complete = [](http_parser* p) -> int {
+    auto& self = *static_cast<HttpParser*>(p->data);
+    self.messageComplete(self.ShouldKeepAlive());
+    return self.m_aborted;
+  };
+
+  // on_chunk_header: call user callback
+  m_settings.on_chunk_header = [](http_parser* p) -> int {
+    auto& self = *static_cast<HttpParser*>(p->data);
+    self.chunkHeader(p->content_length);
+    return self.m_aborted;
+  };
+
+  // on_chunk_complete: call user callback
+  m_settings.on_chunk_complete = [](http_parser* p) -> int {
+    auto& self = *static_cast<HttpParser*>(p->data);
+    self.chunkComplete();
+    return self.m_aborted;
+  };
+}
+
+void HttpParser::Reset(Type type) {
+  http_parser_init(&m_parser,
+                   static_cast<http_parser_type>(static_cast<int>(type)));
+  m_parser.data = this;
+  m_maxLength = 1024;
+  m_state = kStart;
+  m_urlBuf.clear();
+  m_fieldBuf.clear();
+  m_valueBuf.clear();
+  m_aborted = false;
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/HttpServerConnection.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/HttpServerConnection.cpp
new file mode 100644
index 0000000..313ee2b
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/HttpServerConnection.cpp
@@ -0,0 +1,179 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/HttpServerConnection.h"
+
+#include <fmt/format.h>
+#include <wpi/SmallString.h>
+#include <wpi/SmallVector.h>
+#include <wpi/SpanExtras.h>
+#include <wpi/StringExtras.h>
+#include <wpi/fmt/raw_ostream.h>
+
+#include "wpinet/raw_uv_ostream.h"
+
+using namespace wpi;
+
+HttpServerConnection::HttpServerConnection(std::shared_ptr<uv::Stream> stream)
+    : m_stream(*stream) {
+  // process HTTP messages
+  m_messageCompleteConn =
+      m_request.messageComplete.connect_connection([this](bool keepAlive) {
+        m_keepAlive = keepAlive;
+        ProcessRequest();
+      });
+
+  // look for Accept-Encoding headers to determine if gzip is acceptable
+  m_request.messageBegin.connect([this] { m_acceptGzip = false; });
+  m_request.header.connect(
+      [this](std::string_view name, std::string_view value) {
+        if (wpi::equals_lower(name, "accept-encoding") &&
+            wpi::contains(value, "gzip")) {
+          m_acceptGzip = true;
+        }
+      });
+
+  // pass incoming data to HTTP parser
+  m_dataConn =
+      stream->data.connect_connection([this](uv::Buffer& buf, size_t size) {
+        m_request.Execute({buf.base, size});
+        if (m_request.HasError()) {
+          // could not parse; just close the connection
+          m_stream.Close();
+        }
+      });
+
+  // close when remote side closes
+  m_endConn =
+      stream->end.connect_connection([h = stream.get()] { h->Close(); });
+
+  // start reading
+  stream->StartRead();
+}
+
+void HttpServerConnection::BuildCommonHeaders(raw_ostream& os) {
+  os << "Server: WebServer/1.0\r\n"
+        "Cache-Control: no-store, no-cache, must-revalidate, pre-check=0, "
+        "post-check=0, max-age=0\r\n"
+        "Pragma: no-cache\r\n"
+        "Expires: Mon, 3 Jan 2000 12:34:56 GMT\r\n";
+}
+
+void HttpServerConnection::BuildHeader(raw_ostream& os, int code,
+                                       std::string_view codeText,
+                                       std::string_view contentType,
+                                       uint64_t contentLength,
+                                       std::string_view extra) {
+  fmt::print(os, "HTTP/{}.{} {} {}\r\n", m_request.GetMajor(),
+             m_request.GetMinor(), code, codeText);
+  if (contentLength == 0) {
+    m_keepAlive = false;
+  }
+  if (!m_keepAlive) {
+    os << "Connection: close\r\n";
+  }
+  BuildCommonHeaders(os);
+  os << "Content-Type: " << contentType << "\r\n";
+  if (contentLength != 0) {
+    fmt::print(os, "Content-Length: {}\r\n", contentLength);
+  }
+  os << "Access-Control-Allow-Origin: *\r\nAccess-Control-Allow-Methods: *\r\n";
+  if (!extra.empty()) {
+    os << extra;
+  }
+  os << "\r\n";  // header ends with a blank line
+}
+
+void HttpServerConnection::SendData(std::span<const uv::Buffer> bufs,
+                                    bool closeAfter) {
+  m_stream.Write(bufs, [closeAfter, stream = &m_stream](auto bufs, uv::Error) {
+    for (auto&& buf : bufs) {
+      buf.Deallocate();
+    }
+    if (closeAfter) {
+      stream->Close();
+    }
+  });
+}
+
+void HttpServerConnection::SendResponse(int code, std::string_view codeText,
+                                        std::string_view contentType,
+                                        std::string_view content,
+                                        std::string_view extraHeader) {
+  SmallVector<uv::Buffer, 4> toSend;
+  raw_uv_ostream os{toSend, 4096};
+  BuildHeader(os, code, codeText, contentType, content.size(), extraHeader);
+  os << content;
+  // close after write completes if we aren't keeping alive
+  SendData(os.bufs(), !m_keepAlive);
+}
+
+void HttpServerConnection::SendStaticResponse(
+    int code, std::string_view codeText, std::string_view contentType,
+    std::string_view content, bool gzipped, std::string_view extraHeader) {
+  // TODO: handle remote side not accepting gzip (very rare)
+
+  std::string_view contentEncodingHeader;
+  if (gzipped /* && m_acceptGzip*/) {
+    contentEncodingHeader = "Content-Encoding: gzip\r\n";
+  }
+
+  SmallVector<uv::Buffer, 4> bufs;
+  raw_uv_ostream os{bufs, 4096};
+  BuildHeader(os, code, codeText, contentType, content.size(),
+              fmt::format("{}{}", extraHeader, contentEncodingHeader));
+  // can send content without copying
+  bufs.emplace_back(content);
+
+  m_stream.Write(bufs, [closeAfter = !m_keepAlive, stream = &m_stream](
+                           auto bufs, uv::Error) {
+    // don't deallocate the static content
+    for (auto&& buf : wpi::drop_back(bufs)) {
+      buf.Deallocate();
+    }
+    if (closeAfter) {
+      stream->Close();
+    }
+  });
+}
+
+void HttpServerConnection::SendError(int code, std::string_view message) {
+  std::string_view codeText, extra, baseMessage;
+  switch (code) {
+    case 401:
+      codeText = "Unauthorized";
+      extra = "WWW-Authenticate: Basic realm=\"CameraServer\"";
+      baseMessage = "401: Not Authenticated!";
+      break;
+    case 404:
+      codeText = "Not Found";
+      baseMessage = "404: Not Found!";
+      break;
+    case 500:
+      codeText = "Internal Server Error";
+      baseMessage = "500: Internal Server Error!";
+      break;
+    case 400:
+      codeText = "Bad Request";
+      baseMessage = "400: Not Found!";
+      break;
+    case 403:
+      codeText = "Forbidden";
+      baseMessage = "403: Forbidden!";
+      break;
+    case 503:
+      codeText = "Service Unavailable";
+      baseMessage = "503: Service Unavailable";
+      break;
+    default:
+      code = 501;
+      codeText = "Not Implemented";
+      baseMessage = "501: Not Implemented!";
+      break;
+  }
+  SmallString<256> content{baseMessage};
+  content += "\r\n";
+  content += message;
+  SendResponse(code, codeText, "text/plain", content.str(), extra);
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/HttpUtil.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/HttpUtil.cpp
new file mode 100644
index 0000000..12ff084
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/HttpUtil.cpp
@@ -0,0 +1,494 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/HttpUtil.h"
+
+#include <cctype>
+
+#include <fmt/format.h>
+#include <wpi/Base64.h>
+#include <wpi/StringExtras.h>
+#include <wpi/raw_ostream.h>
+
+#include "wpinet/TCPConnector.h"
+
+namespace wpi {
+
+std::string_view UnescapeURI(std::string_view str, SmallVectorImpl<char>& buf,
+                             bool* error) {
+  buf.clear();
+  for (auto i = str.begin(), end = str.end(); i != end; ++i) {
+    // pass non-escaped characters to output
+    if (*i != '%') {
+      // decode + to space
+      if (*i == '+') {
+        buf.push_back(' ');
+      } else {
+        buf.push_back(*i);
+      }
+      continue;
+    }
+
+    // are there enough characters left?
+    if (i + 2 >= end) {
+      *error = true;
+      return {};
+    }
+
+    // replace %xx with the corresponding character
+    unsigned val1 = hexDigitValue(*++i);
+    if (val1 == -1U) {
+      *error = true;
+      return {};
+    }
+    unsigned val2 = hexDigitValue(*++i);
+    if (val2 == -1U) {
+      *error = true;
+      return {};
+    }
+    buf.push_back((val1 << 4) | val2);
+  }
+
+  *error = false;
+  return {buf.data(), buf.size()};
+}
+
+std::string_view EscapeURI(std::string_view str, SmallVectorImpl<char>& buf,
+                           bool spacePlus) {
+  static const char* const hexLut = "0123456789ABCDEF";
+
+  buf.clear();
+  for (auto i = str.begin(), end = str.end(); i != end; ++i) {
+    // pass unreserved characters to output
+    if (std::isalnum(*i) || *i == '-' || *i == '_' || *i == '.' || *i == '~') {
+      buf.push_back(*i);
+      continue;
+    }
+
+    // encode space to +
+    if (spacePlus && *i == ' ') {
+      buf.push_back('+');
+      continue;
+    }
+
+    // convert others to %xx
+    buf.push_back('%');
+    buf.push_back(hexLut[((*i) >> 4) & 0x0f]);
+    buf.push_back(hexLut[(*i) & 0x0f]);
+  }
+
+  return {buf.data(), buf.size()};
+}
+
+HttpQueryMap::HttpQueryMap(std::string_view query) {
+  SmallVector<std::string_view, 16> queryElems;
+  split(query, queryElems, '&', 100, false);
+  for (auto elem : queryElems) {
+    auto [nameEsc, valueEsc] = split(elem, '=');
+    SmallString<64> nameBuf;
+    bool err = false;
+    auto name = wpi::UnescapeURI(nameEsc, nameBuf, &err);
+    // note: ignores duplicates
+    if (!err) {
+      m_elems.try_emplace(name, valueEsc);
+    }
+  }
+}
+
+std::optional<std::string_view> HttpQueryMap::Get(
+    std::string_view name, wpi::SmallVectorImpl<char>& buf) const {
+  auto it = m_elems.find(name);
+  if (it == m_elems.end()) {
+    return {};
+  }
+  bool err = false;
+  auto val = wpi::UnescapeURI(it->second, buf, &err);
+  if (err) {
+    return {};
+  }
+  return val;
+}
+
+HttpPath::HttpPath(std::string_view path) {
+  // special-case root path to be a single empty element
+  if (path == "/") {
+    m_pathEnds.emplace_back(0);
+    return;
+  }
+  wpi::SmallVector<std::string_view, 16> pathElems;
+  split(path, pathElems, '/', 100, false);
+  for (auto elem : pathElems) {
+    SmallString<64> buf;
+    bool err = false;
+    auto val = wpi::UnescapeURI(elem, buf, &err);
+    if (err) {
+      m_pathEnds.clear();
+      return;
+    }
+    m_pathBuf += val;
+    m_pathEnds.emplace_back(m_pathBuf.size());
+  }
+}
+
+bool HttpPath::startswith(size_t start,
+                          std::span<const std::string_view> match) const {
+  if (m_pathEnds.size() < (start + match.size())) {
+    return false;
+  }
+  bool first = start == 0;
+  auto p = m_pathEnds.begin() + start;
+  for (auto m : match) {
+    auto val = slice(m_pathBuf, first ? 0 : *(p - 1), *p);
+    if (val != m) {
+      return false;
+    }
+    first = false;
+    ++p;
+  }
+  return true;
+}
+
+std::string_view HttpPath::operator[](size_t n) const {
+  return slice(m_pathBuf, n == 0 ? 0 : m_pathEnds[n - 1], m_pathEnds[n]);
+}
+
+bool ParseHttpHeaders(raw_istream& is, SmallVectorImpl<char>* contentType,
+                      SmallVectorImpl<char>* contentLength) {
+  if (contentType) {
+    contentType->clear();
+  }
+  if (contentLength) {
+    contentLength->clear();
+  }
+
+  bool inContentType = false;
+  bool inContentLength = false;
+  SmallString<64> lineBuf;
+  for (;;) {
+    std::string_view line = rtrim(is.getline(lineBuf, 1024));
+    if (is.has_error()) {
+      return false;
+    }
+    if (line.empty()) {
+      return true;  // empty line signals end of headers
+    }
+
+    // header fields start at the beginning of the line
+    if (!std::isspace(line[0])) {
+      inContentType = false;
+      inContentLength = false;
+      std::string_view field;
+      std::tie(field, line) = split(line, ':');
+      field = rtrim(field);
+      if (equals_lower(field, "content-type")) {
+        inContentType = true;
+      } else if (equals_lower(field, "content-length")) {
+        inContentLength = true;
+      } else {
+        continue;  // ignore other fields
+      }
+    }
+
+    // collapse whitespace
+    line = ltrim(line);
+
+    // save field data
+    if (inContentType && contentType) {
+      contentType->append(line.begin(), line.end());
+    } else if (inContentLength && contentLength) {
+      contentLength->append(line.begin(), line.end());
+    }
+  }
+}
+
+bool FindMultipartBoundary(raw_istream& is, std::string_view boundary,
+                           std::string* saveBuf) {
+  SmallString<64> searchBuf;
+  searchBuf.resize(boundary.size() + 2);
+  size_t searchPos = 0;
+
+  // Per the spec, the --boundary should be preceded by \r\n, so do a first
+  // pass of 1-byte reads to throw those away (common case) and keep the
+  // last non-\r\n character in searchBuf.
+  if (!saveBuf) {
+    do {
+      is.read(searchBuf.data(), 1);
+      if (is.has_error()) {
+        return false;
+      }
+    } while (searchBuf[0] == '\r' || searchBuf[0] == '\n');
+    searchPos = 1;
+  }
+
+  // Look for --boundary.  Read boundarysize+2 bytes at a time
+  // during the search to speed up the reads, then fast-scan for -,
+  // and only then match the entire boundary.  This will be slow if
+  // there's a bunch of continuous -'s in the output, but that's unlikely.
+  for (;;) {
+    is.read(searchBuf.data() + searchPos, searchBuf.size() - searchPos);
+    if (is.has_error()) {
+      return false;
+    }
+
+    // Did we find the boundary?
+    if (searchBuf[0] == '-' && searchBuf[1] == '-' &&
+        wpi::substr(searchBuf, 2) == boundary) {
+      return true;
+    }
+
+    // Fast-scan for '-'
+    size_t pos = searchBuf.find('-', searchBuf[0] == '-' ? 1 : 0);
+    if (pos == std::string_view::npos) {
+      if (saveBuf) {
+        saveBuf->append(searchBuf.data(), searchBuf.size());
+      }
+    } else {
+      if (saveBuf) {
+        saveBuf->append(searchBuf.data(), pos);
+      }
+
+      // move '-' and following to start of buffer (next read will fill)
+      std::memmove(searchBuf.data(), searchBuf.data() + pos,
+                   searchBuf.size() - pos);
+      searchPos = searchBuf.size() - pos;
+    }
+  }
+}
+
+HttpLocation::HttpLocation(std::string_view url_, bool* error,
+                           std::string* errorMsg)
+    : url{url_} {
+  // Split apart into components
+  std::string_view query{url};
+
+  // scheme:
+  std::string_view scheme;
+  std::tie(scheme, query) = split(query, ':');
+  if (!equals_lower(scheme, "http")) {
+    *errorMsg = "only supports http URLs";
+    *error = true;
+    return;
+  }
+
+  // "//"
+  if (!starts_with(query, "//")) {
+    *errorMsg = "expected http://...";
+    *error = true;
+    return;
+  }
+  query.remove_prefix(2);
+
+  // user:password@host:port/
+  std::string_view authority;
+  std::tie(authority, query) = split(query, '/');
+
+  auto [userpass, hostport] = split(authority, '@');
+  // split leaves the RHS empty if the split char isn't present...
+  if (hostport.empty()) {
+    hostport = userpass;
+    userpass = {};
+  }
+
+  if (!userpass.empty()) {
+    auto [rawUser, rawPassword] = split(userpass, ':');
+    SmallString<64> userBuf, passBuf;
+    user = UnescapeURI(rawUser, userBuf, error);
+    if (*error) {
+      *errorMsg = fmt::format("could not unescape user \"{}\"", rawUser);
+      return;
+    }
+    password = UnescapeURI(rawPassword, passBuf, error);
+    if (*error) {
+      *errorMsg =
+          fmt::format("could not unescape password \"{}\"", rawPassword);
+      return;
+    }
+  }
+
+  std::string_view portStr;
+  std::tie(host, portStr) = rsplit(hostport, ':');
+  if (host.empty()) {
+    *errorMsg = "host is empty";
+    *error = true;
+    return;
+  }
+  if (portStr.empty()) {
+    port = 80;
+  } else if (auto p = parse_integer<int>(portStr, 10)) {
+    port = p.value();
+  } else {
+    *errorMsg = fmt::format("port \"{}\" is not an integer", portStr);
+    *error = true;
+    return;
+  }
+
+  // path?query#fragment
+  std::tie(query, fragment) = split(query, '#');
+  std::tie(path, query) = split(query, '?');
+
+  // Split query string into parameters
+  while (!query.empty()) {
+    // split out next param and value
+    std::string_view rawParam, rawValue;
+    std::tie(rawParam, query) = split(query, '&');
+    if (rawParam.empty()) {
+      continue;  // ignore "&&"
+    }
+    std::tie(rawParam, rawValue) = split(rawParam, '=');
+
+    // unescape param
+    *error = false;
+    SmallString<64> paramBuf;
+    std::string_view param = UnescapeURI(rawParam, paramBuf, error);
+    if (*error) {
+      *errorMsg = fmt::format("could not unescape parameter \"{}\"", rawParam);
+      return;
+    }
+
+    // unescape value
+    SmallString<64> valueBuf;
+    std::string_view value = UnescapeURI(rawValue, valueBuf, error);
+    if (*error) {
+      *errorMsg = fmt::format("could not unescape value \"{}\"", rawValue);
+      return;
+    }
+
+    params.emplace_back(std::make_pair(param, value));
+  }
+
+  *error = false;
+}
+
+void HttpRequest::SetAuth(const HttpLocation& loc) {
+  if (!loc.user.empty()) {
+    SmallString<64> userpass;
+    userpass += loc.user;
+    userpass += ':';
+    userpass += loc.password;
+    Base64Encode(userpass.str(), &auth);
+  }
+}
+
+bool HttpConnection::Handshake(const HttpRequest& request,
+                               std::string* warnMsg) {
+  // send GET request
+  os << "GET /" << request.path << " HTTP/1.1\r\n";
+  os << "Host: " << request.host << "\r\n";
+  if (!request.auth.empty()) {
+    os << "Authorization: Basic " << request.auth << "\r\n";
+  }
+  os << "\r\n";
+  os.flush();
+
+  // read first line of response
+  SmallString<64> lineBuf;
+  std::string_view line = rtrim(is.getline(lineBuf, 1024));
+  if (is.has_error()) {
+    *warnMsg = "disconnected before response";
+    return false;
+  }
+
+  // see if we got a HTTP 200 response
+  std::string_view httpver, code, codeText;
+  std::tie(httpver, line) = split(line, ' ');
+  std::tie(code, codeText) = split(line, ' ');
+  if (!starts_with(httpver, "HTTP")) {
+    *warnMsg = "did not receive HTTP response";
+    return false;
+  }
+  if (code != "200") {
+    *warnMsg = fmt::format("received {} {} response", code, codeText);
+    return false;
+  }
+
+  // Parse headers
+  if (!ParseHttpHeaders(is, &contentType, &contentLength)) {
+    *warnMsg = "disconnected during headers";
+    return false;
+  }
+
+  return true;
+}
+
+void HttpMultipartScanner::SetBoundary(std::string_view boundary) {
+  m_boundaryWith = "\n--";
+  m_boundaryWith += boundary;
+  m_boundaryWithout = "\n";
+  m_boundaryWithout += boundary;
+  m_dashes = kUnknown;
+}
+
+void HttpMultipartScanner::Reset(bool saveSkipped) {
+  m_saveSkipped = saveSkipped;
+  m_state = kBoundary;
+  m_posWith = 0;
+  m_posWithout = 0;
+  m_buf.resize(0);
+}
+
+std::string_view HttpMultipartScanner::Execute(std::string_view in) {
+  if (m_state == kDone) {
+    Reset(m_saveSkipped);
+  }
+  if (m_saveSkipped) {
+    m_buf += in;
+  }
+
+  size_t pos = 0;
+  if (m_state == kBoundary) {
+    for (char ch : in) {
+      ++pos;
+      if (m_dashes != kWithout) {
+        if (ch == m_boundaryWith[m_posWith]) {
+          ++m_posWith;
+          if (m_posWith == m_boundaryWith.size()) {
+            // Found the boundary; transition to padding
+            m_state = kPadding;
+            m_dashes = kWith;  // no longer accept plain 'boundary'
+            break;
+          }
+        } else if (ch == m_boundaryWith[0]) {
+          m_posWith = 1;
+        } else {
+          m_posWith = 0;
+        }
+      }
+
+      if (m_dashes != kWith) {
+        if (ch == m_boundaryWithout[m_posWithout]) {
+          ++m_posWithout;
+          if (m_posWithout == m_boundaryWithout.size()) {
+            // Found the boundary; transition to padding
+            m_state = kPadding;
+            m_dashes = kWithout;  // no longer accept '--boundary'
+            break;
+          }
+        } else if (ch == m_boundaryWithout[0]) {
+          m_posWithout = 1;
+        } else {
+          m_posWithout = 0;
+        }
+      }
+    }
+  }
+
+  if (m_state == kPadding) {
+    for (char ch : drop_front(in, pos)) {
+      ++pos;
+      if (ch == '\n') {
+        // Found the LF; return remaining input buffer (following it)
+        m_state = kDone;
+        if (m_saveSkipped) {
+          m_buf.resize(m_buf.size() - in.size() + pos);
+        }
+        return drop_front(in, pos);
+      }
+    }
+  }
+
+  // We consumed the entire input
+  return {};
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/MimeTypes.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/MimeTypes.cpp
new file mode 100644
index 0000000..d5f6fb3
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/MimeTypes.cpp
@@ -0,0 +1,69 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/MimeTypes.h"
+
+#include <wpi/StringExtras.h>
+#include <wpi/StringMap.h>
+
+namespace wpi {
+
+// derived partially from
+// https://github.com/DEGoodmanWilson/libmime/blob/stable/0.1.2/mime/mime.cpp
+std::string_view MimeTypeFromPath(std::string_view path) {
+  // https://developer.mozilla.org/en-US/docs/Web/HTTP/Basics_of_HTTP/MIME_types
+  static StringMap<const char*> mimeTypes{
+      // text
+      {"css", "text/css"},
+      {"csv", "text/csv"},
+      {"htm", "text/html"},
+      {"html", "text/html"},
+      {"js", "text/javascript"},
+      {"json", "application/json"},
+      {"map", "application/json"},
+      {"md", "text/markdown"},
+      {"txt", "text/plain"},
+      {"xml", "text/xml"},
+
+      // images
+      {"apng", "image/apng"},
+      {"bmp", "image/bmp"},
+      {"gif", "image/gif"},
+      {"cur", "image/x-icon"},
+      {"ico", "image/x-icon"},
+      {"jpg", "image/jpeg"},
+      {"jpeg", "image/jpeg"},
+      {"png", "image/png"},
+      {"svg", "image/svg+xml"},
+      {"tif", "image/tiff"},
+      {"tiff", "image/tiff"},
+      {"webp", "image/webp"},
+
+      // fonts
+      {"otf", "font/otf"},
+      {"ttf", "font/ttf"},
+      {"woff", "font/woff"},
+
+      // misc
+      {"pdf", "application/pdf"},
+      {"zip", "application/zip"},
+  };
+
+  static const char* defaultType = "application/octet-stream";
+
+  auto pos = path.find_last_of("/");
+  if (pos != std::string_view::npos) {
+    path = wpi::substr(path, pos + 1);
+  }
+  auto dot_pos = path.find_last_of(".");
+  if (dot_pos > 0 && dot_pos != std::string_view::npos) {
+    auto type = mimeTypes.find(wpi::substr(path, dot_pos + 1));
+    if (type != mimeTypes.end()) {
+      return type->getValue();
+    }
+  }
+  return defaultType;
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/MulticastHandleManager.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/MulticastHandleManager.cpp
similarity index 100%
rename from third_party/allwpilib/wpiutil/src/main/native/cpp/MulticastHandleManager.cpp
rename to third_party/allwpilib/wpinet/src/main/native/cpp/MulticastHandleManager.cpp
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/MulticastHandleManager.h b/third_party/allwpilib/wpinet/src/main/native/cpp/MulticastHandleManager.h
new file mode 100644
index 0000000..8c070f7
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/MulticastHandleManager.h
@@ -0,0 +1,26 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <memory>
+
+#include <wpi/DenseMap.h>
+#include <wpi/UidVector.h>
+
+#include "wpinet/MulticastServiceAnnouncer.h"
+#include "wpinet/MulticastServiceResolver.h"
+
+namespace wpi {
+struct MulticastHandleManager {
+  wpi::mutex mutex;
+  wpi::UidVector<int, 8> handleIds;
+  wpi::DenseMap<size_t, std::unique_ptr<wpi::MulticastServiceResolver>>
+      resolvers;
+  wpi::DenseMap<size_t, std::unique_ptr<wpi::MulticastServiceAnnouncer>>
+      announcers;
+};
+
+MulticastHandleManager& GetMulticastManager();
+}  // namespace wpi
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/MulticastServiceAnnouncer.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/MulticastServiceAnnouncer.cpp
new file mode 100644
index 0000000..daa7e8d
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/MulticastServiceAnnouncer.cpp
@@ -0,0 +1,67 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/MulticastServiceAnnouncer.h"
+
+#include <wpi/SmallVector.h>
+
+#include "MulticastHandleManager.h"
+
+extern "C" {
+WPI_MulticastServiceAnnouncerHandle WPI_CreateMulticastServiceAnnouncer(
+    const char* serviceName, const char* serviceType, int32_t port,
+    int32_t txtCount, const char** keys, const char** values)
+
+{
+  auto& manager = wpi::GetMulticastManager();
+  std::scoped_lock lock{manager.mutex};
+
+  wpi::SmallVector<std::pair<std::string_view, std::string_view>, 8> txts;
+
+  for (int32_t i = 0; i < txtCount; i++) {
+    txts.emplace_back(
+        std::pair<std::string_view, std::string_view>{keys[i], values[i]});
+  }
+
+  auto announcer = std::make_unique<wpi::MulticastServiceAnnouncer>(
+      serviceName, serviceType, port, txts);
+
+  size_t index = manager.handleIds.emplace_back(3);
+  manager.announcers[index] = std::move(announcer);
+
+  return index;
+}
+
+void WPI_FreeMulticastServiceAnnouncer(
+    WPI_MulticastServiceAnnouncerHandle handle) {
+  auto& manager = wpi::GetMulticastManager();
+  std::scoped_lock lock{manager.mutex};
+  manager.announcers[handle] = nullptr;
+  manager.handleIds.erase(handle);
+}
+
+void WPI_StartMulticastServiceAnnouncer(
+    WPI_MulticastServiceAnnouncerHandle handle) {
+  auto& manager = wpi::GetMulticastManager();
+  std::scoped_lock lock{manager.mutex};
+  auto& announcer = manager.announcers[handle];
+  announcer->Start();
+}
+
+void WPI_StopMulticastServiceAnnouncer(
+    WPI_MulticastServiceAnnouncerHandle handle) {
+  auto& manager = wpi::GetMulticastManager();
+  std::scoped_lock lock{manager.mutex};
+  auto& announcer = manager.announcers[handle];
+  announcer->Stop();
+}
+
+int32_t WPI_GetMulticastServiceAnnouncerHasImplementation(
+    WPI_MulticastServiceAnnouncerHandle handle) {
+  auto& manager = wpi::GetMulticastManager();
+  std::scoped_lock lock{manager.mutex};
+  auto& announcer = manager.announcers[handle];
+  return announcer->HasImplementation();
+}
+}  // extern "C"
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/MulticastServiceResolver.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/MulticastServiceResolver.cpp
new file mode 100644
index 0000000..c16db2e
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/MulticastServiceResolver.cpp
@@ -0,0 +1,149 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/MulticastServiceResolver.h"
+
+#include <wpi/MemAlloc.h>
+
+#include "MulticastHandleManager.h"
+
+extern "C" {
+WPI_MulticastServiceResolverHandle WPI_CreateMulticastServiceResolver(
+    const char* serviceType)
+
+{
+  auto& manager = wpi::GetMulticastManager();
+  std::scoped_lock lock{manager.mutex};
+
+  auto resolver = std::make_unique<wpi::MulticastServiceResolver>(serviceType);
+
+  size_t index = manager.handleIds.emplace_back(2);
+  manager.resolvers[index] = std::move(resolver);
+
+  return index;
+}
+
+void WPI_FreeMulticastServiceResolver(
+    WPI_MulticastServiceResolverHandle handle) {
+  auto& manager = wpi::GetMulticastManager();
+  std::scoped_lock lock{manager.mutex};
+  manager.resolvers[handle] = nullptr;
+  manager.handleIds.erase(handle);
+}
+
+void WPI_StartMulticastServiceResolver(
+    WPI_MulticastServiceResolverHandle handle) {
+  auto& manager = wpi::GetMulticastManager();
+  std::scoped_lock lock{manager.mutex};
+  auto& resolver = manager.resolvers[handle];
+  resolver->Start();
+}
+
+void WPI_StopMulticastServiceResolver(
+    WPI_MulticastServiceResolverHandle handle) {
+  auto& manager = wpi::GetMulticastManager();
+  std::scoped_lock lock{manager.mutex};
+  auto& resolver = manager.resolvers[handle];
+  resolver->Stop();
+}
+
+int32_t WPI_GetMulticastServiceResolverHasImplementation(
+    WPI_MulticastServiceResolverHandle handle) {
+  auto& manager = wpi::GetMulticastManager();
+  std::scoped_lock lock{manager.mutex};
+  auto& resolver = manager.resolvers[handle];
+  return resolver->HasImplementation();
+}
+
+WPI_EventHandle WPI_GetMulticastServiceResolverEventHandle(
+    WPI_MulticastServiceResolverHandle handle) {
+  auto& manager = wpi::GetMulticastManager();
+  std::scoped_lock lock{manager.mutex};
+  auto& resolver = manager.resolvers[handle];
+  return resolver->GetEventHandle();
+}
+
+WPI_ServiceData* WPI_GetMulticastServiceResolverData(
+    WPI_MulticastServiceResolverHandle handle, int32_t* dataCount) {
+  std::vector<wpi::MulticastServiceResolver::ServiceData> allData;
+  {
+    auto& manager = wpi::GetMulticastManager();
+    std::scoped_lock lock{manager.mutex};
+    auto& resolver = manager.resolvers[handle];
+    allData = resolver->GetData();
+  }
+  if (allData.empty()) {
+    *dataCount = 0;
+    return nullptr;
+  }
+  size_t allocSize = sizeof(WPI_ServiceData) * allData.size();
+
+  for (auto&& data : allData) {
+    // Include space for hostName and serviceType (+ terminators)
+    allocSize += data.hostName.size() + data.serviceName.size() + 2;
+
+    size_t keysTotalLength = 0;
+    size_t valuesTotalLength = 0;
+    // Include space for all keys and values, and pointer array
+    for (auto&& t : data.txt) {
+      allocSize += sizeof(const char*);
+      keysTotalLength += (t.first.size() + 1);
+      allocSize += sizeof(const char*);
+      valuesTotalLength += (t.second.size() + 1);
+    }
+    allocSize += keysTotalLength;
+    allocSize += valuesTotalLength;
+  }
+
+  uint8_t* cDataRaw = reinterpret_cast<uint8_t*>(wpi::safe_malloc(allocSize));
+  if (!cDataRaw) {
+    return nullptr;
+  }
+  WPI_ServiceData* rootArray = reinterpret_cast<WPI_ServiceData*>(cDataRaw);
+  cDataRaw += (sizeof(WPI_ServiceData) + allData.size());
+  WPI_ServiceData* currentData = rootArray;
+
+  for (auto&& data : allData) {
+    currentData->ipv4Address = data.ipv4Address;
+    currentData->port = data.port;
+    currentData->txtCount = data.txt.size();
+
+    std::memcpy(cDataRaw, data.hostName.c_str(), data.hostName.size() + 1);
+    currentData->hostName = reinterpret_cast<const char*>(cDataRaw);
+    cDataRaw += data.hostName.size() + 1;
+
+    std::memcpy(cDataRaw, data.serviceName.c_str(),
+                data.serviceName.size() + 1);
+    currentData->serviceName = reinterpret_cast<const char*>(cDataRaw);
+    cDataRaw += data.serviceName.size() + 1;
+
+    char** valuesPtrArr = reinterpret_cast<char**>(cDataRaw);
+    cDataRaw += (sizeof(char**) * data.txt.size());
+    char** keysPtrArr = reinterpret_cast<char**>(cDataRaw);
+    cDataRaw += (sizeof(char**) * data.txt.size());
+
+    currentData->txtKeys = const_cast<const char**>(keysPtrArr);
+    currentData->txtValues = const_cast<const char**>(valuesPtrArr);
+
+    for (size_t i = 0; i < data.txt.size(); i++) {
+      keysPtrArr[i] = reinterpret_cast<char*>(cDataRaw);
+      std::memcpy(keysPtrArr[i], data.txt[i].first.c_str(),
+                  data.txt[i].first.size() + 1);
+      cDataRaw += (data.txt[i].first.size() + 1);
+
+      valuesPtrArr[i] = reinterpret_cast<char*>(cDataRaw);
+      std::memcpy(valuesPtrArr[i], data.txt[i].second.c_str(),
+                  data.txt[i].second.size() + 1);
+      cDataRaw += (data.txt[i].second.size() + 1);
+    }
+    currentData++;
+  }
+
+  return rootArray;
+}
+
+void WPI_FreeServiceData(WPI_ServiceData* serviceData, int32_t length) {
+  std::free(serviceData);
+}
+}  // extern "C"
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/ParallelTcpConnector.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/ParallelTcpConnector.cpp
new file mode 100644
index 0000000..317f0a2
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/ParallelTcpConnector.cpp
@@ -0,0 +1,177 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/ParallelTcpConnector.h"
+
+#include <fmt/format.h>
+#include <wpi/Logger.h>
+
+#include "wpinet/uv/GetAddrInfo.h"
+#include "wpinet/uv/Loop.h"
+#include "wpinet/uv/Tcp.h"
+#include "wpinet/uv/Timer.h"
+#include "wpinet/uv/util.h"
+
+using namespace wpi;
+
+ParallelTcpConnector::ParallelTcpConnector(
+    wpi::uv::Loop& loop, wpi::uv::Timer::Time reconnectRate,
+    wpi::Logger& logger, std::function<void(wpi::uv::Tcp& tcp)> connected,
+    const private_init&)
+    : m_loop{loop},
+      m_logger{logger},
+      m_reconnectRate{reconnectRate},
+      m_connected{std::move(connected)},
+      m_reconnectTimer{uv::Timer::Create(loop)} {
+  m_reconnectTimer->timeout.connect([this] {
+    if (!IsConnected()) {
+      WPI_DEBUG1(m_logger, "timed out, reconnecting");
+      Connect();
+    }
+  });
+}
+
+ParallelTcpConnector::~ParallelTcpConnector() = default;
+
+void ParallelTcpConnector::Close() {
+  CancelAll();
+  m_reconnectTimer->Close();
+}
+
+void ParallelTcpConnector::SetServers(
+    std::span<const std::pair<std::string, unsigned int>> servers) {
+  m_servers.assign(servers.begin(), servers.end());
+  if (!IsConnected()) {
+    Connect();
+  }
+}
+
+void ParallelTcpConnector::Disconnected() {
+  if (m_isConnected) {
+    m_isConnected = false;
+    Connect();
+  }
+}
+
+void ParallelTcpConnector::Succeeded(uv::Tcp& tcp) {
+  if (!m_isConnected) {
+    m_isConnected = true;
+    m_reconnectTimer->Stop();
+    CancelAll(&tcp);
+  }
+}
+
+void ParallelTcpConnector::Connect() {
+  if (IsConnected()) {
+    return;
+  }
+
+  CancelAll();
+  m_reconnectTimer->Start(m_reconnectRate);
+
+  WPI_DEBUG3(m_logger, "starting new connection attempts");
+
+  // kick off parallel lookups
+  for (auto&& server : m_servers) {
+    auto req = std::make_shared<uv::GetAddrInfoReq>();
+    m_resolvers.emplace_back(req);
+
+    req->resolved.connect(
+        [this, req = req.get()](const addrinfo& addrinfo) {
+          if (IsConnected()) {
+            return;
+          }
+
+          // kick off parallel connection attempts
+          for (auto ai = &addrinfo; ai; ai = ai->ai_next) {
+            auto tcp = uv::Tcp::Create(m_loop);
+            m_attempts.emplace_back(tcp);
+
+            auto connreq = std::make_shared<uv::TcpConnectReq>();
+            connreq->connected.connect(
+                [this, tcp = tcp.get()] {
+                  if (m_logger.min_level() <= wpi::WPI_LOG_DEBUG4) {
+                    std::string ip;
+                    unsigned int port = 0;
+                    uv::AddrToName(tcp->GetPeer(), &ip, &port);
+                    WPI_DEBUG4(m_logger,
+                               "successful connection ({}) to {} port {}",
+                               static_cast<void*>(tcp), ip, port);
+                  }
+                  if (IsConnected()) {
+                    tcp->Shutdown([tcp] { tcp->Close(); });
+                    return;
+                  }
+                  if (m_connected) {
+                    m_connected(*tcp);
+                  }
+                },
+                shared_from_this());
+
+            connreq->error = [selfWeak = weak_from_this(),
+                              tcp = tcp.get()](uv::Error err) {
+              if (auto self = selfWeak.lock()) {
+                WPI_DEBUG1(self->m_logger, "connect failure ({}): {}",
+                           static_cast<void*>(tcp), err.str());
+              }
+            };
+
+            if (m_logger.min_level() <= wpi::WPI_LOG_DEBUG4) {
+              std::string ip;
+              unsigned int port = 0;
+              uv::AddrToName(*reinterpret_cast<sockaddr_storage*>(ai->ai_addr),
+                             &ip, &port);
+              WPI_DEBUG4(
+                  m_logger,
+                  "Info({}) starting connection attempt ({}) to {} port {}",
+                  static_cast<void*>(req), static_cast<void*>(tcp.get()), ip,
+                  port);
+            }
+            tcp->Connect(*ai->ai_addr, connreq);
+          }
+        },
+        shared_from_this());
+
+    req->error = [req = req.get(), selfWeak = weak_from_this()](uv::Error err) {
+      if (auto self = selfWeak.lock()) {
+        WPI_DEBUG1(self->m_logger, "GetAddrInfo({}) failure: {}",
+                   static_cast<void*>(req), err.str());
+      }
+    };
+
+    WPI_DEBUG4(m_logger, "starting GetAddrInfo({}) for {} port {}",
+               static_cast<void*>(req.get()), server.first, server.second);
+    addrinfo hints;
+    std::memset(&hints, 0, sizeof(hints));
+    hints.ai_family = AF_UNSPEC;
+    hints.ai_socktype = SOCK_STREAM;
+    hints.ai_protocol = IPPROTO_TCP;
+    hints.ai_flags = AI_NUMERICSERV | AI_ADDRCONFIG;
+    uv::GetAddrInfo(m_loop, req, server.first, fmt::format("{}", server.second),
+                    &hints);
+  }
+}
+
+void ParallelTcpConnector::CancelAll(wpi::uv::Tcp* except) {
+  WPI_DEBUG4(m_logger, "canceling previous attempts");
+  for (auto&& resolverWeak : m_resolvers) {
+    if (auto resolver = resolverWeak.lock()) {
+      WPI_DEBUG4(m_logger, "canceling GetAddrInfo({})",
+                 static_cast<void*>(resolver.get()));
+      resolver->Cancel();
+    }
+  }
+  m_resolvers.clear();
+
+  for (auto&& tcpWeak : m_attempts) {
+    if (auto tcp = tcpWeak.lock()) {
+      if (tcp.get() != except) {
+        WPI_DEBUG4(m_logger, "canceling connection attempt ({})",
+                   static_cast<void*>(tcp.get()));
+        tcp->Close();
+      }
+    }
+  }
+  m_attempts.clear();
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/PortForwarder.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/PortForwarder.cpp
new file mode 100644
index 0000000..257b620
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/PortForwarder.cpp
@@ -0,0 +1,158 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/PortForwarder.h"
+
+#include <fmt/format.h>
+#include <wpi/DenseMap.h>
+
+#include "wpinet/EventLoopRunner.h"
+#include "wpinet/uv/GetAddrInfo.h"
+#include "wpinet/uv/Tcp.h"
+#include "wpinet/uv/Timer.h"
+
+using namespace wpi;
+
+struct PortForwarder::Impl {
+ public:
+  EventLoopRunner runner;
+  DenseMap<unsigned int, std::weak_ptr<uv::Tcp>> servers;
+};
+
+PortForwarder::PortForwarder() : m_impl{new Impl} {}
+
+PortForwarder& PortForwarder::GetInstance() {
+  static PortForwarder instance;
+  return instance;
+}
+
+static void CopyStream(uv::Stream& in, std::weak_ptr<uv::Stream> outWeak) {
+  in.data.connect([&in, outWeak](uv::Buffer& buf, size_t len) {
+    uv::Buffer buf2 = buf.Dup();
+    buf2.len = len;
+    auto out = outWeak.lock();
+    if (!out) {
+      buf2.Deallocate();
+      in.Close();
+      return;
+    }
+    out->Write({buf2}, [](auto bufs, uv::Error) {
+      for (auto buf : bufs) {
+        buf.Deallocate();
+      }
+    });
+  });
+}
+
+void PortForwarder::Add(unsigned int port, std::string_view remoteHost,
+                        unsigned int remotePort) {
+  m_impl->runner.ExecSync([&](uv::Loop& loop) {
+    auto server = uv::Tcp::Create(loop);
+
+    // bind to local port
+    server->Bind("", port);
+
+    // when we get a connection, accept it
+    server->connection.connect([serverPtr = server.get(),
+                                host = std::string{remoteHost}, remotePort] {
+      auto& loop = serverPtr->GetLoopRef();
+      auto client = serverPtr->Accept();
+      if (!client) {
+        return;
+      }
+
+      // close on error
+      client->error.connect(
+          [clientPtr = client.get()](uv::Error err) { clientPtr->Close(); });
+
+      // connected flag
+      auto connected = std::make_shared<bool>(false);
+      client->SetData(connected);
+
+      auto remote = uv::Tcp::Create(loop);
+      remote->error.connect(
+          [remotePtr = remote.get(),
+           clientWeak = std::weak_ptr<uv::Tcp>(client)](uv::Error err) {
+            remotePtr->Close();
+            if (auto client = clientWeak.lock()) {
+              client->Close();
+            }
+          });
+
+      // resolve address
+      uv::GetAddrInfo(
+          loop,
+          [clientWeak = std::weak_ptr<uv::Tcp>(client),
+           remoteWeak = std::weak_ptr<uv::Tcp>(remote)](const addrinfo& addr) {
+            auto remote = remoteWeak.lock();
+            if (!remote) {
+              return;
+            }
+
+            // connect to remote address/port
+            remote->Connect(*addr.ai_addr, [remotePtr = remote.get(),
+                                            remoteWeak, clientWeak] {
+              auto client = clientWeak.lock();
+              if (!client) {
+                remotePtr->Close();
+                return;
+              }
+              *(client->GetData<bool>()) = true;
+
+              // close both when either side closes
+              client->end.connect([clientPtr = client.get(), remoteWeak] {
+                clientPtr->Close();
+                if (auto remote = remoteWeak.lock()) {
+                  remote->Close();
+                }
+              });
+              remotePtr->end.connect([remotePtr, clientWeak] {
+                remotePtr->Close();
+                if (auto client = clientWeak.lock()) {
+                  client->Close();
+                }
+              });
+
+              // copy bidirectionally
+              client->StartRead();
+              remotePtr->StartRead();
+              CopyStream(*client, remoteWeak);
+              CopyStream(*remotePtr, clientWeak);
+            });
+          },
+          host, fmt::to_string(remotePort));
+
+      // time out for connection
+      uv::Timer::SingleShot(loop, uv::Timer::Time{500},
+                            [connectedWeak = std::weak_ptr<bool>(connected),
+                             clientWeak = std::weak_ptr<uv::Tcp>(client),
+                             remoteWeak = std::weak_ptr<uv::Tcp>(remote)] {
+                              if (auto connected = connectedWeak.lock()) {
+                                if (!*connected) {
+                                  if (auto client = clientWeak.lock()) {
+                                    client->Close();
+                                  }
+                                  if (auto remote = remoteWeak.lock()) {
+                                    remote->Close();
+                                  }
+                                }
+                              }
+                            });
+    });
+
+    // start listening for incoming connections
+    server->Listen();
+
+    m_impl->servers[port] = server;
+  });
+}
+
+void PortForwarder::Remove(unsigned int port) {
+  m_impl->runner.ExecSync([&](uv::Loop& loop) {
+    if (auto server = m_impl->servers.lookup(port).lock()) {
+      server->Close();
+      m_impl->servers.erase(port);
+    }
+  });
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/SocketError.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/SocketError.cpp
new file mode 100644
index 0000000..233c5de
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/SocketError.cpp
@@ -0,0 +1,37 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/SocketError.h"
+
+#ifdef _WIN32
+#include <winsock2.h>
+#else
+#include <cerrno>
+#include <cstring>
+#endif
+
+namespace wpi {
+
+int SocketErrno() {
+#ifdef _WIN32
+  return WSAGetLastError();
+#else
+  return errno;
+#endif
+}
+
+std::string SocketStrerror(int code) {
+#ifdef _WIN32
+  LPSTR errstr = nullptr;
+  FormatMessage(FORMAT_MESSAGE_ALLOCATE_BUFFER | FORMAT_MESSAGE_FROM_SYSTEM, 0,
+                code, 0, (LPSTR)&errstr, 0, 0);
+  std::string rv(errstr);
+  LocalFree(errstr);
+  return rv;
+#else
+  return std::strerror(code);
+#endif
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/UDPClient.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/UDPClient.cpp
new file mode 100644
index 0000000..5963d60
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/UDPClient.cpp
@@ -0,0 +1,249 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/UDPClient.h"
+
+#ifdef _WIN32
+#include <WinSock2.h>
+#include <Ws2tcpip.h>
+#pragma comment(lib, "Ws2_32.lib")
+#else
+#include <arpa/inet.h>
+#include <fcntl.h>
+#include <netinet/in.h>
+#include <unistd.h>
+#endif
+
+#include <wpi/Logger.h>
+#include <wpi/SmallString.h>
+
+#include "wpinet/SocketError.h"
+
+using namespace wpi;
+
+UDPClient::UDPClient(Logger& logger) : UDPClient("", logger) {}
+
+UDPClient::UDPClient(std::string_view address, Logger& logger)
+    : m_lsd(0), m_port(0), m_address(address), m_logger(logger) {}
+
+UDPClient::UDPClient(UDPClient&& other)
+    : m_lsd(other.m_lsd),
+      m_port(other.m_port),
+      m_address(std::move(other.m_address)),
+      m_logger(other.m_logger) {
+  other.m_lsd = 0;
+  other.m_port = 0;
+}
+
+UDPClient::~UDPClient() {
+  if (m_lsd > 0) {
+    shutdown();
+  }
+}
+
+UDPClient& UDPClient::operator=(UDPClient&& other) {
+  if (this == &other) {
+    return *this;
+  }
+  shutdown();
+  m_logger = other.m_logger;
+  m_lsd = other.m_lsd;
+  m_address = std::move(other.m_address);
+  m_port = other.m_port;
+  other.m_lsd = 0;
+  other.m_port = 0;
+  return *this;
+}
+
+int UDPClient::start() {
+  return start(0);
+}
+
+int UDPClient::start(int port) {
+  if (m_lsd > 0) {
+    return 0;
+  }
+
+#ifdef _WIN32
+  WSAData wsaData;
+  WORD wVersionRequested = MAKEWORD(2, 2);
+  WSAStartup(wVersionRequested, &wsaData);
+#endif
+
+  m_lsd = socket(AF_INET, SOCK_DGRAM, 0);
+
+  if (m_lsd < 0) {
+    WPI_ERROR(m_logger, "could not create socket");
+    return -1;
+  }
+
+  struct sockaddr_in addr;
+  std::memset(&addr, 0, sizeof(addr));
+  addr.sin_family = AF_INET;
+  if (m_address.size() > 0) {
+#ifdef _WIN32
+    SmallString<128> addr_copy(m_address);
+    addr_copy.push_back('\0');
+    int res = InetPton(PF_INET, addr_copy.data(), &(addr.sin_addr));
+#else
+    int res = inet_pton(PF_INET, m_address.c_str(), &(addr.sin_addr));
+#endif
+    if (res != 1) {
+      WPI_ERROR(m_logger, "could not resolve {} address", m_address);
+      return -1;
+    }
+  } else {
+    addr.sin_addr.s_addr = INADDR_ANY;
+  }
+  addr.sin_port = htons(port);
+
+  if (port != 0) {
+#ifdef _WIN32
+    int optval = 1;
+    setsockopt(m_lsd, SOL_SOCKET, SO_EXCLUSIVEADDRUSE,
+               reinterpret_cast<char*>(&optval), sizeof optval);
+#else
+    int optval = 1;
+    setsockopt(m_lsd, SOL_SOCKET, SO_REUSEADDR,
+               reinterpret_cast<char*>(&optval), sizeof optval);
+#endif
+  }
+
+  int result = bind(m_lsd, reinterpret_cast<sockaddr*>(&addr), sizeof(addr));
+  if (result != 0) {
+    WPI_ERROR(m_logger, "bind() failed: {}", SocketStrerror());
+    return result;
+  }
+  m_port = port;
+  return 0;
+}
+
+void UDPClient::shutdown() {
+  if (m_lsd > 0) {
+#ifdef _WIN32
+    ::shutdown(m_lsd, SD_BOTH);
+    closesocket(m_lsd);
+    WSACleanup();
+#else
+    ::shutdown(m_lsd, SHUT_RDWR);
+    close(m_lsd);
+#endif
+    m_lsd = 0;
+    m_port = 0;
+  }
+}
+
+int UDPClient::send(std::span<const uint8_t> data, std::string_view server,
+                    int port) {
+  // server must be a resolvable IP address
+  struct sockaddr_in addr;
+  std::memset(&addr, 0, sizeof(addr));
+  addr.sin_family = AF_INET;
+  SmallString<128> remoteAddr{server};
+  if (remoteAddr.empty()) {
+    WPI_ERROR(m_logger, "server must be passed");
+    return -1;
+  }
+
+#ifdef _WIN32
+  int res = InetPton(AF_INET, remoteAddr.c_str(), &(addr.sin_addr));
+#else
+  int res = inet_pton(AF_INET, remoteAddr.c_str(), &(addr.sin_addr));
+#endif
+  if (res != 1) {
+    WPI_ERROR(m_logger, "could not resolve {} address", server);
+    return -1;
+  }
+  addr.sin_port = htons(port);
+
+  // sendto should not block
+  int result =
+      sendto(m_lsd, reinterpret_cast<const char*>(data.data()), data.size(), 0,
+             reinterpret_cast<sockaddr*>(&addr), sizeof(addr));
+  return result;
+}
+
+int UDPClient::send(std::string_view data, std::string_view server, int port) {
+  // server must be a resolvable IP address
+  struct sockaddr_in addr;
+  std::memset(&addr, 0, sizeof(addr));
+  addr.sin_family = AF_INET;
+  SmallString<128> remoteAddr{server};
+  if (remoteAddr.empty()) {
+    WPI_ERROR(m_logger, "server must be passed");
+    return -1;
+  }
+
+#ifdef _WIN32
+  int res = InetPton(AF_INET, remoteAddr.c_str(), &(addr.sin_addr));
+#else
+  int res = inet_pton(AF_INET, remoteAddr.c_str(), &(addr.sin_addr));
+#endif
+  if (res != 1) {
+    WPI_ERROR(m_logger, "could not resolve {} address", server);
+    return -1;
+  }
+  addr.sin_port = htons(port);
+
+  // sendto should not block
+  int result = sendto(m_lsd, data.data(), data.size(), 0,
+                      reinterpret_cast<sockaddr*>(&addr), sizeof(addr));
+  return result;
+}
+
+int UDPClient::receive(uint8_t* data_received, int receive_len) {
+  if (m_port == 0) {
+    return -1;  // return if not receiving
+  }
+  return recv(m_lsd, reinterpret_cast<char*>(data_received), receive_len, 0);
+}
+
+int UDPClient::receive(uint8_t* data_received, int receive_len,
+                       SmallVectorImpl<char>* addr_received,
+                       int* port_received) {
+  if (m_port == 0) {
+    return -1;  // return if not receiving
+  }
+
+  struct sockaddr_in remote;
+  socklen_t remote_len = sizeof(remote);
+  std::memset(&remote, 0, sizeof(remote));
+
+  int result =
+      recvfrom(m_lsd, reinterpret_cast<char*>(data_received), receive_len, 0,
+               reinterpret_cast<sockaddr*>(&remote), &remote_len);
+
+  char ip[50];
+#ifdef _WIN32
+  InetNtop(PF_INET, &(remote.sin_addr.s_addr), ip, sizeof(ip) - 1);
+#else
+  inet_ntop(PF_INET, reinterpret_cast<in_addr*>(&(remote.sin_addr.s_addr)), ip,
+            sizeof(ip) - 1);
+#endif
+
+  ip[49] = '\0';
+  int addr_len = std::strlen(ip);
+  addr_received->clear();
+  addr_received->append(&ip[0], &ip[addr_len]);
+
+  *port_received = ntohs(remote.sin_port);
+
+  return result;
+}
+
+int UDPClient::set_timeout(double timeout) {
+  if (timeout < 0) {
+    return -1;
+  }
+  struct timeval tv;
+  tv.tv_sec = timeout;             // truncating will give seconds
+  timeout -= tv.tv_sec;            // remove seconds portion
+  tv.tv_usec = timeout * 1000000;  // fractions of a second to us
+  int ret = setsockopt(m_lsd, SOL_SOCKET, SO_RCVTIMEO,
+                       reinterpret_cast<char*>(&tv), sizeof(tv));
+  if (ret < 0) {
+    WPI_ERROR(m_logger, "set timeout failed");
+  }
+  return ret;
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/WebSocket.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/WebSocket.cpp
new file mode 100644
index 0000000..ba57925
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/WebSocket.cpp
@@ -0,0 +1,707 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/WebSocket.h"
+
+#include <random>
+
+#include <fmt/format.h>
+#include <wpi/Base64.h>
+#include <wpi/SmallString.h>
+#include <wpi/SmallVector.h>
+#include <wpi/StringExtras.h>
+#include <wpi/raw_ostream.h>
+#include <wpi/sha1.h>
+
+#include "wpinet/HttpParser.h"
+#include "wpinet/raw_uv_ostream.h"
+#include "wpinet/uv/Stream.h"
+
+using namespace wpi;
+
+namespace {
+class WebSocketWriteReq : public uv::WriteReq {
+ public:
+  explicit WebSocketWriteReq(
+      std::function<void(std::span<uv::Buffer>, uv::Error)> callback)
+      : m_callback{std::move(callback)} {
+    finish.connect([this](uv::Error err) {
+      for (auto&& buf : m_internalBufs) {
+        buf.Deallocate();
+      }
+      m_callback(m_userBufs, err);
+    });
+  }
+
+  std::function<void(std::span<uv::Buffer>, uv::Error)> m_callback;
+  SmallVector<uv::Buffer, 4> m_internalBufs;
+  SmallVector<uv::Buffer, 4> m_userBufs;
+};
+}  // namespace
+
+static constexpr uint8_t kFlagMasking = 0x80;
+static constexpr uint8_t kLenMask = 0x7f;
+
+class WebSocket::ClientHandshakeData {
+ public:
+  ClientHandshakeData() {
+    // key is a random nonce
+    static std::random_device rd;
+    static std::default_random_engine gen{rd()};
+    std::uniform_int_distribution<unsigned int> dist(0, 255);
+    char nonce[16];  // the nonce sent to the server
+    for (char& v : nonce) {
+      v = static_cast<char>(dist(gen));
+    }
+    raw_svector_ostream os(key);
+    Base64Encode(os, {nonce, 16});
+  }
+  ~ClientHandshakeData() {
+    if (auto t = timer.lock()) {
+      t->Stop();
+      t->Close();
+    }
+  }
+
+  SmallString<64> key;                       // the key sent to the server
+  SmallVector<std::string, 2> protocols;     // valid protocols
+  HttpParser parser{HttpParser::kResponse};  // server response parser
+  bool hasUpgrade = false;
+  bool hasConnection = false;
+  bool hasAccept = false;
+  bool hasProtocol = false;
+
+  std::weak_ptr<uv::Timer> timer;
+};
+
+static std::string_view AcceptHash(std::string_view key,
+                                   SmallVectorImpl<char>& buf) {
+  SHA1 hash;
+  hash.Update(key);
+  hash.Update("258EAFA5-E914-47DA-95CA-C5AB0DC85B11");
+  SmallString<64> hashBuf;
+  return Base64Encode(hash.RawFinal(hashBuf), buf);
+}
+
+WebSocket::WebSocket(uv::Stream& stream, bool server, const private_init&)
+    : m_stream{stream}, m_server{server} {
+  // Connect closed and error signals to ourselves
+  m_stream.closed.connect([this]() { SetClosed(1006, "handle closed"); });
+  m_stream.error.connect([this](uv::Error err) {
+    Terminate(1006, fmt::format("stream error: {}", err.name()));
+  });
+
+  // Start reading
+  m_stream.StopRead();  // we may have been reading
+  m_stream.StartRead();
+  m_stream.data.connect(
+      [this](uv::Buffer& buf, size_t size) { HandleIncoming(buf, size); });
+  m_stream.end.connect(
+      [this]() { Terminate(1006, "remote end closed connection"); });
+}
+
+WebSocket::~WebSocket() = default;
+
+std::shared_ptr<WebSocket> WebSocket::CreateClient(
+    uv::Stream& stream, std::string_view uri, std::string_view host,
+    std::span<const std::string_view> protocols, const ClientOptions& options) {
+  auto ws = std::make_shared<WebSocket>(stream, false, private_init{});
+  stream.SetData(ws);
+  ws->StartClient(uri, host, protocols, options);
+  return ws;
+}
+
+std::shared_ptr<WebSocket> WebSocket::CreateServer(uv::Stream& stream,
+                                                   std::string_view key,
+                                                   std::string_view version,
+                                                   std::string_view protocol) {
+  auto ws = std::make_shared<WebSocket>(stream, true, private_init{});
+  stream.SetData(ws);
+  ws->StartServer(key, version, protocol);
+  return ws;
+}
+
+void WebSocket::Close(uint16_t code, std::string_view reason) {
+  SendClose(code, reason);
+  if (m_state != FAILED && m_state != CLOSED) {
+    m_state = CLOSING;
+  }
+}
+
+void WebSocket::Fail(uint16_t code, std::string_view reason) {
+  if (m_state == FAILED || m_state == CLOSED) {
+    return;
+  }
+  SendClose(code, reason);
+  SetClosed(code, reason, true);
+  Shutdown();
+}
+
+void WebSocket::Terminate(uint16_t code, std::string_view reason) {
+  if (m_state == FAILED || m_state == CLOSED) {
+    return;
+  }
+  SetClosed(code, reason);
+  Shutdown();
+}
+
+void WebSocket::StartClient(std::string_view uri, std::string_view host,
+                            std::span<const std::string_view> protocols,
+                            const ClientOptions& options) {
+  // Create client handshake data
+  m_clientHandshake = std::make_unique<ClientHandshakeData>();
+
+  // Build client request
+  SmallVector<uv::Buffer, 4> bufs;
+  raw_uv_ostream os{bufs, 4096};
+
+  os << "GET " << uri << " HTTP/1.1\r\n";
+  os << "Host: " << host << "\r\n";
+  os << "Upgrade: websocket\r\n";
+  os << "Connection: Upgrade\r\n";
+  os << "Sec-WebSocket-Key: " << m_clientHandshake->key << "\r\n";
+  os << "Sec-WebSocket-Version: 13\r\n";
+
+  // protocols (if provided)
+  if (!protocols.empty()) {
+    os << "Sec-WebSocket-Protocol: ";
+    bool first = true;
+    for (auto protocol : protocols) {
+      if (!first) {
+        os << ", ";
+      } else {
+        first = false;
+      }
+      os << protocol;
+      // also save for later checking against server response
+      m_clientHandshake->protocols.emplace_back(protocol);
+    }
+    os << "\r\n";
+  }
+
+  // other headers
+  for (auto&& header : options.extraHeaders) {
+    os << header.first << ": " << header.second << "\r\n";
+  }
+
+  // finish headers
+  os << "\r\n";
+
+  // Send client request
+  m_stream.Write(bufs, [](auto bufs, uv::Error) {
+    for (auto& buf : bufs) {
+      buf.Deallocate();
+    }
+  });
+
+  // Set up client response handling
+  m_clientHandshake->parser.status.connect([this](std::string_view status) {
+    unsigned int code = m_clientHandshake->parser.GetStatusCode();
+    if (code != 101) {
+      Terminate(code, status);
+    }
+  });
+  m_clientHandshake->parser.header.connect(
+      [this](std::string_view name, std::string_view value) {
+        value = trim(value);
+        if (equals_lower(name, "upgrade")) {
+          if (!equals_lower(value, "websocket")) {
+            return Terminate(1002, "invalid upgrade response value");
+          }
+          m_clientHandshake->hasUpgrade = true;
+        } else if (equals_lower(name, "connection")) {
+          if (!equals_lower(value, "upgrade")) {
+            return Terminate(1002, "invalid connection response value");
+          }
+          m_clientHandshake->hasConnection = true;
+        } else if (equals_lower(name, "sec-websocket-accept")) {
+          // Check against expected response
+          SmallString<64> acceptBuf;
+          if (!equals(value, AcceptHash(m_clientHandshake->key, acceptBuf))) {
+            return Terminate(1002, "invalid accept key");
+          }
+          m_clientHandshake->hasAccept = true;
+        } else if (equals_lower(name, "sec-websocket-extensions")) {
+          // No extensions are supported
+          if (!value.empty()) {
+            return Terminate(1010, "unsupported extension");
+          }
+        } else if (equals_lower(name, "sec-websocket-protocol")) {
+          // Make sure it was one of the provided protocols
+          bool match = false;
+          for (auto&& protocol : m_clientHandshake->protocols) {
+            if (equals_lower(value, protocol)) {
+              match = true;
+              break;
+            }
+          }
+          if (!match) {
+            return Terminate(1003, "unsupported protocol");
+          }
+          m_clientHandshake->hasProtocol = true;
+          m_protocol = value;
+        }
+      });
+  m_clientHandshake->parser.headersComplete.connect([this](bool) {
+    if (!m_clientHandshake->hasUpgrade || !m_clientHandshake->hasConnection ||
+        !m_clientHandshake->hasAccept ||
+        (!m_clientHandshake->hasProtocol &&
+         !m_clientHandshake->protocols.empty())) {
+      return Terminate(1002, "invalid response");
+    }
+    if (m_state == CONNECTING) {
+      m_state = OPEN;
+      open(m_protocol);
+    }
+  });
+
+  // Start handshake timer if a timeout was specified
+  if (options.handshakeTimeout != (uv::Timer::Time::max)()) {
+    auto timer = uv::Timer::Create(m_stream.GetLoopRef());
+    timer->timeout.connect(
+        [this]() { Terminate(1006, "connection timed out"); });
+    timer->Start(options.handshakeTimeout);
+    m_clientHandshake->timer = timer;
+  }
+}
+
+void WebSocket::StartServer(std::string_view key, std::string_view version,
+                            std::string_view protocol) {
+  m_protocol = protocol;
+
+  // Build server response
+  SmallVector<uv::Buffer, 4> bufs;
+  raw_uv_ostream os{bufs, 4096};
+
+  // Handle unsupported version
+  if (version != "13") {
+    os << "HTTP/1.1 426 Upgrade Required\r\n";
+    os << "Upgrade: WebSocket\r\n";
+    os << "Sec-WebSocket-Version: 13\r\n\r\n";
+    m_stream.Write(bufs, [this](auto bufs, uv::Error) {
+      for (auto& buf : bufs) {
+        buf.Deallocate();
+      }
+      // XXX: Should we support sending a new handshake on the same connection?
+      // XXX: "this->" is required by GCC 5.5 (bug)
+      this->Terminate(1003, "unsupported protocol version");
+    });
+    return;
+  }
+
+  os << "HTTP/1.1 101 Switching Protocols\r\n";
+  os << "Upgrade: websocket\r\n";
+  os << "Connection: Upgrade\r\n";
+
+  // accept hash
+  SmallString<64> acceptBuf;
+  os << "Sec-WebSocket-Accept: " << AcceptHash(key, acceptBuf) << "\r\n";
+
+  if (!protocol.empty()) {
+    os << "Sec-WebSocket-Protocol: " << protocol << "\r\n";
+  }
+
+  // end headers
+  os << "\r\n";
+
+  // Send server response
+  m_stream.Write(bufs, [this](auto bufs, uv::Error) {
+    for (auto& buf : bufs) {
+      buf.Deallocate();
+    }
+    if (m_state == CONNECTING) {
+      m_state = OPEN;
+      open(m_protocol);
+    }
+  });
+}
+
+void WebSocket::SendClose(uint16_t code, std::string_view reason) {
+  SmallVector<uv::Buffer, 4> bufs;
+  if (code != 1005) {
+    raw_uv_ostream os{bufs, 4096};
+    const uint8_t codeMsb[] = {static_cast<uint8_t>((code >> 8) & 0xff),
+                               static_cast<uint8_t>(code & 0xff)};
+    os << std::span{codeMsb};
+    os << reason;
+  }
+  Send(kFlagFin | kOpClose, bufs, [](auto bufs, uv::Error) {
+    for (auto&& buf : bufs) {
+      buf.Deallocate();
+    }
+  });
+}
+
+void WebSocket::SetClosed(uint16_t code, std::string_view reason, bool failed) {
+  if (m_state == FAILED || m_state == CLOSED) {
+    return;
+  }
+  m_state = failed ? FAILED : CLOSED;
+  closed(code, reason);
+}
+
+void WebSocket::Shutdown() {
+  m_stream.Shutdown([this] { m_stream.Close(); });
+}
+
+void WebSocket::HandleIncoming(uv::Buffer& buf, size_t size) {
+  // ignore incoming data if we're failed or closed
+  if (m_state == FAILED || m_state == CLOSED) {
+    return;
+  }
+
+  std::string_view data{buf.base, size};
+
+  // Handle connecting state (mainly on client)
+  if (m_state == CONNECTING) {
+    if (m_clientHandshake) {
+      data = m_clientHandshake->parser.Execute(data);
+      // check for parser failure
+      if (m_clientHandshake->parser.HasError()) {
+        return Terminate(1003, "invalid response");
+      }
+      if (m_state != OPEN) {
+        return;  // not done with handshake yet
+      }
+
+      // we're done with the handshake, so release its memory
+      m_clientHandshake.reset();
+
+      // fall through to process additional data after handshake
+    } else {
+      return Terminate(1003, "got data on server before response");
+    }
+  }
+
+  // Message processing
+  while (!data.empty()) {
+    if (m_frameSize == UINT64_MAX) {
+      // Need at least two bytes to determine header length
+      if (m_header.size() < 2u) {
+        size_t toCopy = (std::min)(2u - m_header.size(), data.size());
+        m_header.append(data.data(), data.data() + toCopy);
+        data.remove_prefix(toCopy);
+        if (m_header.size() < 2u) {
+          return;  // need more data
+        }
+
+        // Validate RSV bits are zero
+        if ((m_header[0] & 0x70) != 0) {
+          return Fail(1002, "nonzero RSV");
+        }
+      }
+
+      // Once we have first two bytes, we can calculate the header size
+      if (m_headerSize == 0) {
+        m_headerSize = 2;
+        uint8_t len = m_header[1] & kLenMask;
+        if (len == 126) {
+          m_headerSize += 2;
+        } else if (len == 127) {
+          m_headerSize += 8;
+        }
+        bool masking = (m_header[1] & kFlagMasking) != 0;
+        if (masking) {
+          m_headerSize += 4;  // masking key
+        }
+        // On server side, incoming messages MUST be masked
+        // On client side, incoming messages MUST NOT be masked
+        if (m_server && !masking) {
+          return Fail(1002, "client data not masked");
+        }
+        if (!m_server && masking) {
+          return Fail(1002, "server data masked");
+        }
+      }
+
+      // Need to complete header to calculate message size
+      if (m_header.size() < m_headerSize) {
+        size_t toCopy = (std::min)(m_headerSize - m_header.size(), data.size());
+        m_header.append(data.data(), data.data() + toCopy);
+        data.remove_prefix(toCopy);
+        if (m_header.size() < m_headerSize) {
+          return;  // need more data
+        }
+      }
+
+      if (m_header.size() >= m_headerSize) {
+        // get payload length
+        uint8_t len = m_header[1] & kLenMask;
+        if (len == 126) {
+          m_frameSize = (static_cast<uint16_t>(m_header[2]) << 8) |
+                        static_cast<uint16_t>(m_header[3]);
+        } else if (len == 127) {
+          m_frameSize = (static_cast<uint64_t>(m_header[2]) << 56) |
+                        (static_cast<uint64_t>(m_header[3]) << 48) |
+                        (static_cast<uint64_t>(m_header[4]) << 40) |
+                        (static_cast<uint64_t>(m_header[5]) << 32) |
+                        (static_cast<uint64_t>(m_header[6]) << 24) |
+                        (static_cast<uint64_t>(m_header[7]) << 16) |
+                        (static_cast<uint64_t>(m_header[8]) << 8) |
+                        static_cast<uint64_t>(m_header[9]);
+        } else {
+          m_frameSize = len;
+        }
+
+        // limit maximum size
+        if ((m_payload.size() + m_frameSize) > m_maxMessageSize) {
+          return Fail(1009, "message too large");
+        }
+      }
+    }
+
+    if (m_frameSize != UINT64_MAX) {
+      size_t need = m_frameStart + m_frameSize - m_payload.size();
+      size_t toCopy = (std::min)(need, data.size());
+      m_payload.append(data.data(), data.data() + toCopy);
+      data.remove_prefix(toCopy);
+      need -= toCopy;
+      if (need == 0) {
+        // We have a complete frame
+        // If the message had masking, unmask it
+        if ((m_header[1] & kFlagMasking) != 0) {
+          uint8_t key[4] = {
+              m_header[m_headerSize - 4], m_header[m_headerSize - 3],
+              m_header[m_headerSize - 2], m_header[m_headerSize - 1]};
+          int n = 0;
+          for (uint8_t& ch : std::span{m_payload}.subspan(m_frameStart)) {
+            ch ^= key[n++];
+            if (n >= 4) {
+              n = 0;
+            }
+          }
+        }
+
+        // Handle message
+        bool fin = (m_header[0] & kFlagFin) != 0;
+        uint8_t opcode = m_header[0] & kOpMask;
+        switch (opcode) {
+          case kOpCont:
+            switch (m_fragmentOpcode) {
+              case kOpText:
+                if (!m_combineFragments || fin) {
+                  text(std::string_view{reinterpret_cast<char*>(
+                                            m_payload.data()),
+                                        m_payload.size()},
+                       fin);
+                }
+                break;
+              case kOpBinary:
+                if (!m_combineFragments || fin) {
+                  binary(m_payload, fin);
+                }
+                break;
+              default:
+                // no preceding message?
+                return Fail(1002, "invalid continuation message");
+            }
+            if (fin) {
+              m_fragmentOpcode = 0;
+            }
+            break;
+          case kOpText:
+            if (m_fragmentOpcode != 0) {
+              return Fail(1002, "incomplete fragment");
+            }
+            if (!m_combineFragments || fin) {
+#ifdef WPINET_WEBSOCKET_VERBOSE_DEBUG
+              fmt::print(
+                  "WS RecvText({})\n",
+                  std::string_view{reinterpret_cast<char*>(m_payload.data()),
+                                   m_payload.size()});
+#endif
+              text(std::string_view{reinterpret_cast<char*>(m_payload.data()),
+                                    m_payload.size()},
+                   fin);
+            }
+            if (!fin) {
+              m_fragmentOpcode = opcode;
+            }
+            break;
+          case kOpBinary:
+            if (m_fragmentOpcode != 0) {
+              return Fail(1002, "incomplete fragment");
+            }
+            if (!m_combineFragments || fin) {
+#ifdef WPINET_WEBSOCKET_VERBOSE_DEBUG
+              SmallString<128> str;
+              raw_svector_ostream stros{str};
+              for (auto ch : m_payload) {
+                stros << fmt::format("{:02x},",
+                                     static_cast<unsigned int>(ch) & 0xff);
+              }
+              fmt::print("WS RecvBinary({})\n", str.str());
+#endif
+              binary(m_payload, fin);
+            }
+            if (!fin) {
+              m_fragmentOpcode = opcode;
+            }
+            break;
+          case kOpClose: {
+            uint16_t code;
+            std::string_view reason;
+            if (!fin) {
+              code = 1002;
+              reason = "cannot fragment control frames";
+            } else if (m_payload.size() < 2) {
+              code = 1005;
+            } else {
+              code = (static_cast<uint16_t>(m_payload[0]) << 8) |
+                     static_cast<uint16_t>(m_payload[1]);
+              reason = drop_front(
+                  {reinterpret_cast<char*>(m_payload.data()), m_payload.size()},
+                  2);
+            }
+            // Echo the close if we didn't previously send it
+            if (m_state != CLOSING) {
+              SendClose(code, reason);
+            }
+            SetClosed(code, reason);
+            // If we're the server, shutdown the connection.
+            if (m_server) {
+              Shutdown();
+            }
+            break;
+          }
+          case kOpPing:
+            if (!fin) {
+              return Fail(1002, "cannot fragment control frames");
+            }
+            ping(m_payload);
+            break;
+          case kOpPong:
+            if (!fin) {
+              return Fail(1002, "cannot fragment control frames");
+            }
+            pong(m_payload);
+            break;
+          default:
+            return Fail(1002, "invalid message opcode");
+        }
+
+        // Prepare for next message
+        m_header.clear();
+        m_headerSize = 0;
+        if (!m_combineFragments || fin) {
+          m_payload.clear();
+        }
+        m_frameStart = m_payload.size();
+        m_frameSize = UINT64_MAX;
+      }
+    }
+  }
+}
+
+static void WriteFrame(WebSocketWriteReq& req,
+                       SmallVectorImpl<uv::Buffer>& bufs, bool server,
+                       uint8_t opcode, std::span<const uv::Buffer> data) {
+  SmallVector<uv::Buffer, 4> internalBufs;
+  raw_uv_ostream os{internalBufs, 4096};
+
+#ifdef WPINET_WEBSOCKET_VERBOSE_DEBUG
+  if ((opcode & 0x7f) == 0x01) {
+    SmallString<128> str;
+    for (auto&& d : data) {
+      str.append(std::string_view(d.base, d.len));
+    }
+    fmt::print("WS SendText({})\n", str.str());
+  } else if ((opcode & 0x7f) == 0x02) {
+    SmallString<128> str;
+    raw_svector_ostream stros{str};
+    for (auto&& d : data) {
+      for (auto ch : d.data()) {
+        stros << fmt::format("{:02x},", static_cast<unsigned int>(ch) & 0xff);
+      }
+    }
+    fmt::print("WS SendBinary({})\n", str.str());
+  }
+#endif
+
+  // opcode (includes FIN bit)
+  os << static_cast<unsigned char>(opcode);
+
+  // payload length
+  uint64_t size = 0;
+  for (auto&& buf : data) {
+    size += buf.len;
+  }
+  if (size < 126) {
+    os << static_cast<unsigned char>((server ? 0x00 : kFlagMasking) | size);
+  } else if (size <= 0xffff) {
+    os << static_cast<unsigned char>((server ? 0x00 : kFlagMasking) | 126);
+    const uint8_t sizeMsb[] = {static_cast<uint8_t>((size >> 8) & 0xff),
+                               static_cast<uint8_t>(size & 0xff)};
+    os << std::span{sizeMsb};
+  } else {
+    os << static_cast<unsigned char>((server ? 0x00 : kFlagMasking) | 127);
+    const uint8_t sizeMsb[] = {static_cast<uint8_t>((size >> 56) & 0xff),
+                               static_cast<uint8_t>((size >> 48) & 0xff),
+                               static_cast<uint8_t>((size >> 40) & 0xff),
+                               static_cast<uint8_t>((size >> 32) & 0xff),
+                               static_cast<uint8_t>((size >> 24) & 0xff),
+                               static_cast<uint8_t>((size >> 16) & 0xff),
+                               static_cast<uint8_t>((size >> 8) & 0xff),
+                               static_cast<uint8_t>(size & 0xff)};
+    os << std::span{sizeMsb};
+  }
+
+  // clients need to mask the input data
+  if (!server) {
+    // generate masking key
+    static std::random_device rd;
+    static std::default_random_engine gen{rd()};
+    std::uniform_int_distribution<unsigned int> dist(0, 255);
+    uint8_t key[4];
+    for (uint8_t& v : key) {
+      v = dist(gen);
+    }
+    os << std::span<const uint8_t>{key, 4};
+    // copy and mask data
+    int n = 0;
+    for (auto&& buf : data) {
+      for (auto&& ch : buf.data()) {
+        os << static_cast<unsigned char>(static_cast<uint8_t>(ch) ^ key[n++]);
+        if (n >= 4) {
+          n = 0;
+        }
+      }
+    }
+    bufs.append(internalBufs.begin(), internalBufs.end());
+    // don't send the user bufs as we copied their data
+  } else {
+    bufs.append(internalBufs.begin(), internalBufs.end());
+    // servers can just send the buffers directly without masking
+    bufs.append(data.begin(), data.end());
+  }
+  req.m_internalBufs.append(internalBufs.begin(), internalBufs.end());
+  req.m_userBufs.append(data.begin(), data.end());
+}
+
+void WebSocket::SendFrames(
+    std::span<const Frame> frames,
+    std::function<void(std::span<uv::Buffer>, uv::Error)> callback) {
+  // If we're not open, emit an error and don't send the data
+  if (m_state != OPEN) {
+    int err;
+    if (m_state == CONNECTING) {
+      err = UV_EAGAIN;
+    } else {
+      err = UV_ESHUTDOWN;
+    }
+    SmallVector<uv::Buffer, 4> bufs;
+    for (auto&& frame : frames) {
+      bufs.append(frame.data.begin(), frame.data.end());
+    }
+    callback(bufs, uv::Error{err});
+    return;
+  }
+
+  auto req = std::make_shared<WebSocketWriteReq>(std::move(callback));
+  SmallVector<uv::Buffer, 4> bufs;
+  for (auto&& frame : frames) {
+    WriteFrame(*req, bufs, m_server, frame.opcode, frame.data);
+  }
+  m_stream.Write(bufs, req);
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/WebSocketServer.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/WebSocketServer.cpp
new file mode 100644
index 0000000..09424bb
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/WebSocketServer.cpp
@@ -0,0 +1,172 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/WebSocketServer.h"
+
+#include <utility>
+
+#include <wpi/StringExtras.h>
+#include <wpi/fmt/raw_ostream.h>
+
+#include "wpinet/raw_uv_ostream.h"
+#include "wpinet/uv/Buffer.h"
+#include "wpinet/uv/Stream.h"
+
+using namespace wpi;
+
+WebSocketServerHelper::WebSocketServerHelper(HttpParser& req) {
+  req.header.connect([this](std::string_view name, std::string_view value) {
+    if (equals_lower(name, "host")) {
+      m_gotHost = true;
+    } else if (equals_lower(name, "upgrade")) {
+      if (equals_lower(value, "websocket")) {
+        m_websocket = true;
+      }
+    } else if (equals_lower(name, "sec-websocket-key")) {
+      m_key = value;
+    } else if (equals_lower(name, "sec-websocket-version")) {
+      m_version = value;
+    } else if (equals_lower(name, "sec-websocket-protocol")) {
+      // Protocols are comma delimited, repeated headers add to list
+      SmallVector<std::string_view, 2> protocols;
+      split(value, protocols, ",", -1, false);
+      for (auto protocol : protocols) {
+        protocol = trim(protocol);
+        if (!protocol.empty()) {
+          m_protocols.emplace_back(protocol);
+        }
+      }
+    }
+  });
+  req.headersComplete.connect([&req, this](bool) {
+    if (req.IsUpgrade() && IsUpgrade()) {
+      upgrade();
+    }
+  });
+}
+
+std::pair<bool, std::string_view> WebSocketServerHelper::MatchProtocol(
+    std::span<const std::string_view> protocols) {
+  if (protocols.empty() && m_protocols.empty()) {
+    return {true, {}};
+  }
+  for (auto protocol : protocols) {
+    for (auto&& clientProto : m_protocols) {
+      if (protocol == clientProto) {
+        return {true, protocol};
+      }
+    }
+  }
+  return {false, {}};
+}
+
+WebSocketServer::WebSocketServer(uv::Stream& stream,
+                                 std::span<const std::string_view> protocols,
+                                 ServerOptions options, const private_init&)
+    : m_stream{stream},
+      m_helper{m_req},
+      m_protocols{protocols.begin(), protocols.end()},
+      m_options{std::move(options)} {
+  // Header handling
+  m_req.header.connect([this](std::string_view name, std::string_view value) {
+    if (equals_lower(name, "host")) {
+      if (m_options.checkHost) {
+        if (!m_options.checkHost(value)) {
+          Abort(401, "Unrecognized Host");
+        }
+      }
+    }
+  });
+  m_req.url.connect([this](std::string_view name) {
+    if (m_options.checkUrl) {
+      if (!m_options.checkUrl(name)) {
+        Abort(404, "Not Found");
+      }
+    }
+  });
+  m_req.headersComplete.connect([this](bool) {
+    // We only accept websocket connections
+    if (!m_helper.IsUpgrade() || !m_req.IsUpgrade()) {
+      Abort(426, "Upgrade Required");
+    }
+  });
+
+  // Handle upgrade event
+  m_helper.upgrade.connect([this] {
+    if (m_aborted) {
+      return;
+    }
+
+    // Negotiate sub-protocol
+    SmallVector<std::string_view, 2> protocols{m_protocols.begin(),
+                                               m_protocols.end()};
+    std::string_view protocol = m_helper.MatchProtocol(protocols).second;
+
+    // Disconnect our header reader
+    m_dataConn.disconnect();
+
+    // Accepting the stream may destroy this (as it replaces the stream user
+    // data), so grab a shared pointer first.
+    auto self = shared_from_this();
+
+    // Accept the upgrade
+    auto ws = m_helper.Accept(m_stream, protocol);
+
+    // Connect the websocket open event to our connected event.
+    ws->open.connect_extended(
+        [self, s = ws.get()](auto conn, std::string_view) {
+          self->connected(self->m_req.GetUrl(), *s);
+          conn.disconnect();  // one-shot
+        });
+  });
+
+  // Set up stream
+  stream.StartRead();
+  m_dataConn =
+      stream.data.connect_connection([this](uv::Buffer& buf, size_t size) {
+        if (m_aborted) {
+          return;
+        }
+        m_req.Execute(std::string_view{buf.base, size});
+        if (m_req.HasError()) {
+          Abort(400, "Bad Request");
+        }
+      });
+  m_errorConn =
+      stream.error.connect_connection([this](uv::Error) { m_stream.Close(); });
+  m_endConn = stream.end.connect_connection([this] { m_stream.Close(); });
+}
+
+std::shared_ptr<WebSocketServer> WebSocketServer::Create(
+    uv::Stream& stream, std::span<const std::string_view> protocols,
+    const ServerOptions& options) {
+  auto server = std::make_shared<WebSocketServer>(stream, protocols, options,
+                                                  private_init{});
+  stream.SetData(server);
+  return server;
+}
+
+void WebSocketServer::Abort(uint16_t code, std::string_view reason) {
+  if (m_aborted) {
+    return;
+  }
+  m_aborted = true;
+
+  // Build response
+  SmallVector<uv::Buffer, 4> bufs;
+  raw_uv_ostream os{bufs, 1024};
+
+  // Handle unsupported version
+  fmt::print(os, "HTTP/1.1 {} {}\r\n", code, reason);
+  if (code == 426) {
+    os << "Upgrade: WebSocket\r\n";
+  }
+  os << "\r\n";
+  m_stream.Write(bufs, [this](auto bufs, uv::Error) {
+    for (auto& buf : bufs) {
+      buf.Deallocate();
+    }
+    m_stream.Shutdown([this] { m_stream.Close(); });
+  });
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/hostname.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/hostname.cpp
new file mode 100644
index 0000000..ae25b29
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/hostname.cpp
@@ -0,0 +1,58 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/hostname.h"
+
+#include <cstdlib>
+#include <string>
+#include <string_view>
+
+#include <wpi/SmallVector.h>
+
+#include "uv.h"
+
+namespace wpi {
+
+std::string GetHostname() {
+  std::string rv;
+  char name[256];
+  size_t size = sizeof(name);
+
+  int err = uv_os_gethostname(name, &size);
+  if (err == 0) {
+    rv.assign(name, size);
+  } else if (err == UV_ENOBUFS) {
+    char* name2 = static_cast<char*>(std::malloc(size));
+    err = uv_os_gethostname(name2, &size);
+    if (err == 0) {
+      rv.assign(name2, size);
+    }
+    std::free(name2);
+  }
+
+  return rv;
+}
+
+std::string_view GetHostname(SmallVectorImpl<char>& name) {
+  // Use a tmp array to not require the SmallVector to be too large.
+  char tmpName[256];
+  size_t size = sizeof(tmpName);
+
+  name.clear();
+
+  int err = uv_os_gethostname(tmpName, &size);
+  if (err == 0) {
+    name.append(tmpName, tmpName + size);
+  } else if (err == UV_ENOBUFS) {
+    name.resize(size);
+    err = uv_os_gethostname(name.data(), &size);
+    if (err != 0) {
+      size = 0;
+    }
+  }
+
+  return {name.data(), size};
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/http_parser.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/http_parser.cpp
new file mode 100644
index 0000000..2bec4a7
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/http_parser.cpp
@@ -0,0 +1,2475 @@
+/* Copyright Joyent, Inc. and other Node contributors.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+#include "wpinet/http_parser.h"
+#include <assert.h>
+#include <stddef.h>
+#include <ctype.h>
+#include <string.h>
+#include <limits.h>
+
+#ifdef _WIN32
+#pragma warning(disable : 4018 26451)
+#endif
+
+#ifndef ULLONG_MAX
+# define ULLONG_MAX ((uint64_t) -1) /* 2^64-1 */
+#endif
+
+#ifndef MIN
+# define MIN(a,b) ((a) < (b) ? (a) : (b))
+#endif
+
+#ifndef ARRAY_SIZE
+# define ARRAY_SIZE(a) (sizeof(a) / sizeof((a)[0]))
+#endif
+
+#ifndef BIT_AT
+# define BIT_AT(a, i)                                                \
+  (!!((unsigned int) (a)[(unsigned int) (i) >> 3] &                  \
+   (1 << ((unsigned int) (i) & 7))))
+#endif
+
+#ifndef ELEM_AT
+# define ELEM_AT(a, i, v) ((unsigned int) (i) < ARRAY_SIZE(a) ? (a)[(i)] : (v))
+#endif
+
+#define SET_ERRNO(e)                                                 \
+do {                                                                 \
+  parser->nread = nread;                                             \
+  parser->http_errno = (e);                                          \
+} while(0)
+
+#define CURRENT_STATE() p_state
+#define UPDATE_STATE(V) p_state = (enum state) (V);
+#define RETURN(V)                                                    \
+do {                                                                 \
+  parser->nread = nread;                                             \
+  parser->state = CURRENT_STATE();                                   \
+  return (V);                                                        \
+} while (0);
+#define REEXECUTE()                                                  \
+  goto reexecute;                                                    \
+
+
+#ifdef __GNUC__
+# define LIKELY(X) __builtin_expect(!!(X), 1)
+# define UNLIKELY(X) __builtin_expect(!!(X), 0)
+#else
+# define LIKELY(X) (X)
+# define UNLIKELY(X) (X)
+#endif
+
+
+/* Run the notify callback FOR, returning ER if it fails */
+#define CALLBACK_NOTIFY_(FOR, ER)                                    \
+do {                                                                 \
+  assert(HTTP_PARSER_ERRNO(parser) == HPE_OK);                       \
+                                                                     \
+  if (LIKELY(settings->on_##FOR)) {                                  \
+    parser->state = CURRENT_STATE();                                 \
+    if (UNLIKELY(0 != settings->on_##FOR(parser))) {                 \
+      SET_ERRNO(HPE_CB_##FOR);                                       \
+    }                                                                \
+    UPDATE_STATE(parser->state);                                     \
+                                                                     \
+    /* We either errored above or got paused; get out */             \
+    if (UNLIKELY(HTTP_PARSER_ERRNO(parser) != HPE_OK)) {             \
+      return (ER);                                                   \
+    }                                                                \
+  }                                                                  \
+} while (0)
+
+/* Run the notify callback FOR and consume the current byte */
+#define CALLBACK_NOTIFY(FOR)            CALLBACK_NOTIFY_(FOR, p - data + 1)
+
+/* Run the notify callback FOR and don't consume the current byte */
+#define CALLBACK_NOTIFY_NOADVANCE(FOR)  CALLBACK_NOTIFY_(FOR, p - data)
+
+/* Run data callback FOR with LEN bytes, returning ER if it fails */
+#define CALLBACK_DATA_(FOR, LEN, ER)                                 \
+do {                                                                 \
+  assert(HTTP_PARSER_ERRNO(parser) == HPE_OK);                       \
+                                                                     \
+  if (FOR##_mark) {                                                  \
+    if (LIKELY(settings->on_##FOR)) {                                \
+      parser->state = CURRENT_STATE();                               \
+      if (UNLIKELY(0 !=                                              \
+                   settings->on_##FOR(parser, FOR##_mark, (LEN)))) { \
+        SET_ERRNO(HPE_CB_##FOR);                                     \
+      }                                                              \
+      UPDATE_STATE(parser->state);                                   \
+                                                                     \
+      /* We either errored above or got paused; get out */           \
+      if (UNLIKELY(HTTP_PARSER_ERRNO(parser) != HPE_OK)) {           \
+        return (ER);                                                 \
+      }                                                              \
+    }                                                                \
+    FOR##_mark = NULL;                                               \
+  }                                                                  \
+} while (0)
+
+/* Run the data callback FOR and consume the current byte */
+#define CALLBACK_DATA(FOR)                                           \
+    CALLBACK_DATA_(FOR, p - FOR##_mark, p - data + 1)
+
+/* Run the data callback FOR and don't consume the current byte */
+#define CALLBACK_DATA_NOADVANCE(FOR)                                 \
+    CALLBACK_DATA_(FOR, p - FOR##_mark, p - data)
+
+/* Set the mark FOR; non-destructive if mark is already set */
+#define MARK(FOR)                                                    \
+do {                                                                 \
+  if (!FOR##_mark) {                                                 \
+    FOR##_mark = p;                                                  \
+  }                                                                  \
+} while (0)
+
+/* Don't allow the total size of the HTTP headers (including the status
+ * line) to exceed HTTP_MAX_HEADER_SIZE.  This check is here to protect
+ * embedders against denial-of-service attacks where the attacker feeds
+ * us a never-ending header that the embedder keeps buffering.
+ *
+ * This check is arguably the responsibility of embedders but we're doing
+ * it on the embedder's behalf because most won't bother and this way we
+ * make the web a little safer.  HTTP_MAX_HEADER_SIZE is still far bigger
+ * than any reasonable request or response so this should never affect
+ * day-to-day operation.
+ */
+#define COUNT_HEADER_SIZE(V)                                         \
+do {                                                                 \
+  nread += (V);                                                      \
+  if (UNLIKELY(nread > (HTTP_MAX_HEADER_SIZE))) {                    \
+    SET_ERRNO(HPE_HEADER_OVERFLOW);                                  \
+    goto error;                                                      \
+  }                                                                  \
+} while (0)
+
+
+#define PROXY_CONNECTION "proxy-connection"
+#define CONNECTION "connection"
+#define CONTENT_LENGTH "content-length"
+#define TRANSFER_ENCODING "transfer-encoding"
+#define UPGRADE "upgrade"
+#define CHUNKED "chunked"
+#define KEEP_ALIVE "keep-alive"
+#define CLOSE "close"
+
+namespace wpi {
+
+
+static const char *method_strings[] =
+  {
+#define XX(num, name, string) #string,
+  HTTP_METHOD_MAP(XX)
+#undef XX
+  };
+
+
+/* Tokens as defined by rfc 2616. Also lowercases them.
+ *        token       = 1*<any CHAR except CTLs or separators>
+ *     separators     = "(" | ")" | "<" | ">" | "@"
+ *                    | "," | ";" | ":" | "\" | <">
+ *                    | "/" | "[" | "]" | "?" | "="
+ *                    | "{" | "}" | SP | HT
+ */
+static const char tokens[256] = {
+/*   0 nul    1 soh    2 stx    3 etx    4 eot    5 enq    6 ack    7 bel  */
+        0,       0,       0,       0,       0,       0,       0,       0,
+/*   8 bs     9 ht    10 nl    11 vt    12 np    13 cr    14 so    15 si   */
+        0,       0,       0,       0,       0,       0,       0,       0,
+/*  16 dle   17 dc1   18 dc2   19 dc3   20 dc4   21 nak   22 syn   23 etb */
+        0,       0,       0,       0,       0,       0,       0,       0,
+/*  24 can   25 em    26 sub   27 esc   28 fs    29 gs    30 rs    31 us  */
+        0,       0,       0,       0,       0,       0,       0,       0,
+/*  32 sp    33  !    34  "    35  #    36  $    37  %    38  &    39  '  */
+       ' ',     '!',      0,      '#',     '$',     '%',     '&',    '\'',
+/*  40  (    41  )    42  *    43  +    44  ,    45  -    46  .    47  /  */
+        0,       0,      '*',     '+',      0,      '-',     '.',      0,
+/*  48  0    49  1    50  2    51  3    52  4    53  5    54  6    55  7  */
+       '0',     '1',     '2',     '3',     '4',     '5',     '6',     '7',
+/*  56  8    57  9    58  :    59  ;    60  <    61  =    62  >    63  ?  */
+       '8',     '9',      0,       0,       0,       0,       0,       0,
+/*  64  @    65  A    66  B    67  C    68  D    69  E    70  F    71  G  */
+        0,      'a',     'b',     'c',     'd',     'e',     'f',     'g',
+/*  72  H    73  I    74  J    75  K    76  L    77  M    78  N    79  O  */
+       'h',     'i',     'j',     'k',     'l',     'm',     'n',     'o',
+/*  80  P    81  Q    82  R    83  S    84  T    85  U    86  V    87  W  */
+       'p',     'q',     'r',     's',     't',     'u',     'v',     'w',
+/*  88  X    89  Y    90  Z    91  [    92  \    93  ]    94  ^    95  _  */
+       'x',     'y',     'z',      0,       0,       0,      '^',     '_',
+/*  96  `    97  a    98  b    99  c   100  d   101  e   102  f   103  g  */
+       '`',     'a',     'b',     'c',     'd',     'e',     'f',     'g',
+/* 104  h   105  i   106  j   107  k   108  l   109  m   110  n   111  o  */
+       'h',     'i',     'j',     'k',     'l',     'm',     'n',     'o',
+/* 112  p   113  q   114  r   115  s   116  t   117  u   118  v   119  w  */
+       'p',     'q',     'r',     's',     't',     'u',     'v',     'w',
+/* 120  x   121  y   122  z   123  {   124  |   125  }   126  ~   127 del */
+       'x',     'y',     'z',      0,      '|',      0,      '~',       0 };
+
+
+static const int8_t unhex[256] =
+  {-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1
+  ,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1
+  ,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1
+  , 0, 1, 2, 3, 4, 5, 6, 7, 8, 9,-1,-1,-1,-1,-1,-1
+  ,-1,10,11,12,13,14,15,-1,-1,-1,-1,-1,-1,-1,-1,-1
+  ,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1
+  ,-1,10,11,12,13,14,15,-1,-1,-1,-1,-1,-1,-1,-1,-1
+  ,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1
+  };
+
+
+#if HTTP_PARSER_STRICT
+# define T(v) 0
+#else
+# define T(v) v
+#endif
+
+
+static const uint8_t normal_url_char[32] = {
+/*   0 nul    1 soh    2 stx    3 etx    4 eot    5 enq    6 ack    7 bel  */
+        0    |   0    |   0    |   0    |   0    |   0    |   0    |   0,
+/*   8 bs     9 ht    10 nl    11 vt    12 np    13 cr    14 so    15 si   */
+        0    | T(2)   |   0    |   0    | T(16)  |   0    |   0    |   0,
+/*  16 dle   17 dc1   18 dc2   19 dc3   20 dc4   21 nak   22 syn   23 etb */
+        0    |   0    |   0    |   0    |   0    |   0    |   0    |   0,
+/*  24 can   25 em    26 sub   27 esc   28 fs    29 gs    30 rs    31 us  */
+        0    |   0    |   0    |   0    |   0    |   0    |   0    |   0,
+/*  32 sp    33  !    34  "    35  #    36  $    37  %    38  &    39  '  */
+        0    |   2    |   4    |   0    |   16   |   32   |   64   |  128,
+/*  40  (    41  )    42  *    43  +    44  ,    45  -    46  .    47  /  */
+        1    |   2    |   4    |   8    |   16   |   32   |   64   |  128,
+/*  48  0    49  1    50  2    51  3    52  4    53  5    54  6    55  7  */
+        1    |   2    |   4    |   8    |   16   |   32   |   64   |  128,
+/*  56  8    57  9    58  :    59  ;    60  <    61  =    62  >    63  ?  */
+        1    |   2    |   4    |   8    |   16   |   32   |   64   |   0,
+/*  64  @    65  A    66  B    67  C    68  D    69  E    70  F    71  G  */
+        1    |   2    |   4    |   8    |   16   |   32   |   64   |  128,
+/*  72  H    73  I    74  J    75  K    76  L    77  M    78  N    79  O  */
+        1    |   2    |   4    |   8    |   16   |   32   |   64   |  128,
+/*  80  P    81  Q    82  R    83  S    84  T    85  U    86  V    87  W  */
+        1    |   2    |   4    |   8    |   16   |   32   |   64   |  128,
+/*  88  X    89  Y    90  Z    91  [    92  \    93  ]    94  ^    95  _  */
+        1    |   2    |   4    |   8    |   16   |   32   |   64   |  128,
+/*  96  `    97  a    98  b    99  c   100  d   101  e   102  f   103  g  */
+        1    |   2    |   4    |   8    |   16   |   32   |   64   |  128,
+/* 104  h   105  i   106  j   107  k   108  l   109  m   110  n   111  o  */
+        1    |   2    |   4    |   8    |   16   |   32   |   64   |  128,
+/* 112  p   113  q   114  r   115  s   116  t   117  u   118  v   119  w  */
+        1    |   2    |   4    |   8    |   16   |   32   |   64   |  128,
+/* 120  x   121  y   122  z   123  {   124  |   125  }   126  ~   127 del */
+        1    |   2    |   4    |   8    |   16   |   32   |   64   |   0, };
+
+#undef T
+
+enum state
+  { s_dead = 1 /* important that this is > 0 */
+
+  , s_start_req_or_res
+  , s_res_or_resp_H
+  , s_start_res
+  , s_res_H
+  , s_res_HT
+  , s_res_HTT
+  , s_res_HTTP
+  , s_res_http_major
+  , s_res_http_dot
+  , s_res_http_minor
+  , s_res_http_end
+  , s_res_first_status_code
+  , s_res_status_code
+  , s_res_status_start
+  , s_res_status
+  , s_res_line_almost_done
+
+  , s_start_req
+
+  , s_req_method
+  , s_req_spaces_before_url
+  , s_req_schema
+  , s_req_schema_slash
+  , s_req_schema_slash_slash
+  , s_req_server_start
+  , s_req_server
+  , s_req_server_with_at
+  , s_req_path
+  , s_req_query_string_start
+  , s_req_query_string
+  , s_req_fragment_start
+  , s_req_fragment
+  , s_req_http_start
+  , s_req_http_H
+  , s_req_http_HT
+  , s_req_http_HTT
+  , s_req_http_HTTP
+  , s_req_http_major
+  , s_req_http_dot
+  , s_req_http_minor
+  , s_req_http_end
+  , s_req_line_almost_done
+
+  , s_header_field_start
+  , s_header_field
+  , s_header_value_discard_ws
+  , s_header_value_discard_ws_almost_done
+  , s_header_value_discard_lws
+  , s_header_value_start
+  , s_header_value
+  , s_header_value_lws
+
+  , s_header_almost_done
+
+  , s_chunk_size_start
+  , s_chunk_size
+  , s_chunk_parameters
+  , s_chunk_size_almost_done
+
+  , s_headers_almost_done
+  , s_headers_done
+
+  /* Important: 's_headers_done' must be the last 'header' state. All
+   * states beyond this must be 'body' states. It is used for overflow
+   * checking. See the PARSING_HEADER() macro.
+   */
+
+  , s_chunk_data
+  , s_chunk_data_almost_done
+  , s_chunk_data_done
+
+  , s_body_identity
+  , s_body_identity_eof
+
+  , s_message_done
+  };
+
+
+#define PARSING_HEADER(state) (state <= s_headers_done)
+
+
+enum header_states
+  { h_general = 0
+  , h_C
+  , h_CO
+  , h_CON
+
+  , h_matching_connection
+  , h_matching_proxy_connection
+  , h_matching_content_length
+  , h_matching_transfer_encoding
+  , h_matching_upgrade
+
+  , h_connection
+  , h_content_length
+  , h_content_length_num
+  , h_content_length_ws
+  , h_transfer_encoding
+  , h_upgrade
+
+  , h_matching_transfer_encoding_chunked
+  , h_matching_connection_token_start
+  , h_matching_connection_keep_alive
+  , h_matching_connection_close
+  , h_matching_connection_upgrade
+  , h_matching_connection_token
+
+  , h_transfer_encoding_chunked
+  , h_connection_keep_alive
+  , h_connection_close
+  , h_connection_upgrade
+  };
+
+enum http_host_state
+  {
+    s_http_host_dead = 1
+  , s_http_userinfo_start
+  , s_http_userinfo
+  , s_http_host_start
+  , s_http_host_v6_start
+  , s_http_host
+  , s_http_host_v6
+  , s_http_host_v6_end
+  , s_http_host_v6_zone_start
+  , s_http_host_v6_zone
+  , s_http_host_port_start
+  , s_http_host_port
+};
+
+/* Macros for character classes; depends on strict-mode  */
+#define CR                  '\r'
+#define LF                  '\n'
+#define LOWER(c)            (unsigned char)(c | 0x20)
+#define IS_ALPHA(c)         (LOWER(c) >= 'a' && LOWER(c) <= 'z')
+#define IS_NUM(c)           ((c) >= '0' && (c) <= '9')
+#define IS_ALPHANUM(c)      (IS_ALPHA(c) || IS_NUM(c))
+#define IS_HEX(c)           (IS_NUM(c) || (LOWER(c) >= 'a' && LOWER(c) <= 'f'))
+#define IS_MARK(c)          ((c) == '-' || (c) == '_' || (c) == '.' || \
+  (c) == '!' || (c) == '~' || (c) == '*' || (c) == '\'' || (c) == '(' || \
+  (c) == ')')
+#define IS_USERINFO_CHAR(c) (IS_ALPHANUM(c) || IS_MARK(c) || (c) == '%' || \
+  (c) == ';' || (c) == ':' || (c) == '&' || (c) == '=' || (c) == '+' || \
+  (c) == '$' || (c) == ',')
+
+#define STRICT_TOKEN(c)     ((c == ' ') ? 0 : tokens[(unsigned char)c])
+
+#if HTTP_PARSER_STRICT
+#define TOKEN(c)            STRICT_TOKEN(c)
+#define IS_URL_CHAR(c)      (BIT_AT(normal_url_char, (unsigned char)c))
+#define IS_HOST_CHAR(c)     (IS_ALPHANUM(c) || (c) == '.' || (c) == '-')
+#else
+#define TOKEN(c)            tokens[(unsigned char)c]
+#define IS_URL_CHAR(c)                                                         \
+  (BIT_AT(normal_url_char, (unsigned char)c) || ((c) & 0x80))
+#define IS_HOST_CHAR(c)                                                        \
+  (IS_ALPHANUM(c) || (c) == '.' || (c) == '-' || (c) == '_')
+#endif
+
+/**
+ * Verify that a char is a valid visible (printable) US-ASCII
+ * character or %x80-FF
+ **/
+#define IS_HEADER_CHAR(ch)                                                     \
+  (ch == CR || ch == LF || ch == 9 || ((unsigned char)ch > 31 && ch != 127))
+
+#define start_state (parser->type == HTTP_REQUEST ? s_start_req : s_start_res)
+
+
+#if HTTP_PARSER_STRICT
+# define STRICT_CHECK(cond)                                          \
+do {                                                                 \
+  if (cond) {                                                        \
+    SET_ERRNO(HPE_STRICT);                                           \
+    goto error;                                                      \
+  }                                                                  \
+} while (0)
+# define NEW_MESSAGE() (http_should_keep_alive(parser) ? start_state : s_dead)
+#else
+# define STRICT_CHECK(cond)
+# define NEW_MESSAGE() start_state
+#endif
+
+
+/* Map errno values to strings for human-readable output */
+#define HTTP_STRERROR_GEN(n, s) { "HPE_" #n, s },
+static struct {
+  const char *name;
+  const char *description;
+} http_strerror_tab[] = {
+  HTTP_ERRNO_MAP(HTTP_STRERROR_GEN)
+};
+#undef HTTP_STRERROR_GEN
+
+int http_message_needs_eof(const http_parser *parser);
+
+/* Our URL parser.
+ *
+ * This is designed to be shared by http_parser_execute() for URL validation,
+ * hence it has a state transition + byte-for-byte interface. In addition, it
+ * is meant to be embedded in http_parser_parse_url(), which does the dirty
+ * work of turning state transitions URL components for its API.
+ *
+ * This function should only be invoked with non-space characters. It is
+ * assumed that the caller cares about (and can detect) the transition between
+ * URL and non-URL states by looking for these.
+ */
+static enum state
+parse_url_char(enum state s, const char ch)
+{
+  if (ch == ' ' || ch == '\r' || ch == '\n') {
+    return s_dead;
+  }
+
+#if HTTP_PARSER_STRICT
+  if (ch == '\t' || ch == '\f') {
+    return s_dead;
+  }
+#endif
+
+  switch (s) {
+    case s_req_spaces_before_url:
+      /* Proxied requests are followed by scheme of an absolute URI (alpha).
+       * All methods except CONNECT are followed by '/' or '*'.
+       */
+
+      if (ch == '/' || ch == '*') {
+        return s_req_path;
+      }
+
+      if (IS_ALPHA(ch)) {
+        return s_req_schema;
+      }
+
+      break;
+
+    case s_req_schema:
+      if (IS_ALPHA(ch)) {
+        return s;
+      }
+
+      if (ch == ':') {
+        return s_req_schema_slash;
+      }
+
+      break;
+
+    case s_req_schema_slash:
+      if (ch == '/') {
+        return s_req_schema_slash_slash;
+      }
+
+      break;
+
+    case s_req_schema_slash_slash:
+      if (ch == '/') {
+        return s_req_server_start;
+      }
+
+      break;
+
+    case s_req_server_with_at:
+      if (ch == '@') {
+        return s_dead;
+      }
+
+    /* fall through */
+    case s_req_server_start:
+    case s_req_server:
+      if (ch == '/') {
+        return s_req_path;
+      }
+
+      if (ch == '?') {
+        return s_req_query_string_start;
+      }
+
+      if (ch == '@') {
+        return s_req_server_with_at;
+      }
+
+      if (IS_USERINFO_CHAR(ch) || ch == '[' || ch == ']') {
+        return s_req_server;
+      }
+
+      break;
+
+    case s_req_path:
+      if (IS_URL_CHAR(ch)) {
+        return s;
+      }
+
+      switch (ch) {
+        case '?':
+          return s_req_query_string_start;
+
+        case '#':
+          return s_req_fragment_start;
+      }
+
+      break;
+
+    case s_req_query_string_start:
+    case s_req_query_string:
+      if (IS_URL_CHAR(ch)) {
+        return s_req_query_string;
+      }
+
+      switch (ch) {
+        case '?':
+          /* allow extra '?' in query string */
+          return s_req_query_string;
+
+        case '#':
+          return s_req_fragment_start;
+      }
+
+      break;
+
+    case s_req_fragment_start:
+      if (IS_URL_CHAR(ch)) {
+        return s_req_fragment;
+      }
+
+      switch (ch) {
+        case '?':
+          return s_req_fragment;
+
+        case '#':
+          return s;
+      }
+
+      break;
+
+    case s_req_fragment:
+      if (IS_URL_CHAR(ch)) {
+        return s;
+      }
+
+      switch (ch) {
+        case '?':
+        case '#':
+          return s;
+      }
+
+      break;
+
+    default:
+      break;
+  }
+
+  /* We should never fall out of the switch above unless there's an error */
+  return s_dead;
+}
+
+size_t http_parser_execute (http_parser *parser,
+                            const http_parser_settings *settings,
+                            const char *data,
+                            size_t len)
+{
+  char c, ch;
+  int8_t unhex_val;
+  const char *p = data;
+  const char *header_field_mark = 0;
+  const char *header_value_mark = 0;
+  const char *url_mark = 0;
+  const char *body_mark = 0;
+  const char *status_mark = 0;
+  enum state p_state = (enum state) parser->state;
+  const unsigned int lenient = parser->lenient_http_headers;
+  uint32_t nread = parser->nread;
+
+  /* We're in an error state. Don't bother doing anything. */
+  if (HTTP_PARSER_ERRNO(parser) != HPE_OK) {
+    return 0;
+  }
+
+  if (len == 0) {
+    switch (CURRENT_STATE()) {
+      case s_body_identity_eof:
+        /* Use of CALLBACK_NOTIFY() here would erroneously return 1 byte read if
+         * we got paused.
+         */
+        CALLBACK_NOTIFY_NOADVANCE(message_complete);
+        return 0;
+
+      case s_dead:
+      case s_start_req_or_res:
+      case s_start_res:
+      case s_start_req:
+        return 0;
+
+      default:
+        SET_ERRNO(HPE_INVALID_EOF_STATE);
+        return 1;
+    }
+  }
+
+
+  if (CURRENT_STATE() == s_header_field)
+    header_field_mark = data;
+  if (CURRENT_STATE() == s_header_value)
+    header_value_mark = data;
+  switch (CURRENT_STATE()) {
+  case s_req_path:
+  case s_req_schema:
+  case s_req_schema_slash:
+  case s_req_schema_slash_slash:
+  case s_req_server_start:
+  case s_req_server:
+  case s_req_server_with_at:
+  case s_req_query_string_start:
+  case s_req_query_string:
+  case s_req_fragment_start:
+  case s_req_fragment:
+    url_mark = data;
+    break;
+  case s_res_status:
+    status_mark = data;
+    break;
+  default:
+    break;
+  }
+
+  for (p=data; p != data + len; p++) {
+    ch = *p;
+
+    if (PARSING_HEADER(CURRENT_STATE()))
+      COUNT_HEADER_SIZE(1);
+
+reexecute:
+    switch (CURRENT_STATE()) {
+
+      case s_dead:
+        /* this state is used after a 'Connection: close' message
+         * the parser will error out if it reads another message
+         */
+        if (LIKELY(ch == CR || ch == LF))
+          break;
+
+        SET_ERRNO(HPE_CLOSED_CONNECTION);
+        goto error;
+
+      case s_start_req_or_res:
+      {
+        if (ch == CR || ch == LF)
+          break;
+        parser->flags = 0;
+        parser->content_length = ULLONG_MAX;
+
+        if (ch == 'H') {
+          UPDATE_STATE(s_res_or_resp_H);
+
+          CALLBACK_NOTIFY(message_begin);
+        } else {
+          parser->type = HTTP_REQUEST;
+          UPDATE_STATE(s_start_req);
+          REEXECUTE();
+        }
+
+        break;
+      }
+
+      case s_res_or_resp_H:
+        if (ch == 'T') {
+          parser->type = HTTP_RESPONSE;
+          UPDATE_STATE(s_res_HT);
+        } else {
+          if (UNLIKELY(ch != 'E')) {
+            SET_ERRNO(HPE_INVALID_CONSTANT);
+            goto error;
+          }
+
+          parser->type = HTTP_REQUEST;
+          parser->method = HTTP_HEAD;
+          parser->index = 2;
+          UPDATE_STATE(s_req_method);
+        }
+        break;
+
+      case s_start_res:
+      {
+        parser->flags = 0;
+        parser->content_length = ULLONG_MAX;
+
+        switch (ch) {
+          case 'H':
+            UPDATE_STATE(s_res_H);
+            break;
+
+          case CR:
+          case LF:
+            break;
+
+          default:
+            SET_ERRNO(HPE_INVALID_CONSTANT);
+            goto error;
+        }
+
+        CALLBACK_NOTIFY(message_begin);
+        break;
+      }
+
+      case s_res_H:
+        STRICT_CHECK(ch != 'T');
+        UPDATE_STATE(s_res_HT);
+        break;
+
+      case s_res_HT:
+        STRICT_CHECK(ch != 'T');
+        UPDATE_STATE(s_res_HTT);
+        break;
+
+      case s_res_HTT:
+        STRICT_CHECK(ch != 'P');
+        UPDATE_STATE(s_res_HTTP);
+        break;
+
+      case s_res_HTTP:
+        STRICT_CHECK(ch != '/');
+        UPDATE_STATE(s_res_http_major);
+        break;
+
+      case s_res_http_major:
+        if (UNLIKELY(!IS_NUM(ch))) {
+          SET_ERRNO(HPE_INVALID_VERSION);
+          goto error;
+        }
+
+        parser->http_major = ch - '0';
+        UPDATE_STATE(s_res_http_dot);
+        break;
+
+      case s_res_http_dot:
+      {
+        if (UNLIKELY(ch != '.')) {
+          SET_ERRNO(HPE_INVALID_VERSION);
+          goto error;
+        }
+
+        UPDATE_STATE(s_res_http_minor);
+        break;
+      }
+
+      case s_res_http_minor:
+        if (UNLIKELY(!IS_NUM(ch))) {
+          SET_ERRNO(HPE_INVALID_VERSION);
+          goto error;
+        }
+
+        parser->http_minor = ch - '0';
+        UPDATE_STATE(s_res_http_end);
+        break;
+
+      case s_res_http_end:
+      {
+        if (UNLIKELY(ch != ' ')) {
+          SET_ERRNO(HPE_INVALID_VERSION);
+          goto error;
+        }
+
+        UPDATE_STATE(s_res_first_status_code);
+        break;
+      }
+
+      case s_res_first_status_code:
+      {
+        if (!IS_NUM(ch)) {
+          if (ch == ' ') {
+            break;
+          }
+
+          SET_ERRNO(HPE_INVALID_STATUS);
+          goto error;
+        }
+        parser->status_code = ch - '0';
+        UPDATE_STATE(s_res_status_code);
+        break;
+      }
+
+      case s_res_status_code:
+      {
+        if (!IS_NUM(ch)) {
+          switch (ch) {
+            case ' ':
+              UPDATE_STATE(s_res_status_start);
+              break;
+            case CR:
+            case LF:
+              UPDATE_STATE(s_res_status_start);
+              REEXECUTE();
+              break;
+            default:
+              SET_ERRNO(HPE_INVALID_STATUS);
+              goto error;
+          }
+          break;
+        }
+
+        parser->status_code *= 10;
+        parser->status_code += ch - '0';
+
+        if (UNLIKELY(parser->status_code > 999)) {
+          SET_ERRNO(HPE_INVALID_STATUS);
+          goto error;
+        }
+
+        break;
+      }
+
+      case s_res_status_start:
+      {
+        MARK(status);
+        UPDATE_STATE(s_res_status);
+        parser->index = 0;
+
+        if (ch == CR || ch == LF)
+          REEXECUTE();
+
+        break;
+      }
+
+      case s_res_status:
+        if (ch == CR) {
+          UPDATE_STATE(s_res_line_almost_done);
+          CALLBACK_DATA(status);
+          break;
+        }
+
+        if (ch == LF) {
+          UPDATE_STATE(s_header_field_start);
+          CALLBACK_DATA(status);
+          break;
+        }
+
+        break;
+
+      case s_res_line_almost_done:
+        STRICT_CHECK(ch != LF);
+        UPDATE_STATE(s_header_field_start);
+        break;
+
+      case s_start_req:
+      {
+        if (ch == CR || ch == LF)
+          break;
+        parser->flags = 0;
+        parser->content_length = ULLONG_MAX;
+
+        if (UNLIKELY(!IS_ALPHA(ch))) {
+          SET_ERRNO(HPE_INVALID_METHOD);
+          goto error;
+        }
+
+        parser->method = (enum http_method) 0;
+        parser->index = 1;
+        switch (ch) {
+          case 'A': parser->method = HTTP_ACL; break;
+          case 'B': parser->method = HTTP_BIND; break;
+          case 'C': parser->method = HTTP_CONNECT; /* or COPY, CHECKOUT */ break;
+          case 'D': parser->method = HTTP_DELETE; break;
+          case 'G': parser->method = HTTP_GET; break;
+          case 'H': parser->method = HTTP_HEAD; break;
+          case 'L': parser->method = HTTP_LOCK; /* or LINK */ break;
+          case 'M': parser->method = HTTP_MKCOL; /* or MOVE, MKACTIVITY, MERGE, M-SEARCH, MKCALENDAR */ break;
+          case 'N': parser->method = HTTP_NOTIFY; break;
+          case 'O': parser->method = HTTP_OPTIONS; break;
+          case 'P': parser->method = HTTP_POST;
+            /* or PROPFIND|PROPPATCH|PUT|PATCH|PURGE */
+            break;
+          case 'R': parser->method = HTTP_REPORT; /* or REBIND */ break;
+          case 'S': parser->method = HTTP_SUBSCRIBE; /* or SEARCH, SOURCE */ break;
+          case 'T': parser->method = HTTP_TRACE; break;
+          case 'U': parser->method = HTTP_UNLOCK; /* or UNSUBSCRIBE, UNBIND, UNLINK */ break;
+          default:
+            SET_ERRNO(HPE_INVALID_METHOD);
+            goto error;
+        }
+        UPDATE_STATE(s_req_method);
+
+        CALLBACK_NOTIFY(message_begin);
+
+        break;
+      }
+
+      case s_req_method:
+      {
+        const char *matcher;
+        if (UNLIKELY(ch == '\0')) {
+          SET_ERRNO(HPE_INVALID_METHOD);
+          goto error;
+        }
+
+        matcher = method_strings[parser->method];
+        if (ch == ' ' && matcher[parser->index] == '\0') {
+          UPDATE_STATE(s_req_spaces_before_url);
+        } else if (ch == matcher[parser->index]) {
+          ; /* nada */
+        } else if ((ch >= 'A' && ch <= 'Z') || ch == '-') {
+
+          switch (parser->method << 16 | parser->index << 8 | ch) {
+#define XX(meth, pos, ch, new_meth) \
+            case (HTTP_##meth << 16 | pos << 8 | ch): \
+              parser->method = HTTP_##new_meth; break;
+
+            XX(POST,      1, 'U', PUT)
+            XX(POST,      1, 'A', PATCH)
+            XX(POST,      1, 'R', PROPFIND)
+            XX(PUT,       2, 'R', PURGE)
+            XX(CONNECT,   1, 'H', CHECKOUT)
+            XX(CONNECT,   2, 'P', COPY)
+            XX(MKCOL,     1, 'O', MOVE)
+            XX(MKCOL,     1, 'E', MERGE)
+            XX(MKCOL,     1, '-', MSEARCH)
+            XX(MKCOL,     2, 'A', MKACTIVITY)
+            XX(MKCOL,     3, 'A', MKCALENDAR)
+            XX(SUBSCRIBE, 1, 'E', SEARCH)
+            XX(SUBSCRIBE, 1, 'O', SOURCE)
+            XX(REPORT,    2, 'B', REBIND)
+            XX(PROPFIND,  4, 'P', PROPPATCH)
+            XX(LOCK,      1, 'I', LINK)
+            XX(UNLOCK,    2, 'S', UNSUBSCRIBE)
+            XX(UNLOCK,    2, 'B', UNBIND)
+            XX(UNLOCK,    3, 'I', UNLINK)
+#undef XX
+            default:
+              SET_ERRNO(HPE_INVALID_METHOD);
+              goto error;
+          }
+        } else {
+          SET_ERRNO(HPE_INVALID_METHOD);
+          goto error;
+        }
+
+        ++parser->index;
+        break;
+      }
+
+      case s_req_spaces_before_url:
+      {
+        if (ch == ' ') break;
+
+        MARK(url);
+        if (parser->method == HTTP_CONNECT) {
+          UPDATE_STATE(s_req_server_start);
+        }
+
+        UPDATE_STATE(parse_url_char(CURRENT_STATE(), ch));
+        if (UNLIKELY(CURRENT_STATE() == s_dead)) {
+          SET_ERRNO(HPE_INVALID_URL);
+          goto error;
+        }
+
+        break;
+      }
+
+      case s_req_schema:
+      case s_req_schema_slash:
+      case s_req_schema_slash_slash:
+      case s_req_server_start:
+      {
+        switch (ch) {
+          /* No whitespace allowed here */
+          case ' ':
+          case CR:
+          case LF:
+            SET_ERRNO(HPE_INVALID_URL);
+            goto error;
+          default:
+            UPDATE_STATE(parse_url_char(CURRENT_STATE(), ch));
+            if (UNLIKELY(CURRENT_STATE() == s_dead)) {
+              SET_ERRNO(HPE_INVALID_URL);
+              goto error;
+            }
+        }
+
+        break;
+      }
+
+      case s_req_server:
+      case s_req_server_with_at:
+      case s_req_path:
+      case s_req_query_string_start:
+      case s_req_query_string:
+      case s_req_fragment_start:
+      case s_req_fragment:
+      {
+        switch (ch) {
+          case ' ':
+            UPDATE_STATE(s_req_http_start);
+            CALLBACK_DATA(url);
+            break;
+          case CR:
+          case LF:
+            parser->http_major = 0;
+            parser->http_minor = 9;
+            UPDATE_STATE((ch == CR) ?
+              s_req_line_almost_done :
+              s_header_field_start);
+            CALLBACK_DATA(url);
+            break;
+          default:
+            UPDATE_STATE(parse_url_char(CURRENT_STATE(), ch));
+            if (UNLIKELY(CURRENT_STATE() == s_dead)) {
+              SET_ERRNO(HPE_INVALID_URL);
+              goto error;
+            }
+        }
+        break;
+      }
+
+      case s_req_http_start:
+        switch (ch) {
+          case 'H':
+            UPDATE_STATE(s_req_http_H);
+            break;
+          case ' ':
+            break;
+          default:
+            SET_ERRNO(HPE_INVALID_CONSTANT);
+            goto error;
+        }
+        break;
+
+      case s_req_http_H:
+        STRICT_CHECK(ch != 'T');
+        UPDATE_STATE(s_req_http_HT);
+        break;
+
+      case s_req_http_HT:
+        STRICT_CHECK(ch != 'T');
+        UPDATE_STATE(s_req_http_HTT);
+        break;
+
+      case s_req_http_HTT:
+        STRICT_CHECK(ch != 'P');
+        UPDATE_STATE(s_req_http_HTTP);
+        break;
+
+      case s_req_http_HTTP:
+        STRICT_CHECK(ch != '/');
+        UPDATE_STATE(s_req_http_major);
+        break;
+
+      case s_req_http_major:
+        if (UNLIKELY(!IS_NUM(ch))) {
+          SET_ERRNO(HPE_INVALID_VERSION);
+          goto error;
+        }
+
+        parser->http_major = ch - '0';
+        UPDATE_STATE(s_req_http_dot);
+        break;
+
+      case s_req_http_dot:
+      {
+        if (UNLIKELY(ch != '.')) {
+          SET_ERRNO(HPE_INVALID_VERSION);
+          goto error;
+        }
+
+        UPDATE_STATE(s_req_http_minor);
+        break;
+      }
+
+      case s_req_http_minor:
+        if (UNLIKELY(!IS_NUM(ch))) {
+          SET_ERRNO(HPE_INVALID_VERSION);
+          goto error;
+        }
+
+        parser->http_minor = ch - '0';
+        UPDATE_STATE(s_req_http_end);
+        break;
+
+      case s_req_http_end:
+      {
+        if (ch == CR) {
+          UPDATE_STATE(s_req_line_almost_done);
+          break;
+        }
+
+        if (ch == LF) {
+          UPDATE_STATE(s_header_field_start);
+          break;
+        }
+
+        SET_ERRNO(HPE_INVALID_VERSION);
+        goto error;
+        break;
+      }
+
+      /* end of request line */
+      case s_req_line_almost_done:
+      {
+        if (UNLIKELY(ch != LF)) {
+          SET_ERRNO(HPE_LF_EXPECTED);
+          goto error;
+        }
+
+        UPDATE_STATE(s_header_field_start);
+        break;
+      }
+
+      case s_header_field_start:
+      {
+        if (ch == CR) {
+          UPDATE_STATE(s_headers_almost_done);
+          break;
+        }
+
+        if (ch == LF) {
+          /* they might be just sending \n instead of \r\n so this would be
+           * the second \n to denote the end of headers*/
+          UPDATE_STATE(s_headers_almost_done);
+          REEXECUTE();
+        }
+
+        c = TOKEN(ch);
+
+        if (UNLIKELY(!c)) {
+          SET_ERRNO(HPE_INVALID_HEADER_TOKEN);
+          goto error;
+        }
+
+        MARK(header_field);
+
+        parser->index = 0;
+        UPDATE_STATE(s_header_field);
+
+        switch (c) {
+          case 'c':
+            parser->header_state = h_C;
+            break;
+
+          case 'p':
+            parser->header_state = h_matching_proxy_connection;
+            break;
+
+          case 't':
+            parser->header_state = h_matching_transfer_encoding;
+            break;
+
+          case 'u':
+            parser->header_state = h_matching_upgrade;
+            break;
+
+          default:
+            parser->header_state = h_general;
+            break;
+        }
+        break;
+      }
+
+      case s_header_field:
+      {
+        const char* start = p;
+        for (; p != data + len; p++) {
+          ch = *p;
+          c = TOKEN(ch);
+
+          if (!c)
+            break;
+
+          switch (parser->header_state) {
+            case h_general: {
+              size_t limit = data + len - p;
+              limit = MIN(limit, HTTP_MAX_HEADER_SIZE);
+              while (p+1 < data + limit && TOKEN(p[1])) {
+                p++;
+              }
+              break;
+            }
+
+            case h_C:
+              parser->index++;
+              parser->header_state = (c == 'o' ? h_CO : h_general);
+              break;
+
+            case h_CO:
+              parser->index++;
+              parser->header_state = (c == 'n' ? h_CON : h_general);
+              break;
+
+            case h_CON:
+              parser->index++;
+              switch (c) {
+                case 'n':
+                  parser->header_state = h_matching_connection;
+                  break;
+                case 't':
+                  parser->header_state = h_matching_content_length;
+                  break;
+                default:
+                  parser->header_state = h_general;
+                  break;
+              }
+              break;
+
+            /* connection */
+
+            case h_matching_connection:
+              parser->index++;
+              if (parser->index > sizeof(CONNECTION)-1
+                  || c != CONNECTION[parser->index]) {
+                parser->header_state = h_general;
+              } else if (parser->index == sizeof(CONNECTION)-2) {
+                parser->header_state = h_connection;
+              }
+              break;
+
+            /* proxy-connection */
+
+            case h_matching_proxy_connection:
+              parser->index++;
+              if (parser->index > sizeof(PROXY_CONNECTION)-1
+                  || c != PROXY_CONNECTION[parser->index]) {
+                parser->header_state = h_general;
+              } else if (parser->index == sizeof(PROXY_CONNECTION)-2) {
+                parser->header_state = h_connection;
+              }
+              break;
+
+            /* content-length */
+
+            case h_matching_content_length:
+              parser->index++;
+              if (parser->index > sizeof(CONTENT_LENGTH)-1
+                  || c != CONTENT_LENGTH[parser->index]) {
+                parser->header_state = h_general;
+              } else if (parser->index == sizeof(CONTENT_LENGTH)-2) {
+                parser->header_state = h_content_length;
+              }
+              break;
+
+            /* transfer-encoding */
+
+            case h_matching_transfer_encoding:
+              parser->index++;
+              if (parser->index > sizeof(TRANSFER_ENCODING)-1
+                  || c != TRANSFER_ENCODING[parser->index]) {
+                parser->header_state = h_general;
+              } else if (parser->index == sizeof(TRANSFER_ENCODING)-2) {
+                parser->header_state = h_transfer_encoding;
+              }
+              break;
+
+            /* upgrade */
+
+            case h_matching_upgrade:
+              parser->index++;
+              if (parser->index > sizeof(UPGRADE)-1
+                  || c != UPGRADE[parser->index]) {
+                parser->header_state = h_general;
+              } else if (parser->index == sizeof(UPGRADE)-2) {
+                parser->header_state = h_upgrade;
+              }
+              break;
+
+            case h_connection:
+            case h_content_length:
+            case h_transfer_encoding:
+            case h_upgrade:
+              if (ch != ' ') parser->header_state = h_general;
+              break;
+
+            default:
+              assert(0 && "Unknown header_state");
+              break;
+          }
+        }
+
+        if (p == data + len) {
+          --p;
+          COUNT_HEADER_SIZE(p - start);
+          break;
+        }
+
+        COUNT_HEADER_SIZE(p - start);
+
+        if (ch == ':') {
+          UPDATE_STATE(s_header_value_discard_ws);
+          CALLBACK_DATA(header_field);
+          break;
+        }
+
+        SET_ERRNO(HPE_INVALID_HEADER_TOKEN);
+        goto error;
+      }
+
+      case s_header_value_discard_ws:
+        if (ch == ' ' || ch == '\t') break;
+
+        if (ch == CR) {
+          UPDATE_STATE(s_header_value_discard_ws_almost_done);
+          break;
+        }
+
+        if (ch == LF) {
+          UPDATE_STATE(s_header_value_discard_lws);
+          break;
+        }
+
+        /* fall through */
+
+      case s_header_value_start:
+      {
+        MARK(header_value);
+
+        UPDATE_STATE(s_header_value);
+        parser->index = 0;
+
+        c = LOWER(ch);
+
+        switch (parser->header_state) {
+          case h_upgrade:
+            parser->flags |= F_UPGRADE;
+            parser->header_state = h_general;
+            break;
+
+          case h_transfer_encoding:
+            /* looking for 'Transfer-Encoding: chunked' */
+            if ('c' == c) {
+              parser->header_state = h_matching_transfer_encoding_chunked;
+            } else {
+              parser->header_state = h_general;
+            }
+            break;
+
+          case h_content_length:
+            if (UNLIKELY(!IS_NUM(ch))) {
+              SET_ERRNO(HPE_INVALID_CONTENT_LENGTH);
+              goto error;
+            }
+
+            if (parser->flags & F_CONTENTLENGTH) {
+              SET_ERRNO(HPE_UNEXPECTED_CONTENT_LENGTH);
+              goto error;
+            }
+
+            parser->flags |= F_CONTENTLENGTH;
+            parser->content_length = ch - '0';
+            parser->header_state = h_content_length_num;
+            break;
+
+          case h_connection:
+            /* looking for 'Connection: keep-alive' */
+            if (c == 'k') {
+              parser->header_state = h_matching_connection_keep_alive;
+            /* looking for 'Connection: close' */
+            } else if (c == 'c') {
+              parser->header_state = h_matching_connection_close;
+            } else if (c == 'u') {
+              parser->header_state = h_matching_connection_upgrade;
+            } else {
+              parser->header_state = h_matching_connection_token;
+            }
+            break;
+
+          /* Multi-value `Connection` header */
+          case h_matching_connection_token_start:
+            break;
+
+          default:
+            parser->header_state = h_general;
+            break;
+        }
+        break;
+      }
+
+      case s_header_value:
+      {
+        const char* start = p;
+        enum header_states h_state = (enum header_states) parser->header_state;
+        for (; p != data + len; p++) {
+          ch = *p;
+          if (ch == CR) {
+            UPDATE_STATE(s_header_almost_done);
+            parser->header_state = h_state;
+            CALLBACK_DATA(header_value);
+            break;
+          }
+
+          if (ch == LF) {
+            UPDATE_STATE(s_header_almost_done);
+            COUNT_HEADER_SIZE(p - start);
+            parser->header_state = h_state;
+            CALLBACK_DATA_NOADVANCE(header_value);
+            REEXECUTE();
+          }
+
+          if (!lenient && !IS_HEADER_CHAR(ch)) {
+            SET_ERRNO(HPE_INVALID_HEADER_TOKEN);
+            goto error;
+          }
+
+          c = LOWER(ch);
+
+          switch (h_state) {
+            case h_general:
+            {
+              const char* p_cr;
+              const char* p_lf;
+              size_t limit = data + len - p;
+
+              limit = MIN(limit, HTTP_MAX_HEADER_SIZE);
+
+              p_cr = (const char*) memchr(p, CR, limit);
+              p_lf = (const char*) memchr(p, LF, limit);
+              if (p_cr != NULL) {
+                if (p_lf != NULL && p_cr >= p_lf)
+                  p = p_lf;
+                else
+                  p = p_cr;
+              } else if (UNLIKELY(p_lf != NULL)) {
+                p = p_lf;
+              } else {
+                p = data + len;
+              }
+              --p;
+              break;
+            }
+
+            case h_connection:
+            case h_transfer_encoding:
+              assert(0 && "Shouldn't get here.");
+              break;
+
+            case h_content_length:
+              if (ch == ' ') break;
+              h_state = h_content_length_num;
+              /* fall through */
+
+            case h_content_length_num:
+            {
+              uint64_t t;
+
+              if (ch == ' ') {
+                h_state = h_content_length_ws;
+                break;
+              }
+
+              if (UNLIKELY(!IS_NUM(ch))) {
+                SET_ERRNO(HPE_INVALID_CONTENT_LENGTH);
+                parser->header_state = h_state;
+                goto error;
+              }
+
+              t = parser->content_length;
+              t *= 10;
+              t += ch - '0';
+
+              /* Overflow? Test against a conservative limit for simplicity. */
+              if (UNLIKELY((ULLONG_MAX - 10) / 10 < parser->content_length)) {
+                SET_ERRNO(HPE_INVALID_CONTENT_LENGTH);
+                parser->header_state = h_state;
+                goto error;
+              }
+
+              parser->content_length = t;
+              break;
+            }
+
+            case h_content_length_ws:
+              if (ch == ' ') break;
+              SET_ERRNO(HPE_INVALID_CONTENT_LENGTH);
+              parser->header_state = h_state;
+              goto error;
+
+            /* Transfer-Encoding: chunked */
+            case h_matching_transfer_encoding_chunked:
+              parser->index++;
+              if (parser->index > sizeof(CHUNKED)-1
+                  || c != CHUNKED[parser->index]) {
+                h_state = h_general;
+              } else if (parser->index == sizeof(CHUNKED)-2) {
+                h_state = h_transfer_encoding_chunked;
+              }
+              break;
+
+            case h_matching_connection_token_start:
+              /* looking for 'Connection: keep-alive' */
+              if (c == 'k') {
+                h_state = h_matching_connection_keep_alive;
+              /* looking for 'Connection: close' */
+              } else if (c == 'c') {
+                h_state = h_matching_connection_close;
+              } else if (c == 'u') {
+                h_state = h_matching_connection_upgrade;
+              } else if (STRICT_TOKEN(c)) {
+                h_state = h_matching_connection_token;
+              } else if (c == ' ' || c == '\t') {
+                /* Skip lws */
+              } else {
+                h_state = h_general;
+              }
+              break;
+
+            /* looking for 'Connection: keep-alive' */
+            case h_matching_connection_keep_alive:
+              parser->index++;
+              if (parser->index > sizeof(KEEP_ALIVE)-1
+                  || c != KEEP_ALIVE[parser->index]) {
+                h_state = h_matching_connection_token;
+              } else if (parser->index == sizeof(KEEP_ALIVE)-2) {
+                h_state = h_connection_keep_alive;
+              }
+              break;
+
+            /* looking for 'Connection: close' */
+            case h_matching_connection_close:
+              parser->index++;
+              if (parser->index > sizeof(CLOSE)-1 || c != CLOSE[parser->index]) {
+                h_state = h_matching_connection_token;
+              } else if (parser->index == sizeof(CLOSE)-2) {
+                h_state = h_connection_close;
+              }
+              break;
+
+            /* looking for 'Connection: upgrade' */
+            case h_matching_connection_upgrade:
+              parser->index++;
+              if (parser->index > sizeof(UPGRADE) - 1 ||
+                  c != UPGRADE[parser->index]) {
+                h_state = h_matching_connection_token;
+              } else if (parser->index == sizeof(UPGRADE)-2) {
+                h_state = h_connection_upgrade;
+              }
+              break;
+
+            case h_matching_connection_token:
+              if (ch == ',') {
+                h_state = h_matching_connection_token_start;
+                parser->index = 0;
+              }
+              break;
+
+            case h_transfer_encoding_chunked:
+              if (ch != ' ') h_state = h_general;
+              break;
+
+            case h_connection_keep_alive:
+            case h_connection_close:
+            case h_connection_upgrade:
+              if (ch == ',') {
+                if (h_state == h_connection_keep_alive) {
+                  parser->flags |= F_CONNECTION_KEEP_ALIVE;
+                } else if (h_state == h_connection_close) {
+                  parser->flags |= F_CONNECTION_CLOSE;
+                } else if (h_state == h_connection_upgrade) {
+                  parser->flags |= F_CONNECTION_UPGRADE;
+                }
+                h_state = h_matching_connection_token_start;
+                parser->index = 0;
+              } else if (ch != ' ') {
+                h_state = h_matching_connection_token;
+              }
+              break;
+
+            default:
+              UPDATE_STATE(s_header_value);
+              h_state = h_general;
+              break;
+          }
+        }
+        parser->header_state = h_state;
+
+        if (p == data + len)
+          --p;
+
+        COUNT_HEADER_SIZE(p - start);
+        break;
+      }
+
+      case s_header_almost_done:
+      {
+        if (UNLIKELY(ch != LF)) {
+          SET_ERRNO(HPE_LF_EXPECTED);
+          goto error;
+        }
+
+        UPDATE_STATE(s_header_value_lws);
+        break;
+      }
+
+      case s_header_value_lws:
+      {
+        if (ch == ' ' || ch == '\t') {
+          UPDATE_STATE(s_header_value_start);
+          REEXECUTE();
+        }
+
+        /* finished the header */
+        switch (parser->header_state) {
+          case h_connection_keep_alive:
+            parser->flags |= F_CONNECTION_KEEP_ALIVE;
+            break;
+          case h_connection_close:
+            parser->flags |= F_CONNECTION_CLOSE;
+            break;
+          case h_transfer_encoding_chunked:
+            parser->flags |= F_CHUNKED;
+            break;
+          case h_connection_upgrade:
+            parser->flags |= F_CONNECTION_UPGRADE;
+            break;
+          default:
+            break;
+        }
+
+        UPDATE_STATE(s_header_field_start);
+        REEXECUTE();
+      }
+
+      case s_header_value_discard_ws_almost_done:
+      {
+        STRICT_CHECK(ch != LF);
+        UPDATE_STATE(s_header_value_discard_lws);
+        break;
+      }
+
+      case s_header_value_discard_lws:
+      {
+        if (ch == ' ' || ch == '\t') {
+          UPDATE_STATE(s_header_value_discard_ws);
+          break;
+        } else {
+          switch (parser->header_state) {
+            case h_connection_keep_alive:
+              parser->flags |= F_CONNECTION_KEEP_ALIVE;
+              break;
+            case h_connection_close:
+              parser->flags |= F_CONNECTION_CLOSE;
+              break;
+            case h_connection_upgrade:
+              parser->flags |= F_CONNECTION_UPGRADE;
+              break;
+            case h_transfer_encoding_chunked:
+              parser->flags |= F_CHUNKED;
+              break;
+            default:
+              break;
+          }
+
+          /* header value was empty */
+          MARK(header_value);
+          UPDATE_STATE(s_header_field_start);
+          CALLBACK_DATA_NOADVANCE(header_value);
+          REEXECUTE();
+        }
+      }
+
+      case s_headers_almost_done:
+      {
+        STRICT_CHECK(ch != LF);
+
+        if (parser->flags & F_TRAILING) {
+          /* End of a chunked request */
+          UPDATE_STATE(s_message_done);
+          CALLBACK_NOTIFY_NOADVANCE(chunk_complete);
+          REEXECUTE();
+        }
+
+        /* Cannot use chunked encoding and a content-length header together
+           per the HTTP specification. */
+        if ((parser->flags & F_CHUNKED) &&
+            (parser->flags & F_CONTENTLENGTH)) {
+          SET_ERRNO(HPE_UNEXPECTED_CONTENT_LENGTH);
+          goto error;
+        }
+
+        UPDATE_STATE(s_headers_done);
+
+        /* Set this here so that on_headers_complete() callbacks can see it */
+        if ((parser->flags & F_UPGRADE) &&
+            (parser->flags & F_CONNECTION_UPGRADE)) {
+          /* For responses, "Upgrade: foo" and "Connection: upgrade" are
+           * mandatory only when it is a 101 Switching Protocols response,
+           * otherwise it is purely informational, to announce support.
+           */
+          parser->upgrade =
+              (parser->type == HTTP_REQUEST || parser->status_code == 101);
+        } else {
+          parser->upgrade = (parser->method == HTTP_CONNECT);
+        }
+
+        /* Here we call the headers_complete callback. This is somewhat
+         * different than other callbacks because if the user returns 1, we
+         * will interpret that as saying that this message has no body. This
+         * is needed for the annoying case of receiving a response to a HEAD
+         * request.
+         *
+         * We'd like to use CALLBACK_NOTIFY_NOADVANCE() here but we cannot, so
+         * we have to simulate it by handling a change in errno below.
+         */
+        if (settings->on_headers_complete) {
+          switch (settings->on_headers_complete(parser)) {
+            case 0:
+              break;
+
+            case 2:
+              parser->upgrade = 1;
+
+              /* fall through */
+            case 1:
+              parser->flags |= F_SKIPBODY;
+              break;
+
+            default:
+              SET_ERRNO(HPE_CB_headers_complete);
+              RETURN(p - data); /* Error */
+          }
+        }
+
+        if (HTTP_PARSER_ERRNO(parser) != HPE_OK) {
+          RETURN(p - data);
+        }
+
+        REEXECUTE();
+      }
+
+      case s_headers_done:
+      {
+        int hasBody;
+        STRICT_CHECK(ch != LF);
+
+        parser->nread = 0;
+        nread = 0;
+
+        hasBody = parser->flags & F_CHUNKED ||
+          (parser->content_length > 0 && parser->content_length != ULLONG_MAX);
+        if (parser->upgrade && (parser->method == HTTP_CONNECT ||
+                                (parser->flags & F_SKIPBODY) || !hasBody)) {
+          /* Exit, the rest of the message is in a different protocol. */
+          UPDATE_STATE(NEW_MESSAGE());
+          CALLBACK_NOTIFY(message_complete);
+          RETURN((p - data) + 1);
+        }
+
+        if (parser->flags & F_SKIPBODY) {
+          UPDATE_STATE(NEW_MESSAGE());
+          CALLBACK_NOTIFY(message_complete);
+        } else if (parser->flags & F_CHUNKED) {
+          /* chunked encoding - ignore Content-Length header */
+          UPDATE_STATE(s_chunk_size_start);
+        } else {
+          if (parser->content_length == 0) {
+            /* Content-Length header given but zero: Content-Length: 0\r\n */
+            UPDATE_STATE(NEW_MESSAGE());
+            CALLBACK_NOTIFY(message_complete);
+          } else if (parser->content_length != ULLONG_MAX) {
+            /* Content-Length header given and non-zero */
+            UPDATE_STATE(s_body_identity);
+          } else {
+            if (!http_message_needs_eof(parser)) {
+              /* Assume content-length 0 - read the next */
+              UPDATE_STATE(NEW_MESSAGE());
+              CALLBACK_NOTIFY(message_complete);
+            } else {
+              /* Read body until EOF */
+              UPDATE_STATE(s_body_identity_eof);
+            }
+          }
+        }
+
+        break;
+      }
+
+      case s_body_identity:
+      {
+        uint64_t to_read = MIN(parser->content_length,
+                               (uint64_t) ((data + len) - p));
+
+        assert(parser->content_length != 0
+            && parser->content_length != ULLONG_MAX);
+
+        /* The difference between advancing content_length and p is because
+         * the latter will automaticaly advance on the next loop iteration.
+         * Further, if content_length ends up at 0, we want to see the last
+         * byte again for our message complete callback.
+         */
+        MARK(body);
+        parser->content_length -= to_read;
+        p += to_read - 1;
+
+        if (parser->content_length == 0) {
+          UPDATE_STATE(s_message_done);
+
+          /* Mimic CALLBACK_DATA_NOADVANCE() but with one extra byte.
+           *
+           * The alternative to doing this is to wait for the next byte to
+           * trigger the data callback, just as in every other case. The
+           * problem with this is that this makes it difficult for the test
+           * harness to distinguish between complete-on-EOF and
+           * complete-on-length. It's not clear that this distinction is
+           * important for applications, but let's keep it for now.
+           */
+          CALLBACK_DATA_(body, p - body_mark + 1, p - data);
+          REEXECUTE();
+        }
+
+        break;
+      }
+
+      /* read until EOF */
+      case s_body_identity_eof:
+        MARK(body);
+        p = data + len - 1;
+
+        break;
+
+      case s_message_done:
+        UPDATE_STATE(NEW_MESSAGE());
+        CALLBACK_NOTIFY(message_complete);
+        if (parser->upgrade) {
+          /* Exit, the rest of the message is in a different protocol. */
+          RETURN((p - data) + 1);
+        }
+        break;
+
+      case s_chunk_size_start:
+      {
+        assert(nread == 1);
+        assert(parser->flags & F_CHUNKED);
+
+        unhex_val = unhex[(unsigned char)ch];
+        if (UNLIKELY(unhex_val == -1)) {
+          SET_ERRNO(HPE_INVALID_CHUNK_SIZE);
+          goto error;
+        }
+
+        parser->content_length = unhex_val;
+        UPDATE_STATE(s_chunk_size);
+        break;
+      }
+
+      case s_chunk_size:
+      {
+        uint64_t t;
+
+        assert(parser->flags & F_CHUNKED);
+
+        if (ch == CR) {
+          UPDATE_STATE(s_chunk_size_almost_done);
+          break;
+        }
+
+        unhex_val = unhex[(unsigned char)ch];
+
+        if (unhex_val == -1) {
+          if (ch == ';' || ch == ' ') {
+            UPDATE_STATE(s_chunk_parameters);
+            break;
+          }
+
+          SET_ERRNO(HPE_INVALID_CHUNK_SIZE);
+          goto error;
+        }
+
+        t = parser->content_length;
+        t *= 16;
+        t += unhex_val;
+
+        /* Overflow? Test against a conservative limit for simplicity. */
+        if (UNLIKELY((ULLONG_MAX - 16) / 16 < parser->content_length)) {
+          SET_ERRNO(HPE_INVALID_CONTENT_LENGTH);
+          goto error;
+        }
+
+        parser->content_length = t;
+        break;
+      }
+
+      case s_chunk_parameters:
+      {
+        assert(parser->flags & F_CHUNKED);
+        /* just ignore this shit. TODO check for overflow */
+        if (ch == CR) {
+          UPDATE_STATE(s_chunk_size_almost_done);
+          break;
+        }
+        break;
+      }
+
+      case s_chunk_size_almost_done:
+      {
+        assert(parser->flags & F_CHUNKED);
+        STRICT_CHECK(ch != LF);
+
+        parser->nread = 0;
+        nread = 0;
+
+        if (parser->content_length == 0) {
+          parser->flags |= F_TRAILING;
+          UPDATE_STATE(s_header_field_start);
+        } else {
+          UPDATE_STATE(s_chunk_data);
+        }
+        CALLBACK_NOTIFY(chunk_header);
+        break;
+      }
+
+      case s_chunk_data:
+      {
+        uint64_t to_read = MIN(parser->content_length,
+                               (uint64_t) ((data + len) - p));
+
+        assert(parser->flags & F_CHUNKED);
+        assert(parser->content_length != 0
+            && parser->content_length != ULLONG_MAX);
+
+        /* See the explanation in s_body_identity for why the content
+         * length and data pointers are managed this way.
+         */
+        MARK(body);
+        parser->content_length -= to_read;
+        p += to_read - 1;
+
+        if (parser->content_length == 0) {
+          UPDATE_STATE(s_chunk_data_almost_done);
+        }
+
+        break;
+      }
+
+      case s_chunk_data_almost_done:
+        assert(parser->flags & F_CHUNKED);
+        assert(parser->content_length == 0);
+        STRICT_CHECK(ch != CR);
+        UPDATE_STATE(s_chunk_data_done);
+        CALLBACK_DATA(body);
+        break;
+
+      case s_chunk_data_done:
+        assert(parser->flags & F_CHUNKED);
+        STRICT_CHECK(ch != LF);
+        parser->nread = 0;
+        nread = 0;
+        UPDATE_STATE(s_chunk_size_start);
+        CALLBACK_NOTIFY(chunk_complete);
+        break;
+
+      default:
+        assert(0 && "unhandled state");
+        SET_ERRNO(HPE_INVALID_INTERNAL_STATE);
+        goto error;
+    }
+  }
+
+  /* Run callbacks for any marks that we have leftover after we ran our of
+   * bytes. There should be at most one of these set, so it's OK to invoke
+   * them in series (unset marks will not result in callbacks).
+   *
+   * We use the NOADVANCE() variety of callbacks here because 'p' has already
+   * overflowed 'data' and this allows us to correct for the off-by-one that
+   * we'd otherwise have (since CALLBACK_DATA() is meant to be run with a 'p'
+   * value that's in-bounds).
+   */
+
+  assert(((header_field_mark ? 1 : 0) +
+          (header_value_mark ? 1 : 0) +
+          (url_mark ? 1 : 0)  +
+          (body_mark ? 1 : 0) +
+          (status_mark ? 1 : 0)) <= 1);
+
+  CALLBACK_DATA_NOADVANCE(header_field);
+  CALLBACK_DATA_NOADVANCE(header_value);
+  CALLBACK_DATA_NOADVANCE(url);
+  CALLBACK_DATA_NOADVANCE(body);
+  CALLBACK_DATA_NOADVANCE(status);
+
+  RETURN(len);
+
+error:
+  if (HTTP_PARSER_ERRNO(parser) == HPE_OK) {
+    SET_ERRNO(HPE_UNKNOWN);
+  }
+
+  RETURN(p - data);
+}
+
+
+/* Does the parser need to see an EOF to find the end of the message? */
+int
+http_message_needs_eof (const http_parser *parser)
+{
+  if (parser->type == HTTP_REQUEST) {
+    return 0;
+  }
+
+  /* See RFC 2616 section 4.4 */
+  if (parser->status_code / 100 == 1 || /* 1xx e.g. Continue */
+      parser->status_code == 204 ||     /* No Content */
+      parser->status_code == 304 ||     /* Not Modified */
+      parser->flags & F_SKIPBODY) {     /* response to a HEAD request */
+    return 0;
+  }
+
+  if ((parser->flags & F_CHUNKED) || parser->content_length != ULLONG_MAX) {
+    return 0;
+  }
+
+  return 1;
+}
+
+
+int
+http_should_keep_alive (const http_parser *parser)
+{
+  if (parser->http_major > 0 && parser->http_minor > 0) {
+    /* HTTP/1.1 */
+    if (parser->flags & F_CONNECTION_CLOSE) {
+      return 0;
+    }
+  } else {
+    /* HTTP/1.0 or earlier */
+    if (!(parser->flags & F_CONNECTION_KEEP_ALIVE)) {
+      return 0;
+    }
+  }
+
+  return !http_message_needs_eof(parser);
+}
+
+
+const char *
+http_method_str (enum http_method m)
+{
+  return ELEM_AT(method_strings, m, "<unknown>");
+}
+
+const char *
+http_status_str (enum http_status s)
+{
+  switch (s) {
+#define XX(num, name, string) case HTTP_STATUS_##name: return #string;
+    HTTP_STATUS_MAP(XX)
+#undef XX
+    default: return "<unknown>";
+  }
+}
+
+void
+http_parser_init (http_parser *parser, enum http_parser_type t)
+{
+  void *data = parser->data; /* preserve application data */
+  memset(parser, 0, sizeof(*parser));
+  parser->data = data;
+  parser->type = t;
+  parser->state = (t == HTTP_REQUEST ? s_start_req : (t == HTTP_RESPONSE ? s_start_res : s_start_req_or_res));
+  parser->http_errno = HPE_OK;
+}
+
+void
+http_parser_settings_init(http_parser_settings *settings)
+{
+  memset(settings, 0, sizeof(*settings));
+}
+
+const char *
+http_errno_name(enum http_errno err) {
+  assert(((size_t) err) < ARRAY_SIZE(http_strerror_tab));
+  return http_strerror_tab[err].name;
+}
+
+const char *
+http_errno_description(enum http_errno err) {
+  assert(((size_t) err) < ARRAY_SIZE(http_strerror_tab));
+  return http_strerror_tab[err].description;
+}
+
+static enum http_host_state
+http_parse_host_char(enum http_host_state s, const char ch) {
+  switch(s) {
+    case s_http_userinfo:
+    case s_http_userinfo_start:
+      if (ch == '@') {
+        return s_http_host_start;
+      }
+
+      if (IS_USERINFO_CHAR(ch)) {
+        return s_http_userinfo;
+      }
+      break;
+
+    case s_http_host_start:
+      if (ch == '[') {
+        return s_http_host_v6_start;
+      }
+
+      if (IS_HOST_CHAR(ch)) {
+        return s_http_host;
+      }
+
+      break;
+
+    case s_http_host:
+      if (IS_HOST_CHAR(ch)) {
+        return s_http_host;
+      }
+
+    /* fall through */
+    case s_http_host_v6_end:
+      if (ch == ':') {
+        return s_http_host_port_start;
+      }
+
+      break;
+
+    case s_http_host_v6:
+      if (ch == ']') {
+        return s_http_host_v6_end;
+      }
+
+    /* fall through */
+    case s_http_host_v6_start:
+      if (IS_HEX(ch) || ch == ':' || ch == '.') {
+        return s_http_host_v6;
+      }
+
+      if (s == s_http_host_v6 && ch == '%') {
+        return s_http_host_v6_zone_start;
+      }
+      break;
+
+    case s_http_host_v6_zone:
+      if (ch == ']') {
+        return s_http_host_v6_end;
+      }
+
+    /* fall through */
+    case s_http_host_v6_zone_start:
+      /* RFC 6874 Zone ID consists of 1*( unreserved / pct-encoded) */
+      if (IS_ALPHANUM(ch) || ch == '%' || ch == '.' || ch == '-' || ch == '_' ||
+          ch == '~') {
+        return s_http_host_v6_zone;
+      }
+      break;
+
+    case s_http_host_port:
+    case s_http_host_port_start:
+      if (IS_NUM(ch)) {
+        return s_http_host_port;
+      }
+
+      break;
+
+    default:
+      break;
+  }
+  return s_http_host_dead;
+}
+
+static int
+http_parse_host(const char * buf, struct http_parser_url *u, int found_at) {
+  enum http_host_state s;
+
+  const char *p;
+  size_t buflen = u->field_data[UF_HOST].off + u->field_data[UF_HOST].len;
+
+  assert(u->field_set & (1 << UF_HOST));
+
+  u->field_data[UF_HOST].len = 0;
+
+  s = found_at ? s_http_userinfo_start : s_http_host_start;
+
+  for (p = buf + u->field_data[UF_HOST].off; p < buf + buflen; p++) {
+    enum http_host_state new_s = http_parse_host_char(s, *p);
+
+    if (new_s == s_http_host_dead) {
+      return 1;
+    }
+
+    switch(new_s) {
+      case s_http_host:
+        if (s != s_http_host) {
+          u->field_data[UF_HOST].off = p - buf;
+        }
+        u->field_data[UF_HOST].len++;
+        break;
+
+      case s_http_host_v6:
+        if (s != s_http_host_v6) {
+          u->field_data[UF_HOST].off = p - buf;
+        }
+        u->field_data[UF_HOST].len++;
+        break;
+
+      case s_http_host_v6_zone_start:
+      case s_http_host_v6_zone:
+        u->field_data[UF_HOST].len++;
+        break;
+
+      case s_http_host_port:
+        if (s != s_http_host_port) {
+          u->field_data[UF_PORT].off = p - buf;
+          u->field_data[UF_PORT].len = 0;
+          u->field_set |= (1 << UF_PORT);
+        }
+        u->field_data[UF_PORT].len++;
+        break;
+
+      case s_http_userinfo:
+        if (s != s_http_userinfo) {
+          u->field_data[UF_USERINFO].off = p - buf ;
+          u->field_data[UF_USERINFO].len = 0;
+          u->field_set |= (1 << UF_USERINFO);
+        }
+        u->field_data[UF_USERINFO].len++;
+        break;
+
+      default:
+        break;
+    }
+    s = new_s;
+  }
+
+  /* Make sure we don't end somewhere unexpected */
+  switch (s) {
+    case s_http_host_start:
+    case s_http_host_v6_start:
+    case s_http_host_v6:
+    case s_http_host_v6_zone_start:
+    case s_http_host_v6_zone:
+    case s_http_host_port_start:
+    case s_http_userinfo:
+    case s_http_userinfo_start:
+      return 1;
+    default:
+      break;
+  }
+
+  return 0;
+}
+
+void
+http_parser_url_init(struct http_parser_url *u) {
+  memset(u, 0, sizeof(*u));
+}
+
+int
+http_parser_parse_url(const char *buf, size_t buflen, int is_connect,
+                      struct http_parser_url *u)
+{
+  enum state s;
+  const char *p;
+  enum http_parser_url_fields uf, old_uf;
+  int found_at = 0;
+
+  if (buflen == 0) {
+    return 1;
+  }
+
+  u->port = u->field_set = 0;
+  s = is_connect ? s_req_server_start : s_req_spaces_before_url;
+  old_uf = UF_MAX;
+
+  for (p = buf; p < buf + buflen; p++) {
+    s = parse_url_char(s, *p);
+
+    /* Figure out the next field that we're operating on */
+    switch (s) {
+      case s_dead:
+        return 1;
+
+      /* Skip delimeters */
+      case s_req_schema_slash:
+      case s_req_schema_slash_slash:
+      case s_req_server_start:
+      case s_req_query_string_start:
+      case s_req_fragment_start:
+        continue;
+
+      case s_req_schema:
+        uf = UF_SCHEMA;
+        break;
+
+      case s_req_server_with_at:
+        found_at = 1;
+
+      /* fall through */
+      case s_req_server:
+        uf = UF_HOST;
+        break;
+
+      case s_req_path:
+        uf = UF_PATH;
+        break;
+
+      case s_req_query_string:
+        uf = UF_QUERY;
+        break;
+
+      case s_req_fragment:
+        uf = UF_FRAGMENT;
+        break;
+
+      default:
+        assert(!"Unexpected state");
+        return 1;
+    }
+
+    /* Nothing's changed; soldier on */
+    if (uf == old_uf) {
+      u->field_data[uf].len++;
+      continue;
+    }
+
+    u->field_data[uf].off = p - buf;
+    u->field_data[uf].len = 1;
+
+    u->field_set |= (1 << uf);
+    old_uf = uf;
+  }
+
+  /* host must be present if there is a schema */
+  /* parsing http:///toto will fail */
+  if ((u->field_set & (1 << UF_SCHEMA)) &&
+      (u->field_set & (1 << UF_HOST)) == 0) {
+    return 1;
+  }
+
+  if (u->field_set & (1 << UF_HOST)) {
+    if (http_parse_host(buf, u, found_at) != 0) {
+      return 1;
+    }
+  }
+
+  /* CONNECT requests can only contain "hostname:port" */
+  if (is_connect && u->field_set != ((1 << UF_HOST)|(1 << UF_PORT))) {
+    return 1;
+  }
+
+  if (u->field_set & (1 << UF_PORT)) {
+    uint16_t off;
+    uint16_t len;
+    const char* p;
+    const char* end;
+    unsigned long v;
+
+    off = u->field_data[UF_PORT].off;
+    len = u->field_data[UF_PORT].len;
+    end = buf + off + len;
+
+    /* NOTE: The characters are already validated and are in the [0-9] range */
+    assert(off + len <= buflen && "Port number overflow");
+    v = 0;
+    for (p = buf + off; p < end; p++) {
+      v *= 10;
+      v += *p - '0';
+
+      /* Ports have a max value of 2^16 */
+      if (v > 0xffff) {
+        return 1;
+      }
+    }
+
+    u->port = (uint16_t) v;
+  }
+
+  return 0;
+}
+
+void
+http_parser_pause(http_parser *parser, int paused) {
+  /* Users should only be pausing/unpausing a parser that is not in an error
+   * state. In non-debug builds, there's not much that we can do about this
+   * other than ignore it.
+   */
+  if (HTTP_PARSER_ERRNO(parser) == HPE_OK ||
+      HTTP_PARSER_ERRNO(parser) == HPE_PAUSED) {
+    uint32_t nread = parser->nread; /* used by the SET_ERRNO macro */
+    SET_ERRNO((paused) ? HPE_PAUSED : HPE_OK);
+  } else {
+    assert(0 && "Attempting to pause parser in error state");
+  }
+}
+
+int
+http_body_is_final(const struct http_parser *parser) {
+    return parser->state == s_message_done;
+}
+
+unsigned long
+http_parser_version(void) {
+  return HTTP_PARSER_VERSION_MAJOR * 0x10000 |
+         HTTP_PARSER_VERSION_MINOR * 0x00100 |
+         HTTP_PARSER_VERSION_PATCH * 0x00001;
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/jni/WPINetJNI.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/jni/WPINetJNI.cpp
new file mode 100644
index 0000000..1528001
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/jni/WPINetJNI.cpp
@@ -0,0 +1,335 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <jni.h>
+
+#include <wpi/jni_util.h>
+
+#include "../MulticastHandleManager.h"
+#include "edu_wpi_first_net_WPINetJNI.h"
+#include "wpinet/MulticastServiceAnnouncer.h"
+#include "wpinet/MulticastServiceResolver.h"
+#include "wpinet/PortForwarder.h"
+
+using namespace wpi::java;
+
+static JClass serviceDataCls;
+static JGlobal<jobjectArray> serviceDataEmptyArray;
+
+extern "C" {
+
+JNIEXPORT jint JNICALL JNI_OnLoad(JavaVM* vm, void* reserved) {
+  JNIEnv* env;
+  if (vm->GetEnv(reinterpret_cast<void**>(&env), JNI_VERSION_1_6) != JNI_OK) {
+    return JNI_ERR;
+  }
+
+  serviceDataCls = JClass{env, "edu/wpi/first/net/ServiceData"};
+  if (!serviceDataCls) {
+    return JNI_ERR;
+  }
+
+  serviceDataEmptyArray = JGlobal<jobjectArray>{
+      env, env->NewObjectArray(0, serviceDataCls, nullptr)};
+  if (serviceDataEmptyArray == nullptr) {
+    return JNI_ERR;
+  }
+
+  return JNI_VERSION_1_6;
+}
+
+JNIEXPORT void JNICALL JNI_OnUnload(JavaVM* vm, void* reserved) {
+  JNIEnv* env;
+  if (vm->GetEnv(reinterpret_cast<void**>(&env), JNI_VERSION_1_6) != JNI_OK) {
+    return;
+  }
+
+  serviceDataEmptyArray.free(env);
+  serviceDataCls.free(env);
+}
+
+/*
+ * Class:     edu_wpi_first_net_WPINetJNI
+ * Method:    addPortForwarder
+ * Signature: (ILjava/lang/String;I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_net_WPINetJNI_addPortForwarder
+  (JNIEnv* env, jclass, jint port, jstring remoteHost, jint remotePort)
+{
+  wpi::PortForwarder::GetInstance().Add(static_cast<unsigned int>(port),
+                                        JStringRef{env, remoteHost}.str(),
+                                        static_cast<unsigned int>(remotePort));
+}
+
+/*
+ * Class:     edu_wpi_first_net_WPINetJNI
+ * Method:    removePortForwarder
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_net_WPINetJNI_removePortForwarder
+  (JNIEnv* env, jclass, jint port)
+{
+  wpi::PortForwarder::GetInstance().Remove(port);
+}
+
+/*
+ * Class:     edu_wpi_first_net_WPINetJNI
+ * Method:    createMulticastServiceAnnouncer
+ * Signature: (Ljava/lang/String;Ljava/lang/String;I[Ljava/lang/Object;[Ljava/lang/Object;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_net_WPINetJNI_createMulticastServiceAnnouncer
+  (JNIEnv* env, jclass, jstring serviceName, jstring serviceType, jint port,
+   jobjectArray keys, jobjectArray values)
+{
+  auto& manager = wpi::GetMulticastManager();
+  std::scoped_lock lock{manager.mutex};
+
+  JStringRef serviceNameRef{env, serviceName};
+  JStringRef serviceTypeRef{env, serviceType};
+
+  wpi::SmallVector<std::pair<std::string, std::string>, 8> txtVec;
+
+  if (keys != nullptr && values != nullptr) {
+    size_t keysLen = env->GetArrayLength(keys);
+
+    txtVec.reserve(keysLen);
+    for (size_t i = 0; i < keysLen; i++) {
+      JLocal<jstring> key{
+          env, static_cast<jstring>(env->GetObjectArrayElement(keys, i))};
+      JLocal<jstring> value{
+          env, static_cast<jstring>(env->GetObjectArrayElement(values, i))};
+
+      txtVec.emplace_back(std::pair<std::string, std::string>{
+          JStringRef{env, key}.str(), JStringRef{env, value}.str()});
+    }
+  }
+
+  auto announcer = std::make_unique<wpi::MulticastServiceAnnouncer>(
+      serviceNameRef.str(), serviceTypeRef.str(), port, txtVec);
+
+  size_t index = manager.handleIds.emplace_back(1);
+
+  manager.announcers[index] = std::move(announcer);
+
+  return static_cast<jint>(index);
+}
+
+/*
+ * Class:     edu_wpi_first_net_WPINetJNI
+ * Method:    freeMulticastServiceAnnouncer
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_net_WPINetJNI_freeMulticastServiceAnnouncer
+  (JNIEnv* env, jclass, jint handle)
+{
+  auto& manager = wpi::GetMulticastManager();
+  std::scoped_lock lock{manager.mutex};
+  manager.announcers[handle] = nullptr;
+  manager.handleIds.erase(handle);
+}
+
+/*
+ * Class:     edu_wpi_first_net_WPINetJNI
+ * Method:    startMulticastServiceAnnouncer
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_net_WPINetJNI_startMulticastServiceAnnouncer
+  (JNIEnv* env, jclass, jint handle)
+{
+  auto& manager = wpi::GetMulticastManager();
+  std::scoped_lock lock{manager.mutex};
+  auto& announcer = manager.announcers[handle];
+  announcer->Start();
+}
+
+/*
+ * Class:     edu_wpi_first_net_WPINetJNI
+ * Method:    stopMulticastServiceAnnouncer
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_net_WPINetJNI_stopMulticastServiceAnnouncer
+  (JNIEnv* env, jclass, jint handle)
+{
+  auto& manager = wpi::GetMulticastManager();
+  std::scoped_lock lock{manager.mutex};
+  auto& announcer = manager.announcers[handle];
+  announcer->Stop();
+}
+
+/*
+ * Class:     edu_wpi_first_net_WPINetJNI
+ * Method:    getMulticastServiceAnnouncerHasImplementation
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_net_WPINetJNI_getMulticastServiceAnnouncerHasImplementation
+  (JNIEnv* env, jclass, jint handle)
+{
+  auto& manager = wpi::GetMulticastManager();
+  std::scoped_lock lock{manager.mutex};
+  auto& announcer = manager.announcers[handle];
+  return announcer->HasImplementation();
+}
+
+/*
+ * Class:     edu_wpi_first_net_WPINetJNI
+ * Method:    createMulticastServiceResolver
+ * Signature: (Ljava/lang/String;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_net_WPINetJNI_createMulticastServiceResolver
+  (JNIEnv* env, jclass, jstring serviceType)
+{
+  auto& manager = wpi::GetMulticastManager();
+  std::scoped_lock lock{manager.mutex};
+  JStringRef serviceTypeRef{env, serviceType};
+
+  auto resolver =
+      std::make_unique<wpi::MulticastServiceResolver>(serviceTypeRef.str());
+
+  size_t index = manager.handleIds.emplace_back(2);
+
+  manager.resolvers[index] = std::move(resolver);
+
+  return static_cast<jint>(index);
+}
+
+/*
+ * Class:     edu_wpi_first_net_WPINetJNI
+ * Method:    freeMulticastServiceResolver
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_net_WPINetJNI_freeMulticastServiceResolver
+  (JNIEnv* env, jclass, jint handle)
+{
+  auto& manager = wpi::GetMulticastManager();
+  std::scoped_lock lock{manager.mutex};
+  manager.resolvers[handle] = nullptr;
+  manager.handleIds.erase(handle);
+}
+
+/*
+ * Class:     edu_wpi_first_net_WPINetJNI
+ * Method:    startMulticastServiceResolver
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_net_WPINetJNI_startMulticastServiceResolver
+  (JNIEnv* env, jclass, jint handle)
+{
+  auto& manager = wpi::GetMulticastManager();
+  std::scoped_lock lock{manager.mutex};
+  auto& resolver = manager.resolvers[handle];
+  resolver->Start();
+}
+
+/*
+ * Class:     edu_wpi_first_net_WPINetJNI
+ * Method:    stopMulticastServiceResolver
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_net_WPINetJNI_stopMulticastServiceResolver
+  (JNIEnv* env, jclass, jint handle)
+{
+  auto& manager = wpi::GetMulticastManager();
+  std::scoped_lock lock{manager.mutex};
+  auto& resolver = manager.resolvers[handle];
+  resolver->Stop();
+}
+
+/*
+ * Class:     edu_wpi_first_net_WPINetJNI
+ * Method:    getMulticastServiceResolverHasImplementation
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_net_WPINetJNI_getMulticastServiceResolverHasImplementation
+  (JNIEnv* env, jclass, jint handle)
+{
+  auto& manager = wpi::GetMulticastManager();
+  std::scoped_lock lock{manager.mutex};
+  auto& resolver = manager.resolvers[handle];
+  return resolver->HasImplementation();
+}
+
+/*
+ * Class:     edu_wpi_first_net_WPINetJNI
+ * Method:    getMulticastServiceResolverEventHandle
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_net_WPINetJNI_getMulticastServiceResolverEventHandle
+  (JNIEnv* env, jclass, jint handle)
+{
+  auto& manager = wpi::GetMulticastManager();
+  std::scoped_lock lock{manager.mutex};
+  auto& resolver = manager.resolvers[handle];
+  return resolver->GetEventHandle();
+}
+
+/*
+ * Class:     edu_wpi_first_net_WPINetJNI
+ * Method:    getMulticastServiceResolverData
+ * Signature: (I)[Ljava/lang/Object;
+ */
+JNIEXPORT jobjectArray JNICALL
+Java_edu_wpi_first_net_WPINetJNI_getMulticastServiceResolverData
+  (JNIEnv* env, jclass, jint handle)
+{
+  static jmethodID constructor =
+      env->GetMethodID(serviceDataCls, "<init>",
+                       "(JILjava/lang/String;Ljava/lang/String;[Ljava/lang/"
+                       "String;[Ljava/lang/String;)V");
+  auto& manager = wpi::GetMulticastManager();
+  std::vector<wpi::MulticastServiceResolver::ServiceData> allData;
+  {
+    std::scoped_lock lock{manager.mutex};
+    auto& resolver = manager.resolvers[handle];
+    allData = resolver->GetData();
+  }
+  if (allData.empty()) {
+    return serviceDataEmptyArray;
+  }
+
+  JLocal<jobjectArray> returnData{
+      env, env->NewObjectArray(allData.size(), serviceDataCls, nullptr)};
+
+  for (auto&& data : allData) {
+    JLocal<jstring> serviceName{env, MakeJString(env, data.serviceName)};
+    JLocal<jstring> hostName{env, MakeJString(env, data.hostName)};
+
+    wpi::SmallVector<std::string_view, 8> keysRef;
+    wpi::SmallVector<std::string_view, 8> valuesRef;
+
+    size_t index = 0;
+    for (auto&& txt : data.txt) {
+      keysRef.emplace_back(txt.first);
+      valuesRef.emplace_back(txt.second);
+    }
+
+    JLocal<jobjectArray> keys{env, MakeJStringArray(env, keysRef)};
+    JLocal<jobjectArray> values{env, MakeJStringArray(env, valuesRef)};
+
+    JLocal<jobject> dataItem{
+        env, env->NewObject(serviceDataCls, constructor,
+                            static_cast<jlong>(data.ipv4Address),
+                            static_cast<jint>(data.port), serviceName.obj(),
+                            hostName.obj(), keys.obj(), values.obj())};
+
+    env->SetObjectArrayElement(returnData, index, dataItem);
+    index++;
+  }
+
+  return returnData;
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/raw_socket_istream.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/raw_socket_istream.cpp
new file mode 100644
index 0000000..b57d83d
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/raw_socket_istream.cpp
@@ -0,0 +1,33 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/raw_socket_istream.h"
+
+#include "wpinet/NetworkStream.h"
+
+using namespace wpi;
+
+void raw_socket_istream::read_impl(void* data, size_t len) {
+  char* cdata = static_cast<char*>(data);
+  size_t pos = 0;
+
+  while (pos < len) {
+    NetworkStream::Error err;
+    size_t count = m_stream.receive(&cdata[pos], len - pos, &err, m_timeout);
+    if (count == 0) {
+      error_detected();
+      break;
+    }
+    pos += count;
+  }
+  set_read_count(pos);
+}
+
+void raw_socket_istream::close() {
+  m_stream.close();
+}
+
+size_t raw_socket_istream::in_avail() const {
+  return 0;
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/raw_socket_ostream.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/raw_socket_ostream.cpp
new file mode 100644
index 0000000..5eb0b2b
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/raw_socket_ostream.cpp
@@ -0,0 +1,42 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/raw_socket_ostream.h"
+
+#include "wpinet/NetworkStream.h"
+
+using namespace wpi;
+
+raw_socket_ostream::~raw_socket_ostream() {
+  flush();
+  if (m_shouldClose) {
+    close();
+  }
+}
+
+void raw_socket_ostream::write_impl(const char* data, size_t len) {
+  size_t pos = 0;
+
+  while (pos < len) {
+    NetworkStream::Error err;
+    size_t count = m_stream.send(&data[pos], len - pos, &err);
+    if (count == 0) {
+      error_detected();
+      return;
+    }
+    pos += count;
+  }
+}
+
+uint64_t raw_socket_ostream::current_pos() const {
+  return 0;
+}
+
+void raw_socket_ostream::close() {
+  if (!m_shouldClose) {
+    return;
+  }
+  flush();
+  m_stream.close();
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/raw_uv_ostream.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/raw_uv_ostream.cpp
new file mode 100644
index 0000000..fdbd1b0
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/raw_uv_ostream.cpp
@@ -0,0 +1,39 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/raw_uv_ostream.h"
+
+#include <cstring>
+
+using namespace wpi;
+
+void raw_uv_ostream::write_impl(const char* data, size_t len) {
+  while (len > 0) {
+    // allocate additional buffers as required
+    if (m_left == 0) {
+      m_bufs.emplace_back(m_alloc());
+      // we want bufs() to always be valid, so set len=0 and keep track of the
+      // amount of space remaining separately
+      m_left = m_bufs.back().len;
+      m_bufs.back().len = 0;
+      assert(m_left != 0);
+    }
+
+    size_t amt = (std::min)(m_left, len);
+    auto& buf = m_bufs.back();
+    std::memcpy(buf.base + buf.len, data, amt);
+    data += amt;
+    len -= amt;
+    buf.len += amt;
+    m_left -= amt;
+  }
+}
+
+uint64_t raw_uv_ostream::current_pos() const {
+  uint64_t size = 0;
+  for (auto&& buf : m_bufs) {
+    size += buf.len;
+  }
+  return size;
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Async.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Async.cpp
new file mode 100644
index 0000000..f84bb9b
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Async.cpp
@@ -0,0 +1,33 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/uv/Async.h"
+
+#include "wpinet/uv/Loop.h"
+
+namespace wpi::uv {
+
+Async<>::~Async() noexcept {
+  if (auto loop = m_loop.lock()) {
+    Close();
+  } else {
+    ForceClosed();
+  }
+}
+
+std::shared_ptr<Async<>> Async<>::Create(const std::shared_ptr<Loop>& loop) {
+  auto h = std::make_shared<Async>(loop, private_init{});
+  int err = uv_async_init(loop->GetRaw(), h->GetRaw(), [](uv_async_t* handle) {
+    Async& h = *static_cast<Async*>(handle->data);
+    h.wakeup();
+  });
+  if (err < 0) {
+    loop->ReportError(err);
+    return nullptr;
+  }
+  h->Keep();
+  return h;
+}
+
+}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Check.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Check.cpp
new file mode 100644
index 0000000..13c2229
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Check.cpp
@@ -0,0 +1,29 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/uv/Check.h"
+
+#include "wpinet/uv/Loop.h"
+
+namespace wpi::uv {
+
+std::shared_ptr<Check> Check::Create(Loop& loop) {
+  auto h = std::make_shared<Check>(private_init{});
+  int err = uv_check_init(loop.GetRaw(), h->GetRaw());
+  if (err < 0) {
+    loop.ReportError(err);
+    return nullptr;
+  }
+  h->Keep();
+  return h;
+}
+
+void Check::Start() {
+  Invoke(&uv_check_start, GetRaw(), [](uv_check_t* handle) {
+    Check& h = *static_cast<Check*>(handle->data);
+    h.check();
+  });
+}
+
+}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/uv/FsEvent.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/FsEvent.cpp
new file mode 100644
index 0000000..044390e
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/FsEvent.cpp
@@ -0,0 +1,64 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/uv/FsEvent.h"
+
+#include <cstdlib>
+
+#include <wpi/SmallString.h>
+
+#include "wpinet/uv/Loop.h"
+
+namespace wpi::uv {
+
+std::shared_ptr<FsEvent> FsEvent::Create(Loop& loop) {
+  auto h = std::make_shared<FsEvent>(private_init{});
+  int err = uv_fs_event_init(loop.GetRaw(), h->GetRaw());
+  if (err < 0) {
+    loop.ReportError(err);
+    return nullptr;
+  }
+  h->Keep();
+  return h;
+}
+
+void FsEvent::Start(std::string_view path, unsigned int flags) {
+  SmallString<128> pathBuf{path};
+  Invoke(
+      &uv_fs_event_start, GetRaw(),
+      [](uv_fs_event_t* handle, const char* filename, int events, int status) {
+        FsEvent& h = *static_cast<FsEvent*>(handle->data);
+        if (status < 0) {
+          h.ReportError(status);
+        } else {
+          h.fsEvent(filename, events);
+        }
+      },
+      pathBuf.c_str(), flags);
+}
+
+std::string FsEvent::GetPath() {
+  // Per the libuv docs, GetPath() always gives us a null-terminated string.
+  // common case should be small
+  char buf[128];
+  size_t size = 128;
+  int r = uv_fs_event_getpath(GetRaw(), buf, &size);
+  if (r == 0) {
+    return buf;
+  } else if (r == UV_ENOBUFS) {
+    // need to allocate a big enough buffer
+    char* buf2 = static_cast<char*>(std::malloc(size));
+    r = uv_fs_event_getpath(GetRaw(), buf2, &size);
+    if (r == 0) {
+      std::string out{buf2};
+      std::free(buf2);
+      return out;
+    }
+    std::free(buf2);
+  }
+  ReportError(r);
+  return std::string{};
+}
+
+}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/uv/GetAddrInfo.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/GetAddrInfo.cpp
new file mode 100644
index 0000000..14721f2
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/GetAddrInfo.cpp
@@ -0,0 +1,52 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/uv/GetAddrInfo.h"
+
+#include <wpi/SmallString.h>
+
+#include "wpinet/uv/Loop.h"
+#include "wpinet/uv/util.h"
+
+namespace wpi::uv {
+
+GetAddrInfoReq::GetAddrInfoReq() {
+  error = [this](Error err) { GetLoop().error(err); };
+}
+
+void GetAddrInfo(Loop& loop, const std::shared_ptr<GetAddrInfoReq>& req,
+                 std::string_view node, std::string_view service,
+                 const addrinfo* hints) {
+  SmallString<128> nodeStr{node};
+  SmallString<128> serviceStr{service};
+  int err = uv_getaddrinfo(
+      loop.GetRaw(), req->GetRaw(),
+      [](uv_getaddrinfo_t* req, int status, addrinfo* res) {
+        auto& h = *static_cast<GetAddrInfoReq*>(req->data);
+        if (status < 0) {
+          h.ReportError(status);
+        } else {
+          h.resolved(*res);
+        }
+        uv_freeaddrinfo(res);
+        h.Release();  // this is always a one-shot
+      },
+      node.empty() ? nullptr : nodeStr.c_str(),
+      service.empty() ? nullptr : serviceStr.c_str(), hints);
+  if (err < 0) {
+    loop.ReportError(err);
+  } else {
+    req->Keep();
+  }
+}
+
+void GetAddrInfo(Loop& loop, std::function<void(const addrinfo&)> callback,
+                 std::string_view node, std::string_view service,
+                 const addrinfo* hints) {
+  auto req = std::make_shared<GetAddrInfoReq>();
+  req->resolved.connect(std::move(callback));
+  GetAddrInfo(loop, req, node, service, hints);
+}
+
+}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/uv/GetNameInfo.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/GetNameInfo.cpp
new file mode 100644
index 0000000..a6ad36d
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/GetNameInfo.cpp
@@ -0,0 +1,94 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/uv/GetNameInfo.h"
+
+#include "wpinet/uv/Loop.h"
+#include "wpinet/uv/util.h"
+
+namespace wpi::uv {
+
+GetNameInfoReq::GetNameInfoReq() {
+  error = [this](Error err) { GetLoop().error(err); };
+}
+
+void GetNameInfo(Loop& loop, const std::shared_ptr<GetNameInfoReq>& req,
+                 const sockaddr& addr, int flags) {
+  int err = uv_getnameinfo(
+      loop.GetRaw(), req->GetRaw(),
+      [](uv_getnameinfo_t* req, int status, const char* hostname,
+         const char* service) {
+        auto& h = *static_cast<GetNameInfoReq*>(req->data);
+        if (status < 0) {
+          h.ReportError(status);
+        } else {
+          h.resolved(hostname, service);
+        }
+        h.Release();  // this is always a one-shot
+      },
+      &addr, flags);
+  if (err < 0) {
+    loop.ReportError(err);
+  } else {
+    req->Keep();
+  }
+}
+
+void GetNameInfo(Loop& loop,
+                 std::function<void(const char*, const char*)> callback,
+                 const sockaddr& addr, int flags) {
+  auto req = std::make_shared<GetNameInfoReq>();
+  req->resolved.connect(std::move(callback));
+  GetNameInfo(loop, req, addr, flags);
+}
+
+void GetNameInfo4(Loop& loop, const std::shared_ptr<GetNameInfoReq>& req,
+                  std::string_view ip, unsigned int port, int flags) {
+  sockaddr_in addr;
+  int err = NameToAddr(ip, port, &addr);
+  if (err < 0) {
+    loop.ReportError(err);
+  } else {
+    GetNameInfo(loop, req, reinterpret_cast<const sockaddr&>(addr), flags);
+  }
+}
+
+void GetNameInfo4(Loop& loop,
+                  std::function<void(const char*, const char*)> callback,
+                  std::string_view ip, unsigned int port, int flags) {
+  sockaddr_in addr;
+  int err = NameToAddr(ip, port, &addr);
+  if (err < 0) {
+    loop.ReportError(err);
+  } else {
+    GetNameInfo(loop, std::move(callback),
+                reinterpret_cast<const sockaddr&>(addr), flags);
+  }
+}
+
+void GetNameInfo6(Loop& loop, const std::shared_ptr<GetNameInfoReq>& req,
+                  std::string_view ip, unsigned int port, int flags) {
+  sockaddr_in6 addr;
+  int err = NameToAddr(ip, port, &addr);
+  if (err < 0) {
+    loop.ReportError(err);
+  } else {
+    GetNameInfo(loop, req, reinterpret_cast<const sockaddr&>(addr), flags);
+  }
+}
+
+void GetNameInfo6(Loop& loop,
+                  std::function<void(const char*, const char*)> callback,
+                  std::string_view ip, unsigned int port, int flags) {
+  sockaddr_in6 addr;
+  int err = NameToAddr(ip, port, &addr);
+  if (err < 0) {
+    loop.ReportError(err);
+  } else {
+    GetNameInfo(loop, std::move(callback),
+                reinterpret_cast<const sockaddr&>(addr), flags);
+  }
+}
+
+}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Handle.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Handle.cpp
new file mode 100644
index 0000000..04af133
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Handle.cpp
@@ -0,0 +1,35 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/uv/Handle.h"
+
+using namespace wpi::uv;
+
+Handle::~Handle() noexcept {
+  if (!m_closed && m_uv_handle->type != UV_UNKNOWN_HANDLE) {
+    uv_close(m_uv_handle, [](uv_handle_t* uv_handle) { std::free(uv_handle); });
+  } else {
+    std::free(m_uv_handle);
+  }
+}
+
+void Handle::Close() noexcept {
+  if (!IsClosing()) {
+    uv_close(m_uv_handle, [](uv_handle_t* handle) {
+      Handle& h = *static_cast<Handle*>(handle->data);
+      h.closed();
+      h.Release();  // free ourselves
+    });
+    m_closed = true;
+  }
+}
+
+void Handle::AllocBuf(uv_handle_t* handle, size_t size, uv_buf_t* buf) {
+  auto& h = *static_cast<Handle*>(handle->data);
+  *buf = h.m_allocBuf(size);
+}
+
+void Handle::DefaultFreeBuf(Buffer& buf) {
+  buf.Deallocate();
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Idle.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Idle.cpp
new file mode 100644
index 0000000..452bc7e
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Idle.cpp
@@ -0,0 +1,29 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/uv/Idle.h"
+
+#include "wpinet/uv/Loop.h"
+
+namespace wpi::uv {
+
+std::shared_ptr<Idle> Idle::Create(Loop& loop) {
+  auto h = std::make_shared<Idle>(private_init{});
+  int err = uv_idle_init(loop.GetRaw(), h->GetRaw());
+  if (err < 0) {
+    loop.ReportError(err);
+    return nullptr;
+  }
+  h->Keep();
+  return h;
+}
+
+void Idle::Start() {
+  Invoke(&uv_idle_start, GetRaw(), [](uv_idle_t* handle) {
+    Idle& h = *static_cast<Idle*>(handle->data);
+    h.idle();
+  });
+}
+
+}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Loop.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Loop.cpp
new file mode 100644
index 0000000..d48e230
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Loop.cpp
@@ -0,0 +1,70 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/uv/Loop.h"
+
+using namespace wpi::uv;
+
+Loop::Loop(const private_init&) noexcept {
+#ifndef _WIN32
+  // Ignore SIGPIPE (see https://github.com/joyent/libuv/issues/1254)
+  static bool once = []() {
+    signal(SIGPIPE, SIG_IGN);
+    return true;
+  }();
+  (void)once;
+#endif
+}
+
+Loop::~Loop() noexcept {
+  if (m_loop) {
+    m_loop->data = nullptr;
+    Close();
+  }
+}
+
+std::shared_ptr<Loop> Loop::Create() {
+  auto loop = std::make_shared<Loop>(private_init{});
+  if (uv_loop_init(&loop->m_loopStruct) < 0) {
+    return nullptr;
+  }
+  loop->m_loop = &loop->m_loopStruct;
+  loop->m_loop->data = loop.get();
+  return loop;
+}
+
+std::shared_ptr<Loop> Loop::GetDefault() {
+  static std::shared_ptr<Loop> loop = std::make_shared<Loop>(private_init{});
+  loop->m_loop = uv_default_loop();
+  if (!loop->m_loop) {
+    return nullptr;
+  }
+  loop->m_loop->data = loop.get();
+  return loop;
+}
+
+void Loop::Close() {
+  int err = uv_loop_close(m_loop);
+  if (err < 0) {
+    ReportError(err);
+  }
+}
+
+void Loop::Walk(function_ref<void(Handle&)> callback) {
+  uv_walk(
+      m_loop,
+      [](uv_handle_t* handle, void* func) {
+        auto& h = *static_cast<Handle*>(handle->data);
+        auto& f = *static_cast<function_ref<void(Handle&)>*>(func);
+        f(h);
+      },
+      &callback);
+}
+
+void Loop::Fork() {
+  int err = uv_loop_fork(m_loop);
+  if (err < 0) {
+    ReportError(err);
+  }
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/uv/NameToAddr.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/NameToAddr.cpp
new file mode 100644
index 0000000..2f3a003
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/NameToAddr.cpp
@@ -0,0 +1,59 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/uv/util.h"  // NOLINT(build/include_order)
+
+#include <cstring>
+
+#include <wpi/SmallString.h>
+
+namespace wpi::uv {
+
+int NameToAddr(std::string_view ip, unsigned int port, sockaddr_in* addr) {
+  if (ip.empty()) {
+    std::memset(addr, 0, sizeof(sockaddr_in));
+    addr->sin_family = PF_INET;
+    addr->sin_addr.s_addr = INADDR_ANY;
+    addr->sin_port = htons(port);
+    return 0;
+  } else {
+    SmallString<128> ipBuf{ip};
+    return uv_ip4_addr(ipBuf.c_str(), port, addr);
+  }
+}
+
+int NameToAddr(std::string_view ip, unsigned int port, sockaddr_in6* addr) {
+  if (ip.empty()) {
+    std::memset(addr, 0, sizeof(sockaddr_in6));
+    addr->sin6_family = PF_INET6;
+    addr->sin6_addr = in6addr_any;
+    addr->sin6_port = htons(port);
+    return 0;
+  } else {
+    SmallString<128> ipBuf{ip};
+    return uv_ip6_addr(ipBuf.c_str(), port, addr);
+  }
+}
+
+int NameToAddr(std::string_view ip, in_addr* addr) {
+  if (ip.empty()) {
+    addr->s_addr = INADDR_ANY;
+    return 0;
+  } else {
+    SmallString<128> ipBuf{ip};
+    return uv_inet_pton(AF_INET, ipBuf.c_str(), addr);
+  }
+}
+
+int NameToAddr(std::string_view ip, in6_addr* addr) {
+  if (ip.empty()) {
+    *addr = in6addr_any;
+    return 0;
+  } else {
+    SmallString<128> ipBuf{ip};
+    return uv_inet_pton(AF_INET6, ipBuf.c_str(), addr);
+  }
+}
+
+}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/uv/NetworkStream.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/NetworkStream.cpp
new file mode 100644
index 0000000..3538596
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/NetworkStream.cpp
@@ -0,0 +1,30 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/uv/NetworkStream.h"
+
+namespace wpi::uv {
+
+ConnectReq::ConnectReq() {
+  error = [this](Error err) { GetStream().error(err); };
+}
+
+void NetworkStream::Listen(int backlog) {
+  Invoke(&uv_listen, GetRawStream(), backlog,
+         [](uv_stream_t* handle, int status) {
+           auto& h = *static_cast<NetworkStream*>(handle->data);
+           if (status < 0) {
+             h.ReportError(status);
+           } else {
+             h.connection();
+           }
+         });
+}
+
+void NetworkStream::Listen(std::function<void()> callback, int backlog) {
+  connection.connect(std::move(callback));
+  Listen(backlog);
+}
+
+}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Pipe.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Pipe.cpp
new file mode 100644
index 0000000..9548874
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Pipe.cpp
@@ -0,0 +1,138 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/uv/Pipe.h"
+
+#include <cstdlib>
+
+#include <wpi/SmallString.h>
+
+namespace wpi::uv {
+
+std::shared_ptr<Pipe> Pipe::Create(Loop& loop, bool ipc) {
+  auto h = std::make_shared<Pipe>(private_init{});
+  int err = uv_pipe_init(loop.GetRaw(), h->GetRaw(), ipc ? 1 : 0);
+  if (err < 0) {
+    loop.ReportError(err);
+    return nullptr;
+  }
+  h->Keep();
+  return h;
+}
+
+void Pipe::Reuse(std::function<void()> callback, bool ipc) {
+  if (IsClosing()) {
+    return;
+  }
+  if (!m_reuseData) {
+    m_reuseData = std::make_unique<ReuseData>();
+  }
+  m_reuseData->callback = std::move(callback);
+  m_reuseData->ipc = ipc;
+  uv_close(GetRawHandle(), [](uv_handle_t* handle) {
+    Pipe& h = *static_cast<Pipe*>(handle->data);
+    if (!h.m_reuseData) {
+      return;
+    }
+    auto data = std::move(h.m_reuseData);
+    auto err =
+        uv_pipe_init(h.GetLoopRef().GetRaw(), h.GetRaw(), data->ipc ? 1 : 0);
+    if (err < 0) {
+      h.ReportError(err);
+      return;
+    }
+    data->callback();
+  });
+}
+
+std::shared_ptr<Pipe> Pipe::Accept() {
+  auto client = Create(GetLoopRef(), GetRaw()->ipc);
+  if (!client) {
+    return nullptr;
+  }
+  if (!Accept(client)) {
+    client->Release();
+    return nullptr;
+  }
+  return client;
+}
+
+Pipe* Pipe::DoAccept() {
+  return Accept().get();
+}
+
+void Pipe::Bind(std::string_view name) {
+  SmallString<128> nameBuf{name};
+  Invoke(&uv_pipe_bind, GetRaw(), nameBuf.c_str());
+}
+
+void Pipe::Connect(std::string_view name,
+                   const std::shared_ptr<PipeConnectReq>& req) {
+  SmallString<128> nameBuf{name};
+  uv_pipe_connect(req->GetRaw(), GetRaw(), nameBuf.c_str(),
+                  [](uv_connect_t* req, int status) {
+                    auto& h = *static_cast<PipeConnectReq*>(req->data);
+                    if (status < 0) {
+                      h.ReportError(status);
+                    } else {
+                      h.connected();
+                    }
+                    h.Release();  // this is always a one-shot
+                  });
+  req->Keep();
+}
+
+void Pipe::Connect(std::string_view name, std::function<void()> callback) {
+  auto req = std::make_shared<PipeConnectReq>();
+  req->connected.connect(std::move(callback));
+  Connect(name, req);
+}
+
+std::string Pipe::GetSock() {
+  // Per libuv docs, the returned buffer is NOT null terminated.
+  // common case should be small
+  char buf[128];
+  size_t size = 128;
+  int r = uv_pipe_getsockname(GetRaw(), buf, &size);
+  if (r == 0) {
+    return std::string{buf, size};
+  } else if (r == UV_ENOBUFS) {
+    // need to allocate a big enough buffer
+    char* buf2 = static_cast<char*>(std::malloc(size));
+    r = uv_pipe_getsockname(GetRaw(), buf2, &size);
+    if (r == 0) {
+      std::string out{buf2, size};
+      std::free(buf2);
+      return out;
+    }
+    std::free(buf2);
+  }
+  ReportError(r);
+  return std::string{};
+}
+
+std::string Pipe::GetPeer() {
+  // Per libuv docs, the returned buffer is NOT null terminated.
+  // common case should be small
+  char buf[128];
+  size_t size = 128;
+  int r = uv_pipe_getpeername(GetRaw(), buf, &size);
+  if (r == 0) {
+    return std::string{buf, size};
+  } else if (r == UV_ENOBUFS) {
+    // need to allocate a big enough buffer
+    char* buf2 = static_cast<char*>(std::malloc(size));
+    r = uv_pipe_getpeername(GetRaw(), buf2, &size);
+    if (r == 0) {
+      std::string out{buf2, size};
+      std::free(buf2);
+      return out;
+    }
+    std::free(buf2);
+  }
+  ReportError(r);
+  return std::string{};
+}
+
+}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Poll.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Poll.cpp
new file mode 100644
index 0000000..3713453
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Poll.cpp
@@ -0,0 +1,95 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/uv/Poll.h"
+
+#include "wpinet/uv/Loop.h"
+
+namespace wpi::uv {
+
+std::shared_ptr<Poll> Poll::Create(Loop& loop, int fd) {
+  auto h = std::make_shared<Poll>(private_init{});
+  int err = uv_poll_init(loop.GetRaw(), h->GetRaw(), fd);
+  if (err < 0) {
+    loop.ReportError(err);
+    return nullptr;
+  }
+  h->Keep();
+  return h;
+}
+
+std::shared_ptr<Poll> Poll::CreateSocket(Loop& loop, uv_os_sock_t sock) {
+  auto h = std::make_shared<Poll>(private_init{});
+  int err = uv_poll_init_socket(loop.GetRaw(), h->GetRaw(), sock);
+  if (err < 0) {
+    loop.ReportError(err);
+    return nullptr;
+  }
+  h->Keep();
+  return h;
+}
+
+void Poll::Reuse(int fd, std::function<void()> callback) {
+  if (IsClosing()) {
+    return;
+  }
+  if (!m_reuseData) {
+    m_reuseData = std::make_unique<ReuseData>();
+  }
+  m_reuseData->callback = std::move(callback);
+  m_reuseData->isSocket = false;
+  m_reuseData->fd = fd;
+  uv_close(GetRawHandle(), [](uv_handle_t* handle) {
+    Poll& h = *static_cast<Poll*>(handle->data);
+    if (!h.m_reuseData || h.m_reuseData->isSocket) {
+      return;  // just in case
+    }
+    auto data = std::move(h.m_reuseData);
+    int err = uv_poll_init(h.GetLoopRef().GetRaw(), h.GetRaw(), data->fd);
+    if (err < 0) {
+      h.ReportError(err);
+      return;
+    }
+    data->callback();
+  });
+}
+
+void Poll::ReuseSocket(uv_os_sock_t sock, std::function<void()> callback) {
+  if (IsClosing()) {
+    return;
+  }
+  if (!m_reuseData) {
+    m_reuseData = std::make_unique<ReuseData>();
+  }
+  m_reuseData->callback = std::move(callback);
+  m_reuseData->isSocket = true;
+  m_reuseData->sock = sock;
+  uv_close(GetRawHandle(), [](uv_handle_t* handle) {
+    Poll& h = *static_cast<Poll*>(handle->data);
+    if (!h.m_reuseData || !h.m_reuseData->isSocket) {
+      return;  // just in case
+    }
+    auto data = std::move(h.m_reuseData);
+    int err = uv_poll_init(h.GetLoopRef().GetRaw(), h.GetRaw(), data->sock);
+    if (err < 0) {
+      h.ReportError(err);
+      return;
+    }
+    data->callback();
+  });
+}
+
+void Poll::Start(int events) {
+  Invoke(&uv_poll_start, GetRaw(), events,
+         [](uv_poll_t* handle, int status, int events) {
+           Poll& h = *static_cast<Poll*>(handle->data);
+           if (status < 0) {
+             h.ReportError(status);
+           } else {
+             h.pollEvent(events);
+           }
+         });
+}
+
+}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Prepare.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Prepare.cpp
new file mode 100644
index 0000000..e4ca160
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Prepare.cpp
@@ -0,0 +1,29 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/uv/Prepare.h"
+
+#include "wpinet/uv/Loop.h"
+
+namespace wpi::uv {
+
+std::shared_ptr<Prepare> Prepare::Create(Loop& loop) {
+  auto h = std::make_shared<Prepare>(private_init{});
+  int err = uv_prepare_init(loop.GetRaw(), h->GetRaw());
+  if (err < 0) {
+    loop.ReportError(err);
+    return nullptr;
+  }
+  h->Keep();
+  return h;
+}
+
+void Prepare::Start() {
+  Invoke(&uv_prepare_start, GetRaw(), [](uv_prepare_t* handle) {
+    Prepare& h = *static_cast<Prepare*>(handle->data);
+    h.prepare();
+  });
+}
+
+}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Process.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Process.cpp
new file mode 100644
index 0000000..3c10db6
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Process.cpp
@@ -0,0 +1,134 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/uv/Process.h"
+
+#include <wpi/SmallString.h>
+
+#include "wpinet/uv/Loop.h"
+#include "wpinet/uv/Pipe.h"
+
+namespace wpi::uv {
+
+std::shared_ptr<Process> Process::SpawnArray(Loop& loop, std::string_view file,
+                                             std::span<const Option> options) {
+  // convert Option array to libuv structure
+  uv_process_options_t coptions;
+
+  coptions.exit_cb = [](uv_process_t* handle, int64_t status, int signal) {
+    auto& h = *static_cast<Process*>(handle->data);
+    h.exited(status, signal);
+  };
+
+  SmallString<128> fileBuf{file};
+  coptions.file = fileBuf.c_str();
+  coptions.cwd = nullptr;
+  coptions.flags = 0;
+  coptions.uid = 0;
+  coptions.gid = 0;
+
+  SmallVector<char*, 4> argsBuf;
+  SmallVector<char*, 4> envBuf;
+  struct StdioContainer : public uv_stdio_container_t {
+    StdioContainer() {
+      flags = UV_IGNORE;
+      data.fd = 0;
+    }
+  };
+  SmallVector<StdioContainer, 4> stdioBuf;
+
+  for (auto&& o : options) {
+    switch (o.m_type) {
+      case Option::kArg:
+        argsBuf.push_back(const_cast<char*>(o.m_data.str));
+        break;
+      case Option::kEnv:
+        envBuf.push_back(const_cast<char*>(o.m_data.str));
+        break;
+      case Option::kCwd:
+        coptions.cwd = o.m_data.str[0] == '\0' ? nullptr : o.m_data.str;
+        break;
+      case Option::kUid:
+        coptions.uid = o.m_data.uid;
+        coptions.flags |= UV_PROCESS_SETUID;
+        break;
+      case Option::kGid:
+        coptions.gid = o.m_data.gid;
+        coptions.flags |= UV_PROCESS_SETGID;
+        break;
+      case Option::kSetFlags:
+        coptions.flags |= o.m_data.flags;
+        break;
+      case Option::kClearFlags:
+        coptions.flags &= ~o.m_data.flags;
+        break;
+      case Option::kStdioIgnore: {
+        size_t index = o.m_data.stdio.index;
+        if (index >= stdioBuf.size()) {
+          stdioBuf.resize(index + 1);
+        }
+        stdioBuf[index].flags = UV_IGNORE;
+        stdioBuf[index].data.fd = 0;
+        break;
+      }
+      case Option::kStdioInheritFd: {
+        size_t index = o.m_data.stdio.index;
+        if (index >= stdioBuf.size()) {
+          stdioBuf.resize(index + 1);
+        }
+        stdioBuf[index].flags = UV_INHERIT_FD;
+        stdioBuf[index].data.fd = o.m_data.stdio.fd;
+        break;
+      }
+      case Option::kStdioInheritPipe: {
+        size_t index = o.m_data.stdio.index;
+        if (index >= stdioBuf.size()) {
+          stdioBuf.resize(index + 1);
+        }
+        stdioBuf[index].flags = UV_INHERIT_STREAM;
+        stdioBuf[index].data.stream = o.m_data.stdio.pipe->GetRawStream();
+        break;
+      }
+      case Option::kStdioCreatePipe: {
+        size_t index = o.m_data.stdio.index;
+        if (index >= stdioBuf.size()) {
+          stdioBuf.resize(index + 1);
+        }
+        stdioBuf[index].flags =
+            static_cast<uv_stdio_flags>(UV_CREATE_PIPE | o.m_data.stdio.flags);
+        stdioBuf[index].data.stream = o.m_data.stdio.pipe->GetRawStream();
+        break;
+      }
+      default:
+        break;
+    }
+  }
+
+  if (argsBuf.empty()) {
+    argsBuf.push_back(const_cast<char*>(coptions.file));
+  }
+  argsBuf.push_back(nullptr);
+  coptions.args = argsBuf.data();
+
+  if (envBuf.empty()) {
+    coptions.env = nullptr;
+  } else {
+    envBuf.push_back(nullptr);
+    coptions.env = envBuf.data();
+  }
+
+  coptions.stdio_count = stdioBuf.size();
+  coptions.stdio = static_cast<uv_stdio_container_t*>(stdioBuf.data());
+
+  auto h = std::make_shared<Process>(private_init{});
+  int err = uv_spawn(loop.GetRaw(), h->GetRaw(), &coptions);
+  if (err < 0) {
+    loop.ReportError(err);
+    return nullptr;
+  }
+  h->Keep();
+  return h;
+}
+
+}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Signal.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Signal.cpp
new file mode 100644
index 0000000..10dd7b4
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Signal.cpp
@@ -0,0 +1,32 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/uv/Signal.h"
+
+#include "wpinet/uv/Loop.h"
+
+namespace wpi::uv {
+
+std::shared_ptr<Signal> Signal::Create(Loop& loop) {
+  auto h = std::make_shared<Signal>(private_init{});
+  int err = uv_signal_init(loop.GetRaw(), h->GetRaw());
+  if (err < 0) {
+    loop.ReportError(err);
+    return nullptr;
+  }
+  h->Keep();
+  return h;
+}
+
+void Signal::Start(int signum) {
+  Invoke(
+      &uv_signal_start, GetRaw(),
+      [](uv_signal_t* handle, int signum) {
+        Signal& h = *static_cast<Signal*>(handle->data);
+        h.signal(signum);
+      },
+      signum);
+}
+
+}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Stream.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Stream.cpp
new file mode 100644
index 0000000..e7f6031
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Stream.cpp
@@ -0,0 +1,119 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/uv/Stream.h"
+
+#include <wpi/SmallVector.h>
+
+using namespace wpi;
+using namespace wpi::uv;
+
+namespace {
+class CallbackWriteReq : public WriteReq {
+ public:
+  CallbackWriteReq(std::span<const Buffer> bufs,
+                   std::function<void(std::span<Buffer>, Error)> callback)
+      : m_bufs{bufs.begin(), bufs.end()} {
+    finish.connect(
+        [this, f = std::move(callback)](Error err) { f(m_bufs, err); });
+  }
+
+ private:
+  SmallVector<Buffer, 4> m_bufs;
+};
+}  // namespace
+
+namespace wpi::uv {
+
+ShutdownReq::ShutdownReq() {
+  error = [this](Error err) { GetStream().error(err); };
+}
+
+WriteReq::WriteReq() {
+  error = [this](Error err) { GetStream().error(err); };
+}
+
+void Stream::Shutdown(const std::shared_ptr<ShutdownReq>& req) {
+  if (Invoke(&uv_shutdown, req->GetRaw(), GetRawStream(),
+             [](uv_shutdown_t* req, int status) {
+               auto& h = *static_cast<ShutdownReq*>(req->data);
+               if (status < 0) {
+                 h.ReportError(status);
+               } else {
+                 h.complete();
+               }
+               h.Release();  // this is always a one-shot
+             })) {
+    req->Keep();
+  }
+}
+
+void Stream::Shutdown(std::function<void()> callback) {
+  auto req = std::make_shared<ShutdownReq>();
+  if (callback) {
+    req->complete.connect(std::move(callback));
+  }
+  Shutdown(req);
+}
+
+void Stream::StartRead() {
+  Invoke(&uv_read_start, GetRawStream(), &Handle::AllocBuf,
+         [](uv_stream_t* stream, ssize_t nread, const uv_buf_t* buf) {
+           auto& h = *static_cast<Stream*>(stream->data);
+           Buffer data = *buf;
+
+           // nread=0 is simply ignored
+           if (nread == UV_EOF) {
+             h.end();
+           } else if (nread > 0) {
+             h.data(data, static_cast<size_t>(nread));
+           } else if (nread < 0) {
+             h.ReportError(nread);
+           }
+
+           // free the buffer
+           h.FreeBuf(data);
+         });
+}
+
+void Stream::Write(std::span<const Buffer> bufs,
+                   const std::shared_ptr<WriteReq>& req) {
+  if (Invoke(&uv_write, req->GetRaw(), GetRawStream(), bufs.data(), bufs.size(),
+             [](uv_write_t* r, int status) {
+               auto& h = *static_cast<WriteReq*>(r->data);
+               if (status < 0) {
+                 h.ReportError(status);
+               }
+               h.finish(Error(status));
+               h.Release();  // this is always a one-shot
+             })) {
+    req->Keep();
+  }
+}
+
+void Stream::Write(std::span<const Buffer> bufs,
+                   std::function<void(std::span<Buffer>, Error)> callback) {
+  Write(bufs, std::make_shared<CallbackWriteReq>(bufs, std::move(callback)));
+}
+
+int Stream::TryWrite(std::span<const Buffer> bufs) {
+  int val = uv_try_write(GetRawStream(), bufs.data(), bufs.size());
+  if (val < 0) {
+    this->ReportError(val);
+    return 0;
+  }
+  return val;
+}
+
+int Stream::TryWrite2(std::span<const Buffer> bufs, Stream& send) {
+  int val = uv_try_write2(GetRawStream(), bufs.data(), bufs.size(),
+                          send.GetRawStream());
+  if (val < 0) {
+    this->ReportError(val);
+    return 0;
+  }
+  return val;
+}
+
+}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Tcp.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Tcp.cpp
new file mode 100644
index 0000000..ae01683
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Tcp.cpp
@@ -0,0 +1,181 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/uv/Tcp.h"
+
+#include <cstring>
+
+#include "wpinet/uv/util.h"
+
+namespace wpi::uv {
+
+std::shared_ptr<Tcp> Tcp::Create(Loop& loop, unsigned int flags) {
+  auto h = std::make_shared<Tcp>(private_init{});
+  int err = uv_tcp_init_ex(loop.GetRaw(), h->GetRaw(), flags);
+  if (err < 0) {
+    loop.ReportError(err);
+    return nullptr;
+  }
+  h->Keep();
+  return h;
+}
+
+void Tcp::Reuse(std::function<void()> callback, unsigned int flags) {
+  if (IsClosing()) {
+    return;
+  }
+  if (!m_reuseData) {
+    m_reuseData = std::make_unique<ReuseData>();
+  }
+  m_reuseData->callback = std::move(callback);
+  m_reuseData->flags = flags;
+  uv_close(GetRawHandle(), [](uv_handle_t* handle) {
+    Tcp& h = *static_cast<Tcp*>(handle->data);
+    if (!h.m_reuseData) {
+      return;  // just in case
+    }
+    auto data = std::move(h.m_reuseData);
+    int err = uv_tcp_init_ex(h.GetLoopRef().GetRaw(), h.GetRaw(), data->flags);
+    if (err < 0) {
+      h.ReportError(err);
+      return;
+    }
+    data->callback();
+  });
+}
+
+std::shared_ptr<Tcp> Tcp::Accept() {
+  auto client = Create(GetLoopRef());
+  if (!client) {
+    return nullptr;
+  }
+  if (!Accept(client)) {
+    client->Release();
+    return nullptr;
+  }
+  return client;
+}
+
+Tcp* Tcp::DoAccept() {
+  return Accept().get();
+}
+
+void Tcp::Bind(std::string_view ip, unsigned int port, unsigned int flags) {
+  sockaddr_in addr;
+  int err = NameToAddr(ip, port, &addr);
+  if (err < 0) {
+    ReportError(err);
+  } else {
+    Bind(reinterpret_cast<const sockaddr&>(addr), flags);
+  }
+}
+
+void Tcp::Bind6(std::string_view ip, unsigned int port, unsigned int flags) {
+  sockaddr_in6 addr;
+  int err = NameToAddr(ip, port, &addr);
+  if (err < 0) {
+    ReportError(err);
+  } else {
+    Bind(reinterpret_cast<const sockaddr&>(addr), flags);
+  }
+}
+
+sockaddr_storage Tcp::GetSock() {
+  sockaddr_storage name;
+  int len = sizeof(name);
+  if (!Invoke(&uv_tcp_getsockname, GetRaw(), reinterpret_cast<sockaddr*>(&name),
+              &len)) {
+    std::memset(&name, 0, sizeof(name));
+  }
+  return name;
+}
+
+sockaddr_storage Tcp::GetPeer() {
+  sockaddr_storage name;
+  int len = sizeof(name);
+  if (!Invoke(&uv_tcp_getpeername, GetRaw(), reinterpret_cast<sockaddr*>(&name),
+              &len)) {
+    std::memset(&name, 0, sizeof(name));
+  }
+  return name;
+}
+
+void Tcp::Connect(const sockaddr& addr,
+                  const std::shared_ptr<TcpConnectReq>& req) {
+  if (Invoke(&uv_tcp_connect, req->GetRaw(), GetRaw(), &addr,
+             [](uv_connect_t* req, int status) {
+               auto& h = *static_cast<TcpConnectReq*>(req->data);
+               if (status < 0) {
+                 h.ReportError(status);
+               } else {
+                 h.connected();
+               }
+               h.Release();  // this is always a one-shot
+             })) {
+    req->Keep();
+  }
+}
+
+void Tcp::Connect(const sockaddr& addr, std::function<void()> callback) {
+  auto req = std::make_shared<TcpConnectReq>();
+  req->connected.connect(std::move(callback));
+  Connect(addr, req);
+}
+
+void Tcp::Connect(std::string_view ip, unsigned int port,
+                  const std::shared_ptr<TcpConnectReq>& req) {
+  sockaddr_in addr;
+  int err = NameToAddr(ip, port, &addr);
+  if (err < 0) {
+    ReportError(err);
+  } else {
+    Connect(reinterpret_cast<const sockaddr&>(addr), req);
+  }
+}
+
+void Tcp::Connect(std::string_view ip, unsigned int port,
+                  std::function<void()> callback) {
+  sockaddr_in addr;
+  int err = NameToAddr(ip, port, &addr);
+  if (err < 0) {
+    ReportError(err);
+  } else {
+    Connect(reinterpret_cast<const sockaddr&>(addr), std::move(callback));
+  }
+}
+
+void Tcp::Connect6(std::string_view ip, unsigned int port,
+                   const std::shared_ptr<TcpConnectReq>& req) {
+  sockaddr_in6 addr;
+  int err = NameToAddr(ip, port, &addr);
+  if (err < 0) {
+    ReportError(err);
+  } else {
+    Connect(reinterpret_cast<const sockaddr&>(addr), req);
+  }
+}
+
+void Tcp::Connect6(std::string_view ip, unsigned int port,
+                   std::function<void()> callback) {
+  sockaddr_in6 addr;
+  int err = NameToAddr(ip, port, &addr);
+  if (err < 0) {
+    ReportError(err);
+  } else {
+    Connect(reinterpret_cast<const sockaddr&>(addr), std::move(callback));
+  }
+}
+
+void Tcp::CloseReset() {
+  if (!IsClosing()) {
+    uv_tcp_close_reset(GetRaw(), [](uv_handle_t* handle) {
+      Tcp& h = *static_cast<Tcp*>(handle->data);
+      h.closed();
+      h.Release();  // free ourselves
+    });
+    ForceClosed();
+  }
+}
+
+}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Timer.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Timer.cpp
new file mode 100644
index 0000000..9d52173
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Timer.cpp
@@ -0,0 +1,44 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/uv/Timer.h"
+
+#include "wpinet/uv/Loop.h"
+
+namespace wpi::uv {
+
+std::shared_ptr<Timer> Timer::Create(Loop& loop) {
+  auto h = std::make_shared<Timer>(private_init{});
+  int err = uv_timer_init(loop.GetRaw(), h->GetRaw());
+  if (err < 0) {
+    loop.ReportError(err);
+    return nullptr;
+  }
+  h->Keep();
+  return h;
+}
+
+void Timer::SingleShot(Loop& loop, Time timeout, std::function<void()> func) {
+  auto h = Create(loop);
+  if (!h) {
+    return;
+  }
+  h->timeout.connect([theTimer = h.get(), f = std::move(func)]() {
+    f();
+    theTimer->Close();
+  });
+  h->Start(timeout);
+}
+
+void Timer::Start(Time timeout, Time repeat) {
+  Invoke(
+      &uv_timer_start, GetRaw(),
+      [](uv_timer_t* handle) {
+        Timer& h = *static_cast<Timer*>(handle->data);
+        h.timeout();
+      },
+      timeout.count(), repeat.count());
+}
+
+}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Tty.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Tty.cpp
new file mode 100644
index 0000000..6043a93
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Tty.cpp
@@ -0,0 +1,22 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/uv/Tty.h"
+
+#include "wpinet/uv/Loop.h"
+
+namespace wpi::uv {
+
+std::shared_ptr<Tty> Tty::Create(Loop& loop, uv_file fd, bool readable) {
+  auto h = std::make_shared<Tty>(private_init{});
+  int err = uv_tty_init(loop.GetRaw(), h->GetRaw(), fd, readable ? 1 : 0);
+  if (err < 0) {
+    loop.ReportError(err);
+    return nullptr;
+  }
+  h->Keep();
+  return h;
+}
+
+}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Udp.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Udp.cpp
new file mode 100644
index 0000000..689d5a7
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Udp.cpp
@@ -0,0 +1,196 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/uv/Udp.h"
+
+#include <cstring>
+
+#include <wpi/SmallString.h>
+#include <wpi/SmallVector.h>
+
+#include "wpinet/uv/util.h"
+
+namespace {
+
+using namespace wpi;
+using namespace wpi::uv;
+
+class CallbackUdpSendReq : public UdpSendReq {
+ public:
+  CallbackUdpSendReq(std::span<const Buffer> bufs,
+                     std::function<void(std::span<Buffer>, Error)> callback)
+      : m_bufs{bufs.begin(), bufs.end()} {
+    complete.connect(
+        [this, f = std::move(callback)](Error err) { f(m_bufs, err); });
+  }
+
+ private:
+  SmallVector<Buffer, 4> m_bufs;
+};
+
+}  // namespace
+
+namespace wpi::uv {
+
+UdpSendReq::UdpSendReq() {
+  error = [this](Error err) { GetUdp().error(err); };
+}
+
+std::shared_ptr<Udp> Udp::Create(Loop& loop, unsigned int flags) {
+  auto h = std::make_shared<Udp>(private_init{});
+  int err = uv_udp_init_ex(loop.GetRaw(), h->GetRaw(), flags);
+  if (err < 0) {
+    loop.ReportError(err);
+    return nullptr;
+  }
+  h->Keep();
+  return h;
+}
+
+void Udp::Bind(std::string_view ip, unsigned int port, unsigned int flags) {
+  sockaddr_in addr;
+  int err = NameToAddr(ip, port, &addr);
+  if (err < 0) {
+    ReportError(err);
+  } else {
+    Bind(reinterpret_cast<const sockaddr&>(addr), flags);
+  }
+}
+
+void Udp::Bind6(std::string_view ip, unsigned int port, unsigned int flags) {
+  sockaddr_in6 addr;
+  int err = NameToAddr(ip, port, &addr);
+  if (err < 0) {
+    ReportError(err);
+  } else {
+    Bind(reinterpret_cast<const sockaddr&>(addr), flags);
+  }
+}
+
+void Udp::Connect(std::string_view ip, unsigned int port) {
+  sockaddr_in addr;
+  int err = NameToAddr(ip, port, &addr);
+  if (err < 0) {
+    ReportError(err);
+  } else {
+    Connect(reinterpret_cast<const sockaddr&>(addr));
+  }
+}
+
+void Udp::Connect6(std::string_view ip, unsigned int port) {
+  sockaddr_in6 addr;
+  int err = NameToAddr(ip, port, &addr);
+  if (err < 0) {
+    ReportError(err);
+  } else {
+    Connect(reinterpret_cast<const sockaddr&>(addr));
+  }
+}
+
+sockaddr_storage Udp::GetPeer() {
+  sockaddr_storage name;
+  int len = sizeof(name);
+  if (!Invoke(&uv_udp_getpeername, GetRaw(), reinterpret_cast<sockaddr*>(&name),
+              &len)) {
+    std::memset(&name, 0, sizeof(name));
+  }
+  return name;
+}
+
+sockaddr_storage Udp::GetSock() {
+  sockaddr_storage name;
+  int len = sizeof(name);
+  if (!Invoke(&uv_udp_getsockname, GetRaw(), reinterpret_cast<sockaddr*>(&name),
+              &len)) {
+    std::memset(&name, 0, sizeof(name));
+  }
+  return name;
+}
+
+void Udp::SetMembership(std::string_view multicastAddr,
+                        std::string_view interfaceAddr,
+                        uv_membership membership) {
+  SmallString<128> multicastAddrBuf{multicastAddr};
+  SmallString<128> interfaceAddrBuf{interfaceAddr};
+  Invoke(&uv_udp_set_membership, GetRaw(), multicastAddrBuf.c_str(),
+         interfaceAddrBuf.c_str(), membership);
+}
+
+void Udp::SetSourceMembership(std::string_view multicastAddr,
+                              std::string_view interfaceAddr,
+                              std::string_view sourceAddr,
+                              uv_membership membership) {
+  SmallString<128> multicastAddrBuf{multicastAddr};
+  SmallString<128> interfaceAddrBuf{interfaceAddr};
+  SmallString<128> sourceAddrBuf{sourceAddr};
+  Invoke(&uv_udp_set_source_membership, GetRaw(), multicastAddrBuf.c_str(),
+         interfaceAddrBuf.c_str(), sourceAddrBuf.c_str(), membership);
+}
+
+void Udp::SetMulticastInterface(std::string_view interfaceAddr) {
+  SmallString<128> interfaceAddrBuf{interfaceAddr};
+  Invoke(&uv_udp_set_multicast_interface, GetRaw(), interfaceAddrBuf.c_str());
+}
+
+void Udp::Send(const sockaddr& addr, std::span<const Buffer> bufs,
+               const std::shared_ptr<UdpSendReq>& req) {
+  if (Invoke(&uv_udp_send, req->GetRaw(), GetRaw(), bufs.data(), bufs.size(),
+             &addr, [](uv_udp_send_t* r, int status) {
+               auto& h = *static_cast<UdpSendReq*>(r->data);
+               if (status < 0) {
+                 h.ReportError(status);
+               }
+               h.complete(Error(status));
+               h.Release();  // this is always a one-shot
+             })) {
+    req->Keep();
+  }
+}
+
+void Udp::Send(const sockaddr& addr, std::span<const Buffer> bufs,
+               std::function<void(std::span<Buffer>, Error)> callback) {
+  Send(addr, bufs,
+       std::make_shared<CallbackUdpSendReq>(bufs, std::move(callback)));
+}
+
+void Udp::Send(std::span<const Buffer> bufs,
+               const std::shared_ptr<UdpSendReq>& req) {
+  if (Invoke(&uv_udp_send, req->GetRaw(), GetRaw(), bufs.data(), bufs.size(),
+             nullptr, [](uv_udp_send_t* r, int status) {
+               auto& h = *static_cast<UdpSendReq*>(r->data);
+               if (status < 0) {
+                 h.ReportError(status);
+               }
+               h.complete(Error(status));
+               h.Release();  // this is always a one-shot
+             })) {
+    req->Keep();
+  }
+}
+
+void Udp::Send(std::span<const Buffer> bufs,
+               std::function<void(std::span<Buffer>, Error)> callback) {
+  Send(bufs, std::make_shared<CallbackUdpSendReq>(bufs, std::move(callback)));
+}
+
+void Udp::StartRecv() {
+  Invoke(&uv_udp_recv_start, GetRaw(), &AllocBuf,
+         [](uv_udp_t* handle, ssize_t nread, const uv_buf_t* buf,
+            const sockaddr* addr, unsigned flags) {
+           auto& h = *static_cast<Udp*>(handle->data);
+           Buffer data = *buf;
+
+           // nread=0 is simply ignored
+           if (nread > 0) {
+             h.received(data, static_cast<size_t>(nread), *addr, flags);
+           } else if (nread < 0) {
+             h.ReportError(nread);
+           }
+
+           // free the buffer
+           h.FreeBuf(data);
+         });
+}
+
+}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Work.cpp b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Work.cpp
new file mode 100644
index 0000000..818a93b
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/cpp/uv/Work.cpp
@@ -0,0 +1,50 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/uv/Work.h"
+
+#include "wpinet/uv/Loop.h"
+
+namespace wpi::uv {
+
+WorkReq::WorkReq() {
+  error = [this](Error err) { GetLoop().error(err); };
+}
+
+void QueueWork(Loop& loop, const std::shared_ptr<WorkReq>& req) {
+  int err = uv_queue_work(
+      loop.GetRaw(), req->GetRaw(),
+      [](uv_work_t* req) {
+        auto& h = *static_cast<WorkReq*>(req->data);
+        h.work();
+      },
+      [](uv_work_t* req, int status) {
+        auto& h = *static_cast<WorkReq*>(req->data);
+        if (status < 0) {
+          h.ReportError(status);
+        } else {
+          h.afterWork();
+        }
+        h.Release();  // this is always a one-shot
+      });
+  if (err < 0) {
+    loop.ReportError(err);
+  } else {
+    req->Keep();
+  }
+}
+
+void QueueWork(Loop& loop, std::function<void()> work,
+               std::function<void()> afterWork) {
+  auto req = std::make_shared<WorkReq>();
+  if (work) {
+    req->work.connect(std::move(work));
+  }
+  if (afterWork) {
+    req->afterWork.connect(std::move(afterWork));
+  }
+  QueueWork(loop, req);
+}
+
+}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/DsClient.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/DsClient.h
new file mode 100644
index 0000000..dcebe2f
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/DsClient.h
@@ -0,0 +1,55 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <memory>
+#include <string>
+#include <string_view>
+
+#include <wpi/Signal.h>
+
+namespace wpi {
+
+class Logger;
+
+namespace uv {
+class Loop;
+class Tcp;
+class Timer;
+}  // namespace uv
+
+class DsClient : public std::enable_shared_from_this<DsClient> {
+  struct private_init {};
+
+ public:
+  static std::shared_ptr<DsClient> Create(wpi::uv::Loop& loop,
+                                          wpi::Logger& logger) {
+    return std::make_shared<DsClient>(loop, logger, private_init{});
+  }
+
+  DsClient(wpi::uv::Loop& loop, wpi::Logger& logger, const private_init&);
+  ~DsClient();
+  DsClient(const DsClient&) = delete;
+  DsClient& operator=(const DsClient&) = delete;
+
+  void Close();
+
+  sig::Signal<std::string_view> setIp;
+  sig::Signal<> clearIp;
+
+ private:
+  void Connect();
+  void HandleIncoming(std::string_view in);
+  void ParseJson();
+
+  wpi::Logger& m_logger;
+
+  std::shared_ptr<wpi::uv::Tcp> m_tcp;
+  std::shared_ptr<wpi::uv::Timer> m_timer;
+
+  std::string m_json;
+};
+
+}  // namespace wpi
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/EventLoopRunner.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/EventLoopRunner.h
new file mode 100644
index 0000000..896bae3
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/EventLoopRunner.h
@@ -0,0 +1,63 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_EVENTLOOPRUNNER_H_
+#define WPINET_EVENTLOOPRUNNER_H_
+
+#include <functional>
+#include <memory>
+
+#include <wpi/SafeThread.h>
+
+#include "wpinet/uv/Loop.h"
+
+namespace wpi {
+
+/**
+ * Executes an event loop on a separate thread.
+ */
+class EventLoopRunner {
+ public:
+  using LoopFunc = std::function<void(uv::Loop&)>;
+
+  EventLoopRunner();
+  virtual ~EventLoopRunner();
+
+  /**
+   * Stop the loop.  Once the loop is stopped it cannot be restarted.
+   * This function does not return until the loop has exited.
+   */
+  void Stop();
+
+  /**
+   * Run a function asynchronously (once) on the loop.
+   * This is safe to call from any thread, but is NOT safe to call from the
+   * provided function (it will deadlock).
+   * @param func function to execute on the loop
+   */
+  void ExecAsync(LoopFunc func);
+
+  /**
+   * Run a function synchronously (once) on the loop.
+   * This is safe to call from any thread, but is NOT safe to call from the
+   * provided function (it will deadlock).
+   * This does not return until the function finishes executing.
+   * @param func function to execute on the loop
+   */
+  void ExecSync(LoopFunc func);
+
+  /**
+   * Get the loop.  If the loop thread is not running, returns nullptr.
+   * @return The loop
+   */
+  std::shared_ptr<uv::Loop> GetLoop();
+
+ private:
+  class Thread;
+  SafeThreadOwner<Thread> m_owner;
+};
+
+}  // namespace wpi
+
+#endif  // WPINET_EVENTLOOPRUNNER_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/HttpParser.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/HttpParser.h
new file mode 100644
index 0000000..a2a6ea7
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/HttpParser.h
@@ -0,0 +1,228 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_HTTPPARSER_H_
+#define WPINET_HTTPPARSER_H_
+
+#include <stdint.h>
+
+#include <string_view>
+
+#include <wpi/Signal.h>
+#include <wpi/SmallString.h>
+
+#include "wpinet/http_parser.h"
+
+namespace wpi {
+
+/**
+ * HTTP protocol parser.  Performs incremental parsing with callbacks for each
+ * part of the HTTP protocol.  As this is incremental, it's suitable for use
+ * with event based frameworks that provide arbitrary chunks of data.
+ */
+class HttpParser {
+ public:
+  enum Type {
+    kRequest = HTTP_REQUEST,
+    kResponse = HTTP_RESPONSE,
+    kBoth = HTTP_BOTH
+  };
+
+  /**
+   * Returns the library version. Bits 16-23 contain the major version number,
+   * bits 8-15 the minor version number and bits 0-7 the patch level.
+   */
+  static uint32_t GetParserVersion();
+
+  /**
+   * Constructor.
+   * @param type Type of parser (request or response or both)
+   */
+  explicit HttpParser(Type type);
+
+  /**
+   * Reset the parser to initial state.
+   * This allows reusing the same parser object from request to request.
+   * @param type Type of parser (request or response or both)
+   */
+  void Reset(Type type);
+
+  /**
+   * Set the maximum accepted length for URLs, field names, and field values.
+   * The default is 1024.
+   * @param len maximum length
+   */
+  void SetMaxLength(size_t len) { m_maxLength = len; }
+
+  /**
+   * Executes the parser.  An empty input is treated as EOF.
+   * @param in input data
+   * @return Trailing input data after the parse.
+   */
+  std::string_view Execute(std::string_view in) {
+    in.remove_prefix(
+        http_parser_execute(&m_parser, &m_settings, in.data(), in.size()));
+    return in;
+  }
+
+  /**
+   * Get HTTP major version.
+   */
+  unsigned int GetMajor() const { return m_parser.http_major; }
+
+  /**
+   * Get HTTP minor version.
+   */
+  unsigned int GetMinor() const { return m_parser.http_minor; }
+
+  /**
+   * Get HTTP status code.  Valid only on responses.  Valid in and after
+   * the OnStatus() callback has been called.
+   */
+  unsigned int GetStatusCode() const { return m_parser.status_code; }
+
+  /**
+   * Get HTTP method.  Valid only on requests.
+   */
+  http_method GetMethod() const {
+    return static_cast<http_method>(m_parser.method);
+  }
+
+  /**
+   * Determine if an error occurred.
+   * @return False if no error.
+   */
+  bool HasError() const { return m_parser.http_errno != HPE_OK; }
+
+  /**
+   * Get error number.
+   */
+  http_errno GetError() const {
+    return static_cast<http_errno>(m_parser.http_errno);
+  }
+
+  /**
+   * Abort the parse.  Call this from a callback handler to indicate an error.
+   * This will result in GetError() returning one of the callback-related
+   * errors (e.g. HPE_CB_message_begin).
+   */
+  void Abort() { m_aborted = true; }
+
+  /**
+   * Determine if an upgrade header was present and the parser has exited
+   * because of that.  Should be checked when Execute() returns in addition to
+   * checking GetError().
+   * @return True if upgrade header, false otherwise.
+   */
+  bool IsUpgrade() const { return m_parser.upgrade; }
+
+  /**
+   * If this returns false in the headersComplete or messageComplete
+   * callback, then this should be the last message on the connection.
+   * If you are the server, respond with the "Connection: close" header.
+   * If you are the client, close the connection.
+   */
+  bool ShouldKeepAlive() const { return http_should_keep_alive(&m_parser); }
+
+  /**
+   * Pause the parser.
+   * @param paused True to pause, false to unpause.
+   */
+  void Pause(bool paused) { http_parser_pause(&m_parser, paused); }
+
+  /**
+   * Checks if this is the final chunk of the body.
+   */
+  bool IsBodyFinal() const { return http_body_is_final(&m_parser); }
+
+  /**
+   * Get URL.  Valid in and after the url callback has been called.
+   */
+  std::string_view GetUrl() const { return m_urlBuf.str(); }
+
+  /**
+   * Message begin callback.
+   */
+  sig::Signal<> messageBegin;
+
+  /**
+   * URL callback.
+   *
+   * The parameter to the callback is the complete URL string.
+   */
+  sig::Signal<std::string_view> url;
+
+  /**
+   * Status callback.
+   *
+   * The parameter to the callback is the complete status string.
+   * GetStatusCode() can be used to get the numeric status code.
+   */
+  sig::Signal<std::string_view> status;
+
+  /**
+   * Header field callback.
+   *
+   * The parameters to the callback are the field name and field value.
+   */
+  sig::Signal<std::string_view, std::string_view> header;
+
+  /**
+   * Headers complete callback.
+   *
+   * The parameter to the callback is whether the connection should be kept
+   * alive.  If this is false, then this should be the last message on the
+   * connection.  If you are the server, respond with the "Connection: close"
+   * header.  If you are the client, close the connection.
+   */
+  sig::Signal<bool> headersComplete;
+
+  /**
+   * Body data callback.
+   *
+   * The parameters to the callback is the data chunk and whether this is the
+   * final chunk of data in the message.  Note this callback will be called
+   * multiple times arbitrarily (e.g. it's possible that it may be called with
+   * just a few characters at a time).
+   */
+  sig::Signal<std::string_view, bool> body;
+
+  /**
+   * Headers complete callback.
+   *
+   * The parameter to the callback is whether the connection should be kept
+   * alive.  If this is false, then this should be the last message on the
+   * connection.  If you are the server, respond with the "Connection: close"
+   * header.  If you are the client, close the connection.
+   */
+  sig::Signal<bool> messageComplete;
+
+  /**
+   * Chunk header callback.
+   *
+   * The parameter to the callback is the chunk size.
+   */
+  sig::Signal<uint64_t> chunkHeader;
+
+  /**
+   * Chunk complete callback.
+   */
+  sig::Signal<> chunkComplete;
+
+ private:
+  http_parser m_parser;
+  http_parser_settings m_settings;
+
+  size_t m_maxLength = 1024;
+  enum { kStart, kUrl, kStatus, kField, kValue } m_state = kStart;
+  SmallString<128> m_urlBuf;
+  SmallString<32> m_fieldBuf;
+  SmallString<128> m_valueBuf;
+
+  bool m_aborted = false;
+};
+
+}  // namespace wpi
+
+#endif  // WPINET_HTTPPARSER_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/HttpServerConnection.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/HttpServerConnection.h
new file mode 100644
index 0000000..486f36e
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/HttpServerConnection.h
@@ -0,0 +1,152 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_HTTPSERVERCONNECTION_H_
+#define WPINET_HTTPSERVERCONNECTION_H_
+
+#include <memory>
+#include <span>
+#include <string_view>
+
+#include "wpinet/HttpParser.h"
+#include "wpinet/uv/Stream.h"
+
+namespace wpi {
+
+class raw_ostream;
+
+class HttpServerConnection {
+ public:
+  explicit HttpServerConnection(std::shared_ptr<uv::Stream> stream);
+  virtual ~HttpServerConnection() = default;
+
+ protected:
+  /**
+   * Process an incoming HTTP request.  This is called after the incoming
+   * message completes (e.g. from the HttpParser::messageComplete callback).
+   *
+   * The implementation should read request details from m_request and call the
+   * appropriate Send() functions to send a response back to the client.
+   */
+  virtual void ProcessRequest() = 0;
+
+  /**
+   * Build common response headers.
+   *
+   * Called by SendHeader() to send headers common to every response.
+   * Each line must be terminated with "\r\n".
+   *
+   * The default implementation sends the following:
+   * "Server: WebServer/1.0\r\n"
+   * "Cache-Control: no-store, no-cache, must-revalidate, pre-check=0, "
+   * "post-check=0, max-age=0\r\n"
+   * "Pragma: no-cache\r\n"
+   * "Expires: Mon, 3 Jan 2000 12:34:56 GMT\r\n"
+   *
+   * These parameters should ensure the browser does not cache the response.
+   * A browser should connect for each file and not serve files from its cache.
+   *
+   * @param os response stream
+   */
+  virtual void BuildCommonHeaders(raw_ostream& os);
+
+  /**
+   * Build HTTP response header, along with other header information like
+   * mimetype.  Calls BuildCommonHeaders().
+   *
+   * @param os response stream
+   * @param code HTTP response code (e.g. 200)
+   * @param codeText HTTP response code text (e.g. "OK")
+   * @param contentType MIME content type (e.g. "text/plain")
+   * @param contentLength Length of content.  If 0 is provided, m_keepAlive will
+   *                      be set to false.
+   * @param extra Extra HTTP headers to send, including final "\r\n"
+   */
+  virtual void BuildHeader(raw_ostream& os, int code, std::string_view codeText,
+                           std::string_view contentType, uint64_t contentLength,
+                           std::string_view extra = {});
+
+  /**
+   * Send data to client.
+   *
+   * This is a convenience wrapper around m_stream.Write() to provide
+   * auto-close functionality.
+   *
+   * @param bufs Buffers to write.  Deallocate() will be called on each
+   *             buffer after the write completes.  If different behavior
+   *             is desired, call m_stream.Write() directly instead.
+   * @param closeAfter close the connection after the write completes
+   */
+  void SendData(std::span<const uv::Buffer> bufs, bool closeAfter = false);
+
+  /**
+   * Send HTTP response, along with other header information like mimetype.
+   * Calls BuildHeader().
+   *
+   * @param code HTTP response code (e.g. 200)
+   * @param codeText HTTP response code text (e.g. "OK")
+   * @param contentType MIME content type (e.g. "text/plain")
+   * @param content Response message content
+   * @param extraHeader Extra HTTP headers to send, including final "\r\n"
+   */
+  virtual void SendResponse(int code, std::string_view codeText,
+                            std::string_view contentType,
+                            std::string_view content,
+                            std::string_view extraHeader = {});
+
+  /**
+   * Send HTTP response from static data, along with other header information
+   * like mimetype.  Calls BuildHeader().  Supports gzip pre-compressed data
+   * (it will decompress if the client does not accept gzip encoded data).
+   * Unlike SendResponse(), content is not copied and its contents must remain
+   * valid for an unspecified lifetime.
+   *
+   * @param code HTTP response code (e.g. 200)
+   * @param codeText HTTP response code text (e.g. "OK")
+   * @param contentType MIME content type (e.g. "text/plain")
+   * @param content Response message content
+   * @param gzipped True if content is gzip compressed
+   * @param extraHeader Extra HTTP headers to send, including final "\r\n"
+   */
+  virtual void SendStaticResponse(int code, std::string_view codeText,
+                                  std::string_view contentType,
+                                  std::string_view content, bool gzipped,
+                                  std::string_view extraHeader = {});
+
+  /**
+   * Send error header and message.
+   * This provides standard code responses for 400, 401, 403, 404, 500, and 503.
+   * Other codes will be reported as 501.  For arbitrary code handling, use
+   * SendResponse() instead.
+   *
+   * @param code HTTP error code (e.g. 404)
+   * @param message Additional message text
+   */
+  virtual void SendError(int code, std::string_view message = {});
+
+  /** The HTTP request. */
+  HttpParser m_request{HttpParser::kRequest};
+
+  /** Whether the connection should be kept alive. */
+  bool m_keepAlive = false;
+
+  /** If gzip is an acceptable encoding for responses. */
+  bool m_acceptGzip = false;
+
+  /** The underlying stream for the connection. */
+  uv::Stream& m_stream;
+
+  /** The header reader connection. */
+  sig::ScopedConnection m_dataConn;
+
+  /** The end stream connection. */
+  sig::ScopedConnection m_endConn;
+
+  /** The message complete connection. */
+  sig::Connection m_messageCompleteConn;
+};
+
+}  // namespace wpi
+
+#endif  // WPINET_HTTPSERVERCONNECTION_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/HttpUtil.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/HttpUtil.h
new file mode 100644
index 0000000..fcf6887
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/HttpUtil.h
@@ -0,0 +1,423 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_HTTPUTIL_H_
+#define WPINET_HTTPUTIL_H_
+
+#include <initializer_list>
+#include <memory>
+#include <optional>
+#include <span>
+#include <string>
+#include <string_view>
+#include <utility>
+#include <vector>
+
+#include <wpi/SmallString.h>
+#include <wpi/SmallVector.h>
+#include <wpi/StringMap.h>
+#include <wpi/raw_istream.h>
+
+#include "wpinet/NetworkStream.h"
+#include "wpinet/raw_socket_istream.h"
+#include "wpinet/raw_socket_ostream.h"
+
+namespace wpi {
+
+// Unescape a %xx-encoded URI.
+// @param buf Buffer for output
+// @param error Set to true if an error occurred
+// @return Escaped string
+std::string_view UnescapeURI(std::string_view str, SmallVectorImpl<char>& buf,
+                             bool* error);
+
+// Escape a string with %xx-encoding.
+// @param buf Buffer for output
+// @param spacePlus If true, encodes spaces to '+' rather than "%20"
+// @return Escaped string
+std::string_view EscapeURI(std::string_view str, SmallVectorImpl<char>& buf,
+                           bool spacePlus = true);
+
+// Parse a set of HTTP headers.  Saves just the Content-Type and Content-Length
+// fields.
+// @param is Input stream
+// @param contentType If not null, Content-Type contents are saved here.
+// @param contentLength If not null, Content-Length contents are saved here.
+// @return False if error occurred in input stream
+bool ParseHttpHeaders(raw_istream& is, SmallVectorImpl<char>* contentType,
+                      SmallVectorImpl<char>* contentLength);
+
+// Look for a MIME multi-part boundary.  On return, the input stream will
+// be located at the character following the boundary (usually "\r\n").
+// @param is Input stream
+// @param boundary Boundary string to scan for (not including "--" prefix)
+// @param saveBuf If not null, all scanned characters up to but not including
+//     the boundary are saved to this string
+// @return False if error occurred on input stream, true if boundary found.
+bool FindMultipartBoundary(wpi::raw_istream& is, std::string_view boundary,
+                           std::string* saveBuf);
+
+/**
+ * Map for looking up elements of the query portion of a URI.  Does not
+ * handle multiple elements with the same name.  This is a reference type;
+ * it does not make a copy of the query string, so it is important that the
+ * query string has a lifetime at least as long as this object.
+ */
+class HttpQueryMap {
+ public:
+  /**
+   * Constructs an empty map (with no entries).
+   */
+  HttpQueryMap() = default;
+
+  /**
+   * Constructs from an escaped query string.  Note: does not make a copy of
+   * the query string, so it must not be a temporary.
+   *
+   * @param query query string
+   */
+  explicit HttpQueryMap(std::string_view query);
+
+  /**
+   * Gets an element of the query string.  Both the name and the returned
+   * value are unescaped strings.
+   *
+   * @param name name (unescaped)
+   * @param buf result buffer for value
+   * @return Optional unescaped value.  Returns an empty optional if the
+   *         name is not present in the query map.
+   */
+  std::optional<std::string_view> Get(std::string_view name,
+                                      SmallVectorImpl<char>& buf) const;
+
+ private:
+  StringMap<std::string_view> m_elems;
+};
+
+class HttpPathRef;
+
+/**
+ * Class for HTTP path matching.  A root path is represented as a single
+ * empty element, otherwise the path consists of each non-empty element
+ * between the '/' characters:
+ *  - "" -> []
+ *  - "/" -> [""]
+ *  - "/foo" -> ["foo"]
+ *  - "/foo/bar" -> ["foo", "bar"]
+ *  - "/foo//bar/" -> ["foo", "bar"]
+ *
+ * All path elements are unescaped.
+ */
+class HttpPath {
+ public:
+  /**
+   * Constructs an empty HTTP path.
+   */
+  HttpPath() = default;
+
+  /**
+   * Constructs a HTTP path from an escaped path string.  Makes a copy of the
+   * path, so it's safe to be a temporary.
+   */
+  explicit HttpPath(std::string_view path);
+
+  /**
+   * Evaluates to true if the path is not empty.
+   */
+  explicit operator bool() const { return !empty(); }
+
+  /**
+   * Returns true if the path has no elements.
+   */
+  bool empty() const { return m_pathEnds.empty(); }
+
+  /**
+   * Returns number of elements in the path.
+   */
+  size_t size() const { return m_pathEnds.size(); }
+
+  /**
+   * Returns true if the path exactly matches the provided match list.
+   *
+   * @param match match list
+   * @return True if path equals match list
+   */
+  bool equals(std::initializer_list<std::string_view> match) const {
+    return equals(0, {match.begin(), match.end()});
+  }
+  bool equals(std::span<const std::string_view> match) const {
+    return equals(0, match);
+  }
+  bool equals(std::string_view match) const { return equals(0, {match}); }
+
+  /**
+   * Returns true if the elements of the path starting at the "start" element
+   * match the provided match list, and there are no additional elements.
+   *
+   * @param start element to start matching at
+   * @param match match list
+   * @return True if match
+   */
+  bool equals(size_t start,
+              std::initializer_list<std::string_view> match) const {
+    return equals(start, {match.begin(), match.end()});
+  }
+  bool equals(size_t start, std::span<const std::string_view> match) const {
+    if (m_pathEnds.size() != (start + match.size())) {
+      return false;
+    }
+    return startswith(start, match);
+  }
+  bool equals(size_t start, std::string_view match) const {
+    return equals(start, {match});
+  }
+
+  /**
+   * Returns true if the first elements of the path match the provided match
+   * list.  The path may have additional elements.
+   *
+   * @param match match list
+   * @return True if path starts with match list
+   */
+  bool startswith(std::initializer_list<std::string_view> match) const {
+    return startswith(0, {match.begin(), match.end()});
+  }
+  bool startswith(std::span<const std::string_view> match) const {
+    return startswith(0, match);
+  }
+  bool startswith(std::string_view match) const {
+    return startswith(0, {match});
+  }
+
+  /**
+   * Returns true if the elements of the path starting at the "start" element
+   * match the provided match list.  The path may have additional elements.
+   *
+   * @param start element to start matching at
+   * @param match match list
+   * @return True if path starting at the start element matches the match list
+   */
+  bool startswith(size_t start,
+                  std::initializer_list<std::string_view> match) const {
+    return startswith(start, {match.begin(), match.end()});
+  }
+
+  bool startswith(size_t start, std::span<const std::string_view> match) const;
+
+  bool startswith(size_t start, std::string_view match) const {
+    return startswith(start, {match});
+  }
+
+  /**
+   * Gets a single element of the path.
+   */
+  std::string_view operator[](size_t n) const;
+
+  /**
+   * Returns a path reference with the first N elements of the path removed.
+   */
+  HttpPathRef drop_front(size_t n) const;
+
+ private:
+  SmallString<128> m_pathBuf;
+  SmallVector<size_t, 16> m_pathEnds;
+};
+
+/**
+ * Proxy reference object for a portion of a HttpPath.
+ */
+class HttpPathRef {
+ public:
+  HttpPathRef() = default;
+  /*implicit*/ HttpPathRef(const HttpPath& path,  // NOLINT
+                           size_t start = 0)
+      : m_path(&path), m_start(start) {}
+
+  explicit operator bool() const { return !empty(); }
+  bool empty() const { return m_path && m_path->size() == m_start; }
+  size_t size() const { return m_path ? m_path->size() - m_start : 0; }
+
+  bool equals(std::initializer_list<std::string_view> match) const {
+    return equals(0, {match.begin(), match.end()});
+  }
+  bool equals(std::span<const std::string_view> match) const {
+    return equals(0, match);
+  }
+  bool equals(std::string_view match) const { return equals(0, {match}); }
+
+  bool equals(size_t start,
+              std::initializer_list<std::string_view> match) const {
+    return equals(start, {match.begin(), match.end()});
+  }
+  bool equals(size_t start, std::span<const std::string_view> match) const {
+    return m_path ? m_path->equals(m_start + start, match) : false;
+  }
+  bool equals(size_t start, std::string_view match) const {
+    return equals(start, {match});
+  }
+
+  bool startswith(std::initializer_list<std::string_view> match) const {
+    return startswith(0, {match.begin(), match.end()});
+  }
+  bool startswith(std::span<const std::string_view> match) const {
+    return startswith(0, match);
+  }
+  bool startswith(std::string_view match) const {
+    return startswith(0, {match});
+  }
+
+  bool startswith(size_t start,
+                  std::initializer_list<std::string_view> match) const {
+    return startswith(start, {match.begin(), match.end()});
+  }
+  bool startswith(size_t start, std::span<const std::string_view> match) const {
+    return m_path ? m_path->startswith(m_start + start, match) : false;
+  }
+  bool startswith(size_t start, std::string_view match) const {
+    return startswith(start, {match});
+  }
+
+  std::string_view operator[](size_t n) const {
+    return m_path ? m_path->operator[](m_start + n) : std::string_view{};
+  }
+  HttpPathRef drop_front(size_t n) const {
+    return m_path ? m_path->drop_front(m_start + n) : HttpPathRef{};
+  }
+
+ private:
+  const HttpPath* m_path = nullptr;
+  size_t m_start = 0;
+};
+
+class HttpLocation {
+ public:
+  HttpLocation() = default;
+  HttpLocation(std::string_view url_, bool* error, std::string* errorMsg);
+
+  std::string url;       // retain copy
+  std::string user;      // unescaped
+  std::string password;  // unescaped
+  std::string host;
+  int port;
+  std::string path;  // escaped, not including leading '/'
+  std::vector<std::pair<std::string, std::string>> params;  // unescaped
+  std::string fragment;
+};
+
+class HttpRequest {
+ public:
+  HttpRequest() = default;
+
+  explicit HttpRequest(const HttpLocation& loc)
+      : host{loc.host}, port{loc.port} {
+    SetPath(loc.path, loc.params);
+    SetAuth(loc);
+  }
+
+  template <typename T>
+  HttpRequest(const HttpLocation& loc, const T& extraParams);
+
+  HttpRequest(const HttpLocation& loc, std::string_view path_)
+      : host{loc.host}, port{loc.port}, path{path_} {
+    SetAuth(loc);
+  }
+
+  template <typename T>
+  HttpRequest(const HttpLocation& loc, std::string_view path_, const T& params)
+      : host{loc.host}, port{loc.port} {
+    SetPath(path_, params);
+    SetAuth(loc);
+  }
+
+  SmallString<128> host;
+  int port;
+  std::string auth;
+  SmallString<128> path;
+
+ private:
+  void SetAuth(const HttpLocation& loc);
+  template <typename T>
+  void SetPath(std::string_view path_, const T& params);
+
+  template <typename T>
+  static std::string_view GetFirst(const T& elem) {
+    return elem.first;
+  }
+  template <typename T>
+  static std::string_view GetFirst(const StringMapEntry<T>& elem) {
+    return elem.getKey();
+  }
+  template <typename T>
+  static std::string_view GetSecond(const T& elem) {
+    return elem.second;
+  }
+};
+
+class HttpConnection {
+ public:
+  HttpConnection(std::unique_ptr<wpi::NetworkStream> stream_, int timeout)
+      : stream{std::move(stream_)}, is{*stream, timeout}, os{*stream, true} {}
+
+  bool Handshake(const HttpRequest& request, std::string* warnMsg);
+
+  std::unique_ptr<wpi::NetworkStream> stream;
+  wpi::raw_socket_istream is;
+  wpi::raw_socket_ostream os;
+
+  // Valid after Handshake() is successful
+  SmallString<64> contentType;
+  SmallString<64> contentLength;
+
+  explicit operator bool() const { return stream && !is.has_error(); }
+};
+
+class HttpMultipartScanner {
+ public:
+  explicit HttpMultipartScanner(std::string_view boundary,
+                                bool saveSkipped = false) {
+    Reset(saveSkipped);
+    SetBoundary(boundary);
+  }
+
+  // Change the boundary.  This is only safe to do when IsDone() is true (or
+  // immediately after construction).
+  void SetBoundary(std::string_view boundary);
+
+  // Reset the scanner.  This allows reuse of internal buffers.
+  void Reset(bool saveSkipped = false);
+
+  // Execute the scanner.  Will automatically call Reset() on entry if IsDone()
+  // is true.
+  // @param in input data
+  // @return the input not consumed; empty if all input consumed
+  std::string_view Execute(std::string_view in);
+
+  // Returns true when the boundary has been found.
+  bool IsDone() const { return m_state == kDone; }
+
+  // Get the skipped data.  Will be empty if saveSkipped was false.
+  std::string_view GetSkipped() const {
+    return m_saveSkipped ? std::string_view{m_buf} : std::string_view{};
+  }
+
+ private:
+  SmallString<64> m_boundaryWith, m_boundaryWithout;
+
+  // Internal state
+  enum State { kBoundary, kPadding, kDone };
+  State m_state;
+  size_t m_posWith, m_posWithout;
+  enum Dashes { kUnknown, kWith, kWithout };
+  Dashes m_dashes;
+
+  // Buffer
+  bool m_saveSkipped;
+  std::string m_buf;
+};
+
+}  // namespace wpi
+
+#include "HttpUtil.inc"
+
+#endif  // WPINET_HTTPUTIL_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/HttpUtil.inc b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/HttpUtil.inc
new file mode 100644
index 0000000..f70b8dd
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/HttpUtil.inc
@@ -0,0 +1,55 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_HTTPUTIL_INC_
+#define WPINET_HTTPUTIL_INC_
+
+#include <utility>
+
+#include "wpinet/HttpUtil.h"
+
+namespace wpi {
+
+inline HttpPathRef HttpPath::drop_front(size_t n) const {
+  return HttpPathRef(*this, n);
+}
+
+template <typename T>
+HttpRequest::HttpRequest(const HttpLocation& loc, const T& extraParams)
+    : host{loc.host}, port{loc.port} {
+  StringMap<std::string_view> params;
+  for (const auto& p : loc.params) {
+    params.insert(std::make_pair(GetFirst(p), GetSecond(p)));
+  }
+  for (const auto& p : extraParams) {
+    params.insert(std::make_pair(GetFirst(p), GetSecond(p)));
+  }
+  SetPath(loc.path, params);
+  SetAuth(loc);
+}
+
+template <typename T>
+void HttpRequest::SetPath(std::string_view path_, const T& params) {
+  // Build location including query string
+  raw_svector_ostream pathOs{path};
+  pathOs << path_;
+  bool first = true;
+  for (const auto& param : params) {
+    if (first) {
+      pathOs << '?';
+      first = false;
+    } else {
+      pathOs << '&';
+    }
+    SmallString<64> escapeBuf;
+    pathOs << EscapeURI(GetFirst(param), escapeBuf, false);
+    if (!GetSecond(param).empty()) {
+      pathOs << '=' << EscapeURI(GetSecond(param), escapeBuf, false);
+    }
+  }
+}
+
+}  // namespace wpi
+
+#endif  // WPINET_HTTPUTIL_INC_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/HttpWebSocketServerConnection.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/HttpWebSocketServerConnection.h
new file mode 100644
index 0000000..4095a9c
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/HttpWebSocketServerConnection.h
@@ -0,0 +1,93 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_HTTPWEBSOCKETSERVERCONNECTION_H_
+#define WPINET_HTTPWEBSOCKETSERVERCONNECTION_H_
+
+#include <initializer_list>
+#include <memory>
+#include <span>
+#include <string>
+#include <string_view>
+
+#include <wpi/SmallVector.h>
+
+#include "wpinet/HttpServerConnection.h"
+#include "wpinet/WebSocket.h"
+#include "wpinet/WebSocketServer.h"
+#include "wpinet/uv/Stream.h"
+
+namespace wpi {
+
+/**
+ * A server-side HTTP connection that also accepts WebSocket upgrades.
+ *
+ * @tparam Derived derived class for std::enable_shared_from_this.
+ */
+template <typename Derived>
+class HttpWebSocketServerConnection
+    : public HttpServerConnection,
+      public std::enable_shared_from_this<Derived> {
+ public:
+  /**
+   * Constructor.
+   *
+   * @param stream network stream
+   * @param protocols Acceptable subprotocols
+   */
+  HttpWebSocketServerConnection(std::shared_ptr<uv::Stream> stream,
+                                std::span<const std::string_view> protocols);
+
+  /**
+   * Constructor.
+   *
+   * @param stream network stream
+   * @param protocols Acceptable subprotocols
+   */
+  HttpWebSocketServerConnection(
+      std::shared_ptr<uv::Stream> stream,
+      std::initializer_list<std::string_view> protocols)
+      : HttpWebSocketServerConnection(stream,
+                                      {protocols.begin(), protocols.end()}) {}
+
+ protected:
+  /**
+   * Check that an incoming WebSocket upgrade is okay.  This is called prior
+   * to accepting the upgrade (so prior to ProcessWsUpgrade()).
+   *
+   * The implementation should check other headers and return true if the
+   * WebSocket connection should be accepted.
+   *
+   * @param protocol negotiated subprotocol
+   */
+  virtual bool IsValidWsUpgrade(std::string_view protocol) { return true; }
+
+  /**
+   * Process an incoming WebSocket upgrade.  This is called after the header
+   * reader has been disconnected and the websocket has been accepted.
+   *
+   * The implementation should set up appropriate callbacks on the websocket
+   * object to continue communication.
+   *
+   * @note When a WebSocket upgrade occurs, the stream user data is replaced
+   *       with the websocket, and the websocket user data points to "this".
+   *       Replace the websocket user data with caution!
+   */
+  virtual void ProcessWsUpgrade() = 0;
+
+  /**
+   * WebSocket connection; not valid until ProcessWsUpgrade is called.
+   */
+  WebSocket* m_websocket = nullptr;
+
+ private:
+  WebSocketServerHelper m_helper;
+  SmallVector<std::string, 2> m_protocols;
+};
+
+}  // namespace wpi
+
+#include "HttpWebSocketServerConnection.inc"
+
+#endif  // WPINET_HTTPWEBSOCKETSERVERCONNECTION_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/HttpWebSocketServerConnection.inc b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/HttpWebSocketServerConnection.inc
new file mode 100644
index 0000000..750439d
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/HttpWebSocketServerConnection.inc
@@ -0,0 +1,57 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_HTTPWEBSOCKETSERVERCONNECTION_INC_
+#define WPINET_HTTPWEBSOCKETSERVERCONNECTION_INC_
+
+#include <memory>
+
+#include "wpinet/HttpWebSocketServerConnection.h"
+
+namespace wpi {
+
+template <typename Derived>
+HttpWebSocketServerConnection<Derived>::HttpWebSocketServerConnection(
+    std::shared_ptr<uv::Stream> stream,
+    std::span<const std::string_view> protocols)
+    : HttpServerConnection{stream},
+      m_helper{m_request},
+      m_protocols{protocols.begin(), protocols.end()} {
+  // Handle upgrade event
+  m_helper.upgrade.connect([this] {
+    // Negotiate sub-protocol
+    SmallVector<std::string_view, 2> protocols{m_protocols.begin(),
+                                               m_protocols.end()};
+    std::string_view protocol = m_helper.MatchProtocol(protocols).second;
+
+    // Check that the upgrade is valid
+    if (!IsValidWsUpgrade(protocol)) {
+      return;
+    }
+
+    // Disconnect HttpServerConnection header reader
+    m_dataConn.disconnect();
+    m_messageCompleteConn.disconnect();
+
+    // Accepting the stream may destroy this (as it replaces the stream user
+    // data), so grab a shared pointer first.
+    auto self = this->shared_from_this();
+
+    // Accept the upgrade
+    auto ws = m_helper.Accept(m_stream, protocol);
+
+    // Set this as the websocket user data to keep it around
+    ws->SetData(self);
+
+    // Store in member
+    m_websocket = ws.get();
+
+    // Call derived class function
+    ProcessWsUpgrade();
+  });
+}
+
+}  // namespace wpi
+
+#endif  // WPINET_HTTPWEBSOCKETSERVERCONNECTION_INC_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/MimeTypes.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/MimeTypes.h
new file mode 100644
index 0000000..2f5fe72
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/MimeTypes.h
@@ -0,0 +1,16 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_MIMETYPES_H_
+#define WPINET_MIMETYPES_H_
+
+#include <string_view>
+
+namespace wpi {
+
+std::string_view MimeTypeFromPath(std::string_view path);
+
+}  // namespace wpi
+
+#endif  // WPINET_MIMETYPES_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/MulticastServiceAnnouncer.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/MulticastServiceAnnouncer.h
new file mode 100644
index 0000000..2892919
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/MulticastServiceAnnouncer.h
@@ -0,0 +1,59 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <stdint.h>
+
+#ifdef __cplusplus
+#include <memory>
+#include <span>
+#include <string>
+#include <string_view>
+#include <utility>
+namespace wpi {
+class MulticastServiceAnnouncer {
+ public:
+  MulticastServiceAnnouncer(
+      std::string_view serviceName, std::string_view serviceType, int port,
+      std::span<const std::pair<std::string, std::string>> txt);
+  MulticastServiceAnnouncer(
+      std::string_view serviceName, std::string_view serviceType, int port,
+      std::span<const std::pair<std::string_view, std::string_view>> txt);
+  MulticastServiceAnnouncer(std::string_view serviceName,
+                            std::string_view serviceType, int port);
+  ~MulticastServiceAnnouncer() noexcept;
+  void Start();
+  void Stop();
+  bool HasImplementation() const;
+  struct Impl;
+
+ private:
+  std::unique_ptr<Impl> pImpl;
+};
+}  // namespace wpi
+extern "C" {
+#endif
+
+typedef unsigned int WPI_MulticastServiceAnnouncerHandle;  // NOLINT
+
+WPI_MulticastServiceAnnouncerHandle WPI_CreateMulticastServiceAnnouncer(
+    const char* serviceName, const char* serviceType, int32_t port,
+    int32_t txtCount, const char** keys, const char** values);
+
+void WPI_FreeMulticastServiceAnnouncer(
+    WPI_MulticastServiceAnnouncerHandle handle);
+
+void WPI_StartMulticastServiceAnnouncer(
+    WPI_MulticastServiceAnnouncerHandle handle);
+
+void WPI_StopMulticastServiceAnnouncer(
+    WPI_MulticastServiceAnnouncerHandle handle);
+
+int32_t WPI_GetMulticastServiceAnnouncerHasImplementation(
+    WPI_MulticastServiceAnnouncerHandle handle);
+
+#ifdef __cplusplus
+}  // extern "C"
+#endif
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/MulticastServiceResolver.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/MulticastServiceResolver.h
new file mode 100644
index 0000000..f46a8e4
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/MulticastServiceResolver.h
@@ -0,0 +1,98 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <wpi/Synchronization.h>
+
+#ifdef __cplusplus
+#include <functional>
+#include <memory>
+#include <string>
+#include <string_view>
+#include <utility>
+#include <vector>
+
+#include <wpi/mutex.h>
+namespace wpi {
+class MulticastServiceResolver {
+ public:
+  explicit MulticastServiceResolver(std::string_view serviceType);
+  ~MulticastServiceResolver() noexcept;
+  struct ServiceData {
+    unsigned int ipv4Address;
+    int port;
+    std::string serviceName;
+    std::string hostName;
+    std::vector<std::pair<std::string, std::string>> txt;
+  };
+  void Start();
+  void Stop();
+  WPI_EventHandle GetEventHandle() const { return event.GetHandle(); }
+  std::vector<ServiceData> GetData() {
+    std::scoped_lock lock{mutex};
+    event.Reset();
+    if (queue.empty()) {
+      return {};
+    }
+    std::vector<ServiceData> ret;
+    queue.swap(ret);
+    return ret;
+  }
+  bool HasImplementation() const;
+  struct Impl;
+
+ private:
+  void PushData(ServiceData&& data) {
+    std::scoped_lock lock{mutex};
+    queue.emplace_back(std::forward<ServiceData>(data));
+    event.Set();
+  }
+  wpi::Event event{true};
+  std::vector<ServiceData> queue;
+  wpi::mutex mutex;
+  std::unique_ptr<Impl> pImpl;
+};
+}  // namespace wpi
+extern "C" {
+#endif
+
+typedef unsigned int WPI_MulticastServiceResolverHandle;  // NOLINT
+
+WPI_MulticastServiceResolverHandle WPI_CreateMulticastServiceResolver(
+    const char* serviceType);
+
+void WPI_FreeMulticastServiceResolver(
+    WPI_MulticastServiceResolverHandle handle);
+
+void WPI_StartMulticastServiceResolver(
+    WPI_MulticastServiceResolverHandle handle);
+
+void WPI_StopMulticastServiceResolver(
+    WPI_MulticastServiceResolverHandle handle);
+
+int32_t WPI_GetMulticastServiceResolverHasImplementation(
+    WPI_MulticastServiceResolverHandle handle);
+
+WPI_EventHandle WPI_GetMulticastServiceResolverEventHandle(
+    WPI_MulticastServiceResolverHandle handle);
+
+typedef struct WPI_ServiceData {  // NOLINT
+  uint32_t ipv4Address;
+  int32_t port;
+  const char* serviceName;
+  const char* hostName;
+  int32_t txtCount;
+  const char** txtKeys;
+  const char** txtValues;
+} WPI_ServiceData;
+
+WPI_ServiceData* WPI_GetMulticastServiceResolverData(
+    WPI_MulticastServiceResolverHandle handle, int32_t* dataCount);
+
+void WPI_FreeServiceData(WPI_ServiceData* serviceData, int32_t length);
+
+#ifdef __cplusplus
+}  // extern "C"
+#endif
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/NetworkAcceptor.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/NetworkAcceptor.h
new file mode 100644
index 0000000..6fe2e3b
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/NetworkAcceptor.h
@@ -0,0 +1,29 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_NETWORKACCEPTOR_H_
+#define WPINET_NETWORKACCEPTOR_H_
+
+#include <memory>
+
+#include "wpinet/NetworkStream.h"
+
+namespace wpi {
+
+class NetworkAcceptor {
+ public:
+  NetworkAcceptor() = default;
+  virtual ~NetworkAcceptor() = default;
+
+  virtual int start() = 0;
+  virtual void shutdown() = 0;
+  virtual std::unique_ptr<NetworkStream> accept() = 0;
+
+  NetworkAcceptor(const NetworkAcceptor&) = delete;
+  NetworkAcceptor& operator=(const NetworkAcceptor&) = delete;
+};
+
+}  // namespace wpi
+
+#endif  // WPINET_NETWORKACCEPTOR_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/NetworkStream.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/NetworkStream.h
new file mode 100644
index 0000000..8329b88
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/NetworkStream.h
@@ -0,0 +1,44 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_NETWORKSTREAM_H_
+#define WPINET_NETWORKSTREAM_H_
+
+#include <cstddef>
+#include <string_view>
+
+namespace wpi {
+
+class NetworkStream {
+ public:
+  NetworkStream() = default;
+  virtual ~NetworkStream() = default;
+
+  enum Error {
+    kConnectionClosed = 0,
+    kConnectionReset = -1,
+    kConnectionTimedOut = -2,
+    kWouldBlock = -3
+  };
+
+  virtual size_t send(const char* buffer, size_t len, Error* err) = 0;
+  virtual size_t receive(char* buffer, size_t len, Error* err,
+                         int timeout = 0) = 0;
+  virtual void close() = 0;
+
+  virtual std::string_view getPeerIP() const = 0;
+  virtual int getPeerPort() const = 0;
+  virtual void setNoDelay() = 0;
+
+  // returns false on failure
+  virtual bool setBlocking(bool enabled) = 0;
+  virtual int getNativeHandle() const = 0;
+
+  NetworkStream(const NetworkStream&) = delete;
+  NetworkStream& operator=(const NetworkStream&) = delete;
+};
+
+}  // namespace wpi
+
+#endif  // WPINET_NETWORKSTREAM_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/ParallelTcpConnector.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/ParallelTcpConnector.h
new file mode 100644
index 0000000..e7bc953
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/ParallelTcpConnector.h
@@ -0,0 +1,119 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <stdint.h>
+
+#include <functional>
+#include <memory>
+#include <span>
+#include <string>
+#include <utility>
+#include <vector>
+
+#include "wpinet/uv/Timer.h"
+
+namespace wpi {
+
+class Logger;
+
+namespace uv {
+class GetAddrInfoReq;
+class Loop;
+class Tcp;
+class Timer;
+}  // namespace uv
+
+/**
+ * Parallel TCP connector.  Attempts parallel resolution and connection to
+ * multiple servers with automatic retry if none connect.
+ *
+ * Each successful TCP connection results in a call to the connected callback.
+ * For correct operation, the consuming code (either the connected callback or
+ * e.g. task it starts) must call Succeeded() to indicate if the connection has
+ * succeeded prior to the reconnect rate timeout.  A successful connection
+ * results in the connector terminating all other connection attempts.
+ *
+ * After the reconnect rate times out, all remaining active connection attempts
+ * are canceled and new ones started.
+ */
+class ParallelTcpConnector
+    : public std::enable_shared_from_this<ParallelTcpConnector> {
+  struct private_init {};
+
+ public:
+  /**
+   * Create.
+   *
+   * @param loop loop
+   * @param reconnectRate how long to wait after starting connection attempts
+   *                      to cancel and attempt connecting again
+   * @param logger logger
+   * @param connected callback function when a connection succeeds; may be
+   *                  called multiple times if it does not call Succeeded()
+   *                  before returning
+   * @return Parallel connector
+   */
+  static std::shared_ptr<ParallelTcpConnector> Create(
+      wpi::uv::Loop& loop, wpi::uv::Timer::Time reconnectRate,
+      wpi::Logger& logger, std::function<void(wpi::uv::Tcp& tcp)> connected) {
+    return std::make_shared<ParallelTcpConnector>(
+        loop, reconnectRate, logger, std::move(connected), private_init{});
+  }
+
+  ParallelTcpConnector(wpi::uv::Loop& loop, wpi::uv::Timer::Time reconnectRate,
+                       wpi::Logger& logger,
+                       std::function<void(wpi::uv::Tcp& tcp)> connected,
+                       const private_init&);
+  ~ParallelTcpConnector();
+
+  ParallelTcpConnector(const ParallelTcpConnector&) = delete;
+  ParallelTcpConnector& operator=(const ParallelTcpConnector&) = delete;
+
+  /**
+   * Closes resources, canceling all pending action attempts.
+   */
+  void Close();
+
+  /**
+   * Changes the servers/ports to connect to.  Starts connection attempts if not
+   * already connected.
+   *
+   * @param servers array of server/port pairs
+   */
+  void SetServers(
+      std::span<const std::pair<std::string, unsigned int>> servers);
+
+  /**
+   * Tells the parallel connector that the current connection has terminated and
+   * it is necessary to start reconnection attempts.
+   */
+  void Disconnected();
+
+  /**
+   * Tells the parallel connector that a particular connection has succeeded and
+   * it should stop trying to connect.
+   *
+   * @param tcp connection passed to connected callback
+   */
+  void Succeeded(wpi::uv::Tcp& tcp);
+
+ private:
+  bool IsConnected() const { return m_isConnected || m_servers.empty(); }
+  void Connect();
+  void CancelAll(wpi::uv::Tcp* except = nullptr);
+
+  wpi::uv::Loop& m_loop;
+  wpi::Logger& m_logger;
+  wpi::uv::Timer::Time m_reconnectRate;
+  std::function<void(wpi::uv::Tcp& tcp)> m_connected;
+  std::shared_ptr<wpi::uv::Timer> m_reconnectTimer;
+  std::vector<std::pair<std::string, unsigned int>> m_servers;
+  std::vector<std::weak_ptr<wpi::uv::GetAddrInfoReq>> m_resolvers;
+  std::vector<std::weak_ptr<wpi::uv::Tcp>> m_attempts;
+  bool m_isConnected{false};
+};
+
+}  // namespace wpi
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/PortForwarder.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/PortForwarder.h
new file mode 100644
index 0000000..14453a3
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/PortForwarder.h
@@ -0,0 +1,59 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_PORTFORWARDER_H_
+#define WPINET_PORTFORWARDER_H_
+
+#pragma once
+
+#include <memory>
+#include <string_view>
+
+namespace wpi {
+
+/**
+ * Forward ports to another host.  This is primarily useful for accessing
+ * Ethernet-connected devices from a computer tethered to the RoboRIO USB port.
+ */
+class PortForwarder {
+ public:
+  PortForwarder(const PortForwarder&) = delete;
+  PortForwarder& operator=(const PortForwarder&) = delete;
+
+  /**
+   * Get an instance of the PortForwarder class.
+   *
+   * This is a singleton to guarantee that there is only a single instance
+   * regardless of how many times GetInstance is called.
+   */
+  static PortForwarder& GetInstance();
+
+  /**
+   * Forward a local TCP port to a remote host and port.
+   * Note that local ports less than 1024 won't work as a normal user.
+   *
+   * @param port       local port number
+   * @param remoteHost remote IP address / DNS name
+   * @param remotePort remote port number
+   */
+  void Add(unsigned int port, std::string_view remoteHost,
+           unsigned int remotePort);
+
+  /**
+   * Stop TCP forwarding on a port.
+   *
+   * @param port local port number
+   */
+  void Remove(unsigned int port);
+
+ private:
+  PortForwarder();
+
+  struct Impl;
+  std::unique_ptr<Impl> m_impl;
+};
+
+}  // namespace wpi
+
+#endif  // WPINET_PORTFORWARDER_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/SocketError.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/SocketError.h
new file mode 100644
index 0000000..c944b0c
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/SocketError.h
@@ -0,0 +1,22 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_SOCKETERROR_H_
+#define WPINET_SOCKETERROR_H_
+
+#include <string>
+
+namespace wpi {
+
+int SocketErrno();
+
+std::string SocketStrerror(int code);
+
+inline std::string SocketStrerror() {
+  return SocketStrerror(SocketErrno());
+}
+
+}  // namespace wpi
+
+#endif  // WPINET_SOCKETERROR_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/UDPClient.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/UDPClient.h
new file mode 100644
index 0000000..55e5702
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/UDPClient.h
@@ -0,0 +1,49 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_UDPCLIENT_H_
+#define WPINET_UDPCLIENT_H_
+
+#include <span>
+#include <string>
+#include <string_view>
+
+#include <wpi/SmallVector.h>
+#include <wpi/mutex.h>
+
+namespace wpi {
+
+class Logger;
+
+class UDPClient {
+  int m_lsd;
+  int m_port;
+  std::string m_address;
+  Logger& m_logger;
+
+ public:
+  explicit UDPClient(Logger& logger);
+  UDPClient(std::string_view address, Logger& logger);
+  UDPClient(const UDPClient& other) = delete;
+  UDPClient(UDPClient&& other);
+  ~UDPClient();
+
+  UDPClient& operator=(const UDPClient& other) = delete;
+  UDPClient& operator=(UDPClient&& other);
+
+  int start();
+  int start(int port);
+  void shutdown();
+  // The passed in address MUST be a resolved IP address.
+  int send(std::span<const uint8_t> data, std::string_view server, int port);
+  int send(std::string_view data, std::string_view server, int port);
+  int receive(uint8_t* data_received, int receive_len);
+  int receive(uint8_t* data_received, int receive_len,
+              SmallVectorImpl<char>* addr_received, int* port_received);
+  int set_timeout(double timeout);
+};
+
+}  // namespace wpi
+
+#endif  // WPINET_UDPCLIENT_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/UrlParser.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/UrlParser.h
new file mode 100644
index 0000000..92fd330
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/UrlParser.h
@@ -0,0 +1,96 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_URLPARSER_H_
+#define WPINET_URLPARSER_H_
+
+#include <string_view>
+
+#include <wpi/StringExtras.h>
+
+#include "wpinet/http_parser.h"
+
+namespace wpi {
+
+/**
+ * Parses a URL into its constiuent components.
+ * `schema://userinfo@host:port/the/path?query#fragment`
+ */
+class UrlParser {
+ public:
+  /**
+   * Parse a URL.
+   * @param in input
+   * @param isConnect
+   */
+  UrlParser(std::string_view in, bool isConnect) {
+    m_data = in;
+    http_parser_url_init(&m_url);
+    m_error = http_parser_parse_url(in.data(), in.size(), isConnect, &m_url);
+  }
+
+  /**
+   * Determine if the URL is valid (e.g. the parse was successful).
+   */
+  bool IsValid() const { return !m_error; }
+
+  bool HasSchema() const { return (m_url.field_set & (1 << UF_SCHEMA)) != 0; }
+
+  bool HasHost() const { return (m_url.field_set & (1 << UF_HOST)) != 0; }
+
+  bool HasPort() const { return (m_url.field_set & (1 << UF_PORT)) != 0; }
+
+  bool HasPath() const { return (m_url.field_set & (1 << UF_PATH)) != 0; }
+
+  bool HasQuery() const { return (m_url.field_set & (1 << UF_QUERY)) != 0; }
+
+  bool HasFragment() const {
+    return (m_url.field_set & (1 << UF_FRAGMENT)) != 0;
+  }
+
+  bool HasUserInfo() const {
+    return (m_url.field_set & (1 << UF_USERINFO)) != 0;
+  }
+
+  std::string_view GetSchema() const {
+    return wpi::substr(m_data, m_url.field_data[UF_SCHEMA].off,
+                       m_url.field_data[UF_SCHEMA].len);
+  }
+
+  std::string_view GetHost() const {
+    return wpi::substr(m_data, m_url.field_data[UF_HOST].off,
+                       m_url.field_data[UF_HOST].len);
+  }
+
+  unsigned int GetPort() const { return m_url.port; }
+
+  std::string_view GetPath() const {
+    return wpi::substr(m_data, m_url.field_data[UF_PATH].off,
+                       m_url.field_data[UF_PATH].len);
+  }
+
+  std::string_view GetQuery() const {
+    return wpi::substr(m_data, m_url.field_data[UF_QUERY].off,
+                       m_url.field_data[UF_QUERY].len);
+  }
+
+  std::string_view GetFragment() const {
+    return wpi::substr(m_data, m_url.field_data[UF_FRAGMENT].off,
+                       m_url.field_data[UF_FRAGMENT].len);
+  }
+
+  std::string_view GetUserInfo() const {
+    return wpi::substr(m_data, m_url.field_data[UF_USERINFO].off,
+                       m_url.field_data[UF_USERINFO].len);
+  }
+
+ private:
+  bool m_error;
+  std::string_view m_data;
+  http_parser_url m_url;
+};
+
+}  // namespace wpi
+
+#endif  // WPINET_URLPARSER_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/WebSocket.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/WebSocket.h
new file mode 100644
index 0000000..1f295c9
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/WebSocket.h
@@ -0,0 +1,518 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_WEBSOCKET_H_
+#define WPINET_WEBSOCKET_H_
+
+#include <stdint.h>
+
+#include <functional>
+#include <initializer_list>
+#include <memory>
+#include <span>
+#include <string>
+#include <string_view>
+#include <utility>
+
+#include <wpi/Signal.h>
+#include <wpi/SmallVector.h>
+
+#include "wpinet/uv/Buffer.h"
+#include "wpinet/uv/Error.h"
+#include "wpinet/uv/Timer.h"
+
+namespace wpi {
+
+namespace uv {
+class Stream;
+}  // namespace uv
+
+/**
+ * RFC 6455 compliant WebSocket client and server implementation.
+ */
+class WebSocket : public std::enable_shared_from_this<WebSocket> {
+  struct private_init {};
+
+  static constexpr uint8_t kOpCont = 0x00;
+  static constexpr uint8_t kOpText = 0x01;
+  static constexpr uint8_t kOpBinary = 0x02;
+  static constexpr uint8_t kOpClose = 0x08;
+  static constexpr uint8_t kOpPing = 0x09;
+  static constexpr uint8_t kOpPong = 0x0A;
+  static constexpr uint8_t kOpMask = 0x0F;
+  static constexpr uint8_t kFlagFin = 0x80;
+
+ public:
+  WebSocket(uv::Stream& stream, bool server, const private_init&);
+  WebSocket(const WebSocket&) = delete;
+  WebSocket(WebSocket&&) = delete;
+  WebSocket& operator=(const WebSocket&) = delete;
+  WebSocket& operator=(WebSocket&&) = delete;
+  ~WebSocket();
+
+  /**
+   * Connection states.
+   */
+  enum State {
+    /** The connection is not yet open. */
+    CONNECTING = 0,
+    /** The connection is open and ready to communicate. */
+    OPEN,
+    /** The connection is in the process of closing. */
+    CLOSING,
+    /** The connection failed. */
+    FAILED,
+    /** The connection is closed. */
+    CLOSED
+  };
+
+  /**
+   * Client connection options.
+   */
+  struct ClientOptions {
+    ClientOptions() : handshakeTimeout{(uv::Timer::Time::max)()} {}
+
+    /** Timeout for the handshake request. */
+    uv::Timer::Time handshakeTimeout;  // NOLINT
+
+    /** Additional headers to include in handshake. */
+    std::span<const std::pair<std::string_view, std::string_view>> extraHeaders;
+  };
+
+  /**
+   * Frame.  Used by SendFrames().
+   */
+  struct Frame {
+    static constexpr uint8_t kText = kFlagFin | kOpText;
+    static constexpr uint8_t kBinary = kFlagFin | kOpBinary;
+    static constexpr uint8_t kTextFragment = kOpText;
+    static constexpr uint8_t kBinaryFragment = kOpBinary;
+    static constexpr uint8_t kFragment = kOpCont;
+    static constexpr uint8_t kFinalFragment = kFlagFin | kOpCont;
+    static constexpr uint8_t kPing = kFlagFin | kOpPing;
+    static constexpr uint8_t kPong = kFlagFin | kOpPong;
+
+    Frame(uint8_t opcode, std::span<const uv::Buffer> data)
+        : opcode{opcode}, data{data} {}
+
+    uint8_t opcode;
+    std::span<const uv::Buffer> data;
+  };
+
+  /**
+   * Starts a client connection by performing the initial client handshake.
+   * An open event is emitted when the handshake completes.
+   * This sets the stream user data to the websocket.
+   * @param stream Connection stream
+   * @param uri The Request-URI to send
+   * @param host The host or host:port to send
+   * @param protocols The list of subprotocols
+   * @param options Handshake options
+   */
+  static std::shared_ptr<WebSocket> CreateClient(
+      uv::Stream& stream, std::string_view uri, std::string_view host,
+      std::span<const std::string_view> protocols = {},
+      const ClientOptions& options = {});
+
+  /**
+   * Starts a client connection by performing the initial client handshake.
+   * An open event is emitted when the handshake completes.
+   * This sets the stream user data to the websocket.
+   * @param stream Connection stream
+   * @param uri The Request-URI to send
+   * @param host The host or host:port to send
+   * @param protocols The list of subprotocols
+   * @param options Handshake options
+   */
+  static std::shared_ptr<WebSocket> CreateClient(
+      uv::Stream& stream, std::string_view uri, std::string_view host,
+      std::initializer_list<std::string_view> protocols,
+      const ClientOptions& options = {}) {
+    return CreateClient(stream, uri, host, {protocols.begin(), protocols.end()},
+                        options);
+  }
+
+  /**
+   * Starts a server connection by performing the initial server side handshake.
+   * This should be called after the HTTP headers have been received.
+   * An open event is emitted when the handshake completes.
+   * This sets the stream user data to the websocket.
+   * @param stream Connection stream
+   * @param key The value of the Sec-WebSocket-Key header field in the client
+   *            request
+   * @param version The value of the Sec-WebSocket-Version header field in the
+   *                client request
+   * @param protocol The subprotocol to send to the client (in the
+   *                 Sec-WebSocket-Protocol header field).
+   */
+  static std::shared_ptr<WebSocket> CreateServer(
+      uv::Stream& stream, std::string_view key, std::string_view version,
+      std::string_view protocol = {});
+
+  /**
+   * Get connection state.
+   */
+  State GetState() const { return m_state; }
+
+  /**
+   * Return if the connection is open.  Messages can only be sent on open
+   * connections.
+   */
+  bool IsOpen() const { return m_state == OPEN; }
+
+  /**
+   * Get the underlying stream.
+   */
+  uv::Stream& GetStream() const { return m_stream; }
+
+  /**
+   * Get the selected sub-protocol.  Only valid in or after the open() event.
+   */
+  std::string_view GetProtocol() const { return m_protocol; }
+
+  /**
+   * Set the maximum message size.  Default is 128 KB.  If configured to combine
+   * fragments this maximum applies to the entire message (all combined
+   * fragments).
+   * @param size Maximum message size in bytes
+   */
+  void SetMaxMessageSize(size_t size) { m_maxMessageSize = size; }
+
+  /**
+   * Set whether or not fragmented frames should be combined.  Default is to
+   * combine.  If fragmented frames are combined, the text and binary callbacks
+   * will always have the second parameter (fin) set to true.
+   * @param combine True if fragmented frames should be combined.
+   */
+  void SetCombineFragments(bool combine) { m_combineFragments = combine; }
+
+  /**
+   * Initiate a closing handshake.
+   * @param code A numeric status code (defaults to 1005, no status code)
+   * @param reason A human-readable string explaining why the connection is
+   *               closing (optional).
+   */
+  void Close(uint16_t code = 1005, std::string_view reason = {});
+
+  /**
+   * Send a text message.
+   * @param data UTF-8 encoded data to send
+   * @param callback Callback which is invoked when the write completes.
+   */
+  void SendText(
+      std::span<const uv::Buffer> data,
+      std::function<void(std::span<uv::Buffer>, uv::Error)> callback) {
+    Send(kFlagFin | kOpText, data, std::move(callback));
+  }
+
+  /**
+   * Send a text message.
+   * @param data UTF-8 encoded data to send
+   * @param callback Callback which is invoked when the write completes.
+   */
+  void SendText(
+      std::initializer_list<uv::Buffer> data,
+      std::function<void(std::span<uv::Buffer>, uv::Error)> callback) {
+    SendText({data.begin(), data.end()}, std::move(callback));
+  }
+
+  /**
+   * Send a binary message.
+   * @param data Data to send
+   * @param callback Callback which is invoked when the write completes.
+   */
+  void SendBinary(
+      std::span<const uv::Buffer> data,
+      std::function<void(std::span<uv::Buffer>, uv::Error)> callback) {
+    Send(kFlagFin | kOpBinary, data, std::move(callback));
+  }
+
+  /**
+   * Send a binary message.
+   * @param data Data to send
+   * @param callback Callback which is invoked when the write completes.
+   */
+  void SendBinary(
+      std::initializer_list<uv::Buffer> data,
+      std::function<void(std::span<uv::Buffer>, uv::Error)> callback) {
+    SendBinary({data.begin(), data.end()}, std::move(callback));
+  }
+
+  /**
+   * Send a text message fragment.  This must be followed by one or more
+   * SendFragment() calls, where the last one has fin=True, to complete the
+   * message.
+   * @param data UTF-8 encoded data to send
+   * @param callback Callback which is invoked when the write completes.
+   */
+  void SendTextFragment(
+      std::span<const uv::Buffer> data,
+      std::function<void(std::span<uv::Buffer>, uv::Error)> callback) {
+    Send(kOpText, data, std::move(callback));
+  }
+
+  /**
+   * Send a text message fragment.  This must be followed by one or more
+   * SendFragment() calls, where the last one has fin=True, to complete the
+   * message.
+   * @param data UTF-8 encoded data to send
+   * @param callback Callback which is invoked when the write completes.
+   */
+  void SendTextFragment(
+      std::initializer_list<uv::Buffer> data,
+      std::function<void(std::span<uv::Buffer>, uv::Error)> callback) {
+    SendTextFragment({data.begin(), data.end()}, std::move(callback));
+  }
+
+  /**
+   * Send a text message fragment.  This must be followed by one or more
+   * SendFragment() calls, where the last one has fin=True, to complete the
+   * message.
+   * @param data Data to send
+   * @param callback Callback which is invoked when the write completes.
+   */
+  void SendBinaryFragment(
+      std::span<const uv::Buffer> data,
+      std::function<void(std::span<uv::Buffer>, uv::Error)> callback) {
+    Send(kOpBinary, data, std::move(callback));
+  }
+
+  /**
+   * Send a text message fragment.  This must be followed by one or more
+   * SendFragment() calls, where the last one has fin=True, to complete the
+   * message.
+   * @param data Data to send
+   * @param callback Callback which is invoked when the write completes.
+   */
+  void SendBinaryFragment(
+      std::initializer_list<uv::Buffer> data,
+      std::function<void(std::span<uv::Buffer>, uv::Error)> callback) {
+    SendBinaryFragment({data.begin(), data.end()}, std::move(callback));
+  }
+
+  /**
+   * Send a continuation frame.  This is used to send additional parts of a
+   * message started with SendTextFragment() or SendBinaryFragment().
+   * @param data Data to send
+   * @param fin Set to true if this is the final fragment of the message
+   * @param callback Callback which is invoked when the write completes.
+   */
+  void SendFragment(
+      std::span<const uv::Buffer> data, bool fin,
+      std::function<void(std::span<uv::Buffer>, uv::Error)> callback) {
+    Send(kOpCont | (fin ? kFlagFin : 0), data, std::move(callback));
+  }
+
+  /**
+   * Send a continuation frame.  This is used to send additional parts of a
+   * message started with SendTextFragment() or SendBinaryFragment().
+   * @param data Data to send
+   * @param fin Set to true if this is the final fragment of the message
+   * @param callback Callback which is invoked when the write completes.
+   */
+  void SendFragment(
+      std::initializer_list<uv::Buffer> data, bool fin,
+      std::function<void(std::span<uv::Buffer>, uv::Error)> callback) {
+    SendFragment({data.begin(), data.end()}, fin, std::move(callback));
+  }
+
+  /**
+   * Send a ping frame with no data.
+   * @param callback Optional callback which is invoked when the ping frame
+   *                 write completes.
+   */
+  void SendPing(std::function<void(uv::Error)> callback = nullptr) {
+    SendPing({}, [f = std::move(callback)](auto bufs, uv::Error err) {
+      if (f) {
+        f(err);
+      }
+    });
+  }
+
+  /**
+   * Send a ping frame.
+   * @param data Data to send in the ping frame
+   * @param callback Callback which is invoked when the ping frame
+   *                 write completes.
+   */
+  void SendPing(
+      std::span<const uv::Buffer> data,
+      std::function<void(std::span<uv::Buffer>, uv::Error)> callback) {
+    Send(kFlagFin | kOpPing, data, std::move(callback));
+  }
+
+  /**
+   * Send a ping frame.
+   * @param data Data to send in the ping frame
+   * @param callback Callback which is invoked when the ping frame
+   *                 write completes.
+   */
+  void SendPing(
+      std::initializer_list<uv::Buffer> data,
+      std::function<void(std::span<uv::Buffer>, uv::Error)> callback) {
+    SendPing({data.begin(), data.end()}, std::move(callback));
+  }
+
+  /**
+   * Send a pong frame with no data.
+   * @param callback Optional callback which is invoked when the pong frame
+   *                 write completes.
+   */
+  void SendPong(std::function<void(uv::Error)> callback = nullptr) {
+    SendPong({}, [f = std::move(callback)](auto bufs, uv::Error err) {
+      if (f) {
+        f(err);
+      }
+    });
+  }
+
+  /**
+   * Send a pong frame.
+   * @param data Data to send in the pong frame
+   * @param callback Callback which is invoked when the pong frame
+   *                 write completes.
+   */
+  void SendPong(
+      std::span<const uv::Buffer> data,
+      std::function<void(std::span<uv::Buffer>, uv::Error)> callback) {
+    Send(kFlagFin | kOpPong, data, std::move(callback));
+  }
+
+  /**
+   * Send a pong frame.
+   * @param data Data to send in the pong frame
+   * @param callback Callback which is invoked when the pong frame
+   *                 write completes.
+   */
+  void SendPong(
+      std::initializer_list<uv::Buffer> data,
+      std::function<void(std::span<uv::Buffer>, uv::Error)> callback) {
+    SendPong({data.begin(), data.end()}, std::move(callback));
+  }
+
+  /**
+   * Send multiple frames.
+   *
+   * @param frames Frame type/data pairs
+   * @param callback Callback which is invoked when the write completes.
+   */
+  void SendFrames(
+      std::span<const Frame> frames,
+      std::function<void(std::span<uv::Buffer>, uv::Error)> callback);
+
+  /**
+   * Fail the connection.
+   */
+  void Fail(uint16_t code = 1002, std::string_view reason = "protocol error");
+
+  /**
+   * Forcibly close the connection.
+   */
+  void Terminate(uint16_t code = 1006, std::string_view reason = "terminated");
+
+  /**
+   * Gets user-defined data.
+   * @return User-defined data if any, nullptr otherwise.
+   */
+  template <typename T = void>
+  std::shared_ptr<T> GetData() const {
+    return std::static_pointer_cast<T>(m_data);
+  }
+
+  /**
+   * Sets user-defined data.
+   * @param data User-defined arbitrary data.
+   */
+  void SetData(std::shared_ptr<void> data) { m_data = std::move(data); }
+
+  /**
+   * Shuts down and closes the underlying stream.
+   */
+  void Shutdown();
+
+  /**
+   * Open event.  Emitted when the connection is open and ready to communicate.
+   * The parameter is the selected subprotocol.
+   */
+  sig::Signal<std::string_view> open;
+
+  /**
+   * Close event.  Emitted when the connection is closed.  The first parameter
+   * is a numeric value indicating the status code explaining why the connection
+   * has been closed.  The second parameter is a human-readable string
+   * explaining the reason why the connection has been closed.
+   */
+  sig::Signal<uint16_t, std::string_view> closed;
+
+  /**
+   * Text message event.  Emitted when a text message is received.
+   * The first parameter is the data, the second parameter is true if the
+   * data is the last fragment of the message.
+   */
+  sig::Signal<std::string_view, bool> text;
+
+  /**
+   * Binary message event.  Emitted when a binary message is received.
+   * The first parameter is the data, the second parameter is true if the
+   * data is the last fragment of the message.
+   */
+  sig::Signal<std::span<const uint8_t>, bool> binary;
+
+  /**
+   * Ping event.  Emitted when a ping message is received.
+   */
+  sig::Signal<std::span<const uint8_t>> ping;
+
+  /**
+   * Pong event.  Emitted when a pong message is received.
+   */
+  sig::Signal<std::span<const uint8_t>> pong;
+
+ private:
+  // user data
+  std::shared_ptr<void> m_data;
+
+  // constructor parameters
+  uv::Stream& m_stream;
+  bool m_server;
+
+  // subprotocol, set via constructor (server) or handshake (client)
+  std::string m_protocol;
+
+  // user-settable configuration
+  size_t m_maxMessageSize = 128 * 1024;
+  bool m_combineFragments = true;
+
+  // operating state
+  State m_state = CONNECTING;
+
+  // incoming message buffers/state
+  SmallVector<uint8_t, 14> m_header;
+  size_t m_headerSize = 0;
+  SmallVector<uint8_t, 1024> m_payload;
+  size_t m_frameStart = 0;
+  uint64_t m_frameSize = UINT64_MAX;
+  uint8_t m_fragmentOpcode = 0;
+
+  // temporary data used only during client handshake
+  class ClientHandshakeData;
+  std::unique_ptr<ClientHandshakeData> m_clientHandshake;
+
+  void StartClient(std::string_view uri, std::string_view host,
+                   std::span<const std::string_view> protocols,
+                   const ClientOptions& options);
+  void StartServer(std::string_view key, std::string_view version,
+                   std::string_view protocol);
+  void SendClose(uint16_t code, std::string_view reason);
+  void SetClosed(uint16_t code, std::string_view reason, bool failed = false);
+  void HandleIncoming(uv::Buffer& buf, size_t size);
+  void Send(uint8_t opcode, std::span<const uv::Buffer> data,
+            std::function<void(std::span<uv::Buffer>, uv::Error)> callback) {
+    SendFrames({{Frame{opcode, data}}}, std::move(callback));
+  }
+};
+
+}  // namespace wpi
+
+#endif  // WPINET_WEBSOCKET_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/WebSocketServer.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/WebSocketServer.h
new file mode 100644
index 0000000..9d655d3
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/WebSocketServer.h
@@ -0,0 +1,179 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_WEBSOCKETSERVER_H_
+#define WPINET_WEBSOCKETSERVER_H_
+
+#include <functional>
+#include <initializer_list>
+#include <memory>
+#include <span>
+#include <string>
+#include <string_view>
+#include <utility>
+
+#include <wpi/Signal.h>
+#include <wpi/SmallString.h>
+#include <wpi/SmallVector.h>
+
+#include "wpinet/HttpParser.h"
+#include "wpinet/WebSocket.h"
+
+namespace wpi {
+
+namespace uv {
+class Stream;
+}  // namespace uv
+
+/**
+ * WebSocket HTTP server helper.  Handles websocket-specific headers.  User
+ * must provide the HttpParser.
+ */
+class WebSocketServerHelper {
+ public:
+  /**
+   * Constructor.
+   * @param req HttpParser for request
+   */
+  explicit WebSocketServerHelper(HttpParser& req);
+
+  /**
+   * Get whether or not this was a websocket upgrade.
+   * Only valid during and after the upgrade event.
+   */
+  bool IsWebsocket() const { return m_websocket; }
+
+  /**
+   * Try to find a match to the list of sub-protocols provided by the client.
+   * The list is priority ordered, so the first match wins.
+   * Only valid during and after the upgrade event.
+   * @param protocols Acceptable protocols
+   * @return Pair; first item is true if a match was made, false if not.
+   *         Second item is the matched protocol if a match was made, otherwise
+   *         is empty.
+   */
+  std::pair<bool, std::string_view> MatchProtocol(
+      std::span<const std::string_view> protocols);
+
+  /**
+   * Try to find a match to the list of sub-protocols provided by the client.
+   * The list is priority ordered, so the first match wins.
+   * Only valid during and after the upgrade event.
+   * @param protocols Acceptable protocols
+   * @return Pair; first item is true if a match was made, false if not.
+   *         Second item is the matched protocol if a match was made, otherwise
+   *         is empty.
+   */
+  std::pair<bool, std::string_view> MatchProtocol(
+      std::initializer_list<std::string_view> protocols) {
+    return MatchProtocol({protocols.begin(), protocols.end()});
+  }
+
+  /**
+   * Accept the upgrade.  Disconnect other readers (such as the HttpParser
+   * reader) before calling this.  See also WebSocket::CreateServer().
+   * @param stream Connection stream
+   * @param protocol The subprotocol to send to the client
+   */
+  std::shared_ptr<WebSocket> Accept(uv::Stream& stream,
+                                    std::string_view protocol = {}) {
+    return WebSocket::CreateServer(stream, m_key, m_version, protocol);
+  }
+
+  bool IsUpgrade() const { return m_gotHost && m_websocket; }
+
+  /**
+   * Upgrade event.  Call Accept() to accept the upgrade.
+   */
+  sig::Signal<> upgrade;
+
+ private:
+  bool m_gotHost = false;
+  bool m_websocket = false;
+  SmallVector<std::string, 2> m_protocols;
+  SmallString<64> m_key;
+  SmallString<16> m_version;
+};
+
+/**
+ * Dedicated WebSocket server.
+ */
+class WebSocketServer : public std::enable_shared_from_this<WebSocketServer> {
+  struct private_init {};
+
+ public:
+  /**
+   * Server options.
+   */
+  struct ServerOptions {
+    /**
+     * Checker for URL.  Return true if URL should be accepted.  By default all
+     * URLs are accepted.
+     */
+    std::function<bool(std::string_view)> checkUrl;
+
+    /**
+     * Checker for Host header.  Return true if Host should be accepted.  By
+     * default all hosts are accepted.
+     */
+    std::function<bool(std::string_view)> checkHost;
+  };
+
+  /**
+   * Private constructor.
+   */
+  WebSocketServer(uv::Stream& stream,
+                  std::span<const std::string_view> protocols,
+                  ServerOptions options, const private_init&);
+
+  /**
+   * Starts a dedicated WebSocket server on the provided connection.  The
+   * connection should be an accepted client stream.
+   * This also sets the stream user data to the socket server.
+   * A connected event is emitted when the connection is opened.
+   * @param stream Connection stream
+   * @param protocols Acceptable subprotocols
+   * @param options Handshake options
+   */
+  static std::shared_ptr<WebSocketServer> Create(
+      uv::Stream& stream, std::span<const std::string_view> protocols = {},
+      const ServerOptions& options = {});
+
+  /**
+   * Starts a dedicated WebSocket server on the provided connection.  The
+   * connection should be an accepted client stream.
+   * This also sets the stream user data to the socket server.
+   * A connected event is emitted when the connection is opened.
+   * @param stream Connection stream
+   * @param protocols Acceptable subprotocols
+   * @param options Handshake options
+   */
+  static std::shared_ptr<WebSocketServer> Create(
+      uv::Stream& stream, std::initializer_list<std::string_view> protocols,
+      const ServerOptions& options = {}) {
+    return Create(stream, {protocols.begin(), protocols.end()}, options);
+  }
+
+  /**
+   * Connected event.  First parameter is the URL, second is the websocket.
+   */
+  sig::Signal<std::string_view, WebSocket&> connected;
+
+ private:
+  uv::Stream& m_stream;
+  HttpParser m_req{HttpParser::kRequest};
+  WebSocketServerHelper m_helper;
+  SmallVector<std::string, 2> m_protocols;
+  ServerOptions m_options;
+  bool m_aborted = false;
+  sig::ScopedConnection m_dataConn;
+  sig::ScopedConnection m_errorConn;
+  sig::ScopedConnection m_endConn;
+
+  void Abort(uint16_t code, std::string_view reason);
+};
+
+}  // namespace wpi
+
+#endif  // WPINET_WEBSOCKETSERVER_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/WorkerThread.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/WorkerThread.h
new file mode 100644
index 0000000..b5438cc
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/WorkerThread.h
@@ -0,0 +1,286 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_WORKERTHREAD_H_
+#define WPINET_WORKERTHREAD_H_
+
+#include <functional>
+#include <memory>
+#include <tuple>
+#include <utility>
+#include <vector>
+
+#include <wpi/SafeThread.h>
+#include <wpi/future.h>
+
+#include "wpinet/uv/Async.h"
+
+namespace wpi {
+
+namespace detail {
+
+template <typename R>
+struct WorkerThreadAsync {
+  using AfterWorkFunction = std::function<void(R)>;
+
+  ~WorkerThreadAsync() { UnsetLoop(); }
+
+  void SetLoop(uv::Loop& loop) {
+    auto async = uv::Async<AfterWorkFunction, R>::Create(loop);
+    async->wakeup.connect(
+        [](AfterWorkFunction func, R result) { func(result); });
+    m_async = async;
+  }
+
+  void UnsetLoop() {
+    if (auto async = m_async.lock()) {
+      async->Close();
+      m_async.reset();
+    }
+  }
+
+  std::weak_ptr<uv::Async<AfterWorkFunction, R>> m_async;
+};
+
+template <>
+struct WorkerThreadAsync<void> {
+  using AfterWorkFunction = std::function<void()>;
+
+  ~WorkerThreadAsync() { RemoveLoop(); }
+
+  void SetLoop(uv::Loop& loop) {
+    auto async = uv::Async<AfterWorkFunction>::Create(loop);
+    async->wakeup.connect([](AfterWorkFunction func) { func(); });
+    m_async = async;
+  }
+
+  void RemoveLoop() {
+    if (auto async = m_async.lock()) {
+      async->Close();
+      m_async.reset();
+    }
+  }
+
+  std::weak_ptr<uv::Async<AfterWorkFunction>> m_async;
+};
+
+template <typename R, typename... T>
+struct WorkerThreadRequest {
+  using WorkFunction = std::function<R(T...)>;
+  using AfterWorkFunction = typename WorkerThreadAsync<R>::AfterWorkFunction;
+
+  WorkerThreadRequest() = default;
+  WorkerThreadRequest(uint64_t promiseId_, WorkFunction work_,
+                      std::tuple<T...> params_)
+      : promiseId(promiseId_),
+        work(std::move(work_)),
+        params(std::move(params_)) {}
+  WorkerThreadRequest(WorkFunction work_, AfterWorkFunction afterWork_,
+                      std::tuple<T...> params_)
+      : promiseId(0),
+        work(std::move(work_)),
+        afterWork(std::move(afterWork_)),
+        params(std::move(params_)) {}
+
+  uint64_t promiseId;
+  WorkFunction work;
+  AfterWorkFunction afterWork;
+  std::tuple<T...> params;
+};
+
+template <typename R, typename... T>
+class WorkerThreadThread : public SafeThread {
+ public:
+  using Request = WorkerThreadRequest<R, T...>;
+
+  void Main() override;
+
+  std::vector<Request> m_requests;
+  PromiseFactory<R> m_promises;
+  detail::WorkerThreadAsync<R> m_async;
+};
+
+template <typename R, typename... T>
+void RunWorkerThreadRequest(WorkerThreadThread<R, T...>& thr,
+                            WorkerThreadRequest<R, T...>& req) {
+  R result = std::apply(req.work, std::move(req.params));
+  if (req.afterWork) {
+    if (auto async = thr.m_async.m_async.lock()) {
+      async->Send(std::move(req.afterWork), std::move(result));
+    }
+  } else {
+    thr.m_promises.SetValue(req.promiseId, std::move(result));
+  }
+}
+
+template <typename... T>
+void RunWorkerThreadRequest(WorkerThreadThread<void, T...>& thr,
+                            WorkerThreadRequest<void, T...>& req) {
+  std::apply(req.work, req.params);
+  if (req.afterWork) {
+    if (auto async = thr.m_async.m_async.lock()) {
+      async->Send(std::move(req.afterWork));
+    }
+  } else {
+    thr.m_promises.SetValue(req.promiseId);
+  }
+}
+
+template <typename R, typename... T>
+void WorkerThreadThread<R, T...>::Main() {
+  std::vector<Request> requests;
+  while (m_active) {
+    std::unique_lock lock(m_mutex);
+    m_cond.wait(lock, [&] { return !m_active || !m_requests.empty(); });
+    if (!m_active) {
+      break;
+    }
+
+    // don't want to hold the lock while executing the callbacks
+    requests.swap(m_requests);
+    lock.unlock();
+
+    for (auto&& req : requests) {
+      if (!m_active) {
+        break;  // requests may be long-running
+      }
+      RunWorkerThreadRequest(*this, req);
+    }
+    requests.clear();
+    m_promises.Notify();
+  }
+}
+
+}  // namespace detail
+
+template <typename T>
+class WorkerThread;
+
+template <typename R, typename... T>
+class WorkerThread<R(T...)> final {
+  using Thread = detail::WorkerThreadThread<R, T...>;
+
+ public:
+  using WorkFunction = std::function<R(T...)>;
+  using AfterWorkFunction =
+      typename detail::WorkerThreadAsync<R>::AfterWorkFunction;
+
+  WorkerThread() { m_owner.Start(); }
+
+  /**
+   * Set the loop.  This must be called from the loop thread.
+   * Subsequent calls to QueueWorkThen will run afterWork on the provided
+   * loop (via an async handle).
+   *
+   * @param loop the loop to use for running afterWork routines
+   */
+  void SetLoop(uv::Loop& loop) {
+    if (auto thr = m_owner.GetThread()) {
+      thr->m_async.SetLoop(loop);
+    }
+  }
+
+  /**
+   * Set the loop.  This must be called from the loop thread.
+   * Subsequent calls to QueueWorkThen will run afterWork on the provided
+   * loop (via an async handle).
+   *
+   * @param loop the loop to use for running afterWork routines
+   */
+  void SetLoop(std::shared_ptr<uv::Loop> loop) { SetLoop(*loop); }
+
+  /**
+   * Unset the loop.  This must be called from the loop thread.
+   * Subsequent calls to QueueWorkThen will no longer run afterWork.
+   */
+  void UnsetLoop() {
+    if (auto thr = m_owner.GetThread()) {
+      thr->m_async.UnsetLoop();
+    }
+  }
+
+  /**
+   * Get the handle used by QueueWorkThen() to run afterWork.
+   * This handle is set by SetLoop().
+   * Calling Close() on this handle is the same as calling UnsetLoop().
+   *
+   * @return The handle (if nullptr, no handle is set)
+   */
+  std::shared_ptr<uv::Handle> GetHandle() const {
+    if (auto thr = m_owner.GetThread()) {
+      return thr->m_async.m_async.lock();
+    } else {
+      return nullptr;
+    }
+  }
+
+  /**
+   * Wakeup the worker thread, call the work function, and return a future for
+   * the result.
+   *
+   * It’s safe to call this function from any thread.
+   * The work function will be called on the worker thread.
+   *
+   * The future will return a default-constructed result if this class is
+   * destroyed while waiting for a result.
+   *
+   * @param work Work function (called on worker thread)
+   * @param u Arguments to work function
+   */
+  template <typename... U>
+  future<R> QueueWork(WorkFunction work, U&&... u) {
+    if (auto thr = m_owner.GetThread()) {
+      // create the future
+      uint64_t req = thr->m_promises.CreateRequest();
+
+      // add the parameters to the input queue
+      thr->m_requests.emplace_back(
+          req, std::move(work), std::forward_as_tuple(std::forward<U>(u)...));
+
+      // signal the thread
+      thr->m_cond.notify_one();
+
+      // return future
+      return thr->m_promises.CreateFuture(req);
+    }
+
+    // XXX: is this the right thing to do?
+    return future<R>();
+  }
+
+  /**
+   * Wakeup the worker thread, call the work function, and call the afterWork
+   * function with the result on the loop set by SetLoop().
+   *
+   * It’s safe to call this function from any thread.
+   * The work function will be called on the worker thread, and the afterWork
+   * function will be called on the loop thread.
+   *
+   * SetLoop() must be called prior to calling this function for afterWork to
+   * be called.
+   *
+   * @param work Work function (called on worker thread)
+   * @param afterWork After work function (called on loop thread)
+   * @param u Arguments to work function
+   */
+  template <typename... U>
+  void QueueWorkThen(WorkFunction work, AfterWorkFunction afterWork, U&&... u) {
+    if (auto thr = m_owner.GetThread()) {
+      // add the parameters to the input queue
+      thr->m_requests.emplace_back(
+          std::move(work), std::move(afterWork),
+          std::forward_as_tuple(std::forward<U>(u)...));
+
+      // signal the thread
+      thr->m_cond.notify_one();
+    }
+  }
+
+ private:
+  SafeThreadOwner<Thread> m_owner;
+};
+
+}  // namespace wpi
+
+#endif  // WPINET_WORKERTHREAD_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/hostname.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/hostname.h
new file mode 100644
index 0000000..e356fb4
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/hostname.h
@@ -0,0 +1,19 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_HOSTNAME_H_
+#define WPINET_HOSTNAME_H_
+
+#include <string>
+#include <string_view>
+
+namespace wpi {
+template <typename T>
+class SmallVectorImpl;
+
+std::string GetHostname();
+std::string_view GetHostname(SmallVectorImpl<char>& name);
+}  // namespace wpi
+
+#endif  // WPINET_HOSTNAME_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/http_parser.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/http_parser.h
similarity index 100%
rename from third_party/allwpilib/wpiutil/src/main/native/include/wpi/http_parser.h
rename to third_party/allwpilib/wpinet/src/main/native/include/wpinet/http_parser.h
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/raw_socket_istream.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/raw_socket_istream.h
new file mode 100644
index 0000000..f8f41e3
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/raw_socket_istream.h
@@ -0,0 +1,31 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_RAW_SOCKET_ISTREAM_H_
+#define WPINET_RAW_SOCKET_ISTREAM_H_
+
+#include <wpi/raw_istream.h>
+
+namespace wpi {
+
+class NetworkStream;
+
+class raw_socket_istream : public raw_istream {
+ public:
+  explicit raw_socket_istream(NetworkStream& stream, int timeout = 0)
+      : m_stream(stream), m_timeout(timeout) {}
+
+  void close() override;
+  size_t in_avail() const override;
+
+ private:
+  void read_impl(void* data, size_t len) override;
+
+  NetworkStream& m_stream;
+  int m_timeout;
+};
+
+}  // namespace wpi
+
+#endif  // WPINET_RAW_SOCKET_ISTREAM_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/raw_socket_ostream.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/raw_socket_ostream.h
new file mode 100644
index 0000000..51e0104
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/raw_socket_ostream.h
@@ -0,0 +1,39 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_RAW_SOCKET_OSTREAM_H_
+#define WPINET_RAW_SOCKET_OSTREAM_H_
+
+#include <wpi/raw_ostream.h>
+
+namespace wpi {
+
+class NetworkStream;
+
+class raw_socket_ostream : public raw_ostream {
+ public:
+  raw_socket_ostream(NetworkStream& stream, bool shouldClose)
+      : m_stream(stream), m_shouldClose(shouldClose) {}
+  ~raw_socket_ostream() override;
+
+  void close();
+
+  bool has_error() const { return m_error; }
+  void clear_error() { m_error = false; }
+
+ protected:
+  void error_detected() { m_error = true; }
+
+ private:
+  void write_impl(const char* data, size_t len) override;
+  uint64_t current_pos() const override;
+
+  NetworkStream& m_stream;
+  bool m_error = false;
+  bool m_shouldClose;
+};
+
+}  // namespace wpi
+
+#endif  // WPINET_RAW_SOCKET_OSTREAM_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/raw_uv_ostream.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/raw_uv_ostream.h
new file mode 100644
index 0000000..aa45297
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/raw_uv_ostream.h
@@ -0,0 +1,75 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_RAW_UV_OSTREAM_H_
+#define WPINET_RAW_UV_OSTREAM_H_
+
+#include <functional>
+#include <span>
+#include <utility>
+
+#include <wpi/SmallVector.h>
+#include <wpi/raw_ostream.h>
+
+#include "wpinet/uv/Buffer.h"
+
+namespace wpi {
+
+/**
+ * raw_ostream style output to a SmallVector of uv::Buffer buffers.  Fixed-size
+ * buffers are allocated and appended as necessary to fit the data being output.
+ * The SmallVector need not be empty at start.
+ */
+class raw_uv_ostream : public raw_ostream {
+ public:
+  /**
+   * Construct a new raw_uv_ostream.
+   * @param bufs Buffers vector.  NOT cleared on construction.
+   * @param allocSize Size to allocate for each buffer; allocation will be
+   *                  performed using Buffer::Allocate().
+   */
+  raw_uv_ostream(SmallVectorImpl<uv::Buffer>& bufs, size_t allocSize)
+      : m_bufs(bufs), m_alloc([=] { return uv::Buffer::Allocate(allocSize); }) {
+    SetUnbuffered();
+  }
+
+  /**
+   * Construct a new raw_uv_ostream.
+   * @param bufs Buffers vector.  NOT cleared on construction.
+   * @param alloc Allocator.
+   */
+  raw_uv_ostream(SmallVectorImpl<uv::Buffer>& bufs,
+                 std::function<uv::Buffer()> alloc)
+      : m_bufs(bufs), m_alloc(std::move(alloc)) {
+    SetUnbuffered();
+  }
+
+  ~raw_uv_ostream() override = default;
+
+  /**
+   * Returns an span to the buffers.
+   */
+  std::span<uv::Buffer> bufs() { return m_bufs; }
+
+  void flush() = delete;
+
+  /**
+   * Resets the amount of allocated space.
+   */
+  void reset() { m_left = 0; }
+
+ private:
+  void write_impl(const char* data, size_t len) override;
+  uint64_t current_pos() const override;
+
+  SmallVectorImpl<uv::Buffer>& m_bufs;
+  std::function<uv::Buffer()> m_alloc;
+
+  // How much allocated space is left in the current buffer.
+  size_t m_left = 0;
+};
+
+}  // namespace wpi
+
+#endif  // WPINET_RAW_UV_OSTREAM_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Async.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Async.h
new file mode 100644
index 0000000..eb3a005
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Async.h
@@ -0,0 +1,193 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_UV_ASYNC_H_
+#define WPINET_UV_ASYNC_H_
+
+#include <uv.h>
+
+#include <memory>
+#include <thread>
+#include <tuple>
+#include <utility>
+#include <vector>
+
+#include <wpi/Signal.h>
+#include <wpi/mutex.h>
+
+#include "wpinet/uv/Handle.h"
+#include "wpinet/uv/Loop.h"
+
+namespace wpi::uv {
+
+/**
+ * Async handle.
+ * Async handles allow the user to "wakeup" the event loop and have a signal
+ * generated from another thread.
+ *
+ * Data may be passed into the callback called on the event loop by using
+ * template parameters.  If data parameters are used, the async callback will
+ * be called once for every call to Send().  If no data parameters are used,
+ * the async callback may or may not be called for every call to Send() (e.g.
+ * the calls may be coaleasced).
+ */
+template <typename... T>
+class Async final : public HandleImpl<Async<T...>, uv_async_t> {
+  struct private_init {};
+
+ public:
+  Async(const std::shared_ptr<Loop>& loop, const private_init&)
+      : m_loop{loop} {}
+  ~Async() noexcept override {
+    if (auto loop = m_loop.lock()) {
+      this->Close();
+    } else {
+      this->ForceClosed();
+    }
+  }
+
+  /**
+   * Create an async handle.
+   *
+   * @param loop Loop object where this handle runs.
+   */
+  static std::shared_ptr<Async> Create(Loop& loop) {
+    return Create(loop.shared_from_this());
+  }
+
+  /**
+   * Create an async handle.
+   *
+   * @param loop Loop object where this handle runs.
+   */
+  static std::shared_ptr<Async> Create(const std::shared_ptr<Loop>& loop) {
+    auto h = std::make_shared<Async>(loop, private_init{});
+    int err =
+        uv_async_init(loop->GetRaw(), h->GetRaw(), [](uv_async_t* handle) {
+          auto& h = *static_cast<Async*>(handle->data);
+          std::scoped_lock lock(h.m_mutex);
+          for (auto&& v : h.m_data) {
+            std::apply(h.wakeup, v);
+          }
+          h.m_data.clear();
+        });
+    if (err < 0) {
+      loop->ReportError(err);
+      return nullptr;
+    }
+    h->Keep();
+    return h;
+  }
+
+  /**
+   * Wakeup the event loop and emit the event.
+   *
+   * It’s safe to call this function from any thread including the loop thread.
+   * An async event will be emitted on the loop thread.
+   */
+  template <typename... U>
+  void Send(U&&... u) {
+    auto loop = m_loop.lock();
+    if (loop && loop->GetThreadId() == std::this_thread::get_id()) {
+      // called from within the loop, just call the function directly
+      wakeup(std::forward<U>(u)...);
+      return;
+    }
+
+    {
+      std::scoped_lock lock(m_mutex);
+      m_data.emplace_back(std::forward_as_tuple(std::forward<U>(u)...));
+    }
+    if (loop) {
+      this->Invoke(&uv_async_send, this->GetRaw());
+    }
+  }
+
+  /**
+   * Wakeup the event loop and emit the event.
+   * This function assumes the loop still exists, which makes it a bit faster.
+   *
+   * It’s safe to call this function from any thread.
+   * An async event will be emitted on the loop thread.
+   */
+  void UnsafeSend() { Invoke(&uv_async_send, this->GetRaw()); }
+
+  /**
+   * Signal generated (on event loop thread) when the async event occurs.
+   */
+  sig::Signal<T...> wakeup;
+
+ private:
+  wpi::mutex m_mutex;
+  std::vector<std::tuple<T...>> m_data;
+  std::weak_ptr<Loop> m_loop;
+};
+
+/**
+ * Async specialization for no data parameters.  The async callback may or may
+ * not be called for every call to Send() (e.g. the calls may be coaleasced).
+ */
+template <>
+class Async<> final : public HandleImpl<Async<>, uv_async_t> {
+  struct private_init {};
+
+ public:
+  Async(const std::shared_ptr<Loop>& loop, const private_init&)
+      : m_loop(loop) {}
+  ~Async() noexcept override;
+
+  /**
+   * Create an async handle.
+   *
+   * @param loop Loop object where this handle runs.
+   */
+  static std::shared_ptr<Async> Create(Loop& loop) {
+    return Create(loop.shared_from_this());
+  }
+
+  /**
+   * Create an async handle.
+   *
+   * @param loop Loop object where this handle runs.
+   */
+  static std::shared_ptr<Async> Create(const std::shared_ptr<Loop>& loop);
+
+  /**
+   * Wakeup the event loop and emit the event.
+   *
+   * It’s safe to call this function from any thread.
+   * An async event will be emitted on the loop thread.
+   */
+  void Send() {
+    if (auto loop = m_loop.lock()) {
+      if (loop->GetThreadId() == std::this_thread::get_id()) {
+        // called from within the loop, just call the function directly
+        wakeup();
+      } else {
+        Invoke(&uv_async_send, GetRaw());
+      }
+    }
+  }
+
+  /**
+   * Wakeup the event loop and emit the event.
+   * This function assumes the loop still exists, which makes it a bit faster.
+   *
+   * It’s safe to call this function from any thread.
+   * An async event will be emitted on the loop thread.
+   */
+  void UnsafeSend() { Invoke(&uv_async_send, GetRaw()); }
+
+  /**
+   * Signal generated (on event loop thread) when the async event occurs.
+   */
+  sig::Signal<> wakeup;
+
+ private:
+  std::weak_ptr<Loop> m_loop;
+};
+
+}  // namespace wpi::uv
+
+#endif  // WPINET_UV_ASYNC_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/AsyncFunction.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/AsyncFunction.h
new file mode 100644
index 0000000..82a5913
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/AsyncFunction.h
@@ -0,0 +1,168 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_UV_ASYNCFUNCTION_H_
+#define WPINET_UV_ASYNCFUNCTION_H_
+
+#include <stdint.h>
+#include <uv.h>
+
+#include <functional>
+#include <memory>
+#include <thread>
+#include <tuple>
+#include <utility>
+#include <vector>
+
+#include <wpi/future.h>
+#include <wpi/mutex.h>
+
+#include "wpinet/uv/Handle.h"
+#include "wpinet/uv/Loop.h"
+
+namespace wpi::uv {
+
+template <typename T>
+class AsyncFunction;
+
+/**
+ * Function async handle.
+ * Async handles allow the user to "wakeup" the event loop and have a function
+ * called from another thread that returns a result to the calling thread.
+ */
+template <typename R, typename... T>
+class AsyncFunction<R(T...)> final
+    : public HandleImpl<AsyncFunction<R(T...)>, uv_async_t> {
+  struct private_init {};
+
+ public:
+  AsyncFunction(const std::shared_ptr<Loop>& loop,
+                std::function<void(promise<R>, T...)> func, const private_init&)
+      : wakeup{std::move(func)}, m_loop{loop} {}
+  ~AsyncFunction() noexcept override {
+    if (auto loop = m_loop.lock()) {
+      this->Close();
+    } else {
+      this->ForceClosed();
+    }
+  }
+
+  /**
+   * Create an async handle.
+   *
+   * @param loop Loop object where this handle runs.
+   * @param func wakeup function to be called (sets wakeup value); the function
+   *             needs to return void, and its first parameter is the promise
+   *             for the result.  If no value is set on the promise by the
+   *             wakeup function, a default-constructed value is "returned".
+   */
+  static std::shared_ptr<AsyncFunction> Create(
+      Loop& loop, std::function<void(promise<R>, T...)> func = nullptr) {
+    return Create(loop.shared_from_this(), std::move(func));
+  }
+
+  /**
+   * Create an async handle.
+   *
+   * @param loop Loop object where this handle runs.
+   * @param func wakeup function to be called (sets wakeup value); the function
+   *             needs to return void, and its first parameter is the promise
+   *             for the result.  If no value is set on the promise by the
+   *             wakeup function, a default-constructed value is "returned".
+   */
+  static std::shared_ptr<AsyncFunction> Create(
+      const std::shared_ptr<Loop>& loop,
+      std::function<void(promise<R>, T...)> func = nullptr) {
+    auto h =
+        std::make_shared<AsyncFunction>(loop, std::move(func), private_init{});
+    int err =
+        uv_async_init(loop->GetRaw(), h->GetRaw(), [](uv_async_t* handle) {
+          auto& h = *static_cast<AsyncFunction*>(handle->data);
+          std::unique_lock lock(h.m_mutex);
+
+          if (!h.m_params.empty()) {
+            // for each set of parameters in the input queue, call the wakeup
+            // function and put the result in the output queue if the caller is
+            // waiting for it
+            for (auto&& v : h.m_params) {
+              auto p = h.m_promises.CreatePromise(v.first);
+              if (h.wakeup) {
+                std::apply(h.wakeup,
+                           std::tuple_cat(std::make_tuple(std::move(p)),
+                                          std::move(v.second)));
+              }
+            }
+            h.m_params.clear();
+            // wake up any threads that might be waiting for the result
+            lock.unlock();
+            h.m_promises.Notify();
+          }
+        });
+    if (err < 0) {
+      loop->ReportError(err);
+      return nullptr;
+    }
+    h->Keep();
+    return h;
+  }
+
+  /**
+   * Wakeup the event loop, call the async function, and return a future for
+   * the result.
+   *
+   * It’s safe to call this function from any thread including the loop thread.
+   * The async function will be called on the loop thread.
+   *
+   * The future will return a default-constructed result if this handle is
+   * destroyed while waiting for a result.
+   */
+  template <typename... U>
+  future<R> Call(U&&... u) {
+    // create the future
+    uint64_t req = m_promises.CreateRequest();
+
+    auto loop = m_loop.lock();
+    if (loop && loop->GetThreadId() == std::this_thread::get_id()) {
+      // called from within the loop, just call the function directly
+      wakeup(m_promises.CreatePromise(req), std::forward<U>(u)...);
+      return m_promises.CreateFuture(req);
+    }
+
+    // add the parameters to the input queue
+    {
+      std::scoped_lock lock(m_mutex);
+      m_params.emplace_back(std::piecewise_construct,
+                            std::forward_as_tuple(req),
+                            std::forward_as_tuple(std::forward<U>(u)...));
+    }
+
+    // signal the loop
+    if (loop) {
+      this->Invoke(&uv_async_send, this->GetRaw());
+    }
+
+    // return future
+    return m_promises.CreateFuture(req);
+  }
+
+  template <typename... U>
+  future<R> operator()(U&&... u) {
+    return Call(std::forward<U>(u)...);
+  }
+
+  /**
+   * Function called (on event loop thread) when the async is called.
+   */
+  std::function<void(promise<R>, T...)> wakeup;
+
+ private:
+  wpi::mutex m_mutex;
+  std::vector<std::pair<uint64_t, std::tuple<T...>>> m_params;
+  PromiseFactory<R> m_promises;
+  std::weak_ptr<Loop> m_loop;
+};
+
+}  // namespace wpi::uv
+
+#endif  // WPINET_UV_ASYNCFUNCTION_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Buffer.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Buffer.h
new file mode 100644
index 0000000..4b58b0f
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Buffer.h
@@ -0,0 +1,163 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_UV_BUFFER_H_
+#define WPINET_UV_BUFFER_H_
+
+#include <uv.h>
+
+#include <cstring>
+#include <initializer_list>
+#include <span>
+#include <string_view>
+#include <utility>
+
+#include <wpi/SmallVector.h>
+
+namespace wpi::uv {
+
+/**
+ * Data buffer.  Convenience wrapper around uv_buf_t.
+ */
+class Buffer : public uv_buf_t {
+ public:
+  Buffer() {
+    base = nullptr;
+    len = 0;
+  }
+  /*implicit*/ Buffer(const uv_buf_t& oth) {  // NOLINT
+    base = oth.base;
+    len = oth.len;
+  }
+  /*implicit*/ Buffer(std::string_view str)  // NOLINT
+      : Buffer{str.data(), str.size()} {}
+  /*implicit*/ Buffer(std::span<const uint8_t> arr)  // NOLINT
+      : Buffer{reinterpret_cast<const char*>(arr.data()), arr.size()} {}
+  Buffer(char* base_, size_t len_) {
+    base = base_;
+    len = static_cast<decltype(len)>(len_);
+  }
+  Buffer(const char* base_, size_t len_) {
+    base = const_cast<char*>(base_);
+    len = static_cast<decltype(len)>(len_);
+  }
+
+  std::span<const char> data() const { return {base, len}; }
+  std::span<char> data() { return {base, len}; }
+
+  operator std::span<const char>() const { return data(); }  // NOLINT
+  operator std::span<char>() { return data(); }              // NOLINT
+
+  static Buffer Allocate(size_t size) { return Buffer{new char[size], size}; }
+
+  static Buffer Dup(std::string_view in) {
+    Buffer buf = Allocate(in.size());
+    std::memcpy(buf.base, in.data(), in.size());
+    return buf;
+  }
+
+  static Buffer Dup(std::span<const uint8_t> in) {
+    Buffer buf = Allocate(in.size());
+    std::memcpy(buf.base, in.data(), in.size());
+    return buf;
+  }
+
+  Buffer Dup() const {
+    Buffer buf = Allocate(len);
+    std::memcpy(buf.base, base, len);
+    return buf;
+  }
+
+  void Deallocate() {
+    delete[] base;
+    base = nullptr;
+    len = 0;
+  }
+
+  Buffer Move() {
+    Buffer buf = *this;
+    base = nullptr;
+    len = 0;
+    return buf;
+  }
+
+  friend void swap(Buffer& a, Buffer& b) {
+    using std::swap;
+    swap(a.base, b.base);
+    swap(a.len, b.len);
+  }
+};
+
+/**
+ * A simple pool allocator for Buffers.
+ * Buffers are allocated individually but are reused rather than returned
+ * to the heap.
+ * @tparam DEPTH depth of pool
+ */
+template <size_t DEPTH = 4>
+class SimpleBufferPool {
+ public:
+  /**
+   * Constructor.
+   * @param size Size of each buffer to allocate.
+   */
+  explicit SimpleBufferPool(size_t size = 4096) : m_size{size} {}
+  ~SimpleBufferPool() { Clear(); }
+
+  SimpleBufferPool(const SimpleBufferPool& other) = delete;
+  SimpleBufferPool& operator=(const SimpleBufferPool& other) = delete;
+
+  /**
+   * Allocate a buffer.
+   */
+  Buffer Allocate() {
+    if (m_pool.empty()) {
+      return Buffer::Allocate(m_size);
+    }
+    auto buf = m_pool.back();
+    m_pool.pop_back();
+    buf.len = m_size;
+    return buf;
+  }
+
+  /**
+   * Allocate a buffer.
+   */
+  Buffer operator()() { return Allocate(); }
+
+  /**
+   * Release allocated buffers back into the pool.
+   * This is NOT safe to use with arbitrary buffers unless they were
+   * allocated with the same size as the buffer pool allocation size.
+   */
+  void Release(std::span<Buffer> bufs) {
+    for (auto& buf : bufs) {
+      m_pool.emplace_back(buf.Move());
+    }
+  }
+
+  /**
+   * Clear the pool, releasing all buffers.
+   */
+  void Clear() {
+    for (auto& buf : m_pool) {
+      buf.Deallocate();
+    }
+    m_pool.clear();
+  }
+
+  /**
+   * Get number of buffers left in the pool before a new buffer will be
+   * allocated from the heap.
+   */
+  size_t Remaining() const { return m_pool.size(); }
+
+ private:
+  SmallVector<Buffer, DEPTH> m_pool;
+  size_t m_size;  // NOLINT
+};
+
+}  // namespace wpi::uv
+
+#endif  // WPINET_UV_BUFFER_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Check.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Check.h
new file mode 100644
index 0000000..8f5aa2f
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Check.h
@@ -0,0 +1,66 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_UV_CHECK_H_
+#define WPINET_UV_CHECK_H_
+
+#include <uv.h>
+
+#include <memory>
+
+#include <wpi/Signal.h>
+
+#include "wpinet/uv/Handle.h"
+
+namespace wpi::uv {
+
+class Loop;
+
+/**
+ * Check handle.
+ * Check handles will generate a signal once per loop iteration, right
+ * after polling for I/O.
+ */
+class Check final : public HandleImpl<Check, uv_check_t> {
+  struct private_init {};
+
+ public:
+  explicit Check(const private_init&) {}
+  ~Check() noexcept override = default;
+
+  /**
+   * Create a check handle.
+   *
+   * @param loop Loop object where this handle runs.
+   */
+  static std::shared_ptr<Check> Create(Loop& loop);
+
+  /**
+   * Create a check handle.
+   *
+   * @param loop Loop object where this handle runs.
+   */
+  static std::shared_ptr<Check> Create(const std::shared_ptr<Loop>& loop) {
+    return Create(*loop);
+  }
+
+  /**
+   * Start the handle.
+   */
+  void Start();
+
+  /**
+   * Stop the handle.  The signal will no longer be generated.
+   */
+  void Stop() { Invoke(&uv_check_stop, GetRaw()); }
+
+  /**
+   * Signal generated once per loop iteration after polling for I/O.
+   */
+  sig::Signal<> check;
+};
+
+}  // namespace wpi::uv
+
+#endif  // WPINET_UV_CHECK_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Error.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Error.h
new file mode 100644
index 0000000..cc2a5d5
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Error.h
@@ -0,0 +1,46 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_UV_ERROR_H_
+#define WPINET_UV_ERROR_H_
+
+#include <uv.h>
+
+namespace wpi::uv {
+
+/**
+ * Error code.
+ */
+class Error {
+ public:
+  Error() = default;
+  explicit Error(int err) : m_err(err) {}
+
+  /**
+   * Boolean conversion.  Returns true if error, false if ok.
+   */
+  explicit operator bool() const { return m_err < 0; }
+
+  /**
+   * Returns the error code.
+   */
+  int code() const { return m_err; }
+
+  /**
+   * Returns the error message.
+   */
+  const char* str() const { return uv_strerror(m_err); }
+
+  /**
+   * Returns the error name.
+   */
+  const char* name() const { return uv_err_name(m_err); }
+
+ private:
+  int m_err{UV_UNKNOWN};
+};
+
+}  // namespace wpi::uv
+
+#endif  // WPINET_UV_ERROR_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/FsEvent.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/FsEvent.h
new file mode 100644
index 0000000..ba8a649
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/FsEvent.h
@@ -0,0 +1,80 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_UV_FSEVENT_H_
+#define WPINET_UV_FSEVENT_H_
+
+#include <uv.h>
+
+#include <memory>
+#include <string>
+#include <string_view>
+
+#include <wpi/Signal.h>
+
+#include "wpinet/uv/Handle.h"
+
+namespace wpi::uv {
+
+class Loop;
+
+/**
+ * Filesystem Event handle.
+ */
+class FsEvent final : public HandleImpl<FsEvent, uv_fs_event_t> {
+  struct private_init {};
+
+ public:
+  explicit FsEvent(const private_init&) {}
+  ~FsEvent() noexcept override = default;
+
+  /**
+   * Create a filesystem event handle.
+   *
+   * @param loop Loop object where this handle runs.
+   */
+  static std::shared_ptr<FsEvent> Create(Loop& loop);
+
+  /**
+   * Create a filesystem event handle.
+   *
+   * @param loop Loop object where this handle runs.
+   */
+  static std::shared_ptr<FsEvent> Create(const std::shared_ptr<Loop>& loop) {
+    return Create(*loop);
+  }
+
+  /**
+   * Start watching the specified path for changes.
+   *
+   * @param path Path to watch for changes
+   * @param events Bitmask of event flags.  Only UV_FS_EVENT_RECURSIVE is
+   *               supported (and only on OSX and Windows).
+   */
+  void Start(std::string_view path, unsigned int flags = 0);
+
+  /**
+   * Stop watching for changes.
+   */
+  void Stop() { Invoke(&uv_fs_event_stop, GetRaw()); }
+
+  /**
+   * Get the path being monitored.  Signals error and returns empty string if
+   * an error occurs.
+   * @return Monitored path.
+   */
+  std::string GetPath();
+
+  /**
+   * Signal generated when a filesystem change occurs.  The first parameter
+   * is the filename (if a directory was passed to Start(), the filename is
+   * relative to that directory).  The second parameter is an ORed mask of
+   * UV_RENAME and UV_CHANGE.
+   */
+  sig::Signal<const char*, int> fsEvent;
+};
+
+}  // namespace wpi::uv
+
+#endif  // WPINET_UV_FSEVENT_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/GetAddrInfo.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/GetAddrInfo.h
new file mode 100644
index 0000000..5954110
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/GetAddrInfo.h
@@ -0,0 +1,120 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_UV_GETADDRINFO_H_
+#define WPINET_UV_GETADDRINFO_H_
+
+#include <uv.h>
+
+#include <functional>
+#include <memory>
+#include <string_view>
+#include <utility>
+
+#include <wpi/Signal.h>
+
+#include "wpinet/uv/Request.h"
+
+namespace wpi::uv {
+
+class Loop;
+
+/**
+ * GetAddrInfo request.
+ * For use with `GetAddrInfo()` function family.
+ */
+class GetAddrInfoReq : public RequestImpl<GetAddrInfoReq, uv_getaddrinfo_t> {
+ public:
+  GetAddrInfoReq();
+
+  Loop& GetLoop() const { return *static_cast<Loop*>(GetRaw()->loop->data); }
+
+  /**
+   * Resolved lookup signal.
+   * Parameter is resolved address info.
+   */
+  sig::Signal<const addrinfo&> resolved;
+};
+
+/**
+ * Asynchronous getaddrinfo(3).  HandleResolvedAddress() is called on the
+ * request when the resolution completes.  HandleError() is called on the
+ * request if any errors occur.
+ *
+ * Either node or service may be empty but not both.
+ *
+ * @param loop Event loop
+ * @param req request
+ * @param node Either a numerical network address or a network hostname.
+ * @param service Either a service name or a port number as a string.
+ * @param hints Optional `addrinfo` data structure with additional address
+ *              type constraints.
+ */
+void GetAddrInfo(Loop& loop, const std::shared_ptr<GetAddrInfoReq>& req,
+                 std::string_view node, std::string_view service = {},
+                 const addrinfo* hints = nullptr);
+
+/**
+ * Asynchronous getaddrinfo(3).  HandleResolvedAddress() is called on the
+ * request when the resolution completes.  HandleError() is called on the
+ * request if any errors occur.
+ *
+ * Either node or service may be empty but not both.
+ *
+ * @param loop Event loop
+ * @param req request
+ * @param node Either a numerical network address or a network hostname.
+ * @param service Either a service name or a port number as a string.
+ * @param hints Optional `addrinfo` data structure with additional address
+ *              type constraints.
+ */
+inline void GetAddrInfo(const std::shared_ptr<Loop>& loop,
+                        const std::shared_ptr<GetAddrInfoReq>& req,
+                        std::string_view node, std::string_view service = {},
+                        const addrinfo* hints = nullptr) {
+  GetAddrInfo(*loop, req, node, service, hints);
+}
+
+/**
+ * Asynchronous getaddrinfo(3).  The callback is called when the resolution
+ * completes, and errors are forwarded to the loop.  This is a convenience
+ * wrapper.
+ *
+ * Either node or service may be empty but not both.
+ *
+ * @param loop Event loop
+ * @param callback Callback function to call when resolution completes
+ * @param node Either a numerical network address or a network hostname.
+ * @param service Either a service name or a port number as a string.
+ * @param hints Optional `addrinfo` data structure with additional address
+ *              type constraints.
+ */
+void GetAddrInfo(Loop& loop, std::function<void(const addrinfo&)> callback,
+                 std::string_view node, std::string_view service = {},
+                 const addrinfo* hints = nullptr);
+
+/**
+ * Asynchronous getaddrinfo(3).  The callback is called when the resolution
+ * completes, and errors are forwarded to the loop.  This is a convenience
+ * wrapper.
+ *
+ * Either node or service may be empty but not both.
+ *
+ * @param loop Event loop
+ * @param callback Callback function to call when resolution completes
+ * @param node Either a numerical network address or a network hostname.
+ * @param service Either a service name or a port number as a string.
+ * @param hints Optional `addrinfo` data structure with additional address
+ *              type constraints.
+ */
+inline void GetAddrInfo(const std::shared_ptr<Loop>& loop,
+                        std::function<void(const addrinfo&)> callback,
+                        std::string_view node, std::string_view service = {},
+                        const addrinfo* hints = nullptr) {
+  GetAddrInfo(*loop, std::move(callback), node, service, hints);
+}
+
+}  // namespace wpi::uv
+
+#endif  // WPINET_UV_GETADDRINFO_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/GetNameInfo.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/GetNameInfo.h
new file mode 100644
index 0000000..1bd0f4a
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/GetNameInfo.h
@@ -0,0 +1,229 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_UV_GETNAMEINFO_H_
+#define WPINET_UV_GETNAMEINFO_H_
+
+#include <uv.h>
+
+#include <functional>
+#include <memory>
+#include <string_view>
+#include <utility>
+
+#include <wpi/Signal.h>
+
+#include "wpinet/uv/Request.h"
+
+namespace wpi::uv {
+
+class Loop;
+
+/**
+ * GetNameInfo request.
+ * For use with `GetNameInfo()` function family.
+ */
+class GetNameInfoReq : public RequestImpl<GetNameInfoReq, uv_getnameinfo_t> {
+ public:
+  GetNameInfoReq();
+
+  Loop& GetLoop() const { return *static_cast<Loop*>(GetRaw()->loop->data); }
+
+  /**
+   * Resolved lookup signal.
+   * Parameters are hostname and service.
+   */
+  sig::Signal<const char*, const char*> resolved;
+};
+
+/**
+ * Asynchronous getnameinfo(3).  HandleResolvedName() is called on the
+ * request when the resolution completes.  HandleError() is called on the
+ * request if any errors occur.
+ *
+ * @param loop Event loop
+ * @param req request
+ * @param addr Initialized `sockaddr_in` or `sockaddr_in6` data structure.
+ * @param flags Optional flags to modify the behavior of `getnameinfo`.
+ */
+void GetNameInfo(Loop& loop, const std::shared_ptr<GetNameInfoReq>& req,
+                 const sockaddr& addr, int flags = 0);
+
+/**
+ * Asynchronous getnameinfo(3).  HandleResolvedName() is called on the
+ * request when the resolution completes.  HandleError() is called on the
+ * request if any errors occur.
+ *
+ * @param loop Event loop
+ * @param req request
+ * @param addr Initialized `sockaddr_in` or `sockaddr_in6` data structure.
+ * @param flags Optional flags to modify the behavior of `getnameinfo`.
+ */
+inline void GetNameInfo(const std::shared_ptr<Loop>& loop,
+                        const std::shared_ptr<GetNameInfoReq>& req,
+                        const sockaddr& addr, int flags = 0) {
+  GetNameInfo(*loop, req, addr, flags);
+}
+
+/**
+ * Asynchronous getnameinfo(3).  The callback is called when the resolution
+ * completes, and errors are forwarded to the loop.
+ *
+ * @param loop Event loop
+ * @param callback Callback function to call when resolution completes
+ * @param addr Initialized `sockaddr_in` or `sockaddr_in6` data structure.
+ * @param flags Optional flags to modify the behavior of `getnameinfo`.
+ */
+void GetNameInfo(Loop& loop,
+                 std::function<void(const char*, const char*)> callback,
+                 const sockaddr& addr, int flags = 0);
+
+/**
+ * Asynchronous getnameinfo(3).  The callback is called when the resolution
+ * completes, and errors are forwarded to the loop.
+ *
+ * @param loop Event loop
+ * @param callback Callback function to call when resolution completes
+ * @param addr Initialized `sockaddr_in` or `sockaddr_in6` data structure.
+ * @param flags Optional flags to modify the behavior of `getnameinfo`.
+ * @return Connection object for the callback
+ */
+inline void GetNameInfo(const std::shared_ptr<Loop>& loop,
+                        std::function<void(const char*, const char*)> callback,
+                        const sockaddr& addr, int flags = 0) {
+  GetNameInfo(*loop, std::move(callback), addr, flags);
+}
+
+/**
+ * Asynchronous IPv4 getnameinfo(3).  HandleResolvedName() is called on the
+ * request when the resolution completes.  HandleError() is called on the
+ * request if any errors occur.
+ *
+ * @param loop Event loop
+ * @param req request
+ * @param ip A valid IPv4 address
+ * @param port A valid port number
+ * @param flags Optional flags to modify the behavior of `getnameinfo`.
+ */
+void GetNameInfo4(Loop& loop, const std::shared_ptr<GetNameInfoReq>& req,
+                  std::string_view ip, unsigned int port, int flags = 0);
+
+/**
+ * Asynchronous IPv4 getnameinfo(3).  HandleResolvedName() is called on the
+ * request when the resolution completes.  HandleError() is called on the
+ * request if any errors occur.
+ *
+ * @param loop Event loop
+ * @param req request
+ * @param ip A valid IPv4 address
+ * @param port A valid port number
+ * @param flags Optional flags to modify the behavior of `getnameinfo`.
+ */
+inline void GetNameInfo4(const std::shared_ptr<Loop>& loop,
+                         const std::shared_ptr<GetNameInfoReq>& req,
+                         std::string_view ip, unsigned int port,
+                         int flags = 0) {
+  return GetNameInfo4(*loop, req, ip, port, flags);
+}
+
+/**
+ * Asynchronous IPv4 getnameinfo(3).  The callback is called when the resolution
+ * completes, and errors are forwarded to the loop.
+ *
+ * @param loop Event loop
+ * @param callback Callback function to call when resolution completes
+ * @param ip A valid IPv4 address
+ * @param port A valid port number
+ * @param flags Optional flags to modify the behavior of `getnameinfo`.
+ */
+void GetNameInfo4(Loop& loop,
+                  std::function<void(const char*, const char*)> callback,
+                  std::string_view ip, unsigned int port, int flags = 0);
+
+/**
+ * Asynchronous IPv4 getnameinfo(3).  The callback is called when the resolution
+ * completes, and errors are forwarded to the loop.  This is a convenience
+ * wrapper.
+ *
+ * @param loop Event loop
+ * @param ip A valid IPv4 address
+ * @param port A valid port number
+ * @param callback Callback function to call when resolution completes
+ * @param flags Optional flags to modify the behavior of `getnameinfo`.
+ */
+inline void GetNameInfo4(const std::shared_ptr<Loop>& loop,
+                         std::function<void(const char*, const char*)> callback,
+                         std::string_view ip, unsigned int port,
+                         int flags = 0) {
+  return GetNameInfo4(*loop, std::move(callback), ip, port, flags);
+}
+
+/**
+ * Asynchronous IPv6 getnameinfo(3).  HandleResolvedName() is called on the
+ * request when the resolution completes.  HandleError() is called on the
+ * request if any errors occur.
+ *
+ * @param loop Event loop
+ * @param req request
+ * @param ip A valid IPv6 address
+ * @param port A valid port number
+ * @param flags Optional flags to modify the behavior of `getnameinfo`.
+ */
+void GetNameInfo6(Loop& loop, const std::shared_ptr<GetNameInfoReq>& req,
+                  std::string_view ip, unsigned int port, int flags = 0);
+
+/**
+ * Asynchronous IPv6 getnameinfo(3).  HandleResolvedName() is called on the
+ * request when the resolution completes.  HandleError() is called on the
+ * request if any errors occur.
+ *
+ * @param loop Event loop
+ * @param req request
+ * @param ip A valid IPv6 address
+ * @param port A valid port number
+ * @param flags Optional flags to modify the behavior of `getnameinfo`.
+ */
+inline void GetNameInfo6(const std::shared_ptr<Loop>& loop,
+                         const std::shared_ptr<GetNameInfoReq>& req,
+                         std::string_view ip, unsigned int port,
+                         int flags = 0) {
+  GetNameInfo6(*loop, req, ip, port, flags);
+}
+
+/**
+ * Asynchronous IPv6 getnameinfo(3).  The callback is called when the resolution
+ * completes, and errors are forwarded to the loop.  This is a convenience
+ * wrapper.
+ *
+ * @param loop Event loop
+ * @param callback Callback function to call when resolution completes
+ * @param ip A valid IPv6 address
+ * @param port A valid port number
+ * @param flags Optional flags to modify the behavior of `getnameinfo`.
+ */
+void GetNameInfo6(Loop& loop,
+                  std::function<void(const char*, const char*)> callback,
+                  std::string_view ip, unsigned int port, int flags = 0);
+
+/**
+ * Asynchronous IPv6 getnameinfo(3).  The callback is called when the resolution
+ * completes, and errors are forwarded to the loop.  This is a convenience
+ * wrapper.
+ *
+ * @param loop Event loop
+ * @param callback Callback function to call when resolution completes
+ * @param ip A valid IPv6 address
+ * @param port A valid port number
+ * @param flags Optional flags to modify the behavior of `getnameinfo`.
+ */
+inline void GetNameInfo6(const std::shared_ptr<Loop>& loop,
+                         std::function<void(const char*, const char*)> callback,
+                         std::string_view ip, unsigned int port,
+                         int flags = 0) {
+  return GetNameInfo6(*loop, std::move(callback), ip, port, flags);
+}
+
+}  // namespace wpi::uv
+
+#endif  // WPINET_UV_GETNAMEINFO_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Handle.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Handle.h
new file mode 100644
index 0000000..903d43c
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Handle.h
@@ -0,0 +1,298 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_UV_HANDLE_H_
+#define WPINET_UV_HANDLE_H_
+
+#include <uv.h>
+
+#include <cstdlib>
+#include <functional>
+#include <memory>
+#include <string_view>
+#include <utility>
+
+#include <wpi/Signal.h>
+
+#include "wpinet/uv/Buffer.h"
+#include "wpinet/uv/Error.h"
+#include "wpinet/uv/Loop.h"
+
+namespace wpi::uv {
+
+/**
+ * Handle.
+ * Handles are not moveable or copyable and cannot be directly constructed.
+ * This class provides shared_ptr ownership and shared_from_this.
+ * Use the specific handle type Create() functions to create handles.
+ */
+class Handle : public std::enable_shared_from_this<Handle> {
+ public:
+  using Type = uv_handle_type;
+
+  Handle(const Handle&) = delete;
+  Handle(Handle&&) = delete;
+  Handle& operator=(const Handle&) = delete;
+  Handle& operator=(Handle&&) = delete;
+  virtual ~Handle() noexcept;
+
+  /**
+   * Get the type of the handle.
+   *
+   * A base handle offers no functionality to promote it to the actual handle
+   * type. By means of this function, the type of the underlying handle as
+   * specified by Type is made available.
+   *
+   * @return The actual type of the handle.
+   */
+  Type GetType() const noexcept { return m_uv_handle->type; }
+
+  /**
+   * Get the name of the type of the handle.  E.g. "pipe" for pipe handles.
+   */
+  std::string_view GetTypeName() const noexcept {
+    return uv_handle_type_name(m_uv_handle->type);
+  }
+
+  /**
+   * Get the loop where this handle runs.
+   *
+   * @return The loop.
+   */
+  std::shared_ptr<Loop> GetLoop() const noexcept {
+    return GetLoopRef().shared_from_this();
+  }
+
+  /**
+   * Get the loop where this handle runs.
+   *
+   * @return The loop.
+   */
+  Loop& GetLoopRef() const noexcept {
+    return *static_cast<Loop*>(m_uv_handle->loop->data);
+  }
+
+  /**
+   * Check if the handle is active.
+   *
+   * What _active_ means depends on the type of handle:
+   *
+   * * An AsyncHandle handle is always active and cannot be deactivated,
+   * except by closing it with uv_close().
+   * * A PipeHandle, TcpHandle, UDPHandle, etc. handle - basically any handle
+   * that deals with I/O - is active when it is doing something that involves
+   * I/O, like reading, writing, connecting, accepting new connections, etc.
+   * * A CheckHandle, IdleHandle, TimerHandle, etc. handle is active when it
+   * has been started with a call to `Start()`.
+   *
+   * Rule of thumb: if a handle of type `FooHandle` has a `Start()` member
+   * method, then it’s active from the moment that method is called. Likewise,
+   * `Stop()` deactivates the handle again.
+   *
+   * @return True if the handle is active, false otherwise.
+   */
+  bool IsActive() const noexcept { return uv_is_active(m_uv_handle) != 0; }
+
+  /**
+   * Check if a handle is closing or closed.
+   *
+   * This function should only be used between the initialization of the
+   * handle and the arrival of the close callback.
+   *
+   * @return True if the handle is closing or closed, false otherwise.
+   */
+  bool IsClosing() const noexcept {
+    return m_closed || uv_is_closing(m_uv_handle) != 0;
+  }
+
+  /**
+   * Request handle to be closed.
+   *
+   * This **must** be called on each handle before memory is released.
+   * In-progress requests are cancelled and this can result in error() being
+   * emitted.
+   *
+   * The handle will emit closed() when finished.
+   */
+  void Close() noexcept;
+
+  /**
+   * Set if the loop is closing.
+   *
+   * This is set during EventLoopRunner.Stop(), and can be used for other cases
+   * to indicate the loop should be closing. For instance for a uv_walk loop can
+   * use this to close existing handles.
+   *
+   * @param loopClosing true to set the loop currently in closing stages.
+   */
+  void SetLoopClosing(bool loopClosing) noexcept {
+    m_loopClosing = loopClosing;
+  }
+
+  /**
+   * Get the loop closing status.
+   *
+   * This can be used from closed() in order to tell if a closing loop is the
+   * reason for the close, or another reason.
+   *
+   * @return true if the loop is closing, otherwise false.
+   */
+  bool IsLoopClosing() const noexcept { return m_loopClosing; }
+
+  /**
+   * Reference the given handle.
+   *
+   * References are idempotent, that is, if a handle is already referenced
+   * calling this function again will have no effect.
+   */
+  void Reference() noexcept { uv_ref(m_uv_handle); }
+
+  /**
+   * Unreference the given handle.
+   *
+   * References are idempotent, that is, if a handle is not referenced calling
+   * this function again will have no effect.
+   */
+  void Unreference() noexcept { uv_unref(m_uv_handle); }
+
+  /**
+   * Check if the given handle is referenced.
+   * @return True if the handle is referenced, false otherwise.
+   */
+  bool HasReference() const noexcept { return uv_has_ref(m_uv_handle) != 0; }
+
+  /**
+   * Return the size of the underlying handle type.
+   * @return The size of the underlying handle type.
+   */
+  size_t RawSize() const noexcept { return uv_handle_size(m_uv_handle->type); }
+
+  /**
+   * Get the underlying handle data structure.
+   *
+   * @return The underlying handle data structure.
+   */
+  uv_handle_t* GetRawHandle() const noexcept { return m_uv_handle; }
+
+  /**
+   * Set the functions used for allocating and releasing buffers.  The size
+   * passed to the allocator function is a "suggested" size--it's just an
+   * indication, not related in any way to the pending data to be read.  The
+   * user is free to allocate the amount of memory they decide.  For example,
+   * applications with custom allocation schemes may decide to use a different
+   * size which matches the memory chunks they already have for other purposes.
+   *
+   * @warning Be very careful changing the allocator after the loop has started
+   * running; there are no interlocks between this and buffers currently in
+   * flight.
+   *
+   * @param alloc Allocation function
+   * @param dealloc Deallocation function
+   */
+  void SetBufferAllocator(std::function<Buffer(size_t)> alloc,
+                          std::function<void(Buffer&)> dealloc) {
+    m_allocBuf = std::move(alloc);
+    m_freeBuf = std::move(dealloc);
+  }
+
+  /**
+   * Free a buffer.  Uses the function provided to SetBufFree() or
+   * Buffer::Deallocate by default.
+   *
+   * @param buf The buffer
+   */
+  void FreeBuf(Buffer& buf) const noexcept { m_freeBuf(buf); }
+
+  /**
+   * Gets user-defined data.
+   * @return User-defined data if any, nullptr otherwise.
+   */
+  template <typename T = void>
+  std::shared_ptr<T> GetData() const {
+    return std::static_pointer_cast<T>(m_data);
+  }
+
+  /**
+   * Sets user-defined data.
+   * @param data User-defined arbitrary data.
+   */
+  void SetData(std::shared_ptr<void> data) { m_data = std::move(data); }
+
+  /**
+   * Error signal
+   */
+  sig::Signal<Error> error;
+
+  /**
+   * Closed signal
+   */
+  sig::Signal<> closed;
+
+  /**
+   * Report an error.
+   * @param err Error code
+   */
+  void ReportError(int err) const { error(Error(err)); }
+
+ protected:
+  explicit Handle(uv_handle_t* uv_handle) : m_uv_handle{uv_handle} {
+    m_uv_handle->data = this;
+  }
+
+  void Keep() noexcept { m_self = shared_from_this(); }
+  void Release() noexcept { m_self.reset(); }
+  void ForceClosed() noexcept { m_closed = true; }
+
+  static void AllocBuf(uv_handle_t* handle, size_t size, uv_buf_t* buf);
+  static void DefaultFreeBuf(Buffer& buf);
+
+  template <typename F, typename... Args>
+  bool Invoke(F&& f, Args&&... args) const {
+    auto err = std::forward<F>(f)(std::forward<Args>(args)...);
+    if (err < 0) {
+      ReportError(err);
+    }
+    return err == 0;
+  }
+
+ private:
+  std::shared_ptr<Handle> m_self;
+  uv_handle_t* m_uv_handle;
+  bool m_closed = false;
+  bool m_loopClosing = false;
+  std::function<Buffer(size_t)> m_allocBuf{&Buffer::Allocate};
+  std::function<void(Buffer&)> m_freeBuf{&DefaultFreeBuf};
+  std::shared_ptr<void> m_data;
+};
+
+/**
+ * Handle.
+ */
+template <typename T, typename U>
+class HandleImpl : public Handle {
+ public:
+  std::shared_ptr<T> shared_from_this() {
+    return std::static_pointer_cast<T>(Handle::shared_from_this());
+  }
+
+  std::shared_ptr<const T> shared_from_this() const {
+    return std::static_pointer_cast<const T>(Handle::shared_from_this());
+  }
+
+  /**
+   * Get the underlying handle data structure.
+   *
+   * @return The underlying handle data structure.
+   */
+  U* GetRaw() const noexcept {
+    return reinterpret_cast<U*>(this->GetRawHandle());
+  }
+
+ protected:
+  HandleImpl() : Handle{static_cast<uv_handle_t*>(std::malloc(sizeof(U)))} {}
+};
+
+}  // namespace wpi::uv
+
+#endif  // WPINET_UV_HANDLE_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Idle.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Idle.h
new file mode 100644
index 0000000..4ed6d07
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Idle.h
@@ -0,0 +1,75 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_UV_IDLE_H_
+#define WPINET_UV_IDLE_H_
+
+#include <uv.h>
+
+#include <memory>
+
+#include <wpi/Signal.h>
+
+#include "wpinet/uv/Handle.h"
+
+namespace wpi::uv {
+
+class Loop;
+
+/**
+ * Idle handle.
+ *
+ * Idle handles will generate a signal once per loop iteration, right
+ * before the Prepare handles.
+ *
+ * The notable difference with Prepare handles is that when there are active
+ * idle handles, the loop will perform a zero timeout poll instead of blocking
+ * for I/O.
+ *
+ * @warning Despite the name, idle handles will signal every loop iteration,
+ * not when the loop is actually "idle".  This also means they can easly become
+ * CPU hogs.
+ */
+class Idle final : public HandleImpl<Idle, uv_idle_t> {
+  struct private_init {};
+
+ public:
+  explicit Idle(const private_init&) {}
+  ~Idle() noexcept override = default;
+
+  /**
+   * Create an idle handle.
+   *
+   * @param loop Loop object where this handle runs.
+   */
+  static std::shared_ptr<Idle> Create(Loop& loop);
+
+  /**
+   * Create an idle handle.
+   *
+   * @param loop Loop object where this handle runs.
+   */
+  static std::shared_ptr<Idle> Create(const std::shared_ptr<Loop>& loop) {
+    return Create(*loop);
+  }
+
+  /**
+   * Start the handle.
+   */
+  void Start();
+
+  /**
+   * Stop the handle.  The signal will no longer be generated.
+   */
+  void Stop() { Invoke(&uv_idle_stop, GetRaw()); }
+
+  /**
+   * Signal generated once per loop iteration prior to Prepare signals.
+   */
+  sig::Signal<> idle;
+};
+
+}  // namespace wpi::uv
+
+#endif  // WPINET_UV_IDLE_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Loop.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Loop.h
new file mode 100644
index 0000000..129faf5
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Loop.h
@@ -0,0 +1,254 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_UV_LOOP_H_
+#define WPINET_UV_LOOP_H_
+
+#include <uv.h>
+
+#include <atomic>
+#include <chrono>
+#include <functional>
+#include <memory>
+#include <thread>
+#include <utility>
+
+#include <wpi/Signal.h>
+#include <wpi/function_ref.h>
+
+#include "wpinet/uv/Error.h"
+
+namespace wpi::uv {
+
+class Handle;
+
+/**
+ * Event loop.
+ *
+ * The event loop is the central part of uv functionality.  It takes care of
+ * polling for I/O and scheduling signals to be generated based on different
+ * sources of events.
+ *
+ * The event loop is not moveable, copyable, or directly constructible.  Use
+ * Create() to create an event loop, or GetDefault() to get the default loop
+ * if you know your program will only have a single one.
+ */
+class Loop final : public std::enable_shared_from_this<Loop> {
+  struct private_init {};
+
+ public:
+  using Time = std::chrono::duration<uint64_t, std::milli>;
+
+  enum Mode {
+    kDefault = UV_RUN_DEFAULT,
+    kOnce = UV_RUN_ONCE,
+    kNoWait = UV_RUN_NOWAIT
+  };
+
+  explicit Loop(const private_init&) noexcept;
+
+  Loop(const Loop&) = delete;
+  Loop& operator=(const Loop&) = delete;
+  Loop(Loop&& oth) = delete;
+  Loop& operator=(Loop&& oth) = delete;
+
+  ~Loop() noexcept;
+
+  /**
+   * Create a new event loop.  The created loop is not the default event loop.
+   *
+   * @return The newly created loop.  May return nullptr if a failure occurs.
+   */
+  static std::shared_ptr<Loop> Create();
+
+  /**
+   * Create the default event loop.  Only use this event loop if a single loop
+   * is needed for the entire application.
+   *
+   * @return The newly created loop.  May return nullptr if a failure occurs.
+   */
+  static std::shared_ptr<Loop> GetDefault();
+
+  /**
+   * Release all internal loop resources.
+   *
+   * Call this function only when the loop has finished executing and all open
+   * handles and requests have been closed, or the loop will emit an error.
+   *
+   * error() will be emitted in case of errors.
+   */
+  void Close();
+
+  /**
+   * Run the event loop.
+   *
+   * Available modes are:
+   *
+   * * `Loop::kDefault`: Run the event loop until there are no
+   *                     active and referenced handles or requests.
+   * * `Loop::kOnce`: Run a single event loop iteration. Note that this
+   *                  function blocksif there are no pending callbacks.
+   * * `Loop::kNoWait`: Run a single event loop iteration, but don't block
+   *                    if there are no pending callbacks.
+   *
+   * @return True when done, false in all other cases.
+   */
+  bool Run(Mode mode = kDefault) {
+    m_tid = std::this_thread::get_id();
+    int rv = uv_run(m_loop, static_cast<uv_run_mode>(static_cast<int>(mode)));
+    m_tid = std::thread::id{};
+    return rv == 0;
+  }
+
+  /**
+   * Check if there are active resources.
+   *
+   * @return True if there are active resources in the loop.
+   */
+  bool IsAlive() const noexcept { return uv_loop_alive(m_loop) != 0; }
+
+  /**
+   * Stop the event loop.
+   *
+   * This will cause Run() to end as soon as possible.
+   * This will happen not sooner than the next loop iteration.
+   * If this function was called before blocking for I/O, the loop won’t block
+   * for I/O on this iteration.
+   */
+  void Stop() noexcept { uv_stop(m_loop); }
+
+  /**
+   * Get backend file descriptor.
+   *
+   * Only kqueue, epoll and event ports are supported.
+   * This can be used in conjunction with `run(Loop::kNoWait)` to poll
+   * in one thread and run the event loop’s callbacks in another.
+   *
+   * @return The backend file descriptor.
+   */
+  int GetDescriptor() const noexcept { return uv_backend_fd(m_loop); }
+
+  /**
+   * Get the poll timeout.
+   *
+   * @return A `std::pair` composed of a boolean value that is true in case of
+   * valid timeout, false otherwise, and the timeout
+   * (`std::chrono::duration<uint64_t, std::milli>`).
+   */
+  std::pair<bool, Time> GetTimeout() const noexcept {
+    auto to = uv_backend_timeout(m_loop);
+    return std::make_pair(to == -1, Time{to});
+  }
+
+  /**
+   * Return the current timestamp in milliseconds.
+   *
+   * The timestamp is cached at the start of the event loop tick.
+   * The timestamp increases monotonically from some arbitrary point in
+   * time.
+   * Don’t make assumptions about the starting point, you will only get
+   * disappointed.
+   *
+   * @return The current timestamp in milliseconds (actual type is
+   * `std::chrono::duration<uint64_t, std::milli>`).
+   */
+  Time Now() const noexcept { return Time{uv_now(m_loop)}; }
+
+  /**
+   * Update the event loop’s concept of _now_.
+   *
+   * The current time is cached at the start of the event loop tick in order
+   * to reduce the number of time-related system calls.
+   * You won’t normally need to call this function unless you have callbacks
+   * that block the event loop for longer periods of time, where _longer_ is
+   * somewhat subjective but probably on the order of a millisecond or more.
+   */
+  void UpdateTime() noexcept { uv_update_time(m_loop); }
+
+  /**
+   * Walk the list of handles.
+   *
+   * The callback will be executed once for each handle that is still active.
+   *
+   * @param callback A function to be invoked once for each active handle.
+   */
+  void Walk(function_ref<void(Handle&)> callback);
+
+  /**
+   * Reinitialize any kernel state necessary in the child process after
+   * a fork(2) system call.
+   *
+   * Previously started watchers will continue to be started in the child
+   * process.
+   *
+   * It is necessary to explicitly call this function on every event loop
+   * created in the parent process that you plan to continue to use in the
+   * child, including the default loop (even if you don’t continue to use it
+   * in the parent). This function must be called before calling any API
+   * function using the loop in the child. Failure to do so will result in
+   * undefined behaviour, possibly including duplicate events delivered to
+   * both parent and child or aborting the child process.
+   *
+   * When possible, it is preferred to create a new loop in the child process
+   * instead of reusing a loop created in the parent. New loops created in the
+   * child process after the fork should not use this function.
+   *
+   * Note that this function is not implemented on Windows.
+   * Note also that this function is experimental in `libuv`. It may contain
+   * bugs, and is subject to change or removal. API and ABI stability is not
+   * guaranteed.
+   *
+   * error() will be emitted in case of errors.
+   */
+  void Fork();
+
+  /**
+   * Get the underlying event loop data structure.
+   *
+   * @return The underlying event loop data structure.
+   */
+  uv_loop_t* GetRaw() const noexcept { return m_loop; }
+
+  /**
+   * Gets user-defined data.
+   * @return User-defined data if any, nullptr otherwise.
+   */
+  template <typename T = void>
+  std::shared_ptr<T> GetData() const {
+    return std::static_pointer_cast<T>(m_data);
+  }
+
+  /**
+   * Sets user-defined data.
+   * @param data User-defined arbitrary data.
+   */
+  void SetData(std::shared_ptr<void> data) { m_data = std::move(data); }
+
+  /**
+   * Get the thread id of the loop thread.  If the loop is not currently
+   * running, returns default-constructed thread id.
+   */
+  std::thread::id GetThreadId() const { return m_tid; }
+
+  /**
+   * Error signal
+   */
+  sig::Signal<Error> error;
+
+  /**
+   * Reports error.
+   * @param err Error code
+   */
+  void ReportError(int err) { error(Error(err)); }
+
+ private:
+  std::shared_ptr<void> m_data;
+  uv_loop_t* m_loop;
+  uv_loop_t m_loopStruct;
+  std::atomic<std::thread::id> m_tid;
+};
+
+}  // namespace wpi::uv
+
+#endif  // WPINET_UV_LOOP_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/NetworkStream.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/NetworkStream.h
new file mode 100644
index 0000000..42b0a8a
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/NetworkStream.h
@@ -0,0 +1,154 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_UV_NETWORKSTREAM_H_
+#define WPINET_UV_NETWORKSTREAM_H_
+
+#include <uv.h>
+
+#include <cstdlib>
+#include <functional>
+#include <memory>
+
+#include <wpi/Signal.h>
+
+#include "wpinet/uv/Stream.h"
+
+namespace wpi::uv {
+
+class NetworkStream;
+
+/**
+ * Connection request.
+ */
+class ConnectReq : public RequestImpl<ConnectReq, uv_connect_t> {
+ public:
+  ConnectReq();
+
+  NetworkStream& GetStream() const {
+    return *static_cast<NetworkStream*>(GetRaw()->handle->data);
+  }
+
+  /**
+   * Connection completed signal.
+   */
+  sig::Signal<> connected;
+};
+
+/**
+ * Network stream handle.
+ * This is an abstract type; there are two network stream implementations (Tcp
+ * and Pipe).
+ */
+class NetworkStream : public Stream {
+ public:
+  static constexpr int kDefaultBacklog = 128;
+
+  std::shared_ptr<NetworkStream> shared_from_this() {
+    return std::static_pointer_cast<NetworkStream>(Handle::shared_from_this());
+  }
+
+  std::shared_ptr<const NetworkStream> shared_from_this() const {
+    return std::static_pointer_cast<const NetworkStream>(
+        Handle::shared_from_this());
+  }
+
+  /**
+   * Start listening for incoming connections.  When a new incoming connection
+   * is received the connection signal is generated.
+   * @param backlog the number of connections the kernel might queue, same as
+   *        listen(2).
+   */
+  void Listen(int backlog = kDefaultBacklog);
+
+  /**
+   * Start listening for incoming connections.  This is a convenience wrapper
+   * around `Listen(int)` that also connects a callback to the connection
+   * signal.  When a new incoming connection is received the connection signal
+   * is generated (and the callback is called).
+   * @param callback the callback to call when a connection is received.
+   *        `Accept()` should be called from this callback.
+   * @param backlog the number of connections the kernel might queue, same as
+   *        listen(2).
+   */
+  void Listen(std::function<void()> callback, int backlog = kDefaultBacklog);
+
+  /**
+   * Accept incoming connection.
+   *
+   * This call is used in conjunction with `Listen()` to accept incoming
+   * connections. Call this function after receiving a ListenEvent event to
+   * accept the connection.
+   * An error signal will be emitted in case of errors.
+   *
+   * When the connection signal is emitted it is guaranteed that this
+   * function will complete successfully the first time. If you attempt to use
+   * it more than once, it may fail.
+   * It is suggested to only call this function once per connection signal.
+   *
+   * @return The stream handle for the accepted connection, or nullptr on error.
+   */
+  std::shared_ptr<NetworkStream> Accept() {
+    return DoAccept()->shared_from_this();
+  }
+
+  /**
+   * Accept incoming connection.
+   *
+   * This call is used in conjunction with `Listen()` to accept incoming
+   * connections. Call this function after receiving a connection signal to
+   * accept the connection.
+   * An error signal will be emitted in case of errors.
+   *
+   * When the connection signal is emitted it is guaranteed that this
+   * function will complete successfully the first time. If you attempt to use
+   * it more than once, it may fail.
+   * It is suggested to only call this function once per connection signal.
+   *
+   * @param client Client stream object.
+   * @return False on error.
+   */
+  bool Accept(const std::shared_ptr<NetworkStream>& client) {
+    return Invoke(&uv_accept, GetRawStream(), client->GetRawStream());
+  }
+
+  /**
+   * Signal generated when an incoming connection is received.
+   */
+  sig::Signal<> connection;
+
+ protected:
+  explicit NetworkStream(uv_stream_t* uv_stream) : Stream{uv_stream} {}
+
+  virtual NetworkStream* DoAccept() = 0;
+};
+
+template <typename T, typename U>
+class NetworkStreamImpl : public NetworkStream {
+ public:
+  std::shared_ptr<T> shared_from_this() {
+    return std::static_pointer_cast<T>(Handle::shared_from_this());
+  }
+
+  std::shared_ptr<const T> shared_from_this() const {
+    return std::static_pointer_cast<const T>(Handle::shared_from_this());
+  }
+
+  /**
+   * Get the underlying handle data structure.
+   *
+   * @return The underlying handle data structure.
+   */
+  U* GetRaw() const noexcept {
+    return reinterpret_cast<U*>(this->GetRawHandle());
+  }
+
+ protected:
+  NetworkStreamImpl()
+      : NetworkStream{static_cast<uv_stream_t*>(std::malloc(sizeof(U)))} {}
+};
+
+}  // namespace wpi::uv
+
+#endif  // WPINET_UV_NETWORKSTREAM_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Pipe.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Pipe.h
new file mode 100644
index 0000000..d7ab044
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Pipe.h
@@ -0,0 +1,208 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_UV_PIPE_H_
+#define WPINET_UV_PIPE_H_
+
+#include <uv.h>
+
+#include <functional>
+#include <memory>
+#include <string>
+#include <string_view>
+
+#include "wpinet/uv/NetworkStream.h"
+
+namespace wpi::uv {
+
+class Loop;
+class PipeConnectReq;
+
+/**
+ * Pipe handle.
+ * Pipe handles provide an abstraction over local domain sockets on Unix and
+ * named pipes on Windows.
+ */
+class Pipe final : public NetworkStreamImpl<Pipe, uv_pipe_t> {
+  struct private_init {};
+
+ public:
+  explicit Pipe(const private_init&) {}
+  ~Pipe() noexcept override = default;
+
+  /**
+   * Create a pipe handle.
+   *
+   * @param loop Loop object where this handle runs.
+   * @param ipc Indicates if this pipe will be used for handle passing between
+   *            processes.
+   */
+  static std::shared_ptr<Pipe> Create(Loop& loop, bool ipc = false);
+
+  /**
+   * Create a pipe handle.
+   *
+   * @param loop Loop object where this handle runs.
+   * @param ipc Indicates if this pipe will be used for handle passing between
+   *            processes.
+   */
+  static std::shared_ptr<Pipe> Create(const std::shared_ptr<Loop>& loop,
+                                      bool ipc = false) {
+    return Create(*loop, ipc);
+  }
+
+  /**
+   * Reuse this handle.  This closes the handle, and after the close completes,
+   * reinitializes it (identically to Create) and calls the provided callback.
+   * Unlike Close(), it does NOT emit the closed signal, however, IsClosing()
+   * will return true until the callback is called.  This does nothing if
+   * IsClosing() is true (e.g. if Close() was called).
+   *
+   * @param ipc IPC
+   * @param callback Callback
+   */
+  void Reuse(std::function<void()> callback, bool ipc = false);
+
+  /**
+   * Accept incoming connection.
+   *
+   * This call is used in conjunction with `Listen()` to accept incoming
+   * connections. Call this function after receiving a ListenEvent event to
+   * accept the connection.
+   * An error signal will be emitted in case of errors.
+   *
+   * When the connection signal is emitted it is guaranteed that this
+   * function will complete successfully the first time. If you attempt to use
+   * it more than once, it may fail.
+   * It is suggested to only call this function once per connection signal.
+   *
+   * @return The stream handle for the accepted connection, or nullptr on error.
+   */
+  std::shared_ptr<Pipe> Accept();
+
+  /**
+   * Accept incoming connection.
+   *
+   * This call is used in conjunction with `Listen()` to accept incoming
+   * connections. Call this function after receiving a connection signal to
+   * accept the connection.
+   * An error signal will be emitted in case of errors.
+   *
+   * When the connection signal is emitted it is guaranteed that this
+   * function will complete successfully the first time. If you attempt to use
+   * it more than once, it may fail.
+   * It is suggested to only call this function once per connection signal.
+   *
+   * @param client Client stream object.
+   * @return False on error.
+   */
+  bool Accept(const std::shared_ptr<Pipe>& client) {
+    return NetworkStream::Accept(client);
+  }
+
+  /**
+   * Open an existing file descriptor or HANDLE as a pipe.
+   *
+   * @note The passed file descriptor or HANDLE is not checked for its type, but
+   * it's required that it represents a valid pipe.
+   *
+   * @param file A valid file handle (either a file descriptor or a HANDLE).
+   */
+  void Open(uv_file file) { Invoke(&uv_pipe_open, GetRaw(), file); }
+
+  /**
+   * Bind the pipe to a file path (Unix) or a name (Windows).
+   *
+   * @note Paths on Unix get truncated to `sizeof(sockaddr_un.sun_path)` bytes,
+   * typically between 92 and 108 bytes.
+   *
+   * @param name File path (Unix) or name (Windows).
+   */
+  void Bind(std::string_view name);
+
+  /**
+   * Connect to the Unix domain socket or the named pipe.
+   *
+   * @note Paths on Unix get truncated to `sizeof(sockaddr_un.sun_path)` bytes,
+   * typically between 92 and 108 bytes.
+   *
+   * HandleConnected() is called on the request when the connection has been
+   * established.
+   * HandleError() is called on the request in case of errors during the
+   * connection.
+   *
+   * @param name File path (Unix) or name (Windows).
+   * @param req connection request
+   */
+  void Connect(std::string_view name,
+               const std::shared_ptr<PipeConnectReq>& req);
+
+  /**
+   * Connect to the Unix domain socket or the named pipe.
+   *
+   * @note Paths on Unix get truncated to `sizeof(sockaddr_un.sun_path)` bytes,
+   * typically between 92 and 108 bytes.
+   *
+   * The callback is called when the connection has been established.  Errors
+   * are reported to the stream error handler.
+   *
+   * @param name File path (Unix) or name (Windows).
+   * @param callback Callback function to call when connection established
+   */
+  void Connect(std::string_view name, std::function<void()> callback);
+
+  /**
+   * Get the name of the Unix domain socket or the named pipe.
+   * @return The name (will be empty if an error occurred).
+   */
+  std::string GetSock();
+
+  /**
+   * Get the name of the Unix domain socket or the named pipe to which the
+   * handle is connected.
+   * @return The name (will be empty if an error occurred).
+   */
+  std::string GetPeer();
+
+  /**
+   * Set the number of pending pipe instance handles when the pipe server is
+   * waiting for connections.
+   * @note This setting applies to Windows only.
+   * @param count Number of pending handles.
+   */
+  void SetPendingInstances(int count) {
+    uv_pipe_pending_instances(GetRaw(), count);
+  }
+
+  /**
+   * Alters pipe permissions, allowing it to be accessed from processes run
+   * by different users.  Makes the pipe writable or readable by all users.
+   * Mode can be UV_WRITABLE, UV_READABLE, or both.  This function is blocking.
+   * @param flags chmod flags
+   */
+  void Chmod(int flags) { Invoke(&uv_pipe_chmod, GetRaw(), flags); }
+
+ private:
+  Pipe* DoAccept() override;
+
+  struct ReuseData {
+    std::function<void()> callback;
+    bool ipc;
+  };
+  std::unique_ptr<ReuseData> m_reuseData;
+};
+
+/**
+ * Pipe connection request.
+ */
+class PipeConnectReq : public ConnectReq {
+ public:
+  Pipe& GetStream() const {
+    return *static_cast<Pipe*>(&ConnectReq::GetStream());
+  }
+};
+
+}  // namespace wpi::uv
+
+#endif  // WPINET_UV_PIPE_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Poll.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Poll.h
new file mode 100644
index 0000000..1e63836
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Poll.h
@@ -0,0 +1,122 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_UV_POLL_H_
+#define WPINET_UV_POLL_H_
+
+#include <uv.h>
+
+#include <memory>
+
+#include <wpi/Signal.h>
+
+#include "wpinet/uv/Handle.h"
+
+namespace wpi::uv {
+
+class Loop;
+
+/**
+ * Poll handle.
+ */
+class Poll final : public HandleImpl<Poll, uv_poll_t> {
+  struct private_init {};
+
+ public:
+  explicit Poll(const private_init&) {}
+  ~Poll() noexcept override = default;
+
+  /**
+   * Create a poll handle using a file descriptor.
+   *
+   * @param loop Loop object where this handle runs.
+   * @param fd File descriptor.
+   */
+  static std::shared_ptr<Poll> Create(Loop& loop, int fd);
+
+  /**
+   * Create a poll handle using a file descriptor.
+   *
+   * @param loop Loop object where this handle runs.
+   * @param fd File descriptor.
+   */
+  static std::shared_ptr<Poll> Create(const std::shared_ptr<Loop>& loop,
+                                      int fd) {
+    return Create(*loop, fd);
+  }
+
+  /**
+   * Create a poll handle using a socket descriptor.
+   *
+   * @param loop Loop object where this handle runs.
+   * @param sock Socket descriptor.
+   */
+  static std::shared_ptr<Poll> CreateSocket(Loop& loop, uv_os_sock_t sock);
+
+  /**
+   * Create a poll handle using a socket descriptor.
+   *
+   * @param loop Loop object where this handle runs.
+   * @param sock Socket descriptor.
+   */
+  static std::shared_ptr<Poll> CreateSocket(const std::shared_ptr<Loop>& loop,
+                                            uv_os_sock_t sock) {
+    return CreateSocket(*loop, sock);
+  }
+
+  /**
+   * Reuse this handle.  This closes the handle, and after the close completes,
+   * reinitializes it (identically to Create) and calls the provided callback.
+   * Unlike Close(), it does NOT emit the closed signal, however, IsClosing()
+   * will return true until the callback is called.  This does nothing if
+   * IsClosing() is true (e.g. if Close() was called).
+   *
+   * @param fd File descriptor
+   * @param callback Callback
+   */
+  void Reuse(int fd, std::function<void()> callback);
+
+  /**
+   * Reuse this handle.  This closes the handle, and after the close completes,
+   * reinitializes it (identically to CreateSocket) and calls the provided
+   * callback.  Unlike Close(), it does NOT emit the closed signal, however,
+   * IsClosing() will return true until the callback is called.  This does
+   * nothing if IsClosing() is true (e.g. if Close() was called).
+   *
+   * @param sock Socket descriptor.
+   * @param callback Callback
+   */
+  void ReuseSocket(uv_os_sock_t sock, std::function<void()> callback);
+
+  /**
+   * Start polling the file descriptor.
+   *
+   * @param events Bitmask of events (UV_READABLE, UV_WRITEABLE, UV_PRIORITIZED,
+   *               and UV_DISCONNECT).
+   */
+  void Start(int events);
+
+  /**
+   * Stop polling the file descriptor.
+   */
+  void Stop() { Invoke(&uv_poll_stop, GetRaw()); }
+
+  /**
+   * Signal generated when a poll event occurs.
+   */
+  sig::Signal<int> pollEvent;
+
+ private:
+  struct ReuseData {
+    std::function<void()> callback;
+    bool isSocket;
+    int fd;
+    uv_os_sock_t sock;
+  };
+  std::unique_ptr<ReuseData> m_reuseData;
+};
+
+}  // namespace wpi::uv
+
+#endif  // WPINET_UV_POLL_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Prepare.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Prepare.h
new file mode 100644
index 0000000..e19dd30
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Prepare.h
@@ -0,0 +1,66 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_UV_PREPARE_H_
+#define WPINET_UV_PREPARE_H_
+
+#include <uv.h>
+
+#include <memory>
+
+#include <wpi/Signal.h>
+
+#include "wpinet/uv/Handle.h"
+
+namespace wpi::uv {
+
+class Loop;
+
+/**
+ * Prepare handle.
+ * Prepare handles will generate a signal once per loop iteration, right
+ * before polling for I/O.
+ */
+class Prepare final : public HandleImpl<Prepare, uv_prepare_t> {
+  struct private_init {};
+
+ public:
+  explicit Prepare(const private_init&) {}
+  ~Prepare() noexcept override = default;
+
+  /**
+   * Create a prepare handle.
+   *
+   * @param loop Loop object where this handle runs.
+   */
+  static std::shared_ptr<Prepare> Create(Loop& loop);
+
+  /**
+   * Create a prepare handle.
+   *
+   * @param loop Loop object where this handle runs.
+   */
+  static std::shared_ptr<Prepare> Create(const std::shared_ptr<Loop>& loop) {
+    return Create(*loop);
+  }
+
+  /**
+   * Start the handle.
+   */
+  void Start();
+
+  /**
+   * Stop the handle.  The signal will no longer be generated.
+   */
+  void Stop() { Invoke(&uv_prepare_stop, GetRaw()); }
+
+  /**
+   * Signal generated once per loop iteration prior to polling for I/O.
+   */
+  sig::Signal<> prepare;
+};
+
+}  // namespace wpi::uv
+
+#endif  // WPINET_UV_PREPARE_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Process.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Process.h
new file mode 100644
index 0000000..3d84bde
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Process.h
@@ -0,0 +1,311 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_UV_PROCESS_H_
+#define WPINET_UV_PROCESS_H_
+
+#include <uv.h>
+
+#include <initializer_list>
+#include <memory>
+#include <span>
+#include <string>
+#include <string_view>
+
+#include <wpi/Signal.h>
+#include <wpi/SmallVector.h>
+
+#include "wpinet/uv/Handle.h"
+
+namespace wpi::uv {
+
+class Loop;
+class Pipe;
+
+/**
+ * Process handle.
+ * Process handles will spawn a new process and allow the user to control it
+ * and establish communication channels with it using streams.
+ */
+class Process final : public HandleImpl<Process, uv_process_t> {
+  struct private_init {};
+
+ public:
+  explicit Process(const private_init&) {}
+  ~Process() noexcept override = default;
+
+  /**
+   * Structure for Spawn() option temporaries.  This is a reference type, so if
+   * this value is stored outside of a temporary, be careful about overwriting
+   * what it points to.
+   */
+  struct Option {
+    enum Type {
+      kNone,
+      kArg,
+      kEnv,
+      kCwd,
+      kUid,
+      kGid,
+      kSetFlags,
+      kClearFlags,
+      kStdioIgnore,
+      kStdioInheritFd,
+      kStdioInheritPipe,
+      kStdioCreatePipe
+    };
+
+    Option() : m_type(kNone) {}
+
+    /*implicit*/ Option(const char* arg) {  // NOLINT
+      m_data.str = arg;
+    }
+
+    /*implicit*/ Option(const std::string& arg) {  // NOLINT
+      m_data.str = arg.data();
+    }
+
+    /*implicit*/ Option(std::string_view arg)  // NOLINT
+        : m_strData(arg) {
+      m_data.str = m_strData.c_str();
+    }
+
+    /*implicit*/ Option(const SmallVectorImpl<char>& arg)  // NOLINT
+        : m_strData(arg.data(), arg.size()) {
+      m_data.str = m_strData.c_str();
+    }
+
+    explicit Option(Type type) : m_type(type) {}
+
+    Type m_type = kArg;
+    std::string m_strData;
+    union {
+      const char* str;
+      uv_uid_t uid;
+      uv_gid_t gid;
+      unsigned int flags;
+      struct {
+        size_t index;
+        union {
+          int fd;
+          Pipe* pipe;
+        };
+        unsigned int flags;
+      } stdio;
+    } m_data;
+  };
+
+  /**
+   * Set environment variable for the subprocess.  If not set, the parent's
+   * environment is used.
+   * @param env environment variable
+   */
+  static Option Env(std::string_view env) {
+    Option o(Option::kEnv);
+    o.m_strData = env;
+    o.m_data.str = o.m_strData.c_str();
+    return o;
+  }
+
+  /**
+   * Set the current working directory for the subprocess.
+   * @param cwd current working directory
+   */
+  static Option Cwd(std::string_view cwd) {
+    Option o(Option::kCwd);
+    o.m_strData = cwd;
+    o.m_data.str = o.m_strData.c_str();
+    return o;
+  }
+
+  /**
+   * Set the child process' user id.
+   * @param uid user id
+   */
+  static Option Uid(uv_uid_t uid) {
+    Option o(Option::kUid);
+    o.m_data.uid = uid;
+    return o;
+  }
+
+  /**
+   * Set the child process' group id.
+   * @param gid group id
+   */
+  static Option Gid(uv_gid_t gid) {
+    Option o(Option::kGid);
+    o.m_data.gid = gid;
+    return o;
+  }
+
+  /**
+   * Set spawn flags.
+   * @param flags Bitmask values from uv_process_flags.
+   */
+  static Option SetFlags(unsigned int flags) {
+    Option o(Option::kSetFlags);
+    o.m_data.flags = flags;
+    return o;
+  }
+
+  /**
+   * Clear spawn flags.
+   * @param flags Bitmask values from uv_process_flags.
+   */
+  static Option ClearFlags(unsigned int flags) {
+    Option o(Option::kClearFlags);
+    o.m_data.flags = flags;
+    return o;
+  }
+
+  /**
+   * Explicitly ignore a stdio.
+   * @param index stdio index
+   */
+  static Option StdioIgnore(size_t index) {
+    Option o(Option::kStdioIgnore);
+    o.m_data.stdio.index = index;
+    return o;
+  }
+
+  /**
+   * Inherit a file descriptor from the parent process.
+   * @param index stdio index
+   * @param fd parent file descriptor
+   */
+  static Option StdioInherit(size_t index, int fd) {
+    Option o(Option::kStdioInheritFd);
+    o.m_data.stdio.index = index;
+    o.m_data.stdio.fd = fd;
+    return o;
+  }
+
+  /**
+   * Inherit a pipe from the parent process.
+   * @param index stdio index
+   * @param pipe pipe
+   */
+  static Option StdioInherit(size_t index, Pipe& pipe) {
+    Option o(Option::kStdioInheritPipe);
+    o.m_data.stdio.index = index;
+    o.m_data.stdio.pipe = &pipe;
+    return o;
+  }
+
+  /**
+   * Create a pipe between the child and the parent.
+   * @param index stdio index
+   * @param pipe pipe
+   * @param flags Some combination of UV_READABLE_PIPE, UV_WRITABLE_PIPE, and
+   *              UV_OVERLAPPED_PIPE (Windows only, ignored on Unix).
+   */
+  static Option StdioCreatePipe(size_t index, Pipe& pipe, unsigned int flags) {
+    Option o(Option::kStdioCreatePipe);
+    o.m_data.stdio.index = index;
+    o.m_data.stdio.pipe = &pipe;
+    o.m_data.stdio.flags = flags;
+    return o;
+  }
+
+  /**
+   * Disables inheritance for file descriptors / handles that this process
+   * inherited from its parent.  The effect is that child processes spawned
+   * by this process don't accidentally inherit these handles.
+   *
+   * It is recommended to call this function as early in your program as
+   * possible, before the inherited file descriptors can be closed or
+   * duplicated.
+   */
+  static void DisableStdioInheritance() { uv_disable_stdio_inheritance(); }
+
+  /**
+   * Starts a process.  If the process is not successfully spawned, an error
+   * is generated on the loop and this function returns nullptr.
+   *
+   * Possible reasons for failing to spawn would include (but not be limited to)
+   * the file to execute not existing, not having permissions to use the setuid
+   * or setgid specified, or not having enough memory to allocate for the new
+   * process.
+   *
+   * @param loop Loop object where this handle runs.
+   * @param file Path pointing to the program to be executed
+   * @param options Process options
+   */
+  static std::shared_ptr<Process> SpawnArray(Loop& loop, std::string_view file,
+                                             std::span<const Option> options);
+
+  static std::shared_ptr<Process> SpawnArray(
+      Loop& loop, std::string_view file,
+      std::initializer_list<Option> options) {
+    return SpawnArray(loop, file, {options.begin(), options.end()});
+  }
+
+  template <typename... Args>
+  static std::shared_ptr<Process> Spawn(Loop& loop, std::string_view file,
+                                        const Args&... options) {
+    return SpawnArray(loop, file, {options...});
+  }
+
+  /**
+   * Starts a process.  If the process is not successfully spawned, an error
+   * is generated on the loop and this function returns nullptr.
+   *
+   * Possible reasons for failing to spawn would include (but not be limited to)
+   * the file to execute not existing, not having permissions to use the setuid
+   * or setgid specified, or not having enough memory to allocate for the new
+   * process.
+   *
+   * @param loop Loop object where this handle runs.
+   * @param file Path pointing to the program to be executed
+   * @param options Process options
+   */
+  static std::shared_ptr<Process> SpawnArray(const std::shared_ptr<Loop>& loop,
+                                             std::string_view file,
+                                             std::span<const Option> options) {
+    return SpawnArray(*loop, file, options);
+  }
+
+  static std::shared_ptr<Process> SpawnArray(
+      const std::shared_ptr<Loop>& loop, std::string_view file,
+      std::initializer_list<Option> options) {
+    return SpawnArray(*loop, file, options);
+  }
+
+  template <typename... Args>
+  static std::shared_ptr<Process> Spawn(const std::shared_ptr<Loop>& loop,
+                                        std::string_view file,
+                                        const Args&... options) {
+    return SpawnArray(*loop, file, {options...});
+  }
+
+  /**
+   * Sends the specified signal to the process.
+   * @param signum signal number
+   */
+  void Kill(int signum) { Invoke(&uv_process_kill, GetRaw(), signum); }
+
+  /**
+   * Sends the specified signal to the given PID.
+   * @param pid process ID
+   * @param signum signal number
+   * @return 0 on success, otherwise error code.
+   */
+  static int Kill(int pid, int signum) noexcept { return uv_kill(pid, signum); }
+
+  /**
+   * Get the process ID.
+   * @return Process ID.
+   */
+  uv_pid_t GetPid() const noexcept { return GetRaw()->pid; }
+
+  /**
+   * Signal generated when the process exits.  The parameters are the exit
+   * status and the signal that caused the process to terminate, if any.
+   */
+  sig::Signal<int64_t, int> exited;
+};
+
+}  // namespace wpi::uv
+
+#endif  // WPINET_UV_PROCESS_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Request.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Request.h
new file mode 100644
index 0000000..3fbec6f
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Request.h
@@ -0,0 +1,166 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_UV_REQUEST_H_
+#define WPINET_UV_REQUEST_H_
+
+#include <uv.h>
+
+#include <functional>
+#include <memory>
+
+#include "wpinet/uv/Error.h"
+
+namespace wpi::uv {
+
+/**
+ * Request.  Requests are not moveable or copyable.
+ * This class provides shared_ptr ownership and shared_from_this.
+ */
+class Request : public std::enable_shared_from_this<Request> {
+ public:
+  using Type = uv_req_type;
+
+  Request(const Request&) = delete;
+  Request(Request&&) = delete;
+  Request& operator=(const Request&) = delete;
+  Request& operator=(Request&&) = delete;
+  virtual ~Request() noexcept = default;
+
+  /**
+   * Get the type of the request.
+   *
+   * A base request offers no functionality to promote it to the actual request
+   * type. By means of this function, the type of the underlying request as
+   * specified by Type is made available.
+   *
+   * @return The actual type of the request.
+   */
+  Type GetType() const noexcept { return m_uv_req->type; }
+
+  /**
+   * Get the name of the type of the request.  E.g. "connect" for connect.
+   */
+  const char* GetTypeName() const noexcept {
+    return uv_req_type_name(m_uv_req->type);
+  }
+
+  /**
+   * Cancel a pending request.
+   *
+   * This method fails if the request is executing or has finished
+   * executing.
+   * It can emit an error signal in case of errors.
+   *
+   * @return True in case of success, false otherwise.
+   */
+  bool Cancel() { return uv_cancel(m_uv_req) == 0; }
+
+  /**
+   * Return the size of the underlying request type.
+   * @return The size of the underlying request type.
+   */
+  size_t RawSize() const noexcept { return uv_req_size(m_uv_req->type); }
+
+  /**
+   * Get the underlying request data structure.
+   *
+   * @return The underlying request data structure.
+   */
+  uv_req_t* GetRawReq() noexcept { return m_uv_req; }
+
+  /**
+   * Get the underlying request data structure.
+   *
+   * @return The underlying request data structure.
+   */
+  const uv_req_t* GetRawReq() const noexcept { return m_uv_req; }
+
+  /**
+   * Keep this request in memory even if no outside shared_ptr references
+   * remain.  To release call Release().
+   *
+   * Derived classes can override this method for different memory management
+   * approaches (e.g. pooled storage of requests).
+   */
+  virtual void Keep() noexcept { m_self = shared_from_this(); }
+
+  /**
+   * No longer force holding this request in memory.  Does not immediately
+   * destroy the object unless no outside shared_ptr references remain.
+   *
+   * Derived classes can override this method for different memory management
+   * approaches (e.g. pooled storage of requests).
+   */
+  virtual void Release() noexcept { m_self.reset(); }
+
+  /**
+   * Error callback.  By default, this is set up to report errors to the handle
+   * that created this request.
+   * @param err error code
+   */
+  std::function<void(Error)> error;
+
+  /**
+   * Report an error.
+   * @param err Error code
+   */
+  void ReportError(int err) { error(Error(err)); }
+
+ protected:
+  /**
+   * Constructor.
+   */
+  explicit Request(uv_req_t* uv_req) : m_uv_req{uv_req} {
+    m_uv_req->data = this;
+  }
+
+ private:
+  std::shared_ptr<Request> m_self;
+  uv_req_t* m_uv_req;
+};
+
+/**
+ * Request.  Requests are not moveable or copyable.
+ * @tparam T CRTP derived class
+ * @tparam U underlying libuv request type
+ */
+template <typename T, typename U>
+class RequestImpl : public Request {
+ public:
+  std::shared_ptr<T> shared_from_this() {
+    return std::static_pointer_cast<T>(this->shared_from_this());
+  }
+
+  std::shared_ptr<const T> shared_from_this() const {
+    return std::static_pointer_cast<const T>(this->shared_from_this());
+  }
+
+  /**
+   * Get the underlying request data structure.
+   *
+   * @return The underlying request data structure.
+   */
+  U* GetRaw() noexcept { return &m_uv_req; }
+
+  /**
+   * Get the underlying request data structure.
+   *
+   * @return The underlying request data structure.
+   */
+  const U* GetRaw() const noexcept { return &m_uv_req; }
+
+ protected:
+  /**
+   * Constructor.
+   */
+  RequestImpl() : Request{reinterpret_cast<uv_req_t*>(&m_uv_req)} {}
+
+ private:
+  U m_uv_req;
+};
+
+}  // namespace wpi::uv
+
+#endif  // WPINET_UV_REQUEST_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Signal.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Signal.h
new file mode 100644
index 0000000..12b6839
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Signal.h
@@ -0,0 +1,80 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_UV_SIGNAL_H_
+#define WPINET_UV_SIGNAL_H_
+
+#include <uv.h>
+
+#include <memory>
+
+#include <wpi/Signal.h>
+
+#include "wpinet/uv/Handle.h"
+
+namespace wpi::uv {
+
+class Loop;
+
+/**
+ * Signal handle.
+ */
+class Signal final : public HandleImpl<Signal, uv_signal_t> {
+  struct private_init {};
+
+ public:
+  explicit Signal(const private_init&) {}
+  ~Signal() noexcept override = default;
+
+  /**
+   * Create a signal handle.
+   *
+   * @param loop Loop object where this handle runs.
+   */
+  static std::shared_ptr<Signal> Create(Loop& loop);
+
+  /**
+   * Create a signal handle.
+   *
+   * @param loop Loop object where this handle runs.
+   */
+  static std::shared_ptr<Signal> Create(const std::shared_ptr<Loop>& loop) {
+    return Create(*loop);
+  }
+
+  /**
+   * Start watching for the given signal.
+   *
+   * @param signum Signal to watch for.
+   */
+  void Start(int signum);
+
+  /**
+   * Start watching for the given signal.  Same as Start() but the signal
+   * handler is reset the moment the signal is received.
+   *
+   * @param signum Signal to watch for.
+   */
+  void StartOneshot(int signum);
+
+  /**
+   * Stop watching for the signal.
+   */
+  void Stop() { Invoke(&uv_signal_stop, GetRaw()); }
+
+  /**
+   * Get the signal being monitored.
+   * @return Signal number.
+   */
+  int GetSignal() const { return GetRaw()->signum; }
+
+  /**
+   * Signal generated when a signal occurs.
+   */
+  sig::Signal<int> signal;
+};
+
+}  // namespace wpi::uv
+
+#endif  // WPINET_UV_SIGNAL_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Stream.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Stream.h
new file mode 100644
index 0000000..9568455
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Stream.h
@@ -0,0 +1,332 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_UV_STREAM_H_
+#define WPINET_UV_STREAM_H_
+
+#include <uv.h>
+
+#include <cstdlib>
+#include <functional>
+#include <initializer_list>
+#include <memory>
+#include <span>
+#include <utility>
+
+#include <wpi/Signal.h>
+
+#include "wpinet/uv/Buffer.h"
+#include "wpinet/uv/Handle.h"
+#include "wpinet/uv/Request.h"
+
+namespace wpi::uv {
+
+class Stream;
+
+/**
+ * Shutdown request.
+ */
+class ShutdownReq : public RequestImpl<ShutdownReq, uv_shutdown_t> {
+ public:
+  ShutdownReq();
+
+  Stream& GetStream() const {
+    return *static_cast<Stream*>(GetRaw()->handle->data);
+  }
+
+  /**
+   * Shutdown completed signal.
+   */
+  sig::Signal<> complete;
+};
+
+/**
+ * Write request.
+ */
+class WriteReq : public RequestImpl<WriteReq, uv_write_t> {
+ public:
+  WriteReq();
+
+  Stream& GetStream() const {
+    return *static_cast<Stream*>(GetRaw()->handle->data);
+  }
+
+  /**
+   * Write completed signal.  This is called even if an error occurred.
+   * @param err error value
+   */
+  sig::Signal<Error> finish;
+};
+
+/**
+ * Stream handle.
+ * Stream handles provide an abstraction of a duplex communication channel.
+ * This is an abstract type; there are three stream implementations (Tcp,
+ * Pipe, and Tty).
+ */
+class Stream : public Handle {
+ public:
+  std::shared_ptr<Stream> shared_from_this() {
+    return std::static_pointer_cast<Stream>(Handle::shared_from_this());
+  }
+
+  std::shared_ptr<const Stream> shared_from_this() const {
+    return std::static_pointer_cast<const Stream>(Handle::shared_from_this());
+  }
+
+  /**
+   * Shutdown the outgoing (write) side of a duplex stream. It waits for pending
+   * write requests to complete.  HandleShutdownComplete() is called on the
+   * request after shutdown is complete.
+   *
+   * @param req shutdown request
+   */
+  void Shutdown(const std::shared_ptr<ShutdownReq>& req);
+
+  /**
+   * Shutdown the outgoing (write) side of a duplex stream. It waits for pending
+   * write requests to complete.  The callback is called after shutdown is
+   * complete.  Errors will be reported to the stream error handler.
+   *
+   * @param callback Callback function to call when shutdown completes
+   * @return Connection object for the callback
+   */
+  void Shutdown(std::function<void()> callback = nullptr);
+
+  /**
+   * Start reading data from an incoming stream.
+   *
+   * This will only succeed after a connection has been established.
+   *
+   * A data signal will be emitted several times until there is no more
+   * data to read or `StopRead()` is called.
+   * An end signal will be emitted when there is no more data to read.
+   */
+  void StartRead();
+
+  /**
+   * Stop reading data from the stream.
+   *
+   * This function is idempotent and may be safely called on a stopped stream.
+   */
+  void StopRead() { Invoke(&uv_read_stop, GetRawStream()); }
+
+  /**
+   * Write data to the stream.
+   *
+   * Data are written in order. The lifetime of the data pointers passed in
+   * the `bufs` parameter must exceed the lifetime of the write request.
+   * An easy way to ensure this is to have the write request keep track of
+   * the data and use either its Complete() function or destructor to free the
+   * data.
+   *
+   * The finish signal will be emitted on the request object when the data
+   * has been written (or if an error occurs).
+   * The error signal will be emitted on the request object in case of errors.
+   *
+   * @param bufs The buffers to be written to the stream.
+   * @param req write request
+   */
+  void Write(std::span<const Buffer> bufs,
+             const std::shared_ptr<WriteReq>& req);
+
+  /**
+   * Write data to the stream.
+   *
+   * Data are written in order. The lifetime of the data pointers passed in
+   * the `bufs` parameter must exceed the lifetime of the write request.
+   * An easy way to ensure this is to have the write request keep track of
+   * the data and use either its Complete() function or destructor to free the
+   * data.
+   *
+   * The finish signal will be emitted on the request object when the data
+   * has been written (or if an error occurs).
+   * The error signal will be emitted on the request object in case of errors.
+   *
+   * @param bufs The buffers to be written to the stream.
+   * @param req write request
+   */
+  void Write(std::initializer_list<Buffer> bufs,
+             const std::shared_ptr<WriteReq>& req) {
+    Write({bufs.begin(), bufs.end()}, req);
+  }
+
+  /**
+   * Write data to the stream.
+   *
+   * Data are written in order. The lifetime of the data pointers passed in
+   * the `bufs` parameter must exceed the lifetime of the write request.
+   * The callback can be used to free data after the request completes.
+   *
+   * The callback will be called when the data has been written (even if an
+   * error occurred).  Errors will be reported to the stream error handler.
+   *
+   * @param bufs The buffers to be written to the stream.
+   * @param callback Callback function to call when the write completes
+   */
+  void Write(std::span<const Buffer> bufs,
+             std::function<void(std::span<Buffer>, Error)> callback);
+
+  /**
+   * Write data to the stream.
+   *
+   * Data are written in order. The lifetime of the data pointers passed in
+   * the `bufs` parameter must exceed the lifetime of the write request.
+   * The callback can be used to free data after the request completes.
+   *
+   * The callback will be called when the data has been written (even if an
+   * error occurred).  Errors will be reported to the stream error handler.
+   *
+   * @param bufs The buffers to be written to the stream.
+   * @param callback Callback function to call when the write completes
+   */
+  void Write(std::initializer_list<Buffer> bufs,
+             std::function<void(std::span<Buffer>, Error)> callback) {
+    Write({bufs.begin(), bufs.end()}, std::move(callback));
+  }
+
+  /**
+   * Queue a write request if it can be completed immediately.
+   *
+   * Same as `Write()`, but won’t queue a write request if it can’t be
+   * completed immediately.
+   * An error signal will be emitted in case of errors.
+   *
+   * @param bufs The buffers to be written to the stream.
+   * @return Number of bytes written.
+   */
+  int TryWrite(std::span<const Buffer> bufs);
+
+  /**
+   * Queue a write request if it can be completed immediately.
+   *
+   * Same as `Write()`, but won’t queue a write request if it can’t be
+   * completed immediately.
+   * An error signal will be emitted in case of errors.
+   *
+   * @param bufs The buffers to be written to the stream.
+   * @return Number of bytes written.
+   */
+  int TryWrite(std::initializer_list<Buffer> bufs) {
+    return TryWrite({bufs.begin(), bufs.end()});
+  }
+
+  /**
+   * Same as TryWrite() and extended write function for sending handles over a
+   * pipe.
+   *
+   * Try to send a handle is not supported on Windows, where it returns
+   * UV_EAGAIN.
+   *
+   * @param bufs The buffers to be written to the stream.
+   * @param send send stream
+   * @return Number of bytes written.
+   */
+  int TryWrite2(std::span<const Buffer> bufs, Stream& send);
+
+  /**
+   * Same as TryWrite() and extended write function for sending handles over a
+   * pipe.
+   *
+   * Try to send a handle is not supported on Windows, where it returns
+   * UV_EAGAIN.
+   *
+   * @param bufs The buffers to be written to the stream.
+   * @param send send stream
+   * @return Number of bytes written.
+   */
+  int TryWrite2(std::initializer_list<Buffer> bufs, Stream& send) {
+    return TryWrite2({bufs.begin(), bufs.end()}, send);
+  }
+
+  /**
+   * Check if the stream is readable.
+   * @return True if the stream is readable, false otherwise.
+   */
+  bool IsReadable() const noexcept {
+    return uv_is_readable(GetRawStream()) == 1;
+  }
+
+  /**
+   * @brief Checks if the stream is writable.
+   * @return True if the stream is writable, false otherwise.
+   */
+  bool IsWritable() const noexcept {
+    return uv_is_writable(GetRawStream()) == 1;
+  }
+
+  /**
+   * Enable or disable blocking mode for a stream.
+   *
+   * When blocking mode is enabled all writes complete synchronously. The
+   * interface remains unchanged otherwise, e.g. completion or failure of the
+   * operation will still be reported through events which are emitted
+   * asynchronously.
+   *
+   * @param enable True to enable blocking mode, false otherwise.
+   * @return True in case of success, false otherwise.
+   */
+  bool SetBlocking(bool enable) noexcept {
+    return uv_stream_set_blocking(GetRawStream(), enable) == 0;
+  }
+
+  /**
+   * Gets the amount of queued bytes waiting to be sent.
+   * @return Amount of queued bytes waiting to be sent.
+   */
+  size_t GetWriteQueueSize() const noexcept {
+    return GetRawStream()->write_queue_size;
+  }
+
+  /**
+   * Get the underlying stream data structure.
+   *
+   * @return The underlying stream data structure.
+   */
+  uv_stream_t* GetRawStream() const noexcept {
+    return reinterpret_cast<uv_stream_t*>(GetRawHandle());
+  }
+
+  /**
+   * Signal generated when data was read on a stream.
+   */
+  sig::Signal<Buffer&, size_t> data;
+
+  /**
+   * Signal generated when no more read data is available.
+   */
+  sig::Signal<> end;
+
+ protected:
+  explicit Stream(uv_stream_t* uv_stream)
+      : Handle{reinterpret_cast<uv_handle_t*>(uv_stream)} {}
+};
+
+template <typename T, typename U>
+class StreamImpl : public Stream {
+ public:
+  std::shared_ptr<T> shared_from_this() {
+    return std::static_pointer_cast<T>(Handle::shared_from_this());
+  }
+
+  std::shared_ptr<const T> shared_from_this() const {
+    return std::static_pointer_cast<const T>(Handle::shared_from_this());
+  }
+
+  /**
+   * Get the underlying handle data structure.
+   *
+   * @return The underlying handle data structure.
+   */
+  U* GetRaw() const noexcept {
+    return reinterpret_cast<U*>(this->GetRawHandle());
+  }
+
+ protected:
+  StreamImpl() : Stream{static_cast<uv_stream_t*>(std::malloc(sizeof(U)))} {}
+};
+
+}  // namespace wpi::uv
+
+#endif  // WPINET_UV_STREAM_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Tcp.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Tcp.h
new file mode 100644
index 0000000..dc554db
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Tcp.h
@@ -0,0 +1,371 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_UV_TCP_H_
+#define WPINET_UV_TCP_H_
+
+#include <uv.h>
+
+#include <chrono>
+#include <functional>
+#include <memory>
+#include <string_view>
+#include <utility>
+
+#include "wpinet/uv/NetworkStream.h"
+
+namespace wpi::uv {
+
+class Loop;
+class TcpConnectReq;
+
+/**
+ * TCP handle.
+ * TCP handles are used to represent both TCP streams and servers.
+ */
+class Tcp final : public NetworkStreamImpl<Tcp, uv_tcp_t> {
+  struct private_init {};
+
+ public:
+  using Time = std::chrono::duration<uint64_t, std::milli>;
+
+  explicit Tcp(const private_init&) {}
+  ~Tcp() noexcept override = default;
+
+  /**
+   * Create a TCP handle.
+   *
+   * @param loop Loop object where this handle runs.
+   * @param flags Flags
+   */
+  static std::shared_ptr<Tcp> Create(Loop& loop,
+                                     unsigned int flags = AF_UNSPEC);
+
+  /**
+   * Create a TCP handle.
+   *
+   * @param loop Loop object where this handle runs.
+   * @param flags Flags
+   */
+  static std::shared_ptr<Tcp> Create(const std::shared_ptr<Loop>& loop,
+                                     unsigned int flags = AF_UNSPEC) {
+    return Create(*loop, flags);
+  }
+
+  /**
+   * Reuse this handle.  This closes the handle, and after the close completes,
+   * reinitializes it (identically to Create) and calls the provided callback.
+   * Unlike Close(), it does NOT emit the closed signal, however, IsClosing()
+   * will return true until the callback is called.  This does nothing if
+   * IsClosing() is true (e.g. if Close() was called).
+   *
+   * @param flags Flags
+   * @param callback Callback
+   */
+  void Reuse(std::function<void()> callback, unsigned int flags = AF_UNSPEC);
+
+  /**
+   * Accept incoming connection.
+   *
+   * This call is used in conjunction with `Listen()` to accept incoming
+   * connections. Call this function after receiving a ListenEvent event to
+   * accept the connection.
+   * An error signal will be emitted in case of errors.
+   *
+   * When the connection signal is emitted it is guaranteed that this
+   * function will complete successfully the first time. If you attempt to use
+   * it more than once, it may fail.
+   * It is suggested to only call this function once per connection signal.
+   *
+   * @return The stream handle for the accepted connection, or nullptr on error.
+   */
+  std::shared_ptr<Tcp> Accept();
+
+  /**
+   * Accept incoming connection.
+   *
+   * This call is used in conjunction with `Listen()` to accept incoming
+   * connections. Call this function after receiving a connection signal to
+   * accept the connection.
+   * An error signal will be emitted in case of errors.
+   *
+   * When the connection signal is emitted it is guaranteed that this
+   * function will complete successfully the first time. If you attempt to use
+   * it more than once, it may fail.
+   * It is suggested to only call this function once per connection signal.
+   *
+   * @param client Client stream object.
+   * @return False on error.
+   */
+  bool Accept(const std::shared_ptr<Tcp>& client) {
+    return NetworkStream::Accept(client);
+  }
+
+  /**
+   * Open an existing file descriptor or SOCKET as a TCP handle.
+   *
+   * @note The passed file descriptor or SOCKET is not checked for its type, but
+   * it's required that it represents a valid stream socket.
+   *
+   * @param sock A valid socket handle (either a file descriptor or a SOCKET).
+   */
+  void Open(uv_os_sock_t sock) { Invoke(&uv_tcp_open, GetRaw(), sock); }
+
+  /**
+   * Enable no delay operation (turns off Nagle's algorithm).
+   * @param enable True to enable it, false otherwise.
+   * @return True in case of success, false otherwise.
+   */
+  bool SetNoDelay(bool enable) { return uv_tcp_nodelay(GetRaw(), enable) == 0; }
+
+  /**
+   * Enable/Disable TCP keep-alive.
+   * @param enable True to enable it, false otherwise.
+   * @param time Initial delay in seconds (use
+   * `std::chrono::duration<unsigned int>`).
+   * @return True in case of success, false otherwise.
+   */
+  bool SetKeepAlive(bool enable, Time time = Time{0}) {
+    return uv_tcp_keepalive(GetRaw(), enable,
+                            static_cast<unsigned>(time.count())) == 0;
+  }
+
+  /**
+   * Enable/Disable simultaneous asynchronous accept requests.
+   *
+   * Enable/Disable simultaneous asynchronous accept requests that are
+   * queued by the operating system when listening for new TCP
+   * connections.
+   * This setting is used to tune a TCP server for the desired performance.
+   * Having simultaneous accepts can significantly improve the rate of
+   * accepting connections (which is why it is enabled by default) but may
+   * lead to uneven load distribution in multi-process setups.
+   *
+   * @param enable True to enable it, false otherwise.
+   * @return True in case of success, false otherwise.
+   */
+  bool SetSimultaneousAccepts(bool enable) {
+    return uv_tcp_simultaneous_accepts(GetRaw(), enable) == 0;
+  }
+
+  /**
+   * Bind the handle to an IPv4 or IPv6 address and port.
+   *
+   * A successful call to this function does not guarantee that the call to
+   * `Listen()` or `Connect()` will work properly.
+   * An error signal can be emitted because of either this function or the
+   * ones mentioned above.
+   *
+   * @param addr Initialized `sockaddr_in` or `sockaddr_in6` data structure.
+   * @param flags Optional additional flags.
+   */
+  void Bind(const sockaddr& addr, unsigned int flags = 0) {
+    Invoke(&uv_tcp_bind, GetRaw(), &addr, flags);
+  }
+
+  void Bind(const sockaddr_in& addr, unsigned int flags = 0) {
+    Bind(reinterpret_cast<const sockaddr&>(addr), flags);
+  }
+
+  void Bind(const sockaddr_in6& addr, unsigned int flags = 0) {
+    Bind(reinterpret_cast<const sockaddr&>(addr), flags);
+  }
+
+  /**
+   * Bind the handle to an IPv4 address and port.
+   *
+   * A successful call to this function does not guarantee that the call to
+   * `Listen()` or `Connect()` will work properly.
+   * An error signal can be emitted because of either this function or the
+   * ones mentioned above.
+   *
+   * Available flags are:
+   *
+   * @param ip The address to which to bind.
+   * @param port The port to which to bind.
+   * @param flags Optional additional flags.
+   */
+  void Bind(std::string_view ip, unsigned int port, unsigned int flags = 0);
+
+  /**
+   * Bind the handle to an IPv6 address and port.
+   *
+   * A successful call to this function does not guarantee that the call to
+   * `Listen()` or `Connect()` will work properly.
+   * An error signal can be emitted because of either this function or the
+   * ones mentioned above.
+   *
+   * Available flags are:
+   *
+   * @param ip The address to which to bind.
+   * @param port The port to which to bind.
+   * @param flags Optional additional flags.
+   */
+  void Bind6(std::string_view ip, unsigned int port, unsigned int flags = 0);
+
+  /**
+   * Get the current address to which the handle is bound.
+   * @return The address (will be zeroed if an error occurred).
+   */
+  sockaddr_storage GetSock();
+
+  /**
+   * Get the address of the peer connected to the handle.
+   * @return The address (will be zeroed if an error occurred).
+   */
+  sockaddr_storage GetPeer();
+
+  /**
+   * Establish an IPv4 or IPv6 TCP connection.
+   *
+   * On Windows if the addr is initialized to point to an unspecified address
+   * (`0.0.0.0` or `::`) it will be changed to point to localhost. This is
+   * done to match the behavior of Linux systems.
+   *
+   * The connected signal is emitted on the request when the connection has been
+   * established.
+   * The error signal is emitted on the request in case of errors during the
+   * connection.
+   *
+   * @param addr Initialized `sockaddr_in` or `sockaddr_in6` data structure.
+   * @param req connection request
+   */
+  void Connect(const sockaddr& addr, const std::shared_ptr<TcpConnectReq>& req);
+
+  void Connect(const sockaddr_in& addr,
+               const std::shared_ptr<TcpConnectReq>& req) {
+    Connect(reinterpret_cast<const sockaddr&>(addr), req);
+  }
+
+  void Connect(const sockaddr_in6& addr,
+               const std::shared_ptr<TcpConnectReq>& req) {
+    Connect(reinterpret_cast<const sockaddr&>(addr), req);
+  }
+
+  /**
+   * Establish an IPv4 or IPv6 TCP connection.
+   *
+   * On Windows if the addr is initialized to point to an unspecified address
+   * (`0.0.0.0` or `::`) it will be changed to point to localhost. This is
+   * done to match the behavior of Linux systems.
+   *
+   * The callback is called when the connection has been established.  Errors
+   * are reported to the stream error handler.
+   *
+   * @param addr Initialized `sockaddr_in` or `sockaddr_in6` data structure.
+   * @param callback Callback function to call when connection established
+   */
+  void Connect(const sockaddr& addr, std::function<void()> callback);
+
+  void Connect(const sockaddr_in& addr, std::function<void()> callback) {
+    Connect(reinterpret_cast<const sockaddr&>(addr), std::move(callback));
+  }
+
+  void Connect(const sockaddr_in6& addr, std::function<void()> callback) {
+    Connect(reinterpret_cast<const sockaddr&>(addr), std::move(callback));
+  }
+
+  /**
+   * Establish an IPv4 TCP connection.
+   *
+   * On Windows if the addr is initialized to point to an unspecified address
+   * (`0.0.0.0` or `::`) it will be changed to point to localhost. This is
+   * done to match the behavior of Linux systems.
+   *
+   * The connected signal is emitted on the request when the connection has been
+   * established.
+   * The error signal is emitted on the request in case of errors during the
+   * connection.
+   *
+   * @param ip The address to which to connect to.
+   * @param port The port to which to connect to.
+   * @param req connection request
+   */
+  void Connect(std::string_view ip, unsigned int port,
+               const std::shared_ptr<TcpConnectReq>& req);
+
+  /**
+   * Establish an IPv4 TCP connection.
+   *
+   * On Windows if the addr is initialized to point to an unspecified address
+   * (`0.0.0.0` or `::`) it will be changed to point to localhost. This is
+   * done to match the behavior of Linux systems.
+   *
+   * The callback is called when the connection has been established.  Errors
+   * are reported to the stream error handler.
+   *
+   * @param ip The address to which to connect to.
+   * @param port The port to which to connect to.
+   * @param callback Callback function to call when connection established
+   */
+  void Connect(std::string_view ip, unsigned int port,
+               std::function<void()> callback);
+
+  /**
+   * Establish an IPv6 TCP connection.
+   *
+   * On Windows if the addr is initialized to point to an unspecified address
+   * (`0.0.0.0` or `::`) it will be changed to point to localhost. This is
+   * done to match the behavior of Linux systems.
+   *
+   * The connected signal is emitted on the request when the connection has been
+   * established.
+   * The error signal is emitted on the request in case of errors during the
+   * connection.
+   *
+   * @param ip The address to which to connect to.
+   * @param port The port to which to connect to.
+   * @param req connection request
+   */
+  void Connect6(std::string_view ip, unsigned int port,
+                const std::shared_ptr<TcpConnectReq>& req);
+
+  /**
+   * Establish an IPv6 TCP connection.
+   *
+   * On Windows if the addr is initialized to point to an unspecified address
+   * (`0.0.0.0` or `::`) it will be changed to point to localhost. This is
+   * done to match the behavior of Linux systems.
+   *
+   * The callback is called when the connection has been established.  Errors
+   * are reported to the stream error handler.
+   *
+   * @param ip The address to which to connect to.
+   * @param port The port to which to connect to.
+   * @param callback Callback function to call when connection established
+   */
+  void Connect6(std::string_view ip, unsigned int port,
+                std::function<void()> callback);
+
+  /**
+   * Resets a TCP connection by sending a RST packet. This is accomplished by
+   * setting the SO_LINGER socket option with a linger interval of zero and then
+   * calling Close(). Due to some platform inconsistencies, mixing of
+   * Shutdown() and CloseReset() calls is not allowed.
+   */
+  void CloseReset();
+
+ private:
+  Tcp* DoAccept() override;
+
+  struct ReuseData {
+    std::function<void()> callback;
+    unsigned int flags;
+  };
+  std::unique_ptr<ReuseData> m_reuseData;
+};
+
+/**
+ * TCP connection request.
+ */
+class TcpConnectReq : public ConnectReq {
+ public:
+  Tcp& GetStream() const {
+    return *static_cast<Tcp*>(&ConnectReq::GetStream());
+  }
+};
+
+}  // namespace wpi::uv
+
+#endif  // WPINET_UV_TCP_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Timer.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Timer.h
new file mode 100644
index 0000000..4a1cf54
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Timer.h
@@ -0,0 +1,145 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_UV_TIMER_H_
+#define WPINET_UV_TIMER_H_
+
+#include <uv.h>
+
+#include <chrono>
+#include <functional>
+#include <memory>
+#include <utility>
+
+#include <wpi/Signal.h>
+
+#include "wpinet/uv/Handle.h"
+
+namespace wpi::uv {
+
+class Loop;
+
+/**
+ * Timer handle.
+ * Timer handles are used to schedule signals to be called in the future.
+ */
+class Timer final : public HandleImpl<Timer, uv_timer_t> {
+  struct private_init {};
+
+ public:
+  using Time = std::chrono::duration<uint64_t, std::milli>;
+
+  explicit Timer(const private_init&) {}
+  ~Timer() noexcept override = default;
+
+  /**
+   * Create a timer handle.
+   *
+   * @param loop Loop object where this handle runs.
+   */
+  static std::shared_ptr<Timer> Create(Loop& loop);
+
+  /**
+   * Create a timer handle.
+   *
+   * @param loop Loop object where this handle runs.
+   */
+  static std::shared_ptr<Timer> Create(const std::shared_ptr<Loop>& loop) {
+    return Create(*loop);
+  }
+
+  /**
+   * Create a timer that calls a functor after a given time interval.
+   *
+   * @param loop Loop object where the timer should run.
+   * @param timeout Time interval
+   * @param func Functor
+   */
+  static void SingleShot(Loop& loop, Time timeout, std::function<void()> func);
+
+  /**
+   * Create a timer that calls a functor after a given time interval.
+   *
+   * @param loop Loop object where the timer should run.
+   * @param timeout Time interval
+   * @param func Functor
+   */
+  static void SingleShot(const std::shared_ptr<Loop>& loop, Time timeout,
+                         std::function<void()> func) {
+    return SingleShot(*loop, timeout, std::move(func));
+  }
+
+  /**
+   * Start the timer.
+   *
+   * If timeout is zero, an event is emitted on the next event loop
+   * iteration. If repeat is non-zero, an event is emitted first
+   * after timeout milliseconds and then repeatedly after repeat milliseconds.
+   *
+   * @param timeout Milliseconds before to emit an event (use
+   * `std::chrono::duration<uint64_t, std::milli>`).
+   * @param repeat Milliseconds between successive events (use
+   * `std::chrono::duration<uint64_t, std::milli>`).
+   */
+  void Start(Time timeout, Time repeat = Time{0});
+
+  /**
+   * Stop the timer.
+   */
+  void Stop() { Invoke(&uv_timer_stop, GetRaw()); }
+
+  /**
+   * Stop the timer and restart it if it was repeating.
+   *
+   * Stop the timer, and if it is repeating restart it using the repeat value
+   * as the timeout.
+   * If the timer has never been started before it emits sigError.
+   */
+  void Again() { Invoke(&uv_timer_again, GetRaw()); }
+
+  /**
+   * Set the repeat interval value.
+   *
+   * The timer will be scheduled to run on the given interval and will follow
+   * normal timer semantics in the case of a time-slice overrun.
+   * For example, if a 50ms repeating timer first runs for 17ms, it will be
+   * scheduled to run again 33ms later. If other tasks consume more than the
+   * 33ms following the first timer event, then another event will be emitted
+   * as soon as possible.
+   *
+   * If the repeat value is set from a listener bound to an event, it does
+   * not immediately take effect. If the timer was non-repeating before, it
+   * will have been stopped. If it was repeating, then the old repeat value
+   * will have been used to schedule the next timeout.
+   *
+   * @param repeat Repeat interval in milliseconds (use
+   * `std::chrono::duration<uint64_t, std::milli>`).
+   */
+  void SetRepeat(Time repeat) { uv_timer_set_repeat(GetRaw(), repeat.count()); }
+
+  /**
+   * Get the timer repeat value.
+   * @return Timer repeat value in milliseconds (as a
+   * `std::chrono::duration<uint64_t, std::milli>`).
+   */
+  Time GetRepeat() const { return Time{uv_timer_get_repeat(GetRaw())}; }
+
+  /**
+   * Get the timer due value or 0 if it has expired. The time is relative to
+   * uv_now().
+   *
+   * @return Timer due value in milliseconds (as a
+   * `std::chrono::duration<uint64_t, std::milli>`).
+   */
+  Time GetDueIn() const { return Time{uv_timer_get_due_in(GetRaw())}; }
+
+  /**
+   * Signal generated when the timeout event occurs.
+   */
+  sig::Signal<> timeout;
+};
+
+}  // namespace wpi::uv
+
+#endif  // WPINET_UV_TIMER_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Tty.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Tty.h
new file mode 100644
index 0000000..2dd4f97
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Tty.h
@@ -0,0 +1,85 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_UV_TTY_H_
+#define WPINET_UV_TTY_H_
+
+#include <uv.h>
+
+#include <memory>
+#include <utility>
+
+#include "wpinet/uv/Stream.h"
+
+namespace wpi::uv {
+
+class Loop;
+class Tty;
+
+/**
+ * TTY handle.
+ * TTY handles represent a stream for the console.
+ */
+class Tty final : public StreamImpl<Tty, uv_tty_t> {
+  struct private_init {};
+
+ public:
+  explicit Tty(const private_init&) {}
+  ~Tty() noexcept override = default;
+
+  /**
+   * Create a TTY handle.
+   *
+   * @param loop Loop object where this handle runs.
+   * @param fd File descriptor, usually 0=stdin, 1=stdout, 2=stderr
+   * @param readable Specifies if you plan on calling StartRead().  stdin is
+   *                 readable, stdout is not.
+   */
+  static std::shared_ptr<Tty> Create(Loop& loop, uv_file fd, bool readable);
+
+  /**
+   * Create a TTY handle.
+   *
+   * @param loop Loop object where this handle runs.
+   * @param fd File descriptor, usually 0=stdin, 1=stdout, 2=stderr
+   * @param readable Specifies if you plan on calling StartRead().  stdin is
+   *                 readable, stdout is not.
+   */
+  static std::shared_ptr<Tty> Create(const std::shared_ptr<Loop>& loop,
+                                     uv_file fd, bool readable) {
+    return Create(*loop, fd, readable);
+  }
+
+  /**
+   * Set the TTY using the specified terminal mode.
+   *
+   * @param mode terminal mode
+   */
+  void SetMode(uv_tty_mode_t mode) {
+    int err = uv_tty_set_mode(GetRaw(), mode);
+    if (err < 0) {
+      ReportError(err);
+    }
+  }
+
+  /**
+   * Reset TTY settings to default values for the next process to take over.
+   * Typically called when the program exits.
+   */
+  void ResetMode() { Invoke(&uv_tty_reset_mode); }
+
+  /**
+   * Gets the current window size.
+   * @return Window size (pair of width and height).
+   */
+  std::pair<int, int> GetWindowSize() {
+    int width = 0, height = 0;
+    Invoke(&uv_tty_get_winsize, GetRaw(), &width, &height);
+    return std::make_pair(width, height);
+  }
+};
+
+}  // namespace wpi::uv
+
+#endif  // WPINET_UV_TTY_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Udp.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Udp.h
new file mode 100644
index 0000000..cfa245f
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Udp.h
@@ -0,0 +1,400 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_UV_UDP_H_
+#define WPINET_UV_UDP_H_
+
+#include <uv.h>
+
+#include <functional>
+#include <memory>
+#include <span>
+#include <string_view>
+#include <utility>
+
+#include <wpi/Signal.h>
+
+#include "wpinet/uv/Handle.h"
+#include "wpinet/uv/Request.h"
+
+namespace wpi::uv {
+
+class Loop;
+class Udp;
+
+/**
+ * UDP send request.
+ */
+class UdpSendReq : public RequestImpl<UdpSendReq, uv_udp_send_t> {
+ public:
+  UdpSendReq();
+
+  Udp& GetUdp() const { return *static_cast<Udp*>(GetRaw()->handle->data); }
+
+  /**
+   * Send completed signal.  This is called even if an error occurred.
+   * @param err error value
+   */
+  sig::Signal<Error> complete;
+};
+
+/**
+ * UDP handle.
+ * UDP handles encapsulate UDP communication for both clients and servers.
+ */
+class Udp final : public HandleImpl<Udp, uv_udp_t> {
+  struct private_init {};
+
+ public:
+  explicit Udp(const private_init&) {}
+  ~Udp() noexcept override = default;
+
+  /**
+   * Create a UDP handle.
+   *
+   * @param loop Loop object where this handle runs.
+   * @param flags Flags
+   */
+  static std::shared_ptr<Udp> Create(Loop& loop,
+                                     unsigned int flags = AF_UNSPEC);
+
+  /**
+   * Create a UDP handle.
+   *
+   * @param loop Loop object where this handle runs.
+   * @param flags Flags
+   */
+  static std::shared_ptr<Udp> Create(const std::shared_ptr<Loop>& loop,
+                                     unsigned int flags = AF_UNSPEC) {
+    return Create(*loop, flags);
+  }
+
+  /**
+   * Open an existing file descriptor or SOCKET as a UDP handle.
+   *
+   * @param sock A valid socket handle (either a file descriptor or a SOCKET).
+   */
+  void Open(uv_os_sock_t sock) { Invoke(&uv_udp_open, GetRaw(), sock); }
+
+  /**
+   * Bind the handle to an IPv4 or IPv6 address and port.
+   *
+   * @param addr Initialized `sockaddr_in` or `sockaddr_in6` data structure.
+   * @param flags Optional additional flags.
+   */
+  void Bind(const sockaddr& addr, unsigned int flags = 0) {
+    Invoke(&uv_udp_bind, GetRaw(), &addr, flags);
+  }
+
+  void Bind(const sockaddr_in& addr, unsigned int flags = 0) {
+    Bind(reinterpret_cast<const sockaddr&>(addr), flags);
+  }
+
+  void Bind(const sockaddr_in6& addr, unsigned int flags = 0) {
+    Bind(reinterpret_cast<const sockaddr&>(addr), flags);
+  }
+
+  /**
+   * Bind the handle to an IPv4 address and port.
+   *
+   * @param ip The address to which to bind.
+   * @param port The port to which to bind.
+   * @param flags Optional additional flags.
+   */
+  void Bind(std::string_view ip, unsigned int port, unsigned int flags = 0);
+
+  /**
+   * Bind the handle to an IPv6 address and port.
+   *
+   * @param ip The address to which to bind.
+   * @param port The port to which to bind.
+   * @param flags Optional additional flags.
+   */
+  void Bind6(std::string_view ip, unsigned int port, unsigned int flags = 0);
+
+  /**
+   * Associate the handle to a remote address and port, so every message sent
+   * by this handle is automatically sent to that destination.
+   *
+   * @param addr Initialized `sockaddr_in` or `sockaddr_in6` data structure.
+   */
+  void Connect(const sockaddr& addr) {
+    Invoke(&uv_udp_connect, GetRaw(), &addr);
+  }
+
+  void Connect(const sockaddr_in& addr) {
+    Connect(reinterpret_cast<const sockaddr&>(addr));
+  }
+
+  void Connect(const sockaddr_in6& addr) {
+    Connect(reinterpret_cast<const sockaddr&>(addr));
+  }
+
+  /**
+   * Associate the handle to an IPv4 address and port, so every message sent
+   * by this handle is automatically sent to that destination.
+   *
+   * @param ip The address to which to bind.
+   * @param port The port to which to bind.
+   */
+  void Connect(std::string_view ip, unsigned int port);
+
+  /**
+   * Associate the handle to an IPv6 address and port, so every message sent
+   * by this handle is automatically sent to that destination.
+   *
+   * @param ip The address to which to bind.
+   * @param port The port to which to bind.
+   * @param flags Optional additional flags.
+   */
+  void Connect6(std::string_view ip, unsigned int port);
+
+  /**
+   * Get the remote IP and port on connected UDP handles.
+   * @return The address (will be zeroed if an error occurred).
+   */
+  sockaddr_storage GetPeer();
+
+  /**
+   * Get the current address to which the handle is bound.
+   * @return The address (will be zeroed if an error occurred).
+   */
+  sockaddr_storage GetSock();
+
+  /**
+   * Set membership for a multicast address.
+   *
+   * @param multicastAddr Multicast address to set membership for
+   * @param interfaceAddr Interface address
+   * @param membership Should be UV_JOIN_GROUP or UV_LEAVE_GROUP
+   */
+  void SetMembership(std::string_view multicastAddr,
+                     std::string_view interfaceAddr, uv_membership membership);
+
+  /**
+   * Set membership for a source-specific multicast group.
+   *
+   * @param multicastAddr Multicast address to set membership for
+   * @param interfaceAddr Interface address
+   * @param sourceAddr Source address
+   * @param membership Should be UV_JOIN_GROUP or UV_LEAVE_GROUP
+   */
+  void SetSourceMembership(std::string_view multicastAddr,
+                           std::string_view interfaceAddr,
+                           std::string_view sourceAddr,
+                           uv_membership membership);
+
+  /**
+   * Set IP multicast loop flag.  Makes multicast packets loop back to local
+   * sockets.
+   *
+   * @param enabled True for enabled, false for disabled
+   */
+  void SetMulticastLoop(bool enabled) {
+    Invoke(&uv_udp_set_multicast_loop, GetRaw(), enabled ? 1 : 0);
+  }
+
+  /**
+   * Set the multicast TTL.
+   *
+   * @param ttl Time to live (1-255)
+   */
+  void SetMulticastTtl(int ttl) {
+    Invoke(&uv_udp_set_multicast_ttl, GetRaw(), ttl);
+  }
+
+  /**
+   * Set the multicast interface to send or receive data on.
+   *
+   * @param interfaceAddr Interface address
+   */
+  void SetMulticastInterface(std::string_view interfaceAddr);
+
+  /**
+   * Set broadcast on or off.
+   *
+   * @param enabled True for enabled, false for disabled
+   */
+  void SetBroadcast(bool enabled) {
+    Invoke(&uv_udp_set_broadcast, GetRaw(), enabled ? 1 : 0);
+  }
+
+  /**
+   * Set the time to live (TTL).
+   *
+   * @param ttl Time to live (1-255)
+   */
+  void SetTtl(int ttl) { Invoke(&uv_udp_set_ttl, GetRaw(), ttl); }
+
+  /**
+   * Send data over the UDP socket.  If the socket has not previously been bound
+   * with Bind() it will be bound to 0.0.0.0 (the "all interfaces" IPv4 address)
+   * and a random port number.
+   *
+   * Data are written in order. The lifetime of the data pointers passed in
+   * the `bufs` parameter must exceed the lifetime of the send request.
+   * The callback can be used to free data after the request completes.
+   *
+   * HandleSendComplete() will be called on the request object when the data
+   * has been written.  HandleSendComplete() is called even if an error occurs.
+   * HandleError() will be called on the request object in case of errors.
+   *
+   * @param addr sockaddr_in or sockaddr_in6 with the address and port of the
+   *             remote peer.
+   * @param bufs The buffers to be written to the stream.
+   * @param req write request
+   */
+  void Send(const sockaddr& addr, std::span<const Buffer> bufs,
+            const std::shared_ptr<UdpSendReq>& req);
+
+  void Send(const sockaddr_in& addr, std::span<const Buffer> bufs,
+            const std::shared_ptr<UdpSendReq>& req) {
+    Send(reinterpret_cast<const sockaddr&>(addr), bufs, req);
+  }
+
+  void Send(const sockaddr_in6& addr, std::span<const Buffer> bufs,
+            const std::shared_ptr<UdpSendReq>& req) {
+    Send(reinterpret_cast<const sockaddr&>(addr), bufs, req);
+  }
+
+  /**
+   * Variant of Send() for connected sockets.  Cannot be used with
+   * connectionless sockets.
+   *
+   * @param bufs The buffers to be written to the stream.
+   * @param req write request
+   */
+  void Send(std::span<const Buffer> bufs,
+            const std::shared_ptr<UdpSendReq>& req);
+
+  /**
+   * Send data over the UDP socket.  If the socket has not previously been bound
+   * with Bind() it will be bound to 0.0.0.0 (the "all interfaces" IPv4 address)
+   * and a random port number.
+   *
+   * Data are written in order. The lifetime of the data pointers passed in
+   * the `bufs` parameter must exceed the lifetime of the send request.
+   * The callback can be used to free data after the request completes.
+   *
+   * The callback will be called when the data has been sent.  Errors will
+   * be reported via the error signal.
+   *
+   * @param addr sockaddr_in or sockaddr_in6 with the address and port of the
+   *             remote peer.
+   * @param bufs The buffers to be sent.
+   * @param callback Callback function to call when the data has been sent.
+   */
+  void Send(const sockaddr& addr, std::span<const Buffer> bufs,
+            std::function<void(std::span<Buffer>, Error)> callback);
+
+  void Send(const sockaddr_in& addr, std::span<const Buffer> bufs,
+            std::function<void(std::span<Buffer>, Error)> callback) {
+    Send(reinterpret_cast<const sockaddr&>(addr), bufs, std::move(callback));
+  }
+
+  void Send(const sockaddr_in6& addr, std::span<const Buffer> bufs,
+            std::function<void(std::span<Buffer>, Error)> callback) {
+    Send(reinterpret_cast<const sockaddr&>(addr), bufs, std::move(callback));
+  }
+
+  /**
+   * Variant of Send() for connected sockets.  Cannot be used with
+   * connectionless sockets.
+   *
+   * @param bufs The buffers to be written to the stream.
+   * @param callback Callback function to call when the data has been sent.
+   */
+  void Send(std::span<const Buffer> bufs,
+            std::function<void(std::span<Buffer>, Error)> callback);
+
+  /**
+   * Same as Send(), but won't queue a send request if it can't be completed
+   * immediately.
+   *
+   * @param addr sockaddr_in or sockaddr_in6 with the address and port of the
+   *             remote peer.
+   * @param bufs The buffers to be send.
+   * @return Number of bytes sent.
+   */
+  int TrySend(const sockaddr& addr, std::span<const Buffer> bufs) {
+    int val = uv_udp_try_send(GetRaw(), bufs.data(),
+                              static_cast<unsigned>(bufs.size()), &addr);
+    if (val < 0) {
+      this->ReportError(val);
+      return 0;
+    }
+    return val;
+  }
+
+  int TrySend(const sockaddr_in& addr, std::span<const Buffer> bufs) {
+    return TrySend(reinterpret_cast<const sockaddr&>(addr), bufs);
+  }
+
+  int TrySend(const sockaddr_in6& addr, std::span<const Buffer> bufs) {
+    return TrySend(reinterpret_cast<const sockaddr&>(addr), bufs);
+  }
+
+  /**
+   * Variant of TrySend() for connected sockets.  Cannot be used with
+   * connectionless sockets.
+   *
+   * @param bufs The buffers to be written to the stream.
+   * @return Number of bytes sent.
+   */
+  int TrySend(std::span<const Buffer> bufs) {
+    int val = uv_udp_try_send(GetRaw(), bufs.data(),
+                              static_cast<unsigned>(bufs.size()), nullptr);
+    if (val < 0) {
+      this->ReportError(val);
+      return 0;
+    }
+    return val;
+  }
+
+  /**
+   * Prepare for receiving data.  If the socket has not previously been bound
+   * with Bind() it is bound to 0.0.0.0 (the "all interfaces" IPv4 address) and
+   * a random port number.
+   *
+   * A received signal will be emitted for each received data packet until
+   * `StopRecv()` is called.
+   */
+  void StartRecv();
+
+  /**
+   * Stop listening for incoming datagrams.
+   */
+  void StopRecv() { Invoke(&uv_udp_recv_stop, GetRaw()); }
+
+  /**
+   * Returns true if the UDP handle was created with the UV_UDP_RECVMMSG flag
+   * and the platform supports recvmmsg(2), false otherwise.
+   * @return True if the UDP handle is using recvmmsg.
+   */
+  bool IsUsingRecvmmsg() const { return uv_udp_using_recvmmsg(GetRaw()); }
+
+  /**
+   * Gets the amount of queued bytes waiting to be sent.
+   * @return Amount of queued bytes waiting to be sent.
+   */
+  size_t GetSendQueueSize() const noexcept { return GetRaw()->send_queue_size; }
+
+  /**
+   * Gets the amount of queued packets waiting to be sent.
+   * @return Amount of queued packets waiting to be sent.
+   */
+  size_t GetSendQueueCount() const noexcept {
+    return GetRaw()->send_queue_count;
+  }
+
+  /**
+   * Signal generated for each incoming datagram.  Parameters are the buffer,
+   * the number of bytes received, the address of the sender, and flags.
+   */
+  sig::Signal<Buffer&, size_t, const sockaddr&, unsigned> received;
+};
+
+}  // namespace wpi::uv
+
+#endif  // WPINET_UV_UDP_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Work.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Work.h
new file mode 100644
index 0000000..72293d0
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/Work.h
@@ -0,0 +1,94 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_UV_WORK_H_
+#define WPINET_UV_WORK_H_
+
+#include <uv.h>
+
+#include <functional>
+#include <memory>
+#include <utility>
+
+#include <wpi/Signal.h>
+
+#include "wpinet/uv/Request.h"
+
+namespace wpi::uv {
+
+class Loop;
+
+/**
+ * Work request.
+ * For use with `QueueWork()` function family.
+ */
+class WorkReq : public RequestImpl<WorkReq, uv_work_t> {
+ public:
+  WorkReq();
+
+  Loop& GetLoop() const { return *static_cast<Loop*>(GetRaw()->loop->data); }
+
+  /**
+   * Function(s) that will be run on the thread pool.
+   */
+  sig::Signal<> work;
+
+  /**
+   * Function(s) that will be run on the loop thread after the work on the
+   * thread pool has been completed by the work callback.
+   */
+  sig::Signal<> afterWork;
+};
+
+/**
+ * Initializes a work request which will run on the thread pool.
+ *
+ * @param loop Event loop
+ * @param req request
+ */
+void QueueWork(Loop& loop, const std::shared_ptr<WorkReq>& req);
+
+/**
+ * Initializes a work request which will run on the thread pool.
+ *
+ * @param loop Event loop
+ * @param req request
+ */
+inline void QueueWork(const std::shared_ptr<Loop>& loop,
+                      const std::shared_ptr<WorkReq>& req) {
+  QueueWork(*loop, req);
+}
+
+/**
+ * Initializes a work request which will run on the thread pool.  The work
+ * callback will be run on a thread from the thread pool, and the afterWork
+ * callback will be called on the loop thread after the work completes.  Any
+ * errors are forwarded to the loop.
+ *
+ * @param loop Event loop
+ * @param work Work callback (called from separate thread)
+ * @param afterWork After work callback (called on loop thread)
+ */
+void QueueWork(Loop& loop, std::function<void()> work,
+               std::function<void()> afterWork);
+
+/**
+ * Initializes a work request which will run on the thread pool.  The work
+ * callback will be run on a thread from the thread pool, and the afterWork
+ * callback will be called on the loop thread after the work completes.  Any
+ * errors are forwarded to the loop.
+ *
+ * @param loop Event loop
+ * @param work Work callback (called from separate thread)
+ * @param afterWork After work callback (called on loop thread)
+ */
+inline void QueueWork(const std::shared_ptr<Loop>& loop,
+                      std::function<void()> work,
+                      std::function<void()> afterWork) {
+  QueueWork(*loop, std::move(work), std::move(afterWork));
+}
+
+}  // namespace wpi::uv
+
+#endif  // WPINET_UV_WORK_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/util.h b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/util.h
new file mode 100644
index 0000000..1967c7a
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/include/wpinet/uv/util.h
@@ -0,0 +1,151 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef WPINET_UV_UTIL_H_
+#define WPINET_UV_UTIL_H_
+
+#include <uv.h>
+
+#include <cstring>
+#include <string_view>
+
+#ifdef _WIN32
+#pragma comment(lib, "Ws2_32.lib")
+#endif
+
+namespace wpi::uv {
+
+/**
+ * Convert a binary structure containing an IPv4 address to a string.
+ * @param addr Binary structure
+ * @param ip Output string (any type that has `assign(char*, char*)`)
+ * @param port Output port number
+ * @return Error (same as `uv_ip4_name()`).
+ */
+template <typename T>
+int AddrToName(const sockaddr_in& addr, T* ip, unsigned int* port) {
+  char name[128];
+  int err = uv_ip4_name(&addr, name, 128);
+  if (err == 0) {
+    ip->assign(name, name + std::strlen(name));
+    *port = ntohs(addr.sin_port);
+  } else {
+    ip->assign(name, name);
+  }
+  return err;
+}
+
+/**
+ * Convert a binary structure containing an IPv6 address to a string.
+ * @param addr Binary structure
+ * @param ip Output string (any type that has `assign(char*, char*)`)
+ * @param port Output port number
+ * @return Error (same as `uv_ip6_name()`).
+ */
+template <typename T>
+int AddrToName(const sockaddr_in6& addr, T* ip, unsigned int* port) {
+  char name[128];
+  int err = uv_ip6_name(&addr, name, 128);
+  if (err == 0) {
+    ip->assign(name, name + std::strlen(name));
+    *port = ntohs(addr.sin6_port);
+  } else {
+    ip->assign(name, name);
+  }
+  return err;
+}
+
+/**
+ * Convert a binary structure containing an IPv4 or IPv6 address to a string.
+ * @param addr Binary structure
+ * @param ip Output string (any type that has `assign(char*, char*)`)
+ * @param port Output port number
+ * @return Error (same as `uv_ip6_name()`).
+ */
+template <typename T>
+int AddrToName(const sockaddr_storage& addr, T* ip, unsigned int* port) {
+  if (addr.ss_family == AF_INET) {
+    return AddrToName(reinterpret_cast<const sockaddr_in&>(addr), ip, port);
+  }
+  if (addr.ss_family == AF_INET6) {
+    return AddrToName(reinterpret_cast<const sockaddr_in6&>(addr), ip, port);
+  }
+  char name[1] = {'\0'};
+  ip->assign(name, name);
+  return -1;
+}
+
+/**
+ * Convert a binary IPv4 address to a string.
+ * @param addr Binary address
+ * @param ip Output string (any type that has `assign(char*, char*)`)
+ * @return Error (same as `uv_inet_ntop()`).
+ */
+template <typename T>
+int AddrToName(const in_addr& addr, T* ip) {
+  char name[128];
+  int err = uv_inet_ntop(AF_INET, &addr, name, 128);
+  if (err == 0) {
+    ip->assign(name, name + std::strlen(name));
+  } else {
+    ip->assign(name, name);
+  }
+  return err;
+}
+
+/**
+ * Convert a binary IPv6 address to a string.
+ * @param addr Binary address
+ * @param ip Output string (any type that has `assign(char*, char*)`)
+ * @return Error (same as `uv_inet_ntop()`).
+ */
+template <typename T>
+int AddrToName(const in6_addr& addr, T* ip) {
+  char name[128];
+  int err = uv_inet_ntop(AF_INET6, &addr, name, 128);
+  if (err == 0) {
+    ip->assign(name, name + std::strlen(name));
+  } else {
+    ip->assign(name, name);
+  }
+  return err;
+}
+
+/**
+ * Convert a string containing an IPv4 address to a binary structure.
+ * @param ip IPv4 address string
+ * @param port Port number
+ * @param addr Output binary structure
+ * @return Error (same as `uv_ip4_addr()`).
+ */
+int NameToAddr(std::string_view ip, unsigned int port, sockaddr_in* addr);
+
+/**
+ * Convert a string containing an IPv6 address to a binary structure.
+ * @param ip IPv6 address string
+ * @param port Port number
+ * @param addr Output binary structure
+ * @return Error (same as `uv_ip6_addr()`).
+ */
+int NameToAddr(std::string_view ip, unsigned int port, sockaddr_in6* addr);
+
+/**
+ * Convert a string containing an IPv4 address to binary format.
+ * @param ip IPv4 address string
+ * @param addr Output binary
+ * @return Error (same as `uv_inet_pton()`).
+ */
+int NameToAddr(std::string_view ip, in_addr* addr);
+
+/**
+ * Convert a string containing an IPv6 address to binary format.
+ * @param ip IPv6 address string
+ * @param addr Output binary
+ * @return Error (same as `uv_inet_pton()`).
+ */
+int NameToAddr(std::string_view ip, in6_addr* addr);
+
+}  // namespace wpi::uv
+
+#endif  // WPINET_UV_UTIL_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/linux/AvahiClient.cpp b/third_party/allwpilib/wpinet/src/main/native/linux/AvahiClient.cpp
new file mode 100644
index 0000000..7a5f560
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/linux/AvahiClient.cpp
@@ -0,0 +1,119 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "AvahiClient.h"
+
+#include <wpi/mutex.h>
+
+#include <thread>
+
+#include "dlfcn.h"
+
+using namespace wpi;
+
+#define AvahiFunctionLoad(snake_name)                                          \
+  do {                                                                         \
+    snake_name =                                                               \
+        reinterpret_cast<snake_name##_func>(dlsym(lib, "avahi_" #snake_name)); \
+    if (!snake_name) {                                                         \
+      return;                                                                  \
+    }                                                                          \
+  } while (false)
+
+AvahiFunctionTable::AvahiFunctionTable() {
+  void* lib = dlopen("libavahi-common.so.3", RTLD_LAZY);
+
+  valid = false;
+
+  if (lib == nullptr) {
+    return;
+  }
+
+  AvahiFunctionLoad(threaded_poll_new);
+  AvahiFunctionLoad(threaded_poll_free);
+  AvahiFunctionLoad(threaded_poll_get);
+  AvahiFunctionLoad(threaded_poll_start);
+  AvahiFunctionLoad(threaded_poll_stop);
+  AvahiFunctionLoad(threaded_poll_lock);
+  AvahiFunctionLoad(threaded_poll_unlock);
+  AvahiFunctionLoad(string_list_new_from_array);
+  AvahiFunctionLoad(string_list_free);
+  AvahiFunctionLoad(unescape_label);
+  AvahiFunctionLoad(alternative_service_name);
+  AvahiFunctionLoad(free);
+
+  lib = dlopen("libavahi-client.so.3", RTLD_LAZY);
+
+  if (lib == nullptr) {
+    return;
+  }
+
+  AvahiFunctionLoad(client_new);
+  AvahiFunctionLoad(client_free);
+  AvahiFunctionLoad(service_browser_new);
+  AvahiFunctionLoad(service_browser_get_client);
+  AvahiFunctionLoad(service_browser_free);
+  AvahiFunctionLoad(service_resolver_new);
+  AvahiFunctionLoad(service_resolver_free);
+  AvahiFunctionLoad(entry_group_new);
+  AvahiFunctionLoad(entry_group_free);
+  AvahiFunctionLoad(entry_group_add_service);
+  AvahiFunctionLoad(entry_group_add_service_strlst);
+  AvahiFunctionLoad(entry_group_reset);
+  AvahiFunctionLoad(entry_group_is_empty);
+  AvahiFunctionLoad(entry_group_commit);
+  AvahiFunctionLoad(entry_group_get_client);
+
+  valid = true;
+}
+
+AvahiFunctionTable& AvahiFunctionTable::Get() {
+  static AvahiFunctionTable table;
+  return table;
+}
+
+static wpi::mutex ThreadLoopLock;
+static std::weak_ptr<AvahiThread> ThreadLoop;
+
+std::shared_ptr<AvahiThread> AvahiThread::Get() {
+  std::scoped_lock lock{ThreadLoopLock};
+  auto locked = ThreadLoop.lock();
+  if (!locked) {
+    locked = std::make_unique<AvahiThread>(private_init{});
+    ThreadLoop = locked;
+  }
+  return locked;
+}
+
+AvahiThread::AvahiThread(const private_init&) {
+  if (!table.IsValid()) {
+    return;
+  }
+
+  threadedPoll = table.threaded_poll_new();
+  table.threaded_poll_start(threadedPoll);
+}
+
+AvahiThread::~AvahiThread() noexcept {
+  if (!table.IsValid()) {
+    return;
+  }
+
+  if (threadedPoll) {
+    table.threaded_poll_stop(threadedPoll);
+    table.threaded_poll_free(threadedPoll);
+  }
+}
+
+void AvahiThread::lock() {
+  table.threaded_poll_lock(threadedPoll);
+}
+
+void AvahiThread::unlock() {
+  table.threaded_poll_unlock(threadedPoll);
+}
+
+const AvahiPoll* AvahiThread::GetPoll() const {
+  return table.threaded_poll_get(threadedPoll);
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/linux/AvahiClient.h b/third_party/allwpilib/wpinet/src/main/native/linux/AvahiClient.h
new file mode 100644
index 0000000..1ed93a8
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/linux/AvahiClient.h
@@ -0,0 +1,322 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <stdint.h>
+
+#include <memory>
+
+/***
+  This file is part of avahi.
+  avahi is free software; you can redistribute it and/or modify it
+  under the terms of the GNU Lesser General Public License as
+  published by the Free Software Foundation; either version 2.1 of the
+  License, or (at your option) any later version.
+  avahi is distributed in the hope that it will be useful, but WITHOUT
+  ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
+  or FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General
+  Public License for more details.
+  You should have received a copy of the GNU Lesser General Public
+  License along with avahi; if not, write to the Free Software
+  Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307
+  USA.
+***/
+
+typedef struct AvahiPoll AvahiPoll;
+
+typedef enum {
+  AVAHI_SERVER_INVALID,
+  AVAHI_SERVER_REGISTERING,
+  AVAHI_SERVER_RUNNING,
+  AVAHI_SERVER_COLLISION,
+  AVAHI_SERVER_FAILURE
+} AvahiServerState;
+
+typedef struct AvahiClient AvahiClient;
+
+typedef enum {
+  AVAHI_CLIENT_S_REGISTERING = AVAHI_SERVER_REGISTERING,
+  AVAHI_CLIENT_S_RUNNING = AVAHI_SERVER_RUNNING,
+  AVAHI_CLIENT_S_COLLISION = AVAHI_SERVER_COLLISION,
+  AVAHI_CLIENT_FAILURE = 100,
+  AVAHI_CLIENT_CONNECTING = 101
+} AvahiClientState;
+
+typedef enum {
+  AVAHI_CLIENT_IGNORE_USER_CONFIG = 1,
+  AVAHI_CLIENT_NO_FAIL = 2
+} AvahiClientFlags;
+
+typedef void (*AvahiClientCallback)(AvahiClient* s, AvahiClientState state,
+                                    void* userdata);
+
+typedef struct AvahiServiceBrowser AvahiServiceBrowser;
+
+typedef int AvahiProtocol;
+
+typedef int AvahiIfIndex;
+
+typedef enum {
+  AVAHI_BROWSER_NEW,
+  AVAHI_BROWSER_REMOVE,
+  AVAHI_BROWSER_CACHE_EXHAUSTED,
+  AVAHI_BROWSER_ALL_FOR_NOW,
+  AVAHI_BROWSER_FAILURE
+} AvahiBrowserEvent;
+
+typedef enum {
+  AVAHI_LOOKUP_RESULT_CACHED = 1,
+  AVAHI_LOOKUP_RESULT_WIDE_AREA = 2,
+  AVAHI_LOOKUP_RESULT_MULTICAST = 4,
+  AVAHI_LOOKUP_RESULT_LOCAL = 8,
+  AVAHI_LOOKUP_RESULT_OUR_OWN = 16,
+  AVAHI_LOOKUP_RESULT_STATIC = 32
+} AvahiLookupResultFlags;
+
+typedef void (*AvahiServiceBrowserCallback)(
+    AvahiServiceBrowser* b, AvahiIfIndex interface, AvahiProtocol protocol,
+    AvahiBrowserEvent event, const char* name, const char* type,
+    const char* domain, AvahiLookupResultFlags flags, void* userdata);
+
+typedef enum {
+  AVAHI_LOOKUP_USE_WIDE_AREA = 1,
+  AVAHI_LOOKUP_USE_MULTICAST = 2,
+
+  AVAHI_LOOKUP_NO_TXT = 4,
+  AVAHI_LOOKUP_NO_ADDRESS = 8
+} AvahiLookupFlags;
+
+typedef struct AvahiServiceResolver AvahiServiceResolver;
+
+typedef enum {
+  AVAHI_RESOLVER_FOUND,
+  AVAHI_RESOLVER_FAILURE
+} AvahiResolverEvent;
+
+typedef struct AvahiIPv4Address {
+  uint32_t address;
+} AvahiIPv4Address;
+
+typedef struct AvahiIPv6Address {
+  uint8_t address[16];
+} AvahiIPv6Address;
+
+typedef struct AvahiAddress {
+  AvahiProtocol proto;
+
+  union {
+    AvahiIPv6Address ipv6;
+    AvahiIPv4Address ipv4;
+    uint8_t data[1];
+  } data;
+} AvahiAddress;
+
+typedef struct AvahiStringList {
+  struct AvahiStringList* next;
+  size_t size;
+  uint8_t text[1];
+} AvahiStringList;
+
+typedef void (*AvahiServiceResolverCallback)(
+    AvahiServiceResolver* r, AvahiIfIndex interface, AvahiProtocol protocol,
+    AvahiResolverEvent event, const char* name, const char* type,
+    const char* domain, const char* host_name, const AvahiAddress* a,
+    uint16_t port, AvahiStringList* txt, AvahiLookupResultFlags flags,
+    void* userdata);
+
+typedef struct AvahiThreadedPoll AvahiThreadedPoll;
+
+typedef struct AvahiEntryGroup AvahiEntryGroup;
+
+typedef enum {
+  AVAHI_ENTRY_GROUP_UNCOMMITED,
+  AVAHI_ENTRY_GROUP_REGISTERING,
+  AVAHI_ENTRY_GROUP_ESTABLISHED,
+  AVAHI_ENTRY_GROUP_COLLISION,
+  AVAHI_ENTRY_GROUP_FAILURE
+} AvahiEntryGroupState;
+
+typedef void (*AvahiEntryGroupCallback)(AvahiEntryGroup* g,
+                                        AvahiEntryGroupState state,
+                                        void* userdata);
+
+typedef enum {
+  AVAHI_PUBLISH_UNIQUE = 1,
+  AVAHI_PUBLISH_NO_PROBE = 2,
+  AVAHI_PUBLISH_NO_ANNOUNCE = 4,
+  AVAHI_PUBLISH_ALLOW_MULTIPLE = 8,
+
+  AVAHI_PUBLISH_NO_REVERSE = 16,
+  AVAHI_PUBLISH_NO_COOKIE = 32,
+  AVAHI_PUBLISH_UPDATE = 64,
+  AVAHI_PUBLISH_USE_WIDE_AREA = 128,
+  AVAHI_PUBLISH_USE_MULTICAST = 256
+} AvahiPublishFlags;
+
+enum { AVAHI_IF_UNSPEC = -1 };
+
+enum { AVAHI_PROTO_INET = 0, AVAHI_PROTO_INET6 = 1, AVAHI_PROTO_UNSPEC = -1 };
+
+enum {
+  AVAHI_OK = 0,
+  AVAHI_ERR_FAILURE = -1,
+  AVAHI_ERR_BAD_STATE = -2,
+  AVAHI_ERR_INVALID_HOST_NAME = -3,
+  AVAHI_ERR_INVALID_DOMAIN_NAME = -4,
+  AVAHI_ERR_NO_NETWORK = -5,
+  AVAHI_ERR_INVALID_TTL = -6,
+  AVAHI_ERR_IS_PATTERN = -7,
+  AVAHI_ERR_COLLISION = -8,
+  AVAHI_ERR_INVALID_RECORD = -9,
+
+  AVAHI_ERR_INVALID_SERVICE_NAME = -10,
+  AVAHI_ERR_INVALID_SERVICE_TYPE = -11,
+  AVAHI_ERR_INVALID_PORT = -12,
+  AVAHI_ERR_INVALID_KEY = -13,
+  AVAHI_ERR_INVALID_ADDRESS = -14,
+  AVAHI_ERR_TIMEOUT = -15,
+  AVAHI_ERR_TOO_MANY_CLIENTS = -16,
+  AVAHI_ERR_TOO_MANY_OBJECTS = -17,
+  AVAHI_ERR_TOO_MANY_ENTRIES = -18,
+  AVAHI_ERR_OS = -19,
+
+  AVAHI_ERR_ACCESS_DENIED = -20,
+  AVAHI_ERR_INVALID_OPERATION = -21,
+  AVAHI_ERR_DBUS_ERROR = -22,
+  AVAHI_ERR_DISCONNECTED = -23,
+  AVAHI_ERR_NO_MEMORY = -24,
+  AVAHI_ERR_INVALID_OBJECT = -25,
+  AVAHI_ERR_NO_DAEMON = -26,
+  AVAHI_ERR_INVALID_INTERFACE = -27,
+  AVAHI_ERR_INVALID_PROTOCOL = -28,
+  AVAHI_ERR_INVALID_FLAGS = -29,
+
+  AVAHI_ERR_NOT_FOUND = -30,
+  AVAHI_ERR_INVALID_CONFIG = -31,
+  AVAHI_ERR_VERSION_MISMATCH = -32,
+  AVAHI_ERR_INVALID_SERVICE_SUBTYPE = -33,
+  AVAHI_ERR_INVALID_PACKET = -34,
+  AVAHI_ERR_INVALID_DNS_ERROR = -35,
+  AVAHI_ERR_DNS_FORMERR = -36,
+  AVAHI_ERR_DNS_SERVFAIL = -37,
+  AVAHI_ERR_DNS_NXDOMAIN = -38,
+  AVAHI_ERR_DNS_NOTIMP = -39,
+
+  AVAHI_ERR_DNS_REFUSED = -40,
+  AVAHI_ERR_DNS_YXDOMAIN = -41,
+  AVAHI_ERR_DNS_YXRRSET = -42,
+  AVAHI_ERR_DNS_NXRRSET = -43,
+  AVAHI_ERR_DNS_NOTAUTH = -44,
+  AVAHI_ERR_DNS_NOTZONE = -45,
+  AVAHI_ERR_INVALID_RDATA = -46,
+  AVAHI_ERR_INVALID_DNS_CLASS = -47,
+  AVAHI_ERR_INVALID_DNS_TYPE = -48,
+  AVAHI_ERR_NOT_SUPPORTED = -49,
+
+  AVAHI_ERR_NOT_PERMITTED = -50,
+  AVAHI_ERR_INVALID_ARGUMENT = -51,
+  AVAHI_ERR_IS_EMPTY = -52,
+  AVAHI_ERR_NO_CHANGE = -53,
+
+  AVAHI_ERR_MAX = -54
+};
+
+namespace wpi {
+class AvahiFunctionTable {
+ public:
+#define AvahiFunction(CapName, RetType, Parameters) \
+  using CapName##_func = RetType(*) Parameters;     \
+  CapName##_func CapName = nullptr
+
+  AvahiFunction(threaded_poll_new, AvahiThreadedPoll*, (void));
+  AvahiFunction(threaded_poll_free, void, (AvahiThreadedPoll*));
+  AvahiFunction(threaded_poll_get, const AvahiPoll*, (AvahiThreadedPoll*));
+  AvahiFunction(threaded_poll_start, int, (AvahiThreadedPoll*));
+  AvahiFunction(threaded_poll_stop, int, (AvahiThreadedPoll*));
+  AvahiFunction(threaded_poll_lock, int, (AvahiThreadedPoll*));
+  AvahiFunction(threaded_poll_unlock, int, (AvahiThreadedPoll*));
+
+  AvahiFunction(client_new, AvahiClient*,
+                (const AvahiPoll* poll_api, AvahiClientFlags flags,
+                 AvahiClientCallback callback, void* userdata, int* error));
+  AvahiFunction(client_free, void, (AvahiClient*));
+
+  AvahiFunction(service_browser_new, AvahiServiceBrowser*,
+                (AvahiClient * client, AvahiIfIndex interface,
+                 AvahiProtocol protocol, const char* type, const char* domain,
+                 AvahiLookupFlags flags, AvahiServiceBrowserCallback callback,
+                 void* userdata));
+
+  AvahiFunction(service_browser_free, int, (AvahiServiceBrowser*));
+
+  AvahiFunction(service_resolver_new, AvahiServiceResolver*,
+                (AvahiClient * client, AvahiIfIndex interface,
+                 AvahiProtocol protocol, const char* name, const char* type,
+                 const char* domain, AvahiProtocol aprotocol,
+                 AvahiLookupFlags flags, AvahiServiceResolverCallback callback,
+                 void* userdata));
+  AvahiFunction(service_resolver_free, int, (AvahiServiceResolver*));
+
+  AvahiFunction(entry_group_new, AvahiEntryGroup*,
+                (AvahiClient*, AvahiEntryGroupCallback, void*));
+  AvahiFunction(entry_group_free, int, (AvahiEntryGroup*));
+
+  AvahiFunction(entry_group_add_service, int,
+                (AvahiEntryGroup * group, AvahiIfIndex interface,
+                 AvahiProtocol protocol, AvahiPublishFlags flags,
+                 const char* name, const char* type, const char* domain,
+                 const char* host, uint16_t port, ...));
+
+  AvahiFunction(entry_group_add_service_strlst, int,
+                (AvahiEntryGroup * group, AvahiIfIndex interface,
+                 AvahiProtocol protocol, AvahiPublishFlags flags,
+                 const char* name, const char* type, const char* domain,
+                 const char* host, uint16_t port, AvahiStringList*));
+
+  AvahiFunction(entry_group_reset, int, (AvahiEntryGroup*));
+  AvahiFunction(entry_group_is_empty, int, (AvahiEntryGroup*));
+  AvahiFunction(entry_group_commit, int, (AvahiEntryGroup*));
+  AvahiFunction(entry_group_get_client, AvahiClient*, (AvahiEntryGroup*));
+
+  AvahiFunction(string_list_new_from_array, AvahiStringList*,
+                (const char** array, int len));
+  AvahiFunction(string_list_free, void, (AvahiStringList*));
+
+  AvahiFunction(service_browser_get_client, AvahiClient*,
+                (AvahiServiceBrowser*));
+
+  AvahiFunction(unescape_label, char*, (const char**, char*, size_t));
+  AvahiFunction(alternative_service_name, char*, (const char*));
+  AvahiFunction(free, void, (void*));
+
+  bool IsValid() const { return valid; }
+
+  static AvahiFunctionTable& Get();
+
+ private:
+  AvahiFunctionTable();
+  bool valid;
+};
+
+class AvahiThread {
+ private:
+  struct private_init {};
+
+ public:
+  explicit AvahiThread(const private_init&);
+  ~AvahiThread() noexcept;
+
+  void lock();
+  const AvahiPoll* GetPoll() const;
+  void unlock();
+
+  static std::shared_ptr<AvahiThread> Get();
+
+ private:
+  AvahiThreadedPoll* threadedPoll;
+  AvahiFunctionTable& table = AvahiFunctionTable::Get();
+};
+
+}  // namespace wpi
diff --git a/third_party/allwpilib/wpinet/src/main/native/linux/MulticastServiceAnnouncer.cpp b/third_party/allwpilib/wpinet/src/main/native/linux/MulticastServiceAnnouncer.cpp
new file mode 100644
index 0000000..d04711f
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/linux/MulticastServiceAnnouncer.cpp
@@ -0,0 +1,188 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/MulticastServiceAnnouncer.h"
+
+#include <vector>
+
+#include <fmt/format.h>
+#include <wpi/mutex.h>
+
+#include "AvahiClient.h"
+
+using namespace wpi;
+
+struct MulticastServiceAnnouncer::Impl {
+  AvahiFunctionTable& table = AvahiFunctionTable::Get();
+  std::shared_ptr<AvahiThread> thread = AvahiThread::Get();
+  AvahiClient* client = nullptr;
+  AvahiEntryGroup* group = nullptr;
+  std::string serviceName;
+  std::string serviceType;
+  int port;
+  AvahiStringList* stringList = nullptr;
+
+  ~Impl() noexcept {
+    if (stringList != nullptr && table.IsValid()) {
+      table.string_list_free(stringList);
+    }
+  }
+
+  template <typename T>
+  Impl(std::string_view serviceName, std::string_view serviceType, int port,
+       std::span<const std::pair<T, T>> txt);
+};
+
+template <typename T>
+MulticastServiceAnnouncer::Impl::Impl(std::string_view serviceName,
+                                      std::string_view serviceType, int port,
+                                      std::span<const std::pair<T, T>> txt) {
+  if (!this->table.IsValid()) {
+    return;
+  }
+
+  this->serviceName = serviceName;
+  this->serviceType = serviceType;
+  this->port = port;
+
+  if (txt.empty()) {
+    this->stringList = nullptr;
+  } else {
+    std::vector<std::string> txts;
+    for (auto&& i : txt) {
+      txts.push_back(fmt::format("{}={}", i.first, i.second));
+    }
+
+    std::vector<const char*> txtArr;
+    for (auto&& i : txts) {
+      txtArr.push_back(i.c_str());
+    }
+
+    this->stringList =
+        this->table.string_list_new_from_array(txtArr.data(), txtArr.size());
+  }
+}
+
+static void RegisterService(AvahiClient* client,
+                            MulticastServiceAnnouncer::Impl* impl);
+
+static void EntryGroupCallback(AvahiEntryGroup* group,
+                               AvahiEntryGroupState state, void* userdata) {
+  if (state == AVAHI_ENTRY_GROUP_COLLISION) {
+    // Remote collision
+    MulticastServiceAnnouncer::Impl* impl =
+        reinterpret_cast<MulticastServiceAnnouncer::Impl*>(userdata);
+    char* newName =
+        impl->table.alternative_service_name(impl->serviceName.c_str());
+    impl->serviceName = newName;
+    impl->table.free(newName);
+    RegisterService(impl->table.entry_group_get_client(group), impl);
+  }
+}
+
+static void RegisterService(AvahiClient* client,
+                            MulticastServiceAnnouncer::Impl* impl) {
+  if (impl->group == nullptr) {
+    impl->group = impl->table.entry_group_new(client, EntryGroupCallback, impl);
+  }
+
+  while (true) {
+    if (impl->table.entry_group_is_empty(impl->group)) {
+      int ret = 0;
+      if (impl->stringList == nullptr) {
+        ret = impl->table.entry_group_add_service(
+            impl->group, AVAHI_IF_UNSPEC, AVAHI_PROTO_UNSPEC,
+            AVAHI_PUBLISH_USE_MULTICAST, impl->serviceName.c_str(),
+            impl->serviceType.c_str(), "local", nullptr, impl->port, nullptr);
+      } else {
+        ret = impl->table.entry_group_add_service_strlst(
+            impl->group, AVAHI_IF_UNSPEC, AVAHI_PROTO_UNSPEC,
+            AVAHI_PUBLISH_USE_MULTICAST, impl->serviceName.c_str(),
+            impl->serviceType.c_str(), "local", nullptr, impl->port,
+            impl->stringList);
+      }
+      if (ret == AVAHI_ERR_COLLISION) {
+        // Local collision
+        char* newName =
+            impl->table.alternative_service_name(impl->serviceName.c_str());
+        impl->serviceName = newName;
+        impl->table.free(newName);
+        continue;
+      } else if (ret != AVAHI_OK) {
+        break;
+      }
+      impl->table.entry_group_commit(impl->group);
+      break;
+    }
+  }
+}
+
+static void ClientCallback(AvahiClient* client, AvahiClientState state,
+                           void* userdata) {
+  MulticastServiceAnnouncer::Impl* impl =
+      reinterpret_cast<MulticastServiceAnnouncer::Impl*>(userdata);
+
+  if (state == AVAHI_CLIENT_S_RUNNING) {
+    RegisterService(client, impl);
+  } else if (state == AVAHI_CLIENT_S_COLLISION ||
+             state == AVAHI_CLIENT_S_REGISTERING) {
+    if (impl->group) {
+      impl->table.entry_group_reset(impl->group);
+    }
+  }
+}
+
+MulticastServiceAnnouncer::MulticastServiceAnnouncer(
+    std::string_view serviceName, std::string_view serviceType, int port) {
+  std::span<const std::pair<std::string_view, std::string_view>> txt;
+  pImpl = std::make_unique<Impl>(serviceName, serviceType, port, txt);
+}
+
+MulticastServiceAnnouncer::MulticastServiceAnnouncer(
+    std::string_view serviceName, std::string_view serviceType, int port,
+    std::span<const std::pair<std::string, std::string>> txt) {
+  pImpl = std::make_unique<Impl>(serviceName, serviceType, port, txt);
+}
+
+MulticastServiceAnnouncer::MulticastServiceAnnouncer(
+    std::string_view serviceName, std::string_view serviceType, int port,
+    std::span<const std::pair<std::string_view, std::string_view>> txt) {
+  pImpl = std::make_unique<Impl>(serviceName, serviceType, port, txt);
+}
+
+MulticastServiceAnnouncer::~MulticastServiceAnnouncer() noexcept {
+  Stop();
+}
+
+bool MulticastServiceAnnouncer::HasImplementation() const {
+  return pImpl->table.IsValid();
+}
+
+void MulticastServiceAnnouncer::Start() {
+  if (!pImpl->table.IsValid()) {
+    return;
+  }
+  std::scoped_lock lock{*pImpl->thread};
+  if (pImpl->client) {
+    return;
+  }
+  pImpl->client =
+      pImpl->table.client_new(pImpl->thread->GetPoll(), AVAHI_CLIENT_NO_FAIL,
+                              ClientCallback, pImpl.get(), nullptr);
+}
+
+void MulticastServiceAnnouncer::Stop() {
+  if (!pImpl->table.IsValid()) {
+    return;
+  }
+  std::scoped_lock lock{*pImpl->thread};
+  if (pImpl->client) {
+    if (pImpl->group) {
+      pImpl->table.entry_group_free(pImpl->group);
+      pImpl->group = nullptr;
+    }
+    pImpl->table.client_free(pImpl->client);
+    pImpl->client = nullptr;
+  }
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/linux/MulticastServiceResolver.cpp b/third_party/allwpilib/wpinet/src/main/native/linux/MulticastServiceResolver.cpp
new file mode 100644
index 0000000..a408639
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/linux/MulticastServiceResolver.cpp
@@ -0,0 +1,150 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/MulticastServiceResolver.h"
+
+#include <wpi/SmallString.h>
+#include <wpi/StringExtras.h>
+#include <wpi/mutex.h>
+
+#include "AvahiClient.h"
+
+using namespace wpi;
+
+struct MulticastServiceResolver::Impl {
+  AvahiFunctionTable& table = AvahiFunctionTable::Get();
+  std::shared_ptr<AvahiThread> thread = AvahiThread::Get();
+  AvahiClient* client;
+  AvahiServiceBrowser* browser;
+  std::string serviceType;
+  MulticastServiceResolver* resolver;
+
+  void onFound(ServiceData&& data) {
+    resolver->PushData(std::forward<ServiceData>(data));
+  }
+};
+
+MulticastServiceResolver::MulticastServiceResolver(
+    std::string_view serviceType) {
+  pImpl = std::make_unique<Impl>();
+  pImpl->serviceType = serviceType;
+  pImpl->resolver = this;
+}
+
+MulticastServiceResolver::~MulticastServiceResolver() noexcept {
+  Stop();
+}
+
+bool MulticastServiceResolver::HasImplementation() const {
+  return pImpl->table.IsValid();
+}
+
+static void ResolveCallback(AvahiServiceResolver* r, AvahiIfIndex interface,
+                            AvahiProtocol protocol, AvahiResolverEvent event,
+                            const char* name, const char* type,
+                            const char* domain, const char* host_name,
+                            const AvahiAddress* address, uint16_t port,
+                            AvahiStringList* txt, AvahiLookupResultFlags flags,
+                            void* userdata) {
+  MulticastServiceResolver::Impl* impl =
+      reinterpret_cast<MulticastServiceResolver::Impl*>(userdata);
+
+  if (event == AVAHI_RESOLVER_FOUND) {
+    if (address->proto == AVAHI_PROTO_INET) {
+      AvahiStringList* strLst = txt;
+      MulticastServiceResolver::ServiceData data;
+      while (strLst != nullptr) {
+        std::string_view value{reinterpret_cast<const char*>(strLst->text),
+                               strLst->size};
+        strLst = strLst->next;
+        size_t splitIndex = value.find('=');
+        if (splitIndex == value.npos) {
+          // Todo make this just do key
+          continue;
+        }
+        std::string_view key = wpi::substr(value, 0, splitIndex);
+        value =
+            wpi::substr(value, splitIndex + 1, value.size() - splitIndex - 1);
+        data.txt.emplace_back(std::pair<std::string, std::string>{key, value});
+      }
+      wpi::SmallString<256> outputHostName;
+      char label[256];
+      do {
+        impl->table.unescape_label(&host_name, label, sizeof(label));
+        if (label[0] == '\0') {
+          break;
+        }
+        outputHostName.append(label);
+        outputHostName.append(".");
+      } while (true);
+
+      data.ipv4Address = address->data.ipv4.address;
+      data.port = port;
+      data.serviceName = name;
+      data.hostName = std::string{outputHostName};
+
+      impl->onFound(std::move(data));
+    }
+  }
+
+  impl->table.service_resolver_free(r);
+}
+
+static void BrowseCallback(AvahiServiceBrowser* b, AvahiIfIndex interface,
+                           AvahiProtocol protocol, AvahiBrowserEvent event,
+                           const char* name, const char* type,
+                           const char* domain, AvahiLookupResultFlags flags,
+                           void* userdata) {
+  MulticastServiceResolver::Impl* impl =
+      reinterpret_cast<MulticastServiceResolver::Impl*>(userdata);
+
+  if (event == AVAHI_BROWSER_NEW) {
+    impl->table.service_resolver_new(
+        impl->table.service_browser_get_client(b), interface, protocol, name,
+        type, domain, AVAHI_PROTO_UNSPEC, AVAHI_LOOKUP_USE_MULTICAST,
+        ResolveCallback, userdata);
+  }
+}
+
+static void ClientCallback(AvahiClient* client, AvahiClientState state,
+                           void* userdata) {
+  MulticastServiceResolver::Impl* impl =
+      reinterpret_cast<MulticastServiceResolver::Impl*>(userdata);
+
+  if (state == AVAHI_CLIENT_S_RUNNING) {
+    impl->browser = impl->table.service_browser_new(
+        client, AVAHI_IF_UNSPEC, AVAHI_PROTO_UNSPEC, impl->serviceType.c_str(),
+        "local", AvahiLookupFlags::AVAHI_LOOKUP_USE_MULTICAST, BrowseCallback,
+        userdata);
+  }
+}
+
+void MulticastServiceResolver::Start() {
+  if (!pImpl->table.IsValid()) {
+    return;
+  }
+  std::scoped_lock lock{*pImpl->thread};
+  if (pImpl->client) {
+    return;
+  }
+
+  pImpl->client =
+      pImpl->table.client_new(pImpl->thread->GetPoll(), AVAHI_CLIENT_NO_FAIL,
+                              ClientCallback, pImpl.get(), nullptr);
+}
+
+void MulticastServiceResolver::Stop() {
+  if (!pImpl->table.IsValid()) {
+    return;
+  }
+  std::scoped_lock lock{*pImpl->thread};
+  if (pImpl->client) {
+    if (pImpl->browser) {
+      pImpl->table.service_browser_free(pImpl->browser);
+      pImpl->browser = nullptr;
+    }
+    pImpl->table.client_free(pImpl->client);
+    pImpl->client = nullptr;
+  }
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/macOS/MulticastServiceAnnouncer.cpp b/third_party/allwpilib/wpinet/src/main/native/macOS/MulticastServiceAnnouncer.cpp
new file mode 100644
index 0000000..8c31a3b
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/macOS/MulticastServiceAnnouncer.cpp
@@ -0,0 +1,96 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/MulticastServiceAnnouncer.h"
+
+#include <arpa/inet.h>
+
+#include <wpi/SmallString.h>
+
+#include "dns_sd.h"
+
+using namespace wpi;
+
+struct MulticastServiceAnnouncer::Impl {
+  std::string serviceName;
+  std::string serviceType;
+  int port;
+  DNSServiceRef serviceRef{nullptr};
+  TXTRecordRef txtRecord;
+
+  Impl() { TXTRecordCreate(&txtRecord, 0, nullptr); }
+
+  ~Impl() noexcept { TXTRecordDeallocate(&txtRecord); }
+};
+
+MulticastServiceAnnouncer::MulticastServiceAnnouncer(
+    std::string_view serviceName, std::string_view serviceType, int port) {
+  pImpl = std::make_unique<Impl>();
+  pImpl->serviceName = serviceName;
+  pImpl->serviceType = serviceType;
+  pImpl->port = port;
+}
+
+MulticastServiceAnnouncer::MulticastServiceAnnouncer(
+    std::string_view serviceName, std::string_view serviceType, int port,
+    std::span<const std::pair<std::string, std::string>> txt) {
+  pImpl = std::make_unique<Impl>();
+  pImpl->serviceName = serviceName;
+  pImpl->serviceType = serviceType;
+  pImpl->port = port;
+
+  for (auto&& i : txt) {
+    TXTRecordSetValue(&pImpl->txtRecord, i.first.c_str(), i.second.length(),
+                      i.second.c_str());
+  }
+}
+
+MulticastServiceAnnouncer::MulticastServiceAnnouncer(
+    std::string_view serviceName, std::string_view serviceType, int port,
+    std::span<const std::pair<std::string_view, std::string_view>> txt) {
+  pImpl = std::make_unique<Impl>();
+  pImpl->serviceName = serviceName;
+  pImpl->serviceType = serviceType;
+  pImpl->port = port;
+
+  wpi::SmallString<64> key;
+
+  for (auto&& i : txt) {
+    key.clear();
+    key.append(i.first);
+    key.emplace_back('\0');
+
+    TXTRecordSetValue(&pImpl->txtRecord, key.data(), i.second.length(),
+                      i.second.data());
+  }
+}
+
+MulticastServiceAnnouncer::~MulticastServiceAnnouncer() noexcept {
+  Stop();
+}
+
+bool MulticastServiceAnnouncer::HasImplementation() const {
+  return true;
+}
+
+void MulticastServiceAnnouncer::Start() {
+  if (pImpl->serviceRef) {
+    return;
+  }
+
+  uint16_t len = TXTRecordGetLength(&pImpl->txtRecord);
+  const void* ptr = TXTRecordGetBytesPtr(&pImpl->txtRecord);
+
+  (void)DNSServiceRegister(&pImpl->serviceRef, 0, 0, pImpl->serviceName.c_str(),
+                           pImpl->serviceType.c_str(), "local", nullptr,
+                           htons(pImpl->port), len, ptr, nullptr, nullptr);
+}
+
+void MulticastServiceAnnouncer::Stop() {
+  if (!pImpl->serviceRef) {
+    return;
+  }
+  DNSServiceRefDeallocate(pImpl->serviceRef);
+  pImpl->serviceRef = nullptr;
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/macOS/MulticastServiceResolver.cpp b/third_party/allwpilib/wpinet/src/main/native/macOS/MulticastServiceResolver.cpp
new file mode 100644
index 0000000..eecf819
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/macOS/MulticastServiceResolver.cpp
@@ -0,0 +1,218 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#if defined(__APPLE__)
+
+#include "wpinet/MulticastServiceResolver.h"
+
+#include <netinet/in.h>
+#include <poll.h>
+
+#include <atomic>
+#include <thread>
+#include <vector>
+
+#include <wpi/SmallVector.h>
+
+#include "ResolverThread.h"
+#include "dns_sd.h"
+
+using namespace wpi;
+
+struct DnsResolveState {
+  DnsResolveState(MulticastServiceResolver::Impl* impl,
+                  std::string_view serviceNameView)
+      : pImpl{impl} {
+    data.serviceName = serviceNameView;
+  }
+
+  DNSServiceRef ResolveRef = nullptr;
+  MulticastServiceResolver::Impl* pImpl;
+
+  MulticastServiceResolver::ServiceData data;
+};
+
+struct MulticastServiceResolver::Impl {
+  std::string serviceType;
+  MulticastServiceResolver* resolver;
+  std::shared_ptr<ResolverThread> thread = ResolverThread::Get();
+  std::vector<std::unique_ptr<DnsResolveState>> ResolveStates;
+  DNSServiceRef serviceRef = nullptr;
+
+  void onFound(ServiceData&& data) {
+    resolver->PushData(std::forward<ServiceData>(data));
+  }
+};
+
+MulticastServiceResolver::MulticastServiceResolver(
+    std::string_view serviceType) {
+  pImpl = std::make_unique<Impl>();
+  pImpl->serviceType = serviceType;
+  pImpl->resolver = this;
+}
+
+MulticastServiceResolver::~MulticastServiceResolver() noexcept {
+  Stop();
+}
+
+void ServiceGetAddrInfoReply(DNSServiceRef sdRef, DNSServiceFlags flags,
+                             uint32_t interfaceIndex,
+                             DNSServiceErrorType errorCode,
+                             const char* hostname,
+                             const struct sockaddr* address, uint32_t ttl,
+                             void* context) {
+  if (errorCode != kDNSServiceErr_NoError) {
+    return;
+  }
+
+  DnsResolveState* resolveState = static_cast<DnsResolveState*>(context);
+
+  resolveState->data.hostName = hostname;
+  resolveState->data.ipv4Address =
+      reinterpret_cast<const struct sockaddr_in*>(address)->sin_addr.s_addr;
+
+  resolveState->pImpl->onFound(std::move(resolveState->data));
+
+  resolveState->pImpl->thread->RemoveServiceRefInThread(
+      resolveState->ResolveRef);
+
+  resolveState->pImpl->ResolveStates.erase(std::find_if(
+      resolveState->pImpl->ResolveStates.begin(),
+      resolveState->pImpl->ResolveStates.end(),
+      [resolveState](auto& a) { return a.get() == resolveState; }));
+}
+
+void ServiceResolveReply(DNSServiceRef sdRef, DNSServiceFlags flags,
+                         uint32_t interfaceIndex, DNSServiceErrorType errorCode,
+                         const char* fullname, const char* hosttarget,
+                         uint16_t port, /* In network byte order */
+                         uint16_t txtLen, const unsigned char* txtRecord,
+                         void* context) {
+  if (errorCode != kDNSServiceErr_NoError) {
+    return;
+  }
+
+  DnsResolveState* resolveState = static_cast<DnsResolveState*>(context);
+  resolveState->pImpl->thread->RemoveServiceRefInThread(
+      resolveState->ResolveRef);
+  DNSServiceRefDeallocate(resolveState->ResolveRef);
+  resolveState->ResolveRef = nullptr;
+  resolveState->data.port = ntohs(port);
+
+  int txtCount = TXTRecordGetCount(txtLen, txtRecord);
+  char keyBuf[256];
+  uint8_t valueLen;
+  const void* value;
+
+  for (int i = 0; i < txtCount; i++) {
+    errorCode = TXTRecordGetItemAtIndex(txtLen, txtRecord, i, sizeof(keyBuf),
+                                        keyBuf, &valueLen, &value);
+    if (errorCode == kDNSServiceErr_NoError) {
+      if (valueLen == 0) {
+        // No value
+        resolveState->data.txt.emplace_back(
+            std::pair<std::string, std::string>{std::string{keyBuf}, {}});
+      } else {
+        resolveState->data.txt.emplace_back(std::pair<std::string, std::string>{
+            std::string{keyBuf},
+            std::string{reinterpret_cast<const char*>(value), valueLen}});
+      }
+    }
+  }
+
+  errorCode = DNSServiceGetAddrInfo(
+      &resolveState->ResolveRef, flags, interfaceIndex,
+      kDNSServiceProtocol_IPv4, hosttarget, ServiceGetAddrInfoReply, context);
+
+  if (errorCode == kDNSServiceErr_NoError) {
+    dnssd_sock_t socket = DNSServiceRefSockFD(resolveState->ResolveRef);
+    resolveState->pImpl->thread->AddServiceRef(resolveState->ResolveRef,
+                                               socket);
+  } else {
+    resolveState->pImpl->thread->RemoveServiceRefInThread(
+        resolveState->ResolveRef);
+    resolveState->pImpl->ResolveStates.erase(std::find_if(
+        resolveState->pImpl->ResolveStates.begin(),
+        resolveState->pImpl->ResolveStates.end(),
+        [resolveState](auto& a) { return a.get() == resolveState; }));
+  }
+}
+
+static void DnsCompletion(DNSServiceRef sdRef, DNSServiceFlags flags,
+                          uint32_t interfaceIndex,
+                          DNSServiceErrorType errorCode,
+                          const char* serviceName, const char* regtype,
+                          const char* replyDomain, void* context) {
+  if (errorCode != kDNSServiceErr_NoError) {
+    return;
+  }
+  if (!(flags & kDNSServiceFlagsAdd)) {
+    return;
+  }
+
+  MulticastServiceResolver::Impl* impl =
+      static_cast<MulticastServiceResolver::Impl*>(context);
+  auto& resolveState = impl->ResolveStates.emplace_back(
+      std::make_unique<DnsResolveState>(impl, serviceName));
+
+  errorCode = DNSServiceResolve(&resolveState->ResolveRef, 0, interfaceIndex,
+                                serviceName, regtype, replyDomain,
+                                ServiceResolveReply, resolveState.get());
+
+  if (errorCode == kDNSServiceErr_NoError) {
+    dnssd_sock_t socket = DNSServiceRefSockFD(resolveState->ResolveRef);
+    resolveState->pImpl->thread->AddServiceRef(resolveState->ResolveRef,
+                                               socket);
+  } else {
+    resolveState->pImpl->ResolveStates.erase(std::find_if(
+        resolveState->pImpl->ResolveStates.begin(),
+        resolveState->pImpl->ResolveStates.end(),
+        [r = resolveState.get()](auto& a) { return a.get() == r; }));
+  }
+}
+
+bool MulticastServiceResolver::HasImplementation() const {
+  return true;
+}
+
+void MulticastServiceResolver::Start() {
+  if (pImpl->serviceRef) {
+    return;
+  }
+
+  DNSServiceErrorType status =
+      DNSServiceBrowse(&pImpl->serviceRef, 0, 0, pImpl->serviceType.c_str(),
+                       "local", DnsCompletion, pImpl.get());
+  if (status == kDNSServiceErr_NoError) {
+    dnssd_sock_t socket = DNSServiceRefSockFD(pImpl->serviceRef);
+    pImpl->thread->AddServiceRef(pImpl->serviceRef, socket);
+  }
+}
+
+void MulticastServiceResolver::Stop() {
+  if (!pImpl->serviceRef) {
+    return;
+  }
+  wpi::SmallVector<WPI_EventHandle, 8> cleanupEvents;
+  for (auto&& i : pImpl->ResolveStates) {
+    cleanupEvents.push_back(
+        pImpl->thread->RemoveServiceRefOutsideThread(i->ResolveRef));
+  }
+  cleanupEvents.push_back(
+      pImpl->thread->RemoveServiceRefOutsideThread(pImpl->serviceRef));
+  wpi::SmallVector<WPI_Handle, 8> signaledBuf;
+  signaledBuf.resize(cleanupEvents.size());
+  while (!cleanupEvents.empty()) {
+    auto signaled = wpi::WaitForObjects(cleanupEvents, signaledBuf);
+    for (auto&& s : signaled) {
+      cleanupEvents.erase(
+          std::find(cleanupEvents.begin(), cleanupEvents.end(), s));
+    }
+  }
+
+  pImpl->ResolveStates.clear();
+  pImpl->serviceRef = nullptr;
+}
+
+#endif  // defined(__APPLE__)
diff --git a/third_party/allwpilib/wpinet/src/main/native/macOS/ResolverThread.cpp b/third_party/allwpilib/wpinet/src/main/native/macOS/ResolverThread.cpp
new file mode 100644
index 0000000..1452670
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/macOS/ResolverThread.cpp
@@ -0,0 +1,115 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#if defined(__APPLE__)
+
+#include "ResolverThread.h"
+
+#include <algorithm>
+
+#include <wpi/mutex.h>
+
+using namespace wpi;
+
+ResolverThread::ResolverThread(const private_init&) {}
+
+ResolverThread::~ResolverThread() noexcept {
+  running = false;
+  if (thread.joinable()) {
+    thread.join();
+  }
+}
+
+void ResolverThread::AddServiceRef(DNSServiceRef serviceRef,
+                                   dnssd_sock_t socket) {
+  std::scoped_lock lock{serviceRefMutex};
+  serviceRefs.emplace_back(
+      std::pair<DNSServiceRef, dnssd_sock_t>{serviceRef, socket});
+  if (serviceRefs.size() == 1) {
+    running = false;
+    if (thread.joinable()) {
+      thread.join();
+    }
+    running = true;
+    thread = std::thread([=] { ThreadMain(); });
+  }
+}
+
+void ResolverThread::RemoveServiceRefInThread(DNSServiceRef serviceRef) {
+  std::scoped_lock lock{serviceRefMutex};
+  serviceRefs.erase(
+      std::find_if(serviceRefs.begin(), serviceRefs.end(),
+                   [=](auto& a) { return a.first == serviceRef; }));
+  DNSServiceRefDeallocate(serviceRef);
+}
+
+WPI_EventHandle ResolverThread::RemoveServiceRefOutsideThread(
+    DNSServiceRef serviceRef) {
+  std::scoped_lock lock{serviceRefMutex};
+  WPI_EventHandle handle = CreateEvent(true);
+  serviceRefsToRemove.push_back({serviceRef, handle});
+  return handle;
+}
+
+bool ResolverThread::CleanupRefs() {
+  std::scoped_lock lock{serviceRefMutex};
+  for (auto&& r : serviceRefsToRemove) {
+    serviceRefs.erase(
+        std::find_if(serviceRefs.begin(), serviceRefs.end(),
+                     [=](auto& a) { return a.first == r.first; }));
+    DNSServiceRefDeallocate(r.first);
+    wpi::SetEvent(r.second);
+  }
+  serviceRefsToRemove.clear();
+  return serviceRefs.empty();
+}
+
+void ResolverThread::ThreadMain() {
+  std::vector<pollfd> readSockets;
+  std::vector<DNSServiceRef> serviceRefs;
+
+  while (running) {
+    readSockets.clear();
+    serviceRefs.clear();
+
+    for (auto&& i : this->serviceRefs) {
+      readSockets.emplace_back(pollfd{i.second, POLLIN, 0});
+      serviceRefs.emplace_back(i.first);
+    }
+
+    int res = poll(readSockets.begin().base(), readSockets.size(), 100);
+
+    if (res > 0) {
+      for (size_t i = 0; i < readSockets.size(); i++) {
+        if (readSockets[i].revents == POLLIN) {
+          DNSServiceProcessResult(serviceRefs[i]);
+        }
+      }
+    } else if (res == 0) {
+      if (!running) {
+        CleanupRefs();
+        break;
+      }
+    }
+
+    if (CleanupRefs()) {
+      break;
+    }
+  }
+}
+
+static wpi::mutex ThreadLoopLock;
+static std::weak_ptr<ResolverThread> ThreadLoop;
+
+std::shared_ptr<ResolverThread> ResolverThread::Get() {
+  std::scoped_lock lock{ThreadLoopLock};
+  auto locked = ThreadLoop.lock();
+  if (!locked) {
+    locked = std::make_unique<ResolverThread>(private_init{});
+    ThreadLoop = locked;
+  }
+  return locked;
+}
+
+#endif  // defined(__APPLE__)
diff --git a/third_party/allwpilib/wpinet/src/main/native/macOS/ResolverThread.h b/third_party/allwpilib/wpinet/src/main/native/macOS/ResolverThread.h
new file mode 100644
index 0000000..158cda8
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/macOS/ResolverThread.h
@@ -0,0 +1,50 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#if defined(__APPLE__)
+
+#pragma once
+
+#include <netinet/in.h>
+#include <poll.h>
+
+#include <atomic>
+#include <memory>
+#include <thread>
+#include <utility>
+#include <vector>
+
+#include <wpi/Synchronization.h>
+#include <wpi/mutex.h>
+
+#include "dns_sd.h"
+
+namespace wpi {
+class ResolverThread {
+ private:
+  struct private_init {};
+
+ public:
+  explicit ResolverThread(const private_init&);
+  ~ResolverThread() noexcept;
+
+  void AddServiceRef(DNSServiceRef serviceRef, dnssd_sock_t socket);
+  void RemoveServiceRefInThread(DNSServiceRef serviceRef);
+  WPI_EventHandle RemoveServiceRefOutsideThread(DNSServiceRef serviceRef);
+
+  static std::shared_ptr<ResolverThread> Get();
+
+ private:
+  void ThreadMain();
+  bool CleanupRefs();
+
+  wpi::mutex serviceRefMutex;
+  std::vector<std::pair<DNSServiceRef, WPI_EventHandle>> serviceRefsToRemove;
+  std::vector<std::pair<DNSServiceRef, dnssd_sock_t>> serviceRefs;
+  std::thread thread;
+  std::atomic_bool running;
+};
+}  // namespace wpi
+
+#endif  // defined(__APPLE__)
diff --git a/third_party/allwpilib/wpiutil/src/main/native/resources/bootstrap-4.1.min.js.gz b/third_party/allwpilib/wpinet/src/main/native/resources/bootstrap-4.1.min.js.gz
similarity index 100%
rename from third_party/allwpilib/wpiutil/src/main/native/resources/bootstrap-4.1.min.js.gz
rename to third_party/allwpilib/wpinet/src/main/native/resources/bootstrap-4.1.min.js.gz
Binary files differ
diff --git a/third_party/allwpilib/wpiutil/src/main/native/resources/coreui-2.1.min.css.gz b/third_party/allwpilib/wpinet/src/main/native/resources/coreui-2.1.min.css.gz
similarity index 100%
rename from third_party/allwpilib/wpiutil/src/main/native/resources/coreui-2.1.min.css.gz
rename to third_party/allwpilib/wpinet/src/main/native/resources/coreui-2.1.min.css.gz
Binary files differ
diff --git a/third_party/allwpilib/wpiutil/src/main/native/resources/coreui-2.1.min.js.gz b/third_party/allwpilib/wpinet/src/main/native/resources/coreui-2.1.min.js.gz
similarity index 100%
rename from third_party/allwpilib/wpiutil/src/main/native/resources/coreui-2.1.min.js.gz
rename to third_party/allwpilib/wpinet/src/main/native/resources/coreui-2.1.min.js.gz
Binary files differ
diff --git a/third_party/allwpilib/wpiutil/src/main/native/resources/feather-4.8.min.js.gz b/third_party/allwpilib/wpinet/src/main/native/resources/feather-4.8.min.js.gz
similarity index 100%
rename from third_party/allwpilib/wpiutil/src/main/native/resources/feather-4.8.min.js.gz
rename to third_party/allwpilib/wpinet/src/main/native/resources/feather-4.8.min.js.gz
Binary files differ
diff --git a/third_party/allwpilib/wpiutil/src/main/native/resources/jquery-3.3.slim.min.js.gz b/third_party/allwpilib/wpinet/src/main/native/resources/jquery-3.3.slim.min.js.gz
similarity index 100%
rename from third_party/allwpilib/wpiutil/src/main/native/resources/jquery-3.3.slim.min.js.gz
rename to third_party/allwpilib/wpinet/src/main/native/resources/jquery-3.3.slim.min.js.gz
Binary files differ
diff --git a/third_party/allwpilib/wpiutil/src/main/native/resources/popper-1.14.min.js.gz b/third_party/allwpilib/wpinet/src/main/native/resources/popper-1.14.min.js.gz
similarity index 100%
rename from third_party/allwpilib/wpiutil/src/main/native/resources/popper-1.14.min.js.gz
rename to third_party/allwpilib/wpinet/src/main/native/resources/popper-1.14.min.js.gz
Binary files differ
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/include/uv.h b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/include/uv.h
new file mode 100644
index 0000000..dbaeb1e
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/include/uv.h
@@ -0,0 +1,1834 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+/* See https://github.com/libuv/libuv#documentation for documentation. */
+
+#ifndef UV_H
+#define UV_H
+
+#if defined(BUILDING_UV_SHARED) && defined(USING_UV_SHARED)
+#error "Define either BUILDING_UV_SHARED or USING_UV_SHARED, not both."
+#endif
+
+#ifdef _WIN32
+  /* Windows - set up dll import/export decorators. */
+# if defined(BUILDING_UV_SHARED)
+    /* Building shared library. */
+#   define UV_EXTERN __declspec(dllexport)
+# elif defined(USING_UV_SHARED)
+    /* Using shared library. */
+#   define UV_EXTERN __declspec(dllimport)
+# else
+    /* Building static library. */
+#   define UV_EXTERN /* nothing */
+# endif
+#elif __GNUC__ >= 4
+# define UV_EXTERN __attribute__((visibility("default")))
+#elif defined(__SUNPRO_C) && (__SUNPRO_C >= 0x550) /* Sun Studio >= 8 */
+# define UV_EXTERN __global
+#else
+# define UV_EXTERN /* nothing */
+#endif
+
+#include "uv/errno.h"
+#include "uv/version.h"
+#include <stddef.h>
+#include <stdio.h>
+
+#include <stdint.h>
+
+#if defined(_WIN32)
+# include "uv/win.h"
+#else
+# include "uv/unix.h"
+#endif
+
+/* Expand this list if necessary. */
+#define UV_ERRNO_MAP(XX)                                                      \
+  XX(E2BIG, "argument list too long")                                         \
+  XX(EACCES, "permission denied")                                             \
+  XX(EADDRINUSE, "address already in use")                                    \
+  XX(EADDRNOTAVAIL, "address not available")                                  \
+  XX(EAFNOSUPPORT, "address family not supported")                            \
+  XX(EAGAIN, "resource temporarily unavailable")                              \
+  XX(EAI_ADDRFAMILY, "address family not supported")                          \
+  XX(EAI_AGAIN, "temporary failure")                                          \
+  XX(EAI_BADFLAGS, "bad ai_flags value")                                      \
+  XX(EAI_BADHINTS, "invalid value for hints")                                 \
+  XX(EAI_CANCELED, "request canceled")                                        \
+  XX(EAI_FAIL, "permanent failure")                                           \
+  XX(EAI_FAMILY, "ai_family not supported")                                   \
+  XX(EAI_MEMORY, "out of memory")                                             \
+  XX(EAI_NODATA, "no address")                                                \
+  XX(EAI_NONAME, "unknown node or service")                                   \
+  XX(EAI_OVERFLOW, "argument buffer overflow")                                \
+  XX(EAI_PROTOCOL, "resolved protocol is unknown")                            \
+  XX(EAI_SERVICE, "service not available for socket type")                    \
+  XX(EAI_SOCKTYPE, "socket type not supported")                               \
+  XX(EALREADY, "connection already in progress")                              \
+  XX(EBADF, "bad file descriptor")                                            \
+  XX(EBUSY, "resource busy or locked")                                        \
+  XX(ECANCELED, "operation canceled")                                         \
+  XX(ECHARSET, "invalid Unicode character")                                   \
+  XX(ECONNABORTED, "software caused connection abort")                        \
+  XX(ECONNREFUSED, "connection refused")                                      \
+  XX(ECONNRESET, "connection reset by peer")                                  \
+  XX(EDESTADDRREQ, "destination address required")                            \
+  XX(EEXIST, "file already exists")                                           \
+  XX(EFAULT, "bad address in system call argument")                           \
+  XX(EFBIG, "file too large")                                                 \
+  XX(EHOSTUNREACH, "host is unreachable")                                     \
+  XX(EINTR, "interrupted system call")                                        \
+  XX(EINVAL, "invalid argument")                                              \
+  XX(EIO, "i/o error")                                                        \
+  XX(EISCONN, "socket is already connected")                                  \
+  XX(EISDIR, "illegal operation on a directory")                              \
+  XX(ELOOP, "too many symbolic links encountered")                            \
+  XX(EMFILE, "too many open files")                                           \
+  XX(EMSGSIZE, "message too long")                                            \
+  XX(ENAMETOOLONG, "name too long")                                           \
+  XX(ENETDOWN, "network is down")                                             \
+  XX(ENETUNREACH, "network is unreachable")                                   \
+  XX(ENFILE, "file table overflow")                                           \
+  XX(ENOBUFS, "no buffer space available")                                    \
+  XX(ENODEV, "no such device")                                                \
+  XX(ENOENT, "no such file or directory")                                     \
+  XX(ENOMEM, "not enough memory")                                             \
+  XX(ENONET, "machine is not on the network")                                 \
+  XX(ENOPROTOOPT, "protocol not available")                                   \
+  XX(ENOSPC, "no space left on device")                                       \
+  XX(ENOSYS, "function not implemented")                                      \
+  XX(ENOTCONN, "socket is not connected")                                     \
+  XX(ENOTDIR, "not a directory")                                              \
+  XX(ENOTEMPTY, "directory not empty")                                        \
+  XX(ENOTSOCK, "socket operation on non-socket")                              \
+  XX(ENOTSUP, "operation not supported on socket")                            \
+  XX(EOVERFLOW, "value too large for defined data type")                      \
+  XX(EPERM, "operation not permitted")                                        \
+  XX(EPIPE, "broken pipe")                                                    \
+  XX(EPROTO, "protocol error")                                                \
+  XX(EPROTONOSUPPORT, "protocol not supported")                               \
+  XX(EPROTOTYPE, "protocol wrong type for socket")                            \
+  XX(ERANGE, "result too large")                                              \
+  XX(EROFS, "read-only file system")                                          \
+  XX(ESHUTDOWN, "cannot send after transport endpoint shutdown")              \
+  XX(ESPIPE, "invalid seek")                                                  \
+  XX(ESRCH, "no such process")                                                \
+  XX(ETIMEDOUT, "connection timed out")                                       \
+  XX(ETXTBSY, "text file is busy")                                            \
+  XX(EXDEV, "cross-device link not permitted")                                \
+  XX(UNKNOWN, "unknown error")                                                \
+  XX(EOF, "end of file")                                                      \
+  XX(ENXIO, "no such device or address")                                      \
+  XX(EMLINK, "too many links")                                                \
+  XX(EHOSTDOWN, "host is down")                                               \
+  XX(EREMOTEIO, "remote I/O error")                                           \
+  XX(ENOTTY, "inappropriate ioctl for device")                                \
+  XX(EFTYPE, "inappropriate file type or format")                             \
+  XX(EILSEQ, "illegal byte sequence")                                         \
+  XX(ESOCKTNOSUPPORT, "socket type not supported")                            \
+
+#define UV_HANDLE_TYPE_MAP(XX)                                                \
+  XX(ASYNC, async)                                                            \
+  XX(CHECK, check)                                                            \
+  XX(FS_EVENT, fs_event)                                                      \
+  XX(FS_POLL, fs_poll)                                                        \
+  XX(HANDLE, handle)                                                          \
+  XX(IDLE, idle)                                                              \
+  XX(NAMED_PIPE, pipe)                                                        \
+  XX(POLL, poll)                                                              \
+  XX(PREPARE, prepare)                                                        \
+  XX(PROCESS, process)                                                        \
+  XX(STREAM, stream)                                                          \
+  XX(TCP, tcp)                                                                \
+  XX(TIMER, timer)                                                            \
+  XX(TTY, tty)                                                                \
+  XX(UDP, udp)                                                                \
+  XX(SIGNAL, signal)                                                          \
+
+#define UV_REQ_TYPE_MAP(XX)                                                   \
+  XX(REQ, req)                                                                \
+  XX(CONNECT, connect)                                                        \
+  XX(WRITE, write)                                                            \
+  XX(SHUTDOWN, shutdown)                                                      \
+  XX(UDP_SEND, udp_send)                                                      \
+  XX(FS, fs)                                                                  \
+  XX(WORK, work)                                                              \
+  XX(GETADDRINFO, getaddrinfo)                                                \
+  XX(GETNAMEINFO, getnameinfo)                                                \
+  XX(RANDOM, random)                                                          \
+
+typedef enum {
+#define XX(code, _) UV_ ## code = UV__ ## code,
+  UV_ERRNO_MAP(XX)
+#undef XX
+  UV_ERRNO_MAX = UV__EOF - 1
+} uv_errno_t;
+
+typedef enum {
+  UV_UNKNOWN_HANDLE = 0,
+#define XX(uc, lc) UV_##uc,
+  UV_HANDLE_TYPE_MAP(XX)
+#undef XX
+  UV_FILE,
+  UV_HANDLE_TYPE_MAX
+} uv_handle_type;
+
+typedef enum {
+  UV_UNKNOWN_REQ = 0,
+#define XX(uc, lc) UV_##uc,
+  UV_REQ_TYPE_MAP(XX)
+#undef XX
+  UV_REQ_TYPE_PRIVATE
+  UV_REQ_TYPE_MAX
+} uv_req_type;
+
+
+/* Handle types. */
+typedef struct uv_loop_s uv_loop_t;
+typedef struct uv_handle_s uv_handle_t;
+typedef struct uv_dir_s uv_dir_t;
+typedef struct uv_stream_s uv_stream_t;
+typedef struct uv_tcp_s uv_tcp_t;
+typedef struct uv_udp_s uv_udp_t;
+typedef struct uv_pipe_s uv_pipe_t;
+typedef struct uv_tty_s uv_tty_t;
+typedef struct uv_poll_s uv_poll_t;
+typedef struct uv_timer_s uv_timer_t;
+typedef struct uv_prepare_s uv_prepare_t;
+typedef struct uv_check_s uv_check_t;
+typedef struct uv_idle_s uv_idle_t;
+typedef struct uv_async_s uv_async_t;
+typedef struct uv_process_s uv_process_t;
+typedef struct uv_fs_event_s uv_fs_event_t;
+typedef struct uv_fs_poll_s uv_fs_poll_t;
+typedef struct uv_signal_s uv_signal_t;
+
+/* Request types. */
+typedef struct uv_req_s uv_req_t;
+typedef struct uv_getaddrinfo_s uv_getaddrinfo_t;
+typedef struct uv_getnameinfo_s uv_getnameinfo_t;
+typedef struct uv_shutdown_s uv_shutdown_t;
+typedef struct uv_write_s uv_write_t;
+typedef struct uv_connect_s uv_connect_t;
+typedef struct uv_udp_send_s uv_udp_send_t;
+typedef struct uv_fs_s uv_fs_t;
+typedef struct uv_work_s uv_work_t;
+typedef struct uv_random_s uv_random_t;
+
+/* None of the above. */
+typedef struct uv_env_item_s uv_env_item_t;
+typedef struct uv_cpu_info_s uv_cpu_info_t;
+typedef struct uv_interface_address_s uv_interface_address_t;
+typedef struct uv_dirent_s uv_dirent_t;
+typedef struct uv_passwd_s uv_passwd_t;
+typedef struct uv_utsname_s uv_utsname_t;
+typedef struct uv_statfs_s uv_statfs_t;
+
+typedef enum {
+  UV_LOOP_BLOCK_SIGNAL = 0,
+  UV_METRICS_IDLE_TIME
+} uv_loop_option;
+
+typedef enum {
+  UV_RUN_DEFAULT = 0,
+  UV_RUN_ONCE,
+  UV_RUN_NOWAIT
+} uv_run_mode;
+
+
+UV_EXTERN unsigned int uv_version(void);
+UV_EXTERN const char* uv_version_string(void);
+
+typedef void* (*uv_malloc_func)(size_t size);
+typedef void* (*uv_realloc_func)(void* ptr, size_t size);
+typedef void* (*uv_calloc_func)(size_t count, size_t size);
+typedef void (*uv_free_func)(void* ptr);
+
+UV_EXTERN void uv_library_shutdown(void);
+
+UV_EXTERN int uv_replace_allocator(uv_malloc_func malloc_func,
+                                   uv_realloc_func realloc_func,
+                                   uv_calloc_func calloc_func,
+                                   uv_free_func free_func);
+
+UV_EXTERN uv_loop_t* uv_default_loop(void);
+UV_EXTERN int uv_loop_init(uv_loop_t* loop);
+UV_EXTERN int uv_loop_close(uv_loop_t* loop);
+/*
+ * NOTE:
+ *  This function is DEPRECATED (to be removed after 0.12), users should
+ *  allocate the loop manually and use uv_loop_init instead.
+ */
+UV_EXTERN uv_loop_t* uv_loop_new(void);
+/*
+ * NOTE:
+ *  This function is DEPRECATED (to be removed after 0.12). Users should use
+ *  uv_loop_close and free the memory manually instead.
+ */
+UV_EXTERN void uv_loop_delete(uv_loop_t*);
+UV_EXTERN size_t uv_loop_size(void);
+UV_EXTERN int uv_loop_alive(const uv_loop_t* loop);
+UV_EXTERN int uv_loop_configure(uv_loop_t* loop, uv_loop_option option, ...);
+UV_EXTERN int uv_loop_fork(uv_loop_t* loop);
+
+UV_EXTERN int uv_run(uv_loop_t*, uv_run_mode mode);
+UV_EXTERN void uv_stop(uv_loop_t*);
+
+UV_EXTERN void uv_ref(uv_handle_t*);
+UV_EXTERN void uv_unref(uv_handle_t*);
+UV_EXTERN int uv_has_ref(const uv_handle_t*);
+
+UV_EXTERN void uv_update_time(uv_loop_t*);
+UV_EXTERN uint64_t uv_now(const uv_loop_t*);
+
+UV_EXTERN int uv_backend_fd(const uv_loop_t*);
+UV_EXTERN int uv_backend_timeout(const uv_loop_t*);
+
+typedef void (*uv_alloc_cb)(uv_handle_t* handle,
+                            size_t suggested_size,
+                            uv_buf_t* buf);
+typedef void (*uv_read_cb)(uv_stream_t* stream,
+                           ssize_t nread,
+                           const uv_buf_t* buf);
+typedef void (*uv_write_cb)(uv_write_t* req, int status);
+typedef void (*uv_connect_cb)(uv_connect_t* req, int status);
+typedef void (*uv_shutdown_cb)(uv_shutdown_t* req, int status);
+typedef void (*uv_connection_cb)(uv_stream_t* server, int status);
+typedef void (*uv_close_cb)(uv_handle_t* handle);
+typedef void (*uv_poll_cb)(uv_poll_t* handle, int status, int events);
+typedef void (*uv_timer_cb)(uv_timer_t* handle);
+typedef void (*uv_async_cb)(uv_async_t* handle);
+typedef void (*uv_prepare_cb)(uv_prepare_t* handle);
+typedef void (*uv_check_cb)(uv_check_t* handle);
+typedef void (*uv_idle_cb)(uv_idle_t* handle);
+typedef void (*uv_exit_cb)(uv_process_t*, int64_t exit_status, int term_signal);
+typedef void (*uv_walk_cb)(uv_handle_t* handle, void* arg);
+typedef void (*uv_fs_cb)(uv_fs_t* req);
+typedef void (*uv_work_cb)(uv_work_t* req);
+typedef void (*uv_after_work_cb)(uv_work_t* req, int status);
+typedef void (*uv_getaddrinfo_cb)(uv_getaddrinfo_t* req,
+                                  int status,
+                                  struct addrinfo* res);
+typedef void (*uv_getnameinfo_cb)(uv_getnameinfo_t* req,
+                                  int status,
+                                  const char* hostname,
+                                  const char* service);
+typedef void (*uv_random_cb)(uv_random_t* req,
+                             int status,
+                             void* buf,
+                             size_t buflen);
+
+typedef struct {
+  long tv_sec;
+  long tv_nsec;
+} uv_timespec_t;
+
+
+typedef struct {
+  uint64_t st_dev;
+  uint64_t st_mode;
+  uint64_t st_nlink;
+  uint64_t st_uid;
+  uint64_t st_gid;
+  uint64_t st_rdev;
+  uint64_t st_ino;
+  uint64_t st_size;
+  uint64_t st_blksize;
+  uint64_t st_blocks;
+  uint64_t st_flags;
+  uint64_t st_gen;
+  uv_timespec_t st_atim;
+  uv_timespec_t st_mtim;
+  uv_timespec_t st_ctim;
+  uv_timespec_t st_birthtim;
+} uv_stat_t;
+
+
+typedef void (*uv_fs_event_cb)(uv_fs_event_t* handle,
+                               const char* filename,
+                               int events,
+                               int status);
+
+typedef void (*uv_fs_poll_cb)(uv_fs_poll_t* handle,
+                              int status,
+                              const uv_stat_t* prev,
+                              const uv_stat_t* curr);
+
+typedef void (*uv_signal_cb)(uv_signal_t* handle, int signum);
+
+
+typedef enum {
+  UV_LEAVE_GROUP = 0,
+  UV_JOIN_GROUP
+} uv_membership;
+
+
+UV_EXTERN int uv_translate_sys_error(int sys_errno);
+
+UV_EXTERN const char* uv_strerror(int err);
+UV_EXTERN char* uv_strerror_r(int err, char* buf, size_t buflen);
+
+UV_EXTERN const char* uv_err_name(int err);
+UV_EXTERN char* uv_err_name_r(int err, char* buf, size_t buflen);
+
+
+#define UV_REQ_FIELDS                                                         \
+  /* public */                                                                \
+  void* data;                                                                 \
+  /* read-only */                                                             \
+  uv_req_type type;                                                           \
+  /* private */                                                               \
+  void* reserved[6];                                                          \
+  UV_REQ_PRIVATE_FIELDS                                                       \
+
+/* Abstract base class of all requests. */
+struct uv_req_s {
+  UV_REQ_FIELDS
+};
+
+
+/* Platform-specific request types. */
+UV_PRIVATE_REQ_TYPES
+
+
+UV_EXTERN int uv_shutdown(uv_shutdown_t* req,
+                          uv_stream_t* handle,
+                          uv_shutdown_cb cb);
+
+struct uv_shutdown_s {
+  UV_REQ_FIELDS
+  uv_stream_t* handle;
+  uv_shutdown_cb cb;
+  UV_SHUTDOWN_PRIVATE_FIELDS
+};
+
+
+#define UV_HANDLE_FIELDS                                                      \
+  /* public */                                                                \
+  void* data;                                                                 \
+  /* read-only */                                                             \
+  uv_loop_t* loop;                                                            \
+  uv_handle_type type;                                                        \
+  /* private */                                                               \
+  uv_close_cb close_cb;                                                       \
+  void* handle_queue[2];                                                      \
+  union {                                                                     \
+    int fd;                                                                   \
+    void* reserved[4];                                                        \
+  } u;                                                                        \
+  UV_HANDLE_PRIVATE_FIELDS                                                    \
+
+/* The abstract base class of all handles. */
+struct uv_handle_s {
+  UV_HANDLE_FIELDS
+};
+
+UV_EXTERN size_t uv_handle_size(uv_handle_type type);
+UV_EXTERN uv_handle_type uv_handle_get_type(const uv_handle_t* handle);
+UV_EXTERN const char* uv_handle_type_name(uv_handle_type type);
+UV_EXTERN void* uv_handle_get_data(const uv_handle_t* handle);
+UV_EXTERN uv_loop_t* uv_handle_get_loop(const uv_handle_t* handle);
+UV_EXTERN void uv_handle_set_data(uv_handle_t* handle, void* data);
+
+UV_EXTERN size_t uv_req_size(uv_req_type type);
+UV_EXTERN void* uv_req_get_data(const uv_req_t* req);
+UV_EXTERN void uv_req_set_data(uv_req_t* req, void* data);
+UV_EXTERN uv_req_type uv_req_get_type(const uv_req_t* req);
+UV_EXTERN const char* uv_req_type_name(uv_req_type type);
+
+UV_EXTERN int uv_is_active(const uv_handle_t* handle);
+
+UV_EXTERN void uv_walk(uv_loop_t* loop, uv_walk_cb walk_cb, void* arg);
+
+/* Helpers for ad hoc debugging, no API/ABI stability guaranteed. */
+UV_EXTERN void uv_print_all_handles(uv_loop_t* loop, FILE* stream);
+UV_EXTERN void uv_print_active_handles(uv_loop_t* loop, FILE* stream);
+
+UV_EXTERN void uv_close(uv_handle_t* handle, uv_close_cb close_cb);
+
+UV_EXTERN int uv_send_buffer_size(uv_handle_t* handle, int* value);
+UV_EXTERN int uv_recv_buffer_size(uv_handle_t* handle, int* value);
+
+UV_EXTERN int uv_fileno(const uv_handle_t* handle, uv_os_fd_t* fd);
+
+UV_EXTERN uv_buf_t uv_buf_init(char* base, unsigned int len);
+
+UV_EXTERN int uv_pipe(uv_file fds[2], int read_flags, int write_flags);
+UV_EXTERN int uv_socketpair(int type,
+                            int protocol,
+                            uv_os_sock_t socket_vector[2],
+                            int flags0,
+                            int flags1);
+
+#define UV_STREAM_FIELDS                                                      \
+  /* number of bytes queued for writing */                                    \
+  size_t write_queue_size;                                                    \
+  uv_alloc_cb alloc_cb;                                                       \
+  uv_read_cb read_cb;                                                         \
+  /* private */                                                               \
+  UV_STREAM_PRIVATE_FIELDS
+
+/*
+ * uv_stream_t is a subclass of uv_handle_t.
+ *
+ * uv_stream is an abstract class.
+ *
+ * uv_stream_t is the parent class of uv_tcp_t, uv_pipe_t and uv_tty_t.
+ */
+struct uv_stream_s {
+  UV_HANDLE_FIELDS
+  UV_STREAM_FIELDS
+};
+
+UV_EXTERN size_t uv_stream_get_write_queue_size(const uv_stream_t* stream);
+
+UV_EXTERN int uv_listen(uv_stream_t* stream, int backlog, uv_connection_cb cb);
+UV_EXTERN int uv_accept(uv_stream_t* server, uv_stream_t* client);
+
+UV_EXTERN int uv_read_start(uv_stream_t*,
+                            uv_alloc_cb alloc_cb,
+                            uv_read_cb read_cb);
+UV_EXTERN int uv_read_stop(uv_stream_t*);
+
+UV_EXTERN int uv_write(uv_write_t* req,
+                       uv_stream_t* handle,
+                       const uv_buf_t bufs[],
+                       unsigned int nbufs,
+                       uv_write_cb cb);
+UV_EXTERN int uv_write2(uv_write_t* req,
+                        uv_stream_t* handle,
+                        const uv_buf_t bufs[],
+                        unsigned int nbufs,
+                        uv_stream_t* send_handle,
+                        uv_write_cb cb);
+UV_EXTERN int uv_try_write(uv_stream_t* handle,
+                           const uv_buf_t bufs[],
+                           unsigned int nbufs);
+UV_EXTERN int uv_try_write2(uv_stream_t* handle,
+                            const uv_buf_t bufs[],
+                            unsigned int nbufs,
+                            uv_stream_t* send_handle);
+
+/* uv_write_t is a subclass of uv_req_t. */
+struct uv_write_s {
+  UV_REQ_FIELDS
+  uv_write_cb cb;
+  uv_stream_t* send_handle; /* TODO: make private and unix-only in v2.x. */
+  uv_stream_t* handle;
+  UV_WRITE_PRIVATE_FIELDS
+};
+
+
+UV_EXTERN int uv_is_readable(const uv_stream_t* handle);
+UV_EXTERN int uv_is_writable(const uv_stream_t* handle);
+
+UV_EXTERN int uv_stream_set_blocking(uv_stream_t* handle, int blocking);
+
+UV_EXTERN int uv_is_closing(const uv_handle_t* handle);
+
+
+/*
+ * uv_tcp_t is a subclass of uv_stream_t.
+ *
+ * Represents a TCP stream or TCP server.
+ */
+struct uv_tcp_s {
+  UV_HANDLE_FIELDS
+  UV_STREAM_FIELDS
+  UV_TCP_PRIVATE_FIELDS
+};
+
+UV_EXTERN int uv_tcp_init(uv_loop_t*, uv_tcp_t* handle);
+UV_EXTERN int uv_tcp_init_ex(uv_loop_t*, uv_tcp_t* handle, unsigned int flags);
+UV_EXTERN int uv_tcp_open(uv_tcp_t* handle, uv_os_sock_t sock);
+UV_EXTERN int uv_tcp_nodelay(uv_tcp_t* handle, int enable);
+UV_EXTERN int uv_tcp_keepalive(uv_tcp_t* handle,
+                               int enable,
+                               unsigned int delay);
+UV_EXTERN int uv_tcp_simultaneous_accepts(uv_tcp_t* handle, int enable);
+
+enum uv_tcp_flags {
+  /* Used with uv_tcp_bind, when an IPv6 address is used. */
+  UV_TCP_IPV6ONLY = 1
+};
+
+UV_EXTERN int uv_tcp_bind(uv_tcp_t* handle,
+                          const struct sockaddr* addr,
+                          unsigned int flags);
+UV_EXTERN int uv_tcp_getsockname(const uv_tcp_t* handle,
+                                 struct sockaddr* name,
+                                 int* namelen);
+UV_EXTERN int uv_tcp_getpeername(const uv_tcp_t* handle,
+                                 struct sockaddr* name,
+                                 int* namelen);
+UV_EXTERN int uv_tcp_close_reset(uv_tcp_t* handle, uv_close_cb close_cb);
+UV_EXTERN int uv_tcp_connect(uv_connect_t* req,
+                             uv_tcp_t* handle,
+                             const struct sockaddr* addr,
+                             uv_connect_cb cb);
+
+/* uv_connect_t is a subclass of uv_req_t. */
+struct uv_connect_s {
+  UV_REQ_FIELDS
+  uv_connect_cb cb;
+  uv_stream_t* handle;
+  UV_CONNECT_PRIVATE_FIELDS
+};
+
+
+/*
+ * UDP support.
+ */
+
+enum uv_udp_flags {
+  /* Disables dual stack mode. */
+  UV_UDP_IPV6ONLY = 1,
+  /*
+   * Indicates message was truncated because read buffer was too small. The
+   * remainder was discarded by the OS. Used in uv_udp_recv_cb.
+   */
+  UV_UDP_PARTIAL = 2,
+  /*
+   * Indicates if SO_REUSEADDR will be set when binding the handle.
+   * This sets the SO_REUSEPORT socket flag on the BSDs and OS X. On other
+   * Unix platforms, it sets the SO_REUSEADDR flag.  What that means is that
+   * multiple threads or processes can bind to the same address without error
+   * (provided they all set the flag) but only the last one to bind will receive
+   * any traffic, in effect "stealing" the port from the previous listener.
+   */
+  UV_UDP_REUSEADDR = 4,
+  /*
+   * Indicates that the message was received by recvmmsg, so the buffer provided
+   * must not be freed by the recv_cb callback.
+   */
+  UV_UDP_MMSG_CHUNK = 8,
+  /*
+   * Indicates that the buffer provided has been fully utilized by recvmmsg and
+   * that it should now be freed by the recv_cb callback. When this flag is set
+   * in uv_udp_recv_cb, nread will always be 0 and addr will always be NULL.
+   */
+  UV_UDP_MMSG_FREE = 16,
+  /*
+   * Indicates if IP_RECVERR/IPV6_RECVERR will be set when binding the handle.
+   * This sets IP_RECVERR for IPv4 and IPV6_RECVERR for IPv6 UDP sockets on
+   * Linux. This stops the Linux kernel from suppressing some ICMP error
+   * messages and enables full ICMP error reporting for faster failover.
+   * This flag is no-op on platforms other than Linux.
+   */
+  UV_UDP_LINUX_RECVERR = 32,
+  /*
+   * Indicates that recvmmsg should be used, if available.
+   */
+  UV_UDP_RECVMMSG = 256
+};
+
+typedef void (*uv_udp_send_cb)(uv_udp_send_t* req, int status);
+typedef void (*uv_udp_recv_cb)(uv_udp_t* handle,
+                               ssize_t nread,
+                               const uv_buf_t* buf,
+                               const struct sockaddr* addr,
+                               unsigned flags);
+
+/* uv_udp_t is a subclass of uv_handle_t. */
+struct uv_udp_s {
+  UV_HANDLE_FIELDS
+  /* read-only */
+  /*
+   * Number of bytes queued for sending. This field strictly shows how much
+   * information is currently queued.
+   */
+  size_t send_queue_size;
+  /*
+   * Number of send requests currently in the queue awaiting to be processed.
+   */
+  size_t send_queue_count;
+  UV_UDP_PRIVATE_FIELDS
+};
+
+/* uv_udp_send_t is a subclass of uv_req_t. */
+struct uv_udp_send_s {
+  UV_REQ_FIELDS
+  uv_udp_t* handle;
+  uv_udp_send_cb cb;
+  UV_UDP_SEND_PRIVATE_FIELDS
+};
+
+UV_EXTERN int uv_udp_init(uv_loop_t*, uv_udp_t* handle);
+UV_EXTERN int uv_udp_init_ex(uv_loop_t*, uv_udp_t* handle, unsigned int flags);
+UV_EXTERN int uv_udp_open(uv_udp_t* handle, uv_os_sock_t sock);
+UV_EXTERN int uv_udp_bind(uv_udp_t* handle,
+                          const struct sockaddr* addr,
+                          unsigned int flags);
+UV_EXTERN int uv_udp_connect(uv_udp_t* handle, const struct sockaddr* addr);
+
+UV_EXTERN int uv_udp_getpeername(const uv_udp_t* handle,
+                                 struct sockaddr* name,
+                                 int* namelen);
+UV_EXTERN int uv_udp_getsockname(const uv_udp_t* handle,
+                                 struct sockaddr* name,
+                                 int* namelen);
+UV_EXTERN int uv_udp_set_membership(uv_udp_t* handle,
+                                    const char* multicast_addr,
+                                    const char* interface_addr,
+                                    uv_membership membership);
+UV_EXTERN int uv_udp_set_source_membership(uv_udp_t* handle,
+                                           const char* multicast_addr,
+                                           const char* interface_addr,
+                                           const char* source_addr,
+                                           uv_membership membership);
+UV_EXTERN int uv_udp_set_multicast_loop(uv_udp_t* handle, int on);
+UV_EXTERN int uv_udp_set_multicast_ttl(uv_udp_t* handle, int ttl);
+UV_EXTERN int uv_udp_set_multicast_interface(uv_udp_t* handle,
+                                             const char* interface_addr);
+UV_EXTERN int uv_udp_set_broadcast(uv_udp_t* handle, int on);
+UV_EXTERN int uv_udp_set_ttl(uv_udp_t* handle, int ttl);
+UV_EXTERN int uv_udp_send(uv_udp_send_t* req,
+                          uv_udp_t* handle,
+                          const uv_buf_t bufs[],
+                          unsigned int nbufs,
+                          const struct sockaddr* addr,
+                          uv_udp_send_cb send_cb);
+UV_EXTERN int uv_udp_try_send(uv_udp_t* handle,
+                              const uv_buf_t bufs[],
+                              unsigned int nbufs,
+                              const struct sockaddr* addr);
+UV_EXTERN int uv_udp_recv_start(uv_udp_t* handle,
+                                uv_alloc_cb alloc_cb,
+                                uv_udp_recv_cb recv_cb);
+UV_EXTERN int uv_udp_using_recvmmsg(const uv_udp_t* handle);
+UV_EXTERN int uv_udp_recv_stop(uv_udp_t* handle);
+UV_EXTERN size_t uv_udp_get_send_queue_size(const uv_udp_t* handle);
+UV_EXTERN size_t uv_udp_get_send_queue_count(const uv_udp_t* handle);
+
+
+/*
+ * uv_tty_t is a subclass of uv_stream_t.
+ *
+ * Representing a stream for the console.
+ */
+struct uv_tty_s {
+  UV_HANDLE_FIELDS
+  UV_STREAM_FIELDS
+  UV_TTY_PRIVATE_FIELDS
+};
+
+typedef enum {
+  /* Initial/normal terminal mode */
+  UV_TTY_MODE_NORMAL,
+  /* Raw input mode (On Windows, ENABLE_WINDOW_INPUT is also enabled) */
+  UV_TTY_MODE_RAW,
+  /* Binary-safe I/O mode for IPC (Unix-only) */
+  UV_TTY_MODE_IO
+} uv_tty_mode_t;
+
+typedef enum {
+  /*
+   * The console supports handling of virtual terminal sequences
+   * (Windows10 new console, ConEmu)
+   */
+  UV_TTY_SUPPORTED,
+  /* The console cannot process the virtual terminal sequence.  (Legacy
+   * console)
+   */
+  UV_TTY_UNSUPPORTED
+} uv_tty_vtermstate_t;
+
+
+UV_EXTERN int uv_tty_init(uv_loop_t*, uv_tty_t*, uv_file fd, int readable);
+UV_EXTERN int uv_tty_set_mode(uv_tty_t*, uv_tty_mode_t mode);
+UV_EXTERN int uv_tty_reset_mode(void);
+UV_EXTERN int uv_tty_get_winsize(uv_tty_t*, int* width, int* height);
+UV_EXTERN void uv_tty_set_vterm_state(uv_tty_vtermstate_t state);
+UV_EXTERN int uv_tty_get_vterm_state(uv_tty_vtermstate_t* state);
+
+inline int uv_tty_set_mode(uv_tty_t* handle, int mode) {
+  return uv_tty_set_mode(handle, static_cast<uv_tty_mode_t>(mode));
+}
+
+UV_EXTERN uv_handle_type uv_guess_handle(uv_file file);
+
+/*
+ * uv_pipe_t is a subclass of uv_stream_t.
+ *
+ * Representing a pipe stream or pipe server. On Windows this is a Named
+ * Pipe. On Unix this is a Unix domain socket.
+ */
+struct uv_pipe_s {
+  UV_HANDLE_FIELDS
+  UV_STREAM_FIELDS
+  int ipc; /* non-zero if this pipe is used for passing handles */
+  UV_PIPE_PRIVATE_FIELDS
+};
+
+UV_EXTERN int uv_pipe_init(uv_loop_t*, uv_pipe_t* handle, int ipc);
+UV_EXTERN int uv_pipe_open(uv_pipe_t*, uv_file file);
+UV_EXTERN int uv_pipe_bind(uv_pipe_t* handle, const char* name);
+UV_EXTERN void uv_pipe_connect(uv_connect_t* req,
+                               uv_pipe_t* handle,
+                               const char* name,
+                               uv_connect_cb cb);
+UV_EXTERN int uv_pipe_getsockname(const uv_pipe_t* handle,
+                                  char* buffer,
+                                  size_t* size);
+UV_EXTERN int uv_pipe_getpeername(const uv_pipe_t* handle,
+                                  char* buffer,
+                                  size_t* size);
+UV_EXTERN void uv_pipe_pending_instances(uv_pipe_t* handle, int count);
+UV_EXTERN int uv_pipe_pending_count(uv_pipe_t* handle);
+UV_EXTERN uv_handle_type uv_pipe_pending_type(uv_pipe_t* handle);
+UV_EXTERN int uv_pipe_chmod(uv_pipe_t* handle, int flags);
+
+
+struct uv_poll_s {
+  UV_HANDLE_FIELDS
+  uv_poll_cb poll_cb;
+  UV_POLL_PRIVATE_FIELDS
+};
+
+enum uv_poll_event {
+  UV_READABLE = 1,
+  UV_WRITABLE = 2,
+  UV_DISCONNECT = 4,
+  UV_PRIORITIZED = 8
+};
+
+UV_EXTERN int uv_poll_init(uv_loop_t* loop, uv_poll_t* handle, int fd);
+UV_EXTERN int uv_poll_init_socket(uv_loop_t* loop,
+                                  uv_poll_t* handle,
+                                  uv_os_sock_t socket);
+UV_EXTERN int uv_poll_start(uv_poll_t* handle, int events, uv_poll_cb cb);
+UV_EXTERN int uv_poll_stop(uv_poll_t* handle);
+
+
+struct uv_prepare_s {
+  UV_HANDLE_FIELDS
+  UV_PREPARE_PRIVATE_FIELDS
+};
+
+UV_EXTERN int uv_prepare_init(uv_loop_t*, uv_prepare_t* prepare);
+UV_EXTERN int uv_prepare_start(uv_prepare_t* prepare, uv_prepare_cb cb);
+UV_EXTERN int uv_prepare_stop(uv_prepare_t* prepare);
+
+
+struct uv_check_s {
+  UV_HANDLE_FIELDS
+  UV_CHECK_PRIVATE_FIELDS
+};
+
+UV_EXTERN int uv_check_init(uv_loop_t*, uv_check_t* check);
+UV_EXTERN int uv_check_start(uv_check_t* check, uv_check_cb cb);
+UV_EXTERN int uv_check_stop(uv_check_t* check);
+
+
+struct uv_idle_s {
+  UV_HANDLE_FIELDS
+  UV_IDLE_PRIVATE_FIELDS
+};
+
+UV_EXTERN int uv_idle_init(uv_loop_t*, uv_idle_t* idle);
+UV_EXTERN int uv_idle_start(uv_idle_t* idle, uv_idle_cb cb);
+UV_EXTERN int uv_idle_stop(uv_idle_t* idle);
+
+
+struct uv_async_s {
+  UV_HANDLE_FIELDS
+  UV_ASYNC_PRIVATE_FIELDS
+};
+
+UV_EXTERN int uv_async_init(uv_loop_t*,
+                            uv_async_t* async,
+                            uv_async_cb async_cb);
+UV_EXTERN int uv_async_send(uv_async_t* async);
+
+
+/*
+ * uv_timer_t is a subclass of uv_handle_t.
+ *
+ * Used to get woken up at a specified time in the future.
+ */
+struct uv_timer_s {
+  UV_HANDLE_FIELDS
+  UV_TIMER_PRIVATE_FIELDS
+};
+
+UV_EXTERN int uv_timer_init(uv_loop_t*, uv_timer_t* handle);
+UV_EXTERN int uv_timer_start(uv_timer_t* handle,
+                             uv_timer_cb cb,
+                             uint64_t timeout,
+                             uint64_t repeat);
+UV_EXTERN int uv_timer_stop(uv_timer_t* handle);
+UV_EXTERN int uv_timer_again(uv_timer_t* handle);
+UV_EXTERN void uv_timer_set_repeat(uv_timer_t* handle, uint64_t repeat);
+UV_EXTERN uint64_t uv_timer_get_repeat(const uv_timer_t* handle);
+UV_EXTERN uint64_t uv_timer_get_due_in(const uv_timer_t* handle);
+
+
+/*
+ * uv_getaddrinfo_t is a subclass of uv_req_t.
+ *
+ * Request object for uv_getaddrinfo.
+ */
+struct uv_getaddrinfo_s {
+  UV_REQ_FIELDS
+  /* read-only */
+  uv_loop_t* loop;
+  /* struct addrinfo* addrinfo is marked as private, but it really isn't. */
+  UV_GETADDRINFO_PRIVATE_FIELDS
+};
+
+
+UV_EXTERN int uv_getaddrinfo(uv_loop_t* loop,
+                             uv_getaddrinfo_t* req,
+                             uv_getaddrinfo_cb getaddrinfo_cb,
+                             const char* node,
+                             const char* service,
+                             const struct addrinfo* hints);
+UV_EXTERN void uv_freeaddrinfo(struct addrinfo* ai);
+
+
+/*
+* uv_getnameinfo_t is a subclass of uv_req_t.
+*
+* Request object for uv_getnameinfo.
+*/
+struct uv_getnameinfo_s {
+  UV_REQ_FIELDS
+  /* read-only */
+  uv_loop_t* loop;
+  /* host and service are marked as private, but they really aren't. */
+  UV_GETNAMEINFO_PRIVATE_FIELDS
+};
+
+UV_EXTERN int uv_getnameinfo(uv_loop_t* loop,
+                             uv_getnameinfo_t* req,
+                             uv_getnameinfo_cb getnameinfo_cb,
+                             const struct sockaddr* addr,
+                             int flags);
+
+
+/* uv_spawn() options. */
+typedef enum {
+  UV_IGNORE         = 0x00,
+  UV_CREATE_PIPE    = 0x01,
+  UV_INHERIT_FD     = 0x02,
+  UV_INHERIT_STREAM = 0x04,
+
+  /*
+   * When UV_CREATE_PIPE is specified, UV_READABLE_PIPE and UV_WRITABLE_PIPE
+   * determine the direction of flow, from the child process' perspective. Both
+   * flags may be specified to create a duplex data stream.
+   */
+  UV_READABLE_PIPE  = 0x10,
+  UV_WRITABLE_PIPE  = 0x20,
+
+  /*
+   * When UV_CREATE_PIPE is specified, specifying UV_NONBLOCK_PIPE opens the
+   * handle in non-blocking mode in the child. This may cause loss of data,
+   * if the child is not designed to handle to encounter this mode,
+   * but can also be significantly more efficient.
+   */
+  UV_NONBLOCK_PIPE  = 0x40,
+  UV_OVERLAPPED_PIPE = 0x40 /* old name, for compatibility */
+} uv_stdio_flags;
+
+typedef struct uv_stdio_container_s {
+  uv_stdio_flags flags;
+
+  union {
+    uv_stream_t* stream;
+    int fd;
+  } data;
+} uv_stdio_container_t;
+
+typedef struct uv_process_options_s {
+  uv_exit_cb exit_cb; /* Called after the process exits. */
+  const char* file;   /* Path to program to execute. */
+  /*
+   * Command line arguments. args[0] should be the path to the program. On
+   * Windows this uses CreateProcess which concatenates the arguments into a
+   * string this can cause some strange errors. See the note at
+   * windows_verbatim_arguments.
+   */
+  char** args;
+  /*
+   * This will be set as the environ variable in the subprocess. If this is
+   * NULL then the parents environ will be used.
+   */
+  char** env;
+  /*
+   * If non-null this represents a directory the subprocess should execute
+   * in. Stands for current working directory.
+   */
+  const char* cwd;
+  /*
+   * Various flags that control how uv_spawn() behaves. See the definition of
+   * `enum uv_process_flags` below.
+   */
+  unsigned int flags;
+  /*
+   * The `stdio` field points to an array of uv_stdio_container_t structs that
+   * describe the file descriptors that will be made available to the child
+   * process. The convention is that stdio[0] points to stdin, fd 1 is used for
+   * stdout, and fd 2 is stderr.
+   *
+   * Note that on windows file descriptors greater than 2 are available to the
+   * child process only if the child processes uses the MSVCRT runtime.
+   */
+  int stdio_count;
+  uv_stdio_container_t* stdio;
+  /*
+   * Libuv can change the child process' user/group id. This happens only when
+   * the appropriate bits are set in the flags fields. This is not supported on
+   * windows; uv_spawn() will fail and set the error to UV_ENOTSUP.
+   */
+  uv_uid_t uid;
+  uv_gid_t gid;
+} uv_process_options_t;
+
+/*
+ * These are the flags that can be used for the uv_process_options.flags field.
+ */
+enum uv_process_flags {
+  /*
+   * Set the child process' user id. The user id is supplied in the `uid` field
+   * of the options struct. This does not work on windows; setting this flag
+   * will cause uv_spawn() to fail.
+   */
+  UV_PROCESS_SETUID = (1 << 0),
+  /*
+   * Set the child process' group id. The user id is supplied in the `gid`
+   * field of the options struct. This does not work on windows; setting this
+   * flag will cause uv_spawn() to fail.
+   */
+  UV_PROCESS_SETGID = (1 << 1),
+  /*
+   * Do not wrap any arguments in quotes, or perform any other escaping, when
+   * converting the argument list into a command line string. This option is
+   * only meaningful on Windows systems. On Unix it is silently ignored.
+   */
+  UV_PROCESS_WINDOWS_VERBATIM_ARGUMENTS = (1 << 2),
+  /*
+   * Spawn the child process in a detached state - this will make it a process
+   * group leader, and will effectively enable the child to keep running after
+   * the parent exits.  Note that the child process will still keep the
+   * parent's event loop alive unless the parent process calls uv_unref() on
+   * the child's process handle.
+   */
+  UV_PROCESS_DETACHED = (1 << 3),
+  /*
+   * Hide the subprocess window that would normally be created. This option is
+   * only meaningful on Windows systems. On Unix it is silently ignored.
+   */
+  UV_PROCESS_WINDOWS_HIDE = (1 << 4),
+  /*
+   * Hide the subprocess console window that would normally be created. This
+   * option is only meaningful on Windows systems. On Unix it is silently
+   * ignored.
+   */
+  UV_PROCESS_WINDOWS_HIDE_CONSOLE = (1 << 5),
+  /*
+   * Hide the subprocess GUI window that would normally be created. This
+   * option is only meaningful on Windows systems. On Unix it is silently
+   * ignored.
+   */
+  UV_PROCESS_WINDOWS_HIDE_GUI = (1 << 6)
+};
+
+/*
+ * uv_process_t is a subclass of uv_handle_t.
+ */
+struct uv_process_s {
+  UV_HANDLE_FIELDS
+  uv_exit_cb exit_cb;
+  int pid;
+  UV_PROCESS_PRIVATE_FIELDS
+};
+
+UV_EXTERN int uv_spawn(uv_loop_t* loop,
+                       uv_process_t* handle,
+                       const uv_process_options_t* options);
+UV_EXTERN int uv_process_kill(uv_process_t*, int signum);
+UV_EXTERN int uv_kill(int pid, int signum);
+UV_EXTERN uv_pid_t uv_process_get_pid(const uv_process_t*);
+
+
+/*
+ * uv_work_t is a subclass of uv_req_t.
+ */
+struct uv_work_s {
+  UV_REQ_FIELDS
+  uv_loop_t* loop;
+  uv_work_cb work_cb;
+  uv_after_work_cb after_work_cb;
+  UV_WORK_PRIVATE_FIELDS
+};
+
+UV_EXTERN int uv_queue_work(uv_loop_t* loop,
+                            uv_work_t* req,
+                            uv_work_cb work_cb,
+                            uv_after_work_cb after_work_cb);
+
+UV_EXTERN int uv_cancel(uv_req_t* req);
+
+
+struct uv_cpu_times_s {
+  uint64_t user; /* milliseconds */
+  uint64_t nice; /* milliseconds */
+  uint64_t sys; /* milliseconds */
+  uint64_t idle; /* milliseconds */
+  uint64_t irq; /* milliseconds */
+};
+
+struct uv_cpu_info_s {
+  char* model;
+  int speed;
+  struct uv_cpu_times_s cpu_times;
+};
+
+struct uv_interface_address_s {
+  char* name;
+  char phys_addr[6];
+  int is_internal;
+  union {
+    struct sockaddr_in address4;
+    struct sockaddr_in6 address6;
+  } address;
+  union {
+    struct sockaddr_in netmask4;
+    struct sockaddr_in6 netmask6;
+  } netmask;
+};
+
+struct uv_passwd_s {
+  char* username;
+  unsigned long uid;
+  unsigned long gid;
+  char* shell;
+  char* homedir;
+};
+
+struct uv_utsname_s {
+  char sysname[256];
+  char release[256];
+  char version[256];
+  char machine[256];
+  /* This struct does not contain the nodename and domainname fields present in
+     the utsname type. domainname is a GNU extension. Both fields are referred
+     to as meaningless in the docs. */
+};
+
+struct uv_statfs_s {
+  uint64_t f_type;
+  uint64_t f_bsize;
+  uint64_t f_blocks;
+  uint64_t f_bfree;
+  uint64_t f_bavail;
+  uint64_t f_files;
+  uint64_t f_ffree;
+  uint64_t f_spare[4];
+};
+
+typedef enum {
+  UV_DIRENT_UNKNOWN,
+  UV_DIRENT_FILE,
+  UV_DIRENT_DIR,
+  UV_DIRENT_LINK,
+  UV_DIRENT_FIFO,
+  UV_DIRENT_SOCKET,
+  UV_DIRENT_CHAR,
+  UV_DIRENT_BLOCK
+} uv_dirent_type_t;
+
+struct uv_dirent_s {
+  const char* name;
+  uv_dirent_type_t type;
+};
+
+UV_EXTERN char** uv_setup_args(int argc, char** argv);
+UV_EXTERN int uv_get_process_title(char* buffer, size_t size);
+UV_EXTERN int uv_set_process_title(const char* title);
+UV_EXTERN int uv_resident_set_memory(size_t* rss);
+UV_EXTERN int uv_uptime(double* uptime);
+UV_EXTERN uv_os_fd_t uv_get_osfhandle(int fd);
+UV_EXTERN int uv_open_osfhandle(uv_os_fd_t os_fd);
+
+typedef struct {
+  long tv_sec;
+  long tv_usec;
+} uv_timeval_t;
+
+typedef struct {
+  int64_t tv_sec;
+  int32_t tv_usec;
+} uv_timeval64_t;
+
+typedef struct {
+   uv_timeval_t ru_utime; /* user CPU time used */
+   uv_timeval_t ru_stime; /* system CPU time used */
+   uint64_t ru_maxrss;    /* maximum resident set size */
+   uint64_t ru_ixrss;     /* integral shared memory size */
+   uint64_t ru_idrss;     /* integral unshared data size */
+   uint64_t ru_isrss;     /* integral unshared stack size */
+   uint64_t ru_minflt;    /* page reclaims (soft page faults) */
+   uint64_t ru_majflt;    /* page faults (hard page faults) */
+   uint64_t ru_nswap;     /* swaps */
+   uint64_t ru_inblock;   /* block input operations */
+   uint64_t ru_oublock;   /* block output operations */
+   uint64_t ru_msgsnd;    /* IPC messages sent */
+   uint64_t ru_msgrcv;    /* IPC messages received */
+   uint64_t ru_nsignals;  /* signals received */
+   uint64_t ru_nvcsw;     /* voluntary context switches */
+   uint64_t ru_nivcsw;    /* involuntary context switches */
+} uv_rusage_t;
+
+UV_EXTERN int uv_getrusage(uv_rusage_t* rusage);
+
+UV_EXTERN int uv_os_homedir(char* buffer, size_t* size);
+UV_EXTERN int uv_os_tmpdir(char* buffer, size_t* size);
+UV_EXTERN int uv_os_get_passwd(uv_passwd_t* pwd);
+UV_EXTERN void uv_os_free_passwd(uv_passwd_t* pwd);
+UV_EXTERN uv_pid_t uv_os_getpid(void);
+UV_EXTERN uv_pid_t uv_os_getppid(void);
+
+#if defined(__PASE__)
+/* On IBM i PASE, the highest process priority is -10 */
+# define UV_PRIORITY_LOW 39          /* RUNPTY(99) */
+# define UV_PRIORITY_BELOW_NORMAL 15 /* RUNPTY(50) */
+# define UV_PRIORITY_NORMAL 0        /* RUNPTY(20) */
+# define UV_PRIORITY_ABOVE_NORMAL -4 /* RUNTY(12) */
+# define UV_PRIORITY_HIGH -7         /* RUNPTY(6) */
+# define UV_PRIORITY_HIGHEST -10     /* RUNPTY(1) */
+#else
+# define UV_PRIORITY_LOW 19
+# define UV_PRIORITY_BELOW_NORMAL 10
+# define UV_PRIORITY_NORMAL 0
+# define UV_PRIORITY_ABOVE_NORMAL -7
+# define UV_PRIORITY_HIGH -14
+# define UV_PRIORITY_HIGHEST -20
+#endif
+
+UV_EXTERN int uv_os_getpriority(uv_pid_t pid, int* priority);
+UV_EXTERN int uv_os_setpriority(uv_pid_t pid, int priority);
+
+UV_EXTERN unsigned int uv_available_parallelism(void);
+UV_EXTERN int uv_cpu_info(uv_cpu_info_t** cpu_infos, int* count);
+UV_EXTERN void uv_free_cpu_info(uv_cpu_info_t* cpu_infos, int count);
+
+UV_EXTERN int uv_interface_addresses(uv_interface_address_t** addresses,
+                                     int* count);
+UV_EXTERN void uv_free_interface_addresses(uv_interface_address_t* addresses,
+                                           int count);
+
+struct uv_env_item_s {
+  char* name;
+  char* value;
+};
+
+UV_EXTERN int uv_os_environ(uv_env_item_t** envitems, int* count);
+UV_EXTERN void uv_os_free_environ(uv_env_item_t* envitems, int count);
+UV_EXTERN int uv_os_getenv(const char* name, char* buffer, size_t* size);
+UV_EXTERN int uv_os_setenv(const char* name, const char* value);
+UV_EXTERN int uv_os_unsetenv(const char* name);
+
+#ifdef MAXHOSTNAMELEN
+# define UV_MAXHOSTNAMESIZE (MAXHOSTNAMELEN + 1)
+#else
+  /*
+    Fallback for the maximum hostname size, including the null terminator. The
+    Windows gethostname() documentation states that 256 bytes will always be
+    large enough to hold the null-terminated hostname.
+  */
+# define UV_MAXHOSTNAMESIZE 256
+#endif
+
+UV_EXTERN int uv_os_gethostname(char* buffer, size_t* size);
+
+UV_EXTERN int uv_os_uname(uv_utsname_t* buffer);
+
+UV_EXTERN uint64_t uv_metrics_idle_time(uv_loop_t* loop);
+
+typedef enum {
+  UV_FS_UNKNOWN = -1,
+  UV_FS_CUSTOM,
+  UV_FS_OPEN,
+  UV_FS_CLOSE,
+  UV_FS_READ,
+  UV_FS_WRITE,
+  UV_FS_SENDFILE,
+  UV_FS_STAT,
+  UV_FS_LSTAT,
+  UV_FS_FSTAT,
+  UV_FS_FTRUNCATE,
+  UV_FS_UTIME,
+  UV_FS_FUTIME,
+  UV_FS_ACCESS,
+  UV_FS_CHMOD,
+  UV_FS_FCHMOD,
+  UV_FS_FSYNC,
+  UV_FS_FDATASYNC,
+  UV_FS_UNLINK,
+  UV_FS_RMDIR,
+  UV_FS_MKDIR,
+  UV_FS_MKDTEMP,
+  UV_FS_RENAME,
+  UV_FS_SCANDIR,
+  UV_FS_LINK,
+  UV_FS_SYMLINK,
+  UV_FS_READLINK,
+  UV_FS_CHOWN,
+  UV_FS_FCHOWN,
+  UV_FS_REALPATH,
+  UV_FS_COPYFILE,
+  UV_FS_LCHOWN,
+  UV_FS_OPENDIR,
+  UV_FS_READDIR,
+  UV_FS_CLOSEDIR,
+  UV_FS_STATFS,
+  UV_FS_MKSTEMP,
+  UV_FS_LUTIME
+} uv_fs_type;
+
+struct uv_dir_s {
+  uv_dirent_t* dirents;
+  size_t nentries;
+  void* reserved[4];
+  UV_DIR_PRIVATE_FIELDS
+};
+
+/* uv_fs_t is a subclass of uv_req_t. */
+struct uv_fs_s {
+  UV_REQ_FIELDS
+  uv_fs_type fs_type;
+  uv_loop_t* loop;
+  uv_fs_cb cb;
+  ssize_t result;
+  void* ptr;
+  const char* path;
+  uv_stat_t statbuf;  /* Stores the result of uv_fs_stat() and uv_fs_fstat(). */
+  UV_FS_PRIVATE_FIELDS
+};
+
+UV_EXTERN uv_fs_type uv_fs_get_type(const uv_fs_t*);
+UV_EXTERN ssize_t uv_fs_get_result(const uv_fs_t*);
+UV_EXTERN int uv_fs_get_system_error(const uv_fs_t*);
+UV_EXTERN void* uv_fs_get_ptr(const uv_fs_t*);
+UV_EXTERN const char* uv_fs_get_path(const uv_fs_t*);
+UV_EXTERN uv_stat_t* uv_fs_get_statbuf(uv_fs_t*);
+
+UV_EXTERN void uv_fs_req_cleanup(uv_fs_t* req);
+UV_EXTERN int uv_fs_close(uv_loop_t* loop,
+                          uv_fs_t* req,
+                          uv_file file,
+                          uv_fs_cb cb);
+UV_EXTERN int uv_fs_open(uv_loop_t* loop,
+                         uv_fs_t* req,
+                         const char* path,
+                         int flags,
+                         int mode,
+                         uv_fs_cb cb);
+UV_EXTERN int uv_fs_read(uv_loop_t* loop,
+                         uv_fs_t* req,
+                         uv_file file,
+                         const uv_buf_t bufs[],
+                         unsigned int nbufs,
+                         int64_t offset,
+                         uv_fs_cb cb);
+UV_EXTERN int uv_fs_unlink(uv_loop_t* loop,
+                           uv_fs_t* req,
+                           const char* path,
+                           uv_fs_cb cb);
+UV_EXTERN int uv_fs_write(uv_loop_t* loop,
+                          uv_fs_t* req,
+                          uv_file file,
+                          const uv_buf_t bufs[],
+                          unsigned int nbufs,
+                          int64_t offset,
+                          uv_fs_cb cb);
+/*
+ * This flag can be used with uv_fs_copyfile() to return an error if the
+ * destination already exists.
+ */
+#define UV_FS_COPYFILE_EXCL   0x0001
+
+/*
+ * This flag can be used with uv_fs_copyfile() to attempt to create a reflink.
+ * If copy-on-write is not supported, a fallback copy mechanism is used.
+ */
+#define UV_FS_COPYFILE_FICLONE 0x0002
+
+/*
+ * This flag can be used with uv_fs_copyfile() to attempt to create a reflink.
+ * If copy-on-write is not supported, an error is returned.
+ */
+#define UV_FS_COPYFILE_FICLONE_FORCE 0x0004
+
+UV_EXTERN int uv_fs_copyfile(uv_loop_t* loop,
+                             uv_fs_t* req,
+                             const char* path,
+                             const char* new_path,
+                             int flags,
+                             uv_fs_cb cb);
+UV_EXTERN int uv_fs_mkdir(uv_loop_t* loop,
+                          uv_fs_t* req,
+                          const char* path,
+                          int mode,
+                          uv_fs_cb cb);
+UV_EXTERN int uv_fs_mkdtemp(uv_loop_t* loop,
+                            uv_fs_t* req,
+                            const char* tpl,
+                            uv_fs_cb cb);
+UV_EXTERN int uv_fs_mkstemp(uv_loop_t* loop,
+                            uv_fs_t* req,
+                            const char* tpl,
+                            uv_fs_cb cb);
+UV_EXTERN int uv_fs_rmdir(uv_loop_t* loop,
+                          uv_fs_t* req,
+                          const char* path,
+                          uv_fs_cb cb);
+UV_EXTERN int uv_fs_scandir(uv_loop_t* loop,
+                            uv_fs_t* req,
+                            const char* path,
+                            int flags,
+                            uv_fs_cb cb);
+UV_EXTERN int uv_fs_scandir_next(uv_fs_t* req,
+                                 uv_dirent_t* ent);
+UV_EXTERN int uv_fs_opendir(uv_loop_t* loop,
+                            uv_fs_t* req,
+                            const char* path,
+                            uv_fs_cb cb);
+UV_EXTERN int uv_fs_readdir(uv_loop_t* loop,
+                            uv_fs_t* req,
+                            uv_dir_t* dir,
+                            uv_fs_cb cb);
+UV_EXTERN int uv_fs_closedir(uv_loop_t* loop,
+                             uv_fs_t* req,
+                             uv_dir_t* dir,
+                             uv_fs_cb cb);
+UV_EXTERN int uv_fs_stat(uv_loop_t* loop,
+                         uv_fs_t* req,
+                         const char* path,
+                         uv_fs_cb cb);
+UV_EXTERN int uv_fs_fstat(uv_loop_t* loop,
+                          uv_fs_t* req,
+                          uv_file file,
+                          uv_fs_cb cb);
+UV_EXTERN int uv_fs_rename(uv_loop_t* loop,
+                           uv_fs_t* req,
+                           const char* path,
+                           const char* new_path,
+                           uv_fs_cb cb);
+UV_EXTERN int uv_fs_fsync(uv_loop_t* loop,
+                          uv_fs_t* req,
+                          uv_file file,
+                          uv_fs_cb cb);
+UV_EXTERN int uv_fs_fdatasync(uv_loop_t* loop,
+                              uv_fs_t* req,
+                              uv_file file,
+                              uv_fs_cb cb);
+UV_EXTERN int uv_fs_ftruncate(uv_loop_t* loop,
+                              uv_fs_t* req,
+                              uv_file file,
+                              int64_t offset,
+                              uv_fs_cb cb);
+UV_EXTERN int uv_fs_sendfile(uv_loop_t* loop,
+                             uv_fs_t* req,
+                             uv_file out_fd,
+                             uv_file in_fd,
+                             int64_t in_offset,
+                             size_t length,
+                             uv_fs_cb cb);
+UV_EXTERN int uv_fs_access(uv_loop_t* loop,
+                           uv_fs_t* req,
+                           const char* path,
+                           int mode,
+                           uv_fs_cb cb);
+UV_EXTERN int uv_fs_chmod(uv_loop_t* loop,
+                          uv_fs_t* req,
+                          const char* path,
+                          int mode,
+                          uv_fs_cb cb);
+UV_EXTERN int uv_fs_utime(uv_loop_t* loop,
+                          uv_fs_t* req,
+                          const char* path,
+                          double atime,
+                          double mtime,
+                          uv_fs_cb cb);
+UV_EXTERN int uv_fs_futime(uv_loop_t* loop,
+                           uv_fs_t* req,
+                           uv_file file,
+                           double atime,
+                           double mtime,
+                           uv_fs_cb cb);
+UV_EXTERN int uv_fs_lutime(uv_loop_t* loop,
+                           uv_fs_t* req,
+                           const char* path,
+                           double atime,
+                           double mtime,
+                           uv_fs_cb cb);
+UV_EXTERN int uv_fs_lstat(uv_loop_t* loop,
+                          uv_fs_t* req,
+                          const char* path,
+                          uv_fs_cb cb);
+UV_EXTERN int uv_fs_link(uv_loop_t* loop,
+                         uv_fs_t* req,
+                         const char* path,
+                         const char* new_path,
+                         uv_fs_cb cb);
+
+/*
+ * This flag can be used with uv_fs_symlink() on Windows to specify whether
+ * path argument points to a directory.
+ */
+#define UV_FS_SYMLINK_DIR          0x0001
+
+/*
+ * This flag can be used with uv_fs_symlink() on Windows to specify whether
+ * the symlink is to be created using junction points.
+ */
+#define UV_FS_SYMLINK_JUNCTION     0x0002
+
+UV_EXTERN int uv_fs_symlink(uv_loop_t* loop,
+                            uv_fs_t* req,
+                            const char* path,
+                            const char* new_path,
+                            int flags,
+                            uv_fs_cb cb);
+UV_EXTERN int uv_fs_readlink(uv_loop_t* loop,
+                             uv_fs_t* req,
+                             const char* path,
+                             uv_fs_cb cb);
+UV_EXTERN int uv_fs_realpath(uv_loop_t* loop,
+                             uv_fs_t* req,
+                             const char* path,
+                             uv_fs_cb cb);
+UV_EXTERN int uv_fs_fchmod(uv_loop_t* loop,
+                           uv_fs_t* req,
+                           uv_file file,
+                           int mode,
+                           uv_fs_cb cb);
+UV_EXTERN int uv_fs_chown(uv_loop_t* loop,
+                          uv_fs_t* req,
+                          const char* path,
+                          uv_uid_t uid,
+                          uv_gid_t gid,
+                          uv_fs_cb cb);
+UV_EXTERN int uv_fs_fchown(uv_loop_t* loop,
+                           uv_fs_t* req,
+                           uv_file file,
+                           uv_uid_t uid,
+                           uv_gid_t gid,
+                           uv_fs_cb cb);
+UV_EXTERN int uv_fs_lchown(uv_loop_t* loop,
+                           uv_fs_t* req,
+                           const char* path,
+                           uv_uid_t uid,
+                           uv_gid_t gid,
+                           uv_fs_cb cb);
+UV_EXTERN int uv_fs_statfs(uv_loop_t* loop,
+                           uv_fs_t* req,
+                           const char* path,
+                           uv_fs_cb cb);
+
+
+enum uv_fs_event {
+  UV_RENAME = 1,
+  UV_CHANGE = 2
+};
+
+
+struct uv_fs_event_s {
+  UV_HANDLE_FIELDS
+  /* private */
+  char* path;
+  UV_FS_EVENT_PRIVATE_FIELDS
+};
+
+
+/*
+ * uv_fs_stat() based polling file watcher.
+ */
+struct uv_fs_poll_s {
+  UV_HANDLE_FIELDS
+  /* Private, don't touch. */
+  void* poll_ctx;
+};
+
+UV_EXTERN int uv_fs_poll_init(uv_loop_t* loop, uv_fs_poll_t* handle);
+UV_EXTERN int uv_fs_poll_start(uv_fs_poll_t* handle,
+                               uv_fs_poll_cb poll_cb,
+                               const char* path,
+                               unsigned int interval);
+UV_EXTERN int uv_fs_poll_stop(uv_fs_poll_t* handle);
+UV_EXTERN int uv_fs_poll_getpath(uv_fs_poll_t* handle,
+                                 char* buffer,
+                                 size_t* size);
+
+
+struct uv_signal_s {
+  UV_HANDLE_FIELDS
+  uv_signal_cb signal_cb;
+  int signum;
+  UV_SIGNAL_PRIVATE_FIELDS
+};
+
+UV_EXTERN int uv_signal_init(uv_loop_t* loop, uv_signal_t* handle);
+UV_EXTERN int uv_signal_start(uv_signal_t* handle,
+                              uv_signal_cb signal_cb,
+                              int signum);
+UV_EXTERN int uv_signal_start_oneshot(uv_signal_t* handle,
+                                      uv_signal_cb signal_cb,
+                                      int signum);
+UV_EXTERN int uv_signal_stop(uv_signal_t* handle);
+
+UV_EXTERN void uv_loadavg(double avg[3]);
+
+
+/*
+ * Flags to be passed to uv_fs_event_start().
+ */
+enum uv_fs_event_flags {
+  /*
+   * By default, if the fs event watcher is given a directory name, we will
+   * watch for all events in that directory. This flags overrides this behavior
+   * and makes fs_event report only changes to the directory entry itself. This
+   * flag does not affect individual files watched.
+   * This flag is currently not implemented yet on any backend.
+   */
+  UV_FS_EVENT_WATCH_ENTRY = 1,
+
+  /*
+   * By default uv_fs_event will try to use a kernel interface such as inotify
+   * or kqueue to detect events. This may not work on remote filesystems such
+   * as NFS mounts. This flag makes fs_event fall back to calling stat() on a
+   * regular interval.
+   * This flag is currently not implemented yet on any backend.
+   */
+  UV_FS_EVENT_STAT = 2,
+
+  /*
+   * By default, event watcher, when watching directory, is not registering
+   * (is ignoring) changes in it's subdirectories.
+   * This flag will override this behaviour on platforms that support it.
+   */
+  UV_FS_EVENT_RECURSIVE = 4
+};
+
+
+UV_EXTERN int uv_fs_event_init(uv_loop_t* loop, uv_fs_event_t* handle);
+UV_EXTERN int uv_fs_event_start(uv_fs_event_t* handle,
+                                uv_fs_event_cb cb,
+                                const char* path,
+                                unsigned int flags);
+UV_EXTERN int uv_fs_event_stop(uv_fs_event_t* handle);
+UV_EXTERN int uv_fs_event_getpath(uv_fs_event_t* handle,
+                                  char* buffer,
+                                  size_t* size);
+
+UV_EXTERN int uv_ip4_addr(const char* ip, int port, struct sockaddr_in* addr);
+UV_EXTERN int uv_ip6_addr(const char* ip, int port, struct sockaddr_in6* addr);
+
+UV_EXTERN int uv_ip4_name(const struct sockaddr_in* src, char* dst, size_t size);
+UV_EXTERN int uv_ip6_name(const struct sockaddr_in6* src, char* dst, size_t size);
+UV_EXTERN int uv_ip_name(const struct sockaddr* src, char* dst, size_t size);
+
+UV_EXTERN int uv_inet_ntop(int af, const void* src, char* dst, size_t size);
+UV_EXTERN int uv_inet_pton(int af, const char* src, void* dst);
+
+
+struct uv_random_s {
+  UV_REQ_FIELDS
+  /* read-only */
+  uv_loop_t* loop;
+  /* private */
+  int status;
+  void* buf;
+  size_t buflen;
+  uv_random_cb cb;
+  struct uv__work work_req;
+};
+
+UV_EXTERN int uv_random(uv_loop_t* loop,
+                        uv_random_t* req,
+                        void *buf,
+                        size_t buflen,
+                        unsigned flags,  /* For future extension; must be 0. */
+                        uv_random_cb cb);
+
+#if defined(IF_NAMESIZE)
+# define UV_IF_NAMESIZE (IF_NAMESIZE + 1)
+#elif defined(IFNAMSIZ)
+# define UV_IF_NAMESIZE (IFNAMSIZ + 1)
+#else
+# define UV_IF_NAMESIZE (16 + 1)
+#endif
+
+UV_EXTERN int uv_if_indextoname(unsigned int ifindex,
+                                char* buffer,
+                                size_t* size);
+UV_EXTERN int uv_if_indextoiid(unsigned int ifindex,
+                               char* buffer,
+                               size_t* size);
+
+UV_EXTERN int uv_exepath(char* buffer, size_t* size);
+
+UV_EXTERN int uv_cwd(char* buffer, size_t* size);
+
+UV_EXTERN int uv_chdir(const char* dir);
+
+UV_EXTERN uint64_t uv_get_free_memory(void);
+UV_EXTERN uint64_t uv_get_total_memory(void);
+UV_EXTERN uint64_t uv_get_constrained_memory(void);
+
+UV_EXTERN uint64_t uv_hrtime(void);
+UV_EXTERN void uv_sleep(unsigned int msec);
+
+UV_EXTERN void uv_disable_stdio_inheritance(void);
+
+UV_EXTERN int uv_dlopen(const char* filename, uv_lib_t* lib);
+UV_EXTERN void uv_dlclose(uv_lib_t* lib);
+UV_EXTERN int uv_dlsym(uv_lib_t* lib, const char* name, void** ptr);
+UV_EXTERN const char* uv_dlerror(const uv_lib_t* lib);
+
+UV_EXTERN int uv_mutex_init(uv_mutex_t* handle);
+UV_EXTERN int uv_mutex_init_recursive(uv_mutex_t* handle);
+UV_EXTERN void uv_mutex_destroy(uv_mutex_t* handle);
+UV_EXTERN void uv_mutex_lock(uv_mutex_t* handle);
+UV_EXTERN int uv_mutex_trylock(uv_mutex_t* handle);
+UV_EXTERN void uv_mutex_unlock(uv_mutex_t* handle);
+
+UV_EXTERN int uv_rwlock_init(uv_rwlock_t* rwlock);
+UV_EXTERN void uv_rwlock_destroy(uv_rwlock_t* rwlock);
+UV_EXTERN void uv_rwlock_rdlock(uv_rwlock_t* rwlock);
+UV_EXTERN int uv_rwlock_tryrdlock(uv_rwlock_t* rwlock);
+UV_EXTERN void uv_rwlock_rdunlock(uv_rwlock_t* rwlock);
+UV_EXTERN void uv_rwlock_wrlock(uv_rwlock_t* rwlock);
+UV_EXTERN int uv_rwlock_trywrlock(uv_rwlock_t* rwlock);
+UV_EXTERN void uv_rwlock_wrunlock(uv_rwlock_t* rwlock);
+
+UV_EXTERN int uv_sem_init(uv_sem_t* sem, unsigned int value);
+UV_EXTERN void uv_sem_destroy(uv_sem_t* sem);
+UV_EXTERN void uv_sem_post(uv_sem_t* sem);
+UV_EXTERN void uv_sem_wait(uv_sem_t* sem);
+UV_EXTERN int uv_sem_trywait(uv_sem_t* sem);
+
+UV_EXTERN int uv_cond_init(uv_cond_t* cond);
+UV_EXTERN void uv_cond_destroy(uv_cond_t* cond);
+UV_EXTERN void uv_cond_signal(uv_cond_t* cond);
+UV_EXTERN void uv_cond_broadcast(uv_cond_t* cond);
+
+UV_EXTERN int uv_barrier_init(uv_barrier_t* barrier, unsigned int count);
+UV_EXTERN void uv_barrier_destroy(uv_barrier_t* barrier);
+UV_EXTERN int uv_barrier_wait(uv_barrier_t* barrier);
+
+UV_EXTERN void uv_cond_wait(uv_cond_t* cond, uv_mutex_t* mutex);
+UV_EXTERN int uv_cond_timedwait(uv_cond_t* cond,
+                                uv_mutex_t* mutex,
+                                uint64_t timeout);
+
+UV_EXTERN void uv_once(uv_once_t* guard, void (*callback)(void));
+
+UV_EXTERN int uv_key_create(uv_key_t* key);
+UV_EXTERN void uv_key_delete(uv_key_t* key);
+UV_EXTERN void* uv_key_get(uv_key_t* key);
+UV_EXTERN void uv_key_set(uv_key_t* key, void* value);
+
+UV_EXTERN int uv_gettimeofday(uv_timeval64_t* tv);
+
+typedef void (*uv_thread_cb)(void* arg);
+
+UV_EXTERN int uv_thread_create(uv_thread_t* tid, uv_thread_cb entry, void* arg);
+
+typedef enum {
+  UV_THREAD_NO_FLAGS = 0x00,
+  UV_THREAD_HAS_STACK_SIZE = 0x01
+} uv_thread_create_flags;
+
+struct uv_thread_options_s {
+  unsigned int flags;
+  size_t stack_size;
+  /* More fields may be added at any time. */
+};
+
+typedef struct uv_thread_options_s uv_thread_options_t;
+
+UV_EXTERN int uv_thread_create_ex(uv_thread_t* tid,
+                                  const uv_thread_options_t* params,
+                                  uv_thread_cb entry,
+                                  void* arg);
+UV_EXTERN uv_thread_t uv_thread_self(void);
+UV_EXTERN int uv_thread_join(uv_thread_t *tid);
+UV_EXTERN int uv_thread_equal(const uv_thread_t* t1, const uv_thread_t* t2);
+
+/* The presence of these unions force similar struct layout. */
+#define XX(_, name) uv_ ## name ## _t name;
+union uv_any_handle {
+  UV_HANDLE_TYPE_MAP(XX)
+};
+
+union uv_any_req {
+  UV_REQ_TYPE_MAP(XX)
+};
+#undef XX
+
+
+struct uv_loop_s {
+  /* User data - use this for whatever. */
+  void* data;
+  /* Loop reference counting. */
+  unsigned int active_handles;
+  void* handle_queue[2];
+  union {
+    void* unused;
+    unsigned int count;
+  } active_reqs;
+  /* Internal storage for future extensions. */
+  void* internal_fields;
+  /* Internal flag to signal loop stop. */
+  unsigned int stop_flag;
+  UV_LOOP_PRIVATE_FIELDS
+};
+
+UV_EXTERN void* uv_loop_get_data(const uv_loop_t*);
+UV_EXTERN void uv_loop_set_data(uv_loop_t*, void* data);
+
+/* Don't export the private CPP symbols. */
+#undef UV_HANDLE_TYPE_PRIVATE
+#undef UV_REQ_TYPE_PRIVATE
+#undef UV_REQ_PRIVATE_FIELDS
+#undef UV_STREAM_PRIVATE_FIELDS
+#undef UV_TCP_PRIVATE_FIELDS
+#undef UV_PREPARE_PRIVATE_FIELDS
+#undef UV_CHECK_PRIVATE_FIELDS
+#undef UV_IDLE_PRIVATE_FIELDS
+#undef UV_ASYNC_PRIVATE_FIELDS
+#undef UV_TIMER_PRIVATE_FIELDS
+#undef UV_GETADDRINFO_PRIVATE_FIELDS
+#undef UV_GETNAMEINFO_PRIVATE_FIELDS
+#undef UV_FS_REQ_PRIVATE_FIELDS
+#undef UV_WORK_PRIVATE_FIELDS
+#undef UV_FS_EVENT_PRIVATE_FIELDS
+#undef UV_SIGNAL_PRIVATE_FIELDS
+#undef UV_LOOP_PRIVATE_FIELDS
+#undef UV_LOOP_PRIVATE_PLATFORM_FIELDS
+#undef UV__ERR
+
+#endif /* UV_H */
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/include/uv/bsd.h b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/include/uv/bsd.h
similarity index 100%
rename from third_party/allwpilib/wpiutil/src/main/native/libuv/include/uv/bsd.h
rename to third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/include/uv/bsd.h
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/include/uv/darwin.h b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/include/uv/darwin.h
similarity index 100%
rename from third_party/allwpilib/wpiutil/src/main/native/libuv/include/uv/darwin.h
rename to third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/include/uv/darwin.h
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/include/uv/errno.h b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/include/uv/errno.h
new file mode 100644
index 0000000..71906b3
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/include/uv/errno.h
@@ -0,0 +1,460 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#ifndef UV_ERRNO_H_
+#define UV_ERRNO_H_
+
+#include <errno.h>
+#if EDOM > 0
+# define UV__ERR(x) (-(x))
+#else
+# define UV__ERR(x) (x)
+#endif
+
+#define UV__EOF     (-4095)
+#define UV__UNKNOWN (-4094)
+
+#define UV__EAI_ADDRFAMILY  (-3000)
+#define UV__EAI_AGAIN       (-3001)
+#define UV__EAI_BADFLAGS    (-3002)
+#define UV__EAI_CANCELED    (-3003)
+#define UV__EAI_FAIL        (-3004)
+#define UV__EAI_FAMILY      (-3005)
+#define UV__EAI_MEMORY      (-3006)
+#define UV__EAI_NODATA      (-3007)
+#define UV__EAI_NONAME      (-3008)
+#define UV__EAI_OVERFLOW    (-3009)
+#define UV__EAI_SERVICE     (-3010)
+#define UV__EAI_SOCKTYPE    (-3011)
+#define UV__EAI_BADHINTS    (-3013)
+#define UV__EAI_PROTOCOL    (-3014)
+
+/* Only map to the system errno on non-Windows platforms. It's apparently
+ * a fairly common practice for Windows programmers to redefine errno codes.
+ */
+#if defined(E2BIG) && !defined(_WIN32)
+# define UV__E2BIG UV__ERR(E2BIG)
+#else
+# define UV__E2BIG (-4093)
+#endif
+
+#if defined(EACCES) && !defined(_WIN32)
+# define UV__EACCES UV__ERR(EACCES)
+#else
+# define UV__EACCES (-4092)
+#endif
+
+#if defined(EADDRINUSE) && !defined(_WIN32)
+# define UV__EADDRINUSE UV__ERR(EADDRINUSE)
+#else
+# define UV__EADDRINUSE (-4091)
+#endif
+
+#if defined(EADDRNOTAVAIL) && !defined(_WIN32)
+# define UV__EADDRNOTAVAIL UV__ERR(EADDRNOTAVAIL)
+#else
+# define UV__EADDRNOTAVAIL (-4090)
+#endif
+
+#if defined(EAFNOSUPPORT) && !defined(_WIN32)
+# define UV__EAFNOSUPPORT UV__ERR(EAFNOSUPPORT)
+#else
+# define UV__EAFNOSUPPORT (-4089)
+#endif
+
+#if defined(EAGAIN) && !defined(_WIN32)
+# define UV__EAGAIN UV__ERR(EAGAIN)
+#else
+# define UV__EAGAIN (-4088)
+#endif
+
+#if defined(EALREADY) && !defined(_WIN32)
+# define UV__EALREADY UV__ERR(EALREADY)
+#else
+# define UV__EALREADY (-4084)
+#endif
+
+#if defined(EBADF) && !defined(_WIN32)
+# define UV__EBADF UV__ERR(EBADF)
+#else
+# define UV__EBADF (-4083)
+#endif
+
+#if defined(EBUSY) && !defined(_WIN32)
+# define UV__EBUSY UV__ERR(EBUSY)
+#else
+# define UV__EBUSY (-4082)
+#endif
+
+#if defined(ECANCELED) && !defined(_WIN32)
+# define UV__ECANCELED UV__ERR(ECANCELED)
+#else
+# define UV__ECANCELED (-4081)
+#endif
+
+#if defined(ECHARSET) && !defined(_WIN32)
+# define UV__ECHARSET UV__ERR(ECHARSET)
+#else
+# define UV__ECHARSET (-4080)
+#endif
+
+#if defined(ECONNABORTED) && !defined(_WIN32)
+# define UV__ECONNABORTED UV__ERR(ECONNABORTED)
+#else
+# define UV__ECONNABORTED (-4079)
+#endif
+
+#if defined(ECONNREFUSED) && !defined(_WIN32)
+# define UV__ECONNREFUSED UV__ERR(ECONNREFUSED)
+#else
+# define UV__ECONNREFUSED (-4078)
+#endif
+
+#if defined(ECONNRESET) && !defined(_WIN32)
+# define UV__ECONNRESET UV__ERR(ECONNRESET)
+#else
+# define UV__ECONNRESET (-4077)
+#endif
+
+#if defined(EDESTADDRREQ) && !defined(_WIN32)
+# define UV__EDESTADDRREQ UV__ERR(EDESTADDRREQ)
+#else
+# define UV__EDESTADDRREQ (-4076)
+#endif
+
+#if defined(EEXIST) && !defined(_WIN32)
+# define UV__EEXIST UV__ERR(EEXIST)
+#else
+# define UV__EEXIST (-4075)
+#endif
+
+#if defined(EFAULT) && !defined(_WIN32)
+# define UV__EFAULT UV__ERR(EFAULT)
+#else
+# define UV__EFAULT (-4074)
+#endif
+
+#if defined(EHOSTUNREACH) && !defined(_WIN32)
+# define UV__EHOSTUNREACH UV__ERR(EHOSTUNREACH)
+#else
+# define UV__EHOSTUNREACH (-4073)
+#endif
+
+#if defined(EINTR) && !defined(_WIN32)
+# define UV__EINTR UV__ERR(EINTR)
+#else
+# define UV__EINTR (-4072)
+#endif
+
+#if defined(EINVAL) && !defined(_WIN32)
+# define UV__EINVAL UV__ERR(EINVAL)
+#else
+# define UV__EINVAL (-4071)
+#endif
+
+#if defined(EIO) && !defined(_WIN32)
+# define UV__EIO UV__ERR(EIO)
+#else
+# define UV__EIO (-4070)
+#endif
+
+#if defined(EISCONN) && !defined(_WIN32)
+# define UV__EISCONN UV__ERR(EISCONN)
+#else
+# define UV__EISCONN (-4069)
+#endif
+
+#if defined(EISDIR) && !defined(_WIN32)
+# define UV__EISDIR UV__ERR(EISDIR)
+#else
+# define UV__EISDIR (-4068)
+#endif
+
+#if defined(ELOOP) && !defined(_WIN32)
+# define UV__ELOOP UV__ERR(ELOOP)
+#else
+# define UV__ELOOP (-4067)
+#endif
+
+#if defined(EMFILE) && !defined(_WIN32)
+# define UV__EMFILE UV__ERR(EMFILE)
+#else
+# define UV__EMFILE (-4066)
+#endif
+
+#if defined(EMSGSIZE) && !defined(_WIN32)
+# define UV__EMSGSIZE UV__ERR(EMSGSIZE)
+#else
+# define UV__EMSGSIZE (-4065)
+#endif
+
+#if defined(ENAMETOOLONG) && !defined(_WIN32)
+# define UV__ENAMETOOLONG UV__ERR(ENAMETOOLONG)
+#else
+# define UV__ENAMETOOLONG (-4064)
+#endif
+
+#if defined(ENETDOWN) && !defined(_WIN32)
+# define UV__ENETDOWN UV__ERR(ENETDOWN)
+#else
+# define UV__ENETDOWN (-4063)
+#endif
+
+#if defined(ENETUNREACH) && !defined(_WIN32)
+# define UV__ENETUNREACH UV__ERR(ENETUNREACH)
+#else
+# define UV__ENETUNREACH (-4062)
+#endif
+
+#if defined(ENFILE) && !defined(_WIN32)
+# define UV__ENFILE UV__ERR(ENFILE)
+#else
+# define UV__ENFILE (-4061)
+#endif
+
+#if defined(ENOBUFS) && !defined(_WIN32)
+# define UV__ENOBUFS UV__ERR(ENOBUFS)
+#else
+# define UV__ENOBUFS (-4060)
+#endif
+
+#if defined(ENODEV) && !defined(_WIN32)
+# define UV__ENODEV UV__ERR(ENODEV)
+#else
+# define UV__ENODEV (-4059)
+#endif
+
+#if defined(ENOENT) && !defined(_WIN32)
+# define UV__ENOENT UV__ERR(ENOENT)
+#else
+# define UV__ENOENT (-4058)
+#endif
+
+#if defined(ENOMEM) && !defined(_WIN32)
+# define UV__ENOMEM UV__ERR(ENOMEM)
+#else
+# define UV__ENOMEM (-4057)
+#endif
+
+#if defined(ENONET) && !defined(_WIN32)
+# define UV__ENONET UV__ERR(ENONET)
+#else
+# define UV__ENONET (-4056)
+#endif
+
+#if defined(ENOSPC) && !defined(_WIN32)
+# define UV__ENOSPC UV__ERR(ENOSPC)
+#else
+# define UV__ENOSPC (-4055)
+#endif
+
+#if defined(ENOSYS) && !defined(_WIN32)
+# define UV__ENOSYS UV__ERR(ENOSYS)
+#else
+# define UV__ENOSYS (-4054)
+#endif
+
+#if defined(ENOTCONN) && !defined(_WIN32)
+# define UV__ENOTCONN UV__ERR(ENOTCONN)
+#else
+# define UV__ENOTCONN (-4053)
+#endif
+
+#if defined(ENOTDIR) && !defined(_WIN32)
+# define UV__ENOTDIR UV__ERR(ENOTDIR)
+#else
+# define UV__ENOTDIR (-4052)
+#endif
+
+#if defined(ENOTEMPTY) && !defined(_WIN32)
+# define UV__ENOTEMPTY UV__ERR(ENOTEMPTY)
+#else
+# define UV__ENOTEMPTY (-4051)
+#endif
+
+#if defined(ENOTSOCK) && !defined(_WIN32)
+# define UV__ENOTSOCK UV__ERR(ENOTSOCK)
+#else
+# define UV__ENOTSOCK (-4050)
+#endif
+
+#if defined(ENOTSUP) && !defined(_WIN32)
+# define UV__ENOTSUP UV__ERR(ENOTSUP)
+#else
+# define UV__ENOTSUP (-4049)
+#endif
+
+#if defined(EPERM) && !defined(_WIN32)
+# define UV__EPERM UV__ERR(EPERM)
+#else
+# define UV__EPERM (-4048)
+#endif
+
+#if defined(EPIPE) && !defined(_WIN32)
+# define UV__EPIPE UV__ERR(EPIPE)
+#else
+# define UV__EPIPE (-4047)
+#endif
+
+#if defined(EPROTO) && !defined(_WIN32)
+# define UV__EPROTO UV__ERR(EPROTO)
+#else
+# define UV__EPROTO (-4046)
+#endif
+
+#if defined(EPROTONOSUPPORT) && !defined(_WIN32)
+# define UV__EPROTONOSUPPORT UV__ERR(EPROTONOSUPPORT)
+#else
+# define UV__EPROTONOSUPPORT (-4045)
+#endif
+
+#if defined(EPROTOTYPE) && !defined(_WIN32)
+# define UV__EPROTOTYPE UV__ERR(EPROTOTYPE)
+#else
+# define UV__EPROTOTYPE (-4044)
+#endif
+
+#if defined(EROFS) && !defined(_WIN32)
+# define UV__EROFS UV__ERR(EROFS)
+#else
+# define UV__EROFS (-4043)
+#endif
+
+#if defined(ESHUTDOWN) && !defined(_WIN32)
+# define UV__ESHUTDOWN UV__ERR(ESHUTDOWN)
+#else
+# define UV__ESHUTDOWN (-4042)
+#endif
+
+#if defined(ESPIPE) && !defined(_WIN32)
+# define UV__ESPIPE UV__ERR(ESPIPE)
+#else
+# define UV__ESPIPE (-4041)
+#endif
+
+#if defined(ESRCH) && !defined(_WIN32)
+# define UV__ESRCH UV__ERR(ESRCH)
+#else
+# define UV__ESRCH (-4040)
+#endif
+
+#if defined(ETIMEDOUT) && !defined(_WIN32)
+# define UV__ETIMEDOUT UV__ERR(ETIMEDOUT)
+#else
+# define UV__ETIMEDOUT (-4039)
+#endif
+
+#if defined(ETXTBSY) && !defined(_WIN32)
+# define UV__ETXTBSY UV__ERR(ETXTBSY)
+#else
+# define UV__ETXTBSY (-4038)
+#endif
+
+#if defined(EXDEV) && !defined(_WIN32)
+# define UV__EXDEV UV__ERR(EXDEV)
+#else
+# define UV__EXDEV (-4037)
+#endif
+
+#if defined(EFBIG) && !defined(_WIN32)
+# define UV__EFBIG UV__ERR(EFBIG)
+#else
+# define UV__EFBIG (-4036)
+#endif
+
+#if defined(ENOPROTOOPT) && !defined(_WIN32)
+# define UV__ENOPROTOOPT UV__ERR(ENOPROTOOPT)
+#else
+# define UV__ENOPROTOOPT (-4035)
+#endif
+
+#if defined(ERANGE) && !defined(_WIN32)
+# define UV__ERANGE UV__ERR(ERANGE)
+#else
+# define UV__ERANGE (-4034)
+#endif
+
+#if defined(ENXIO) && !defined(_WIN32)
+# define UV__ENXIO UV__ERR(ENXIO)
+#else
+# define UV__ENXIO (-4033)
+#endif
+
+#if defined(EMLINK) && !defined(_WIN32)
+# define UV__EMLINK UV__ERR(EMLINK)
+#else
+# define UV__EMLINK (-4032)
+#endif
+
+/* EHOSTDOWN is not visible on BSD-like systems when _POSIX_C_SOURCE is
+ * defined. Fortunately, its value is always 64 so it's possible albeit
+ * icky to hard-code it.
+ */
+#if defined(EHOSTDOWN) && !defined(_WIN32)
+# define UV__EHOSTDOWN UV__ERR(EHOSTDOWN)
+#elif defined(__APPLE__) || \
+      defined(__DragonFly__) || \
+      defined(__FreeBSD__) || \
+      defined(__FreeBSD_kernel__) || \
+      defined(__NetBSD__) || \
+      defined(__OpenBSD__)
+# define UV__EHOSTDOWN (-64)
+#else
+# define UV__EHOSTDOWN (-4031)
+#endif
+
+#if defined(EREMOTEIO) && !defined(_WIN32)
+# define UV__EREMOTEIO UV__ERR(EREMOTEIO)
+#else
+# define UV__EREMOTEIO (-4030)
+#endif
+
+#if defined(ENOTTY) && !defined(_WIN32)
+# define UV__ENOTTY UV__ERR(ENOTTY)
+#else
+# define UV__ENOTTY (-4029)
+#endif
+
+#if defined(EFTYPE) && !defined(_WIN32)
+# define UV__EFTYPE UV__ERR(EFTYPE)
+#else
+# define UV__EFTYPE (-4028)
+#endif
+
+#if defined(EILSEQ) && !defined(_WIN32)
+# define UV__EILSEQ UV__ERR(EILSEQ)
+#else
+# define UV__EILSEQ (-4027)
+#endif
+
+#if defined(EOVERFLOW) && !defined(_WIN32)
+# define UV__EOVERFLOW UV__ERR(EOVERFLOW)
+#else
+# define UV__EOVERFLOW (-4026)
+#endif
+
+#if defined(ESOCKTNOSUPPORT) && !defined(_WIN32)
+# define UV__ESOCKTNOSUPPORT UV__ERR(ESOCKTNOSUPPORT)
+#else
+# define UV__ESOCKTNOSUPPORT (-4025)
+#endif
+
+#endif /* UV_ERRNO_H_ */
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/include/uv/linux.h b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/include/uv/linux.h
similarity index 100%
rename from third_party/allwpilib/wpiutil/src/main/native/libuv/include/uv/linux.h
rename to third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/include/uv/linux.h
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/include/uv/posix.h b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/include/uv/posix.h
similarity index 100%
rename from third_party/allwpilib/wpiutil/src/main/native/libuv/include/uv/posix.h
rename to third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/include/uv/posix.h
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/include/uv/threadpool.h b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/include/uv/threadpool.h
similarity index 100%
rename from third_party/allwpilib/wpiutil/src/main/native/libuv/include/uv/threadpool.h
rename to third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/include/uv/threadpool.h
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/include/uv/tree.h b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/include/uv/tree.h
new file mode 100644
index 0000000..2b28835
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/include/uv/tree.h
@@ -0,0 +1,768 @@
+/*-
+ * Copyright 2002 Niels Provos <provos@citi.umich.edu>
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ * 1. Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR
+ * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES
+ * OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
+ * IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
+ * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+ * DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+ * THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
+ * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef  UV_TREE_H_
+#define  UV_TREE_H_
+
+#ifndef UV__UNUSED
+# if __GNUC__
+#  define UV__UNUSED __attribute__((unused))
+# else
+#  define UV__UNUSED
+# endif
+#endif
+
+/*
+ * This file defines data structures for different types of trees:
+ * splay trees and red-black trees.
+ *
+ * A splay tree is a self-organizing data structure.  Every operation
+ * on the tree causes a splay to happen.  The splay moves the requested
+ * node to the root of the tree and partly rebalances it.
+ *
+ * This has the benefit that request locality causes faster lookups as
+ * the requested nodes move to the top of the tree.  On the other hand,
+ * every lookup causes memory writes.
+ *
+ * The Balance Theorem bounds the total access time for m operations
+ * and n inserts on an initially empty tree as O((m + n)lg n).  The
+ * amortized cost for a sequence of m accesses to a splay tree is O(lg n);
+ *
+ * A red-black tree is a binary search tree with the node color as an
+ * extra attribute.  It fulfills a set of conditions:
+ *  - every search path from the root to a leaf consists of the
+ *    same number of black nodes,
+ *  - each red node (except for the root) has a black parent,
+ *  - each leaf node is black.
+ *
+ * Every operation on a red-black tree is bounded as O(lg n).
+ * The maximum height of a red-black tree is 2lg (n+1).
+ */
+
+#define SPLAY_HEAD(name, type)                                                \
+struct name {                                                                 \
+  struct type *sph_root; /* root of the tree */                               \
+}
+
+#define SPLAY_INITIALIZER(root)                                               \
+  { NULL }
+
+#define SPLAY_INIT(root) do {                                                 \
+  (root)->sph_root = NULL;                                                    \
+} while (/*CONSTCOND*/ 0)
+
+#define SPLAY_ENTRY(type)                                                     \
+struct {                                                                      \
+  struct type *spe_left;          /* left element */                          \
+  struct type *spe_right;         /* right element */                         \
+}
+
+#define SPLAY_LEFT(elm, field)    (elm)->field.spe_left
+#define SPLAY_RIGHT(elm, field)   (elm)->field.spe_right
+#define SPLAY_ROOT(head)          (head)->sph_root
+#define SPLAY_EMPTY(head)         (SPLAY_ROOT(head) == NULL)
+
+/* SPLAY_ROTATE_{LEFT,RIGHT} expect that tmp hold SPLAY_{RIGHT,LEFT} */
+#define SPLAY_ROTATE_RIGHT(head, tmp, field) do {                             \
+  SPLAY_LEFT((head)->sph_root, field) = SPLAY_RIGHT(tmp, field);              \
+  SPLAY_RIGHT(tmp, field) = (head)->sph_root;                                 \
+  (head)->sph_root = tmp;                                                     \
+} while (/*CONSTCOND*/ 0)
+
+#define SPLAY_ROTATE_LEFT(head, tmp, field) do {                              \
+  SPLAY_RIGHT((head)->sph_root, field) = SPLAY_LEFT(tmp, field);              \
+  SPLAY_LEFT(tmp, field) = (head)->sph_root;                                  \
+  (head)->sph_root = tmp;                                                     \
+} while (/*CONSTCOND*/ 0)
+
+#define SPLAY_LINKLEFT(head, tmp, field) do {                                 \
+  SPLAY_LEFT(tmp, field) = (head)->sph_root;                                  \
+  tmp = (head)->sph_root;                                                     \
+  (head)->sph_root = SPLAY_LEFT((head)->sph_root, field);                     \
+} while (/*CONSTCOND*/ 0)
+
+#define SPLAY_LINKRIGHT(head, tmp, field) do {                                \
+  SPLAY_RIGHT(tmp, field) = (head)->sph_root;                                 \
+  tmp = (head)->sph_root;                                                     \
+  (head)->sph_root = SPLAY_RIGHT((head)->sph_root, field);                    \
+} while (/*CONSTCOND*/ 0)
+
+#define SPLAY_ASSEMBLE(head, node, left, right, field) do {                   \
+  SPLAY_RIGHT(left, field) = SPLAY_LEFT((head)->sph_root, field);             \
+  SPLAY_LEFT(right, field) = SPLAY_RIGHT((head)->sph_root, field);            \
+  SPLAY_LEFT((head)->sph_root, field) = SPLAY_RIGHT(node, field);             \
+  SPLAY_RIGHT((head)->sph_root, field) = SPLAY_LEFT(node, field);             \
+} while (/*CONSTCOND*/ 0)
+
+/* Generates prototypes and inline functions */
+
+#define SPLAY_PROTOTYPE(name, type, field, cmp)                               \
+void name##_SPLAY(struct name *, struct type *);                              \
+void name##_SPLAY_MINMAX(struct name *, int);                                 \
+struct type *name##_SPLAY_INSERT(struct name *, struct type *);               \
+struct type *name##_SPLAY_REMOVE(struct name *, struct type *);               \
+                                                                              \
+/* Finds the node with the same key as elm */                                 \
+static __inline struct type *                                                 \
+name##_SPLAY_FIND(struct name *head, struct type *elm)                        \
+{                                                                             \
+  if (SPLAY_EMPTY(head))                                                      \
+    return(NULL);                                                             \
+  name##_SPLAY(head, elm);                                                    \
+  if ((cmp)(elm, (head)->sph_root) == 0)                                      \
+    return (head->sph_root);                                                  \
+  return (NULL);                                                              \
+}                                                                             \
+                                                                              \
+static __inline struct type *                                                 \
+name##_SPLAY_NEXT(struct name *head, struct type *elm)                        \
+{                                                                             \
+  name##_SPLAY(head, elm);                                                    \
+  if (SPLAY_RIGHT(elm, field) != NULL) {                                      \
+    elm = SPLAY_RIGHT(elm, field);                                            \
+    while (SPLAY_LEFT(elm, field) != NULL) {                                  \
+      elm = SPLAY_LEFT(elm, field);                                           \
+    }                                                                         \
+  } else                                                                      \
+    elm = NULL;                                                               \
+  return (elm);                                                               \
+}                                                                             \
+                                                                              \
+static __inline struct type *                                                 \
+name##_SPLAY_MIN_MAX(struct name *head, int val)                              \
+{                                                                             \
+  name##_SPLAY_MINMAX(head, val);                                             \
+  return (SPLAY_ROOT(head));                                                  \
+}
+
+/* Main splay operation.
+ * Moves node close to the key of elm to top
+ */
+#define SPLAY_GENERATE(name, type, field, cmp)                                \
+struct type *                                                                 \
+name##_SPLAY_INSERT(struct name *head, struct type *elm)                      \
+{                                                                             \
+    if (SPLAY_EMPTY(head)) {                                                  \
+      SPLAY_LEFT(elm, field) = SPLAY_RIGHT(elm, field) = NULL;                \
+    } else {                                                                  \
+      int __comp;                                                             \
+      name##_SPLAY(head, elm);                                                \
+      __comp = (cmp)(elm, (head)->sph_root);                                  \
+      if(__comp < 0) {                                                        \
+        SPLAY_LEFT(elm, field) = SPLAY_LEFT((head)->sph_root, field);         \
+        SPLAY_RIGHT(elm, field) = (head)->sph_root;                           \
+        SPLAY_LEFT((head)->sph_root, field) = NULL;                           \
+      } else if (__comp > 0) {                                                \
+        SPLAY_RIGHT(elm, field) = SPLAY_RIGHT((head)->sph_root, field);       \
+        SPLAY_LEFT(elm, field) = (head)->sph_root;                            \
+        SPLAY_RIGHT((head)->sph_root, field) = NULL;                          \
+      } else                                                                  \
+        return ((head)->sph_root);                                            \
+    }                                                                         \
+    (head)->sph_root = (elm);                                                 \
+    return (NULL);                                                            \
+}                                                                             \
+                                                                              \
+struct type *                                                                 \
+name##_SPLAY_REMOVE(struct name *head, struct type *elm)                      \
+{                                                                             \
+  struct type *__tmp;                                                         \
+  if (SPLAY_EMPTY(head))                                                      \
+    return (NULL);                                                            \
+  name##_SPLAY(head, elm);                                                    \
+  if ((cmp)(elm, (head)->sph_root) == 0) {                                    \
+    if (SPLAY_LEFT((head)->sph_root, field) == NULL) {                        \
+      (head)->sph_root = SPLAY_RIGHT((head)->sph_root, field);                \
+    } else {                                                                  \
+      __tmp = SPLAY_RIGHT((head)->sph_root, field);                           \
+      (head)->sph_root = SPLAY_LEFT((head)->sph_root, field);                 \
+      name##_SPLAY(head, elm);                                                \
+      SPLAY_RIGHT((head)->sph_root, field) = __tmp;                           \
+    }                                                                         \
+    return (elm);                                                             \
+  }                                                                           \
+  return (NULL);                                                              \
+}                                                                             \
+                                                                              \
+void                                                                          \
+name##_SPLAY(struct name *head, struct type *elm)                             \
+{                                                                             \
+  struct type __node, *__left, *__right, *__tmp;                              \
+  int __comp;                                                                 \
+                                                                              \
+  SPLAY_LEFT(&__node, field) = SPLAY_RIGHT(&__node, field) = NULL;            \
+  __left = __right = &__node;                                                 \
+                                                                              \
+  while ((__comp = (cmp)(elm, (head)->sph_root)) != 0) {                      \
+    if (__comp < 0) {                                                         \
+      __tmp = SPLAY_LEFT((head)->sph_root, field);                            \
+      if (__tmp == NULL)                                                      \
+        break;                                                                \
+      if ((cmp)(elm, __tmp) < 0){                                             \
+        SPLAY_ROTATE_RIGHT(head, __tmp, field);                               \
+        if (SPLAY_LEFT((head)->sph_root, field) == NULL)                      \
+          break;                                                              \
+      }                                                                       \
+      SPLAY_LINKLEFT(head, __right, field);                                   \
+    } else if (__comp > 0) {                                                  \
+      __tmp = SPLAY_RIGHT((head)->sph_root, field);                           \
+      if (__tmp == NULL)                                                      \
+        break;                                                                \
+      if ((cmp)(elm, __tmp) > 0){                                             \
+        SPLAY_ROTATE_LEFT(head, __tmp, field);                                \
+        if (SPLAY_RIGHT((head)->sph_root, field) == NULL)                     \
+          break;                                                              \
+      }                                                                       \
+      SPLAY_LINKRIGHT(head, __left, field);                                   \
+    }                                                                         \
+  }                                                                           \
+  SPLAY_ASSEMBLE(head, &__node, __left, __right, field);                      \
+}                                                                             \
+                                                                              \
+/* Splay with either the minimum or the maximum element                       \
+ * Used to find minimum or maximum element in tree.                           \
+ */                                                                           \
+void name##_SPLAY_MINMAX(struct name *head, int __comp)                       \
+{                                                                             \
+  struct type __node, *__left, *__right, *__tmp;                              \
+                                                                              \
+  SPLAY_LEFT(&__node, field) = SPLAY_RIGHT(&__node, field) = NULL;            \
+  __left = __right = &__node;                                                 \
+                                                                              \
+  for (;;) {                                                                  \
+    if (__comp < 0) {                                                         \
+      __tmp = SPLAY_LEFT((head)->sph_root, field);                            \
+      if (__tmp == NULL)                                                      \
+        break;                                                                \
+      if (__comp < 0){                                                        \
+        SPLAY_ROTATE_RIGHT(head, __tmp, field);                               \
+        if (SPLAY_LEFT((head)->sph_root, field) == NULL)                      \
+          break;                                                              \
+      }                                                                       \
+      SPLAY_LINKLEFT(head, __right, field);                                   \
+    } else if (__comp > 0) {                                                  \
+      __tmp = SPLAY_RIGHT((head)->sph_root, field);                           \
+      if (__tmp == NULL)                                                      \
+        break;                                                                \
+      if (__comp > 0) {                                                       \
+        SPLAY_ROTATE_LEFT(head, __tmp, field);                                \
+        if (SPLAY_RIGHT((head)->sph_root, field) == NULL)                     \
+          break;                                                              \
+      }                                                                       \
+      SPLAY_LINKRIGHT(head, __left, field);                                   \
+    }                                                                         \
+  }                                                                           \
+  SPLAY_ASSEMBLE(head, &__node, __left, __right, field);                      \
+}
+
+#define SPLAY_NEGINF  -1
+#define SPLAY_INF     1
+
+#define SPLAY_INSERT(name, x, y)  name##_SPLAY_INSERT(x, y)
+#define SPLAY_REMOVE(name, x, y)  name##_SPLAY_REMOVE(x, y)
+#define SPLAY_FIND(name, x, y)    name##_SPLAY_FIND(x, y)
+#define SPLAY_NEXT(name, x, y)    name##_SPLAY_NEXT(x, y)
+#define SPLAY_MIN(name, x)        (SPLAY_EMPTY(x) ? NULL                      \
+                                  : name##_SPLAY_MIN_MAX(x, SPLAY_NEGINF))
+#define SPLAY_MAX(name, x)        (SPLAY_EMPTY(x) ? NULL                      \
+                                  : name##_SPLAY_MIN_MAX(x, SPLAY_INF))
+
+#define SPLAY_FOREACH(x, name, head)                                          \
+  for ((x) = SPLAY_MIN(name, head);                                           \
+       (x) != NULL;                                                           \
+       (x) = SPLAY_NEXT(name, head, x))
+
+/* Macros that define a red-black tree */
+#define RB_HEAD(name, type)                                                   \
+struct name {                                                                 \
+  struct type *rbh_root; /* root of the tree */                               \
+}
+
+#define RB_INITIALIZER(root)                                                  \
+  { NULL }
+
+#define RB_INIT(root) do {                                                    \
+  (root)->rbh_root = NULL;                                                    \
+} while (/*CONSTCOND*/ 0)
+
+#define RB_BLACK  0
+#define RB_RED    1
+#define RB_ENTRY(type)                                                        \
+struct {                                                                      \
+  struct type *rbe_left;        /* left element */                            \
+  struct type *rbe_right;       /* right element */                           \
+  struct type *rbe_parent;      /* parent element */                          \
+  int rbe_color;                /* node color */                              \
+}
+
+#define RB_LEFT(elm, field)     (elm)->field.rbe_left
+#define RB_RIGHT(elm, field)    (elm)->field.rbe_right
+#define RB_PARENT(elm, field)   (elm)->field.rbe_parent
+#define RB_COLOR(elm, field)    (elm)->field.rbe_color
+#define RB_ROOT(head)           (head)->rbh_root
+#define RB_EMPTY(head)          (RB_ROOT(head) == NULL)
+
+#define RB_SET(elm, parent, field) do {                                       \
+  RB_PARENT(elm, field) = parent;                                             \
+  RB_LEFT(elm, field) = RB_RIGHT(elm, field) = NULL;                          \
+  RB_COLOR(elm, field) = RB_RED;                                              \
+} while (/*CONSTCOND*/ 0)
+
+#define RB_SET_BLACKRED(black, red, field) do {                               \
+  RB_COLOR(black, field) = RB_BLACK;                                          \
+  RB_COLOR(red, field) = RB_RED;                                              \
+} while (/*CONSTCOND*/ 0)
+
+#ifndef RB_AUGMENT
+#define RB_AUGMENT(x)  do {} while (0)
+#endif
+
+#define RB_ROTATE_LEFT(head, elm, tmp, field) do {                            \
+  (tmp) = RB_RIGHT(elm, field);                                               \
+  if ((RB_RIGHT(elm, field) = RB_LEFT(tmp, field)) != NULL) {                 \
+    RB_PARENT(RB_LEFT(tmp, field), field) = (elm);                            \
+  }                                                                           \
+  RB_AUGMENT(elm);                                                            \
+  if ((RB_PARENT(tmp, field) = RB_PARENT(elm, field)) != NULL) {              \
+    if ((elm) == RB_LEFT(RB_PARENT(elm, field), field))                       \
+      RB_LEFT(RB_PARENT(elm, field), field) = (tmp);                          \
+    else                                                                      \
+      RB_RIGHT(RB_PARENT(elm, field), field) = (tmp);                         \
+  } else                                                                      \
+    (head)->rbh_root = (tmp);                                                 \
+  RB_LEFT(tmp, field) = (elm);                                                \
+  RB_PARENT(elm, field) = (tmp);                                              \
+  RB_AUGMENT(tmp);                                                            \
+  if ((RB_PARENT(tmp, field)))                                                \
+    RB_AUGMENT(RB_PARENT(tmp, field));                                        \
+} while (/*CONSTCOND*/ 0)
+
+#define RB_ROTATE_RIGHT(head, elm, tmp, field) do {                           \
+  (tmp) = RB_LEFT(elm, field);                                                \
+  if ((RB_LEFT(elm, field) = RB_RIGHT(tmp, field)) != NULL) {                 \
+    RB_PARENT(RB_RIGHT(tmp, field), field) = (elm);                           \
+  }                                                                           \
+  RB_AUGMENT(elm);                                                            \
+  if ((RB_PARENT(tmp, field) = RB_PARENT(elm, field)) != NULL) {              \
+    if ((elm) == RB_LEFT(RB_PARENT(elm, field), field))                       \
+      RB_LEFT(RB_PARENT(elm, field), field) = (tmp);                          \
+    else                                                                      \
+      RB_RIGHT(RB_PARENT(elm, field), field) = (tmp);                         \
+  } else                                                                      \
+    (head)->rbh_root = (tmp);                                                 \
+  RB_RIGHT(tmp, field) = (elm);                                               \
+  RB_PARENT(elm, field) = (tmp);                                              \
+  RB_AUGMENT(tmp);                                                            \
+  if ((RB_PARENT(tmp, field)))                                                \
+    RB_AUGMENT(RB_PARENT(tmp, field));                                        \
+} while (/*CONSTCOND*/ 0)
+
+/* Generates prototypes and inline functions */
+#define  RB_PROTOTYPE(name, type, field, cmp)                                 \
+  RB_PROTOTYPE_INTERNAL(name, type, field, cmp,)
+#define  RB_PROTOTYPE_STATIC(name, type, field, cmp)                          \
+  RB_PROTOTYPE_INTERNAL(name, type, field, cmp, UV__UNUSED static)
+#define RB_PROTOTYPE_INTERNAL(name, type, field, cmp, attr)                   \
+attr void name##_RB_INSERT_COLOR(struct name *, struct type *);               \
+attr void name##_RB_REMOVE_COLOR(struct name *, struct type *, struct type *);\
+attr struct type *name##_RB_REMOVE(struct name *, struct type *);             \
+attr struct type *name##_RB_INSERT(struct name *, struct type *);             \
+attr struct type *name##_RB_FIND(struct name *, struct type *);               \
+attr struct type *name##_RB_NFIND(struct name *, struct type *);              \
+attr struct type *name##_RB_NEXT(struct type *);                              \
+attr struct type *name##_RB_PREV(struct type *);                              \
+attr struct type *name##_RB_MINMAX(struct name *, int);                       \
+                                                                              \
+
+/* Main rb operation.
+ * Moves node close to the key of elm to top
+ */
+#define  RB_GENERATE(name, type, field, cmp)                                  \
+  RB_GENERATE_INTERNAL(name, type, field, cmp,)
+#define  RB_GENERATE_STATIC(name, type, field, cmp)                           \
+  RB_GENERATE_INTERNAL(name, type, field, cmp, UV__UNUSED static)
+#define RB_GENERATE_INTERNAL(name, type, field, cmp, attr)                    \
+attr void                                                                     \
+name##_RB_INSERT_COLOR(struct name *head, struct type *elm)                   \
+{                                                                             \
+  struct type *parent, *gparent, *tmp;                                        \
+  while ((parent = RB_PARENT(elm, field)) != NULL &&                          \
+      RB_COLOR(parent, field) == RB_RED) {                                    \
+    gparent = RB_PARENT(parent, field);                                       \
+    if (parent == RB_LEFT(gparent, field)) {                                  \
+      tmp = RB_RIGHT(gparent, field);                                         \
+      if (tmp && RB_COLOR(tmp, field) == RB_RED) {                            \
+        RB_COLOR(tmp, field) = RB_BLACK;                                      \
+        RB_SET_BLACKRED(parent, gparent, field);                              \
+        elm = gparent;                                                        \
+        continue;                                                             \
+      }                                                                       \
+      if (RB_RIGHT(parent, field) == elm) {                                   \
+        RB_ROTATE_LEFT(head, parent, tmp, field);                             \
+        tmp = parent;                                                         \
+        parent = elm;                                                         \
+        elm = tmp;                                                            \
+      }                                                                       \
+      RB_SET_BLACKRED(parent, gparent, field);                                \
+      RB_ROTATE_RIGHT(head, gparent, tmp, field);                             \
+    } else {                                                                  \
+      tmp = RB_LEFT(gparent, field);                                          \
+      if (tmp && RB_COLOR(tmp, field) == RB_RED) {                            \
+        RB_COLOR(tmp, field) = RB_BLACK;                                      \
+        RB_SET_BLACKRED(parent, gparent, field);                              \
+        elm = gparent;                                                        \
+        continue;                                                             \
+      }                                                                       \
+      if (RB_LEFT(parent, field) == elm) {                                    \
+        RB_ROTATE_RIGHT(head, parent, tmp, field);                            \
+        tmp = parent;                                                         \
+        parent = elm;                                                         \
+        elm = tmp;                                                            \
+      }                                                                       \
+      RB_SET_BLACKRED(parent, gparent, field);                                \
+      RB_ROTATE_LEFT(head, gparent, tmp, field);                              \
+    }                                                                         \
+  }                                                                           \
+  RB_COLOR(head->rbh_root, field) = RB_BLACK;                                 \
+}                                                                             \
+                                                                              \
+attr void                                                                     \
+name##_RB_REMOVE_COLOR(struct name *head, struct type *parent,                \
+    struct type *elm)                                                         \
+{                                                                             \
+  struct type *tmp;                                                           \
+  while ((elm == NULL || RB_COLOR(elm, field) == RB_BLACK) &&                 \
+      elm != RB_ROOT(head)) {                                                 \
+    if (RB_LEFT(parent, field) == elm) {                                      \
+      tmp = RB_RIGHT(parent, field);                                          \
+      if (RB_COLOR(tmp, field) == RB_RED) {                                   \
+        RB_SET_BLACKRED(tmp, parent, field);                                  \
+        RB_ROTATE_LEFT(head, parent, tmp, field);                             \
+        tmp = RB_RIGHT(parent, field);                                        \
+      }                                                                       \
+      if ((RB_LEFT(tmp, field) == NULL ||                                     \
+          RB_COLOR(RB_LEFT(tmp, field), field) == RB_BLACK) &&                \
+          (RB_RIGHT(tmp, field) == NULL ||                                    \
+          RB_COLOR(RB_RIGHT(tmp, field), field) == RB_BLACK)) {               \
+        RB_COLOR(tmp, field) = RB_RED;                                        \
+        elm = parent;                                                         \
+        parent = RB_PARENT(elm, field);                                       \
+      } else {                                                                \
+        if (RB_RIGHT(tmp, field) == NULL ||                                   \
+            RB_COLOR(RB_RIGHT(tmp, field), field) == RB_BLACK) {              \
+          struct type *oleft;                                                 \
+          if ((oleft = RB_LEFT(tmp, field))                                   \
+              != NULL)                                                        \
+            RB_COLOR(oleft, field) = RB_BLACK;                                \
+          RB_COLOR(tmp, field) = RB_RED;                                      \
+          RB_ROTATE_RIGHT(head, tmp, oleft, field);                           \
+          tmp = RB_RIGHT(parent, field);                                      \
+        }                                                                     \
+        RB_COLOR(tmp, field) = RB_COLOR(parent, field);                       \
+        RB_COLOR(parent, field) = RB_BLACK;                                   \
+        if (RB_RIGHT(tmp, field))                                             \
+          RB_COLOR(RB_RIGHT(tmp, field), field) = RB_BLACK;                   \
+        RB_ROTATE_LEFT(head, parent, tmp, field);                             \
+        elm = RB_ROOT(head);                                                  \
+        break;                                                                \
+      }                                                                       \
+    } else {                                                                  \
+      tmp = RB_LEFT(parent, field);                                           \
+      if (RB_COLOR(tmp, field) == RB_RED) {                                   \
+        RB_SET_BLACKRED(tmp, parent, field);                                  \
+        RB_ROTATE_RIGHT(head, parent, tmp, field);                            \
+        tmp = RB_LEFT(parent, field);                                         \
+      }                                                                       \
+      if ((RB_LEFT(tmp, field) == NULL ||                                     \
+          RB_COLOR(RB_LEFT(tmp, field), field) == RB_BLACK) &&                \
+          (RB_RIGHT(tmp, field) == NULL ||                                    \
+          RB_COLOR(RB_RIGHT(tmp, field), field) == RB_BLACK)) {               \
+        RB_COLOR(tmp, field) = RB_RED;                                        \
+        elm = parent;                                                         \
+        parent = RB_PARENT(elm, field);                                       \
+      } else {                                                                \
+        if (RB_LEFT(tmp, field) == NULL ||                                    \
+            RB_COLOR(RB_LEFT(tmp, field), field) == RB_BLACK) {               \
+          struct type *oright;                                                \
+          if ((oright = RB_RIGHT(tmp, field))                                 \
+              != NULL)                                                        \
+            RB_COLOR(oright, field) = RB_BLACK;                               \
+          RB_COLOR(tmp, field) = RB_RED;                                      \
+          RB_ROTATE_LEFT(head, tmp, oright, field);                           \
+          tmp = RB_LEFT(parent, field);                                       \
+        }                                                                     \
+        RB_COLOR(tmp, field) = RB_COLOR(parent, field);                       \
+        RB_COLOR(parent, field) = RB_BLACK;                                   \
+        if (RB_LEFT(tmp, field))                                              \
+          RB_COLOR(RB_LEFT(tmp, field), field) = RB_BLACK;                    \
+        RB_ROTATE_RIGHT(head, parent, tmp, field);                            \
+        elm = RB_ROOT(head);                                                  \
+        break;                                                                \
+      }                                                                       \
+    }                                                                         \
+  }                                                                           \
+  if (elm)                                                                    \
+    RB_COLOR(elm, field) = RB_BLACK;                                          \
+}                                                                             \
+                                                                              \
+attr struct type *                                                            \
+name##_RB_REMOVE(struct name *head, struct type *elm)                         \
+{                                                                             \
+  struct type *child, *parent, *old = elm;                                    \
+  int color;                                                                  \
+  if (RB_LEFT(elm, field) == NULL)                                            \
+    child = RB_RIGHT(elm, field);                                             \
+  else if (RB_RIGHT(elm, field) == NULL)                                      \
+    child = RB_LEFT(elm, field);                                              \
+  else {                                                                      \
+    struct type *left;                                                        \
+    elm = RB_RIGHT(elm, field);                                               \
+    while ((left = RB_LEFT(elm, field)) != NULL)                              \
+      elm = left;                                                             \
+    child = RB_RIGHT(elm, field);                                             \
+    parent = RB_PARENT(elm, field);                                           \
+    color = RB_COLOR(elm, field);                                             \
+    if (child)                                                                \
+      RB_PARENT(child, field) = parent;                                       \
+    if (parent) {                                                             \
+      if (RB_LEFT(parent, field) == elm)                                      \
+        RB_LEFT(parent, field) = child;                                       \
+      else                                                                    \
+        RB_RIGHT(parent, field) = child;                                      \
+      RB_AUGMENT(parent);                                                     \
+    } else                                                                    \
+      RB_ROOT(head) = child;                                                  \
+    if (RB_PARENT(elm, field) == old)                                         \
+      parent = elm;                                                           \
+    (elm)->field = (old)->field;                                              \
+    if (RB_PARENT(old, field)) {                                              \
+      if (RB_LEFT(RB_PARENT(old, field), field) == old)                       \
+        RB_LEFT(RB_PARENT(old, field), field) = elm;                          \
+      else                                                                    \
+        RB_RIGHT(RB_PARENT(old, field), field) = elm;                         \
+      RB_AUGMENT(RB_PARENT(old, field));                                      \
+    } else                                                                    \
+      RB_ROOT(head) = elm;                                                    \
+    RB_PARENT(RB_LEFT(old, field), field) = elm;                              \
+    if (RB_RIGHT(old, field))                                                 \
+      RB_PARENT(RB_RIGHT(old, field), field) = elm;                           \
+    if (parent) {                                                             \
+      left = parent;                                                          \
+      do {                                                                    \
+        RB_AUGMENT(left);                                                     \
+      } while ((left = RB_PARENT(left, field)) != NULL);                      \
+    }                                                                         \
+    goto color;                                                               \
+  }                                                                           \
+  parent = RB_PARENT(elm, field);                                             \
+  color = RB_COLOR(elm, field);                                               \
+  if (child)                                                                  \
+    RB_PARENT(child, field) = parent;                                         \
+  if (parent) {                                                               \
+    if (RB_LEFT(parent, field) == elm)                                        \
+      RB_LEFT(parent, field) = child;                                         \
+    else                                                                      \
+      RB_RIGHT(parent, field) = child;                                        \
+    RB_AUGMENT(parent);                                                       \
+  } else                                                                      \
+    RB_ROOT(head) = child;                                                    \
+color:                                                                        \
+  if (color == RB_BLACK)                                                      \
+    name##_RB_REMOVE_COLOR(head, parent, child);                              \
+  return (old);                                                               \
+}                                                                             \
+                                                                              \
+/* Inserts a node into the RB tree */                                         \
+attr struct type *                                                            \
+name##_RB_INSERT(struct name *head, struct type *elm)                         \
+{                                                                             \
+  struct type *tmp;                                                           \
+  struct type *parent = NULL;                                                 \
+  int comp = 0;                                                               \
+  tmp = RB_ROOT(head);                                                        \
+  while (tmp) {                                                               \
+    parent = tmp;                                                             \
+    comp = (cmp)(elm, parent);                                                \
+    if (comp < 0)                                                             \
+      tmp = RB_LEFT(tmp, field);                                              \
+    else if (comp > 0)                                                        \
+      tmp = RB_RIGHT(tmp, field);                                             \
+    else                                                                      \
+      return (tmp);                                                           \
+  }                                                                           \
+  RB_SET(elm, parent, field);                                                 \
+  if (parent != NULL) {                                                       \
+    if (comp < 0)                                                             \
+      RB_LEFT(parent, field) = elm;                                           \
+    else                                                                      \
+      RB_RIGHT(parent, field) = elm;                                          \
+    RB_AUGMENT(parent);                                                       \
+  } else                                                                      \
+    RB_ROOT(head) = elm;                                                      \
+  name##_RB_INSERT_COLOR(head, elm);                                          \
+  return (NULL);                                                              \
+}                                                                             \
+                                                                              \
+/* Finds the node with the same key as elm */                                 \
+attr struct type *                                                            \
+name##_RB_FIND(struct name *head, struct type *elm)                           \
+{                                                                             \
+  struct type *tmp = RB_ROOT(head);                                           \
+  int comp;                                                                   \
+  while (tmp) {                                                               \
+    comp = cmp(elm, tmp);                                                     \
+    if (comp < 0)                                                             \
+      tmp = RB_LEFT(tmp, field);                                              \
+    else if (comp > 0)                                                        \
+      tmp = RB_RIGHT(tmp, field);                                             \
+    else                                                                      \
+      return (tmp);                                                           \
+  }                                                                           \
+  return (NULL);                                                              \
+}                                                                             \
+                                                                              \
+/* Finds the first node greater than or equal to the search key */            \
+attr struct type *                                                            \
+name##_RB_NFIND(struct name *head, struct type *elm)                          \
+{                                                                             \
+  struct type *tmp = RB_ROOT(head);                                           \
+  struct type *res = NULL;                                                    \
+  int comp;                                                                   \
+  while (tmp) {                                                               \
+    comp = cmp(elm, tmp);                                                     \
+    if (comp < 0) {                                                           \
+      res = tmp;                                                              \
+      tmp = RB_LEFT(tmp, field);                                              \
+    }                                                                         \
+    else if (comp > 0)                                                        \
+      tmp = RB_RIGHT(tmp, field);                                             \
+    else                                                                      \
+      return (tmp);                                                           \
+  }                                                                           \
+  return (res);                                                               \
+}                                                                             \
+                                                                              \
+/* ARGSUSED */                                                                \
+attr struct type *                                                            \
+name##_RB_NEXT(struct type *elm)                                              \
+{                                                                             \
+  if (RB_RIGHT(elm, field)) {                                                 \
+    elm = RB_RIGHT(elm, field);                                               \
+    while (RB_LEFT(elm, field))                                               \
+      elm = RB_LEFT(elm, field);                                              \
+  } else {                                                                    \
+    if (RB_PARENT(elm, field) &&                                              \
+        (elm == RB_LEFT(RB_PARENT(elm, field), field)))                       \
+      elm = RB_PARENT(elm, field);                                            \
+    else {                                                                    \
+      while (RB_PARENT(elm, field) &&                                         \
+          (elm == RB_RIGHT(RB_PARENT(elm, field), field)))                    \
+        elm = RB_PARENT(elm, field);                                          \
+      elm = RB_PARENT(elm, field);                                            \
+    }                                                                         \
+  }                                                                           \
+  return (elm);                                                               \
+}                                                                             \
+                                                                              \
+/* ARGSUSED */                                                                \
+attr struct type *                                                            \
+name##_RB_PREV(struct type *elm)                                              \
+{                                                                             \
+  if (RB_LEFT(elm, field)) {                                                  \
+    elm = RB_LEFT(elm, field);                                                \
+    while (RB_RIGHT(elm, field))                                              \
+      elm = RB_RIGHT(elm, field);                                             \
+  } else {                                                                    \
+    if (RB_PARENT(elm, field) &&                                              \
+        (elm == RB_RIGHT(RB_PARENT(elm, field), field)))                      \
+      elm = RB_PARENT(elm, field);                                            \
+    else {                                                                    \
+      while (RB_PARENT(elm, field) &&                                         \
+          (elm == RB_LEFT(RB_PARENT(elm, field), field)))                     \
+        elm = RB_PARENT(elm, field);                                          \
+      elm = RB_PARENT(elm, field);                                            \
+    }                                                                         \
+  }                                                                           \
+  return (elm);                                                               \
+}                                                                             \
+                                                                              \
+attr struct type *                                                            \
+name##_RB_MINMAX(struct name *head, int val)                                  \
+{                                                                             \
+  struct type *tmp = RB_ROOT(head);                                           \
+  struct type *parent = NULL;                                                 \
+  while (tmp) {                                                               \
+    parent = tmp;                                                             \
+    if (val < 0)                                                              \
+      tmp = RB_LEFT(tmp, field);                                              \
+    else                                                                      \
+      tmp = RB_RIGHT(tmp, field);                                             \
+  }                                                                           \
+  return (parent);                                                            \
+}
+
+#define RB_NEGINF   -1
+#define RB_INF      1
+
+#define RB_INSERT(name, x, y)   name##_RB_INSERT(x, y)
+#define RB_REMOVE(name, x, y)   name##_RB_REMOVE(x, y)
+#define RB_FIND(name, x, y)     name##_RB_FIND(x, y)
+#define RB_NFIND(name, x, y)    name##_RB_NFIND(x, y)
+#define RB_NEXT(name, x, y)     name##_RB_NEXT(y)
+#define RB_PREV(name, x, y)     name##_RB_PREV(y)
+#define RB_MIN(name, x)         name##_RB_MINMAX(x, RB_NEGINF)
+#define RB_MAX(name, x)         name##_RB_MINMAX(x, RB_INF)
+
+#define RB_FOREACH(x, name, head)                                             \
+  for ((x) = RB_MIN(name, head);                                              \
+       (x) != NULL;                                                           \
+       (x) = name##_RB_NEXT(x))
+
+#define RB_FOREACH_FROM(x, name, y)                                           \
+  for ((x) = (y);                                                             \
+      ((x) != NULL) && ((y) = name##_RB_NEXT(x), (x) != NULL);                \
+       (x) = (y))
+
+#define RB_FOREACH_SAFE(x, name, head, y)                                     \
+  for ((x) = RB_MIN(name, head);                                              \
+      ((x) != NULL) && ((y) = name##_RB_NEXT(x), (x) != NULL);                \
+       (x) = (y))
+
+#define RB_FOREACH_REVERSE(x, name, head)                                     \
+  for ((x) = RB_MAX(name, head);                                              \
+       (x) != NULL;                                                           \
+       (x) = name##_RB_PREV(x))
+
+#define RB_FOREACH_REVERSE_FROM(x, name, y)                                   \
+  for ((x) = (y);                                                             \
+      ((x) != NULL) && ((y) = name##_RB_PREV(x), (x) != NULL);                \
+       (x) = (y))
+
+#define RB_FOREACH_REVERSE_SAFE(x, name, head, y)                             \
+  for ((x) = RB_MAX(name, head);                                              \
+      ((x) != NULL) && ((y) = name##_RB_PREV(x), (x) != NULL);                \
+       (x) = (y))
+
+#endif  /* UV_TREE_H_ */
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/include/uv/unix.h b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/include/uv/unix.h
new file mode 100644
index 0000000..256fef3
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/include/uv/unix.h
@@ -0,0 +1,497 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#ifndef UV_UNIX_H
+#define UV_UNIX_H
+
+#include <sys/types.h>
+#include <sys/stat.h>
+#include <fcntl.h>
+#include <dirent.h>
+
+#include <sys/socket.h>
+#include <netinet/in.h>
+#include <netinet/tcp.h>
+#include <arpa/inet.h>
+#include <netdb.h>  /* MAXHOSTNAMELEN on Solaris */
+
+#include <termios.h>
+#include <pwd.h>
+
+#if !defined(__MVS__)
+#include <semaphore.h>
+#include <sys/param.h> /* MAXHOSTNAMELEN on Linux and the BSDs */
+#endif
+#include <pthread.h>
+#include <signal.h>
+
+#include "uv/threadpool.h"
+
+#if defined(__linux__)
+# include "uv/linux.h"
+#elif defined(__APPLE__)
+# include "uv/darwin.h"
+#elif defined(__DragonFly__)       || \
+      defined(__FreeBSD__)         || \
+      defined(__FreeBSD_kernel__)  || \
+      defined(__OpenBSD__)         || \
+      defined(__NetBSD__)
+# include "uv/bsd.h"
+#elif defined(__CYGWIN__) || \
+      defined(__MSYS__)   || \
+      defined(__HAIKU__)  || \
+      defined(__QNX__)    || \
+      defined(__GNU__)
+# include "uv/posix.h"
+#endif
+
+#ifndef NI_MAXHOST
+# define NI_MAXHOST 1025
+#endif
+
+#ifndef NI_MAXSERV
+# define NI_MAXSERV 32
+#endif
+
+#ifndef UV_IO_PRIVATE_PLATFORM_FIELDS
+# define UV_IO_PRIVATE_PLATFORM_FIELDS /* empty */
+#endif
+
+struct uv__io_s;
+struct uv_loop_s;
+
+typedef void (*uv__io_cb)(struct uv_loop_s* loop,
+                          struct uv__io_s* w,
+                          unsigned int events);
+typedef struct uv__io_s uv__io_t;
+
+struct uv__io_s {
+  uv__io_cb cb;
+  void* pending_queue[2];
+  void* watcher_queue[2];
+  unsigned int pevents; /* Pending event mask i.e. mask at next tick. */
+  unsigned int events;  /* Current event mask. */
+  int fd;
+  UV_IO_PRIVATE_PLATFORM_FIELDS
+};
+
+#ifndef UV_PLATFORM_SEM_T
+# define UV_PLATFORM_SEM_T sem_t
+#endif
+
+#ifndef UV_PLATFORM_LOOP_FIELDS
+# define UV_PLATFORM_LOOP_FIELDS /* empty */
+#endif
+
+#ifndef UV_PLATFORM_FS_EVENT_FIELDS
+# define UV_PLATFORM_FS_EVENT_FIELDS /* empty */
+#endif
+
+#ifndef UV_STREAM_PRIVATE_PLATFORM_FIELDS
+# define UV_STREAM_PRIVATE_PLATFORM_FIELDS /* empty */
+#endif
+
+/* Note: May be cast to struct iovec. See writev(2). */
+typedef struct uv_buf_t {
+  char* base;
+  size_t len;
+} uv_buf_t;
+
+typedef int uv_file;
+typedef int uv_os_sock_t;
+typedef int uv_os_fd_t;
+typedef pid_t uv_pid_t;
+
+#define UV_ONCE_INIT PTHREAD_ONCE_INIT
+
+typedef pthread_once_t uv_once_t;
+typedef pthread_t uv_thread_t;
+typedef pthread_mutex_t uv_mutex_t;
+typedef pthread_rwlock_t uv_rwlock_t;
+typedef UV_PLATFORM_SEM_T uv_sem_t;
+typedef pthread_cond_t uv_cond_t;
+typedef pthread_key_t uv_key_t;
+
+/* Note: guard clauses should match uv_barrier_init's in src/unix/thread.c. */
+#if defined(_AIX) || \
+    defined(__OpenBSD__) || \
+    !defined(PTHREAD_BARRIER_SERIAL_THREAD)
+/* TODO(bnoordhuis) Merge into uv_barrier_t in v2. */
+struct _uv_barrier {
+  uv_mutex_t mutex;
+  uv_cond_t cond;
+  unsigned threshold;
+  unsigned in;
+  unsigned out;
+};
+
+typedef struct {
+  struct _uv_barrier* b;
+# if defined(PTHREAD_BARRIER_SERIAL_THREAD)
+  /* TODO(bnoordhuis) Remove padding in v2. */
+  char pad[sizeof(pthread_barrier_t) - sizeof(struct _uv_barrier*)];
+# endif
+} uv_barrier_t;
+#else
+typedef pthread_barrier_t uv_barrier_t;
+#endif
+
+/* Platform-specific definitions for uv_spawn support. */
+typedef gid_t uv_gid_t;
+typedef uid_t uv_uid_t;
+
+typedef struct dirent uv__dirent_t;
+
+#define UV_DIR_PRIVATE_FIELDS \
+  DIR* dir;
+
+#if defined(DT_UNKNOWN)
+# define HAVE_DIRENT_TYPES
+# if defined(DT_REG)
+#  define UV__DT_FILE DT_REG
+# else
+#  define UV__DT_FILE -1
+# endif
+# if defined(DT_DIR)
+#  define UV__DT_DIR DT_DIR
+# else
+#  define UV__DT_DIR -2
+# endif
+# if defined(DT_LNK)
+#  define UV__DT_LINK DT_LNK
+# else
+#  define UV__DT_LINK -3
+# endif
+# if defined(DT_FIFO)
+#  define UV__DT_FIFO DT_FIFO
+# else
+#  define UV__DT_FIFO -4
+# endif
+# if defined(DT_SOCK)
+#  define UV__DT_SOCKET DT_SOCK
+# else
+#  define UV__DT_SOCKET -5
+# endif
+# if defined(DT_CHR)
+#  define UV__DT_CHAR DT_CHR
+# else
+#  define UV__DT_CHAR -6
+# endif
+# if defined(DT_BLK)
+#  define UV__DT_BLOCK DT_BLK
+# else
+#  define UV__DT_BLOCK -7
+# endif
+#endif
+
+/* Platform-specific definitions for uv_dlopen support. */
+#define UV_DYNAMIC /* empty */
+
+typedef struct {
+  void* handle;
+  char* errmsg;
+} uv_lib_t;
+
+#define UV_LOOP_PRIVATE_FIELDS                                                \
+  unsigned long flags;                                                        \
+  int backend_fd;                                                             \
+  void* pending_queue[2];                                                     \
+  void* watcher_queue[2];                                                     \
+  void** watchers;                                                            \
+  unsigned int nwatchers;                                                     \
+  unsigned int nfds;                                                          \
+  void* wq[2];                                                                \
+  uv_mutex_t wq_mutex;                                                        \
+  uv_async_t wq_async;                                                        \
+  uv_rwlock_t cloexec_lock;                                                   \
+  uv_handle_t* closing_handles;                                               \
+  void* process_handles[2];                                                   \
+  void* prepare_handles[2];                                                   \
+  void* check_handles[2];                                                     \
+  void* idle_handles[2];                                                      \
+  void* async_handles[2];                                                     \
+  void (*async_unused)(void);  /* TODO(bnoordhuis) Remove in libuv v2. */     \
+  uv__io_t async_io_watcher;                                                  \
+  int async_wfd;                                                              \
+  struct {                                                                    \
+    void* min;                                                                \
+    unsigned int nelts;                                                       \
+  } timer_heap;                                                               \
+  uint64_t timer_counter;                                                     \
+  uint64_t time;                                                              \
+  int signal_pipefd[2];                                                       \
+  uv__io_t signal_io_watcher;                                                 \
+  uv_signal_t child_watcher;                                                  \
+  int emfile_fd;                                                              \
+  UV_PLATFORM_LOOP_FIELDS                                                     \
+
+#define UV_REQ_TYPE_PRIVATE /* empty */
+
+#define UV_REQ_PRIVATE_FIELDS  /* empty */
+
+#define UV_PRIVATE_REQ_TYPES /* empty */
+
+#define UV_WRITE_PRIVATE_FIELDS                                               \
+  void* queue[2];                                                             \
+  unsigned int write_index;                                                   \
+  uv_buf_t* bufs;                                                             \
+  unsigned int nbufs;                                                         \
+  int error;                                                                  \
+  uv_buf_t bufsml[4];                                                         \
+
+#define UV_CONNECT_PRIVATE_FIELDS                                             \
+  void* queue[2];                                                             \
+
+#define UV_SHUTDOWN_PRIVATE_FIELDS /* empty */
+
+#define UV_UDP_SEND_PRIVATE_FIELDS                                            \
+  void* queue[2];                                                             \
+  struct sockaddr_storage addr;                                               \
+  unsigned int nbufs;                                                         \
+  uv_buf_t* bufs;                                                             \
+  ssize_t status;                                                             \
+  uv_udp_send_cb send_cb;                                                     \
+  uv_buf_t bufsml[4];                                                         \
+
+#define UV_HANDLE_PRIVATE_FIELDS                                              \
+  uv_handle_t* next_closing;                                                  \
+  unsigned int flags;                                                         \
+
+#define UV_STREAM_PRIVATE_FIELDS                                              \
+  uv_connect_t *connect_req;                                                  \
+  uv_shutdown_t *shutdown_req;                                                \
+  uv__io_t io_watcher;                                                        \
+  void* write_queue[2];                                                       \
+  void* write_completed_queue[2];                                             \
+  uv_connection_cb connection_cb;                                             \
+  int delayed_error;                                                          \
+  int accepted_fd;                                                            \
+  void* queued_fds;                                                           \
+  UV_STREAM_PRIVATE_PLATFORM_FIELDS                                           \
+
+#define UV_TCP_PRIVATE_FIELDS /* empty */
+
+#define UV_UDP_PRIVATE_FIELDS                                                 \
+  uv_alloc_cb alloc_cb;                                                       \
+  uv_udp_recv_cb recv_cb;                                                     \
+  uv__io_t io_watcher;                                                        \
+  void* write_queue[2];                                                       \
+  void* write_completed_queue[2];                                             \
+
+#define UV_PIPE_PRIVATE_FIELDS                                                \
+  const char* pipe_fname; /* strdup'ed */
+
+#define UV_POLL_PRIVATE_FIELDS                                                \
+  uv__io_t io_watcher;
+
+#define UV_PREPARE_PRIVATE_FIELDS                                             \
+  uv_prepare_cb prepare_cb;                                                   \
+  void* queue[2];                                                             \
+
+#define UV_CHECK_PRIVATE_FIELDS                                               \
+  uv_check_cb check_cb;                                                       \
+  void* queue[2];                                                             \
+
+#define UV_IDLE_PRIVATE_FIELDS                                                \
+  uv_idle_cb idle_cb;                                                         \
+  void* queue[2];                                                             \
+
+#define UV_ASYNC_PRIVATE_FIELDS                                               \
+  uv_async_cb async_cb;                                                       \
+  void* queue[2];                                                             \
+  int pending;                                                                \
+
+#define UV_TIMER_PRIVATE_FIELDS                                               \
+  uv_timer_cb timer_cb;                                                       \
+  void* heap_node[3];                                                         \
+  uint64_t timeout;                                                           \
+  uint64_t repeat;                                                            \
+  uint64_t start_id;
+
+#define UV_GETADDRINFO_PRIVATE_FIELDS                                         \
+  struct uv__work work_req;                                                   \
+  uv_getaddrinfo_cb cb;                                                       \
+  struct addrinfo* hints;                                                     \
+  char* hostname;                                                             \
+  char* service;                                                              \
+  struct addrinfo* addrinfo;                                                  \
+  int retcode;
+
+#define UV_GETNAMEINFO_PRIVATE_FIELDS                                         \
+  struct uv__work work_req;                                                   \
+  uv_getnameinfo_cb getnameinfo_cb;                                           \
+  struct sockaddr_storage storage;                                            \
+  int flags;                                                                  \
+  char host[NI_MAXHOST];                                                      \
+  char service[NI_MAXSERV];                                                   \
+  int retcode;
+
+#define UV_PROCESS_PRIVATE_FIELDS                                             \
+  void* queue[2];                                                             \
+  int status;                                                                 \
+
+#define UV_FS_PRIVATE_FIELDS                                                  \
+  const char *new_path;                                                       \
+  uv_file file;                                                               \
+  int flags;                                                                  \
+  mode_t mode;                                                                \
+  unsigned int nbufs;                                                         \
+  uv_buf_t* bufs;                                                             \
+  off_t off;                                                                  \
+  uv_uid_t uid;                                                               \
+  uv_gid_t gid;                                                               \
+  double atime;                                                               \
+  double mtime;                                                               \
+  struct uv__work work_req;                                                   \
+  uv_buf_t bufsml[4];                                                         \
+
+#define UV_WORK_PRIVATE_FIELDS                                                \
+  struct uv__work work_req;
+
+#define UV_TTY_PRIVATE_FIELDS                                                 \
+  struct termios orig_termios;                                                \
+  int mode;
+
+#define UV_SIGNAL_PRIVATE_FIELDS                                              \
+  /* RB_ENTRY(uv_signal_s) tree_entry; */                                     \
+  struct {                                                                    \
+    struct uv_signal_s* rbe_left;                                             \
+    struct uv_signal_s* rbe_right;                                            \
+    struct uv_signal_s* rbe_parent;                                           \
+    int rbe_color;                                                            \
+  } tree_entry;                                                               \
+  /* Use two counters here so we don have to fiddle with atomics. */          \
+  unsigned int caught_signals;                                                \
+  unsigned int dispatched_signals;
+
+#define UV_FS_EVENT_PRIVATE_FIELDS                                            \
+  uv_fs_event_cb cb;                                                          \
+  UV_PLATFORM_FS_EVENT_FIELDS                                                 \
+
+/* fs open() flags supported on this platform: */
+#if defined(O_APPEND)
+# define UV_FS_O_APPEND       O_APPEND
+#else
+# define UV_FS_O_APPEND       0
+#endif
+#if defined(O_CREAT)
+# define UV_FS_O_CREAT        O_CREAT
+#else
+# define UV_FS_O_CREAT        0
+#endif
+
+#if defined(__linux__) && defined(__arm__)
+# define UV_FS_O_DIRECT       0x10000
+#elif defined(__linux__) && defined(__m68k__)
+# define UV_FS_O_DIRECT       0x10000
+#elif defined(__linux__) && defined(__mips__)
+# define UV_FS_O_DIRECT       0x08000
+#elif defined(__linux__) && defined(__powerpc__)
+# define UV_FS_O_DIRECT       0x20000
+#elif defined(__linux__) && defined(__s390x__)
+# define UV_FS_O_DIRECT       0x04000
+#elif defined(__linux__) && defined(__x86_64__)
+# define UV_FS_O_DIRECT       0x04000
+#elif defined(O_DIRECT)
+# define UV_FS_O_DIRECT       O_DIRECT
+#else
+# define UV_FS_O_DIRECT       0
+#endif
+
+#if defined(O_DIRECTORY)
+# define UV_FS_O_DIRECTORY    O_DIRECTORY
+#else
+# define UV_FS_O_DIRECTORY    0
+#endif
+#if defined(O_DSYNC)
+# define UV_FS_O_DSYNC        O_DSYNC
+#else
+# define UV_FS_O_DSYNC        0
+#endif
+#if defined(O_EXCL)
+# define UV_FS_O_EXCL         O_EXCL
+#else
+# define UV_FS_O_EXCL         0
+#endif
+#if defined(O_EXLOCK)
+# define UV_FS_O_EXLOCK       O_EXLOCK
+#else
+# define UV_FS_O_EXLOCK       0
+#endif
+#if defined(O_NOATIME)
+# define UV_FS_O_NOATIME      O_NOATIME
+#else
+# define UV_FS_O_NOATIME      0
+#endif
+#if defined(O_NOCTTY)
+# define UV_FS_O_NOCTTY       O_NOCTTY
+#else
+# define UV_FS_O_NOCTTY       0
+#endif
+#if defined(O_NOFOLLOW)
+# define UV_FS_O_NOFOLLOW     O_NOFOLLOW
+#else
+# define UV_FS_O_NOFOLLOW     0
+#endif
+#if defined(O_NONBLOCK)
+# define UV_FS_O_NONBLOCK     O_NONBLOCK
+#else
+# define UV_FS_O_NONBLOCK     0
+#endif
+#if defined(O_RDONLY)
+# define UV_FS_O_RDONLY       O_RDONLY
+#else
+# define UV_FS_O_RDONLY       0
+#endif
+#if defined(O_RDWR)
+# define UV_FS_O_RDWR         O_RDWR
+#else
+# define UV_FS_O_RDWR         0
+#endif
+#if defined(O_SYMLINK)
+# define UV_FS_O_SYMLINK      O_SYMLINK
+#else
+# define UV_FS_O_SYMLINK      0
+#endif
+#if defined(O_SYNC)
+# define UV_FS_O_SYNC         O_SYNC
+#else
+# define UV_FS_O_SYNC         0
+#endif
+#if defined(O_TRUNC)
+# define UV_FS_O_TRUNC        O_TRUNC
+#else
+# define UV_FS_O_TRUNC        0
+#endif
+#if defined(O_WRONLY)
+# define UV_FS_O_WRONLY       O_WRONLY
+#else
+# define UV_FS_O_WRONLY       0
+#endif
+
+/* fs open() flags supported on other platforms: */
+#define UV_FS_O_FILEMAP       0
+#define UV_FS_O_RANDOM        0
+#define UV_FS_O_SHORT_LIVED   0
+#define UV_FS_O_SEQUENTIAL    0
+#define UV_FS_O_TEMPORARY     0
+
+#endif /* UV_UNIX_H */
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/include/uv/version.h b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/include/uv/version.h
new file mode 100644
index 0000000..9c9d292
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/include/uv/version.h
@@ -0,0 +1,43 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#ifndef UV_VERSION_H
+#define UV_VERSION_H
+
+ /*
+ * Versions with the same major number are ABI stable. API is allowed to
+ * evolve between minor releases, but only in a backwards compatible way.
+ * Make sure you update the -soname directives in configure.ac
+ * whenever you bump UV_VERSION_MAJOR or UV_VERSION_MINOR (but
+ * not UV_VERSION_PATCH.)
+ */
+
+#define UV_VERSION_MAJOR 1
+#define UV_VERSION_MINOR 44
+#define UV_VERSION_PATCH 2
+#define UV_VERSION_IS_RELEASE 1
+#define UV_VERSION_SUFFIX ""
+
+#define UV_VERSION_HEX  ((UV_VERSION_MAJOR << 16) | \
+                         (UV_VERSION_MINOR <<  8) | \
+                         (UV_VERSION_PATCH))
+
+#endif /* UV_VERSION_H */
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/include/uv/win.h b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/include/uv/win.h
new file mode 100644
index 0000000..0a33366
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/include/uv/win.h
@@ -0,0 +1,698 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#ifndef _WIN32_WINNT
+# define _WIN32_WINNT   0x0600
+#endif
+
+#if !defined(_SSIZE_T_) && !defined(_SSIZE_T_DEFINED)
+typedef intptr_t ssize_t;
+# define SSIZE_MAX INTPTR_MAX
+# define _SSIZE_T_
+# define _SSIZE_T_DEFINED
+#endif
+
+#include <winsock2.h>
+
+#if defined(__MINGW32__) && !defined(__MINGW64_VERSION_MAJOR)
+typedef struct pollfd {
+  SOCKET fd;
+  short  events;
+  short  revents;
+} WSAPOLLFD, *PWSAPOLLFD, *LPWSAPOLLFD;
+#endif
+
+#ifndef LOCALE_INVARIANT
+# define LOCALE_INVARIANT 0x007f
+#endif
+
+#include <mswsock.h>
+// Disable the typedef in mstcpip.h of MinGW.
+#define _TCP_INITIAL_RTO_PARAMETERS _TCP_INITIAL_RTO_PARAMETERS__AVOID
+#define TCP_INITIAL_RTO_PARAMETERS TCP_INITIAL_RTO_PARAMETERS__AVOID
+#define PTCP_INITIAL_RTO_PARAMETERS PTCP_INITIAL_RTO_PARAMETERS__AVOID
+#include <ws2tcpip.h>
+#undef _TCP_INITIAL_RTO_PARAMETERS
+#undef TCP_INITIAL_RTO_PARAMETERS
+#undef PTCP_INITIAL_RTO_PARAMETERS
+#include <windows.h>
+
+#include <process.h>
+#include <signal.h>
+#include <fcntl.h>
+#include <sys/stat.h>
+
+#include <stdint.h>
+
+#include "uv/tree.h"
+#include "uv/threadpool.h"
+
+#define MAX_PIPENAME_LEN 256
+
+#ifndef S_IFLNK
+# define S_IFLNK 0xA000
+#endif
+
+/* Additional signals supported by uv_signal and or uv_kill. The CRT defines
+ * the following signals already:
+ *
+ *   #define SIGINT           2
+ *   #define SIGILL           4
+ *   #define SIGABRT_COMPAT   6
+ *   #define SIGFPE           8
+ *   #define SIGSEGV         11
+ *   #define SIGTERM         15
+ *   #define SIGBREAK        21
+ *   #define SIGABRT         22
+ *
+ * The additional signals have values that are common on other Unix
+ * variants (Linux and Darwin)
+ */
+#define SIGHUP                1
+#define SIGKILL               9
+#define SIGWINCH             28
+
+/* Redefine NSIG to take SIGWINCH into consideration */
+#if defined(NSIG) && NSIG <= SIGWINCH
+# undef NSIG
+#endif
+#ifndef NSIG
+# define NSIG SIGWINCH + 1
+#endif
+
+/* The CRT defines SIGABRT_COMPAT as 6, which equals SIGABRT on many unix-like
+ * platforms. However MinGW doesn't define it, so we do. */
+#ifndef SIGABRT_COMPAT
+# define SIGABRT_COMPAT       6
+#endif
+
+/*
+ * Guids and typedefs for winsock extension functions
+ * Mingw32 doesn't have these :-(
+ */
+#ifndef WSAID_ACCEPTEX
+# define WSAID_ACCEPTEX                                                       \
+         {0xb5367df1, 0xcbac, 0x11cf,                                         \
+         {0x95, 0xca, 0x00, 0x80, 0x5f, 0x48, 0xa1, 0x92}}
+
+# define WSAID_CONNECTEX                                                      \
+         {0x25a207b9, 0xddf3, 0x4660,                                         \
+         {0x8e, 0xe9, 0x76, 0xe5, 0x8c, 0x74, 0x06, 0x3e}}
+
+# define WSAID_GETACCEPTEXSOCKADDRS                                           \
+         {0xb5367df2, 0xcbac, 0x11cf,                                         \
+         {0x95, 0xca, 0x00, 0x80, 0x5f, 0x48, 0xa1, 0x92}}
+
+# define WSAID_DISCONNECTEX                                                   \
+         {0x7fda2e11, 0x8630, 0x436f,                                         \
+         {0xa0, 0x31, 0xf5, 0x36, 0xa6, 0xee, 0xc1, 0x57}}
+
+# define WSAID_TRANSMITFILE                                                   \
+         {0xb5367df0, 0xcbac, 0x11cf,                                         \
+         {0x95, 0xca, 0x00, 0x80, 0x5f, 0x48, 0xa1, 0x92}}
+
+  typedef BOOL (PASCAL *LPFN_ACCEPTEX)
+                      (SOCKET sListenSocket,
+                       SOCKET sAcceptSocket,
+                       PVOID lpOutputBuffer,
+                       DWORD dwReceiveDataLength,
+                       DWORD dwLocalAddressLength,
+                       DWORD dwRemoteAddressLength,
+                       LPDWORD lpdwBytesReceived,
+                       LPOVERLAPPED lpOverlapped);
+
+  typedef BOOL (PASCAL *LPFN_CONNECTEX)
+                      (SOCKET s,
+                       const struct sockaddr* name,
+                       int namelen,
+                       PVOID lpSendBuffer,
+                       DWORD dwSendDataLength,
+                       LPDWORD lpdwBytesSent,
+                       LPOVERLAPPED lpOverlapped);
+
+  typedef void (PASCAL *LPFN_GETACCEPTEXSOCKADDRS)
+                      (PVOID lpOutputBuffer,
+                       DWORD dwReceiveDataLength,
+                       DWORD dwLocalAddressLength,
+                       DWORD dwRemoteAddressLength,
+                       LPSOCKADDR* LocalSockaddr,
+                       LPINT LocalSockaddrLength,
+                       LPSOCKADDR* RemoteSockaddr,
+                       LPINT RemoteSockaddrLength);
+
+  typedef BOOL (PASCAL *LPFN_DISCONNECTEX)
+                      (SOCKET hSocket,
+                       LPOVERLAPPED lpOverlapped,
+                       DWORD dwFlags,
+                       DWORD reserved);
+
+  typedef BOOL (PASCAL *LPFN_TRANSMITFILE)
+                      (SOCKET hSocket,
+                       HANDLE hFile,
+                       DWORD nNumberOfBytesToWrite,
+                       DWORD nNumberOfBytesPerSend,
+                       LPOVERLAPPED lpOverlapped,
+                       LPTRANSMIT_FILE_BUFFERS lpTransmitBuffers,
+                       DWORD dwFlags);
+
+  typedef PVOID RTL_SRWLOCK;
+  typedef RTL_SRWLOCK SRWLOCK, *PSRWLOCK;
+#endif
+
+typedef int (WSAAPI* LPFN_WSARECV)
+            (SOCKET socket,
+             LPWSABUF buffers,
+             DWORD buffer_count,
+             LPDWORD bytes,
+             LPDWORD flags,
+             LPWSAOVERLAPPED overlapped,
+             LPWSAOVERLAPPED_COMPLETION_ROUTINE completion_routine);
+
+typedef int (WSAAPI* LPFN_WSARECVFROM)
+            (SOCKET socket,
+             LPWSABUF buffers,
+             DWORD buffer_count,
+             LPDWORD bytes,
+             LPDWORD flags,
+             struct sockaddr* addr,
+             LPINT addr_len,
+             LPWSAOVERLAPPED overlapped,
+             LPWSAOVERLAPPED_COMPLETION_ROUTINE completion_routine);
+
+#pragma warning(push)
+#pragma warning(disable : 28251)
+
+#ifndef _NTDEF_
+  typedef LONG NTSTATUS;
+  typedef NTSTATUS *PNTSTATUS;
+#endif
+
+#pragma warning(pop)
+
+#ifndef RTL_CONDITION_VARIABLE_INIT
+  typedef PVOID CONDITION_VARIABLE, *PCONDITION_VARIABLE;
+#endif
+
+typedef struct _AFD_POLL_HANDLE_INFO {
+  HANDLE Handle;
+  ULONG Events;
+  NTSTATUS Status;
+} AFD_POLL_HANDLE_INFO, *PAFD_POLL_HANDLE_INFO;
+
+typedef struct _AFD_POLL_INFO {
+  LARGE_INTEGER Timeout;
+  ULONG NumberOfHandles;
+  ULONG Exclusive;
+  AFD_POLL_HANDLE_INFO Handles[1];
+} AFD_POLL_INFO, *PAFD_POLL_INFO;
+
+#define UV_MSAFD_PROVIDER_COUNT 4
+
+
+/**
+ * It should be possible to cast uv_buf_t[] to WSABUF[]
+ * see http://msdn.microsoft.com/en-us/library/ms741542(v=vs.85).aspx
+ */
+typedef struct uv_buf_t {
+  ULONG len;
+  char* base;
+} uv_buf_t;
+
+typedef int uv_file;
+typedef SOCKET uv_os_sock_t;
+typedef HANDLE uv_os_fd_t;
+typedef int uv_pid_t;
+
+typedef HANDLE uv_thread_t;
+
+typedef HANDLE uv_sem_t;
+
+typedef CRITICAL_SECTION uv_mutex_t;
+
+/* This condition variable implementation is based on the SetEvent solution
+ * (section 3.2) at http://www.cs.wustl.edu/~schmidt/win32-cv-1.html
+ * We could not use the SignalObjectAndWait solution (section 3.4) because
+ * it want the 2nd argument (type uv_mutex_t) of uv_cond_wait() and
+ * uv_cond_timedwait() to be HANDLEs, but we use CRITICAL_SECTIONs.
+ */
+
+typedef union {
+  CONDITION_VARIABLE cond_var;
+  struct {
+    unsigned int waiters_count;
+    CRITICAL_SECTION waiters_count_lock;
+    HANDLE signal_event;
+    HANDLE broadcast_event;
+  } unused_; /* TODO: retained for ABI compatibility; remove me in v2.x. */
+} uv_cond_t;
+
+typedef struct {
+  SRWLOCK read_write_lock_;
+  /* TODO: retained for ABI compatibility; remove me in v2.x */
+#ifdef _WIN64
+  unsigned char padding_[72];
+#else
+  unsigned char padding_[44];
+#endif
+} uv_rwlock_t;
+
+typedef struct {
+  unsigned int n;
+  unsigned int count;
+  uv_mutex_t mutex;
+  uv_sem_t turnstile1;
+  uv_sem_t turnstile2;
+} uv_barrier_t;
+
+typedef struct {
+  DWORD tls_index;
+} uv_key_t;
+
+#define UV_ONCE_INIT { 0, NULL }
+
+typedef struct uv_once_s {
+  unsigned char ran;
+  HANDLE event;
+} uv_once_t;
+
+/* Platform-specific definitions for uv_spawn support. */
+typedef unsigned char uv_uid_t;
+typedef unsigned char uv_gid_t;
+
+typedef struct uv__dirent_s {
+  int d_type;
+  char d_name[1];
+} uv__dirent_t;
+
+#define UV_DIR_PRIVATE_FIELDS \
+  HANDLE dir_handle;          \
+  WIN32_FIND_DATAW find_data; \
+  BOOL need_find_call;
+
+#define HAVE_DIRENT_TYPES
+#define UV__DT_DIR     UV_DIRENT_DIR
+#define UV__DT_FILE    UV_DIRENT_FILE
+#define UV__DT_LINK    UV_DIRENT_LINK
+#define UV__DT_FIFO    UV_DIRENT_FIFO
+#define UV__DT_SOCKET  UV_DIRENT_SOCKET
+#define UV__DT_CHAR    UV_DIRENT_CHAR
+#define UV__DT_BLOCK   UV_DIRENT_BLOCK
+
+/* Platform-specific definitions for uv_dlopen support. */
+#define UV_DYNAMIC FAR WINAPI
+typedef struct {
+  HMODULE handle;
+  char* errmsg;
+} uv_lib_t;
+
+#define UV_LOOP_PRIVATE_FIELDS                                                \
+    /* The loop's I/O completion port */                                      \
+  HANDLE iocp;                                                                \
+  /* The current time according to the event loop. in msecs. */               \
+  uint64_t time;                                                              \
+  /* Tail of a single-linked circular queue of pending reqs. If the queue */  \
+  /* is empty, tail_ is NULL. If there is only one item, */                   \
+  /* tail_->next_req == tail_ */                                              \
+  uv_req_t* pending_reqs_tail;                                                \
+  /* Head of a single-linked list of closed handles */                        \
+  uv_handle_t* endgame_handles;                                               \
+  /* TODO(bnoordhuis) Stop heap-allocating |timer_heap| in libuv v2.x. */     \
+  void* timer_heap;                                                           \
+    /* Lists of active loop (prepare / check / idle) watchers */              \
+  uv_prepare_t* prepare_handles;                                              \
+  uv_check_t* check_handles;                                                  \
+  uv_idle_t* idle_handles;                                                    \
+  /* This pointer will refer to the prepare/check/idle handle whose */        \
+  /* callback is scheduled to be called next. This is needed to allow */      \
+  /* safe removal from one of the lists above while that list being */        \
+  /* iterated over. */                                                        \
+  uv_prepare_t* next_prepare_handle;                                          \
+  uv_check_t* next_check_handle;                                              \
+  uv_idle_t* next_idle_handle;                                                \
+  /* This handle holds the peer sockets for the fast variant of uv_poll_t */  \
+  SOCKET poll_peer_sockets[UV_MSAFD_PROVIDER_COUNT];                          \
+  /* Counter to keep track of active tcp streams */                           \
+  unsigned int active_tcp_streams;                                            \
+  /* Counter to keep track of active udp streams */                           \
+  unsigned int active_udp_streams;                                            \
+  /* Counter to started timer */                                              \
+  uint64_t timer_counter;                                                     \
+  /* Threadpool */                                                            \
+  void* wq[2];                                                                \
+  uv_mutex_t wq_mutex;                                                        \
+  uv_async_t wq_async;
+
+#define UV_REQ_TYPE_PRIVATE                                                   \
+  /* TODO: remove the req suffix */                                           \
+  UV_ACCEPT,                                                                  \
+  UV_FS_EVENT_REQ,                                                            \
+  UV_POLL_REQ,                                                                \
+  UV_PROCESS_EXIT,                                                            \
+  UV_READ,                                                                    \
+  UV_UDP_RECV,                                                                \
+  UV_WAKEUP,                                                                  \
+  UV_SIGNAL_REQ,
+
+#define UV_REQ_PRIVATE_FIELDS                                                 \
+  union {                                                                     \
+    /* Used by I/O operations */                                              \
+    struct {                                                                  \
+      OVERLAPPED overlapped;                                                  \
+      size_t queued_bytes;                                                    \
+    } io;                                                                     \
+    /* in v2, we can move these to the UV_CONNECT_PRIVATE_FIELDS */           \
+    struct {                                                                  \
+      ULONG_PTR result; /* overlapped.Internal is reused to hold the result */\
+      HANDLE pipeHandle;                                                      \
+      DWORD duplex_flags;                                                     \
+    } connect;                                                                \
+  } u;                                                                        \
+  struct uv_req_s* next_req;
+
+#define UV_WRITE_PRIVATE_FIELDS \
+  int coalesced;                \
+  uv_buf_t write_buffer;        \
+  HANDLE event_handle;          \
+  HANDLE wait_handle;
+
+#define UV_CONNECT_PRIVATE_FIELDS                                             \
+  /* empty */
+
+#define UV_SHUTDOWN_PRIVATE_FIELDS                                            \
+  /* empty */
+
+#define UV_UDP_SEND_PRIVATE_FIELDS                                            \
+  /* empty */
+
+#define UV_PRIVATE_REQ_TYPES                                                  \
+  typedef struct uv_pipe_accept_s {                                           \
+    UV_REQ_FIELDS                                                             \
+    HANDLE pipeHandle;                                                        \
+    struct uv_pipe_accept_s* next_pending;                                    \
+  } uv_pipe_accept_t;                                                         \
+                                                                              \
+  typedef struct uv_tcp_accept_s {                                            \
+    UV_REQ_FIELDS                                                             \
+    SOCKET accept_socket;                                                     \
+    char accept_buffer[sizeof(struct sockaddr_storage) * 2 + 32];             \
+    HANDLE event_handle;                                                      \
+    HANDLE wait_handle;                                                       \
+    struct uv_tcp_accept_s* next_pending;                                     \
+  } uv_tcp_accept_t;                                                          \
+                                                                              \
+  typedef struct uv_read_s {                                                  \
+    UV_REQ_FIELDS                                                             \
+    HANDLE event_handle;                                                      \
+    HANDLE wait_handle;                                                       \
+  } uv_read_t;
+
+#define uv_stream_connection_fields                                           \
+  unsigned int write_reqs_pending;                                            \
+  uv_shutdown_t* shutdown_req;
+
+#define uv_stream_server_fields                                               \
+  uv_connection_cb connection_cb;
+
+#define UV_STREAM_PRIVATE_FIELDS                                              \
+  unsigned int reqs_pending;                                                  \
+  int activecnt;                                                              \
+  uv_read_t read_req;                                                         \
+  union {                                                                     \
+    struct { uv_stream_connection_fields } conn;                              \
+    struct { uv_stream_server_fields     } serv;                              \
+  } stream;
+
+#define uv_tcp_server_fields                                                  \
+  uv_tcp_accept_t* accept_reqs;                                               \
+  unsigned int processed_accepts;                                             \
+  uv_tcp_accept_t* pending_accepts;                                           \
+  LPFN_ACCEPTEX func_acceptex;
+
+#define uv_tcp_connection_fields                                              \
+  uv_buf_t read_buffer;                                                       \
+  LPFN_CONNECTEX func_connectex;
+
+#define UV_TCP_PRIVATE_FIELDS                                                 \
+  SOCKET socket;                                                              \
+  int delayed_error;                                                          \
+  union {                                                                     \
+    struct { uv_tcp_server_fields } serv;                                     \
+    struct { uv_tcp_connection_fields } conn;                                 \
+  } tcp;
+
+#define UV_UDP_PRIVATE_FIELDS                                                 \
+  SOCKET socket;                                                              \
+  unsigned int reqs_pending;                                                  \
+  int activecnt;                                                              \
+  uv_req_t recv_req;                                                          \
+  uv_buf_t recv_buffer;                                                       \
+  struct sockaddr_storage recv_from;                                          \
+  int recv_from_len;                                                          \
+  uv_udp_recv_cb recv_cb;                                                     \
+  uv_alloc_cb alloc_cb;                                                       \
+  LPFN_WSARECV func_wsarecv;                                                  \
+  LPFN_WSARECVFROM func_wsarecvfrom;
+
+#define uv_pipe_server_fields                                                 \
+  int pending_instances;                                                      \
+  uv_pipe_accept_t* accept_reqs;                                              \
+  uv_pipe_accept_t* pending_accepts;
+
+#define uv_pipe_connection_fields                                             \
+  uv_timer_t* eof_timer;                                                      \
+  uv_write_t dummy; /* TODO: retained for ABI compat; remove this in v2.x. */ \
+  DWORD ipc_remote_pid;                                                       \
+  union {                                                                     \
+    uint32_t payload_remaining;                                               \
+    uint64_t dummy; /* TODO: retained for ABI compat; remove this in v2.x. */ \
+  } ipc_data_frame;                                                           \
+  void* ipc_xfer_queue[2];                                                    \
+  int ipc_xfer_queue_length;                                                  \
+  uv_write_t* non_overlapped_writes_tail;                                     \
+  CRITICAL_SECTION readfile_thread_lock;                                      \
+  volatile HANDLE readfile_thread_handle;
+
+#define UV_PIPE_PRIVATE_FIELDS                                                \
+  HANDLE handle;                                                              \
+  WCHAR* name;                                                                \
+  union {                                                                     \
+    struct { uv_pipe_server_fields } serv;                                    \
+    struct { uv_pipe_connection_fields } conn;                                \
+  } pipe;
+
+/* TODO: put the parser states in an union - TTY handles are always half-duplex
+ * so read-state can safely overlap write-state. */
+#define UV_TTY_PRIVATE_FIELDS                                                 \
+  HANDLE handle;                                                              \
+  union {                                                                     \
+    struct {                                                                  \
+      /* Used for readable TTY handles */                                     \
+      /* TODO: remove me in v2.x. */                                          \
+      HANDLE unused_;                                                         \
+      uv_buf_t read_line_buffer;                                              \
+      HANDLE read_raw_wait;                                                   \
+      /* Fields used for translating win keystrokes into vt100 characters */  \
+      char last_key[8];                                                       \
+      unsigned char last_key_offset;                                          \
+      unsigned char last_key_len;                                             \
+      WCHAR last_utf16_high_surrogate;                                        \
+      INPUT_RECORD last_input_record;                                         \
+    } rd;                                                                     \
+    struct {                                                                  \
+      /* Used for writable TTY handles */                                     \
+      /* utf8-to-utf16 conversion state */                                    \
+      unsigned int utf8_codepoint;                                            \
+      unsigned char utf8_bytes_left;                                          \
+      /* eol conversion state */                                              \
+      unsigned char previous_eol;                                             \
+      /* ansi parser state */                                                 \
+      unsigned short ansi_parser_state;                                       \
+      unsigned char ansi_csi_argc;                                            \
+      unsigned short ansi_csi_argv[4];                                        \
+      COORD saved_position;                                                   \
+      WORD saved_attributes;                                                  \
+    } wr;                                                                     \
+  } tty;
+
+#define UV_POLL_PRIVATE_FIELDS                                                \
+  SOCKET socket;                                                              \
+  /* Used in fast mode */                                                     \
+  SOCKET peer_socket;                                                         \
+  AFD_POLL_INFO afd_poll_info_1;                                              \
+  AFD_POLL_INFO afd_poll_info_2;                                              \
+  /* Used in fast and slow mode. */                                           \
+  uv_req_t poll_req_1;                                                        \
+  uv_req_t poll_req_2;                                                        \
+  unsigned char submitted_events_1;                                           \
+  unsigned char submitted_events_2;                                           \
+  unsigned char mask_events_1;                                                \
+  unsigned char mask_events_2;                                                \
+  unsigned char events;
+
+#define UV_TIMER_PRIVATE_FIELDS                                               \
+  void* heap_node[3];                                                         \
+  int unused;                                                                 \
+  uint64_t timeout;                                                           \
+  uint64_t repeat;                                                            \
+  uint64_t start_id;                                                          \
+  uv_timer_cb timer_cb;
+
+#define UV_ASYNC_PRIVATE_FIELDS                                               \
+  struct uv_req_s async_req;                                                  \
+  uv_async_cb async_cb;                                                       \
+  /* char to avoid alignment issues */                                        \
+  char volatile async_sent;
+
+#define UV_PREPARE_PRIVATE_FIELDS                                             \
+  uv_prepare_t* prepare_prev;                                                 \
+  uv_prepare_t* prepare_next;                                                 \
+  uv_prepare_cb prepare_cb;
+
+#define UV_CHECK_PRIVATE_FIELDS                                               \
+  uv_check_t* check_prev;                                                     \
+  uv_check_t* check_next;                                                     \
+  uv_check_cb check_cb;
+
+#define UV_IDLE_PRIVATE_FIELDS                                                \
+  uv_idle_t* idle_prev;                                                       \
+  uv_idle_t* idle_next;                                                       \
+  uv_idle_cb idle_cb;
+
+#define UV_HANDLE_PRIVATE_FIELDS                                              \
+  uv_handle_t* endgame_next;                                                  \
+  unsigned int flags;
+
+#define UV_GETADDRINFO_PRIVATE_FIELDS                                         \
+  struct uv__work work_req;                                                   \
+  uv_getaddrinfo_cb getaddrinfo_cb;                                           \
+  void* alloc;                                                                \
+  WCHAR* node;                                                                \
+  WCHAR* service;                                                             \
+  /* The addrinfoW field is used to store a pointer to the hints, and    */   \
+  /* later on to store the result of GetAddrInfoW. The final result will */   \
+  /* be converted to struct addrinfo* and stored in the addrinfo field.  */   \
+  struct addrinfoW* addrinfow;                                                \
+  struct addrinfo* addrinfo;                                                  \
+  int retcode;
+
+#define UV_GETNAMEINFO_PRIVATE_FIELDS                                         \
+  struct uv__work work_req;                                                   \
+  uv_getnameinfo_cb getnameinfo_cb;                                           \
+  struct sockaddr_storage storage;                                            \
+  int flags;                                                                  \
+  char host[NI_MAXHOST];                                                      \
+  char service[NI_MAXSERV];                                                   \
+  int retcode;
+
+#define UV_PROCESS_PRIVATE_FIELDS                                             \
+  struct uv_process_exit_s {                                                  \
+    UV_REQ_FIELDS                                                             \
+  } exit_req;                                                                 \
+  BYTE* child_stdio_buffer;                                                   \
+  int exit_signal;                                                            \
+  HANDLE wait_handle;                                                         \
+  HANDLE process_handle;                                                      \
+  volatile char exit_cb_pending;
+
+#define UV_FS_PRIVATE_FIELDS                                                  \
+  struct uv__work work_req;                                                   \
+  int flags;                                                                  \
+  DWORD sys_errno_;                                                           \
+  union {                                                                     \
+    /* TODO: remove me in 0.9. */                                             \
+    WCHAR* pathw;                                                             \
+    int fd;                                                                   \
+  } file;                                                                     \
+  union {                                                                     \
+    struct {                                                                  \
+      int mode;                                                               \
+      WCHAR* new_pathw;                                                       \
+      int file_flags;                                                         \
+      int fd_out;                                                             \
+      unsigned int nbufs;                                                     \
+      uv_buf_t* bufs;                                                         \
+      int64_t offset;                                                         \
+      uv_buf_t bufsml[4];                                                     \
+    } info;                                                                   \
+    struct {                                                                  \
+      double atime;                                                           \
+      double mtime;                                                           \
+    } time;                                                                   \
+  } fs;
+
+#define UV_WORK_PRIVATE_FIELDS                                                \
+  struct uv__work work_req;
+
+#define UV_FS_EVENT_PRIVATE_FIELDS                                            \
+  struct uv_fs_event_req_s {                                                  \
+    UV_REQ_FIELDS                                                             \
+  } req;                                                                      \
+  HANDLE dir_handle;                                                          \
+  int req_pending;                                                            \
+  uv_fs_event_cb cb;                                                          \
+  WCHAR* filew;                                                               \
+  WCHAR* short_filew;                                                         \
+  WCHAR* dirw;                                                                \
+  char* buffer;
+
+#define UV_SIGNAL_PRIVATE_FIELDS                                              \
+  RB_ENTRY(uv_signal_s) tree_entry;                                           \
+  struct uv_req_s signal_req;                                                 \
+  unsigned long pending_signum;
+
+#ifndef F_OK
+#define F_OK 0
+#endif
+#ifndef R_OK
+#define R_OK 4
+#endif
+#ifndef W_OK
+#define W_OK 2
+#endif
+#ifndef X_OK
+#define X_OK 1
+#endif
+
+/* fs open() flags supported on this platform: */
+#define UV_FS_O_APPEND       _O_APPEND
+#define UV_FS_O_CREAT        _O_CREAT
+#define UV_FS_O_EXCL         _O_EXCL
+#define UV_FS_O_FILEMAP      0x20000000
+#define UV_FS_O_RANDOM       _O_RANDOM
+#define UV_FS_O_RDONLY       _O_RDONLY
+#define UV_FS_O_RDWR         _O_RDWR
+#define UV_FS_O_SEQUENTIAL   _O_SEQUENTIAL
+#define UV_FS_O_SHORT_LIVED  _O_SHORT_LIVED
+#define UV_FS_O_TEMPORARY    _O_TEMPORARY
+#define UV_FS_O_TRUNC        _O_TRUNC
+#define UV_FS_O_WRONLY       _O_WRONLY
+
+/* fs open() flags supported on other platforms (or mapped on this platform): */
+#define UV_FS_O_DIRECT       0x02000000 /* FILE_FLAG_NO_BUFFERING */
+#define UV_FS_O_DIRECTORY    0
+#define UV_FS_O_DSYNC        0x04000000 /* FILE_FLAG_WRITE_THROUGH */
+#define UV_FS_O_EXLOCK       0x10000000 /* EXCLUSIVE SHARING MODE */
+#define UV_FS_O_NOATIME      0
+#define UV_FS_O_NOCTTY       0
+#define UV_FS_O_NOFOLLOW     0
+#define UV_FS_O_NONBLOCK     0
+#define UV_FS_O_SYMLINK      0
+#define UV_FS_O_SYNC         0x08000000 /* FILE_FLAG_WRITE_THROUGH */
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/fs-poll.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/fs-poll.cpp
new file mode 100644
index 0000000..1a7ca70
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/fs-poll.cpp
@@ -0,0 +1,288 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "uv-common.h"
+
+#ifdef _WIN32
+#include "win/internal.h"
+#include "win/handle-inl.h"
+#define uv__make_close_pending(h) uv__want_endgame((h)->loop, (h))
+#else
+#include "unix/internal.h"
+#endif
+
+#include <assert.h>
+#include <stdlib.h>
+#include <string.h>
+
+
+struct poll_ctx {
+  uv_fs_poll_t* parent_handle;
+  int busy_polling;
+  unsigned int interval;
+  uint64_t start_time;
+  uv_loop_t* loop;
+  uv_fs_poll_cb poll_cb;
+  uv_timer_t timer_handle;
+  uv_fs_t fs_req; /* TODO(bnoordhuis) mark fs_req internal */
+  uv_stat_t statbuf;
+  struct poll_ctx* previous; /* context from previous start()..stop() period */
+  char path[1]; /* variable length */
+};
+
+static int statbuf_eq(const uv_stat_t* a, const uv_stat_t* b);
+static void poll_cb(uv_fs_t* req);
+static void timer_cb(uv_timer_t* timer);
+static void timer_close_cb(uv_handle_t* handle);
+
+static uv_stat_t zero_statbuf;
+
+
+int uv_fs_poll_init(uv_loop_t* loop, uv_fs_poll_t* handle) {
+  uv__handle_init(loop, (uv_handle_t*)handle, UV_FS_POLL);
+  handle->poll_ctx = NULL;
+  return 0;
+}
+
+
+int uv_fs_poll_start(uv_fs_poll_t* handle,
+                     uv_fs_poll_cb cb,
+                     const char* path,
+                     unsigned int interval) {
+  struct poll_ctx* ctx;
+  uv_loop_t* loop;
+  size_t len;
+  int err;
+
+  if (uv_is_active((uv_handle_t*)handle))
+    return 0;
+
+  loop = handle->loop;
+  len = strlen(path);
+  ctx = (struct poll_ctx*)uv__calloc(1, sizeof(*ctx) + len);
+
+  if (ctx == NULL)
+    return UV_ENOMEM;
+
+  ctx->loop = loop;
+  ctx->poll_cb = cb;
+  ctx->interval = interval ? interval : 1;
+  ctx->start_time = uv_now(loop);
+  ctx->parent_handle = handle;
+  memcpy(ctx->path, path, len + 1);
+
+  err = uv_timer_init(loop, &ctx->timer_handle);
+  if (err < 0)
+    goto error;
+
+  ctx->timer_handle.flags |= UV_HANDLE_INTERNAL;
+  uv__handle_unref(&ctx->timer_handle);
+
+  err = uv_fs_stat(loop, &ctx->fs_req, ctx->path, poll_cb);
+  if (err < 0)
+    goto error;
+
+  if (handle->poll_ctx != NULL)
+    ctx->previous = (struct poll_ctx*)handle->poll_ctx;
+  handle->poll_ctx = ctx;
+  uv__handle_start(handle);
+
+  return 0;
+
+error:
+  uv__free(ctx);
+  return err;
+}
+
+
+int uv_fs_poll_stop(uv_fs_poll_t* handle) {
+  struct poll_ctx* ctx;
+
+  if (!uv_is_active((uv_handle_t*)handle))
+    return 0;
+
+  ctx = (struct poll_ctx*)handle->poll_ctx;
+  assert(ctx != NULL);
+  assert(ctx->parent_handle == handle);
+
+  /* Close the timer if it's active. If it's inactive, there's a stat request
+   * in progress and poll_cb will take care of the cleanup.
+   */
+  if (uv_is_active((uv_handle_t*)&ctx->timer_handle))
+    uv_close((uv_handle_t*)&ctx->timer_handle, timer_close_cb);
+
+  uv__handle_stop(handle);
+
+  return 0;
+}
+
+
+int uv_fs_poll_getpath(uv_fs_poll_t* handle, char* buffer, size_t* size) {
+  struct poll_ctx* ctx;
+  size_t required_len;
+
+  if (!uv_is_active((uv_handle_t*)handle)) {
+    *size = 0;
+    return UV_EINVAL;
+  }
+
+  ctx = (struct poll_ctx*)handle->poll_ctx;
+  assert(ctx != NULL);
+
+  required_len = strlen(ctx->path);
+  if (required_len >= *size) {
+    *size = required_len + 1;
+    return UV_ENOBUFS;
+  }
+
+  memcpy(buffer, ctx->path, required_len);
+  *size = required_len;
+  buffer[required_len] = '\0';
+
+  return 0;
+}
+
+
+void uv__fs_poll_close(uv_fs_poll_t* handle) {
+  uv_fs_poll_stop(handle);
+
+  if (handle->poll_ctx == NULL)
+    uv__make_close_pending((uv_handle_t*)handle);
+}
+
+
+static void timer_cb(uv_timer_t* timer) {
+  struct poll_ctx* ctx;
+
+  ctx = container_of(timer, struct poll_ctx, timer_handle);
+  assert(ctx->parent_handle != NULL);
+  assert(ctx->parent_handle->poll_ctx == ctx);
+  ctx->start_time = uv_now(ctx->loop);
+
+  if (uv_fs_stat(ctx->loop, &ctx->fs_req, ctx->path, poll_cb))
+    abort();
+}
+
+
+static void poll_cb(uv_fs_t* req) {
+  uv_stat_t* statbuf;
+  struct poll_ctx* ctx;
+  uint64_t interval;
+  uv_fs_poll_t* handle;
+
+  ctx = container_of(req, struct poll_ctx, fs_req);
+  handle = ctx->parent_handle;
+
+  if (!uv_is_active((uv_handle_t*)handle) || uv__is_closing(handle))
+    goto out;
+
+  if (req->result != 0) {
+    if (ctx->busy_polling != req->result) {
+      ctx->poll_cb(ctx->parent_handle,
+                   req->result,
+                   &ctx->statbuf,
+                   &zero_statbuf);
+      ctx->busy_polling = req->result;
+    }
+    goto out;
+  }
+
+  statbuf = &req->statbuf;
+
+  if (ctx->busy_polling != 0)
+    if (ctx->busy_polling < 0 || !statbuf_eq(&ctx->statbuf, statbuf))
+      ctx->poll_cb(ctx->parent_handle, 0, &ctx->statbuf, statbuf);
+
+  ctx->statbuf = *statbuf;
+  ctx->busy_polling = 1;
+
+out:
+  uv_fs_req_cleanup(req);
+
+  if (!uv_is_active((uv_handle_t*)handle) || uv__is_closing(handle)) {
+    uv_close((uv_handle_t*)&ctx->timer_handle, timer_close_cb);
+    return;
+  }
+
+  /* Reschedule timer, subtract the delay from doing the stat(). */
+  interval = ctx->interval;
+  interval -= (uv_now(ctx->loop) - ctx->start_time) % interval;
+
+  if (uv_timer_start(&ctx->timer_handle, timer_cb, interval, 0))
+    abort();
+}
+
+
+static void timer_close_cb(uv_handle_t* timer) {
+  struct poll_ctx* ctx;
+  struct poll_ctx* it;
+  struct poll_ctx* last;
+  uv_fs_poll_t* handle;
+
+  ctx = container_of(timer, struct poll_ctx, timer_handle);
+  handle = ctx->parent_handle;
+  if (ctx == handle->poll_ctx) {
+    handle->poll_ctx = ctx->previous;
+    if (handle->poll_ctx == NULL && uv__is_closing(handle))
+      uv__make_close_pending((uv_handle_t*)handle);
+  } else {
+    for (last = (struct poll_ctx*)handle->poll_ctx, it = last->previous;
+         it != ctx;
+         last = it, it = it->previous) {
+      assert(last->previous != NULL);
+    }
+    last->previous = ctx->previous;
+  }
+  uv__free(ctx);
+}
+
+
+static int statbuf_eq(const uv_stat_t* a, const uv_stat_t* b) {
+  return a->st_ctim.tv_nsec == b->st_ctim.tv_nsec
+      && a->st_mtim.tv_nsec == b->st_mtim.tv_nsec
+      && a->st_birthtim.tv_nsec == b->st_birthtim.tv_nsec
+      && a->st_ctim.tv_sec == b->st_ctim.tv_sec
+      && a->st_mtim.tv_sec == b->st_mtim.tv_sec
+      && a->st_birthtim.tv_sec == b->st_birthtim.tv_sec
+      && a->st_size == b->st_size
+      && a->st_mode == b->st_mode
+      && a->st_uid == b->st_uid
+      && a->st_gid == b->st_gid
+      && a->st_ino == b->st_ino
+      && a->st_dev == b->st_dev
+      && a->st_flags == b->st_flags
+      && a->st_gen == b->st_gen;
+}
+
+
+#if defined(_WIN32)
+
+#include "win/internal.h"
+#include "win/handle-inl.h"
+
+void uv__fs_poll_endgame(uv_loop_t* loop, uv_fs_poll_t* handle) {
+  assert(handle->flags & UV_HANDLE_CLOSING);
+  assert(!(handle->flags & UV_HANDLE_CLOSED));
+  uv__handle_close(handle);
+}
+
+#endif /* _WIN32 */
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/heap-inl.h b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/heap-inl.h
similarity index 100%
rename from third_party/allwpilib/wpiutil/src/main/native/libuv/src/heap-inl.h
rename to third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/heap-inl.h
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/idna.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/idna.cpp
new file mode 100644
index 0000000..36a39a0
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/idna.cpp
@@ -0,0 +1,315 @@
+/* Copyright (c) 2011, 2018 Ben Noordhuis <info@bnoordhuis.nl>
+ *
+ * Permission to use, copy, modify, and/or distribute this software for any
+ * purpose with or without fee is hereby granted, provided that the above
+ * copyright notice and this permission notice appear in all copies.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
+ * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
+ * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
+ * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
+ * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
+ * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
+ * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
+ */
+
+/* Derived from https://github.com/bnoordhuis/punycode
+ * but updated to support IDNA 2008.
+ */
+
+#include "uv.h"
+#include "idna.h"
+#include <assert.h>
+#include <string.h>
+#include <limits.h> /* UINT_MAX */
+
+static unsigned uv__utf8_decode1_slow(const char** p,
+                                      const char* pe,
+                                      unsigned a) {
+  unsigned b;
+  unsigned c;
+  unsigned d;
+  unsigned min;
+
+  if (a > 0xF7)
+    return -1;
+
+  switch (pe - *p) {
+  default:
+    if (a > 0xEF) {
+      min = 0x10000;
+      a = a & 7;
+      b = (unsigned char) *(*p)++;
+      c = (unsigned char) *(*p)++;
+      d = (unsigned char) *(*p)++;
+      break;
+    }
+    /* Fall through. */
+  case 2:
+    if (a > 0xDF) {
+      min = 0x800;
+      b = 0x80 | (a & 15);
+      c = (unsigned char) *(*p)++;
+      d = (unsigned char) *(*p)++;
+      a = 0;
+      break;
+    }
+    /* Fall through. */
+  case 1:
+    if (a > 0xBF) {
+      min = 0x80;
+      b = 0x80;
+      c = 0x80 | (a & 31);
+      d = (unsigned char) *(*p)++;
+      a = 0;
+      break;
+    }
+    /* Fall through. */
+  case 0:
+    return -1;  /* Invalid continuation byte. */
+  }
+
+  if (0x80 != (0xC0 & (b ^ c ^ d)))
+    return -1;  /* Invalid sequence. */
+
+  b &= 63;
+  c &= 63;
+  d &= 63;
+  a = (a << 18) | (b << 12) | (c << 6) | d;
+
+  if (a < min)
+    return -1;  /* Overlong sequence. */
+
+  if (a > 0x10FFFF)
+    return -1;  /* Four-byte sequence > U+10FFFF. */
+
+  if (a >= 0xD800 && a <= 0xDFFF)
+    return -1;  /* Surrogate pair. */
+
+  return a;
+}
+
+unsigned uv__utf8_decode1(const char** p, const char* pe) {
+  unsigned a;
+
+  assert(*p < pe);
+
+  a = (unsigned char) *(*p)++;
+
+  if (a < 128)
+    return a;  /* ASCII, common case. */
+
+  return uv__utf8_decode1_slow(p, pe, a);
+}
+
+static int uv__idna_toascii_label(const char* s, const char* se,
+                                  char** d, char* de) {
+  static const char alphabet[] = "abcdefghijklmnopqrstuvwxyz0123456789";
+  const char* ss;
+  unsigned c = 0;
+  unsigned h;
+  unsigned k;
+  unsigned n;
+  unsigned m;
+  unsigned q;
+  unsigned t;
+  unsigned x;
+  unsigned y;
+  unsigned bias;
+  unsigned delta;
+  unsigned todo;
+  int first;
+
+  h = 0;
+  ss = s;
+  todo = 0;
+
+  /* Note: after this loop we've visited all UTF-8 characters and know
+   * they're legal so we no longer need to check for decode errors.
+   */
+  while (s < se) {
+    c = uv__utf8_decode1(&s, se);
+
+    if (c == UINT_MAX)
+      return UV_EINVAL;
+
+    if (c < 128)
+      h++;
+    else
+      todo++;
+  }
+
+  /* Only write "xn--" when there are non-ASCII characters. */
+  if (todo > 0) {
+    if (*d < de) *(*d)++ = 'x';
+    if (*d < de) *(*d)++ = 'n';
+    if (*d < de) *(*d)++ = '-';
+    if (*d < de) *(*d)++ = '-';
+  }
+
+  /* Write ASCII characters. */
+  x = 0;
+  s = ss;
+  while (s < se) {
+    c = uv__utf8_decode1(&s, se);
+    assert(c != UINT_MAX);
+
+    if (c > 127)
+      continue;
+
+    if (*d < de)
+      *(*d)++ = c;
+
+    if (++x == h)
+      break;  /* Visited all ASCII characters. */
+  }
+
+  if (todo == 0)
+    return h;
+
+  /* Only write separator when we've written ASCII characters first. */
+  if (h > 0)
+    if (*d < de)
+      *(*d)++ = '-';
+
+  n = 128;
+  bias = 72;
+  delta = 0;
+  first = 1;
+
+  while (todo > 0) {
+    m = -1;
+    s = ss;
+
+    while (s < se) {
+      c = uv__utf8_decode1(&s, se);
+      assert(c != UINT_MAX);
+
+      if (c >= n)
+        if (c < m)
+          m = c;
+    }
+
+    x = m - n;
+    y = h + 1;
+
+    if (x > ~delta / y)
+      return UV_E2BIG;  /* Overflow. */
+
+    delta += x * y;
+    n = m;
+
+    s = ss;
+    while (s < se) {
+      c = uv__utf8_decode1(&s, se);
+      assert(c != UINT_MAX);
+
+      if (c < n)
+        if (++delta == 0)
+          return UV_E2BIG;  /* Overflow. */
+
+      if (c != n)
+        continue;
+
+      for (k = 36, q = delta; /* empty */; k += 36) {
+        t = 1;
+
+        if (k > bias)
+          t = k - bias;
+
+        if (t > 26)
+          t = 26;
+
+        if (q < t)
+          break;
+
+        /* TODO(bnoordhuis) Since 1 <= t <= 26 and therefore
+         * 10 <= y <= 35, we can optimize the long division
+         * into a table-based reciprocal multiplication.
+         */
+        x = q - t;
+        y = 36 - t;  /* 10 <= y <= 35 since 1 <= t <= 26. */
+        q = x / y;
+        t = t + x % y;  /* 1 <= t <= 35 because of y. */
+
+        if (*d < de)
+          *(*d)++ = alphabet[t];
+      }
+
+      if (*d < de)
+        *(*d)++ = alphabet[q];
+
+      delta /= 2;
+
+      if (first) {
+        delta /= 350;
+        first = 0;
+      }
+
+      /* No overflow check is needed because |delta| was just
+       * divided by 2 and |delta+delta >= delta + delta/h|.
+       */
+      h++;
+      delta += delta / h;
+
+      for (bias = 0; delta > 35 * 26 / 2; bias += 36)
+        delta /= 35;
+
+      bias += 36 * delta / (delta + 38);
+      delta = 0;
+      todo--;
+    }
+
+    delta++;
+    n++;
+  }
+
+  return 0;
+}
+
+long uv__idna_toascii(const char* s, const char* se, char* d, char* de) {
+  const char* si;
+  const char* st;
+  unsigned c;
+  char* ds;
+  int rc;
+
+  ds = d;
+
+  si = s;
+  while (si < se) {
+    st = si;
+    c = uv__utf8_decode1(&si, se);
+
+    if (c == UINT_MAX)
+      return UV_EINVAL;
+
+    if (c != '.')
+      if (c != 0x3002)  /* 。 */
+        if (c != 0xFF0E)  /* . */
+          if (c != 0xFF61)  /* 。 */
+            continue;
+
+    rc = uv__idna_toascii_label(s, st, &d, de);
+
+    if (rc < 0)
+      return rc;
+
+    if (d < de)
+      *d++ = '.';
+
+    s = si;
+  }
+
+  if (s < se) {
+    rc = uv__idna_toascii_label(s, se, &d, de);
+
+    if (rc < 0)
+      return rc;
+  }
+
+  if (d < de)
+    *d++ = '\0';
+
+  return d - ds;  /* Number of bytes written. */
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/idna.h b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/idna.h
similarity index 100%
rename from third_party/allwpilib/wpiutil/src/main/native/libuv/src/idna.h
rename to third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/idna.h
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/inet.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/inet.cpp
new file mode 100644
index 0000000..1b19025
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/inet.cpp
@@ -0,0 +1,308 @@
+/*
+ * Copyright (c) 2004 by Internet Systems Consortium, Inc. ("ISC")
+ * Copyright (c) 1996-1999 by Internet Software Consortium.
+ *
+ * Permission to use, copy, modify, and distribute this software for any
+ * purpose with or without fee is hereby granted, provided that the above
+ * copyright notice and this permission notice appear in all copies.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS" AND ISC DISCLAIMS ALL WARRANTIES
+ * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
+ * MERCHANTABILITY AND FITNESS.  IN NO EVENT SHALL ISC BE LIABLE FOR
+ * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
+ * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
+ * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT
+ * OF OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
+ */
+
+#include <stdio.h>
+#include <string.h>
+
+#if defined(_MSC_VER) && _MSC_VER < 1600
+# include "uv/stdint-msvc2008.h"
+#else
+# include <stdint.h>
+#endif
+
+#include "uv.h"
+#include "uv-common.h"
+
+#ifdef _WIN32
+#pragma warning(disable : 6001)
+#endif
+
+#define UV__INET_ADDRSTRLEN         16
+#define UV__INET6_ADDRSTRLEN        46
+
+
+static int inet_ntop4(const unsigned char *src, char *dst, size_t size);
+static int inet_ntop6(const unsigned char *src, char *dst, size_t size);
+static int inet_pton4(const char *src, unsigned char *dst);
+static int inet_pton6(const char *src, unsigned char *dst);
+
+
+int uv_inet_ntop(int af, const void* src, char* dst, size_t size) {
+  switch (af) {
+  case AF_INET:
+    return (inet_ntop4((const unsigned char*)src, dst, size));
+  case AF_INET6:
+    return (inet_ntop6((const unsigned char*)src, dst, size));
+  default:
+    return UV_EAFNOSUPPORT;
+  }
+  /* NOTREACHED */
+}
+
+
+static int inet_ntop4(const unsigned char *src, char *dst, size_t size) {
+  static const char fmt[] = "%u.%u.%u.%u";
+  char tmp[UV__INET_ADDRSTRLEN];
+  int l;
+
+  l = snprintf(tmp, sizeof(tmp), fmt, src[0], src[1], src[2], src[3]);
+  if (l <= 0 || (size_t) l >= size) {
+    return UV_ENOSPC;
+  }
+  uv__strscpy(dst, tmp, size);
+  return 0;
+}
+
+
+static int inet_ntop6(const unsigned char *src, char *dst, size_t size) {
+  /*
+   * Note that int32_t and int16_t need only be "at least" large enough
+   * to contain a value of the specified size.  On some systems, like
+   * Crays, there is no such thing as an integer variable with 16 bits.
+   * Keep this in mind if you think this function should have been coded
+   * to use pointer overlays.  All the world's not a VAX.
+   */
+  char tmp[UV__INET6_ADDRSTRLEN], *tp;
+  struct { int base, len; } best, cur;
+  unsigned int words[sizeof(struct in6_addr) / sizeof(uint16_t)];
+  int i;
+
+  /*
+   * Preprocess:
+   *  Copy the input (bytewise) array into a wordwise array.
+   *  Find the longest run of 0x00's in src[] for :: shorthanding.
+   */
+  memset(words, '\0', sizeof words);
+  for (i = 0; i < (int) sizeof(struct in6_addr); i++)
+    words[i / 2] |= (src[i] << ((1 - (i % 2)) << 3));
+  best.base = -1;
+  best.len = 0;
+  cur.base = -1;
+  cur.len = 0;
+  for (i = 0; i < (int) ARRAY_SIZE(words); i++) {
+    if (words[i] == 0) {
+      if (cur.base == -1)
+        cur.base = i, cur.len = 1;
+      else
+        cur.len++;
+    } else {
+      if (cur.base != -1) {
+        if (best.base == -1 || cur.len > best.len)
+          best = cur;
+        cur.base = -1;
+      }
+    }
+  }
+  if (cur.base != -1) {
+    if (best.base == -1 || cur.len > best.len)
+      best = cur;
+  }
+  if (best.base != -1 && best.len < 2)
+    best.base = -1;
+
+  /*
+   * Format the result.
+   */
+  tp = tmp;
+  for (i = 0; i < (int) ARRAY_SIZE(words); i++) {
+    /* Are we inside the best run of 0x00's? */
+    if (best.base != -1 && i >= best.base &&
+        i < (best.base + best.len)) {
+      if (i == best.base)
+        *tp++ = ':';
+      continue;
+    }
+    /* Are we following an initial run of 0x00s or any real hex? */
+    if (i != 0)
+      *tp++ = ':';
+    /* Is this address an encapsulated IPv4? */
+    if (i == 6 && best.base == 0 && (best.len == 6 ||
+        (best.len == 7 && words[7] != 0x0001) ||
+        (best.len == 5 && words[5] == 0xffff))) {
+      int err = inet_ntop4(src+12, tp, sizeof tmp - (tp - tmp));
+      if (err)
+        return err;
+      tp += strlen(tp);
+      break;
+    }
+    tp += sprintf(tp, "%x", words[i]);
+  }
+  /* Was it a trailing run of 0x00's? */
+  if (best.base != -1 && (best.base + best.len) == ARRAY_SIZE(words))
+    *tp++ = ':';
+  *tp++ = '\0';
+  if ((size_t) (tp - tmp) > size)
+    return UV_ENOSPC;
+  uv__strscpy(dst, tmp, size);
+  return 0;
+}
+
+
+int uv_inet_pton(int af, const char* src, void* dst) {
+  if (src == NULL || dst == NULL)
+    return UV_EINVAL;
+
+  switch (af) {
+  case AF_INET:
+    return (inet_pton4(src, (unsigned char*)dst));
+  case AF_INET6: {
+    int len;
+    char tmp[UV__INET6_ADDRSTRLEN], *s;
+    const char *p;
+    s = (char*) src;
+    p = strchr(src, '%');
+    if (p != NULL) {
+      s = tmp;
+      len = p - src;
+      if (len > UV__INET6_ADDRSTRLEN-1)
+        return UV_EINVAL;
+      memcpy(s, src, len);
+      s[len] = '\0';
+    }
+    return inet_pton6(s, (unsigned char*)dst);
+  }
+  default:
+    return UV_EAFNOSUPPORT;
+  }
+  /* NOTREACHED */
+}
+
+
+static int inet_pton4(const char *src, unsigned char *dst) {
+  static const char digits[] = "0123456789";
+  int saw_digit, octets, ch;
+  unsigned char tmp[sizeof(struct in_addr)], *tp;
+
+  saw_digit = 0;
+  octets = 0;
+  *(tp = tmp) = 0;
+  while ((ch = *src++) != '\0') {
+    const char *pch;
+
+    if ((pch = strchr(digits, ch)) != NULL) {
+      unsigned int nw = *tp * 10 + (pch - digits);
+
+      if (saw_digit && *tp == 0)
+        return UV_EINVAL;
+      if (nw > 255)
+        return UV_EINVAL;
+      *tp = nw;
+      if (!saw_digit) {
+        if (++octets > 4)
+          return UV_EINVAL;
+        saw_digit = 1;
+      }
+    } else if (ch == '.' && saw_digit) {
+      if (octets == 4)
+        return UV_EINVAL;
+      *++tp = 0;
+      saw_digit = 0;
+    } else
+      return UV_EINVAL;
+  }
+  if (octets < 4)
+    return UV_EINVAL;
+  memcpy(dst, tmp, sizeof(struct in_addr));
+  return 0;
+}
+
+
+static int inet_pton6(const char *src, unsigned char *dst) {
+  static const char xdigits_l[] = "0123456789abcdef",
+                    xdigits_u[] = "0123456789ABCDEF";
+  unsigned char tmp[sizeof(struct in6_addr)], *tp, *endp, *colonp;
+  const char *xdigits, *curtok;
+  int ch, seen_xdigits;
+  unsigned int val;
+
+  memset((tp = tmp), '\0', sizeof tmp);
+  endp = tp + sizeof tmp;
+  colonp = NULL;
+  /* Leading :: requires some special handling. */
+  if (*src == ':')
+    if (*++src != ':')
+      return UV_EINVAL;
+  curtok = src;
+  seen_xdigits = 0;
+  val = 0;
+  while ((ch = *src++) != '\0') {
+    const char *pch;
+
+    if ((pch = strchr((xdigits = xdigits_l), ch)) == NULL)
+      pch = strchr((xdigits = xdigits_u), ch);
+    if (pch != NULL) {
+      val <<= 4;
+      val |= (pch - xdigits);
+      if (++seen_xdigits > 4)
+        return UV_EINVAL;
+      continue;
+    }
+    if (ch == ':') {
+      curtok = src;
+      if (!seen_xdigits) {
+        if (colonp)
+          return UV_EINVAL;
+        colonp = tp;
+        continue;
+      } else if (*src == '\0') {
+        return UV_EINVAL;
+      }
+      if (tp + sizeof(uint16_t) > endp)
+        return UV_EINVAL;
+      *tp++ = (unsigned char) (val >> 8) & 0xff;
+      *tp++ = (unsigned char) val & 0xff;
+      seen_xdigits = 0;
+      val = 0;
+      continue;
+    }
+    if (ch == '.' && ((tp + sizeof(struct in_addr)) <= endp)) {
+      int err = inet_pton4(curtok, tp);
+      if (err == 0) {
+        tp += sizeof(struct in_addr);
+        seen_xdigits = 0;
+        break;  /*%< '\\0' was seen by inet_pton4(). */
+      }
+    }
+    return UV_EINVAL;
+  }
+  if (seen_xdigits) {
+    if (tp + sizeof(uint16_t) > endp)
+      return UV_EINVAL;
+    *tp++ = (unsigned char) (val >> 8) & 0xff;
+    *tp++ = (unsigned char) val & 0xff;
+  }
+  if (colonp != NULL) {
+    /*
+     * Since some memmove()'s erroneously fail to handle
+     * overlapping regions, we'll do the shift by hand.
+     */
+    const int n = tp - colonp;
+    int i;
+
+    if (tp == endp)
+      return UV_EINVAL;
+    for (i = 1; i <= n; i++) {
+      endp[- i] = colonp[n - i];
+      colonp[n - i] = 0;
+    }
+    tp = endp;
+  }
+  if (tp != endp)
+    return UV_EINVAL;
+  memcpy(dst, tmp, sizeof tmp);
+  return 0;
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/queue.h b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/queue.h
similarity index 100%
rename from third_party/allwpilib/wpiutil/src/main/native/libuv/src/queue.h
rename to third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/queue.h
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/random.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/random.cpp
new file mode 100644
index 0000000..e75f77d
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/random.cpp
@@ -0,0 +1,123 @@
+/* Copyright libuv contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "uv-common.h"
+
+#ifdef _WIN32
+#  include "win/internal.h"
+#else
+#  include "unix/internal.h"
+#endif
+
+static int uv__random(void* buf, size_t buflen) {
+  int rc;
+
+#if defined(__PASE__)
+  rc = uv__random_readpath("/dev/urandom", buf, buflen);
+#elif defined(_AIX) || defined(__QNX__)
+  rc = uv__random_readpath("/dev/random", buf, buflen);
+#elif defined(__APPLE__) || defined(__OpenBSD__) || \
+     (defined(__ANDROID_API__) && __ANDROID_API__ >= 28)
+  rc = uv__random_getentropy(buf, buflen);
+  if (rc == UV_ENOSYS)
+    rc = uv__random_devurandom(buf, buflen);
+#elif defined(__NetBSD__)
+  rc = uv__random_sysctl(buf, buflen);
+#elif defined(__FreeBSD__) || defined(__linux__)
+  rc = uv__random_getrandom(buf, buflen);
+  if (rc == UV_ENOSYS)
+    rc = uv__random_devurandom(buf, buflen);
+# if defined(__linux__)
+  switch (rc) {
+    case UV_EACCES:
+    case UV_EIO:
+    case UV_ELOOP:
+    case UV_EMFILE:
+    case UV_ENFILE:
+    case UV_ENOENT:
+    case UV_EPERM:
+      rc = uv__random_sysctl(buf, buflen);
+      break;
+  }
+# endif
+#elif defined(_WIN32)
+  uv__once_init();
+  rc = uv__random_rtlgenrandom(buf, buflen);
+#else
+  rc = uv__random_devurandom(buf, buflen);
+#endif
+
+  return rc;
+}
+
+
+static void uv__random_work(struct uv__work* w) {
+  uv_random_t* req;
+
+  req = container_of(w, uv_random_t, work_req);
+  req->status = uv__random(req->buf, req->buflen);
+}
+
+
+static void uv__random_done(struct uv__work* w, int status) {
+  uv_random_t* req;
+
+  req = container_of(w, uv_random_t, work_req);
+  uv__req_unregister(req->loop, req);
+
+  if (status == 0)
+    status = req->status;
+
+  req->cb(req, status, req->buf, req->buflen);
+}
+
+
+int uv_random(uv_loop_t* loop,
+              uv_random_t* req,
+              void *buf,
+              size_t buflen,
+              unsigned flags,
+              uv_random_cb cb) {
+  if (buflen > 0x7FFFFFFFu)
+    return UV_E2BIG;
+
+  if (flags != 0)
+    return UV_EINVAL;
+
+  if (cb == NULL)
+    return uv__random(buf, buflen);
+
+  uv__req_init(loop, req, UV_RANDOM);
+  req->loop = loop;
+  req->status = 0;
+  req->cb = cb;
+  req->buf = buf;
+  req->buflen = buflen;
+
+  uv__work_submit(loop,
+                  &req->work_req,
+                  UV__WORK_CPU,
+                  uv__random_work,
+                  uv__random_done);
+
+  return 0;
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/strscpy.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/strscpy.cpp
new file mode 100644
index 0000000..6b4cc3b
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/strscpy.cpp
@@ -0,0 +1,38 @@
+/* Copyright libuv project contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "strscpy.h"
+#include <limits.h>  /* SSIZE_MAX */
+
+ssize_t uv__strscpy(char* d, const char* s, size_t n) {
+  size_t i;
+
+  for (i = 0; i < n; i++)
+    if ('\0' == (d[i] = s[i]))
+      return i > SSIZE_MAX ? (ssize_t) UV_E2BIG : (ssize_t) i;
+
+  if (i == 0)
+    return 0;
+
+  d[--i] = '\0';
+
+  return UV_E2BIG;
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/strscpy.h b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/strscpy.h
new file mode 100644
index 0000000..e8d4724
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/strscpy.h
@@ -0,0 +1,39 @@
+/* Copyright libuv project contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#ifndef UV_STRSCPY_H_
+#define UV_STRSCPY_H_
+
+/* Include uv.h for its definitions of size_t and ssize_t.
+ * size_t can be obtained directly from <stddef.h> but ssize_t requires
+ * some hoop jumping on Windows that I didn't want to duplicate here.
+ */
+#include "uv.h"
+
+/* Copies up to |n-1| bytes from |s| to |d| and always zero-terminates
+ * the result, except when |n==0|. Returns the number of bytes copied
+ * or UV_E2BIG if |d| is too small.
+ *
+ * See https://www.kernel.org/doc/htmldocs/kernel-api/API-strscpy.html
+ */
+ssize_t uv__strscpy(char* d, const char* s, size_t n);
+
+#endif  /* UV_STRSCPY_H_ */
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/strtok.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/strtok.cpp
new file mode 100644
index 0000000..45ddea5
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/strtok.cpp
@@ -0,0 +1,52 @@
+/* Copyright libuv project contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <stdlib.h>
+#include "strtok.h"
+
+char* uv__strtok(char* str, const char* sep, char** itr) {
+  const char* sep_itr;
+  char* tmp;
+  char* start;
+
+  if (str == NULL)
+    start = tmp = *itr;
+  else
+    start = tmp = str;
+
+  if (tmp == NULL)
+    return NULL;
+
+  while (*tmp != '\0') {
+    sep_itr = sep;
+    while (*sep_itr != '\0') {
+      if (*tmp == *sep_itr) {
+        *itr = tmp + 1;
+        *tmp = '\0';
+        return start;
+      }
+      sep_itr++;
+    }
+    tmp++;
+  }
+  *itr = NULL;
+  return start;
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/strtok.h b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/strtok.h
new file mode 100644
index 0000000..3799ff5
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/strtok.h
@@ -0,0 +1,27 @@
+/* Copyright libuv project contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#ifndef UV_STRTOK_H_
+#define UV_STRTOK_H_
+
+char* uv__strtok(char* str, const char* sep, char** itr);
+
+#endif  /* UV_STRTOK_H_ */
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/threadpool.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/threadpool.cpp
new file mode 100644
index 0000000..718972c
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/threadpool.cpp
@@ -0,0 +1,397 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv-common.h"
+
+#if !defined(_WIN32)
+# include "unix/internal.h"
+#endif
+
+#include <stdlib.h>
+
+#ifdef _WIN32
+#pragma warning(disable: 6001 6011)
+#endif
+
+#define MAX_THREADPOOL_SIZE 1024
+
+static uv_once_t once = UV_ONCE_INIT;
+static uv_cond_t cond;
+static uv_mutex_t mutex;
+static unsigned int idle_threads;
+static unsigned int slow_io_work_running;
+static unsigned int nthreads;
+static uv_thread_t* threads;
+static uv_thread_t default_threads[4];
+static QUEUE exit_message;
+static QUEUE wq;
+static QUEUE run_slow_work_message;
+static QUEUE slow_io_pending_wq;
+
+static unsigned int slow_work_thread_threshold(void) {
+  return (nthreads + 1) / 2;
+}
+
+static void uv__cancelled(struct uv__work* w) {
+  abort();
+}
+
+
+/* To avoid deadlock with uv_cancel() it's crucial that the worker
+ * never holds the global mutex and the loop-local mutex at the same time.
+ */
+static void worker(void* arg) {
+  struct uv__work* w;
+  QUEUE* q;
+  int is_slow_work;
+
+  uv_sem_post((uv_sem_t*) arg);
+  arg = NULL;
+
+  uv_mutex_lock(&mutex);
+  for (;;) {
+    /* `mutex` should always be locked at this point. */
+
+    /* Keep waiting while either no work is present or only slow I/O
+       and we're at the threshold for that. */
+    while (QUEUE_EMPTY(&wq) ||
+           (QUEUE_HEAD(&wq) == &run_slow_work_message &&
+            QUEUE_NEXT(&run_slow_work_message) == &wq &&
+            slow_io_work_running >= slow_work_thread_threshold())) {
+      idle_threads += 1;
+      uv_cond_wait(&cond, &mutex);
+      idle_threads -= 1;
+    }
+
+    q = QUEUE_HEAD(&wq);
+    if (q == &exit_message) {
+      uv_cond_signal(&cond);
+      uv_mutex_unlock(&mutex);
+      break;
+    }
+
+    QUEUE_REMOVE(q);
+    QUEUE_INIT(q);  /* Signal uv_cancel() that the work req is executing. */
+
+    is_slow_work = 0;
+    if (q == &run_slow_work_message) {
+      /* If we're at the slow I/O threshold, re-schedule until after all
+         other work in the queue is done. */
+      if (slow_io_work_running >= slow_work_thread_threshold()) {
+        QUEUE_INSERT_TAIL(&wq, q);
+        continue;
+      }
+
+      /* If we encountered a request to run slow I/O work but there is none
+         to run, that means it's cancelled => Start over. */
+      if (QUEUE_EMPTY(&slow_io_pending_wq))
+        continue;
+
+      is_slow_work = 1;
+      slow_io_work_running++;
+
+      q = QUEUE_HEAD(&slow_io_pending_wq);
+      QUEUE_REMOVE(q);
+      QUEUE_INIT(q);
+
+      /* If there is more slow I/O work, schedule it to be run as well. */
+      if (!QUEUE_EMPTY(&slow_io_pending_wq)) {
+        QUEUE_INSERT_TAIL(&wq, &run_slow_work_message);
+        if (idle_threads > 0)
+          uv_cond_signal(&cond);
+      }
+    }
+
+    uv_mutex_unlock(&mutex);
+
+    w = QUEUE_DATA(q, struct uv__work, wq);
+    w->work(w);
+
+    uv_mutex_lock(&w->loop->wq_mutex);
+    w->work = NULL;  /* Signal uv_cancel() that the work req is done
+                        executing. */
+    QUEUE_INSERT_TAIL(&w->loop->wq, &w->wq);
+    uv_async_send(&w->loop->wq_async);
+    uv_mutex_unlock(&w->loop->wq_mutex);
+
+    /* Lock `mutex` since that is expected at the start of the next
+     * iteration. */
+    uv_mutex_lock(&mutex);
+    if (is_slow_work) {
+      /* `slow_io_work_running` is protected by `mutex`. */
+      slow_io_work_running--;
+    }
+  }
+}
+
+
+static void post(QUEUE* q, enum uv__work_kind kind) {
+  uv_mutex_lock(&mutex);
+  if (kind == UV__WORK_SLOW_IO) {
+    /* Insert into a separate queue. */
+    QUEUE_INSERT_TAIL(&slow_io_pending_wq, q);
+    if (!QUEUE_EMPTY(&run_slow_work_message)) {
+      /* Running slow I/O tasks is already scheduled => Nothing to do here.
+         The worker that runs said other task will schedule this one as well. */
+      uv_mutex_unlock(&mutex);
+      return;
+    }
+    q = &run_slow_work_message;
+  }
+
+  QUEUE_INSERT_TAIL(&wq, q);
+  if (idle_threads > 0)
+    uv_cond_signal(&cond);
+  uv_mutex_unlock(&mutex);
+}
+
+
+#ifdef __MVS__
+/* TODO(itodorov) - zos: revisit when Woz compiler is available. */
+__attribute__((destructor))
+#endif
+void uv__threadpool_cleanup(void) {
+  unsigned int i;
+
+  if (nthreads == 0)
+    return;
+
+#ifndef __MVS__
+  /* TODO(gabylb) - zos: revisit when Woz compiler is available. */
+  post(&exit_message, UV__WORK_CPU);
+#endif
+
+  for (i = 0; i < nthreads; i++)
+    if (uv_thread_join(threads + i))
+      abort();
+
+  if (threads != default_threads)
+    uv__free(threads);
+
+  uv_mutex_destroy(&mutex);
+  uv_cond_destroy(&cond);
+
+  threads = NULL;
+  nthreads = 0;
+}
+
+
+static void init_threads(void) {
+  unsigned int i;
+  const char* val;
+  uv_sem_t sem;
+
+  nthreads = ARRAY_SIZE(default_threads);
+  val = getenv("UV_THREADPOOL_SIZE");
+  if (val != NULL)
+    nthreads = atoi(val);
+  if (nthreads == 0)
+    nthreads = 1;
+  if (nthreads > MAX_THREADPOOL_SIZE)
+    nthreads = MAX_THREADPOOL_SIZE;
+
+  threads = default_threads;
+  if (nthreads > ARRAY_SIZE(default_threads)) {
+    threads = (uv_thread_t*)uv__malloc(nthreads * sizeof(threads[0]));
+    if (threads == NULL) {
+      nthreads = ARRAY_SIZE(default_threads);
+      threads = default_threads;
+    }
+  }
+
+  if (uv_cond_init(&cond))
+    abort();
+
+  if (uv_mutex_init(&mutex))
+    abort();
+
+  QUEUE_INIT(&wq);
+  QUEUE_INIT(&slow_io_pending_wq);
+  QUEUE_INIT(&run_slow_work_message);
+
+  if (uv_sem_init(&sem, 0))
+    abort();
+
+  for (i = 0; i < nthreads; i++)
+    if (uv_thread_create(threads + i, worker, &sem))
+      abort();
+
+  for (i = 0; i < nthreads; i++)
+    uv_sem_wait(&sem);
+
+  uv_sem_destroy(&sem);
+}
+
+
+#ifndef _WIN32
+static void reset_once(void) {
+  uv_once_t child_once = UV_ONCE_INIT;
+  memcpy(&once, &child_once, sizeof(child_once));
+}
+#endif
+
+
+static void init_once(void) {
+#ifndef _WIN32
+  /* Re-initialize the threadpool after fork.
+   * Note that this discards the global mutex and condition as well
+   * as the work queue.
+   */
+  if (pthread_atfork(NULL, NULL, &reset_once))
+    abort();
+#endif
+  init_threads();
+}
+
+
+void uv__work_submit(uv_loop_t* loop,
+                     struct uv__work* w,
+                     enum uv__work_kind kind,
+                     void (*work)(struct uv__work* w),
+                     void (*done)(struct uv__work* w, int status)) {
+  uv_once(&once, init_once);
+  w->loop = loop;
+  w->work = work;
+  w->done = done;
+  post(&w->wq, kind);
+}
+
+
+static int uv__work_cancel(uv_loop_t* loop, uv_req_t* req, struct uv__work* w) {
+  int cancelled;
+
+  uv_mutex_lock(&mutex);
+  uv_mutex_lock(&w->loop->wq_mutex);
+
+  cancelled = !QUEUE_EMPTY(&w->wq) && w->work != NULL;
+  if (cancelled)
+    QUEUE_REMOVE(&w->wq);
+
+  uv_mutex_unlock(&w->loop->wq_mutex);
+  uv_mutex_unlock(&mutex);
+
+  if (!cancelled)
+    return UV_EBUSY;
+
+  w->work = uv__cancelled;
+  uv_mutex_lock(&loop->wq_mutex);
+  QUEUE_INSERT_TAIL(&loop->wq, &w->wq);
+  uv_async_send(&loop->wq_async);
+  uv_mutex_unlock(&loop->wq_mutex);
+
+  return 0;
+}
+
+
+void uv__work_done(uv_async_t* handle) {
+  struct uv__work* w;
+  uv_loop_t* loop;
+  QUEUE* q;
+  QUEUE wq;
+  int err;
+
+  loop = container_of(handle, uv_loop_t, wq_async);
+  uv_mutex_lock(&loop->wq_mutex);
+  QUEUE_MOVE(&loop->wq, &wq);
+  uv_mutex_unlock(&loop->wq_mutex);
+
+  while (!QUEUE_EMPTY(&wq)) {
+    q = QUEUE_HEAD(&wq);
+    QUEUE_REMOVE(q);
+
+    w = container_of(q, struct uv__work, wq);
+    err = (w->work == uv__cancelled) ? UV_ECANCELED : 0;
+    w->done(w, err);
+  }
+}
+
+
+static void uv__queue_work(struct uv__work* w) {
+  uv_work_t* req = container_of(w, uv_work_t, work_req);
+
+  req->work_cb(req);
+}
+
+
+static void uv__queue_done(struct uv__work* w, int err) {
+  uv_work_t* req;
+
+  req = container_of(w, uv_work_t, work_req);
+  uv__req_unregister(req->loop, req);
+
+  if (req->after_work_cb == NULL)
+    return;
+
+  req->after_work_cb(req, err);
+}
+
+
+int uv_queue_work(uv_loop_t* loop,
+                  uv_work_t* req,
+                  uv_work_cb work_cb,
+                  uv_after_work_cb after_work_cb) {
+  if (work_cb == NULL)
+    return UV_EINVAL;
+
+  uv__req_init(loop, req, UV_WORK);
+  req->loop = loop;
+  req->work_cb = work_cb;
+  req->after_work_cb = after_work_cb;
+  uv__work_submit(loop,
+                  &req->work_req,
+                  UV__WORK_CPU,
+                  uv__queue_work,
+                  uv__queue_done);
+  return 0;
+}
+
+
+int uv_cancel(uv_req_t* req) {
+  struct uv__work* wreq;
+  uv_loop_t* loop;
+
+  switch (req->type) {
+  case UV_FS:
+    loop =  ((uv_fs_t*) req)->loop;
+    wreq = &((uv_fs_t*) req)->work_req;
+    break;
+  case UV_GETADDRINFO:
+    loop =  ((uv_getaddrinfo_t*) req)->loop;
+    wreq = &((uv_getaddrinfo_t*) req)->work_req;
+    break;
+  case UV_GETNAMEINFO:
+    loop = ((uv_getnameinfo_t*) req)->loop;
+    wreq = &((uv_getnameinfo_t*) req)->work_req;
+    break;
+  case UV_RANDOM:
+    loop = ((uv_random_t*) req)->loop;
+    wreq = &((uv_random_t*) req)->work_req;
+    break;
+  case UV_WORK:
+    loop =  ((uv_work_t*) req)->loop;
+    wreq = &((uv_work_t*) req)->work_req;
+    break;
+  default:
+    return UV_EINVAL;
+  }
+
+  return uv__work_cancel(loop, req, wreq);
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/timer.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/timer.cpp
new file mode 100644
index 0000000..bc680e7
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/timer.cpp
@@ -0,0 +1,185 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "uv-common.h"
+#include "heap-inl.h"
+
+#include <assert.h>
+#include <limits.h>
+
+
+static struct heap *timer_heap(const uv_loop_t* loop) {
+#ifdef _WIN32
+  return (struct heap*) loop->timer_heap;
+#else
+  return (struct heap*) &loop->timer_heap;
+#endif
+}
+
+
+static int timer_less_than(const struct heap_node* ha,
+                           const struct heap_node* hb) {
+  const uv_timer_t* a;
+  const uv_timer_t* b;
+
+  a = container_of(ha, uv_timer_t, heap_node);
+  b = container_of(hb, uv_timer_t, heap_node);
+
+  if (a->timeout < b->timeout)
+    return 1;
+  if (b->timeout < a->timeout)
+    return 0;
+
+  /* Compare start_id when both have the same timeout. start_id is
+   * allocated with loop->timer_counter in uv_timer_start().
+   */
+  return a->start_id < b->start_id;
+}
+
+
+int uv_timer_init(uv_loop_t* loop, uv_timer_t* handle) {
+  uv__handle_init(loop, (uv_handle_t*)handle, UV_TIMER);
+  handle->timer_cb = NULL;
+  handle->timeout = 0;
+  handle->repeat = 0;
+  return 0;
+}
+
+
+int uv_timer_start(uv_timer_t* handle,
+                   uv_timer_cb cb,
+                   uint64_t timeout,
+                   uint64_t repeat) {
+  uint64_t clamped_timeout;
+
+  if (uv__is_closing(handle) || cb == NULL)
+    return UV_EINVAL;
+
+  if (uv__is_active(handle))
+    uv_timer_stop(handle);
+
+  clamped_timeout = handle->loop->time + timeout;
+  if (clamped_timeout < timeout)
+    clamped_timeout = (uint64_t) -1;
+
+  handle->timer_cb = cb;
+  handle->timeout = clamped_timeout;
+  handle->repeat = repeat;
+  /* start_id is the second index to be compared in timer_less_than() */
+  handle->start_id = handle->loop->timer_counter++;
+
+  heap_insert(timer_heap(handle->loop),
+              (struct heap_node*) &handle->heap_node,
+              timer_less_than);
+  uv__handle_start(handle);
+
+  return 0;
+}
+
+
+int uv_timer_stop(uv_timer_t* handle) {
+  if (!uv__is_active(handle))
+    return 0;
+
+  heap_remove(timer_heap(handle->loop),
+              (struct heap_node*) &handle->heap_node,
+              timer_less_than);
+  uv__handle_stop(handle);
+
+  return 0;
+}
+
+
+int uv_timer_again(uv_timer_t* handle) {
+  if (handle->timer_cb == NULL)
+    return UV_EINVAL;
+
+  if (handle->repeat) {
+    uv_timer_stop(handle);
+    uv_timer_start(handle, handle->timer_cb, handle->repeat, handle->repeat);
+  }
+
+  return 0;
+}
+
+
+void uv_timer_set_repeat(uv_timer_t* handle, uint64_t repeat) {
+  handle->repeat = repeat;
+}
+
+
+uint64_t uv_timer_get_repeat(const uv_timer_t* handle) {
+  return handle->repeat;
+}
+
+
+uint64_t uv_timer_get_due_in(const uv_timer_t* handle) {
+  if (handle->loop->time >= handle->timeout)
+    return 0;
+
+  return handle->timeout - handle->loop->time;
+}
+
+
+int uv__next_timeout(const uv_loop_t* loop) {
+  const struct heap_node* heap_node;
+  const uv_timer_t* handle;
+  uint64_t diff;
+
+  heap_node = heap_min(timer_heap(loop));
+  if (heap_node == NULL)
+    return -1; /* block indefinitely */
+
+  handle = container_of(heap_node, uv_timer_t, heap_node);
+  if (handle->timeout <= loop->time)
+    return 0;
+
+  diff = handle->timeout - loop->time;
+  if (diff > INT_MAX)
+    diff = INT_MAX;
+
+  return (int) diff;
+}
+
+
+void uv__run_timers(uv_loop_t* loop) {
+  struct heap_node* heap_node;
+  uv_timer_t* handle;
+
+  for (;;) {
+    heap_node = heap_min(timer_heap(loop));
+    if (heap_node == NULL)
+      break;
+
+    handle = container_of(heap_node, uv_timer_t, heap_node);
+    if (handle->timeout > loop->time)
+      break;
+
+    uv_timer_stop(handle);
+    uv_timer_again(handle);
+    handle->timer_cb(handle);
+  }
+}
+
+
+void uv__timer_close(uv_timer_t* handle) {
+  uv_timer_stop(handle);
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/async.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/async.cpp
new file mode 100644
index 0000000..e1805c3
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/async.cpp
@@ -0,0 +1,253 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+/* This file contains both the uv__async internal infrastructure and the
+ * user-facing uv_async_t functions.
+ */
+
+#include "uv.h"
+#include "internal.h"
+#include "atomic-ops.h"
+
+#include <errno.h>
+#include <stdio.h>  /* snprintf() */
+#include <assert.h>
+#include <stdlib.h>
+#include <string.h>
+#include <unistd.h>
+#include <sched.h>  /* sched_yield() */
+
+#ifdef __linux__
+#include <sys/eventfd.h>
+#endif
+
+static void uv__async_send(uv_loop_t* loop);
+static int uv__async_start(uv_loop_t* loop);
+
+
+int uv_async_init(uv_loop_t* loop, uv_async_t* handle, uv_async_cb async_cb) {
+  int err;
+
+  err = uv__async_start(loop);
+  if (err)
+    return err;
+
+  uv__handle_init(loop, (uv_handle_t*)handle, UV_ASYNC);
+  handle->async_cb = async_cb;
+  handle->pending = 0;
+
+  QUEUE_INSERT_TAIL(&loop->async_handles, &handle->queue);
+  uv__handle_start(handle);
+
+  return 0;
+}
+
+
+int uv_async_send(uv_async_t* handle) {
+  /* Do a cheap read first. */
+  if (ACCESS_ONCE(int, handle->pending) != 0)
+    return 0;
+
+  /* Tell the other thread we're busy with the handle. */
+  if (cmpxchgi(&handle->pending, 0, 1) != 0)
+    return 0;
+
+  /* Wake up the other thread's event loop. */
+  uv__async_send(handle->loop);
+
+  /* Tell the other thread we're done. */
+  if (cmpxchgi(&handle->pending, 1, 2) != 1)
+    abort();
+
+  return 0;
+}
+
+
+/* Only call this from the event loop thread. */
+static int uv__async_spin(uv_async_t* handle) {
+  int i;
+  int rc;
+
+  for (;;) {
+    /* 997 is not completely chosen at random. It's a prime number, acyclical
+     * by nature, and should therefore hopefully dampen sympathetic resonance.
+     */
+    for (i = 0; i < 997; i++) {
+      /* rc=0 -- handle is not pending.
+       * rc=1 -- handle is pending, other thread is still working with it.
+       * rc=2 -- handle is pending, other thread is done.
+       */
+      rc = cmpxchgi(&handle->pending, 2, 0);
+
+      if (rc != 1)
+        return rc;
+
+      /* Other thread is busy with this handle, spin until it's done. */
+      cpu_relax();
+    }
+
+    /* Yield the CPU. We may have preempted the other thread while it's
+     * inside the critical section and if it's running on the same CPU
+     * as us, we'll just burn CPU cycles until the end of our time slice.
+     */
+    sched_yield();
+  }
+}
+
+
+void uv__async_close(uv_async_t* handle) {
+  uv__async_spin(handle);
+  QUEUE_REMOVE(&handle->queue);
+  uv__handle_stop(handle);
+}
+
+
+static void uv__async_io(uv_loop_t* loop, uv__io_t* w, unsigned int events) {
+  char buf[1024];
+  ssize_t r;
+  QUEUE queue;
+  QUEUE* q;
+  uv_async_t* h;
+
+  assert(w == &loop->async_io_watcher);
+
+  for (;;) {
+    r = read(w->fd, buf, sizeof(buf));
+
+    if (r == sizeof(buf))
+      continue;
+
+    if (r != -1)
+      break;
+
+    if (errno == EAGAIN || errno == EWOULDBLOCK)
+      break;
+
+    if (errno == EINTR)
+      continue;
+
+    abort();
+  }
+
+  QUEUE_MOVE(&loop->async_handles, &queue);
+  while (!QUEUE_EMPTY(&queue)) {
+    q = QUEUE_HEAD(&queue);
+    h = QUEUE_DATA(q, uv_async_t, queue);
+
+    QUEUE_REMOVE(q);
+    QUEUE_INSERT_TAIL(&loop->async_handles, q);
+
+    if (0 == uv__async_spin(h))
+      continue;  /* Not pending. */
+
+    if (h->async_cb == NULL)
+      continue;
+
+    h->async_cb(h);
+  }
+}
+
+
+static void uv__async_send(uv_loop_t* loop) {
+  const void* buf;
+  ssize_t len;
+  int fd;
+  int r;
+
+  buf = "";
+  len = 1;
+  fd = loop->async_wfd;
+
+#if defined(__linux__)
+  if (fd == -1) {
+    static const uint64_t val = 1;
+    buf = &val;
+    len = sizeof(val);
+    fd = loop->async_io_watcher.fd;  /* eventfd */
+  }
+#endif
+
+  do
+    r = write(fd, buf, len);
+  while (r == -1 && errno == EINTR);
+
+  if (r == len)
+    return;
+
+  if (r == -1)
+    if (errno == EAGAIN || errno == EWOULDBLOCK)
+      return;
+
+  abort();
+}
+
+
+static int uv__async_start(uv_loop_t* loop) {
+  int pipefd[2];
+  int err;
+
+  if (loop->async_io_watcher.fd != -1)
+    return 0;
+
+#ifdef __linux__
+  err = eventfd(0, EFD_CLOEXEC | EFD_NONBLOCK);
+  if (err < 0)
+    return UV__ERR(errno);
+
+  pipefd[0] = err;
+  pipefd[1] = -1;
+#else
+  err = uv__make_pipe(pipefd, UV_NONBLOCK_PIPE);
+  if (err < 0)
+    return err;
+#endif
+
+  uv__io_init(&loop->async_io_watcher, uv__async_io, pipefd[0]);
+  uv__io_start(loop, &loop->async_io_watcher, POLLIN);
+  loop->async_wfd = pipefd[1];
+
+  return 0;
+}
+
+
+int uv__async_fork(uv_loop_t* loop) {
+  if (loop->async_io_watcher.fd == -1) /* never started */
+    return 0;
+
+  uv__async_stop(loop);
+
+  return uv__async_start(loop);
+}
+
+
+void uv__async_stop(uv_loop_t* loop) {
+  if (loop->async_io_watcher.fd == -1)
+    return;
+
+  if (loop->async_wfd != -1) {
+    if (loop->async_wfd != loop->async_io_watcher.fd)
+      uv__close(loop->async_wfd);
+    loop->async_wfd = -1;
+  }
+
+  uv__io_stop(loop, &loop->async_io_watcher, POLLIN);
+  uv__close(loop->async_io_watcher.fd);
+  loop->async_io_watcher.fd = -1;
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/atomic-ops.h b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/atomic-ops.h
new file mode 100644
index 0000000..58043c4
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/atomic-ops.h
@@ -0,0 +1,64 @@
+/* Copyright (c) 2013, Ben Noordhuis <info@bnoordhuis.nl>
+ *
+ * Permission to use, copy, modify, and/or distribute this software for any
+ * purpose with or without fee is hereby granted, provided that the above
+ * copyright notice and this permission notice appear in all copies.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
+ * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
+ * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
+ * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
+ * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
+ * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
+ * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
+ */
+
+#ifndef UV_ATOMIC_OPS_H_
+#define UV_ATOMIC_OPS_H_
+
+#include "internal.h"  /* UV_UNUSED */
+
+#if defined(__SUNPRO_C) || defined(__SUNPRO_CC)
+#include <atomic.h>
+#endif
+
+UV_UNUSED(static int cmpxchgi(int* ptr, int oldval, int newval));
+UV_UNUSED(static void cpu_relax(void));
+
+/* Prefer hand-rolled assembly over the gcc builtins because the latter also
+ * issue full memory barriers.
+ */
+UV_UNUSED(static int cmpxchgi(int* ptr, int oldval, int newval)) {
+#if defined(__i386__) || defined(__x86_64__)
+  int out;
+  __asm__ __volatile__ ("lock; cmpxchg %2, %1;"
+                        : "=a" (out), "+m" (*(volatile int*) ptr)
+                        : "r" (newval), "0" (oldval)
+                        : "memory");
+  return out;
+#elif defined(__MVS__)
+  /* Use hand-rolled assembly because codegen from builtin __plo_CSST results in
+   * a runtime bug.
+   */
+  __asm(" cs %0,%2,%1 \n " : "+r"(oldval), "+m"(*ptr) : "r"(newval) :);
+  return oldval;
+#elif defined(__SUNPRO_C) || defined(__SUNPRO_CC)
+  return atomic_cas_uint((uint_t *)ptr, (uint_t)oldval, (uint_t)newval);
+#else
+  return __sync_val_compare_and_swap(ptr, oldval, newval);
+#endif
+}
+
+UV_UNUSED(static void cpu_relax(void)) {
+#if defined(__i386__) || defined(__x86_64__)
+  __asm__ __volatile__ ("rep; nop" ::: "memory");  /* a.k.a. PAUSE */
+#elif (defined(__arm__) && __ARM_ARCH >= 7) || defined(__aarch64__)
+  __asm__ __volatile__ ("yield" ::: "memory");
+#elif (defined(__ppc__) || defined(__ppc64__)) && defined(__APPLE__)
+  __asm volatile ("" : : : "memory");
+#elif !defined(__APPLE__) && (defined(__powerpc64__) || defined(__ppc64__) || defined(__PPC64__))
+  __asm__ __volatile__ ("or 1,1,1; or 2,2,2" ::: "memory");
+#endif
+}
+
+#endif  /* UV_ATOMIC_OPS_H_ */
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/bsd-ifaddrs.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/bsd-ifaddrs.cpp
new file mode 100644
index 0000000..c3dd71a
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/bsd-ifaddrs.cpp
@@ -0,0 +1,163 @@
+/* Copyright libuv project contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <errno.h>
+#include <stddef.h>
+
+#include <ifaddrs.h>
+#include <net/if.h>
+#if !defined(__CYGWIN__) && !defined(__MSYS__) && !defined(__GNU__)
+#include <net/if_dl.h>
+#endif
+
+#if defined(__HAIKU__)
+#define IFF_RUNNING IFF_LINK
+#endif
+
+static int uv__ifaddr_exclude(struct ifaddrs *ent, int exclude_type) {
+  if (!((ent->ifa_flags & IFF_UP) && (ent->ifa_flags & IFF_RUNNING)))
+    return 1;
+  if (ent->ifa_addr == NULL)
+    return 1;
+#if !defined(__CYGWIN__) && !defined(__MSYS__) && !defined(__GNU__)
+  /*
+   * If `exclude_type` is `UV__EXCLUDE_IFPHYS`, return whether `sa_family`
+   * equals `AF_LINK`. Otherwise, the result depends on the operating
+   * system with `AF_LINK` or `PF_INET`.
+   */
+  if (exclude_type == UV__EXCLUDE_IFPHYS)
+    return (ent->ifa_addr->sa_family != AF_LINK);
+#endif
+#if defined(__APPLE__) || defined(__FreeBSD__) || defined(__DragonFly__) || \
+    defined(__HAIKU__)
+  /*
+   * On BSD getifaddrs returns information related to the raw underlying
+   * devices. We're not interested in this information.
+   */
+  if (ent->ifa_addr->sa_family == AF_LINK)
+    return 1;
+#elif defined(__NetBSD__) || defined(__OpenBSD__)
+  if (ent->ifa_addr->sa_family != PF_INET &&
+      ent->ifa_addr->sa_family != PF_INET6)
+    return 1;
+#endif
+  return 0;
+}
+
+int uv_interface_addresses(uv_interface_address_t** addresses, int* count) {
+  struct ifaddrs* addrs;
+  struct ifaddrs* ent;
+  uv_interface_address_t* address;
+#if !(defined(__CYGWIN__) || defined(__MSYS__)) && !defined(__GNU__)
+  int i;
+#endif
+
+  *count = 0;
+  *addresses = NULL;
+
+  if (getifaddrs(&addrs) != 0)
+    return UV__ERR(errno);
+
+  /* Count the number of interfaces */
+  for (ent = addrs; ent != NULL; ent = ent->ifa_next) {
+    if (uv__ifaddr_exclude(ent, UV__EXCLUDE_IFADDR))
+      continue;
+    (*count)++;
+  }
+
+  if (*count == 0) {
+    freeifaddrs(addrs);
+    return 0;
+  }
+
+  /* Make sure the memory is initiallized to zero using calloc() */
+  *addresses = (uv_interface_address_t*)uv__calloc(*count, sizeof(**addresses));
+
+  if (*addresses == NULL) {
+    freeifaddrs(addrs);
+    return UV_ENOMEM;
+  }
+
+  address = *addresses;
+
+  for (ent = addrs; ent != NULL; ent = ent->ifa_next) {
+    if (uv__ifaddr_exclude(ent, UV__EXCLUDE_IFADDR))
+      continue;
+
+    address->name = uv__strdup(ent->ifa_name);
+
+    if (ent->ifa_addr->sa_family == AF_INET6) {
+      address->address.address6 = *((struct sockaddr_in6*) ent->ifa_addr);
+    } else {
+      address->address.address4 = *((struct sockaddr_in*) ent->ifa_addr);
+    }
+
+    if (ent->ifa_netmask == NULL) {
+      memset(&address->netmask, 0, sizeof(address->netmask));
+    } else if (ent->ifa_netmask->sa_family == AF_INET6) {
+      address->netmask.netmask6 = *((struct sockaddr_in6*) ent->ifa_netmask);
+    } else {
+      address->netmask.netmask4 = *((struct sockaddr_in*) ent->ifa_netmask);
+    }
+
+    address->is_internal = !!(ent->ifa_flags & IFF_LOOPBACK);
+
+    address++;
+  }
+
+#if !(defined(__CYGWIN__) || defined(__MSYS__)) && !defined(__GNU__)
+  /* Fill in physical addresses for each interface */
+  for (ent = addrs; ent != NULL; ent = ent->ifa_next) {
+    if (uv__ifaddr_exclude(ent, UV__EXCLUDE_IFPHYS))
+      continue;
+
+    address = *addresses;
+
+    for (i = 0; i < *count; i++) {
+      if (strcmp(address->name, ent->ifa_name) == 0) {
+        struct sockaddr_dl* sa_addr;
+        sa_addr = (struct sockaddr_dl*)(ent->ifa_addr);
+        memcpy(address->phys_addr, LLADDR(sa_addr), sizeof(address->phys_addr));
+      }
+      address++;
+    }
+  }
+#endif
+
+  freeifaddrs(addrs);
+
+  return 0;
+}
+
+
+void uv_free_interface_addresses(uv_interface_address_t* addresses,
+                                 int count) {
+  int i;
+
+  for (i = 0; i < count; i++) {
+    uv__free(addresses[i].name);
+  }
+
+  uv__free(addresses);
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/core.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/core.cpp
new file mode 100644
index 0000000..4c23f60
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/core.cpp
@@ -0,0 +1,1676 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+#include "strtok.h"
+
+#include <stddef.h> /* NULL */
+#include <stdio.h> /* printf */
+#include <stdlib.h>
+#include <string.h> /* strerror */
+#include <errno.h>
+#include <assert.h>
+#include <unistd.h>
+#include <sys/types.h>
+#include <sys/stat.h>
+#include <fcntl.h>  /* O_CLOEXEC */
+#include <sys/ioctl.h>
+#include <sys/socket.h>
+#include <sys/un.h>
+#include <netinet/in.h>
+#include <arpa/inet.h>
+#include <limits.h> /* INT_MAX, PATH_MAX, IOV_MAX */
+#include <sys/uio.h> /* writev */
+#include <sys/resource.h> /* getrusage */
+#include <pwd.h>
+#include <sys/utsname.h>
+#include <sys/time.h>
+
+#ifdef __sun
+# include <sys/filio.h>
+# include <sys/types.h>
+# include <sys/wait.h>
+#endif
+
+#if defined(__APPLE__)
+# include <sys/filio.h>
+# endif /* defined(__APPLE__) */
+
+
+#if defined(__APPLE__) && !TARGET_OS_IPHONE
+# include <crt_externs.h>
+# include <mach-o/dyld.h> /* _NSGetExecutablePath */
+# define environ (*_NSGetEnviron())
+#else /* defined(__APPLE__) && !TARGET_OS_IPHONE */
+extern char** environ;
+#endif /* !(defined(__APPLE__) && !TARGET_OS_IPHONE) */
+
+
+#if defined(__DragonFly__)      || \
+    defined(__FreeBSD__)        || \
+    defined(__FreeBSD_kernel__) || \
+    defined(__NetBSD__)         || \
+    defined(__OpenBSD__)
+# include <sys/sysctl.h>
+# include <sys/filio.h>
+# include <sys/wait.h>
+# if defined(__FreeBSD__)
+#  define uv__accept4 accept4
+# endif
+# if defined(__NetBSD__)
+#  define uv__accept4(a, b, c, d) paccept((a), (b), (c), NULL, (d))
+# endif
+#endif
+
+#if defined(__MVS__)
+# include <sys/ioctl.h>
+# include "zos-sys-info.h"
+#endif
+
+#if defined(__linux__)
+# include <sched.h>
+# include <sys/syscall.h>
+# define uv__accept4 accept4
+#endif
+
+#if defined(__linux__) && defined(__SANITIZE_THREAD__) && defined(__clang__)
+# include <sanitizer/linux_syscall_hooks.h>
+#endif
+
+static void uv__run_pending(uv_loop_t* loop);
+
+/* Verify that uv_buf_t is ABI-compatible with struct iovec. */
+STATIC_ASSERT(sizeof(uv_buf_t) == sizeof(struct iovec));
+STATIC_ASSERT(sizeof(((uv_buf_t*) 0)->base) ==
+              sizeof(((struct iovec*) 0)->iov_base));
+STATIC_ASSERT(sizeof(((uv_buf_t*) 0)->len) ==
+              sizeof(((struct iovec*) 0)->iov_len));
+STATIC_ASSERT(offsetof(uv_buf_t, base) == offsetof(struct iovec, iov_base));
+STATIC_ASSERT(offsetof(uv_buf_t, len) == offsetof(struct iovec, iov_len));
+
+
+uint64_t uv_hrtime(void) {
+  return uv__hrtime(UV_CLOCK_PRECISE);
+}
+
+
+void uv_close(uv_handle_t* handle, uv_close_cb close_cb) {
+  assert(!uv__is_closing(handle));
+
+  handle->flags |= UV_HANDLE_CLOSING;
+  handle->close_cb = close_cb;
+
+  switch (handle->type) {
+  case UV_NAMED_PIPE:
+    uv__pipe_close((uv_pipe_t*)handle);
+    break;
+
+  case UV_TTY:
+    uv__stream_close((uv_stream_t*)handle);
+    break;
+
+  case UV_TCP:
+    uv__tcp_close((uv_tcp_t*)handle);
+    break;
+
+  case UV_UDP:
+    uv__udp_close((uv_udp_t*)handle);
+    break;
+
+  case UV_PREPARE:
+    uv__prepare_close((uv_prepare_t*)handle);
+    break;
+
+  case UV_CHECK:
+    uv__check_close((uv_check_t*)handle);
+    break;
+
+  case UV_IDLE:
+    uv__idle_close((uv_idle_t*)handle);
+    break;
+
+  case UV_ASYNC:
+    uv__async_close((uv_async_t*)handle);
+    break;
+
+  case UV_TIMER:
+    uv__timer_close((uv_timer_t*)handle);
+    break;
+
+  case UV_PROCESS:
+    uv__process_close((uv_process_t*)handle);
+    break;
+
+  case UV_FS_EVENT:
+    uv__fs_event_close((uv_fs_event_t*)handle);
+#if defined(__sun) || defined(__MVS__)
+    /*
+     * On Solaris, illumos, and z/OS we will not be able to dissociate the
+     * watcher for an event which is pending delivery, so we cannot always call
+     * uv__make_close_pending() straight away. The backend will call the
+     * function once the event has cleared.
+     */
+    return;
+#endif
+    break;
+
+  case UV_POLL:
+    uv__poll_close((uv_poll_t*)handle);
+    break;
+
+  case UV_FS_POLL:
+    uv__fs_poll_close((uv_fs_poll_t*)handle);
+    /* Poll handles use file system requests, and one of them may still be
+     * running. The poll code will call uv__make_close_pending() for us. */
+    return;
+
+  case UV_SIGNAL:
+    uv__signal_close((uv_signal_t*) handle);
+    break;
+
+  default:
+    assert(0);
+  }
+
+  uv__make_close_pending(handle);
+}
+
+int uv__socket_sockopt(uv_handle_t* handle, int optname, int* value) {
+  int r;
+  int fd;
+  socklen_t len;
+
+  if (handle == NULL || value == NULL)
+    return UV_EINVAL;
+
+  if (handle->type == UV_TCP || handle->type == UV_NAMED_PIPE)
+    fd = uv__stream_fd((uv_stream_t*) handle);
+  else if (handle->type == UV_UDP)
+    fd = ((uv_udp_t *) handle)->io_watcher.fd;
+  else
+    return UV_ENOTSUP;
+
+  len = sizeof(*value);
+
+  if (*value == 0)
+    r = getsockopt(fd, SOL_SOCKET, optname, value, &len);
+  else
+    r = setsockopt(fd, SOL_SOCKET, optname, (const void*) value, len);
+
+  if (r < 0)
+    return UV__ERR(errno);
+
+  return 0;
+}
+
+void uv__make_close_pending(uv_handle_t* handle) {
+  assert(handle->flags & UV_HANDLE_CLOSING);
+  assert(!(handle->flags & UV_HANDLE_CLOSED));
+  handle->next_closing = handle->loop->closing_handles;
+  handle->loop->closing_handles = handle;
+}
+
+int uv__getiovmax(void) {
+#if defined(IOV_MAX)
+  return IOV_MAX;
+#elif defined(_SC_IOV_MAX)
+  static int iovmax_cached = -1;
+  int iovmax;
+
+  iovmax = uv__load_relaxed(&iovmax_cached);
+  if (iovmax != -1)
+    return iovmax;
+
+  /* On some embedded devices (arm-linux-uclibc based ip camera),
+   * sysconf(_SC_IOV_MAX) can not get the correct value. The return
+   * value is -1 and the errno is EINPROGRESS. Degrade the value to 1.
+   */
+  iovmax = sysconf(_SC_IOV_MAX);
+  if (iovmax == -1)
+    iovmax = 1;
+
+  uv__store_relaxed(&iovmax_cached, iovmax);
+
+  return iovmax;
+#else
+  return 1024;
+#endif
+}
+
+
+static void uv__finish_close(uv_handle_t* handle) {
+  uv_signal_t* sh;
+
+  /* Note: while the handle is in the UV_HANDLE_CLOSING state now, it's still
+   * possible for it to be active in the sense that uv__is_active() returns
+   * true.
+   *
+   * A good example is when the user calls uv_shutdown(), immediately followed
+   * by uv_close(). The handle is considered active at this point because the
+   * completion of the shutdown req is still pending.
+   */
+  assert(handle->flags & UV_HANDLE_CLOSING);
+  assert(!(handle->flags & UV_HANDLE_CLOSED));
+  handle->flags |= UV_HANDLE_CLOSED;
+
+  switch (handle->type) {
+    case UV_PREPARE:
+    case UV_CHECK:
+    case UV_IDLE:
+    case UV_ASYNC:
+    case UV_TIMER:
+    case UV_PROCESS:
+    case UV_FS_EVENT:
+    case UV_FS_POLL:
+    case UV_POLL:
+      break;
+
+    case UV_SIGNAL:
+      /* If there are any caught signals "trapped" in the signal pipe,
+       * we can't call the close callback yet. Reinserting the handle
+       * into the closing queue makes the event loop spin but that's
+       * okay because we only need to deliver the pending events.
+       */
+      sh = (uv_signal_t*) handle;
+      if (sh->caught_signals > sh->dispatched_signals) {
+        handle->flags ^= UV_HANDLE_CLOSED;
+        uv__make_close_pending(handle);  /* Back into the queue. */
+        return;
+      }
+      break;
+
+    case UV_NAMED_PIPE:
+    case UV_TCP:
+    case UV_TTY:
+      uv__stream_destroy((uv_stream_t*)handle);
+      break;
+
+    case UV_UDP:
+      uv__udp_finish_close((uv_udp_t*)handle);
+      break;
+
+    default:
+      assert(0);
+      break;
+  }
+
+  uv__handle_unref(handle);
+  QUEUE_REMOVE(&handle->handle_queue);
+
+  if (handle->close_cb) {
+    handle->close_cb(handle);
+  }
+}
+
+
+static void uv__run_closing_handles(uv_loop_t* loop) {
+  uv_handle_t* p;
+  uv_handle_t* q;
+
+  p = loop->closing_handles;
+  loop->closing_handles = NULL;
+
+  while (p) {
+    q = p->next_closing;
+    uv__finish_close(p);
+    p = q;
+  }
+}
+
+
+int uv_is_closing(const uv_handle_t* handle) {
+  return uv__is_closing(handle);
+}
+
+
+int uv_backend_fd(const uv_loop_t* loop) {
+  return loop->backend_fd;
+}
+
+
+static int uv__loop_alive(const uv_loop_t* loop) {
+  return uv__has_active_handles(loop) ||
+         uv__has_active_reqs(loop) ||
+         !QUEUE_EMPTY(&loop->pending_queue) ||
+         loop->closing_handles != NULL;
+}
+
+
+static int uv__backend_timeout(const uv_loop_t* loop) {
+  if (loop->stop_flag == 0 &&
+      /* uv__loop_alive(loop) && */
+      (uv__has_active_handles(loop) || uv__has_active_reqs(loop)) &&
+      QUEUE_EMPTY(&loop->pending_queue) &&
+      QUEUE_EMPTY(&loop->idle_handles) &&
+      loop->closing_handles == NULL)
+    return uv__next_timeout(loop);
+  return 0;
+}
+
+
+int uv_backend_timeout(const uv_loop_t* loop) {
+  if (QUEUE_EMPTY(&loop->watcher_queue))
+    return uv__backend_timeout(loop);
+  /* Need to call uv_run to update the backend fd state. */
+  return 0;
+}
+
+
+int uv_loop_alive(const uv_loop_t* loop) {
+  return uv__loop_alive(loop);
+}
+
+
+int uv_run(uv_loop_t* loop, uv_run_mode mode) {
+  int timeout;
+  int r;
+  int can_sleep;
+
+  r = uv__loop_alive(loop);
+  if (!r)
+    uv__update_time(loop);
+
+  while (r != 0 && loop->stop_flag == 0) {
+    uv__update_time(loop);
+    uv__run_timers(loop);
+
+    can_sleep =
+        QUEUE_EMPTY(&loop->pending_queue) && QUEUE_EMPTY(&loop->idle_handles);
+
+    uv__run_pending(loop);
+    uv__run_idle(loop);
+    uv__run_prepare(loop);
+
+    timeout = 0;
+    if ((mode == UV_RUN_ONCE && can_sleep) || mode == UV_RUN_DEFAULT)
+      timeout = uv__backend_timeout(loop);
+
+    uv__io_poll(loop, timeout);
+
+    /* Process immediate callbacks (e.g. write_cb) a small fixed number of
+     * times to avoid loop starvation.*/
+    for (r = 0; r < 8 && !QUEUE_EMPTY(&loop->pending_queue); r++)
+      uv__run_pending(loop);
+
+    /* Run one final update on the provider_idle_time in case uv__io_poll
+     * returned because the timeout expired, but no events were received. This
+     * call will be ignored if the provider_entry_time was either never set (if
+     * the timeout == 0) or was already updated b/c an event was received.
+     */
+    uv__metrics_update_idle_time(loop);
+
+    uv__run_check(loop);
+    uv__run_closing_handles(loop);
+
+    if (mode == UV_RUN_ONCE) {
+      /* UV_RUN_ONCE implies forward progress: at least one callback must have
+       * been invoked when it returns. uv__io_poll() can return without doing
+       * I/O (meaning: no callbacks) when its timeout expires - which means we
+       * have pending timers that satisfy the forward progress constraint.
+       *
+       * UV_RUN_NOWAIT makes no guarantees about progress so it's omitted from
+       * the check.
+       */
+      uv__update_time(loop);
+      uv__run_timers(loop);
+    }
+
+    r = uv__loop_alive(loop);
+    if (mode == UV_RUN_ONCE || mode == UV_RUN_NOWAIT)
+      break;
+  }
+
+  /* The if statement lets gcc compile it to a conditional store. Avoids
+   * dirtying a cache line.
+   */
+  if (loop->stop_flag != 0)
+    loop->stop_flag = 0;
+
+  return r;
+}
+
+
+void uv_update_time(uv_loop_t* loop) {
+  uv__update_time(loop);
+}
+
+
+int uv_is_active(const uv_handle_t* handle) {
+  return uv__is_active(handle);
+}
+
+
+/* Open a socket in non-blocking close-on-exec mode, atomically if possible. */
+int uv__socket(int domain, int type, int protocol) {
+  int sockfd;
+  int err;
+
+#if defined(SOCK_NONBLOCK) && defined(SOCK_CLOEXEC)
+  sockfd = socket(domain, type | SOCK_NONBLOCK | SOCK_CLOEXEC, protocol);
+  if (sockfd != -1)
+    return sockfd;
+
+  if (errno != EINVAL)
+    return UV__ERR(errno);
+#endif
+
+  sockfd = socket(domain, type, protocol);
+  if (sockfd == -1)
+    return UV__ERR(errno);
+
+  err = uv__nonblock(sockfd, 1);
+  if (err == 0)
+    err = uv__cloexec(sockfd, 1);
+
+  if (err) {
+    uv__close(sockfd);
+    return err;
+  }
+
+#if defined(SO_NOSIGPIPE)
+  {
+    int on = 1;
+    setsockopt(sockfd, SOL_SOCKET, SO_NOSIGPIPE, &on, sizeof(on));
+  }
+#endif
+
+  return sockfd;
+}
+
+/* get a file pointer to a file in read-only and close-on-exec mode */
+FILE* uv__open_file(const char* path) {
+  int fd;
+  FILE* fp;
+
+  fd = uv__open_cloexec(path, O_RDONLY);
+  if (fd < 0)
+    return NULL;
+
+   fp = fdopen(fd, "r");
+   if (fp == NULL)
+     uv__close(fd);
+
+   return fp;
+}
+
+
+int uv__accept(int sockfd) {
+  int peerfd;
+  int err;
+
+  (void) &err;
+  assert(sockfd >= 0);
+
+  do
+#ifdef uv__accept4
+    peerfd = uv__accept4(sockfd, NULL, NULL, SOCK_NONBLOCK|SOCK_CLOEXEC);
+#else
+    peerfd = accept(sockfd, NULL, NULL);
+#endif
+  while (peerfd == -1 && errno == EINTR);
+
+  if (peerfd == -1)
+    return UV__ERR(errno);
+
+#ifndef uv__accept4
+  err = uv__cloexec(peerfd, 1);
+  if (err == 0)
+    err = uv__nonblock(peerfd, 1);
+
+  if (err != 0) {
+    uv__close(peerfd);
+    return err;
+  }
+#endif
+
+  return peerfd;
+}
+
+
+#if defined(__APPLE__)
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Wdollar-in-identifier-extension"
+#if defined(__LP64__)
+  extern "C" int close$NOCANCEL(int);
+#else
+  extern "C" int close$NOCANCEL$UNIX2003(int);
+#endif
+#pragma GCC diagnostic pop
+#endif
+
+/* close() on macos has the "interesting" quirk that it fails with EINTR
+ * without closing the file descriptor when a thread is in the cancel state.
+ * That's why libuv calls close$NOCANCEL() instead.
+ *
+ * glibc on linux has a similar issue: close() is a cancellation point and
+ * will unwind the thread when it's in the cancel state. Work around that
+ * by making the system call directly. Musl libc is unaffected.
+ */
+int uv__close_nocancel(int fd) {
+#if defined(__APPLE__)
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Wdollar-in-identifier-extension"
+#if defined(__LP64__) || TARGET_OS_IPHONE
+  return close$NOCANCEL(fd);
+#else
+  return close$NOCANCEL$UNIX2003(fd);
+#endif
+#pragma GCC diagnostic pop
+#elif defined(__linux__) && defined(__SANITIZE_THREAD__) && defined(__clang__)
+  long rc;
+  __sanitizer_syscall_pre_close(fd);
+  rc = syscall(SYS_close, fd);
+  __sanitizer_syscall_post_close(rc, fd);
+  return rc;
+#elif defined(__linux__) && !defined(__SANITIZE_THREAD__)
+  return syscall(SYS_close, fd);
+#else
+  return close(fd);
+#endif
+}
+
+
+int uv__close_nocheckstdio(int fd) {
+  int saved_errno;
+  int rc;
+
+  assert(fd > -1);  /* Catch uninitialized io_watcher.fd bugs. */
+
+  saved_errno = errno;
+  rc = uv__close_nocancel(fd);
+  if (rc == -1) {
+    rc = UV__ERR(errno);
+    if (rc == UV_EINTR || rc == UV__ERR(EINPROGRESS))
+      rc = 0;    /* The close is in progress, not an error. */
+    errno = saved_errno;
+  }
+
+  return rc;
+}
+
+
+int uv__close(int fd) {
+  assert(fd > STDERR_FILENO);  /* Catch stdio close bugs. */
+#if defined(__MVS__)
+  SAVE_ERRNO(epoll_file_close(fd));
+#endif
+  return uv__close_nocheckstdio(fd);
+}
+
+#if UV__NONBLOCK_IS_IOCTL
+int uv__nonblock_ioctl(int fd, int set) {
+  int r;
+
+  do
+    r = ioctl(fd, FIONBIO, &set);
+  while (r == -1 && errno == EINTR);
+
+  if (r)
+    return UV__ERR(errno);
+
+  return 0;
+}
+#endif
+
+
+int uv__nonblock_fcntl(int fd, int set) {
+  int flags;
+  int r;
+
+  do
+    r = fcntl(fd, F_GETFL);
+  while (r == -1 && errno == EINTR);
+
+  if (r == -1)
+    return UV__ERR(errno);
+
+  /* Bail out now if already set/clear. */
+  if (!!(r & O_NONBLOCK) == !!set)
+    return 0;
+
+  if (set)
+    flags = r | O_NONBLOCK;
+  else
+    flags = r & ~O_NONBLOCK;
+
+  do
+    r = fcntl(fd, F_SETFL, flags);
+  while (r == -1 && errno == EINTR);
+
+  if (r)
+    return UV__ERR(errno);
+
+  return 0;
+}
+
+
+int uv__cloexec(int fd, int set) {
+  int flags;
+  int r;
+
+  flags = 0;
+  if (set)
+    flags = FD_CLOEXEC;
+
+  do
+    r = fcntl(fd, F_SETFD, flags);
+  while (r == -1 && errno == EINTR);
+
+  if (r)
+    return UV__ERR(errno);
+
+  return 0;
+}
+
+
+ssize_t uv__recvmsg(int fd, struct msghdr* msg, int flags) {
+#if defined(__ANDROID__)   || \
+    defined(__DragonFly__) || \
+    defined(__FreeBSD__)   || \
+    defined(__NetBSD__)    || \
+    defined(__OpenBSD__)   || \
+    defined(__linux__)
+  ssize_t rc;
+  rc = recvmsg(fd, msg, flags | MSG_CMSG_CLOEXEC);
+  if (rc == -1)
+    return UV__ERR(errno);
+  return rc;
+#else
+  struct cmsghdr* cmsg;
+  int* pfd;
+  int* end;
+  ssize_t rc;
+  rc = recvmsg(fd, msg, flags);
+  if (rc == -1)
+    return UV__ERR(errno);
+  if (msg->msg_controllen == 0)
+    return rc;
+  for (cmsg = CMSG_FIRSTHDR(msg); cmsg != NULL; cmsg = CMSG_NXTHDR(msg, cmsg))
+    if (cmsg->cmsg_type == SCM_RIGHTS)
+      for (pfd = (int*) CMSG_DATA(cmsg),
+           end = (int*) ((char*) cmsg + cmsg->cmsg_len);
+           pfd < end;
+           pfd += 1)
+        uv__cloexec(*pfd, 1);
+  return rc;
+#endif
+}
+
+
+int uv_cwd(char* buffer, size_t* size) {
+  char scratch[1 + UV__PATH_MAX];
+
+  if (buffer == NULL || size == NULL)
+    return UV_EINVAL;
+
+  /* Try to read directly into the user's buffer first... */
+  if (getcwd(buffer, *size) != NULL)
+    goto fixup;
+
+  if (errno != ERANGE)
+    return UV__ERR(errno);
+
+  /* ...or into scratch space if the user's buffer is too small
+   * so we can report how much space to provide on the next try.
+   */
+  if (getcwd(scratch, sizeof(scratch)) == NULL)
+    return UV__ERR(errno);
+
+  buffer = scratch;
+
+fixup:
+
+  *size = strlen(buffer);
+
+  if (*size > 1 && buffer[*size - 1] == '/') {
+    *size -= 1;
+    buffer[*size] = '\0';
+  }
+
+  if (buffer == scratch) {
+    *size += 1;
+    return UV_ENOBUFS;
+  }
+
+  return 0;
+}
+
+
+int uv_chdir(const char* dir) {
+  if (chdir(dir))
+    return UV__ERR(errno);
+
+  return 0;
+}
+
+
+void uv_disable_stdio_inheritance(void) {
+  int fd;
+
+  /* Set the CLOEXEC flag on all open descriptors. Unconditionally try the
+   * first 16 file descriptors. After that, bail out after the first error.
+   */
+  for (fd = 0; ; fd++)
+    if (uv__cloexec(fd, 1) && fd > 15)
+      break;
+}
+
+
+int uv_fileno(const uv_handle_t* handle, uv_os_fd_t* fd) {
+  int fd_out;
+
+  switch (handle->type) {
+  case UV_TCP:
+  case UV_NAMED_PIPE:
+  case UV_TTY:
+    fd_out = uv__stream_fd((uv_stream_t*) handle);
+    break;
+
+  case UV_UDP:
+    fd_out = ((uv_udp_t *) handle)->io_watcher.fd;
+    break;
+
+  case UV_POLL:
+    fd_out = ((uv_poll_t *) handle)->io_watcher.fd;
+    break;
+
+  default:
+    return UV_EINVAL;
+  }
+
+  if (uv__is_closing(handle) || fd_out == -1)
+    return UV_EBADF;
+
+  *fd = fd_out;
+  return 0;
+}
+
+
+static void uv__run_pending(uv_loop_t* loop) {
+  QUEUE* q;
+  QUEUE pq;
+  uv__io_t* w;
+
+  QUEUE_MOVE(&loop->pending_queue, &pq);
+
+  while (!QUEUE_EMPTY(&pq)) {
+    q = QUEUE_HEAD(&pq);
+    QUEUE_REMOVE(q);
+    QUEUE_INIT(q);
+    w = QUEUE_DATA(q, uv__io_t, pending_queue);
+    w->cb(loop, w, POLLOUT);
+  }
+}
+
+
+static unsigned int next_power_of_two(unsigned int val) {
+  val -= 1;
+  val |= val >> 1;
+  val |= val >> 2;
+  val |= val >> 4;
+  val |= val >> 8;
+  val |= val >> 16;
+  val += 1;
+  return val;
+}
+
+static void maybe_resize(uv_loop_t* loop, unsigned int len) {
+  void** watchers;
+  void* fake_watcher_list;
+  void* fake_watcher_count;
+  unsigned int nwatchers;
+  unsigned int i;
+
+  if (len <= loop->nwatchers)
+    return;
+
+  /* Preserve fake watcher list and count at the end of the watchers */
+  if (loop->watchers != NULL) {
+    fake_watcher_list = loop->watchers[loop->nwatchers];
+    fake_watcher_count = loop->watchers[loop->nwatchers + 1];
+  } else {
+    fake_watcher_list = NULL;
+    fake_watcher_count = NULL;
+  }
+
+  nwatchers = next_power_of_two(len + 2) - 2;
+  watchers = (void**)
+      uv__reallocf(loop->watchers, (nwatchers + 2) * sizeof(loop->watchers[0]));
+
+  if (watchers == NULL)
+    abort();
+  for (i = loop->nwatchers; i < nwatchers; i++)
+    watchers[i] = NULL;
+  watchers[nwatchers] = fake_watcher_list;
+  watchers[nwatchers + 1] = fake_watcher_count;
+
+  loop->watchers = watchers;
+  loop->nwatchers = nwatchers;
+}
+
+
+void uv__io_init(uv__io_t* w, uv__io_cb cb, int fd) {
+  assert(cb != NULL);
+  assert(fd >= -1);
+  QUEUE_INIT(&w->pending_queue);
+  QUEUE_INIT(&w->watcher_queue);
+  w->cb = cb;
+  w->fd = fd;
+  w->events = 0;
+  w->pevents = 0;
+
+#if defined(UV_HAVE_KQUEUE)
+  w->rcount = 0;
+  w->wcount = 0;
+#endif /* defined(UV_HAVE_KQUEUE) */
+}
+
+
+void uv__io_start(uv_loop_t* loop, uv__io_t* w, unsigned int events) {
+  assert(0 == (events & ~(POLLIN | POLLOUT | UV__POLLRDHUP | UV__POLLPRI)));
+  assert(0 != events);
+  assert(w->fd >= 0);
+  assert(w->fd < INT_MAX);
+
+  w->pevents |= events;
+  maybe_resize(loop, w->fd + 1);
+
+#if !defined(__sun)
+  /* The event ports backend needs to rearm all file descriptors on each and
+   * every tick of the event loop but the other backends allow us to
+   * short-circuit here if the event mask is unchanged.
+   */
+  if (w->events == w->pevents)
+    return;
+#endif
+
+  if (QUEUE_EMPTY(&w->watcher_queue))
+    QUEUE_INSERT_TAIL(&loop->watcher_queue, &w->watcher_queue);
+
+  if (loop->watchers[w->fd] == NULL) {
+    loop->watchers[w->fd] = w;
+    loop->nfds++;
+  }
+}
+
+
+void uv__io_stop(uv_loop_t* loop, uv__io_t* w, unsigned int events) {
+  assert(0 == (events & ~(POLLIN | POLLOUT | UV__POLLRDHUP | UV__POLLPRI)));
+  assert(0 != events);
+
+  if (w->fd == -1)
+    return;
+
+  assert(w->fd >= 0);
+
+  /* Happens when uv__io_stop() is called on a handle that was never started. */
+  if ((unsigned) w->fd >= loop->nwatchers)
+    return;
+
+  w->pevents &= ~events;
+
+  if (w->pevents == 0) {
+    QUEUE_REMOVE(&w->watcher_queue);
+    QUEUE_INIT(&w->watcher_queue);
+    w->events = 0;
+
+    if (w == loop->watchers[w->fd]) {
+      assert(loop->nfds > 0);
+      loop->watchers[w->fd] = NULL;
+      loop->nfds--;
+    }
+  }
+  else if (QUEUE_EMPTY(&w->watcher_queue))
+    QUEUE_INSERT_TAIL(&loop->watcher_queue, &w->watcher_queue);
+}
+
+
+void uv__io_close(uv_loop_t* loop, uv__io_t* w) {
+  uv__io_stop(loop, w, POLLIN | POLLOUT | UV__POLLRDHUP | UV__POLLPRI);
+  QUEUE_REMOVE(&w->pending_queue);
+
+  /* Remove stale events for this file descriptor */
+  if (w->fd != -1)
+    uv__platform_invalidate_fd(loop, w->fd);
+}
+
+
+void uv__io_feed(uv_loop_t* loop, uv__io_t* w) {
+  if (QUEUE_EMPTY(&w->pending_queue))
+    QUEUE_INSERT_TAIL(&loop->pending_queue, &w->pending_queue);
+}
+
+
+int uv__io_active(const uv__io_t* w, unsigned int events) {
+  assert(0 == (events & ~(POLLIN | POLLOUT | UV__POLLRDHUP | UV__POLLPRI)));
+  assert(0 != events);
+  return 0 != (w->pevents & events);
+}
+
+
+int uv__fd_exists(uv_loop_t* loop, int fd) {
+  return (unsigned) fd < loop->nwatchers && loop->watchers[fd] != NULL;
+}
+
+
+int uv_getrusage(uv_rusage_t* rusage) {
+  struct rusage usage;
+
+  if (getrusage(RUSAGE_SELF, &usage))
+    return UV__ERR(errno);
+
+  rusage->ru_utime.tv_sec = usage.ru_utime.tv_sec;
+  rusage->ru_utime.tv_usec = usage.ru_utime.tv_usec;
+
+  rusage->ru_stime.tv_sec = usage.ru_stime.tv_sec;
+  rusage->ru_stime.tv_usec = usage.ru_stime.tv_usec;
+
+#if !defined(__MVS__) && !defined(__HAIKU__)
+  rusage->ru_maxrss = usage.ru_maxrss;
+  rusage->ru_ixrss = usage.ru_ixrss;
+  rusage->ru_idrss = usage.ru_idrss;
+  rusage->ru_isrss = usage.ru_isrss;
+  rusage->ru_minflt = usage.ru_minflt;
+  rusage->ru_majflt = usage.ru_majflt;
+  rusage->ru_nswap = usage.ru_nswap;
+  rusage->ru_inblock = usage.ru_inblock;
+  rusage->ru_oublock = usage.ru_oublock;
+  rusage->ru_msgsnd = usage.ru_msgsnd;
+  rusage->ru_msgrcv = usage.ru_msgrcv;
+  rusage->ru_nsignals = usage.ru_nsignals;
+  rusage->ru_nvcsw = usage.ru_nvcsw;
+  rusage->ru_nivcsw = usage.ru_nivcsw;
+#endif
+
+  return 0;
+}
+
+
+int uv__open_cloexec(const char* path, int flags) {
+#if defined(O_CLOEXEC)
+  int fd;
+
+  fd = open(path, flags | O_CLOEXEC);
+  if (fd == -1)
+    return UV__ERR(errno);
+
+  return fd;
+#else  /* O_CLOEXEC */
+  int err;
+  int fd;
+
+  fd = open(path, flags);
+  if (fd == -1)
+    return UV__ERR(errno);
+
+  err = uv__cloexec(fd, 1);
+  if (err) {
+    uv__close(fd);
+    return err;
+  }
+
+  return fd;
+#endif  /* O_CLOEXEC */
+}
+
+
+int uv__slurp(const char* filename, char* buf, size_t len) {
+  ssize_t n;
+  int fd;
+
+  assert(len > 0);
+
+  fd = uv__open_cloexec(filename, O_RDONLY);
+  if (fd < 0)
+    return fd;
+
+  do
+    n = read(fd, buf, len - 1);
+  while (n == -1 && errno == EINTR);
+
+  if (uv__close_nocheckstdio(fd))
+    abort();
+
+  if (n < 0)
+    return UV__ERR(errno);
+
+  buf[n] = '\0';
+
+  return 0;
+}
+
+
+int uv__dup2_cloexec(int oldfd, int newfd) {
+#if defined(__FreeBSD__) || defined(__NetBSD__) || defined(__linux__)
+  int r;
+
+  r = dup3(oldfd, newfd, O_CLOEXEC);
+  if (r == -1)
+    return UV__ERR(errno);
+
+  return r;
+#else
+  int err;
+  int r;
+
+  r = dup2(oldfd, newfd);  /* Never retry. */
+  if (r == -1)
+    return UV__ERR(errno);
+
+  err = uv__cloexec(newfd, 1);
+  if (err != 0) {
+    uv__close(newfd);
+    return err;
+  }
+
+  return r;
+#endif
+}
+
+
+int uv_os_homedir(char* buffer, size_t* size) {
+  uv_passwd_t pwd;
+  size_t len;
+  int r;
+
+  /* Check if the HOME environment variable is set first. The task of
+     performing input validation on buffer and size is taken care of by
+     uv_os_getenv(). */
+  r = uv_os_getenv("HOME", buffer, size);
+
+  if (r != UV_ENOENT)
+    return r;
+
+  /* HOME is not set, so call uv__getpwuid_r() */
+  r = uv__getpwuid_r(&pwd);
+
+  if (r != 0) {
+    return r;
+  }
+
+  len = strlen(pwd.homedir);
+
+  if (len >= *size) {
+    *size = len + 1;
+    uv_os_free_passwd(&pwd);
+    return UV_ENOBUFS;
+  }
+
+  memcpy(buffer, pwd.homedir, len + 1);
+  *size = len;
+  uv_os_free_passwd(&pwd);
+
+  return 0;
+}
+
+
+int uv_os_tmpdir(char* buffer, size_t* size) {
+  const char* buf;
+  size_t len;
+
+  if (buffer == NULL || size == NULL || *size == 0)
+    return UV_EINVAL;
+
+#define CHECK_ENV_VAR(name)                                                   \
+  do {                                                                        \
+    buf = getenv(name);                                                       \
+    if (buf != NULL)                                                          \
+      goto return_buffer;                                                     \
+  }                                                                           \
+  while (0)
+
+  /* Check the TMPDIR, TMP, TEMP, and TEMPDIR environment variables in order */
+  CHECK_ENV_VAR("TMPDIR");
+  CHECK_ENV_VAR("TMP");
+  CHECK_ENV_VAR("TEMP");
+  CHECK_ENV_VAR("TEMPDIR");
+
+#undef CHECK_ENV_VAR
+
+  /* No temp environment variables defined */
+  #if defined(__ANDROID__)
+    buf = "/data/local/tmp";
+  #else
+    buf = "/tmp";
+  #endif
+
+return_buffer:
+  len = strlen(buf);
+
+  if (len >= *size) {
+    *size = len + 1;
+    return UV_ENOBUFS;
+  }
+
+  /* The returned directory should not have a trailing slash. */
+  if (len > 1 && buf[len - 1] == '/') {
+    len--;
+  }
+
+  memcpy(buffer, buf, len + 1);
+  buffer[len] = '\0';
+  *size = len;
+
+  return 0;
+}
+
+
+int uv__getpwuid_r(uv_passwd_t* pwd) {
+  struct passwd pw;
+  struct passwd* result;
+  char* buf;
+  uid_t uid;
+  size_t bufsize;
+  size_t name_size;
+  size_t homedir_size;
+  size_t shell_size;
+  int r;
+
+  if (pwd == NULL)
+    return UV_EINVAL;
+
+  uid = geteuid();
+
+  /* Calling sysconf(_SC_GETPW_R_SIZE_MAX) would get the suggested size, but it
+   * is frequently 1024 or 4096, so we can just use that directly. The pwent
+   * will not usually be large. */
+  for (bufsize = 2000;; bufsize *= 2) {
+    buf = (char*)uv__malloc(bufsize);
+
+    if (buf == NULL)
+      return UV_ENOMEM;
+
+    do
+      r = getpwuid_r(uid, &pw, buf, bufsize, &result);
+    while (r == EINTR);
+
+    if (r != 0 || result == NULL)
+      uv__free(buf);
+
+    if (r != ERANGE)
+      break;
+  }
+
+  if (r != 0)
+    return UV__ERR(r);
+
+  if (result == NULL)
+    return UV_ENOENT;
+
+  /* Allocate memory for the username, shell, and home directory */
+  name_size = strlen(pw.pw_name) + 1;
+  homedir_size = strlen(pw.pw_dir) + 1;
+  shell_size = strlen(pw.pw_shell) + 1;
+  pwd->username = (char*)uv__malloc(name_size + homedir_size + shell_size);
+
+  if (pwd->username == NULL) {
+    uv__free(buf);
+    return UV_ENOMEM;
+  }
+
+  /* Copy the username */
+  memcpy(pwd->username, pw.pw_name, name_size);
+
+  /* Copy the home directory */
+  pwd->homedir = pwd->username + name_size;
+  memcpy(pwd->homedir, pw.pw_dir, homedir_size);
+
+  /* Copy the shell */
+  pwd->shell = pwd->homedir + homedir_size;
+  memcpy(pwd->shell, pw.pw_shell, shell_size);
+
+  /* Copy the uid and gid */
+  pwd->uid = pw.pw_uid;
+  pwd->gid = pw.pw_gid;
+
+  uv__free(buf);
+
+  return 0;
+}
+
+
+void uv_os_free_passwd(uv_passwd_t* pwd) {
+  if (pwd == NULL)
+    return;
+
+  /*
+    The memory for name, shell, and homedir are allocated in a single
+    uv__malloc() call. The base of the pointer is stored in pwd->username, so
+    that is the field that needs to be freed.
+  */
+  uv__free(pwd->username);
+  pwd->username = NULL;
+  pwd->shell = NULL;
+  pwd->homedir = NULL;
+}
+
+
+int uv_os_get_passwd(uv_passwd_t* pwd) {
+  return uv__getpwuid_r(pwd);
+}
+
+
+int uv_translate_sys_error(int sys_errno) {
+  /* If < 0 then it's already a libuv error. */
+  return sys_errno <= 0 ? sys_errno : -sys_errno;
+}
+
+
+int uv_os_environ(uv_env_item_t** envitems, int* count) {
+  int i, j, cnt;
+  uv_env_item_t* envitem;
+
+  *envitems = NULL;
+  *count = 0;
+
+  for (i = 0; environ[i] != NULL; i++);
+
+  *envitems = (uv_env_item_s*)uv__calloc(i, sizeof(**envitems));
+
+  if (*envitems == NULL)
+    return UV_ENOMEM;
+
+  for (j = 0, cnt = 0; j < i; j++) {
+    char* buf;
+    char* ptr;
+
+    if (environ[j] == NULL)
+      break;
+
+    buf = uv__strdup(environ[j]);
+    if (buf == NULL)
+      goto fail;
+
+    ptr = strchr(buf, '=');
+    if (ptr == NULL) {
+      uv__free(buf);
+      continue;
+    }
+
+    *ptr = '\0';
+
+    envitem = &(*envitems)[cnt];
+    envitem->name = buf;
+    envitem->value = ptr + 1;
+
+    cnt++;
+  }
+
+  *count = cnt;
+  return 0;
+
+fail:
+  for (i = 0; i < cnt; i++) {
+    envitem = &(*envitems)[cnt];
+    uv__free(envitem->name);
+  }
+  uv__free(*envitems);
+
+  *envitems = NULL;
+  *count = 0;
+  return UV_ENOMEM;
+}
+
+
+int uv_os_getenv(const char* name, char* buffer, size_t* size) {
+  char* var;
+  size_t len;
+
+  if (name == NULL || buffer == NULL || size == NULL || *size == 0)
+    return UV_EINVAL;
+
+  var = getenv(name);
+
+  if (var == NULL)
+    return UV_ENOENT;
+
+  len = strlen(var);
+
+  if (len >= *size) {
+    *size = len + 1;
+    return UV_ENOBUFS;
+  }
+
+  memcpy(buffer, var, len + 1);
+  *size = len;
+
+  return 0;
+}
+
+
+int uv_os_setenv(const char* name, const char* value) {
+  if (name == NULL || value == NULL)
+    return UV_EINVAL;
+
+  if (setenv(name, value, 1) != 0)
+    return UV__ERR(errno);
+
+  return 0;
+}
+
+
+int uv_os_unsetenv(const char* name) {
+  if (name == NULL)
+    return UV_EINVAL;
+
+  if (unsetenv(name) != 0)
+    return UV__ERR(errno);
+
+  return 0;
+}
+
+
+int uv_os_gethostname(char* buffer, size_t* size) {
+  /*
+    On some platforms, if the input buffer is not large enough, gethostname()
+    succeeds, but truncates the result. libuv can detect this and return ENOBUFS
+    instead by creating a large enough buffer and comparing the hostname length
+    to the size input.
+  */
+  char buf[UV_MAXHOSTNAMESIZE];
+  size_t len;
+
+  if (buffer == NULL || size == NULL || *size == 0)
+    return UV_EINVAL;
+
+  if (gethostname(buf, sizeof(buf)) != 0)
+    return UV__ERR(errno);
+
+  buf[sizeof(buf) - 1] = '\0'; /* Null terminate, just to be safe. */
+  len = strlen(buf);
+
+  if (len >= *size) {
+    *size = len + 1;
+    return UV_ENOBUFS;
+  }
+
+  memcpy(buffer, buf, len + 1);
+  *size = len;
+  return 0;
+}
+
+
+uv_os_fd_t uv_get_osfhandle(int fd) {
+  return fd;
+}
+
+int uv_open_osfhandle(uv_os_fd_t os_fd) {
+  return os_fd;
+}
+
+uv_pid_t uv_os_getpid(void) {
+  return getpid();
+}
+
+
+uv_pid_t uv_os_getppid(void) {
+  return getppid();
+}
+
+
+int uv_os_getpriority(uv_pid_t pid, int* priority) {
+  int r;
+
+  if (priority == NULL)
+    return UV_EINVAL;
+
+  errno = 0;
+  r = getpriority(PRIO_PROCESS, (int) pid);
+
+  if (r == -1 && errno != 0)
+    return UV__ERR(errno);
+
+  *priority = r;
+  return 0;
+}
+
+
+int uv_os_setpriority(uv_pid_t pid, int priority) {
+  if (priority < UV_PRIORITY_HIGHEST || priority > UV_PRIORITY_LOW)
+    return UV_EINVAL;
+
+  if (setpriority(PRIO_PROCESS, (int) pid, priority) != 0)
+    return UV__ERR(errno);
+
+  return 0;
+}
+
+
+int uv_os_uname(uv_utsname_t* buffer) {
+  struct utsname buf;
+  int r;
+
+  if (buffer == NULL)
+    return UV_EINVAL;
+
+  if (uname(&buf) == -1) {
+    r = UV__ERR(errno);
+    goto error;
+  }
+
+  r = uv__strscpy(buffer->sysname, buf.sysname, sizeof(buffer->sysname));
+  if (r == UV_E2BIG)
+    goto error;
+
+#ifdef _AIX
+  r = snprintf(buffer->release,
+               sizeof(buffer->release),
+               "%s.%s",
+               buf.version,
+               buf.release);
+  if (r >= sizeof(buffer->release)) {
+    r = UV_E2BIG;
+    goto error;
+  }
+#else
+  r = uv__strscpy(buffer->release, buf.release, sizeof(buffer->release));
+  if (r == UV_E2BIG)
+    goto error;
+#endif
+
+  r = uv__strscpy(buffer->version, buf.version, sizeof(buffer->version));
+  if (r == UV_E2BIG)
+    goto error;
+
+#if defined(_AIX) || defined(__PASE__)
+  r = uv__strscpy(buffer->machine, "ppc64", sizeof(buffer->machine));
+#else
+  r = uv__strscpy(buffer->machine, buf.machine, sizeof(buffer->machine));
+#endif
+
+  if (r == UV_E2BIG)
+    goto error;
+
+  return 0;
+
+error:
+  buffer->sysname[0] = '\0';
+  buffer->release[0] = '\0';
+  buffer->version[0] = '\0';
+  buffer->machine[0] = '\0';
+  return r;
+}
+
+int uv__getsockpeername(const uv_handle_t* handle,
+                        uv__peersockfunc func,
+                        struct sockaddr* name,
+                        int* namelen) {
+  socklen_t socklen;
+  uv_os_fd_t fd;
+  int r;
+
+  r = uv_fileno(handle, &fd);
+  if (r < 0)
+    return r;
+
+  /* sizeof(socklen_t) != sizeof(int) on some systems. */
+  socklen = (socklen_t) *namelen;
+
+  if (func(fd, name, &socklen))
+    return UV__ERR(errno);
+
+  *namelen = (int) socklen;
+  return 0;
+}
+
+int uv_gettimeofday(uv_timeval64_t* tv) {
+  struct timeval time;
+
+  if (tv == NULL)
+    return UV_EINVAL;
+
+  if (gettimeofday(&time, NULL) != 0)
+    return UV__ERR(errno);
+
+  tv->tv_sec = (int64_t) time.tv_sec;
+  tv->tv_usec = (int32_t) time.tv_usec;
+  return 0;
+}
+
+void uv_sleep(unsigned int msec) {
+  struct timespec timeout;
+  int rc;
+
+  timeout.tv_sec = msec / 1000;
+  timeout.tv_nsec = (msec % 1000) * 1000 * 1000;
+
+  do
+    rc = nanosleep(&timeout, &timeout);
+  while (rc == -1 && errno == EINTR);
+
+  assert(rc == 0);
+}
+
+int uv__search_path(const char* prog, char* buf, size_t* buflen) {
+  char abspath[UV__PATH_MAX];
+  size_t abspath_size;
+  char trypath[UV__PATH_MAX];
+  char* cloned_path;
+  char* path_env;
+  char* token;
+  char* itr;
+
+  if (buf == NULL || buflen == NULL || *buflen == 0)
+    return UV_EINVAL;
+
+  /*
+   * Possibilities for prog:
+   * i) an absolute path such as: /home/user/myprojects/nodejs/node
+   * ii) a relative path such as: ./node or ../myprojects/nodejs/node
+   * iii) a bare filename such as "node", after exporting PATH variable
+   *     to its location.
+   */
+
+  /* Case i) and ii) absolute or relative paths */
+  if (strchr(prog, '/') != NULL) {
+    if (realpath(prog, abspath) != abspath)
+      return UV__ERR(errno);
+
+    abspath_size = strlen(abspath);
+
+    *buflen -= 1;
+    if (*buflen > abspath_size)
+      *buflen = abspath_size;
+
+    memcpy(buf, abspath, *buflen);
+    buf[*buflen] = '\0';
+
+    return 0;
+  }
+
+  /* Case iii). Search PATH environment variable */
+  cloned_path = NULL;
+  token = NULL;
+  path_env = getenv("PATH");
+
+  if (path_env == NULL)
+    return UV_EINVAL;
+
+  cloned_path = uv__strdup(path_env);
+  if (cloned_path == NULL)
+    return UV_ENOMEM;
+
+  token = uv__strtok(cloned_path, ":", &itr);
+  while (token != NULL) {
+    snprintf(trypath, sizeof(trypath) - 1, "%s/%s", token, prog);
+    if (realpath(trypath, abspath) == abspath) {
+      /* Check the match is executable */
+      if (access(abspath, X_OK) == 0) {
+        abspath_size = strlen(abspath);
+
+        *buflen -= 1;
+        if (*buflen > abspath_size)
+          *buflen = abspath_size;
+
+        memcpy(buf, abspath, *buflen);
+        buf[*buflen] = '\0';
+
+        uv__free(cloned_path);
+        return 0;
+      }
+    }
+    token = uv__strtok(NULL, ":", &itr);
+  }
+  uv__free(cloned_path);
+
+  /* Out of tokens (path entries), and no match found */
+  return UV_EINVAL;
+}
+
+
+unsigned int uv_available_parallelism(void) {
+#ifdef __linux__
+  cpu_set_t set;
+  long rc;
+
+  memset(&set, 0, sizeof(set));
+
+  /* sysconf(_SC_NPROCESSORS_ONLN) in musl calls sched_getaffinity() but in
+   * glibc it's... complicated... so for consistency try sched_getaffinity()
+   * before falling back to sysconf(_SC_NPROCESSORS_ONLN).
+   */
+  if (0 == sched_getaffinity(0, sizeof(set), &set))
+    rc = CPU_COUNT(&set);
+  else
+    rc = sysconf(_SC_NPROCESSORS_ONLN);
+
+  if (rc < 1)
+    rc = 1;
+
+  return (unsigned) rc;
+#elif defined(__MVS__)
+  int rc;
+
+  rc = __get_num_online_cpus();
+  if (rc < 1)
+    rc = 1;
+
+  return (unsigned) rc;
+#else  /* __linux__ */
+  long rc;
+
+  rc = sysconf(_SC_NPROCESSORS_ONLN);
+  if (rc < 1)
+    rc = 1;
+
+  return (unsigned) rc;
+#endif  /* __linux__ */
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/cygwin.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/cygwin.cpp
new file mode 100644
index 0000000..169958d
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/cygwin.cpp
@@ -0,0 +1,53 @@
+/* Copyright libuv project contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <sys/sysinfo.h>
+#include <unistd.h>
+
+int uv_uptime(double* uptime) {
+  struct sysinfo info;
+
+  if (sysinfo(&info) < 0)
+    return UV__ERR(errno);
+
+  *uptime = info.uptime;
+  return 0;
+}
+
+int uv_resident_set_memory(size_t* rss) {
+  /* FIXME: read /proc/meminfo? */
+  *rss = 0;
+  return 0;
+}
+
+int uv_cpu_info(uv_cpu_info_t** cpu_infos, int* count) {
+  /* FIXME: read /proc/stat? */
+  *cpu_infos = NULL;
+  *count = 0;
+  return UV_ENOSYS;
+}
+
+uint64_t uv_get_constrained_memory(void) {
+  return 0;  /* Memory constraints are unknown. */
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/darwin-proctitle.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/darwin-proctitle.cpp
new file mode 100644
index 0000000..9bd55dd
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/darwin-proctitle.cpp
@@ -0,0 +1,193 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <dlfcn.h>
+#include <errno.h>
+#include <pthread.h>
+#include <stdlib.h>
+#include <string.h>
+
+#include <TargetConditionals.h>
+
+#if !TARGET_OS_IPHONE
+#include "darwin-stub.h"
+#endif
+
+
+static int uv__pthread_setname_np(const char* name) {
+  char namebuf[64];  /* MAXTHREADNAMESIZE */
+  int err;
+
+  strncpy(namebuf, name, sizeof(namebuf) - 1);
+  namebuf[sizeof(namebuf) - 1] = '\0';
+
+  err = pthread_setname_np(namebuf);
+  if (err)
+    return UV__ERR(err);
+
+  return 0;
+}
+
+
+int uv__set_process_title(const char* title) {
+#if TARGET_OS_IPHONE
+  return uv__pthread_setname_np(title);
+#else
+  CFStringRef (*pCFStringCreateWithCString)(CFAllocatorRef,
+                                            const char*,
+                                            CFStringEncoding);
+  CFBundleRef (*pCFBundleGetBundleWithIdentifier)(CFStringRef);
+  void *(*pCFBundleGetDataPointerForName)(CFBundleRef, CFStringRef);
+  void *(*pCFBundleGetFunctionPointerForName)(CFBundleRef, CFStringRef);
+  CFTypeRef (*pLSGetCurrentApplicationASN)(void);
+  OSStatus (*pLSSetApplicationInformationItem)(int,
+                                               CFTypeRef,
+                                               CFStringRef,
+                                               CFStringRef,
+                                               CFDictionaryRef*);
+  void* application_services_handle;
+  void* core_foundation_handle;
+  CFBundleRef launch_services_bundle;
+  CFStringRef* display_name_key;
+  CFDictionaryRef (*pCFBundleGetInfoDictionary)(CFBundleRef);
+  CFBundleRef (*pCFBundleGetMainBundle)(void);
+  CFDictionaryRef (*pLSApplicationCheckIn)(int, CFDictionaryRef);
+  void (*pLSSetApplicationLaunchServicesServerConnectionStatus)(uint64_t,
+                                                                void*);
+  CFTypeRef asn;
+  int err;
+
+  err = UV_ENOENT;
+  application_services_handle = dlopen("/System/Library/Frameworks/"
+                                       "ApplicationServices.framework/"
+                                       "Versions/A/ApplicationServices",
+                                       RTLD_LAZY | RTLD_LOCAL);
+  core_foundation_handle = dlopen("/System/Library/Frameworks/"
+                                  "CoreFoundation.framework/"
+                                  "Versions/A/CoreFoundation",
+                                  RTLD_LAZY | RTLD_LOCAL);
+
+  if (application_services_handle == NULL || core_foundation_handle == NULL)
+    goto out;
+
+  *(void **)(&pCFStringCreateWithCString) =
+      dlsym(core_foundation_handle, "CFStringCreateWithCString");
+  *(void **)(&pCFBundleGetBundleWithIdentifier) =
+      dlsym(core_foundation_handle, "CFBundleGetBundleWithIdentifier");
+  *(void **)(&pCFBundleGetDataPointerForName) =
+      dlsym(core_foundation_handle, "CFBundleGetDataPointerForName");
+  *(void **)(&pCFBundleGetFunctionPointerForName) =
+      dlsym(core_foundation_handle, "CFBundleGetFunctionPointerForName");
+
+  if (pCFStringCreateWithCString == NULL ||
+      pCFBundleGetBundleWithIdentifier == NULL ||
+      pCFBundleGetDataPointerForName == NULL ||
+      pCFBundleGetFunctionPointerForName == NULL) {
+    goto out;
+  }
+
+#define S(s) pCFStringCreateWithCString(NULL, (s), kCFStringEncodingUTF8)
+
+  launch_services_bundle =
+      pCFBundleGetBundleWithIdentifier(S("com.apple.LaunchServices"));
+
+  if (launch_services_bundle == NULL)
+    goto out;
+
+  *(void **)(&pLSGetCurrentApplicationASN) =
+      pCFBundleGetFunctionPointerForName(launch_services_bundle,
+                                         S("_LSGetCurrentApplicationASN"));
+
+  if (pLSGetCurrentApplicationASN == NULL)
+    goto out;
+
+  *(void **)(&pLSSetApplicationInformationItem) =
+      pCFBundleGetFunctionPointerForName(launch_services_bundle,
+                                         S("_LSSetApplicationInformationItem"));
+
+  if (pLSSetApplicationInformationItem == NULL)
+    goto out;
+
+  display_name_key = (CFStringRef*)
+      pCFBundleGetDataPointerForName(launch_services_bundle,
+                                     S("_kLSDisplayNameKey"));
+
+  if (display_name_key == NULL || *display_name_key == NULL)
+    goto out;
+
+  *(void **)(&pCFBundleGetInfoDictionary) = dlsym(core_foundation_handle,
+                                     "CFBundleGetInfoDictionary");
+  *(void **)(&pCFBundleGetMainBundle) = dlsym(core_foundation_handle,
+                                 "CFBundleGetMainBundle");
+  if (pCFBundleGetInfoDictionary == NULL || pCFBundleGetMainBundle == NULL)
+    goto out;
+
+  *(void **)(&pLSApplicationCheckIn) = pCFBundleGetFunctionPointerForName(
+      launch_services_bundle,
+      S("_LSApplicationCheckIn"));
+
+  if (pLSApplicationCheckIn == NULL)
+    goto out;
+
+  *(void **)(&pLSSetApplicationLaunchServicesServerConnectionStatus) =
+      pCFBundleGetFunctionPointerForName(
+          launch_services_bundle,
+          S("_LSSetApplicationLaunchServicesServerConnectionStatus"));
+
+  if (pLSSetApplicationLaunchServicesServerConnectionStatus == NULL)
+    goto out;
+
+  pLSSetApplicationLaunchServicesServerConnectionStatus(0, NULL);
+
+  /* Check into process manager?! */
+  pLSApplicationCheckIn(-2,
+                        pCFBundleGetInfoDictionary(pCFBundleGetMainBundle()));
+
+  asn = pLSGetCurrentApplicationASN();
+
+  err = UV_EBUSY;
+  if (asn == NULL)
+    goto out;
+
+  err = UV_EINVAL;
+  if (pLSSetApplicationInformationItem(-2,  /* Magic value. */
+                                       asn,
+                                       *display_name_key,
+                                       S(title),
+                                       NULL) != noErr) {
+    goto out;
+  }
+
+  uv__pthread_setname_np(title);  /* Don't care if it fails. */
+  err = 0;
+
+out:
+  if (core_foundation_handle != NULL)
+    dlclose(core_foundation_handle);
+
+  if (application_services_handle != NULL)
+    dlclose(application_services_handle);
+
+  return err;
+#endif  /* !TARGET_OS_IPHONE */
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/darwin-stub.h b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/darwin-stub.h
new file mode 100644
index 0000000..433e3ef
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/darwin-stub.h
@@ -0,0 +1,113 @@
+/* Copyright libuv project contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#ifndef UV_DARWIN_STUB_H_
+#define UV_DARWIN_STUB_H_
+
+#include <stdint.h>
+
+struct CFArrayCallBacks;
+struct CFRunLoopSourceContext;
+struct FSEventStreamContext;
+struct CFRange;
+
+typedef double CFAbsoluteTime;
+typedef double CFTimeInterval;
+typedef int FSEventStreamEventFlags;
+typedef int OSStatus;
+typedef long CFIndex;
+typedef struct CFArrayCallBacks CFArrayCallBacks;
+typedef struct CFRunLoopSourceContext CFRunLoopSourceContext;
+typedef struct FSEventStreamContext FSEventStreamContext;
+typedef uint32_t FSEventStreamCreateFlags;
+typedef uint64_t FSEventStreamEventId;
+typedef unsigned CFStringEncoding;
+typedef void* CFAllocatorRef;
+typedef void* CFArrayRef;
+typedef void* CFBundleRef;
+typedef void* CFDataRef;
+typedef void* CFDictionaryRef;
+typedef void* CFMutableDictionaryRef;
+typedef struct CFRange CFRange;
+typedef void* CFRunLoopRef;
+typedef void* CFRunLoopSourceRef;
+typedef void* CFStringRef;
+typedef void* CFTypeRef;
+typedef void* FSEventStreamRef;
+
+typedef uint32_t IOOptionBits;
+typedef unsigned int io_iterator_t;
+typedef unsigned int io_object_t;
+typedef unsigned int io_service_t;
+typedef unsigned int io_registry_entry_t;
+
+
+typedef void (*FSEventStreamCallback)(const FSEventStreamRef,
+                                      void*,
+                                      size_t,
+                                      void*,
+                                      const FSEventStreamEventFlags*,
+                                      const FSEventStreamEventId*);
+
+struct CFRunLoopSourceContext {
+  CFIndex version;
+  void* info;
+  void* pad[7];
+  void (*perform)(void*);
+};
+
+struct FSEventStreamContext {
+  CFIndex version;
+  void* info;
+  void* pad[3];
+};
+
+struct CFRange {
+  CFIndex location;
+  CFIndex length;
+};
+
+static const CFStringEncoding kCFStringEncodingUTF8 = 0x8000100;
+static const OSStatus noErr = 0;
+
+static const FSEventStreamEventId kFSEventStreamEventIdSinceNow = -1;
+
+static const int kFSEventStreamCreateFlagNoDefer = 2;
+static const int kFSEventStreamCreateFlagFileEvents = 16;
+
+static const int kFSEventStreamEventFlagEventIdsWrapped = 8;
+static const int kFSEventStreamEventFlagHistoryDone = 16;
+static const int kFSEventStreamEventFlagItemChangeOwner = 0x4000;
+static const int kFSEventStreamEventFlagItemCreated = 0x100;
+static const int kFSEventStreamEventFlagItemFinderInfoMod = 0x2000;
+static const int kFSEventStreamEventFlagItemInodeMetaMod = 0x400;
+static const int kFSEventStreamEventFlagItemIsDir = 0x20000;
+static const int kFSEventStreamEventFlagItemModified = 0x1000;
+static const int kFSEventStreamEventFlagItemRemoved = 0x200;
+static const int kFSEventStreamEventFlagItemRenamed = 0x800;
+static const int kFSEventStreamEventFlagItemXattrMod = 0x8000;
+static const int kFSEventStreamEventFlagKernelDropped = 4;
+static const int kFSEventStreamEventFlagMount = 64;
+static const int kFSEventStreamEventFlagRootChanged = 32;
+static const int kFSEventStreamEventFlagUnmount = 128;
+static const int kFSEventStreamEventFlagUserDropped = 2;
+
+#endif  /* UV_DARWIN_STUB_H_ */
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/darwin.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/darwin.cpp
new file mode 100644
index 0000000..ed51a6a
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/darwin.cpp
@@ -0,0 +1,384 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <assert.h>
+#include <stdint.h>
+#include <errno.h>
+
+#include <dlfcn.h>
+#include <mach/mach.h>
+#include <mach/mach_time.h>
+#include <mach-o/dyld.h> /* _NSGetExecutablePath */
+#include <sys/resource.h>
+#include <sys/sysctl.h>
+#include <unistd.h>  /* sysconf */
+
+#include "darwin-stub.h"
+
+static uv_once_t once = UV_ONCE_INIT;
+static uint64_t (*time_func)(void);
+static mach_timebase_info_data_t timebase;
+
+typedef unsigned char UInt8;
+
+int uv__platform_loop_init(uv_loop_t* loop) {
+  loop->cf_state = NULL;
+
+  if (uv__kqueue_init(loop))
+    return UV__ERR(errno);
+
+  return 0;
+}
+
+
+void uv__platform_loop_delete(uv_loop_t* loop) {
+  uv__fsevents_loop_delete(loop);
+}
+
+
+static void uv__hrtime_init_once(void) {
+  if (KERN_SUCCESS != mach_timebase_info(&timebase))
+    abort();
+
+  time_func = (uint64_t (*)(void)) dlsym(RTLD_DEFAULT, "mach_continuous_time");
+  if (time_func == NULL)
+    time_func = mach_absolute_time;
+}
+
+
+uint64_t uv__hrtime(uv_clocktype_t type) {
+  uv_once(&once, uv__hrtime_init_once);
+  return time_func() * timebase.numer / timebase.denom;
+}
+
+
+int uv_exepath(char* buffer, size_t* size) {
+  /* realpath(exepath) may be > PATH_MAX so double it to be on the safe side. */
+  char abspath[PATH_MAX * 2 + 1];
+  char exepath[PATH_MAX + 1];
+  uint32_t exepath_size;
+  size_t abspath_size;
+
+  if (buffer == NULL || size == NULL || *size == 0)
+    return UV_EINVAL;
+
+  exepath_size = sizeof(exepath);
+  if (_NSGetExecutablePath(exepath, &exepath_size))
+    return UV_EIO;
+
+  if (realpath(exepath, abspath) != abspath)
+    return UV__ERR(errno);
+
+  abspath_size = strlen(abspath);
+  if (abspath_size == 0)
+    return UV_EIO;
+
+  *size -= 1;
+  if (*size > abspath_size)
+    *size = abspath_size;
+
+  memcpy(buffer, abspath, *size);
+  buffer[*size] = '\0';
+
+  return 0;
+}
+
+
+uint64_t uv_get_free_memory(void) {
+  vm_statistics_data_t info;
+  mach_msg_type_number_t count = sizeof(info) / sizeof(integer_t);
+
+  if (host_statistics(mach_host_self(), HOST_VM_INFO,
+                      (host_info_t)&info, &count) != KERN_SUCCESS) {
+    return UV_EINVAL;  /* FIXME(bnoordhuis) Translate error. */
+  }
+
+  return (uint64_t) info.free_count * sysconf(_SC_PAGESIZE);
+}
+
+
+uint64_t uv_get_total_memory(void) {
+  uint64_t info;
+  int which[] = {CTL_HW, HW_MEMSIZE};
+  size_t size = sizeof(info);
+
+  if (sysctl(which, ARRAY_SIZE(which), &info, &size, NULL, 0))
+    return UV__ERR(errno);
+
+  return (uint64_t) info;
+}
+
+
+uint64_t uv_get_constrained_memory(void) {
+  return 0;  /* Memory constraints are unknown. */
+}
+
+
+void uv_loadavg(double avg[3]) {
+  struct loadavg info;
+  size_t size = sizeof(info);
+  int which[] = {CTL_VM, VM_LOADAVG};
+
+  if (sysctl(which, ARRAY_SIZE(which), &info, &size, NULL, 0) < 0) return;
+
+  avg[0] = (double) info.ldavg[0] / info.fscale;
+  avg[1] = (double) info.ldavg[1] / info.fscale;
+  avg[2] = (double) info.ldavg[2] / info.fscale;
+}
+
+
+int uv_resident_set_memory(size_t* rss) {
+  mach_msg_type_number_t count;
+  task_basic_info_data_t info;
+  kern_return_t err;
+
+  count = TASK_BASIC_INFO_COUNT;
+  err = task_info(mach_task_self(),
+                  TASK_BASIC_INFO,
+                  (task_info_t) &info,
+                  &count);
+  (void) &err;
+  /* task_info(TASK_BASIC_INFO) cannot really fail. Anything other than
+   * KERN_SUCCESS implies a libuv bug.
+   */
+  assert(err == KERN_SUCCESS);
+  *rss = info.resident_size;
+
+  return 0;
+}
+
+
+int uv_uptime(double* uptime) {
+  time_t now;
+  struct timeval info;
+  size_t size = sizeof(info);
+  static int which[] = {CTL_KERN, KERN_BOOTTIME};
+
+  if (sysctl(which, ARRAY_SIZE(which), &info, &size, NULL, 0))
+    return UV__ERR(errno);
+
+  now = time(NULL);
+  *uptime = now - info.tv_sec;
+
+  return 0;
+}
+
+static int uv__get_cpu_speed(uint64_t* speed) {
+  /* IOKit */
+  void (*pIOObjectRelease)(io_object_t);
+  kern_return_t (*pIOMasterPort)(mach_port_t, mach_port_t*);
+  CFMutableDictionaryRef (*pIOServiceMatching)(const char*);
+  kern_return_t (*pIOServiceGetMatchingServices)(mach_port_t,
+                                                 CFMutableDictionaryRef,
+                                                 io_iterator_t*);
+  io_service_t (*pIOIteratorNext)(io_iterator_t);
+  CFTypeRef (*pIORegistryEntryCreateCFProperty)(io_registry_entry_t,
+                                                CFStringRef,
+                                                CFAllocatorRef,
+                                                IOOptionBits);
+
+  /* CoreFoundation */
+  CFStringRef (*pCFStringCreateWithCString)(CFAllocatorRef,
+                                            const char*,
+                                            CFStringEncoding);
+  CFStringEncoding (*pCFStringGetSystemEncoding)(void);
+  UInt8 *(*pCFDataGetBytePtr)(CFDataRef);
+  CFIndex (*pCFDataGetLength)(CFDataRef);
+  void (*pCFDataGetBytes)(CFDataRef, CFRange, UInt8*);
+  void (*pCFRelease)(CFTypeRef);
+
+  void* core_foundation_handle;
+  void* iokit_handle;
+  int err;
+
+  kern_return_t kr;
+  mach_port_t mach_port;
+  io_iterator_t it;
+  io_object_t service;
+
+  mach_port = 0;
+
+  err = UV_ENOENT;
+  core_foundation_handle = dlopen("/System/Library/Frameworks/"
+                                  "CoreFoundation.framework/"
+                                  "CoreFoundation",
+                                  RTLD_LAZY | RTLD_LOCAL);
+  iokit_handle = dlopen("/System/Library/Frameworks/IOKit.framework/"
+                        "IOKit",
+                        RTLD_LAZY | RTLD_LOCAL);
+
+  if (core_foundation_handle == NULL || iokit_handle == NULL)
+    goto out;
+
+#define V(handle, symbol)                                                     \
+  do {                                                                        \
+    *(void **)(&p ## symbol) = dlsym((handle), #symbol);                      \
+    if (p ## symbol == NULL)                                                  \
+      goto out;                                                               \
+  }                                                                           \
+  while (0)
+  V(iokit_handle, IOMasterPort);
+  V(iokit_handle, IOServiceMatching);
+  V(iokit_handle, IOServiceGetMatchingServices);
+  V(iokit_handle, IOIteratorNext);
+  V(iokit_handle, IOObjectRelease);
+  V(iokit_handle, IORegistryEntryCreateCFProperty);
+  V(core_foundation_handle, CFStringCreateWithCString);
+  V(core_foundation_handle, CFStringGetSystemEncoding);
+  V(core_foundation_handle, CFDataGetBytePtr);
+  V(core_foundation_handle, CFDataGetLength);
+  V(core_foundation_handle, CFDataGetBytes);
+  V(core_foundation_handle, CFRelease);
+#undef V
+
+#define S(s) pCFStringCreateWithCString(NULL, (s), kCFStringEncodingUTF8)
+
+  // Braces ensure goto doesn't jump into device_type_str's and
+  // clock_frequency_str's lifetimes after their initialization
+  {
+    kr = pIOMasterPort(MACH_PORT_NULL, &mach_port);
+    (void) kr;
+    assert(kr == KERN_SUCCESS);
+    CFMutableDictionaryRef classes_to_match
+        = pIOServiceMatching("IOPlatformDevice");
+    kr = pIOServiceGetMatchingServices(mach_port, classes_to_match, &it);
+    assert(kr == KERN_SUCCESS);
+    service = pIOIteratorNext(it);
+
+    CFStringRef device_type_str = S("device_type");
+    CFStringRef clock_frequency_str = S("clock-frequency");
+
+    while (service != 0) {
+      CFDataRef data;
+      data = pIORegistryEntryCreateCFProperty(service,
+                                              device_type_str,
+                                              NULL,
+                                              0);
+      if (data) {
+        const UInt8* raw = pCFDataGetBytePtr(data);
+        if (strncmp((char*)raw, "cpu", 3) == 0 ||
+            strncmp((char*)raw, "processor", 9) == 0) {
+          CFDataRef freq_ref;
+          freq_ref = pIORegistryEntryCreateCFProperty(service,
+                                                      clock_frequency_str,
+                                                      NULL,
+                                                      0);
+          if (freq_ref) {
+            const UInt8* freq_ref_ptr = pCFDataGetBytePtr(freq_ref);
+            CFIndex len = pCFDataGetLength(freq_ref);
+            if (len == 8)
+              memcpy(speed, freq_ref_ptr, 8);
+            else if (len == 4) {
+              uint32_t v;
+              memcpy(&v, freq_ref_ptr, 4);
+              *speed = v;
+            } else {
+              *speed = 0;
+            }
+
+            pCFRelease(freq_ref);
+            pCFRelease(data);
+            break;
+          }
+        }
+        pCFRelease(data);
+      }
+
+      service = pIOIteratorNext(it);
+    }
+
+    pIOObjectRelease(it);
+
+    err = 0;
+
+    if (device_type_str != NULL)
+      pCFRelease(device_type_str);
+    if (clock_frequency_str != NULL)
+      pCFRelease(clock_frequency_str);
+  }
+
+out:
+  if (core_foundation_handle != NULL)
+    dlclose(core_foundation_handle);
+
+  if (iokit_handle != NULL)
+    dlclose(iokit_handle);
+
+  mach_port_deallocate(mach_task_self(), mach_port);
+
+  return err;
+}
+
+int uv_cpu_info(uv_cpu_info_t** cpu_infos, int* count) {
+  unsigned int ticks = (unsigned int)sysconf(_SC_CLK_TCK),
+               multiplier = ((uint64_t)1000L / ticks);
+  char model[512];
+  size_t size;
+  unsigned int i;
+  natural_t numcpus;
+  mach_msg_type_number_t msg_type;
+  processor_cpu_load_info_data_t *info;
+  uv_cpu_info_t* cpu_info;
+  uint64_t cpuspeed;
+  int err;
+
+  size = sizeof(model);
+  if (sysctlbyname("machdep.cpu.brand_string", &model, &size, NULL, 0) &&
+      sysctlbyname("hw.model", &model, &size, NULL, 0)) {
+    return UV__ERR(errno);
+  }
+
+  err = uv__get_cpu_speed(&cpuspeed);
+  if (err < 0)
+    return err;
+
+  if (host_processor_info(mach_host_self(), PROCESSOR_CPU_LOAD_INFO, &numcpus,
+                          (processor_info_array_t*)&info,
+                          &msg_type) != KERN_SUCCESS) {
+    return UV_EINVAL;  /* FIXME(bnoordhuis) Translate error. */
+  }
+
+  *cpu_infos = (uv_cpu_info_t*)uv__malloc(numcpus * sizeof(**cpu_infos));
+  if (!(*cpu_infos)) {
+    vm_deallocate(mach_task_self(), (vm_address_t)info, msg_type);
+    return UV_ENOMEM;
+  }
+
+  *count = numcpus;
+
+  for (i = 0; i < numcpus; i++) {
+    cpu_info = &(*cpu_infos)[i];
+
+    cpu_info->cpu_times.user = (uint64_t)(info[i].cpu_ticks[0]) * multiplier;
+    cpu_info->cpu_times.nice = (uint64_t)(info[i].cpu_ticks[3]) * multiplier;
+    cpu_info->cpu_times.sys = (uint64_t)(info[i].cpu_ticks[1]) * multiplier;
+    cpu_info->cpu_times.idle = (uint64_t)(info[i].cpu_ticks[2]) * multiplier;
+    cpu_info->cpu_times.irq = 0;
+
+    cpu_info->model = uv__strdup(model);
+    cpu_info->speed = cpuspeed/1000000;
+  }
+  vm_deallocate(mach_task_self(), (vm_address_t)info, msg_type);
+
+  return 0;
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/dl.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/dl.cpp
new file mode 100644
index 0000000..80b3333
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/dl.cpp
@@ -0,0 +1,80 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <dlfcn.h>
+#include <errno.h>
+#include <string.h>
+#include <locale.h>
+
+static int uv__dlerror(uv_lib_t* lib);
+
+
+int uv_dlopen(const char* filename, uv_lib_t* lib) {
+  dlerror(); /* Reset error status. */
+  lib->errmsg = NULL;
+  lib->handle = dlopen(filename, RTLD_LAZY);
+  return lib->handle ? 0 : uv__dlerror(lib);
+}
+
+
+void uv_dlclose(uv_lib_t* lib) {
+  uv__free(lib->errmsg);
+  lib->errmsg = NULL;
+
+  if (lib->handle) {
+    /* Ignore errors. No good way to signal them without leaking memory. */
+    dlclose(lib->handle);
+    lib->handle = NULL;
+  }
+}
+
+
+int uv_dlsym(uv_lib_t* lib, const char* name, void** ptr) {
+  dlerror(); /* Reset error status. */
+  *ptr = dlsym(lib->handle, name);
+  return *ptr ? 0 : uv__dlerror(lib);
+}
+
+
+const char* uv_dlerror(const uv_lib_t* lib) {
+  return lib->errmsg ? lib->errmsg : "no error";
+}
+
+
+static int uv__dlerror(uv_lib_t* lib) {
+  const char* errmsg;
+
+  uv__free(lib->errmsg);
+
+  errmsg = dlerror();
+
+  if (errmsg) {
+    lib->errmsg = uv__strdup(errmsg);
+    return -1;
+  }
+  else {
+    lib->errmsg = NULL;
+    return 0;
+  }
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/epoll.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/epoll.cpp
new file mode 100644
index 0000000..4c057fb
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/epoll.cpp
@@ -0,0 +1,422 @@
+/* Copyright libuv contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+#include <errno.h>
+#include <sys/epoll.h>
+
+int uv__epoll_init(uv_loop_t* loop) {
+  int fd;
+  fd = epoll_create1(O_CLOEXEC);
+
+  /* epoll_create1() can fail either because it's not implemented (old kernel)
+   * or because it doesn't understand the O_CLOEXEC flag.
+   */
+  if (fd == -1 && (errno == ENOSYS || errno == EINVAL)) {
+    fd = epoll_create(256);
+
+    if (fd != -1)
+      uv__cloexec(fd, 1);
+  }
+
+  loop->backend_fd = fd;
+  if (fd == -1)
+    return UV__ERR(errno);
+
+  return 0;
+}
+
+
+void uv__platform_invalidate_fd(uv_loop_t* loop, int fd) {
+  struct epoll_event* events;
+  struct epoll_event dummy;
+  uintptr_t i;
+  uintptr_t nfds;
+
+  assert(loop->watchers != NULL);
+  assert(fd >= 0);
+
+  events = (struct epoll_event*) loop->watchers[loop->nwatchers];
+  nfds = (uintptr_t) loop->watchers[loop->nwatchers + 1];
+  if (events != NULL)
+    /* Invalidate events with same file descriptor */
+    for (i = 0; i < nfds; i++)
+      if (events[i].data.fd == fd)
+        events[i].data.fd = -1;
+
+  /* Remove the file descriptor from the epoll.
+   * This avoids a problem where the same file description remains open
+   * in another process, causing repeated junk epoll events.
+   *
+   * We pass in a dummy epoll_event, to work around a bug in old kernels.
+   */
+  if (loop->backend_fd >= 0) {
+    /* Work around a bug in kernels 3.10 to 3.19 where passing a struct that
+     * has the EPOLLWAKEUP flag set generates spurious audit syslog warnings.
+     */
+    memset(&dummy, 0, sizeof(dummy));
+    epoll_ctl(loop->backend_fd, EPOLL_CTL_DEL, fd, &dummy);
+  }
+}
+
+
+int uv__io_check_fd(uv_loop_t* loop, int fd) {
+  struct epoll_event e;
+  int rc;
+
+  memset(&e, 0, sizeof(e));
+  e.events = POLLIN;
+  e.data.fd = -1;
+
+  rc = 0;
+  if (epoll_ctl(loop->backend_fd, EPOLL_CTL_ADD, fd, &e))
+    if (errno != EEXIST)
+      rc = UV__ERR(errno);
+
+  if (rc == 0)
+    if (epoll_ctl(loop->backend_fd, EPOLL_CTL_DEL, fd, &e))
+      abort();
+
+  return rc;
+}
+
+
+void uv__io_poll(uv_loop_t* loop, int timeout) {
+  /* A bug in kernels < 2.6.37 makes timeouts larger than ~30 minutes
+   * effectively infinite on 32 bits architectures.  To avoid blocking
+   * indefinitely, we cap the timeout and poll again if necessary.
+   *
+   * Note that "30 minutes" is a simplification because it depends on
+   * the value of CONFIG_HZ.  The magic constant assumes CONFIG_HZ=1200,
+   * that being the largest value I have seen in the wild (and only once.)
+   */
+  static const int max_safe_timeout = 1789569;
+  static int no_epoll_pwait_cached;
+  static int no_epoll_wait_cached;
+  int no_epoll_pwait;
+  int no_epoll_wait;
+  struct epoll_event events[1024];
+  struct epoll_event* pe;
+  struct epoll_event e;
+  int real_timeout;
+  QUEUE* q;
+  uv__io_t* w;
+  sigset_t sigset;
+  uint64_t sigmask;
+  uint64_t base;
+  int have_signals;
+  int nevents;
+  int count;
+  int nfds;
+  int fd;
+  int op;
+  int i;
+  int user_timeout;
+  int reset_timeout;
+
+  if (loop->nfds == 0) {
+    assert(QUEUE_EMPTY(&loop->watcher_queue));
+    return;
+  }
+
+  memset(&e, 0, sizeof(e));
+
+  while (!QUEUE_EMPTY(&loop->watcher_queue)) {
+    q = QUEUE_HEAD(&loop->watcher_queue);
+    QUEUE_REMOVE(q);
+    QUEUE_INIT(q);
+
+    w = QUEUE_DATA(q, uv__io_t, watcher_queue);
+    assert(w->pevents != 0);
+    assert(w->fd >= 0);
+    assert(w->fd < (int) loop->nwatchers);
+
+    e.events = w->pevents;
+    e.data.fd = w->fd;
+
+    if (w->events == 0)
+      op = EPOLL_CTL_ADD;
+    else
+      op = EPOLL_CTL_MOD;
+
+    /* XXX Future optimization: do EPOLL_CTL_MOD lazily if we stop watching
+     * events, skip the syscall and squelch the events after epoll_wait().
+     */
+    if (epoll_ctl(loop->backend_fd, op, w->fd, &e)) {
+      if (errno != EEXIST)
+        abort();
+
+      assert(op == EPOLL_CTL_ADD);
+
+      /* We've reactivated a file descriptor that's been watched before. */
+      if (epoll_ctl(loop->backend_fd, EPOLL_CTL_MOD, w->fd, &e))
+        abort();
+    }
+
+    w->events = w->pevents;
+  }
+
+  sigmask = 0;
+  if (loop->flags & UV_LOOP_BLOCK_SIGPROF) {
+    sigemptyset(&sigset);
+    sigaddset(&sigset, SIGPROF);
+    sigmask |= 1 << (SIGPROF - 1);
+  }
+
+  assert(timeout >= -1);
+  base = loop->time;
+  count = 48; /* Benchmarks suggest this gives the best throughput. */
+  real_timeout = timeout;
+
+  if (uv__get_internal_fields(loop)->flags & UV_METRICS_IDLE_TIME) {
+    reset_timeout = 1;
+    user_timeout = timeout;
+    timeout = 0;
+  } else {
+    reset_timeout = 0;
+    user_timeout = 0;
+  }
+
+  /* You could argue there is a dependency between these two but
+   * ultimately we don't care about their ordering with respect
+   * to one another. Worst case, we make a few system calls that
+   * could have been avoided because another thread already knows
+   * they fail with ENOSYS. Hardly the end of the world.
+   */
+  no_epoll_pwait = uv__load_relaxed(&no_epoll_pwait_cached);
+  no_epoll_wait = uv__load_relaxed(&no_epoll_wait_cached);
+
+  for (;;) {
+    /* Only need to set the provider_entry_time if timeout != 0. The function
+     * will return early if the loop isn't configured with UV_METRICS_IDLE_TIME.
+     */
+    if (timeout != 0)
+      uv__metrics_set_provider_entry_time(loop);
+
+    /* See the comment for max_safe_timeout for an explanation of why
+     * this is necessary.  Executive summary: kernel bug workaround.
+     */
+    if (sizeof(int32_t) == sizeof(long) && timeout >= max_safe_timeout)
+      timeout = max_safe_timeout;
+
+    if (sigmask != 0 && no_epoll_pwait != 0)
+      if (pthread_sigmask(SIG_BLOCK, &sigset, NULL))
+        abort();
+
+    if (no_epoll_wait != 0 || (sigmask != 0 && no_epoll_pwait == 0)) {
+      nfds = epoll_pwait(loop->backend_fd,
+                         events,
+                         ARRAY_SIZE(events),
+                         timeout,
+                         &sigset);
+      if (nfds == -1 && errno == ENOSYS) {
+        uv__store_relaxed(&no_epoll_pwait_cached, 1);
+        no_epoll_pwait = 1;
+      }
+    } else {
+      nfds = epoll_wait(loop->backend_fd,
+                        events,
+                        ARRAY_SIZE(events),
+                        timeout);
+      if (nfds == -1 && errno == ENOSYS) {
+        uv__store_relaxed(&no_epoll_wait_cached, 1);
+        no_epoll_wait = 1;
+      }
+    }
+
+    if (sigmask != 0 && no_epoll_pwait != 0)
+      if (pthread_sigmask(SIG_UNBLOCK, &sigset, NULL))
+        abort();
+
+    /* Update loop->time unconditionally. It's tempting to skip the update when
+     * timeout == 0 (i.e. non-blocking poll) but there is no guarantee that the
+     * operating system didn't reschedule our process while in the syscall.
+     */
+    SAVE_ERRNO(uv__update_time(loop));
+
+    if (nfds == 0) {
+      assert(timeout != -1);
+
+      if (reset_timeout != 0) {
+        timeout = user_timeout;
+        reset_timeout = 0;
+      }
+
+      if (timeout == -1)
+        continue;
+
+      if (timeout == 0)
+        return;
+
+      /* We may have been inside the system call for longer than |timeout|
+       * milliseconds so we need to update the timestamp to avoid drift.
+       */
+      goto update_timeout;
+    }
+
+    if (nfds == -1) {
+      if (errno == ENOSYS) {
+        /* epoll_wait() or epoll_pwait() failed, try the other system call. */
+        assert(no_epoll_wait == 0 || no_epoll_pwait == 0);
+        continue;
+      }
+
+      if (errno != EINTR)
+        abort();
+
+      if (reset_timeout != 0) {
+        timeout = user_timeout;
+        reset_timeout = 0;
+      }
+
+      if (timeout == -1)
+        continue;
+
+      if (timeout == 0)
+        return;
+
+      /* Interrupted by a signal. Update timeout and poll again. */
+      goto update_timeout;
+    }
+
+    have_signals = 0;
+    nevents = 0;
+
+    {
+      /* Squelch a -Waddress-of-packed-member warning with gcc >= 9. */
+      union {
+        struct epoll_event* events;
+        uv__io_t* watchers;
+      } x;
+
+      x.events = events;
+      assert(loop->watchers != NULL);
+      loop->watchers[loop->nwatchers] = x.watchers;
+      loop->watchers[loop->nwatchers + 1] = (void*) (uintptr_t) nfds;
+    }
+
+    for (i = 0; i < nfds; i++) {
+      pe = events + i;
+      fd = pe->data.fd;
+
+      /* Skip invalidated events, see uv__platform_invalidate_fd */
+      if (fd == -1)
+        continue;
+
+      assert(fd >= 0);
+      assert((unsigned) fd < loop->nwatchers);
+
+      w = (uv__io_t*)loop->watchers[fd];
+
+      if (w == NULL) {
+        /* File descriptor that we've stopped watching, disarm it.
+         *
+         * Ignore all errors because we may be racing with another thread
+         * when the file descriptor is closed.
+         */
+        epoll_ctl(loop->backend_fd, EPOLL_CTL_DEL, fd, pe);
+        continue;
+      }
+
+      /* Give users only events they're interested in. Prevents spurious
+       * callbacks when previous callback invocation in this loop has stopped
+       * the current watcher. Also, filters out events that users has not
+       * requested us to watch.
+       */
+      pe->events &= w->pevents | POLLERR | POLLHUP;
+
+      /* Work around an epoll quirk where it sometimes reports just the
+       * EPOLLERR or EPOLLHUP event.  In order to force the event loop to
+       * move forward, we merge in the read/write events that the watcher
+       * is interested in; uv__read() and uv__write() will then deal with
+       * the error or hangup in the usual fashion.
+       *
+       * Note to self: happens when epoll reports EPOLLIN|EPOLLHUP, the user
+       * reads the available data, calls uv_read_stop(), then sometime later
+       * calls uv_read_start() again.  By then, libuv has forgotten about the
+       * hangup and the kernel won't report EPOLLIN again because there's
+       * nothing left to read.  If anything, libuv is to blame here.  The
+       * current hack is just a quick bandaid; to properly fix it, libuv
+       * needs to remember the error/hangup event.  We should get that for
+       * free when we switch over to edge-triggered I/O.
+       */
+      if (pe->events == POLLERR || pe->events == POLLHUP)
+        pe->events |=
+          w->pevents & (POLLIN | POLLOUT | UV__POLLRDHUP | UV__POLLPRI);
+
+      if (pe->events != 0) {
+        /* Run signal watchers last.  This also affects child process watchers
+         * because those are implemented in terms of signal watchers.
+         */
+        if (w == &loop->signal_io_watcher) {
+          have_signals = 1;
+        } else {
+          uv__metrics_update_idle_time(loop);
+          w->cb(loop, w, pe->events);
+        }
+
+        nevents++;
+      }
+    }
+
+    if (reset_timeout != 0) {
+      timeout = user_timeout;
+      reset_timeout = 0;
+    }
+
+    if (have_signals != 0) {
+      uv__metrics_update_idle_time(loop);
+      loop->signal_io_watcher.cb(loop, &loop->signal_io_watcher, POLLIN);
+    }
+
+    loop->watchers[loop->nwatchers] = NULL;
+    loop->watchers[loop->nwatchers + 1] = NULL;
+
+    if (have_signals != 0)
+      return;  /* Event loop should cycle now so don't poll again. */
+
+    if (nevents != 0) {
+      if (nfds == ARRAY_SIZE(events) && --count != 0) {
+        /* Poll for more events but don't block this time. */
+        timeout = 0;
+        continue;
+      }
+      return;
+    }
+
+    if (timeout == 0)
+      return;
+
+    if (timeout == -1)
+      continue;
+
+update_timeout:
+    assert(timeout > 0);
+
+    real_timeout -= (loop->time - base);
+    if (real_timeout <= 0)
+      return;
+
+    timeout = real_timeout;
+  }
+}
+
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/freebsd.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/freebsd.cpp
new file mode 100644
index 0000000..6700ff6
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/freebsd.cpp
@@ -0,0 +1,304 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <assert.h>
+#include <string.h>
+#include <errno.h>
+
+#include <paths.h>
+#include <sys/user.h>
+#include <sys/types.h>
+#include <sys/resource.h>
+#include <sys/sysctl.h>
+#include <vm/vm_param.h> /* VM_LOADAVG */
+#include <time.h>
+#include <stdlib.h>
+#include <unistd.h> /* sysconf */
+#include <fcntl.h>
+
+#ifndef CPUSTATES
+# define CPUSTATES 5U
+#endif
+#ifndef CP_USER
+# define CP_USER 0
+# define CP_NICE 1
+# define CP_SYS 2
+# define CP_IDLE 3
+# define CP_INTR 4
+#endif
+
+
+int uv__platform_loop_init(uv_loop_t* loop) {
+  return uv__kqueue_init(loop);
+}
+
+
+void uv__platform_loop_delete(uv_loop_t* loop) {
+}
+
+int uv_exepath(char* buffer, size_t* size) {
+  char abspath[PATH_MAX * 2 + 1];
+  int mib[4];
+  size_t abspath_size;
+
+  if (buffer == NULL || size == NULL || *size == 0)
+    return UV_EINVAL;
+
+  mib[0] = CTL_KERN;
+  mib[1] = KERN_PROC;
+  mib[2] = KERN_PROC_PATHNAME;
+  mib[3] = -1;
+
+  abspath_size = sizeof abspath;
+  if (sysctl(mib, ARRAY_SIZE(mib), abspath, &abspath_size, NULL, 0))
+    return UV__ERR(errno);
+
+  assert(abspath_size > 0);
+  abspath_size -= 1;
+  *size -= 1;
+
+  if (*size > abspath_size)
+    *size = abspath_size;
+
+  memcpy(buffer, abspath, *size);
+  buffer[*size] = '\0';
+
+  return 0;
+}
+
+uint64_t uv_get_free_memory(void) {
+  int freecount;
+  size_t size = sizeof(freecount);
+
+  if (sysctlbyname("vm.stats.vm.v_free_count", &freecount, &size, NULL, 0))
+    return UV__ERR(errno);
+
+  return (uint64_t) freecount * sysconf(_SC_PAGESIZE);
+
+}
+
+
+uint64_t uv_get_total_memory(void) {
+  unsigned long info;
+  int which[] = {CTL_HW, HW_PHYSMEM};
+
+  size_t size = sizeof(info);
+
+  if (sysctl(which, ARRAY_SIZE(which), &info, &size, NULL, 0))
+    return UV__ERR(errno);
+
+  return (uint64_t) info;
+}
+
+
+uint64_t uv_get_constrained_memory(void) {
+  return 0;  /* Memory constraints are unknown. */
+}
+
+
+void uv_loadavg(double avg[3]) {
+  struct loadavg info;
+  size_t size = sizeof(info);
+  int which[] = {CTL_VM, VM_LOADAVG};
+
+  if (sysctl(which, ARRAY_SIZE(which), &info, &size, NULL, 0) < 0) return;
+
+  avg[0] = (double) info.ldavg[0] / info.fscale;
+  avg[1] = (double) info.ldavg[1] / info.fscale;
+  avg[2] = (double) info.ldavg[2] / info.fscale;
+}
+
+
+int uv_resident_set_memory(size_t* rss) {
+  struct kinfo_proc kinfo;
+  size_t page_size;
+  size_t kinfo_size;
+  int mib[4];
+
+  mib[0] = CTL_KERN;
+  mib[1] = KERN_PROC;
+  mib[2] = KERN_PROC_PID;
+  mib[3] = getpid();
+
+  kinfo_size = sizeof(kinfo);
+
+  if (sysctl(mib, ARRAY_SIZE(mib), &kinfo, &kinfo_size, NULL, 0))
+    return UV__ERR(errno);
+
+  page_size = getpagesize();
+
+#ifdef __DragonFly__
+  *rss = kinfo.kp_vm_rssize * page_size;
+#else
+  *rss = kinfo.ki_rssize * page_size;
+#endif
+
+  return 0;
+}
+
+
+int uv_uptime(double* uptime) {
+  int r;
+  struct timespec sp;
+  r = clock_gettime(CLOCK_MONOTONIC, &sp);
+  if (r)
+    return UV__ERR(errno);
+
+  *uptime = sp.tv_sec;
+  return 0;
+}
+
+
+int uv_cpu_info(uv_cpu_info_t** cpu_infos, int* count) {
+  unsigned int ticks = (unsigned int)sysconf(_SC_CLK_TCK),
+               multiplier = ((uint64_t)1000L / ticks), cpuspeed, maxcpus,
+               cur = 0;
+  uv_cpu_info_t* cpu_info;
+  const char* maxcpus_key;
+  const char* cptimes_key;
+  const char* model_key;
+  char model[512];
+  long* cp_times;
+  int numcpus;
+  size_t size;
+  int i;
+
+#if defined(__DragonFly__)
+  /* This is not quite correct but DragonFlyBSD doesn't seem to have anything
+   * comparable to kern.smp.maxcpus or kern.cp_times (kern.cp_time is a total,
+   * not per CPU). At least this stops uv_cpu_info() from failing completely.
+   */
+  maxcpus_key = "hw.ncpu";
+  cptimes_key = "kern.cp_time";
+#else
+  maxcpus_key = "kern.smp.maxcpus";
+  cptimes_key = "kern.cp_times";
+#endif
+
+#if defined(__arm__) || defined(__aarch64__)
+  /* The key hw.model and hw.clockrate are not available on FreeBSD ARM. */
+  model_key = "hw.machine";
+  cpuspeed = 0;
+#else
+  model_key = "hw.model";
+
+  size = sizeof(cpuspeed);
+  if (sysctlbyname("hw.clockrate", &cpuspeed, &size, NULL, 0))
+    return -errno;
+#endif
+
+  size = sizeof(model);
+  if (sysctlbyname(model_key, &model, &size, NULL, 0))
+    return UV__ERR(errno);
+
+  size = sizeof(numcpus);
+  if (sysctlbyname("hw.ncpu", &numcpus, &size, NULL, 0))
+    return UV__ERR(errno);
+
+  *cpu_infos = (uv_cpu_info_t*)uv__malloc(numcpus * sizeof(**cpu_infos));
+  if (!(*cpu_infos))
+    return UV_ENOMEM;
+
+  *count = numcpus;
+
+  /* kern.cp_times on FreeBSD i386 gives an array up to maxcpus instead of
+   * ncpu.
+   */
+  size = sizeof(maxcpus);
+  if (sysctlbyname(maxcpus_key, &maxcpus, &size, NULL, 0)) {
+    uv__free(*cpu_infos);
+    return UV__ERR(errno);
+  }
+
+  size = maxcpus * CPUSTATES * sizeof(long);
+
+  cp_times = (long*)uv__malloc(size);
+  if (cp_times == NULL) {
+    uv__free(*cpu_infos);
+    return UV_ENOMEM;
+  }
+
+  if (sysctlbyname(cptimes_key, cp_times, &size, NULL, 0)) {
+    uv__free(cp_times);
+    uv__free(*cpu_infos);
+    return UV__ERR(errno);
+  }
+
+  for (i = 0; i < numcpus; i++) {
+    cpu_info = &(*cpu_infos)[i];
+
+    cpu_info->cpu_times.user = (uint64_t)(cp_times[CP_USER+cur]) * multiplier;
+    cpu_info->cpu_times.nice = (uint64_t)(cp_times[CP_NICE+cur]) * multiplier;
+    cpu_info->cpu_times.sys = (uint64_t)(cp_times[CP_SYS+cur]) * multiplier;
+    cpu_info->cpu_times.idle = (uint64_t)(cp_times[CP_IDLE+cur]) * multiplier;
+    cpu_info->cpu_times.irq = (uint64_t)(cp_times[CP_INTR+cur]) * multiplier;
+
+    cpu_info->model = uv__strdup(model);
+    cpu_info->speed = cpuspeed;
+
+    cur+=CPUSTATES;
+  }
+
+  uv__free(cp_times);
+  return 0;
+}
+
+
+int uv__sendmmsg(int fd, struct uv__mmsghdr* mmsg, unsigned int vlen) {
+#if __FreeBSD__ >= 11 && !defined(__DragonFly__)
+  return sendmmsg(fd,
+                  (struct mmsghdr*) mmsg,
+                  vlen,
+                  0 /* flags */);
+#else
+  return errno = ENOSYS, -1;
+#endif
+}
+
+
+int uv__recvmmsg(int fd, struct uv__mmsghdr* mmsg, unsigned int vlen) {
+#if __FreeBSD__ >= 11 && !defined(__DragonFly__)
+  return recvmmsg(fd,
+                  (struct mmsghdr*) mmsg,
+                  vlen,
+                  0 /* flags */,
+                  NULL /* timeout */);
+#else
+  return errno = ENOSYS, -1;
+#endif
+}
+
+ssize_t
+uv__fs_copy_file_range(int fd_in,
+                       off_t* off_in,
+                       int fd_out,
+                       off_t* off_out,
+                       size_t len,
+                       unsigned int flags)
+{
+#if __FreeBSD__ >= 13 && !defined(__DragonFly__)
+	return copy_file_range(fd_in, off_in, fd_out, off_out, len, flags);
+#else
+	return errno = ENOSYS, -1;
+#endif
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/fs.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/fs.cpp
new file mode 100644
index 0000000..1a61524
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/fs.cpp
@@ -0,0 +1,2259 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+/* Caveat emptor: this file deviates from the libuv convention of returning
+ * negated errno codes. Most uv_fs_*() functions map directly to the system
+ * call of the same name. For more complex wrappers, it's easier to just
+ * return -1 with errno set. The dispatcher in uv__fs_work() takes care of
+ * getting the errno to the right place (req->result or as the return value.)
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <errno.h>
+#include <dlfcn.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <limits.h> /* PATH_MAX */
+
+#include <sys/types.h>
+#include <sys/socket.h>
+#include <sys/stat.h>
+#include <sys/time.h>
+#include <sys/uio.h>
+#include <pthread.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <poll.h>
+
+#if defined(__DragonFly__)        ||                                      \
+    defined(__FreeBSD__)          ||                                      \
+    defined(__FreeBSD_kernel__)   ||                                      \
+    defined(__OpenBSD__)          ||                                      \
+    defined(__NetBSD__)
+# define HAVE_PREADV 1
+#else
+# define HAVE_PREADV 0
+#endif
+
+#if defined(__linux__)
+# include "sys/utsname.h"
+#endif
+
+#if defined(__linux__) || defined(__sun)
+# include <sys/sendfile.h>
+# include <sys/sysmacros.h>
+#endif
+
+#if defined(__APPLE__)
+# include <sys/sysctl.h>
+#elif defined(__linux__) && !defined(FICLONE)
+# include <sys/ioctl.h>
+# define FICLONE _IOW(0x94, 9, int)
+#endif
+
+#if defined(_AIX) && !defined(_AIX71)
+# include <utime.h>
+#endif
+
+#if defined(__APPLE__)            ||                                      \
+    defined(__DragonFly__)        ||                                      \
+    defined(__FreeBSD__)          ||                                      \
+    defined(__FreeBSD_kernel__)   ||                                      \
+    defined(__OpenBSD__)          ||                                      \
+    defined(__NetBSD__)
+# include <sys/param.h>
+# include <sys/mount.h>
+#elif defined(__sun)      || \
+      defined(__MVS__)    || \
+      defined(__NetBSD__) || \
+      defined(__HAIKU__)  || \
+      defined(__QNX__)
+# include <sys/statvfs.h>
+#else
+# include <sys/statfs.h>
+#endif
+
+#if defined(_AIX) && _XOPEN_SOURCE <= 600
+extern char *mkdtemp(char *template); /* See issue #740 on AIX < 7 */
+#endif
+
+#define INIT(subtype)                                                         \
+  do {                                                                        \
+    if (req == NULL)                                                          \
+      return UV_EINVAL;                                                       \
+    UV_REQ_INIT(req, UV_FS);                                                  \
+    req->fs_type = UV_FS_ ## subtype;                                         \
+    req->result = 0;                                                          \
+    req->ptr = NULL;                                                          \
+    req->loop = loop;                                                         \
+    req->path = NULL;                                                         \
+    req->new_path = NULL;                                                     \
+    req->bufs = NULL;                                                         \
+    req->cb = cb;                                                             \
+  }                                                                           \
+  while (0)
+
+#define PATH                                                                  \
+  do {                                                                        \
+    assert(path != NULL);                                                     \
+    if (cb == NULL) {                                                         \
+      req->path = path;                                                       \
+    } else {                                                                  \
+      req->path = uv__strdup(path);                                           \
+      if (req->path == NULL)                                                  \
+        return UV_ENOMEM;                                                     \
+    }                                                                         \
+  }                                                                           \
+  while (0)
+
+#define PATH2                                                                 \
+  do {                                                                        \
+    if (cb == NULL) {                                                         \
+      req->path = path;                                                       \
+      req->new_path = new_path;                                               \
+    } else {                                                                  \
+      size_t path_len;                                                        \
+      size_t new_path_len;                                                    \
+      path_len = strlen(path) + 1;                                            \
+      new_path_len = strlen(new_path) + 1;                                    \
+      req->path = (char*)uv__malloc(path_len + new_path_len);                 \
+      if (req->path == NULL)                                                  \
+        return UV_ENOMEM;                                                     \
+      req->new_path = req->path + path_len;                                   \
+      memcpy((void*) req->path, path, path_len);                              \
+      memcpy((void*) req->new_path, new_path, new_path_len);                  \
+    }                                                                         \
+  }                                                                           \
+  while (0)
+
+#define POST                                                                  \
+  do {                                                                        \
+    if (cb != NULL) {                                                         \
+      uv__req_register(loop, req);                                            \
+      uv__work_submit(loop,                                                   \
+                      &req->work_req,                                         \
+                      UV__WORK_FAST_IO,                                       \
+                      uv__fs_work,                                            \
+                      uv__fs_done);                                           \
+      return 0;                                                               \
+    }                                                                         \
+    else {                                                                    \
+      uv__fs_work(&req->work_req);                                            \
+      return req->result;                                                     \
+    }                                                                         \
+  }                                                                           \
+  while (0)
+
+
+static int uv__fs_close(int fd) {
+  int rc;
+
+  rc = uv__close_nocancel(fd);
+  if (rc == -1)
+    if (errno == EINTR || errno == EINPROGRESS)
+      rc = 0;  /* The close is in progress, not an error. */
+
+  return rc;
+}
+
+
+static ssize_t uv__fs_fsync(uv_fs_t* req) {
+#if defined(__APPLE__)
+  /* Apple's fdatasync and fsync explicitly do NOT flush the drive write cache
+   * to the drive platters. This is in contrast to Linux's fdatasync and fsync
+   * which do, according to recent man pages. F_FULLFSYNC is Apple's equivalent
+   * for flushing buffered data to permanent storage. If F_FULLFSYNC is not
+   * supported by the file system we fall back to F_BARRIERFSYNC or fsync().
+   * This is the same approach taken by sqlite, except sqlite does not issue
+   * an F_BARRIERFSYNC call.
+   */
+  int r;
+
+  r = fcntl(req->file, F_FULLFSYNC);
+  if (r != 0)
+    r = fcntl(req->file, 85 /* F_BARRIERFSYNC */);  /* fsync + barrier */
+  if (r != 0)
+    r = fsync(req->file);
+  return r;
+#else
+  return fsync(req->file);
+#endif
+}
+
+
+static ssize_t uv__fs_fdatasync(uv_fs_t* req) {
+#if defined(__linux__) || defined(__sun) || defined(__NetBSD__)
+  return fdatasync(req->file);
+#elif defined(__APPLE__)
+  /* See the comment in uv__fs_fsync. */
+  return uv__fs_fsync(req);
+#else
+  return fsync(req->file);
+#endif
+}
+
+
+UV_UNUSED(static struct timespec uv__fs_to_timespec(double time)) {
+  struct timespec ts;
+  ts.tv_sec  = time;
+  ts.tv_nsec = (time - ts.tv_sec) * 1e9;
+
+ /* TODO(bnoordhuis) Remove this. utimesat() has nanosecond resolution but we
+  * stick to microsecond resolution for the sake of consistency with other
+  * platforms. I'm the original author of this compatibility hack but I'm
+  * less convinced it's useful nowadays.
+  */
+  ts.tv_nsec -= ts.tv_nsec % 1000;
+
+  if (ts.tv_nsec < 0) {
+    ts.tv_nsec += 1e9;
+    ts.tv_sec -= 1;
+  }
+  return ts;
+}
+
+UV_UNUSED(static struct timeval uv__fs_to_timeval(double time)) {
+  struct timeval tv;
+  tv.tv_sec  = time;
+  tv.tv_usec = (time - tv.tv_sec) * 1e6;
+  if (tv.tv_usec < 0) {
+    tv.tv_usec += 1e6;
+    tv.tv_sec -= 1;
+  }
+  return tv;
+}
+
+static ssize_t uv__fs_futime(uv_fs_t* req) {
+#if defined(__linux__)                                                        \
+    || defined(_AIX71)                                                        \
+    || defined(__HAIKU__)                                                     \
+    || defined(__GNU__)
+  struct timespec ts[2];
+  ts[0] = uv__fs_to_timespec(req->atime);
+  ts[1] = uv__fs_to_timespec(req->mtime);
+  return futimens(req->file, ts);
+#elif defined(__APPLE__)                                                      \
+    || defined(__DragonFly__)                                                 \
+    || defined(__FreeBSD__)                                                   \
+    || defined(__FreeBSD_kernel__)                                            \
+    || defined(__NetBSD__)                                                    \
+    || defined(__OpenBSD__)                                                   \
+    || defined(__sun)
+  struct timeval tv[2];
+  tv[0] = uv__fs_to_timeval(req->atime);
+  tv[1] = uv__fs_to_timeval(req->mtime);
+# if defined(__sun)
+  return futimesat(req->file, NULL, tv);
+# else
+  return futimes(req->file, tv);
+# endif
+#elif defined(__MVS__)
+  attrib_t atr;
+  memset(&atr, 0, sizeof(atr));
+  atr.att_mtimechg = 1;
+  atr.att_atimechg = 1;
+  atr.att_mtime = req->mtime;
+  atr.att_atime = req->atime;
+  return __fchattr(req->file, &atr, sizeof(atr));
+#else
+  errno = ENOSYS;
+  return -1;
+#endif
+}
+
+
+static ssize_t uv__fs_mkdtemp(uv_fs_t* req) {
+  return mkdtemp((char*) req->path) ? 0 : -1;
+}
+
+
+static int (*uv__mkostemp)(char*, int);
+
+
+static void uv__mkostemp_initonce(void) {
+  /* z/os doesn't have RTLD_DEFAULT but that's okay
+   * because it doesn't have mkostemp(O_CLOEXEC) either.
+   */
+#ifdef RTLD_DEFAULT
+  uv__mkostemp = (int (*)(char*, int)) dlsym(RTLD_DEFAULT, "mkostemp");
+
+  /* We don't care about errors, but we do want to clean them up.
+   * If there has been no error, then dlerror() will just return
+   * NULL.
+   */
+  dlerror();
+#endif  /* RTLD_DEFAULT */
+}
+
+
+static int uv__fs_mkstemp(uv_fs_t* req) {
+  static uv_once_t once = UV_ONCE_INIT;
+  int r;
+#ifdef O_CLOEXEC
+  static int no_cloexec_support;
+#endif
+  static const char pattern[] = "XXXXXX";
+  static const size_t pattern_size = sizeof(pattern) - 1;
+  char* path;
+  size_t path_length;
+
+  path = (char*) req->path;
+  path_length = strlen(path);
+
+  /* EINVAL can be returned for 2 reasons:
+      1. The template's last 6 characters were not XXXXXX
+      2. open() didn't support O_CLOEXEC
+     We want to avoid going to the fallback path in case
+     of 1, so it's manually checked before. */
+  if (path_length < pattern_size ||
+      strcmp(path + path_length - pattern_size, pattern)) {
+    errno = EINVAL;
+    r = -1;
+    goto clobber;
+  }
+
+  uv_once(&once, uv__mkostemp_initonce);
+
+#ifdef O_CLOEXEC
+  if (uv__load_relaxed(&no_cloexec_support) == 0 && uv__mkostemp != NULL) {
+    r = uv__mkostemp(path, O_CLOEXEC);
+
+    if (r >= 0)
+      return r;
+
+    /* If mkostemp() returns EINVAL, it means the kernel doesn't
+       support O_CLOEXEC, so we just fallback to mkstemp() below. */
+    if (errno != EINVAL)
+      goto clobber;
+
+    /* We set the static variable so that next calls don't even
+       try to use mkostemp. */
+    uv__store_relaxed(&no_cloexec_support, 1);
+  }
+#endif  /* O_CLOEXEC */
+
+  if (req->cb != NULL)
+    uv_rwlock_rdlock(&req->loop->cloexec_lock);
+
+  r = mkstemp(path);
+
+  /* In case of failure `uv__cloexec` will leave error in `errno`,
+   * so it is enough to just set `r` to `-1`.
+   */
+  if (r >= 0 && uv__cloexec(r, 1) != 0) {
+    r = uv__close(r);
+    if (r != 0)
+      abort();
+    r = -1;
+  }
+
+  if (req->cb != NULL)
+    uv_rwlock_rdunlock(&req->loop->cloexec_lock);
+
+clobber:
+  if (r < 0)
+    path[0] = '\0';
+  return r;
+}
+
+
+static ssize_t uv__fs_open(uv_fs_t* req) {
+#ifdef O_CLOEXEC
+  return open(req->path, req->flags | O_CLOEXEC, req->mode);
+#else  /* O_CLOEXEC */
+  int r;
+
+  if (req->cb != NULL)
+    uv_rwlock_rdlock(&req->loop->cloexec_lock);
+
+  r = open(req->path, req->flags, req->mode);
+
+  /* In case of failure `uv__cloexec` will leave error in `errno`,
+   * so it is enough to just set `r` to `-1`.
+   */
+  if (r >= 0 && uv__cloexec(r, 1) != 0) {
+    r = uv__close(r);
+    if (r != 0)
+      abort();
+    r = -1;
+  }
+
+  if (req->cb != NULL)
+    uv_rwlock_rdunlock(&req->loop->cloexec_lock);
+
+  return r;
+#endif  /* O_CLOEXEC */
+}
+
+
+#if !HAVE_PREADV
+static ssize_t uv__fs_preadv(uv_file fd,
+                             uv_buf_t* bufs,
+                             unsigned int nbufs,
+                             off_t off) {
+  uv_buf_t* buf;
+  uv_buf_t* end;
+  ssize_t result;
+  ssize_t rc;
+  size_t pos;
+
+  assert(nbufs > 0);
+
+  result = 0;
+  pos = 0;
+  buf = bufs + 0;
+  end = bufs + nbufs;
+
+  for (;;) {
+    do
+      rc = pread(fd, buf->base + pos, buf->len - pos, off + result);
+    while (rc == -1 && errno == EINTR);
+
+    if (rc == 0)
+      break;
+
+    if (rc == -1 && result == 0)
+      return UV__ERR(errno);
+
+    if (rc == -1)
+      break;  /* We read some data so return that, ignore the error. */
+
+    pos += rc;
+    result += rc;
+
+    if (pos < buf->len)
+      continue;
+
+    pos = 0;
+    buf += 1;
+
+    if (buf == end)
+      break;
+  }
+
+  return result;
+}
+#endif
+
+
+static ssize_t uv__fs_read(uv_fs_t* req) {
+#if defined(__linux__)
+  static int no_preadv;
+#endif
+  unsigned int iovmax;
+  ssize_t result;
+
+  iovmax = uv__getiovmax();
+  if (req->nbufs > iovmax)
+    req->nbufs = iovmax;
+
+  if (req->off < 0) {
+    if (req->nbufs == 1)
+      result = read(req->file, req->bufs[0].base, req->bufs[0].len);
+    else
+      result = readv(req->file, (struct iovec*) req->bufs, req->nbufs);
+  } else {
+    if (req->nbufs == 1) {
+      result = pread(req->file, req->bufs[0].base, req->bufs[0].len, req->off);
+      goto done;
+    }
+
+#if HAVE_PREADV
+    result = preadv(req->file, (struct iovec*) req->bufs, req->nbufs, req->off);
+#else
+# if defined(__linux__)
+    if (uv__load_relaxed(&no_preadv)) retry:
+# endif
+    {
+      result = uv__fs_preadv(req->file, req->bufs, req->nbufs, req->off);
+    }
+# if defined(__linux__)
+    else {
+      result = uv__preadv(req->file,
+                          (struct iovec*)req->bufs,
+                          req->nbufs,
+                          req->off);
+      if (result == -1 && errno == ENOSYS) {
+        uv__store_relaxed(&no_preadv, 1);
+        goto retry;
+      }
+    }
+# endif
+#endif
+  }
+
+done:
+  /* Early cleanup of bufs allocation, since we're done with it. */
+  if (req->bufs != req->bufsml)
+    uv__free(req->bufs);
+
+  req->bufs = NULL;
+  req->nbufs = 0;
+
+#ifdef __PASE__
+  /* PASE returns EOPNOTSUPP when reading a directory, convert to EISDIR */
+  if (result == -1 && errno == EOPNOTSUPP) {
+    struct stat buf;
+    ssize_t rc;
+    rc = fstat(req->file, &buf);
+    if (rc == 0 && S_ISDIR(buf.st_mode)) {
+      errno = EISDIR;
+    }
+  }
+#endif
+
+  return result;
+}
+
+
+#if defined(__APPLE__) && !defined(MAC_OS_X_VERSION_10_8)
+#define UV_CONST_DIRENT uv__dirent_t
+#else
+#define UV_CONST_DIRENT const uv__dirent_t
+#endif
+
+
+static int uv__fs_scandir_filter(UV_CONST_DIRENT* dent) {
+  return strcmp(dent->d_name, ".") != 0 && strcmp(dent->d_name, "..") != 0;
+}
+
+
+static int uv__fs_scandir_sort(UV_CONST_DIRENT** a, UV_CONST_DIRENT** b) {
+  return strcmp((*a)->d_name, (*b)->d_name);
+}
+
+
+static ssize_t uv__fs_scandir(uv_fs_t* req) {
+  uv__dirent_t** dents;
+  int n;
+
+  dents = NULL;
+  n = scandir(req->path, &dents, uv__fs_scandir_filter, uv__fs_scandir_sort);
+
+  /* NOTE: We will use nbufs as an index field */
+  req->nbufs = 0;
+
+  if (n == 0) {
+    /* OS X still needs to deallocate some memory.
+     * Memory was allocated using the system allocator, so use free() here.
+     */
+    free(dents);
+    dents = NULL;
+  } else if (n == -1) {
+    return n;
+  }
+
+  req->ptr = dents;
+
+  return n;
+}
+
+static int uv__fs_opendir(uv_fs_t* req) {
+  uv_dir_t* dir;
+
+  dir = (uv_dir_t*)uv__malloc(sizeof(*dir));
+  if (dir == NULL)
+    goto error;
+
+  dir->dir = opendir(req->path);
+  if (dir->dir == NULL)
+    goto error;
+
+  req->ptr = dir;
+  return 0;
+
+error:
+  uv__free(dir);
+  req->ptr = NULL;
+  return -1;
+}
+
+static int uv__fs_readdir(uv_fs_t* req) {
+  uv_dir_t* dir;
+  uv_dirent_t* dirent;
+  struct dirent* res;
+  unsigned int dirent_idx;
+  unsigned int i;
+
+  dir = (uv_dir_t*)req->ptr;
+  dirent_idx = 0;
+
+  while (dirent_idx < dir->nentries) {
+    /* readdir() returns NULL on end of directory, as well as on error. errno
+       is used to differentiate between the two conditions. */
+    errno = 0;
+    res = readdir(dir->dir);
+
+    if (res == NULL) {
+      if (errno != 0)
+        goto error;
+      break;
+    }
+
+    if (strcmp(res->d_name, ".") == 0 || strcmp(res->d_name, "..") == 0)
+      continue;
+
+    dirent = &dir->dirents[dirent_idx];
+    dirent->name = uv__strdup(res->d_name);
+
+    if (dirent->name == NULL)
+      goto error;
+
+    dirent->type = uv__fs_get_dirent_type(res);
+    ++dirent_idx;
+  }
+
+  return dirent_idx;
+
+error:
+  for (i = 0; i < dirent_idx; ++i) {
+    uv__free((char*) dir->dirents[i].name);
+    dir->dirents[i].name = NULL;
+  }
+
+  return -1;
+}
+
+static int uv__fs_closedir(uv_fs_t* req) {
+  uv_dir_t* dir;
+
+  dir = (uv_dir_t*)req->ptr;
+
+  if (dir->dir != NULL) {
+    closedir(dir->dir);
+    dir->dir = NULL;
+  }
+
+  uv__free(req->ptr);
+  req->ptr = NULL;
+  return 0;
+}
+
+static int uv__fs_statfs(uv_fs_t* req) {
+  uv_statfs_t* stat_fs;
+#if defined(__sun)      || \
+    defined(__MVS__)    || \
+    defined(__NetBSD__) || \
+    defined(__HAIKU__)  || \
+    defined(__QNX__)
+  struct statvfs buf;
+
+  if (0 != statvfs(req->path, &buf))
+#else
+  struct statfs buf;
+
+  if (0 != statfs(req->path, &buf))
+#endif /* defined(__sun) */
+    return -1;
+
+  stat_fs = (uv_statfs_t*)uv__malloc(sizeof(*stat_fs));
+  if (stat_fs == NULL) {
+    errno = ENOMEM;
+    return -1;
+  }
+
+#if defined(__sun)        || \
+    defined(__MVS__)      || \
+    defined(__OpenBSD__)  || \
+    defined(__NetBSD__)   || \
+    defined(__HAIKU__)    || \
+    defined(__QNX__)
+  stat_fs->f_type = 0;  /* f_type is not supported. */
+#else
+  stat_fs->f_type = buf.f_type;
+#endif
+  stat_fs->f_bsize = buf.f_bsize;
+  stat_fs->f_blocks = buf.f_blocks;
+  stat_fs->f_bfree = buf.f_bfree;
+  stat_fs->f_bavail = buf.f_bavail;
+  stat_fs->f_files = buf.f_files;
+  stat_fs->f_ffree = buf.f_ffree;
+  req->ptr = stat_fs;
+  return 0;
+}
+
+static ssize_t uv__fs_pathmax_size(const char* path) {
+  ssize_t pathmax;
+
+  pathmax = pathconf(path, _PC_PATH_MAX);
+
+  if (pathmax == -1)
+    pathmax = UV__PATH_MAX;
+
+  return pathmax;
+}
+
+static ssize_t uv__fs_readlink(uv_fs_t* req) {
+  ssize_t maxlen;
+  ssize_t len;
+  char* buf;
+
+#if defined(_POSIX_PATH_MAX) || defined(PATH_MAX)
+  maxlen = uv__fs_pathmax_size(req->path);
+#else
+  /* We may not have a real PATH_MAX.  Read size of link.  */
+  struct stat st;
+  int ret;
+  ret = lstat(req->path, &st);
+  if (ret != 0)
+    return -1;
+  if (!S_ISLNK(st.st_mode)) {
+    errno = EINVAL;
+    return -1;
+  }
+
+  maxlen = st.st_size;
+
+  /* According to readlink(2) lstat can report st_size == 0
+     for some symlinks, such as those in /proc or /sys.  */
+  if (maxlen == 0)
+    maxlen = uv__fs_pathmax_size(req->path);
+#endif
+
+  buf = (char*)uv__malloc(maxlen);
+
+  if (buf == NULL) {
+    errno = ENOMEM;
+    return -1;
+  }
+
+#if defined(__MVS__)
+  len = os390_readlink(req->path, buf, maxlen);
+#else
+  len = readlink(req->path, buf, maxlen);
+#endif
+
+  if (len == -1) {
+    uv__free(buf);
+    return -1;
+  }
+
+  /* Uncommon case: resize to make room for the trailing nul byte. */
+  if (len == maxlen) {
+    buf = (char*)uv__reallocf(buf, len + 1);
+
+    if (buf == NULL)
+      return -1;
+  }
+
+  buf[len] = '\0';
+  req->ptr = buf;
+
+  return 0;
+}
+
+static ssize_t uv__fs_realpath(uv_fs_t* req) {
+  char* buf;
+
+#if defined(_POSIX_VERSION) && _POSIX_VERSION >= 200809L
+  buf = realpath(req->path, NULL);
+  if (buf == NULL)
+    return -1;
+#else
+  ssize_t len;
+
+  len = uv__fs_pathmax_size(req->path);
+  buf = (char*)uv__malloc(len + 1);
+
+  if (buf == NULL) {
+    errno = ENOMEM;
+    return -1;
+  }
+
+  if (realpath(req->path, buf) == NULL) {
+    uv__free(buf);
+    return -1;
+  }
+#endif
+
+  req->ptr = buf;
+
+  return 0;
+}
+
+static ssize_t uv__fs_sendfile_emul(uv_fs_t* req) {
+  struct pollfd pfd;
+  int use_pread;
+  off_t offset;
+  ssize_t nsent;
+  ssize_t nread;
+  ssize_t nwritten;
+  size_t buflen;
+  size_t len;
+  ssize_t n;
+  int in_fd;
+  int out_fd;
+  char buf[8192];
+
+  len = req->bufsml[0].len;
+  in_fd = req->flags;
+  out_fd = req->file;
+  offset = req->off;
+  use_pread = 1;
+
+  /* Here are the rules regarding errors:
+   *
+   * 1. Read errors are reported only if nsent==0, otherwise we return nsent.
+   *    The user needs to know that some data has already been sent, to stop
+   *    them from sending it twice.
+   *
+   * 2. Write errors are always reported. Write errors are bad because they
+   *    mean data loss: we've read data but now we can't write it out.
+   *
+   * We try to use pread() and fall back to regular read() if the source fd
+   * doesn't support positional reads, for example when it's a pipe fd.
+   *
+   * If we get EAGAIN when writing to the target fd, we poll() on it until
+   * it becomes writable again.
+   *
+   * FIXME: If we get a write error when use_pread==1, it should be safe to
+   *        return the number of sent bytes instead of an error because pread()
+   *        is, in theory, idempotent. However, special files in /dev or /proc
+   *        may support pread() but not necessarily return the same data on
+   *        successive reads.
+   *
+   * FIXME: There is no way now to signal that we managed to send *some* data
+   *        before a write error.
+   */
+  for (nsent = 0; (size_t) nsent < len; ) {
+    buflen = len - nsent;
+
+    if (buflen > sizeof(buf))
+      buflen = sizeof(buf);
+
+    do
+      if (use_pread)
+        nread = pread(in_fd, buf, buflen, offset);
+      else
+        nread = read(in_fd, buf, buflen);
+    while (nread == -1 && errno == EINTR);
+
+    if (nread == 0)
+      goto out;
+
+    if (nread == -1) {
+      if (use_pread && nsent == 0 && (errno == EIO || errno == ESPIPE)) {
+        use_pread = 0;
+        continue;
+      }
+
+      if (nsent == 0)
+        nsent = -1;
+
+      goto out;
+    }
+
+    for (nwritten = 0; nwritten < nread; ) {
+      do
+        n = write(out_fd, buf + nwritten, nread - nwritten);
+      while (n == -1 && errno == EINTR);
+
+      if (n != -1) {
+        nwritten += n;
+        continue;
+      }
+
+      if (errno != EAGAIN && errno != EWOULDBLOCK) {
+        nsent = -1;
+        goto out;
+      }
+
+      pfd.fd = out_fd;
+      pfd.events = POLLOUT;
+      pfd.revents = 0;
+
+      do
+        n = poll(&pfd, 1, -1);
+      while (n == -1 && errno == EINTR);
+
+      if (n == -1 || (pfd.revents & ~POLLOUT) != 0) {
+        errno = EIO;
+        nsent = -1;
+        goto out;
+      }
+    }
+
+    offset += nread;
+    nsent += nread;
+  }
+
+out:
+  if (nsent != -1)
+    req->off = offset;
+
+  return nsent;
+}
+
+
+#ifdef __linux__
+static unsigned uv__kernel_version(void) {
+  static unsigned cached_version;
+  struct utsname u;
+  unsigned version;
+  unsigned major;
+  unsigned minor;
+  unsigned patch;
+
+  version = uv__load_relaxed(&cached_version);
+  if (version != 0)
+    return version;
+
+  if (-1 == uname(&u))
+    return 0;
+
+  if (3 != sscanf(u.release, "%u.%u.%u", &major, &minor, &patch))
+    return 0;
+
+  version = major * 65536 + minor * 256 + patch;
+  uv__store_relaxed(&cached_version, version);
+
+  return version;
+}
+
+
+/* Pre-4.20 kernels have a bug where CephFS uses the RADOS copy-from command
+ * in copy_file_range() when it shouldn't. There is no workaround except to
+ * fall back to a regular copy.
+ */
+static int uv__is_buggy_cephfs(int fd) {
+  struct statfs s;
+
+  if (-1 == fstatfs(fd, &s))
+    return 0;
+
+  if (s.f_type != /* CephFS */ 0xC36400)
+    return 0;
+
+  return uv__kernel_version() < /* 4.20.0 */ 0x041400;
+}
+
+
+static int uv__is_cifs_or_smb(int fd) {
+  struct statfs s;
+
+  if (-1 == fstatfs(fd, &s))
+    return 0;
+
+  switch ((unsigned) s.f_type) {
+  case 0x0000517Bu:  /* SMB */
+  case 0xFE534D42u:  /* SMB2 */
+  case 0xFF534D42u:  /* CIFS */
+    return 1;
+  }
+
+  return 0;
+}
+
+
+static ssize_t uv__fs_try_copy_file_range(int in_fd, off_t* off,
+                                          int out_fd, size_t len) {
+  static int no_copy_file_range_support;
+  ssize_t r;
+
+  if (uv__load_relaxed(&no_copy_file_range_support)) {
+    errno = ENOSYS;
+    return -1;
+  }
+
+  r = uv__fs_copy_file_range(in_fd, off, out_fd, NULL, len, 0);
+
+  if (r != -1)
+    return r;
+
+  switch (errno) {
+  case EACCES:
+    /* Pre-4.20 kernels have a bug where CephFS uses the RADOS
+     * copy-from command when it shouldn't.
+     */
+    if (uv__is_buggy_cephfs(in_fd))
+      errno = ENOSYS;  /* Use fallback. */
+    break;
+  case ENOSYS:
+    uv__store_relaxed(&no_copy_file_range_support, 1);
+    break;
+  case EPERM:
+    /* It's been reported that CIFS spuriously fails.
+     * Consider it a transient error.
+     */
+    if (uv__is_cifs_or_smb(out_fd))
+      errno = ENOSYS;  /* Use fallback. */
+    break;
+  case ENOTSUP:
+  case EXDEV:
+    /* ENOTSUP - it could work on another file system type.
+     * EXDEV - it will not work when in_fd and out_fd are not on the same
+     *         mounted filesystem (pre Linux 5.3)
+     */
+    errno = ENOSYS;  /* Use fallback. */
+    break;
+  }
+
+  return -1;
+}
+
+#endif  /* __linux__ */
+
+
+static ssize_t uv__fs_sendfile(uv_fs_t* req) {
+  int in_fd;
+  int out_fd;
+
+  in_fd = req->flags;
+  out_fd = req->file;
+
+#if defined(__linux__) || defined(__sun)
+  {
+    off_t off;
+    ssize_t r;
+    size_t len;
+    int try_sendfile;
+
+    off = req->off;
+    len = req->bufsml[0].len;
+    try_sendfile = 1;
+
+#ifdef __linux__
+    r = uv__fs_try_copy_file_range(in_fd, &off, out_fd, len);
+    try_sendfile = (r == -1 && errno == ENOSYS);
+#endif
+
+    if (try_sendfile)
+      r = sendfile(out_fd, in_fd, &off, len);
+
+    /* sendfile() on SunOS returns EINVAL if the target fd is not a socket but
+     * it still writes out data. Fortunately, we can detect it by checking if
+     * the offset has been updated.
+     */
+    if (r != -1 || off > req->off) {
+      r = off - req->off;
+      req->off = off;
+      return r;
+    }
+
+    if (errno == EINVAL ||
+        errno == EIO ||
+        errno == ENOTSOCK ||
+        errno == EXDEV) {
+      errno = 0;
+      return uv__fs_sendfile_emul(req);
+    }
+
+    return -1;
+  }
+#elif defined(__APPLE__)           || \
+      defined(__DragonFly__)       || \
+      defined(__FreeBSD__)         || \
+      defined(__FreeBSD_kernel__)
+  {
+    off_t len;
+    ssize_t r;
+
+    /* sendfile() on FreeBSD and Darwin returns EAGAIN if the target fd is in
+     * non-blocking mode and not all data could be written. If a non-zero
+     * number of bytes have been sent, we don't consider it an error.
+     */
+
+#if defined(__FreeBSD__) || defined(__DragonFly__)
+#if defined(__FreeBSD__)
+    off_t off;
+
+    off = req->off;
+    r = uv__fs_copy_file_range(in_fd, &off, out_fd, NULL, req->bufsml[0].len, 0);
+    if (r >= 0) {
+        r = off - req->off;
+        req->off = off;
+        return r;
+    }
+#endif
+    len = 0;
+    r = sendfile(in_fd, out_fd, req->off, req->bufsml[0].len, NULL, &len, 0);
+#elif defined(__FreeBSD_kernel__)
+    len = 0;
+    r = bsd_sendfile(in_fd,
+                     out_fd,
+                     req->off,
+                     req->bufsml[0].len,
+                     NULL,
+                     &len,
+                     0);
+#else
+    /* The darwin sendfile takes len as an input for the length to send,
+     * so make sure to initialize it with the caller's value. */
+    len = req->bufsml[0].len;
+    r = sendfile(in_fd, out_fd, req->off, &len, NULL, 0);
+#endif
+
+     /*
+     * The man page for sendfile(2) on DragonFly states that `len` contains
+     * a meaningful value ONLY in case of EAGAIN and EINTR.
+     * Nothing is said about it's value in case of other errors, so better
+     * not depend on the potential wrong assumption that is was not modified
+     * by the syscall.
+     */
+    if (r == 0 || ((errno == EAGAIN || errno == EINTR) && len != 0)) {
+      req->off += len;
+      return (ssize_t) len;
+    }
+
+    if (errno == EINVAL ||
+        errno == EIO ||
+        errno == ENOTSOCK ||
+        errno == EXDEV) {
+      errno = 0;
+      return uv__fs_sendfile_emul(req);
+    }
+
+    return -1;
+  }
+#else
+  /* Squelch compiler warnings. */
+  (void) &in_fd;
+  (void) &out_fd;
+
+  return uv__fs_sendfile_emul(req);
+#endif
+}
+
+
+static ssize_t uv__fs_utime(uv_fs_t* req) {
+#if defined(__linux__)                                                         \
+    || defined(_AIX71)                                                         \
+    || defined(__sun)                                                          \
+    || defined(__HAIKU__)
+  struct timespec ts[2];
+  ts[0] = uv__fs_to_timespec(req->atime);
+  ts[1] = uv__fs_to_timespec(req->mtime);
+  return utimensat(AT_FDCWD, req->path, ts, 0);
+#elif defined(__APPLE__)                                                      \
+    || defined(__DragonFly__)                                                 \
+    || defined(__FreeBSD__)                                                   \
+    || defined(__FreeBSD_kernel__)                                            \
+    || defined(__NetBSD__)                                                    \
+    || defined(__OpenBSD__)
+  struct timeval tv[2];
+  tv[0] = uv__fs_to_timeval(req->atime);
+  tv[1] = uv__fs_to_timeval(req->mtime);
+  return utimes(req->path, tv);
+#elif defined(_AIX)                                                           \
+    && !defined(_AIX71)
+  struct utimbuf buf;
+  buf.actime = req->atime;
+  buf.modtime = req->mtime;
+  return utime(req->path, &buf);
+#elif defined(__MVS__)
+  attrib_t atr;
+  memset(&atr, 0, sizeof(atr));
+  atr.att_mtimechg = 1;
+  atr.att_atimechg = 1;
+  atr.att_mtime = req->mtime;
+  atr.att_atime = req->atime;
+  return __lchattr((char*) req->path, &atr, sizeof(atr));
+#else
+  errno = ENOSYS;
+  return -1;
+#endif
+}
+
+
+static ssize_t uv__fs_lutime(uv_fs_t* req) {
+#if defined(__linux__)            ||                                           \
+    defined(_AIX71)               ||                                           \
+    defined(__sun)                ||                                           \
+    defined(__HAIKU__)            ||                                           \
+    defined(__GNU__)              ||                                           \
+    defined(__OpenBSD__)
+  struct timespec ts[2];
+  ts[0] = uv__fs_to_timespec(req->atime);
+  ts[1] = uv__fs_to_timespec(req->mtime);
+  return utimensat(AT_FDCWD, req->path, ts, AT_SYMLINK_NOFOLLOW);
+#elif defined(__APPLE__)          ||                                          \
+      defined(__DragonFly__)      ||                                          \
+      defined(__FreeBSD__)        ||                                          \
+      defined(__FreeBSD_kernel__) ||                                          \
+      defined(__NetBSD__)
+  struct timeval tv[2];
+  tv[0] = uv__fs_to_timeval(req->atime);
+  tv[1] = uv__fs_to_timeval(req->mtime);
+  return lutimes(req->path, tv);
+#else
+  errno = ENOSYS;
+  return -1;
+#endif
+}
+
+
+static ssize_t uv__fs_write(uv_fs_t* req) {
+#if defined(__linux__)
+  static int no_pwritev;
+#endif
+  ssize_t r;
+
+  /* Serialize writes on OS X, concurrent write() and pwrite() calls result in
+   * data loss. We can't use a per-file descriptor lock, the descriptor may be
+   * a dup().
+   */
+#if defined(__APPLE__)
+  static pthread_mutex_t lock = PTHREAD_MUTEX_INITIALIZER;
+
+  if (pthread_mutex_lock(&lock))
+    abort();
+#endif
+
+  if (req->off < 0) {
+    if (req->nbufs == 1)
+      r = write(req->file, req->bufs[0].base, req->bufs[0].len);
+    else
+      r = writev(req->file, (struct iovec*) req->bufs, req->nbufs);
+  } else {
+    if (req->nbufs == 1) {
+      r = pwrite(req->file, req->bufs[0].base, req->bufs[0].len, req->off);
+      goto done;
+    }
+#if HAVE_PREADV
+    r = pwritev(req->file, (struct iovec*) req->bufs, req->nbufs, req->off);
+#else
+# if defined(__linux__)
+    if (no_pwritev) retry:
+# endif
+    {
+      r = pwrite(req->file, req->bufs[0].base, req->bufs[0].len, req->off);
+    }
+# if defined(__linux__)
+    else {
+      r = uv__pwritev(req->file,
+                      (struct iovec*) req->bufs,
+                      req->nbufs,
+                      req->off);
+      if (r == -1 && errno == ENOSYS) {
+        no_pwritev = 1;
+        goto retry;
+      }
+    }
+# endif
+#endif
+  }
+
+done:
+#if defined(__APPLE__)
+  if (pthread_mutex_unlock(&lock))
+    abort();
+#endif
+
+  return r;
+}
+
+static ssize_t uv__fs_copyfile(uv_fs_t* req) {
+  uv_fs_t fs_req;
+  uv_file srcfd;
+  uv_file dstfd;
+  struct stat src_statsbuf;
+  struct stat dst_statsbuf;
+  int dst_flags;
+  int result;
+  int err;
+  off_t bytes_to_send;
+  off_t in_offset;
+  off_t bytes_written;
+  size_t bytes_chunk;
+
+  dstfd = -1;
+  err = 0;
+
+  /* Open the source file. */
+  srcfd = uv_fs_open(NULL, &fs_req, req->path, O_RDONLY, 0, NULL);
+  uv_fs_req_cleanup(&fs_req);
+
+  if (srcfd < 0)
+    return srcfd;
+
+  /* Get the source file's mode. */
+  if (fstat(srcfd, &src_statsbuf)) {
+    err = UV__ERR(errno);
+    goto out;
+  }
+
+  dst_flags = O_WRONLY | O_CREAT;
+
+  if (req->flags & UV_FS_COPYFILE_EXCL)
+    dst_flags |= O_EXCL;
+
+  /* Open the destination file. */
+  dstfd = uv_fs_open(NULL,
+                     &fs_req,
+                     req->new_path,
+                     dst_flags,
+                     src_statsbuf.st_mode,
+                     NULL);
+  uv_fs_req_cleanup(&fs_req);
+
+  if (dstfd < 0) {
+    err = dstfd;
+    goto out;
+  }
+
+  /* If the file is not being opened exclusively, verify that the source and
+     destination are not the same file. If they are the same, bail out early. */
+  if ((req->flags & UV_FS_COPYFILE_EXCL) == 0) {
+    /* Get the destination file's mode. */
+    if (fstat(dstfd, &dst_statsbuf)) {
+      err = UV__ERR(errno);
+      goto out;
+    }
+
+    /* Check if srcfd and dstfd refer to the same file */
+    if (src_statsbuf.st_dev == dst_statsbuf.st_dev &&
+        src_statsbuf.st_ino == dst_statsbuf.st_ino) {
+      goto out;
+    }
+
+    /* Truncate the file in case the destination already existed. */
+    if (ftruncate(dstfd, 0) != 0) {
+      err = UV__ERR(errno);
+      goto out;
+    }
+  }
+
+  if (fchmod(dstfd, src_statsbuf.st_mode) == -1) {
+    err = UV__ERR(errno);
+#ifdef __linux__
+    /* fchmod() on CIFS shares always fails with EPERM unless the share is
+     * mounted with "noperm". As fchmod() is a meaningless operation on such
+     * shares anyway, detect that condition and squelch the error.
+     */
+    if (err != UV_EPERM)
+      goto out;
+
+    if (!uv__is_cifs_or_smb(dstfd))
+      goto out;
+
+    err = 0;
+#else  /* !__linux__ */
+    goto out;
+#endif  /* !__linux__ */
+  }
+
+#ifdef FICLONE
+  if (req->flags & UV_FS_COPYFILE_FICLONE ||
+      req->flags & UV_FS_COPYFILE_FICLONE_FORCE) {
+    if (ioctl(dstfd, FICLONE, srcfd) == 0) {
+      /* ioctl() with FICLONE succeeded. */
+      goto out;
+    }
+    /* If an error occurred and force was set, return the error to the caller;
+     * fall back to sendfile() when force was not set. */
+    if (req->flags & UV_FS_COPYFILE_FICLONE_FORCE) {
+      err = UV__ERR(errno);
+      goto out;
+    }
+  }
+#else
+  if (req->flags & UV_FS_COPYFILE_FICLONE_FORCE) {
+    err = UV_ENOSYS;
+    goto out;
+  }
+#endif
+
+  bytes_to_send = src_statsbuf.st_size;
+  in_offset = 0;
+  while (bytes_to_send != 0) {
+    bytes_chunk = SSIZE_MAX;
+    if (bytes_to_send < (off_t) bytes_chunk)
+      bytes_chunk = bytes_to_send;
+    uv_fs_sendfile(NULL, &fs_req, dstfd, srcfd, in_offset, bytes_chunk, NULL);
+    bytes_written = fs_req.result;
+    uv_fs_req_cleanup(&fs_req);
+
+    if (bytes_written < 0) {
+      err = bytes_written;
+      break;
+    }
+
+    bytes_to_send -= bytes_written;
+    in_offset += bytes_written;
+  }
+
+out:
+  if (err < 0)
+    result = err;
+  else
+    result = 0;
+
+  /* Close the source file. */
+  err = uv__close_nocheckstdio(srcfd);
+
+  /* Don't overwrite any existing errors. */
+  if (err != 0 && result == 0)
+    result = err;
+
+  /* Close the destination file if it is open. */
+  if (dstfd >= 0) {
+    err = uv__close_nocheckstdio(dstfd);
+
+    /* Don't overwrite any existing errors. */
+    if (err != 0 && result == 0)
+      result = err;
+
+    /* Remove the destination file if something went wrong. */
+    if (result != 0) {
+      uv_fs_unlink(NULL, &fs_req, req->new_path, NULL);
+      /* Ignore the unlink return value, as an error already happened. */
+      uv_fs_req_cleanup(&fs_req);
+    }
+  }
+
+  if (result == 0)
+    return 0;
+
+  errno = UV__ERR(result);
+  return -1;
+}
+
+static void uv__to_stat(struct stat* src, uv_stat_t* dst) {
+  dst->st_dev = src->st_dev;
+  dst->st_mode = src->st_mode;
+  dst->st_nlink = src->st_nlink;
+  dst->st_uid = src->st_uid;
+  dst->st_gid = src->st_gid;
+  dst->st_rdev = src->st_rdev;
+  dst->st_ino = src->st_ino;
+  dst->st_size = src->st_size;
+  dst->st_blksize = src->st_blksize;
+  dst->st_blocks = src->st_blocks;
+
+#if defined(__APPLE__)
+  dst->st_atim.tv_sec = src->st_atimespec.tv_sec;
+  dst->st_atim.tv_nsec = src->st_atimespec.tv_nsec;
+  dst->st_mtim.tv_sec = src->st_mtimespec.tv_sec;
+  dst->st_mtim.tv_nsec = src->st_mtimespec.tv_nsec;
+  dst->st_ctim.tv_sec = src->st_ctimespec.tv_sec;
+  dst->st_ctim.tv_nsec = src->st_ctimespec.tv_nsec;
+  dst->st_birthtim.tv_sec = src->st_birthtimespec.tv_sec;
+  dst->st_birthtim.tv_nsec = src->st_birthtimespec.tv_nsec;
+  dst->st_flags = src->st_flags;
+  dst->st_gen = src->st_gen;
+#elif defined(__ANDROID__)
+  dst->st_atim.tv_sec = src->st_atime;
+  dst->st_atim.tv_nsec = src->st_atimensec;
+  dst->st_mtim.tv_sec = src->st_mtime;
+  dst->st_mtim.tv_nsec = src->st_mtimensec;
+  dst->st_ctim.tv_sec = src->st_ctime;
+  dst->st_ctim.tv_nsec = src->st_ctimensec;
+  dst->st_birthtim.tv_sec = src->st_ctime;
+  dst->st_birthtim.tv_nsec = src->st_ctimensec;
+  dst->st_flags = 0;
+  dst->st_gen = 0;
+#elif !defined(_AIX) &&         \
+    !defined(__MVS__) && (      \
+    defined(__DragonFly__)   || \
+    defined(__FreeBSD__)     || \
+    defined(__OpenBSD__)     || \
+    defined(__NetBSD__)      || \
+    defined(_GNU_SOURCE)     || \
+    defined(_BSD_SOURCE)     || \
+    defined(_SVID_SOURCE)    || \
+    defined(_XOPEN_SOURCE)   || \
+    defined(_DEFAULT_SOURCE))
+  dst->st_atim.tv_sec = src->st_atim.tv_sec;
+  dst->st_atim.tv_nsec = src->st_atim.tv_nsec;
+  dst->st_mtim.tv_sec = src->st_mtim.tv_sec;
+  dst->st_mtim.tv_nsec = src->st_mtim.tv_nsec;
+  dst->st_ctim.tv_sec = src->st_ctim.tv_sec;
+  dst->st_ctim.tv_nsec = src->st_ctim.tv_nsec;
+# if defined(__FreeBSD__)    || \
+     defined(__NetBSD__)
+  dst->st_birthtim.tv_sec = src->st_birthtim.tv_sec;
+  dst->st_birthtim.tv_nsec = src->st_birthtim.tv_nsec;
+  dst->st_flags = src->st_flags;
+  dst->st_gen = src->st_gen;
+# else
+  dst->st_birthtim.tv_sec = src->st_ctim.tv_sec;
+  dst->st_birthtim.tv_nsec = src->st_ctim.tv_nsec;
+  dst->st_flags = 0;
+  dst->st_gen = 0;
+# endif
+#else
+  dst->st_atim.tv_sec = src->st_atime;
+  dst->st_atim.tv_nsec = 0;
+  dst->st_mtim.tv_sec = src->st_mtime;
+  dst->st_mtim.tv_nsec = 0;
+  dst->st_ctim.tv_sec = src->st_ctime;
+  dst->st_ctim.tv_nsec = 0;
+  dst->st_birthtim.tv_sec = src->st_ctime;
+  dst->st_birthtim.tv_nsec = 0;
+  dst->st_flags = 0;
+  dst->st_gen = 0;
+#endif
+}
+
+
+static int uv__fs_statx(int fd,
+                        const char* path,
+                        int is_fstat,
+                        int is_lstat,
+                        uv_stat_t* buf) {
+  STATIC_ASSERT(UV_ENOSYS != -1);
+#ifdef __linux__
+  static int no_statx;
+  struct uv__statx statxbuf;
+  int dirfd;
+  int flags;
+  int mode;
+  int rc;
+
+  if (uv__load_relaxed(&no_statx))
+    return UV_ENOSYS;
+
+  dirfd = AT_FDCWD;
+  flags = 0; /* AT_STATX_SYNC_AS_STAT */
+  mode = 0xFFF; /* STATX_BASIC_STATS + STATX_BTIME */
+
+  if (is_fstat) {
+    dirfd = fd;
+    flags |= 0x1000; /* AT_EMPTY_PATH */
+  }
+
+  if (is_lstat)
+    flags |= AT_SYMLINK_NOFOLLOW;
+
+  rc = uv__statx(dirfd, path, flags, mode, &statxbuf);
+
+  switch (rc) {
+  case 0:
+    break;
+  case -1:
+    /* EPERM happens when a seccomp filter rejects the system call.
+     * Has been observed with libseccomp < 2.3.3 and docker < 18.04.
+     * EOPNOTSUPP is used on DVS exported filesystems
+     */
+    if (errno != EINVAL && errno != EPERM && errno != ENOSYS && errno != EOPNOTSUPP)
+      return -1;
+    /* Fall through. */
+  default:
+    /* Normally on success, zero is returned and On error, -1 is returned.
+     * Observed on S390 RHEL running in a docker container with statx not
+     * implemented, rc might return 1 with 0 set as the error code in which
+     * case we return ENOSYS.
+     */
+    uv__store_relaxed(&no_statx, 1);
+    return UV_ENOSYS;
+  }
+
+  buf->st_dev = makedev(statxbuf.stx_dev_major, statxbuf.stx_dev_minor);
+  buf->st_mode = statxbuf.stx_mode;
+  buf->st_nlink = statxbuf.stx_nlink;
+  buf->st_uid = statxbuf.stx_uid;
+  buf->st_gid = statxbuf.stx_gid;
+  buf->st_rdev = makedev(statxbuf.stx_rdev_major, statxbuf.stx_rdev_minor);
+  buf->st_ino = statxbuf.stx_ino;
+  buf->st_size = statxbuf.stx_size;
+  buf->st_blksize = statxbuf.stx_blksize;
+  buf->st_blocks = statxbuf.stx_blocks;
+  buf->st_atim.tv_sec = statxbuf.stx_atime.tv_sec;
+  buf->st_atim.tv_nsec = statxbuf.stx_atime.tv_nsec;
+  buf->st_mtim.tv_sec = statxbuf.stx_mtime.tv_sec;
+  buf->st_mtim.tv_nsec = statxbuf.stx_mtime.tv_nsec;
+  buf->st_ctim.tv_sec = statxbuf.stx_ctime.tv_sec;
+  buf->st_ctim.tv_nsec = statxbuf.stx_ctime.tv_nsec;
+  buf->st_birthtim.tv_sec = statxbuf.stx_btime.tv_sec;
+  buf->st_birthtim.tv_nsec = statxbuf.stx_btime.tv_nsec;
+  buf->st_flags = 0;
+  buf->st_gen = 0;
+
+  return 0;
+#else
+  return UV_ENOSYS;
+#endif /* __linux__ */
+}
+
+
+static int uv__fs_stat(const char *path, uv_stat_t *buf) {
+  struct stat pbuf;
+  int ret;
+
+  ret = uv__fs_statx(-1, path, /* is_fstat */ 0, /* is_lstat */ 0, buf);
+  if (ret != UV_ENOSYS)
+    return ret;
+
+  ret = stat(path, &pbuf);
+  if (ret == 0)
+    uv__to_stat(&pbuf, buf);
+
+  return ret;
+}
+
+
+static int uv__fs_lstat(const char *path, uv_stat_t *buf) {
+  struct stat pbuf;
+  int ret;
+
+  ret = uv__fs_statx(-1, path, /* is_fstat */ 0, /* is_lstat */ 1, buf);
+  if (ret != UV_ENOSYS)
+    return ret;
+
+  ret = lstat(path, &pbuf);
+  if (ret == 0)
+    uv__to_stat(&pbuf, buf);
+
+  return ret;
+}
+
+
+static int uv__fs_fstat(int fd, uv_stat_t *buf) {
+  struct stat pbuf;
+  int ret;
+
+  ret = uv__fs_statx(fd, "", /* is_fstat */ 1, /* is_lstat */ 0, buf);
+  if (ret != UV_ENOSYS)
+    return ret;
+
+  ret = fstat(fd, &pbuf);
+  if (ret == 0)
+    uv__to_stat(&pbuf, buf);
+
+  return ret;
+}
+
+static size_t uv__fs_buf_offset(uv_buf_t* bufs, size_t size) {
+  size_t offset;
+  /* Figure out which bufs are done */
+  for (offset = 0; size > 0 && bufs[offset].len <= size; ++offset)
+    size -= bufs[offset].len;
+
+  /* Fix a partial read/write */
+  if (size > 0) {
+    bufs[offset].base += size;
+    bufs[offset].len -= size;
+  }
+  return offset;
+}
+
+static ssize_t uv__fs_write_all(uv_fs_t* req) {
+  unsigned int iovmax;
+  unsigned int nbufs;
+  uv_buf_t* bufs;
+  ssize_t total;
+  ssize_t result;
+
+  iovmax = uv__getiovmax();
+  nbufs = req->nbufs;
+  bufs = req->bufs;
+  total = 0;
+
+  while (nbufs > 0) {
+    req->nbufs = nbufs;
+    if (req->nbufs > iovmax)
+      req->nbufs = iovmax;
+
+    do
+      result = uv__fs_write(req);
+    while (result < 0 && errno == EINTR);
+
+    if (result <= 0) {
+      if (total == 0)
+        total = result;
+      break;
+    }
+
+    if (req->off >= 0)
+      req->off += result;
+
+    req->nbufs = uv__fs_buf_offset(req->bufs, result);
+    req->bufs += req->nbufs;
+    nbufs -= req->nbufs;
+    total += result;
+  }
+
+  if (bufs != req->bufsml)
+    uv__free(bufs);
+
+  req->bufs = NULL;
+  req->nbufs = 0;
+
+  return total;
+}
+
+
+static void uv__fs_work(struct uv__work* w) {
+  int retry_on_eintr;
+  uv_fs_t* req;
+  ssize_t r;
+
+  req = container_of(w, uv_fs_t, work_req);
+  retry_on_eintr = !(req->fs_type == UV_FS_CLOSE ||
+                     req->fs_type == UV_FS_READ);
+
+  do {
+    errno = 0;
+
+#define X(type, action)                                                       \
+  case UV_FS_ ## type:                                                        \
+    r = action;                                                               \
+    break;
+
+    switch (req->fs_type) {
+    X(ACCESS, access(req->path, req->flags));
+    X(CHMOD, chmod(req->path, req->mode));
+    X(CHOWN, chown(req->path, req->uid, req->gid));
+    X(CLOSE, uv__fs_close(req->file));
+    X(COPYFILE, uv__fs_copyfile(req));
+    X(FCHMOD, fchmod(req->file, req->mode));
+    X(FCHOWN, fchown(req->file, req->uid, req->gid));
+    X(LCHOWN, lchown(req->path, req->uid, req->gid));
+    X(FDATASYNC, uv__fs_fdatasync(req));
+    X(FSTAT, uv__fs_fstat(req->file, &req->statbuf));
+    X(FSYNC, uv__fs_fsync(req));
+    X(FTRUNCATE, ftruncate(req->file, req->off));
+    X(FUTIME, uv__fs_futime(req));
+    X(LUTIME, uv__fs_lutime(req));
+    X(LSTAT, uv__fs_lstat(req->path, &req->statbuf));
+    X(LINK, link(req->path, req->new_path));
+    X(MKDIR, mkdir(req->path, req->mode));
+    X(MKDTEMP, uv__fs_mkdtemp(req));
+    X(MKSTEMP, uv__fs_mkstemp(req));
+    X(OPEN, uv__fs_open(req));
+    X(READ, uv__fs_read(req));
+    X(SCANDIR, uv__fs_scandir(req));
+    X(OPENDIR, uv__fs_opendir(req));
+    X(READDIR, uv__fs_readdir(req));
+    X(CLOSEDIR, uv__fs_closedir(req));
+    X(READLINK, uv__fs_readlink(req));
+    X(REALPATH, uv__fs_realpath(req));
+    X(RENAME, rename(req->path, req->new_path));
+    X(RMDIR, rmdir(req->path));
+    X(SENDFILE, uv__fs_sendfile(req));
+    X(STAT, uv__fs_stat(req->path, &req->statbuf));
+    X(STATFS, uv__fs_statfs(req));
+    X(SYMLINK, symlink(req->path, req->new_path));
+    X(UNLINK, unlink(req->path));
+    X(UTIME, uv__fs_utime(req));
+    X(WRITE, uv__fs_write_all(req));
+    default: abort();
+    }
+#undef X
+  } while (r == -1 && errno == EINTR && retry_on_eintr);
+
+  if (r == -1)
+    req->result = UV__ERR(errno);
+  else
+    req->result = r;
+
+  if (r == 0 && (req->fs_type == UV_FS_STAT ||
+                 req->fs_type == UV_FS_FSTAT ||
+                 req->fs_type == UV_FS_LSTAT)) {
+    req->ptr = &req->statbuf;
+  }
+}
+
+
+static void uv__fs_done(struct uv__work* w, int status) {
+  uv_fs_t* req;
+
+  req = container_of(w, uv_fs_t, work_req);
+  uv__req_unregister(req->loop, req);
+
+  if (status == UV_ECANCELED) {
+    assert(req->result == 0);
+    req->result = UV_ECANCELED;
+  }
+
+  req->cb(req);
+}
+
+
+int uv_fs_access(uv_loop_t* loop,
+                 uv_fs_t* req,
+                 const char* path,
+                 int flags,
+                 uv_fs_cb cb) {
+  INIT(ACCESS);
+  PATH;
+  req->flags = flags;
+  POST;
+}
+
+
+int uv_fs_chmod(uv_loop_t* loop,
+                uv_fs_t* req,
+                const char* path,
+                int mode,
+                uv_fs_cb cb) {
+  INIT(CHMOD);
+  PATH;
+  req->mode = mode;
+  POST;
+}
+
+
+int uv_fs_chown(uv_loop_t* loop,
+                uv_fs_t* req,
+                const char* path,
+                uv_uid_t uid,
+                uv_gid_t gid,
+                uv_fs_cb cb) {
+  INIT(CHOWN);
+  PATH;
+  req->uid = uid;
+  req->gid = gid;
+  POST;
+}
+
+
+int uv_fs_close(uv_loop_t* loop, uv_fs_t* req, uv_file file, uv_fs_cb cb) {
+  INIT(CLOSE);
+  req->file = file;
+  POST;
+}
+
+
+int uv_fs_fchmod(uv_loop_t* loop,
+                 uv_fs_t* req,
+                 uv_file file,
+                 int mode,
+                 uv_fs_cb cb) {
+  INIT(FCHMOD);
+  req->file = file;
+  req->mode = mode;
+  POST;
+}
+
+
+int uv_fs_fchown(uv_loop_t* loop,
+                 uv_fs_t* req,
+                 uv_file file,
+                 uv_uid_t uid,
+                 uv_gid_t gid,
+                 uv_fs_cb cb) {
+  INIT(FCHOWN);
+  req->file = file;
+  req->uid = uid;
+  req->gid = gid;
+  POST;
+}
+
+
+int uv_fs_lchown(uv_loop_t* loop,
+                 uv_fs_t* req,
+                 const char* path,
+                 uv_uid_t uid,
+                 uv_gid_t gid,
+                 uv_fs_cb cb) {
+  INIT(LCHOWN);
+  PATH;
+  req->uid = uid;
+  req->gid = gid;
+  POST;
+}
+
+
+int uv_fs_fdatasync(uv_loop_t* loop, uv_fs_t* req, uv_file file, uv_fs_cb cb) {
+  INIT(FDATASYNC);
+  req->file = file;
+  POST;
+}
+
+
+int uv_fs_fstat(uv_loop_t* loop, uv_fs_t* req, uv_file file, uv_fs_cb cb) {
+  INIT(FSTAT);
+  req->file = file;
+  POST;
+}
+
+
+int uv_fs_fsync(uv_loop_t* loop, uv_fs_t* req, uv_file file, uv_fs_cb cb) {
+  INIT(FSYNC);
+  req->file = file;
+  POST;
+}
+
+
+int uv_fs_ftruncate(uv_loop_t* loop,
+                    uv_fs_t* req,
+                    uv_file file,
+                    int64_t off,
+                    uv_fs_cb cb) {
+  INIT(FTRUNCATE);
+  req->file = file;
+  req->off = off;
+  POST;
+}
+
+
+int uv_fs_futime(uv_loop_t* loop,
+                 uv_fs_t* req,
+                 uv_file file,
+                 double atime,
+                 double mtime,
+                 uv_fs_cb cb) {
+  INIT(FUTIME);
+  req->file = file;
+  req->atime = atime;
+  req->mtime = mtime;
+  POST;
+}
+
+int uv_fs_lutime(uv_loop_t* loop,
+                 uv_fs_t* req,
+                 const char* path,
+                 double atime,
+                 double mtime,
+                 uv_fs_cb cb) {
+  INIT(LUTIME);
+  PATH;
+  req->atime = atime;
+  req->mtime = mtime;
+  POST;
+}
+
+
+int uv_fs_lstat(uv_loop_t* loop, uv_fs_t* req, const char* path, uv_fs_cb cb) {
+  INIT(LSTAT);
+  PATH;
+  POST;
+}
+
+
+int uv_fs_link(uv_loop_t* loop,
+               uv_fs_t* req,
+               const char* path,
+               const char* new_path,
+               uv_fs_cb cb) {
+  INIT(LINK);
+  PATH2;
+  POST;
+}
+
+
+int uv_fs_mkdir(uv_loop_t* loop,
+                uv_fs_t* req,
+                const char* path,
+                int mode,
+                uv_fs_cb cb) {
+  INIT(MKDIR);
+  PATH;
+  req->mode = mode;
+  POST;
+}
+
+
+int uv_fs_mkdtemp(uv_loop_t* loop,
+                  uv_fs_t* req,
+                  const char* tpl,
+                  uv_fs_cb cb) {
+  INIT(MKDTEMP);
+  req->path = uv__strdup(tpl);
+  if (req->path == NULL)
+    return UV_ENOMEM;
+  POST;
+}
+
+
+int uv_fs_mkstemp(uv_loop_t* loop,
+                  uv_fs_t* req,
+                  const char* tpl,
+                  uv_fs_cb cb) {
+  INIT(MKSTEMP);
+  req->path = uv__strdup(tpl);
+  if (req->path == NULL)
+    return UV_ENOMEM;
+  POST;
+}
+
+
+int uv_fs_open(uv_loop_t* loop,
+               uv_fs_t* req,
+               const char* path,
+               int flags,
+               int mode,
+               uv_fs_cb cb) {
+  INIT(OPEN);
+  PATH;
+  req->flags = flags;
+  req->mode = mode;
+  POST;
+}
+
+
+int uv_fs_read(uv_loop_t* loop, uv_fs_t* req,
+               uv_file file,
+               const uv_buf_t bufs[],
+               unsigned int nbufs,
+               int64_t off,
+               uv_fs_cb cb) {
+  INIT(READ);
+
+  if (bufs == NULL || nbufs == 0)
+    return UV_EINVAL;
+
+  req->file = file;
+
+  req->nbufs = nbufs;
+  req->bufs = req->bufsml;
+  if (nbufs > ARRAY_SIZE(req->bufsml))
+    req->bufs = (uv_buf_t*)uv__malloc(nbufs * sizeof(*bufs));
+
+  if (req->bufs == NULL)
+    return UV_ENOMEM;
+
+  memcpy(req->bufs, bufs, nbufs * sizeof(*bufs));
+
+  req->off = off;
+  POST;
+}
+
+
+int uv_fs_scandir(uv_loop_t* loop,
+                  uv_fs_t* req,
+                  const char* path,
+                  int flags,
+                  uv_fs_cb cb) {
+  INIT(SCANDIR);
+  PATH;
+  req->flags = flags;
+  POST;
+}
+
+int uv_fs_opendir(uv_loop_t* loop,
+                  uv_fs_t* req,
+                  const char* path,
+                  uv_fs_cb cb) {
+  INIT(OPENDIR);
+  PATH;
+  POST;
+}
+
+int uv_fs_readdir(uv_loop_t* loop,
+                  uv_fs_t* req,
+                  uv_dir_t* dir,
+                  uv_fs_cb cb) {
+  INIT(READDIR);
+
+  if (dir == NULL || dir->dir == NULL || dir->dirents == NULL)
+    return UV_EINVAL;
+
+  req->ptr = dir;
+  POST;
+}
+
+int uv_fs_closedir(uv_loop_t* loop,
+                   uv_fs_t* req,
+                   uv_dir_t* dir,
+                   uv_fs_cb cb) {
+  INIT(CLOSEDIR);
+
+  if (dir == NULL)
+    return UV_EINVAL;
+
+  req->ptr = dir;
+  POST;
+}
+
+int uv_fs_readlink(uv_loop_t* loop,
+                   uv_fs_t* req,
+                   const char* path,
+                   uv_fs_cb cb) {
+  INIT(READLINK);
+  PATH;
+  POST;
+}
+
+
+int uv_fs_realpath(uv_loop_t* loop,
+                  uv_fs_t* req,
+                  const char * path,
+                  uv_fs_cb cb) {
+  INIT(REALPATH);
+  PATH;
+  POST;
+}
+
+
+int uv_fs_rename(uv_loop_t* loop,
+                 uv_fs_t* req,
+                 const char* path,
+                 const char* new_path,
+                 uv_fs_cb cb) {
+  INIT(RENAME);
+  PATH2;
+  POST;
+}
+
+
+int uv_fs_rmdir(uv_loop_t* loop, uv_fs_t* req, const char* path, uv_fs_cb cb) {
+  INIT(RMDIR);
+  PATH;
+  POST;
+}
+
+
+int uv_fs_sendfile(uv_loop_t* loop,
+                   uv_fs_t* req,
+                   uv_file out_fd,
+                   uv_file in_fd,
+                   int64_t off,
+                   size_t len,
+                   uv_fs_cb cb) {
+  INIT(SENDFILE);
+  req->flags = in_fd; /* hack */
+  req->file = out_fd;
+  req->off = off;
+  req->bufsml[0].len = len;
+  POST;
+}
+
+
+int uv_fs_stat(uv_loop_t* loop, uv_fs_t* req, const char* path, uv_fs_cb cb) {
+  INIT(STAT);
+  PATH;
+  POST;
+}
+
+
+int uv_fs_symlink(uv_loop_t* loop,
+                  uv_fs_t* req,
+                  const char* path,
+                  const char* new_path,
+                  int flags,
+                  uv_fs_cb cb) {
+  INIT(SYMLINK);
+  PATH2;
+  req->flags = flags;
+  POST;
+}
+
+
+int uv_fs_unlink(uv_loop_t* loop, uv_fs_t* req, const char* path, uv_fs_cb cb) {
+  INIT(UNLINK);
+  PATH;
+  POST;
+}
+
+
+int uv_fs_utime(uv_loop_t* loop,
+                uv_fs_t* req,
+                const char* path,
+                double atime,
+                double mtime,
+                uv_fs_cb cb) {
+  INIT(UTIME);
+  PATH;
+  req->atime = atime;
+  req->mtime = mtime;
+  POST;
+}
+
+
+int uv_fs_write(uv_loop_t* loop,
+                uv_fs_t* req,
+                uv_file file,
+                const uv_buf_t bufs[],
+                unsigned int nbufs,
+                int64_t off,
+                uv_fs_cb cb) {
+  INIT(WRITE);
+
+  if (bufs == NULL || nbufs == 0)
+    return UV_EINVAL;
+
+  req->file = file;
+
+  req->nbufs = nbufs;
+  req->bufs = req->bufsml;
+  if (nbufs > ARRAY_SIZE(req->bufsml))
+    req->bufs = (uv_buf_t*)uv__malloc(nbufs * sizeof(*bufs));
+
+  if (req->bufs == NULL)
+    return UV_ENOMEM;
+
+  memcpy(req->bufs, bufs, nbufs * sizeof(*bufs));
+
+  req->off = off;
+  POST;
+}
+
+
+void uv_fs_req_cleanup(uv_fs_t* req) {
+  if (req == NULL)
+    return;
+
+  /* Only necessary for asychronous requests, i.e., requests with a callback.
+   * Synchronous ones don't copy their arguments and have req->path and
+   * req->new_path pointing to user-owned memory.  UV_FS_MKDTEMP and
+   * UV_FS_MKSTEMP are the exception to the rule, they always allocate memory.
+   */
+  if (req->path != NULL &&
+      (req->cb != NULL ||
+        req->fs_type == UV_FS_MKDTEMP || req->fs_type == UV_FS_MKSTEMP))
+    uv__free((void*) req->path);  /* Memory is shared with req->new_path. */
+
+  req->path = NULL;
+  req->new_path = NULL;
+
+  if (req->fs_type == UV_FS_READDIR && req->ptr != NULL)
+    uv__fs_readdir_cleanup(req);
+
+  if (req->fs_type == UV_FS_SCANDIR && req->ptr != NULL)
+    uv__fs_scandir_cleanup(req);
+
+  if (req->bufs != req->bufsml)
+    uv__free(req->bufs);
+  req->bufs = NULL;
+
+  if (req->fs_type != UV_FS_OPENDIR && req->ptr != &req->statbuf)
+    uv__free(req->ptr);
+  req->ptr = NULL;
+}
+
+
+int uv_fs_copyfile(uv_loop_t* loop,
+                   uv_fs_t* req,
+                   const char* path,
+                   const char* new_path,
+                   int flags,
+                   uv_fs_cb cb) {
+  INIT(COPYFILE);
+
+  if (flags & ~(UV_FS_COPYFILE_EXCL |
+                UV_FS_COPYFILE_FICLONE |
+                UV_FS_COPYFILE_FICLONE_FORCE)) {
+    return UV_EINVAL;
+  }
+
+  PATH2;
+  req->flags = flags;
+  POST;
+}
+
+
+int uv_fs_statfs(uv_loop_t* loop,
+                 uv_fs_t* req,
+                 const char* path,
+                 uv_fs_cb cb) {
+  INIT(STATFS);
+  PATH;
+  POST;
+}
+
+int uv_fs_get_system_error(const uv_fs_t* req) {
+  return -req->result;
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/fsevents.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/fsevents.cpp
new file mode 100644
index 0000000..648c8a9
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/fsevents.cpp
@@ -0,0 +1,916 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#if TARGET_OS_IPHONE || MAC_OS_X_VERSION_MAX_ALLOWED < 1070
+
+/* iOS (currently) doesn't provide the FSEvents-API (nor CoreServices) */
+/* macOS prior to 10.7 doesn't provide the full FSEvents API so use kqueue */
+
+int uv__fsevents_init(uv_fs_event_t* handle) {
+  return 0;
+}
+
+
+int uv__fsevents_close(uv_fs_event_t* handle) {
+  return 0;
+}
+
+
+void uv__fsevents_loop_delete(uv_loop_t* loop) {
+}
+
+#else /* TARGET_OS_IPHONE */
+
+#include "darwin-stub.h"
+
+#include <dlfcn.h>
+#include <assert.h>
+#include <stdlib.h>
+#include <pthread.h>
+
+static const int kFSEventsModified =
+    kFSEventStreamEventFlagItemChangeOwner |
+    kFSEventStreamEventFlagItemFinderInfoMod |
+    kFSEventStreamEventFlagItemInodeMetaMod |
+    kFSEventStreamEventFlagItemModified |
+    kFSEventStreamEventFlagItemXattrMod;
+
+static const int kFSEventsRenamed =
+    kFSEventStreamEventFlagItemCreated |
+    kFSEventStreamEventFlagItemRemoved |
+    kFSEventStreamEventFlagItemRenamed;
+
+static const int kFSEventsSystem =
+    kFSEventStreamEventFlagUserDropped |
+    kFSEventStreamEventFlagKernelDropped |
+    kFSEventStreamEventFlagEventIdsWrapped |
+    kFSEventStreamEventFlagHistoryDone |
+    kFSEventStreamEventFlagMount |
+    kFSEventStreamEventFlagUnmount |
+    kFSEventStreamEventFlagRootChanged;
+
+typedef struct uv__fsevents_event_s uv__fsevents_event_t;
+typedef struct uv__cf_loop_signal_s uv__cf_loop_signal_t;
+typedef struct uv__cf_loop_state_s uv__cf_loop_state_t;
+
+enum uv__cf_loop_signal_type_e {
+  kUVCFLoopSignalRegular,
+  kUVCFLoopSignalClosing
+};
+typedef enum uv__cf_loop_signal_type_e uv__cf_loop_signal_type_t;
+
+struct uv__cf_loop_signal_s {
+  QUEUE member;
+  uv_fs_event_t* handle;
+  uv__cf_loop_signal_type_t type;
+};
+
+struct uv__fsevents_event_s {
+  QUEUE member;
+  int events;
+  char path[1];
+};
+
+struct uv__cf_loop_state_s {
+  CFRunLoopRef loop;
+  CFRunLoopSourceRef signal_source;
+  int fsevent_need_reschedule;
+  FSEventStreamRef fsevent_stream;
+  uv_sem_t fsevent_sem;
+  uv_mutex_t fsevent_mutex;
+  void* fsevent_handles[2];
+  unsigned int fsevent_handle_count;
+};
+
+/* Forward declarations */
+static void uv__cf_loop_cb(void* arg);
+static void* uv__cf_loop_runner(void* arg);
+static int uv__cf_loop_signal(uv_loop_t* loop,
+                              uv_fs_event_t* handle,
+                              uv__cf_loop_signal_type_t type);
+
+/* Lazy-loaded by uv__fsevents_global_init(). */
+static CFArrayRef (*pCFArrayCreate)(CFAllocatorRef,
+                                    const void**,
+                                    CFIndex,
+                                    const CFArrayCallBacks*);
+static void (*pCFRelease)(CFTypeRef);
+static void (*pCFRunLoopAddSource)(CFRunLoopRef,
+                                   CFRunLoopSourceRef,
+                                   CFStringRef);
+static CFRunLoopRef (*pCFRunLoopGetCurrent)(void);
+static void (*pCFRunLoopRemoveSource)(CFRunLoopRef,
+                                      CFRunLoopSourceRef,
+                                      CFStringRef);
+static void (*pCFRunLoopRun)(void);
+static CFRunLoopSourceRef (*pCFRunLoopSourceCreate)(CFAllocatorRef,
+                                                    CFIndex,
+                                                    CFRunLoopSourceContext*);
+static void (*pCFRunLoopSourceSignal)(CFRunLoopSourceRef);
+static void (*pCFRunLoopStop)(CFRunLoopRef);
+static void (*pCFRunLoopWakeUp)(CFRunLoopRef);
+static CFStringRef (*pCFStringCreateWithFileSystemRepresentation)(
+    CFAllocatorRef,
+    const char*);
+static CFStringEncoding (*pCFStringGetSystemEncoding)(void);
+static CFStringRef (*pkCFRunLoopDefaultMode);
+static FSEventStreamRef (*pFSEventStreamCreate)(CFAllocatorRef,
+                                                FSEventStreamCallback,
+                                                FSEventStreamContext*,
+                                                CFArrayRef,
+                                                FSEventStreamEventId,
+                                                CFTimeInterval,
+                                                FSEventStreamCreateFlags);
+static void (*pFSEventStreamFlushSync)(FSEventStreamRef);
+static void (*pFSEventStreamInvalidate)(FSEventStreamRef);
+static void (*pFSEventStreamRelease)(FSEventStreamRef);
+static void (*pFSEventStreamScheduleWithRunLoop)(FSEventStreamRef,
+                                                 CFRunLoopRef,
+                                                 CFStringRef);
+static int (*pFSEventStreamStart)(FSEventStreamRef);
+static void (*pFSEventStreamStop)(FSEventStreamRef);
+
+#define UV__FSEVENTS_PROCESS(handle, block)                                   \
+    do {                                                                      \
+      QUEUE events;                                                           \
+      QUEUE* q;                                                               \
+      uv__fsevents_event_t* event;                                            \
+      int err;                                                                \
+      uv_mutex_lock(&(handle)->cf_mutex);                                     \
+      /* Split-off all events and empty original queue */                     \
+      QUEUE_MOVE(&(handle)->cf_events, &events);                              \
+      /* Get error (if any) and zero original one */                          \
+      err = (handle)->cf_error;                                               \
+      (handle)->cf_error = 0;                                                 \
+      uv_mutex_unlock(&(handle)->cf_mutex);                                   \
+      /* Loop through events, deallocating each after processing */           \
+      while (!QUEUE_EMPTY(&events)) {                                         \
+        q = QUEUE_HEAD(&events);                                              \
+        event = QUEUE_DATA(q, uv__fsevents_event_t, member);                  \
+        QUEUE_REMOVE(q);                                                      \
+        /* NOTE: Checking uv__is_active() is required here, because handle    \
+         * callback may close handle and invoking it after it will lead to    \
+         * incorrect behaviour */                                             \
+        if (!uv__is_closing((handle)) && uv__is_active((handle)))             \
+          block                                                               \
+        /* Free allocated data */                                             \
+        uv__free(event);                                                      \
+      }                                                                       \
+      if (err != 0 && !uv__is_closing((handle)) && uv__is_active((handle)))   \
+        (handle)->cb((handle), NULL, 0, err);                                 \
+    } while (0)
+
+
+/* Runs in UV loop's thread, when there're events to report to handle */
+static void uv__fsevents_cb(uv_async_t* cb) {
+  uv_fs_event_t* handle;
+
+  handle = (uv_fs_event_t*)cb->data;
+
+  UV__FSEVENTS_PROCESS(handle, {
+    handle->cb(handle, event->path[0] ? event->path : NULL, event->events, 0);
+  });
+}
+
+
+/* Runs in CF thread, pushed event into handle's event list */
+static void uv__fsevents_push_event(uv_fs_event_t* handle,
+                                    QUEUE* events,
+                                    int err) {
+  assert(events != NULL || err != 0);
+  uv_mutex_lock(&handle->cf_mutex);
+
+  /* Concatenate two queues */
+  if (events != NULL)
+    QUEUE_ADD(&handle->cf_events, events);
+
+  /* Propagate error */
+  if (err != 0)
+    handle->cf_error = err;
+  uv_mutex_unlock(&handle->cf_mutex);
+
+  uv_async_send(handle->cf_cb);
+}
+
+
+/* Runs in CF thread, when there're events in FSEventStream */
+static void uv__fsevents_event_cb(const FSEventStreamRef streamRef,
+                                  void* info,
+                                  size_t numEvents,
+                                  void* eventPaths,
+                                  const FSEventStreamEventFlags eventFlags[],
+                                  const FSEventStreamEventId eventIds[]) {
+  size_t i;
+  int len;
+  char** paths;
+  char* path;
+  char* pos;
+  uv_fs_event_t* handle;
+  QUEUE* q;
+  uv_loop_t* loop;
+  uv__cf_loop_state_t* state;
+  uv__fsevents_event_t* event;
+  FSEventStreamEventFlags flags;
+  QUEUE head;
+
+  loop = (uv_loop_t*)info;
+  state = (uv__cf_loop_state_t*)loop->cf_state;
+  assert(state != NULL);
+  paths = (char**)eventPaths;
+
+  /* For each handle */
+  uv_mutex_lock(&state->fsevent_mutex);
+  QUEUE_FOREACH(q, &state->fsevent_handles) {
+    handle = QUEUE_DATA(q, uv_fs_event_t, cf_member);
+    QUEUE_INIT(&head);
+
+    /* Process and filter out events */
+    for (i = 0; i < numEvents; i++) {
+      flags = eventFlags[i];
+
+      /* Ignore system events */
+      if (flags & kFSEventsSystem)
+        continue;
+
+      path = paths[i];
+      len = strlen(path);
+
+      if (handle->realpath_len == 0)
+        continue; /* This should be unreachable */
+
+      /* Filter out paths that are outside handle's request */
+      if (len < handle->realpath_len)
+        continue;
+
+      /* Make sure that realpath actually named a directory,
+       * (unless watching root, which alone keeps a trailing slash on the realpath)
+       * or that we matched the whole string */
+      if (handle->realpath_len != len &&
+          handle->realpath_len > 1 &&
+          path[handle->realpath_len] != '/')
+        continue;
+
+      if (memcmp(path, handle->realpath, handle->realpath_len) != 0)
+        continue;
+
+      if (!(handle->realpath_len == 1 && handle->realpath[0] == '/')) {
+        /* Remove common prefix, unless the watched folder is "/" */
+        path += handle->realpath_len;
+        len -= handle->realpath_len;
+
+        /* Ignore events with path equal to directory itself */
+        if (len <= 1 && (flags & kFSEventStreamEventFlagItemIsDir))
+          continue;
+
+        if (len == 0) {
+          /* Since we're using fsevents to watch the file itself,
+           * realpath == path, and we now need to get the basename of the file back
+           * (for commonality with other codepaths and platforms). */
+          while (len < handle->realpath_len && path[-1] != '/') {
+            path--;
+            len++;
+          }
+          /* Created and Removed seem to be always set, but don't make sense */
+          flags &= ~kFSEventsRenamed;
+        } else {
+          /* Skip forward slash */
+          path++;
+          len--;
+        }
+      }
+
+      /* Do not emit events from subdirectories (without option set) */
+      if ((handle->cf_flags & UV_FS_EVENT_RECURSIVE) == 0 && *path != '\0') {
+        pos = strchr(path + 1, '/');
+        if (pos != NULL)
+          continue;
+      }
+
+      event = (uv__fsevents_event_t*)uv__malloc(sizeof(*event) + len);
+      if (event == NULL)
+        break;
+
+      memset(event, 0, sizeof(*event));
+      memcpy(event->path, path, len + 1);
+      event->events = UV_RENAME;
+
+      if (0 == (flags & kFSEventsRenamed)) {
+        if (0 != (flags & kFSEventsModified) ||
+            0 == (flags & kFSEventStreamEventFlagItemIsDir))
+          event->events = UV_CHANGE;
+      }
+
+      QUEUE_INSERT_TAIL(&head, &event->member);
+    }
+
+    if (!QUEUE_EMPTY(&head))
+      uv__fsevents_push_event(handle, &head, 0);
+  }
+  uv_mutex_unlock(&state->fsevent_mutex);
+}
+
+
+/* Runs in CF thread */
+static int uv__fsevents_create_stream(uv_loop_t* loop, CFArrayRef paths) {
+  uv__cf_loop_state_t* state;
+  FSEventStreamContext ctx;
+  FSEventStreamRef ref;
+  CFAbsoluteTime latency;
+  FSEventStreamCreateFlags flags;
+
+  /* Initialize context */
+  memset(&ctx, 0, sizeof(ctx));
+  ctx.info = loop;
+
+  latency = 0.05;
+
+  /* Explanation of selected flags:
+   * 1. NoDefer - without this flag, events that are happening continuously
+   *    (i.e. each event is happening after time interval less than `latency`,
+   *    counted from previous event), will be deferred and passed to callback
+   *    once they'll either fill whole OS buffer, or when this continuous stream
+   *    will stop (i.e. there'll be delay between events, bigger than
+   *    `latency`).
+   *    Specifying this flag will invoke callback after `latency` time passed
+   *    since event.
+   * 2. FileEvents - fire callback for file changes too (by default it is firing
+   *    it only for directory changes).
+   */
+  flags = kFSEventStreamCreateFlagNoDefer | kFSEventStreamCreateFlagFileEvents;
+
+  /*
+   * NOTE: It might sound like a good idea to remember last seen StreamEventId,
+   * but in reality one dir might have last StreamEventId less than, the other,
+   * that is being watched now. Which will cause FSEventStream API to report
+   * changes to files from the past.
+   */
+  ref = pFSEventStreamCreate(NULL,
+                             &uv__fsevents_event_cb,
+                             &ctx,
+                             paths,
+                             kFSEventStreamEventIdSinceNow,
+                             latency,
+                             flags);
+  assert(ref != NULL);
+
+  state = (uv__cf_loop_state_t*)loop->cf_state;
+  pFSEventStreamScheduleWithRunLoop(ref,
+                                    state->loop,
+                                    *pkCFRunLoopDefaultMode);
+  if (!pFSEventStreamStart(ref)) {
+    pFSEventStreamInvalidate(ref);
+    pFSEventStreamRelease(ref);
+    return UV_EMFILE;
+  }
+
+  state->fsevent_stream = ref;
+  return 0;
+}
+
+
+/* Runs in CF thread */
+static void uv__fsevents_destroy_stream(uv_loop_t* loop) {
+  uv__cf_loop_state_t* state;
+
+  state = (uv__cf_loop_state_t*)loop->cf_state;
+
+  if (state->fsevent_stream == NULL)
+    return;
+
+  /* Stop emitting events */
+  pFSEventStreamStop(state->fsevent_stream);
+
+  /* Release stream */
+  pFSEventStreamInvalidate(state->fsevent_stream);
+  pFSEventStreamRelease(state->fsevent_stream);
+  state->fsevent_stream = NULL;
+}
+
+
+/* Runs in CF thread, when there're new fsevent handles to add to stream */
+static void uv__fsevents_reschedule(uv_fs_event_t* handle,
+                                    uv__cf_loop_signal_type_t type) {
+  uv__cf_loop_state_t* state;
+  QUEUE* q;
+  uv_fs_event_t* curr;
+  CFArrayRef cf_paths;
+  CFStringRef* paths;
+  unsigned int i;
+  int err;
+  unsigned int path_count;
+
+  state = (uv__cf_loop_state_t*)handle->loop->cf_state;
+  paths = NULL;
+  cf_paths = NULL;
+  err = 0;
+  /* NOTE: `i` is used in deallocation loop below */
+  i = 0;
+
+  /* Optimization to prevent O(n^2) time spent when starting to watch
+   * many files simultaneously
+   */
+  uv_mutex_lock(&state->fsevent_mutex);
+  if (state->fsevent_need_reschedule == 0) {
+    uv_mutex_unlock(&state->fsevent_mutex);
+    goto final;
+  }
+  state->fsevent_need_reschedule = 0;
+  uv_mutex_unlock(&state->fsevent_mutex);
+
+  /* Destroy previous FSEventStream */
+  uv__fsevents_destroy_stream(handle->loop);
+
+  /* Any failure below will be a memory failure */
+  err = UV_ENOMEM;
+
+  /* Create list of all watched paths */
+  uv_mutex_lock(&state->fsevent_mutex);
+  path_count = state->fsevent_handle_count;
+  if (path_count != 0) {
+    paths = (CFStringRef*)uv__malloc(sizeof(*paths) * path_count);
+    if (paths == NULL) {
+      uv_mutex_unlock(&state->fsevent_mutex);
+      goto final;
+    }
+
+    q = &state->fsevent_handles;
+    for (; i < path_count; i++) {
+      q = QUEUE_NEXT(q);
+      assert(q != &state->fsevent_handles);
+      curr = QUEUE_DATA(q, uv_fs_event_t, cf_member);
+
+      assert(curr->realpath != NULL);
+      paths[i] =
+          pCFStringCreateWithFileSystemRepresentation(NULL, curr->realpath);
+      if (paths[i] == NULL) {
+        uv_mutex_unlock(&state->fsevent_mutex);
+        goto final;
+      }
+    }
+  }
+  uv_mutex_unlock(&state->fsevent_mutex);
+  err = 0;
+
+  if (path_count != 0) {
+    /* Create new FSEventStream */
+    cf_paths = pCFArrayCreate(NULL, (const void**) paths, path_count, NULL);
+    if (cf_paths == NULL) {
+      err = UV_ENOMEM;
+      goto final;
+    }
+    err = uv__fsevents_create_stream(handle->loop, cf_paths);
+  }
+
+final:
+  /* Deallocate all paths in case of failure */
+  if (err != 0) {
+    if (cf_paths == NULL) {
+      while (i != 0)
+        pCFRelease(paths[--i]);
+      uv__free(paths);
+    } else {
+      /* CFArray takes ownership of both strings and original C-array */
+      pCFRelease(cf_paths);
+    }
+
+    /* Broadcast error to all handles */
+    uv_mutex_lock(&state->fsevent_mutex);
+    QUEUE_FOREACH(q, &state->fsevent_handles) {
+      curr = QUEUE_DATA(q, uv_fs_event_t, cf_member);
+      uv__fsevents_push_event(curr, NULL, err);
+    }
+    uv_mutex_unlock(&state->fsevent_mutex);
+  }
+
+  /*
+   * Main thread will block until the removal of handle from the list,
+   * we must tell it when we're ready.
+   *
+   * NOTE: This is coupled with `uv_sem_wait()` in `uv__fsevents_close`
+   */
+  if (type == kUVCFLoopSignalClosing)
+    uv_sem_post(&state->fsevent_sem);
+}
+
+
+static int uv__fsevents_global_init(void) {
+  static pthread_mutex_t global_init_mutex = PTHREAD_MUTEX_INITIALIZER;
+  static void* core_foundation_handle;
+  static void* core_services_handle;
+  int err;
+
+  err = 0;
+  pthread_mutex_lock(&global_init_mutex);
+  if (core_foundation_handle != NULL)
+    goto out;
+
+  /* The libraries are never unloaded because we currently don't have a good
+   * mechanism for keeping a reference count. It's unlikely to be an issue
+   * but if it ever becomes one, we can turn the dynamic library handles into
+   * per-event loop properties and have the dynamic linker keep track for us.
+   */
+  err = UV_ENOSYS;
+  core_foundation_handle = dlopen("/System/Library/Frameworks/"
+                                  "CoreFoundation.framework/"
+                                  "Versions/A/CoreFoundation",
+                                  RTLD_LAZY | RTLD_LOCAL);
+  if (core_foundation_handle == NULL)
+    goto out;
+
+  core_services_handle = dlopen("/System/Library/Frameworks/"
+                                "CoreServices.framework/"
+                                "Versions/A/CoreServices",
+                                RTLD_LAZY | RTLD_LOCAL);
+  if (core_services_handle == NULL)
+    goto out;
+
+  err = UV_ENOENT;
+#define V(handle, symbol)                                                     \
+  do {                                                                        \
+    *(void **)(&p ## symbol) = dlsym((handle), #symbol);                      \
+    if (p ## symbol == NULL)                                                  \
+      goto out;                                                               \
+  }                                                                           \
+  while (0)
+  V(core_foundation_handle, CFArrayCreate);
+  V(core_foundation_handle, CFRelease);
+  V(core_foundation_handle, CFRunLoopAddSource);
+  V(core_foundation_handle, CFRunLoopGetCurrent);
+  V(core_foundation_handle, CFRunLoopRemoveSource);
+  V(core_foundation_handle, CFRunLoopRun);
+  V(core_foundation_handle, CFRunLoopSourceCreate);
+  V(core_foundation_handle, CFRunLoopSourceSignal);
+  V(core_foundation_handle, CFRunLoopStop);
+  V(core_foundation_handle, CFRunLoopWakeUp);
+  V(core_foundation_handle, CFStringCreateWithFileSystemRepresentation);
+  V(core_foundation_handle, CFStringGetSystemEncoding);
+  V(core_foundation_handle, kCFRunLoopDefaultMode);
+  V(core_services_handle, FSEventStreamCreate);
+  V(core_services_handle, FSEventStreamFlushSync);
+  V(core_services_handle, FSEventStreamInvalidate);
+  V(core_services_handle, FSEventStreamRelease);
+  V(core_services_handle, FSEventStreamScheduleWithRunLoop);
+  V(core_services_handle, FSEventStreamStart);
+  V(core_services_handle, FSEventStreamStop);
+#undef V
+  err = 0;
+
+out:
+  if (err && core_services_handle != NULL) {
+    dlclose(core_services_handle);
+    core_services_handle = NULL;
+  }
+
+  if (err && core_foundation_handle != NULL) {
+    dlclose(core_foundation_handle);
+    core_foundation_handle = NULL;
+  }
+
+  pthread_mutex_unlock(&global_init_mutex);
+  return err;
+}
+
+
+/* Runs in UV loop */
+static int uv__fsevents_loop_init(uv_loop_t* loop) {
+  CFRunLoopSourceContext ctx;
+  uv__cf_loop_state_t* state;
+  pthread_attr_t attr;
+  int err;
+
+  if (loop->cf_state != NULL)
+    return 0;
+
+  err = uv__fsevents_global_init();
+  if (err)
+    return err;
+
+  state = (uv__cf_loop_state_t*)uv__calloc(1, sizeof(*state));
+  if (state == NULL)
+    return UV_ENOMEM;
+
+  err = uv_mutex_init(&loop->cf_mutex);
+  if (err)
+    goto fail_mutex_init;
+
+  err = uv_sem_init(&loop->cf_sem, 0);
+  if (err)
+    goto fail_sem_init;
+
+  QUEUE_INIT(&loop->cf_signals);
+
+  err = uv_sem_init(&state->fsevent_sem, 0);
+  if (err)
+    goto fail_fsevent_sem_init;
+
+  err = uv_mutex_init(&state->fsevent_mutex);
+  if (err)
+    goto fail_fsevent_mutex_init;
+
+  QUEUE_INIT(&state->fsevent_handles);
+  state->fsevent_need_reschedule = 0;
+  state->fsevent_handle_count = 0;
+
+  memset(&ctx, 0, sizeof(ctx));
+  ctx.info = loop;
+  ctx.perform = uv__cf_loop_cb;
+  state->signal_source = pCFRunLoopSourceCreate(NULL, 0, &ctx);
+  if (state->signal_source == NULL) {
+    err = UV_ENOMEM;
+    goto fail_signal_source_create;
+  }
+
+  if (pthread_attr_init(&attr))
+    abort();
+
+  if (pthread_attr_setstacksize(&attr, uv__thread_stack_size()))
+    abort();
+
+  loop->cf_state = state;
+
+  /* uv_thread_t is an alias for pthread_t. */
+  err = UV__ERR(pthread_create(&loop->cf_thread, &attr, uv__cf_loop_runner, loop));
+
+  if (pthread_attr_destroy(&attr))
+    abort();
+
+  if (err)
+    goto fail_thread_create;
+
+  /* Synchronize threads */
+  uv_sem_wait(&loop->cf_sem);
+  return 0;
+
+fail_thread_create:
+  loop->cf_state = NULL;
+
+fail_signal_source_create:
+  uv_mutex_destroy(&state->fsevent_mutex);
+
+fail_fsevent_mutex_init:
+  uv_sem_destroy(&state->fsevent_sem);
+
+fail_fsevent_sem_init:
+  uv_sem_destroy(&loop->cf_sem);
+
+fail_sem_init:
+  uv_mutex_destroy(&loop->cf_mutex);
+
+fail_mutex_init:
+  uv__free(state);
+  return err;
+}
+
+
+/* Runs in UV loop */
+void uv__fsevents_loop_delete(uv_loop_t* loop) {
+  uv__cf_loop_signal_t* s;
+  uv__cf_loop_state_t* state;
+  QUEUE* q;
+
+  if (loop->cf_state == NULL)
+    return;
+
+  if (uv__cf_loop_signal(loop, NULL, kUVCFLoopSignalRegular) != 0)
+    abort();
+
+  uv_thread_join(&loop->cf_thread);
+  uv_sem_destroy(&loop->cf_sem);
+  uv_mutex_destroy(&loop->cf_mutex);
+
+  /* Free any remaining data */
+  while (!QUEUE_EMPTY(&loop->cf_signals)) {
+    q = QUEUE_HEAD(&loop->cf_signals);
+    s = QUEUE_DATA(q, uv__cf_loop_signal_t, member);
+    QUEUE_REMOVE(q);
+    uv__free(s);
+  }
+
+  /* Destroy state */
+  state = (uv__cf_loop_state_t*)loop->cf_state;
+  uv_sem_destroy(&state->fsevent_sem);
+  uv_mutex_destroy(&state->fsevent_mutex);
+  pCFRelease(state->signal_source);
+  uv__free(state);
+  loop->cf_state = NULL;
+}
+
+
+/* Runs in CF thread. This is the CF loop's body */
+static void* uv__cf_loop_runner(void* arg) {
+  uv_loop_t* loop;
+  uv__cf_loop_state_t* state;
+
+  loop = (uv_loop_t*)arg;
+  state = (uv__cf_loop_state_t*)loop->cf_state;
+  state->loop = pCFRunLoopGetCurrent();
+
+  pCFRunLoopAddSource(state->loop,
+                      state->signal_source,
+                      *pkCFRunLoopDefaultMode);
+
+  uv_sem_post(&loop->cf_sem);
+
+  pCFRunLoopRun();
+  pCFRunLoopRemoveSource(state->loop,
+                         state->signal_source,
+                         *pkCFRunLoopDefaultMode);
+
+  state->loop = NULL;
+
+  return NULL;
+}
+
+
+/* Runs in CF thread, executed after `uv__cf_loop_signal()` */
+static void uv__cf_loop_cb(void* arg) {
+  uv_loop_t* loop;
+  uv__cf_loop_state_t* state;
+  QUEUE* item;
+  QUEUE split_head;
+  uv__cf_loop_signal_t* s;
+
+  loop = (uv_loop_t*)arg;
+  state = (uv__cf_loop_state_t*)loop->cf_state;
+
+  uv_mutex_lock(&loop->cf_mutex);
+  QUEUE_MOVE(&loop->cf_signals, &split_head);
+  uv_mutex_unlock(&loop->cf_mutex);
+
+  while (!QUEUE_EMPTY(&split_head)) {
+    item = QUEUE_HEAD(&split_head);
+    QUEUE_REMOVE(item);
+
+    s = QUEUE_DATA(item, uv__cf_loop_signal_t, member);
+
+    /* This was a termination signal */
+    if (s->handle == NULL)
+      pCFRunLoopStop(state->loop);
+    else
+      uv__fsevents_reschedule(s->handle, s->type);
+
+    uv__free(s);
+  }
+}
+
+
+/* Runs in UV loop to notify CF thread */
+int uv__cf_loop_signal(uv_loop_t* loop,
+                       uv_fs_event_t* handle,
+                       uv__cf_loop_signal_type_t type) {
+  uv__cf_loop_signal_t* item;
+  uv__cf_loop_state_t* state;
+
+  item = (uv__cf_loop_signal_t*)uv__malloc(sizeof(*item));
+  if (item == NULL)
+    return UV_ENOMEM;
+
+  item->handle = handle;
+  item->type = type;
+
+  uv_mutex_lock(&loop->cf_mutex);
+  QUEUE_INSERT_TAIL(&loop->cf_signals, &item->member);
+
+  state = (uv__cf_loop_state_t*)loop->cf_state;
+  assert(state != NULL);
+  pCFRunLoopSourceSignal(state->signal_source);
+  pCFRunLoopWakeUp(state->loop);
+
+  uv_mutex_unlock(&loop->cf_mutex);
+
+  return 0;
+}
+
+
+/* Runs in UV loop to initialize handle */
+int uv__fsevents_init(uv_fs_event_t* handle) {
+  int err;
+  uv__cf_loop_state_t* state;
+
+  err = uv__fsevents_loop_init(handle->loop);
+  if (err)
+    return err;
+
+  /* Get absolute path to file */
+  handle->realpath = realpath(handle->path, NULL);
+  if (handle->realpath == NULL)
+    return UV__ERR(errno);
+  handle->realpath_len = strlen(handle->realpath);
+
+  /* Initialize event queue */
+  QUEUE_INIT(&handle->cf_events);
+  handle->cf_error = 0;
+
+  /*
+   * Events will occur in other thread.
+   * Initialize callback for getting them back into event loop's thread
+   */
+  handle->cf_cb = (uv_async_t*)uv__malloc(sizeof(*handle->cf_cb));
+  if (handle->cf_cb == NULL) {
+    err = UV_ENOMEM;
+    goto fail_cf_cb_malloc;
+  }
+
+  handle->cf_cb->data = handle;
+  uv_async_init(handle->loop, handle->cf_cb, uv__fsevents_cb);
+  handle->cf_cb->flags |= UV_HANDLE_INTERNAL;
+  uv_unref((uv_handle_t*) handle->cf_cb);
+
+  err = uv_mutex_init(&handle->cf_mutex);
+  if (err)
+    goto fail_cf_mutex_init;
+
+  /* Insert handle into the list */
+  state = (uv__cf_loop_state_t*)handle->loop->cf_state;
+  uv_mutex_lock(&state->fsevent_mutex);
+  QUEUE_INSERT_TAIL(&state->fsevent_handles, &handle->cf_member);
+  state->fsevent_handle_count++;
+  state->fsevent_need_reschedule = 1;
+  uv_mutex_unlock(&state->fsevent_mutex);
+
+  /* Reschedule FSEventStream */
+  assert(handle != NULL);
+  err = uv__cf_loop_signal(handle->loop, handle, kUVCFLoopSignalRegular);
+  if (err)
+    goto fail_loop_signal;
+
+  return 0;
+
+fail_loop_signal:
+  uv_mutex_destroy(&handle->cf_mutex);
+
+fail_cf_mutex_init:
+  uv__free(handle->cf_cb);
+  handle->cf_cb = NULL;
+
+fail_cf_cb_malloc:
+  uv__free(handle->realpath);
+  handle->realpath = NULL;
+  handle->realpath_len = 0;
+
+  return err;
+}
+
+
+/* Runs in UV loop to de-initialize handle */
+int uv__fsevents_close(uv_fs_event_t* handle) {
+  int err;
+  uv__cf_loop_state_t* state;
+
+  if (handle->cf_cb == NULL)
+    return UV_EINVAL;
+
+  /* Remove handle from  the list */
+  state = (uv__cf_loop_state_t*)handle->loop->cf_state;
+  uv_mutex_lock(&state->fsevent_mutex);
+  QUEUE_REMOVE(&handle->cf_member);
+  state->fsevent_handle_count--;
+  state->fsevent_need_reschedule = 1;
+  uv_mutex_unlock(&state->fsevent_mutex);
+
+  /* Reschedule FSEventStream */
+  assert(handle != NULL);
+  err = uv__cf_loop_signal(handle->loop, handle, kUVCFLoopSignalClosing);
+  if (err)
+    return UV__ERR(err);
+
+  /* Wait for deinitialization */
+  uv_sem_wait(&state->fsevent_sem);
+
+  uv_close((uv_handle_t*) handle->cf_cb, (uv_close_cb) uv__free);
+  handle->cf_cb = NULL;
+
+  /* Free data in queue */
+  UV__FSEVENTS_PROCESS(handle, {
+    /* NOP */
+  });
+
+  uv_mutex_destroy(&handle->cf_mutex);
+  uv__free(handle->realpath);
+  handle->realpath = NULL;
+  handle->realpath_len = 0;
+
+  return 0;
+}
+
+#endif /* TARGET_OS_IPHONE */
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/getaddrinfo.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/getaddrinfo.cpp
new file mode 100644
index 0000000..41dc390
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/getaddrinfo.cpp
@@ -0,0 +1,252 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+/* Expose glibc-specific EAI_* error codes. Needs to be defined before we
+ * include any headers.
+ */
+
+#include "uv.h"
+#include "internal.h"
+#include "idna.h"
+
+#include <errno.h>
+#include <stddef.h> /* NULL */
+#include <stdlib.h>
+#include <string.h>
+#include <net/if.h> /* if_indextoname() */
+
+/* EAI_* constants. */
+#include <netdb.h>
+
+
+int uv__getaddrinfo_translate_error(int sys_err) {
+  switch (sys_err) {
+  case 0: return 0;
+#if defined(EAI_ADDRFAMILY)
+  case EAI_ADDRFAMILY: return UV_EAI_ADDRFAMILY;
+#endif
+#if defined(EAI_AGAIN)
+  case EAI_AGAIN: return UV_EAI_AGAIN;
+#endif
+#if defined(EAI_BADFLAGS)
+  case EAI_BADFLAGS: return UV_EAI_BADFLAGS;
+#endif
+#if defined(EAI_BADHINTS)
+  case EAI_BADHINTS: return UV_EAI_BADHINTS;
+#endif
+#if defined(EAI_CANCELED)
+  case EAI_CANCELED: return UV_EAI_CANCELED;
+#endif
+#if defined(EAI_FAIL)
+  case EAI_FAIL: return UV_EAI_FAIL;
+#endif
+#if defined(EAI_FAMILY)
+  case EAI_FAMILY: return UV_EAI_FAMILY;
+#endif
+#if defined(EAI_MEMORY)
+  case EAI_MEMORY: return UV_EAI_MEMORY;
+#endif
+#if defined(EAI_NODATA)
+  case EAI_NODATA: return UV_EAI_NODATA;
+#endif
+#if defined(EAI_NONAME)
+# if !defined(EAI_NODATA) || EAI_NODATA != EAI_NONAME
+  case EAI_NONAME: return UV_EAI_NONAME;
+# endif
+#endif
+#if defined(EAI_OVERFLOW)
+  case EAI_OVERFLOW: return UV_EAI_OVERFLOW;
+#endif
+#if defined(EAI_PROTOCOL)
+  case EAI_PROTOCOL: return UV_EAI_PROTOCOL;
+#endif
+#if defined(EAI_SERVICE)
+  case EAI_SERVICE: return UV_EAI_SERVICE;
+#endif
+#if defined(EAI_SOCKTYPE)
+  case EAI_SOCKTYPE: return UV_EAI_SOCKTYPE;
+#endif
+#if defined(EAI_SYSTEM)
+  case EAI_SYSTEM: return UV__ERR(errno);
+#endif
+  }
+  assert(!"unknown EAI_* error code");
+  abort();
+#ifndef __SUNPRO_C
+  return 0;  /* Pacify compiler. */
+#endif
+}
+
+
+static void uv__getaddrinfo_work(struct uv__work* w) {
+  uv_getaddrinfo_t* req;
+  int err;
+
+  req = container_of(w, uv_getaddrinfo_t, work_req);
+  err = getaddrinfo(req->hostname, req->service, req->hints, &req->addrinfo);
+  req->retcode = uv__getaddrinfo_translate_error(err);
+}
+
+
+static void uv__getaddrinfo_done(struct uv__work* w, int status) {
+  uv_getaddrinfo_t* req;
+
+  req = container_of(w, uv_getaddrinfo_t, work_req);
+  uv__req_unregister(req->loop, req);
+
+  /* See initialization in uv_getaddrinfo(). */
+  if (req->hints)
+    uv__free(req->hints);
+  else if (req->service)
+    uv__free(req->service);
+  else if (req->hostname)
+    uv__free(req->hostname);
+  else
+    assert(0);
+
+  req->hints = NULL;
+  req->service = NULL;
+  req->hostname = NULL;
+
+  if (status == UV_ECANCELED) {
+    assert(req->retcode == 0);
+    req->retcode = UV_EAI_CANCELED;
+  }
+
+  if (req->cb)
+    req->cb(req, req->retcode, req->addrinfo);
+}
+
+
+int uv_getaddrinfo(uv_loop_t* loop,
+                   uv_getaddrinfo_t* req,
+                   uv_getaddrinfo_cb cb,
+                   const char* hostname,
+                   const char* service,
+                   const struct addrinfo* hints) {
+  char hostname_ascii[256];
+  size_t hostname_len;
+  size_t service_len;
+  size_t hints_len;
+  size_t len;
+  char* buf;
+  long rc;
+
+  if (req == NULL || (hostname == NULL && service == NULL))
+    return UV_EINVAL;
+
+  /* FIXME(bnoordhuis) IDNA does not seem to work z/OS,
+   * probably because it uses EBCDIC rather than ASCII.
+   */
+#ifdef __MVS__
+  (void) &hostname_ascii;
+#else
+  if (hostname != NULL) {
+    rc = uv__idna_toascii(hostname,
+                          hostname + strlen(hostname),
+                          hostname_ascii,
+                          hostname_ascii + sizeof(hostname_ascii));
+    if (rc < 0)
+      return rc;
+    hostname = hostname_ascii;
+  }
+#endif
+
+  hostname_len = hostname ? strlen(hostname) + 1 : 0;
+  service_len = service ? strlen(service) + 1 : 0;
+  hints_len = hints ? sizeof(*hints) : 0;
+  buf = (char*)uv__malloc(hostname_len + service_len + hints_len);
+
+  if (buf == NULL)
+    return UV_ENOMEM;
+
+  uv__req_init(loop, req, UV_GETADDRINFO);
+  req->loop = loop;
+  req->cb = cb;
+  req->addrinfo = NULL;
+  req->hints = NULL;
+  req->service = NULL;
+  req->hostname = NULL;
+  req->retcode = 0;
+
+  /* order matters, see uv_getaddrinfo_done() */
+  len = 0;
+
+  if (hints) {
+    req->hints = (struct addrinfo*)memcpy(buf + len, hints, sizeof(*hints));
+    len += sizeof(*hints);
+  }
+
+  if (service) {
+    req->service = (char*)memcpy(buf + len, service, service_len);
+    len += service_len;
+  }
+
+  if (hostname)
+    req->hostname = (char*)memcpy(buf + len, hostname, hostname_len);
+
+  if (cb) {
+    uv__work_submit(loop,
+                    &req->work_req,
+                    UV__WORK_SLOW_IO,
+                    uv__getaddrinfo_work,
+                    uv__getaddrinfo_done);
+    return 0;
+  } else {
+    uv__getaddrinfo_work(&req->work_req);
+    uv__getaddrinfo_done(&req->work_req, 0);
+    return req->retcode;
+  }
+}
+
+
+void uv_freeaddrinfo(struct addrinfo* ai) {
+  if (ai)
+    freeaddrinfo(ai);
+}
+
+
+int uv_if_indextoname(unsigned int ifindex, char* buffer, size_t* size) {
+  char ifname_buf[UV_IF_NAMESIZE];
+  size_t len;
+
+  if (buffer == NULL || size == NULL || *size == 0)
+    return UV_EINVAL;
+
+  if (if_indextoname(ifindex, ifname_buf) == NULL)
+    return UV__ERR(errno);
+
+  len = strnlen(ifname_buf, sizeof(ifname_buf));
+
+  if (*size <= len) {
+    *size = len + 1;
+    return UV_ENOBUFS;
+  }
+
+  memcpy(buffer, ifname_buf, len);
+  buffer[len] = '\0';
+  *size = len;
+
+  return 0;
+}
+
+int uv_if_indextoiid(unsigned int ifindex, char* buffer, size_t* size) {
+  return uv_if_indextoname(ifindex, buffer, size);
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/getnameinfo.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/getnameinfo.cpp
similarity index 100%
rename from third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/getnameinfo.cpp
rename to third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/getnameinfo.cpp
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/ibmi.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/ibmi.cpp
new file mode 100644
index 0000000..56af31e
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/ibmi.cpp
@@ -0,0 +1,537 @@
+/* Copyright libuv project contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <stdio.h>
+#include <stdint.h>
+#include <stdlib.h>
+#include <string.h>
+#include <errno.h>
+
+#include <sys/types.h>
+#include <sys/socket.h>
+#include <sys/ioctl.h>
+#include <net/if.h>
+#include <netinet/in.h>
+#include <arpa/inet.h>
+
+#include <sys/time.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <utmp.h>
+#include <libgen.h>
+
+#include <sys/protosw.h>
+#include <procinfo.h>
+#include <sys/proc.h>
+#include <sys/procfs.h>
+
+#include <ctype.h>
+
+#include <sys/mntctl.h>
+#include <sys/vmount.h>
+#include <limits.h>
+#include <strings.h>
+#include <sys/vnode.h>
+
+#include <as400_protos.h>
+#include <as400_types.h>
+
+char* original_exepath = NULL;
+uv_mutex_t process_title_mutex;
+uv_once_t process_title_mutex_once = UV_ONCE_INIT;
+
+typedef struct {
+  int bytes_available;
+  int bytes_returned;
+  char current_date_and_time[8];
+  char system_name[8];
+  char elapsed_time[6];
+  char restricted_state_flag;
+  char reserved;
+  int percent_processing_unit_used;
+  int jobs_in_system;
+  int percent_permanent_addresses;
+  int percent_temporary_addresses;
+  int system_asp;
+  int percent_system_asp_used;
+  int total_auxiliary_storage;
+  int current_unprotected_storage_used;
+  int maximum_unprotected_storage_used;
+  int percent_db_capability;
+  int main_storage_size;
+  int number_of_partitions;
+  int partition_identifier;
+  int reserved1;
+  int current_processing_capacity;
+  char processor_sharing_attribute;
+  char reserved2[3];
+  int number_of_processors;
+  int active_jobs_in_system;
+  int active_threads_in_system;
+  int maximum_jobs_in_system;
+  int percent_temporary_256mb_segments_used;
+  int percent_temporary_4gb_segments_used;
+  int percent_permanent_256mb_segments_used;
+  int percent_permanent_4gb_segments_used;
+  int percent_current_interactive_performance;
+  int percent_uncapped_cpu_capacity_used;
+  int percent_shared_processor_pool_used;
+  long main_storage_size_long;
+} SSTS0200;
+
+
+typedef struct {
+  char header[208];
+  unsigned char loca_adapter_address[12];
+} LIND0500;
+
+
+typedef struct {
+  int bytes_provided;
+  int bytes_available;
+  char msgid[7];
+} errcode_s;
+
+
+static const unsigned char e2a[256] = {
+    0, 1, 2, 3, 156, 9, 134, 127, 151, 141, 142, 11, 12, 13, 14, 15,
+    16, 17, 18, 19, 157, 133, 8, 135, 24, 25, 146, 143, 28, 29, 30, 31,
+    128, 129, 130, 131, 132, 10, 23, 27, 136, 137, 138, 139, 140, 5, 6, 7,
+    144, 145, 22, 147, 148, 149, 150, 4, 152, 153, 154, 155, 20, 21, 158, 26,
+    32, 160, 161, 162, 163, 164, 165, 166, 167, 168, 91, 46, 60, 40, 43, 33,
+    38, 169, 170, 171, 172, 173, 174, 175, 176, 177, 93, 36, 42, 41, 59, 94,
+    45, 47, 178, 179, 180, 181, 182, 183, 184, 185, 124, 44, 37, 95, 62, 63,
+    186, 187, 188, 189, 190, 191, 192, 193, 194, 96, 58, 35, 64, 39, 61, 34,
+    195, 97, 98, 99, 100, 101, 102, 103, 104, 105, 196, 197, 198, 199, 200, 201,
+    202, 106, 107, 108, 109, 110, 111, 112, 113, 114, 203, 204, 205, 206, 207, 208,
+    209, 126, 115, 116, 117, 118, 119, 120, 121, 122, 210, 211, 212, 213, 214, 215,
+    216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231,
+    123, 65, 66, 67, 68, 69, 70, 71, 72, 73, 232, 233, 234, 235, 236, 237,
+    125, 74, 75, 76, 77, 78, 79, 80, 81, 82, 238, 239, 240, 241, 242, 243,
+    92, 159, 83, 84, 85, 86, 87, 88, 89, 90, 244, 245, 246, 247, 248, 249,
+    48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 250, 251, 252, 253, 254, 255};
+
+
+static const unsigned char a2e[256] = {
+    0, 1, 2, 3, 55, 45, 46, 47, 22, 5, 37, 11, 12, 13, 14, 15,
+    16, 17, 18, 19, 60, 61, 50, 38, 24, 25, 63, 39, 28, 29, 30, 31,
+    64, 79, 127, 123, 91, 108, 80, 125, 77, 93, 92, 78, 107, 96, 75, 97,
+    240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 122, 94, 76, 126, 110, 111,
+    124, 193, 194, 195, 196, 197, 198, 199, 200, 201, 209, 210, 211, 212, 213, 214,
+    215, 216, 217, 226, 227, 228, 229, 230, 231, 232, 233, 74, 224, 90, 95, 109,
+    121, 129, 130, 131, 132, 133, 134, 135, 136, 137, 145, 146, 147, 148, 149, 150,
+    151, 152, 153, 162, 163, 164, 165, 166, 167, 168, 169, 192, 106, 208, 161, 7,
+    32, 33, 34, 35, 36, 21, 6, 23, 40, 41, 42, 43, 44, 9, 10, 27,
+    48, 49, 26, 51, 52, 53, 54, 8, 56, 57, 58, 59, 4, 20, 62, 225,
+    65, 66, 67, 68, 69, 70, 71, 72, 73, 81, 82, 83, 84, 85, 86, 87,
+    88, 89, 98, 99, 100, 101, 102, 103, 104, 105, 112, 113, 114, 115, 116, 117,
+    118, 119, 120, 128, 138, 139, 140, 141, 142, 143, 144, 154, 155, 156, 157, 158,
+    159, 160, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183,
+    184, 185, 186, 187, 188, 189, 190, 191, 202, 203, 204, 205, 206, 207, 218, 219,
+    220, 221, 222, 223, 234, 235, 236, 237, 238, 239, 250, 251, 252, 253, 254, 255};
+
+
+static void iconv_e2a(unsigned char src[], unsigned char dst[], size_t length) {
+  size_t i;
+  for (i = 0; i < length; i++)
+    dst[i] = e2a[src[i]];
+}
+
+
+static void iconv_a2e(const char* src, unsigned char dst[], size_t length) {
+  size_t srclen;
+  size_t i;
+
+  srclen = strlen(src);
+  if (srclen > length)
+    srclen = length;
+  for (i = 0; i < srclen; i++)
+    dst[i] = a2e[src[i]];
+  /* padding the remaining part with spaces */
+  for (; i < length; i++)
+    dst[i] = a2e[' '];
+}
+
+void init_process_title_mutex_once(void) {
+  uv_mutex_init(&process_title_mutex);
+}
+
+static int get_ibmi_system_status(SSTS0200* rcvr) {
+  /* rcvrlen is input parameter 2 to QWCRSSTS */
+  unsigned int rcvrlen = sizeof(*rcvr);
+  unsigned char format[8], reset_status[10];
+
+  /* format is input parameter 3 to QWCRSSTS */
+  iconv_a2e("SSTS0200", format, sizeof(format));
+  /* reset_status is input parameter 4 */
+  iconv_a2e("*NO", reset_status, sizeof(reset_status));
+
+  /* errcode is input parameter 5 to QWCRSSTS */
+  errcode_s errcode;
+
+  /* qwcrssts_pointer is the 16-byte tagged system pointer to QWCRSSTS */
+  ILEpointer __attribute__((aligned(16))) qwcrssts_pointer;
+
+  /* qwcrssts_argv is the array of argument pointers to QWCRSSTS */
+  void* qwcrssts_argv[6];
+
+  /* Set the IBM i pointer to the QSYS/QWCRSSTS *PGM object */
+  int rc = _RSLOBJ2(&qwcrssts_pointer, RSLOBJ_TS_PGM, "QWCRSSTS", "QSYS");
+
+  if (rc != 0)
+    return rc;
+
+  /* initialize the QWCRSSTS returned info structure */
+  memset(rcvr, 0, sizeof(*rcvr));
+
+  /* initialize the QWCRSSTS error code structure */
+  memset(&errcode, 0, sizeof(errcode));
+  errcode.bytes_provided = sizeof(errcode);
+
+  /* initialize the array of argument pointers for the QWCRSSTS API */
+  qwcrssts_argv[0] = rcvr;
+  qwcrssts_argv[1] = &rcvrlen;
+  qwcrssts_argv[2] = &format;
+  qwcrssts_argv[3] = &reset_status;
+  qwcrssts_argv[4] = &errcode;
+  qwcrssts_argv[5] = NULL;
+
+  /* Call the IBM i QWCRSSTS API from PASE */
+  rc = _PGMCALL(&qwcrssts_pointer, qwcrssts_argv, 0);
+
+  return rc;
+}
+
+
+uint64_t uv_get_free_memory(void) {
+  SSTS0200 rcvr;
+
+  if (get_ibmi_system_status(&rcvr))
+    return 0;
+
+  return (uint64_t)rcvr.main_storage_size * 1024ULL;
+}
+
+
+uint64_t uv_get_total_memory(void) {
+  SSTS0200 rcvr;
+
+  if (get_ibmi_system_status(&rcvr))
+    return 0;
+
+  return (uint64_t)rcvr.main_storage_size * 1024ULL;
+}
+
+
+uint64_t uv_get_constrained_memory(void) {
+  return 0;  /* Memory constraints are unknown. */
+}
+
+
+void uv_loadavg(double avg[3]) {
+  SSTS0200 rcvr;
+
+  if (get_ibmi_system_status(&rcvr)) {
+    avg[0] = avg[1] = avg[2] = 0;
+    return;
+  }
+
+  /* The average (in tenths) of the elapsed time during which the processing
+   * units were in use. For example, a value of 411 in binary would be 41.1%.
+   * This percentage could be greater than 100% for an uncapped partition.
+   */
+  double processing_unit_used_percent =
+    rcvr.percent_processing_unit_used / 1000.0;
+
+  avg[0] = avg[1] = avg[2] = processing_unit_used_percent;
+}
+
+
+int uv_resident_set_memory(size_t* rss) {
+  *rss = 0;
+  return 0;
+}
+
+
+int uv_uptime(double* uptime) {
+  return UV_ENOSYS;
+}
+
+
+int uv_cpu_info(uv_cpu_info_t** cpu_infos, int* count) {
+  unsigned int numcpus, idx = 0;
+  uv_cpu_info_t* cpu_info;
+
+  *cpu_infos = NULL;
+  *count = 0;
+
+  numcpus = sysconf(_SC_NPROCESSORS_ONLN);
+
+  *cpu_infos = (uv_cpu_info_t*)uv__malloc(numcpus * sizeof(uv_cpu_info_t));
+  if (!*cpu_infos) {
+    return UV_ENOMEM;
+  }
+
+  cpu_info = *cpu_infos;
+  for (idx = 0; idx < numcpus; idx++) {
+    cpu_info->speed = 0;
+    cpu_info->model = uv__strdup("unknown");
+    cpu_info->cpu_times.user = 0;
+    cpu_info->cpu_times.sys = 0;
+    cpu_info->cpu_times.idle = 0;
+    cpu_info->cpu_times.irq = 0;
+    cpu_info->cpu_times.nice = 0;
+    cpu_info++;
+  }
+  *count = numcpus;
+
+  return 0;
+}
+
+
+static int get_ibmi_physical_address(const char* line, char (*phys_addr)[6]) {
+  LIND0500 rcvr;
+  /* rcvrlen is input parameter 2 to QDCRLIND */
+  unsigned int rcvrlen = sizeof(rcvr);
+  unsigned char format[8], line_name[10];
+  unsigned char mac_addr[sizeof(rcvr.loca_adapter_address)];
+  int c[6];
+
+  /* format is input parameter 3 to QDCRLIND */
+  iconv_a2e("LIND0500", format, sizeof(format));
+
+  /* line_name is input parameter 4 to QDCRLIND */
+  iconv_a2e(line, line_name, sizeof(line_name));
+
+  /* err is input parameter 5 to QDCRLIND */
+  errcode_s err;
+
+  /* qwcrssts_pointer is the 16-byte tagged system pointer to QDCRLIND */
+  ILEpointer __attribute__((aligned(16))) qdcrlind_pointer;
+
+  /* qwcrssts_argv is the array of argument pointers to QDCRLIND */
+  void* qdcrlind_argv[6];
+
+  /* Set the IBM i pointer to the QSYS/QDCRLIND *PGM object */
+  int rc = _RSLOBJ2(&qdcrlind_pointer, RSLOBJ_TS_PGM, "QDCRLIND", "QSYS");
+
+  if (rc != 0)
+    return rc;
+
+  /* initialize the QDCRLIND returned info structure */
+  memset(&rcvr, 0, sizeof(rcvr));
+
+  /* initialize the QDCRLIND error code structure */
+  memset(&err, 0, sizeof(err));
+  err.bytes_provided = sizeof(err);
+
+  /* initialize the array of argument pointers for the QDCRLIND API */
+  qdcrlind_argv[0] = &rcvr;
+  qdcrlind_argv[1] = &rcvrlen;
+  qdcrlind_argv[2] = &format;
+  qdcrlind_argv[3] = &line_name;
+  qdcrlind_argv[4] = &err;
+  qdcrlind_argv[5] = NULL;
+
+  /* Call the IBM i QDCRLIND API from PASE */
+  rc = _PGMCALL(&qdcrlind_pointer, qdcrlind_argv, 0);
+  if (rc != 0)
+    return rc;
+
+  if (err.bytes_available > 0) {
+    return -1;
+  }
+
+  /* convert ebcdic loca_adapter_address to ascii first */
+  iconv_e2a(rcvr.loca_adapter_address, mac_addr,
+            sizeof(rcvr.loca_adapter_address));
+
+  /* convert loca_adapter_address(char[12]) to phys_addr(char[6]) */
+  int r = sscanf(mac_addr, "%02x%02x%02x%02x%02x%02x",
+                &c[0], &c[1], &c[2], &c[3], &c[4], &c[5]);
+
+  if (r == ARRAY_SIZE(c)) {
+    (*phys_addr)[0] = c[0];
+    (*phys_addr)[1] = c[1];
+    (*phys_addr)[2] = c[2];
+    (*phys_addr)[3] = c[3];
+    (*phys_addr)[4] = c[4];
+    (*phys_addr)[5] = c[5];
+  } else {
+    memset(*phys_addr, 0, sizeof(*phys_addr));
+    rc = -1;
+  }
+  return rc;
+}
+
+
+int uv_interface_addresses(uv_interface_address_t** addresses, int* count) {
+  uv_interface_address_t* address;
+  struct ifaddrs_pase *ifap = NULL, *cur;
+  int inet6, r = 0;
+
+  *count = 0;
+  *addresses = NULL;
+
+  if (Qp2getifaddrs(&ifap))
+    return UV_ENOSYS;
+
+  /* The first loop to get the size of the array to be allocated */
+  for (cur = ifap; cur; cur = cur->ifa_next) {
+    if (!(cur->ifa_addr->sa_family == AF_INET6 ||
+          cur->ifa_addr->sa_family == AF_INET))
+      continue;
+
+    if (!(cur->ifa_flags & IFF_UP && cur->ifa_flags & IFF_RUNNING))
+      continue;
+
+    (*count)++;
+  }
+
+  if (*count == 0) {
+    Qp2freeifaddrs(ifap);
+    return 0;
+  }
+
+  /* Alloc the return interface structs */
+  *addresses = uv__calloc(*count, sizeof(**addresses));
+  if (*addresses == NULL) {
+    Qp2freeifaddrs(ifap);
+    return UV_ENOMEM;
+  }
+  address = *addresses;
+
+  /* The second loop to fill in the array */
+  for (cur = ifap; cur; cur = cur->ifa_next) {
+    if (!(cur->ifa_addr->sa_family == AF_INET6 ||
+          cur->ifa_addr->sa_family == AF_INET))
+      continue;
+
+    if (!(cur->ifa_flags & IFF_UP && cur->ifa_flags & IFF_RUNNING))
+      continue;
+
+    address->name = uv__strdup(cur->ifa_name);
+
+    inet6 = (cur->ifa_addr->sa_family == AF_INET6);
+
+    if (inet6) {
+      address->address.address6 = *((struct sockaddr_in6*)cur->ifa_addr);
+      address->netmask.netmask6 = *((struct sockaddr_in6*)cur->ifa_netmask);
+      address->netmask.netmask6.sin6_family = AF_INET6;
+    } else {
+      address->address.address4 = *((struct sockaddr_in*)cur->ifa_addr);
+      address->netmask.netmask4 = *((struct sockaddr_in*)cur->ifa_netmask);
+      address->netmask.netmask4.sin_family = AF_INET;
+    }
+    address->is_internal = cur->ifa_flags & IFF_LOOPBACK ? 1 : 0;
+    if (!address->is_internal) {
+      int rc = -1;
+      size_t name_len = strlen(address->name);
+      /* To get the associated MAC address, we must convert the address to a
+       * line description. Normally, the name field contains the line
+       * description name, but for VLANs it has the VLAN appended with a
+       * period. Since object names can also contain periods and numbers, there
+       * is no way to know if a returned name is for a VLAN or not. eg.
+       * *LIND ETH1.1 and *LIND ETH1, VLAN 1 both have the same name: ETH1.1
+       *
+       * Instead, we apply the same heuristic used by some of the XPF ioctls:
+       * - names > 10 *must* contain a VLAN
+       * - assume names <= 10 do not contain a VLAN and try directly
+       * - if >10 or QDCRLIND returned an error, try to strip off a VLAN
+       *   and try again
+       * - if we still get an error or couldn't find a period, leave the MAC as
+       *   00:00:00:00:00:00
+       */
+      if (name_len <= 10) {
+        /* Assume name does not contain a VLAN ID */
+        rc = get_ibmi_physical_address(address->name, &address->phys_addr);
+      }
+
+      if (name_len > 10 || rc != 0) {
+        /* The interface name must contain a VLAN ID suffix. Attempt to strip
+         * it off so we can get the line description to pass to QDCRLIND.
+         */
+        char* temp_name = uv__strdup(address->name);
+        char* dot = strrchr(temp_name, '.');
+        if (dot != NULL) {
+          *dot = '\0';
+          if (strlen(temp_name) <= 10) {
+            rc = get_ibmi_physical_address(temp_name, &address->phys_addr);
+          }
+        }
+        uv__free(temp_name);
+      }
+    }
+
+    address++;
+  }
+
+  Qp2freeifaddrs(ifap);
+  return r;
+}
+
+
+void uv_free_interface_addresses(uv_interface_address_t* addresses, int count) {
+  int i;
+
+  for (i = 0; i < count; ++i) {
+    uv__free(addresses[i].name);
+  }
+
+  uv__free(addresses);
+}
+
+char** uv_setup_args(int argc, char** argv) {
+  char exepath[UV__PATH_MAX];
+  char* s;
+  size_t size;
+
+  if (argc > 0) {
+    /* Use argv[0] to determine value for uv_exepath(). */
+    size = sizeof(exepath);
+    if (uv__search_path(argv[0], exepath, &size) == 0) {
+      uv_once(&process_title_mutex_once, init_process_title_mutex_once);
+      uv_mutex_lock(&process_title_mutex);
+      original_exepath = uv__strdup(exepath);
+      uv_mutex_unlock(&process_title_mutex);
+    }
+  }
+
+  return argv;
+}
+
+int uv_set_process_title(const char* title) {
+  return 0;
+}
+
+int uv_get_process_title(char* buffer, size_t size) {
+  if (buffer == NULL || size == 0)
+    return UV_EINVAL;
+
+  buffer[0] = '\0';
+  return 0;
+}
+
+void uv__process_title_cleanup(void) {
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/internal.h b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/internal.h
new file mode 100644
index 0000000..2b65415
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/internal.h
@@ -0,0 +1,371 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#ifndef UV_UNIX_INTERNAL_H_
+#define UV_UNIX_INTERNAL_H_
+
+#include "uv-common.h"
+
+#include <assert.h>
+#include <limits.h> /* _POSIX_PATH_MAX, PATH_MAX */
+#include <stdlib.h> /* abort */
+#include <string.h> /* strrchr */
+#include <fcntl.h>  /* O_CLOEXEC and O_NONBLOCK, if supported. */
+#include <stdio.h>
+#include <errno.h>
+#include <sys/socket.h>
+
+#if defined(__STRICT_ANSI__)
+# define inline __inline
+#endif
+
+#if defined(__linux__)
+# include "linux-syscalls.h"
+#endif /* __linux__ */
+
+#if defined(__MVS__)
+# include "os390-syscalls.h"
+#endif /* __MVS__ */
+
+#if defined(__sun)
+# include <sys/port.h>
+# include <port.h>
+#endif /* __sun */
+
+#if defined(_AIX)
+# define reqevents events
+# define rtnevents revents
+# include <sys/poll.h>
+#else
+# include <poll.h>
+#endif /* _AIX */
+
+#if defined(__APPLE__) && !TARGET_OS_IPHONE
+# include <AvailabilityMacros.h>
+#endif
+
+/*
+ * Define common detection for active Thread Sanitizer
+ * - clang uses __has_feature(thread_sanitizer)
+ * - gcc-7+ uses __SANITIZE_THREAD__
+ */
+#if defined(__has_feature)
+# if __has_feature(thread_sanitizer)
+#  define __SANITIZE_THREAD__ 1
+# endif
+#endif
+
+#if defined(PATH_MAX)
+# define UV__PATH_MAX PATH_MAX
+#else
+# define UV__PATH_MAX 8192
+#endif
+
+#if defined(__ANDROID__)
+int uv__pthread_sigmask(int how, const sigset_t* set, sigset_t* oset);
+# ifdef pthread_sigmask
+# undef pthread_sigmask
+# endif
+# define pthread_sigmask(how, set, oldset) uv__pthread_sigmask(how, set, oldset)
+#endif
+
+#define ACCESS_ONCE(type, var)                                                \
+  (*(volatile type*) &(var))
+
+#define ROUND_UP(a, b)                                                        \
+  ((a) % (b) ? ((a) + (b)) - ((a) % (b)) : (a))
+
+#define UNREACHABLE()                                                         \
+  do {                                                                        \
+    assert(0 && "unreachable code");                                          \
+    abort();                                                                  \
+  }                                                                           \
+  while (0)
+
+#define SAVE_ERRNO(block)                                                     \
+  do {                                                                        \
+    int _saved_errno = errno;                                                 \
+    do { block; } while (0);                                                  \
+    errno = _saved_errno;                                                     \
+  }                                                                           \
+  while (0)
+
+/* The __clang__ and __INTEL_COMPILER checks are superfluous because they
+ * define __GNUC__. They are here to convey to you, dear reader, that these
+ * macros are enabled when compiling with clang or icc.
+ */
+#if defined(__clang__) ||                                                     \
+    defined(__GNUC__) ||                                                      \
+    defined(__INTEL_COMPILER)
+# define UV_UNUSED(declaration)     __attribute__((unused)) declaration
+#else
+# define UV_UNUSED(declaration)     declaration
+#endif
+
+/* Leans on the fact that, on Linux, POLLRDHUP == EPOLLRDHUP. */
+#ifdef POLLRDHUP
+# define UV__POLLRDHUP POLLRDHUP
+#else
+# define UV__POLLRDHUP 0x2000
+#endif
+
+#ifdef POLLPRI
+# define UV__POLLPRI POLLPRI
+#else
+# define UV__POLLPRI 0
+#endif
+
+#if !defined(O_CLOEXEC) && defined(__FreeBSD__)
+/*
+ * It may be that we are just missing `__POSIX_VISIBLE >= 200809`.
+ * Try using fixed value const and give up, if it doesn't work
+ */
+# define O_CLOEXEC 0x00100000
+#endif
+
+typedef struct uv__stream_queued_fds_s uv__stream_queued_fds_t;
+
+/* loop flags */
+enum {
+  UV_LOOP_BLOCK_SIGPROF = 0x1,
+  UV_LOOP_REAP_CHILDREN = 0x2
+};
+
+/* flags of excluding ifaddr */
+enum {
+  UV__EXCLUDE_IFPHYS,
+  UV__EXCLUDE_IFADDR
+};
+
+typedef enum {
+  UV_CLOCK_PRECISE = 0,  /* Use the highest resolution clock available. */
+  UV_CLOCK_FAST = 1      /* Use the fastest clock with <= 1ms granularity. */
+} uv_clocktype_t;
+
+struct uv__stream_queued_fds_s {
+  unsigned int size;
+  unsigned int offset;
+  int fds[1];
+};
+
+
+#if defined(_AIX) || \
+    defined(__APPLE__) || \
+    defined(__DragonFly__) || \
+    defined(__FreeBSD__) || \
+    defined(__FreeBSD_kernel__) || \
+    defined(__linux__) || \
+    defined(__OpenBSD__) || \
+    defined(__NetBSD__)
+#define uv__nonblock uv__nonblock_ioctl
+#define UV__NONBLOCK_IS_IOCTL 1
+#else
+#define uv__nonblock uv__nonblock_fcntl
+#define UV__NONBLOCK_IS_IOCTL 0
+#endif
+
+/* On Linux, uv__nonblock_fcntl() and uv__nonblock_ioctl() do not commute
+ * when O_NDELAY is not equal to O_NONBLOCK.  Case in point: linux/sparc32
+ * and linux/sparc64, where O_NDELAY is O_NONBLOCK + another bit.
+ *
+ * Libuv uses uv__nonblock_fcntl() directly sometimes so ensure that it
+ * commutes with uv__nonblock().
+ */
+#if defined(__linux__) && O_NDELAY != O_NONBLOCK
+#undef uv__nonblock
+#define uv__nonblock uv__nonblock_fcntl
+#undef UV__NONBLOCK_IS_IOCTL
+#define UV__NONBLOCK_IS_FCNTL
+#endif
+
+/* core */
+int uv__cloexec(int fd, int set);
+int uv__nonblock_ioctl(int fd, int set);
+int uv__nonblock_fcntl(int fd, int set);
+int uv__close(int fd); /* preserves errno */
+int uv__close_nocheckstdio(int fd);
+int uv__close_nocancel(int fd);
+int uv__socket(int domain, int type, int protocol);
+ssize_t uv__recvmsg(int fd, struct msghdr *msg, int flags);
+void uv__make_close_pending(uv_handle_t* handle);
+int uv__getiovmax(void);
+
+void uv__io_init(uv__io_t* w, uv__io_cb cb, int fd);
+void uv__io_start(uv_loop_t* loop, uv__io_t* w, unsigned int events);
+void uv__io_stop(uv_loop_t* loop, uv__io_t* w, unsigned int events);
+void uv__io_close(uv_loop_t* loop, uv__io_t* w);
+void uv__io_feed(uv_loop_t* loop, uv__io_t* w);
+int uv__io_active(const uv__io_t* w, unsigned int events);
+int uv__io_check_fd(uv_loop_t* loop, int fd);
+void uv__io_poll(uv_loop_t* loop, int timeout); /* in milliseconds or -1 */
+int uv__io_fork(uv_loop_t* loop);
+int uv__fd_exists(uv_loop_t* loop, int fd);
+
+/* async */
+void uv__async_stop(uv_loop_t* loop);
+int uv__async_fork(uv_loop_t* loop);
+
+
+/* loop */
+void uv__run_idle(uv_loop_t* loop);
+void uv__run_check(uv_loop_t* loop);
+void uv__run_prepare(uv_loop_t* loop);
+
+/* stream */
+void uv__stream_init(uv_loop_t* loop, uv_stream_t* stream,
+    uv_handle_type type);
+int uv__stream_open(uv_stream_t*, int fd, int flags);
+void uv__stream_destroy(uv_stream_t* stream);
+#if defined(__APPLE__)
+int uv__stream_try_select(uv_stream_t* stream, int* fd);
+#endif /* defined(__APPLE__) */
+void uv__server_io(uv_loop_t* loop, uv__io_t* w, unsigned int events);
+int uv__accept(int sockfd);
+int uv__dup2_cloexec(int oldfd, int newfd);
+int uv__open_cloexec(const char* path, int flags);
+int uv__slurp(const char* filename, char* buf, size_t len);
+
+/* tcp */
+int uv__tcp_listen(uv_tcp_t* tcp, int backlog, uv_connection_cb cb);
+int uv__tcp_nodelay(int fd, int on);
+int uv__tcp_keepalive(int fd, int on, unsigned int delay);
+
+/* pipe */
+int uv__pipe_listen(uv_pipe_t* handle, int backlog, uv_connection_cb cb);
+
+/* signal */
+void uv__signal_close(uv_signal_t* handle);
+void uv__signal_global_once_init(void);
+void uv__signal_loop_cleanup(uv_loop_t* loop);
+int uv__signal_loop_fork(uv_loop_t* loop);
+
+/* platform specific */
+uint64_t uv__hrtime(uv_clocktype_t type);
+int uv__kqueue_init(uv_loop_t* loop);
+int uv__epoll_init(uv_loop_t* loop);
+int uv__platform_loop_init(uv_loop_t* loop);
+void uv__platform_loop_delete(uv_loop_t* loop);
+void uv__platform_invalidate_fd(uv_loop_t* loop, int fd);
+
+/* various */
+void uv__async_close(uv_async_t* handle);
+void uv__check_close(uv_check_t* handle);
+void uv__fs_event_close(uv_fs_event_t* handle);
+void uv__idle_close(uv_idle_t* handle);
+void uv__pipe_close(uv_pipe_t* handle);
+void uv__poll_close(uv_poll_t* handle);
+void uv__prepare_close(uv_prepare_t* handle);
+void uv__process_close(uv_process_t* handle);
+void uv__stream_close(uv_stream_t* handle);
+void uv__tcp_close(uv_tcp_t* handle);
+size_t uv__thread_stack_size(void);
+void uv__udp_close(uv_udp_t* handle);
+void uv__udp_finish_close(uv_udp_t* handle);
+FILE* uv__open_file(const char* path);
+int uv__getpwuid_r(uv_passwd_t* pwd);
+int uv__search_path(const char* prog, char* buf, size_t* buflen);
+void uv__wait_children(uv_loop_t* loop);
+
+/* random */
+int uv__random_devurandom(void* buf, size_t buflen);
+int uv__random_getrandom(void* buf, size_t buflen);
+int uv__random_getentropy(void* buf, size_t buflen);
+int uv__random_readpath(const char* path, void* buf, size_t buflen);
+int uv__random_sysctl(void* buf, size_t buflen);
+
+#if defined(__APPLE__)
+int uv___stream_fd(const uv_stream_t* handle);
+#define uv__stream_fd(handle) (uv___stream_fd((const uv_stream_t*) (handle)))
+#else
+#define uv__stream_fd(handle) ((handle)->io_watcher.fd)
+#endif /* defined(__APPLE__) */
+
+int uv__make_pipe(int fds[2], int flags);
+
+#if defined(__APPLE__)
+
+int uv__fsevents_init(uv_fs_event_t* handle);
+int uv__fsevents_close(uv_fs_event_t* handle);
+void uv__fsevents_loop_delete(uv_loop_t* loop);
+
+#endif /* defined(__APPLE__) */
+
+UV_UNUSED(static void uv__update_time(uv_loop_t* loop)) {
+  /* Use a fast time source if available.  We only need millisecond precision.
+   */
+  loop->time = uv__hrtime(UV_CLOCK_FAST) / 1000000;
+}
+
+UV_UNUSED(static const char* uv__basename_r(const char* path)) {
+  const char* s;
+
+  s = strrchr(path, '/');
+  if (s == NULL)
+    return (char*) path;
+
+  return s + 1;
+}
+
+#if defined(__linux__)
+int uv__inotify_fork(uv_loop_t* loop, void* old_watchers);
+#endif
+
+typedef int (*uv__peersockfunc)(int, struct sockaddr*, socklen_t*);
+
+int uv__getsockpeername(const uv_handle_t* handle,
+                        uv__peersockfunc func,
+                        struct sockaddr* name,
+                        int* namelen);
+
+#if defined(__linux__)            ||                                      \
+    defined(__FreeBSD__)          ||                                      \
+    defined(__FreeBSD_kernel__)   ||                                       \
+    defined(__DragonFly__)
+#define HAVE_MMSG 1
+struct uv__mmsghdr {
+  struct msghdr msg_hdr;
+  unsigned int msg_len;
+};
+
+int uv__recvmmsg(int fd, struct uv__mmsghdr* mmsg, unsigned int vlen);
+int uv__sendmmsg(int fd, struct uv__mmsghdr* mmsg, unsigned int vlen);
+#else
+#define HAVE_MMSG 0
+#endif
+
+#if defined(__sun)
+#if !defined(_POSIX_VERSION) || _POSIX_VERSION < 200809L
+size_t strnlen(const char* s, size_t maxlen);
+#endif
+#endif
+
+#if defined(__FreeBSD__)
+ssize_t
+uv__fs_copy_file_range(int fd_in,
+                       off_t* off_in,
+                       int fd_out,
+                       off_t* off_out,
+                       size_t len,
+                       unsigned int flags);
+#endif
+
+
+#endif /* UV_UNIX_INTERNAL_H_ */
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/kqueue.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/kqueue.cpp
new file mode 100644
index 0000000..86eb529
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/kqueue.cpp
@@ -0,0 +1,605 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <assert.h>
+#include <stdlib.h>
+#include <string.h>
+#include <errno.h>
+
+#include <sys/sysctl.h>
+#include <sys/types.h>
+#include <sys/event.h>
+#include <sys/time.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <time.h>
+
+/*
+ * Required on
+ * - Until at least FreeBSD 11.0
+ * - Older versions of Mac OS X
+ *
+ * http://www.boost.org/doc/libs/1_61_0/boost/asio/detail/kqueue_reactor.hpp
+ */
+#ifndef EV_OOBAND
+#define EV_OOBAND  EV_FLAG1
+#endif
+
+static void uv__fs_event(uv_loop_t* loop, uv__io_t* w, unsigned int fflags);
+
+
+int uv__kqueue_init(uv_loop_t* loop) {
+  loop->backend_fd = kqueue();
+  if (loop->backend_fd == -1)
+    return UV__ERR(errno);
+
+  uv__cloexec(loop->backend_fd, 1);
+
+  return 0;
+}
+
+
+#if defined(__APPLE__) && MAC_OS_X_VERSION_MAX_ALLOWED >= 1070
+static int uv__has_forked_with_cfrunloop;
+#endif
+
+int uv__io_fork(uv_loop_t* loop) {
+  int err;
+  loop->backend_fd = -1;
+  err = uv__kqueue_init(loop);
+  if (err)
+    return err;
+
+#if defined(__APPLE__) && MAC_OS_X_VERSION_MAX_ALLOWED >= 1070
+  if (loop->cf_state != NULL) {
+    /* We cannot start another CFRunloop and/or thread in the child
+       process; CF aborts if you try or if you try to touch the thread
+       at all to kill it. So the best we can do is ignore it from now
+       on. This means we can't watch directories in the same way
+       anymore (like other BSDs). It also means we cannot properly
+       clean up the allocated resources; calling
+       uv__fsevents_loop_delete from uv_loop_close will crash the
+       process. So we sidestep the issue by pretending like we never
+       started it in the first place.
+    */
+    uv__store_relaxed(&uv__has_forked_with_cfrunloop, 1);
+    uv__free(loop->cf_state);
+    loop->cf_state = NULL;
+  }
+#endif /* #if defined(__APPLE__) && MAC_OS_X_VERSION_MAX_ALLOWED >= 1070 */
+  return err;
+}
+
+
+int uv__io_check_fd(uv_loop_t* loop, int fd) {
+  struct kevent ev;
+  int rc;
+
+  rc = 0;
+  EV_SET(&ev, fd, EVFILT_READ, EV_ADD, 0, 0, 0);
+  if (kevent(loop->backend_fd, &ev, 1, NULL, 0, NULL))
+    rc = UV__ERR(errno);
+
+  EV_SET(&ev, fd, EVFILT_READ, EV_DELETE, 0, 0, 0);
+  if (rc == 0)
+    if (kevent(loop->backend_fd, &ev, 1, NULL, 0, NULL))
+      abort();
+
+  return rc;
+}
+
+
+void uv__io_poll(uv_loop_t* loop, int timeout) {
+  struct kevent events[1024];
+  struct kevent* ev;
+  struct timespec spec;
+  unsigned int nevents;
+  unsigned int revents;
+  QUEUE* q;
+  uv__io_t* w;
+  uv_process_t* process;
+  sigset_t* pset;
+  sigset_t set;
+  uint64_t base;
+  uint64_t diff;
+  int have_signals;
+  int filter;
+  int fflags;
+  int count;
+  int nfds;
+  int fd;
+  int op;
+  int i;
+  int user_timeout;
+  int reset_timeout;
+
+  if (loop->nfds == 0) {
+    assert(QUEUE_EMPTY(&loop->watcher_queue));
+    return;
+  }
+
+  nevents = 0;
+
+  while (!QUEUE_EMPTY(&loop->watcher_queue)) {
+    q = QUEUE_HEAD(&loop->watcher_queue);
+    QUEUE_REMOVE(q);
+    QUEUE_INIT(q);
+
+    w = QUEUE_DATA(q, uv__io_t, watcher_queue);
+    assert(w->pevents != 0);
+    assert(w->fd >= 0);
+    assert(w->fd < (int) loop->nwatchers);
+
+    if ((w->events & POLLIN) == 0 && (w->pevents & POLLIN) != 0) {
+      filter = EVFILT_READ;
+      fflags = 0;
+      op = EV_ADD;
+
+      if (w->cb == uv__fs_event) {
+        filter = EVFILT_VNODE;
+        fflags = NOTE_ATTRIB | NOTE_WRITE  | NOTE_RENAME
+               | NOTE_DELETE | NOTE_EXTEND | NOTE_REVOKE;
+        op = EV_ADD | EV_ONESHOT; /* Stop the event from firing repeatedly. */
+      }
+
+      EV_SET(events + nevents, w->fd, filter, op, fflags, 0, 0);
+
+      if (++nevents == ARRAY_SIZE(events)) {
+        if (kevent(loop->backend_fd, events, nevents, NULL, 0, NULL))
+          abort();
+        nevents = 0;
+      }
+    }
+
+    if ((w->events & POLLOUT) == 0 && (w->pevents & POLLOUT) != 0) {
+      EV_SET(events + nevents, w->fd, EVFILT_WRITE, EV_ADD, 0, 0, 0);
+
+      if (++nevents == ARRAY_SIZE(events)) {
+        if (kevent(loop->backend_fd, events, nevents, NULL, 0, NULL))
+          abort();
+        nevents = 0;
+      }
+    }
+
+   if ((w->events & UV__POLLPRI) == 0 && (w->pevents & UV__POLLPRI) != 0) {
+      EV_SET(events + nevents, w->fd, EV_OOBAND, EV_ADD, 0, 0, 0);
+
+      if (++nevents == ARRAY_SIZE(events)) {
+        if (kevent(loop->backend_fd, events, nevents, NULL, 0, NULL))
+          abort();
+        nevents = 0;
+      }
+    }
+
+    w->events = w->pevents;
+  }
+
+  pset = NULL;
+  if (loop->flags & UV_LOOP_BLOCK_SIGPROF) {
+    pset = &set;
+    sigemptyset(pset);
+    sigaddset(pset, SIGPROF);
+  }
+
+  assert(timeout >= -1);
+  base = loop->time;
+  count = 48; /* Benchmarks suggest this gives the best throughput. */
+
+  if (uv__get_internal_fields(loop)->flags & UV_METRICS_IDLE_TIME) {
+    reset_timeout = 1;
+    user_timeout = timeout;
+    timeout = 0;
+  } else {
+    reset_timeout = 0;
+  }
+
+  for (;; nevents = 0) {
+    /* Only need to set the provider_entry_time if timeout != 0. The function
+     * will return early if the loop isn't configured with UV_METRICS_IDLE_TIME.
+     */
+    if (timeout != 0)
+      uv__metrics_set_provider_entry_time(loop);
+
+    if (timeout != -1) {
+      spec.tv_sec = timeout / 1000;
+      spec.tv_nsec = (timeout % 1000) * 1000000;
+    }
+
+    if (pset != NULL)
+      pthread_sigmask(SIG_BLOCK, pset, NULL);
+
+    nfds = kevent(loop->backend_fd,
+                  events,
+                  nevents,
+                  events,
+                  ARRAY_SIZE(events),
+                  timeout == -1 ? NULL : &spec);
+
+    if (pset != NULL)
+      pthread_sigmask(SIG_UNBLOCK, pset, NULL);
+
+    /* Update loop->time unconditionally. It's tempting to skip the update when
+     * timeout == 0 (i.e. non-blocking poll) but there is no guarantee that the
+     * operating system didn't reschedule our process while in the syscall.
+     */
+    SAVE_ERRNO(uv__update_time(loop));
+
+    if (nfds == 0) {
+      if (reset_timeout != 0) {
+        timeout = user_timeout;
+        reset_timeout = 0;
+        if (timeout == -1)
+          continue;
+        if (timeout > 0)
+          goto update_timeout;
+      }
+
+      assert(timeout != -1);
+      return;
+    }
+
+    if (nfds == -1) {
+      if (errno != EINTR)
+        abort();
+
+      if (reset_timeout != 0) {
+        timeout = user_timeout;
+        reset_timeout = 0;
+      }
+
+      if (timeout == 0)
+        return;
+
+      if (timeout == -1)
+        continue;
+
+      /* Interrupted by a signal. Update timeout and poll again. */
+      goto update_timeout;
+    }
+
+    have_signals = 0;
+    nevents = 0;
+
+    assert(loop->watchers != NULL);
+    loop->watchers[loop->nwatchers] = (uv__io_t*) events;
+    loop->watchers[loop->nwatchers + 1] = (uv__io_t*) (uintptr_t) nfds;
+    for (i = 0; i < nfds; i++) {
+      ev = events + i;
+      fd = ev->ident;
+
+      /* Handle kevent NOTE_EXIT results */
+      if (ev->filter == EVFILT_PROC) {
+        QUEUE_FOREACH(q, &loop->process_handles) {
+          process = QUEUE_DATA(q, uv_process_t, queue);
+          if (process->pid == fd) {
+            process->flags |= UV_HANDLE_REAP;
+            loop->flags |= UV_LOOP_REAP_CHILDREN;
+            break;
+          }
+        }
+        nevents++;
+        continue;
+      }
+
+      /* Skip invalidated events, see uv__platform_invalidate_fd */
+      if (fd == -1)
+        continue;
+      w = (uv__io_t*)loop->watchers[fd];
+
+      if (w == NULL) {
+        /* File descriptor that we've stopped watching, disarm it.
+         * TODO: batch up. */
+        struct kevent events[1];
+
+        EV_SET(events + 0, fd, ev->filter, EV_DELETE, 0, 0, 0);
+        if (kevent(loop->backend_fd, events, 1, NULL, 0, NULL))
+          if (errno != EBADF && errno != ENOENT)
+            abort();
+
+        continue;
+      }
+
+      if (ev->filter == EVFILT_VNODE) {
+        assert(w->events == POLLIN);
+        assert(w->pevents == POLLIN);
+        uv__metrics_update_idle_time(loop);
+        w->cb(loop, w, ev->fflags); /* XXX always uv__fs_event() */
+        nevents++;
+        continue;
+      }
+
+      revents = 0;
+
+      if (ev->filter == EVFILT_READ) {
+        if (w->pevents & POLLIN) {
+          revents |= POLLIN;
+          w->rcount = ev->data;
+        } else {
+          /* TODO batch up */
+          struct kevent events[1];
+          EV_SET(events + 0, fd, ev->filter, EV_DELETE, 0, 0, 0);
+          if (kevent(loop->backend_fd, events, 1, NULL, 0, NULL))
+            if (errno != ENOENT)
+              abort();
+        }
+        if ((ev->flags & EV_EOF) && (w->pevents & UV__POLLRDHUP))
+          revents |= UV__POLLRDHUP;
+      }
+
+      if (ev->filter == EV_OOBAND) {
+        if (w->pevents & UV__POLLPRI) {
+          revents |= UV__POLLPRI;
+          w->rcount = ev->data;
+        } else {
+          /* TODO batch up */
+          struct kevent events[1];
+          EV_SET(events + 0, fd, ev->filter, EV_DELETE, 0, 0, 0);
+          if (kevent(loop->backend_fd, events, 1, NULL, 0, NULL))
+            if (errno != ENOENT)
+              abort();
+        }
+      }
+
+      if (ev->filter == EVFILT_WRITE) {
+        if (w->pevents & POLLOUT) {
+          revents |= POLLOUT;
+          w->wcount = ev->data;
+        } else {
+          /* TODO batch up */
+          struct kevent events[1];
+          EV_SET(events + 0, fd, ev->filter, EV_DELETE, 0, 0, 0);
+          if (kevent(loop->backend_fd, events, 1, NULL, 0, NULL))
+            if (errno != ENOENT)
+              abort();
+        }
+      }
+
+      if (ev->flags & EV_ERROR)
+        revents |= POLLERR;
+
+      if (revents == 0)
+        continue;
+
+      /* Run signal watchers last.  This also affects child process watchers
+       * because those are implemented in terms of signal watchers.
+       */
+      if (w == &loop->signal_io_watcher) {
+        have_signals = 1;
+      } else {
+        uv__metrics_update_idle_time(loop);
+        w->cb(loop, w, revents);
+      }
+
+      nevents++;
+    }
+
+    if (loop->flags & UV_LOOP_REAP_CHILDREN) {
+      loop->flags &= ~UV_LOOP_REAP_CHILDREN;
+      uv__wait_children(loop);
+    }
+
+    if (reset_timeout != 0) {
+      timeout = user_timeout;
+      reset_timeout = 0;
+    }
+
+    if (have_signals != 0) {
+      uv__metrics_update_idle_time(loop);
+      loop->signal_io_watcher.cb(loop, &loop->signal_io_watcher, POLLIN);
+    }
+
+    loop->watchers[loop->nwatchers] = NULL;
+    loop->watchers[loop->nwatchers + 1] = NULL;
+
+    if (have_signals != 0)
+      return;  /* Event loop should cycle now so don't poll again. */
+
+    if (nevents != 0) {
+      if (nfds == ARRAY_SIZE(events) && --count != 0) {
+        /* Poll for more events but don't block this time. */
+        timeout = 0;
+        continue;
+      }
+      return;
+    }
+
+    if (timeout == 0)
+      return;
+
+    if (timeout == -1)
+      continue;
+
+update_timeout:
+    assert(timeout > 0);
+
+    diff = loop->time - base;
+    if (diff >= (uint64_t) timeout)
+      return;
+
+    timeout -= diff;
+  }
+}
+
+
+void uv__platform_invalidate_fd(uv_loop_t* loop, int fd) {
+  struct kevent* events;
+  uintptr_t i;
+  uintptr_t nfds;
+
+  assert(loop->watchers != NULL);
+  assert(fd >= 0);
+
+  events = (struct kevent*) loop->watchers[loop->nwatchers];
+  nfds = (uintptr_t) loop->watchers[loop->nwatchers + 1];
+  if (events == NULL)
+    return;
+
+  /* Invalidate events with same file descriptor */
+  for (i = 0; i < nfds; i++)
+    if ((int) events[i].ident == fd && events[i].filter != EVFILT_PROC)
+      events[i].ident = -1;
+}
+
+
+static void uv__fs_event(uv_loop_t* loop, uv__io_t* w, unsigned int fflags) {
+  uv_fs_event_t* handle;
+  struct kevent ev;
+  int events;
+  const char* path;
+#if defined(F_GETPATH)
+  /* MAXPATHLEN == PATH_MAX but the former is what XNU calls it internally. */
+  char pathbuf[MAXPATHLEN];
+#endif
+
+  handle = container_of(w, uv_fs_event_t, event_watcher);
+
+  if (fflags & (NOTE_ATTRIB | NOTE_EXTEND))
+    events = UV_CHANGE;
+  else
+    events = UV_RENAME;
+
+  path = NULL;
+#if defined(F_GETPATH)
+  /* Also works when the file has been unlinked from the file system. Passing
+   * in the path when the file has been deleted is arguably a little strange
+   * but it's consistent with what the inotify backend does.
+   */
+  if (fcntl(handle->event_watcher.fd, F_GETPATH, pathbuf) == 0)
+    path = uv__basename_r(pathbuf);
+#endif
+  handle->cb(handle, path, events, 0);
+
+  if (handle->event_watcher.fd == -1)
+    return;
+
+  /* Watcher operates in one-shot mode, re-arm it. */
+  fflags = NOTE_ATTRIB | NOTE_WRITE  | NOTE_RENAME
+         | NOTE_DELETE | NOTE_EXTEND | NOTE_REVOKE;
+
+  EV_SET(&ev, w->fd, EVFILT_VNODE, EV_ADD | EV_ONESHOT, fflags, 0, 0);
+
+  if (kevent(loop->backend_fd, &ev, 1, NULL, 0, NULL))
+    abort();
+}
+
+
+int uv_fs_event_init(uv_loop_t* loop, uv_fs_event_t* handle) {
+  uv__handle_init(loop, (uv_handle_t*)handle, UV_FS_EVENT);
+  return 0;
+}
+
+
+int uv_fs_event_start(uv_fs_event_t* handle,
+                      uv_fs_event_cb cb,
+                      const char* path,
+                      unsigned int flags) {
+  int fd;
+#if defined(__APPLE__) && MAC_OS_X_VERSION_MAX_ALLOWED >= 1070
+  struct stat statbuf;
+#endif
+
+  if (uv__is_active(handle))
+    return UV_EINVAL;
+
+  handle->cb = cb;
+  handle->path = uv__strdup(path);
+  if (handle->path == NULL)
+    return UV_ENOMEM;
+
+  /* TODO open asynchronously - but how do we report back errors? */
+  fd = open(handle->path, O_RDONLY);
+  if (fd == -1) {
+    uv__free(handle->path);
+    handle->path = NULL;
+    return UV__ERR(errno);
+  }
+
+#if defined(__APPLE__) && MAC_OS_X_VERSION_MAX_ALLOWED >= 1070
+  /* Nullify field to perform checks later */
+  handle->cf_cb = NULL;
+  handle->realpath = NULL;
+  handle->realpath_len = 0;
+  handle->cf_flags = flags;
+
+  if (fstat(fd, &statbuf))
+    goto fallback;
+  /* FSEvents works only with directories */
+  if (!(statbuf.st_mode & S_IFDIR))
+    goto fallback;
+
+  if (0 == uv__load_relaxed(&uv__has_forked_with_cfrunloop)) {
+    int r;
+    /* The fallback fd is no longer needed */
+    uv__close_nocheckstdio(fd);
+    handle->event_watcher.fd = -1;
+    r = uv__fsevents_init(handle);
+    if (r == 0) {
+      uv__handle_start(handle);
+    } else {
+      uv__free(handle->path);
+      handle->path = NULL;
+    }
+    return r;
+  }
+fallback:
+#endif /* #if defined(__APPLE__) && MAC_OS_X_VERSION_MAX_ALLOWED >= 1070 */
+
+  uv__handle_start(handle);
+  uv__io_init(&handle->event_watcher, uv__fs_event, fd);
+  uv__io_start(handle->loop, &handle->event_watcher, POLLIN);
+
+  return 0;
+}
+
+
+int uv_fs_event_stop(uv_fs_event_t* handle) {
+  int r;
+  r = 0;
+
+  if (!uv__is_active(handle))
+    return 0;
+
+  uv__handle_stop(handle);
+
+#if defined(__APPLE__) && MAC_OS_X_VERSION_MAX_ALLOWED >= 1070
+  if (0 == uv__load_relaxed(&uv__has_forked_with_cfrunloop))
+    if (handle->cf_cb != NULL)
+      r = uv__fsevents_close(handle);
+#endif
+
+  if (handle->event_watcher.fd != -1) {
+    uv__io_close(handle->loop, &handle->event_watcher);
+    uv__close(handle->event_watcher.fd);
+    handle->event_watcher.fd = -1;
+  }
+
+  uv__free(handle->path);
+  handle->path = NULL;
+
+  return r;
+}
+
+
+void uv__fs_event_close(uv_fs_event_t* handle) {
+  uv_fs_event_stop(handle);
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/linux-core.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/linux-core.cpp
new file mode 100644
index 0000000..12ed7ff
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/linux-core.cpp
@@ -0,0 +1,841 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+/* We lean on the fact that POLL{IN,OUT,ERR,HUP} correspond with their
+ * EPOLL* counterparts.  We use the POLL* variants in this file because that
+ * is what libuv uses elsewhere.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <inttypes.h>
+#include <stdint.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <assert.h>
+#include <errno.h>
+
+#include <net/if.h>
+#include <sys/epoll.h>
+#include <sys/param.h>
+#include <sys/prctl.h>
+#include <sys/sysinfo.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <time.h>
+
+#define HAVE_IFADDRS_H 1
+
+# if defined(__ANDROID_API__) && __ANDROID_API__ < 24
+# undef HAVE_IFADDRS_H
+#endif
+
+#ifdef __UCLIBC__
+# if __UCLIBC_MAJOR__ < 0 && __UCLIBC_MINOR__ < 9 && __UCLIBC_SUBLEVEL__ < 32
+#  undef HAVE_IFADDRS_H
+# endif
+#endif
+
+#ifdef HAVE_IFADDRS_H
+# include <ifaddrs.h>
+# include <sys/socket.h>
+# include <net/ethernet.h>
+# include <netpacket/packet.h>
+#endif /* HAVE_IFADDRS_H */
+
+/* Available from 2.6.32 onwards. */
+#ifndef CLOCK_MONOTONIC_COARSE
+# define CLOCK_MONOTONIC_COARSE 6
+#endif
+
+#ifdef __FRC_ROBORIO__
+#include "wpi/timestamp.h"
+#endif
+
+/* This is rather annoying: CLOCK_BOOTTIME lives in <linux/time.h> but we can't
+ * include that file because it conflicts with <time.h>. We'll just have to
+ * define it ourselves.
+ */
+#ifndef CLOCK_BOOTTIME
+# define CLOCK_BOOTTIME 7
+#endif
+
+static int read_models(unsigned int numcpus, uv_cpu_info_t* ci);
+static int read_times(FILE* statfile_fp,
+                      unsigned int numcpus,
+                      uv_cpu_info_t* ci);
+static void read_speeds(unsigned int numcpus, uv_cpu_info_t* ci);
+static uint64_t read_cpufreq(unsigned int cpunum);
+
+int uv__platform_loop_init(uv_loop_t* loop) {
+  
+  loop->inotify_fd = -1;
+  loop->inotify_watchers = NULL;
+
+  return uv__epoll_init(loop);
+}
+
+
+int uv__io_fork(uv_loop_t* loop) {
+  int err;
+  void* old_watchers;
+
+  old_watchers = loop->inotify_watchers;
+
+  uv__close(loop->backend_fd);
+  loop->backend_fd = -1;
+  uv__platform_loop_delete(loop);
+
+  err = uv__platform_loop_init(loop);
+  if (err)
+    return err;
+
+  return uv__inotify_fork(loop, old_watchers);
+}
+
+
+void uv__platform_loop_delete(uv_loop_t* loop) {
+  if (loop->inotify_fd == -1) return;
+  uv__io_stop(loop, &loop->inotify_read_watcher, POLLIN);
+  uv__close(loop->inotify_fd);
+  loop->inotify_fd = -1;
+}
+
+
+uint64_t uv__hrtime(uv_clocktype_t type) {
+#ifdef __FRC_ROBORIO__
+  return wpi::Now() * 1000u;
+#else
+  static clock_t fast_clock_id = -1;
+  struct timespec t;
+  clock_t clock_id;
+
+  /* Prefer CLOCK_MONOTONIC_COARSE if available but only when it has
+   * millisecond granularity or better.  CLOCK_MONOTONIC_COARSE is
+   * serviced entirely from the vDSO, whereas CLOCK_MONOTONIC may
+   * decide to make a costly system call.
+   */
+  /* TODO(bnoordhuis) Use CLOCK_MONOTONIC_COARSE for UV_CLOCK_PRECISE
+   * when it has microsecond granularity or better (unlikely).
+   */
+  clock_id = CLOCK_MONOTONIC;
+  if (type != UV_CLOCK_FAST)
+    goto done;
+
+  clock_id = uv__load_relaxed(&fast_clock_id);
+  if (clock_id != -1)
+    goto done;
+
+  clock_id = CLOCK_MONOTONIC;
+  if (0 == clock_getres(CLOCK_MONOTONIC_COARSE, &t))
+    if (t.tv_nsec <= 1 * 1000 * 1000)
+      clock_id = CLOCK_MONOTONIC_COARSE;
+
+  uv__store_relaxed(&fast_clock_id, clock_id);
+
+done:
+
+  if (clock_gettime(clock_id, &t))
+    return 0;  /* Not really possible. */
+
+  return t.tv_sec * (uint64_t) 1e9 + t.tv_nsec;
+#endif
+}
+
+
+int uv_resident_set_memory(size_t* rss) {
+  char buf[1024];
+  const char* s;
+  ssize_t n;
+  long val;
+  int fd;
+  int i;
+
+  do
+    fd = open("/proc/self/stat", O_RDONLY);
+  while (fd == -1 && errno == EINTR);
+
+  if (fd == -1)
+    return UV__ERR(errno);
+
+  do
+    n = read(fd, buf, sizeof(buf) - 1);
+  while (n == -1 && errno == EINTR);
+
+  uv__close(fd);
+  if (n == -1)
+    return UV__ERR(errno);
+  buf[n] = '\0';
+
+  s = strchr(buf, ' ');
+  if (s == NULL)
+    goto err;
+
+  s += 1;
+  if (*s != '(')
+    goto err;
+
+  s = strchr(s, ')');
+  if (s == NULL)
+    goto err;
+
+  for (i = 1; i <= 22; i++) {
+    s = strchr(s + 1, ' ');
+    if (s == NULL)
+      goto err;
+  }
+
+  errno = 0;
+  val = strtol(s, NULL, 10);
+  if (errno != 0)
+    goto err;
+  if (val < 0)
+    goto err;
+
+  *rss = val * getpagesize();
+  return 0;
+
+err:
+  return UV_EINVAL;
+}
+
+int uv_uptime(double* uptime) {
+  static volatile int no_clock_boottime;
+  char buf[128];
+  struct timespec now;
+  int r;
+
+  /* Try /proc/uptime first, then fallback to clock_gettime(). */
+
+  if (0 == uv__slurp("/proc/uptime", buf, sizeof(buf)))
+    if (1 == sscanf(buf, "%lf", uptime))
+      return 0;
+
+  /* Try CLOCK_BOOTTIME first, fall back to CLOCK_MONOTONIC if not available
+   * (pre-2.6.39 kernels). CLOCK_MONOTONIC doesn't increase when the system
+   * is suspended.
+   */
+  if (no_clock_boottime) {
+    retry_clock_gettime: r = clock_gettime(CLOCK_MONOTONIC, &now);
+  }
+  else if ((r = clock_gettime(CLOCK_BOOTTIME, &now)) && errno == EINVAL) {
+    no_clock_boottime = 1;
+    goto retry_clock_gettime;
+  }
+
+  if (r)
+    return UV__ERR(errno);
+
+  *uptime = now.tv_sec;
+  return 0;
+}
+
+
+static int uv__cpu_num(FILE* statfile_fp, unsigned int* numcpus) {
+  unsigned int num;
+  char buf[1024];
+
+  if (!fgets(buf, sizeof(buf), statfile_fp))
+    return UV_EIO;
+
+  num = 0;
+  while (fgets(buf, sizeof(buf), statfile_fp)) {
+    if (strncmp(buf, "cpu", 3))
+      break;
+    num++;
+  }
+
+  if (num == 0)
+    return UV_EIO;
+
+  *numcpus = num;
+  return 0;
+}
+
+
+int uv_cpu_info(uv_cpu_info_t** cpu_infos, int* count) {
+  unsigned int numcpus;
+  uv_cpu_info_t* ci;
+  int err;
+  FILE* statfile_fp;
+
+  *cpu_infos = NULL;
+  *count = 0;
+
+  statfile_fp = uv__open_file("/proc/stat");
+  if (statfile_fp == NULL)
+    return UV__ERR(errno);
+
+  err = uv__cpu_num(statfile_fp, &numcpus);
+  if (err < 0)
+    goto out;
+
+  err = UV_ENOMEM;
+  ci = (uv_cpu_info_t*)uv__calloc(numcpus, sizeof(*ci));
+  if (ci == NULL)
+    goto out;
+
+  err = read_models(numcpus, ci);
+  if (err == 0)
+    err = read_times(statfile_fp, numcpus, ci);
+
+  if (err) {
+    uv_free_cpu_info(ci, numcpus);
+    goto out;
+  }
+
+  /* read_models() on x86 also reads the CPU speed from /proc/cpuinfo.
+   * We don't check for errors here. Worst case, the field is left zero.
+   */
+  if (ci[0].speed == 0)
+    read_speeds(numcpus, ci);
+
+  *cpu_infos = ci;
+  *count = numcpus;
+  err = 0;
+
+out:
+
+  if (fclose(statfile_fp))
+    if (errno != EINTR && errno != EINPROGRESS)
+      abort();
+
+  return err;
+}
+
+
+static void read_speeds(unsigned int numcpus, uv_cpu_info_t* ci) {
+  unsigned int num;
+
+  for (num = 0; num < numcpus; num++)
+    ci[num].speed = read_cpufreq(num) / 1000;
+}
+
+
+/* Also reads the CPU frequency on ppc and x86. The other architectures only
+ * have a BogoMIPS field, which may not be very accurate.
+ *
+ * Note: Simply returns on error, uv_cpu_info() takes care of the cleanup.
+ */
+static int read_models(unsigned int numcpus, uv_cpu_info_t* ci) {
+#if defined(__PPC__)
+  static const char model_marker[] = "cpu\t\t: ";
+  static const char speed_marker[] = "clock\t\t: ";
+#else
+  static const char model_marker[] = "model name\t: ";
+  static const char speed_marker[] = "cpu MHz\t\t: ";
+#endif
+  const char* inferred_model;
+  unsigned int model_idx;
+  unsigned int speed_idx;
+  unsigned int part_idx;
+  char buf[1024];
+  char* model;
+  FILE* fp;
+  int model_id;
+
+  /* Most are unused on non-ARM, non-MIPS and non-x86 architectures. */
+  (void) &model_marker;
+  (void) &speed_marker;
+  (void) &speed_idx;
+  (void) &part_idx;
+  (void) &model;
+  (void) &buf;
+  (void) &fp;
+  (void) &model_id;
+
+  model_idx = 0;
+  speed_idx = 0;
+  part_idx = 0;
+
+#if defined(__arm__) || \
+    defined(__i386__) || \
+    defined(__mips__) || \
+    defined(__aarch64__) || \
+    defined(__PPC__) || \
+    defined(__x86_64__)
+  fp = uv__open_file("/proc/cpuinfo");
+  if (fp == NULL)
+    return UV__ERR(errno);
+
+  while (fgets(buf, sizeof(buf), fp)) {
+    if (model_idx < numcpus) {
+      if (strncmp(buf, model_marker, sizeof(model_marker) - 1) == 0) {
+        model = buf + sizeof(model_marker) - 1;
+        model = uv__strndup(model, strlen(model) - 1);  /* Strip newline. */
+        if (model == NULL) {
+          fclose(fp);
+          return UV_ENOMEM;
+        }
+        ci[model_idx++].model = model;
+        continue;
+      }
+    }
+#if defined(__arm__) || defined(__mips__) || defined(__aarch64__)
+    if (model_idx < numcpus) {
+#if defined(__arm__)
+      /* Fallback for pre-3.8 kernels. */
+      static const char model_marker[] = "Processor\t: ";
+#elif defined(__aarch64__)
+      static const char part_marker[] = "CPU part\t: ";
+
+      /* Adapted from: https://github.com/karelzak/util-linux */
+      struct vendor_part {
+        const int id;
+        const char* name;
+      };
+
+      static const struct vendor_part arm_chips[] = {
+        { 0x811, "ARM810" },
+        { 0x920, "ARM920" },
+        { 0x922, "ARM922" },
+        { 0x926, "ARM926" },
+        { 0x940, "ARM940" },
+        { 0x946, "ARM946" },
+        { 0x966, "ARM966" },
+        { 0xa20, "ARM1020" },
+        { 0xa22, "ARM1022" },
+        { 0xa26, "ARM1026" },
+        { 0xb02, "ARM11 MPCore" },
+        { 0xb36, "ARM1136" },
+        { 0xb56, "ARM1156" },
+        { 0xb76, "ARM1176" },
+        { 0xc05, "Cortex-A5" },
+        { 0xc07, "Cortex-A7" },
+        { 0xc08, "Cortex-A8" },
+        { 0xc09, "Cortex-A9" },
+        { 0xc0d, "Cortex-A17" },  /* Originally A12 */
+        { 0xc0f, "Cortex-A15" },
+        { 0xc0e, "Cortex-A17" },
+        { 0xc14, "Cortex-R4" },
+        { 0xc15, "Cortex-R5" },
+        { 0xc17, "Cortex-R7" },
+        { 0xc18, "Cortex-R8" },
+        { 0xc20, "Cortex-M0" },
+        { 0xc21, "Cortex-M1" },
+        { 0xc23, "Cortex-M3" },
+        { 0xc24, "Cortex-M4" },
+        { 0xc27, "Cortex-M7" },
+        { 0xc60, "Cortex-M0+" },
+        { 0xd01, "Cortex-A32" },
+        { 0xd03, "Cortex-A53" },
+        { 0xd04, "Cortex-A35" },
+        { 0xd05, "Cortex-A55" },
+        { 0xd06, "Cortex-A65" },
+        { 0xd07, "Cortex-A57" },
+        { 0xd08, "Cortex-A72" },
+        { 0xd09, "Cortex-A73" },
+        { 0xd0a, "Cortex-A75" },
+        { 0xd0b, "Cortex-A76" },
+        { 0xd0c, "Neoverse-N1" },
+        { 0xd0d, "Cortex-A77" },
+        { 0xd0e, "Cortex-A76AE" },
+        { 0xd13, "Cortex-R52" },
+        { 0xd20, "Cortex-M23" },
+        { 0xd21, "Cortex-M33" },
+        { 0xd41, "Cortex-A78" },
+        { 0xd42, "Cortex-A78AE" },
+        { 0xd4a, "Neoverse-E1" },
+        { 0xd4b, "Cortex-A78C" },
+      };
+
+      if (strncmp(buf, part_marker, sizeof(part_marker) - 1) == 0) {
+        model = buf + sizeof(part_marker) - 1;
+
+        errno = 0;
+        model_id = strtol(model, NULL, 16);
+        if ((errno != 0) || model_id < 0) {
+          fclose(fp);
+          return UV_EINVAL;
+        }
+
+        for (part_idx = 0; part_idx < ARRAY_SIZE(arm_chips); part_idx++) {
+          if (model_id == arm_chips[part_idx].id) {
+            model = uv__strdup(arm_chips[part_idx].name);
+            if (model == NULL) {
+              fclose(fp);
+              return UV_ENOMEM;
+            }
+            ci[model_idx++].model = model;
+            break;
+          }
+        }
+      }
+#else	/* defined(__mips__) */
+      static const char model_marker[] = "cpu model\t\t: ";
+#endif
+      if (strncmp(buf, model_marker, sizeof(model_marker) - 1) == 0) {
+        model = buf + sizeof(model_marker) - 1;
+        model = uv__strndup(model, strlen(model) - 1);  /* Strip newline. */
+        if (model == NULL) {
+          fclose(fp);
+          return UV_ENOMEM;
+        }
+        ci[model_idx++].model = model;
+        continue;
+      }
+    }
+#else  /* !__arm__ && !__mips__ && !__aarch64__ */
+    if (speed_idx < numcpus) {
+      if (strncmp(buf, speed_marker, sizeof(speed_marker) - 1) == 0) {
+        ci[speed_idx++].speed = atoi(buf + sizeof(speed_marker) - 1);
+        continue;
+      }
+    }
+#endif  /* __arm__ || __mips__ || __aarch64__ */
+  }
+
+  fclose(fp);
+#endif  /* __arm__ || __i386__ || __mips__ || __PPC__ || __x86_64__ || __aarch__ */
+
+  /* Now we want to make sure that all the models contain *something* because
+   * it's not safe to leave them as null. Copy the last entry unless there
+   * isn't one, in that case we simply put "unknown" into everything.
+   */
+  inferred_model = "unknown";
+  if (model_idx > 0)
+    inferred_model = ci[model_idx - 1].model;
+
+  while (model_idx < numcpus) {
+    model = uv__strndup(inferred_model, strlen(inferred_model));
+    if (model == NULL)
+      return UV_ENOMEM;
+    ci[model_idx++].model = model;
+  }
+
+  return 0;
+}
+
+
+static int read_times(FILE* statfile_fp,
+                      unsigned int numcpus,
+                      uv_cpu_info_t* ci) {
+  struct uv_cpu_times_s ts;
+  unsigned int ticks;
+  unsigned int multiplier;
+  uint64_t user;
+  uint64_t nice;
+  uint64_t sys;
+  uint64_t idle;
+  uint64_t dummy;
+  uint64_t irq;
+  uint64_t num;
+  uint64_t len;
+  char buf[1024];
+
+  ticks = (unsigned int)sysconf(_SC_CLK_TCK);
+  assert(ticks != (unsigned int) -1);
+  assert(ticks != 0);
+  multiplier = ((uint64_t)1000L / ticks);
+
+  rewind(statfile_fp);
+
+  if (!fgets(buf, sizeof(buf), statfile_fp))
+    abort();
+
+  num = 0;
+
+  while (fgets(buf, sizeof(buf), statfile_fp)) {
+    if (num >= numcpus)
+      break;
+
+    if (strncmp(buf, "cpu", 3))
+      break;
+
+    /* skip "cpu<num> " marker */
+    {
+      unsigned int n;
+      int r = sscanf(buf, "cpu%u ", &n);
+      assert(r == 1);
+      (void) r;  /* silence build warning */
+      for (len = sizeof("cpu0"); n /= 10; len++);
+    }
+
+    /* Line contains user, nice, system, idle, iowait, irq, softirq, steal,
+     * guest, guest_nice but we're only interested in the first four + irq.
+     *
+     * Don't use %*s to skip fields or %ll to read straight into the uint64_t
+     * fields, they're not allowed in C89 mode.
+     */
+    if (6 != sscanf(buf + len,
+                    "%" PRIu64 " %" PRIu64 " %" PRIu64
+                    "%" PRIu64 " %" PRIu64 " %" PRIu64,
+                    &user,
+                    &nice,
+                    &sys,
+                    &idle,
+                    &dummy,
+                    &irq))
+      abort();
+
+    ts.user = user * multiplier;
+    ts.nice = nice * multiplier;
+    ts.sys  = sys * multiplier;
+    ts.idle = idle * multiplier;
+    ts.irq  = irq * multiplier;
+    ci[num++].cpu_times = ts;
+  }
+  assert(num == numcpus);
+
+  return 0;
+}
+
+
+static uint64_t read_cpufreq(unsigned int cpunum) {
+  uint64_t val;
+  char buf[1024];
+  FILE* fp;
+
+  snprintf(buf,
+           sizeof(buf),
+           "/sys/devices/system/cpu/cpu%u/cpufreq/scaling_cur_freq",
+           cpunum);
+
+  fp = uv__open_file(buf);
+  if (fp == NULL)
+    return 0;
+
+  if (fscanf(fp, "%" PRIu64, &val) != 1)
+    val = 0;
+
+  fclose(fp);
+
+  return val;
+}
+
+
+#ifdef HAVE_IFADDRS_H
+static int uv__ifaddr_exclude(struct ifaddrs *ent, int exclude_type) {
+  if (!((ent->ifa_flags & IFF_UP) && (ent->ifa_flags & IFF_RUNNING)))
+    return 1;
+  if (ent->ifa_addr == NULL)
+    return 1;
+  /*
+   * On Linux getifaddrs returns information related to the raw underlying
+   * devices. We're not interested in this information yet.
+   */
+  if (ent->ifa_addr->sa_family == PF_PACKET)
+    return exclude_type;
+  return !exclude_type;
+}
+#endif
+
+int uv_interface_addresses(uv_interface_address_t** addresses, int* count) {
+#ifndef HAVE_IFADDRS_H
+  *count = 0;
+  *addresses = NULL;
+  return UV_ENOSYS;
+#else
+  struct ifaddrs *addrs, *ent;
+  uv_interface_address_t* address;
+  int i;
+  struct sockaddr_ll *sll;
+
+  *count = 0;
+  *addresses = NULL;
+
+  if (getifaddrs(&addrs))
+    return UV__ERR(errno);
+
+  /* Count the number of interfaces */
+  for (ent = addrs; ent != NULL; ent = ent->ifa_next) {
+    if (uv__ifaddr_exclude(ent, UV__EXCLUDE_IFADDR))
+      continue;
+
+    (*count)++;
+  }
+
+  if (*count == 0) {
+    freeifaddrs(addrs);
+    return 0;
+  }
+
+  /* Make sure the memory is initiallized to zero using calloc() */
+  *addresses = (uv_interface_address_t*)uv__calloc(*count, sizeof(**addresses));
+  if (!(*addresses)) {
+    freeifaddrs(addrs);
+    return UV_ENOMEM;
+  }
+
+  address = *addresses;
+
+  for (ent = addrs; ent != NULL; ent = ent->ifa_next) {
+    if (uv__ifaddr_exclude(ent, UV__EXCLUDE_IFADDR))
+      continue;
+
+    address->name = uv__strdup(ent->ifa_name);
+
+    if (ent->ifa_addr->sa_family == AF_INET6) {
+      address->address.address6 = *((struct sockaddr_in6*) ent->ifa_addr);
+    } else {
+      address->address.address4 = *((struct sockaddr_in*) ent->ifa_addr);
+    }
+
+    if (ent->ifa_netmask->sa_family == AF_INET6) {
+      address->netmask.netmask6 = *((struct sockaddr_in6*) ent->ifa_netmask);
+    } else {
+      address->netmask.netmask4 = *((struct sockaddr_in*) ent->ifa_netmask);
+    }
+
+    address->is_internal = !!(ent->ifa_flags & IFF_LOOPBACK);
+
+    address++;
+  }
+
+  /* Fill in physical addresses for each interface */
+  for (ent = addrs; ent != NULL; ent = ent->ifa_next) {
+    if (uv__ifaddr_exclude(ent, UV__EXCLUDE_IFPHYS))
+      continue;
+
+    address = *addresses;
+
+    for (i = 0; i < (*count); i++) {
+      size_t namelen = strlen(ent->ifa_name);
+      /* Alias interface share the same physical address */
+      if (strncmp(address->name, ent->ifa_name, namelen) == 0 &&
+          (address->name[namelen] == 0 || address->name[namelen] == ':')) {
+        sll = (struct sockaddr_ll*)ent->ifa_addr;
+        memcpy(address->phys_addr, sll->sll_addr, sizeof(address->phys_addr));
+      }
+      address++;
+    }
+  }
+
+  freeifaddrs(addrs);
+
+  return 0;
+#endif
+}
+
+
+void uv_free_interface_addresses(uv_interface_address_t* addresses,
+  int count) {
+  int i;
+
+  for (i = 0; i < count; i++) {
+    uv__free(addresses[i].name);
+  }
+
+  uv__free(addresses);
+}
+
+
+void uv__set_process_title(const char* title) {
+#if defined(PR_SET_NAME)
+  prctl(PR_SET_NAME, title);  /* Only copies first 16 characters. */
+#endif
+}
+
+
+static uint64_t uv__read_proc_meminfo(const char* what) {
+  uint64_t rc;
+  char* p;
+  char buf[4096];  /* Large enough to hold all of /proc/meminfo. */
+
+  if (uv__slurp("/proc/meminfo", buf, sizeof(buf)))
+    return 0;
+
+  p = strstr(buf, what);
+
+  if (p == NULL)
+    return 0;
+
+  p += strlen(what);
+
+  rc = 0;
+  sscanf(p, "%" PRIu64 " kB", &rc);
+
+  return rc * 1024;
+}
+
+
+uint64_t uv_get_free_memory(void) {
+  struct sysinfo info;
+  uint64_t rc;
+
+  rc = uv__read_proc_meminfo("MemAvailable:");
+
+  if (rc != 0)
+    return rc;
+
+  if (0 == sysinfo(&info))
+    return (uint64_t) info.freeram * info.mem_unit;
+
+  return 0;
+}
+
+
+uint64_t uv_get_total_memory(void) {
+  struct sysinfo info;
+  uint64_t rc;
+
+  rc = uv__read_proc_meminfo("MemTotal:");
+
+  if (rc != 0)
+    return rc;
+
+  if (0 == sysinfo(&info))
+    return (uint64_t) info.totalram * info.mem_unit;
+
+  return 0;
+}
+
+
+static uint64_t uv__read_cgroups_uint64(const char* cgroup, const char* param) {
+  char filename[256];
+  char buf[32];  /* Large enough to hold an encoded uint64_t. */
+  uint64_t rc;
+
+  rc = 0;
+  snprintf(filename, sizeof(filename), "/sys/fs/cgroup/%s/%s", cgroup, param);
+  if (0 == uv__slurp(filename, buf, sizeof(buf)))
+    sscanf(buf, "%" PRIu64, &rc);
+
+  return rc;
+}
+
+
+uint64_t uv_get_constrained_memory(void) {
+  /*
+   * This might return 0 if there was a problem getting the memory limit from
+   * cgroups. This is OK because a return value of 0 signifies that the memory
+   * limit is unknown.
+   */
+  return uv__read_cgroups_uint64("memory", "memory.limit_in_bytes");
+}
+
+
+void uv_loadavg(double avg[3]) {
+  struct sysinfo info;
+  char buf[128];  /* Large enough to hold all of /proc/loadavg. */
+
+  if (0 == uv__slurp("/proc/loadavg", buf, sizeof(buf)))
+    if (3 == sscanf(buf, "%lf %lf %lf", &avg[0], &avg[1], &avg[2]))
+      return;
+
+  if (sysinfo(&info) < 0)
+    return;
+
+  avg[0] = (double) info.loads[0] / 65536.0;
+  avg[1] = (double) info.loads[1] / 65536.0;
+  avg[2] = (double) info.loads[2] / 65536.0;
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/linux-inotify.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/linux-inotify.cpp
new file mode 100644
index 0000000..f5366e9
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/linux-inotify.cpp
@@ -0,0 +1,327 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "uv/tree.h"
+#include "internal.h"
+
+#include <stdint.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <assert.h>
+#include <errno.h>
+
+#include <sys/inotify.h>
+#include <sys/types.h>
+#include <unistd.h>
+
+struct watcher_list {
+  RB_ENTRY(watcher_list) entry;
+  QUEUE watchers;
+  int iterating;
+  char* path;
+  int wd;
+};
+
+struct watcher_root {
+  struct watcher_list* rbh_root;
+};
+#define CAST(p) ((struct watcher_root*)(p))
+
+
+static int compare_watchers(const struct watcher_list* a,
+                            const struct watcher_list* b) {
+  if (a->wd < b->wd) return -1;
+  if (a->wd > b->wd) return 1;
+  return 0;
+}
+
+
+RB_GENERATE_STATIC(watcher_root, watcher_list, entry, compare_watchers)
+
+
+static void uv__inotify_read(uv_loop_t* loop,
+                             uv__io_t* w,
+                             unsigned int revents);
+
+static void maybe_free_watcher_list(struct watcher_list* w,
+                                    uv_loop_t* loop);
+
+static int init_inotify(uv_loop_t* loop) {
+  int fd;
+
+  if (loop->inotify_fd != -1)
+    return 0;
+
+  fd = inotify_init1(IN_NONBLOCK | IN_CLOEXEC);
+  if (fd < 0)
+    return UV__ERR(errno);
+
+  loop->inotify_fd = fd;
+  uv__io_init(&loop->inotify_read_watcher, uv__inotify_read, loop->inotify_fd);
+  uv__io_start(loop, &loop->inotify_read_watcher, POLLIN);
+
+  return 0;
+}
+
+
+int uv__inotify_fork(uv_loop_t* loop, void* old_watchers) {
+  /* Open the inotify_fd, and re-arm all the inotify watchers. */
+  int err;
+  struct watcher_list* tmp_watcher_list_iter;
+  struct watcher_list* watcher_list;
+  struct watcher_list tmp_watcher_list;
+  QUEUE queue;
+  QUEUE* q;
+  uv_fs_event_t* handle;
+  char* tmp_path;
+
+  if (old_watchers != NULL) {
+    /* We must restore the old watcher list to be able to close items
+     * out of it.
+     */
+    loop->inotify_watchers = old_watchers;
+
+    QUEUE_INIT(&tmp_watcher_list.watchers);
+    /* Note that the queue we use is shared with the start and stop()
+     * functions, making QUEUE_FOREACH unsafe to use. So we use the
+     * QUEUE_MOVE trick to safely iterate. Also don't free the watcher
+     * list until we're done iterating. c.f. uv__inotify_read.
+     */
+    RB_FOREACH_SAFE(watcher_list, watcher_root,
+                    CAST(&old_watchers), tmp_watcher_list_iter) {
+      watcher_list->iterating = 1;
+      QUEUE_MOVE(&watcher_list->watchers, &queue);
+      while (!QUEUE_EMPTY(&queue)) {
+        q = QUEUE_HEAD(&queue);
+        handle = QUEUE_DATA(q, uv_fs_event_t, watchers);
+        /* It's critical to keep a copy of path here, because it
+         * will be set to NULL by stop() and then deallocated by
+         * maybe_free_watcher_list
+         */
+        tmp_path = uv__strdup(handle->path);
+        assert(tmp_path != NULL);
+        QUEUE_REMOVE(q);
+        QUEUE_INSERT_TAIL(&watcher_list->watchers, q);
+        uv_fs_event_stop(handle);
+
+        QUEUE_INSERT_TAIL(&tmp_watcher_list.watchers, &handle->watchers);
+        handle->path = tmp_path;
+      }
+      watcher_list->iterating = 0;
+      maybe_free_watcher_list(watcher_list, loop);
+    }
+
+    QUEUE_MOVE(&tmp_watcher_list.watchers, &queue);
+    while (!QUEUE_EMPTY(&queue)) {
+        q = QUEUE_HEAD(&queue);
+        QUEUE_REMOVE(q);
+        handle = QUEUE_DATA(q, uv_fs_event_t, watchers);
+        tmp_path = handle->path;
+        handle->path = NULL;
+        err = uv_fs_event_start(handle, handle->cb, tmp_path, 0);
+        uv__free(tmp_path);
+        if (err)
+          return err;
+    }
+  }
+
+  return 0;
+}
+
+
+static struct watcher_list* find_watcher(uv_loop_t* loop, int wd) {
+  struct watcher_list w;
+  w.wd = wd;
+  return RB_FIND(watcher_root, CAST(&loop->inotify_watchers), &w);
+}
+
+static void maybe_free_watcher_list(struct watcher_list* w, uv_loop_t* loop) {
+  /* if the watcher_list->watchers is being iterated over, we can't free it. */
+  if ((!w->iterating) && QUEUE_EMPTY(&w->watchers)) {
+    /* No watchers left for this path. Clean up. */
+    RB_REMOVE(watcher_root, CAST(&loop->inotify_watchers), w);
+    inotify_rm_watch(loop->inotify_fd, w->wd);
+    uv__free(w);
+  }
+}
+
+static void uv__inotify_read(uv_loop_t* loop,
+                             uv__io_t* dummy,
+                             unsigned int events) {
+  const struct inotify_event* e;
+  struct watcher_list* w;
+  uv_fs_event_t* h;
+  QUEUE queue;
+  QUEUE* q;
+  const char* path;
+  ssize_t size;
+  const char *p;
+  /* needs to be large enough for sizeof(inotify_event) + strlen(path) */
+  char buf[4096];
+
+  for (;;) {
+    do
+      size = read(loop->inotify_fd, buf, sizeof(buf));
+    while (size == -1 && errno == EINTR);
+
+    if (size == -1) {
+      assert(errno == EAGAIN || errno == EWOULDBLOCK);
+      break;
+    }
+
+    assert(size > 0); /* pre-2.6.21 thing, size=0 == read buffer too small */
+
+    /* Now we have one or more inotify_event structs. */
+    for (p = buf; p < buf + size; p += sizeof(*e) + e->len) {
+      e = (const struct inotify_event*) p;
+
+      events = 0;
+      if (e->mask & (IN_ATTRIB|IN_MODIFY))
+        events |= UV_CHANGE;
+      if (e->mask & ~(IN_ATTRIB|IN_MODIFY))
+        events |= UV_RENAME;
+
+      w = find_watcher(loop, e->wd);
+      if (w == NULL)
+        continue; /* Stale event, no watchers left. */
+
+      /* inotify does not return the filename when monitoring a single file
+       * for modifications. Repurpose the filename for API compatibility.
+       * I'm not convinced this is a good thing, maybe it should go.
+       */
+      path = e->len ? (const char*) (e + 1) : uv__basename_r(w->path);
+
+      /* We're about to iterate over the queue and call user's callbacks.
+       * What can go wrong?
+       * A callback could call uv_fs_event_stop()
+       * and the queue can change under our feet.
+       * So, we use QUEUE_MOVE() trick to safely iterate over the queue.
+       * And we don't free the watcher_list until we're done iterating.
+       *
+       * First,
+       * tell uv_fs_event_stop() (that could be called from a user's callback)
+       * not to free watcher_list.
+       */
+      w->iterating = 1;
+      QUEUE_MOVE(&w->watchers, &queue);
+      while (!QUEUE_EMPTY(&queue)) {
+        q = QUEUE_HEAD(&queue);
+        h = QUEUE_DATA(q, uv_fs_event_t, watchers);
+
+        QUEUE_REMOVE(q);
+        QUEUE_INSERT_TAIL(&w->watchers, q);
+
+        h->cb(h, path, events, 0);
+      }
+      /* done iterating, time to (maybe) free empty watcher_list */
+      w->iterating = 0;
+      maybe_free_watcher_list(w, loop);
+    }
+  }
+}
+
+
+int uv_fs_event_init(uv_loop_t* loop, uv_fs_event_t* handle) {
+  uv__handle_init(loop, (uv_handle_t*)handle, UV_FS_EVENT);
+  return 0;
+}
+
+
+int uv_fs_event_start(uv_fs_event_t* handle,
+                      uv_fs_event_cb cb,
+                      const char* path,
+                      unsigned int flags) {
+  struct watcher_list* w;
+  size_t len;
+  int events;
+  int err;
+  int wd;
+
+  if (uv__is_active(handle))
+    return UV_EINVAL;
+
+  err = init_inotify(handle->loop);
+  if (err)
+    return err;
+
+  events = IN_ATTRIB
+         | IN_CREATE
+         | IN_MODIFY
+         | IN_DELETE
+         | IN_DELETE_SELF
+         | IN_MOVE_SELF
+         | IN_MOVED_FROM
+         | IN_MOVED_TO;
+
+  wd = inotify_add_watch(handle->loop->inotify_fd, path, events);
+  if (wd == -1)
+    return UV__ERR(errno);
+
+  w = find_watcher(handle->loop, wd);
+  if (w)
+    goto no_insert;
+
+  len = strlen(path) + 1;
+  w = (watcher_list*)uv__malloc(sizeof(*w) + len);
+  if (w == NULL)
+    return UV_ENOMEM;
+
+  w->wd = wd;
+  w->path = (char*)memcpy(w + 1, path, len);
+  QUEUE_INIT(&w->watchers);
+  w->iterating = 0;
+  RB_INSERT(watcher_root, CAST(&handle->loop->inotify_watchers), w);
+
+no_insert:
+  uv__handle_start(handle);
+  QUEUE_INSERT_TAIL(&w->watchers, &handle->watchers);
+  handle->path = w->path;
+  handle->cb = cb;
+  handle->wd = wd;
+
+  return 0;
+}
+
+
+int uv_fs_event_stop(uv_fs_event_t* handle) {
+  struct watcher_list* w;
+
+  if (!uv__is_active(handle))
+    return 0;
+
+  w = find_watcher(handle->loop, handle->wd);
+  assert(w != NULL);
+
+  handle->wd = -1;
+  handle->path = NULL;
+  uv__handle_stop(handle);
+  QUEUE_REMOVE(&handle->watchers);
+
+  maybe_free_watcher_list(w, handle->loop);
+
+  return 0;
+}
+
+
+void uv__fs_event_close(uv_fs_event_t* handle) {
+  uv_fs_event_stop(handle);
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/linux-syscalls.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/linux-syscalls.cpp
new file mode 100644
index 0000000..5071cd5
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/linux-syscalls.cpp
@@ -0,0 +1,264 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "linux-syscalls.h"
+#include <unistd.h>
+#include <signal.h>
+#include <sys/syscall.h>
+#include <sys/types.h>
+#include <errno.h>
+
+#if defined(__arm__)
+# if defined(__thumb__) || defined(__ARM_EABI__)
+#  define UV_SYSCALL_BASE 0
+# else
+#  define UV_SYSCALL_BASE 0x900000
+# endif
+#endif /* __arm__ */
+
+#ifndef __NR_recvmmsg
+# if defined(__x86_64__)
+#  define __NR_recvmmsg 299
+# elif defined(__arm__)
+#  define __NR_recvmmsg (UV_SYSCALL_BASE + 365)
+# endif
+#endif /* __NR_recvmsg */
+
+#ifndef __NR_sendmmsg
+# if defined(__x86_64__)
+#  define __NR_sendmmsg 307
+# elif defined(__arm__)
+#  define __NR_sendmmsg (UV_SYSCALL_BASE + 374)
+# endif
+#endif /* __NR_sendmmsg */
+
+#ifndef __NR_utimensat
+# if defined(__x86_64__)
+#  define __NR_utimensat 280
+# elif defined(__i386__)
+#  define __NR_utimensat 320
+# elif defined(__arm__)
+#  define __NR_utimensat (UV_SYSCALL_BASE + 348)
+# endif
+#endif /* __NR_utimensat */
+
+#ifndef __NR_preadv
+# if defined(__x86_64__)
+#  define __NR_preadv 295
+# elif defined(__i386__)
+#  define __NR_preadv 333
+# elif defined(__arm__)
+#  define __NR_preadv (UV_SYSCALL_BASE + 361)
+# endif
+#endif /* __NR_preadv */
+
+#ifndef __NR_pwritev
+# if defined(__x86_64__)
+#  define __NR_pwritev 296
+# elif defined(__i386__)
+#  define __NR_pwritev 334
+# elif defined(__arm__)
+#  define __NR_pwritev (UV_SYSCALL_BASE + 362)
+# endif
+#endif /* __NR_pwritev */
+
+#ifndef __NR_dup3
+# if defined(__x86_64__)
+#  define __NR_dup3 292
+# elif defined(__i386__)
+#  define __NR_dup3 330
+# elif defined(__arm__)
+#  define __NR_dup3 (UV_SYSCALL_BASE + 358)
+# endif
+#endif /* __NR_pwritev */
+
+#ifndef __NR_copy_file_range
+# if defined(__x86_64__)
+#  define __NR_copy_file_range 326
+# elif defined(__i386__)
+#  define __NR_copy_file_range 377
+# elif defined(__s390__)
+#  define __NR_copy_file_range 375
+# elif defined(__arm__)
+#  define __NR_copy_file_range (UV_SYSCALL_BASE + 391)
+# elif defined(__aarch64__)
+#  define __NR_copy_file_range 285
+# elif defined(__powerpc__)
+#  define __NR_copy_file_range 379
+# elif defined(__arc__)
+#  define __NR_copy_file_range 285
+# endif
+#endif /* __NR_copy_file_range */
+
+#ifndef __NR_statx
+# if defined(__x86_64__)
+#  define __NR_statx 332
+# elif defined(__i386__)
+#  define __NR_statx 383
+# elif defined(__aarch64__)
+#  define __NR_statx 397
+# elif defined(__arm__)
+#  define __NR_statx (UV_SYSCALL_BASE + 397)
+# elif defined(__ppc__)
+#  define __NR_statx 383
+# elif defined(__s390__)
+#  define __NR_statx 379
+# endif
+#endif /* __NR_statx */
+
+#ifndef __NR_getrandom
+# if defined(__x86_64__)
+#  define __NR_getrandom 318
+# elif defined(__i386__)
+#  define __NR_getrandom 355
+# elif defined(__aarch64__)
+#  define __NR_getrandom 384
+# elif defined(__arm__)
+#  define __NR_getrandom (UV_SYSCALL_BASE + 384)
+# elif defined(__ppc__)
+#  define __NR_getrandom 359
+# elif defined(__s390__)
+#  define __NR_getrandom 349
+# endif
+#endif /* __NR_getrandom */
+
+struct uv__mmsghdr;
+
+int uv__sendmmsg(int fd, struct uv__mmsghdr* mmsg, unsigned int vlen) {
+#if defined(__i386__)
+  unsigned long args[4];
+  int rc;
+
+  args[0] = (unsigned long) fd;
+  args[1] = (unsigned long) mmsg;
+  args[2] = (unsigned long) vlen;
+  args[3] = /* flags */ 0;
+
+  /* socketcall() raises EINVAL when SYS_SENDMMSG is not supported. */
+  rc = syscall(/* __NR_socketcall */ 102, 20 /* SYS_SENDMMSG */, args);
+  if (rc == -1)
+    if (errno == EINVAL)
+      errno = ENOSYS;
+
+  return rc;
+#elif defined(__NR_sendmmsg)
+  return syscall(__NR_sendmmsg, fd, mmsg, vlen, /* flags */ 0);
+#else
+  return errno = ENOSYS, -1;
+#endif
+}
+
+
+int uv__recvmmsg(int fd, struct uv__mmsghdr* mmsg, unsigned int vlen) {
+#if defined(__i386__)
+  unsigned long args[5];
+  int rc;
+
+  args[0] = (unsigned long) fd;
+  args[1] = (unsigned long) mmsg;
+  args[2] = (unsigned long) vlen;
+  args[3] = /* flags */ 0;
+  args[4] = /* timeout */ 0;
+
+  /* socketcall() raises EINVAL when SYS_RECVMMSG is not supported. */
+  rc = syscall(/* __NR_socketcall */ 102, 19 /* SYS_RECVMMSG */, args);
+  if (rc == -1)
+    if (errno == EINVAL)
+      errno = ENOSYS;
+
+  return rc;
+#elif defined(__NR_recvmmsg)
+  return syscall(__NR_recvmmsg, fd, mmsg, vlen, /* flags */ 0, /* timeout */ 0);
+#else
+  return errno = ENOSYS, -1;
+#endif
+}
+
+
+ssize_t uv__preadv(int fd, const struct iovec *iov, int iovcnt, int64_t offset) {
+#if !defined(__NR_preadv) || defined(__ANDROID_API__) && __ANDROID_API__ < 24
+  return errno = ENOSYS, -1;
+#else
+  return syscall(__NR_preadv, fd, iov, iovcnt, (long)offset, (long)(offset >> 32));
+#endif
+}
+
+
+ssize_t uv__pwritev(int fd, const struct iovec *iov, int iovcnt, int64_t offset) {
+#if !defined(__NR_pwritev) || defined(__ANDROID_API__) && __ANDROID_API__ < 24
+  return errno = ENOSYS, -1;
+#else
+  return syscall(__NR_pwritev, fd, iov, iovcnt, (long)offset, (long)(offset >> 32));
+#endif
+}
+
+
+int uv__dup3(int oldfd, int newfd, int flags) {
+#if !defined(__NR_dup3) || defined(__ANDROID_API__) && __ANDROID_API__ < 21
+  return errno = ENOSYS, -1;
+#else
+  return syscall(__NR_dup3, oldfd, newfd, flags);
+#endif
+}
+
+
+ssize_t
+uv__fs_copy_file_range(int fd_in,
+                       off_t* off_in,
+                       int fd_out,
+                       off_t* off_out,
+                       size_t len,
+                       unsigned int flags)
+{
+#ifdef __NR_copy_file_range
+  return syscall(__NR_copy_file_range,
+                 fd_in,
+                 off_in,
+                 fd_out,
+                 off_out,
+                 len,
+                 flags);
+#else
+  return errno = ENOSYS, -1;
+#endif
+}
+
+
+int uv__statx(int dirfd,
+              const char* path,
+              int flags,
+              unsigned int mask,
+              struct uv__statx* statxbuf) {
+#if !defined(__NR_statx) || defined(__ANDROID_API__) && __ANDROID_API__ < 30
+  return errno = ENOSYS, -1;
+#else
+  return syscall(__NR_statx, dirfd, path, flags, mask, statxbuf);
+#endif
+}
+
+
+ssize_t uv__getrandom(void* buf, size_t buflen, unsigned flags) {
+#if !defined(__NR_getrandom) || defined(__ANDROID_API__) && __ANDROID_API__ < 28
+  return errno = ENOSYS, -1;
+#else
+  return syscall(__NR_getrandom, buf, buflen, flags);
+#endif
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/linux-syscalls.h b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/linux-syscalls.h
new file mode 100644
index 0000000..b4d9082
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/linux-syscalls.h
@@ -0,0 +1,78 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#ifndef UV_LINUX_SYSCALL_H_
+#define UV_LINUX_SYSCALL_H_
+
+#include <stdint.h>
+#include <signal.h>
+#include <sys/types.h>
+#include <sys/time.h>
+#include <sys/socket.h>
+
+struct uv__statx_timestamp {
+  int64_t tv_sec;
+  uint32_t tv_nsec;
+  int32_t unused0;
+};
+
+struct uv__statx {
+  uint32_t stx_mask;
+  uint32_t stx_blksize;
+  uint64_t stx_attributes;
+  uint32_t stx_nlink;
+  uint32_t stx_uid;
+  uint32_t stx_gid;
+  uint16_t stx_mode;
+  uint16_t unused0;
+  uint64_t stx_ino;
+  uint64_t stx_size;
+  uint64_t stx_blocks;
+  uint64_t stx_attributes_mask;
+  struct uv__statx_timestamp stx_atime;
+  struct uv__statx_timestamp stx_btime;
+  struct uv__statx_timestamp stx_ctime;
+  struct uv__statx_timestamp stx_mtime;
+  uint32_t stx_rdev_major;
+  uint32_t stx_rdev_minor;
+  uint32_t stx_dev_major;
+  uint32_t stx_dev_minor;
+  uint64_t unused1[14];
+};
+
+ssize_t uv__preadv(int fd, const struct iovec *iov, int iovcnt, int64_t offset);
+ssize_t uv__pwritev(int fd, const struct iovec *iov, int iovcnt, int64_t offset);
+int uv__dup3(int oldfd, int newfd, int flags);
+ssize_t
+uv__fs_copy_file_range(int fd_in,
+                       off_t* off_in,
+                       int fd_out,
+                       off_t* off_out,
+                       size_t len,
+                       unsigned int flags);
+int uv__statx(int dirfd,
+              const char* path,
+              int flags,
+              unsigned int mask,
+              struct uv__statx* statxbuf);
+ssize_t uv__getrandom(void* buf, size_t buflen, unsigned flags);
+
+#endif /* UV_LINUX_SYSCALL_H_ */
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/loop-watcher.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/loop-watcher.cpp
similarity index 100%
rename from third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/loop-watcher.cpp
rename to third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/loop-watcher.cpp
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/loop.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/loop.cpp
new file mode 100644
index 0000000..2e819cd
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/loop.cpp
@@ -0,0 +1,228 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "uv/tree.h"
+#include "internal.h"
+#include "heap-inl.h"
+#include <stdlib.h>
+#include <string.h>
+#include <unistd.h>
+
+int uv_loop_init(uv_loop_t* loop) {
+  uv__loop_internal_fields_t* lfields;
+  void* saved_data;
+  int err;
+
+
+  saved_data = loop->data;
+  memset(loop, 0, sizeof(*loop));
+  loop->data = saved_data;
+
+  lfields = (uv__loop_internal_fields_t*) uv__calloc(1, sizeof(*lfields));
+  if (lfields == NULL)
+    return UV_ENOMEM;
+  loop->internal_fields = lfields;
+
+  err = uv_mutex_init(&lfields->loop_metrics.lock);
+  if (err)
+    goto fail_metrics_mutex_init;
+
+  heap_init((struct heap*) &loop->timer_heap);
+  QUEUE_INIT(&loop->wq);
+  QUEUE_INIT(&loop->idle_handles);
+  QUEUE_INIT(&loop->async_handles);
+  QUEUE_INIT(&loop->check_handles);
+  QUEUE_INIT(&loop->prepare_handles);
+  QUEUE_INIT(&loop->handle_queue);
+
+  loop->active_handles = 0;
+  loop->active_reqs.count = 0;
+  loop->nfds = 0;
+  loop->watchers = NULL;
+  loop->nwatchers = 0;
+  QUEUE_INIT(&loop->pending_queue);
+  QUEUE_INIT(&loop->watcher_queue);
+
+  loop->closing_handles = NULL;
+  uv__update_time(loop);
+  loop->async_io_watcher.fd = -1;
+  loop->async_wfd = -1;
+  loop->signal_pipefd[0] = -1;
+  loop->signal_pipefd[1] = -1;
+  loop->backend_fd = -1;
+  loop->emfile_fd = -1;
+
+  loop->timer_counter = 0;
+  loop->stop_flag = 0;
+
+  err = uv__platform_loop_init(loop);
+  if (err)
+    goto fail_platform_init;
+
+  uv__signal_global_once_init();
+  err = uv_signal_init(loop, &loop->child_watcher);
+  if (err)
+    goto fail_signal_init;
+
+  uv__handle_unref(&loop->child_watcher);
+  loop->child_watcher.flags |= UV_HANDLE_INTERNAL;
+  QUEUE_INIT(&loop->process_handles);
+
+  err = uv_rwlock_init(&loop->cloexec_lock);
+  if (err)
+    goto fail_rwlock_init;
+
+  err = uv_mutex_init(&loop->wq_mutex);
+  if (err)
+    goto fail_mutex_init;
+
+  err = uv_async_init(loop, &loop->wq_async, uv__work_done);
+  if (err)
+    goto fail_async_init;
+
+  uv__handle_unref(&loop->wq_async);
+  loop->wq_async.flags |= UV_HANDLE_INTERNAL;
+
+  return 0;
+
+fail_async_init:
+  uv_mutex_destroy(&loop->wq_mutex);
+
+fail_mutex_init:
+  uv_rwlock_destroy(&loop->cloexec_lock);
+
+fail_rwlock_init:
+  uv__signal_loop_cleanup(loop);
+
+fail_signal_init:
+  uv__platform_loop_delete(loop);
+
+fail_platform_init:
+  uv_mutex_destroy(&lfields->loop_metrics.lock);
+
+fail_metrics_mutex_init:
+  uv__free(lfields);
+  loop->internal_fields = NULL;
+
+  uv__free(loop->watchers);
+  loop->nwatchers = 0;
+  return err;
+}
+
+
+int uv_loop_fork(uv_loop_t* loop) {
+  int err;
+  unsigned int i;
+  uv__io_t* w;
+
+  err = uv__io_fork(loop);
+  if (err)
+    return err;
+
+  err = uv__async_fork(loop);
+  if (err)
+    return err;
+
+  err = uv__signal_loop_fork(loop);
+  if (err)
+    return err;
+
+  /* Rearm all the watchers that aren't re-queued by the above. */
+  for (i = 0; i < loop->nwatchers; i++) {
+    w = (uv__io_t*)loop->watchers[i];
+    if (w == NULL)
+      continue;
+
+    if (w->pevents != 0 && QUEUE_EMPTY(&w->watcher_queue)) {
+      w->events = 0; /* Force re-registration in uv__io_poll. */
+      QUEUE_INSERT_TAIL(&loop->watcher_queue, &w->watcher_queue);
+    }
+  }
+
+  return 0;
+}
+
+
+void uv__loop_close(uv_loop_t* loop) {
+  uv__loop_internal_fields_t* lfields;
+
+  uv__signal_loop_cleanup(loop);
+  uv__platform_loop_delete(loop);
+  uv__async_stop(loop);
+
+  if (loop->emfile_fd != -1) {
+    uv__close(loop->emfile_fd);
+    loop->emfile_fd = -1;
+  }
+
+  if (loop->backend_fd != -1) {
+    uv__close(loop->backend_fd);
+    loop->backend_fd = -1;
+  }
+
+  uv_mutex_lock(&loop->wq_mutex);
+  assert(QUEUE_EMPTY(&loop->wq) && "thread pool work queue not empty!");
+  assert(!uv__has_active_reqs(loop));
+  uv_mutex_unlock(&loop->wq_mutex);
+  uv_mutex_destroy(&loop->wq_mutex);
+
+  /*
+   * Note that all thread pool stuff is finished at this point and
+   * it is safe to just destroy rw lock
+   */
+  uv_rwlock_destroy(&loop->cloexec_lock);
+
+#if 0
+  assert(QUEUE_EMPTY(&loop->pending_queue));
+  assert(QUEUE_EMPTY(&loop->watcher_queue));
+  assert(loop->nfds == 0);
+#endif
+
+  uv__free(loop->watchers);
+  loop->watchers = NULL;
+  loop->nwatchers = 0;
+
+  lfields = uv__get_internal_fields(loop);
+  uv_mutex_destroy(&lfields->loop_metrics.lock);
+  uv__free(lfields);
+  loop->internal_fields = NULL;
+}
+
+
+int uv__loop_configure(uv_loop_t* loop, uv_loop_option option, va_list ap) {
+  uv__loop_internal_fields_t* lfields;
+
+  lfields = uv__get_internal_fields(loop);
+  if (option == UV_METRICS_IDLE_TIME) {
+    lfields->flags |= UV_METRICS_IDLE_TIME;
+    return 0;
+  }
+
+  if (option != UV_LOOP_BLOCK_SIGNAL)
+    return UV_ENOSYS;
+
+  if (va_arg(ap, int) != SIGPROF)
+    return UV_EINVAL;
+
+  loop->flags |= UV_LOOP_BLOCK_SIGPROF;
+  return 0;
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/netbsd.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/netbsd.cpp
new file mode 100644
index 0000000..b6886a1
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/netbsd.cpp
@@ -0,0 +1,259 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <assert.h>
+#include <string.h>
+#include <errno.h>
+
+#include <kvm.h>
+#include <paths.h>
+#include <unistd.h>
+#include <time.h>
+#include <stdlib.h>
+#include <fcntl.h>
+
+#include <sys/resource.h>
+#include <sys/types.h>
+#include <sys/sysctl.h>
+#include <uvm/uvm_extern.h>
+
+#include <unistd.h>
+#include <time.h>
+
+
+int uv__platform_loop_init(uv_loop_t* loop) {
+  return uv__kqueue_init(loop);
+}
+
+
+void uv__platform_loop_delete(uv_loop_t* loop) {
+}
+
+
+void uv_loadavg(double avg[3]) {
+  struct loadavg info;
+  size_t size = sizeof(info);
+  int which[] = {CTL_VM, VM_LOADAVG};
+
+  if (sysctl(which, ARRAY_SIZE(which), &info, &size, NULL, 0) == -1) return;
+
+  avg[0] = (double) info.ldavg[0] / info.fscale;
+  avg[1] = (double) info.ldavg[1] / info.fscale;
+  avg[2] = (double) info.ldavg[2] / info.fscale;
+}
+
+
+int uv_exepath(char* buffer, size_t* size) {
+  /* Intermediate buffer, retrieving partial path name does not work
+   * As of NetBSD-8(beta), vnode->path translator does not handle files
+   * with longer names than 31 characters.
+   */
+  char int_buf[PATH_MAX];
+  size_t int_size;
+  int mib[4];
+
+  if (buffer == NULL || size == NULL || *size == 0)
+    return UV_EINVAL;
+
+  mib[0] = CTL_KERN;
+  mib[1] = KERN_PROC_ARGS;
+  mib[2] = -1;
+  mib[3] = KERN_PROC_PATHNAME;
+  int_size = ARRAY_SIZE(int_buf);
+
+  if (sysctl(mib, 4, int_buf, &int_size, NULL, 0))
+    return UV__ERR(errno);
+
+  /* Copy string from the intermediate buffer to outer one with appropriate
+   * length.
+   */
+  /* TODO(bnoordhuis) Check uv__strscpy() return value. */
+  uv__strscpy(buffer, int_buf, *size);
+
+  /* Set new size. */
+  *size = strlen(buffer);
+
+  return 0;
+}
+
+
+uint64_t uv_get_free_memory(void) {
+  struct uvmexp info;
+  size_t size = sizeof(info);
+  int which[] = {CTL_VM, VM_UVMEXP};
+
+  if (sysctl(which, ARRAY_SIZE(which), &info, &size, NULL, 0))
+    return UV__ERR(errno);
+
+  return (uint64_t) info.free * sysconf(_SC_PAGESIZE);
+}
+
+
+uint64_t uv_get_total_memory(void) {
+#if defined(HW_PHYSMEM64)
+  uint64_t info;
+  int which[] = {CTL_HW, HW_PHYSMEM64};
+#else
+  unsigned int info;
+  int which[] = {CTL_HW, HW_PHYSMEM};
+#endif
+  size_t size = sizeof(info);
+
+  if (sysctl(which, ARRAY_SIZE(which), &info, &size, NULL, 0))
+    return UV__ERR(errno);
+
+  return (uint64_t) info;
+}
+
+
+uint64_t uv_get_constrained_memory(void) {
+  return 0;  /* Memory constraints are unknown. */
+}
+
+
+int uv_resident_set_memory(size_t* rss) {
+  kvm_t *kd = NULL;
+  struct kinfo_proc2 *kinfo = NULL;
+  pid_t pid;
+  int nprocs;
+  int max_size = sizeof(struct kinfo_proc2);
+  int page_size;
+
+  page_size = getpagesize();
+  pid = getpid();
+
+  kd = kvm_open(NULL, NULL, NULL, KVM_NO_FILES, "kvm_open");
+
+  if (kd == NULL) goto error;
+
+  kinfo = kvm_getproc2(kd, KERN_PROC_PID, pid, max_size, &nprocs);
+  if (kinfo == NULL) goto error;
+
+  *rss = kinfo->p_vm_rssize * page_size;
+
+  kvm_close(kd);
+
+  return 0;
+
+error:
+  if (kd) kvm_close(kd);
+  return UV_EPERM;
+}
+
+
+int uv_uptime(double* uptime) {
+  time_t now;
+  struct timeval info;
+  size_t size = sizeof(info);
+  static int which[] = {CTL_KERN, KERN_BOOTTIME};
+
+  if (sysctl(which, ARRAY_SIZE(which), &info, &size, NULL, 0))
+    return UV__ERR(errno);
+
+  now = time(NULL);
+
+  *uptime = (double)(now - info.tv_sec);
+  return 0;
+}
+
+
+int uv_cpu_info(uv_cpu_info_t** cpu_infos, int* count) {
+  unsigned int ticks = (unsigned int)sysconf(_SC_CLK_TCK);
+  unsigned int multiplier = ((uint64_t)1000L / ticks);
+  unsigned int cur = 0;
+  uv_cpu_info_t* cpu_info;
+  u_int64_t* cp_times;
+  char model[512];
+  u_int64_t cpuspeed;
+  int numcpus;
+  size_t size;
+  int i;
+
+  size = sizeof(model);
+  if (sysctlbyname("machdep.cpu_brand", &model, &size, NULL, 0) &&
+      sysctlbyname("hw.model", &model, &size, NULL, 0)) {
+    return UV__ERR(errno);
+  }
+
+  size = sizeof(numcpus);
+  if (sysctlbyname("hw.ncpu", &numcpus, &size, NULL, 0))
+    return UV__ERR(errno);
+  *count = numcpus;
+
+  /* Only i386 and amd64 have machdep.tsc_freq */
+  size = sizeof(cpuspeed);
+  if (sysctlbyname("machdep.tsc_freq", &cpuspeed, &size, NULL, 0))
+    cpuspeed = 0;
+
+  size = numcpus * CPUSTATES * sizeof(*cp_times);
+  cp_times = (u_int64_t*)uv__malloc(size);
+  if (cp_times == NULL)
+    return UV_ENOMEM;
+
+  if (sysctlbyname("kern.cp_time", cp_times, &size, NULL, 0))
+    return UV__ERR(errno);
+
+  *cpu_infos = (uv_cpu_info_t*)uv__malloc(numcpus * sizeof(**cpu_infos));
+  if (!(*cpu_infos)) {
+    uv__free(cp_times);
+    uv__free(*cpu_infos);
+    return UV_ENOMEM;
+  }
+
+  for (i = 0; i < numcpus; i++) {
+    cpu_info = &(*cpu_infos)[i];
+    cpu_info->cpu_times.user = (uint64_t)(cp_times[CP_USER+cur]) * multiplier;
+    cpu_info->cpu_times.nice = (uint64_t)(cp_times[CP_NICE+cur]) * multiplier;
+    cpu_info->cpu_times.sys = (uint64_t)(cp_times[CP_SYS+cur]) * multiplier;
+    cpu_info->cpu_times.idle = (uint64_t)(cp_times[CP_IDLE+cur]) * multiplier;
+    cpu_info->cpu_times.irq = (uint64_t)(cp_times[CP_INTR+cur]) * multiplier;
+    cpu_info->model = uv__strdup(model);
+    cpu_info->speed = (int)(cpuspeed/(uint64_t) 1e6);
+    cur += CPUSTATES;
+  }
+  uv__free(cp_times);
+  return 0;
+}
+
+int uv__random_sysctl(void* buf, size_t len) {
+  static int name[] = {CTL_KERN, KERN_ARND};
+  size_t count, req;
+  unsigned char* p;
+
+  p = buf;
+  while (len) {
+    req = len < 32 ? len : 32;
+    count = req;
+
+    if (sysctl(name, ARRAY_SIZE(name), p, &count, NULL, 0) == -1)
+      return UV__ERR(errno);
+
+    if (count != req)
+      return UV_EIO;  /* Can't happen. */
+
+    p += count;
+    len -= count;
+  }
+
+  return 0;
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/no-fsevents.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/no-fsevents.cpp
similarity index 100%
rename from third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/no-fsevents.cpp
rename to third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/no-fsevents.cpp
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/no-proctitle.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/no-proctitle.cpp
new file mode 100644
index 0000000..32aa0af
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/no-proctitle.cpp
@@ -0,0 +1,45 @@
+/* Copyright libuv project contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <errno.h>
+#include <stddef.h>
+
+char** uv_setup_args(int argc, char** argv) {
+  return argv;
+}
+
+void uv__process_title_cleanup(void) {
+}
+
+int uv_set_process_title(const char* title) {
+  return 0;
+}
+
+int uv_get_process_title(char* buffer, size_t size) {
+  if (buffer == NULL || size == 0)
+    return UV_EINVAL;
+
+  buffer[0] = '\0';
+  return 0;
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/openbsd.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/openbsd.cpp
new file mode 100644
index 0000000..62740f7
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/openbsd.cpp
@@ -0,0 +1,240 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <sys/types.h>
+#include <sys/param.h>
+#include <sys/resource.h>
+#include <sys/sched.h>
+#include <sys/time.h>
+#include <sys/sysctl.h>
+
+#include <errno.h>
+#include <fcntl.h>
+#include <paths.h>
+#include <stdlib.h>
+#include <string.h>
+#include <unistd.h>
+
+
+int uv__platform_loop_init(uv_loop_t* loop) {
+  return uv__kqueue_init(loop);
+}
+
+
+void uv__platform_loop_delete(uv_loop_t* loop) {
+}
+
+
+void uv_loadavg(double avg[3]) {
+  struct loadavg info;
+  size_t size = sizeof(info);
+  int which[] = {CTL_VM, VM_LOADAVG};
+
+  if (sysctl(which, ARRAY_SIZE(which), &info, &size, NULL, 0) < 0) return;
+
+  avg[0] = (double) info.ldavg[0] / info.fscale;
+  avg[1] = (double) info.ldavg[1] / info.fscale;
+  avg[2] = (double) info.ldavg[2] / info.fscale;
+}
+
+
+int uv_exepath(char* buffer, size_t* size) {
+  int mib[4];
+  char **argsbuf = NULL;
+  size_t argsbuf_size = 100U;
+  size_t exepath_size;
+  pid_t mypid;
+  int err;
+
+  if (buffer == NULL || size == NULL || *size == 0)
+    return UV_EINVAL;
+
+  mypid = getpid();
+  for (;;) {
+    err = UV_ENOMEM;
+    argsbuf = (char**)uv__reallocf(argsbuf, argsbuf_size);
+    if (argsbuf == NULL)
+      goto out;
+    mib[0] = CTL_KERN;
+    mib[1] = KERN_PROC_ARGS;
+    mib[2] = mypid;
+    mib[3] = KERN_PROC_ARGV;
+    if (sysctl(mib, ARRAY_SIZE(mib), argsbuf, &argsbuf_size, NULL, 0) == 0) {
+      break;
+    }
+    if (errno != ENOMEM) {
+      err = UV__ERR(errno);
+      goto out;
+    }
+    argsbuf_size *= 2U;
+  }
+
+  if (argsbuf[0] == NULL) {
+    err = UV_EINVAL;  /* FIXME(bnoordhuis) More appropriate error. */
+    goto out;
+  }
+
+  *size -= 1;
+  exepath_size = strlen(argsbuf[0]);
+  if (*size > exepath_size)
+    *size = exepath_size;
+
+  memcpy(buffer, argsbuf[0], *size);
+  buffer[*size] = '\0';
+  err = 0;
+
+out:
+  uv__free(argsbuf);
+
+  return err;
+}
+
+
+uint64_t uv_get_free_memory(void) {
+  struct uvmexp info;
+  size_t size = sizeof(info);
+  int which[] = {CTL_VM, VM_UVMEXP};
+
+  if (sysctl(which, ARRAY_SIZE(which), &info, &size, NULL, 0))
+    return UV__ERR(errno);
+
+  return (uint64_t) info.free * sysconf(_SC_PAGESIZE);
+}
+
+
+uint64_t uv_get_total_memory(void) {
+  uint64_t info;
+  int which[] = {CTL_HW, HW_PHYSMEM64};
+  size_t size = sizeof(info);
+
+  if (sysctl(which, ARRAY_SIZE(which), &info, &size, NULL, 0))
+    return UV__ERR(errno);
+
+  return (uint64_t) info;
+}
+
+
+uint64_t uv_get_constrained_memory(void) {
+  return 0;  /* Memory constraints are unknown. */
+}
+
+
+int uv_resident_set_memory(size_t* rss) {
+  struct kinfo_proc kinfo;
+  size_t page_size = getpagesize();
+  size_t size = sizeof(struct kinfo_proc);
+  int mib[6];
+
+  mib[0] = CTL_KERN;
+  mib[1] = KERN_PROC;
+  mib[2] = KERN_PROC_PID;
+  mib[3] = getpid();
+  mib[4] = sizeof(struct kinfo_proc);
+  mib[5] = 1;
+
+  if (sysctl(mib, ARRAY_SIZE(mib), &kinfo, &size, NULL, 0) < 0)
+    return UV__ERR(errno);
+
+  *rss = kinfo.p_vm_rssize * page_size;
+  return 0;
+}
+
+
+int uv_uptime(double* uptime) {
+  time_t now;
+  struct timeval info;
+  size_t size = sizeof(info);
+  static int which[] = {CTL_KERN, KERN_BOOTTIME};
+
+  if (sysctl(which, ARRAY_SIZE(which), &info, &size, NULL, 0))
+    return UV__ERR(errno);
+
+  now = time(NULL);
+
+  *uptime = (double)(now - info.tv_sec);
+  return 0;
+}
+
+
+int uv_cpu_info(uv_cpu_info_t** cpu_infos, int* count) {
+  unsigned int ticks = (unsigned int)sysconf(_SC_CLK_TCK),
+               multiplier = ((uint64_t)1000L / ticks), cpuspeed;
+  uint64_t info[CPUSTATES];
+  char model[512];
+  int numcpus = 1;
+  int which[] = {CTL_HW,HW_MODEL};
+  int percpu[] = {CTL_KERN,KERN_CPTIME2,0};
+  size_t size;
+  int i, j;
+  uv_cpu_info_t* cpu_info;
+
+  size = sizeof(model);
+  if (sysctl(which, ARRAY_SIZE(which), &model, &size, NULL, 0))
+    return UV__ERR(errno);
+
+  which[1] = HW_NCPUONLINE;
+  size = sizeof(numcpus);
+  if (sysctl(which, ARRAY_SIZE(which), &numcpus, &size, NULL, 0))
+    return UV__ERR(errno);
+
+  *cpu_infos = (uv_cpu_info_t*)uv__malloc(numcpus * sizeof(**cpu_infos));
+  if (!(*cpu_infos))
+    return UV_ENOMEM;
+
+  i = 0;
+  *count = numcpus;
+
+  which[1] = HW_CPUSPEED;
+  size = sizeof(cpuspeed);
+  if (sysctl(which, ARRAY_SIZE(which), &cpuspeed, &size, NULL, 0))
+    goto error;
+
+  size = sizeof(info);
+  for (i = 0; i < numcpus; i++) {
+    percpu[2] = i;
+    if (sysctl(percpu, ARRAY_SIZE(percpu), &info, &size, NULL, 0))
+      goto error;
+
+    cpu_info = &(*cpu_infos)[i];
+
+    cpu_info->cpu_times.user = (uint64_t)(info[CP_USER]) * multiplier;
+    cpu_info->cpu_times.nice = (uint64_t)(info[CP_NICE]) * multiplier;
+    cpu_info->cpu_times.sys = (uint64_t)(info[CP_SYS]) * multiplier;
+    cpu_info->cpu_times.idle = (uint64_t)(info[CP_IDLE]) * multiplier;
+    cpu_info->cpu_times.irq = (uint64_t)(info[CP_INTR]) * multiplier;
+
+    cpu_info->model = uv__strdup(model);
+    cpu_info->speed = cpuspeed;
+  }
+
+  return 0;
+
+error:
+  *count = 0;
+  for (j = 0; j < i; j++)
+    uv__free((*cpu_infos)[j].model);
+
+  uv__free(*cpu_infos);
+  *cpu_infos = NULL;
+  return UV__ERR(errno);
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/pipe.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/pipe.cpp
new file mode 100644
index 0000000..c8ba31d
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/pipe.cpp
@@ -0,0 +1,437 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <assert.h>
+#include <errno.h>
+#include <string.h>
+#include <sys/un.h>
+#include <unistd.h>
+#include <stdlib.h>
+
+
+int uv_pipe_init(uv_loop_t* loop, uv_pipe_t* handle, int ipc) {
+  uv__stream_init(loop, (uv_stream_t*)handle, UV_NAMED_PIPE);
+  handle->shutdown_req = NULL;
+  handle->connect_req = NULL;
+  handle->pipe_fname = NULL;
+  handle->ipc = ipc;
+  return 0;
+}
+
+
+int uv_pipe_bind(uv_pipe_t* handle, const char* name) {
+  struct sockaddr_un saddr;
+  const char* pipe_fname;
+  int sockfd;
+  int err;
+
+  pipe_fname = NULL;
+
+  /* Already bound? */
+  if (uv__stream_fd(handle) >= 0)
+    return UV_EINVAL;
+  if (uv__is_closing(handle)) {
+    return UV_EINVAL;
+  }
+  /* Make a copy of the file name, it outlives this function's scope. */
+  pipe_fname = uv__strdup(name);
+  if (pipe_fname == NULL)
+    return UV_ENOMEM;
+
+  /* We've got a copy, don't touch the original any more. */
+  name = NULL;
+
+  err = uv__socket(AF_UNIX, SOCK_STREAM, 0);
+  if (err < 0)
+    goto err_socket;
+  sockfd = err;
+
+  memset(&saddr, 0, sizeof saddr);
+  uv__strscpy(saddr.sun_path, pipe_fname, sizeof(saddr.sun_path));
+  saddr.sun_family = AF_UNIX;
+
+  if (bind(sockfd, (struct sockaddr*)&saddr, sizeof saddr)) {
+    err = UV__ERR(errno);
+    /* Convert ENOENT to EACCES for compatibility with Windows. */
+    if (err == UV_ENOENT)
+      err = UV_EACCES;
+
+    uv__close(sockfd);
+    goto err_socket;
+  }
+
+  /* Success. */
+  handle->flags |= UV_HANDLE_BOUND;
+  handle->pipe_fname = pipe_fname; /* Is a strdup'ed copy. */
+  handle->io_watcher.fd = sockfd;
+  return 0;
+
+err_socket:
+  uv__free((void*)pipe_fname);
+  return err;
+}
+
+
+int uv__pipe_listen(uv_pipe_t* handle, int backlog, uv_connection_cb cb) {
+  if (uv__stream_fd(handle) == -1)
+    return UV_EINVAL;
+
+  if (handle->ipc)
+    return UV_EINVAL;
+
+#if defined(__MVS__) || defined(__PASE__)
+  /* On zOS, backlog=0 has undefined behaviour */
+  /* On IBMi PASE, backlog=0 leads to "Connection refused" error */
+  if (backlog == 0)
+    backlog = 1;
+  else if (backlog < 0)
+    backlog = SOMAXCONN;
+#endif
+
+  if (listen(uv__stream_fd(handle), backlog))
+    return UV__ERR(errno);
+
+  handle->connection_cb = cb;
+  handle->io_watcher.cb = uv__server_io;
+  uv__io_start(handle->loop, &handle->io_watcher, POLLIN);
+  return 0;
+}
+
+
+void uv__pipe_close(uv_pipe_t* handle) {
+  if (handle->pipe_fname) {
+    /*
+     * Unlink the file system entity before closing the file descriptor.
+     * Doing it the other way around introduces a race where our process
+     * unlinks a socket with the same name that's just been created by
+     * another thread or process.
+     */
+    unlink(handle->pipe_fname);
+    uv__free((void*)handle->pipe_fname);
+    handle->pipe_fname = NULL;
+  }
+
+  uv__stream_close((uv_stream_t*)handle);
+}
+
+
+int uv_pipe_open(uv_pipe_t* handle, uv_file fd) {
+  int flags;
+  int mode;
+  int err;
+  flags = 0;
+
+  if (uv__fd_exists(handle->loop, fd))
+    return UV_EEXIST;
+
+  do
+    mode = fcntl(fd, F_GETFL);
+  while (mode == -1 && errno == EINTR);
+
+  if (mode == -1)
+    return UV__ERR(errno); /* according to docs, must be EBADF */
+
+  err = uv__nonblock(fd, 1);
+  if (err)
+    return err;
+
+#if defined(__APPLE__)
+  err = uv__stream_try_select((uv_stream_t*) handle, &fd);
+  if (err)
+    return err;
+#endif /* defined(__APPLE__) */
+
+  mode &= O_ACCMODE;
+  if (mode != O_WRONLY)
+    flags |= UV_HANDLE_READABLE;
+  if (mode != O_RDONLY)
+    flags |= UV_HANDLE_WRITABLE;
+
+  return uv__stream_open((uv_stream_t*)handle, fd, flags);
+}
+
+
+void uv_pipe_connect(uv_connect_t* req,
+                    uv_pipe_t* handle,
+                    const char* name,
+                    uv_connect_cb cb) {
+  struct sockaddr_un saddr;
+  int new_sock;
+  int err;
+  int r;
+
+  new_sock = (uv__stream_fd(handle) == -1);
+
+  if (new_sock) {
+    err = uv__socket(AF_UNIX, SOCK_STREAM, 0);
+    if (err < 0)
+      goto out;
+    handle->io_watcher.fd = err;
+  }
+
+  memset(&saddr, 0, sizeof saddr);
+  uv__strscpy(saddr.sun_path, name, sizeof(saddr.sun_path));
+  saddr.sun_family = AF_UNIX;
+
+  do {
+    r = connect(uv__stream_fd(handle),
+                (struct sockaddr*)&saddr, sizeof saddr);
+  }
+  while (r == -1 && errno == EINTR);
+
+  if (r == -1 && errno != EINPROGRESS) {
+    err = UV__ERR(errno);
+#if defined(__CYGWIN__) || defined(__MSYS__)
+    /* EBADF is supposed to mean that the socket fd is bad, but
+       Cygwin reports EBADF instead of ENOTSOCK when the file is
+       not a socket.  We do not expect to see a bad fd here
+       (e.g. due to new_sock), so translate the error.  */
+    if (err == UV_EBADF)
+      err = UV_ENOTSOCK;
+#endif
+    goto out;
+  }
+
+  err = 0;
+  if (new_sock) {
+    err = uv__stream_open((uv_stream_t*)handle,
+                          uv__stream_fd(handle),
+                          UV_HANDLE_READABLE | UV_HANDLE_WRITABLE);
+  }
+
+  if (err == 0)
+    uv__io_start(handle->loop, &handle->io_watcher, POLLOUT);
+
+out:
+  handle->delayed_error = err;
+  handle->connect_req = req;
+
+  uv__req_init(handle->loop, req, UV_CONNECT);
+  req->handle = (uv_stream_t*)handle;
+  req->cb = cb;
+  QUEUE_INIT(&req->queue);
+
+  /* Force callback to run on next tick in case of error. */
+  if (err)
+    uv__io_feed(handle->loop, &handle->io_watcher);
+
+}
+
+
+static int uv__pipe_getsockpeername(const uv_pipe_t* handle,
+                                    uv__peersockfunc func,
+                                    char* buffer,
+                                    size_t* size) {
+  struct sockaddr_un sa;
+  socklen_t addrlen;
+  int err;
+
+  addrlen = sizeof(sa);
+  memset(&sa, 0, addrlen);
+  err = uv__getsockpeername((const uv_handle_t*) handle,
+                            func,
+                            (struct sockaddr*) &sa,
+                            (int*) &addrlen);
+  if (err < 0) {
+    *size = 0;
+    return err;
+  }
+
+#if defined(__linux__)
+  if (sa.sun_path[0] == 0)
+    /* Linux abstract namespace */
+    addrlen -= offsetof(struct sockaddr_un, sun_path);
+  else
+#endif
+    addrlen = strlen(sa.sun_path);
+
+
+  if ((size_t)addrlen >= *size) {
+    *size = addrlen + 1;
+    return UV_ENOBUFS;
+  }
+
+  memcpy(buffer, sa.sun_path, addrlen);
+  *size = addrlen;
+
+  /* only null-terminate if it's not an abstract socket */
+  if (buffer[0] != '\0')
+    buffer[addrlen] = '\0';
+
+  return 0;
+}
+
+
+int uv_pipe_getsockname(const uv_pipe_t* handle, char* buffer, size_t* size) {
+  return uv__pipe_getsockpeername(handle, getsockname, buffer, size);
+}
+
+
+int uv_pipe_getpeername(const uv_pipe_t* handle, char* buffer, size_t* size) {
+  return uv__pipe_getsockpeername(handle, getpeername, buffer, size);
+}
+
+
+void uv_pipe_pending_instances(uv_pipe_t* handle, int count) {
+}
+
+
+int uv_pipe_pending_count(uv_pipe_t* handle) {
+  uv__stream_queued_fds_t* queued_fds;
+
+  if (!handle->ipc)
+    return 0;
+
+  if (handle->accepted_fd == -1)
+    return 0;
+
+  if (handle->queued_fds == NULL)
+    return 1;
+
+  queued_fds = (uv__stream_queued_fds_t*)(handle->queued_fds);
+  return queued_fds->offset + 1;
+}
+
+
+uv_handle_type uv_pipe_pending_type(uv_pipe_t* handle) {
+  if (!handle->ipc)
+    return UV_UNKNOWN_HANDLE;
+
+  if (handle->accepted_fd == -1)
+    return UV_UNKNOWN_HANDLE;
+  else
+    return uv_guess_handle(handle->accepted_fd);
+}
+
+
+int uv_pipe_chmod(uv_pipe_t* handle, int mode) {
+  unsigned desired_mode;
+  struct stat pipe_stat;
+  char* name_buffer;
+  size_t name_len;
+  int r;
+
+  if (handle == NULL || uv__stream_fd(handle) == -1)
+    return UV_EBADF;
+
+  if (mode != UV_READABLE &&
+      mode != UV_WRITABLE &&
+      mode != (UV_WRITABLE | UV_READABLE))
+    return UV_EINVAL;
+
+  /* Unfortunately fchmod does not work on all platforms, we will use chmod. */
+  name_len = 0;
+  r = uv_pipe_getsockname(handle, NULL, &name_len);
+  if (r != UV_ENOBUFS)
+    return r;
+
+  name_buffer = (char*)uv__malloc(name_len);
+  if (name_buffer == NULL)
+    return UV_ENOMEM;
+
+  r = uv_pipe_getsockname(handle, name_buffer, &name_len);
+  if (r != 0) {
+    uv__free(name_buffer);
+    return r;
+  }
+
+  /* stat must be used as fstat has a bug on Darwin */
+  if (stat(name_buffer, &pipe_stat) == -1) {
+    uv__free(name_buffer);
+    return -errno;
+  }
+
+  desired_mode = 0;
+  if (mode & UV_READABLE)
+    desired_mode |= S_IRUSR | S_IRGRP | S_IROTH;
+  if (mode & UV_WRITABLE)
+    desired_mode |= S_IWUSR | S_IWGRP | S_IWOTH;
+
+  /* Exit early if pipe already has desired mode. */
+  if ((pipe_stat.st_mode & desired_mode) == desired_mode) {
+    uv__free(name_buffer);
+    return 0;
+  }
+
+  pipe_stat.st_mode |= desired_mode;
+
+  r = chmod(name_buffer, pipe_stat.st_mode);
+  uv__free(name_buffer);
+
+  return r != -1 ? 0 : UV__ERR(errno);
+}
+
+
+int uv_pipe(uv_os_fd_t fds[2], int read_flags, int write_flags) {
+  uv_os_fd_t temp[2];
+  int err;
+#if defined(__FreeBSD__) || defined(__linux__)
+  int flags = O_CLOEXEC;
+
+  if ((read_flags & UV_NONBLOCK_PIPE) && (write_flags & UV_NONBLOCK_PIPE))
+    flags |= UV_FS_O_NONBLOCK;
+
+  if (pipe2(temp, flags))
+    return UV__ERR(errno);
+
+  if (flags & UV_FS_O_NONBLOCK) {
+    fds[0] = temp[0];
+    fds[1] = temp[1];
+    return 0;
+  }
+#else
+  if (pipe(temp))
+    return UV__ERR(errno);
+
+  if ((err = uv__cloexec(temp[0], 1)))
+    goto fail;
+
+  if ((err = uv__cloexec(temp[1], 1)))
+    goto fail;
+#endif
+
+  if (read_flags & UV_NONBLOCK_PIPE)
+    if ((err = uv__nonblock(temp[0], 1)))
+      goto fail;
+
+  if (write_flags & UV_NONBLOCK_PIPE)
+    if ((err = uv__nonblock(temp[1], 1)))
+      goto fail;
+
+  fds[0] = temp[0];
+  fds[1] = temp[1];
+  return 0;
+
+fail:
+  uv__close(temp[0]);
+  uv__close(temp[1]);
+  return err;
+}
+
+
+int uv__make_pipe(int fds[2], int flags) {
+  return uv_pipe(fds,
+                 flags & UV_NONBLOCK_PIPE,
+                 flags & UV_NONBLOCK_PIPE);
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/poll.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/poll.cpp
new file mode 100644
index 0000000..7364731
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/poll.cpp
@@ -0,0 +1,160 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <unistd.h>
+#include <assert.h>
+#include <errno.h>
+
+
+static void uv__poll_io(uv_loop_t* loop, uv__io_t* w, unsigned int events) {
+  uv_poll_t* handle;
+  int pevents;
+
+  handle = container_of(w, uv_poll_t, io_watcher);
+
+  /*
+   * As documented in the kernel source fs/kernfs/file.c #780
+   * poll will return POLLERR|POLLPRI in case of sysfs
+   * polling. This does not happen in case of out-of-band
+   * TCP messages.
+   *
+   * The above is the case on (at least) FreeBSD and Linux.
+   *
+   * So to properly determine a POLLPRI or a POLLERR we need
+   * to check for both.
+   */
+  if ((events & POLLERR) && !(events & UV__POLLPRI)) {
+    uv__io_stop(loop, w, POLLIN | POLLOUT | UV__POLLRDHUP | UV__POLLPRI);
+    uv__handle_stop(handle);
+    handle->poll_cb(handle, UV_EBADF, 0);
+    return;
+  }
+
+  pevents = 0;
+  if (events & POLLIN)
+    pevents |= UV_READABLE;
+  if (events & UV__POLLPRI)
+    pevents |= UV_PRIORITIZED;
+  if (events & POLLOUT)
+    pevents |= UV_WRITABLE;
+  if (events & UV__POLLRDHUP)
+    pevents |= UV_DISCONNECT;
+
+  handle->poll_cb(handle, 0, pevents);
+}
+
+
+int uv_poll_init(uv_loop_t* loop, uv_poll_t* handle, int fd) {
+  int err;
+
+  if (uv__fd_exists(loop, fd))
+    return UV_EEXIST;
+
+  err = uv__io_check_fd(loop, fd);
+  if (err)
+    return err;
+
+  /* If ioctl(FIONBIO) reports ENOTTY, try fcntl(F_GETFL) + fcntl(F_SETFL).
+   * Workaround for e.g. kqueue fds not supporting ioctls.
+   */
+  err = uv__nonblock(fd, 1);
+#if UV__NONBLOCK_IS_IOCTL
+  if (err == UV_ENOTTY)
+    err = uv__nonblock_fcntl(fd, 1);
+#endif
+
+  if (err)
+    return err;
+
+  uv__handle_init(loop, (uv_handle_t*) handle, UV_POLL);
+  uv__io_init(&handle->io_watcher, uv__poll_io, fd);
+  handle->poll_cb = NULL;
+  return 0;
+}
+
+
+int uv_poll_init_socket(uv_loop_t* loop, uv_poll_t* handle,
+    uv_os_sock_t socket) {
+  return uv_poll_init(loop, handle, socket);
+}
+
+
+static void uv__poll_stop(uv_poll_t* handle) {
+  uv__io_stop(handle->loop,
+              &handle->io_watcher,
+              POLLIN | POLLOUT | UV__POLLRDHUP | UV__POLLPRI);
+  uv__handle_stop(handle);
+  uv__platform_invalidate_fd(handle->loop, handle->io_watcher.fd);
+}
+
+
+int uv_poll_stop(uv_poll_t* handle) {
+  assert(!uv__is_closing(handle));
+  uv__poll_stop(handle);
+  return 0;
+}
+
+
+int uv_poll_start(uv_poll_t* handle, int pevents, uv_poll_cb poll_cb) {
+  void** watchers;
+  uv__io_t* w;
+  int events;
+
+  assert((pevents & ~(UV_READABLE | UV_WRITABLE | UV_DISCONNECT |
+                      UV_PRIORITIZED)) == 0);
+  assert(!uv__is_closing(handle));
+
+  watchers = handle->loop->watchers;
+  w = &handle->io_watcher;
+
+  if (uv__fd_exists(handle->loop, w->fd))
+    if (watchers[w->fd] != w)
+      return UV_EEXIST;
+
+  uv__poll_stop(handle);
+
+  if (pevents == 0)
+    return 0;
+
+  events = 0;
+  if (pevents & UV_READABLE)
+    events |= POLLIN;
+  if (pevents & UV_PRIORITIZED)
+    events |= UV__POLLPRI;
+  if (pevents & UV_WRITABLE)
+    events |= POLLOUT;
+  if (pevents & UV_DISCONNECT)
+    events |= UV__POLLRDHUP;
+
+  uv__io_start(handle->loop, &handle->io_watcher, events);
+  uv__handle_start(handle);
+  handle->poll_cb = poll_cb;
+
+  return 0;
+}
+
+
+void uv__poll_close(uv_poll_t* handle) {
+  uv__poll_stop(handle);
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/posix-hrtime.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/posix-hrtime.cpp
similarity index 100%
rename from third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/posix-hrtime.cpp
rename to third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/posix-hrtime.cpp
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/posix-poll.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/posix-poll.cpp
new file mode 100644
index 0000000..8da038d
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/posix-poll.cpp
@@ -0,0 +1,374 @@
+/* Copyright libuv project contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+/* POSIX defines poll() as a portable way to wait on file descriptors.
+ * Here we maintain a dynamically sized array of file descriptors and
+ * events to pass as the first argument to poll().
+ */
+
+#include <assert.h>
+#include <stddef.h>
+#include <stdint.h>
+#include <errno.h>
+#include <unistd.h>
+
+int uv__platform_loop_init(uv_loop_t* loop) {
+  loop->poll_fds = NULL;
+  loop->poll_fds_used = 0;
+  loop->poll_fds_size = 0;
+  loop->poll_fds_iterating = 0;
+  return 0;
+}
+
+void uv__platform_loop_delete(uv_loop_t* loop) {
+  uv__free(loop->poll_fds);
+  loop->poll_fds = NULL;
+}
+
+int uv__io_fork(uv_loop_t* loop) {
+  uv__platform_loop_delete(loop);
+  return uv__platform_loop_init(loop);
+}
+
+/* Allocate or dynamically resize our poll fds array.  */
+static void uv__pollfds_maybe_resize(uv_loop_t* loop) {
+  size_t i;
+  size_t n;
+  struct pollfd* p;
+
+  if (loop->poll_fds_used < loop->poll_fds_size)
+    return;
+
+  n = loop->poll_fds_size ? loop->poll_fds_size * 2 : 64;
+  p = (struct pollfd*)uv__reallocf(loop->poll_fds, n * sizeof(*loop->poll_fds));
+  if (p == NULL)
+    abort();
+
+  loop->poll_fds = p;
+  for (i = loop->poll_fds_size; i < n; i++) {
+    loop->poll_fds[i].fd = -1;
+    loop->poll_fds[i].events = 0;
+    loop->poll_fds[i].revents = 0;
+  }
+  loop->poll_fds_size = n;
+}
+
+/* Primitive swap operation on poll fds array elements.  */
+static void uv__pollfds_swap(uv_loop_t* loop, size_t l, size_t r) {
+  struct pollfd pfd;
+  pfd = loop->poll_fds[l];
+  loop->poll_fds[l] = loop->poll_fds[r];
+  loop->poll_fds[r] = pfd;
+}
+
+/* Add a watcher's fd to our poll fds array with its pending events.  */
+static void uv__pollfds_add(uv_loop_t* loop, uv__io_t* w) {
+  size_t i;
+  struct pollfd* pe;
+
+  /* If the fd is already in the set just update its events.  */
+  assert(!loop->poll_fds_iterating);
+  for (i = 0; i < loop->poll_fds_used; ++i) {
+    if (loop->poll_fds[i].fd == w->fd) {
+      loop->poll_fds[i].events = w->pevents;
+      return;
+    }
+  }
+
+  /* Otherwise, allocate a new slot in the set for the fd.  */
+  uv__pollfds_maybe_resize(loop);
+  pe = &loop->poll_fds[loop->poll_fds_used++];
+  pe->fd = w->fd;
+  pe->events = w->pevents;
+}
+
+/* Remove a watcher's fd from our poll fds array.  */
+static void uv__pollfds_del(uv_loop_t* loop, int fd) {
+  size_t i;
+  assert(!loop->poll_fds_iterating);
+  for (i = 0; i < loop->poll_fds_used;) {
+    if (loop->poll_fds[i].fd == fd) {
+      /* swap to last position and remove */
+      --loop->poll_fds_used;
+      uv__pollfds_swap(loop, i, loop->poll_fds_used);
+      loop->poll_fds[loop->poll_fds_used].fd = -1;
+      loop->poll_fds[loop->poll_fds_used].events = 0;
+      loop->poll_fds[loop->poll_fds_used].revents = 0;
+      /* This method is called with an fd of -1 to purge the invalidated fds,
+       * so we may possibly have multiples to remove.
+       */
+      if (-1 != fd)
+        return;
+    } else {
+      /* We must only increment the loop counter when the fds do not match.
+       * Otherwise, when we are purging an invalidated fd, the value just
+       * swapped here from the previous end of the array will be skipped.
+       */
+       ++i;
+    }
+  }
+}
+
+
+void uv__io_poll(uv_loop_t* loop, int timeout) {
+  sigset_t* pset;
+  sigset_t set;
+  uint64_t time_base;
+  uint64_t time_diff;
+  QUEUE* q;
+  uv__io_t* w;
+  size_t i;
+  unsigned int nevents;
+  int nfds;
+  int have_signals;
+  struct pollfd* pe;
+  int fd;
+  int user_timeout;
+  int reset_timeout;
+
+  if (loop->nfds == 0) {
+    assert(QUEUE_EMPTY(&loop->watcher_queue));
+    return;
+  }
+
+  /* Take queued watchers and add their fds to our poll fds array.  */
+  while (!QUEUE_EMPTY(&loop->watcher_queue)) {
+    q = QUEUE_HEAD(&loop->watcher_queue);
+    QUEUE_REMOVE(q);
+    QUEUE_INIT(q);
+
+    w = QUEUE_DATA(q, uv__io_t, watcher_queue);
+    assert(w->pevents != 0);
+    assert(w->fd >= 0);
+    assert(w->fd < (int) loop->nwatchers);
+
+    uv__pollfds_add(loop, w);
+
+    w->events = w->pevents;
+  }
+
+  /* Prepare a set of signals to block around poll(), if any.  */
+  pset = NULL;
+  if (loop->flags & UV_LOOP_BLOCK_SIGPROF) {
+    pset = &set;
+    sigemptyset(pset);
+    sigaddset(pset, SIGPROF);
+  }
+
+  assert(timeout >= -1);
+  time_base = loop->time;
+
+  if (uv__get_internal_fields(loop)->flags & UV_METRICS_IDLE_TIME) {
+    reset_timeout = 1;
+    user_timeout = timeout;
+    timeout = 0;
+  } else {
+    reset_timeout = 0;
+  }
+
+  /* Loop calls to poll() and processing of results.  If we get some
+   * results from poll() but they turn out not to be interesting to
+   * our caller then we need to loop around and poll() again.
+   */
+  for (;;) {
+    /* Only need to set the provider_entry_time if timeout != 0. The function
+     * will return early if the loop isn't configured with UV_METRICS_IDLE_TIME.
+     */
+    if (timeout != 0)
+      uv__metrics_set_provider_entry_time(loop);
+
+    if (pset != NULL)
+      if (pthread_sigmask(SIG_BLOCK, pset, NULL))
+        abort();
+    nfds = poll(loop->poll_fds, (nfds_t)loop->poll_fds_used, timeout);
+    if (pset != NULL)
+      if (pthread_sigmask(SIG_UNBLOCK, pset, NULL))
+        abort();
+
+    /* Update loop->time unconditionally. It's tempting to skip the update when
+     * timeout == 0 (i.e. non-blocking poll) but there is no guarantee that the
+     * operating system didn't reschedule our process while in the syscall.
+     */
+    SAVE_ERRNO(uv__update_time(loop));
+
+    if (nfds == 0) {
+      if (reset_timeout != 0) {
+        timeout = user_timeout;
+        reset_timeout = 0;
+        if (timeout == -1)
+          continue;
+        if (timeout > 0)
+          goto update_timeout;
+      }
+
+      assert(timeout != -1);
+      return;
+    }
+
+    if (nfds == -1) {
+      if (errno != EINTR)
+        abort();
+
+      if (reset_timeout != 0) {
+        timeout = user_timeout;
+        reset_timeout = 0;
+      }
+
+      if (timeout == -1)
+        continue;
+
+      if (timeout == 0)
+        return;
+
+      /* Interrupted by a signal. Update timeout and poll again. */
+      goto update_timeout;
+    }
+
+    /* Tell uv__platform_invalidate_fd not to manipulate our array
+     * while we are iterating over it.
+     */
+    loop->poll_fds_iterating = 1;
+
+    /* Initialize a count of events that we care about.  */
+    nevents = 0;
+    have_signals = 0;
+
+    /* Loop over the entire poll fds array looking for returned events.  */
+    for (i = 0; i < loop->poll_fds_used; i++) {
+      pe = loop->poll_fds + i;
+      fd = pe->fd;
+
+      /* Skip invalidated events, see uv__platform_invalidate_fd.  */
+      if (fd == -1)
+        continue;
+
+      assert(fd >= 0);
+      assert((unsigned) fd < loop->nwatchers);
+
+      w = loop->watchers[fd];
+
+      if (w == NULL) {
+        /* File descriptor that we've stopped watching, ignore.  */
+        uv__platform_invalidate_fd(loop, fd);
+        continue;
+      }
+
+      /* Filter out events that user has not requested us to watch
+       * (e.g. POLLNVAL).
+       */
+      pe->revents &= w->pevents | POLLERR | POLLHUP;
+
+      if (pe->revents != 0) {
+        /* Run signal watchers last.  */
+        if (w == &loop->signal_io_watcher) {
+          have_signals = 1;
+        } else {
+          uv__metrics_update_idle_time(loop);
+          w->cb(loop, w, pe->revents);
+        }
+
+        nevents++;
+      }
+    }
+
+    if (reset_timeout != 0) {
+      timeout = user_timeout;
+      reset_timeout = 0;
+    }
+
+    if (have_signals != 0) {
+      uv__metrics_update_idle_time(loop);
+      loop->signal_io_watcher.cb(loop, &loop->signal_io_watcher, POLLIN);
+    }
+
+    loop->poll_fds_iterating = 0;
+
+    /* Purge invalidated fds from our poll fds array.  */
+    uv__pollfds_del(loop, -1);
+
+    if (have_signals != 0)
+      return;  /* Event loop should cycle now so don't poll again. */
+
+    if (nevents != 0)
+      return;
+
+    if (timeout == 0)
+      return;
+
+    if (timeout == -1)
+      continue;
+
+update_timeout:
+    assert(timeout > 0);
+
+    time_diff = loop->time - time_base;
+    if (time_diff >= (uint64_t) timeout)
+      return;
+
+    timeout -= time_diff;
+  }
+}
+
+/* Remove the given fd from our poll fds array because no one
+ * is interested in its events anymore.
+ */
+void uv__platform_invalidate_fd(uv_loop_t* loop, int fd) {
+  size_t i;
+
+  assert(fd >= 0);
+
+  if (loop->poll_fds_iterating) {
+    /* uv__io_poll is currently iterating.  Just invalidate fd.  */
+    for (i = 0; i < loop->poll_fds_used; i++)
+      if (loop->poll_fds[i].fd == fd) {
+        loop->poll_fds[i].fd = -1;
+        loop->poll_fds[i].events = 0;
+        loop->poll_fds[i].revents = 0;
+      }
+  } else {
+    /* uv__io_poll is not iterating.  Delete fd from the set.  */
+    uv__pollfds_del(loop, fd);
+  }
+}
+
+/* Check whether the given fd is supported by poll().  */
+int uv__io_check_fd(uv_loop_t* loop, int fd) {
+  struct pollfd p[1];
+  int rv;
+
+  p[0].fd = fd;
+  p[0].events = POLLIN;
+
+  do
+    rv = poll(p, 1, 0);
+  while (rv == -1 && (errno == EINTR || errno == EAGAIN));
+
+  if (rv == -1)
+    return UV__ERR(errno);
+
+  if (p[0].revents & POLLNVAL)
+    return UV_EINVAL;
+
+  return 0;
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/process.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/process.cpp
new file mode 100644
index 0000000..0916aa4
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/process.cpp
@@ -0,0 +1,1085 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <stdio.h>
+#include <stdlib.h>
+#include <assert.h>
+#include <errno.h>
+#include <signal.h>
+#include <string.h>
+
+#include <sys/types.h>
+#include <sys/wait.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <poll.h>
+
+#if defined(__APPLE__)
+# include <spawn.h>
+# include <paths.h>
+# include <sys/kauth.h>
+# include <sys/types.h>
+# include <sys/sysctl.h>
+# include <dlfcn.h>
+# include <crt_externs.h>
+# include <xlocale.h>
+# define environ (*_NSGetEnviron())
+
+/* macOS 10.14 back does not define this constant */
+# ifndef POSIX_SPAWN_SETSID
+#  define POSIX_SPAWN_SETSID 1024
+# endif
+
+#else
+extern char **environ;
+#endif
+
+#if defined(__linux__) || defined(__GLIBC__)
+# include <grp.h>
+#endif
+
+#if defined(__MVS__)
+# include "zos-base.h"
+#endif
+
+#if defined(__APPLE__) || \
+    defined(__DragonFly__) || \
+    defined(__FreeBSD__) || \
+    defined(__NetBSD__) || \
+    defined(__OpenBSD__)
+#include <sys/event.h>
+#else
+#define UV_USE_SIGCHLD
+#endif
+
+
+#ifdef UV_USE_SIGCHLD
+static void uv__chld(uv_signal_t* handle, int signum) {
+  assert(signum == SIGCHLD);
+  uv__wait_children(handle->loop);
+}
+#endif
+
+void uv__wait_children(uv_loop_t* loop) {
+  uv_process_t* process;
+  int exit_status;
+  int term_signal;
+  int status;
+  int options;
+  pid_t pid;
+  QUEUE pending;
+  QUEUE* q;
+  QUEUE* h;
+
+  QUEUE_INIT(&pending);
+
+  h = &loop->process_handles;
+  q = QUEUE_HEAD(h);
+  while (q != h) {
+    process = QUEUE_DATA(q, uv_process_t, queue);
+    q = QUEUE_NEXT(q);
+
+#ifndef UV_USE_SIGCHLD
+    if ((process->flags & UV_HANDLE_REAP) == 0)
+      continue;
+    options = 0;
+    process->flags &= ~UV_HANDLE_REAP;
+#else
+    options = WNOHANG;
+#endif
+
+    do
+      pid = waitpid(process->pid, &status, options);
+    while (pid == -1 && errno == EINTR);
+
+#ifdef UV_USE_SIGCHLD
+    if (pid == 0) /* Not yet exited */
+      continue;
+#endif
+
+    if (pid == -1) {
+      if (errno != ECHILD)
+        abort();
+      /* The child died, and we missed it. This probably means someone else
+       * stole the waitpid from us. Handle this by not handling it at all. */
+      continue;
+    }
+
+    assert(pid == process->pid);
+    process->status = status;
+    QUEUE_REMOVE(&process->queue);
+    QUEUE_INSERT_TAIL(&pending, &process->queue);
+  }
+
+  h = &pending;
+  q = QUEUE_HEAD(h);
+  while (q != h) {
+    process = QUEUE_DATA(q, uv_process_t, queue);
+    q = QUEUE_NEXT(q);
+
+    QUEUE_REMOVE(&process->queue);
+    QUEUE_INIT(&process->queue);
+    uv__handle_stop(process);
+
+    if (process->exit_cb == NULL)
+      continue;
+
+    exit_status = 0;
+    if (WIFEXITED(process->status))
+      exit_status = WEXITSTATUS(process->status);
+
+    term_signal = 0;
+    if (WIFSIGNALED(process->status))
+      term_signal = WTERMSIG(process->status);
+
+    process->exit_cb(process, exit_status, term_signal);
+  }
+  assert(QUEUE_EMPTY(&pending));
+}
+
+/*
+ * Used for initializing stdio streams like options.stdin_stream. Returns
+ * zero on success. See also the cleanup section in uv_spawn().
+ */
+static int uv__process_init_stdio(uv_stdio_container_t* container, int fds[2]) {
+  int mask;
+  int fd;
+
+  mask = UV_IGNORE | UV_CREATE_PIPE | UV_INHERIT_FD | UV_INHERIT_STREAM;
+
+  switch (container->flags & mask) {
+  case UV_IGNORE:
+    return 0;
+
+  case UV_CREATE_PIPE:
+    assert(container->data.stream != NULL);
+    if (container->data.stream->type != UV_NAMED_PIPE)
+      return UV_EINVAL;
+    else
+      return uv_socketpair(SOCK_STREAM, 0, fds, 0, 0);
+
+  case UV_INHERIT_FD:
+  case UV_INHERIT_STREAM:
+    if (container->flags & UV_INHERIT_FD)
+      fd = container->data.fd;
+    else
+      fd = uv__stream_fd(container->data.stream);
+
+    if (fd == -1)
+      return UV_EINVAL;
+
+    fds[1] = fd;
+    return 0;
+
+  default:
+    assert(0 && "Unexpected flags");
+    return UV_EINVAL;
+  }
+}
+
+
+static int uv__process_open_stream(uv_stdio_container_t* container,
+                                   int pipefds[2]) {
+  int flags;
+  int err;
+
+  if (!(container->flags & UV_CREATE_PIPE) || pipefds[0] < 0)
+    return 0;
+
+  err = uv__close(pipefds[1]);
+  if (err != 0)
+    abort();
+
+  pipefds[1] = -1;
+  uv__nonblock(pipefds[0], 1);
+
+  flags = 0;
+  if (container->flags & UV_WRITABLE_PIPE)
+    flags |= UV_HANDLE_READABLE;
+  if (container->flags & UV_READABLE_PIPE)
+    flags |= UV_HANDLE_WRITABLE;
+
+  return uv__stream_open(container->data.stream, pipefds[0], flags);
+}
+
+
+static void uv__process_close_stream(uv_stdio_container_t* container) {
+  if (!(container->flags & UV_CREATE_PIPE)) return;
+  uv__stream_close(container->data.stream);
+}
+
+
+static void uv__write_int(int fd, int val) {
+  ssize_t n;
+
+  do
+    n = write(fd, &val, sizeof(val));
+  while (n == -1 && errno == EINTR);
+
+  /* The write might have failed (e.g. if the parent process has died),
+   * but we have nothing left but to _exit ourself now too. */
+  _exit(127);
+}
+
+
+static void uv__write_errno(int error_fd) {
+  uv__write_int(error_fd, UV__ERR(errno));
+}
+
+
+#if !(defined(__APPLE__) && (TARGET_OS_TV || TARGET_OS_WATCH))
+/* execvp is marked __WATCHOS_PROHIBITED __TVOS_PROHIBITED, so must be
+ * avoided. Since this isn't called on those targets, the function
+ * doesn't even need to be defined for them.
+ */
+static void uv__process_child_init(const uv_process_options_t* options,
+                                   int stdio_count,
+                                   int (*pipes)[2],
+                                   int error_fd) {
+  sigset_t signewset;
+  int close_fd;
+  int use_fd;
+  int fd;
+  int n;
+
+  /* Reset signal disposition first. Use a hard-coded limit because NSIG is not
+   * fixed on Linux: it's either 32, 34 or 64, depending on whether RT signals
+   * are enabled. We are not allowed to touch RT signal handlers, glibc uses
+   * them internally.
+   */
+  for (n = 1; n < 32; n += 1) {
+    if (n == SIGKILL || n == SIGSTOP)
+      continue;  /* Can't be changed. */
+
+#if defined(__HAIKU__)
+    if (n == SIGKILLTHR)
+      continue;  /* Can't be changed. */
+#endif
+
+    if (SIG_ERR != signal(n, SIG_DFL))
+      continue;
+
+    uv__write_errno(error_fd);
+  }
+
+  if (options->flags & UV_PROCESS_DETACHED)
+    setsid();
+
+  /* First duplicate low numbered fds, since it's not safe to duplicate them,
+   * they could get replaced. Example: swapping stdout and stderr; without
+   * this fd 2 (stderr) would be duplicated into fd 1, thus making both
+   * stdout and stderr go to the same fd, which was not the intention. */
+  for (fd = 0; fd < stdio_count; fd++) {
+    use_fd = pipes[fd][1];
+    if (use_fd < 0 || use_fd >= fd)
+      continue;
+#ifdef F_DUPFD_CLOEXEC /* POSIX 2008 */
+    pipes[fd][1] = fcntl(use_fd, F_DUPFD_CLOEXEC, stdio_count);
+#else
+    pipes[fd][1] = fcntl(use_fd, F_DUPFD, stdio_count);
+#endif
+    if (pipes[fd][1] == -1)
+      uv__write_errno(error_fd);
+#ifndef F_DUPFD_CLOEXEC /* POSIX 2008 */
+    n = uv__cloexec(pipes[fd][1], 1);
+    if (n)
+      uv__write_int(error_fd, n);
+#endif
+  }
+
+  for (fd = 0; fd < stdio_count; fd++) {
+    close_fd = -1;
+    use_fd = pipes[fd][1];
+
+    if (use_fd < 0) {
+      if (fd >= 3)
+        continue;
+      else {
+        /* Redirect stdin, stdout and stderr to /dev/null even if UV_IGNORE is
+         * set. */
+        uv__close_nocheckstdio(fd); /* Free up fd, if it happens to be open. */
+        use_fd = open("/dev/null", fd == 0 ? O_RDONLY : O_RDWR);
+        close_fd = use_fd;
+
+        if (use_fd < 0)
+          uv__write_errno(error_fd);
+      }
+    }
+
+    if (fd == use_fd) {
+      if (close_fd == -1) {
+        n = uv__cloexec(use_fd, 0);
+        if (n)
+          uv__write_int(error_fd, n);
+      }
+    }
+    else {
+      fd = dup2(use_fd, fd);
+    }
+
+    if (fd == -1)
+      uv__write_errno(error_fd);
+
+    if (fd <= 2 && close_fd == -1)
+      uv__nonblock_fcntl(fd, 0);
+
+    if (close_fd >= stdio_count)
+      uv__close(close_fd);
+  }
+
+  if (options->cwd != NULL && chdir(options->cwd))
+    uv__write_errno(error_fd);
+
+  if (options->flags & (UV_PROCESS_SETUID | UV_PROCESS_SETGID)) {
+    /* When dropping privileges from root, the `setgroups` call will
+     * remove any extraneous groups. If we don't call this, then
+     * even though our uid has dropped, we may still have groups
+     * that enable us to do super-user things. This will fail if we
+     * aren't root, so don't bother checking the return value, this
+     * is just done as an optimistic privilege dropping function.
+     */
+    SAVE_ERRNO(setgroups(0, NULL));
+  }
+
+  if ((options->flags & UV_PROCESS_SETGID) && setgid(options->gid))
+    uv__write_errno(error_fd);
+
+  if ((options->flags & UV_PROCESS_SETUID) && setuid(options->uid))
+    uv__write_errno(error_fd);
+
+  if (options->env != NULL)
+    environ = options->env;
+
+  /* Reset signal mask just before exec. */
+  sigemptyset(&signewset);
+  if (sigprocmask(SIG_SETMASK, &signewset, NULL) != 0)
+    abort();
+
+#ifdef __MVS__
+  execvpe(options->file, options->args, environ);
+#else
+  execvp(options->file, options->args);
+#endif
+
+  uv__write_errno(error_fd);
+}
+#endif
+
+
+#if defined(__APPLE__)
+typedef struct uv__posix_spawn_fncs_tag {
+  struct {
+    int (*addchdir_np)(const posix_spawn_file_actions_t *, const char *);
+  } file_actions;
+} uv__posix_spawn_fncs_t;
+
+
+static uv_once_t posix_spawn_init_once = UV_ONCE_INIT;
+static uv__posix_spawn_fncs_t posix_spawn_fncs;
+static int posix_spawn_can_use_setsid;
+
+
+static void uv__spawn_init_posix_spawn_fncs(void) {
+  /* Try to locate all non-portable functions at runtime */
+  posix_spawn_fncs.file_actions.addchdir_np =
+    (int (*)(void* const*, const char*)) dlsym(RTLD_DEFAULT, "posix_spawn_file_actions_addchdir_np");
+}
+
+
+static void uv__spawn_init_can_use_setsid(void) {
+  int which[] = {CTL_KERN, KERN_OSRELEASE};
+  unsigned major;
+  unsigned minor;
+  unsigned patch;
+  char buf[256];
+  size_t len;
+
+  len = sizeof(buf);
+  if (sysctl(which, ARRAY_SIZE(which), buf, &len, NULL, 0))
+    return;
+
+  /* NULL specifies to use LC_C_LOCALE */
+  if (3 != sscanf_l(buf, NULL, "%u.%u.%u", &major, &minor, &patch))
+    return;
+
+  posix_spawn_can_use_setsid = (major >= 19);  /* macOS Catalina */
+}
+
+
+static void uv__spawn_init_posix_spawn(void) {
+  /* Init handles to all potentially non-defined functions */
+  uv__spawn_init_posix_spawn_fncs();
+
+  /* Init feature detection for POSIX_SPAWN_SETSID flag */
+  uv__spawn_init_can_use_setsid();
+}
+
+
+static int uv__spawn_set_posix_spawn_attrs(
+    posix_spawnattr_t* attrs,
+    const uv__posix_spawn_fncs_t* posix_spawn_fncs,
+    const uv_process_options_t* options) {
+  int err;
+  unsigned int flags;
+  sigset_t signal_set;
+
+  err = posix_spawnattr_init(attrs);
+  if (err != 0) {
+    /* If initialization fails, no need to de-init, just return */
+    return err;
+  }
+
+  if (options->flags & (UV_PROCESS_SETUID | UV_PROCESS_SETGID)) {
+    /* kauth_cred_issuser currently requires exactly uid == 0 for these
+     * posixspawn_attrs (set_groups_np, setuid_np, setgid_np), which deviates
+     * from the normal specification of setuid (which also uses euid), and they
+     * are also undocumented syscalls, so we do not use them. */
+    err = ENOSYS;
+    goto error;
+  }
+
+  /* Set flags for spawn behavior
+   * 1) POSIX_SPAWN_CLOEXEC_DEFAULT: (Apple Extension) All descriptors in the
+   *    parent will be treated as if they had been created with O_CLOEXEC. The
+   *    only fds that will be passed on to the child are those manipulated by
+   *    the file actions
+   * 2) POSIX_SPAWN_SETSIGDEF: Signals mentioned in spawn-sigdefault in the
+   *    spawn attributes will be reset to behave as their default
+   * 3) POSIX_SPAWN_SETSIGMASK: Signal mask will be set to the value of
+   *    spawn-sigmask in attributes
+   * 4) POSIX_SPAWN_SETSID: Make the process a new session leader if a detached
+   *    session was requested. */
+  flags = POSIX_SPAWN_CLOEXEC_DEFAULT |
+          POSIX_SPAWN_SETSIGDEF |
+          POSIX_SPAWN_SETSIGMASK;
+  if (options->flags & UV_PROCESS_DETACHED) {
+    /* If running on a version of macOS where this flag is not supported,
+     * revert back to the fork/exec flow. Otherwise posix_spawn will
+     * silently ignore the flag. */
+    if (!posix_spawn_can_use_setsid) {
+      err = ENOSYS;
+      goto error;
+    }
+
+    flags |= POSIX_SPAWN_SETSID;
+  }
+  err = posix_spawnattr_setflags(attrs, flags);
+  if (err != 0)
+    goto error;
+
+  /* Reset all signal the child to their default behavior */
+  sigfillset(&signal_set);
+  err = posix_spawnattr_setsigdefault(attrs, &signal_set);
+  if (err != 0)
+    goto error;
+
+  /* Reset the signal mask for all signals */
+  sigemptyset(&signal_set);
+  err = posix_spawnattr_setsigmask(attrs, &signal_set);
+  if (err != 0)
+    goto error;
+
+  return err;
+
+error:
+  (void) posix_spawnattr_destroy(attrs);
+  return err;
+}
+
+
+static int uv__spawn_set_posix_spawn_file_actions(
+    posix_spawn_file_actions_t* actions,
+    const uv__posix_spawn_fncs_t* posix_spawn_fncs,
+    const uv_process_options_t* options,
+    int stdio_count,
+    int (*pipes)[2]) {
+  int fd;
+  int fd2;
+  int use_fd;
+  int err;
+
+  err = posix_spawn_file_actions_init(actions);
+  if (err != 0) {
+    /* If initialization fails, no need to de-init, just return */
+    return err;
+  }
+
+  /* Set the current working directory if requested */
+  if (options->cwd != NULL) {
+    if (posix_spawn_fncs->file_actions.addchdir_np == NULL) {
+      err = ENOSYS;
+      goto error;
+    }
+
+    err = posix_spawn_fncs->file_actions.addchdir_np(actions, options->cwd);
+    if (err != 0)
+      goto error;
+  }
+
+  /* Do not return ENOSYS after this point, as we may mutate pipes. */
+
+  /* First duplicate low numbered fds, since it's not safe to duplicate them,
+   * they could get replaced. Example: swapping stdout and stderr; without
+   * this fd 2 (stderr) would be duplicated into fd 1, thus making both
+   * stdout and stderr go to the same fd, which was not the intention. */
+  for (fd = 0; fd < stdio_count; fd++) {
+    use_fd = pipes[fd][1];
+    if (use_fd < 0 || use_fd >= fd)
+      continue;
+    use_fd = stdio_count;
+    for (fd2 = 0; fd2 < stdio_count; fd2++) {
+      /* If we were not setting POSIX_SPAWN_CLOEXEC_DEFAULT, we would need to
+       * also consider whether fcntl(fd, F_GETFD) returned without the
+       * FD_CLOEXEC flag set. */
+      if (pipes[fd2][1] == use_fd) {
+        use_fd++;
+        fd2 = 0;
+      }
+    }
+    err = posix_spawn_file_actions_adddup2(
+      actions,
+      pipes[fd][1],
+      use_fd);
+    assert(err != ENOSYS);
+    if (err != 0)
+      goto error;
+    pipes[fd][1] = use_fd;
+  }
+
+  /* Second, move the descriptors into their respective places */
+  for (fd = 0; fd < stdio_count; fd++) {
+    use_fd = pipes[fd][1];
+    if (use_fd < 0) {
+      if (fd >= 3)
+        continue;
+      else {
+        /* If ignored, redirect to (or from) /dev/null, */
+        err = posix_spawn_file_actions_addopen(
+          actions,
+          fd,
+          "/dev/null",
+          fd == 0 ? O_RDONLY : O_RDWR,
+          0);
+        assert(err != ENOSYS);
+        if (err != 0)
+          goto error;
+        continue;
+      }
+    }
+
+    if (fd == use_fd)
+        err = posix_spawn_file_actions_addinherit_np(actions, fd);
+    else
+        err = posix_spawn_file_actions_adddup2(actions, use_fd, fd);
+    assert(err != ENOSYS);
+    if (err != 0)
+      goto error;
+
+    /* Make sure the fd is marked as non-blocking (state shared between child
+     * and parent). */
+    uv__nonblock_fcntl(use_fd, 0);
+  }
+
+  /* Finally, close all the superfluous descriptors */
+  for (fd = 0; fd < stdio_count; fd++) {
+    use_fd = pipes[fd][1];
+    if (use_fd < stdio_count)
+      continue;
+
+    /* Check if we already closed this. */
+    for (fd2 = 0; fd2 < fd; fd2++) {
+      if (pipes[fd2][1] == use_fd)
+          break;
+    }
+    if (fd2 < fd)
+      continue;
+
+    err = posix_spawn_file_actions_addclose(actions, use_fd);
+    assert(err != ENOSYS);
+    if (err != 0)
+      goto error;
+  }
+
+  return 0;
+
+error:
+  (void) posix_spawn_file_actions_destroy(actions);
+  return err;
+}
+
+char* uv__spawn_find_path_in_env(char** env) {
+  char** env_iterator;
+  const char path_var[] = "PATH=";
+
+  /* Look for an environment variable called PATH in the
+   * provided env array, and return its value if found */
+  for (env_iterator = env; *env_iterator != NULL; env_iterator++) {
+    if (strncmp(*env_iterator, path_var, sizeof(path_var) - 1) == 0) {
+      /* Found "PATH=" at the beginning of the string */
+      return *env_iterator + sizeof(path_var) - 1;
+    }
+  }
+
+  return NULL;
+}
+
+
+static int uv__spawn_resolve_and_spawn(const uv_process_options_t* options,
+                                       posix_spawnattr_t* attrs,
+                                       posix_spawn_file_actions_t* actions,
+                                       pid_t* pid) {
+  const char *p;
+  const char *z;
+  const char *path;
+  size_t l;
+  size_t k;
+  int err;
+  int seen_eacces;
+
+  path = NULL;
+  err = -1;
+  seen_eacces = 0;
+
+  /* Short circuit for erroneous case */
+  if (options->file == NULL)
+    return ENOENT;
+
+  /* The environment for the child process is that of the parent unless overriden
+   * by options->env */
+  char** env = environ;
+  if (options->env != NULL)
+    env = options->env;
+
+  /* If options->file contains a slash, posix_spawn/posix_spawnp should behave
+   * the same, and do not involve PATH resolution at all. The libc
+   * `posix_spawnp` provided by Apple is buggy (since 10.15), so we now emulate it
+   * here, per https://github.com/libuv/libuv/pull/3583. */
+  if (strchr(options->file, '/') != NULL) {
+    do
+      err = posix_spawn(pid, options->file, actions, attrs, options->args, env);
+    while (err == EINTR);
+    return err;
+  }
+
+  /* Look for the definition of PATH in the provided env */
+  path = uv__spawn_find_path_in_env(env);
+
+  /* The following resolution logic (execvpe emulation) is copied from
+   * https://git.musl-libc.org/cgit/musl/tree/src/process/execvp.c
+   * and adapted to work for our specific usage */
+
+  /* If no path was provided in env, use the default value
+   * to look for the executable */
+  if (path == NULL)
+    path = _PATH_DEFPATH;
+
+  k = strnlen(options->file, NAME_MAX + 1);
+  if (k > NAME_MAX)
+    return ENAMETOOLONG;
+
+  l = strnlen(path, PATH_MAX - 1) + 1;
+
+  for (p = path;; p = z) {
+    /* Compose the new process file from the entry in the PATH
+     * environment variable and the actual file name */
+    char b[PATH_MAX + NAME_MAX];
+    z = strchr(p, ':');
+    if (!z)
+      z = p + strlen(p);
+    if ((size_t)(z - p) >= l) {
+      if (!*z++)
+        break;
+
+      continue;
+    }
+    memcpy(b, p, z - p);
+    b[z - p] = '/';
+    memcpy(b + (z - p) + (z > p), options->file, k + 1);
+
+    /* Try to spawn the new process file. If it fails with ENOENT, the
+     * new process file is not in this PATH entry, continue with the next
+     * PATH entry. */
+    do
+      err = posix_spawn(pid, b, actions, attrs, options->args, env);
+    while (err == EINTR);
+
+    switch (err) {
+    case EACCES:
+      seen_eacces = 1;
+      break; /* continue search */
+    case ENOENT:
+    case ENOTDIR:
+      break; /* continue search */
+    default:
+      return err;
+    }
+
+    if (!*z++)
+      break;
+  }
+
+  if (seen_eacces)
+    return EACCES;
+  return err;
+}
+
+
+static int uv__spawn_and_init_child_posix_spawn(
+    const uv_process_options_t* options,
+    int stdio_count,
+    int (*pipes)[2],
+    pid_t* pid,
+    const uv__posix_spawn_fncs_t* posix_spawn_fncs) {
+  int err;
+  posix_spawnattr_t attrs;
+  posix_spawn_file_actions_t actions;
+
+  err = uv__spawn_set_posix_spawn_attrs(&attrs, posix_spawn_fncs, options);
+  if (err != 0)
+    goto error;
+
+  /* This may mutate pipes. */
+  err = uv__spawn_set_posix_spawn_file_actions(&actions,
+                                               posix_spawn_fncs,
+                                               options,
+                                               stdio_count,
+                                               pipes);
+  if (err != 0) {
+    (void) posix_spawnattr_destroy(&attrs);
+    goto error;
+  }
+
+  /* Try to spawn options->file resolving in the provided environment
+   * if any */
+  err = uv__spawn_resolve_and_spawn(options, &attrs, &actions, pid);
+  assert(err != ENOSYS);
+
+  /* Destroy the actions/attributes */
+  (void) posix_spawn_file_actions_destroy(&actions);
+  (void) posix_spawnattr_destroy(&attrs);
+
+error:
+  /* In an error situation, the attributes and file actions are
+   * already destroyed, only the happy path requires cleanup */
+  return UV__ERR(err);
+}
+#endif
+
+static int uv__spawn_and_init_child_fork(const uv_process_options_t* options,
+                                         int stdio_count,
+                                         int (*pipes)[2],
+                                         int error_fd,
+                                         pid_t* pid) {
+  sigset_t signewset;
+  sigset_t sigoldset;
+
+  /* Start the child with most signals blocked, to avoid any issues before we
+   * can reset them, but allow program failures to exit (and not hang). */
+  sigfillset(&signewset);
+  sigdelset(&signewset, SIGKILL);
+  sigdelset(&signewset, SIGSTOP);
+  sigdelset(&signewset, SIGTRAP);
+  sigdelset(&signewset, SIGSEGV);
+  sigdelset(&signewset, SIGBUS);
+  sigdelset(&signewset, SIGILL);
+  sigdelset(&signewset, SIGSYS);
+  sigdelset(&signewset, SIGABRT);
+  if (pthread_sigmask(SIG_BLOCK, &signewset, &sigoldset) != 0)
+    abort();
+
+  *pid = fork();
+
+  if (*pid == 0) {
+    /* Fork succeeded, in the child process */
+    uv__process_child_init(options, stdio_count, pipes, error_fd);
+    abort();
+  }
+
+  if (pthread_sigmask(SIG_SETMASK, &sigoldset, NULL) != 0)
+    abort();
+
+  if (*pid == -1)
+    /* Failed to fork */
+    return UV__ERR(errno);
+
+  /* Fork succeeded, in the parent process */
+  return 0;
+}
+
+static int uv__spawn_and_init_child(
+    uv_loop_t* loop,
+    const uv_process_options_t* options,
+    int stdio_count,
+    int (*pipes)[2],
+    pid_t* pid) {
+  int signal_pipe[2] = { -1, -1 };
+  int status;
+  int err;
+  int exec_errorno;
+  ssize_t r;
+
+#if defined(__APPLE__)
+  uv_once(&posix_spawn_init_once, uv__spawn_init_posix_spawn);
+
+  /* Special child process spawn case for macOS Big Sur (11.0) onwards
+   *
+   * Big Sur introduced a significant performance degradation on a call to
+   * fork/exec when the process has many pages mmaped in with MAP_JIT, like, say
+   * a javascript interpreter. Electron-based applications, for example,
+   * are impacted; though the magnitude of the impact depends on how much the
+   * app relies on subprocesses.
+   *
+   * On macOS, though, posix_spawn is implemented in a way that does not
+   * exhibit the problem. This block implements the forking and preparation
+   * logic with posix_spawn and its related primitives. It also takes advantage of
+   * the macOS extension POSIX_SPAWN_CLOEXEC_DEFAULT that makes impossible to
+   * leak descriptors to the child process. */
+  err = uv__spawn_and_init_child_posix_spawn(options,
+                                             stdio_count,
+                                             pipes,
+                                             pid,
+                                             &posix_spawn_fncs);
+
+  /* The posix_spawn flow will return UV_ENOSYS if any of the posix_spawn_x_np
+   * non-standard functions is both _needed_ and _undefined_. In those cases,
+   * default back to the fork/execve strategy. For all other errors, just fail. */
+  if (err != UV_ENOSYS)
+    return err;
+
+#endif
+
+  /* This pipe is used by the parent to wait until
+   * the child has called `execve()`. We need this
+   * to avoid the following race condition:
+   *
+   *    if ((pid = fork()) > 0) {
+   *      kill(pid, SIGTERM);
+   *    }
+   *    else if (pid == 0) {
+   *      execve("/bin/cat", argp, envp);
+   *    }
+   *
+   * The parent sends a signal immediately after forking.
+   * Since the child may not have called `execve()` yet,
+   * there is no telling what process receives the signal,
+   * our fork or /bin/cat.
+   *
+   * To avoid ambiguity, we create a pipe with both ends
+   * marked close-on-exec. Then, after the call to `fork()`,
+   * the parent polls the read end until it EOFs or errors with EPIPE.
+   */
+  err = uv__make_pipe(signal_pipe, 0);
+  if (err)
+    return err;
+
+  /* Acquire write lock to prevent opening new fds in worker threads */
+  uv_rwlock_wrlock(&loop->cloexec_lock);
+
+  err = uv__spawn_and_init_child_fork(options, stdio_count, pipes, signal_pipe[1], pid);
+
+  /* Release lock in parent process */
+  uv_rwlock_wrunlock(&loop->cloexec_lock);
+
+  uv__close(signal_pipe[1]);
+
+  if (err == 0) {
+    do
+      r = read(signal_pipe[0], &exec_errorno, sizeof(exec_errorno));
+    while (r == -1 && errno == EINTR);
+
+    if (r == 0)
+      ; /* okay, EOF */
+    else if (r == sizeof(exec_errorno)) {
+      do
+        err = waitpid(*pid, &status, 0); /* okay, read errorno */
+      while (err == -1 && errno == EINTR);
+      assert(err == *pid);
+      err = exec_errorno;
+    } else if (r == -1 && errno == EPIPE) {
+      /* Something unknown happened to our child before spawn */
+      do
+        err = waitpid(*pid, &status, 0); /* okay, got EPIPE */
+      while (err == -1 && errno == EINTR);
+      assert(err == *pid);
+      err = UV_EPIPE;
+    } else
+      abort();
+  }
+
+  uv__close_nocheckstdio(signal_pipe[0]);
+
+  return err;
+}
+
+int uv_spawn(uv_loop_t* loop,
+             uv_process_t* process,
+             const uv_process_options_t* options) {
+#if defined(__APPLE__) && (TARGET_OS_TV || TARGET_OS_WATCH)
+  /* fork is marked __WATCHOS_PROHIBITED __TVOS_PROHIBITED. */
+  return UV_ENOSYS;
+#else
+  int pipes_storage[8][2];
+  int (*pipes)[2];
+  int stdio_count;
+  pid_t pid;
+  int err;
+  int exec_errorno;
+  int i;
+
+  assert(options->file != NULL);
+  assert(!(options->flags & ~(UV_PROCESS_DETACHED |
+                              UV_PROCESS_SETGID |
+                              UV_PROCESS_SETUID |
+                              UV_PROCESS_WINDOWS_HIDE |
+                              UV_PROCESS_WINDOWS_HIDE_CONSOLE |
+                              UV_PROCESS_WINDOWS_HIDE_GUI |
+                              UV_PROCESS_WINDOWS_VERBATIM_ARGUMENTS)));
+
+  uv__handle_init(loop, (uv_handle_t*)process, UV_PROCESS);
+  QUEUE_INIT(&process->queue);
+  process->status = 0;
+
+  stdio_count = options->stdio_count;
+  if (stdio_count < 3)
+    stdio_count = 3;
+
+  err = UV_ENOMEM;
+  pipes = pipes_storage;
+  if (stdio_count > (int) ARRAY_SIZE(pipes_storage))
+    pipes = (int (*)[2])uv__malloc(stdio_count * sizeof(*pipes));
+
+  if (pipes == NULL)
+    goto error;
+
+  for (i = 0; i < stdio_count; i++) {
+    pipes[i][0] = -1;
+    pipes[i][1] = -1;
+  }
+
+  for (i = 0; i < options->stdio_count; i++) {
+    err = uv__process_init_stdio(options->stdio + i, pipes[i]);
+    if (err)
+      goto error;
+  }
+
+#ifdef UV_USE_SIGCHLD
+  uv_signal_start(&loop->child_watcher, uv__chld, SIGCHLD);
+#endif
+
+  /* Spawn the child */
+  exec_errorno = uv__spawn_and_init_child(loop, options, stdio_count, pipes, &pid);
+
+#if 0
+  /* This runs into a nodejs issue (it expects initialized streams, even if the
+   * exec failed).
+   * See https://github.com/libuv/libuv/pull/3107#issuecomment-782482608 */
+  if (exec_errorno != 0)
+      goto error;
+#endif
+
+  /* Activate this handle if exec() happened successfully, even if we later
+   * fail to open a stdio handle. This ensures we can eventually reap the child
+   * with waitpid. */
+  if (exec_errorno == 0) {
+#ifndef UV_USE_SIGCHLD
+    struct kevent event;
+    EV_SET(&event, pid, EVFILT_PROC, EV_ADD | EV_ONESHOT, NOTE_EXIT, 0, 0);
+    if (kevent(loop->backend_fd, &event, 1, NULL, 0, NULL)) {
+      if (errno != ESRCH)
+        abort();
+      /* Process already exited. Call waitpid on the next loop iteration. */
+      process->flags |= UV_HANDLE_REAP;
+      loop->flags |= UV_LOOP_REAP_CHILDREN;
+    }
+#endif
+
+    process->pid = pid;
+    process->exit_cb = options->exit_cb;
+    QUEUE_INSERT_TAIL(&loop->process_handles, &process->queue);
+    uv__handle_start(process);
+  }
+
+  for (i = 0; i < options->stdio_count; i++) {
+    err = uv__process_open_stream(options->stdio + i, pipes[i]);
+    if (err == 0)
+      continue;
+
+    while (i--)
+      uv__process_close_stream(options->stdio + i);
+
+    goto error;
+  }
+
+  if (pipes != pipes_storage)
+    uv__free(pipes);
+
+  return exec_errorno;
+
+error:
+  if (pipes != NULL) {
+    for (i = 0; i < stdio_count; i++) {
+      if (i < options->stdio_count)
+        if (options->stdio[i].flags & (UV_INHERIT_FD | UV_INHERIT_STREAM))
+          continue;
+      if (pipes[i][0] != -1)
+        uv__close_nocheckstdio(pipes[i][0]);
+      if (pipes[i][1] != -1)
+        uv__close_nocheckstdio(pipes[i][1]);
+    }
+
+    if (pipes != pipes_storage)
+      uv__free(pipes);
+  }
+
+  return err;
+#endif
+}
+
+
+int uv_process_kill(uv_process_t* process, int signum) {
+  return uv_kill(process->pid, signum);
+}
+
+
+int uv_kill(int pid, int signum) {
+  if (kill(pid, signum)) {
+#if defined(__MVS__)
+    /* EPERM is returned if the process is a zombie. */
+    siginfo_t infop;
+    if (errno == EPERM &&
+        waitid(P_PID, pid, &infop, WNOHANG | WNOWAIT | WEXITED) == 0)
+      return 0;
+#endif
+    return UV__ERR(errno);
+  } else
+    return 0;
+}
+
+
+void uv__process_close(uv_process_t* handle) {
+  QUEUE_REMOVE(&handle->queue);
+  uv__handle_stop(handle);
+  if (QUEUE_EMPTY(&handle->loop->process_handles))
+    uv_signal_stop(&handle->loop->child_watcher);
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/procfs-exepath.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/procfs-exepath.cpp
similarity index 100%
rename from third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/procfs-exepath.cpp
rename to third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/procfs-exepath.cpp
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/proctitle.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/proctitle.cpp
new file mode 100644
index 0000000..8cdec75
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/proctitle.cpp
@@ -0,0 +1,157 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <stdlib.h>
+#include <string.h>
+
+struct uv__process_title {
+  char* str;
+  size_t len;  /* Length of the current process title. */
+  size_t cap;  /* Maximum capacity. Computed once in uv_setup_args(). */
+};
+
+extern void uv__set_process_title(const char* title);
+
+static uv_mutex_t process_title_mutex;
+static uv_once_t process_title_mutex_once = UV_ONCE_INIT;
+static struct uv__process_title process_title;
+static void* args_mem;
+
+
+static void init_process_title_mutex_once(void) {
+  uv_mutex_init(&process_title_mutex);
+}
+
+
+char** uv_setup_args(int argc, char** argv) {
+  struct uv__process_title pt;
+  char** new_argv;
+  size_t size;
+  char* s;
+  int i;
+
+  if (argc <= 0)
+    return argv;
+
+  pt.str = argv[0];
+  pt.len = strlen(argv[0]);
+  pt.cap = pt.len + 1;
+
+  /* Calculate how much memory we need for the argv strings. */
+  size = pt.cap;
+  for (i = 1; i < argc; i++)
+    size += strlen(argv[i]) + 1;
+
+  /* Add space for the argv pointers. */
+  size += (argc + 1) * sizeof(char*);
+
+  new_argv = (char**)uv__malloc(size);
+  if (new_argv == NULL)
+    return argv;
+
+  /* Copy over the strings and set up the pointer table. */
+  i = 0;
+  s = (char*) &new_argv[argc + 1];
+  size = pt.cap;
+  goto loop;
+
+  for (/* empty */; i < argc; i++) {
+    size = strlen(argv[i]) + 1;
+  loop:
+    memcpy(s, argv[i], size);
+    new_argv[i] = s;
+    s += size;
+  }
+  new_argv[i] = NULL;
+
+  pt.cap = argv[i - 1] + size - argv[0];
+
+  args_mem = new_argv;
+  process_title = pt;
+
+  return new_argv;
+}
+
+
+int uv_set_process_title(const char* title) {
+  struct uv__process_title* pt;
+  size_t len;
+
+  /* If uv_setup_args wasn't called or failed, we can't continue. */
+  if (args_mem == NULL)
+    return UV_ENOBUFS;
+
+  pt = &process_title;
+  len = strlen(title);
+
+  uv_once(&process_title_mutex_once, init_process_title_mutex_once);
+  uv_mutex_lock(&process_title_mutex);
+
+  if (len >= pt->cap) {
+    len = 0;
+    if (pt->cap > 0)
+      len = pt->cap - 1;
+  }
+
+  memcpy(pt->str, title, len);
+  memset(pt->str + len, '\0', pt->cap - len);
+  pt->len = len;
+  uv__set_process_title(pt->str);
+
+  uv_mutex_unlock(&process_title_mutex);
+
+  return 0;
+}
+
+
+int uv_get_process_title(char* buffer, size_t size) {
+  if (buffer == NULL || size == 0)
+    return UV_EINVAL;
+
+  /* If uv_setup_args wasn't called or failed, we can't continue. */
+  if (args_mem == NULL)
+    return UV_ENOBUFS;
+
+  uv_once(&process_title_mutex_once, init_process_title_mutex_once);
+  uv_mutex_lock(&process_title_mutex);
+
+  if (size <= process_title.len) {
+    uv_mutex_unlock(&process_title_mutex);
+    return UV_ENOBUFS;
+  }
+
+  if (process_title.len != 0)
+    memcpy(buffer, process_title.str, process_title.len + 1);
+
+  buffer[process_title.len] = '\0';
+
+  uv_mutex_unlock(&process_title_mutex);
+
+  return 0;
+}
+
+
+void uv__process_title_cleanup(void) {
+  uv__free(args_mem);  /* Keep valgrind happy. */
+  args_mem = NULL;
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/pthread-fixes.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/pthread-fixes.cpp
new file mode 100644
index 0000000..022d79c
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/pthread-fixes.cpp
@@ -0,0 +1,58 @@
+/* Copyright (c) 2013, Sony Mobile Communications AB
+ * Copyright (c) 2012, Google Inc.
+   All rights reserved.
+
+   Redistribution and use in source and binary forms, with or without
+   modification, are permitted provided that the following conditions are
+   met:
+
+     * Redistributions of source code must retain the above copyright
+   notice, this list of conditions and the following disclaimer.
+       * Redistributions in binary form must reproduce the above
+   copyright notice, this list of conditions and the following disclaimer
+   in the documentation and/or other materials provided with the
+   distribution.
+       * Neither the name of Google Inc. nor the names of its
+   contributors may be used to endorse or promote products derived from
+   this software without specific prior written permission.
+
+   THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+   "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+   LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+   A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+   OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+   SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
+   LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+   DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+   THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+   (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+   OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*/
+
+/* Android versions < 4.1 have a broken pthread_sigmask. */
+#include "uv-common.h"
+
+#include <errno.h>
+#include <pthread.h>
+#include <signal.h>
+
+int uv__pthread_sigmask(int how, const sigset_t* set, sigset_t* oset) {
+  static int workaround;
+  int err;
+
+  if (uv__load_relaxed(&workaround)) {
+    return sigprocmask(how, set, oset);
+  } else {
+    err = pthread_sigmask(how, set, oset);
+    if (err) {
+      if (err == EINVAL && sigprocmask(how, set, oset) == 0) {
+        uv__store_relaxed(&workaround, 1);
+        return 0;
+      } else {
+        return -1;
+      }
+    }
+  }
+
+  return 0;
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/random-devurandom.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/random-devurandom.cpp
new file mode 100644
index 0000000..05e52a5
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/random-devurandom.cpp
@@ -0,0 +1,93 @@
+/* Copyright libuv contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <sys/stat.h>
+#include <unistd.h>
+
+static uv_once_t once = UV_ONCE_INIT;
+static int status;
+
+
+int uv__random_readpath(const char* path, void* buf, size_t buflen) {
+  struct stat s;
+  size_t pos;
+  ssize_t n;
+  int fd;
+
+  fd = uv__open_cloexec(path, O_RDONLY);
+
+  if (fd < 0)
+    return fd;
+
+  if (fstat(fd, &s)) {
+    uv__close(fd);
+    return UV__ERR(errno);
+  }
+
+  if (!S_ISCHR(s.st_mode)) {
+    uv__close(fd);
+    return UV_EIO;
+  }
+
+  for (pos = 0; pos != buflen; pos += n) {
+    do
+      n = read(fd, (char*) buf + pos, buflen - pos);
+    while (n == -1 && errno == EINTR);
+
+    if (n == -1) {
+      uv__close(fd);
+      return UV__ERR(errno);
+    }
+
+    if (n == 0) {
+      uv__close(fd);
+      return UV_EIO;
+    }
+  }
+
+  uv__close(fd);
+  return 0;
+}
+
+
+static void uv__random_devurandom_init(void) {
+  char c;
+
+  /* Linux's random(4) man page suggests applications should read at least
+   * once from /dev/random before switching to /dev/urandom in order to seed
+   * the system RNG. Reads from /dev/random can of course block indefinitely
+   * until entropy is available but that's the point.
+   */
+  status = uv__random_readpath("/dev/random", &c, 1);
+}
+
+
+int uv__random_devurandom(void* buf, size_t buflen) {
+  uv_once(&once, uv__random_devurandom_init);
+
+  if (status != 0)
+    return status;
+
+  return uv__random_readpath("/dev/urandom", buf, buflen);
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/random-getentropy.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/random-getentropy.cpp
new file mode 100644
index 0000000..c45d9fd
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/random-getentropy.cpp
@@ -0,0 +1,57 @@
+/* Copyright libuv contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <stddef.h>
+#include <dlfcn.h>
+
+typedef int (*uv__getentropy_cb)(void *, size_t);
+
+static uv__getentropy_cb uv__getentropy;
+static uv_once_t once = UV_ONCE_INIT;
+
+
+static void uv__random_getentropy_init(void) {
+  uv__getentropy = (uv__getentropy_cb) dlsym(RTLD_DEFAULT, "getentropy");
+}
+
+
+int uv__random_getentropy(void* buf, size_t buflen) {
+  size_t pos;
+  size_t stride;
+
+  uv_once(&once, uv__random_getentropy_init);
+
+  if (uv__getentropy == NULL)
+    return UV_ENOSYS;
+
+  /* getentropy() returns an error for requests > 256 bytes. */
+  for (pos = 0, stride = 256; pos + stride < buflen; pos += stride)
+    if (uv__getentropy((char *) buf + pos, stride))
+      return UV__ERR(errno);
+
+  if (uv__getentropy((char *) buf + pos, buflen - pos))
+    return UV__ERR(errno);
+
+  return 0;
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/random-getrandom.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/random-getrandom.cpp
new file mode 100644
index 0000000..bcc9408
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/random-getrandom.cpp
@@ -0,0 +1,88 @@
+/* Copyright libuv contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#ifdef __linux__
+
+#include "linux-syscalls.h"
+
+#define uv__random_getrandom_init() 0
+
+#else  /* !__linux__ */
+
+#include <stddef.h>
+#include <dlfcn.h>
+
+typedef ssize_t (*uv__getrandom_cb)(void *, size_t, unsigned);
+
+static uv__getrandom_cb uv__getrandom;
+static uv_once_t once = UV_ONCE_INIT;
+
+static void uv__random_getrandom_init_once(void) {
+  uv__getrandom = (uv__getrandom_cb) dlsym(RTLD_DEFAULT, "getrandom");
+}
+
+static int uv__random_getrandom_init(void) {
+  uv_once(&once, uv__random_getrandom_init_once);
+
+  if (uv__getrandom == NULL)
+    return UV_ENOSYS;
+
+  return 0;
+}
+
+#endif  /* !__linux__ */
+
+int uv__random_getrandom(void* buf, size_t buflen) {
+  ssize_t n;
+  size_t pos;
+  int rc;
+
+  rc = uv__random_getrandom_init();
+  if (rc != 0)
+    return rc;
+
+  for (pos = 0; pos != buflen; pos += n) {
+    do {
+      n = buflen - pos;
+
+      /* Most getrandom() implementations promise that reads <= 256 bytes
+       * will always succeed and won't be interrupted by signals.
+       * It's therefore useful to split it up in smaller reads because
+       * one big read may, in theory, continuously fail with EINTR.
+       */
+      if (n > 256)
+        n = 256;
+
+      n = uv__getrandom((char *) buf + pos, n, 0);
+    } while (n == -1 && errno == EINTR);
+
+    if (n == -1)
+      return UV__ERR(errno);
+
+    if (n == 0)
+      return UV_EIO;
+  }
+
+  return 0;
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/random-sysctl-linux.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/random-sysctl-linux.cpp
new file mode 100644
index 0000000..9ef18df
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/random-sysctl-linux.cpp
@@ -0,0 +1,99 @@
+/* Copyright libuv contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <errno.h>
+#include <string.h>
+
+#include <syscall.h>
+#include <unistd.h>
+
+
+struct uv__sysctl_args {
+  int* name;
+  int nlen;
+  void* oldval;
+  size_t* oldlenp;
+  void* newval;
+  size_t newlen;
+  unsigned long unused[4];
+};
+
+
+int uv__random_sysctl(void* buf, size_t buflen) {
+  static int name[] = {1 /*CTL_KERN*/, 40 /*KERN_RANDOM*/, 6 /*RANDOM_UUID*/};
+  struct uv__sysctl_args args;
+  char uuid[16];
+  char* p;
+  char* pe;
+  size_t n;
+
+  p = (char*)buf;
+  pe = p + buflen;
+
+  while (p < pe) {
+    memset(&args, 0, sizeof(args));
+
+    args.name = name;
+    args.nlen = ARRAY_SIZE(name);
+    args.oldval = uuid;
+    args.oldlenp = &n;
+    n = sizeof(uuid);
+
+    /* Emits a deprecation warning with some kernels but that seems like
+     * an okay trade-off for the fallback of the fallback: this function is
+     * only called when neither getrandom(2) nor /dev/urandom are available.
+     * Fails with ENOSYS on kernels configured without CONFIG_SYSCTL_SYSCALL.
+     * At least arm64 never had a _sysctl system call and therefore doesn't
+     * have a SYS__sysctl define either.
+     */
+#ifdef SYS__sysctl
+    if (syscall(SYS__sysctl, &args) == -1)
+      return UV__ERR(errno);
+#else
+    {
+      (void) &args;
+      return UV_ENOSYS;
+    }
+#endif
+
+    if (n != sizeof(uuid))
+      return UV_EIO;  /* Can't happen. */
+
+    /* uuid[] is now a type 4 UUID. Bytes 6 and 8 (counting from zero) contain
+     * 4 and 5 bits of entropy, respectively. For ease of use, we skip those
+     * and only use 14 of the 16 bytes.
+     */
+    uuid[6] = uuid[14];
+    uuid[8] = uuid[15];
+
+    n = pe - p;
+    if (n > 14)
+      n = 14;
+
+    memcpy(p, uuid, n);
+    p += n;
+  }
+
+  return 0;
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/signal.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/signal.cpp
new file mode 100644
index 0000000..1133c73
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/signal.cpp
@@ -0,0 +1,558 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <assert.h>
+#include <errno.h>
+#include <signal.h>
+#include <stdlib.h>
+#include <string.h>
+#include <unistd.h>
+
+#ifndef SA_RESTART
+# define SA_RESTART 0
+#endif
+
+typedef struct {
+  uv_signal_t* handle;
+  int signum;
+} uv__signal_msg_t;
+
+RB_HEAD(uv__signal_tree_s, uv_signal_s);
+
+
+static int uv__signal_unlock(void);
+static int uv__signal_start(uv_signal_t* handle,
+                            uv_signal_cb signal_cb,
+                            int signum,
+                            int oneshot);
+static void uv__signal_event(uv_loop_t* loop, uv__io_t* w, unsigned int events);
+static int uv__signal_compare(uv_signal_t* w1, uv_signal_t* w2);
+static void uv__signal_stop(uv_signal_t* handle);
+static void uv__signal_unregister_handler(int signum);
+
+
+static uv_once_t uv__signal_global_init_guard = UV_ONCE_INIT;
+static struct uv__signal_tree_s uv__signal_tree =
+    RB_INITIALIZER(uv__signal_tree);
+static int uv__signal_lock_pipefd[2] = { -1, -1 };
+
+RB_GENERATE_STATIC(uv__signal_tree_s,
+                   uv_signal_s, tree_entry,
+                   uv__signal_compare)
+
+static void uv__signal_global_reinit(void);
+
+static void uv__signal_global_init(void) {
+  if (uv__signal_lock_pipefd[0] == -1)
+    /* pthread_atfork can register before and after handlers, one
+     * for each child. This only registers one for the child. That
+     * state is both persistent and cumulative, so if we keep doing
+     * it the handler functions will be called multiple times. Thus
+     * we only want to do it once.
+     */
+    if (pthread_atfork(NULL, NULL, &uv__signal_global_reinit))
+      abort();
+
+  uv__signal_global_reinit();
+}
+
+
+void uv__signal_cleanup(void) {
+  /* We can only use signal-safe functions here.
+   * That includes read/write and close, fortunately.
+   * We do all of this directly here instead of resetting
+   * uv__signal_global_init_guard because
+   * uv__signal_global_once_init is only called from uv_loop_init
+   * and this needs to function in existing loops.
+   */
+  if (uv__signal_lock_pipefd[0] != -1) {
+    uv__close(uv__signal_lock_pipefd[0]);
+    uv__signal_lock_pipefd[0] = -1;
+  }
+
+  if (uv__signal_lock_pipefd[1] != -1) {
+    uv__close(uv__signal_lock_pipefd[1]);
+    uv__signal_lock_pipefd[1] = -1;
+  }
+}
+
+
+static void uv__signal_global_reinit(void) {
+  uv__signal_cleanup();
+
+  if (uv__make_pipe(uv__signal_lock_pipefd, 0))
+    abort();
+
+  if (uv__signal_unlock())
+    abort();
+}
+
+
+void uv__signal_global_once_init(void) {
+  uv_once(&uv__signal_global_init_guard, uv__signal_global_init);
+}
+
+
+static int uv__signal_lock(void) {
+  int r;
+  char data;
+
+  do {
+    r = read(uv__signal_lock_pipefd[0], &data, sizeof data);
+  } while (r < 0 && errno == EINTR);
+
+  return (r < 0) ? -1 : 0;
+}
+
+
+static int uv__signal_unlock(void) {
+  int r;
+  char data = 42;
+
+  do {
+    r = write(uv__signal_lock_pipefd[1], &data, sizeof data);
+  } while (r < 0 && errno == EINTR);
+
+  return (r < 0) ? -1 : 0;
+}
+
+
+static void uv__signal_block_and_lock(sigset_t* saved_sigmask) {
+  sigset_t new_mask;
+
+  if (sigfillset(&new_mask))
+    abort();
+
+  /* to shut up valgrind */
+  sigemptyset(saved_sigmask);
+  if (pthread_sigmask(SIG_SETMASK, &new_mask, saved_sigmask))
+    abort();
+
+  if (uv__signal_lock())
+    abort();
+}
+
+
+static void uv__signal_unlock_and_unblock(sigset_t* saved_sigmask) {
+  if (uv__signal_unlock())
+    abort();
+
+  if (pthread_sigmask(SIG_SETMASK, saved_sigmask, NULL))
+    abort();
+}
+
+
+static uv_signal_t* uv__signal_first_handle(int signum) {
+  /* This function must be called with the signal lock held. */
+  uv_signal_t lookup;
+  uv_signal_t* handle;
+
+  lookup.signum = signum;
+  lookup.flags = 0;
+  lookup.loop = NULL;
+
+  handle = RB_NFIND(uv__signal_tree_s, &uv__signal_tree, &lookup);
+
+  if (handle != NULL && handle->signum == signum)
+    return handle;
+
+  return NULL;
+}
+
+
+static void uv__signal_handler(int signum) {
+  uv__signal_msg_t msg;
+  uv_signal_t* handle;
+  int saved_errno;
+
+  saved_errno = errno;
+  memset(&msg, 0, sizeof msg);
+
+  if (uv__signal_lock()) {
+    errno = saved_errno;
+    return;
+  }
+
+  for (handle = uv__signal_first_handle(signum);
+       handle != NULL && handle->signum == signum;
+       handle = RB_NEXT(uv__signal_tree_s, &uv__signal_tree, handle)) {
+    int r;
+
+    msg.signum = signum;
+    msg.handle = handle;
+
+    /* write() should be atomic for small data chunks, so the entire message
+     * should be written at once. In theory the pipe could become full, in
+     * which case the user is out of luck.
+     */
+    do {
+      r = write(handle->loop->signal_pipefd[1], &msg, sizeof msg);
+    } while (r == -1 && errno == EINTR);
+
+    assert(r == sizeof msg ||
+           (r == -1 && (errno == EAGAIN || errno == EWOULDBLOCK)));
+
+    if (r != -1)
+      handle->caught_signals++;
+  }
+
+  uv__signal_unlock();
+  errno = saved_errno;
+}
+
+
+static int uv__signal_register_handler(int signum, int oneshot) {
+  /* When this function is called, the signal lock must be held. */
+  struct sigaction sa;
+
+  /* XXX use a separate signal stack? */
+  memset(&sa, 0, sizeof(sa));
+  if (sigfillset(&sa.sa_mask))
+    abort();
+  sa.sa_handler = uv__signal_handler;
+  sa.sa_flags = SA_RESTART;
+  if (oneshot)
+    sa.sa_flags |= SA_RESETHAND;
+
+  /* XXX save old action so we can restore it later on? */
+  if (sigaction(signum, &sa, NULL))
+    return UV__ERR(errno);
+
+  return 0;
+}
+
+
+static void uv__signal_unregister_handler(int signum) {
+  /* When this function is called, the signal lock must be held. */
+  struct sigaction sa;
+
+  memset(&sa, 0, sizeof(sa));
+  sa.sa_handler = SIG_DFL;
+
+  /* sigaction can only fail with EINVAL or EFAULT; an attempt to deregister a
+   * signal implies that it was successfully registered earlier, so EINVAL
+   * should never happen.
+   */
+  if (sigaction(signum, &sa, NULL))
+    abort();
+}
+
+
+static int uv__signal_loop_once_init(uv_loop_t* loop) {
+  int err;
+
+  /* Return if already initialized. */
+  if (loop->signal_pipefd[0] != -1)
+    return 0;
+
+  err = uv__make_pipe(loop->signal_pipefd, UV_NONBLOCK_PIPE);
+  if (err)
+    return err;
+
+  uv__io_init(&loop->signal_io_watcher,
+              uv__signal_event,
+              loop->signal_pipefd[0]);
+  uv__io_start(loop, &loop->signal_io_watcher, POLLIN);
+
+  return 0;
+}
+
+
+int uv__signal_loop_fork(uv_loop_t* loop) {
+  uv__io_stop(loop, &loop->signal_io_watcher, POLLIN);
+  uv__close(loop->signal_pipefd[0]);
+  uv__close(loop->signal_pipefd[1]);
+  loop->signal_pipefd[0] = -1;
+  loop->signal_pipefd[1] = -1;
+  return uv__signal_loop_once_init(loop);
+}
+
+
+void uv__signal_loop_cleanup(uv_loop_t* loop) {
+  QUEUE* q;
+
+  /* Stop all the signal watchers that are still attached to this loop. This
+   * ensures that the (shared) signal tree doesn't contain any invalid entries
+   * entries, and that signal handlers are removed when appropriate.
+   * It's safe to use QUEUE_FOREACH here because the handles and the handle
+   * queue are not modified by uv__signal_stop().
+   */
+  QUEUE_FOREACH(q, &loop->handle_queue) {
+    uv_handle_t* handle = QUEUE_DATA(q, uv_handle_t, handle_queue);
+
+    if (handle->type == UV_SIGNAL)
+      uv__signal_stop((uv_signal_t*) handle);
+  }
+
+  if (loop->signal_pipefd[0] != -1) {
+    uv__close(loop->signal_pipefd[0]);
+    loop->signal_pipefd[0] = -1;
+  }
+
+  if (loop->signal_pipefd[1] != -1) {
+    uv__close(loop->signal_pipefd[1]);
+    loop->signal_pipefd[1] = -1;
+  }
+}
+
+
+int uv_signal_init(uv_loop_t* loop, uv_signal_t* handle) {
+  int err;
+
+  err = uv__signal_loop_once_init(loop);
+  if (err)
+    return err;
+
+  uv__handle_init(loop, (uv_handle_t*) handle, UV_SIGNAL);
+  handle->signum = 0;
+  handle->caught_signals = 0;
+  handle->dispatched_signals = 0;
+
+  return 0;
+}
+
+
+void uv__signal_close(uv_signal_t* handle) {
+  uv__signal_stop(handle);
+}
+
+
+int uv_signal_start(uv_signal_t* handle, uv_signal_cb signal_cb, int signum) {
+  return uv__signal_start(handle, signal_cb, signum, 0);
+}
+
+
+int uv_signal_start_oneshot(uv_signal_t* handle,
+                            uv_signal_cb signal_cb,
+                            int signum) {
+  return uv__signal_start(handle, signal_cb, signum, 1);
+}
+
+
+static int uv__signal_start(uv_signal_t* handle,
+                            uv_signal_cb signal_cb,
+                            int signum,
+                            int oneshot) {
+  sigset_t saved_sigmask;
+  int err;
+  uv_signal_t* first_handle;
+
+  assert(!uv__is_closing(handle));
+
+  /* If the user supplies signum == 0, then return an error already. If the
+   * signum is otherwise invalid then uv__signal_register will find out
+   * eventually.
+   */
+  if (signum == 0)
+    return UV_EINVAL;
+
+  /* Short circuit: if the signal watcher is already watching {signum} don't
+   * go through the process of deregistering and registering the handler.
+   * Additionally, this avoids pending signals getting lost in the small
+   * time frame that handle->signum == 0.
+   */
+  if (signum == handle->signum) {
+    handle->signal_cb = signal_cb;
+    return 0;
+  }
+
+  /* If the signal handler was already active, stop it first. */
+  if (handle->signum != 0) {
+    uv__signal_stop(handle);
+  }
+
+  uv__signal_block_and_lock(&saved_sigmask);
+
+  /* If at this point there are no active signal watchers for this signum (in
+   * any of the loops), it's time to try and register a handler for it here.
+   * Also in case there's only one-shot handlers and a regular handler comes in.
+   */
+  first_handle = uv__signal_first_handle(signum);
+  if (first_handle == NULL ||
+      (!oneshot && (first_handle->flags & UV_SIGNAL_ONE_SHOT))) {
+    err = uv__signal_register_handler(signum, oneshot);
+    if (err) {
+      /* Registering the signal handler failed. Must be an invalid signal. */
+      uv__signal_unlock_and_unblock(&saved_sigmask);
+      return err;
+    }
+  }
+
+  handle->signum = signum;
+  if (oneshot)
+    handle->flags |= UV_SIGNAL_ONE_SHOT;
+
+  RB_INSERT(uv__signal_tree_s, &uv__signal_tree, handle);
+
+  uv__signal_unlock_and_unblock(&saved_sigmask);
+
+  handle->signal_cb = signal_cb;
+  uv__handle_start(handle);
+
+  return 0;
+}
+
+
+static void uv__signal_event(uv_loop_t* loop,
+                             uv__io_t* w,
+                             unsigned int events) {
+  uv__signal_msg_t* msg;
+  uv_signal_t* handle;
+  char buf[sizeof(uv__signal_msg_t) * 32];
+  size_t bytes, end, i;
+  int r;
+
+  bytes = 0;
+  end = 0;
+
+  do {
+    r = read(loop->signal_pipefd[0], buf + bytes, sizeof(buf) - bytes);
+
+    if (r == -1 && errno == EINTR)
+      continue;
+
+    if (r == -1 && (errno == EAGAIN || errno == EWOULDBLOCK)) {
+      /* If there are bytes in the buffer already (which really is extremely
+       * unlikely if possible at all) we can't exit the function here. We'll
+       * spin until more bytes are read instead.
+       */
+      if (bytes > 0)
+        continue;
+
+      /* Otherwise, there was nothing there. */
+      return;
+    }
+
+    /* Other errors really should never happen. */
+    if (r == -1)
+      abort();
+
+    bytes += r;
+
+    /* `end` is rounded down to a multiple of sizeof(uv__signal_msg_t). */
+    end = (bytes / sizeof(uv__signal_msg_t)) * sizeof(uv__signal_msg_t);
+
+    for (i = 0; i < end; i += sizeof(uv__signal_msg_t)) {
+      msg = (uv__signal_msg_t*) (buf + i);
+      handle = msg->handle;
+
+      if (msg->signum == handle->signum) {
+        assert(!(handle->flags & UV_HANDLE_CLOSING));
+        handle->signal_cb(handle, handle->signum);
+      }
+
+      handle->dispatched_signals++;
+
+      if (handle->flags & UV_SIGNAL_ONE_SHOT)
+        uv__signal_stop(handle);
+    }
+
+    bytes -= end;
+
+    /* If there are any "partial" messages left, move them to the start of the
+     * the buffer, and spin. This should not happen.
+     */
+    if (bytes) {
+      memmove(buf, buf + end, bytes);
+      continue;
+    }
+  } while (end == sizeof buf);
+}
+
+
+static int uv__signal_compare(uv_signal_t* w1, uv_signal_t* w2) {
+  int f1;
+  int f2;
+  /* Compare signums first so all watchers with the same signnum end up
+   * adjacent.
+   */
+  if (w1->signum < w2->signum) return -1;
+  if (w1->signum > w2->signum) return 1;
+
+  /* Handlers without UV_SIGNAL_ONE_SHOT set will come first, so if the first
+   * handler returned is a one-shot handler, the rest will be too.
+   */
+  f1 = w1->flags & UV_SIGNAL_ONE_SHOT;
+  f2 = w2->flags & UV_SIGNAL_ONE_SHOT;
+  if (f1 < f2) return -1;
+  if (f1 > f2) return 1;
+
+  /* Sort by loop pointer, so we can easily look up the first item after
+   * { .signum = x, .loop = NULL }.
+   */
+  if (w1->loop < w2->loop) return -1;
+  if (w1->loop > w2->loop) return 1;
+
+  if (w1 < w2) return -1;
+  if (w1 > w2) return 1;
+
+  return 0;
+}
+
+
+int uv_signal_stop(uv_signal_t* handle) {
+  assert(!uv__is_closing(handle));
+  uv__signal_stop(handle);
+  return 0;
+}
+
+
+static void uv__signal_stop(uv_signal_t* handle) {
+  uv_signal_t* removed_handle;
+  sigset_t saved_sigmask;
+  uv_signal_t* first_handle;
+  int rem_oneshot;
+  int first_oneshot;
+  int ret;
+
+  /* If the watcher wasn't started, this is a no-op. */
+  if (handle->signum == 0)
+    return;
+
+  uv__signal_block_and_lock(&saved_sigmask);
+
+  removed_handle = RB_REMOVE(uv__signal_tree_s, &uv__signal_tree, handle);
+  assert(removed_handle == handle);
+  (void) removed_handle;
+
+  /* Check if there are other active signal watchers observing this signal. If
+   * not, unregister the signal handler.
+   */
+  first_handle = uv__signal_first_handle(handle->signum);
+  if (first_handle == NULL) {
+    uv__signal_unregister_handler(handle->signum);
+  } else {
+    rem_oneshot = handle->flags & UV_SIGNAL_ONE_SHOT;
+    first_oneshot = first_handle->flags & UV_SIGNAL_ONE_SHOT;
+    if (first_oneshot && !rem_oneshot) {
+      ret = uv__signal_register_handler(handle->signum, 1);
+      assert(ret == 0);
+      (void)ret;
+    }
+  }
+
+  uv__signal_unlock_and_unblock(&saved_sigmask);
+
+  handle->signum = 0;
+  uv__handle_stop(handle);
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/spinlock.h b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/spinlock.h
similarity index 100%
rename from third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/spinlock.h
rename to third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/spinlock.h
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/stream.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/stream.cpp
new file mode 100644
index 0000000..fa25812
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/stream.cpp
@@ -0,0 +1,1639 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <assert.h>
+#include <errno.h>
+
+#include <sys/types.h>
+#include <sys/socket.h>
+#include <sys/uio.h>
+#include <sys/un.h>
+#include <unistd.h>
+#include <limits.h> /* IOV_MAX */
+
+#if defined(__APPLE__)
+# include <sys/event.h>
+# include <sys/time.h>
+# include <sys/select.h>
+
+/* Forward declaration */
+typedef struct uv__stream_select_s uv__stream_select_t;
+
+struct uv__stream_select_s {
+  uv_stream_t* stream;
+  uv_thread_t thread;
+  uv_sem_t close_sem;
+  uv_sem_t async_sem;
+  uv_async_t async;
+  int events;
+  int fake_fd;
+  int int_fd;
+  int fd;
+  fd_set* sread;
+  size_t sread_sz;
+  fd_set* swrite;
+  size_t swrite_sz;
+};
+#endif /* defined(__APPLE__) */
+
+static void uv__stream_connect(uv_stream_t*);
+static void uv__write(uv_stream_t* stream);
+static void uv__read(uv_stream_t* stream);
+static void uv__stream_io(uv_loop_t* loop, uv__io_t* w, unsigned int events);
+static void uv__write_callbacks(uv_stream_t* stream);
+static size_t uv__write_req_size(uv_write_t* req);
+static void uv__drain(uv_stream_t* stream);
+
+
+void uv__stream_init(uv_loop_t* loop,
+                     uv_stream_t* stream,
+                     uv_handle_type type) {
+  int err;
+
+  uv__handle_init(loop, (uv_handle_t*)stream, type);
+  stream->read_cb = NULL;
+  stream->alloc_cb = NULL;
+  stream->close_cb = NULL;
+  stream->connection_cb = NULL;
+  stream->connect_req = NULL;
+  stream->shutdown_req = NULL;
+  stream->accepted_fd = -1;
+  stream->queued_fds = NULL;
+  stream->delayed_error = 0;
+  QUEUE_INIT(&stream->write_queue);
+  QUEUE_INIT(&stream->write_completed_queue);
+  stream->write_queue_size = 0;
+
+  if (loop->emfile_fd == -1) {
+    err = uv__open_cloexec("/dev/null", O_RDONLY);
+    if (err < 0)
+        /* In the rare case that "/dev/null" isn't mounted open "/"
+         * instead.
+         */
+        err = uv__open_cloexec("/", O_RDONLY);
+    if (err >= 0)
+      loop->emfile_fd = err;
+  }
+
+#if defined(__APPLE__)
+  stream->select = NULL;
+#endif /* defined(__APPLE_) */
+
+  uv__io_init(&stream->io_watcher, uv__stream_io, -1);
+}
+
+
+static void uv__stream_osx_interrupt_select(uv_stream_t* stream) {
+#if defined(__APPLE__)
+  /* Notify select() thread about state change */
+  uv__stream_select_t* s;
+  int r;
+
+  s = (uv__stream_select_t*)stream->select;
+  if (s == NULL)
+    return;
+
+  /* Interrupt select() loop
+   * NOTE: fake_fd and int_fd are socketpair(), thus writing to one will
+   * emit read event on other side
+   */
+  do
+    r = write(s->fake_fd, "x", 1);
+  while (r == -1 && errno == EINTR);
+
+  assert(r == 1);
+#else  /* !defined(__APPLE__) */
+  /* No-op on any other platform */
+#endif  /* !defined(__APPLE__) */
+}
+
+
+#if defined(__APPLE__)
+static void uv__stream_osx_select(void* arg) {
+  uv_stream_t* stream;
+  uv__stream_select_t* s;
+  char buf[1024];
+  int events;
+  int fd;
+  int r;
+  int max_fd;
+
+  stream = (uv_stream_t*)arg;
+  s = (uv__stream_select_t*)stream->select;
+  fd = s->fd;
+
+  if (fd > s->int_fd)
+    max_fd = fd;
+  else
+    max_fd = s->int_fd;
+
+  for (;;) {
+    /* Terminate on semaphore */
+    if (uv_sem_trywait(&s->close_sem) == 0)
+      break;
+
+    /* Watch fd using select(2) */
+    memset(s->sread, 0, s->sread_sz);
+    memset(s->swrite, 0, s->swrite_sz);
+
+    if (uv__io_active(&stream->io_watcher, POLLIN))
+      FD_SET(fd, s->sread);
+    if (uv__io_active(&stream->io_watcher, POLLOUT))
+      FD_SET(fd, s->swrite);
+    FD_SET(s->int_fd, s->sread);
+
+    /* Wait indefinitely for fd events */
+    r = select(max_fd + 1, s->sread, s->swrite, NULL, NULL);
+    if (r == -1) {
+      if (errno == EINTR)
+        continue;
+
+      /* XXX: Possible?! */
+      abort();
+    }
+
+    /* Ignore timeouts */
+    if (r == 0)
+      continue;
+
+    /* Empty socketpair's buffer in case of interruption */
+    if (FD_ISSET(s->int_fd, s->sread))
+      for (;;) {
+        r = read(s->int_fd, buf, sizeof(buf));
+
+        if (r == sizeof(buf))
+          continue;
+
+        if (r != -1)
+          break;
+
+        if (errno == EAGAIN || errno == EWOULDBLOCK)
+          break;
+
+        if (errno == EINTR)
+          continue;
+
+        abort();
+      }
+
+    /* Handle events */
+    events = 0;
+    if (FD_ISSET(fd, s->sread))
+      events |= POLLIN;
+    if (FD_ISSET(fd, s->swrite))
+      events |= POLLOUT;
+
+    assert(events != 0 || FD_ISSET(s->int_fd, s->sread));
+    if (events != 0) {
+      ACCESS_ONCE(int, s->events) = events;
+
+      uv_async_send(&s->async);
+      uv_sem_wait(&s->async_sem);
+
+      /* Should be processed at this stage */
+      assert((s->events == 0) || (stream->flags & UV_HANDLE_CLOSING));
+    }
+  }
+}
+
+
+static void uv__stream_osx_select_cb(uv_async_t* handle) {
+  uv__stream_select_t* s;
+  uv_stream_t* stream;
+  int events;
+
+  s = container_of(handle, uv__stream_select_t, async);
+  stream = s->stream;
+
+  /* Get and reset stream's events */
+  events = s->events;
+  ACCESS_ONCE(int, s->events) = 0;
+
+  assert(events != 0);
+  assert(events == (events & (POLLIN | POLLOUT)));
+
+  /* Invoke callback on event-loop */
+  if ((events & POLLIN) && uv__io_active(&stream->io_watcher, POLLIN))
+    uv__stream_io(stream->loop, &stream->io_watcher, POLLIN);
+
+  if ((events & POLLOUT) && uv__io_active(&stream->io_watcher, POLLOUT))
+    uv__stream_io(stream->loop, &stream->io_watcher, POLLOUT);
+
+  if (stream->flags & UV_HANDLE_CLOSING)
+    return;
+
+  /* NOTE: It is important to do it here, otherwise `select()` might be called
+   * before the actual `uv__read()`, leading to the blocking syscall
+   */
+  uv_sem_post(&s->async_sem);
+}
+
+
+static void uv__stream_osx_cb_close(uv_handle_t* async) {
+  uv__stream_select_t* s;
+
+  s = container_of(async, uv__stream_select_t, async);
+  uv__free(s);
+}
+
+
+int uv__stream_try_select(uv_stream_t* stream, int* fd) {
+  /*
+   * kqueue doesn't work with some files from /dev mount on osx.
+   * select(2) in separate thread for those fds
+   */
+
+  struct kevent filter[1];
+  struct kevent events[1];
+  struct timespec timeout;
+  uv__stream_select_t* s;
+  int fds[2];
+  int err;
+  int ret;
+  int kq;
+  int old_fd;
+  int max_fd;
+  size_t sread_sz;
+  size_t swrite_sz;
+
+  kq = kqueue();
+  if (kq == -1) {
+    perror("(libuv) kqueue()");
+    return UV__ERR(errno);
+  }
+
+  EV_SET(&filter[0], *fd, EVFILT_READ, EV_ADD | EV_ENABLE, 0, 0, 0);
+
+  /* Use small timeout, because we only want to capture EINVALs */
+  timeout.tv_sec = 0;
+  timeout.tv_nsec = 1;
+
+  do
+    ret = kevent(kq, filter, 1, events, 1, &timeout);
+  while (ret == -1 && errno == EINTR);
+
+  uv__close(kq);
+
+  if (ret == -1)
+    return UV__ERR(errno);
+
+  if (ret == 0 || (events[0].flags & EV_ERROR) == 0 || events[0].data != EINVAL)
+    return 0;
+
+  /* At this point we definitely know that this fd won't work with kqueue */
+
+  /*
+   * Create fds for io watcher and to interrupt the select() loop.
+   * NOTE: do it ahead of malloc below to allocate enough space for fd_sets
+   */
+  if (socketpair(AF_UNIX, SOCK_STREAM, 0, fds))
+    return UV__ERR(errno);
+
+  max_fd = *fd;
+  if (fds[1] > max_fd)
+    max_fd = fds[1];
+
+  sread_sz = ROUND_UP(max_fd + 1, sizeof(uint32_t) * NBBY) / NBBY;
+  swrite_sz = sread_sz;
+
+  s = (uv__stream_select_t*)uv__malloc(sizeof(*s) + sread_sz + swrite_sz);
+  if (s == NULL) {
+    err = UV_ENOMEM;
+    goto failed_malloc;
+  }
+
+  s->events = 0;
+  s->fd = *fd;
+  s->sread = (fd_set*) ((char*) s + sizeof(*s));
+  s->sread_sz = sread_sz;
+  s->swrite = (fd_set*) ((char*) s->sread + sread_sz);
+  s->swrite_sz = swrite_sz;
+
+  err = uv_async_init(stream->loop, &s->async, uv__stream_osx_select_cb);
+  if (err)
+    goto failed_async_init;
+
+  s->async.flags |= UV_HANDLE_INTERNAL;
+  uv__handle_unref(&s->async);
+
+  err = uv_sem_init(&s->close_sem, 0);
+  if (err != 0)
+    goto failed_close_sem_init;
+
+  err = uv_sem_init(&s->async_sem, 0);
+  if (err != 0)
+    goto failed_async_sem_init;
+
+  s->fake_fd = fds[0];
+  s->int_fd = fds[1];
+
+  old_fd = *fd;
+  s->stream = stream;
+  stream->select = s;
+  *fd = s->fake_fd;
+
+  err = uv_thread_create(&s->thread, uv__stream_osx_select, stream);
+  if (err != 0)
+    goto failed_thread_create;
+
+  return 0;
+
+failed_thread_create:
+  s->stream = NULL;
+  stream->select = NULL;
+  *fd = old_fd;
+
+  uv_sem_destroy(&s->async_sem);
+
+failed_async_sem_init:
+  uv_sem_destroy(&s->close_sem);
+
+failed_close_sem_init:
+  uv__close(fds[0]);
+  uv__close(fds[1]);
+  uv_close((uv_handle_t*) &s->async, uv__stream_osx_cb_close);
+  return err;
+
+failed_async_init:
+  uv__free(s);
+
+failed_malloc:
+  uv__close(fds[0]);
+  uv__close(fds[1]);
+
+  return err;
+}
+#endif /* defined(__APPLE__) */
+
+
+int uv__stream_open(uv_stream_t* stream, int fd, int flags) {
+#if defined(__APPLE__)
+  int enable;
+#endif
+
+  if (!(stream->io_watcher.fd == -1 || stream->io_watcher.fd == fd))
+    return UV_EBUSY;
+
+  assert(fd >= 0);
+  stream->flags |= flags;
+
+  if (stream->type == UV_TCP) {
+    if ((stream->flags & UV_HANDLE_TCP_NODELAY) && uv__tcp_nodelay(fd, 1))
+      return UV__ERR(errno);
+
+    /* TODO Use delay the user passed in. */
+    if ((stream->flags & UV_HANDLE_TCP_KEEPALIVE) &&
+        uv__tcp_keepalive(fd, 1, 60)) {
+      return UV__ERR(errno);
+    }
+  }
+
+#if defined(__APPLE__)
+  enable = 1;
+  if (setsockopt(fd, SOL_SOCKET, SO_OOBINLINE, &enable, sizeof(enable)) &&
+      errno != ENOTSOCK &&
+      errno != EINVAL) {
+    return UV__ERR(errno);
+  }
+#endif
+
+  stream->io_watcher.fd = fd;
+
+  return 0;
+}
+
+
+void uv__stream_flush_write_queue(uv_stream_t* stream, int error) {
+  uv_write_t* req;
+  QUEUE* q;
+  while (!QUEUE_EMPTY(&stream->write_queue)) {
+    q = QUEUE_HEAD(&stream->write_queue);
+    QUEUE_REMOVE(q);
+
+    req = QUEUE_DATA(q, uv_write_t, queue);
+    req->error = error;
+
+    QUEUE_INSERT_TAIL(&stream->write_completed_queue, &req->queue);
+  }
+}
+
+
+void uv__stream_destroy(uv_stream_t* stream) {
+  assert(!uv__io_active(&stream->io_watcher, POLLIN | POLLOUT));
+  assert(stream->flags & UV_HANDLE_CLOSED);
+
+  if (stream->connect_req) {
+    uv__req_unregister(stream->loop, stream->connect_req);
+    stream->connect_req->cb(stream->connect_req, UV_ECANCELED);
+    stream->connect_req = NULL;
+  }
+
+  uv__stream_flush_write_queue(stream, UV_ECANCELED);
+  uv__write_callbacks(stream);
+  uv__drain(stream);
+
+  assert(stream->write_queue_size == 0);
+}
+
+
+/* Implements a best effort approach to mitigating accept() EMFILE errors.
+ * We have a spare file descriptor stashed away that we close to get below
+ * the EMFILE limit. Next, we accept all pending connections and close them
+ * immediately to signal the clients that we're overloaded - and we are, but
+ * we still keep on trucking.
+ *
+ * There is one caveat: it's not reliable in a multi-threaded environment.
+ * The file descriptor limit is per process. Our party trick fails if another
+ * thread opens a file or creates a socket in the time window between us
+ * calling close() and accept().
+ */
+static int uv__emfile_trick(uv_loop_t* loop, int accept_fd) {
+  int err;
+  int emfile_fd;
+
+  if (loop->emfile_fd == -1)
+    return UV_EMFILE;
+
+  uv__close(loop->emfile_fd);
+  loop->emfile_fd = -1;
+
+  do {
+    err = uv__accept(accept_fd);
+    if (err >= 0)
+      uv__close(err);
+  } while (err >= 0 || err == UV_EINTR);
+
+  emfile_fd = uv__open_cloexec("/", O_RDONLY);
+  if (emfile_fd >= 0)
+    loop->emfile_fd = emfile_fd;
+
+  return err;
+}
+
+
+#if defined(UV_HAVE_KQUEUE)
+# define UV_DEC_BACKLOG(w) w->rcount--;
+#else
+# define UV_DEC_BACKLOG(w) /* no-op */
+#endif /* defined(UV_HAVE_KQUEUE) */
+
+
+void uv__server_io(uv_loop_t* loop, uv__io_t* w, unsigned int events) {
+  uv_stream_t* stream;
+  int err;
+
+  stream = container_of(w, uv_stream_t, io_watcher);
+  assert(events & POLLIN);
+  assert(stream->accepted_fd == -1);
+  assert(!(stream->flags & UV_HANDLE_CLOSING));
+
+  uv__io_start(stream->loop, &stream->io_watcher, POLLIN);
+
+  /* connection_cb can close the server socket while we're
+   * in the loop so check it on each iteration.
+   */
+  while (uv__stream_fd(stream) != -1) {
+    assert(stream->accepted_fd == -1);
+
+#if defined(UV_HAVE_KQUEUE)
+    if (w->rcount <= 0)
+      return;
+#endif /* defined(UV_HAVE_KQUEUE) */
+
+    err = uv__accept(uv__stream_fd(stream));
+    if (err < 0) {
+      if (err == UV_EAGAIN || err == UV__ERR(EWOULDBLOCK))
+        return;  /* Not an error. */
+
+      if (err == UV_ECONNABORTED)
+        continue;  /* Ignore. Nothing we can do about that. */
+
+      if (err == UV_EMFILE || err == UV_ENFILE) {
+        err = uv__emfile_trick(loop, uv__stream_fd(stream));
+        if (err == UV_EAGAIN || err == UV__ERR(EWOULDBLOCK))
+          break;
+      }
+
+      stream->connection_cb(stream, err);
+      continue;
+    }
+
+    UV_DEC_BACKLOG(w)
+    stream->accepted_fd = err;
+    stream->connection_cb(stream, 0);
+
+    if (stream->accepted_fd != -1) {
+      /* The user hasn't yet accepted called uv_accept() */
+      uv__io_stop(loop, &stream->io_watcher, POLLIN);
+      return;
+    }
+
+    if (stream->type == UV_TCP &&
+        (stream->flags & UV_HANDLE_TCP_SINGLE_ACCEPT)) {
+      /* Give other processes a chance to accept connections. */
+      struct timespec timeout = { 0, 1 };
+      nanosleep(&timeout, NULL);
+    }
+  }
+}
+
+
+#undef UV_DEC_BACKLOG
+
+
+int uv_accept(uv_stream_t* server, uv_stream_t* client) {
+  int err;
+
+  assert(server->loop == client->loop);
+
+  if (server->accepted_fd == -1)
+    return UV_EAGAIN;
+
+  switch (client->type) {
+    case UV_NAMED_PIPE:
+    case UV_TCP:
+      err = uv__stream_open(client,
+                            server->accepted_fd,
+                            UV_HANDLE_READABLE | UV_HANDLE_WRITABLE);
+      if (err) {
+        /* TODO handle error */
+        uv__close(server->accepted_fd);
+        goto done;
+      }
+      break;
+
+    case UV_UDP:
+      err = uv_udp_open((uv_udp_t*) client, server->accepted_fd);
+      if (err) {
+        uv__close(server->accepted_fd);
+        goto done;
+      }
+      break;
+
+    default:
+      return UV_EINVAL;
+  }
+
+  client->flags |= UV_HANDLE_BOUND;
+
+done:
+  /* Process queued fds */
+  if (server->queued_fds != NULL) {
+    uv__stream_queued_fds_t* queued_fds;
+
+    queued_fds = (uv__stream_queued_fds_t*)(server->queued_fds);
+
+    /* Read first */
+    server->accepted_fd = queued_fds->fds[0];
+
+    /* All read, free */
+    assert(queued_fds->offset > 0);
+    if (--queued_fds->offset == 0) {
+      uv__free(queued_fds);
+      server->queued_fds = NULL;
+    } else {
+      /* Shift rest */
+      memmove(queued_fds->fds,
+              queued_fds->fds + 1,
+              queued_fds->offset * sizeof(*queued_fds->fds));
+    }
+  } else {
+    server->accepted_fd = -1;
+    if (err == 0)
+      uv__io_start(server->loop, &server->io_watcher, POLLIN);
+  }
+  return err;
+}
+
+
+int uv_listen(uv_stream_t* stream, int backlog, uv_connection_cb cb) {
+  int err;
+  if (uv__is_closing(stream)) {
+    return UV_EINVAL;
+  }
+  switch (stream->type) {
+  case UV_TCP:
+    err = uv__tcp_listen((uv_tcp_t*)stream, backlog, cb);
+    break;
+
+  case UV_NAMED_PIPE:
+    err = uv__pipe_listen((uv_pipe_t*)stream, backlog, cb);
+    break;
+
+  default:
+    err = UV_EINVAL;
+  }
+
+  if (err == 0)
+    uv__handle_start(stream);
+
+  return err;
+}
+
+
+static void uv__drain(uv_stream_t* stream) {
+  uv_shutdown_t* req;
+  int err;
+
+  assert(QUEUE_EMPTY(&stream->write_queue));
+  if (!(stream->flags & UV_HANDLE_CLOSING)) {
+    uv__io_stop(stream->loop, &stream->io_watcher, POLLOUT);
+    uv__stream_osx_interrupt_select(stream);
+  }
+
+  if (!(stream->flags & UV_HANDLE_SHUTTING))
+    return;
+
+  req = stream->shutdown_req;
+  assert(req);
+
+  if ((stream->flags & UV_HANDLE_CLOSING) ||
+      !(stream->flags & UV_HANDLE_SHUT)) {
+    stream->shutdown_req = NULL;
+    stream->flags &= ~UV_HANDLE_SHUTTING;
+    uv__req_unregister(stream->loop, req);
+
+    err = 0;
+    if (stream->flags & UV_HANDLE_CLOSING)
+      /* The user destroyed the stream before we got to do the shutdown. */
+      err = UV_ECANCELED;
+    else if (shutdown(uv__stream_fd(stream), SHUT_WR))
+      err = UV__ERR(errno);
+    else /* Success. */
+      stream->flags |= UV_HANDLE_SHUT;
+
+    if (req->cb != NULL)
+      req->cb(req, err);
+  }
+}
+
+
+static ssize_t uv__writev(int fd, struct iovec* vec, size_t n) {
+  if (n == 1)
+    return write(fd, vec->iov_base, vec->iov_len);
+  else
+    return writev(fd, vec, n);
+}
+
+
+static size_t uv__write_req_size(uv_write_t* req) {
+  size_t size;
+
+  assert(req->bufs != NULL);
+  size = uv__count_bufs(req->bufs + req->write_index,
+                        req->nbufs - req->write_index);
+  assert(req->handle->write_queue_size >= size);
+
+  return size;
+}
+
+
+/* Returns 1 if all write request data has been written, or 0 if there is still
+ * more data to write.
+ *
+ * Note: the return value only says something about the *current* request.
+ * There may still be other write requests sitting in the queue.
+ */
+static int uv__write_req_update(uv_stream_t* stream,
+                                uv_write_t* req,
+                                size_t n) {
+  uv_buf_t* buf;
+  size_t len;
+
+  assert(n <= stream->write_queue_size);
+  stream->write_queue_size -= n;
+
+  buf = req->bufs + req->write_index;
+
+  do {
+    len = n < buf->len ? n : buf->len;
+    buf->base += len;
+    buf->len -= len;
+    buf += (buf->len == 0);  /* Advance to next buffer if this one is empty. */
+    n -= len;
+  } while (n > 0);
+
+  req->write_index = buf - req->bufs;
+
+  return req->write_index == req->nbufs;
+}
+
+
+static void uv__write_req_finish(uv_write_t* req) {
+  uv_stream_t* stream = req->handle;
+
+  /* Pop the req off tcp->write_queue. */
+  QUEUE_REMOVE(&req->queue);
+
+  /* Only free when there was no error. On error, we touch up write_queue_size
+   * right before making the callback. The reason we don't do that right away
+   * is that a write_queue_size > 0 is our only way to signal to the user that
+   * they should stop writing - which they should if we got an error. Something
+   * to revisit in future revisions of the libuv API.
+   */
+  if (req->error == 0) {
+    if (req->bufs != req->bufsml)
+      uv__free(req->bufs);
+    req->bufs = NULL;
+  }
+
+  /* Add it to the write_completed_queue where it will have its
+   * callback called in the near future.
+   */
+  QUEUE_INSERT_TAIL(&stream->write_completed_queue, &req->queue);
+  uv__io_feed(stream->loop, &stream->io_watcher);
+}
+
+
+static int uv__handle_fd(uv_handle_t* handle) {
+  switch (handle->type) {
+    case UV_NAMED_PIPE:
+    case UV_TCP:
+      return ((uv_stream_t*) handle)->io_watcher.fd;
+
+    case UV_UDP:
+      return ((uv_udp_t*) handle)->io_watcher.fd;
+
+    default:
+      return -1;
+  }
+}
+
+static int uv__try_write(uv_stream_t* stream,
+                         const uv_buf_t bufs[],
+                         unsigned int nbufs,
+                         uv_stream_t* send_handle) {
+  struct iovec* iov;
+  int iovmax;
+  int iovcnt;
+  ssize_t n;
+
+  /*
+   * Cast to iovec. We had to have our own uv_buf_t instead of iovec
+   * because Windows's WSABUF is not an iovec.
+   */
+  iov = (struct iovec*) bufs;
+  iovcnt = nbufs;
+
+  iovmax = uv__getiovmax();
+
+  /* Limit iov count to avoid EINVALs from writev() */
+  if (iovcnt > iovmax)
+    iovcnt = iovmax;
+
+  /*
+   * Now do the actual writev. Note that we've been updating the pointers
+   * inside the iov each time we write. So there is no need to offset it.
+   */
+  if (send_handle != NULL) {
+    int fd_to_send;
+    struct msghdr msg;
+    struct cmsghdr *cmsg;
+    union {
+      char data[64];
+      struct cmsghdr alias;
+    } scratch;
+
+    if (uv__is_closing(send_handle))
+      return UV_EBADF;
+
+    fd_to_send = uv__handle_fd((uv_handle_t*) send_handle);
+
+    memset(&scratch, 0, sizeof(scratch));
+
+    assert(fd_to_send >= 0);
+
+    msg.msg_name = NULL;
+    msg.msg_namelen = 0;
+    msg.msg_iov = iov;
+    msg.msg_iovlen = iovcnt;
+    msg.msg_flags = 0;
+
+    msg.msg_control = &scratch.alias;
+    msg.msg_controllen = CMSG_SPACE(sizeof(fd_to_send));
+
+    cmsg = CMSG_FIRSTHDR(&msg);
+    cmsg->cmsg_level = SOL_SOCKET;
+    cmsg->cmsg_type = SCM_RIGHTS;
+    cmsg->cmsg_len = CMSG_LEN(sizeof(fd_to_send));
+
+    /* silence aliasing warning */
+    {
+      void* pv = CMSG_DATA(cmsg);
+      int* pi = (int*)pv;
+      *pi = fd_to_send;
+    }
+
+    do
+      n = sendmsg(uv__stream_fd(stream), &msg, 0);
+    while (n == -1 && errno == EINTR);
+  } else {
+    do
+      n = uv__writev(uv__stream_fd(stream), iov, iovcnt);
+    while (n == -1 && errno == EINTR);
+  }
+
+  if (n >= 0)
+    return n;
+
+  if (errno == EAGAIN || errno == EWOULDBLOCK || errno == ENOBUFS)
+    return UV_EAGAIN;
+
+#ifdef __APPLE__
+  /* macOS versions 10.10 and 10.15 - and presumbaly 10.11 to 10.14, too -
+   * have a bug where a race condition causes the kernel to return EPROTOTYPE
+   * because the socket isn't fully constructed. It's probably the result of
+   * the peer closing the connection and that is why libuv translates it to
+   * ECONNRESET. Previously, libuv retried until the EPROTOTYPE error went
+   * away but some VPN software causes the same behavior except the error is
+   * permanent, not transient, turning the retry mechanism into an infinite
+   * loop. See https://github.com/libuv/libuv/pull/482.
+   */
+  if (errno == EPROTOTYPE)
+    return UV_ECONNRESET;
+#endif  /* __APPLE__ */
+
+  return UV__ERR(errno);
+}
+
+static void uv__write(uv_stream_t* stream) {
+  QUEUE* q;
+  uv_write_t* req;
+  ssize_t n;
+
+  assert(uv__stream_fd(stream) >= 0);
+
+  for (;;) {
+    if (QUEUE_EMPTY(&stream->write_queue))
+      return;
+
+    q = QUEUE_HEAD(&stream->write_queue);
+    req = QUEUE_DATA(q, uv_write_t, queue);
+    assert(req->handle == stream);
+
+    n = uv__try_write(stream,
+                      &(req->bufs[req->write_index]),
+                      req->nbufs - req->write_index,
+                      req->send_handle);
+
+    /* Ensure the handle isn't sent again in case this is a partial write. */
+    if (n >= 0) {
+      req->send_handle = NULL;
+      if (uv__write_req_update(stream, req, n)) {
+        uv__write_req_finish(req);
+        return;  /* TODO(bnoordhuis) Start trying to write the next request. */
+      }
+    } else if (n != UV_EAGAIN)
+      break;
+
+    /* If this is a blocking stream, try again. */
+    if (stream->flags & UV_HANDLE_BLOCKING_WRITES)
+      continue;
+
+    /* We're not done. */
+    uv__io_start(stream->loop, &stream->io_watcher, POLLOUT);
+
+    /* Notify select() thread about state change */
+    uv__stream_osx_interrupt_select(stream);
+
+    return;
+  }
+
+  req->error = n;
+  uv__write_req_finish(req);
+  uv__io_stop(stream->loop, &stream->io_watcher, POLLOUT);
+  uv__stream_osx_interrupt_select(stream);
+}
+
+
+static void uv__write_callbacks(uv_stream_t* stream) {
+  uv_write_t* req;
+  QUEUE* q;
+  QUEUE pq;
+
+  if (QUEUE_EMPTY(&stream->write_completed_queue))
+    return;
+
+// FIXME: GCC 12.1 gives a possibly real warning, but we don't know how to fix
+// it
+#if __GNUC__ >= 12
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Wdangling-pointer="
+#endif  // __GNUC__ >= 12
+  QUEUE_MOVE(&stream->write_completed_queue, &pq);
+#if __GNUC__ >= 12
+#pragma GCC diagnostic pop
+#endif  // __GNUC__ >= 12
+
+  while (!QUEUE_EMPTY(&pq)) {
+    /* Pop a req off write_completed_queue. */
+    q = QUEUE_HEAD(&pq);
+    req = QUEUE_DATA(q, uv_write_t, queue);
+    QUEUE_REMOVE(q);
+    uv__req_unregister(stream->loop, req);
+
+    if (req->bufs != NULL) {
+      stream->write_queue_size -= uv__write_req_size(req);
+      if (req->bufs != req->bufsml)
+        uv__free(req->bufs);
+      req->bufs = NULL;
+    }
+
+    /* NOTE: call callback AFTER freeing the request data. */
+    if (req->cb)
+      req->cb(req, req->error);
+  }
+}
+
+
+static void uv__stream_eof(uv_stream_t* stream, const uv_buf_t* buf) {
+  stream->flags |= UV_HANDLE_READ_EOF;
+  stream->flags &= ~UV_HANDLE_READING;
+  uv__io_stop(stream->loop, &stream->io_watcher, POLLIN);
+  uv__handle_stop(stream);
+  uv__stream_osx_interrupt_select(stream);
+  stream->read_cb(stream, UV_EOF, buf);
+}
+
+
+static int uv__stream_queue_fd(uv_stream_t* stream, int fd) {
+  uv__stream_queued_fds_t* queued_fds;
+  unsigned int queue_size;
+
+  queued_fds = (uv__stream_queued_fds_t*)stream->queued_fds;
+  if (queued_fds == NULL) {
+    queue_size = 8;
+    queued_fds = (uv__stream_queued_fds_t*)
+        uv__malloc((queue_size - 1) * sizeof(*queued_fds->fds) +
+                   sizeof(*queued_fds));
+    if (queued_fds == NULL)
+      return UV_ENOMEM;
+    queued_fds->size = queue_size;
+    queued_fds->offset = 0;
+    stream->queued_fds = queued_fds;
+
+    /* Grow */
+  } else if (queued_fds->size == queued_fds->offset) {
+    queue_size = queued_fds->size + 8;
+    queued_fds = (uv__stream_queued_fds_t*)
+        uv__realloc(queued_fds, (queue_size - 1) * sizeof(*queued_fds->fds) +
+                    sizeof(*queued_fds));
+
+    /*
+     * Allocation failure, report back.
+     * NOTE: if it is fatal - sockets will be closed in uv__stream_close
+     */
+    if (queued_fds == NULL)
+      return UV_ENOMEM;
+    queued_fds->size = queue_size;
+    stream->queued_fds = queued_fds;
+  }
+
+  /* Put fd in a queue */
+  queued_fds->fds[queued_fds->offset++] = fd;
+
+  return 0;
+}
+
+
+#if defined(__PASE__)
+/* on IBMi PASE the control message length can not exceed 256. */
+# define UV__CMSG_FD_COUNT 60
+#else
+# define UV__CMSG_FD_COUNT 64
+#endif
+#define UV__CMSG_FD_SIZE (UV__CMSG_FD_COUNT * sizeof(int))
+
+
+static int uv__stream_recv_cmsg(uv_stream_t* stream, struct msghdr* msg) {
+  struct cmsghdr* cmsg;
+
+  for (cmsg = CMSG_FIRSTHDR(msg); cmsg != NULL; cmsg = CMSG_NXTHDR(msg, cmsg)) {
+    char* start;
+    char* end;
+    int err;
+    void* pv;
+    int* pi;
+    unsigned int i;
+    unsigned int count;
+
+    if (cmsg->cmsg_type != SCM_RIGHTS) {
+      fprintf(stderr, "ignoring non-SCM_RIGHTS ancillary data: %d\n",
+          cmsg->cmsg_type);
+      continue;
+    }
+
+    /* silence aliasing warning */
+    pv = CMSG_DATA(cmsg);
+    pi = (int*)pv;
+
+    /* Count available fds */
+    start = (char*) cmsg;
+    end = (char*) cmsg + cmsg->cmsg_len;
+    count = 0;
+    while (start + CMSG_LEN(count * sizeof(*pi)) < end)
+      count++;
+    assert(start + CMSG_LEN(count * sizeof(*pi)) == end);
+
+    for (i = 0; i < count; i++) {
+      /* Already has accepted fd, queue now */
+      if (stream->accepted_fd != -1) {
+        err = uv__stream_queue_fd(stream, pi[i]);
+        if (err != 0) {
+          /* Close rest */
+          for (; i < count; i++)
+            uv__close(pi[i]);
+          return err;
+        }
+      } else {
+        stream->accepted_fd = pi[i];
+      }
+    }
+  }
+
+  return 0;
+}
+
+
+#ifdef __clang__
+# pragma clang diagnostic push
+# pragma clang diagnostic ignored "-Wgnu-folding-constant"
+# pragma clang diagnostic ignored "-Wvla-extension"
+#endif
+
+static void uv__read(uv_stream_t* stream) {
+  uv_buf_t buf;
+  ssize_t nread;
+  struct msghdr msg;
+  char cmsg_space[CMSG_SPACE(UV__CMSG_FD_SIZE)];
+  int count;
+  int err;
+  int is_ipc;
+
+  stream->flags &= ~UV_HANDLE_READ_PARTIAL;
+
+  /* Prevent loop starvation when the data comes in as fast as (or faster than)
+   * we can read it. XXX Need to rearm fd if we switch to edge-triggered I/O.
+   */
+  count = 32;
+
+  is_ipc = stream->type == UV_NAMED_PIPE && ((uv_pipe_t*) stream)->ipc;
+
+  /* XXX: Maybe instead of having UV_HANDLE_READING we just test if
+   * tcp->read_cb is NULL or not?
+   */
+  while (stream->read_cb
+      && (stream->flags & UV_HANDLE_READING)
+      && (count-- > 0)) {
+    assert(stream->alloc_cb != NULL);
+
+    buf = uv_buf_init(NULL, 0);
+    stream->alloc_cb((uv_handle_t*)stream, 64 * 1024, &buf);
+    if (buf.base == NULL || buf.len == 0) {
+      /* User indicates it can't or won't handle the read. */
+      stream->read_cb(stream, UV_ENOBUFS, &buf);
+      return;
+    }
+
+    assert(buf.base != NULL);
+    assert(uv__stream_fd(stream) >= 0);
+
+    if (!is_ipc) {
+      do {
+        nread = read(uv__stream_fd(stream), buf.base, buf.len);
+      }
+      while (nread < 0 && errno == EINTR);
+    } else {
+      /* ipc uses recvmsg */
+      msg.msg_flags = 0;
+      msg.msg_iov = (struct iovec*) &buf;
+      msg.msg_iovlen = 1;
+      msg.msg_name = NULL;
+      msg.msg_namelen = 0;
+      /* Set up to receive a descriptor even if one isn't in the message */
+      msg.msg_controllen = sizeof(cmsg_space);
+      msg.msg_control = cmsg_space;
+
+      do {
+        nread = uv__recvmsg(uv__stream_fd(stream), &msg, 0);
+      }
+      while (nread < 0 && errno == EINTR);
+    }
+
+    if (nread < 0) {
+      /* Error */
+      if (errno == EAGAIN || errno == EWOULDBLOCK) {
+        /* Wait for the next one. */
+        if (stream->flags & UV_HANDLE_READING) {
+          uv__io_start(stream->loop, &stream->io_watcher, POLLIN);
+          uv__stream_osx_interrupt_select(stream);
+        }
+        stream->read_cb(stream, 0, &buf);
+#if defined(__CYGWIN__) || defined(__MSYS__)
+      } else if (errno == ECONNRESET && stream->type == UV_NAMED_PIPE) {
+        uv__stream_eof(stream, &buf);
+        return;
+#endif
+      } else {
+        /* Error. User should call uv_close(). */
+        stream->flags &= ~(UV_HANDLE_READABLE | UV_HANDLE_WRITABLE);
+        stream->read_cb(stream, UV__ERR(errno), &buf);
+        if (stream->flags & UV_HANDLE_READING) {
+          stream->flags &= ~UV_HANDLE_READING;
+          uv__io_stop(stream->loop, &stream->io_watcher, POLLIN);
+          uv__handle_stop(stream);
+          uv__stream_osx_interrupt_select(stream);
+        }
+      }
+      return;
+    } else if (nread == 0) {
+      uv__stream_eof(stream, &buf);
+      return;
+    } else {
+      /* Successful read */
+      ssize_t buflen = buf.len;
+
+      if (is_ipc) {
+        err = uv__stream_recv_cmsg(stream, &msg);
+        if (err != 0) {
+          stream->read_cb(stream, err, &buf);
+          return;
+        }
+      }
+
+#if defined(__MVS__)
+      if (is_ipc && msg.msg_controllen > 0) {
+        uv_buf_t blankbuf;
+        int nread;
+        struct iovec *old;
+
+        blankbuf.base = 0;
+        blankbuf.len = 0;
+        old = msg.msg_iov;
+        msg.msg_iov = (struct iovec*) &blankbuf;
+        nread = 0;
+        do {
+          nread = uv__recvmsg(uv__stream_fd(stream), &msg, 0);
+          err = uv__stream_recv_cmsg(stream, &msg);
+          if (err != 0) {
+            stream->read_cb(stream, err, &buf);
+            msg.msg_iov = old;
+            return;
+          }
+        } while (nread == 0 && msg.msg_controllen > 0);
+        msg.msg_iov = old;
+      }
+#endif
+      stream->read_cb(stream, nread, &buf);
+
+      /* Return if we didn't fill the buffer, there is no more data to read. */
+      if (nread < buflen) {
+        stream->flags |= UV_HANDLE_READ_PARTIAL;
+        return;
+      }
+    }
+  }
+}
+
+
+#ifdef __clang__
+# pragma clang diagnostic pop
+#endif
+
+#undef UV__CMSG_FD_COUNT
+#undef UV__CMSG_FD_SIZE
+
+
+int uv_shutdown(uv_shutdown_t* req, uv_stream_t* stream, uv_shutdown_cb cb) {
+  assert(stream->type == UV_TCP ||
+         stream->type == UV_TTY ||
+         stream->type == UV_NAMED_PIPE);
+
+  if (!(stream->flags & UV_HANDLE_WRITABLE) ||
+      stream->flags & UV_HANDLE_SHUT ||
+      stream->flags & UV_HANDLE_SHUTTING ||
+      uv__is_closing(stream)) {
+    return UV_ENOTCONN;
+  }
+
+  assert(uv__stream_fd(stream) >= 0);
+
+  /* Initialize request. The `shutdown(2)` call will always be deferred until
+   * `uv__drain`, just before the callback is run. */
+  uv__req_init(stream->loop, req, UV_SHUTDOWN);
+  req->handle = stream;
+  req->cb = cb;
+  stream->shutdown_req = req;
+  stream->flags |= UV_HANDLE_SHUTTING;
+  stream->flags &= ~UV_HANDLE_WRITABLE;
+
+  if (QUEUE_EMPTY(&stream->write_queue))
+    uv__io_feed(stream->loop, &stream->io_watcher);
+
+  return 0;
+}
+
+
+static void uv__stream_io(uv_loop_t* loop, uv__io_t* w, unsigned int events) {
+  uv_stream_t* stream;
+
+  stream = container_of(w, uv_stream_t, io_watcher);
+
+  assert(stream->type == UV_TCP ||
+         stream->type == UV_NAMED_PIPE ||
+         stream->type == UV_TTY);
+  assert(!(stream->flags & UV_HANDLE_CLOSING));
+
+  if (stream->connect_req) {
+    uv__stream_connect(stream);
+    return;
+  }
+
+  assert(uv__stream_fd(stream) >= 0);
+
+  /* Ignore POLLHUP here. Even if it's set, there may still be data to read. */
+  if (events & (POLLIN | POLLERR | POLLHUP))
+    uv__read(stream);
+
+  if (uv__stream_fd(stream) == -1)
+    return;  /* read_cb closed stream. */
+
+  /* Short-circuit iff POLLHUP is set, the user is still interested in read
+   * events and uv__read() reported a partial read but not EOF. If the EOF
+   * flag is set, uv__read() called read_cb with err=UV_EOF and we don't
+   * have to do anything. If the partial read flag is not set, we can't
+   * report the EOF yet because there is still data to read.
+   */
+  if ((events & POLLHUP) &&
+      (stream->flags & UV_HANDLE_READING) &&
+      (stream->flags & UV_HANDLE_READ_PARTIAL) &&
+      !(stream->flags & UV_HANDLE_READ_EOF)) {
+    uv_buf_t buf = { NULL, 0 };
+    uv__stream_eof(stream, &buf);
+  }
+
+  if (uv__stream_fd(stream) == -1)
+    return;  /* read_cb closed stream. */
+
+  if (events & (POLLOUT | POLLERR | POLLHUP)) {
+    uv__write(stream);
+    uv__write_callbacks(stream);
+
+    /* Write queue drained. */
+    if (QUEUE_EMPTY(&stream->write_queue))
+      uv__drain(stream);
+  }
+}
+
+
+/**
+ * We get called here from directly following a call to connect(2).
+ * In order to determine if we've errored out or succeeded must call
+ * getsockopt.
+ */
+static void uv__stream_connect(uv_stream_t* stream) {
+  int error;
+  uv_connect_t* req = stream->connect_req;
+  socklen_t errorsize = sizeof(int);
+
+  assert(stream->type == UV_TCP || stream->type == UV_NAMED_PIPE);
+  assert(req);
+
+  if (stream->delayed_error) {
+    /* To smooth over the differences between unixes errors that
+     * were reported synchronously on the first connect can be delayed
+     * until the next tick--which is now.
+     */
+    error = stream->delayed_error;
+    stream->delayed_error = 0;
+  } else {
+    /* Normal situation: we need to get the socket error from the kernel. */
+    assert(uv__stream_fd(stream) >= 0);
+    getsockopt(uv__stream_fd(stream),
+               SOL_SOCKET,
+               SO_ERROR,
+               &error,
+               &errorsize);
+    error = UV__ERR(error);
+  }
+
+  if (error == UV__ERR(EINPROGRESS))
+    return;
+
+  stream->connect_req = NULL;
+  uv__req_unregister(stream->loop, req);
+
+  if (error < 0 || QUEUE_EMPTY(&stream->write_queue)) {
+    uv__io_stop(stream->loop, &stream->io_watcher, POLLOUT);
+  }
+
+  if (req->cb)
+    req->cb(req, error);
+
+  if (uv__stream_fd(stream) == -1)
+    return;
+
+  if (error < 0) {
+    uv__stream_flush_write_queue(stream, UV_ECANCELED);
+    uv__write_callbacks(stream);
+  }
+}
+
+
+static int uv__check_before_write(uv_stream_t* stream,
+                                  unsigned int nbufs,
+                                  uv_stream_t* send_handle) {
+  assert(nbufs > 0);
+  assert((stream->type == UV_TCP ||
+          stream->type == UV_NAMED_PIPE ||
+          stream->type == UV_TTY) &&
+         "uv_write (unix) does not yet support other types of streams");
+
+  if (uv__stream_fd(stream) < 0)
+    return UV_EBADF;
+
+  if (!(stream->flags & UV_HANDLE_WRITABLE))
+    return UV_EPIPE;
+
+  if (send_handle != NULL) {
+    if (stream->type != UV_NAMED_PIPE || !((uv_pipe_t*)stream)->ipc)
+      return UV_EINVAL;
+
+    /* XXX We abuse uv_write2() to send over UDP handles to child processes.
+     * Don't call uv__stream_fd() on those handles, it's a macro that on OS X
+     * evaluates to a function that operates on a uv_stream_t with a couple of
+     * OS X specific fields. On other Unices it does (handle)->io_watcher.fd,
+     * which works but only by accident.
+     */
+    if (uv__handle_fd((uv_handle_t*) send_handle) < 0)
+      return UV_EBADF;
+
+#if defined(__CYGWIN__) || defined(__MSYS__)
+    /* Cygwin recvmsg always sets msg_controllen to zero, so we cannot send it.
+       See https://github.com/mirror/newlib-cygwin/blob/86fc4bf0/winsup/cygwin/fhandler_socket.cc#L1736-L1743 */
+    return UV_ENOSYS;
+#endif
+  }
+
+  return 0;
+}
+
+int uv_write2(uv_write_t* req,
+              uv_stream_t* stream,
+              const uv_buf_t bufs[],
+              unsigned int nbufs,
+              uv_stream_t* send_handle,
+              uv_write_cb cb) {
+  int empty_queue;
+  int err;
+
+  err = uv__check_before_write(stream, nbufs, send_handle);
+  if (err < 0)
+    return err;
+
+  /* It's legal for write_queue_size > 0 even when the write_queue is empty;
+   * it means there are error-state requests in the write_completed_queue that
+   * will touch up write_queue_size later, see also uv__write_req_finish().
+   * We could check that write_queue is empty instead but that implies making
+   * a write() syscall when we know that the handle is in error mode.
+   */
+  empty_queue = (stream->write_queue_size == 0);
+
+  /* Initialize the req */
+  uv__req_init(stream->loop, req, UV_WRITE);
+  req->cb = cb;
+  req->handle = stream;
+  req->error = 0;
+  req->send_handle = send_handle;
+  QUEUE_INIT(&req->queue);
+
+  req->bufs = req->bufsml;
+  if (nbufs > ARRAY_SIZE(req->bufsml))
+    req->bufs = (uv_buf_t*)uv__malloc(nbufs * sizeof(bufs[0]));
+
+  if (req->bufs == NULL)
+    return UV_ENOMEM;
+
+  memcpy(req->bufs, bufs, nbufs * sizeof(bufs[0]));
+  req->nbufs = nbufs;
+  req->write_index = 0;
+  stream->write_queue_size += uv__count_bufs(bufs, nbufs);
+
+  /* Append the request to write_queue. */
+  QUEUE_INSERT_TAIL(&stream->write_queue, &req->queue);
+
+  /* If the queue was empty when this function began, we should attempt to
+   * do the write immediately. Otherwise start the write_watcher and wait
+   * for the fd to become writable.
+   */
+  if (stream->connect_req) {
+    /* Still connecting, do nothing. */
+  }
+  else if (empty_queue) {
+    uv__write(stream);
+  }
+  else {
+    /*
+     * blocking streams should never have anything in the queue.
+     * if this assert fires then somehow the blocking stream isn't being
+     * sufficiently flushed in uv__write.
+     */
+    assert(!(stream->flags & UV_HANDLE_BLOCKING_WRITES));
+    uv__io_start(stream->loop, &stream->io_watcher, POLLOUT);
+    uv__stream_osx_interrupt_select(stream);
+  }
+
+  return 0;
+}
+
+
+/* The buffers to be written must remain valid until the callback is called.
+ * This is not required for the uv_buf_t array.
+ */
+int uv_write(uv_write_t* req,
+             uv_stream_t* handle,
+             const uv_buf_t bufs[],
+             unsigned int nbufs,
+             uv_write_cb cb) {
+  return uv_write2(req, handle, bufs, nbufs, NULL, cb);
+}
+
+
+int uv_try_write(uv_stream_t* stream,
+                 const uv_buf_t bufs[],
+                 unsigned int nbufs) {
+  return uv_try_write2(stream, bufs, nbufs, NULL);
+}
+
+
+int uv_try_write2(uv_stream_t* stream,
+                  const uv_buf_t bufs[],
+                  unsigned int nbufs,
+                  uv_stream_t* send_handle) {
+  int err;
+
+  /* Connecting or already writing some data */
+  if (stream->connect_req != NULL || stream->write_queue_size != 0)
+    return UV_EAGAIN;
+
+  err = uv__check_before_write(stream, nbufs, NULL);
+  if (err < 0)
+    return err;
+
+  return uv__try_write(stream, bufs, nbufs, send_handle);
+}
+
+
+int uv__read_start(uv_stream_t* stream,
+                   uv_alloc_cb alloc_cb,
+                   uv_read_cb read_cb) {
+  assert(stream->type == UV_TCP || stream->type == UV_NAMED_PIPE ||
+      stream->type == UV_TTY);
+
+  /* The UV_HANDLE_READING flag is irrelevant of the state of the stream - it
+   * just expresses the desired state of the user. */
+  stream->flags |= UV_HANDLE_READING;
+  stream->flags &= ~UV_HANDLE_READ_EOF;
+
+  /* TODO: try to do the read inline? */
+  assert(uv__stream_fd(stream) >= 0);
+  assert(alloc_cb);
+
+  stream->read_cb = read_cb;
+  stream->alloc_cb = alloc_cb;
+
+  uv__io_start(stream->loop, &stream->io_watcher, POLLIN);
+  uv__handle_start(stream);
+  uv__stream_osx_interrupt_select(stream);
+
+  return 0;
+}
+
+
+int uv_read_stop(uv_stream_t* stream) {
+  if (!(stream->flags & UV_HANDLE_READING))
+    return 0;
+
+  stream->flags &= ~UV_HANDLE_READING;
+  uv__io_stop(stream->loop, &stream->io_watcher, POLLIN);
+  uv__handle_stop(stream);
+  uv__stream_osx_interrupt_select(stream);
+
+  stream->read_cb = NULL;
+  stream->alloc_cb = NULL;
+  return 0;
+}
+
+
+int uv_is_readable(const uv_stream_t* stream) {
+  return !!(stream->flags & UV_HANDLE_READABLE);
+}
+
+
+int uv_is_writable(const uv_stream_t* stream) {
+  return !!(stream->flags & UV_HANDLE_WRITABLE);
+}
+
+
+#if defined(__APPLE__)
+int uv___stream_fd(const uv_stream_t* handle) {
+  const uv__stream_select_t* s;
+
+  assert(handle->type == UV_TCP ||
+         handle->type == UV_TTY ||
+         handle->type == UV_NAMED_PIPE);
+
+  s = (const uv__stream_select_t*)handle->select;
+  if (s != NULL)
+    return s->fd;
+
+  return handle->io_watcher.fd;
+}
+#endif /* defined(__APPLE__) */
+
+
+void uv__stream_close(uv_stream_t* handle) {
+  unsigned int i;
+  uv__stream_queued_fds_t* queued_fds;
+
+#if defined(__APPLE__)
+  /* Terminate select loop first */
+  if (handle->select != NULL) {
+    uv__stream_select_t* s;
+
+    s = (uv__stream_select_t*)handle->select;
+
+    uv_sem_post(&s->close_sem);
+    uv_sem_post(&s->async_sem);
+    uv__stream_osx_interrupt_select(handle);
+    uv_thread_join(&s->thread);
+    uv_sem_destroy(&s->close_sem);
+    uv_sem_destroy(&s->async_sem);
+    uv__close(s->fake_fd);
+    uv__close(s->int_fd);
+    uv_close((uv_handle_t*) &s->async, uv__stream_osx_cb_close);
+
+    handle->select = NULL;
+  }
+#endif /* defined(__APPLE__) */
+
+  uv__io_close(handle->loop, &handle->io_watcher);
+  uv_read_stop(handle);
+  uv__handle_stop(handle);
+  handle->flags &= ~(UV_HANDLE_READABLE | UV_HANDLE_WRITABLE);
+
+  if (handle->io_watcher.fd != -1) {
+    /* Don't close stdio file descriptors.  Nothing good comes from it. */
+    if (handle->io_watcher.fd > STDERR_FILENO)
+      uv__close(handle->io_watcher.fd);
+    handle->io_watcher.fd = -1;
+  }
+
+  if (handle->accepted_fd != -1) {
+    uv__close(handle->accepted_fd);
+    handle->accepted_fd = -1;
+  }
+
+  /* Close all queued fds */
+  if (handle->queued_fds != NULL) {
+    queued_fds = (uv__stream_queued_fds_t*)(handle->queued_fds);
+    for (i = 0; i < queued_fds->offset; i++)
+      uv__close(queued_fds->fds[i]);
+    uv__free(handle->queued_fds);
+    handle->queued_fds = NULL;
+  }
+
+  assert(!uv__io_active(&handle->io_watcher, POLLIN | POLLOUT));
+}
+
+
+int uv_stream_set_blocking(uv_stream_t* handle, int blocking) {
+  /* Don't need to check the file descriptor, uv__nonblock()
+   * will fail with EBADF if it's not valid.
+   */
+  return uv__nonblock(uv__stream_fd(handle), !blocking);
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/tcp.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/tcp.cpp
new file mode 100644
index 0000000..73fc657
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/tcp.cpp
@@ -0,0 +1,519 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <stdlib.h>
+#include <unistd.h>
+#include <assert.h>
+#include <errno.h>
+
+
+static int new_socket(uv_tcp_t* handle, int domain, unsigned long flags) {
+  struct sockaddr_storage saddr;
+  socklen_t slen;
+  int sockfd;
+  int err;
+
+  err = uv__socket(domain, SOCK_STREAM, 0);
+  if (err < 0)
+    return err;
+  sockfd = err;
+
+  err = uv__stream_open((uv_stream_t*) handle, sockfd, flags);
+  if (err) {
+    uv__close(sockfd);
+    return err;
+  }
+
+  if (flags & UV_HANDLE_BOUND) {
+    /* Bind this new socket to an arbitrary port */
+    slen = sizeof(saddr);
+    memset(&saddr, 0, sizeof(saddr));
+    if (getsockname(uv__stream_fd(handle), (struct sockaddr*) &saddr, &slen)) {
+      uv__close(sockfd);
+      return UV__ERR(errno);
+    }
+
+    if (bind(uv__stream_fd(handle), (struct sockaddr*) &saddr, slen)) {
+      uv__close(sockfd);
+      return UV__ERR(errno);
+    }
+  }
+
+  return 0;
+}
+
+
+static int maybe_new_socket(uv_tcp_t* handle, int domain, unsigned long flags) {
+  struct sockaddr_storage saddr;
+  socklen_t slen;
+
+  if (domain == AF_UNSPEC) {
+    handle->flags |= flags;
+    return 0;
+  }
+
+  if (uv__stream_fd(handle) != -1) {
+
+    if (flags & UV_HANDLE_BOUND) {
+
+      if (handle->flags & UV_HANDLE_BOUND) {
+        /* It is already bound to a port. */
+        handle->flags |= flags;
+        return 0;
+      }
+
+      /* Query to see if tcp socket is bound. */
+      slen = sizeof(saddr);
+      memset(&saddr, 0, sizeof(saddr));
+      if (getsockname(uv__stream_fd(handle), (struct sockaddr*) &saddr, &slen))
+        return UV__ERR(errno);
+
+      if ((saddr.ss_family == AF_INET6 &&
+          ((struct sockaddr_in6*) &saddr)->sin6_port != 0) ||
+          (saddr.ss_family == AF_INET &&
+          ((struct sockaddr_in*) &saddr)->sin_port != 0)) {
+        /* Handle is already bound to a port. */
+        handle->flags |= flags;
+        return 0;
+      }
+
+      /* Bind to arbitrary port */
+      if (bind(uv__stream_fd(handle), (struct sockaddr*) &saddr, slen))
+        return UV__ERR(errno);
+    }
+
+    handle->flags |= flags;
+    return 0;
+  }
+
+  return new_socket(handle, domain, flags);
+}
+
+
+int uv_tcp_init_ex(uv_loop_t* loop, uv_tcp_t* tcp, unsigned int flags) {
+  int domain;
+
+  /* Use the lower 8 bits for the domain */
+  domain = flags & 0xFF;
+  if (domain != AF_INET && domain != AF_INET6 && domain != AF_UNSPEC)
+    return UV_EINVAL;
+
+  if (flags & ~0xFF)
+    return UV_EINVAL;
+
+  uv__stream_init(loop, (uv_stream_t*)tcp, UV_TCP);
+
+  /* If anything fails beyond this point we need to remove the handle from
+   * the handle queue, since it was added by uv__handle_init in uv_stream_init.
+   */
+
+  if (domain != AF_UNSPEC) {
+    int err = maybe_new_socket(tcp, domain, 0);
+    if (err) {
+      QUEUE_REMOVE(&tcp->handle_queue);
+      return err;
+    }
+  }
+
+  return 0;
+}
+
+
+int uv_tcp_init(uv_loop_t* loop, uv_tcp_t* tcp) {
+  return uv_tcp_init_ex(loop, tcp, AF_UNSPEC);
+}
+
+
+int uv__tcp_bind(uv_tcp_t* tcp,
+                 const struct sockaddr* addr,
+                 unsigned int addrlen,
+                 unsigned int flags) {
+  int err;
+  int on;
+
+  /* Cannot set IPv6-only mode on non-IPv6 socket. */
+  if ((flags & UV_TCP_IPV6ONLY) && addr->sa_family != AF_INET6)
+    return UV_EINVAL;
+
+  err = maybe_new_socket(tcp, addr->sa_family, 0);
+  if (err)
+    return err;
+
+  on = 1;
+  if (setsockopt(tcp->io_watcher.fd, SOL_SOCKET, SO_REUSEADDR, &on, sizeof(on)))
+    return UV__ERR(errno);
+
+#ifndef __OpenBSD__
+#ifdef IPV6_V6ONLY
+  if (addr->sa_family == AF_INET6) {
+    on = (flags & UV_TCP_IPV6ONLY) != 0;
+    if (setsockopt(tcp->io_watcher.fd,
+                   IPPROTO_IPV6,
+                   IPV6_V6ONLY,
+                   &on,
+                   sizeof on) == -1) {
+#if defined(__MVS__)
+      if (errno == EOPNOTSUPP)
+        return UV_EINVAL;
+#endif
+      return UV__ERR(errno);
+    }
+  }
+#endif
+#endif
+
+  errno = 0;
+  err = bind(tcp->io_watcher.fd, addr, addrlen);
+  if (err == -1 && errno != EADDRINUSE) {
+    if (errno == EAFNOSUPPORT)
+      /* OSX, other BSDs and SunoS fail with EAFNOSUPPORT when binding a
+       * socket created with AF_INET to an AF_INET6 address or vice versa. */
+      return UV_EINVAL;
+    return UV__ERR(errno);
+  }
+  tcp->delayed_error = (err == -1) ? UV__ERR(errno) : 0;
+
+  tcp->flags |= UV_HANDLE_BOUND;
+  if (addr->sa_family == AF_INET6)
+    tcp->flags |= UV_HANDLE_IPV6;
+
+  return 0;
+}
+
+
+int uv__tcp_connect(uv_connect_t* req,
+                    uv_tcp_t* handle,
+                    const struct sockaddr* addr,
+                    unsigned int addrlen,
+                    uv_connect_cb cb) {
+  int err;
+  int r;
+
+  assert(handle->type == UV_TCP);
+
+  if (handle->connect_req != NULL)
+    return UV_EALREADY;  /* FIXME(bnoordhuis) UV_EINVAL or maybe UV_EBUSY. */
+
+  if (handle->delayed_error != 0)
+    goto out;
+
+  err = maybe_new_socket(handle,
+                         addr->sa_family,
+                         UV_HANDLE_READABLE | UV_HANDLE_WRITABLE);
+  if (err)
+    return err;
+
+  do {
+    errno = 0;
+    r = connect(uv__stream_fd(handle), addr, addrlen);
+  } while (r == -1 && errno == EINTR);
+
+  /* We not only check the return value, but also check the errno != 0.
+   * Because in rare cases connect() will return -1 but the errno
+   * is 0 (for example, on Android 4.3, OnePlus phone A0001_12_150227)
+   * and actually the tcp three-way handshake is completed.
+   */
+  if (r == -1 && errno != 0) {
+    if (errno == EINPROGRESS)
+      ; /* not an error */
+    else if (errno == ECONNREFUSED
+#if defined(__OpenBSD__)
+      || errno == EINVAL
+#endif
+      )
+    /* If we get ECONNREFUSED (Solaris) or EINVAL (OpenBSD) wait until the
+     * next tick to report the error. Solaris and OpenBSD wants to report
+     * immediately -- other unixes want to wait.
+     */
+      handle->delayed_error = UV__ERR(ECONNREFUSED);
+    else
+      return UV__ERR(errno);
+  }
+
+out:
+
+  uv__req_init(handle->loop, req, UV_CONNECT);
+  req->cb = cb;
+  req->handle = (uv_stream_t*) handle;
+  QUEUE_INIT(&req->queue);
+  handle->connect_req = req;
+
+  uv__io_start(handle->loop, &handle->io_watcher, POLLOUT);
+
+  if (handle->delayed_error)
+    uv__io_feed(handle->loop, &handle->io_watcher);
+
+  return 0;
+}
+
+
+int uv_tcp_open(uv_tcp_t* handle, uv_os_sock_t sock) {
+  int err;
+
+  if (uv__fd_exists(handle->loop, sock))
+    return UV_EEXIST;
+
+  err = uv__nonblock(sock, 1);
+  if (err)
+    return err;
+
+  return uv__stream_open((uv_stream_t*)handle,
+                         sock,
+                         UV_HANDLE_READABLE | UV_HANDLE_WRITABLE);
+}
+
+
+int uv_tcp_getsockname(const uv_tcp_t* handle,
+                       struct sockaddr* name,
+                       int* namelen) {
+
+  if (handle->delayed_error)
+    return handle->delayed_error;
+
+  return uv__getsockpeername((const uv_handle_t*) handle,
+                             getsockname,
+                             name,
+                             namelen);
+}
+
+
+int uv_tcp_getpeername(const uv_tcp_t* handle,
+                       struct sockaddr* name,
+                       int* namelen) {
+
+  if (handle->delayed_error)
+    return handle->delayed_error;
+
+  return uv__getsockpeername((const uv_handle_t*) handle,
+                             getpeername,
+                             name,
+                             namelen);
+}
+
+
+int uv_tcp_close_reset(uv_tcp_t* handle, uv_close_cb close_cb) {
+  int fd;
+  struct linger l = { 1, 0 };
+
+  /* Disallow setting SO_LINGER to zero due to some platform inconsistencies */
+  if (handle->flags & UV_HANDLE_SHUTTING)
+    return UV_EINVAL;
+
+  fd = uv__stream_fd(handle);
+  if (0 != setsockopt(fd, SOL_SOCKET, SO_LINGER, &l, sizeof(l))) {
+    if (errno == EINVAL) {
+      /* Open Group Specifications Issue 7, 2018 edition states that
+       * EINVAL may mean the socket has been shut down already.
+       * Behavior observed on Solaris, illumos and macOS. */
+      errno = 0;
+    } else {
+      return UV__ERR(errno);
+    }
+  }
+
+  uv_close((uv_handle_t*) handle, close_cb);
+  return 0;
+}
+
+
+int uv__tcp_listen(uv_tcp_t* tcp, int backlog, uv_connection_cb cb) {
+  static int single_accept_cached = -1;
+  unsigned long flags;
+  int single_accept;
+  int err;
+
+  if (tcp->delayed_error)
+    return tcp->delayed_error;
+
+  single_accept = uv__load_relaxed(&single_accept_cached);
+  if (single_accept == -1) {
+    const char* val = getenv("UV_TCP_SINGLE_ACCEPT");
+    single_accept = (val != NULL && atoi(val) != 0);  /* Off by default. */
+    uv__store_relaxed(&single_accept_cached, single_accept);
+  }
+
+  if (single_accept)
+    tcp->flags |= UV_HANDLE_TCP_SINGLE_ACCEPT;
+
+  flags = 0;
+#if defined(__MVS__)
+  /* on zOS the listen call does not bind automatically
+     if the socket is unbound. Hence the manual binding to
+     an arbitrary port is required to be done manually
+  */
+  flags |= UV_HANDLE_BOUND;
+#endif
+  err = maybe_new_socket(tcp, AF_INET, flags);
+  if (err)
+    return err;
+
+  if (listen(tcp->io_watcher.fd, backlog))
+    return UV__ERR(errno);
+
+  tcp->connection_cb = cb;
+  tcp->flags |= UV_HANDLE_BOUND;
+
+  /* Start listening for connections. */
+  tcp->io_watcher.cb = uv__server_io;
+  uv__io_start(tcp->loop, &tcp->io_watcher, POLLIN);
+
+  return 0;
+}
+
+
+int uv__tcp_nodelay(int fd, int on) {
+  if (setsockopt(fd, IPPROTO_TCP, TCP_NODELAY, &on, sizeof(on)))
+    return UV__ERR(errno);
+  return 0;
+}
+
+
+int uv__tcp_keepalive(int fd, int on, unsigned int delay) {
+  if (setsockopt(fd, SOL_SOCKET, SO_KEEPALIVE, &on, sizeof(on)))
+    return UV__ERR(errno);
+
+#ifdef TCP_KEEPIDLE
+  if (on) {
+    int intvl = 1;  /*  1 second; same as default on Win32 */
+    int cnt = 10;  /* 10 retries; same as hardcoded on Win32 */
+    if (setsockopt(fd, IPPROTO_TCP, TCP_KEEPIDLE, &delay, sizeof(delay)))
+      return UV__ERR(errno);
+    if (setsockopt(fd, IPPROTO_TCP, TCP_KEEPINTVL, &intvl, sizeof(intvl)))
+      return UV__ERR(errno);
+    if (setsockopt(fd, IPPROTO_TCP, TCP_KEEPCNT, &cnt, sizeof(cnt)))
+      return UV__ERR(errno);
+  }
+#endif
+
+  /* Solaris/SmartOS, if you don't support keep-alive,
+   * then don't advertise it in your system headers...
+   */
+  /* FIXME(bnoordhuis) That's possibly because sizeof(delay) should be 1. */
+#if defined(TCP_KEEPALIVE) && !defined(__sun)
+  if (on && setsockopt(fd, IPPROTO_TCP, TCP_KEEPALIVE, &delay, sizeof(delay)))
+    return UV__ERR(errno);
+#endif
+
+  return 0;
+}
+
+
+int uv_tcp_nodelay(uv_tcp_t* handle, int on) {
+  int err;
+
+  if (uv__stream_fd(handle) != -1) {
+    err = uv__tcp_nodelay(uv__stream_fd(handle), on);
+    if (err)
+      return err;
+  }
+
+  if (on)
+    handle->flags |= UV_HANDLE_TCP_NODELAY;
+  else
+    handle->flags &= ~UV_HANDLE_TCP_NODELAY;
+
+  return 0;
+}
+
+
+int uv_tcp_keepalive(uv_tcp_t* handle, int on, unsigned int delay) {
+  int err;
+
+  if (uv__stream_fd(handle) != -1) {
+    err =uv__tcp_keepalive(uv__stream_fd(handle), on, delay);
+    if (err)
+      return err;
+  }
+
+  if (on)
+    handle->flags |= UV_HANDLE_TCP_KEEPALIVE;
+  else
+    handle->flags &= ~UV_HANDLE_TCP_KEEPALIVE;
+
+  /* TODO Store delay if uv__stream_fd(handle) == -1 but don't want to enlarge
+   *      uv_tcp_t with an int that's almost never used...
+   */
+
+  return 0;
+}
+
+
+int uv_tcp_simultaneous_accepts(uv_tcp_t* handle, int enable) {
+  if (enable)
+    handle->flags &= ~UV_HANDLE_TCP_SINGLE_ACCEPT;
+  else
+    handle->flags |= UV_HANDLE_TCP_SINGLE_ACCEPT;
+  return 0;
+}
+
+
+void uv__tcp_close(uv_tcp_t* handle) {
+  uv__stream_close((uv_stream_t*)handle);
+}
+
+
+int uv_socketpair(int type, int protocol, uv_os_sock_t fds[2], int flags0, int flags1) {
+  uv_os_sock_t temp[2];
+  int err;
+#if defined(__FreeBSD__) || defined(__linux__)
+  int flags;
+
+  flags = type | SOCK_CLOEXEC;
+  if ((flags0 & UV_NONBLOCK_PIPE) && (flags1 & UV_NONBLOCK_PIPE))
+    flags |= SOCK_NONBLOCK;
+
+  if (socketpair(AF_UNIX, flags, protocol, temp))
+    return UV__ERR(errno);
+
+  if (flags & UV_FS_O_NONBLOCK) {
+    fds[0] = temp[0];
+    fds[1] = temp[1];
+    return 0;
+  }
+#else
+  if (socketpair(AF_UNIX, type, protocol, temp))
+    return UV__ERR(errno);
+
+  if ((err = uv__cloexec(temp[0], 1)))
+    goto fail;
+  if ((err = uv__cloexec(temp[1], 1)))
+    goto fail;
+#endif
+
+  if (flags0 & UV_NONBLOCK_PIPE)
+    if ((err = uv__nonblock(temp[0], 1)))
+        goto fail;
+  if (flags1 & UV_NONBLOCK_PIPE)
+    if ((err = uv__nonblock(temp[1], 1)))
+      goto fail;
+
+  fds[0] = temp[0];
+  fds[1] = temp[1];
+  return 0;
+
+fail:
+  uv__close(temp[0]);
+  uv__close(temp[1]);
+  return err;
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/thread.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/thread.cpp
new file mode 100644
index 0000000..392a071
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/thread.cpp
@@ -0,0 +1,854 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <pthread.h>
+#include <assert.h>
+#include <errno.h>
+
+#include <sys/time.h>
+#include <sys/resource.h>  /* getrlimit() */
+#include <unistd.h>  /* getpagesize() */
+
+#include <limits.h>
+
+#ifdef __MVS__
+#include <sys/ipc.h>
+#include <sys/sem.h>
+#endif
+
+#if defined(__GLIBC__) && !defined(__UCLIBC__)
+#include <gnu/libc-version.h>  /* gnu_get_libc_version() */
+#endif
+
+#undef NANOSEC
+#define NANOSEC ((uint64_t) 1e9)
+
+#if defined(PTHREAD_BARRIER_SERIAL_THREAD)
+STATIC_ASSERT(sizeof(uv_barrier_t) == sizeof(pthread_barrier_t));
+#endif
+
+/* Note: guard clauses should match uv_barrier_t's in include/uv/unix.h. */
+#if defined(_AIX) || \
+    defined(__OpenBSD__) || \
+    !defined(PTHREAD_BARRIER_SERIAL_THREAD)
+int uv_barrier_init(uv_barrier_t* barrier, unsigned int count) {
+  struct _uv_barrier* b;
+  int rc;
+
+  if (barrier == NULL || count == 0)
+    return UV_EINVAL;
+
+  b = (_uv_barrier*)uv__malloc(sizeof(*b));
+  if (b == NULL)
+    return UV_ENOMEM;
+
+  b->in = 0;
+  b->out = 0;
+  b->threshold = count;
+
+  rc = uv_mutex_init(&b->mutex);
+  if (rc != 0)
+    goto error2;
+
+  rc = uv_cond_init(&b->cond);
+  if (rc != 0)
+    goto error;
+
+  barrier->b = b;
+  return 0;
+
+error:
+  uv_mutex_destroy(&b->mutex);
+error2:
+  uv__free(b);
+  return rc;
+}
+
+int uv_barrier_wait(uv_barrier_t* barrier) {
+  struct _uv_barrier* b;
+  int last;
+
+  if (barrier == NULL || barrier->b == NULL)
+    return UV_EINVAL;
+
+  b = barrier->b;
+  /* Lock the mutex*/
+  uv_mutex_lock(&b->mutex);
+
+  if (++b->in == b->threshold) {
+    b->in = 0;
+    b->out = b->threshold;
+    uv_cond_signal(&b->cond);
+  } else {
+    do
+      uv_cond_wait(&b->cond, &b->mutex);
+    while (b->in != 0);
+  }
+
+  last = (--b->out == 0);
+  uv_cond_signal(&b->cond);
+
+  uv_mutex_unlock(&b->mutex);
+  return last;
+}
+
+void uv_barrier_destroy(uv_barrier_t* barrier) {
+  struct _uv_barrier* b;
+
+  b = barrier->b;
+  uv_mutex_lock(&b->mutex);
+
+  assert(b->in == 0);
+  while (b->out != 0)
+    uv_cond_wait(&b->cond, &b->mutex);
+
+  if (b->in != 0)
+    abort();
+
+  uv_mutex_unlock(&b->mutex);
+  uv_mutex_destroy(&b->mutex);
+  uv_cond_destroy(&b->cond);
+
+  uv__free(barrier->b);
+  barrier->b = NULL;
+}
+
+#else
+
+int uv_barrier_init(uv_barrier_t* barrier, unsigned int count) {
+  return UV__ERR(pthread_barrier_init(barrier, NULL, count));
+}
+
+
+int uv_barrier_wait(uv_barrier_t* barrier) {
+  int rc;
+
+  rc = pthread_barrier_wait(barrier);
+  if (rc != 0)
+    if (rc != PTHREAD_BARRIER_SERIAL_THREAD)
+      abort();
+
+  return rc == PTHREAD_BARRIER_SERIAL_THREAD;
+}
+
+
+void uv_barrier_destroy(uv_barrier_t* barrier) {
+  if (pthread_barrier_destroy(barrier))
+    abort();
+}
+
+#endif
+
+
+/* Musl's PTHREAD_STACK_MIN is 2 KB on all architectures, which is
+ * too small to safely receive signals on.
+ *
+ * Musl's PTHREAD_STACK_MIN + MINSIGSTKSZ == 8192 on arm64 (which has
+ * the largest MINSIGSTKSZ of the architectures that musl supports) so
+ * let's use that as a lower bound.
+ *
+ * We use a hardcoded value because PTHREAD_STACK_MIN + MINSIGSTKSZ
+ * is between 28 and 133 KB when compiling against glibc, depending
+ * on the architecture.
+ */
+static size_t uv__min_stack_size(void) {
+  static const size_t min = 8192;
+
+#ifdef PTHREAD_STACK_MIN  /* Not defined on NetBSD. */
+  if (min < (size_t) PTHREAD_STACK_MIN)
+    return PTHREAD_STACK_MIN;
+#endif  /* PTHREAD_STACK_MIN */
+
+  return min;
+}
+
+
+/* On Linux, threads created by musl have a much smaller stack than threads
+ * created by glibc (80 vs. 2048 or 4096 kB.)  Follow glibc for consistency.
+ */
+static size_t uv__default_stack_size(void) {
+#if !defined(__linux__)
+  return 0;
+#elif defined(__PPC__) || defined(__ppc__) || defined(__powerpc__)
+  return 4 << 20;  /* glibc default. */
+#else
+  return 2 << 20;  /* glibc default. */
+#endif
+}
+
+
+/* On MacOS, threads other than the main thread are created with a reduced
+ * stack size by default.  Adjust to RLIMIT_STACK aligned to the page size.
+ */
+size_t uv__thread_stack_size(void) {
+#if defined(__APPLE__) || defined(__linux__)
+  struct rlimit lim;
+
+  /* getrlimit() can fail on some aarch64 systems due to a glibc bug where
+   * the system call wrapper invokes the wrong system call. Don't treat
+   * that as fatal, just use the default stack size instead.
+   */
+  if (getrlimit(RLIMIT_STACK, &lim))
+    return uv__default_stack_size();
+
+  if (lim.rlim_cur == RLIM_INFINITY)
+    return uv__default_stack_size();
+
+  /* pthread_attr_setstacksize() expects page-aligned values. */
+  lim.rlim_cur -= lim.rlim_cur % (rlim_t) getpagesize();
+
+  if (lim.rlim_cur >= (rlim_t) uv__min_stack_size())
+    return lim.rlim_cur;
+#endif
+
+  return uv__default_stack_size();
+}
+
+
+int uv_thread_create(uv_thread_t *tid, void (*entry)(void *arg), void *arg) {
+  uv_thread_options_t params;
+  params.flags = UV_THREAD_NO_FLAGS;
+  return uv_thread_create_ex(tid, &params, entry, arg);
+}
+
+int uv_thread_create_ex(uv_thread_t* tid,
+                        const uv_thread_options_t* params,
+                        void (*entry)(void *arg),
+                        void *arg) {
+  int err;
+  pthread_attr_t* attr;
+  pthread_attr_t attr_storage;
+  size_t pagesize;
+  size_t stack_size;
+  size_t min_stack_size;
+
+  stack_size =
+      params->flags & UV_THREAD_HAS_STACK_SIZE ? params->stack_size : 0;
+
+  attr = NULL;
+  if (stack_size == 0) {
+    stack_size = uv__thread_stack_size();
+  } else {
+    pagesize = (size_t)getpagesize();
+    /* Round up to the nearest page boundary. */
+    stack_size = (stack_size + pagesize - 1) &~ (pagesize - 1);
+    min_stack_size = uv__min_stack_size();
+    if (stack_size < min_stack_size)
+      stack_size = min_stack_size;
+  }
+
+  if (stack_size > 0) {
+    attr = &attr_storage;
+
+    if (pthread_attr_init(attr))
+      abort();
+
+    if (pthread_attr_setstacksize(attr, stack_size))
+      abort();
+  }
+
+  err = pthread_create(tid, attr, (void*(*)(void*)) (void(*)(void)) entry, arg);
+
+  if (attr != NULL)
+    pthread_attr_destroy(attr);
+
+  return UV__ERR(err);
+}
+
+
+uv_thread_t uv_thread_self(void) {
+  return pthread_self();
+}
+
+int uv_thread_join(uv_thread_t *tid) {
+  return UV__ERR(pthread_join(*tid, NULL));
+}
+
+
+int uv_thread_equal(const uv_thread_t* t1, const uv_thread_t* t2) {
+  return pthread_equal(*t1, *t2);
+}
+
+
+int uv_mutex_init(uv_mutex_t* mutex) {
+#if defined(NDEBUG) || !defined(PTHREAD_MUTEX_ERRORCHECK)
+  return UV__ERR(pthread_mutex_init(mutex, NULL));
+#else
+  pthread_mutexattr_t attr;
+  int err;
+
+  if (pthread_mutexattr_init(&attr))
+    abort();
+
+  if (pthread_mutexattr_settype(&attr, PTHREAD_MUTEX_ERRORCHECK))
+    abort();
+
+  err = pthread_mutex_init(mutex, &attr);
+
+  if (pthread_mutexattr_destroy(&attr))
+    abort();
+
+  return UV__ERR(err);
+#endif
+}
+
+
+int uv_mutex_init_recursive(uv_mutex_t* mutex) {
+  pthread_mutexattr_t attr;
+  int err;
+
+  if (pthread_mutexattr_init(&attr))
+    abort();
+
+  if (pthread_mutexattr_settype(&attr, PTHREAD_MUTEX_RECURSIVE))
+    abort();
+
+  err = pthread_mutex_init(mutex, &attr);
+
+  if (pthread_mutexattr_destroy(&attr))
+    abort();
+
+  return UV__ERR(err);
+}
+
+
+void uv_mutex_destroy(uv_mutex_t* mutex) {
+  if (pthread_mutex_destroy(mutex))
+    abort();
+}
+
+
+void uv_mutex_lock(uv_mutex_t* mutex) {
+  if (pthread_mutex_lock(mutex))
+    abort();
+}
+
+
+int uv_mutex_trylock(uv_mutex_t* mutex) {
+  int err;
+
+  err = pthread_mutex_trylock(mutex);
+  if (err) {
+    if (err != EBUSY && err != EAGAIN)
+      abort();
+    return UV_EBUSY;
+  }
+
+  return 0;
+}
+
+
+void uv_mutex_unlock(uv_mutex_t* mutex) {
+  if (pthread_mutex_unlock(mutex))
+    abort();
+}
+
+
+int uv_rwlock_init(uv_rwlock_t* rwlock) {
+  return UV__ERR(pthread_rwlock_init(rwlock, NULL));
+}
+
+
+void uv_rwlock_destroy(uv_rwlock_t* rwlock) {
+  if (pthread_rwlock_destroy(rwlock))
+    abort();
+}
+
+
+void uv_rwlock_rdlock(uv_rwlock_t* rwlock) {
+  if (pthread_rwlock_rdlock(rwlock))
+    abort();
+}
+
+
+int uv_rwlock_tryrdlock(uv_rwlock_t* rwlock) {
+  int err;
+
+  err = pthread_rwlock_tryrdlock(rwlock);
+  if (err) {
+    if (err != EBUSY && err != EAGAIN)
+      abort();
+    return UV_EBUSY;
+  }
+
+  return 0;
+}
+
+
+void uv_rwlock_rdunlock(uv_rwlock_t* rwlock) {
+  if (pthread_rwlock_unlock(rwlock))
+    abort();
+}
+
+
+void uv_rwlock_wrlock(uv_rwlock_t* rwlock) {
+  if (pthread_rwlock_wrlock(rwlock))
+    abort();
+}
+
+
+int uv_rwlock_trywrlock(uv_rwlock_t* rwlock) {
+  int err;
+
+  err = pthread_rwlock_trywrlock(rwlock);
+  if (err) {
+    if (err != EBUSY && err != EAGAIN)
+      abort();
+    return UV_EBUSY;
+  }
+
+  return 0;
+}
+
+
+void uv_rwlock_wrunlock(uv_rwlock_t* rwlock) {
+  if (pthread_rwlock_unlock(rwlock))
+    abort();
+}
+
+
+void uv_once(uv_once_t* guard, void (*callback)(void)) {
+  if (pthread_once(guard, callback))
+    abort();
+}
+
+#if defined(__APPLE__) && defined(__MACH__)
+
+int uv_sem_init(uv_sem_t* sem, unsigned int value) {
+  kern_return_t err;
+
+  err = semaphore_create(mach_task_self(), sem, SYNC_POLICY_FIFO, value);
+  if (err == KERN_SUCCESS)
+    return 0;
+  if (err == KERN_INVALID_ARGUMENT)
+    return UV_EINVAL;
+  if (err == KERN_RESOURCE_SHORTAGE)
+    return UV_ENOMEM;
+
+  abort();
+  return UV_EINVAL;  /* Satisfy the compiler. */
+}
+
+
+void uv_sem_destroy(uv_sem_t* sem) {
+  if (semaphore_destroy(mach_task_self(), *sem))
+    abort();
+}
+
+
+void uv_sem_post(uv_sem_t* sem) {
+  if (semaphore_signal(*sem))
+    abort();
+}
+
+
+void uv_sem_wait(uv_sem_t* sem) {
+  int r;
+
+  do
+    r = semaphore_wait(*sem);
+  while (r == KERN_ABORTED);
+
+  if (r != KERN_SUCCESS)
+    abort();
+}
+
+
+int uv_sem_trywait(uv_sem_t* sem) {
+  mach_timespec_t interval;
+  kern_return_t err;
+
+  interval.tv_sec = 0;
+  interval.tv_nsec = 0;
+
+  err = semaphore_timedwait(*sem, interval);
+  if (err == KERN_SUCCESS)
+    return 0;
+  if (err == KERN_OPERATION_TIMED_OUT)
+    return UV_EAGAIN;
+
+  abort();
+  return UV_EINVAL;  /* Satisfy the compiler. */
+}
+
+#else /* !(defined(__APPLE__) && defined(__MACH__)) */
+
+#if defined(__GLIBC__) && !defined(__UCLIBC__)
+
+/* Hack around https://sourceware.org/bugzilla/show_bug.cgi?id=12674
+ * by providing a custom implementation for glibc < 2.21 in terms of other
+ * concurrency primitives.
+ * Refs: https://github.com/nodejs/node/issues/19903 */
+
+/* To preserve ABI compatibility, we treat the uv_sem_t as storage for
+ * a pointer to the actual struct we're using underneath. */
+
+static uv_once_t glibc_version_check_once = UV_ONCE_INIT;
+static int platform_needs_custom_semaphore = 0;
+
+static void glibc_version_check(void) {
+  const char* version = gnu_get_libc_version();
+  platform_needs_custom_semaphore =
+      version[0] == '2' && version[1] == '.' &&
+      atoi(version + 2) < 21;
+}
+
+#elif defined(__MVS__)
+
+#define platform_needs_custom_semaphore 1
+
+#else /* !defined(__GLIBC__) && !defined(__MVS__) */
+
+#define platform_needs_custom_semaphore 0
+
+#endif
+
+typedef struct uv_semaphore_s {
+  uv_mutex_t mutex;
+  uv_cond_t cond;
+  unsigned int value;
+} uv_semaphore_t;
+
+#if (defined(__GLIBC__) && !defined(__UCLIBC__)) || \
+    platform_needs_custom_semaphore
+STATIC_ASSERT(sizeof(uv_sem_t) >= sizeof(uv_semaphore_t*));
+#endif
+
+static int uv__custom_sem_init(uv_sem_t* sem_, unsigned int value) {
+  int err;
+  uv_semaphore_t* sem;
+
+  sem = (uv_semaphore_t*)uv__malloc(sizeof(*sem));
+  if (sem == NULL)
+    return UV_ENOMEM;
+
+  if ((err = uv_mutex_init(&sem->mutex)) != 0) {
+    uv__free(sem);
+    return err;
+  }
+
+  if ((err = uv_cond_init(&sem->cond)) != 0) {
+    uv_mutex_destroy(&sem->mutex);
+    uv__free(sem);
+    return err;
+  }
+
+  sem->value = value;
+  *(uv_semaphore_t**)sem_ = sem;
+  return 0;
+}
+
+
+static void uv__custom_sem_destroy(uv_sem_t* sem_) {
+  uv_semaphore_t* sem;
+
+  sem = *(uv_semaphore_t**)sem_;
+  uv_cond_destroy(&sem->cond);
+  uv_mutex_destroy(&sem->mutex);
+  uv__free(sem);
+}
+
+
+static void uv__custom_sem_post(uv_sem_t* sem_) {
+  uv_semaphore_t* sem;
+
+  sem = *(uv_semaphore_t**)sem_;
+  uv_mutex_lock(&sem->mutex);
+  sem->value++;
+  if (sem->value == 1)
+    uv_cond_signal(&sem->cond);
+  uv_mutex_unlock(&sem->mutex);
+}
+
+
+static void uv__custom_sem_wait(uv_sem_t* sem_) {
+  uv_semaphore_t* sem;
+
+  sem = *(uv_semaphore_t**)sem_;
+  uv_mutex_lock(&sem->mutex);
+  while (sem->value == 0)
+    uv_cond_wait(&sem->cond, &sem->mutex);
+  sem->value--;
+  uv_mutex_unlock(&sem->mutex);
+}
+
+
+static int uv__custom_sem_trywait(uv_sem_t* sem_) {
+  uv_semaphore_t* sem;
+
+  sem = *(uv_semaphore_t**)sem_;
+  if (uv_mutex_trylock(&sem->mutex) != 0)
+    return UV_EAGAIN;
+
+  if (sem->value == 0) {
+    uv_mutex_unlock(&sem->mutex);
+    return UV_EAGAIN;
+  }
+
+  sem->value--;
+  uv_mutex_unlock(&sem->mutex);
+
+  return 0;
+}
+
+static int uv__sem_init(uv_sem_t* sem, unsigned int value) {
+  if (sem_init(sem, 0, value))
+    return UV__ERR(errno);
+  return 0;
+}
+
+
+static void uv__sem_destroy(uv_sem_t* sem) {
+  if (sem_destroy(sem))
+    abort();
+}
+
+
+static void uv__sem_post(uv_sem_t* sem) {
+  if (sem_post(sem))
+    abort();
+}
+
+
+static void uv__sem_wait(uv_sem_t* sem) {
+  int r;
+
+  do
+    r = sem_wait(sem);
+  while (r == -1 && errno == EINTR);
+
+  if (r)
+    abort();
+}
+
+
+static int uv__sem_trywait(uv_sem_t* sem) {
+  int r;
+
+  do
+    r = sem_trywait(sem);
+  while (r == -1 && errno == EINTR);
+
+  if (r) {
+    if (errno == EAGAIN)
+      return UV_EAGAIN;
+    abort();
+  }
+
+  return 0;
+}
+
+int uv_sem_init(uv_sem_t* sem, unsigned int value) {
+#if defined(__GLIBC__) && !defined(__UCLIBC__)
+  uv_once(&glibc_version_check_once, glibc_version_check);
+#endif
+
+  if (platform_needs_custom_semaphore)
+    return uv__custom_sem_init(sem, value);
+  else
+    return uv__sem_init(sem, value);
+}
+
+
+void uv_sem_destroy(uv_sem_t* sem) {
+  if (platform_needs_custom_semaphore)
+    uv__custom_sem_destroy(sem);
+  else
+    uv__sem_destroy(sem);
+}
+
+
+void uv_sem_post(uv_sem_t* sem) {
+  if (platform_needs_custom_semaphore)
+    uv__custom_sem_post(sem);
+  else
+    uv__sem_post(sem);
+}
+
+
+void uv_sem_wait(uv_sem_t* sem) {
+  if (platform_needs_custom_semaphore)
+    uv__custom_sem_wait(sem);
+  else
+    uv__sem_wait(sem);
+}
+
+
+int uv_sem_trywait(uv_sem_t* sem) {
+  if (platform_needs_custom_semaphore)
+    return uv__custom_sem_trywait(sem);
+  else
+    return uv__sem_trywait(sem);
+}
+
+#endif /* defined(__APPLE__) && defined(__MACH__) */
+
+
+#if defined(__APPLE__) && defined(__MACH__) || defined(__MVS__)
+
+int uv_cond_init(uv_cond_t* cond) {
+  return UV__ERR(pthread_cond_init(cond, NULL));
+}
+
+#else /* !(defined(__APPLE__) && defined(__MACH__)) */
+
+int uv_cond_init(uv_cond_t* cond) {
+  pthread_condattr_t attr;
+  int err;
+
+  err = pthread_condattr_init(&attr);
+  if (err)
+    return UV__ERR(err);
+
+  err = pthread_condattr_setclock(&attr, CLOCK_MONOTONIC);
+  if (err)
+    goto error2;
+
+  err = pthread_cond_init(cond, &attr);
+  if (err)
+    goto error2;
+
+  err = pthread_condattr_destroy(&attr);
+  if (err)
+    goto error;
+
+  return 0;
+
+error:
+  pthread_cond_destroy(cond);
+error2:
+  pthread_condattr_destroy(&attr);
+  return UV__ERR(err);
+}
+
+#endif /* defined(__APPLE__) && defined(__MACH__) */
+
+void uv_cond_destroy(uv_cond_t* cond) {
+#if defined(__APPLE__) && defined(__MACH__)
+  /* It has been reported that destroying condition variables that have been
+   * signalled but not waited on can sometimes result in application crashes.
+   * See https://codereview.chromium.org/1323293005.
+   */
+  pthread_mutex_t mutex;
+  struct timespec ts;
+  int err;
+
+  if (pthread_mutex_init(&mutex, NULL))
+    abort();
+
+  if (pthread_mutex_lock(&mutex))
+    abort();
+
+  ts.tv_sec = 0;
+  ts.tv_nsec = 1;
+
+  err = pthread_cond_timedwait_relative_np(cond, &mutex, &ts);
+  if (err != 0 && err != ETIMEDOUT)
+    abort();
+
+  if (pthread_mutex_unlock(&mutex))
+    abort();
+
+  if (pthread_mutex_destroy(&mutex))
+    abort();
+#endif /* defined(__APPLE__) && defined(__MACH__) */
+
+  if (pthread_cond_destroy(cond))
+    abort();
+}
+
+void uv_cond_signal(uv_cond_t* cond) {
+  if (pthread_cond_signal(cond))
+    abort();
+}
+
+void uv_cond_broadcast(uv_cond_t* cond) {
+  if (pthread_cond_broadcast(cond))
+    abort();
+}
+
+void uv_cond_wait(uv_cond_t* cond, uv_mutex_t* mutex) {
+  if (pthread_cond_wait(cond, mutex))
+    abort();
+}
+
+
+int uv_cond_timedwait(uv_cond_t* cond, uv_mutex_t* mutex, uint64_t timeout) {
+  int r;
+  struct timespec ts;
+#if defined(__MVS__)
+  struct timeval tv;
+#endif
+
+#if defined(__APPLE__) && defined(__MACH__)
+  ts.tv_sec = timeout / NANOSEC;
+  ts.tv_nsec = timeout % NANOSEC;
+  r = pthread_cond_timedwait_relative_np(cond, mutex, &ts);
+#else
+#if defined(__MVS__)
+  if (gettimeofday(&tv, NULL))
+    abort();
+  timeout += tv.tv_sec * NANOSEC + tv.tv_usec * 1e3;
+#else
+  timeout += uv__hrtime(UV_CLOCK_PRECISE);
+#endif
+  ts.tv_sec = timeout / NANOSEC;
+  ts.tv_nsec = timeout % NANOSEC;
+  r = pthread_cond_timedwait(cond, mutex, &ts);
+#endif
+
+
+  if (r == 0)
+    return 0;
+
+  if (r == ETIMEDOUT)
+    return UV_ETIMEDOUT;
+
+  abort();
+#ifndef __SUNPRO_C
+  return UV_EINVAL;  /* Satisfy the compiler. */
+#endif
+}
+
+
+int uv_key_create(uv_key_t* key) {
+  return UV__ERR(pthread_key_create(key, NULL));
+}
+
+
+void uv_key_delete(uv_key_t* key) {
+  if (pthread_key_delete(*key))
+    abort();
+}
+
+
+void* uv_key_get(uv_key_t* key) {
+  return pthread_getspecific(*key);
+}
+
+
+void uv_key_set(uv_key_t* key, void* value) {
+  if (pthread_setspecific(*key, value))
+    abort();
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/tty.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/tty.cpp
new file mode 100644
index 0000000..ed81e26
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/tty.cpp
@@ -0,0 +1,467 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+#include "spinlock.h"
+
+#include <stdlib.h>
+#include <assert.h>
+#include <unistd.h>
+#include <termios.h>
+#include <errno.h>
+#include <sys/ioctl.h>
+
+#if defined(__MVS__) && !defined(IMAXBEL)
+#define IMAXBEL 0
+#endif
+
+#if defined(__PASE__)
+/* On IBM i PASE, for better compatibility with running interactive programs in
+ * a 5250 environment, isatty() will return true for the stdin/stdout/stderr
+ * streams created by QSH/QP2TERM.
+ *
+ * For more, see docs on PASE_STDIO_ISATTY in
+ * https://www.ibm.com/support/knowledgecenter/ssw_ibm_i_74/apis/pase_environ.htm
+ *
+ * This behavior causes problems for Node as it expects that if isatty() returns
+ * true that TTY ioctls will be supported by that fd (which is not an
+ * unreasonable expectation) and when they don't it crashes with assertion
+ * errors.
+ *
+ * Here, we create our own version of isatty() that uses ioctl() to identify
+ * whether the fd is *really* a TTY or not.
+ */
+static int isreallyatty(int file) {
+  int rc;
+ 
+  rc = !ioctl(file, TXISATTY + 0x81, NULL);
+  if (!rc && errno != EBADF)
+      errno = ENOTTY;
+
+  return rc;
+}
+#define isatty(fd) isreallyatty(fd)
+#endif
+
+static int orig_termios_fd = -1;
+static struct termios orig_termios;
+static uv_spinlock_t termios_spinlock = UV_SPINLOCK_INITIALIZER;
+
+int uv__tcsetattr(int fd, int how, const struct termios *term) {
+  int rc;
+
+  do
+    rc = tcsetattr(fd, how, term);
+  while (rc == -1 && errno == EINTR);
+
+  if (rc == -1)
+    return UV__ERR(errno);
+
+  return 0;
+}
+
+static int uv__tty_is_peripheral(const int fd) {
+  int result;
+#if defined(__linux__) || defined(__FreeBSD__) || defined(__FreeBSD_kernel__)
+  int dummy;
+
+  result = ioctl(fd, TIOCGPTN, &dummy) != 0;
+#elif defined(__APPLE__)
+  char dummy[256];
+
+  result = ioctl(fd, TIOCPTYGNAME, &dummy) != 0;
+#elif defined(__NetBSD__)
+  /*
+   * NetBSD as an extension returns with ptsname(3) and ptsname_r(3) the
+   * peripheral device name for both descriptors, the controller one and
+   * peripheral one.
+   *
+   * Implement function to compare major device number with pts devices.
+   *
+   * The major numbers are machine-dependent, on NetBSD/amd64 they are
+   * respectively:
+   *  - controller tty: ptc - major 6
+   *  - peripheral tty:  pts - major 5
+   */
+
+  struct stat sb;
+  /* Lookup device's major for the pts driver and cache it. */
+  static devmajor_t pts = NODEVMAJOR;
+
+  if (pts == NODEVMAJOR) {
+    pts = getdevmajor("pts", S_IFCHR);
+    if (pts == NODEVMAJOR)
+      abort();
+  }
+
+  /* Lookup stat structure behind the file descriptor. */
+  if (fstat(fd, &sb) != 0)
+    abort();
+
+  /* Assert character device. */
+  if (!S_ISCHR(sb.st_mode))
+    abort();
+
+  /* Assert valid major. */
+  if (major(sb.st_rdev) == NODEVMAJOR)
+    abort();
+
+  result = (pts == major(sb.st_rdev));
+#else
+  /* Fallback to ptsname
+   */
+  result = ptsname(fd) == NULL;
+#endif
+  return result;
+}
+
+int uv_tty_init(uv_loop_t* loop, uv_tty_t* tty, int fd, int unused) {
+  uv_handle_type type;
+  int flags;
+  int newfd;
+  int r;
+  int saved_flags;
+  int mode;
+  char path[256];
+  (void)unused; /* deprecated parameter is no longer needed */
+
+  /* File descriptors that refer to files cannot be monitored with epoll.
+   * That restriction also applies to character devices like /dev/random
+   * (but obviously not /dev/tty.)
+   */
+  type = uv_guess_handle(fd);
+  if (type == UV_FILE || type == UV_UNKNOWN_HANDLE)
+    return UV_EINVAL;
+
+  flags = 0;
+  newfd = -1;
+
+  /* Save the fd flags in case we need to restore them due to an error. */
+  do
+    saved_flags = fcntl(fd, F_GETFL);
+  while (saved_flags == -1 && errno == EINTR);
+
+  if (saved_flags == -1)
+    return UV__ERR(errno);
+  mode = saved_flags & O_ACCMODE;
+
+  /* Reopen the file descriptor when it refers to a tty. This lets us put the
+   * tty in non-blocking mode without affecting other processes that share it
+   * with us.
+   *
+   * Example: `node | cat` - if we put our fd 0 in non-blocking mode, it also
+   * affects fd 1 of `cat` because both file descriptors refer to the same
+   * struct file in the kernel. When we reopen our fd 0, it points to a
+   * different struct file, hence changing its properties doesn't affect
+   * other processes.
+   */
+  if (type == UV_TTY) {
+    /* Reopening a pty in controller mode won't work either because the reopened
+     * pty will be in peripheral mode (*BSD) or reopening will allocate a new
+     * controller/peripheral pair (Linux). Therefore check if the fd points to a
+     * peripheral device.
+     */
+    if (uv__tty_is_peripheral(fd) && ttyname_r(fd, path, sizeof(path)) == 0)
+      r = uv__open_cloexec(path, mode | O_NOCTTY);
+    else
+      r = -1;
+
+    if (r < 0) {
+      /* fallback to using blocking writes */
+      if (mode != O_RDONLY)
+        flags |= UV_HANDLE_BLOCKING_WRITES;
+      goto skip;
+    }
+
+    newfd = r;
+
+    r = uv__dup2_cloexec(newfd, fd);
+    if (r < 0 && r != UV_EINVAL) {
+      /* EINVAL means newfd == fd which could conceivably happen if another
+       * thread called close(fd) between our calls to isatty() and open().
+       * That's a rather unlikely event but let's handle it anyway.
+       */
+      uv__close(newfd);
+      return r;
+    }
+
+    fd = newfd;
+  }
+
+skip:
+  uv__stream_init(loop, (uv_stream_t*) tty, UV_TTY);
+
+  /* If anything fails beyond this point we need to remove the handle from
+   * the handle queue, since it was added by uv__handle_init in uv_stream_init.
+   */
+
+  if (!(flags & UV_HANDLE_BLOCKING_WRITES))
+    uv__nonblock(fd, 1);
+
+#if defined(__APPLE__)
+  r = uv__stream_try_select((uv_stream_t*) tty, &fd);
+  if (r) {
+    int rc = r;
+    if (newfd != -1)
+      uv__close(newfd);
+    QUEUE_REMOVE(&tty->handle_queue);
+    do
+      r = fcntl(fd, F_SETFL, saved_flags);
+    while (r == -1 && errno == EINTR);
+    return rc;
+  }
+#endif
+
+  if (mode != O_WRONLY)
+    flags |= UV_HANDLE_READABLE;
+  if (mode != O_RDONLY)
+    flags |= UV_HANDLE_WRITABLE;
+
+  uv__stream_open((uv_stream_t*) tty, fd, flags);
+  tty->mode = UV_TTY_MODE_NORMAL;
+
+  return 0;
+}
+
+static void uv__tty_make_raw(struct termios* tio) {
+  assert(tio != NULL);
+
+#if defined __sun || defined __MVS__
+  /*
+   * This implementation of cfmakeraw for Solaris and derivatives is taken from
+   * http://www.perkin.org.uk/posts/solaris-portability-cfmakeraw.html.
+   */
+  tio->c_iflag &= ~(IMAXBEL | IGNBRK | BRKINT | PARMRK | ISTRIP | INLCR |
+                    IGNCR | ICRNL | IXON);
+  tio->c_oflag &= ~OPOST;
+  tio->c_lflag &= ~(ECHO | ECHONL | ICANON | ISIG | IEXTEN);
+  tio->c_cflag &= ~(CSIZE | PARENB);
+  tio->c_cflag |= CS8;
+
+  /*
+   * By default, most software expects a pending read to block until at
+   * least one byte becomes available.  As per termio(7I), this requires
+   * setting the MIN and TIME parameters appropriately.
+   *
+   * As a somewhat unfortunate artifact of history, the MIN and TIME slots
+   * in the control character array overlap with the EOF and EOL slots used
+   * for canonical mode processing.  Because the EOF character needs to be
+   * the ASCII EOT value (aka Control-D), it has the byte value 4.  When
+   * switching to raw mode, this is interpreted as a MIN value of 4; i.e.,
+   * reads will block until at least four bytes have been input.
+   *
+   * Other platforms with a distinct MIN slot like Linux and FreeBSD appear
+   * to default to a MIN value of 1, so we'll force that value here:
+   */
+  tio->c_cc[VMIN] = 1;
+  tio->c_cc[VTIME] = 0;
+#else
+  cfmakeraw(tio);
+#endif /* #ifdef __sun */
+}
+
+int uv_tty_set_mode(uv_tty_t* tty, uv_tty_mode_t mode) {
+  struct termios tmp;
+  int fd;
+  int rc;
+
+  if (tty->mode == (int) mode)
+    return 0;
+
+  fd = uv__stream_fd(tty);
+  if (tty->mode == UV_TTY_MODE_NORMAL && mode != UV_TTY_MODE_NORMAL) {
+    do
+      rc = tcgetattr(fd, &tty->orig_termios);
+    while (rc == -1 && errno == EINTR);
+
+    if (rc == -1)
+      return UV__ERR(errno);
+
+    /* This is used for uv_tty_reset_mode() */
+    uv_spinlock_lock(&termios_spinlock);
+    if (orig_termios_fd == -1) {
+      orig_termios = tty->orig_termios;
+      orig_termios_fd = fd;
+    }
+    uv_spinlock_unlock(&termios_spinlock);
+  }
+
+  tmp = tty->orig_termios;
+  switch (mode) {
+    case UV_TTY_MODE_NORMAL:
+      break;
+    case UV_TTY_MODE_RAW:
+      tmp.c_iflag &= ~(BRKINT | ICRNL | INPCK | ISTRIP | IXON);
+      tmp.c_oflag |= (ONLCR);
+      tmp.c_cflag |= (CS8);
+      tmp.c_lflag &= ~(ECHO | ICANON | IEXTEN | ISIG);
+      tmp.c_cc[VMIN] = 1;
+      tmp.c_cc[VTIME] = 0;
+      break;
+    case UV_TTY_MODE_IO:
+      uv__tty_make_raw(&tmp);
+      break;
+  }
+
+  /* Apply changes after draining */
+  rc = uv__tcsetattr(fd, TCSADRAIN, &tmp);
+  if (rc == 0)
+    tty->mode = mode;
+
+  return rc;
+}
+
+
+int uv_tty_get_winsize(uv_tty_t* tty, int* width, int* height) {
+  struct winsize ws;
+  int err;
+
+  do
+    err = ioctl(uv__stream_fd(tty), TIOCGWINSZ, &ws);
+  while (err == -1 && errno == EINTR);
+
+  if (err == -1)
+    return UV__ERR(errno);
+
+  *width = ws.ws_col;
+  *height = ws.ws_row;
+
+  return 0;
+}
+
+
+uv_handle_type uv_guess_handle(uv_file file) {
+  struct sockaddr_storage ss;
+  struct stat s;
+  socklen_t len;
+  int type;
+
+  if (file < 0)
+    return UV_UNKNOWN_HANDLE;
+
+  if (isatty(file))
+    return UV_TTY;
+
+  if (fstat(file, &s)) {
+#if defined(__PASE__)
+    /* On ibmi receiving RST from TCP instead of FIN immediately puts fd into
+     * an error state. fstat will return EINVAL, getsockname will also return
+     * EINVAL, even if sockaddr_storage is valid. (If file does not refer to a
+     * socket, ENOTSOCK is returned instead.)
+     * In such cases, we will permit the user to open the connection as uv_tcp
+     * still, so that the user can get immediately notified of the error in
+     * their read callback and close this fd.
+     */
+    len = sizeof(ss);
+    if (getsockname(file, (struct sockaddr*) &ss, &len)) {
+      if (errno == EINVAL)
+        return UV_TCP;
+    }
+#endif
+    return UV_UNKNOWN_HANDLE;
+  }
+
+  if (S_ISREG(s.st_mode))
+    return UV_FILE;
+
+  if (S_ISCHR(s.st_mode))
+    return UV_FILE;  /* XXX UV_NAMED_PIPE? */
+
+  if (S_ISFIFO(s.st_mode))
+    return UV_NAMED_PIPE;
+
+  if (!S_ISSOCK(s.st_mode))
+    return UV_UNKNOWN_HANDLE;
+
+  len = sizeof(ss);
+  if (getsockname(file, (struct sockaddr*) &ss, &len)) {
+#if defined(_AIX)
+    /* On aix receiving RST from TCP instead of FIN immediately puts fd into
+     * an error state. In such case getsockname will return EINVAL, even if
+     * sockaddr_storage is valid.
+     * In such cases, we will permit the user to open the connection as uv_tcp
+     * still, so that the user can get immediately notified of the error in
+     * their read callback and close this fd.
+     */
+    if (errno == EINVAL) {
+      return UV_TCP;
+    }
+#endif
+    return UV_UNKNOWN_HANDLE;
+  }
+
+  len = sizeof(type);
+  if (getsockopt(file, SOL_SOCKET, SO_TYPE, &type, &len))
+    return UV_UNKNOWN_HANDLE;
+
+  if (type == SOCK_DGRAM)
+    if (ss.ss_family == AF_INET || ss.ss_family == AF_INET6)
+      return UV_UDP;
+
+  if (type == SOCK_STREAM) {
+#if defined(_AIX) || defined(__DragonFly__)
+    /* on AIX/DragonFly the getsockname call returns an empty sa structure
+     * for sockets of type AF_UNIX.  For all other types it will
+     * return a properly filled in structure.
+     */
+    if (len == 0)
+      return UV_NAMED_PIPE;
+#endif /* defined(_AIX) || defined(__DragonFly__) */
+
+    if (ss.ss_family == AF_INET || ss.ss_family == AF_INET6)
+      return UV_TCP;
+    if (ss.ss_family == AF_UNIX)
+      return UV_NAMED_PIPE;
+  }
+
+  return UV_UNKNOWN_HANDLE;
+}
+
+
+/* This function is async signal-safe, meaning that it's safe to call from
+ * inside a signal handler _unless_ execution was inside uv_tty_set_mode()'s
+ * critical section when the signal was raised.
+ */
+int uv_tty_reset_mode(void) {
+  int saved_errno;
+  int err;
+
+  saved_errno = errno;
+  if (!uv_spinlock_trylock(&termios_spinlock))
+    return UV_EBUSY;  /* In uv_tty_set_mode(). */
+
+  err = 0;
+  if (orig_termios_fd != -1)
+    err = uv__tcsetattr(orig_termios_fd, TCSANOW, &orig_termios);
+
+  uv_spinlock_unlock(&termios_spinlock);
+  errno = saved_errno;
+
+  return err;
+}
+
+void uv_tty_set_vterm_state(uv_tty_vtermstate_t state) {
+}
+
+int uv_tty_get_vterm_state(uv_tty_vtermstate_t* state) {
+  return UV_ENOTSUP;
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/udp.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/udp.cpp
new file mode 100644
index 0000000..a130aea
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/unix/udp.cpp
@@ -0,0 +1,1416 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <assert.h>
+#include <string.h>
+#include <errno.h>
+#include <stdlib.h>
+#include <unistd.h>
+#if defined(__MVS__)
+#include <xti.h>
+#endif
+#include <sys/un.h>
+
+#if defined(IPV6_JOIN_GROUP) && !defined(IPV6_ADD_MEMBERSHIP)
+# define IPV6_ADD_MEMBERSHIP IPV6_JOIN_GROUP
+#endif
+
+#if defined(IPV6_LEAVE_GROUP) && !defined(IPV6_DROP_MEMBERSHIP)
+# define IPV6_DROP_MEMBERSHIP IPV6_LEAVE_GROUP
+#endif
+
+union uv__sockaddr {
+  struct sockaddr_in6 in6;
+  struct sockaddr_in in;
+  struct sockaddr addr;
+};
+
+static void uv__udp_run_completed(uv_udp_t* handle);
+static void uv__udp_io(uv_loop_t* loop, uv__io_t* w, unsigned int revents);
+static void uv__udp_recvmsg(uv_udp_t* handle);
+static void uv__udp_sendmsg(uv_udp_t* handle);
+static int uv__udp_maybe_deferred_bind(uv_udp_t* handle,
+                                       int domain,
+                                       unsigned int flags);
+
+#if HAVE_MMSG
+
+#define UV__MMSG_MAXWIDTH 20
+
+static int uv__udp_recvmmsg(uv_udp_t* handle, uv_buf_t* buf);
+static void uv__udp_sendmmsg(uv_udp_t* handle);
+
+static int uv__recvmmsg_avail;
+static int uv__sendmmsg_avail;
+static uv_once_t once = UV_ONCE_INIT;
+
+static void uv__udp_mmsg_init(void) {
+  int ret;
+  int s;
+  s = uv__socket(AF_INET, SOCK_DGRAM, 0);
+  if (s < 0)
+    return;
+  ret = uv__sendmmsg(s, NULL, 0);
+  if (ret == 0 || errno != ENOSYS) {
+    uv__sendmmsg_avail = 1;
+    uv__recvmmsg_avail = 1;
+  } else {
+    ret = uv__recvmmsg(s, NULL, 0);
+    if (ret == 0 || errno != ENOSYS)
+      uv__recvmmsg_avail = 1;
+  }
+  uv__close(s);
+}
+
+#endif
+
+void uv__udp_close(uv_udp_t* handle) {
+  uv__io_close(handle->loop, &handle->io_watcher);
+  uv__handle_stop(handle);
+
+  if (handle->io_watcher.fd != -1) {
+    uv__close(handle->io_watcher.fd);
+    handle->io_watcher.fd = -1;
+  }
+}
+
+
+void uv__udp_finish_close(uv_udp_t* handle) {
+  uv_udp_send_t* req;
+  QUEUE* q;
+
+  assert(!uv__io_active(&handle->io_watcher, POLLIN | POLLOUT));
+  assert(handle->io_watcher.fd == -1);
+
+  while (!QUEUE_EMPTY(&handle->write_queue)) {
+    q = QUEUE_HEAD(&handle->write_queue);
+    QUEUE_REMOVE(q);
+
+    req = QUEUE_DATA(q, uv_udp_send_t, queue);
+    req->status = UV_ECANCELED;
+    QUEUE_INSERT_TAIL(&handle->write_completed_queue, &req->queue);
+  }
+
+  uv__udp_run_completed(handle);
+
+  assert(handle->send_queue_size == 0);
+  assert(handle->send_queue_count == 0);
+
+  /* Now tear down the handle. */
+  handle->recv_cb = NULL;
+  handle->alloc_cb = NULL;
+  /* but _do not_ touch close_cb */
+}
+
+
+static void uv__udp_run_completed(uv_udp_t* handle) {
+  uv_udp_send_t* req;
+  QUEUE* q;
+
+  assert(!(handle->flags & UV_HANDLE_UDP_PROCESSING));
+  handle->flags |= UV_HANDLE_UDP_PROCESSING;
+
+  while (!QUEUE_EMPTY(&handle->write_completed_queue)) {
+    q = QUEUE_HEAD(&handle->write_completed_queue);
+    QUEUE_REMOVE(q);
+
+    req = QUEUE_DATA(q, uv_udp_send_t, queue);
+    uv__req_unregister(handle->loop, req);
+
+    handle->send_queue_size -= uv__count_bufs(req->bufs, req->nbufs);
+    handle->send_queue_count--;
+
+    if (req->bufs != req->bufsml)
+      uv__free(req->bufs);
+    req->bufs = NULL;
+
+    if (req->send_cb == NULL)
+      continue;
+
+    /* req->status >= 0 == bytes written
+     * req->status <  0 == errno
+     */
+    if (req->status >= 0)
+      req->send_cb(req, 0);
+    else
+      req->send_cb(req, req->status);
+  }
+
+  if (QUEUE_EMPTY(&handle->write_queue)) {
+    /* Pending queue and completion queue empty, stop watcher. */
+    uv__io_stop(handle->loop, &handle->io_watcher, POLLOUT);
+    if (!uv__io_active(&handle->io_watcher, POLLIN))
+      uv__handle_stop(handle);
+  }
+
+  handle->flags &= ~UV_HANDLE_UDP_PROCESSING;
+}
+
+
+static void uv__udp_io(uv_loop_t* loop, uv__io_t* w, unsigned int revents) {
+  uv_udp_t* handle;
+
+  handle = container_of(w, uv_udp_t, io_watcher);
+  assert(handle->type == UV_UDP);
+
+  if (revents & POLLIN)
+    uv__udp_recvmsg(handle);
+
+  if (revents & POLLOUT) {
+    uv__udp_sendmsg(handle);
+    uv__udp_run_completed(handle);
+  }
+}
+
+#if HAVE_MMSG
+static int uv__udp_recvmmsg(uv_udp_t* handle, uv_buf_t* buf) {
+  struct sockaddr_in6 peers[UV__MMSG_MAXWIDTH];
+  struct iovec iov[UV__MMSG_MAXWIDTH];
+  struct uv__mmsghdr msgs[UV__MMSG_MAXWIDTH];
+  ssize_t nread;
+  uv_buf_t chunk_buf;
+  size_t chunks;
+  int flags;
+  size_t k;
+
+  /* prepare structures for recvmmsg */
+  chunks = buf->len / UV__UDP_DGRAM_MAXSIZE;
+  if (chunks > ARRAY_SIZE(iov))
+    chunks = ARRAY_SIZE(iov);
+  for (k = 0; k < chunks; ++k) {
+    iov[k].iov_base = buf->base + k * UV__UDP_DGRAM_MAXSIZE;
+    iov[k].iov_len = UV__UDP_DGRAM_MAXSIZE;
+    memset(&msgs[k].msg_hdr, 0, sizeof(msgs[k].msg_hdr));
+    msgs[k].msg_hdr.msg_iov = iov + k;
+    msgs[k].msg_hdr.msg_iovlen = 1;
+    msgs[k].msg_hdr.msg_name = peers + k;
+    msgs[k].msg_hdr.msg_namelen = sizeof(peers[0]);
+    msgs[k].msg_hdr.msg_control = NULL;
+    msgs[k].msg_hdr.msg_controllen = 0;
+    msgs[k].msg_hdr.msg_flags = 0;
+  }
+
+  do
+    nread = uv__recvmmsg(handle->io_watcher.fd, msgs, chunks);
+  while (nread == -1 && errno == EINTR);
+
+  if (nread < 1) {
+    if (nread == 0 || errno == EAGAIN || errno == EWOULDBLOCK)
+      handle->recv_cb(handle, 0, buf, NULL, 0);
+    else
+      handle->recv_cb(handle, UV__ERR(errno), buf, NULL, 0);
+  } else {
+    /* pass each chunk to the application */
+    for (k = 0; k < (size_t) nread && handle->recv_cb != NULL; k++) {
+      flags = UV_UDP_MMSG_CHUNK;
+      if (msgs[k].msg_hdr.msg_flags & MSG_TRUNC)
+        flags |= UV_UDP_PARTIAL;
+
+      chunk_buf = uv_buf_init((char*) iov[k].iov_base, iov[k].iov_len);
+      handle->recv_cb(handle,
+                      msgs[k].msg_len,
+                      &chunk_buf,
+                      (const sockaddr*) msgs[k].msg_hdr.msg_name,
+                      flags);
+    }
+
+    /* one last callback so the original buffer is freed */
+    if (handle->recv_cb != NULL)
+      handle->recv_cb(handle, 0, buf, NULL, UV_UDP_MMSG_FREE);
+  }
+  return nread;
+}
+#endif
+
+static void uv__udp_recvmsg(uv_udp_t* handle) {
+  struct sockaddr_storage peer;
+  struct msghdr h;
+  ssize_t nread;
+  uv_buf_t buf;
+  int flags;
+  int count;
+
+  assert(handle->recv_cb != NULL);
+  assert(handle->alloc_cb != NULL);
+
+  /* Prevent loop starvation when the data comes in as fast as (or faster than)
+   * we can read it. XXX Need to rearm fd if we switch to edge-triggered I/O.
+   */
+  count = 32;
+
+  do {
+    buf = uv_buf_init(NULL, 0);
+    handle->alloc_cb((uv_handle_t*) handle, UV__UDP_DGRAM_MAXSIZE, &buf);
+    if (buf.base == NULL || buf.len == 0) {
+      handle->recv_cb(handle, UV_ENOBUFS, &buf, NULL, 0);
+      return;
+    }
+    assert(buf.base != NULL);
+
+#if HAVE_MMSG
+    if (uv_udp_using_recvmmsg(handle)) {
+      nread = uv__udp_recvmmsg(handle, &buf);
+      if (nread > 0)
+        count -= nread;
+      continue;
+    }
+#endif
+
+    memset(&h, 0, sizeof(h));
+    memset(&peer, 0, sizeof(peer));
+    h.msg_name = &peer;
+    h.msg_namelen = sizeof(peer);
+    h.msg_iov = (iovec*) &buf;
+    h.msg_iovlen = 1;
+
+    do {
+      nread = recvmsg(handle->io_watcher.fd, &h, 0);
+    }
+    while (nread == -1 && errno == EINTR);
+
+    if (nread == -1) {
+      if (errno == EAGAIN || errno == EWOULDBLOCK)
+        handle->recv_cb(handle, 0, &buf, NULL, 0);
+      else
+        handle->recv_cb(handle, UV__ERR(errno), &buf, NULL, 0);
+    }
+    else {
+      flags = 0;
+      if (h.msg_flags & MSG_TRUNC)
+        flags |= UV_UDP_PARTIAL;
+
+      handle->recv_cb(handle, nread, &buf, (const struct sockaddr*) &peer, flags);
+    }
+    count--;
+  }
+  /* recv_cb callback may decide to pause or close the handle */
+  while (nread != -1
+      && count > 0
+      && handle->io_watcher.fd != -1
+      && handle->recv_cb != NULL);
+}
+
+#if HAVE_MMSG
+static void uv__udp_sendmmsg(uv_udp_t* handle) {
+  uv_udp_send_t* req;
+  struct uv__mmsghdr h[UV__MMSG_MAXWIDTH];
+  struct uv__mmsghdr *p;
+  QUEUE* q;
+  ssize_t npkts;
+  size_t pkts;
+  size_t i;
+
+  if (QUEUE_EMPTY(&handle->write_queue))
+    return;
+
+write_queue_drain:
+  for (pkts = 0, q = QUEUE_HEAD(&handle->write_queue);
+       pkts < UV__MMSG_MAXWIDTH && q != &handle->write_queue;
+       ++pkts, q = QUEUE_HEAD(q)) {
+    assert(q != NULL);
+    req = QUEUE_DATA(q, uv_udp_send_t, queue);
+    assert(req != NULL);
+
+    p = &h[pkts];
+    memset(p, 0, sizeof(*p));
+    if (req->addr.ss_family == AF_UNSPEC) {
+      p->msg_hdr.msg_name = NULL;
+      p->msg_hdr.msg_namelen = 0;
+    } else {
+      p->msg_hdr.msg_name = &req->addr;
+      if (req->addr.ss_family == AF_INET6)
+        p->msg_hdr.msg_namelen = sizeof(struct sockaddr_in6);
+      else if (req->addr.ss_family == AF_INET)
+        p->msg_hdr.msg_namelen = sizeof(struct sockaddr_in);
+      else if (req->addr.ss_family == AF_UNIX)
+        p->msg_hdr.msg_namelen = sizeof(struct sockaddr_un);
+      else {
+        assert(0 && "unsupported address family");
+        abort();
+      }
+    }
+    h[pkts].msg_hdr.msg_iov = (struct iovec*) req->bufs;
+    h[pkts].msg_hdr.msg_iovlen = req->nbufs;
+  }
+
+  do
+    npkts = uv__sendmmsg(handle->io_watcher.fd, h, pkts);
+  while (npkts == -1 && errno == EINTR);
+
+  if (npkts < 1) {
+    if (errno == EAGAIN || errno == EWOULDBLOCK || errno == ENOBUFS)
+      return;
+    for (i = 0, q = QUEUE_HEAD(&handle->write_queue);
+         i < pkts && q != &handle->write_queue;
+         ++i, q = QUEUE_HEAD(&handle->write_queue)) {
+      assert(q != NULL);
+      req = QUEUE_DATA(q, uv_udp_send_t, queue);
+      assert(req != NULL);
+
+      req->status = UV__ERR(errno);
+      QUEUE_REMOVE(&req->queue);
+      QUEUE_INSERT_TAIL(&handle->write_completed_queue, &req->queue);
+    }
+    uv__io_feed(handle->loop, &handle->io_watcher);
+    return;
+  }
+
+  /* Safety: npkts known to be >0 below. Hence cast from ssize_t
+   * to size_t safe.
+   */
+  for (i = 0, q = QUEUE_HEAD(&handle->write_queue);
+       i < (size_t)npkts && q != &handle->write_queue;
+       ++i, q = QUEUE_HEAD(&handle->write_queue)) {
+    assert(q != NULL);
+    req = QUEUE_DATA(q, uv_udp_send_t, queue);
+    assert(req != NULL);
+
+    req->status = req->bufs[0].len;
+
+    /* Sending a datagram is an atomic operation: either all data
+     * is written or nothing is (and EMSGSIZE is raised). That is
+     * why we don't handle partial writes. Just pop the request
+     * off the write queue and onto the completed queue, done.
+     */
+    QUEUE_REMOVE(&req->queue);
+    QUEUE_INSERT_TAIL(&handle->write_completed_queue, &req->queue);
+  }
+
+  /* couldn't batch everything, continue sending (jump to avoid stack growth) */
+  if (!QUEUE_EMPTY(&handle->write_queue))
+    goto write_queue_drain;
+  uv__io_feed(handle->loop, &handle->io_watcher);
+  return;
+}
+#endif
+
+static void uv__udp_sendmsg(uv_udp_t* handle) {
+  uv_udp_send_t* req;
+  struct msghdr h;
+  QUEUE* q;
+  ssize_t size;
+
+#if HAVE_MMSG
+  uv_once(&once, uv__udp_mmsg_init);
+  if (uv__sendmmsg_avail) {
+    uv__udp_sendmmsg(handle);
+    return;
+  }
+#endif
+
+  while (!QUEUE_EMPTY(&handle->write_queue)) {
+    q = QUEUE_HEAD(&handle->write_queue);
+    assert(q != NULL);
+
+    req = QUEUE_DATA(q, uv_udp_send_t, queue);
+    assert(req != NULL);
+
+    memset(&h, 0, sizeof h);
+    if (req->addr.ss_family == AF_UNSPEC) {
+      h.msg_name = NULL;
+      h.msg_namelen = 0;
+    } else {
+      h.msg_name = &req->addr;
+      if (req->addr.ss_family == AF_INET6)
+        h.msg_namelen = sizeof(struct sockaddr_in6);
+      else if (req->addr.ss_family == AF_INET)
+        h.msg_namelen = sizeof(struct sockaddr_in);
+      else if (req->addr.ss_family == AF_UNIX)
+        h.msg_namelen = sizeof(struct sockaddr_un);
+      else {
+        assert(0 && "unsupported address family");
+        abort();
+      }
+    }
+    h.msg_iov = (struct iovec*) req->bufs;
+    h.msg_iovlen = req->nbufs;
+
+    do {
+      size = sendmsg(handle->io_watcher.fd, &h, 0);
+    } while (size == -1 && errno == EINTR);
+
+    if (size == -1) {
+      if (errno == EAGAIN || errno == EWOULDBLOCK || errno == ENOBUFS)
+        break;
+    }
+
+    req->status = (size == -1 ? UV__ERR(errno) : size);
+
+    /* Sending a datagram is an atomic operation: either all data
+     * is written or nothing is (and EMSGSIZE is raised). That is
+     * why we don't handle partial writes. Just pop the request
+     * off the write queue and onto the completed queue, done.
+     */
+    QUEUE_REMOVE(&req->queue);
+    QUEUE_INSERT_TAIL(&handle->write_completed_queue, &req->queue);
+    uv__io_feed(handle->loop, &handle->io_watcher);
+  }
+}
+
+/* On the BSDs, SO_REUSEPORT implies SO_REUSEADDR but with some additional
+ * refinements for programs that use multicast.
+ *
+ * Linux as of 3.9 has a SO_REUSEPORT socket option but with semantics that
+ * are different from the BSDs: it _shares_ the port rather than steal it
+ * from the current listener.  While useful, it's not something we can emulate
+ * on other platforms so we don't enable it.
+ *
+ * zOS does not support getsockname with SO_REUSEPORT option when using
+ * AF_UNIX.
+ */
+static int uv__set_reuse(int fd) {
+  int yes;
+  yes = 1;
+
+#if defined(SO_REUSEPORT) && defined(__MVS__)
+  struct sockaddr_in sockfd;
+  unsigned int sockfd_len = sizeof(sockfd);
+  if (getsockname(fd, (struct sockaddr*) &sockfd, &sockfd_len) == -1)
+      return UV__ERR(errno);
+  if (sockfd.sin_family == AF_UNIX) {
+    if (setsockopt(fd, SOL_SOCKET, SO_REUSEADDR, &yes, sizeof(yes)))
+      return UV__ERR(errno);
+  } else {
+    if (setsockopt(fd, SOL_SOCKET, SO_REUSEPORT, &yes, sizeof(yes)))
+       return UV__ERR(errno);
+  }
+#elif defined(SO_REUSEPORT) && !defined(__linux__) && !defined(__GNU__)
+  if (setsockopt(fd, SOL_SOCKET, SO_REUSEPORT, &yes, sizeof(yes)))
+    return UV__ERR(errno);
+#else
+  if (setsockopt(fd, SOL_SOCKET, SO_REUSEADDR, &yes, sizeof(yes)))
+    return UV__ERR(errno);
+#endif
+
+  return 0;
+}
+
+/*
+ * The Linux kernel suppresses some ICMP error messages by default for UDP
+ * sockets. Setting IP_RECVERR/IPV6_RECVERR on the socket enables full ICMP
+ * error reporting, hopefully resulting in faster failover to working name
+ * servers.
+ */
+static int uv__set_recverr(int fd, sa_family_t ss_family) {
+#if defined(__linux__)
+  int yes;
+
+  yes = 1;
+  if (ss_family == AF_INET) {
+    if (setsockopt(fd, IPPROTO_IP, IP_RECVERR, &yes, sizeof(yes)))
+      return UV__ERR(errno);
+  } else if (ss_family == AF_INET6) {
+    if (setsockopt(fd, IPPROTO_IPV6, IPV6_RECVERR, &yes, sizeof(yes)))
+       return UV__ERR(errno);
+  }
+#endif
+  return 0;
+}
+
+
+int uv__udp_bind(uv_udp_t* handle,
+                 const struct sockaddr* addr,
+                 unsigned int addrlen,
+                 unsigned int flags) {
+  int err;
+  int yes;
+  int fd;
+
+  /* Check for bad flags. */
+  if (flags & ~(UV_UDP_IPV6ONLY | UV_UDP_REUSEADDR | UV_UDP_LINUX_RECVERR))
+    return UV_EINVAL;
+
+  /* Cannot set IPv6-only mode on non-IPv6 socket. */
+  if ((flags & UV_UDP_IPV6ONLY) && addr->sa_family != AF_INET6)
+    return UV_EINVAL;
+
+  fd = handle->io_watcher.fd;
+  if (fd == -1) {
+    err = uv__socket(addr->sa_family, SOCK_DGRAM, 0);
+    if (err < 0)
+      return err;
+    fd = err;
+    handle->io_watcher.fd = fd;
+  }
+
+  if (flags & UV_UDP_LINUX_RECVERR) {
+    err = uv__set_recverr(fd, addr->sa_family);
+    if (err)
+      return err;
+  }
+
+  if (flags & UV_UDP_REUSEADDR) {
+    err = uv__set_reuse(fd);
+    if (err)
+      return err;
+  }
+
+  if (flags & UV_UDP_IPV6ONLY) {
+#ifdef IPV6_V6ONLY
+    yes = 1;
+    if (setsockopt(fd, IPPROTO_IPV6, IPV6_V6ONLY, &yes, sizeof yes) == -1) {
+      err = UV__ERR(errno);
+      return err;
+    }
+#else
+    err = UV_ENOTSUP;
+    return err;
+#endif
+  }
+
+  if (bind(fd, addr, addrlen)) {
+    err = UV__ERR(errno);
+    if (errno == EAFNOSUPPORT)
+      /* OSX, other BSDs and SunoS fail with EAFNOSUPPORT when binding a
+       * socket created with AF_INET to an AF_INET6 address or vice versa. */
+      err = UV_EINVAL;
+    return err;
+  }
+
+  if (addr->sa_family == AF_INET6)
+    handle->flags |= UV_HANDLE_IPV6;
+
+  handle->flags |= UV_HANDLE_BOUND;
+  return 0;
+}
+
+
+static int uv__udp_maybe_deferred_bind(uv_udp_t* handle,
+                                       int domain,
+                                       unsigned int flags) {
+  union uv__sockaddr taddr;
+  socklen_t addrlen;
+
+  if (handle->io_watcher.fd != -1)
+    return 0;
+
+  switch (domain) {
+  case AF_INET:
+  {
+    struct sockaddr_in* addr = &taddr.in;
+    memset(addr, 0, sizeof *addr);
+    addr->sin_family = AF_INET;
+    addr->sin_addr.s_addr = INADDR_ANY;
+    addrlen = sizeof *addr;
+    break;
+  }
+  case AF_INET6:
+  {
+    struct sockaddr_in6* addr = &taddr.in6;
+    memset(addr, 0, sizeof *addr);
+    addr->sin6_family = AF_INET6;
+    addr->sin6_addr = in6addr_any;
+    addrlen = sizeof *addr;
+    break;
+  }
+  default:
+    assert(0 && "unsupported address family");
+    abort();
+  }
+
+  return uv__udp_bind(handle, &taddr.addr, addrlen, flags);
+}
+
+
+int uv__udp_connect(uv_udp_t* handle,
+                    const struct sockaddr* addr,
+                    unsigned int addrlen) {
+  int err;
+
+  err = uv__udp_maybe_deferred_bind(handle, addr->sa_family, 0);
+  if (err)
+    return err;
+
+  do {
+    errno = 0;
+    err = connect(handle->io_watcher.fd, addr, addrlen);
+  } while (err == -1 && errno == EINTR);
+
+  if (err)
+    return UV__ERR(errno);
+
+  handle->flags |= UV_HANDLE_UDP_CONNECTED;
+
+  return 0;
+}
+
+/* From https://pubs.opengroup.org/onlinepubs/9699919799/functions/connect.html
+ * Any of uv supported UNIXs kernel should be standardized, but the kernel
+ * implementation logic not same, let's use pseudocode to explain the udp
+ * disconnect behaviors:
+ *
+ * Predefined stubs for pseudocode:
+ *   1. sodisconnect: The function to perform the real udp disconnect
+ *   2. pru_connect: The function to perform the real udp connect
+ *   3. so: The kernel object match with socket fd
+ *   4. addr: The sockaddr parameter from user space
+ *
+ * BSDs:
+ *   if(sodisconnect(so) == 0) { // udp disconnect succeed
+ *     if (addr->sa_len != so->addr->sa_len) return EINVAL;
+ *     if (addr->sa_family != so->addr->sa_family) return EAFNOSUPPORT;
+ *     pru_connect(so);
+ *   }
+ *   else return EISCONN;
+ *
+ * z/OS (same with Windows):
+ *   if(addr->sa_len < so->addr->sa_len) return EINVAL;
+ *   if (addr->sa_family == AF_UNSPEC) sodisconnect(so);
+ *
+ * AIX:
+ *   if(addr->sa_len != sizeof(struct sockaddr)) return EINVAL; // ignore ip proto version
+ *   if (addr->sa_family == AF_UNSPEC) sodisconnect(so);
+ *
+ * Linux,Others:
+ *   if(addr->sa_len < sizeof(struct sockaddr)) return EINVAL;
+ *   if (addr->sa_family == AF_UNSPEC) sodisconnect(so);
+ */
+int uv__udp_disconnect(uv_udp_t* handle) {
+    int r;
+#if defined(__MVS__)
+    struct sockaddr_storage addr;
+#else
+    struct sockaddr addr;
+#endif
+
+    memset(&addr, 0, sizeof(addr));
+
+#if defined(__MVS__)
+    addr.ss_family = AF_UNSPEC;
+#else
+    addr.sa_family = AF_UNSPEC;
+#endif
+
+    do {
+      errno = 0;
+#ifdef __PASE__
+      /* On IBMi a connectionless transport socket can be disconnected by
+       * either setting the addr parameter to NULL or setting the
+       * addr_length parameter to zero, and issuing another connect().
+       * https://www.ibm.com/docs/en/i/7.4?topic=ssw_ibm_i_74/apis/connec.htm
+       */
+      r = connect(handle->io_watcher.fd, (struct sockaddr*) NULL, 0);
+#else
+      r = connect(handle->io_watcher.fd, (struct sockaddr*) &addr, sizeof(addr));
+#endif
+    } while (r == -1 && errno == EINTR);
+
+    if (r == -1) {
+#if defined(BSD)  /* The macro BSD is from sys/param.h */
+      if (errno != EAFNOSUPPORT && errno != EINVAL)
+        return UV__ERR(errno);
+#else
+      return UV__ERR(errno);
+#endif
+    }
+
+    handle->flags &= ~UV_HANDLE_UDP_CONNECTED;
+    return 0;
+}
+
+int uv__udp_send(uv_udp_send_t* req,
+                 uv_udp_t* handle,
+                 const uv_buf_t bufs[],
+                 unsigned int nbufs,
+                 const struct sockaddr* addr,
+                 unsigned int addrlen,
+                 uv_udp_send_cb send_cb) {
+  int err;
+  int empty_queue;
+
+  assert(nbufs > 0);
+
+  if (addr) {
+    err = uv__udp_maybe_deferred_bind(handle, addr->sa_family, 0);
+    if (err)
+      return err;
+  }
+
+  /* It's legal for send_queue_count > 0 even when the write_queue is empty;
+   * it means there are error-state requests in the write_completed_queue that
+   * will touch up send_queue_size/count later.
+   */
+  empty_queue = (handle->send_queue_count == 0);
+
+  uv__req_init(handle->loop, req, UV_UDP_SEND);
+  assert(addrlen <= sizeof(req->addr));
+  if (addr == NULL)
+    req->addr.ss_family = AF_UNSPEC;
+  else
+    memcpy(&req->addr, addr, addrlen);
+  req->send_cb = send_cb;
+  req->handle = handle;
+  req->nbufs = nbufs;
+
+  req->bufs = req->bufsml;
+  if (nbufs > ARRAY_SIZE(req->bufsml))
+    req->bufs = (uv_buf_t*)uv__malloc(nbufs * sizeof(bufs[0]));
+
+  if (req->bufs == NULL) {
+    uv__req_unregister(handle->loop, req);
+    return UV_ENOMEM;
+  }
+
+  memcpy(req->bufs, bufs, nbufs * sizeof(bufs[0]));
+  handle->send_queue_size += uv__count_bufs(req->bufs, req->nbufs);
+  handle->send_queue_count++;
+  QUEUE_INSERT_TAIL(&handle->write_queue, &req->queue);
+  uv__handle_start(handle);
+
+  if (empty_queue && !(handle->flags & UV_HANDLE_UDP_PROCESSING)) {
+    uv__udp_sendmsg(handle);
+
+    /* `uv__udp_sendmsg` may not be able to do non-blocking write straight
+     * away. In such cases the `io_watcher` has to be queued for asynchronous
+     * write.
+     */
+    if (!QUEUE_EMPTY(&handle->write_queue))
+      uv__io_start(handle->loop, &handle->io_watcher, POLLOUT);
+  } else {
+    uv__io_start(handle->loop, &handle->io_watcher, POLLOUT);
+  }
+
+  return 0;
+}
+
+
+int uv__udp_try_send(uv_udp_t* handle,
+                     const uv_buf_t bufs[],
+                     unsigned int nbufs,
+                     const struct sockaddr* addr,
+                     unsigned int addrlen) {
+  int err;
+  struct msghdr h;
+  ssize_t size;
+
+  assert(nbufs > 0);
+
+  /* already sending a message */
+  if (handle->send_queue_count != 0)
+    return UV_EAGAIN;
+
+  if (addr) {
+    err = uv__udp_maybe_deferred_bind(handle, addr->sa_family, 0);
+    if (err)
+      return err;
+  } else {
+    assert(handle->flags & UV_HANDLE_UDP_CONNECTED);
+  }
+
+  memset(&h, 0, sizeof h);
+  h.msg_name = (struct sockaddr*) addr;
+  h.msg_namelen = addrlen;
+  h.msg_iov = (struct iovec*) bufs;
+  h.msg_iovlen = nbufs;
+
+  do {
+    size = sendmsg(handle->io_watcher.fd, &h, 0);
+  } while (size == -1 && errno == EINTR);
+
+  if (size == -1) {
+    if (errno == EAGAIN || errno == EWOULDBLOCK || errno == ENOBUFS)
+      return UV_EAGAIN;
+    else
+      return UV__ERR(errno);
+  }
+
+  return size;
+}
+
+
+static int uv__udp_set_membership4(uv_udp_t* handle,
+                                   const struct sockaddr_in* multicast_addr,
+                                   const char* interface_addr,
+                                   uv_membership membership) {
+  struct ip_mreq mreq;
+  int optname;
+  int err;
+
+  memset(&mreq, 0, sizeof mreq);
+
+  if (interface_addr) {
+    err = uv_inet_pton(AF_INET, interface_addr, &mreq.imr_interface.s_addr);
+    if (err)
+      return err;
+  } else {
+    mreq.imr_interface.s_addr = htonl(INADDR_ANY);
+  }
+
+  mreq.imr_multiaddr.s_addr = multicast_addr->sin_addr.s_addr;
+
+  switch (membership) {
+  case UV_JOIN_GROUP:
+    optname = IP_ADD_MEMBERSHIP;
+    break;
+  case UV_LEAVE_GROUP:
+    optname = IP_DROP_MEMBERSHIP;
+    break;
+  default:
+    return UV_EINVAL;
+  }
+
+  if (setsockopt(handle->io_watcher.fd,
+                 IPPROTO_IP,
+                 optname,
+                 &mreq,
+                 sizeof(mreq))) {
+#if defined(__MVS__)
+  if (errno == ENXIO)
+    return UV_ENODEV;
+#endif
+    return UV__ERR(errno);
+  }
+
+  return 0;
+}
+
+
+static int uv__udp_set_membership6(uv_udp_t* handle,
+                                   const struct sockaddr_in6* multicast_addr,
+                                   const char* interface_addr,
+                                   uv_membership membership) {
+  int optname;
+  struct ipv6_mreq mreq;
+  struct sockaddr_in6 addr6;
+
+  memset(&mreq, 0, sizeof mreq);
+
+  if (interface_addr) {
+    if (uv_ip6_addr(interface_addr, 0, &addr6))
+      return UV_EINVAL;
+    mreq.ipv6mr_interface = addr6.sin6_scope_id;
+  } else {
+    mreq.ipv6mr_interface = 0;
+  }
+
+  mreq.ipv6mr_multiaddr = multicast_addr->sin6_addr;
+
+  switch (membership) {
+  case UV_JOIN_GROUP:
+    optname = IPV6_ADD_MEMBERSHIP;
+    break;
+  case UV_LEAVE_GROUP:
+    optname = IPV6_DROP_MEMBERSHIP;
+    break;
+  default:
+    return UV_EINVAL;
+  }
+
+  if (setsockopt(handle->io_watcher.fd,
+                 IPPROTO_IPV6,
+                 optname,
+                 &mreq,
+                 sizeof(mreq))) {
+#if defined(__MVS__)
+  if (errno == ENXIO)
+    return UV_ENODEV;
+#endif
+    return UV__ERR(errno);
+  }
+
+  return 0;
+}
+
+
+#if !defined(__OpenBSD__) &&                                        \
+    !defined(__NetBSD__) &&                                         \
+    !defined(__ANDROID__) &&                                        \
+    !defined(__DragonFly__) &&                                      \
+    !defined(__QNX__) &&                                            \
+    !defined(__GNU__)
+static int uv__udp_set_source_membership4(uv_udp_t* handle,
+                                          const struct sockaddr_in* multicast_addr,
+                                          const char* interface_addr,
+                                          const struct sockaddr_in* source_addr,
+                                          uv_membership membership) {
+  struct ip_mreq_source mreq;
+  int optname;
+  int err;
+
+  err = uv__udp_maybe_deferred_bind(handle, AF_INET, UV_UDP_REUSEADDR);
+  if (err)
+    return err;
+
+  memset(&mreq, 0, sizeof(mreq));
+
+  if (interface_addr != NULL) {
+    err = uv_inet_pton(AF_INET, interface_addr, &mreq.imr_interface.s_addr);
+    if (err)
+      return err;
+  } else {
+    mreq.imr_interface.s_addr = htonl(INADDR_ANY);
+  }
+
+  mreq.imr_multiaddr.s_addr = multicast_addr->sin_addr.s_addr;
+  mreq.imr_sourceaddr.s_addr = source_addr->sin_addr.s_addr;
+
+  if (membership == UV_JOIN_GROUP)
+    optname = IP_ADD_SOURCE_MEMBERSHIP;
+  else if (membership == UV_LEAVE_GROUP)
+    optname = IP_DROP_SOURCE_MEMBERSHIP;
+  else
+    return UV_EINVAL;
+
+  if (setsockopt(handle->io_watcher.fd,
+                 IPPROTO_IP,
+                 optname,
+                 &mreq,
+                 sizeof(mreq))) {
+    return UV__ERR(errno);
+  }
+
+  return 0;
+}
+
+
+static int uv__udp_set_source_membership6(uv_udp_t* handle,
+                                          const struct sockaddr_in6* multicast_addr,
+                                          const char* interface_addr,
+                                          const struct sockaddr_in6* source_addr,
+                                          uv_membership membership) {
+  struct group_source_req mreq;
+  struct sockaddr_in6 addr6;
+  int optname;
+  int err;
+
+  err = uv__udp_maybe_deferred_bind(handle, AF_INET6, UV_UDP_REUSEADDR);
+  if (err)
+    return err;
+
+  memset(&mreq, 0, sizeof(mreq));
+
+  if (interface_addr != NULL) {
+    err = uv_ip6_addr(interface_addr, 0, &addr6);
+    if (err)
+      return err;
+    mreq.gsr_interface = addr6.sin6_scope_id;
+  } else {
+    mreq.gsr_interface = 0;
+  }
+
+  STATIC_ASSERT(sizeof(mreq.gsr_group) >= sizeof(*multicast_addr));
+  STATIC_ASSERT(sizeof(mreq.gsr_source) >= sizeof(*source_addr));
+  memcpy(&mreq.gsr_group, multicast_addr, sizeof(*multicast_addr));
+  memcpy(&mreq.gsr_source, source_addr, sizeof(*source_addr));
+
+  if (membership == UV_JOIN_GROUP)
+    optname = MCAST_JOIN_SOURCE_GROUP;
+  else if (membership == UV_LEAVE_GROUP)
+    optname = MCAST_LEAVE_SOURCE_GROUP;
+  else
+    return UV_EINVAL;
+
+  if (setsockopt(handle->io_watcher.fd,
+                 IPPROTO_IPV6,
+                 optname,
+                 &mreq,
+                 sizeof(mreq))) {
+    return UV__ERR(errno);
+  }
+
+  return 0;
+}
+#endif
+
+
+int uv__udp_init_ex(uv_loop_t* loop,
+                    uv_udp_t* handle,
+                    unsigned flags,
+                    int domain) {
+  int fd;
+
+  fd = -1;
+  if (domain != AF_UNSPEC) {
+    fd = uv__socket(domain, SOCK_DGRAM, 0);
+    if (fd < 0)
+      return fd;
+  }
+
+  uv__handle_init(loop, (uv_handle_t*)handle, UV_UDP);
+  handle->alloc_cb = NULL;
+  handle->recv_cb = NULL;
+  handle->send_queue_size = 0;
+  handle->send_queue_count = 0;
+  uv__io_init(&handle->io_watcher, uv__udp_io, fd);
+  QUEUE_INIT(&handle->write_queue);
+  QUEUE_INIT(&handle->write_completed_queue);
+
+  return 0;
+}
+
+
+int uv_udp_using_recvmmsg(const uv_udp_t* handle) {
+#if HAVE_MMSG
+  if (handle->flags & UV_HANDLE_UDP_RECVMMSG) {
+    uv_once(&once, uv__udp_mmsg_init);
+    return uv__recvmmsg_avail;
+  }
+#endif
+  return 0;
+}
+
+
+int uv_udp_open(uv_udp_t* handle, uv_os_sock_t sock) {
+  int err;
+
+  /* Check for already active socket. */
+  if (handle->io_watcher.fd != -1)
+    return UV_EBUSY;
+
+  if (uv__fd_exists(handle->loop, sock))
+    return UV_EEXIST;
+
+  err = uv__nonblock(sock, 1);
+  if (err)
+    return err;
+
+  err = uv__set_reuse(sock);
+  if (err)
+    return err;
+
+  handle->io_watcher.fd = sock;
+  if (uv__udp_is_connected(handle))
+    handle->flags |= UV_HANDLE_UDP_CONNECTED;
+
+  return 0;
+}
+
+
+int uv_udp_set_membership(uv_udp_t* handle,
+                          const char* multicast_addr,
+                          const char* interface_addr,
+                          uv_membership membership) {
+  int err;
+  struct sockaddr_in addr4;
+  struct sockaddr_in6 addr6;
+
+  if (uv_ip4_addr(multicast_addr, 0, &addr4) == 0) {
+    err = uv__udp_maybe_deferred_bind(handle, AF_INET, UV_UDP_REUSEADDR);
+    if (err)
+      return err;
+    return uv__udp_set_membership4(handle, &addr4, interface_addr, membership);
+  } else if (uv_ip6_addr(multicast_addr, 0, &addr6) == 0) {
+    err = uv__udp_maybe_deferred_bind(handle, AF_INET6, UV_UDP_REUSEADDR);
+    if (err)
+      return err;
+    return uv__udp_set_membership6(handle, &addr6, interface_addr, membership);
+  } else {
+    return UV_EINVAL;
+  }
+}
+
+
+int uv_udp_set_source_membership(uv_udp_t* handle,
+                                 const char* multicast_addr,
+                                 const char* interface_addr,
+                                 const char* source_addr,
+                                 uv_membership membership) {
+#if !defined(__OpenBSD__) &&                                        \
+    !defined(__NetBSD__) &&                                         \
+    !defined(__ANDROID__) &&                                        \
+    !defined(__DragonFly__) &&                                      \
+    !defined(__QNX__) &&                                            \
+    !defined(__GNU__)
+  int err;
+  union uv__sockaddr mcast_addr;
+  union uv__sockaddr src_addr;
+
+  err = uv_ip4_addr(multicast_addr, 0, &mcast_addr.in);
+  if (err) {
+    err = uv_ip6_addr(multicast_addr, 0, &mcast_addr.in6);
+    if (err)
+      return err;
+    err = uv_ip6_addr(source_addr, 0, &src_addr.in6);
+    if (err)
+      return err;
+    return uv__udp_set_source_membership6(handle,
+                                          &mcast_addr.in6,
+                                          interface_addr,
+                                          &src_addr.in6,
+                                          membership);
+  }
+
+  err = uv_ip4_addr(source_addr, 0, &src_addr.in);
+  if (err)
+    return err;
+  return uv__udp_set_source_membership4(handle,
+                                        &mcast_addr.in,
+                                        interface_addr,
+                                        &src_addr.in,
+                                        membership);
+#else
+  return UV_ENOSYS;
+#endif
+}
+
+
+static int uv__setsockopt(uv_udp_t* handle,
+                         int option4,
+                         int option6,
+                         const void* val,
+                         socklen_t size) {
+  int r;
+
+  if (handle->flags & UV_HANDLE_IPV6)
+    r = setsockopt(handle->io_watcher.fd,
+                   IPPROTO_IPV6,
+                   option6,
+                   val,
+                   size);
+  else
+    r = setsockopt(handle->io_watcher.fd,
+                   IPPROTO_IP,
+                   option4,
+                   val,
+                   size);
+  if (r)
+    return UV__ERR(errno);
+
+  return 0;
+}
+
+static int uv__setsockopt_maybe_char(uv_udp_t* handle,
+                                     int option4,
+                                     int option6,
+                                     int val) {
+#if defined(__sun) || defined(_AIX) || defined(__MVS__)
+  char arg = val;
+#elif defined(__OpenBSD__)
+  unsigned char arg = val;
+#else
+  int arg = val;
+#endif
+
+  if (val < 0 || val > 255)
+    return UV_EINVAL;
+
+  return uv__setsockopt(handle, option4, option6, &arg, sizeof(arg));
+}
+
+
+int uv_udp_set_broadcast(uv_udp_t* handle, int on) {
+  if (setsockopt(handle->io_watcher.fd,
+                 SOL_SOCKET,
+                 SO_BROADCAST,
+                 &on,
+                 sizeof(on))) {
+    return UV__ERR(errno);
+  }
+
+  return 0;
+}
+
+
+int uv_udp_set_ttl(uv_udp_t* handle, int ttl) {
+  if (ttl < 1 || ttl > 255)
+    return UV_EINVAL;
+
+#if defined(__MVS__)
+  if (!(handle->flags & UV_HANDLE_IPV6))
+    return UV_ENOTSUP;  /* zOS does not support setting ttl for IPv4 */
+#endif
+
+/*
+ * On Solaris and derivatives such as SmartOS, the length of socket options
+ * is sizeof(int) for IP_TTL and IPV6_UNICAST_HOPS,
+ * so hardcode the size of these options on this platform,
+ * and use the general uv__setsockopt_maybe_char call on other platforms.
+ */
+#if defined(__sun) || defined(_AIX) || defined(__OpenBSD__) || \
+    defined(__MVS__) || defined(__QNX__)
+
+  return uv__setsockopt(handle,
+                        IP_TTL,
+                        IPV6_UNICAST_HOPS,
+                        &ttl,
+                        sizeof(ttl));
+
+#else /* !(defined(__sun) || defined(_AIX) || defined (__OpenBSD__) ||
+           defined(__MVS__) || defined(__QNX__)) */
+
+  return uv__setsockopt_maybe_char(handle,
+                                   IP_TTL,
+                                   IPV6_UNICAST_HOPS,
+                                   ttl);
+
+#endif /* defined(__sun) || defined(_AIX) || defined (__OpenBSD__) ||
+          defined(__MVS__) || defined(__QNX__) */
+}
+
+
+int uv_udp_set_multicast_ttl(uv_udp_t* handle, int ttl) {
+/*
+ * On Solaris and derivatives such as SmartOS, the length of socket options
+ * is sizeof(int) for IPV6_MULTICAST_HOPS and sizeof(char) for
+ * IP_MULTICAST_TTL, so hardcode the size of the option in the IPv6 case,
+ * and use the general uv__setsockopt_maybe_char call otherwise.
+ */
+#if defined(__sun) || defined(_AIX) || defined(__OpenBSD__) || \
+    defined(__MVS__) || defined(__QNX__)
+  if (handle->flags & UV_HANDLE_IPV6)
+    return uv__setsockopt(handle,
+                          IP_MULTICAST_TTL,
+                          IPV6_MULTICAST_HOPS,
+                          &ttl,
+                          sizeof(ttl));
+#endif /* defined(__sun) || defined(_AIX) || defined(__OpenBSD__) || \
+    defined(__MVS__) || defined(__QNX__) */
+
+  return uv__setsockopt_maybe_char(handle,
+                                   IP_MULTICAST_TTL,
+                                   IPV6_MULTICAST_HOPS,
+                                   ttl);
+}
+
+
+int uv_udp_set_multicast_loop(uv_udp_t* handle, int on) {
+/*
+ * On Solaris and derivatives such as SmartOS, the length of socket options
+ * is sizeof(int) for IPV6_MULTICAST_LOOP and sizeof(char) for
+ * IP_MULTICAST_LOOP, so hardcode the size of the option in the IPv6 case,
+ * and use the general uv__setsockopt_maybe_char call otherwise.
+ */
+#if defined(__sun) || defined(_AIX) || defined(__OpenBSD__) || \
+    defined(__MVS__) || defined(__QNX__)
+  if (handle->flags & UV_HANDLE_IPV6)
+    return uv__setsockopt(handle,
+                          IP_MULTICAST_LOOP,
+                          IPV6_MULTICAST_LOOP,
+                          &on,
+                          sizeof(on));
+#endif /* defined(__sun) || defined(_AIX) ||defined(__OpenBSD__) ||
+    defined(__MVS__) || defined(__QNX__) */
+
+  return uv__setsockopt_maybe_char(handle,
+                                   IP_MULTICAST_LOOP,
+                                   IPV6_MULTICAST_LOOP,
+                                   on);
+}
+
+int uv_udp_set_multicast_interface(uv_udp_t* handle, const char* interface_addr) {
+  struct sockaddr_storage addr_st;
+  struct sockaddr_in* addr4;
+  struct sockaddr_in6* addr6;
+
+  addr4 = (struct sockaddr_in*) &addr_st;
+  addr6 = (struct sockaddr_in6*) &addr_st;
+
+  if (!interface_addr) {
+    memset(&addr_st, 0, sizeof addr_st);
+    if (handle->flags & UV_HANDLE_IPV6) {
+      addr_st.ss_family = AF_INET6;
+      addr6->sin6_scope_id = 0;
+    } else {
+      addr_st.ss_family = AF_INET;
+      addr4->sin_addr.s_addr = htonl(INADDR_ANY);
+    }
+  } else if (uv_ip4_addr(interface_addr, 0, addr4) == 0) {
+    /* nothing, address was parsed */
+  } else if (uv_ip6_addr(interface_addr, 0, addr6) == 0) {
+    /* nothing, address was parsed */
+  } else {
+    return UV_EINVAL;
+  }
+
+  if (addr_st.ss_family == AF_INET) {
+    if (setsockopt(handle->io_watcher.fd,
+                   IPPROTO_IP,
+                   IP_MULTICAST_IF,
+                   (void*) &addr4->sin_addr,
+                   sizeof(addr4->sin_addr)) == -1) {
+      return UV__ERR(errno);
+    }
+  } else if (addr_st.ss_family == AF_INET6) {
+    if (setsockopt(handle->io_watcher.fd,
+                   IPPROTO_IPV6,
+                   IPV6_MULTICAST_IF,
+                   &addr6->sin6_scope_id,
+                   sizeof(addr6->sin6_scope_id)) == -1) {
+      return UV__ERR(errno);
+    }
+  } else {
+    assert(0 && "unexpected address family");
+    abort();
+  }
+
+  return 0;
+}
+
+int uv_udp_getpeername(const uv_udp_t* handle,
+                       struct sockaddr* name,
+                       int* namelen) {
+
+  return uv__getsockpeername((const uv_handle_t*) handle,
+                             getpeername,
+                             name,
+                             namelen);
+}
+
+int uv_udp_getsockname(const uv_udp_t* handle,
+                       struct sockaddr* name,
+                       int* namelen) {
+
+  return uv__getsockpeername((const uv_handle_t*) handle,
+                             getsockname,
+                             name,
+                             namelen);
+}
+
+
+int uv__udp_recv_start(uv_udp_t* handle,
+                       uv_alloc_cb alloc_cb,
+                       uv_udp_recv_cb recv_cb) {
+  int err;
+
+  if (alloc_cb == NULL || recv_cb == NULL)
+    return UV_EINVAL;
+
+  if (uv__io_active(&handle->io_watcher, POLLIN))
+    return UV_EALREADY;  /* FIXME(bnoordhuis) Should be UV_EBUSY. */
+
+  err = uv__udp_maybe_deferred_bind(handle, AF_INET, 0);
+  if (err)
+    return err;
+
+  handle->alloc_cb = alloc_cb;
+  handle->recv_cb = recv_cb;
+
+  uv__io_start(handle->loop, &handle->io_watcher, POLLIN);
+  uv__handle_start(handle);
+
+  return 0;
+}
+
+
+int uv__udp_recv_stop(uv_udp_t* handle) {
+  uv__io_stop(handle->loop, &handle->io_watcher, POLLIN);
+
+  if (!uv__io_active(&handle->io_watcher, POLLOUT))
+    uv__handle_stop(handle);
+
+  handle->alloc_cb = NULL;
+  handle->recv_cb = NULL;
+
+  return 0;
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/uv-common.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/uv-common.cpp
new file mode 100644
index 0000000..8ab600d
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/uv-common.cpp
@@ -0,0 +1,990 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "uv-common.h"
+
+#include <assert.h>
+#include <errno.h>
+#include <stdarg.h>
+#include <stddef.h> /* NULL */
+#include <stdio.h>
+#include <stdlib.h> /* malloc */
+#include <string.h> /* memset */
+
+#if defined(_WIN32)
+# include <malloc.h> /* malloc */
+#else
+# include <net/if.h> /* if_nametoindex */
+# include <sys/un.h> /* AF_UNIX, sockaddr_un */
+#endif
+
+
+typedef struct {
+  uv_malloc_func local_malloc;
+  uv_realloc_func local_realloc;
+  uv_calloc_func local_calloc;
+  uv_free_func local_free;
+} uv__allocator_t;
+
+static uv__allocator_t uv__allocator = {
+  malloc,
+  realloc,
+  calloc,
+  free,
+};
+
+char* uv__strdup(const char* s) {
+  size_t len = strlen(s) + 1;
+  char* m = (char*)uv__malloc(len);
+  if (m == NULL)
+    return NULL;
+  return (char*)memcpy(m, s, len);
+}
+
+char* uv__strndup(const char* s, size_t n) {
+  char* m;
+  size_t len = strlen(s);
+  if (n < len)
+    len = n;
+  m = (char*)uv__malloc(len + 1);
+  if (m == NULL)
+    return NULL;
+  m[len] = '\0';
+  return (char*)memcpy(m, s, len);
+}
+
+void* uv__malloc(size_t size) {
+  if (size > 0)
+    return uv__allocator.local_malloc(size);
+  return NULL;
+}
+
+void uv__free(void* ptr) {
+  int saved_errno;
+
+  /* Libuv expects that free() does not clobber errno.  The system allocator
+   * honors that assumption but custom allocators may not be so careful.
+   */
+  saved_errno = errno;
+  uv__allocator.local_free(ptr);
+  errno = saved_errno;
+}
+
+void* uv__calloc(size_t count, size_t size) {
+  return uv__allocator.local_calloc(count, size);
+}
+
+void* uv__realloc(void* ptr, size_t size) {
+  if (size > 0)
+    return uv__allocator.local_realloc(ptr, size);
+  uv__free(ptr);
+  return NULL;
+}
+
+void* uv__reallocf(void* ptr, size_t size) {
+  void* newptr;
+
+  newptr = uv__realloc(ptr, size);
+  if (newptr == NULL)
+    if (size > 0)
+      uv__free(ptr);
+
+  return newptr;
+}
+
+int uv_replace_allocator(uv_malloc_func malloc_func,
+                         uv_realloc_func realloc_func,
+                         uv_calloc_func calloc_func,
+                         uv_free_func free_func) {
+  if (malloc_func == NULL || realloc_func == NULL ||
+      calloc_func == NULL || free_func == NULL) {
+    return UV_EINVAL;
+  }
+
+  uv__allocator.local_malloc = malloc_func;
+  uv__allocator.local_realloc = realloc_func;
+  uv__allocator.local_calloc = calloc_func;
+  uv__allocator.local_free = free_func;
+
+  return 0;
+}
+
+#define XX(uc, lc) case UV_##uc: return sizeof(uv_##lc##_t);
+
+size_t uv_handle_size(uv_handle_type type) {
+  switch (type) {
+    UV_HANDLE_TYPE_MAP(XX)
+    default:
+      return -1;
+  }
+}
+
+size_t uv_req_size(uv_req_type type) {
+  switch(type) {
+    UV_REQ_TYPE_MAP(XX)
+    default:
+      return -1;
+  }
+}
+
+#undef XX
+
+
+size_t uv_loop_size(void) {
+  return sizeof(uv_loop_t);
+}
+
+
+uv_buf_t uv_buf_init(char* base, unsigned int len) {
+  uv_buf_t buf;
+  buf.base = base;
+  buf.len = len;
+  return buf;
+}
+
+
+static const char* uv__unknown_err_code(int err) {
+  char buf[32];
+  char* copy;
+
+  snprintf(buf, sizeof(buf), "Unknown system error %d", err);
+  copy = uv__strdup(buf);
+
+  return copy != NULL ? copy : "Unknown system error";
+}
+
+#define UV_ERR_NAME_GEN_R(name, _) \
+case UV_## name: \
+  uv__strscpy(buf, #name, buflen); break;
+char* uv_err_name_r(int err, char* buf, size_t buflen) {
+  switch (err) {
+    UV_ERRNO_MAP(UV_ERR_NAME_GEN_R)
+    default: snprintf(buf, buflen, "Unknown system error %d", err);
+  }
+  return buf;
+}
+#undef UV_ERR_NAME_GEN_R
+
+
+#define UV_ERR_NAME_GEN(name, _) case UV_ ## name: return #name;
+const char* uv_err_name(int err) {
+  switch (err) {
+    UV_ERRNO_MAP(UV_ERR_NAME_GEN)
+  }
+  return uv__unknown_err_code(err);
+}
+#undef UV_ERR_NAME_GEN
+
+
+#define UV_STRERROR_GEN_R(name, msg) \
+case UV_ ## name: \
+  snprintf(buf, buflen, "%s", msg); break;
+char* uv_strerror_r(int err, char* buf, size_t buflen) {
+  switch (err) {
+    UV_ERRNO_MAP(UV_STRERROR_GEN_R)
+    default: snprintf(buf, buflen, "Unknown system error %d", err);
+  }
+  return buf;
+}
+#undef UV_STRERROR_GEN_R
+
+
+#define UV_STRERROR_GEN(name, msg) case UV_ ## name: return msg;
+const char* uv_strerror(int err) {
+  switch (err) {
+    UV_ERRNO_MAP(UV_STRERROR_GEN)
+  }
+  return uv__unknown_err_code(err);
+}
+#undef UV_STRERROR_GEN
+
+
+int uv_ip4_addr(const char* ip, int port, struct sockaddr_in* addr) {
+  memset(addr, 0, sizeof(*addr));
+  addr->sin_family = AF_INET;
+  addr->sin_port = htons(port);
+#ifdef SIN6_LEN
+  addr->sin_len = sizeof(*addr);
+#endif
+  return uv_inet_pton(AF_INET, ip, &(addr->sin_addr.s_addr));
+}
+
+
+int uv_ip6_addr(const char* ip, int port, struct sockaddr_in6* addr) {
+  char address_part[40];
+  size_t address_part_size;
+  const char* zone_index;
+
+  memset(addr, 0, sizeof(*addr));
+  addr->sin6_family = AF_INET6;
+  addr->sin6_port = htons(port);
+#ifdef SIN6_LEN
+  addr->sin6_len = sizeof(*addr);
+#endif
+
+  zone_index = strchr(ip, '%');
+  if (zone_index != NULL) {
+    address_part_size = zone_index - ip;
+    if (address_part_size >= sizeof(address_part))
+      address_part_size = sizeof(address_part) - 1;
+
+    memcpy(address_part, ip, address_part_size);
+    address_part[address_part_size] = '\0';
+    ip = address_part;
+
+    zone_index++; /* skip '%' */
+    /* NOTE: unknown interface (id=0) is silently ignored */
+#ifdef _WIN32
+    addr->sin6_scope_id = atoi(zone_index);
+#else
+    addr->sin6_scope_id = if_nametoindex(zone_index);
+#endif
+  }
+
+  return uv_inet_pton(AF_INET6, ip, &addr->sin6_addr);
+}
+
+
+int uv_ip4_name(const struct sockaddr_in* src, char* dst, size_t size) {
+  return uv_inet_ntop(AF_INET, &src->sin_addr, dst, size);
+}
+
+
+int uv_ip6_name(const struct sockaddr_in6* src, char* dst, size_t size) {
+  return uv_inet_ntop(AF_INET6, &src->sin6_addr, dst, size);
+}
+
+
+int uv_ip_name(const struct sockaddr *src, char *dst, size_t size) {
+  switch (src->sa_family) {
+  case AF_INET:
+    return uv_inet_ntop(AF_INET, &((struct sockaddr_in *)src)->sin_addr,
+                        dst, size);
+  case AF_INET6:
+    return uv_inet_ntop(AF_INET6, &((struct sockaddr_in6 *)src)->sin6_addr,
+                        dst, size);
+  default:
+    return UV_EAFNOSUPPORT;
+  }
+}
+
+
+int uv_tcp_bind(uv_tcp_t* handle,
+                const struct sockaddr* addr,
+                unsigned int flags) {
+  unsigned int addrlen;
+
+  if (handle->type != UV_TCP)
+    return UV_EINVAL;
+  if (uv__is_closing(handle)) {
+    return UV_EINVAL;
+  }
+  if (addr->sa_family == AF_INET)
+    addrlen = sizeof(struct sockaddr_in);
+  else if (addr->sa_family == AF_INET6)
+    addrlen = sizeof(struct sockaddr_in6);
+  else
+    return UV_EINVAL;
+
+  return uv__tcp_bind(handle, addr, addrlen, flags);
+}
+
+
+int uv_udp_init_ex(uv_loop_t* loop, uv_udp_t* handle, unsigned flags) {
+  unsigned extra_flags;
+  int domain;
+  int rc;
+
+  /* Use the lower 8 bits for the domain. */
+  domain = flags & 0xFF;
+  if (domain != AF_INET && domain != AF_INET6 && domain != AF_UNSPEC)
+    return UV_EINVAL;
+
+  /* Use the higher bits for extra flags. */
+  extra_flags = flags & ~0xFF;
+  if (extra_flags & ~UV_UDP_RECVMMSG)
+    return UV_EINVAL;
+
+  rc = uv__udp_init_ex(loop, handle, flags, domain);
+
+  if (rc == 0)
+    if (extra_flags & UV_UDP_RECVMMSG)
+      handle->flags |= UV_HANDLE_UDP_RECVMMSG;
+
+  return rc;
+}
+
+
+int uv_udp_init(uv_loop_t* loop, uv_udp_t* handle) {
+  return uv_udp_init_ex(loop, handle, AF_UNSPEC);
+}
+
+
+int uv_udp_bind(uv_udp_t* handle,
+                const struct sockaddr* addr,
+                unsigned int flags) {
+  unsigned int addrlen;
+
+  if (handle->type != UV_UDP)
+    return UV_EINVAL;
+
+  if (addr->sa_family == AF_INET)
+    addrlen = sizeof(struct sockaddr_in);
+  else if (addr->sa_family == AF_INET6)
+    addrlen = sizeof(struct sockaddr_in6);
+  else
+    return UV_EINVAL;
+
+  return uv__udp_bind(handle, addr, addrlen, flags);
+}
+
+
+int uv_tcp_connect(uv_connect_t* req,
+                   uv_tcp_t* handle,
+                   const struct sockaddr* addr,
+                   uv_connect_cb cb) {
+  unsigned int addrlen;
+
+  if (handle->type != UV_TCP)
+    return UV_EINVAL;
+
+  if (addr->sa_family == AF_INET)
+    addrlen = sizeof(struct sockaddr_in);
+  else if (addr->sa_family == AF_INET6)
+    addrlen = sizeof(struct sockaddr_in6);
+  else
+    return UV_EINVAL;
+
+  return uv__tcp_connect(req, handle, addr, addrlen, cb);
+}
+
+
+int uv_udp_connect(uv_udp_t* handle, const struct sockaddr* addr) {
+  unsigned int addrlen;
+
+  if (handle->type != UV_UDP)
+    return UV_EINVAL;
+
+  /* Disconnect the handle */
+  if (addr == NULL) {
+    if (!(handle->flags & UV_HANDLE_UDP_CONNECTED))
+      return UV_ENOTCONN;
+
+    return uv__udp_disconnect(handle);
+  }
+
+  if (addr->sa_family == AF_INET)
+    addrlen = sizeof(struct sockaddr_in);
+  else if (addr->sa_family == AF_INET6)
+    addrlen = sizeof(struct sockaddr_in6);
+  else
+    return UV_EINVAL;
+
+  if (handle->flags & UV_HANDLE_UDP_CONNECTED)
+    return UV_EISCONN;
+
+  return uv__udp_connect(handle, addr, addrlen);
+}
+
+
+int uv__udp_is_connected(uv_udp_t* handle) {
+  struct sockaddr_storage addr;
+  int addrlen;
+  if (handle->type != UV_UDP)
+    return 0;
+
+  addrlen = sizeof(addr);
+  if (uv_udp_getpeername(handle, (struct sockaddr*) &addr, &addrlen) != 0)
+    return 0;
+
+  return addrlen > 0;
+}
+
+
+int uv__udp_check_before_send(uv_udp_t* handle, const struct sockaddr* addr) {
+  unsigned int addrlen;
+
+  if (handle->type != UV_UDP)
+    return UV_EINVAL;
+
+  if (addr != NULL && (handle->flags & UV_HANDLE_UDP_CONNECTED))
+    return UV_EISCONN;
+
+  if (addr == NULL && !(handle->flags & UV_HANDLE_UDP_CONNECTED))
+    return UV_EDESTADDRREQ;
+
+  if (addr != NULL) {
+    if (addr->sa_family == AF_INET)
+      addrlen = sizeof(struct sockaddr_in);
+    else if (addr->sa_family == AF_INET6)
+      addrlen = sizeof(struct sockaddr_in6);
+#if defined(AF_UNIX) && !defined(_WIN32)
+    else if (addr->sa_family == AF_UNIX)
+      addrlen = sizeof(struct sockaddr_un);
+#endif
+    else
+      return UV_EINVAL;
+  } else {
+    addrlen = 0;
+  }
+
+  return addrlen;
+}
+
+
+int uv_udp_send(uv_udp_send_t* req,
+                uv_udp_t* handle,
+                const uv_buf_t bufs[],
+                unsigned int nbufs,
+                const struct sockaddr* addr,
+                uv_udp_send_cb send_cb) {
+  int addrlen;
+
+  addrlen = uv__udp_check_before_send(handle, addr);
+  if (addrlen < 0)
+    return addrlen;
+
+  return uv__udp_send(req, handle, bufs, nbufs, addr, addrlen, send_cb);
+}
+
+
+int uv_udp_try_send(uv_udp_t* handle,
+                    const uv_buf_t bufs[],
+                    unsigned int nbufs,
+                    const struct sockaddr* addr) {
+  int addrlen;
+
+  addrlen = uv__udp_check_before_send(handle, addr);
+  if (addrlen < 0)
+    return addrlen;
+
+  return uv__udp_try_send(handle, bufs, nbufs, addr, addrlen);
+}
+
+
+int uv_udp_recv_start(uv_udp_t* handle,
+                      uv_alloc_cb alloc_cb,
+                      uv_udp_recv_cb recv_cb) {
+  if (handle->type != UV_UDP || alloc_cb == NULL || recv_cb == NULL)
+    return UV_EINVAL;
+  else
+    return uv__udp_recv_start(handle, alloc_cb, recv_cb);
+}
+
+
+int uv_udp_recv_stop(uv_udp_t* handle) {
+  if (handle->type != UV_UDP)
+    return UV_EINVAL;
+  else
+    return uv__udp_recv_stop(handle);
+}
+
+
+void uv_walk(uv_loop_t* loop, uv_walk_cb walk_cb, void* arg) {
+  QUEUE queue;
+  QUEUE* q;
+  uv_handle_t* h;
+
+// FIXME: GCC 12.1 gives a possibly real warning, but we don't know how to fix
+// it
+#if __GNUC__ >= 12
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Wdangling-pointer="
+#endif  // __GNUC__ >= 12
+  QUEUE_MOVE(&loop->handle_queue, &queue);
+#if __GNUC__ >= 12
+#pragma GCC diagnostic pop
+#endif  // __GNUC__ >= 12
+  while (!QUEUE_EMPTY(&queue)) {
+    q = QUEUE_HEAD(&queue);
+    h = QUEUE_DATA(q, uv_handle_t, handle_queue);
+
+    QUEUE_REMOVE(q);
+    QUEUE_INSERT_TAIL(&loop->handle_queue, q);
+
+    if (h->flags & UV_HANDLE_INTERNAL) continue;
+    walk_cb(h, arg);
+  }
+}
+
+
+static void uv__print_handles(uv_loop_t* loop, int only_active, FILE* stream) {
+  const char* type;
+  QUEUE* q;
+  uv_handle_t* h;
+
+  if (loop == NULL)
+    loop = uv_default_loop();
+
+  QUEUE_FOREACH(q, &loop->handle_queue) {
+    h = QUEUE_DATA(q, uv_handle_t, handle_queue);
+
+    if (only_active && !uv__is_active(h))
+      continue;
+
+    switch (h->type) {
+#define X(uc, lc) case UV_##uc: type = #lc; break;
+      UV_HANDLE_TYPE_MAP(X)
+#undef X
+      default: type = "<unknown>";
+    }
+
+    fprintf(stream,
+            "[%c%c%c] %-8s %p\n",
+            "R-"[!(h->flags & UV_HANDLE_REF)],
+            "A-"[!(h->flags & UV_HANDLE_ACTIVE)],
+            "I-"[!(h->flags & UV_HANDLE_INTERNAL)],
+            type,
+            (void*)h);
+  }
+}
+
+
+void uv_print_all_handles(uv_loop_t* loop, FILE* stream) {
+  uv__print_handles(loop, 0, stream);
+}
+
+
+void uv_print_active_handles(uv_loop_t* loop, FILE* stream) {
+  uv__print_handles(loop, 1, stream);
+}
+
+
+void uv_ref(uv_handle_t* handle) {
+  uv__handle_ref(handle);
+}
+
+
+void uv_unref(uv_handle_t* handle) {
+  uv__handle_unref(handle);
+}
+
+
+int uv_has_ref(const uv_handle_t* handle) {
+  return uv__has_ref(handle);
+}
+
+
+void uv_stop(uv_loop_t* loop) {
+  loop->stop_flag = 1;
+}
+
+
+uint64_t uv_now(const uv_loop_t* loop) {
+  return loop->time;
+}
+
+
+
+size_t uv__count_bufs(const uv_buf_t bufs[], unsigned int nbufs) {
+  unsigned int i;
+  size_t bytes;
+
+  bytes = 0;
+  for (i = 0; i < nbufs; i++)
+    bytes += (size_t) bufs[i].len;
+
+  return bytes;
+}
+
+int uv_recv_buffer_size(uv_handle_t* handle, int* value) {
+  return uv__socket_sockopt(handle, SO_RCVBUF, value);
+}
+
+int uv_send_buffer_size(uv_handle_t* handle, int *value) {
+  return uv__socket_sockopt(handle, SO_SNDBUF, value);
+}
+
+int uv_fs_event_getpath(uv_fs_event_t* handle, char* buffer, size_t* size) {
+  size_t required_len;
+
+  if (!uv__is_active(handle)) {
+    *size = 0;
+    return UV_EINVAL;
+  }
+
+  required_len = strlen(handle->path);
+  if (required_len >= *size) {
+    *size = required_len + 1;
+    return UV_ENOBUFS;
+  }
+
+  memcpy(buffer, handle->path, required_len);
+  *size = required_len;
+  buffer[required_len] = '\0';
+
+  return 0;
+}
+
+/* The windows implementation does not have the same structure layout as
+ * the unix implementation (nbufs is not directly inside req but is
+ * contained in a nested union/struct) so this function locates it.
+*/
+static unsigned int* uv__get_nbufs(uv_fs_t* req) {
+#ifdef _WIN32
+  return &req->fs.info.nbufs;
+#else
+  return &req->nbufs;
+#endif
+}
+
+/* uv_fs_scandir() uses the system allocator to allocate memory on non-Windows
+ * systems. So, the memory should be released using free(). On Windows,
+ * uv__malloc() is used, so use uv__free() to free memory.
+*/
+#ifdef _WIN32
+# define uv__fs_scandir_free uv__free
+#else
+# define uv__fs_scandir_free free
+#endif
+
+void uv__fs_scandir_cleanup(uv_fs_t* req) {
+  uv__dirent_t** dents;
+
+  unsigned int* nbufs = uv__get_nbufs(req);
+
+  dents = (uv__dirent_t**)(req->ptr);
+  if (*nbufs > 0 && *nbufs != (unsigned int) req->result)
+    (*nbufs)--;
+  for (; *nbufs < (unsigned int) req->result; (*nbufs)++)
+    uv__fs_scandir_free(dents[*nbufs]);
+
+  uv__fs_scandir_free(req->ptr);
+  req->ptr = NULL;
+}
+
+
+int uv_fs_scandir_next(uv_fs_t* req, uv_dirent_t* ent) {
+  uv__dirent_t** dents;
+  uv__dirent_t* dent;
+  unsigned int* nbufs;
+
+  /* Check to see if req passed */
+  if (req->result < 0)
+    return req->result;
+
+  /* Ptr will be null if req was canceled or no files found */
+  if (!req->ptr)
+    return UV_EOF;
+
+  nbufs = uv__get_nbufs(req);
+  assert(nbufs);
+
+  dents = (uv__dirent_t**)(req->ptr);
+
+  /* Free previous entity */
+  if (*nbufs > 0)
+    uv__fs_scandir_free(dents[*nbufs - 1]);
+
+  /* End was already reached */
+  if (*nbufs == (unsigned int) req->result) {
+    uv__fs_scandir_free(dents);
+    req->ptr = NULL;
+    return UV_EOF;
+  }
+
+  dent = dents[(*nbufs)++];
+
+  ent->name = dent->d_name;
+  ent->type = uv__fs_get_dirent_type(dent);
+
+  return 0;
+}
+
+uv_dirent_type_t uv__fs_get_dirent_type(uv__dirent_t* dent) {
+  uv_dirent_type_t type;
+
+#ifdef HAVE_DIRENT_TYPES
+  switch (dent->d_type) {
+    case UV__DT_DIR:
+      type = UV_DIRENT_DIR;
+      break;
+    case UV__DT_FILE:
+      type = UV_DIRENT_FILE;
+      break;
+    case UV__DT_LINK:
+      type = UV_DIRENT_LINK;
+      break;
+    case UV__DT_FIFO:
+      type = UV_DIRENT_FIFO;
+      break;
+    case UV__DT_SOCKET:
+      type = UV_DIRENT_SOCKET;
+      break;
+    case UV__DT_CHAR:
+      type = UV_DIRENT_CHAR;
+      break;
+    case UV__DT_BLOCK:
+      type = UV_DIRENT_BLOCK;
+      break;
+    default:
+      type = UV_DIRENT_UNKNOWN;
+  }
+#else
+  type = UV_DIRENT_UNKNOWN;
+#endif
+
+  return type;
+}
+
+void uv__fs_readdir_cleanup(uv_fs_t* req) {
+  uv_dir_t* dir;
+  uv_dirent_t* dirents;
+  int i;
+
+  if (req->ptr == NULL)
+    return;
+
+  dir = (uv_dir_t*)req->ptr;
+  dirents = dir->dirents;
+  req->ptr = NULL;
+
+  if (dirents == NULL)
+    return;
+
+  for (i = 0; i < req->result; ++i) {
+    uv__free((char*) dirents[i].name);
+    dirents[i].name = NULL;
+  }
+}
+
+
+#ifdef __clang__
+# pragma clang diagnostic push
+# pragma clang diagnostic ignored "-Wvarargs"
+#endif
+
+int uv_loop_configure(uv_loop_t* loop, uv_loop_option option, ...) {
+  va_list ap;
+  int err;
+
+  va_start(ap, option);
+  /* Any platform-agnostic options should be handled here. */
+  err = uv__loop_configure(loop, option, ap);
+  va_end(ap);
+
+  return err;
+}
+
+#ifdef __clang__
+# pragma clang diagnostic pop
+#endif
+
+
+static uv_loop_t default_loop_struct;
+static uv_loop_t* default_loop_ptr;
+
+
+uv_loop_t* uv_default_loop(void) {
+  if (default_loop_ptr != NULL)
+    return default_loop_ptr;
+
+  if (uv_loop_init(&default_loop_struct))
+    return NULL;
+
+  default_loop_ptr = &default_loop_struct;
+  return default_loop_ptr;
+}
+
+
+uv_loop_t* uv_loop_new(void) {
+  uv_loop_t* loop;
+
+  loop = (uv_loop_t*)uv__malloc(sizeof(*loop));
+  if (loop == NULL)
+    return NULL;
+
+  if (uv_loop_init(loop)) {
+    uv__free(loop);
+    return NULL;
+  }
+
+  return loop;
+}
+
+
+int uv_loop_close(uv_loop_t* loop) {
+  QUEUE* q;
+  uv_handle_t* h;
+#ifndef NDEBUG
+  void* saved_data;
+#endif
+
+  if (uv__has_active_reqs(loop))
+    return UV_EBUSY;
+
+  QUEUE_FOREACH(q, &loop->handle_queue) {
+    h = QUEUE_DATA(q, uv_handle_t, handle_queue);
+    if (!(h->flags & UV_HANDLE_INTERNAL))
+      return UV_EBUSY;
+  }
+
+  uv__loop_close(loop);
+
+#ifndef NDEBUG
+  saved_data = loop->data;
+  memset(loop, -1, sizeof(*loop));
+  loop->data = saved_data;
+#endif
+  if (loop == default_loop_ptr)
+    default_loop_ptr = NULL;
+
+  return 0;
+}
+
+
+void uv_loop_delete(uv_loop_t* loop) {
+  uv_loop_t* default_loop;
+  int err;
+
+  default_loop = default_loop_ptr;
+
+  err = uv_loop_close(loop);
+  (void) err;    /* Squelch compiler warnings. */
+  assert(err == 0);
+  if (loop != default_loop)
+    uv__free(loop);
+}
+
+
+int uv_read_start(uv_stream_t* stream,
+                  uv_alloc_cb alloc_cb,
+                  uv_read_cb read_cb) {
+  if (stream == NULL || alloc_cb == NULL || read_cb == NULL)
+    return UV_EINVAL;
+
+  if (stream->flags & UV_HANDLE_CLOSING)
+    return UV_EINVAL;
+
+  if (stream->flags & UV_HANDLE_READING)
+    return UV_EALREADY;
+
+  if (!(stream->flags & UV_HANDLE_READABLE))
+    return UV_ENOTCONN;
+
+  return uv__read_start(stream, alloc_cb, read_cb);
+}
+
+
+void uv_os_free_environ(uv_env_item_t* envitems, int count) {
+  int i;
+
+  for (i = 0; i < count; i++) {
+    uv__free(envitems[i].name);
+  }
+
+  uv__free(envitems);
+}
+
+
+void uv_free_cpu_info(uv_cpu_info_t* cpu_infos, int count) {
+  int i;
+
+  for (i = 0; i < count; i++)
+    uv__free(cpu_infos[i].model);
+
+  uv__free(cpu_infos);
+}
+
+
+/* Also covers __clang__ and __INTEL_COMPILER. Disabled on Windows because
+ * threads have already been forcibly terminated by the operating system
+ * by the time destructors run, ergo, it's not safe to try to clean them up.
+ */
+#if defined(__GNUC__) && !defined(_WIN32)
+__attribute__((destructor))
+#endif
+void uv_library_shutdown(void) {
+  static int was_shutdown;
+
+  if (uv__load_relaxed(&was_shutdown))
+    return;
+
+  uv__process_title_cleanup();
+  uv__signal_cleanup();
+#ifdef __MVS__
+  /* TODO(itodorov) - zos: revisit when Woz compiler is available. */
+  uv__os390_cleanup();
+#else
+  uv__threadpool_cleanup();
+#endif
+  uv__store_relaxed(&was_shutdown, 1);
+}
+
+
+void uv__metrics_update_idle_time(uv_loop_t* loop) {
+  uv__loop_metrics_t* loop_metrics;
+  uint64_t entry_time;
+  uint64_t exit_time;
+
+  if (!(uv__get_internal_fields(loop)->flags & UV_METRICS_IDLE_TIME))
+    return;
+
+  loop_metrics = uv__get_loop_metrics(loop);
+
+  /* The thread running uv__metrics_update_idle_time() is always the same
+   * thread that sets provider_entry_time. So it's unnecessary to lock before
+   * retrieving this value.
+   */
+  if (loop_metrics->provider_entry_time == 0)
+    return;
+
+  exit_time = uv_hrtime();
+
+  uv_mutex_lock(&loop_metrics->lock);
+  entry_time = loop_metrics->provider_entry_time;
+  loop_metrics->provider_entry_time = 0;
+  loop_metrics->provider_idle_time += exit_time - entry_time;
+  uv_mutex_unlock(&loop_metrics->lock);
+}
+
+
+void uv__metrics_set_provider_entry_time(uv_loop_t* loop) {
+  uv__loop_metrics_t* loop_metrics;
+  uint64_t now;
+
+  if (!(uv__get_internal_fields(loop)->flags & UV_METRICS_IDLE_TIME))
+    return;
+
+  now = uv_hrtime();
+  loop_metrics = uv__get_loop_metrics(loop);
+  uv_mutex_lock(&loop_metrics->lock);
+  loop_metrics->provider_entry_time = now;
+  uv_mutex_unlock(&loop_metrics->lock);
+}
+
+
+uint64_t uv_metrics_idle_time(uv_loop_t* loop) {
+  uv__loop_metrics_t* loop_metrics;
+  uint64_t entry_time;
+  uint64_t idle_time;
+
+  loop_metrics = uv__get_loop_metrics(loop);
+  uv_mutex_lock(&loop_metrics->lock);
+  idle_time = loop_metrics->provider_idle_time;
+  entry_time = loop_metrics->provider_entry_time;
+  uv_mutex_unlock(&loop_metrics->lock);
+
+  if (entry_time > 0)
+    idle_time += uv_hrtime() - entry_time;
+  return idle_time;
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/uv-common.h b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/uv-common.h
new file mode 100644
index 0000000..6001b0c
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/uv-common.h
@@ -0,0 +1,376 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+/*
+ * This file is private to libuv. It provides common functionality to both
+ * Windows and Unix backends.
+ */
+
+#ifndef UV_COMMON_H_
+#define UV_COMMON_H_
+
+#include <assert.h>
+#include <stdarg.h>
+#include <stddef.h>
+
+#if defined(_MSC_VER) && _MSC_VER < 1600
+# include "uv/stdint-msvc2008.h"
+#else
+# include <stdint.h>
+#endif
+
+#include "uv.h"
+#include "uv/tree.h"
+#include "queue.h"
+#include "strscpy.h"
+
+#if EDOM > 0
+# define UV__ERR(x) (-(x))
+#else
+# define UV__ERR(x) (x)
+#endif
+
+#if !defined(snprintf) && defined(_MSC_VER) && _MSC_VER < 1900
+extern int snprintf(char*, size_t, const char*, ...);
+#endif
+
+#define ARRAY_SIZE(a) (sizeof(a) / sizeof((a)[0]))
+
+#define container_of(ptr, type, member) \
+  ((type *) ((char *) (ptr) - offsetof(type, member)))
+
+#define STATIC_ASSERT(expr)                                                   \
+  void uv__static_assert(int static_assert_failed[1 - 2 * !(expr)])
+
+#if defined(__GNUC__) && (__GNUC__ > 4 || __GNUC__ == 4 && __GNUC_MINOR__ >= 7)
+#define uv__load_relaxed(p) __atomic_load_n(p, __ATOMIC_RELAXED)
+#define uv__store_relaxed(p, v) __atomic_store_n(p, v, __ATOMIC_RELAXED)
+#else
+#define uv__load_relaxed(p) (*p)
+#define uv__store_relaxed(p, v) do *p = v; while (0)
+#endif
+
+#define UV__UDP_DGRAM_MAXSIZE (64 * 1024)
+
+/* Handle flags. Some flags are specific to Windows or UNIX. */
+enum {
+  /* Used by all handles. */
+  UV_HANDLE_CLOSING                     = 0x00000001,
+  UV_HANDLE_CLOSED                      = 0x00000002,
+  UV_HANDLE_ACTIVE                      = 0x00000004,
+  UV_HANDLE_REF                         = 0x00000008,
+  UV_HANDLE_INTERNAL                    = 0x00000010,
+  UV_HANDLE_ENDGAME_QUEUED              = 0x00000020,
+
+  /* Used by streams. */
+  UV_HANDLE_LISTENING                   = 0x00000040,
+  UV_HANDLE_CONNECTION                  = 0x00000080,
+  UV_HANDLE_SHUTTING                    = 0x00000100,
+  UV_HANDLE_SHUT                        = 0x00000200,
+  UV_HANDLE_READ_PARTIAL                = 0x00000400,
+  UV_HANDLE_READ_EOF                    = 0x00000800,
+
+  /* Used by streams and UDP handles. */
+  UV_HANDLE_READING                     = 0x00001000,
+  UV_HANDLE_BOUND                       = 0x00002000,
+  UV_HANDLE_READABLE                    = 0x00004000,
+  UV_HANDLE_WRITABLE                    = 0x00008000,
+  UV_HANDLE_READ_PENDING                = 0x00010000,
+  UV_HANDLE_SYNC_BYPASS_IOCP            = 0x00020000,
+  UV_HANDLE_ZERO_READ                   = 0x00040000,
+  UV_HANDLE_EMULATE_IOCP                = 0x00080000,
+  UV_HANDLE_BLOCKING_WRITES             = 0x00100000,
+  UV_HANDLE_CANCELLATION_PENDING        = 0x00200000,
+
+  /* Used by uv_tcp_t and uv_udp_t handles */
+  UV_HANDLE_IPV6                        = 0x00400000,
+
+  /* Only used by uv_tcp_t handles. */
+  UV_HANDLE_TCP_NODELAY                 = 0x01000000,
+  UV_HANDLE_TCP_KEEPALIVE               = 0x02000000,
+  UV_HANDLE_TCP_SINGLE_ACCEPT           = 0x04000000,
+  UV_HANDLE_TCP_ACCEPT_STATE_CHANGING   = 0x08000000,
+  UV_HANDLE_SHARED_TCP_SOCKET           = 0x10000000,
+
+  /* Only used by uv_udp_t handles. */
+  UV_HANDLE_UDP_PROCESSING              = 0x01000000,
+  UV_HANDLE_UDP_CONNECTED               = 0x02000000,
+  UV_HANDLE_UDP_RECVMMSG                = 0x04000000,
+
+  /* Only used by uv_pipe_t handles. */
+  UV_HANDLE_NON_OVERLAPPED_PIPE         = 0x01000000,
+  UV_HANDLE_PIPESERVER                  = 0x02000000,
+
+  /* Only used by uv_tty_t handles. */
+  UV_HANDLE_TTY_READABLE                = 0x01000000,
+  UV_HANDLE_TTY_RAW                     = 0x02000000,
+  UV_HANDLE_TTY_SAVED_POSITION          = 0x04000000,
+  UV_HANDLE_TTY_SAVED_ATTRIBUTES        = 0x08000000,
+
+  /* Only used by uv_signal_t handles. */
+  UV_SIGNAL_ONE_SHOT_DISPATCHED         = 0x01000000,
+  UV_SIGNAL_ONE_SHOT                    = 0x02000000,
+
+  /* Only used by uv_poll_t handles. */
+  UV_HANDLE_POLL_SLOW                   = 0x01000000,
+
+  /* Only used by uv_process_t handles. */
+  UV_HANDLE_REAP                        = 0x10000000
+};
+
+int uv__loop_configure(uv_loop_t* loop, uv_loop_option option, va_list ap);
+
+void uv__loop_close(uv_loop_t* loop);
+
+int uv__read_start(uv_stream_t* stream,
+                   uv_alloc_cb alloc_cb,
+                   uv_read_cb read_cb);
+
+int uv__tcp_bind(uv_tcp_t* tcp,
+                 const struct sockaddr* addr,
+                 unsigned int addrlen,
+                 unsigned int flags);
+
+int uv__tcp_connect(uv_connect_t* req,
+                   uv_tcp_t* handle,
+                   const struct sockaddr* addr,
+                   unsigned int addrlen,
+                   uv_connect_cb cb);
+
+int uv__udp_init_ex(uv_loop_t* loop,
+                    uv_udp_t* handle,
+                    unsigned flags,
+                    int domain);
+
+int uv__udp_bind(uv_udp_t* handle,
+                 const struct sockaddr* addr,
+                 unsigned int  addrlen,
+                 unsigned int flags);
+
+int uv__udp_connect(uv_udp_t* handle,
+                    const struct sockaddr* addr,
+                    unsigned int addrlen);
+
+int uv__udp_disconnect(uv_udp_t* handle);
+
+int uv__udp_is_connected(uv_udp_t* handle);
+
+int uv__udp_send(uv_udp_send_t* req,
+                 uv_udp_t* handle,
+                 const uv_buf_t bufs[],
+                 unsigned int nbufs,
+                 const struct sockaddr* addr,
+                 unsigned int addrlen,
+                 uv_udp_send_cb send_cb);
+
+int uv__udp_try_send(uv_udp_t* handle,
+                     const uv_buf_t bufs[],
+                     unsigned int nbufs,
+                     const struct sockaddr* addr,
+                     unsigned int addrlen);
+
+int uv__udp_recv_start(uv_udp_t* handle, uv_alloc_cb alloccb,
+                       uv_udp_recv_cb recv_cb);
+
+int uv__udp_recv_stop(uv_udp_t* handle);
+
+void uv__fs_poll_close(uv_fs_poll_t* handle);
+
+int uv__getaddrinfo_translate_error(int sys_err);    /* EAI_* error. */
+
+enum uv__work_kind {
+  UV__WORK_CPU,
+  UV__WORK_FAST_IO,
+  UV__WORK_SLOW_IO
+};
+
+void uv__work_submit(uv_loop_t* loop,
+                     struct uv__work *w,
+                     enum uv__work_kind kind,
+                     void (*work)(struct uv__work *w),
+                     void (*done)(struct uv__work *w, int status));
+
+void uv__work_done(uv_async_t* handle);
+
+size_t uv__count_bufs(const uv_buf_t bufs[], unsigned int nbufs);
+
+int uv__socket_sockopt(uv_handle_t* handle, int optname, int* value);
+
+void uv__fs_scandir_cleanup(uv_fs_t* req);
+void uv__fs_readdir_cleanup(uv_fs_t* req);
+uv_dirent_type_t uv__fs_get_dirent_type(uv__dirent_t* dent);
+
+int uv__next_timeout(const uv_loop_t* loop);
+void uv__run_timers(uv_loop_t* loop);
+void uv__timer_close(uv_timer_t* handle);
+
+void uv__process_title_cleanup(void);
+void uv__signal_cleanup(void);
+void uv__threadpool_cleanup(void);
+
+#define uv__has_active_reqs(loop)                                             \
+  ((loop)->active_reqs.count > 0)
+
+#define uv__req_register(loop, req)                                           \
+  do {                                                                        \
+    (loop)->active_reqs.count++;                                              \
+  }                                                                           \
+  while (0)
+
+#define uv__req_unregister(loop, req)                                         \
+  do {                                                                        \
+    assert(uv__has_active_reqs(loop));                                        \
+    (loop)->active_reqs.count--;                                              \
+  }                                                                           \
+  while (0)
+
+#define uv__has_active_handles(loop)                                          \
+  ((loop)->active_handles > 0)
+
+#define uv__active_handle_add(h)                                              \
+  do {                                                                        \
+    (h)->loop->active_handles++;                                              \
+  }                                                                           \
+  while (0)
+
+#define uv__active_handle_rm(h)                                               \
+  do {                                                                        \
+    (h)->loop->active_handles--;                                              \
+  }                                                                           \
+  while (0)
+
+#define uv__is_active(h)                                                      \
+  (((h)->flags & UV_HANDLE_ACTIVE) != 0)
+
+#define uv__is_closing(h)                                                     \
+  (((h)->flags & (UV_HANDLE_CLOSING | UV_HANDLE_CLOSED)) != 0)
+
+#define uv__handle_start(h)                                                   \
+  do {                                                                        \
+    if (((h)->flags & UV_HANDLE_ACTIVE) != 0) break;                          \
+    (h)->flags |= UV_HANDLE_ACTIVE;                                           \
+    if (((h)->flags & UV_HANDLE_REF) != 0) uv__active_handle_add(h);          \
+  }                                                                           \
+  while (0)
+
+#define uv__handle_stop(h)                                                    \
+  do {                                                                        \
+    if (((h)->flags & UV_HANDLE_ACTIVE) == 0) break;                          \
+    (h)->flags &= ~UV_HANDLE_ACTIVE;                                          \
+    if (((h)->flags & UV_HANDLE_REF) != 0) uv__active_handle_rm(h);           \
+  }                                                                           \
+  while (0)
+
+#define uv__handle_ref(h)                                                     \
+  do {                                                                        \
+    if (((h)->flags & UV_HANDLE_REF) != 0) break;                             \
+    (h)->flags |= UV_HANDLE_REF;                                              \
+    if (((h)->flags & UV_HANDLE_CLOSING) != 0) break;                         \
+    if (((h)->flags & UV_HANDLE_ACTIVE) != 0) uv__active_handle_add(h);       \
+  }                                                                           \
+  while (0)
+
+#define uv__handle_unref(h)                                                   \
+  do {                                                                        \
+    if (((h)->flags & UV_HANDLE_REF) == 0) break;                             \
+    (h)->flags &= ~UV_HANDLE_REF;                                             \
+    if (((h)->flags & UV_HANDLE_CLOSING) != 0) break;                         \
+    if (((h)->flags & UV_HANDLE_ACTIVE) != 0) uv__active_handle_rm(h);        \
+  }                                                                           \
+  while (0)
+
+#define uv__has_ref(h)                                                        \
+  (((h)->flags & UV_HANDLE_REF) != 0)
+
+#if defined(_WIN32)
+# define uv__handle_platform_init(h) ((h)->u.fd = -1)
+#else
+# define uv__handle_platform_init(h) ((h)->next_closing = NULL)
+#endif
+
+#define uv__handle_init(loop_, h, type_)                                      \
+  do {                                                                        \
+    (h)->loop = (loop_);                                                      \
+    (h)->type = (type_);                                                      \
+    (h)->flags = UV_HANDLE_REF;  /* Ref the loop when active. */              \
+    QUEUE_INSERT_TAIL(&(loop_)->handle_queue, &(h)->handle_queue);            \
+    uv__handle_platform_init(h);                                              \
+  }                                                                           \
+  while (0)
+
+/* Note: uses an open-coded version of SET_REQ_SUCCESS() because of
+ * a circular dependency between src/uv-common.h and src/win/internal.h.
+ */
+#if defined(_WIN32)
+# define UV_REQ_INIT(req, typ)                                                \
+  do {                                                                        \
+    (req)->type = (typ);                                                      \
+    (req)->u.io.overlapped.Internal = 0;  /* SET_REQ_SUCCESS() */             \
+  }                                                                           \
+  while (0)
+#else
+# define UV_REQ_INIT(req, typ)                                                \
+  do {                                                                        \
+    (req)->type = (typ);                                                      \
+  }                                                                           \
+  while (0)
+#endif
+
+#define uv__req_init(loop, req, typ)                                          \
+  do {                                                                        \
+    UV_REQ_INIT(req, typ);                                                    \
+    uv__req_register(loop, req);                                              \
+  }                                                                           \
+  while (0)
+
+#define uv__get_internal_fields(loop)                                         \
+  ((uv__loop_internal_fields_t*) loop->internal_fields)
+
+#define uv__get_loop_metrics(loop)                                            \
+  (&uv__get_internal_fields(loop)->loop_metrics)
+
+/* Allocator prototypes */
+void *uv__calloc(size_t count, size_t size);
+char *uv__strdup(const char* s);
+char *uv__strndup(const char* s, size_t n);
+void* uv__malloc(size_t size);
+void uv__free(void* ptr);
+void* uv__realloc(void* ptr, size_t size);
+void* uv__reallocf(void* ptr, size_t size);
+
+typedef struct uv__loop_metrics_s uv__loop_metrics_t;
+typedef struct uv__loop_internal_fields_s uv__loop_internal_fields_t;
+
+struct uv__loop_metrics_s {
+  uint64_t provider_entry_time;
+  uint64_t provider_idle_time;
+  uv_mutex_t lock;
+};
+
+void uv__metrics_update_idle_time(uv_loop_t* loop);
+void uv__metrics_set_provider_entry_time(uv_loop_t* loop);
+
+struct uv__loop_internal_fields_s {
+  unsigned int flags;
+  uv__loop_metrics_t loop_metrics;
+};
+
+#endif /* UV_COMMON_H_ */
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/uv-data-getter-setters.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/uv-data-getter-setters.cpp
new file mode 100644
index 0000000..0bd0448
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/uv-data-getter-setters.cpp
@@ -0,0 +1,119 @@
+/* Copyright libuv project contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+
+const char* uv_handle_type_name(uv_handle_type type) {
+  switch (type) {
+#define XX(uc,lc) case UV_##uc: return #lc;
+  UV_HANDLE_TYPE_MAP(XX)
+#undef XX
+  case UV_FILE: return "file";
+  case UV_HANDLE_TYPE_MAX:
+  case UV_UNKNOWN_HANDLE: return NULL;
+  }
+  return NULL;
+}
+
+uv_handle_type uv_handle_get_type(const uv_handle_t* handle) {
+  return handle->type;
+}
+
+void* uv_handle_get_data(const uv_handle_t* handle) {
+  return handle->data;
+}
+
+uv_loop_t* uv_handle_get_loop(const uv_handle_t* handle) {
+  return handle->loop;
+}
+
+void uv_handle_set_data(uv_handle_t* handle, void* data) {
+  handle->data = data;
+}
+
+const char* uv_req_type_name(uv_req_type type) {
+  switch (type) {
+#define XX(uc,lc) case UV_##uc: return #lc;
+  UV_REQ_TYPE_MAP(XX)
+#undef XX
+  case UV_REQ_TYPE_MAX:
+  case UV_UNKNOWN_REQ:
+  default: /* UV_REQ_TYPE_PRIVATE */
+    break;
+  }
+  return NULL;
+}
+
+uv_req_type uv_req_get_type(const uv_req_t* req) {
+  return req->type;
+}
+
+void* uv_req_get_data(const uv_req_t* req) {
+  return req->data;
+}
+
+void uv_req_set_data(uv_req_t* req, void* data) {
+  req->data = data;
+}
+
+size_t uv_stream_get_write_queue_size(const uv_stream_t* stream) {
+  return stream->write_queue_size;
+}
+
+size_t uv_udp_get_send_queue_size(const uv_udp_t* handle) {
+  return handle->send_queue_size;
+}
+
+size_t uv_udp_get_send_queue_count(const uv_udp_t* handle) {
+  return handle->send_queue_count;
+}
+
+uv_pid_t uv_process_get_pid(const uv_process_t* proc) {
+  return proc->pid;
+}
+
+uv_fs_type uv_fs_get_type(const uv_fs_t* req) {
+  return req->fs_type;
+}
+
+ssize_t uv_fs_get_result(const uv_fs_t* req) {
+  return req->result;
+}
+
+void* uv_fs_get_ptr(const uv_fs_t* req) {
+  return req->ptr;
+}
+
+const char* uv_fs_get_path(const uv_fs_t* req) {
+  return req->path;
+}
+
+uv_stat_t* uv_fs_get_statbuf(uv_fs_t* req) {
+  return &req->statbuf;
+}
+
+void* uv_loop_get_data(const uv_loop_t* loop) {
+  return loop->data;
+}
+
+void uv_loop_set_data(uv_loop_t* loop, void* data) {
+  loop->data = data;
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/version.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/version.cpp
similarity index 100%
rename from third_party/allwpilib/wpiutil/src/main/native/libuv/src/version.cpp
rename to third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/version.cpp
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/async.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/async.cpp
new file mode 100644
index 0000000..b904676
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/async.cpp
@@ -0,0 +1,98 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <assert.h>
+
+#include "uv.h"
+#include "internal.h"
+#include "atomicops-inl.h"
+#include "handle-inl.h"
+#include "req-inl.h"
+
+
+void uv__async_endgame(uv_loop_t* loop, uv_async_t* handle) {
+  if (handle->flags & UV_HANDLE_CLOSING &&
+      !handle->async_sent) {
+    assert(!(handle->flags & UV_HANDLE_CLOSED));
+    uv__handle_close(handle);
+  }
+}
+
+
+int uv_async_init(uv_loop_t* loop, uv_async_t* handle, uv_async_cb async_cb) {
+  uv_req_t* req;
+
+  uv__handle_init(loop, (uv_handle_t*) handle, UV_ASYNC);
+  handle->async_sent = 0;
+  handle->async_cb = async_cb;
+
+  req = &handle->async_req;
+  UV_REQ_INIT(req, UV_WAKEUP);
+  req->data = handle;
+
+  uv__handle_start(handle);
+
+  return 0;
+}
+
+
+void uv__async_close(uv_loop_t* loop, uv_async_t* handle) {
+  if (!((uv_async_t*)handle)->async_sent) {
+    uv__want_endgame(loop, (uv_handle_t*) handle);
+  }
+
+  uv__handle_closing(handle);
+}
+
+
+int uv_async_send(uv_async_t* handle) {
+  uv_loop_t* loop = handle->loop;
+
+  if (handle->type != UV_ASYNC) {
+    /* Can't set errno because that's not thread-safe. */
+    return -1;
+  }
+
+  /* The user should make sure never to call uv_async_send to a closing or
+   * closed handle. */
+  assert(!(handle->flags & UV_HANDLE_CLOSING));
+
+  if (!uv__atomic_exchange_set(&handle->async_sent)) {
+    POST_COMPLETION_FOR_REQ(loop, &handle->async_req);
+  }
+
+  return 0;
+}
+
+
+void uv__process_async_wakeup_req(uv_loop_t* loop, uv_async_t* handle,
+    uv_req_t* req) {
+  assert(handle->type == UV_ASYNC);
+  assert(req->type == UV_WAKEUP);
+
+  handle->async_sent = 0;
+
+  if (handle->flags & UV_HANDLE_CLOSING) {
+    uv__want_endgame(loop, (uv_handle_t*)handle);
+  } else if (handle->async_cb != NULL) {
+    handle->async_cb(handle);
+  }
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/atomicops-inl.h b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/atomicops-inl.h
new file mode 100644
index 0000000..2f984c6
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/atomicops-inl.h
@@ -0,0 +1,61 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#ifndef UV_WIN_ATOMICOPS_INL_H_
+#define UV_WIN_ATOMICOPS_INL_H_
+
+#include "uv.h"
+#include "internal.h"
+
+
+/* Atomic set operation on char */
+#ifdef _MSC_VER /* MSVC */
+
+/* _InterlockedOr8 is supported by MSVC on x32 and x64. It is slightly less
+ * efficient than InterlockedExchange, but InterlockedExchange8 does not exist,
+ * and interlocked operations on larger targets might require the target to be
+ * aligned. */
+#pragma intrinsic(_InterlockedOr8)
+
+static char INLINE uv__atomic_exchange_set(char volatile* target) {
+  return _InterlockedOr8(target, 1);
+}
+
+#else /* GCC, Clang in mingw mode */
+
+static inline char uv__atomic_exchange_set(char volatile* target) {
+#if defined(__i386__) || defined(__x86_64__)
+  /* Mingw-32 version, hopefully this works for 64-bit gcc as well. */
+  const char one = 1;
+  char old_value;
+  __asm__ __volatile__ ("lock xchgb %0, %1\n\t"
+                        : "=r"(old_value), "=m"(*target)
+                        : "0"(one), "m"(*target)
+                        : "memory");
+  return old_value;
+#else
+  return __sync_fetch_and_or(target, 1);
+#endif
+}
+
+#endif
+
+#endif /* UV_WIN_ATOMICOPS_INL_H_ */
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/core.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/core.cpp
new file mode 100644
index 0000000..0752edf
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/core.cpp
@@ -0,0 +1,754 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <assert.h>
+#include <errno.h>
+#include <limits.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#if defined(_MSC_VER) || defined(__MINGW64_VERSION_MAJOR)
+#include <crtdbg.h>
+#endif
+
+#include "uv.h"
+#include "internal.h"
+#include "queue.h"
+#include "handle-inl.h"
+#include "heap-inl.h"
+#include "req-inl.h"
+
+/* uv_once initialization guards */
+static uv_once_t uv_init_guard_ = UV_ONCE_INIT;
+
+
+#if defined(_DEBUG) && (defined(_MSC_VER) || defined(__MINGW64_VERSION_MAJOR))
+/* Our crt debug report handler allows us to temporarily disable asserts
+ * just for the current thread.
+ */
+
+UV_THREAD_LOCAL int uv__crt_assert_enabled = TRUE;
+
+static int uv__crt_dbg_report_handler(int report_type, char *message, int *ret_val) {
+  if (uv__crt_assert_enabled || report_type != _CRT_ASSERT)
+    return FALSE;
+
+  if (ret_val) {
+    /* Set ret_val to 0 to continue with normal execution.
+     * Set ret_val to 1 to trigger a breakpoint.
+    */
+
+    if(IsDebuggerPresent())
+      *ret_val = 1;
+    else
+      *ret_val = 0;
+  }
+
+  /* Don't call _CrtDbgReport. */
+  return TRUE;
+}
+#else
+UV_THREAD_LOCAL int uv__crt_assert_enabled = FALSE;
+#endif
+
+
+#if !defined(__MINGW32__) || __MSVCRT_VERSION__ >= 0x800
+static void uv__crt_invalid_parameter_handler(const wchar_t* expression,
+    const wchar_t* function, const wchar_t * file, unsigned int line,
+    uintptr_t reserved) {
+  /* No-op. */
+}
+#endif
+
+static uv_loop_t** uv__loops;
+static int uv__loops_size;
+static int uv__loops_capacity;
+#define UV__LOOPS_CHUNK_SIZE 8
+static uv_mutex_t uv__loops_lock;
+
+
+static void uv__loops_init(void) {
+  uv_mutex_init(&uv__loops_lock);
+}
+
+
+static int uv__loops_add(uv_loop_t* loop) {
+  uv_loop_t** new_loops;
+  int new_capacity, i;
+
+  uv_mutex_lock(&uv__loops_lock);
+
+  if (uv__loops_size == uv__loops_capacity) {
+    new_capacity = uv__loops_capacity + UV__LOOPS_CHUNK_SIZE;
+    new_loops = (uv_loop_t**)
+        uv__realloc(uv__loops, sizeof(uv_loop_t*) * new_capacity);
+    if (!new_loops)
+      goto failed_loops_realloc;
+    uv__loops = new_loops;
+    for (i = uv__loops_capacity; i < new_capacity; ++i)
+      uv__loops[i] = NULL;
+    uv__loops_capacity = new_capacity;
+  }
+  uv__loops[uv__loops_size] = loop;
+  ++uv__loops_size;
+
+  uv_mutex_unlock(&uv__loops_lock);
+  return 0;
+
+failed_loops_realloc:
+  uv_mutex_unlock(&uv__loops_lock);
+  return ERROR_OUTOFMEMORY;
+}
+
+
+static void uv__loops_remove(uv_loop_t* loop) {
+  int loop_index;
+  int smaller_capacity;
+  uv_loop_t** new_loops;
+
+  uv_mutex_lock(&uv__loops_lock);
+
+  for (loop_index = 0; loop_index < uv__loops_size; ++loop_index) {
+    if (uv__loops[loop_index] == loop)
+      break;
+  }
+  /* If loop was not found, ignore */
+  if (loop_index == uv__loops_size)
+    goto loop_removed;
+
+  uv__loops[loop_index] = uv__loops[uv__loops_size - 1];
+  uv__loops[uv__loops_size - 1] = NULL;
+  --uv__loops_size;
+
+  if (uv__loops_size == 0) {
+    uv__loops_capacity = 0;
+    uv__free(uv__loops);
+    uv__loops = NULL;
+    goto loop_removed;
+  }
+
+  /* If we didn't grow to big skip downsizing */
+  if (uv__loops_capacity < 4 * UV__LOOPS_CHUNK_SIZE)
+    goto loop_removed;
+
+  /* Downsize only if more than half of buffer is free */
+  smaller_capacity = uv__loops_capacity / 2;
+  if (uv__loops_size >= smaller_capacity)
+    goto loop_removed;
+  new_loops = (uv_loop_t**)
+      uv__realloc(uv__loops, sizeof(uv_loop_t*) * smaller_capacity);
+  if (!new_loops)
+    goto loop_removed;
+  uv__loops = new_loops;
+  uv__loops_capacity = smaller_capacity;
+
+loop_removed:
+  uv_mutex_unlock(&uv__loops_lock);
+}
+
+void uv__wake_all_loops(void) {
+  int i;
+  uv_loop_t* loop;
+
+  uv_mutex_lock(&uv__loops_lock);
+  for (i = 0; i < uv__loops_size; ++i) {
+    loop = uv__loops[i];
+    assert(loop);
+    if (loop->iocp != INVALID_HANDLE_VALUE)
+      PostQueuedCompletionStatus(loop->iocp, 0, 0, NULL);
+  }
+  uv_mutex_unlock(&uv__loops_lock);
+}
+
+static void uv__init(void) {
+  /* Tell Windows that we will handle critical errors. */
+  SetErrorMode(SEM_FAILCRITICALERRORS | SEM_NOGPFAULTERRORBOX |
+               SEM_NOOPENFILEERRORBOX);
+
+  /* Tell the CRT to not exit the application when an invalid parameter is
+   * passed. The main issue is that invalid FDs will trigger this behavior.
+   */
+#if !defined(__MINGW32__) || __MSVCRT_VERSION__ >= 0x800
+  _set_invalid_parameter_handler(uv__crt_invalid_parameter_handler);
+#endif
+
+  /* We also need to setup our debug report handler because some CRT
+   * functions (eg _get_osfhandle) raise an assert when called with invalid
+   * FDs even though they return the proper error code in the release build.
+   */
+#if defined(_DEBUG) && (defined(_MSC_VER) || defined(__MINGW64_VERSION_MAJOR))
+  _CrtSetReportHook(uv__crt_dbg_report_handler);
+#endif
+
+  /* Initialize tracking of all uv loops */
+  uv__loops_init();
+
+  /* Fetch winapi function pointers. This must be done first because other
+   * initialization code might need these function pointers to be loaded.
+   */
+  uv__winapi_init();
+
+  /* Initialize winsock */
+  uv__winsock_init();
+
+  /* Initialize FS */
+  uv__fs_init();
+
+  /* Initialize signal stuff */
+  uv__signals_init();
+
+  /* Initialize console */
+  uv__console_init();
+
+  /* Initialize utilities */
+  uv__util_init();
+
+  /* Initialize system wakeup detection */
+  uv__init_detect_system_wakeup();
+}
+
+
+int uv_loop_init(uv_loop_t* loop) {
+  uv__loop_internal_fields_t* lfields;
+  struct heap* timer_heap;
+  int err;
+
+  /* Initialize libuv itself first */
+  uv__once_init();
+
+  /* Create an I/O completion port */
+  loop->iocp = CreateIoCompletionPort(INVALID_HANDLE_VALUE, NULL, 0, 1);
+  if (loop->iocp == NULL)
+    return uv_translate_sys_error(GetLastError());
+
+  lfields = (uv__loop_internal_fields_t*) uv__calloc(1, sizeof(*lfields));
+  if (lfields == NULL)
+    return UV_ENOMEM;
+  loop->internal_fields = lfields;
+
+  err = uv_mutex_init(&lfields->loop_metrics.lock);
+  if (err)
+    goto fail_metrics_mutex_init;
+
+  /* To prevent uninitialized memory access, loop->time must be initialized
+   * to zero before calling uv_update_time for the first time.
+   */
+  loop->time = 0;
+  uv_update_time(loop);
+
+  QUEUE_INIT(&loop->wq);
+  QUEUE_INIT(&loop->handle_queue);
+  loop->active_reqs.count = 0;
+  loop->active_handles = 0;
+
+  loop->pending_reqs_tail = NULL;
+
+  loop->endgame_handles = NULL;
+
+  loop->timer_heap = timer_heap = (heap*)uv__malloc(sizeof(*timer_heap));
+  if (timer_heap == NULL) {
+    err = UV_ENOMEM;
+    goto fail_timers_alloc;
+  }
+
+  heap_init(timer_heap);
+
+  loop->check_handles = NULL;
+  loop->prepare_handles = NULL;
+  loop->idle_handles = NULL;
+
+  loop->next_prepare_handle = NULL;
+  loop->next_check_handle = NULL;
+  loop->next_idle_handle = NULL;
+
+  memset(&loop->poll_peer_sockets, 0, sizeof loop->poll_peer_sockets);
+
+  loop->active_tcp_streams = 0;
+  loop->active_udp_streams = 0;
+
+  loop->timer_counter = 0;
+  loop->stop_flag = 0;
+
+  err = uv_mutex_init(&loop->wq_mutex);
+  if (err)
+    goto fail_mutex_init;
+
+  err = uv_async_init(loop, &loop->wq_async, uv__work_done);
+  if (err)
+    goto fail_async_init;
+
+  uv__handle_unref(&loop->wq_async);
+  loop->wq_async.flags |= UV_HANDLE_INTERNAL;
+
+  err = uv__loops_add(loop);
+  if (err)
+    goto fail_async_init;
+
+  return 0;
+
+fail_async_init:
+  uv_mutex_destroy(&loop->wq_mutex);
+
+fail_mutex_init:
+  uv__free(timer_heap);
+  loop->timer_heap = NULL;
+
+fail_timers_alloc:
+  uv_mutex_destroy(&lfields->loop_metrics.lock);
+
+fail_metrics_mutex_init:
+  uv__free(lfields);
+  loop->internal_fields = NULL;
+  CloseHandle(loop->iocp);
+  loop->iocp = INVALID_HANDLE_VALUE;
+
+  return err;
+}
+
+
+void uv_update_time(uv_loop_t* loop) {
+  uint64_t new_time = uv__hrtime(1000);
+  assert(new_time >= loop->time);
+  loop->time = new_time;
+}
+
+
+void uv__once_init(void) {
+  uv_once(&uv_init_guard_, uv__init);
+}
+
+
+void uv__loop_close(uv_loop_t* loop) {
+  uv__loop_internal_fields_t* lfields;
+  size_t i;
+
+  uv__loops_remove(loop);
+
+  /* Close the async handle without needing an extra loop iteration.
+   * We might have a pending message, but we're just going to destroy the IOCP
+   * soon, so we can just discard it now without the usual risk of a getting
+   * another notification from GetQueuedCompletionStatusEx after calling the
+   * close_cb (which we also skip defining). We'll assert later that queue was
+   * actually empty and all reqs handled. */
+  loop->wq_async.async_sent = 0;
+  loop->wq_async.close_cb = NULL;
+  uv__handle_closing(&loop->wq_async);
+  uv__handle_close(&loop->wq_async);
+
+  for (i = 0; i < ARRAY_SIZE(loop->poll_peer_sockets); i++) {
+    SOCKET sock = loop->poll_peer_sockets[i];
+    if (sock != 0 && sock != INVALID_SOCKET)
+      closesocket(sock);
+  }
+
+  uv_mutex_lock(&loop->wq_mutex);
+  assert(QUEUE_EMPTY(&loop->wq) && "thread pool work queue not empty!");
+  assert(!uv__has_active_reqs(loop));
+  uv_mutex_unlock(&loop->wq_mutex);
+  uv_mutex_destroy(&loop->wq_mutex);
+
+  uv__free(loop->timer_heap);
+  loop->timer_heap = NULL;
+
+  lfields = uv__get_internal_fields(loop);
+  uv_mutex_destroy(&lfields->loop_metrics.lock);
+  uv__free(lfields);
+  loop->internal_fields = NULL;
+
+  CloseHandle(loop->iocp);
+}
+
+
+int uv__loop_configure(uv_loop_t* loop, uv_loop_option option, va_list ap) {
+  uv__loop_internal_fields_t* lfields;
+
+  lfields = uv__get_internal_fields(loop);
+  if (option == UV_METRICS_IDLE_TIME) {
+    lfields->flags |= UV_METRICS_IDLE_TIME;
+    return 0;
+  }
+
+  return UV_ENOSYS;
+}
+
+
+int uv_backend_fd(const uv_loop_t* loop) {
+  return -1;
+}
+
+
+int uv_loop_fork(uv_loop_t* loop) {
+  return UV_ENOSYS;
+}
+
+
+static int uv__loop_alive(const uv_loop_t* loop) {
+  return uv__has_active_handles(loop) ||
+         uv__has_active_reqs(loop) ||
+         loop->pending_reqs_tail != NULL ||
+         loop->endgame_handles != NULL;
+}
+
+
+int uv_loop_alive(const uv_loop_t* loop) {
+  return uv__loop_alive(loop);
+}
+
+
+int uv_backend_timeout(const uv_loop_t* loop) {
+  if (loop->stop_flag == 0 &&
+      /* uv__loop_alive(loop) && */
+      (uv__has_active_handles(loop) || uv__has_active_reqs(loop)) &&
+      loop->pending_reqs_tail == NULL &&
+      loop->idle_handles == NULL &&
+      loop->endgame_handles == NULL)
+    return uv__next_timeout(loop);
+  return 0;
+}
+
+
+static void uv__poll_wine(uv_loop_t* loop, DWORD timeout) {
+  DWORD bytes;
+  ULONG_PTR key;
+  OVERLAPPED* overlapped;
+  uv_req_t* req;
+  int repeat;
+  uint64_t timeout_time;
+  uint64_t user_timeout;
+  int reset_timeout;
+
+  timeout_time = loop->time + timeout;
+
+  if (uv__get_internal_fields(loop)->flags & UV_METRICS_IDLE_TIME) {
+    reset_timeout = 1;
+    user_timeout = timeout;
+    timeout = 0;
+  } else {
+    reset_timeout = 0;
+  }
+
+  for (repeat = 0; ; repeat++) {
+    /* Only need to set the provider_entry_time if timeout != 0. The function
+     * will return early if the loop isn't configured with UV_METRICS_IDLE_TIME.
+     */
+    if (timeout != 0)
+      uv__metrics_set_provider_entry_time(loop);
+
+    GetQueuedCompletionStatus(loop->iocp,
+                              &bytes,
+                              &key,
+                              &overlapped,
+                              timeout);
+
+    if (reset_timeout != 0) {
+      timeout = user_timeout;
+      reset_timeout = 0;
+    }
+
+    /* Placed here because on success the loop will break whether there is an
+     * empty package or not, or if GetQueuedCompletionStatus returned early then
+     * the timeout will be updated and the loop will run again. In either case
+     * the idle time will need to be updated.
+     */
+    uv__metrics_update_idle_time(loop);
+
+    if (overlapped) {
+      /* Package was dequeued */
+      req = uv__overlapped_to_req(overlapped);
+      uv__insert_pending_req(loop, req);
+
+      /* Some time might have passed waiting for I/O,
+       * so update the loop time here.
+       */
+      uv_update_time(loop);
+    } else if (GetLastError() != WAIT_TIMEOUT) {
+      /* Serious error */
+      uv_fatal_error(GetLastError(), "GetQueuedCompletionStatus");
+    } else if (timeout > 0) {
+      /* GetQueuedCompletionStatus can occasionally return a little early.
+       * Make sure that the desired timeout target time is reached.
+       */
+      uv_update_time(loop);
+      if (timeout_time > loop->time) {
+        timeout = (DWORD)(timeout_time - loop->time);
+        /* The first call to GetQueuedCompletionStatus should return very
+         * close to the target time and the second should reach it, but
+         * this is not stated in the documentation. To make sure a busy
+         * loop cannot happen, the timeout is increased exponentially
+         * starting on the third round.
+         */
+        timeout += repeat ? (1 << (repeat - 1)) : 0;
+        continue;
+      }
+    }
+    break;
+  }
+}
+
+
+static void uv__poll(uv_loop_t* loop, DWORD timeout) {
+  BOOL success;
+  uv_req_t* req;
+  OVERLAPPED_ENTRY overlappeds[128];
+  ULONG count;
+  ULONG i;
+  int repeat;
+  uint64_t timeout_time;
+  uint64_t user_timeout;
+  int reset_timeout;
+
+  timeout_time = loop->time + timeout;
+
+  if (uv__get_internal_fields(loop)->flags & UV_METRICS_IDLE_TIME) {
+    reset_timeout = 1;
+    user_timeout = timeout;
+    timeout = 0;
+  } else {
+    reset_timeout = 0;
+  }
+
+  for (repeat = 0; ; repeat++) {
+    /* Only need to set the provider_entry_time if timeout != 0. The function
+     * will return early if the loop isn't configured with UV_METRICS_IDLE_TIME.
+     */
+    if (timeout != 0)
+      uv__metrics_set_provider_entry_time(loop);
+
+    success = pGetQueuedCompletionStatusEx(loop->iocp,
+                                           overlappeds,
+                                           ARRAY_SIZE(overlappeds),
+                                           &count,
+                                           timeout,
+                                           FALSE);
+
+    if (reset_timeout != 0) {
+      timeout = user_timeout;
+      reset_timeout = 0;
+    }
+
+    /* Placed here because on success the loop will break whether there is an
+     * empty package or not, or if GetQueuedCompletionStatus returned early then
+     * the timeout will be updated and the loop will run again. In either case
+     * the idle time will need to be updated.
+     */
+    uv__metrics_update_idle_time(loop);
+
+    if (success) {
+      for (i = 0; i < count; i++) {
+        /* Package was dequeued, but see if it is not a empty package
+         * meant only to wake us up.
+         */
+        if (overlappeds[i].lpOverlapped) {
+          req = uv__overlapped_to_req(overlappeds[i].lpOverlapped);
+          uv__insert_pending_req(loop, req);
+        }
+      }
+
+      /* Some time might have passed waiting for I/O,
+       * so update the loop time here.
+       */
+      uv_update_time(loop);
+    } else if (GetLastError() != WAIT_TIMEOUT) {
+      /* Serious error */
+      uv_fatal_error(GetLastError(), "GetQueuedCompletionStatusEx");
+    } else if (timeout > 0) {
+      /* GetQueuedCompletionStatus can occasionally return a little early.
+       * Make sure that the desired timeout target time is reached.
+       */
+      uv_update_time(loop);
+      if (timeout_time > loop->time) {
+        timeout = (DWORD)(timeout_time - loop->time);
+        /* The first call to GetQueuedCompletionStatus should return very
+         * close to the target time and the second should reach it, but
+         * this is not stated in the documentation. To make sure a busy
+         * loop cannot happen, the timeout is increased exponentially
+         * starting on the third round.
+         */
+        timeout += repeat ? (1 << (repeat - 1)) : 0;
+        continue;
+      }
+    }
+    break;
+  }
+}
+
+
+int uv_run(uv_loop_t *loop, uv_run_mode mode) {
+  DWORD timeout;
+  int r;
+  int can_sleep;
+
+  r = uv__loop_alive(loop);
+  if (!r)
+    uv_update_time(loop);
+
+  while (r != 0 && loop->stop_flag == 0) {
+    uv_update_time(loop);
+    uv__run_timers(loop);
+
+    can_sleep = loop->pending_reqs_tail == NULL && loop->idle_handles == NULL;
+
+    uv__process_reqs(loop);
+    uv__idle_invoke(loop);
+    uv__prepare_invoke(loop);
+
+    timeout = 0;
+    if ((mode == UV_RUN_ONCE && can_sleep) || mode == UV_RUN_DEFAULT)
+      timeout = uv_backend_timeout(loop);
+
+    if (pGetQueuedCompletionStatusEx)
+      uv__poll(loop, timeout);
+    else
+      uv__poll_wine(loop, timeout);
+
+    /* Process immediate callbacks (e.g. write_cb) a small fixed number of
+     * times to avoid loop starvation.*/
+    for (r = 0; r < 8 && loop->pending_reqs_tail != NULL; r++)
+      uv__process_reqs(loop);
+
+    /* Run one final update on the provider_idle_time in case uv__poll*
+     * returned because the timeout expired, but no events were received. This
+     * call will be ignored if the provider_entry_time was either never set (if
+     * the timeout == 0) or was already updated b/c an event was received.
+     */
+    uv__metrics_update_idle_time(loop);
+
+    uv__check_invoke(loop);
+    uv__process_endgames(loop);
+
+    if (mode == UV_RUN_ONCE) {
+      /* UV_RUN_ONCE implies forward progress: at least one callback must have
+       * been invoked when it returns. uv__io_poll() can return without doing
+       * I/O (meaning: no callbacks) when its timeout expires - which means we
+       * have pending timers that satisfy the forward progress constraint.
+       *
+       * UV_RUN_NOWAIT makes no guarantees about progress so it's omitted from
+       * the check.
+       */
+      uv_update_time(loop);
+      uv__run_timers(loop);
+    }
+
+    r = uv__loop_alive(loop);
+    if (mode == UV_RUN_ONCE || mode == UV_RUN_NOWAIT)
+      break;
+  }
+
+  /* The if statement lets the compiler compile it to a conditional store.
+   * Avoids dirtying a cache line.
+   */
+  if (loop->stop_flag != 0)
+    loop->stop_flag = 0;
+
+  return r;
+}
+
+
+int uv_fileno(const uv_handle_t* handle, uv_os_fd_t* fd) {
+  uv_os_fd_t fd_out;
+
+  switch (handle->type) {
+  case UV_TCP:
+    fd_out = (uv_os_fd_t)((uv_tcp_t*) handle)->socket;
+    break;
+
+  case UV_NAMED_PIPE:
+    fd_out = ((uv_pipe_t*) handle)->handle;
+    break;
+
+  case UV_TTY:
+    fd_out = ((uv_tty_t*) handle)->handle;
+    break;
+
+  case UV_UDP:
+    fd_out = (uv_os_fd_t)((uv_udp_t*) handle)->socket;
+    break;
+
+  case UV_POLL:
+    fd_out = (uv_os_fd_t)((uv_poll_t*) handle)->socket;
+    break;
+
+  default:
+    return UV_EINVAL;
+  }
+
+  if (uv_is_closing(handle) || fd_out == INVALID_HANDLE_VALUE)
+    return UV_EBADF;
+
+  *fd = fd_out;
+  return 0;
+}
+
+
+int uv__socket_sockopt(uv_handle_t* handle, int optname, int* value) {
+  int r;
+  int len;
+  SOCKET socket;
+
+  if (handle == NULL || value == NULL)
+    return UV_EINVAL;
+
+  if (handle->type == UV_TCP)
+    socket = ((uv_tcp_t*) handle)->socket;
+  else if (handle->type == UV_UDP)
+    socket = ((uv_udp_t*) handle)->socket;
+  else
+    return UV_ENOTSUP;
+
+  len = sizeof(*value);
+
+  if (*value == 0)
+    r = getsockopt(socket, SOL_SOCKET, optname, (char*) value, &len);
+  else
+    r = setsockopt(socket, SOL_SOCKET, optname, (const char*) value, len);
+
+  if (r == SOCKET_ERROR)
+    return uv_translate_sys_error(WSAGetLastError());
+
+  return 0;
+}
+
+int uv_cpumask_size(void) {
+  return (int)(sizeof(DWORD_PTR) * 8);
+}
+
+int uv__getsockpeername(const uv_handle_t* handle,
+                        uv__peersockfunc func,
+                        struct sockaddr* name,
+                        int* namelen,
+                        int delayed_error) {
+
+  int result;
+  uv_os_fd_t fd;
+
+  result = uv_fileno(handle, &fd);
+  if (result != 0)
+    return result;
+
+  if (delayed_error)
+    return uv_translate_sys_error(delayed_error);
+
+  result = func((SOCKET) fd, name, namelen);
+  if (result != 0)
+    return uv_translate_sys_error(WSAGetLastError());
+
+  return 0;
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/detect-wakeup.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/detect-wakeup.cpp
new file mode 100644
index 0000000..ab19361
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/detect-wakeup.cpp
@@ -0,0 +1,56 @@
+/* Copyright libuv project contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+#include "winapi.h"
+
+static void uv__register_system_resume_callback(void);
+
+void uv__init_detect_system_wakeup(void) {
+  /* Try registering system power event callback. This is the cleanest
+   * method, but it will only work on Win8 and above.
+   */
+  uv__register_system_resume_callback();
+}
+
+static ULONG CALLBACK uv__system_resume_callback(PVOID Context,
+                                                 ULONG Type,
+                                                 PVOID Setting) {
+  if (Type == PBT_APMRESUMESUSPEND || Type == PBT_APMRESUMEAUTOMATIC)
+    uv__wake_all_loops();
+
+  return 0;
+}
+
+static void uv__register_system_resume_callback(void) {
+  _DEVICE_NOTIFY_SUBSCRIBE_PARAMETERS recipient;
+  _HPOWERNOTIFY registration_handle;
+
+  if (pPowerRegisterSuspendResumeNotification == NULL)
+    return;
+
+  recipient.Callback = uv__system_resume_callback;
+  recipient.Context = NULL;
+  (*pPowerRegisterSuspendResumeNotification)(DEVICE_NOTIFY_CALLBACK,
+                                             &recipient,
+                                             &registration_handle);
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/dl.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/dl.cpp
similarity index 100%
rename from third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/dl.cpp
rename to third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/dl.cpp
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/error.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/error.cpp
new file mode 100644
index 0000000..3a269da
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/error.cpp
@@ -0,0 +1,173 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <assert.h>
+#include <errno.h>
+#include <stdio.h>
+#include <string.h>
+#include <stdlib.h>
+
+#include "uv.h"
+#include "internal.h"
+
+
+/*
+ * Display an error message and abort the event loop.
+ */
+void uv_fatal_error(const int errorno, const char* syscall) {
+  char* buf = NULL;
+  const char* errmsg;
+
+  FormatMessageA(FORMAT_MESSAGE_ALLOCATE_BUFFER | FORMAT_MESSAGE_FROM_SYSTEM |
+      FORMAT_MESSAGE_IGNORE_INSERTS, NULL, errorno,
+      MAKELANGID(LANG_NEUTRAL, SUBLANG_DEFAULT), (LPSTR)&buf, 0, NULL);
+
+  if (buf) {
+    errmsg = buf;
+  } else {
+    errmsg = "Unknown error";
+  }
+
+  /* FormatMessage messages include a newline character already, so don't add
+   * another. */
+  if (syscall) {
+    fprintf(stderr, "%s: (%d) %s", syscall, errorno, errmsg);
+  } else {
+    fprintf(stderr, "(%d) %s", errorno, errmsg);
+  }
+
+  if (buf) {
+    LocalFree(buf);
+  }
+
+  DebugBreak();
+  abort();
+}
+
+
+int uv_translate_sys_error(int sys_errno) {
+  if (sys_errno <= 0) {
+    return sys_errno;  /* If < 0 then it's already a libuv error. */
+  }
+
+  switch (sys_errno) {
+    case ERROR_NOACCESS:                    return UV_EACCES;
+    case WSAEACCES:                         return UV_EACCES;
+    case ERROR_ELEVATION_REQUIRED:          return UV_EACCES;
+    case ERROR_CANT_ACCESS_FILE:            return UV_EACCES;
+    case ERROR_ADDRESS_ALREADY_ASSOCIATED:  return UV_EADDRINUSE;
+    case WSAEADDRINUSE:                     return UV_EADDRINUSE;
+    case WSAEADDRNOTAVAIL:                  return UV_EADDRNOTAVAIL;
+    case WSAEAFNOSUPPORT:                   return UV_EAFNOSUPPORT;
+    case WSAEWOULDBLOCK:                    return UV_EAGAIN;
+    case WSAEALREADY:                       return UV_EALREADY;
+    case ERROR_INVALID_FLAGS:               return UV_EBADF;
+    case ERROR_INVALID_HANDLE:              return UV_EBADF;
+    case ERROR_LOCK_VIOLATION:              return UV_EBUSY;
+    case ERROR_PIPE_BUSY:                   return UV_EBUSY;
+    case ERROR_SHARING_VIOLATION:           return UV_EBUSY;
+    case ERROR_OPERATION_ABORTED:           return UV_ECANCELED;
+    case WSAEINTR:                          return UV_ECANCELED;
+    case ERROR_NO_UNICODE_TRANSLATION:      return UV_ECHARSET;
+    case ERROR_CONNECTION_ABORTED:          return UV_ECONNABORTED;
+    case WSAECONNABORTED:                   return UV_ECONNABORTED;
+    case ERROR_CONNECTION_REFUSED:          return UV_ECONNREFUSED;
+    case WSAECONNREFUSED:                   return UV_ECONNREFUSED;
+    case ERROR_NETNAME_DELETED:             return UV_ECONNRESET;
+    case WSAECONNRESET:                     return UV_ECONNRESET;
+    case ERROR_ALREADY_EXISTS:              return UV_EEXIST;
+    case ERROR_FILE_EXISTS:                 return UV_EEXIST;
+    case ERROR_BUFFER_OVERFLOW:             return UV_EFAULT;
+    case WSAEFAULT:                         return UV_EFAULT;
+    case ERROR_HOST_UNREACHABLE:            return UV_EHOSTUNREACH;
+    case WSAEHOSTUNREACH:                   return UV_EHOSTUNREACH;
+    case ERROR_INSUFFICIENT_BUFFER:         return UV_EINVAL;
+    case ERROR_INVALID_DATA:                return UV_EINVAL;
+    case ERROR_INVALID_PARAMETER:           return UV_EINVAL;
+    case ERROR_SYMLINK_NOT_SUPPORTED:       return UV_EINVAL;
+    case WSAEINVAL:                         return UV_EINVAL;
+    case WSAEPFNOSUPPORT:                   return UV_EINVAL;
+    case ERROR_BEGINNING_OF_MEDIA:          return UV_EIO;
+    case ERROR_BUS_RESET:                   return UV_EIO;
+    case ERROR_CRC:                         return UV_EIO;
+    case ERROR_DEVICE_DOOR_OPEN:            return UV_EIO;
+    case ERROR_DEVICE_REQUIRES_CLEANING:    return UV_EIO;
+    case ERROR_DISK_CORRUPT:                return UV_EIO;
+    case ERROR_EOM_OVERFLOW:                return UV_EIO;
+    case ERROR_FILEMARK_DETECTED:           return UV_EIO;
+    case ERROR_GEN_FAILURE:                 return UV_EIO;
+    case ERROR_INVALID_BLOCK_LENGTH:        return UV_EIO;
+    case ERROR_IO_DEVICE:                   return UV_EIO;
+    case ERROR_NO_DATA_DETECTED:            return UV_EIO;
+    case ERROR_NO_SIGNAL_SENT:              return UV_EIO;
+    case ERROR_OPEN_FAILED:                 return UV_EIO;
+    case ERROR_SETMARK_DETECTED:            return UV_EIO;
+    case ERROR_SIGNAL_REFUSED:              return UV_EIO;
+    case WSAEISCONN:                        return UV_EISCONN;
+    case ERROR_CANT_RESOLVE_FILENAME:       return UV_ELOOP;
+    case ERROR_TOO_MANY_OPEN_FILES:         return UV_EMFILE;
+    case WSAEMFILE:                         return UV_EMFILE;
+    case WSAEMSGSIZE:                       return UV_EMSGSIZE;
+    case ERROR_FILENAME_EXCED_RANGE:        return UV_ENAMETOOLONG;
+    case ERROR_NETWORK_UNREACHABLE:         return UV_ENETUNREACH;
+    case WSAENETUNREACH:                    return UV_ENETUNREACH;
+    case WSAENOBUFS:                        return UV_ENOBUFS;
+    case ERROR_BAD_PATHNAME:                return UV_ENOENT;
+    case ERROR_DIRECTORY:                   return UV_ENOENT;
+    case ERROR_ENVVAR_NOT_FOUND:            return UV_ENOENT;
+    case ERROR_FILE_NOT_FOUND:              return UV_ENOENT;
+    case ERROR_INVALID_NAME:                return UV_ENOENT;
+    case ERROR_INVALID_DRIVE:               return UV_ENOENT;
+    case ERROR_INVALID_REPARSE_DATA:        return UV_ENOENT;
+    case ERROR_MOD_NOT_FOUND:               return UV_ENOENT;
+    case ERROR_PATH_NOT_FOUND:              return UV_ENOENT;
+    case WSAHOST_NOT_FOUND:                 return UV_ENOENT;
+    case WSANO_DATA:                        return UV_ENOENT;
+    case ERROR_NOT_ENOUGH_MEMORY:           return UV_ENOMEM;
+    case ERROR_OUTOFMEMORY:                 return UV_ENOMEM;
+    case ERROR_CANNOT_MAKE:                 return UV_ENOSPC;
+    case ERROR_DISK_FULL:                   return UV_ENOSPC;
+    case ERROR_EA_TABLE_FULL:               return UV_ENOSPC;
+    case ERROR_END_OF_MEDIA:                return UV_ENOSPC;
+    case ERROR_HANDLE_DISK_FULL:            return UV_ENOSPC;
+    case ERROR_NOT_CONNECTED:               return UV_ENOTCONN;
+    case WSAENOTCONN:                       return UV_ENOTCONN;
+    case ERROR_DIR_NOT_EMPTY:               return UV_ENOTEMPTY;
+    case WSAENOTSOCK:                       return UV_ENOTSOCK;
+    case ERROR_NOT_SUPPORTED:               return UV_ENOTSUP;
+    case ERROR_BROKEN_PIPE:                 return UV_EOF;
+    case ERROR_ACCESS_DENIED:               return UV_EPERM;
+    case ERROR_PRIVILEGE_NOT_HELD:          return UV_EPERM;
+    case ERROR_BAD_PIPE:                    return UV_EPIPE;
+    case ERROR_NO_DATA:                     return UV_EPIPE;
+    case ERROR_PIPE_NOT_CONNECTED:          return UV_EPIPE;
+    case WSAESHUTDOWN:                      return UV_EPIPE;
+    case WSAEPROTONOSUPPORT:                return UV_EPROTONOSUPPORT;
+    case ERROR_WRITE_PROTECT:               return UV_EROFS;
+    case ERROR_SEM_TIMEOUT:                 return UV_ETIMEDOUT;
+    case WSAETIMEDOUT:                      return UV_ETIMEDOUT;
+    case ERROR_NOT_SAME_DEVICE:             return UV_EXDEV;
+    case ERROR_INVALID_FUNCTION:            return UV_EISDIR;
+    case ERROR_META_EXPANSION_TOO_LONG:     return UV_E2BIG;
+    case WSAESOCKTNOSUPPORT:                return UV_ESOCKTNOSUPPORT;
+    default:                                return UV_UNKNOWN;
+  }
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/fs-event.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/fs-event.cpp
new file mode 100644
index 0000000..3244a4e
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/fs-event.cpp
@@ -0,0 +1,610 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#define _CRT_NONSTDC_NO_WARNINGS
+
+#include <assert.h>
+#include <errno.h>
+#include <stdio.h>
+#include <string.h>
+
+#include "uv.h"
+#include "internal.h"
+#include "handle-inl.h"
+#include "req-inl.h"
+
+
+const unsigned int uv_directory_watcher_buffer_size = 4096;
+
+
+static void uv__fs_event_queue_readdirchanges(uv_loop_t* loop,
+    uv_fs_event_t* handle) {
+  assert(handle->dir_handle != INVALID_HANDLE_VALUE);
+  assert(!handle->req_pending);
+
+  memset(&(handle->req.u.io.overlapped), 0,
+         sizeof(handle->req.u.io.overlapped));
+  if (!ReadDirectoryChangesW(handle->dir_handle,
+                             handle->buffer,
+                             uv_directory_watcher_buffer_size,
+                             (handle->flags & UV_FS_EVENT_RECURSIVE) ? TRUE : FALSE,
+                             FILE_NOTIFY_CHANGE_FILE_NAME      |
+                               FILE_NOTIFY_CHANGE_DIR_NAME     |
+                               FILE_NOTIFY_CHANGE_ATTRIBUTES   |
+                               FILE_NOTIFY_CHANGE_SIZE         |
+                               FILE_NOTIFY_CHANGE_LAST_WRITE   |
+                               FILE_NOTIFY_CHANGE_LAST_ACCESS  |
+                               FILE_NOTIFY_CHANGE_CREATION     |
+                               FILE_NOTIFY_CHANGE_SECURITY,
+                             NULL,
+                             &handle->req.u.io.overlapped,
+                             NULL)) {
+    /* Make this req pending reporting an error. */
+    SET_REQ_ERROR(&handle->req, GetLastError());
+    uv__insert_pending_req(loop, (uv_req_t*)&handle->req);
+  }
+
+  handle->req_pending = 1;
+}
+
+static void uv__relative_path(const WCHAR* filename,
+                              const WCHAR* dir,
+                              WCHAR** relpath) {
+  size_t relpathlen;
+  size_t filenamelen = wcslen(filename);
+  size_t dirlen = wcslen(dir);
+  assert(!_wcsnicmp(filename, dir, dirlen));
+  if (dirlen > 0 && dir[dirlen - 1] == '\\')
+    dirlen--;
+  relpathlen = filenamelen - dirlen - 1;
+  *relpath = (WCHAR*)uv__malloc((relpathlen + 1) * sizeof(WCHAR));
+  if (!*relpath)
+    uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+  wcsncpy(*relpath, filename + dirlen + 1, relpathlen);
+  (*relpath)[relpathlen] = L'\0';
+}
+
+static int uv__split_path(const WCHAR* filename, WCHAR** dir,
+    WCHAR** file) {
+  size_t len, i;
+  DWORD dir_len;
+
+  if (filename == NULL) {
+    if (dir != NULL)
+      *dir = NULL;
+    *file = NULL;
+    return 0;
+  }
+
+  len = wcslen(filename);
+  i = len;
+  while (i > 0 && filename[--i] != '\\' && filename[i] != '/');
+
+  if (i == 0) {
+    if (dir) {
+      dir_len = GetCurrentDirectoryW(0, NULL);
+      if (dir_len == 0) {
+        return -1;
+      }
+      *dir = (WCHAR*)uv__malloc(dir_len * sizeof(WCHAR));
+      if (!*dir) {
+        uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+      }
+
+      if (!GetCurrentDirectoryW(dir_len, *dir)) {
+        uv__free(*dir);
+        *dir = NULL;
+        return -1;
+      }
+    }
+
+    *file = wcsdup(filename);
+  } else {
+    if (dir) {
+      *dir = (WCHAR*)uv__malloc((i + 2) * sizeof(WCHAR));
+      if (!*dir) {
+        uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+      }
+      wcsncpy(*dir, filename, i + 1);
+      (*dir)[i + 1] = L'\0';
+    }
+
+    *file = (WCHAR*)uv__malloc((len - i) * sizeof(WCHAR));
+    if (!*file) {
+      uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+    }
+    wcsncpy(*file, filename + i + 1, len - i - 1);
+    (*file)[len - i - 1] = L'\0';
+  }
+
+  return 0;
+}
+
+
+int uv_fs_event_init(uv_loop_t* loop, uv_fs_event_t* handle) {
+  uv__handle_init(loop, (uv_handle_t*) handle, UV_FS_EVENT);
+  handle->dir_handle = INVALID_HANDLE_VALUE;
+  handle->buffer = NULL;
+  handle->req_pending = 0;
+  handle->filew = NULL;
+  handle->short_filew = NULL;
+  handle->dirw = NULL;
+
+  UV_REQ_INIT(&handle->req, UV_FS_EVENT_REQ);
+  handle->req.data = handle;
+
+  return 0;
+}
+
+
+int uv_fs_event_start(uv_fs_event_t* handle,
+                      uv_fs_event_cb cb,
+                      const char* path,
+                      unsigned int flags) {
+  int name_size, is_path_dir, size;
+  DWORD attr, last_error;
+  WCHAR* dir = NULL, *dir_to_watch, *pathw = NULL;
+  DWORD short_path_buffer_len;
+  WCHAR *short_path_buffer;
+  WCHAR* short_path, *long_path;
+
+  short_path = NULL;
+  if (uv__is_active(handle))
+    return UV_EINVAL;
+
+  handle->cb = cb;
+  handle->path = uv__strdup(path);
+  if (!handle->path) {
+    uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+  }
+
+  uv__handle_start(handle);
+
+  /* Convert name to UTF16. */
+
+  name_size = MultiByteToWideChar(CP_UTF8, 0, path, -1, NULL, 0) *
+              sizeof(WCHAR);
+  pathw = (WCHAR*)uv__malloc(name_size);
+  if (!pathw) {
+    uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+  }
+
+  if (!MultiByteToWideChar(CP_UTF8,
+                           0,
+                           path,
+                           -1,
+                           pathw,
+                           name_size / sizeof(WCHAR))) {
+    return uv_translate_sys_error(GetLastError());
+  }
+
+  /* Determine whether path is a file or a directory. */
+  attr = GetFileAttributesW(pathw);
+  if (attr == INVALID_FILE_ATTRIBUTES) {
+    last_error = GetLastError();
+    goto error;
+  }
+
+  is_path_dir = (attr & FILE_ATTRIBUTE_DIRECTORY) ? 1 : 0;
+
+  if (is_path_dir) {
+     /* path is a directory, so that's the directory that we will watch. */
+
+    /* Convert to long path. */
+    size = GetLongPathNameW(pathw, NULL, 0);
+
+    if (size) {
+      long_path = (WCHAR*)uv__malloc(size * sizeof(WCHAR));
+      if (!long_path) {
+        uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+      }
+
+      size = GetLongPathNameW(pathw, long_path, size);
+      if (size) {
+        long_path[size] = '\0';
+      } else {
+        uv__free(long_path);
+        long_path = NULL;
+      }
+
+      if (long_path) {
+        uv__free(pathw);
+        pathw = long_path;
+      }
+    }
+
+    dir_to_watch = pathw;
+  } else {
+    /*
+     * path is a file.  So we split path into dir & file parts, and
+     * watch the dir directory.
+     */
+
+    /* Convert to short path. */
+    short_path_buffer = NULL;
+    short_path_buffer_len = GetShortPathNameW(pathw, NULL, 0);
+    if (short_path_buffer_len == 0) {
+      goto short_path_done;
+    }
+    short_path_buffer = (WCHAR*)uv__malloc(short_path_buffer_len * sizeof(WCHAR));
+    if (short_path_buffer == NULL) {
+      goto short_path_done;
+    }
+    if (GetShortPathNameW(pathw,
+                          short_path_buffer,
+                          short_path_buffer_len) == 0) {
+      uv__free(short_path_buffer);
+      short_path_buffer = NULL;
+    }
+short_path_done:
+    short_path = short_path_buffer;
+
+    if (uv__split_path(pathw, &dir, &handle->filew) != 0) {
+      last_error = GetLastError();
+      goto error;
+    }
+
+    if (uv__split_path(short_path, NULL, &handle->short_filew) != 0) {
+      last_error = GetLastError();
+      goto error;
+    }
+
+    dir_to_watch = dir;
+    uv__free(pathw);
+    pathw = NULL;
+  }
+
+  handle->dir_handle = CreateFileW(dir_to_watch,
+                                   FILE_LIST_DIRECTORY,
+                                   FILE_SHARE_READ | FILE_SHARE_DELETE |
+                                     FILE_SHARE_WRITE,
+                                   NULL,
+                                   OPEN_EXISTING,
+                                   FILE_FLAG_BACKUP_SEMANTICS |
+                                     FILE_FLAG_OVERLAPPED,
+                                   NULL);
+
+  if (dir) {
+    uv__free(dir);
+    dir = NULL;
+  }
+
+  if (handle->dir_handle == INVALID_HANDLE_VALUE) {
+    last_error = GetLastError();
+    goto error;
+  }
+
+  if (CreateIoCompletionPort(handle->dir_handle,
+                             handle->loop->iocp,
+                             (ULONG_PTR)handle,
+                             0) == NULL) {
+    last_error = GetLastError();
+    goto error;
+  }
+
+  if (!handle->buffer) {
+    handle->buffer = (char*)uv__malloc(uv_directory_watcher_buffer_size);
+  }
+  if (!handle->buffer) {
+    uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+  }
+
+  memset(&(handle->req.u.io.overlapped), 0,
+         sizeof(handle->req.u.io.overlapped));
+
+  if (!ReadDirectoryChangesW(handle->dir_handle,
+                             handle->buffer,
+                             uv_directory_watcher_buffer_size,
+                             (flags & UV_FS_EVENT_RECURSIVE) ? TRUE : FALSE,
+                             FILE_NOTIFY_CHANGE_FILE_NAME      |
+                               FILE_NOTIFY_CHANGE_DIR_NAME     |
+                               FILE_NOTIFY_CHANGE_ATTRIBUTES   |
+                               FILE_NOTIFY_CHANGE_SIZE         |
+                               FILE_NOTIFY_CHANGE_LAST_WRITE   |
+                               FILE_NOTIFY_CHANGE_LAST_ACCESS  |
+                               FILE_NOTIFY_CHANGE_CREATION     |
+                               FILE_NOTIFY_CHANGE_SECURITY,
+                             NULL,
+                             &handle->req.u.io.overlapped,
+                             NULL)) {
+    last_error = GetLastError();
+    goto error;
+  }
+
+  assert(is_path_dir ? pathw != NULL : pathw == NULL);
+  handle->dirw = pathw;
+  handle->req_pending = 1;
+  return 0;
+
+error:
+  if (handle->path) {
+    uv__free(handle->path);
+    handle->path = NULL;
+  }
+
+  if (handle->filew) {
+    uv__free(handle->filew);
+    handle->filew = NULL;
+  }
+
+  if (handle->short_filew) {
+    uv__free(handle->short_filew);
+    handle->short_filew = NULL;
+  }
+
+  uv__free(pathw);
+
+  if (handle->dir_handle != INVALID_HANDLE_VALUE) {
+    CloseHandle(handle->dir_handle);
+    handle->dir_handle = INVALID_HANDLE_VALUE;
+  }
+
+  if (handle->buffer) {
+    uv__free(handle->buffer);
+    handle->buffer = NULL;
+  }
+
+  if (uv__is_active(handle))
+    uv__handle_stop(handle);
+
+  uv__free(short_path);
+
+  return uv_translate_sys_error(last_error);
+}
+
+
+int uv_fs_event_stop(uv_fs_event_t* handle) {
+  if (!uv__is_active(handle))
+    return 0;
+
+  if (handle->dir_handle != INVALID_HANDLE_VALUE) {
+    CloseHandle(handle->dir_handle);
+    handle->dir_handle = INVALID_HANDLE_VALUE;
+  }
+
+  uv__handle_stop(handle);
+
+  if (handle->filew) {
+    uv__free(handle->filew);
+    handle->filew = NULL;
+  }
+
+  if (handle->short_filew) {
+    uv__free(handle->short_filew);
+    handle->short_filew = NULL;
+  }
+
+  if (handle->path) {
+    uv__free(handle->path);
+    handle->path = NULL;
+  }
+
+  if (handle->dirw) {
+    uv__free(handle->dirw);
+    handle->dirw = NULL;
+  }
+
+  return 0;
+}
+
+
+static int file_info_cmp(WCHAR* str, WCHAR* file_name, size_t file_name_len) {
+  size_t str_len;
+
+  if (str == NULL)
+    return -1;
+
+  str_len = wcslen(str);
+
+  /*
+    Since we only care about equality, return early if the strings
+    aren't the same length
+  */
+  if (str_len != (file_name_len / sizeof(WCHAR)))
+    return -1;
+
+  return _wcsnicmp(str, file_name, str_len);
+}
+
+
+void uv__process_fs_event_req(uv_loop_t* loop, uv_req_t* req,
+    uv_fs_event_t* handle) {
+  FILE_NOTIFY_INFORMATION* file_info;
+  int err, sizew, size;
+  char* filename = NULL;
+  WCHAR* filenamew = NULL;
+  WCHAR* long_filenamew = NULL;
+  DWORD offset = 0;
+
+  assert(req->type == UV_FS_EVENT_REQ);
+  assert(handle->req_pending);
+  handle->req_pending = 0;
+
+  /* Don't report any callbacks if:
+   * - We're closing, just push the handle onto the endgame queue
+   * - We are not active, just ignore the callback
+   */
+  if (!uv__is_active(handle)) {
+    if (handle->flags & UV_HANDLE_CLOSING) {
+      uv__want_endgame(loop, (uv_handle_t*) handle);
+    }
+    return;
+  }
+
+  file_info = (FILE_NOTIFY_INFORMATION*)(handle->buffer + offset);
+
+  if (REQ_SUCCESS(req)) {
+    if (req->u.io.overlapped.InternalHigh > 0) {
+      do {
+        file_info = (FILE_NOTIFY_INFORMATION*)((char*)file_info + offset);
+        assert(!filename);
+        assert(!filenamew);
+        assert(!long_filenamew);
+
+        /*
+         * Fire the event only if we were asked to watch a directory,
+         * or if the filename filter matches.
+         */
+        if (handle->dirw ||
+            file_info_cmp(handle->filew,
+                          file_info->FileName,
+                          file_info->FileNameLength) == 0 ||
+            file_info_cmp(handle->short_filew,
+                          file_info->FileName,
+                          file_info->FileNameLength) == 0) {
+
+          if (handle->dirw) {
+            /*
+             * We attempt to resolve the long form of the file name explicitly.
+             * We only do this for file names that might still exist on disk.
+             * If this fails, we use the name given by ReadDirectoryChangesW.
+             * This may be the long form or the 8.3 short name in some cases.
+             */
+            if (file_info->Action != FILE_ACTION_REMOVED &&
+              file_info->Action != FILE_ACTION_RENAMED_OLD_NAME) {
+              /* Construct a full path to the file. */
+              size = wcslen(handle->dirw) +
+                file_info->FileNameLength / sizeof(WCHAR) + 2;
+
+              filenamew = (WCHAR*)uv__malloc(size * sizeof(WCHAR));
+              if (!filenamew) {
+                uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+              }
+
+              _snwprintf(filenamew, size, L"%s\\%.*s", handle->dirw,
+                file_info->FileNameLength / (DWORD)sizeof(WCHAR),
+                file_info->FileName);
+
+              filenamew[size - 1] = L'\0';
+
+              /* Convert to long name. */
+              size = GetLongPathNameW(filenamew, NULL, 0);
+
+              if (size) {
+                long_filenamew = (WCHAR*)uv__malloc(size * sizeof(WCHAR));
+                if (!long_filenamew) {
+                  uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+                }
+
+                size = GetLongPathNameW(filenamew, long_filenamew, size);
+                if (size) {
+                  long_filenamew[size] = '\0';
+                } else {
+                  uv__free(long_filenamew);
+                  long_filenamew = NULL;
+                }
+              }
+
+              uv__free(filenamew);
+
+              if (long_filenamew) {
+                /* Get the file name out of the long path. */
+                uv__relative_path(long_filenamew,
+                                  handle->dirw,
+                                  &filenamew);
+                uv__free(long_filenamew);
+                long_filenamew = filenamew;
+                sizew = -1;
+              } else {
+                /* We couldn't get the long filename, use the one reported. */
+                filenamew = file_info->FileName;
+                sizew = file_info->FileNameLength / sizeof(WCHAR);
+              }
+            } else {
+              /*
+               * Removed or renamed events cannot be resolved to the long form.
+               * We therefore use the name given by ReadDirectoryChangesW.
+               * This may be the long form or the 8.3 short name in some cases.
+               */
+              filenamew = file_info->FileName;
+              sizew = file_info->FileNameLength / sizeof(WCHAR);
+            }
+          } else {
+            /* We already have the long name of the file, so just use it. */
+            filenamew = handle->filew;
+            sizew = -1;
+          }
+
+          /* Convert the filename to utf8. */
+          uv__convert_utf16_to_utf8(filenamew, sizew, &filename);
+
+          switch (file_info->Action) {
+            case FILE_ACTION_ADDED:
+            case FILE_ACTION_REMOVED:
+            case FILE_ACTION_RENAMED_OLD_NAME:
+            case FILE_ACTION_RENAMED_NEW_NAME:
+              handle->cb(handle, filename, UV_RENAME, 0);
+              break;
+
+            case FILE_ACTION_MODIFIED:
+              handle->cb(handle, filename, UV_CHANGE, 0);
+              break;
+          }
+
+          uv__free(filename);
+          filename = NULL;
+          uv__free(long_filenamew);
+          long_filenamew = NULL;
+          filenamew = NULL;
+        }
+
+        offset = file_info->NextEntryOffset;
+      } while (offset && !(handle->flags & UV_HANDLE_CLOSING));
+    } else {
+      handle->cb(handle, NULL, UV_CHANGE, 0);
+    }
+  } else {
+    err = GET_REQ_ERROR(req);
+    handle->cb(handle, NULL, 0, uv_translate_sys_error(err));
+  }
+
+  if (handle->flags & UV_HANDLE_CLOSING) {
+    uv__want_endgame(loop, (uv_handle_t*)handle);
+  } else if (uv__is_active(handle)) {
+    uv__fs_event_queue_readdirchanges(loop, handle);
+  }
+}
+
+
+void uv__fs_event_close(uv_loop_t* loop, uv_fs_event_t* handle) {
+  uv_fs_event_stop(handle);
+
+  uv__handle_closing(handle);
+
+  if (!handle->req_pending) {
+    uv__want_endgame(loop, (uv_handle_t*)handle);
+  }
+
+}
+
+
+void uv__fs_event_endgame(uv_loop_t* loop, uv_fs_event_t* handle) {
+  if ((handle->flags & UV_HANDLE_CLOSING) && !handle->req_pending) {
+    assert(!(handle->flags & UV_HANDLE_CLOSED));
+
+    if (handle->buffer) {
+      uv__free(handle->buffer);
+      handle->buffer = NULL;
+    }
+
+    uv__handle_close(handle);
+  }
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/fs-fd-hash-inl.h b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/fs-fd-hash-inl.h
new file mode 100644
index 0000000..703a8d8
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/fs-fd-hash-inl.h
@@ -0,0 +1,200 @@
+/* Copyright libuv project contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#ifndef UV_WIN_FS_FD_HASH_INL_H_
+#define UV_WIN_FS_FD_HASH_INL_H_
+
+#include "uv.h"
+#include "internal.h"
+
+/* Files are only inserted in uv__fd_hash when the UV_FS_O_FILEMAP flag is
+ * specified. Thus, when uv__fd_hash_get returns true, the file mapping in the
+ * info structure should be used for read/write operations.
+ *
+ * If the file is empty, the mapping field will be set to
+ * INVALID_HANDLE_VALUE. This is not an issue since the file mapping needs to
+ * be created anyway when the file size changes.
+ *
+ * Since file descriptors are sequential integers, the modulo operator is used
+ * as hashing function. For each bucket, a single linked list of arrays is
+ * kept to minimize allocations. A statically allocated memory buffer is kept
+ * for the first array in each bucket. */
+
+
+#define UV__FD_HASH_SIZE 256
+#define UV__FD_HASH_GROUP_SIZE 16
+
+struct uv__fd_info_s {
+  int flags;
+  BOOLEAN is_directory;
+  HANDLE mapping;
+  LARGE_INTEGER size;
+  LARGE_INTEGER current_pos;
+};
+
+struct uv__fd_hash_entry_s {
+  uv_file fd;
+  struct uv__fd_info_s info;
+};
+
+struct uv__fd_hash_entry_group_s {
+  struct uv__fd_hash_entry_s entries[UV__FD_HASH_GROUP_SIZE];
+  struct uv__fd_hash_entry_group_s* next;
+};
+
+struct uv__fd_hash_bucket_s {
+  size_t size;
+  struct uv__fd_hash_entry_group_s* data;
+};
+
+
+static uv_mutex_t uv__fd_hash_mutex;
+
+static struct uv__fd_hash_entry_group_s
+  uv__fd_hash_entry_initial[UV__FD_HASH_SIZE * UV__FD_HASH_GROUP_SIZE];
+static struct uv__fd_hash_bucket_s uv__fd_hash[UV__FD_HASH_SIZE];
+
+
+INLINE static void uv__fd_hash_init(void) {
+  size_t i;
+  int err;
+
+  err = uv_mutex_init(&uv__fd_hash_mutex);
+  if (err) {
+    uv_fatal_error(err, "uv_mutex_init");
+  }
+
+  for (i = 0; i < ARRAY_SIZE(uv__fd_hash); ++i) {
+    uv__fd_hash[i].size = 0;
+    uv__fd_hash[i].data =
+        uv__fd_hash_entry_initial + i * UV__FD_HASH_GROUP_SIZE;
+  }
+}
+
+#define FIND_COMMON_VARIABLES                                                \
+  unsigned i;                                                                \
+  unsigned bucket = fd % ARRAY_SIZE(uv__fd_hash);                            \
+  struct uv__fd_hash_entry_s* entry_ptr = NULL;                              \
+  struct uv__fd_hash_entry_group_s* group_ptr;                               \
+  struct uv__fd_hash_bucket_s* bucket_ptr = &uv__fd_hash[bucket];
+
+#define FIND_IN_GROUP_PTR(group_size)                                        \
+  do {                                                                       \
+    for (i = 0; i < group_size; ++i) {                                       \
+      if (group_ptr->entries[i].fd == fd) {                                  \
+        entry_ptr = &group_ptr->entries[i];                                  \
+        break;                                                               \
+      }                                                                      \
+    }                                                                        \
+  } while (0)
+
+#define FIND_IN_BUCKET_PTR()                                                 \
+  do {                                                                       \
+    size_t first_group_size = bucket_ptr->size % UV__FD_HASH_GROUP_SIZE;     \
+    if (bucket_ptr->size != 0 && first_group_size == 0)                      \
+      first_group_size = UV__FD_HASH_GROUP_SIZE;                             \
+    group_ptr = bucket_ptr->data;                                            \
+    FIND_IN_GROUP_PTR(first_group_size);                                     \
+    for (group_ptr = group_ptr->next;                                        \
+         group_ptr != NULL && entry_ptr == NULL;                             \
+         group_ptr = group_ptr->next)                                        \
+      FIND_IN_GROUP_PTR(UV__FD_HASH_GROUP_SIZE);                             \
+  } while (0)
+
+INLINE static int uv__fd_hash_get(int fd, struct uv__fd_info_s* info) {
+  FIND_COMMON_VARIABLES
+
+  uv_mutex_lock(&uv__fd_hash_mutex);
+
+  FIND_IN_BUCKET_PTR();
+
+  if (entry_ptr != NULL) {
+    *info = entry_ptr->info;
+  }
+
+  uv_mutex_unlock(&uv__fd_hash_mutex);
+  return entry_ptr != NULL;
+}
+
+INLINE static void uv__fd_hash_add(int fd, struct uv__fd_info_s* info) {
+  FIND_COMMON_VARIABLES
+
+  uv_mutex_lock(&uv__fd_hash_mutex);
+
+  FIND_IN_BUCKET_PTR();
+
+  if (entry_ptr == NULL) {
+    i = bucket_ptr->size % UV__FD_HASH_GROUP_SIZE;
+
+    if (bucket_ptr->size != 0 && i == 0) {
+      struct uv__fd_hash_entry_group_s* new_group_ptr =
+        (struct uv__fd_hash_entry_group_s*)uv__malloc(sizeof(*new_group_ptr));
+      if (new_group_ptr == NULL) {
+        uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+      }
+      new_group_ptr->next = bucket_ptr->data;
+      bucket_ptr->data = new_group_ptr;
+    }
+
+    bucket_ptr->size += 1;
+    entry_ptr = &bucket_ptr->data->entries[i];
+    entry_ptr->fd = fd;
+  }
+
+  entry_ptr->info = *info;
+
+  uv_mutex_unlock(&uv__fd_hash_mutex);
+}
+
+INLINE static int uv__fd_hash_remove(int fd, struct uv__fd_info_s* info) {
+  FIND_COMMON_VARIABLES
+
+  uv_mutex_lock(&uv__fd_hash_mutex);
+
+  FIND_IN_BUCKET_PTR();
+
+  if (entry_ptr != NULL) {
+    *info = entry_ptr->info;
+
+    bucket_ptr->size -= 1;
+
+    i = bucket_ptr->size % UV__FD_HASH_GROUP_SIZE;
+    if (entry_ptr != &bucket_ptr->data->entries[i]) {
+      *entry_ptr = bucket_ptr->data->entries[i];
+    }
+
+    if (bucket_ptr->size != 0 &&
+        bucket_ptr->size % UV__FD_HASH_GROUP_SIZE == 0) {
+      struct uv__fd_hash_entry_group_s* old_group_ptr = bucket_ptr->data;
+      bucket_ptr->data = old_group_ptr->next;
+      uv__free(old_group_ptr);
+    }
+  }
+
+  uv_mutex_unlock(&uv__fd_hash_mutex);
+  return entry_ptr != NULL;
+}
+
+#undef FIND_COMMON_VARIABLES
+#undef FIND_IN_GROUP_PTR
+#undef FIND_IN_BUCKET_PTR
+
+#endif /* UV_WIN_FS_FD_HASH_INL_H_ */
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/fs.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/fs.cpp
new file mode 100644
index 0000000..71c9b16
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/fs.cpp
@@ -0,0 +1,3442 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#define _CRT_NONSTDC_NO_WARNINGS
+
+#include <assert.h>
+#include <stdlib.h>
+#include <direct.h>
+#include <errno.h>
+#include <fcntl.h>
+#include <io.h>
+#include <limits.h>
+#include <sys/stat.h>
+#include <sys/utime.h>
+#include <stdio.h>
+
+#include "uv.h"
+#include "internal.h"
+#include "req-inl.h"
+#include "handle-inl.h"
+#include "fs-fd-hash-inl.h"
+
+#pragma comment(lib, "Advapi32.lib")
+
+#define UV_FS_FREE_PATHS         0x0002
+#define UV_FS_FREE_PTR           0x0008
+#define UV_FS_CLEANEDUP          0x0010
+
+
+#define INIT(subtype)                                                         \
+  do {                                                                        \
+    if (req == NULL)                                                          \
+      return UV_EINVAL;                                                       \
+    uv__fs_req_init(loop, req, subtype, cb);                                  \
+  }                                                                           \
+  while (0)
+
+#define POST                                                                  \
+  do {                                                                        \
+    if (cb != NULL) {                                                         \
+      uv__req_register(loop, req);                                            \
+      uv__work_submit(loop,                                                   \
+                      &req->work_req,                                         \
+                      UV__WORK_FAST_IO,                                       \
+                      uv__fs_work,                                            \
+                      uv__fs_done);                                           \
+      return 0;                                                               \
+    } else {                                                                  \
+      uv__fs_work(&req->work_req);                                            \
+      return req->result;                                                     \
+    }                                                                         \
+  }                                                                           \
+  while (0)
+
+#define SET_REQ_RESULT(req, result_value)                                   \
+  do {                                                                      \
+    req->result = (result_value);                                           \
+    assert(req->result != -1);                                              \
+  } while (0)
+
+#define SET_REQ_WIN32_ERROR(req, sys_errno)                                 \
+  do {                                                                      \
+    req->sys_errno_ = (sys_errno);                                          \
+    req->result = uv_translate_sys_error(req->sys_errno_);                  \
+  } while (0)
+
+#define SET_REQ_UV_ERROR(req, uv_errno, sys_errno)                          \
+  do {                                                                      \
+    req->result = (uv_errno);                                               \
+    req->sys_errno_ = (sys_errno);                                          \
+  } while (0)
+
+#define VERIFY_FD(fd, req)                                                  \
+  if (fd == -1) {                                                           \
+    req->result = UV_EBADF;                                                 \
+    req->sys_errno_ = ERROR_INVALID_HANDLE;                                 \
+    return;                                                                 \
+  }
+
+#define MILLION ((int64_t) 1000 * 1000)
+#define BILLION ((int64_t) 1000 * 1000 * 1000)
+
+static void uv__filetime_to_timespec(uv_timespec_t *ts, int64_t filetime) {
+  filetime -= 116444736 * BILLION;
+  ts->tv_sec = (long) (filetime / (10 * MILLION));
+  ts->tv_nsec = (long) ((filetime - ts->tv_sec * 10 * MILLION) * 100U);
+  if (ts->tv_nsec < 0) {
+    ts->tv_sec -= 1;
+    ts->tv_nsec += 1e9;
+  }
+}
+
+#define TIME_T_TO_FILETIME(time, filetime_ptr)                              \
+  do {                                                                      \
+    int64_t bigtime = ((time) * 10 * MILLION + 116444736 * BILLION);        \
+    (filetime_ptr)->dwLowDateTime = (uint64_t) bigtime & 0xFFFFFFFF;        \
+    (filetime_ptr)->dwHighDateTime = (uint64_t) bigtime >> 32;              \
+  } while(0)
+
+#define IS_SLASH(c) ((c) == L'\\' || (c) == L'/')
+#define IS_LETTER(c) (((c) >= L'a' && (c) <= L'z') || \
+  ((c) >= L'A' && (c) <= L'Z'))
+
+#define MIN(a,b) (((a) < (b)) ? (a) : (b))
+
+const WCHAR JUNCTION_PREFIX[] = L"\\??\\";
+const WCHAR JUNCTION_PREFIX_LEN = 4;
+
+const WCHAR LONG_PATH_PREFIX[] = L"\\\\?\\";
+const WCHAR LONG_PATH_PREFIX_LEN = 4;
+
+const WCHAR UNC_PATH_PREFIX[] = L"\\\\?\\UNC\\";
+const WCHAR UNC_PATH_PREFIX_LEN = 8;
+
+static int uv__file_symlink_usermode_flag = SYMBOLIC_LINK_FLAG_ALLOW_UNPRIVILEGED_CREATE;
+
+static DWORD uv__allocation_granularity;
+
+
+void uv__fs_init(void) {
+  SYSTEM_INFO system_info;
+
+  GetSystemInfo(&system_info);
+  uv__allocation_granularity = system_info.dwAllocationGranularity;
+
+  uv__fd_hash_init();
+}
+
+
+INLINE static int fs__capture_path(uv_fs_t* req, const char* path,
+    const char* new_path, const int copy_path) {
+  char* buf;
+  char* pos;
+  ssize_t buf_sz = 0, path_len = 0, pathw_len = 0, new_pathw_len = 0;
+
+  /* new_path can only be set if path is also set. */
+  assert(new_path == NULL || path != NULL);
+
+  if (path != NULL) {
+    pathw_len = MultiByteToWideChar(CP_UTF8,
+                                    0,
+                                    path,
+                                    -1,
+                                    NULL,
+                                    0);
+    if (pathw_len == 0) {
+      return GetLastError();
+    }
+
+    buf_sz += pathw_len * sizeof(WCHAR);
+  }
+
+  if (path != NULL && copy_path) {
+    path_len = 1 + strlen(path);
+    buf_sz += path_len;
+  }
+
+  if (new_path != NULL) {
+    new_pathw_len = MultiByteToWideChar(CP_UTF8,
+                                        0,
+                                        new_path,
+                                        -1,
+                                        NULL,
+                                        0);
+    if (new_pathw_len == 0) {
+      return GetLastError();
+    }
+
+    buf_sz += new_pathw_len * sizeof(WCHAR);
+  }
+
+
+  if (buf_sz == 0) {
+    req->file.pathw = NULL;
+    req->fs.info.new_pathw = NULL;
+    req->path = NULL;
+    return 0;
+  }
+
+  buf = (char*) uv__malloc(buf_sz);
+  if (buf == NULL) {
+    return ERROR_OUTOFMEMORY;
+  }
+
+  pos = buf;
+
+  if (path != NULL) {
+    DWORD r = MultiByteToWideChar(CP_UTF8,
+                                  0,
+                                  path,
+                                  -1,
+                                  (WCHAR*) pos,
+                                  pathw_len);
+    assert(r == (DWORD) pathw_len);
+    req->file.pathw = (WCHAR*) pos;
+    pos += r * sizeof(WCHAR);
+  } else {
+    req->file.pathw = NULL;
+  }
+
+  if (new_path != NULL) {
+    DWORD r = MultiByteToWideChar(CP_UTF8,
+                                  0,
+                                  new_path,
+                                  -1,
+                                  (WCHAR*) pos,
+                                  new_pathw_len);
+    assert(r == (DWORD) new_pathw_len);
+    req->fs.info.new_pathw = (WCHAR*) pos;
+    pos += r * sizeof(WCHAR);
+  } else {
+    req->fs.info.new_pathw = NULL;
+  }
+
+  req->path = path;
+  if (path != NULL && copy_path) {
+    memcpy(pos, path, path_len);
+    assert(path_len == buf_sz - (pos - buf));
+    req->path = pos;
+  }
+
+  req->flags |= UV_FS_FREE_PATHS;
+
+  return 0;
+}
+
+
+
+INLINE static void uv__fs_req_init(uv_loop_t* loop, uv_fs_t* req,
+    uv_fs_type fs_type, const uv_fs_cb cb) {
+  uv__once_init();
+  UV_REQ_INIT(req, UV_FS);
+  req->loop = loop;
+  req->flags = 0;
+  req->fs_type = fs_type;
+  req->sys_errno_ = 0;
+  req->result = 0;
+  req->ptr = NULL;
+  req->path = NULL;
+  req->cb = cb;
+  memset(&req->fs, 0, sizeof(req->fs));
+}
+
+
+static int fs__wide_to_utf8(WCHAR* w_source_ptr,
+                               DWORD w_source_len,
+                               char** target_ptr,
+                               uint64_t* target_len_ptr) {
+  int r;
+  int target_len;
+  char* target;
+  target_len = WideCharToMultiByte(CP_UTF8,
+                                   0,
+                                   w_source_ptr,
+                                   w_source_len,
+                                   NULL,
+                                   0,
+                                   NULL,
+                                   NULL);
+
+  if (target_len == 0) {
+    return -1;
+  }
+
+  if (target_len_ptr != NULL) {
+    *target_len_ptr = target_len;
+  }
+
+  if (target_ptr == NULL) {
+    return 0;
+  }
+
+  target = (char*)uv__malloc(target_len + 1);
+  if (target == NULL) {
+    SetLastError(ERROR_OUTOFMEMORY);
+    return -1;
+  }
+
+  r = WideCharToMultiByte(CP_UTF8,
+                          0,
+                          w_source_ptr,
+                          w_source_len,
+                          target,
+                          target_len,
+                          NULL,
+                          NULL);
+  assert(r == target_len);
+  target[target_len] = '\0';
+  *target_ptr = target;
+  return 0;
+}
+
+
+INLINE static int fs__readlink_handle(HANDLE handle, char** target_ptr,
+    uint64_t* target_len_ptr) {
+  char buffer[MAXIMUM_REPARSE_DATA_BUFFER_SIZE];
+  REPARSE_DATA_BUFFER* reparse_data = (REPARSE_DATA_BUFFER*) buffer;
+  WCHAR* w_target;
+  DWORD w_target_len;
+  DWORD bytes;
+  size_t i;
+  size_t len;
+
+  if (!DeviceIoControl(handle,
+                       FSCTL_GET_REPARSE_POINT,
+                       NULL,
+                       0,
+                       buffer,
+                       sizeof buffer,
+                       &bytes,
+                       NULL)) {
+    return -1;
+  }
+
+  if (reparse_data->ReparseTag == IO_REPARSE_TAG_SYMLINK) {
+    /* Real symlink */
+    w_target = reparse_data->SymbolicLinkReparseBuffer.PathBuffer +
+        (reparse_data->SymbolicLinkReparseBuffer.SubstituteNameOffset /
+        sizeof(WCHAR));
+    w_target_len =
+        reparse_data->SymbolicLinkReparseBuffer.SubstituteNameLength /
+        sizeof(WCHAR);
+
+    /* Real symlinks can contain pretty much everything, but the only thing we
+     * really care about is undoing the implicit conversion to an NT namespaced
+     * path that CreateSymbolicLink will perform on absolute paths. If the path
+     * is win32-namespaced then the user must have explicitly made it so, and
+     * we better just return the unmodified reparse data. */
+    if (w_target_len >= 4 &&
+        w_target[0] == L'\\' &&
+        w_target[1] == L'?' &&
+        w_target[2] == L'?' &&
+        w_target[3] == L'\\') {
+      /* Starts with \??\ */
+      if (w_target_len >= 6 &&
+          ((w_target[4] >= L'A' && w_target[4] <= L'Z') ||
+           (w_target[4] >= L'a' && w_target[4] <= L'z')) &&
+          w_target[5] == L':' &&
+          (w_target_len == 6 || w_target[6] == L'\\')) {
+        /* \??\<drive>:\ */
+        w_target += 4;
+        w_target_len -= 4;
+
+      } else if (w_target_len >= 8 &&
+                 (w_target[4] == L'U' || w_target[4] == L'u') &&
+                 (w_target[5] == L'N' || w_target[5] == L'n') &&
+                 (w_target[6] == L'C' || w_target[6] == L'c') &&
+                 w_target[7] == L'\\') {
+        /* \??\UNC\<server>\<share>\ - make sure the final path looks like
+         * \\<server>\<share>\ */
+        w_target += 6;
+        w_target[0] = L'\\';
+        w_target_len -= 6;
+      }
+    }
+
+  } else if (reparse_data->ReparseTag == IO_REPARSE_TAG_MOUNT_POINT) {
+    /* Junction. */
+    w_target = reparse_data->MountPointReparseBuffer.PathBuffer +
+        (reparse_data->MountPointReparseBuffer.SubstituteNameOffset /
+        sizeof(WCHAR));
+    w_target_len = reparse_data->MountPointReparseBuffer.SubstituteNameLength /
+        sizeof(WCHAR);
+
+    /* Only treat junctions that look like \??\<drive>:\ as symlink. Junctions
+     * can also be used as mount points, like \??\Volume{<guid>}, but that's
+     * confusing for programs since they wouldn't be able to actually
+     * understand such a path when returned by uv_readlink(). UNC paths are
+     * never valid for junctions so we don't care about them. */
+    if (!(w_target_len >= 6 &&
+          w_target[0] == L'\\' &&
+          w_target[1] == L'?' &&
+          w_target[2] == L'?' &&
+          w_target[3] == L'\\' &&
+          ((w_target[4] >= L'A' && w_target[4] <= L'Z') ||
+           (w_target[4] >= L'a' && w_target[4] <= L'z')) &&
+          w_target[5] == L':' &&
+          (w_target_len == 6 || w_target[6] == L'\\'))) {
+      SetLastError(ERROR_SYMLINK_NOT_SUPPORTED);
+      return -1;
+    }
+
+    /* Remove leading \??\ */
+    w_target += 4;
+    w_target_len -= 4;
+
+  } else if (reparse_data->ReparseTag == IO_REPARSE_TAG_APPEXECLINK) {
+    /* String #3 in the list has the target filename. */
+    if (reparse_data->AppExecLinkReparseBuffer.StringCount < 3) {
+      SetLastError(ERROR_SYMLINK_NOT_SUPPORTED);
+      return -1;
+    }
+    w_target = reparse_data->AppExecLinkReparseBuffer.StringList;
+    /* The StringList buffer contains a list of strings separated by "\0",   */
+    /* with "\0\0" terminating the list. Move to the 3rd string in the list: */
+    for (i = 0; i < 2; ++i) {
+      len = wcslen(w_target);
+      if (len == 0) {
+        SetLastError(ERROR_SYMLINK_NOT_SUPPORTED);
+        return -1;
+      }
+      w_target += len + 1;
+    }
+    w_target_len = wcslen(w_target);
+    if (w_target_len == 0) {
+      SetLastError(ERROR_SYMLINK_NOT_SUPPORTED);
+      return -1;
+    }
+    /* Make sure it is an absolute path. */
+    if (!(w_target_len >= 3 &&
+         ((w_target[0] >= L'a' && w_target[0] <= L'z') ||
+          (w_target[0] >= L'A' && w_target[0] <= L'Z')) &&
+         w_target[1] == L':' &&
+         w_target[2] == L'\\')) {
+      SetLastError(ERROR_SYMLINK_NOT_SUPPORTED);
+      return -1;
+    }
+
+  } else {
+    /* Reparse tag does not indicate a symlink. */
+    SetLastError(ERROR_SYMLINK_NOT_SUPPORTED);
+    return -1;
+  }
+
+  return fs__wide_to_utf8(w_target, w_target_len, target_ptr, target_len_ptr);
+}
+
+
+void fs__open(uv_fs_t* req) {
+  DWORD access;
+  DWORD share;
+  DWORD disposition;
+  DWORD attributes = 0;
+  HANDLE file;
+  int fd, current_umask;
+  int flags = req->fs.info.file_flags;
+  struct uv__fd_info_s fd_info;
+
+  /* Adjust flags to be compatible with the memory file mapping. Save the
+   * original flags to emulate the correct behavior. */
+  if (flags & UV_FS_O_FILEMAP) {
+    fd_info.flags = flags;
+    fd_info.current_pos.QuadPart = 0;
+
+    if ((flags & (UV_FS_O_RDONLY | UV_FS_O_WRONLY | UV_FS_O_RDWR)) ==
+        UV_FS_O_WRONLY) {
+      /* CreateFileMapping always needs read access */
+      flags = (flags & ~UV_FS_O_WRONLY) | UV_FS_O_RDWR;
+    }
+
+    if (flags & UV_FS_O_APPEND) {
+      /* Clear the append flag and ensure RDRW mode */
+      flags &= ~UV_FS_O_APPEND;
+      flags &= ~(UV_FS_O_RDONLY | UV_FS_O_WRONLY | UV_FS_O_RDWR);
+      flags |= UV_FS_O_RDWR;
+    }
+  }
+
+  /* Obtain the active umask. umask() never fails and returns the previous
+   * umask. */
+  current_umask = umask(0);
+  umask(current_umask);
+
+  /* convert flags and mode to CreateFile parameters */
+  switch (flags & (UV_FS_O_RDONLY | UV_FS_O_WRONLY | UV_FS_O_RDWR)) {
+  case UV_FS_O_RDONLY:
+    access = FILE_GENERIC_READ;
+    break;
+  case UV_FS_O_WRONLY:
+    access = FILE_GENERIC_WRITE;
+    break;
+  case UV_FS_O_RDWR:
+    access = FILE_GENERIC_READ | FILE_GENERIC_WRITE;
+    break;
+  default:
+    goto einval;
+  }
+
+  if (flags & UV_FS_O_APPEND) {
+    access &= ~FILE_WRITE_DATA;
+    access |= FILE_APPEND_DATA;
+  }
+
+  /*
+   * Here is where we deviate significantly from what CRT's _open()
+   * does. We indiscriminately use all the sharing modes, to match
+   * UNIX semantics. In particular, this ensures that the file can
+   * be deleted even whilst it's open, fixing issue
+   * https://github.com/nodejs/node-v0.x-archive/issues/1449.
+   * We still support exclusive sharing mode, since it is necessary
+   * for opening raw block devices, otherwise Windows will prevent
+   * any attempt to write past the master boot record.
+   */
+  if (flags & UV_FS_O_EXLOCK) {
+    share = 0;
+  } else {
+    share = FILE_SHARE_READ | FILE_SHARE_WRITE | FILE_SHARE_DELETE;
+  }
+
+  switch (flags & (UV_FS_O_CREAT | UV_FS_O_EXCL | UV_FS_O_TRUNC)) {
+  case 0:
+  case UV_FS_O_EXCL:
+    disposition = OPEN_EXISTING;
+    break;
+  case UV_FS_O_CREAT:
+    disposition = OPEN_ALWAYS;
+    break;
+  case UV_FS_O_CREAT | UV_FS_O_EXCL:
+  case UV_FS_O_CREAT | UV_FS_O_TRUNC | UV_FS_O_EXCL:
+    disposition = CREATE_NEW;
+    break;
+  case UV_FS_O_TRUNC:
+  case UV_FS_O_TRUNC | UV_FS_O_EXCL:
+    disposition = TRUNCATE_EXISTING;
+    break;
+  case UV_FS_O_CREAT | UV_FS_O_TRUNC:
+    disposition = CREATE_ALWAYS;
+    break;
+  default:
+    goto einval;
+  }
+
+  attributes |= FILE_ATTRIBUTE_NORMAL;
+  if (flags & UV_FS_O_CREAT) {
+    if (!((req->fs.info.mode & ~current_umask) & _S_IWRITE)) {
+      attributes |= FILE_ATTRIBUTE_READONLY;
+    }
+  }
+
+  if (flags & UV_FS_O_TEMPORARY ) {
+    attributes |= FILE_FLAG_DELETE_ON_CLOSE | FILE_ATTRIBUTE_TEMPORARY;
+    access |= DELETE;
+  }
+
+  if (flags & UV_FS_O_SHORT_LIVED) {
+    attributes |= FILE_ATTRIBUTE_TEMPORARY;
+  }
+
+  switch (flags & (UV_FS_O_SEQUENTIAL | UV_FS_O_RANDOM)) {
+  case 0:
+    break;
+  case UV_FS_O_SEQUENTIAL:
+    attributes |= FILE_FLAG_SEQUENTIAL_SCAN;
+    break;
+  case UV_FS_O_RANDOM:
+    attributes |= FILE_FLAG_RANDOM_ACCESS;
+    break;
+  default:
+    goto einval;
+  }
+
+  if (flags & UV_FS_O_DIRECT) {
+    /*
+     * FILE_APPEND_DATA and FILE_FLAG_NO_BUFFERING are mutually exclusive.
+     * Windows returns 87, ERROR_INVALID_PARAMETER if these are combined.
+     *
+     * FILE_APPEND_DATA is included in FILE_GENERIC_WRITE:
+     *
+     * FILE_GENERIC_WRITE = STANDARD_RIGHTS_WRITE |
+     *                      FILE_WRITE_DATA |
+     *                      FILE_WRITE_ATTRIBUTES |
+     *                      FILE_WRITE_EA |
+     *                      FILE_APPEND_DATA |
+     *                      SYNCHRONIZE
+     *
+     * Note: Appends are also permitted by FILE_WRITE_DATA.
+     *
+     * In order for direct writes and direct appends to succeed, we therefore
+     * exclude FILE_APPEND_DATA if FILE_WRITE_DATA is specified, and otherwise
+     * fail if the user's sole permission is a direct append, since this
+     * particular combination is invalid.
+     */
+    if (access & FILE_APPEND_DATA) {
+      if (access & FILE_WRITE_DATA) {
+        access &= ~FILE_APPEND_DATA;
+      } else {
+        goto einval;
+      }
+    }
+    attributes |= FILE_FLAG_NO_BUFFERING;
+  }
+
+  switch (flags & (UV_FS_O_DSYNC | UV_FS_O_SYNC)) {
+  case 0:
+    break;
+  case UV_FS_O_DSYNC:
+  case UV_FS_O_SYNC:
+    attributes |= FILE_FLAG_WRITE_THROUGH;
+    break;
+  default:
+    goto einval;
+  }
+
+  /* Setting this flag makes it possible to open a directory. */
+  attributes |= FILE_FLAG_BACKUP_SEMANTICS;
+
+  file = CreateFileW(req->file.pathw,
+                     access,
+                     share,
+                     NULL,
+                     disposition,
+                     attributes,
+                     NULL);
+  if (file == INVALID_HANDLE_VALUE) {
+    DWORD error = GetLastError();
+    if (error == ERROR_FILE_EXISTS && (flags & UV_FS_O_CREAT) &&
+        !(flags & UV_FS_O_EXCL)) {
+      /* Special case: when ERROR_FILE_EXISTS happens and UV_FS_O_CREAT was
+       * specified, it means the path referred to a directory. */
+      SET_REQ_UV_ERROR(req, UV_EISDIR, error);
+    } else {
+      SET_REQ_WIN32_ERROR(req, GetLastError());
+    }
+    return;
+  }
+
+  fd = _open_osfhandle((intptr_t) file, flags);
+  if (fd < 0) {
+    /* The only known failure mode for _open_osfhandle() is EMFILE, in which
+     * case GetLastError() will return zero. However we'll try to handle other
+     * errors as well, should they ever occur.
+     */
+    if (errno == EMFILE)
+      SET_REQ_UV_ERROR(req, UV_EMFILE, ERROR_TOO_MANY_OPEN_FILES);
+    else if (GetLastError() != ERROR_SUCCESS)
+      SET_REQ_WIN32_ERROR(req, GetLastError());
+    else
+      SET_REQ_WIN32_ERROR(req, (DWORD) UV_UNKNOWN);
+    CloseHandle(file);
+    return;
+  }
+
+  if (flags & UV_FS_O_FILEMAP) {
+    FILE_STANDARD_INFO file_info;
+    if (!GetFileInformationByHandleEx(file,
+                                      FileStandardInfo,
+                                      &file_info,
+                                      sizeof file_info)) {
+      SET_REQ_WIN32_ERROR(req, GetLastError());
+      CloseHandle(file);
+      return;
+    }
+    fd_info.is_directory = file_info.Directory;
+
+    if (fd_info.is_directory) {
+      fd_info.size.QuadPart = 0;
+      fd_info.mapping = INVALID_HANDLE_VALUE;
+    } else {
+      if (!GetFileSizeEx(file, &fd_info.size)) {
+        SET_REQ_WIN32_ERROR(req, GetLastError());
+        CloseHandle(file);
+        return;
+      }
+
+      if (fd_info.size.QuadPart == 0) {
+        fd_info.mapping = INVALID_HANDLE_VALUE;
+      } else {
+        DWORD flProtect = (fd_info.flags & (UV_FS_O_RDONLY | UV_FS_O_WRONLY |
+          UV_FS_O_RDWR)) == UV_FS_O_RDONLY ? PAGE_READONLY : PAGE_READWRITE;
+        fd_info.mapping = CreateFileMapping(file,
+                                            NULL,
+                                            flProtect,
+                                            fd_info.size.HighPart,
+                                            fd_info.size.LowPart,
+                                            NULL);
+        if (fd_info.mapping == NULL) {
+          SET_REQ_WIN32_ERROR(req, GetLastError());
+          CloseHandle(file);
+          return;
+        }
+      }
+    }
+
+    uv__fd_hash_add(fd, &fd_info);
+  }
+
+  SET_REQ_RESULT(req, fd);
+  return;
+
+ einval:
+  SET_REQ_UV_ERROR(req, UV_EINVAL, ERROR_INVALID_PARAMETER);
+}
+
+void fs__close(uv_fs_t* req) {
+  int fd = req->file.fd;
+  int result;
+  struct uv__fd_info_s fd_info;
+
+  VERIFY_FD(fd, req);
+
+  if (uv__fd_hash_remove(fd, &fd_info)) {
+    if (fd_info.mapping != INVALID_HANDLE_VALUE) {
+      CloseHandle(fd_info.mapping);
+    }
+  }
+
+  if (fd > 2)
+    result = _close(fd);
+  else
+    result = 0;
+
+  /* _close doesn't set _doserrno on failure, but it does always set errno
+   * to EBADF on failure.
+   */
+  if (result == -1) {
+    assert(errno == EBADF);
+    SET_REQ_UV_ERROR(req, UV_EBADF, ERROR_INVALID_HANDLE);
+  } else {
+    SET_REQ_RESULT(req, 0);
+  }
+}
+
+
+LONG fs__filemap_ex_filter(LONG excode, PEXCEPTION_POINTERS pep,
+                           int* perror) {
+  if (excode != (LONG)EXCEPTION_IN_PAGE_ERROR) {
+    return EXCEPTION_CONTINUE_SEARCH;
+  }
+
+  assert(perror != NULL);
+  if (pep != NULL && pep->ExceptionRecord != NULL &&
+      pep->ExceptionRecord->NumberParameters >= 3) {
+    NTSTATUS status = (NTSTATUS)pep->ExceptionRecord->ExceptionInformation[3];
+    *perror = pRtlNtStatusToDosError(status);
+    if (*perror != ERROR_SUCCESS) {
+      return EXCEPTION_EXECUTE_HANDLER;
+    }
+  }
+  *perror = UV_UNKNOWN;
+  return EXCEPTION_EXECUTE_HANDLER;
+}
+
+
+void fs__read_filemap(uv_fs_t* req, struct uv__fd_info_s* fd_info) {
+  int fd = req->file.fd; /* VERIFY_FD done in fs__read */
+  int rw_flags = fd_info->flags &
+    (UV_FS_O_RDONLY | UV_FS_O_WRONLY | UV_FS_O_RDWR);
+  size_t read_size, done_read;
+  unsigned int index;
+  LARGE_INTEGER pos, end_pos;
+  size_t view_offset;
+  LARGE_INTEGER view_base;
+  void* view;
+
+  if (rw_flags == UV_FS_O_WRONLY) {
+    SET_REQ_WIN32_ERROR(req, ERROR_INVALID_FLAGS);
+    return;
+  }
+  if (fd_info->is_directory) {
+    SET_REQ_WIN32_ERROR(req, ERROR_INVALID_FUNCTION);
+    return;
+  }
+
+  if (req->fs.info.offset == -1) {
+    pos = fd_info->current_pos;
+  } else {
+    pos.QuadPart = req->fs.info.offset;
+  }
+
+  /* Make sure we wont read past EOF. */
+  if (pos.QuadPart >= fd_info->size.QuadPart) {
+    SET_REQ_RESULT(req, 0);
+    return;
+  }
+
+  read_size = 0;
+  for (index = 0; index < req->fs.info.nbufs; ++index) {
+    read_size += req->fs.info.bufs[index].len;
+  }
+  read_size = (size_t) MIN((LONGLONG) read_size,
+                           fd_info->size.QuadPart - pos.QuadPart);
+  if (read_size == 0) {
+    SET_REQ_RESULT(req, 0);
+    return;
+  }
+
+  end_pos.QuadPart = pos.QuadPart + read_size;
+
+  view_offset = pos.QuadPart % uv__allocation_granularity;
+  view_base.QuadPart = pos.QuadPart - view_offset;
+  view = MapViewOfFile(fd_info->mapping,
+                       FILE_MAP_READ,
+                       view_base.HighPart,
+                       view_base.LowPart,
+                       view_offset + read_size);
+  if (view == NULL) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    return;
+  }
+
+  done_read = 0;
+  for (index = 0;
+       index < req->fs.info.nbufs && done_read < read_size;
+       ++index) {
+    size_t this_read_size = MIN(req->fs.info.bufs[index].len,
+                                read_size - done_read);
+#ifdef _MSC_VER
+    int err = 0;
+    __try {
+#endif
+      memcpy(req->fs.info.bufs[index].base,
+             (char*)view + view_offset + done_read,
+             this_read_size);
+#ifdef _MSC_VER
+    }
+    __except (fs__filemap_ex_filter(GetExceptionCode(),
+                                    GetExceptionInformation(), &err)) {
+      SET_REQ_WIN32_ERROR(req, err);
+      UnmapViewOfFile(view);
+      return;
+    }
+#endif
+    done_read += this_read_size;
+  }
+  assert(done_read == read_size);
+
+  if (!UnmapViewOfFile(view)) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    return;
+  }
+
+  if (req->fs.info.offset == -1) {
+    fd_info->current_pos = end_pos;
+    uv__fd_hash_add(fd, fd_info);
+  }
+
+  SET_REQ_RESULT(req, read_size);
+  return;
+}
+
+void fs__read(uv_fs_t* req) {
+  int fd = req->file.fd;
+  int64_t offset = req->fs.info.offset;
+  HANDLE handle;
+  OVERLAPPED overlapped, *overlapped_ptr;
+  LARGE_INTEGER offset_;
+  DWORD bytes;
+  DWORD error;
+  int result;
+  unsigned int index;
+  LARGE_INTEGER original_position;
+  LARGE_INTEGER zero_offset;
+  int restore_position;
+  struct uv__fd_info_s fd_info;
+
+  VERIFY_FD(fd, req);
+
+  if (uv__fd_hash_get(fd, &fd_info)) {
+    fs__read_filemap(req, &fd_info);
+    return;
+  }
+
+  zero_offset.QuadPart = 0;
+  restore_position = 0;
+  handle = uv__get_osfhandle(fd);
+
+  if (handle == INVALID_HANDLE_VALUE) {
+    SET_REQ_WIN32_ERROR(req, ERROR_INVALID_HANDLE);
+    return;
+  }
+
+  if (offset != -1) {
+    memset(&overlapped, 0, sizeof overlapped);
+    overlapped_ptr = &overlapped;
+    if (SetFilePointerEx(handle, zero_offset, &original_position,
+                         FILE_CURRENT)) {
+      restore_position = 1;
+    }
+  } else {
+    overlapped_ptr = NULL;
+  }
+
+  index = 0;
+  bytes = 0;
+  do {
+    DWORD incremental_bytes;
+
+    if (offset != -1) {
+      offset_.QuadPart = offset + bytes;
+      overlapped.Offset = offset_.LowPart;
+      overlapped.OffsetHigh = offset_.HighPart;
+    }
+
+    result = ReadFile(handle,
+                      req->fs.info.bufs[index].base,
+                      req->fs.info.bufs[index].len,
+                      &incremental_bytes,
+                      overlapped_ptr);
+    bytes += incremental_bytes;
+    ++index;
+  } while (result && index < req->fs.info.nbufs);
+
+  if (restore_position)
+    SetFilePointerEx(handle, original_position, NULL, FILE_BEGIN);
+
+  if (result || bytes > 0) {
+    SET_REQ_RESULT(req, bytes);
+  } else {
+    error = GetLastError();
+    if (error == ERROR_ACCESS_DENIED) {
+      error = ERROR_INVALID_FLAGS;
+    }
+
+    if (error == ERROR_HANDLE_EOF || error == ERROR_BROKEN_PIPE) {
+      SET_REQ_RESULT(req, bytes);
+    } else {
+      SET_REQ_WIN32_ERROR(req, error);
+    }
+  }
+}
+
+
+void fs__write_filemap(uv_fs_t* req, HANDLE file,
+                       struct uv__fd_info_s* fd_info) {
+  int fd = req->file.fd; /* VERIFY_FD done in fs__write */
+  int force_append = fd_info->flags & UV_FS_O_APPEND;
+  int rw_flags = fd_info->flags &
+    (UV_FS_O_RDONLY | UV_FS_O_WRONLY | UV_FS_O_RDWR);
+  size_t write_size, done_write;
+  unsigned int index;
+  LARGE_INTEGER pos, end_pos;
+  size_t view_offset;
+  LARGE_INTEGER view_base;
+  void* view;
+  FILETIME ft;
+
+  if (rw_flags == UV_FS_O_RDONLY) {
+    SET_REQ_WIN32_ERROR(req, ERROR_INVALID_FLAGS);
+    return;
+  }
+  if (fd_info->is_directory) {
+    SET_REQ_WIN32_ERROR(req, ERROR_INVALID_FUNCTION);
+    return;
+  }
+
+  write_size = 0;
+  for (index = 0; index < req->fs.info.nbufs; ++index) {
+    write_size += req->fs.info.bufs[index].len;
+  }
+
+  if (write_size == 0) {
+    SET_REQ_RESULT(req, 0);
+    return;
+  }
+
+  if (force_append) {
+    pos = fd_info->size;
+  } else if (req->fs.info.offset == -1) {
+    pos = fd_info->current_pos;
+  } else {
+    pos.QuadPart = req->fs.info.offset;
+  }
+
+  end_pos.QuadPart = pos.QuadPart + write_size;
+
+  /* Recreate the mapping to enlarge the file if needed */
+  if (end_pos.QuadPart > fd_info->size.QuadPart) {
+    if (fd_info->mapping != INVALID_HANDLE_VALUE) {
+      CloseHandle(fd_info->mapping);
+    }
+
+    fd_info->mapping = CreateFileMapping(file,
+                                         NULL,
+                                         PAGE_READWRITE,
+                                         end_pos.HighPart,
+                                         end_pos.LowPart,
+                                         NULL);
+    if (fd_info->mapping == NULL) {
+      SET_REQ_WIN32_ERROR(req, GetLastError());
+      CloseHandle(file);
+      fd_info->mapping = INVALID_HANDLE_VALUE;
+      fd_info->size.QuadPart = 0;
+      fd_info->current_pos.QuadPart = 0;
+      uv__fd_hash_add(fd, fd_info);
+      return;
+    }
+
+    fd_info->size = end_pos;
+    uv__fd_hash_add(fd, fd_info);
+  }
+
+  view_offset = pos.QuadPart % uv__allocation_granularity;
+  view_base.QuadPart = pos.QuadPart - view_offset;
+  view = MapViewOfFile(fd_info->mapping,
+                       FILE_MAP_WRITE,
+                       view_base.HighPart,
+                       view_base.LowPart,
+                       view_offset + write_size);
+  if (view == NULL) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    return;
+  }
+
+  done_write = 0;
+  for (index = 0; index < req->fs.info.nbufs; ++index) {
+#ifdef _MSC_VER
+    int err = 0;
+    __try {
+#endif
+      memcpy((char*)view + view_offset + done_write,
+             req->fs.info.bufs[index].base,
+             req->fs.info.bufs[index].len);
+#ifdef _MSC_VER
+    }
+    __except (fs__filemap_ex_filter(GetExceptionCode(),
+                                    GetExceptionInformation(), &err)) {
+      SET_REQ_WIN32_ERROR(req, err);
+      UnmapViewOfFile(view);
+      return;
+    }
+#endif
+    done_write += req->fs.info.bufs[index].len;
+  }
+  assert(done_write == write_size);
+
+  if (!FlushViewOfFile(view, 0)) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    UnmapViewOfFile(view);
+    return;
+  }
+  if (!UnmapViewOfFile(view)) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    return;
+  }
+
+  if (req->fs.info.offset == -1) {
+    fd_info->current_pos = end_pos;
+    uv__fd_hash_add(fd, fd_info);
+  }
+
+  GetSystemTimeAsFileTime(&ft);
+  SetFileTime(file, NULL, NULL, &ft);
+
+  SET_REQ_RESULT(req, done_write);
+}
+
+void fs__write(uv_fs_t* req) {
+  int fd = req->file.fd;
+  int64_t offset = req->fs.info.offset;
+  HANDLE handle;
+  OVERLAPPED overlapped, *overlapped_ptr;
+  LARGE_INTEGER offset_;
+  DWORD bytes;
+  DWORD error;
+  int result;
+  unsigned int index;
+  LARGE_INTEGER original_position;
+  LARGE_INTEGER zero_offset;
+  int restore_position;
+  struct uv__fd_info_s fd_info;
+
+  VERIFY_FD(fd, req);
+
+  zero_offset.QuadPart = 0;
+  restore_position = 0;
+  handle = uv__get_osfhandle(fd);
+  if (handle == INVALID_HANDLE_VALUE) {
+    SET_REQ_WIN32_ERROR(req, ERROR_INVALID_HANDLE);
+    return;
+  }
+
+  if (uv__fd_hash_get(fd, &fd_info)) {
+    fs__write_filemap(req, handle, &fd_info);
+    return;
+  }
+
+  if (offset != -1) {
+    memset(&overlapped, 0, sizeof overlapped);
+    overlapped_ptr = &overlapped;
+    if (SetFilePointerEx(handle, zero_offset, &original_position,
+                         FILE_CURRENT)) {
+      restore_position = 1;
+    }
+  } else {
+    overlapped_ptr = NULL;
+  }
+
+  index = 0;
+  bytes = 0;
+  do {
+    DWORD incremental_bytes;
+
+    if (offset != -1) {
+      offset_.QuadPart = offset + bytes;
+      overlapped.Offset = offset_.LowPart;
+      overlapped.OffsetHigh = offset_.HighPart;
+    }
+
+    result = WriteFile(handle,
+                       req->fs.info.bufs[index].base,
+                       req->fs.info.bufs[index].len,
+                       &incremental_bytes,
+                       overlapped_ptr);
+    bytes += incremental_bytes;
+    ++index;
+  } while (result && index < req->fs.info.nbufs);
+
+  if (restore_position)
+    SetFilePointerEx(handle, original_position, NULL, FILE_BEGIN);
+
+  if (result || bytes > 0) {
+    SET_REQ_RESULT(req, bytes);
+  } else {
+    error = GetLastError();
+
+    if (error == ERROR_ACCESS_DENIED) {
+      error = ERROR_INVALID_FLAGS;
+    }
+
+    SET_REQ_WIN32_ERROR(req, error);
+  }
+}
+
+
+void fs__rmdir(uv_fs_t* req) {
+  int result = _wrmdir(req->file.pathw);
+  if (result == -1)
+    SET_REQ_WIN32_ERROR(req, _doserrno);
+  else
+    SET_REQ_RESULT(req, 0);
+}
+
+
+void fs__unlink(uv_fs_t* req) {
+  const WCHAR* pathw = req->file.pathw;
+  HANDLE handle;
+  BY_HANDLE_FILE_INFORMATION info;
+  FILE_DISPOSITION_INFORMATION disposition;
+  IO_STATUS_BLOCK iosb;
+  NTSTATUS status;
+
+  handle = CreateFileW(pathw,
+                       FILE_READ_ATTRIBUTES | FILE_WRITE_ATTRIBUTES | DELETE,
+                       FILE_SHARE_READ | FILE_SHARE_WRITE | FILE_SHARE_DELETE,
+                       NULL,
+                       OPEN_EXISTING,
+                       FILE_FLAG_OPEN_REPARSE_POINT | FILE_FLAG_BACKUP_SEMANTICS,
+                       NULL);
+
+  if (handle == INVALID_HANDLE_VALUE) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    return;
+  }
+
+  if (!GetFileInformationByHandle(handle, &info)) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    CloseHandle(handle);
+    return;
+  }
+
+  if (info.dwFileAttributes & FILE_ATTRIBUTE_DIRECTORY) {
+    /* Do not allow deletion of directories, unless it is a symlink. When the
+     * path refers to a non-symlink directory, report EPERM as mandated by
+     * POSIX.1. */
+
+    /* Check if it is a reparse point. If it's not, it's a normal directory. */
+    if (!(info.dwFileAttributes & FILE_ATTRIBUTE_REPARSE_POINT)) {
+      SET_REQ_WIN32_ERROR(req, ERROR_ACCESS_DENIED);
+      CloseHandle(handle);
+      return;
+    }
+
+    /* Read the reparse point and check if it is a valid symlink. If not, don't
+     * unlink. */
+    if (fs__readlink_handle(handle, NULL, NULL) < 0) {
+      DWORD error = GetLastError();
+      if (error == ERROR_SYMLINK_NOT_SUPPORTED)
+        error = ERROR_ACCESS_DENIED;
+      SET_REQ_WIN32_ERROR(req, error);
+      CloseHandle(handle);
+      return;
+    }
+  }
+
+  if (info.dwFileAttributes & FILE_ATTRIBUTE_READONLY) {
+    /* Remove read-only attribute */
+    FILE_BASIC_INFORMATION basic = { 0 };
+
+    basic.FileAttributes = (info.dwFileAttributes & ~FILE_ATTRIBUTE_READONLY) |
+                           FILE_ATTRIBUTE_ARCHIVE;
+
+    status = pNtSetInformationFile(handle,
+                                   &iosb,
+                                   &basic,
+                                   sizeof basic,
+                                   FileBasicInformation);
+    if (!NT_SUCCESS(status)) {
+      SET_REQ_WIN32_ERROR(req, pRtlNtStatusToDosError(status));
+      CloseHandle(handle);
+      return;
+    }
+  }
+
+  /* Try to set the delete flag. */
+  disposition.DeleteFile = TRUE;
+  status = pNtSetInformationFile(handle,
+                                 &iosb,
+                                 &disposition,
+                                 sizeof disposition,
+                                 FileDispositionInformation);
+  if (NT_SUCCESS(status)) {
+    SET_REQ_SUCCESS(req);
+  } else {
+    SET_REQ_WIN32_ERROR(req, pRtlNtStatusToDosError(status));
+  }
+
+  CloseHandle(handle);
+}
+
+
+void fs__mkdir(uv_fs_t* req) {
+  /* TODO: use req->mode. */
+  if (CreateDirectoryW(req->file.pathw, NULL)) {
+    SET_REQ_RESULT(req, 0);
+  } else {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    if (req->sys_errno_ == ERROR_INVALID_NAME ||
+        req->sys_errno_ == ERROR_DIRECTORY)
+      req->result = UV_EINVAL;
+  }
+}
+
+typedef int (*uv__fs_mktemp_func)(uv_fs_t* req);
+
+/* OpenBSD original: lib/libc/stdio/mktemp.c */
+void fs__mktemp(uv_fs_t* req, uv__fs_mktemp_func func) {
+  static const WCHAR *tempchars =
+    L"abcdefghijklmnopqrstuvwxyzABCDEFGHIJKLMNOPQRSTUVWXYZ0123456789";
+  static const size_t num_chars = 62;
+  static const size_t num_x = 6;
+  WCHAR *cp, *ep;
+  unsigned int tries, i;
+  size_t len;
+  uint64_t v;
+  char* path;
+  
+  path = (char*)req->path;
+  len = wcslen(req->file.pathw);
+  ep = req->file.pathw + len;
+  if (len < num_x || wcsncmp(ep - num_x, L"XXXXXX", num_x)) {
+    SET_REQ_UV_ERROR(req, UV_EINVAL, ERROR_INVALID_PARAMETER);
+    goto clobber;
+  }
+
+  tries = TMP_MAX;
+  do {
+    if (uv__random_rtlgenrandom((void *)&v, sizeof(v)) < 0) {
+      SET_REQ_UV_ERROR(req, UV_EIO, ERROR_IO_DEVICE);
+      goto clobber;
+    }
+
+    cp = ep - num_x;
+    for (i = 0; i < num_x; i++) {
+      *cp++ = tempchars[v % num_chars];
+      v /= num_chars;
+    }
+
+    if (func(req)) {
+      if (req->result >= 0) {
+        len = strlen(path);
+        wcstombs(path + len - num_x, ep - num_x, num_x);
+      }
+      return;
+    }
+  } while (--tries);
+
+  SET_REQ_WIN32_ERROR(req, GetLastError());
+
+clobber:
+  path[0] = '\0';
+}
+
+
+static int fs__mkdtemp_func(uv_fs_t* req) {
+  DWORD error;
+  if (CreateDirectoryW(req->file.pathw, NULL)) {
+    SET_REQ_RESULT(req, 0);
+    return 1;
+  }
+  error = GetLastError();
+  if (error != ERROR_ALREADY_EXISTS) {
+    SET_REQ_WIN32_ERROR(req, error);
+    return 1;
+  }
+
+  return 0;
+}
+
+
+void fs__mkdtemp(uv_fs_t* req) {
+  fs__mktemp(req, fs__mkdtemp_func);
+}
+
+
+static int fs__mkstemp_func(uv_fs_t* req) {
+  HANDLE file;
+  int fd;
+
+  file = CreateFileW(req->file.pathw,
+                     GENERIC_READ | GENERIC_WRITE,
+                     FILE_SHARE_READ | FILE_SHARE_WRITE | FILE_SHARE_DELETE,
+                     NULL,
+                     CREATE_NEW,
+                     FILE_ATTRIBUTE_NORMAL,
+                     NULL);
+
+  if (file == INVALID_HANDLE_VALUE) {
+    DWORD error;
+    error = GetLastError();
+
+    /* If the file exists, the main fs__mktemp() function
+       will retry. If it's another error, we want to stop. */
+    if (error != ERROR_FILE_EXISTS) {
+      SET_REQ_WIN32_ERROR(req, error);
+      return 1;
+    }
+
+    return 0;
+  }
+
+  fd = _open_osfhandle((intptr_t) file, 0);
+  if (fd < 0) {
+    /* The only known failure mode for _open_osfhandle() is EMFILE, in which
+     * case GetLastError() will return zero. However we'll try to handle other
+     * errors as well, should they ever occur.
+     */
+    if (errno == EMFILE)
+      SET_REQ_UV_ERROR(req, UV_EMFILE, ERROR_TOO_MANY_OPEN_FILES);
+    else if (GetLastError() != ERROR_SUCCESS)
+      SET_REQ_WIN32_ERROR(req, GetLastError());
+    else
+      SET_REQ_WIN32_ERROR(req, UV_UNKNOWN);
+    CloseHandle(file);
+    return 1;
+  }
+
+  SET_REQ_RESULT(req, fd);
+
+  return 1;
+}
+
+
+void fs__mkstemp(uv_fs_t* req) {
+  fs__mktemp(req, fs__mkstemp_func);
+}
+
+
+void fs__scandir(uv_fs_t* req) {
+  static const size_t dirents_initial_size = 32;
+
+  HANDLE dir_handle = INVALID_HANDLE_VALUE;
+
+  uv__dirent_t** dirents = NULL;
+  size_t dirents_size = 0;
+  size_t dirents_used = 0;
+
+  IO_STATUS_BLOCK iosb;
+  NTSTATUS status;
+
+  /* Buffer to hold directory entries returned by NtQueryDirectoryFile.
+   * It's important that this buffer can hold at least one entry, regardless
+   * of the length of the file names present in the enumerated directory.
+   * A file name is at most 256 WCHARs long.
+   * According to MSDN, the buffer must be aligned at an 8-byte boundary.
+   */
+#if _MSC_VER
+  __declspec(align(8)) char buffer[8192];
+#else
+  __attribute__ ((aligned (8))) char buffer[8192];
+#endif
+
+  STATIC_ASSERT(sizeof buffer >=
+                sizeof(FILE_DIRECTORY_INFORMATION) + 256 * sizeof(WCHAR));
+
+  /* Open the directory. */
+  dir_handle =
+      CreateFileW(req->file.pathw,
+                  FILE_LIST_DIRECTORY | SYNCHRONIZE,
+                  FILE_SHARE_READ | FILE_SHARE_WRITE | FILE_SHARE_DELETE,
+                  NULL,
+                  OPEN_EXISTING,
+                  FILE_FLAG_BACKUP_SEMANTICS,
+                  NULL);
+  if (dir_handle == INVALID_HANDLE_VALUE)
+    goto win32_error;
+
+  /* Read the first chunk. */
+  status = pNtQueryDirectoryFile(dir_handle,
+                                 NULL,
+                                 NULL,
+                                 NULL,
+                                 &iosb,
+                                 &buffer,
+                                 sizeof buffer,
+                                 FileDirectoryInformation,
+                                 FALSE,
+                                 NULL,
+                                 TRUE);
+
+  /* If the handle is not a directory, we'll get STATUS_INVALID_PARAMETER.
+   * This should be reported back as UV_ENOTDIR.
+   */
+  if (status == (NTSTATUS)STATUS_INVALID_PARAMETER)
+    goto not_a_directory_error;
+
+  while (NT_SUCCESS(status)) {
+    char* position = buffer;
+    size_t next_entry_offset = 0;
+
+    do {
+      FILE_DIRECTORY_INFORMATION* info;
+      uv__dirent_t* dirent;
+
+      size_t wchar_len;
+      size_t utf8_len;
+
+      /* Obtain a pointer to the current directory entry. */
+      position += next_entry_offset;
+      info = (FILE_DIRECTORY_INFORMATION*) position;
+
+      /* Fetch the offset to the next directory entry. */
+      next_entry_offset = info->NextEntryOffset;
+
+      /* Compute the length of the filename in WCHARs. */
+      wchar_len = info->FileNameLength / sizeof info->FileName[0];
+
+      /* Skip over '.' and '..' entries.  It has been reported that
+       * the SharePoint driver includes the terminating zero byte in
+       * the filename length.  Strip those first.
+       */
+      while (wchar_len > 0 && info->FileName[wchar_len - 1] == L'\0')
+        wchar_len -= 1;
+
+      if (wchar_len == 0)
+        continue;
+      if (wchar_len == 1 && info->FileName[0] == L'.')
+        continue;
+      if (wchar_len == 2 && info->FileName[0] == L'.' &&
+          info->FileName[1] == L'.')
+        continue;
+
+      /* Compute the space required to store the filename as UTF-8. */
+      utf8_len = WideCharToMultiByte(
+          CP_UTF8, 0, &info->FileName[0], wchar_len, NULL, 0, NULL, NULL);
+      if (utf8_len == 0)
+        goto win32_error;
+
+      /* Resize the dirent array if needed. */
+      if (dirents_used >= dirents_size) {
+        size_t new_dirents_size =
+            dirents_size == 0 ? dirents_initial_size : dirents_size << 1;
+        uv__dirent_t** new_dirents = (uv__dirent_t**)
+            uv__realloc(dirents, new_dirents_size * sizeof *dirents);
+
+        if (new_dirents == NULL)
+          goto out_of_memory_error;
+
+        dirents_size = new_dirents_size;
+        dirents = new_dirents;
+      }
+
+      /* Allocate space for the uv dirent structure. The dirent structure
+       * includes room for the first character of the filename, but `utf8_len`
+       * doesn't count the NULL terminator at this point.
+       */
+      dirent = (uv__dirent_t*)uv__malloc(sizeof *dirent + utf8_len);
+      if (dirent == NULL)
+        goto out_of_memory_error;
+
+      dirents[dirents_used++] = dirent;
+
+      /* Convert file name to UTF-8. */
+      if (WideCharToMultiByte(CP_UTF8,
+                              0,
+                              &info->FileName[0],
+                              wchar_len,
+                              &dirent->d_name[0],
+                              utf8_len,
+                              NULL,
+                              NULL) == 0)
+        goto win32_error;
+
+      /* Add a null terminator to the filename. */
+      dirent->d_name[utf8_len] = '\0';
+
+      /* Fill out the type field. */
+      if (info->FileAttributes & FILE_ATTRIBUTE_DEVICE)
+        dirent->d_type = UV__DT_CHAR;
+      else if (info->FileAttributes & FILE_ATTRIBUTE_REPARSE_POINT)
+        dirent->d_type = UV__DT_LINK;
+      else if (info->FileAttributes & FILE_ATTRIBUTE_DIRECTORY)
+        dirent->d_type = UV__DT_DIR;
+      else
+        dirent->d_type = UV__DT_FILE;
+    } while (next_entry_offset != 0);
+
+    /* Read the next chunk. */
+    status = pNtQueryDirectoryFile(dir_handle,
+                                   NULL,
+                                   NULL,
+                                   NULL,
+                                   &iosb,
+                                   &buffer,
+                                   sizeof buffer,
+                                   FileDirectoryInformation,
+                                   FALSE,
+                                   NULL,
+                                   FALSE);
+
+    /* After the first pNtQueryDirectoryFile call, the function may return
+     * STATUS_SUCCESS even if the buffer was too small to hold at least one
+     * directory entry.
+     */
+    if (status == STATUS_SUCCESS && iosb.Information == 0)
+      status = STATUS_BUFFER_OVERFLOW;
+  }
+
+  if (status != STATUS_NO_MORE_FILES)
+    goto nt_error;
+
+  CloseHandle(dir_handle);
+
+  /* Store the result in the request object. */
+  req->ptr = dirents;
+  if (dirents != NULL)
+    req->flags |= UV_FS_FREE_PTR;
+
+  SET_REQ_RESULT(req, dirents_used);
+
+  /* `nbufs` will be used as index by uv_fs_scandir_next. */
+  req->fs.info.nbufs = 0;
+
+  return;
+
+nt_error:
+  SET_REQ_WIN32_ERROR(req, pRtlNtStatusToDosError(status));
+  goto cleanup;
+
+win32_error:
+  SET_REQ_WIN32_ERROR(req, GetLastError());
+  goto cleanup;
+
+not_a_directory_error:
+  SET_REQ_UV_ERROR(req, UV_ENOTDIR, ERROR_DIRECTORY);
+  goto cleanup;
+
+out_of_memory_error:
+  SET_REQ_UV_ERROR(req, UV_ENOMEM, ERROR_OUTOFMEMORY);
+  goto cleanup;
+
+cleanup:
+  if (dir_handle != INVALID_HANDLE_VALUE)
+    CloseHandle(dir_handle);
+  while (dirents_used > 0)
+    uv__free(dirents[--dirents_used]);
+  if (dirents != NULL)
+    uv__free(dirents);
+}
+
+void fs__opendir(uv_fs_t* req) {
+  WCHAR* pathw;
+  size_t len;
+  const WCHAR* fmt;
+  WCHAR* find_path;
+  uv_dir_t* dir;
+
+  pathw = req->file.pathw;
+  dir = NULL;
+  find_path = NULL;
+
+  /* Figure out whether path is a file or a directory. */
+  if (!(GetFileAttributesW(pathw) & FILE_ATTRIBUTE_DIRECTORY)) {
+    SET_REQ_UV_ERROR(req, UV_ENOTDIR, ERROR_DIRECTORY);
+    goto error;
+  }
+
+  dir = (uv_dir_t*)uv__malloc(sizeof(*dir));
+  if (dir == NULL) {
+    SET_REQ_UV_ERROR(req, UV_ENOMEM, ERROR_OUTOFMEMORY);
+    goto error;
+  }
+
+  len = wcslen(pathw);
+
+  if (len == 0)
+    fmt = L"./*";
+  else if (IS_SLASH(pathw[len - 1]))
+    fmt = L"%s*";
+  else
+    fmt = L"%s\\*";
+
+  find_path = (WCHAR*)uv__malloc(sizeof(WCHAR) * (len + 4));
+  if (find_path == NULL) {
+    SET_REQ_UV_ERROR(req, UV_ENOMEM, ERROR_OUTOFMEMORY);
+    goto error;
+  }
+
+  _snwprintf(find_path, len + 3, fmt, pathw);
+  dir->dir_handle = FindFirstFileW(find_path, &dir->find_data);
+  uv__free(find_path);
+  find_path = NULL;
+  if (dir->dir_handle == INVALID_HANDLE_VALUE &&
+      GetLastError() != ERROR_FILE_NOT_FOUND) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    goto error;
+  }
+
+  dir->need_find_call = FALSE;
+  req->ptr = dir;
+  SET_REQ_RESULT(req, 0);
+  return;
+
+error:
+  uv__free(dir);
+  uv__free(find_path);
+  req->ptr = NULL;
+}
+
+void fs__readdir(uv_fs_t* req) {
+  uv_dir_t* dir;
+  uv_dirent_t* dirents;
+  uv__dirent_t dent;
+  unsigned int dirent_idx;
+  PWIN32_FIND_DATAW find_data;
+  unsigned int i;
+  int r;
+
+  req->flags |= UV_FS_FREE_PTR;
+  dir = (uv_dir_t*)req->ptr;
+  dirents = dir->dirents;
+  memset(dirents, 0, dir->nentries * sizeof(*dir->dirents));
+  find_data = &dir->find_data;
+  dirent_idx = 0;
+
+  while (dirent_idx < dir->nentries) {
+    if (dir->need_find_call && FindNextFileW(dir->dir_handle, find_data) == 0) {
+      if (GetLastError() == ERROR_NO_MORE_FILES)
+        break;
+      goto error;
+    }
+
+    /* Skip "." and ".." entries. */
+    if (find_data->cFileName[0] == L'.' &&
+        (find_data->cFileName[1] == L'\0' ||
+        (find_data->cFileName[1] == L'.' &&
+        find_data->cFileName[2] == L'\0'))) {
+      dir->need_find_call = TRUE;
+      continue;
+    }
+
+    r = uv__convert_utf16_to_utf8((const WCHAR*) &find_data->cFileName,
+                                  -1,
+                                  (char**) &dirents[dirent_idx].name);
+    if (r != 0)
+      goto error;
+
+    /* Copy file type. */
+    if ((find_data->dwFileAttributes & FILE_ATTRIBUTE_DIRECTORY) != 0)
+      dent.d_type = UV__DT_DIR;
+    else if ((find_data->dwFileAttributes & FILE_ATTRIBUTE_REPARSE_POINT) != 0)
+      dent.d_type = UV__DT_LINK;
+    else if ((find_data->dwFileAttributes & FILE_ATTRIBUTE_DEVICE) != 0)
+      dent.d_type = UV__DT_CHAR;
+    else
+      dent.d_type = UV__DT_FILE;
+
+    dirents[dirent_idx].type = uv__fs_get_dirent_type(&dent);
+    dir->need_find_call = TRUE;
+    ++dirent_idx;
+  }
+
+  SET_REQ_RESULT(req, dirent_idx);
+  return;
+
+error:
+  SET_REQ_WIN32_ERROR(req, GetLastError());
+  for (i = 0; i < dirent_idx; ++i) {
+    uv__free((char*) dirents[i].name);
+    dirents[i].name = NULL;
+  }
+}
+
+void fs__closedir(uv_fs_t* req) {
+  uv_dir_t* dir;
+
+  dir = (uv_dir_t*)req->ptr;
+  FindClose(dir->dir_handle);
+  uv__free(req->ptr);
+  SET_REQ_RESULT(req, 0);
+}
+
+INLINE static int fs__stat_handle(HANDLE handle, uv_stat_t* statbuf,
+    int do_lstat) {
+  FILE_ALL_INFORMATION file_info;
+  FILE_FS_VOLUME_INFORMATION volume_info;
+  NTSTATUS nt_status;
+  IO_STATUS_BLOCK io_status;
+
+  nt_status = pNtQueryInformationFile(handle,
+                                      &io_status,
+                                      &file_info,
+                                      sizeof file_info,
+                                      FileAllInformation);
+
+  /* Buffer overflow (a warning status code) is expected here. */
+  if (NT_ERROR(nt_status)) {
+    SetLastError(pRtlNtStatusToDosError(nt_status));
+    return -1;
+  }
+
+  nt_status = pNtQueryVolumeInformationFile(handle,
+                                            &io_status,
+                                            &volume_info,
+                                            sizeof volume_info,
+                                            FileFsVolumeInformation);
+
+  /* Buffer overflow (a warning status code) is expected here. */
+  if (io_status.Status == STATUS_NOT_IMPLEMENTED) {
+    statbuf->st_dev = 0;
+  } else if (NT_ERROR(nt_status)) {
+    SetLastError(pRtlNtStatusToDosError(nt_status));
+    return -1;
+  } else {
+    statbuf->st_dev = volume_info.VolumeSerialNumber;
+  }
+
+  /* Todo: st_mode should probably always be 0666 for everyone. We might also
+   * want to report 0777 if the file is a .exe or a directory.
+   *
+   * Currently it's based on whether the 'readonly' attribute is set, which
+   * makes little sense because the semantics are so different: the 'read-only'
+   * flag is just a way for a user to protect against accidental deletion, and
+   * serves no security purpose. Windows uses ACLs for that.
+   *
+   * Also people now use uv_fs_chmod() to take away the writable bit for good
+   * reasons. Windows however just makes the file read-only, which makes it
+   * impossible to delete the file afterwards, since read-only files can't be
+   * deleted.
+   *
+   * IOW it's all just a clusterfuck and we should think of something that
+   * makes slightly more sense.
+   *
+   * And uv_fs_chmod should probably just fail on windows or be a total no-op.
+   * There's nothing sensible it can do anyway.
+   */
+  statbuf->st_mode = 0;
+
+  /*
+  * On Windows, FILE_ATTRIBUTE_REPARSE_POINT is a general purpose mechanism
+  * by which filesystem drivers can intercept and alter file system requests.
+  *
+  * The only reparse points we care about are symlinks and mount points, both
+  * of which are treated as POSIX symlinks. Further, we only care when
+  * invoked via lstat, which seeks information about the link instead of its
+  * target. Otherwise, reparse points must be treated as regular files.
+  */
+  if (do_lstat &&
+      (file_info.BasicInformation.FileAttributes & FILE_ATTRIBUTE_REPARSE_POINT)) {
+    /*
+     * If reading the link fails, the reparse point is not a symlink and needs
+     * to be treated as a regular file. The higher level lstat function will
+     * detect this failure and retry without do_lstat if appropriate.
+     */
+    if (fs__readlink_handle(handle, NULL, &statbuf->st_size) != 0)
+      return -1;
+    statbuf->st_mode |= S_IFLNK;
+  }
+
+  if (statbuf->st_mode == 0) {
+    if (file_info.BasicInformation.FileAttributes & FILE_ATTRIBUTE_DIRECTORY) {
+      statbuf->st_mode |= _S_IFDIR;
+      statbuf->st_size = 0;
+    } else {
+      statbuf->st_mode |= _S_IFREG;
+      statbuf->st_size = file_info.StandardInformation.EndOfFile.QuadPart;
+    }
+  }
+
+  if (file_info.BasicInformation.FileAttributes & FILE_ATTRIBUTE_READONLY)
+    statbuf->st_mode |= _S_IREAD | (_S_IREAD >> 3) | (_S_IREAD >> 6);
+  else
+    statbuf->st_mode |= (_S_IREAD | _S_IWRITE) | ((_S_IREAD | _S_IWRITE) >> 3) |
+                        ((_S_IREAD | _S_IWRITE) >> 6);
+
+  uv__filetime_to_timespec(&statbuf->st_atim,
+                           file_info.BasicInformation.LastAccessTime.QuadPart);
+  uv__filetime_to_timespec(&statbuf->st_ctim,
+                           file_info.BasicInformation.ChangeTime.QuadPart);
+  uv__filetime_to_timespec(&statbuf->st_mtim,
+                           file_info.BasicInformation.LastWriteTime.QuadPart);
+  uv__filetime_to_timespec(&statbuf->st_birthtim,
+                           file_info.BasicInformation.CreationTime.QuadPart);
+
+  statbuf->st_ino = file_info.InternalInformation.IndexNumber.QuadPart;
+
+  /* st_blocks contains the on-disk allocation size in 512-byte units. */
+  statbuf->st_blocks =
+      (uint64_t) file_info.StandardInformation.AllocationSize.QuadPart >> 9;
+
+  statbuf->st_nlink = file_info.StandardInformation.NumberOfLinks;
+
+  /* The st_blksize is supposed to be the 'optimal' number of bytes for reading
+   * and writing to the disk. That is, for any definition of 'optimal' - it's
+   * supposed to at least avoid read-update-write behavior when writing to the
+   * disk.
+   *
+   * However nobody knows this and even fewer people actually use this value,
+   * and in order to fill it out we'd have to make another syscall to query the
+   * volume for FILE_FS_SECTOR_SIZE_INFORMATION.
+   *
+   * Therefore we'll just report a sensible value that's quite commonly okay
+   * on modern hardware.
+   *
+   * 4096 is the minimum required to be compatible with newer Advanced Format
+   * drives (which have 4096 bytes per physical sector), and to be backwards
+   * compatible with older drives (which have 512 bytes per physical sector).
+   */
+  statbuf->st_blksize = 4096;
+
+  /* Todo: set st_flags to something meaningful. Also provide a wrapper for
+   * chattr(2).
+   */
+  statbuf->st_flags = 0;
+
+  /* Windows has nothing sensible to say about these values, so they'll just
+   * remain empty.
+   */
+  statbuf->st_gid = 0;
+  statbuf->st_uid = 0;
+  statbuf->st_rdev = 0;
+  statbuf->st_gen = 0;
+
+  return 0;
+}
+
+
+INLINE static void fs__stat_prepare_path(WCHAR* pathw) {
+  size_t len = wcslen(pathw);
+
+  /* TODO: ignore namespaced paths. */
+  if (len > 1 && pathw[len - 2] != L':' &&
+      (pathw[len - 1] == L'\\' || pathw[len - 1] == L'/')) {
+    pathw[len - 1] = '\0';
+  }
+}
+
+
+INLINE static DWORD fs__stat_impl_from_path(WCHAR* path,
+                                            int do_lstat,
+                                            uv_stat_t* statbuf) {
+  HANDLE handle;
+  DWORD flags;
+  DWORD ret;
+
+  flags = FILE_FLAG_BACKUP_SEMANTICS;
+  if (do_lstat)
+    flags |= FILE_FLAG_OPEN_REPARSE_POINT;
+
+  handle = CreateFileW(path,
+                       FILE_READ_ATTRIBUTES,
+                       FILE_SHARE_READ | FILE_SHARE_WRITE | FILE_SHARE_DELETE,
+                       NULL,
+                       OPEN_EXISTING,
+                       flags,
+                       NULL);
+
+  if (handle == INVALID_HANDLE_VALUE)
+    return GetLastError();
+
+  if (fs__stat_handle(handle, statbuf, do_lstat) != 0)
+    ret = GetLastError();
+  else
+    ret = 0;
+
+  CloseHandle(handle);
+  return ret;
+}
+
+
+INLINE static void fs__stat_impl(uv_fs_t* req, int do_lstat) {
+  DWORD error;
+
+  error = fs__stat_impl_from_path(req->file.pathw, do_lstat, &req->statbuf);
+  if (error != 0) {
+    if (do_lstat &&
+        (error == ERROR_SYMLINK_NOT_SUPPORTED ||
+         error == ERROR_NOT_A_REPARSE_POINT)) {
+      /* We opened a reparse point but it was not a symlink. Try again. */
+      fs__stat_impl(req, 0);
+    } else {
+      /* Stat failed. */
+      SET_REQ_WIN32_ERROR(req, error);
+    }
+
+    return;
+  }
+
+  req->ptr = &req->statbuf;
+  SET_REQ_RESULT(req, 0);
+}
+
+
+static void fs__stat(uv_fs_t* req) {
+  fs__stat_prepare_path(req->file.pathw);
+  fs__stat_impl(req, 0);
+}
+
+
+static void fs__lstat(uv_fs_t* req) {
+  fs__stat_prepare_path(req->file.pathw);
+  fs__stat_impl(req, 1);
+}
+
+
+static void fs__fstat(uv_fs_t* req) {
+  int fd = req->file.fd;
+  HANDLE handle;
+
+  VERIFY_FD(fd, req);
+
+  handle = uv__get_osfhandle(fd);
+
+  if (handle == INVALID_HANDLE_VALUE) {
+    SET_REQ_WIN32_ERROR(req, ERROR_INVALID_HANDLE);
+    return;
+  }
+
+  if (fs__stat_handle(handle, &req->statbuf, 0) != 0) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    return;
+  }
+
+  req->ptr = &req->statbuf;
+  SET_REQ_RESULT(req, 0);
+}
+
+
+static void fs__rename(uv_fs_t* req) {
+  if (!MoveFileExW(req->file.pathw, req->fs.info.new_pathw, MOVEFILE_REPLACE_EXISTING)) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    return;
+  }
+
+  SET_REQ_RESULT(req, 0);
+}
+
+
+INLINE static void fs__sync_impl(uv_fs_t* req) {
+  int fd = req->file.fd;
+  int result;
+
+  VERIFY_FD(fd, req);
+
+  result = FlushFileBuffers(uv__get_osfhandle(fd)) ? 0 : -1;
+  if (result == -1) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+  } else {
+    SET_REQ_RESULT(req, result);
+  }
+}
+
+
+static void fs__fsync(uv_fs_t* req) {
+  fs__sync_impl(req);
+}
+
+
+static void fs__fdatasync(uv_fs_t* req) {
+  fs__sync_impl(req);
+}
+
+
+static void fs__ftruncate(uv_fs_t* req) {
+  int fd = req->file.fd;
+  HANDLE handle;
+  struct uv__fd_info_s fd_info = { 0 };
+  NTSTATUS status;
+  IO_STATUS_BLOCK io_status;
+  FILE_END_OF_FILE_INFORMATION eof_info;
+
+  VERIFY_FD(fd, req);
+
+  handle = uv__get_osfhandle(fd);
+
+  if (uv__fd_hash_get(fd, &fd_info)) {
+    if (fd_info.is_directory) {
+      SET_REQ_WIN32_ERROR(req, ERROR_ACCESS_DENIED);
+      return;
+    }
+
+    if (fd_info.mapping != INVALID_HANDLE_VALUE) {
+      CloseHandle(fd_info.mapping);
+    }
+  }
+
+  eof_info.EndOfFile.QuadPart = req->fs.info.offset;
+
+  status = pNtSetInformationFile(handle,
+                                 &io_status,
+                                 &eof_info,
+                                 sizeof eof_info,
+                                 FileEndOfFileInformation);
+
+  if (NT_SUCCESS(status)) {
+    SET_REQ_RESULT(req, 0);
+  } else {
+    SET_REQ_WIN32_ERROR(req, pRtlNtStatusToDosError(status));
+
+    if (fd_info.flags) {
+      CloseHandle(handle);
+      fd_info.mapping = INVALID_HANDLE_VALUE;
+      fd_info.size.QuadPart = 0;
+      fd_info.current_pos.QuadPart = 0;
+      uv__fd_hash_add(fd, &fd_info);
+      return;
+    }
+  }
+
+  if (fd_info.flags) {
+    fd_info.size = eof_info.EndOfFile;
+
+    if (fd_info.size.QuadPart == 0) {
+      fd_info.mapping = INVALID_HANDLE_VALUE;
+    } else {
+      DWORD flProtect = (fd_info.flags & (UV_FS_O_RDONLY | UV_FS_O_WRONLY |
+        UV_FS_O_RDWR)) == UV_FS_O_RDONLY ? PAGE_READONLY : PAGE_READWRITE;
+      fd_info.mapping = CreateFileMapping(handle,
+                                          NULL,
+                                          flProtect,
+                                          fd_info.size.HighPart,
+                                          fd_info.size.LowPart,
+                                          NULL);
+      if (fd_info.mapping == NULL) {
+        SET_REQ_WIN32_ERROR(req, GetLastError());
+        CloseHandle(handle);
+        fd_info.mapping = INVALID_HANDLE_VALUE;
+        fd_info.size.QuadPart = 0;
+        fd_info.current_pos.QuadPart = 0;
+        uv__fd_hash_add(fd, &fd_info);
+        return;
+      }
+    }
+
+    uv__fd_hash_add(fd, &fd_info);
+  }
+}
+
+
+static void fs__copyfile(uv_fs_t* req) {
+  int flags;
+  int overwrite;
+  uv_stat_t statbuf;
+  uv_stat_t new_statbuf;
+
+  flags = req->fs.info.file_flags;
+
+  if (flags & UV_FS_COPYFILE_FICLONE_FORCE) {
+    SET_REQ_UV_ERROR(req, UV_ENOSYS, ERROR_NOT_SUPPORTED);
+    return;
+  }
+
+  overwrite = flags & UV_FS_COPYFILE_EXCL;
+
+  if (CopyFileW(req->file.pathw, req->fs.info.new_pathw, overwrite) != 0) {
+    SET_REQ_RESULT(req, 0);
+    return;
+  }
+
+  SET_REQ_WIN32_ERROR(req, GetLastError());
+  if (req->result != UV_EBUSY)
+    return;
+
+  /* if error UV_EBUSY check if src and dst file are the same */
+  if (fs__stat_impl_from_path(req->file.pathw, 0, &statbuf) != 0 ||
+      fs__stat_impl_from_path(req->fs.info.new_pathw, 0, &new_statbuf) != 0) {
+    return;
+  }
+
+  if (statbuf.st_dev == new_statbuf.st_dev &&
+      statbuf.st_ino == new_statbuf.st_ino) {
+    SET_REQ_RESULT(req, 0);
+  }
+}
+
+
+static void fs__sendfile(uv_fs_t* req) {
+  int fd_in = req->file.fd, fd_out = req->fs.info.fd_out;
+  size_t length = req->fs.info.bufsml[0].len;
+  int64_t offset = req->fs.info.offset;
+  const size_t max_buf_size = 65536;
+  size_t buf_size = length < max_buf_size ? length : max_buf_size;
+  int n, result = 0;
+  int64_t result_offset = 0;
+  char* buf = (char*) uv__malloc(buf_size);
+  if (!buf) {
+    uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+  }
+
+  if (offset != -1) {
+    result_offset = _lseeki64(fd_in, offset, SEEK_SET);
+  }
+
+  if (result_offset == -1) {
+    result = -1;
+  } else {
+    while (length > 0) {
+      n = _read(fd_in, buf, length < buf_size ? length : buf_size);
+      if (n == 0) {
+        break;
+      } else if (n == -1) {
+        result = -1;
+        break;
+      }
+
+      length -= n;
+
+      n = _write(fd_out, buf, n);
+      if (n == -1) {
+        result = -1;
+        break;
+      }
+
+      result += n;
+    }
+  }
+
+  uv__free(buf);
+
+  SET_REQ_RESULT(req, result);
+}
+
+
+static void fs__access(uv_fs_t* req) {
+  DWORD attr = GetFileAttributesW(req->file.pathw);
+
+  if (attr == INVALID_FILE_ATTRIBUTES) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    return;
+  }
+
+  /*
+   * Access is possible if
+   * - write access wasn't requested,
+   * - or the file isn't read-only,
+   * - or it's a directory.
+   * (Directories cannot be read-only on Windows.)
+   */
+  if (!(req->fs.info.mode & W_OK) ||
+      !(attr & FILE_ATTRIBUTE_READONLY) ||
+      (attr & FILE_ATTRIBUTE_DIRECTORY)) {
+    SET_REQ_RESULT(req, 0);
+  } else {
+    SET_REQ_WIN32_ERROR(req, UV_EPERM);
+  }
+
+}
+
+
+static void fs__chmod(uv_fs_t* req) {
+  int result = _wchmod(req->file.pathw, req->fs.info.mode);
+  if (result == -1)
+    SET_REQ_WIN32_ERROR(req, _doserrno);
+  else
+    SET_REQ_RESULT(req, 0);
+}
+
+
+static void fs__fchmod(uv_fs_t* req) {
+  int fd = req->file.fd;
+  int clear_archive_flag;
+  HANDLE handle;
+  NTSTATUS nt_status;
+  IO_STATUS_BLOCK io_status;
+  FILE_BASIC_INFORMATION file_info;
+
+  VERIFY_FD(fd, req);
+
+  handle = ReOpenFile(uv__get_osfhandle(fd), FILE_WRITE_ATTRIBUTES, 0, 0);
+  if (handle == INVALID_HANDLE_VALUE) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    return;
+  }
+
+  nt_status = pNtQueryInformationFile(handle,
+                                      &io_status,
+                                      &file_info,
+                                      sizeof file_info,
+                                      FileBasicInformation);
+
+  if (!NT_SUCCESS(nt_status)) {
+    SET_REQ_WIN32_ERROR(req, pRtlNtStatusToDosError(nt_status));
+    goto fchmod_cleanup;
+  }
+
+  /* Test if the Archive attribute is cleared */
+  if ((file_info.FileAttributes & FILE_ATTRIBUTE_ARCHIVE) == 0) {
+      /* Set Archive flag, otherwise setting or clearing the read-only
+         flag will not work */
+      file_info.FileAttributes |= FILE_ATTRIBUTE_ARCHIVE;
+      nt_status = pNtSetInformationFile(handle,
+                                        &io_status,
+                                        &file_info,
+                                        sizeof file_info,
+                                        FileBasicInformation);
+      if (!NT_SUCCESS(nt_status)) {
+        SET_REQ_WIN32_ERROR(req, pRtlNtStatusToDosError(nt_status));
+        goto fchmod_cleanup;
+      }
+      /* Remeber to clear the flag later on */
+      clear_archive_flag = 1;
+  } else {
+      clear_archive_flag = 0;
+  }
+
+  if (req->fs.info.mode & _S_IWRITE) {
+    file_info.FileAttributes &= ~FILE_ATTRIBUTE_READONLY;
+  } else {
+    file_info.FileAttributes |= FILE_ATTRIBUTE_READONLY;
+  }
+
+  nt_status = pNtSetInformationFile(handle,
+                                    &io_status,
+                                    &file_info,
+                                    sizeof file_info,
+                                    FileBasicInformation);
+
+  if (!NT_SUCCESS(nt_status)) {
+    SET_REQ_WIN32_ERROR(req, pRtlNtStatusToDosError(nt_status));
+    goto fchmod_cleanup;
+  }
+
+  if (clear_archive_flag) {
+      file_info.FileAttributes &= ~FILE_ATTRIBUTE_ARCHIVE;
+      if (file_info.FileAttributes == 0) {
+          file_info.FileAttributes = FILE_ATTRIBUTE_NORMAL;
+      }
+      nt_status = pNtSetInformationFile(handle,
+                                        &io_status,
+                                        &file_info,
+                                        sizeof file_info,
+                                        FileBasicInformation);
+      if (!NT_SUCCESS(nt_status)) {
+        SET_REQ_WIN32_ERROR(req, pRtlNtStatusToDosError(nt_status));
+        goto fchmod_cleanup;
+      }
+  }
+
+  SET_REQ_SUCCESS(req);
+fchmod_cleanup:
+  CloseHandle(handle);
+}
+
+
+INLINE static int fs__utime_handle(HANDLE handle, double atime, double mtime) {
+  FILETIME filetime_a, filetime_m;
+
+  TIME_T_TO_FILETIME(atime, &filetime_a);
+  TIME_T_TO_FILETIME(mtime, &filetime_m);
+
+  if (!SetFileTime(handle, NULL, &filetime_a, &filetime_m)) {
+    return -1;
+  }
+
+  return 0;
+}
+
+INLINE static DWORD fs__utime_impl_from_path(WCHAR* path,
+                                             double atime,
+                                             double mtime,
+                                             int do_lutime) {
+  HANDLE handle;
+  DWORD flags;
+  DWORD ret;
+
+  flags = FILE_FLAG_BACKUP_SEMANTICS;
+  if (do_lutime) {
+    flags |= FILE_FLAG_OPEN_REPARSE_POINT;
+  }
+
+  handle = CreateFileW(path,
+                       FILE_WRITE_ATTRIBUTES,
+                       FILE_SHARE_READ | FILE_SHARE_WRITE | FILE_SHARE_DELETE,
+                       NULL,
+                       OPEN_EXISTING,
+                       flags,
+                       NULL);
+
+  if (handle == INVALID_HANDLE_VALUE)
+    return GetLastError();
+
+  if (fs__utime_handle(handle, atime, mtime) != 0)
+    ret = GetLastError();
+  else
+    ret = 0;
+
+  CloseHandle(handle);
+  return ret;
+}
+
+INLINE static void fs__utime_impl(uv_fs_t* req, int do_lutime) {
+  DWORD error;
+
+  error = fs__utime_impl_from_path(req->file.pathw,
+                                   req->fs.time.atime,
+                                   req->fs.time.mtime,
+                                   do_lutime);
+
+  if (error != 0) {
+    if (do_lutime &&
+        (error == ERROR_SYMLINK_NOT_SUPPORTED ||
+         error == ERROR_NOT_A_REPARSE_POINT)) {
+      /* Opened file is a reparse point but not a symlink. Try again. */
+      fs__utime_impl(req, 0);
+    } else {
+      /* utime failed. */
+      SET_REQ_WIN32_ERROR(req, error);
+    }
+
+    return;
+  }
+
+  SET_REQ_RESULT(req, 0);
+}
+
+static void fs__utime(uv_fs_t* req) {
+  fs__utime_impl(req, /* do_lutime */ 0);
+}
+
+
+static void fs__futime(uv_fs_t* req) {
+  int fd = req->file.fd;
+  HANDLE handle;
+  VERIFY_FD(fd, req);
+
+  handle = uv__get_osfhandle(fd);
+
+  if (handle == INVALID_HANDLE_VALUE) {
+    SET_REQ_WIN32_ERROR(req, ERROR_INVALID_HANDLE);
+    return;
+  }
+
+  if (fs__utime_handle(handle, req->fs.time.atime, req->fs.time.mtime) != 0) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    return;
+  }
+
+  SET_REQ_RESULT(req, 0);
+}
+
+static void fs__lutime(uv_fs_t* req) {
+  fs__utime_impl(req, /* do_lutime */ 1);
+}
+
+
+static void fs__link(uv_fs_t* req) {
+  DWORD r = CreateHardLinkW(req->fs.info.new_pathw, req->file.pathw, NULL);
+  if (r == 0)
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+  else
+    SET_REQ_RESULT(req, 0);
+}
+
+
+static void fs__create_junction(uv_fs_t* req, const WCHAR* path,
+    const WCHAR* new_path) {
+  HANDLE handle = INVALID_HANDLE_VALUE;
+  REPARSE_DATA_BUFFER *buffer = NULL;
+  int created = 0;
+  int target_len;
+  int is_absolute, is_long_path;
+  int needed_buf_size, used_buf_size, used_data_size, path_buf_len;
+  int start, len, i;
+  int add_slash;
+  DWORD bytes;
+  WCHAR* path_buf;
+
+  target_len = wcslen(path);
+  is_long_path = wcsncmp(path, LONG_PATH_PREFIX, LONG_PATH_PREFIX_LEN) == 0;
+
+  if (is_long_path) {
+    is_absolute = 1;
+  } else {
+    is_absolute = target_len >= 3 && IS_LETTER(path[0]) &&
+      path[1] == L':' && IS_SLASH(path[2]);
+  }
+
+  if (!is_absolute) {
+    /* Not supporting relative paths */
+    SET_REQ_UV_ERROR(req, UV_EINVAL, ERROR_NOT_SUPPORTED);
+    return;
+  }
+
+  /* Do a pessimistic calculation of the required buffer size */
+  needed_buf_size =
+      FIELD_OFFSET(REPARSE_DATA_BUFFER, MountPointReparseBuffer.PathBuffer) +
+      JUNCTION_PREFIX_LEN * sizeof(WCHAR) +
+      2 * (target_len + 2) * sizeof(WCHAR);
+
+  /* Allocate the buffer */
+  buffer = (REPARSE_DATA_BUFFER*)uv__malloc(needed_buf_size);
+  if (!buffer) {
+    uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+  }
+
+  /* Grab a pointer to the part of the buffer where filenames go */
+  path_buf = (WCHAR*)&(buffer->MountPointReparseBuffer.PathBuffer);
+  path_buf_len = 0;
+
+  /* Copy the substitute (internal) target path */
+  start = path_buf_len;
+
+  wcsncpy((WCHAR*)&path_buf[path_buf_len], JUNCTION_PREFIX,
+    JUNCTION_PREFIX_LEN);
+  path_buf_len += JUNCTION_PREFIX_LEN;
+
+  add_slash = 0;
+  for (i = is_long_path ? LONG_PATH_PREFIX_LEN : 0; path[i] != L'\0'; i++) {
+    if (IS_SLASH(path[i])) {
+      add_slash = 1;
+      continue;
+    }
+
+    if (add_slash) {
+      path_buf[path_buf_len++] = L'\\';
+      add_slash = 0;
+    }
+
+    path_buf[path_buf_len++] = path[i];
+  }
+  path_buf[path_buf_len++] = L'\\';
+  len = path_buf_len - start;
+
+  /* Set the info about the substitute name */
+  buffer->MountPointReparseBuffer.SubstituteNameOffset = start * sizeof(WCHAR);
+  buffer->MountPointReparseBuffer.SubstituteNameLength = len * sizeof(WCHAR);
+
+  /* Insert null terminator */
+  path_buf[path_buf_len++] = L'\0';
+
+  /* Copy the print name of the target path */
+  start = path_buf_len;
+  add_slash = 0;
+  for (i = is_long_path ? LONG_PATH_PREFIX_LEN : 0; path[i] != L'\0'; i++) {
+    if (IS_SLASH(path[i])) {
+      add_slash = 1;
+      continue;
+    }
+
+    if (add_slash) {
+      path_buf[path_buf_len++] = L'\\';
+      add_slash = 0;
+    }
+
+    path_buf[path_buf_len++] = path[i];
+  }
+  len = path_buf_len - start;
+  if (len == 2) {
+    path_buf[path_buf_len++] = L'\\';
+    len++;
+  }
+
+  /* Set the info about the print name */
+  buffer->MountPointReparseBuffer.PrintNameOffset = start * sizeof(WCHAR);
+  buffer->MountPointReparseBuffer.PrintNameLength = len * sizeof(WCHAR);
+
+  /* Insert another null terminator */
+  path_buf[path_buf_len++] = L'\0';
+
+  /* Calculate how much buffer space was actually used */
+  used_buf_size = FIELD_OFFSET(REPARSE_DATA_BUFFER, MountPointReparseBuffer.PathBuffer) +
+    path_buf_len * sizeof(WCHAR);
+  used_data_size = used_buf_size -
+    FIELD_OFFSET(REPARSE_DATA_BUFFER, MountPointReparseBuffer);
+
+  /* Put general info in the data buffer */
+  buffer->ReparseTag = IO_REPARSE_TAG_MOUNT_POINT;
+  buffer->ReparseDataLength = used_data_size;
+  buffer->Reserved = 0;
+
+  /* Create a new directory */
+  if (!CreateDirectoryW(new_path, NULL)) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    goto error;
+  }
+  created = 1;
+
+  /* Open the directory */
+  handle = CreateFileW(new_path,
+                       GENERIC_WRITE,
+                       0,
+                       NULL,
+                       OPEN_EXISTING,
+                       FILE_FLAG_BACKUP_SEMANTICS |
+                         FILE_FLAG_OPEN_REPARSE_POINT,
+                       NULL);
+  if (handle == INVALID_HANDLE_VALUE) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    goto error;
+  }
+
+  /* Create the actual reparse point */
+  if (!DeviceIoControl(handle,
+                       FSCTL_SET_REPARSE_POINT,
+                       buffer,
+                       used_buf_size,
+                       NULL,
+                       0,
+                       &bytes,
+                       NULL)) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    goto error;
+  }
+
+  /* Clean up */
+  CloseHandle(handle);
+  uv__free(buffer);
+
+  SET_REQ_RESULT(req, 0);
+  return;
+
+error:
+  uv__free(buffer);
+
+  if (handle != INVALID_HANDLE_VALUE) {
+    CloseHandle(handle);
+  }
+
+  if (created) {
+    RemoveDirectoryW(new_path);
+  }
+}
+
+
+static void fs__symlink(uv_fs_t* req) {
+  WCHAR* pathw;
+  WCHAR* new_pathw;
+  int flags;
+  int err;
+
+  pathw = req->file.pathw;
+  new_pathw = req->fs.info.new_pathw;
+
+  if (req->fs.info.file_flags & UV_FS_SYMLINK_JUNCTION) {
+    fs__create_junction(req, pathw, new_pathw);
+    return;
+  }
+
+  if (req->fs.info.file_flags & UV_FS_SYMLINK_DIR)
+    flags = SYMBOLIC_LINK_FLAG_DIRECTORY | uv__file_symlink_usermode_flag;
+  else
+    flags = uv__file_symlink_usermode_flag;
+
+  if (CreateSymbolicLinkW(new_pathw, pathw, flags)) {
+    SET_REQ_RESULT(req, 0);
+    return;
+  }
+
+  /* Something went wrong. We will test if it is because of user-mode
+   * symlinks.
+   */
+  err = GetLastError();
+  if (err == ERROR_INVALID_PARAMETER &&
+      flags & SYMBOLIC_LINK_FLAG_ALLOW_UNPRIVILEGED_CREATE) {
+    /* This system does not support user-mode symlinks. We will clear the
+     * unsupported flag and retry.
+     */
+    uv__file_symlink_usermode_flag = 0;
+    fs__symlink(req);
+  } else {
+    SET_REQ_WIN32_ERROR(req, err);
+  }
+}
+
+
+static void fs__readlink(uv_fs_t* req) {
+  HANDLE handle;
+
+  handle = CreateFileW(req->file.pathw,
+                       0,
+                       0,
+                       NULL,
+                       OPEN_EXISTING,
+                       FILE_FLAG_OPEN_REPARSE_POINT | FILE_FLAG_BACKUP_SEMANTICS,
+                       NULL);
+
+  if (handle == INVALID_HANDLE_VALUE) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    return;
+  }
+
+  if (fs__readlink_handle(handle, (char**) &req->ptr, NULL) != 0) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    CloseHandle(handle);
+    return;
+  }
+
+  req->flags |= UV_FS_FREE_PTR;
+  SET_REQ_RESULT(req, 0);
+
+  CloseHandle(handle);
+}
+
+
+static ssize_t fs__realpath_handle(HANDLE handle, char** realpath_ptr) {
+  int r;
+  DWORD w_realpath_len;
+  WCHAR* w_realpath_ptr = NULL;
+  WCHAR* w_realpath_buf;
+
+  w_realpath_len = GetFinalPathNameByHandleW(handle, NULL, 0, VOLUME_NAME_DOS);
+  if (w_realpath_len == 0) {
+    return -1;
+  }
+
+  w_realpath_buf = (WCHAR*)uv__malloc((w_realpath_len + 1) * sizeof(WCHAR));
+  if (w_realpath_buf == NULL) {
+    SetLastError(ERROR_OUTOFMEMORY);
+    return -1;
+  }
+  w_realpath_ptr = w_realpath_buf;
+
+  if (GetFinalPathNameByHandleW(
+          handle, w_realpath_ptr, w_realpath_len, VOLUME_NAME_DOS) == 0) {
+    uv__free(w_realpath_buf);
+    SetLastError(ERROR_INVALID_HANDLE);
+    return -1;
+  }
+
+  /* convert UNC path to long path */
+  if (wcsncmp(w_realpath_ptr,
+              UNC_PATH_PREFIX,
+              UNC_PATH_PREFIX_LEN) == 0) {
+    w_realpath_ptr += 6;
+    *w_realpath_ptr = L'\\';
+    w_realpath_len -= 6;
+  } else if (wcsncmp(w_realpath_ptr,
+                      LONG_PATH_PREFIX,
+                      LONG_PATH_PREFIX_LEN) == 0) {
+    w_realpath_ptr += 4;
+    w_realpath_len -= 4;
+  } else {
+    uv__free(w_realpath_buf);
+    SetLastError(ERROR_INVALID_HANDLE);
+    return -1;
+  }
+
+  r = fs__wide_to_utf8(w_realpath_ptr, w_realpath_len, realpath_ptr, NULL);
+  uv__free(w_realpath_buf);
+  return r;
+}
+
+static void fs__realpath(uv_fs_t* req) {
+  HANDLE handle;
+
+  handle = CreateFileW(req->file.pathw,
+                       0,
+                       0,
+                       NULL,
+                       OPEN_EXISTING,
+                       FILE_ATTRIBUTE_NORMAL | FILE_FLAG_BACKUP_SEMANTICS,
+                       NULL);
+  if (handle == INVALID_HANDLE_VALUE) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    return;
+  }
+
+  if (fs__realpath_handle(handle, (char**) &req->ptr) == -1) {
+    CloseHandle(handle);
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    return;
+  }
+
+  CloseHandle(handle);
+  req->flags |= UV_FS_FREE_PTR;
+  SET_REQ_RESULT(req, 0);
+}
+
+
+static void fs__chown(uv_fs_t* req) {
+  SET_REQ_RESULT(req, 0);
+}
+
+
+static void fs__fchown(uv_fs_t* req) {
+  SET_REQ_RESULT(req, 0);
+}
+
+
+static void fs__lchown(uv_fs_t* req) {
+  SET_REQ_RESULT(req, 0);
+}
+
+
+static void fs__statfs(uv_fs_t* req) {
+  uv_statfs_t* stat_fs;
+  DWORD sectors_per_cluster;
+  DWORD bytes_per_sector;
+  DWORD free_clusters;
+  DWORD total_clusters;
+  WCHAR* pathw;
+
+  pathw = req->file.pathw;
+retry_get_disk_free_space:
+  if (0 == GetDiskFreeSpaceW(pathw,
+                             &sectors_per_cluster,
+                             &bytes_per_sector,
+                             &free_clusters,
+                             &total_clusters)) {
+    DWORD err;
+    WCHAR* fpart;
+    size_t len;
+    DWORD ret;
+    BOOL is_second;
+
+    err = GetLastError();
+    is_second = pathw != req->file.pathw;
+    if (err != ERROR_DIRECTORY || is_second) {
+      if (is_second)
+        uv__free(pathw);
+
+      SET_REQ_WIN32_ERROR(req, err);
+      return;
+    }
+
+    len = MAX_PATH + 1;
+    pathw = (WCHAR*)uv__malloc(len * sizeof(*pathw));
+    if (pathw == NULL) {
+      SET_REQ_UV_ERROR(req, UV_ENOMEM, ERROR_OUTOFMEMORY);
+      return;
+    }
+retry_get_full_path_name:
+    ret = GetFullPathNameW(req->file.pathw,
+                           len,
+                           pathw,
+                           &fpart);
+    if (ret == 0) {
+      uv__free(pathw);
+      SET_REQ_WIN32_ERROR(req, err);
+      return;
+    } else if (ret > len) {
+      len = ret;
+      pathw = (WCHAR*)uv__reallocf(pathw, len * sizeof(*pathw));
+      if (pathw == NULL) {
+        SET_REQ_UV_ERROR(req, UV_ENOMEM, ERROR_OUTOFMEMORY);
+        return;
+      }
+      goto retry_get_full_path_name;
+    }
+    if (fpart != 0)
+      *fpart = L'\0';
+
+    goto retry_get_disk_free_space;
+  }
+  if (pathw != req->file.pathw) {
+    uv__free(pathw);
+  }
+
+  stat_fs = (uv_statfs_t*)uv__malloc(sizeof(*stat_fs));
+  if (stat_fs == NULL) {
+    SET_REQ_UV_ERROR(req, UV_ENOMEM, ERROR_OUTOFMEMORY);
+    return;
+  }
+
+  stat_fs->f_type = 0;
+  stat_fs->f_bsize = bytes_per_sector * sectors_per_cluster;
+  stat_fs->f_blocks = total_clusters;
+  stat_fs->f_bfree = free_clusters;
+  stat_fs->f_bavail = free_clusters;
+  stat_fs->f_files = 0;
+  stat_fs->f_ffree = 0;
+  req->ptr = stat_fs;
+  req->flags |= UV_FS_FREE_PTR;
+  SET_REQ_RESULT(req, 0);
+}
+
+
+static void uv__fs_work(struct uv__work* w) {
+  uv_fs_t* req;
+
+  req = container_of(w, uv_fs_t, work_req);
+  assert(req->type == UV_FS);
+
+#define XX(uc, lc)  case UV_FS_##uc: fs__##lc(req); break;
+  switch (req->fs_type) {
+    XX(OPEN, open)
+    XX(CLOSE, close)
+    XX(READ, read)
+    XX(WRITE, write)
+    XX(COPYFILE, copyfile)
+    XX(SENDFILE, sendfile)
+    XX(STAT, stat)
+    XX(LSTAT, lstat)
+    XX(FSTAT, fstat)
+    XX(FTRUNCATE, ftruncate)
+    XX(UTIME, utime)
+    XX(FUTIME, futime)
+    XX(LUTIME, lutime)
+    XX(ACCESS, access)
+    XX(CHMOD, chmod)
+    XX(FCHMOD, fchmod)
+    XX(FSYNC, fsync)
+    XX(FDATASYNC, fdatasync)
+    XX(UNLINK, unlink)
+    XX(RMDIR, rmdir)
+    XX(MKDIR, mkdir)
+    XX(MKDTEMP, mkdtemp)
+    XX(MKSTEMP, mkstemp)
+    XX(RENAME, rename)
+    XX(SCANDIR, scandir)
+    XX(READDIR, readdir)
+    XX(OPENDIR, opendir)
+    XX(CLOSEDIR, closedir)
+    XX(LINK, link)
+    XX(SYMLINK, symlink)
+    XX(READLINK, readlink)
+    XX(REALPATH, realpath)
+    XX(CHOWN, chown)
+    XX(FCHOWN, fchown)
+    XX(LCHOWN, lchown)
+    XX(STATFS, statfs)
+    default:
+      assert(!"bad uv_fs_type");
+  }
+}
+
+
+static void uv__fs_done(struct uv__work* w, int status) {
+  uv_fs_t* req;
+
+  req = container_of(w, uv_fs_t, work_req);
+  uv__req_unregister(req->loop, req);
+
+  if (status == UV_ECANCELED) {
+    assert(req->result == 0);
+    SET_REQ_UV_ERROR(req, UV_ECANCELED, 0);
+  }
+
+  req->cb(req);
+}
+
+
+void uv_fs_req_cleanup(uv_fs_t* req) {
+  if (req == NULL)
+    return;
+
+  if (req->flags & UV_FS_CLEANEDUP)
+    return;
+
+  if (req->flags & UV_FS_FREE_PATHS)
+    uv__free(req->file.pathw);
+
+  if (req->flags & UV_FS_FREE_PTR) {
+    if (req->fs_type == UV_FS_SCANDIR && req->ptr != NULL)
+      uv__fs_scandir_cleanup(req);
+    else if (req->fs_type == UV_FS_READDIR)
+      uv__fs_readdir_cleanup(req);
+    else
+      uv__free(req->ptr);
+  }
+
+  if (req->fs.info.bufs != req->fs.info.bufsml)
+    uv__free(req->fs.info.bufs);
+
+  req->path = NULL;
+  req->file.pathw = NULL;
+  req->fs.info.new_pathw = NULL;
+  req->fs.info.bufs = NULL;
+  req->ptr = NULL;
+
+  req->flags |= UV_FS_CLEANEDUP;
+}
+
+
+int uv_fs_open(uv_loop_t* loop, uv_fs_t* req, const char* path, int flags,
+    int mode, uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_OPEN);
+  err = fs__capture_path(req, path, NULL, cb != NULL);
+  if (err) {
+    SET_REQ_WIN32_ERROR(req, err);
+    return req->result;
+  }
+
+  req->fs.info.file_flags = flags;
+  req->fs.info.mode = mode;
+  POST;
+}
+
+
+int uv_fs_close(uv_loop_t* loop, uv_fs_t* req, uv_file fd, uv_fs_cb cb) {
+  INIT(UV_FS_CLOSE);
+  req->file.fd = fd;
+  POST;
+}
+
+
+int uv_fs_read(uv_loop_t* loop,
+               uv_fs_t* req,
+               uv_file fd,
+               const uv_buf_t bufs[],
+               unsigned int nbufs,
+               int64_t offset,
+               uv_fs_cb cb) {
+  INIT(UV_FS_READ);
+
+  if (bufs == NULL || nbufs == 0) {
+    SET_REQ_UV_ERROR(req, UV_EINVAL, ERROR_INVALID_PARAMETER);
+    return UV_EINVAL;
+  }
+
+  req->file.fd = fd;
+
+  req->fs.info.nbufs = nbufs;
+  req->fs.info.bufs = req->fs.info.bufsml;
+  if (nbufs > ARRAY_SIZE(req->fs.info.bufsml))
+    req->fs.info.bufs = (uv_buf_t*)uv__malloc(nbufs * sizeof(*bufs));
+
+  if (req->fs.info.bufs == NULL) {
+    SET_REQ_UV_ERROR(req, UV_ENOMEM, ERROR_OUTOFMEMORY);
+    return UV_ENOMEM;
+  }
+
+  memcpy(req->fs.info.bufs, bufs, nbufs * sizeof(*bufs));
+
+  req->fs.info.offset = offset;
+  POST;
+}
+
+
+int uv_fs_write(uv_loop_t* loop,
+                uv_fs_t* req,
+                uv_file fd,
+                const uv_buf_t bufs[],
+                unsigned int nbufs,
+                int64_t offset,
+                uv_fs_cb cb) {
+  INIT(UV_FS_WRITE);
+
+  if (bufs == NULL || nbufs == 0) {
+    SET_REQ_UV_ERROR(req, UV_EINVAL, ERROR_INVALID_PARAMETER);
+    return UV_EINVAL;
+  }
+
+  req->file.fd = fd;
+
+  req->fs.info.nbufs = nbufs;
+  req->fs.info.bufs = req->fs.info.bufsml;
+  if (nbufs > ARRAY_SIZE(req->fs.info.bufsml))
+    req->fs.info.bufs = (uv_buf_t*)uv__malloc(nbufs * sizeof(*bufs));
+
+  if (req->fs.info.bufs == NULL) {
+    SET_REQ_UV_ERROR(req, UV_ENOMEM, ERROR_OUTOFMEMORY);
+    return UV_ENOMEM;
+  }
+
+  memcpy(req->fs.info.bufs, bufs, nbufs * sizeof(*bufs));
+
+  req->fs.info.offset = offset;
+  POST;
+}
+
+
+int uv_fs_unlink(uv_loop_t* loop, uv_fs_t* req, const char* path,
+    uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_UNLINK);
+  err = fs__capture_path(req, path, NULL, cb != NULL);
+  if (err) {
+    SET_REQ_WIN32_ERROR(req, err);
+    return req->result;
+  }
+
+  POST;
+}
+
+
+int uv_fs_mkdir(uv_loop_t* loop, uv_fs_t* req, const char* path, int mode,
+    uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_MKDIR);
+  err = fs__capture_path(req, path, NULL, cb != NULL);
+  if (err) {
+    SET_REQ_WIN32_ERROR(req, err);
+    return req->result;
+  }
+
+  req->fs.info.mode = mode;
+  POST;
+}
+
+
+int uv_fs_mkdtemp(uv_loop_t* loop,
+                  uv_fs_t* req,
+                  const char* tpl,
+                  uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_MKDTEMP);
+  err = fs__capture_path(req, tpl, NULL, TRUE);
+  if (err) {
+    SET_REQ_WIN32_ERROR(req, err);
+    return req->result;
+  }
+
+  POST;
+}
+
+
+int uv_fs_mkstemp(uv_loop_t* loop,
+                  uv_fs_t* req,
+                  const char* tpl,
+                  uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_MKSTEMP);
+  err = fs__capture_path(req, tpl, NULL, TRUE);
+  if (err) {
+    SET_REQ_WIN32_ERROR(req, err);
+    return req->result;
+  }
+
+  POST;
+}
+
+
+int uv_fs_rmdir(uv_loop_t* loop, uv_fs_t* req, const char* path, uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_RMDIR);
+  err = fs__capture_path(req, path, NULL, cb != NULL);
+  if (err) {
+    SET_REQ_WIN32_ERROR(req, err);
+    return req->result;
+  }
+
+  POST;
+}
+
+
+int uv_fs_scandir(uv_loop_t* loop, uv_fs_t* req, const char* path, int flags,
+    uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_SCANDIR);
+  err = fs__capture_path(req, path, NULL, cb != NULL);
+  if (err) {
+    SET_REQ_WIN32_ERROR(req, err);
+    return req->result;
+  }
+
+  req->fs.info.file_flags = flags;
+  POST;
+}
+
+int uv_fs_opendir(uv_loop_t* loop,
+                  uv_fs_t* req,
+                  const char* path,
+                  uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_OPENDIR);
+  err = fs__capture_path(req, path, NULL, cb != NULL);
+  if (err) {
+    SET_REQ_WIN32_ERROR(req, err);
+    return req->result;
+  }
+  POST;
+}
+
+int uv_fs_readdir(uv_loop_t* loop,
+                  uv_fs_t* req,
+                  uv_dir_t* dir,
+                  uv_fs_cb cb) {
+  INIT(UV_FS_READDIR);
+
+  if (dir == NULL ||
+      dir->dirents == NULL ||
+      dir->dir_handle == INVALID_HANDLE_VALUE) {
+    SET_REQ_UV_ERROR(req, UV_EINVAL, ERROR_INVALID_PARAMETER);
+    return UV_EINVAL;
+  }
+
+  req->ptr = dir;
+  POST;
+}
+
+int uv_fs_closedir(uv_loop_t* loop,
+                   uv_fs_t* req,
+                   uv_dir_t* dir,
+                   uv_fs_cb cb) {
+  INIT(UV_FS_CLOSEDIR);
+  if (dir == NULL) {
+    SET_REQ_UV_ERROR(req, UV_EINVAL, ERROR_INVALID_PARAMETER);
+    return UV_EINVAL;
+  }
+  req->ptr = dir;
+  POST;
+}
+
+int uv_fs_link(uv_loop_t* loop, uv_fs_t* req, const char* path,
+    const char* new_path, uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_LINK);
+  err = fs__capture_path(req, path, new_path, cb != NULL);
+  if (err) {
+    SET_REQ_WIN32_ERROR(req, err);
+    return req->result;
+  }
+
+  POST;
+}
+
+
+int uv_fs_symlink(uv_loop_t* loop, uv_fs_t* req, const char* path,
+    const char* new_path, int flags, uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_SYMLINK);
+  err = fs__capture_path(req, path, new_path, cb != NULL);
+  if (err) {
+    SET_REQ_WIN32_ERROR(req, err);
+    return req->result;
+  }
+
+  req->fs.info.file_flags = flags;
+  POST;
+}
+
+
+int uv_fs_readlink(uv_loop_t* loop, uv_fs_t* req, const char* path,
+    uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_READLINK);
+  err = fs__capture_path(req, path, NULL, cb != NULL);
+  if (err) {
+    SET_REQ_WIN32_ERROR(req, err);
+    return req->result;
+  }
+
+  POST;
+}
+
+
+int uv_fs_realpath(uv_loop_t* loop, uv_fs_t* req, const char* path,
+    uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_REALPATH);
+
+  if (!path) {
+    SET_REQ_UV_ERROR(req, UV_EINVAL, ERROR_INVALID_PARAMETER);
+    return UV_EINVAL;
+  }
+
+  err = fs__capture_path(req, path, NULL, cb != NULL);
+  if (err) {
+    SET_REQ_WIN32_ERROR(req, err);
+    return req->result;
+  }
+
+  POST;
+}
+
+
+int uv_fs_chown(uv_loop_t* loop, uv_fs_t* req, const char* path, uv_uid_t uid,
+    uv_gid_t gid, uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_CHOWN);
+  err = fs__capture_path(req, path, NULL, cb != NULL);
+  if (err) {
+    SET_REQ_WIN32_ERROR(req, err);
+    return req->result;
+  }
+
+  POST;
+}
+
+
+int uv_fs_fchown(uv_loop_t* loop, uv_fs_t* req, uv_file fd, uv_uid_t uid,
+    uv_gid_t gid, uv_fs_cb cb) {
+  INIT(UV_FS_FCHOWN);
+  POST;
+}
+
+
+int uv_fs_lchown(uv_loop_t* loop, uv_fs_t* req, const char* path, uv_uid_t uid,
+    uv_gid_t gid, uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_LCHOWN);
+  err = fs__capture_path(req, path, NULL, cb != NULL);
+  if (err) {
+    SET_REQ_WIN32_ERROR(req, err);
+    return req->result;
+  }
+
+  POST;
+}
+
+
+int uv_fs_stat(uv_loop_t* loop, uv_fs_t* req, const char* path, uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_STAT);
+  err = fs__capture_path(req, path, NULL, cb != NULL);
+  if (err) {
+    SET_REQ_WIN32_ERROR(req, err);
+    return req->result;
+  }
+
+  POST;
+}
+
+
+int uv_fs_lstat(uv_loop_t* loop, uv_fs_t* req, const char* path, uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_LSTAT);
+  err = fs__capture_path(req, path, NULL, cb != NULL);
+  if (err) {
+    SET_REQ_WIN32_ERROR(req, err);
+    return req->result;
+  }
+
+  POST;
+}
+
+
+int uv_fs_fstat(uv_loop_t* loop, uv_fs_t* req, uv_file fd, uv_fs_cb cb) {
+  INIT(UV_FS_FSTAT);
+  req->file.fd = fd;
+  POST;
+}
+
+
+int uv_fs_rename(uv_loop_t* loop, uv_fs_t* req, const char* path,
+    const char* new_path, uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_RENAME);
+  err = fs__capture_path(req, path, new_path, cb != NULL);
+  if (err) {
+    SET_REQ_WIN32_ERROR(req, err);
+    return req->result;
+  }
+
+  POST;
+}
+
+
+int uv_fs_fsync(uv_loop_t* loop, uv_fs_t* req, uv_file fd, uv_fs_cb cb) {
+  INIT(UV_FS_FSYNC);
+  req->file.fd = fd;
+  POST;
+}
+
+
+int uv_fs_fdatasync(uv_loop_t* loop, uv_fs_t* req, uv_file fd, uv_fs_cb cb) {
+  INIT(UV_FS_FDATASYNC);
+  req->file.fd = fd;
+  POST;
+}
+
+
+int uv_fs_ftruncate(uv_loop_t* loop, uv_fs_t* req, uv_file fd,
+    int64_t offset, uv_fs_cb cb) {
+  INIT(UV_FS_FTRUNCATE);
+  req->file.fd = fd;
+  req->fs.info.offset = offset;
+  POST;
+}
+
+
+int uv_fs_copyfile(uv_loop_t* loop,
+                   uv_fs_t* req,
+                   const char* path,
+                   const char* new_path,
+                   int flags,
+                   uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_COPYFILE);
+
+  if (flags & ~(UV_FS_COPYFILE_EXCL |
+                UV_FS_COPYFILE_FICLONE |
+                UV_FS_COPYFILE_FICLONE_FORCE)) {
+    SET_REQ_UV_ERROR(req, UV_EINVAL, ERROR_INVALID_PARAMETER);
+    return UV_EINVAL;
+  }
+
+  err = fs__capture_path(req, path, new_path, cb != NULL);
+  if (err) {
+    SET_REQ_WIN32_ERROR(req, err);
+    return req->result;
+  }
+
+  req->fs.info.file_flags = flags;
+  POST;
+}
+
+
+int uv_fs_sendfile(uv_loop_t* loop, uv_fs_t* req, uv_file fd_out,
+    uv_file fd_in, int64_t in_offset, size_t length, uv_fs_cb cb) {
+  INIT(UV_FS_SENDFILE);
+  req->file.fd = fd_in;
+  req->fs.info.fd_out = fd_out;
+  req->fs.info.offset = in_offset;
+  req->fs.info.bufsml[0].len = length;
+  POST;
+}
+
+
+int uv_fs_access(uv_loop_t* loop,
+                 uv_fs_t* req,
+                 const char* path,
+                 int flags,
+                 uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_ACCESS);
+  err = fs__capture_path(req, path, NULL, cb != NULL);
+  if (err) {
+    SET_REQ_WIN32_ERROR(req, err);
+    return req->result;
+  }
+
+  req->fs.info.mode = flags;
+  POST;
+}
+
+
+int uv_fs_chmod(uv_loop_t* loop, uv_fs_t* req, const char* path, int mode,
+    uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_CHMOD);
+  err = fs__capture_path(req, path, NULL, cb != NULL);
+  if (err) {
+    SET_REQ_WIN32_ERROR(req, err);
+    return req->result;
+  }
+
+  req->fs.info.mode = mode;
+  POST;
+}
+
+
+int uv_fs_fchmod(uv_loop_t* loop, uv_fs_t* req, uv_file fd, int mode,
+    uv_fs_cb cb) {
+  INIT(UV_FS_FCHMOD);
+  req->file.fd = fd;
+  req->fs.info.mode = mode;
+  POST;
+}
+
+
+int uv_fs_utime(uv_loop_t* loop, uv_fs_t* req, const char* path, double atime,
+    double mtime, uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_UTIME);
+  err = fs__capture_path(req, path, NULL, cb != NULL);
+  if (err) {
+    SET_REQ_WIN32_ERROR(req, err);
+    return req->result;
+  }
+
+  req->fs.time.atime = atime;
+  req->fs.time.mtime = mtime;
+  POST;
+}
+
+
+int uv_fs_futime(uv_loop_t* loop, uv_fs_t* req, uv_file fd, double atime,
+    double mtime, uv_fs_cb cb) {
+  INIT(UV_FS_FUTIME);
+  req->file.fd = fd;
+  req->fs.time.atime = atime;
+  req->fs.time.mtime = mtime;
+  POST;
+}
+
+int uv_fs_lutime(uv_loop_t* loop, uv_fs_t* req, const char* path, double atime,
+    double mtime, uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_LUTIME);
+  err = fs__capture_path(req, path, NULL, cb != NULL);
+  if (err) {
+    SET_REQ_WIN32_ERROR(req, err);
+    return req->result;
+  }
+
+  req->fs.time.atime = atime;
+  req->fs.time.mtime = mtime;
+  POST;
+}
+
+
+int uv_fs_statfs(uv_loop_t* loop,
+                 uv_fs_t* req,
+                 const char* path,
+                 uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_STATFS);
+  err = fs__capture_path(req, path, NULL, cb != NULL);
+  if (err) {
+    SET_REQ_WIN32_ERROR(req, err);
+    return req->result;
+  }
+
+  POST;
+}
+
+int uv_fs_get_system_error(const uv_fs_t* req) {
+  return req->sys_errno_;
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/getaddrinfo.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/getaddrinfo.cpp
similarity index 100%
rename from third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/getaddrinfo.cpp
rename to third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/getaddrinfo.cpp
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/getnameinfo.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/getnameinfo.cpp
similarity index 100%
rename from third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/getnameinfo.cpp
rename to third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/getnameinfo.cpp
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/handle-inl.h b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/handle-inl.h
new file mode 100644
index 0000000..5c843c2
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/handle-inl.h
@@ -0,0 +1,180 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#ifndef UV_WIN_HANDLE_INL_H_
+#define UV_WIN_HANDLE_INL_H_
+
+#include <assert.h>
+#include <io.h>
+
+#include "uv.h"
+#include "internal.h"
+
+
+#define DECREASE_ACTIVE_COUNT(loop, handle)                             \
+  do {                                                                  \
+    if (--(handle)->activecnt == 0 &&                                   \
+        !((handle)->flags & UV_HANDLE_CLOSING)) {                       \
+      uv__handle_stop((handle));                                        \
+    }                                                                   \
+    assert((handle)->activecnt >= 0);                                   \
+  } while (0)
+
+
+#define INCREASE_ACTIVE_COUNT(loop, handle)                             \
+  do {                                                                  \
+    if ((handle)->activecnt++ == 0) {                                   \
+      uv__handle_start((handle));                                       \
+    }                                                                   \
+    assert((handle)->activecnt > 0);                                    \
+  } while (0)
+
+
+#define DECREASE_PENDING_REQ_COUNT(handle)                              \
+  do {                                                                  \
+    assert(handle->reqs_pending > 0);                                   \
+    handle->reqs_pending--;                                             \
+                                                                        \
+    if (handle->flags & UV_HANDLE_CLOSING &&                            \
+        handle->reqs_pending == 0) {                                    \
+      uv__want_endgame(loop, (uv_handle_t*)handle);                     \
+    }                                                                   \
+  } while (0)
+
+
+#define uv__handle_closing(handle)                                      \
+  do {                                                                  \
+    assert(!((handle)->flags & UV_HANDLE_CLOSING));                     \
+                                                                        \
+    if (!(((handle)->flags & UV_HANDLE_ACTIVE) &&                       \
+          ((handle)->flags & UV_HANDLE_REF)))                           \
+      uv__active_handle_add((uv_handle_t*) (handle));                   \
+                                                                        \
+    (handle)->flags |= UV_HANDLE_CLOSING;                               \
+    (handle)->flags &= ~UV_HANDLE_ACTIVE;                               \
+  } while (0)
+
+
+#define uv__handle_close(handle)                                        \
+  do {                                                                  \
+    QUEUE_REMOVE(&(handle)->handle_queue);                              \
+    uv__active_handle_rm((uv_handle_t*) (handle));                      \
+                                                                        \
+    (handle)->flags |= UV_HANDLE_CLOSED;                                \
+                                                                        \
+    if ((handle)->close_cb)                                             \
+      (handle)->close_cb((uv_handle_t*) (handle));                      \
+  } while (0)
+
+
+INLINE static void uv__want_endgame(uv_loop_t* loop, uv_handle_t* handle) {
+  if (!(handle->flags & UV_HANDLE_ENDGAME_QUEUED)) {
+    handle->flags |= UV_HANDLE_ENDGAME_QUEUED;
+
+    handle->endgame_next = loop->endgame_handles;
+    loop->endgame_handles = handle;
+  }
+}
+
+
+INLINE static void uv__process_endgames(uv_loop_t* loop) {
+  uv_handle_t* handle;
+
+  while (loop->endgame_handles) {
+    handle = loop->endgame_handles;
+    loop->endgame_handles = handle->endgame_next;
+
+    handle->flags &= ~UV_HANDLE_ENDGAME_QUEUED;
+
+    switch (handle->type) {
+      case UV_TCP:
+        uv__tcp_endgame(loop, (uv_tcp_t*) handle);
+        break;
+
+      case UV_NAMED_PIPE:
+        uv__pipe_endgame(loop, (uv_pipe_t*) handle);
+        break;
+
+      case UV_TTY:
+        uv__tty_endgame(loop, (uv_tty_t*) handle);
+        break;
+
+      case UV_UDP:
+        uv__udp_endgame(loop, (uv_udp_t*) handle);
+        break;
+
+      case UV_POLL:
+        uv__poll_endgame(loop, (uv_poll_t*) handle);
+        break;
+
+      case UV_TIMER:
+        uv__timer_close((uv_timer_t*) handle);
+        uv__handle_close(handle);
+        break;
+
+      case UV_PREPARE:
+      case UV_CHECK:
+      case UV_IDLE:
+        uv__loop_watcher_endgame(loop, handle);
+        break;
+
+      case UV_ASYNC:
+        uv__async_endgame(loop, (uv_async_t*) handle);
+        break;
+
+      case UV_SIGNAL:
+        uv__signal_endgame(loop, (uv_signal_t*) handle);
+        break;
+
+      case UV_PROCESS:
+        uv__process_endgame(loop, (uv_process_t*) handle);
+        break;
+
+      case UV_FS_EVENT:
+        uv__fs_event_endgame(loop, (uv_fs_event_t*) handle);
+        break;
+
+      case UV_FS_POLL:
+        uv__fs_poll_endgame(loop, (uv_fs_poll_t*) handle);
+        break;
+
+      default:
+        assert(0);
+        break;
+    }
+  }
+}
+
+INLINE static HANDLE uv__get_osfhandle(int fd)
+{
+  /* _get_osfhandle() raises an assert in debug builds if the FD is invalid.
+   * But it also correctly checks the FD and returns INVALID_HANDLE_VALUE for
+   * invalid FDs in release builds (or if you let the assert continue). So this
+   * wrapper function disables asserts when calling _get_osfhandle. */
+
+  HANDLE handle;
+  UV_BEGIN_DISABLE_CRT_ASSERT();
+  handle = (HANDLE) _get_osfhandle(fd);
+  UV_END_DISABLE_CRT_ASSERT();
+  return handle;
+}
+
+#endif /* UV_WIN_HANDLE_INL_H_ */
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/handle.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/handle.cpp
new file mode 100644
index 0000000..53a81fd
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/handle.cpp
@@ -0,0 +1,162 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <assert.h>
+#include <io.h>
+#include <stdlib.h>
+
+#include "uv.h"
+#include "internal.h"
+#include "handle-inl.h"
+
+
+uv_handle_type uv_guess_handle(uv_file file) {
+  HANDLE handle;
+  DWORD mode;
+
+  if (file < 0) {
+    return UV_UNKNOWN_HANDLE;
+  }
+
+  handle = uv__get_osfhandle(file);
+
+  switch (GetFileType(handle)) {
+    case FILE_TYPE_CHAR:
+      if (GetConsoleMode(handle, &mode)) {
+        return UV_TTY;
+      } else {
+        return UV_FILE;
+      }
+
+    case FILE_TYPE_PIPE:
+      return UV_NAMED_PIPE;
+
+    case FILE_TYPE_DISK:
+      return UV_FILE;
+
+    default:
+      return UV_UNKNOWN_HANDLE;
+  }
+}
+
+
+int uv_is_active(const uv_handle_t* handle) {
+  return (handle->flags & UV_HANDLE_ACTIVE) &&
+        !(handle->flags & UV_HANDLE_CLOSING);
+}
+
+
+void uv_close(uv_handle_t* handle, uv_close_cb cb) {
+  uv_loop_t* loop = handle->loop;
+
+  if (handle->flags & UV_HANDLE_CLOSING) {
+    assert(0);
+    return;
+  }
+
+  handle->close_cb = cb;
+
+  /* Handle-specific close actions */
+  switch (handle->type) {
+    case UV_TCP:
+      uv__tcp_close(loop, (uv_tcp_t*)handle);
+      return;
+
+    case UV_NAMED_PIPE:
+      uv__pipe_close(loop, (uv_pipe_t*) handle);
+      return;
+
+    case UV_TTY:
+      uv__tty_close((uv_tty_t*) handle);
+      return;
+
+    case UV_UDP:
+      uv__udp_close(loop, (uv_udp_t*) handle);
+      return;
+
+    case UV_POLL:
+      uv__poll_close(loop, (uv_poll_t*) handle);
+      return;
+
+    case UV_TIMER:
+      uv_timer_stop((uv_timer_t*)handle);
+      uv__handle_closing(handle);
+      uv__want_endgame(loop, handle);
+      return;
+
+    case UV_PREPARE:
+      uv_prepare_stop((uv_prepare_t*)handle);
+      uv__handle_closing(handle);
+      uv__want_endgame(loop, handle);
+      return;
+
+    case UV_CHECK:
+      uv_check_stop((uv_check_t*)handle);
+      uv__handle_closing(handle);
+      uv__want_endgame(loop, handle);
+      return;
+
+    case UV_IDLE:
+      uv_idle_stop((uv_idle_t*)handle);
+      uv__handle_closing(handle);
+      uv__want_endgame(loop, handle);
+      return;
+
+    case UV_ASYNC:
+      uv__async_close(loop, (uv_async_t*) handle);
+      return;
+
+    case UV_SIGNAL:
+      uv__signal_close(loop, (uv_signal_t*) handle);
+      return;
+
+    case UV_PROCESS:
+      uv__process_close(loop, (uv_process_t*) handle);
+      return;
+
+    case UV_FS_EVENT:
+      uv__fs_event_close(loop, (uv_fs_event_t*) handle);
+      return;
+
+    case UV_FS_POLL:
+      uv__fs_poll_close((uv_fs_poll_t*) handle);
+      uv__handle_closing(handle);
+      return;
+
+    default:
+      /* Not supported */
+      abort();
+  }
+}
+
+
+int uv_is_closing(const uv_handle_t* handle) {
+  return !!(handle->flags & (UV_HANDLE_CLOSING | UV_HANDLE_CLOSED));
+}
+
+
+uv_os_fd_t uv_get_osfhandle(int fd) {
+  return uv__get_osfhandle(fd);
+}
+
+int uv_open_osfhandle(uv_os_fd_t os_fd) {
+  return _open_osfhandle((intptr_t) os_fd, 0);
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/internal.h b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/internal.h
new file mode 100644
index 0000000..89c72b8
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/internal.h
@@ -0,0 +1,343 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#ifndef UV_WIN_INTERNAL_H_
+#define UV_WIN_INTERNAL_H_
+
+#include "uv.h"
+#include "../uv-common.h"
+
+#include "uv/tree.h"
+#include "winapi.h"
+#include "winsock.h"
+
+#ifdef _MSC_VER
+# define INLINE __inline
+# define UV_THREAD_LOCAL __declspec( thread )
+#else
+# define INLINE inline
+# define UV_THREAD_LOCAL __thread
+#endif
+
+
+#ifdef _DEBUG
+
+extern UV_THREAD_LOCAL int uv__crt_assert_enabled;
+
+#define UV_BEGIN_DISABLE_CRT_ASSERT()                           \
+  {                                                             \
+    int uv__saved_crt_assert_enabled = uv__crt_assert_enabled;  \
+    uv__crt_assert_enabled = FALSE;
+
+
+#define UV_END_DISABLE_CRT_ASSERT()                             \
+    uv__crt_assert_enabled = uv__saved_crt_assert_enabled;      \
+  }
+
+#else
+#define UV_BEGIN_DISABLE_CRT_ASSERT()
+#define UV_END_DISABLE_CRT_ASSERT()
+#endif
+
+/*
+ * TCP
+ */
+
+typedef enum {
+  UV__IPC_SOCKET_XFER_NONE = 0,
+  UV__IPC_SOCKET_XFER_TCP_CONNECTION,
+  UV__IPC_SOCKET_XFER_TCP_SERVER
+} uv__ipc_socket_xfer_type_t;
+
+typedef struct {
+  WSAPROTOCOL_INFOW socket_info;
+  uint32_t delayed_error;
+} uv__ipc_socket_xfer_info_t;
+
+int uv__tcp_listen(uv_tcp_t* handle, int backlog, uv_connection_cb cb);
+int uv__tcp_accept(uv_tcp_t* server, uv_tcp_t* client);
+int uv__tcp_read_start(uv_tcp_t* handle, uv_alloc_cb alloc_cb,
+    uv_read_cb read_cb);
+int uv__tcp_write(uv_loop_t* loop, uv_write_t* req, uv_tcp_t* handle,
+    const uv_buf_t bufs[], unsigned int nbufs, uv_write_cb cb);
+int uv__tcp_try_write(uv_tcp_t* handle, const uv_buf_t bufs[],
+    unsigned int nbufs);
+
+void uv__process_tcp_read_req(uv_loop_t* loop, uv_tcp_t* handle, uv_req_t* req);
+void uv__process_tcp_write_req(uv_loop_t* loop, uv_tcp_t* handle,
+    uv_write_t* req);
+void uv__process_tcp_accept_req(uv_loop_t* loop, uv_tcp_t* handle,
+    uv_req_t* req);
+void uv__process_tcp_connect_req(uv_loop_t* loop, uv_tcp_t* handle,
+    uv_connect_t* req);
+void uv__process_tcp_shutdown_req(uv_loop_t* loop,
+                                  uv_tcp_t* stream,
+                                  uv_shutdown_t* req);
+
+void uv__tcp_close(uv_loop_t* loop, uv_tcp_t* tcp);
+void uv__tcp_endgame(uv_loop_t* loop, uv_tcp_t* handle);
+
+int uv__tcp_xfer_export(uv_tcp_t* handle,
+                        int pid,
+                        uv__ipc_socket_xfer_type_t* xfer_type,
+                        uv__ipc_socket_xfer_info_t* xfer_info);
+int uv__tcp_xfer_import(uv_tcp_t* tcp,
+                        uv__ipc_socket_xfer_type_t xfer_type,
+                        uv__ipc_socket_xfer_info_t* xfer_info);
+
+
+/*
+ * UDP
+ */
+void uv__process_udp_recv_req(uv_loop_t* loop, uv_udp_t* handle, uv_req_t* req);
+void uv__process_udp_send_req(uv_loop_t* loop, uv_udp_t* handle,
+    uv_udp_send_t* req);
+
+void uv__udp_close(uv_loop_t* loop, uv_udp_t* handle);
+void uv__udp_endgame(uv_loop_t* loop, uv_udp_t* handle);
+
+
+/*
+ * Pipes
+ */
+int uv__create_stdio_pipe_pair(uv_loop_t* loop,
+    uv_pipe_t* parent_pipe, HANDLE* child_pipe_ptr, unsigned int flags);
+
+int uv__pipe_listen(uv_pipe_t* handle, int backlog, uv_connection_cb cb);
+int uv__pipe_accept(uv_pipe_t* server, uv_stream_t* client);
+int uv__pipe_read_start(uv_pipe_t* handle, uv_alloc_cb alloc_cb,
+    uv_read_cb read_cb);
+void uv__pipe_read_stop(uv_pipe_t* handle);
+int uv__pipe_write(uv_loop_t* loop,
+                   uv_write_t* req,
+                   uv_pipe_t* handle,
+                   const uv_buf_t bufs[],
+                   size_t nbufs,
+                   uv_stream_t* send_handle,
+                   uv_write_cb cb);
+void uv__pipe_shutdown(uv_loop_t* loop, uv_pipe_t* handle, uv_shutdown_t* req);
+
+void uv__process_pipe_read_req(uv_loop_t* loop, uv_pipe_t* handle,
+    uv_req_t* req);
+void uv__process_pipe_write_req(uv_loop_t* loop, uv_pipe_t* handle,
+    uv_write_t* req);
+void uv__process_pipe_accept_req(uv_loop_t* loop, uv_pipe_t* handle,
+    uv_req_t* raw_req);
+void uv__process_pipe_connect_req(uv_loop_t* loop, uv_pipe_t* handle,
+    uv_connect_t* req);
+void uv__process_pipe_shutdown_req(uv_loop_t* loop, uv_pipe_t* handle,
+    uv_shutdown_t* req);
+
+void uv__pipe_close(uv_loop_t* loop, uv_pipe_t* handle);
+void uv__pipe_endgame(uv_loop_t* loop, uv_pipe_t* handle);
+
+
+/*
+ * TTY
+ */
+void uv__console_init(void);
+
+int uv__tty_read_start(uv_tty_t* handle, uv_alloc_cb alloc_cb,
+    uv_read_cb read_cb);
+int uv__tty_read_stop(uv_tty_t* handle);
+int uv__tty_write(uv_loop_t* loop, uv_write_t* req, uv_tty_t* handle,
+    const uv_buf_t bufs[], unsigned int nbufs, uv_write_cb cb);
+int uv__tty_try_write(uv_tty_t* handle, const uv_buf_t bufs[],
+    unsigned int nbufs);
+void uv__tty_close(uv_tty_t* handle);
+
+void uv__process_tty_read_req(uv_loop_t* loop, uv_tty_t* handle,
+    uv_req_t* req);
+void uv__process_tty_write_req(uv_loop_t* loop, uv_tty_t* handle,
+    uv_write_t* req);
+/*
+ * uv__process_tty_accept_req() is a stub to keep DELEGATE_STREAM_REQ working
+ * TODO: find a way to remove it
+ */
+void uv__process_tty_accept_req(uv_loop_t* loop, uv_tty_t* handle,
+    uv_req_t* raw_req);
+/*
+ * uv__process_tty_connect_req() is a stub to keep DELEGATE_STREAM_REQ working
+ * TODO: find a way to remove it
+ */
+void uv__process_tty_connect_req(uv_loop_t* loop, uv_tty_t* handle,
+    uv_connect_t* req);
+void uv__process_tty_shutdown_req(uv_loop_t* loop,
+                                  uv_tty_t* stream,
+                                  uv_shutdown_t* req);
+void uv__tty_endgame(uv_loop_t* loop, uv_tty_t* handle);
+
+
+/*
+ * Poll watchers
+ */
+void uv__process_poll_req(uv_loop_t* loop, uv_poll_t* handle,
+    uv_req_t* req);
+
+int uv__poll_close(uv_loop_t* loop, uv_poll_t* handle);
+void uv__poll_endgame(uv_loop_t* loop, uv_poll_t* handle);
+
+
+/*
+ * Loop watchers
+ */
+void uv__loop_watcher_endgame(uv_loop_t* loop, uv_handle_t* handle);
+
+void uv__prepare_invoke(uv_loop_t* loop);
+void uv__check_invoke(uv_loop_t* loop);
+void uv__idle_invoke(uv_loop_t* loop);
+
+void uv__once_init(void);
+
+
+/*
+ * Async watcher
+ */
+void uv__async_close(uv_loop_t* loop, uv_async_t* handle);
+void uv__async_endgame(uv_loop_t* loop, uv_async_t* handle);
+
+void uv__process_async_wakeup_req(uv_loop_t* loop, uv_async_t* handle,
+    uv_req_t* req);
+
+
+/*
+ * Signal watcher
+ */
+void uv__signals_init(void);
+int uv__signal_dispatch(int signum);
+
+void uv__signal_close(uv_loop_t* loop, uv_signal_t* handle);
+void uv__signal_endgame(uv_loop_t* loop, uv_signal_t* handle);
+
+void uv__process_signal_req(uv_loop_t* loop, uv_signal_t* handle,
+    uv_req_t* req);
+
+
+/*
+ * Spawn
+ */
+void uv__process_proc_exit(uv_loop_t* loop, uv_process_t* handle);
+void uv__process_close(uv_loop_t* loop, uv_process_t* handle);
+void uv__process_endgame(uv_loop_t* loop, uv_process_t* handle);
+
+
+/*
+ * FS
+ */
+void uv__fs_init(void);
+
+
+/*
+ * FS Event
+ */
+void uv__process_fs_event_req(uv_loop_t* loop, uv_req_t* req,
+    uv_fs_event_t* handle);
+void uv__fs_event_close(uv_loop_t* loop, uv_fs_event_t* handle);
+void uv__fs_event_endgame(uv_loop_t* loop, uv_fs_event_t* handle);
+
+
+/*
+ * Stat poller.
+ */
+void uv__fs_poll_endgame(uv_loop_t* loop, uv_fs_poll_t* handle);
+
+
+/*
+ * Utilities.
+ */
+void uv__util_init(void);
+
+uint64_t uv__hrtime(unsigned int scale);
+__declspec(noreturn) void uv_fatal_error(const int errorno, const char* syscall);
+int uv__getpwuid_r(uv_passwd_t* pwd);
+int uv__convert_utf16_to_utf8(const WCHAR* utf16, int utf16len, char** utf8);
+int uv__convert_utf8_to_utf16(const char* utf8, int utf8len, WCHAR** utf16);
+
+typedef int (WINAPI *uv__peersockfunc)(SOCKET, struct sockaddr*, int*);
+
+int uv__getsockpeername(const uv_handle_t* handle,
+                        uv__peersockfunc func,
+                        struct sockaddr* name,
+                        int* namelen,
+                        int delayed_error);
+
+int uv__random_rtlgenrandom(void* buf, size_t buflen);
+
+
+/*
+ * Process stdio handles.
+ */
+int uv__stdio_create(uv_loop_t* loop,
+                     const uv_process_options_t* options,
+                     BYTE** buffer_ptr);
+void uv__stdio_destroy(BYTE* buffer);
+void uv__stdio_noinherit(BYTE* buffer);
+int uv__stdio_verify(BYTE* buffer, WORD size);
+WORD uv__stdio_size(BYTE* buffer);
+HANDLE uv__stdio_handle(BYTE* buffer, int fd);
+
+
+/*
+ * Winapi and ntapi utility functions
+ */
+void uv__winapi_init(void);
+
+
+/*
+ * Winsock utility functions
+ */
+void uv__winsock_init(void);
+
+int uv__ntstatus_to_winsock_error(NTSTATUS status);
+
+BOOL uv__get_acceptex_function(SOCKET socket, LPFN_ACCEPTEX* target);
+BOOL uv__get_connectex_function(SOCKET socket, LPFN_CONNECTEX* target);
+
+int WSAAPI uv__wsarecv_workaround(SOCKET socket, WSABUF* buffers,
+    DWORD buffer_count, DWORD* bytes, DWORD* flags, WSAOVERLAPPED *overlapped,
+    LPWSAOVERLAPPED_COMPLETION_ROUTINE completion_routine);
+int WSAAPI uv__wsarecvfrom_workaround(SOCKET socket, WSABUF* buffers,
+    DWORD buffer_count, DWORD* bytes, DWORD* flags, struct sockaddr* addr,
+    int* addr_len, WSAOVERLAPPED *overlapped,
+    LPWSAOVERLAPPED_COMPLETION_ROUTINE completion_routine);
+
+int WSAAPI uv__msafd_poll(SOCKET socket, AFD_POLL_INFO* info_in,
+    AFD_POLL_INFO* info_out, OVERLAPPED* overlapped);
+
+/* Whether there are any non-IFS LSPs stacked on TCP */
+extern int uv_tcp_non_ifs_lsp_ipv4;
+extern int uv_tcp_non_ifs_lsp_ipv6;
+
+/* Ip address used to bind to any port at any interface */
+extern struct sockaddr_in uv_addr_ip4_any_;
+extern struct sockaddr_in6 uv_addr_ip6_any_;
+
+/*
+ * Wake all loops with fake message
+ */
+void uv__wake_all_loops(void);
+
+/*
+ * Init system wake-up detection
+ */
+void uv__init_detect_system_wakeup(void);
+
+#endif /* UV_WIN_INTERNAL_H_ */
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/loop-watcher.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/loop-watcher.cpp
new file mode 100644
index 0000000..fad9e8a
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/loop-watcher.cpp
@@ -0,0 +1,122 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <assert.h>
+
+#include "uv.h"
+#include "internal.h"
+#include "handle-inl.h"
+
+
+void uv__loop_watcher_endgame(uv_loop_t* loop, uv_handle_t* handle) {
+  if (handle->flags & UV_HANDLE_CLOSING) {
+    assert(!(handle->flags & UV_HANDLE_CLOSED));
+    handle->flags |= UV_HANDLE_CLOSED;
+    uv__handle_close(handle);
+  }
+}
+
+
+#define UV_LOOP_WATCHER_DEFINE(name, NAME)                                    \
+  int uv_##name##_init(uv_loop_t* loop, uv_##name##_t* handle) {              \
+    uv__handle_init(loop, (uv_handle_t*) handle, UV_##NAME);                  \
+                                                                              \
+    return 0;                                                                 \
+  }                                                                           \
+                                                                              \
+                                                                              \
+  int uv_##name##_start(uv_##name##_t* handle, uv_##name##_cb cb) {           \
+    uv_loop_t* loop = handle->loop;                                           \
+    uv_##name##_t* old_head;                                                  \
+                                                                              \
+    assert(handle->type == UV_##NAME);                                        \
+                                                                              \
+    if (uv__is_active(handle))                                                \
+      return 0;                                                               \
+                                                                              \
+    if (cb == NULL)                                                           \
+      return UV_EINVAL;                                                       \
+                                                                              \
+    old_head = loop->name##_handles;                                          \
+                                                                              \
+    handle->name##_next = old_head;                                           \
+    handle->name##_prev = NULL;                                               \
+                                                                              \
+    if (old_head) {                                                           \
+      old_head->name##_prev = handle;                                         \
+    }                                                                         \
+                                                                              \
+    loop->name##_handles = handle;                                            \
+                                                                              \
+    handle->name##_cb = cb;                                                   \
+    uv__handle_start(handle);                                                 \
+                                                                              \
+    return 0;                                                                 \
+  }                                                                           \
+                                                                              \
+                                                                              \
+  int uv_##name##_stop(uv_##name##_t* handle) {                               \
+    uv_loop_t* loop = handle->loop;                                           \
+                                                                              \
+    assert(handle->type == UV_##NAME);                                        \
+                                                                              \
+    if (!uv__is_active(handle))                                               \
+      return 0;                                                               \
+                                                                              \
+    /* Update loop head if needed */                                          \
+    if (loop->name##_handles == handle) {                                     \
+      loop->name##_handles = handle->name##_next;                             \
+    }                                                                         \
+                                                                              \
+    /* Update the iterator-next pointer of needed */                          \
+    if (loop->next_##name##_handle == handle) {                               \
+      loop->next_##name##_handle = handle->name##_next;                       \
+    }                                                                         \
+                                                                              \
+    if (handle->name##_prev) {                                                \
+      handle->name##_prev->name##_next = handle->name##_next;                 \
+    }                                                                         \
+    if (handle->name##_next) {                                                \
+      handle->name##_next->name##_prev = handle->name##_prev;                 \
+    }                                                                         \
+                                                                              \
+    uv__handle_stop(handle);                                                  \
+                                                                              \
+    return 0;                                                                 \
+  }                                                                           \
+                                                                              \
+                                                                              \
+  void uv__##name##_invoke(uv_loop_t* loop) {                                 \
+    uv_##name##_t* handle;                                                    \
+                                                                              \
+    (loop)->next_##name##_handle = (loop)->name##_handles;                    \
+                                                                              \
+    while ((loop)->next_##name##_handle != NULL) {                            \
+      handle = (loop)->next_##name##_handle;                                  \
+      (loop)->next_##name##_handle = handle->name##_next;                     \
+                                                                              \
+      handle->name##_cb(handle);                                              \
+    }                                                                         \
+  }
+
+UV_LOOP_WATCHER_DEFINE(prepare, PREPARE)
+UV_LOOP_WATCHER_DEFINE(check, CHECK)
+UV_LOOP_WATCHER_DEFINE(idle, IDLE)
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/pipe.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/pipe.cpp
new file mode 100644
index 0000000..f413a72
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/pipe.cpp
@@ -0,0 +1,2643 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#define _CRT_NONSTDC_NO_WARNINGS
+
+#include <assert.h>
+#include <io.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+
+#include "handle-inl.h"
+#include "internal.h"
+#include "req-inl.h"
+#include "stream-inl.h"
+#include "uv-common.h"
+#include "uv.h"
+
+#include <aclapi.h>
+#include <accctrl.h>
+
+/* A zero-size buffer for use by uv_pipe_read */
+static char uv_zero_[] = "";
+
+/* Null uv_buf_t */
+static const uv_buf_t uv_null_buf_ = { 0, NULL };
+
+/* The timeout that the pipe will wait for the remote end to write data when
+ * the local ends wants to shut it down. */
+static const int64_t eof_timeout = 50; /* ms */
+
+static const int default_pending_pipe_instances = 4;
+
+/* Pipe prefix */
+static char pipe_prefix[] = "\\\\?\\pipe";
+static const int pipe_prefix_len = sizeof(pipe_prefix) - 1;
+
+/* IPC incoming xfer queue item. */
+typedef struct {
+  uv__ipc_socket_xfer_type_t xfer_type;
+  uv__ipc_socket_xfer_info_t xfer_info;
+  QUEUE member;
+} uv__ipc_xfer_queue_item_t;
+
+/* IPC frame header flags. */
+/* clang-format off */
+enum {
+  UV__IPC_FRAME_HAS_DATA                = 0x01,
+  UV__IPC_FRAME_HAS_SOCKET_XFER         = 0x02,
+  UV__IPC_FRAME_XFER_IS_TCP_CONNECTION  = 0x04,
+  /* These are combinations of the flags above. */
+  UV__IPC_FRAME_XFER_FLAGS              = 0x06,
+  UV__IPC_FRAME_VALID_FLAGS             = 0x07
+};
+/* clang-format on */
+
+/* IPC frame header. */
+typedef struct {
+  uint32_t flags;
+  uint32_t reserved1;   /* Ignored. */
+  uint32_t data_length; /* Must be zero if there is no data. */
+  uint32_t reserved2;   /* Must be zero. */
+} uv__ipc_frame_header_t;
+
+/* To implement the IPC protocol correctly, these structures must have exactly
+ * the right size. */
+STATIC_ASSERT(sizeof(uv__ipc_frame_header_t) == 16);
+STATIC_ASSERT(sizeof(uv__ipc_socket_xfer_info_t) == 632);
+
+/* Coalesced write request. */
+typedef struct {
+  uv_write_t req;       /* Internal heap-allocated write request. */
+  uv_write_t* user_req; /* Pointer to user-specified uv_write_t. */
+} uv__coalesced_write_t;
+
+
+static void eof_timer_init(uv_pipe_t* pipe);
+static void eof_timer_start(uv_pipe_t* pipe);
+static void eof_timer_stop(uv_pipe_t* pipe);
+static void eof_timer_cb(uv_timer_t* timer);
+static void eof_timer_destroy(uv_pipe_t* pipe);
+static void eof_timer_close_cb(uv_handle_t* handle);
+
+
+static void uv__unique_pipe_name(char* ptr, char* name, size_t size) {
+  snprintf(name, size, "\\\\?\\pipe\\uv\\%p-%lu", ptr, GetCurrentProcessId());
+}
+
+
+int uv_pipe_init(uv_loop_t* loop, uv_pipe_t* handle, int ipc) {
+  uv__stream_init(loop, (uv_stream_t*)handle, UV_NAMED_PIPE);
+
+  handle->reqs_pending = 0;
+  handle->handle = INVALID_HANDLE_VALUE;
+  handle->name = NULL;
+  handle->pipe.conn.ipc_remote_pid = 0;
+  handle->pipe.conn.ipc_data_frame.payload_remaining = 0;
+  QUEUE_INIT(&handle->pipe.conn.ipc_xfer_queue);
+  handle->pipe.conn.ipc_xfer_queue_length = 0;
+  handle->ipc = ipc;
+  handle->pipe.conn.non_overlapped_writes_tail = NULL;
+
+  return 0;
+}
+
+
+static void uv__pipe_connection_init(uv_pipe_t* handle) {
+  assert(!(handle->flags & UV_HANDLE_PIPESERVER));
+  uv__connection_init((uv_stream_t*) handle);
+  handle->read_req.data = handle;
+  handle->pipe.conn.eof_timer = NULL;
+}
+
+
+static HANDLE open_named_pipe(const WCHAR* name, DWORD* duplex_flags) {
+  HANDLE pipeHandle;
+
+  /*
+   * Assume that we have a duplex pipe first, so attempt to
+   * connect with GENERIC_READ | GENERIC_WRITE.
+   */
+  pipeHandle = CreateFileW(name,
+                           GENERIC_READ | GENERIC_WRITE,
+                           0,
+                           NULL,
+                           OPEN_EXISTING,
+                           FILE_FLAG_OVERLAPPED,
+                           NULL);
+  if (pipeHandle != INVALID_HANDLE_VALUE) {
+    *duplex_flags = UV_HANDLE_READABLE | UV_HANDLE_WRITABLE;
+    return pipeHandle;
+  }
+
+  /*
+   * If the pipe is not duplex CreateFileW fails with
+   * ERROR_ACCESS_DENIED.  In that case try to connect
+   * as a read-only or write-only.
+   */
+  if (GetLastError() == ERROR_ACCESS_DENIED) {
+    pipeHandle = CreateFileW(name,
+                             GENERIC_READ | FILE_WRITE_ATTRIBUTES,
+                             0,
+                             NULL,
+                             OPEN_EXISTING,
+                             FILE_FLAG_OVERLAPPED,
+                             NULL);
+
+    if (pipeHandle != INVALID_HANDLE_VALUE) {
+      *duplex_flags = UV_HANDLE_READABLE;
+      return pipeHandle;
+    }
+  }
+
+  if (GetLastError() == ERROR_ACCESS_DENIED) {
+    pipeHandle = CreateFileW(name,
+                             GENERIC_WRITE | FILE_READ_ATTRIBUTES,
+                             0,
+                             NULL,
+                             OPEN_EXISTING,
+                             FILE_FLAG_OVERLAPPED,
+                             NULL);
+
+    if (pipeHandle != INVALID_HANDLE_VALUE) {
+      *duplex_flags = UV_HANDLE_WRITABLE;
+      return pipeHandle;
+    }
+  }
+
+  return INVALID_HANDLE_VALUE;
+}
+
+
+static void close_pipe(uv_pipe_t* pipe) {
+  assert(pipe->u.fd == -1 || pipe->u.fd > 2);
+  if (pipe->u.fd == -1)
+    CloseHandle(pipe->handle);
+  else
+    close(pipe->u.fd);
+
+  pipe->u.fd = -1;
+  pipe->handle = INVALID_HANDLE_VALUE;
+}
+
+
+static int uv__pipe_server(
+    HANDLE* pipeHandle_ptr, DWORD access,
+    char* name, size_t nameSize, char* random) {
+  HANDLE pipeHandle;
+  int err;
+
+  for (;;) {
+    uv__unique_pipe_name(random, name, nameSize);
+
+    pipeHandle = CreateNamedPipeA(name,
+      access | FILE_FLAG_FIRST_PIPE_INSTANCE,
+      PIPE_TYPE_BYTE | PIPE_READMODE_BYTE | PIPE_WAIT, 1, 65536, 65536, 0,
+      NULL);
+
+    if (pipeHandle != INVALID_HANDLE_VALUE) {
+      /* No name collisions.  We're done. */
+      break;
+    }
+
+    err = GetLastError();
+    if (err != ERROR_PIPE_BUSY && err != ERROR_ACCESS_DENIED) {
+      goto error;
+    }
+
+    /* Pipe name collision.  Increment the random number and try again. */
+    random++;
+  }
+
+  *pipeHandle_ptr = pipeHandle;
+
+  return 0;
+
+ error:
+  if (pipeHandle != INVALID_HANDLE_VALUE)
+    CloseHandle(pipeHandle);
+
+  return err;
+}
+
+
+static int uv__create_pipe_pair(
+    HANDLE* server_pipe_ptr, HANDLE* client_pipe_ptr,
+    unsigned int server_flags, unsigned int client_flags,
+    int inherit_client, char* random) {
+  /* allowed flags are: UV_READABLE_PIPE | UV_WRITABLE_PIPE | UV_NONBLOCK_PIPE */
+  char pipe_name[64];
+  SECURITY_ATTRIBUTES sa;
+  DWORD server_access;
+  DWORD client_access;
+  HANDLE server_pipe;
+  HANDLE client_pipe;
+  int err;
+
+  server_pipe = INVALID_HANDLE_VALUE;
+  client_pipe = INVALID_HANDLE_VALUE;
+
+  server_access = 0;
+  if (server_flags & UV_READABLE_PIPE)
+    server_access |= PIPE_ACCESS_INBOUND;
+  if (server_flags & UV_WRITABLE_PIPE)
+    server_access |= PIPE_ACCESS_OUTBOUND;
+  if (server_flags & UV_NONBLOCK_PIPE)
+    server_access |= FILE_FLAG_OVERLAPPED;
+  server_access |= WRITE_DAC;
+
+  client_access = 0;
+  if (client_flags & UV_READABLE_PIPE)
+    client_access |= GENERIC_READ;
+  else
+    client_access |= FILE_READ_ATTRIBUTES;
+  if (client_flags & UV_WRITABLE_PIPE)
+    client_access |= GENERIC_WRITE;
+  else
+    client_access |= FILE_WRITE_ATTRIBUTES;
+  client_access |= WRITE_DAC;
+
+  /* Create server pipe handle. */
+  err = uv__pipe_server(&server_pipe,
+                        server_access,
+                        pipe_name,
+                        sizeof(pipe_name),
+                        random);
+  if (err)
+    goto error;
+
+  /* Create client pipe handle. */
+  sa.nLength = sizeof sa;
+  sa.lpSecurityDescriptor = NULL;
+  sa.bInheritHandle = inherit_client;
+
+  client_pipe = CreateFileA(pipe_name,
+                            client_access,
+                            0,
+                            &sa,
+                            OPEN_EXISTING,
+                            (client_flags & UV_NONBLOCK_PIPE) ? FILE_FLAG_OVERLAPPED : 0,
+                            NULL);
+  if (client_pipe == INVALID_HANDLE_VALUE) {
+    err = GetLastError();
+    goto error;
+  }
+
+#ifndef NDEBUG
+  /* Validate that the pipe was opened in the right mode. */
+  {
+    DWORD mode;
+    BOOL r;
+    r = GetNamedPipeHandleState(client_pipe, &mode, NULL, NULL, NULL, NULL, 0);
+    if (r == TRUE) {
+      assert(mode == (PIPE_READMODE_BYTE | PIPE_WAIT));
+    } else {
+      fprintf(stderr, "libuv assertion failure: GetNamedPipeHandleState failed\n");
+    }
+  }
+#endif
+
+  /* Do a blocking ConnectNamedPipe.  This should not block because we have
+   * both ends of the pipe created. */
+  if (!ConnectNamedPipe(server_pipe, NULL)) {
+    if (GetLastError() != ERROR_PIPE_CONNECTED) {
+      err = GetLastError();
+      goto error;
+    }
+  }
+
+  *client_pipe_ptr = client_pipe;
+  *server_pipe_ptr = server_pipe;
+  return 0;
+
+ error:
+  if (server_pipe != INVALID_HANDLE_VALUE)
+    CloseHandle(server_pipe);
+
+  if (client_pipe != INVALID_HANDLE_VALUE)
+    CloseHandle(client_pipe);
+
+  return err;
+}
+
+
+int uv_pipe(uv_file fds[2], int read_flags, int write_flags) {
+  uv_file temp[2];
+  int err;
+  HANDLE readh;
+  HANDLE writeh;
+
+  /* Make the server side the inbound (read) end, */
+  /* so that both ends will have FILE_READ_ATTRIBUTES permission. */
+  /* TODO: better source of local randomness than &fds? */
+  read_flags |= UV_READABLE_PIPE;
+  write_flags |= UV_WRITABLE_PIPE;
+  err = uv__create_pipe_pair(&readh, &writeh, read_flags, write_flags, 0, (char*) &fds[0]);
+  if (err != 0)
+    return err;
+  temp[0] = _open_osfhandle((intptr_t) readh, 0);
+  if (temp[0] == -1) {
+    if (errno == UV_EMFILE)
+      err = UV_EMFILE;
+    else
+      err = UV_UNKNOWN;
+    CloseHandle(readh);
+    CloseHandle(writeh);
+    return err;
+  }
+  temp[1] = _open_osfhandle((intptr_t) writeh, 0);
+  if (temp[1] == -1) {
+    if (errno == UV_EMFILE)
+      err = UV_EMFILE;
+    else
+      err = UV_UNKNOWN;
+    _close(temp[0]);
+    CloseHandle(writeh);
+    return err;
+  }
+  fds[0] = temp[0];
+  fds[1] = temp[1];
+  return 0;
+}
+
+
+int uv__create_stdio_pipe_pair(uv_loop_t* loop,
+    uv_pipe_t* parent_pipe, HANDLE* child_pipe_ptr, unsigned int flags) {
+  /* The parent_pipe is always the server_pipe and kept by libuv.
+   * The child_pipe is always the client_pipe and is passed to the child.
+   * The flags are specified with respect to their usage in the child. */
+  HANDLE server_pipe;
+  HANDLE client_pipe;
+  unsigned int server_flags;
+  unsigned int client_flags;
+  int err;
+
+  uv__pipe_connection_init(parent_pipe);
+
+  server_pipe = INVALID_HANDLE_VALUE;
+  client_pipe = INVALID_HANDLE_VALUE;
+
+  server_flags = 0;
+  client_flags = 0;
+  if (flags & UV_READABLE_PIPE) {
+    /* The server needs inbound (read) access too, otherwise CreateNamedPipe()
+     * won't give us the FILE_READ_ATTRIBUTES permission. We need that to probe
+     * the state of the write buffer when we're trying to shutdown the pipe. */
+    server_flags |= UV_READABLE_PIPE | UV_WRITABLE_PIPE;
+    client_flags |= UV_READABLE_PIPE;
+  }
+  if (flags & UV_WRITABLE_PIPE) {
+    server_flags |= UV_READABLE_PIPE;
+    client_flags |= UV_WRITABLE_PIPE;
+  }
+  server_flags |= UV_NONBLOCK_PIPE;
+  if (flags & UV_NONBLOCK_PIPE || parent_pipe->ipc) {
+    client_flags |= UV_NONBLOCK_PIPE;
+  }
+
+  err = uv__create_pipe_pair(&server_pipe, &client_pipe,
+          server_flags, client_flags, 1, (char*) server_pipe);
+  if (err)
+    goto error;
+
+  if (CreateIoCompletionPort(server_pipe,
+                             loop->iocp,
+                             (ULONG_PTR) parent_pipe,
+                             0) == NULL) {
+    err = GetLastError();
+    goto error;
+  }
+
+  parent_pipe->handle = server_pipe;
+  *child_pipe_ptr = client_pipe;
+
+  /* The server end is now readable and/or writable. */
+  if (flags & UV_READABLE_PIPE)
+    parent_pipe->flags |= UV_HANDLE_WRITABLE;
+  if (flags & UV_WRITABLE_PIPE)
+    parent_pipe->flags |= UV_HANDLE_READABLE;
+
+  return 0;
+
+ error:
+  if (server_pipe != INVALID_HANDLE_VALUE)
+    CloseHandle(server_pipe);
+
+  if (client_pipe != INVALID_HANDLE_VALUE)
+    CloseHandle(client_pipe);
+
+  return err;
+}
+
+
+static int uv__set_pipe_handle(uv_loop_t* loop,
+                               uv_pipe_t* handle,
+                               HANDLE pipeHandle,
+                               int fd,
+                               DWORD duplex_flags) {
+  NTSTATUS nt_status;
+  IO_STATUS_BLOCK io_status;
+  FILE_MODE_INFORMATION mode_info;
+  DWORD mode = PIPE_READMODE_BYTE | PIPE_WAIT;
+  DWORD current_mode = 0;
+  DWORD err = 0;
+
+  assert(handle->flags & UV_HANDLE_CONNECTION);
+  assert(!(handle->flags & UV_HANDLE_PIPESERVER));
+  if (handle->flags & UV_HANDLE_CLOSING)
+    return UV_EINVAL;
+  if (handle->handle != INVALID_HANDLE_VALUE)
+    return UV_EBUSY;
+
+  if (!SetNamedPipeHandleState(pipeHandle, &mode, NULL, NULL)) {
+    err = GetLastError();
+    if (err == ERROR_ACCESS_DENIED) {
+      /*
+       * SetNamedPipeHandleState can fail if the handle doesn't have either
+       * GENERIC_WRITE  or FILE_WRITE_ATTRIBUTES.
+       * But if the handle already has the desired wait and blocking modes
+       * we can continue.
+       */
+      if (!GetNamedPipeHandleState(pipeHandle, &current_mode, NULL, NULL,
+                                   NULL, NULL, 0)) {
+        return uv_translate_sys_error(GetLastError());
+      } else if (current_mode & PIPE_NOWAIT) {
+        return UV_EACCES;
+      }
+    } else {
+      /* If this returns ERROR_INVALID_PARAMETER we probably opened
+       * something that is not a pipe. */
+      if (err == ERROR_INVALID_PARAMETER) {
+        return UV_ENOTSOCK;
+      }
+      return uv_translate_sys_error(err);
+    }
+  }
+
+  /* Check if the pipe was created with FILE_FLAG_OVERLAPPED. */
+  nt_status = pNtQueryInformationFile(pipeHandle,
+                                      &io_status,
+                                      &mode_info,
+                                      sizeof(mode_info),
+                                      FileModeInformation);
+  if (nt_status != STATUS_SUCCESS) {
+    return uv_translate_sys_error(err);
+  }
+
+  if (mode_info.Mode & FILE_SYNCHRONOUS_IO_ALERT ||
+      mode_info.Mode & FILE_SYNCHRONOUS_IO_NONALERT) {
+    /* Non-overlapped pipe. */
+    handle->flags |= UV_HANDLE_NON_OVERLAPPED_PIPE;
+    handle->pipe.conn.readfile_thread_handle = NULL;
+    InitializeCriticalSection(&handle->pipe.conn.readfile_thread_lock);
+  } else {
+    /* Overlapped pipe.  Try to associate with IOCP. */
+    if (CreateIoCompletionPort(pipeHandle,
+                               loop->iocp,
+                               (ULONG_PTR) handle,
+                               0) == NULL) {
+      handle->flags |= UV_HANDLE_EMULATE_IOCP;
+    }
+  }
+
+  handle->handle = pipeHandle;
+  handle->u.fd = fd;
+  handle->flags |= duplex_flags;
+
+  return 0;
+}
+
+
+static int pipe_alloc_accept(uv_loop_t* loop, uv_pipe_t* handle,
+                             uv_pipe_accept_t* req, BOOL firstInstance) {
+  assert(req->pipeHandle == INVALID_HANDLE_VALUE);
+
+  req->pipeHandle =
+      CreateNamedPipeW(handle->name,
+                       PIPE_ACCESS_DUPLEX | FILE_FLAG_OVERLAPPED | WRITE_DAC |
+                         (firstInstance ? FILE_FLAG_FIRST_PIPE_INSTANCE : 0),
+                       PIPE_TYPE_BYTE | PIPE_READMODE_BYTE | PIPE_WAIT,
+                       PIPE_UNLIMITED_INSTANCES, 65536, 65536, 0, NULL);
+
+  if (req->pipeHandle == INVALID_HANDLE_VALUE) {
+    return 0;
+  }
+
+  /* Associate it with IOCP so we can get events. */
+  if (CreateIoCompletionPort(req->pipeHandle,
+                             loop->iocp,
+                             (ULONG_PTR) handle,
+                             0) == NULL) {
+    uv_fatal_error(GetLastError(), "CreateIoCompletionPort");
+  }
+
+  /* Stash a handle in the server object for use from places such as
+   * getsockname and chmod. As we transfer ownership of these to client
+   * objects, we'll allocate new ones here. */
+  handle->handle = req->pipeHandle;
+
+  return 1;
+}
+
+
+static DWORD WINAPI pipe_shutdown_thread_proc(void* parameter) {
+  uv_loop_t* loop;
+  uv_pipe_t* handle;
+  uv_shutdown_t* req;
+
+  req = (uv_shutdown_t*) parameter;
+  assert(req);
+  handle = (uv_pipe_t*) req->handle;
+  assert(handle);
+  loop = handle->loop;
+  assert(loop);
+
+  FlushFileBuffers(handle->handle);
+
+  /* Post completed */
+  POST_COMPLETION_FOR_REQ(loop, req);
+
+  return 0;
+}
+
+
+void uv__pipe_shutdown(uv_loop_t* loop, uv_pipe_t* handle, uv_shutdown_t *req) {
+  DWORD result;
+  NTSTATUS nt_status;
+  IO_STATUS_BLOCK io_status;
+  FILE_PIPE_LOCAL_INFORMATION pipe_info;
+
+  assert(handle->flags & UV_HANDLE_CONNECTION);
+  assert(req != NULL);
+  assert(handle->stream.conn.write_reqs_pending == 0);
+  SET_REQ_SUCCESS(req);
+
+  if (handle->flags & UV_HANDLE_CLOSING) {
+    uv__insert_pending_req(loop, (uv_req_t*) req);
+    return;
+  }
+
+  /* Try to avoid flushing the pipe buffer in the thread pool. */
+  nt_status = pNtQueryInformationFile(handle->handle,
+                                      &io_status,
+                                      &pipe_info,
+                                      sizeof pipe_info,
+                                      FilePipeLocalInformation);
+
+  if (nt_status != STATUS_SUCCESS) {
+    SET_REQ_ERROR(req, pRtlNtStatusToDosError(nt_status));
+    handle->flags |= UV_HANDLE_WRITABLE; /* Questionable. */
+    uv__insert_pending_req(loop, (uv_req_t*) req);
+    return;
+  }
+
+  if (pipe_info.OutboundQuota == pipe_info.WriteQuotaAvailable) {
+    /* Short-circuit, no need to call FlushFileBuffers:
+     * all writes have been read. */
+    uv__insert_pending_req(loop, (uv_req_t*) req);
+    return;
+  }
+
+  /* Run FlushFileBuffers in the thread pool. */
+  result = QueueUserWorkItem(pipe_shutdown_thread_proc,
+                             req,
+                             WT_EXECUTELONGFUNCTION);
+  if (!result) {
+    SET_REQ_ERROR(req, GetLastError());
+    handle->flags |= UV_HANDLE_WRITABLE; /* Questionable. */
+    uv__insert_pending_req(loop, (uv_req_t*) req);
+    return;
+  }
+}
+
+
+void uv__pipe_endgame(uv_loop_t* loop, uv_pipe_t* handle) {
+  uv__ipc_xfer_queue_item_t* xfer_queue_item;
+
+  assert(handle->reqs_pending == 0);
+  assert(handle->flags & UV_HANDLE_CLOSING);
+  assert(!(handle->flags & UV_HANDLE_CLOSED));
+
+  if (handle->flags & UV_HANDLE_CONNECTION) {
+    /* Free pending sockets */
+    while (!QUEUE_EMPTY(&handle->pipe.conn.ipc_xfer_queue)) {
+      QUEUE* q;
+      SOCKET socket;
+
+      q = QUEUE_HEAD(&handle->pipe.conn.ipc_xfer_queue);
+      QUEUE_REMOVE(q);
+      xfer_queue_item = QUEUE_DATA(q, uv__ipc_xfer_queue_item_t, member);
+
+      /* Materialize socket and close it */
+      socket = WSASocketW(FROM_PROTOCOL_INFO,
+                          FROM_PROTOCOL_INFO,
+                          FROM_PROTOCOL_INFO,
+                          &xfer_queue_item->xfer_info.socket_info,
+                          0,
+                          WSA_FLAG_OVERLAPPED);
+      uv__free(xfer_queue_item);
+
+      if (socket != INVALID_SOCKET)
+        closesocket(socket);
+    }
+    handle->pipe.conn.ipc_xfer_queue_length = 0;
+
+    if (handle->flags & UV_HANDLE_EMULATE_IOCP) {
+      if (handle->read_req.wait_handle != INVALID_HANDLE_VALUE) {
+        UnregisterWait(handle->read_req.wait_handle);
+        handle->read_req.wait_handle = INVALID_HANDLE_VALUE;
+      }
+      if (handle->read_req.event_handle != NULL) {
+        CloseHandle(handle->read_req.event_handle);
+        handle->read_req.event_handle = NULL;
+      }
+    }
+
+    if (handle->flags & UV_HANDLE_NON_OVERLAPPED_PIPE)
+      DeleteCriticalSection(&handle->pipe.conn.readfile_thread_lock);
+  }
+
+  if (handle->flags & UV_HANDLE_PIPESERVER) {
+    assert(handle->pipe.serv.accept_reqs);
+    uv__free(handle->pipe.serv.accept_reqs);
+    handle->pipe.serv.accept_reqs = NULL;
+  }
+
+  uv__handle_close(handle);
+}
+
+
+void uv_pipe_pending_instances(uv_pipe_t* handle, int count) {
+  if (handle->flags & UV_HANDLE_BOUND)
+    return;
+  handle->pipe.serv.pending_instances = count;
+  handle->flags |= UV_HANDLE_PIPESERVER;
+}
+
+
+/* Creates a pipe server. */
+int uv_pipe_bind(uv_pipe_t* handle, const char* name) {
+  uv_loop_t* loop = handle->loop;
+  int i, err, nameSize;
+  uv_pipe_accept_t* req;
+
+  if (handle->flags & UV_HANDLE_BOUND) {
+    return UV_EINVAL;
+  }
+
+  if (!name) {
+    return UV_EINVAL;
+  }
+  if (uv__is_closing(handle)) {
+    return UV_EINVAL;
+  }
+  if (!(handle->flags & UV_HANDLE_PIPESERVER)) {
+    handle->pipe.serv.pending_instances = default_pending_pipe_instances;
+  }
+
+  handle->pipe.serv.accept_reqs = (uv_pipe_accept_t*)
+    uv__malloc(sizeof(uv_pipe_accept_t) * handle->pipe.serv.pending_instances);
+  if (!handle->pipe.serv.accept_reqs) {
+    uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+  }
+
+  for (i = 0; i < handle->pipe.serv.pending_instances; i++) {
+    req = &handle->pipe.serv.accept_reqs[i];
+    UV_REQ_INIT(req, UV_ACCEPT);
+    req->data = handle;
+    req->pipeHandle = INVALID_HANDLE_VALUE;
+    req->next_pending = NULL;
+  }
+
+  /* Convert name to UTF16. */
+  nameSize = MultiByteToWideChar(CP_UTF8, 0, name, -1, NULL, 0) * sizeof(WCHAR);
+  handle->name = (WCHAR*)uv__malloc(nameSize);
+  if (!handle->name) {
+    uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+  }
+
+  if (!MultiByteToWideChar(CP_UTF8,
+                           0,
+                           name,
+                           -1,
+                           handle->name,
+                           nameSize / sizeof(WCHAR))) {
+    err = GetLastError();
+    goto error;
+  }
+
+  /*
+   * Attempt to create the first pipe with FILE_FLAG_FIRST_PIPE_INSTANCE.
+   * If this fails then there's already a pipe server for the given pipe name.
+   */
+  if (!pipe_alloc_accept(loop,
+                         handle,
+                         &handle->pipe.serv.accept_reqs[0],
+                         TRUE)) {
+    err = GetLastError();
+    if (err == ERROR_ACCESS_DENIED) {
+      err = WSAEADDRINUSE;  /* Translates to UV_EADDRINUSE. */
+    } else if (err == ERROR_PATH_NOT_FOUND || err == ERROR_INVALID_NAME) {
+      err = WSAEACCES;  /* Translates to UV_EACCES. */
+    }
+    goto error;
+  }
+
+  handle->pipe.serv.pending_accepts = NULL;
+  handle->flags |= UV_HANDLE_PIPESERVER;
+  handle->flags |= UV_HANDLE_BOUND;
+
+  return 0;
+
+error:
+  if (handle->name) {
+    uv__free(handle->name);
+    handle->name = NULL;
+  }
+
+  return uv_translate_sys_error(err);
+}
+
+
+static DWORD WINAPI pipe_connect_thread_proc(void* parameter) {
+  uv_loop_t* loop;
+  uv_pipe_t* handle;
+  uv_connect_t* req;
+  HANDLE pipeHandle = INVALID_HANDLE_VALUE;
+  DWORD duplex_flags;
+
+  req = (uv_connect_t*) parameter;
+  assert(req);
+  handle = (uv_pipe_t*) req->handle;
+  assert(handle);
+  loop = handle->loop;
+  assert(loop);
+
+  /* We're here because CreateFile on a pipe returned ERROR_PIPE_BUSY. We wait
+   * up to 30 seconds for the pipe to become available with WaitNamedPipe. */
+  while (WaitNamedPipeW(handle->name, 30000)) {
+    /* The pipe is now available, try to connect. */
+    pipeHandle = open_named_pipe(handle->name, &duplex_flags);
+    if (pipeHandle != INVALID_HANDLE_VALUE)
+      break;
+
+    SwitchToThread();
+  }
+
+  if (pipeHandle != INVALID_HANDLE_VALUE) {
+    SET_REQ_SUCCESS(req);
+    req->u.connect.pipeHandle = pipeHandle;
+    req->u.connect.duplex_flags = duplex_flags;
+  } else {
+    SET_REQ_ERROR(req, GetLastError());
+  }
+
+  /* Post completed */
+  POST_COMPLETION_FOR_REQ(loop, req);
+
+  return 0;
+}
+
+
+void uv_pipe_connect(uv_connect_t* req, uv_pipe_t* handle,
+    const char* name, uv_connect_cb cb) {
+  uv_loop_t* loop = handle->loop;
+  int err, nameSize;
+  HANDLE pipeHandle = INVALID_HANDLE_VALUE;
+  DWORD duplex_flags;
+
+  UV_REQ_INIT(req, UV_CONNECT);
+  req->handle = (uv_stream_t*) handle;
+  req->cb = cb;
+  req->u.connect.pipeHandle = INVALID_HANDLE_VALUE;
+  req->u.connect.duplex_flags = 0;
+
+  if (handle->flags & UV_HANDLE_PIPESERVER) {
+    err = ERROR_INVALID_PARAMETER;
+    goto error;
+  }
+  if (handle->flags & UV_HANDLE_CONNECTION) {
+    err = ERROR_PIPE_BUSY;
+    goto error;
+  }
+  uv__pipe_connection_init(handle);
+
+  /* Convert name to UTF16. */
+  nameSize = MultiByteToWideChar(CP_UTF8, 0, name, -1, NULL, 0) * sizeof(WCHAR);
+  handle->name = (WCHAR*)uv__malloc(nameSize);
+  if (!handle->name) {
+    uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+  }
+
+  if (!MultiByteToWideChar(CP_UTF8,
+                           0,
+                           name,
+                           -1,
+                           handle->name,
+                           nameSize / sizeof(WCHAR))) {
+    err = GetLastError();
+    goto error;
+  }
+
+  pipeHandle = open_named_pipe(handle->name, &duplex_flags);
+  if (pipeHandle == INVALID_HANDLE_VALUE) {
+    if (GetLastError() == ERROR_PIPE_BUSY) {
+      /* Wait for the server to make a pipe instance available. */
+      if (!QueueUserWorkItem(&pipe_connect_thread_proc,
+                             req,
+                             WT_EXECUTELONGFUNCTION)) {
+        err = GetLastError();
+        goto error;
+      }
+
+      REGISTER_HANDLE_REQ(loop, handle, req);
+      handle->reqs_pending++;
+
+      return;
+    }
+
+    err = GetLastError();
+    goto error;
+  }
+
+  req->u.connect.pipeHandle = pipeHandle;
+  req->u.connect.duplex_flags = duplex_flags;
+  SET_REQ_SUCCESS(req);
+  uv__insert_pending_req(loop, (uv_req_t*) req);
+  handle->reqs_pending++;
+  REGISTER_HANDLE_REQ(loop, handle, req);
+  return;
+
+error:
+  if (handle->name) {
+    uv__free(handle->name);
+    handle->name = NULL;
+  }
+
+  if (pipeHandle != INVALID_HANDLE_VALUE)
+    CloseHandle(pipeHandle);
+
+  /* Make this req pending reporting an error. */
+  SET_REQ_ERROR(req, err);
+  uv__insert_pending_req(loop, (uv_req_t*) req);
+  handle->reqs_pending++;
+  REGISTER_HANDLE_REQ(loop, handle, req);
+  return;
+}
+
+
+void uv__pipe_interrupt_read(uv_pipe_t* handle) {
+  BOOL r;
+
+  if (!(handle->flags & UV_HANDLE_READ_PENDING))
+    return; /* No pending reads. */
+  if (handle->flags & UV_HANDLE_CANCELLATION_PENDING)
+    return; /* Already cancelled. */
+  if (handle->handle == INVALID_HANDLE_VALUE)
+    return; /* Pipe handle closed. */
+
+  if (!(handle->flags & UV_HANDLE_NON_OVERLAPPED_PIPE)) {
+    /* Cancel asynchronous read. */
+    r = CancelIoEx(handle->handle, &handle->read_req.u.io.overlapped);
+    assert(r || GetLastError() == ERROR_NOT_FOUND);
+    (void) r;
+  } else {
+    /* Cancel synchronous read (which is happening in the thread pool). */
+    HANDLE thread;
+    volatile HANDLE* thread_ptr = &handle->pipe.conn.readfile_thread_handle;
+
+    EnterCriticalSection(&handle->pipe.conn.readfile_thread_lock);
+
+    thread = *thread_ptr;
+    if (thread == NULL) {
+      /* The thread pool thread has not yet reached the point of blocking, we
+       * can pre-empt it by setting thread_handle to INVALID_HANDLE_VALUE. */
+      *thread_ptr = INVALID_HANDLE_VALUE;
+
+    } else {
+      /* Spin until the thread has acknowledged (by setting the thread to
+       * INVALID_HANDLE_VALUE) that it is past the point of blocking. */
+      while (thread != INVALID_HANDLE_VALUE) {
+        r = CancelSynchronousIo(thread);
+        assert(r || GetLastError() == ERROR_NOT_FOUND);
+        SwitchToThread(); /* Yield thread. */
+        thread = *thread_ptr;
+      }
+    }
+
+    LeaveCriticalSection(&handle->pipe.conn.readfile_thread_lock);
+  }
+
+  /* Set flag to indicate that read has been cancelled. */
+  handle->flags |= UV_HANDLE_CANCELLATION_PENDING;
+}
+
+
+void uv__pipe_read_stop(uv_pipe_t* handle) {
+  handle->flags &= ~UV_HANDLE_READING;
+  DECREASE_ACTIVE_COUNT(handle->loop, handle);
+  uv__pipe_interrupt_read(handle);
+}
+
+
+/* Cleans up uv_pipe_t (server or connection) and all resources associated with
+ * it. */
+void uv__pipe_close(uv_loop_t* loop, uv_pipe_t* handle) {
+  int i;
+  HANDLE pipeHandle;
+
+  if (handle->flags & UV_HANDLE_READING) {
+    handle->flags &= ~UV_HANDLE_READING;
+    DECREASE_ACTIVE_COUNT(loop, handle);
+  }
+
+  if (handle->flags & UV_HANDLE_LISTENING) {
+    handle->flags &= ~UV_HANDLE_LISTENING;
+    DECREASE_ACTIVE_COUNT(loop, handle);
+  }
+
+  handle->flags &= ~(UV_HANDLE_READABLE | UV_HANDLE_WRITABLE);
+
+  uv__handle_closing(handle);
+
+  uv__pipe_interrupt_read(handle);
+
+  if (handle->name) {
+    uv__free(handle->name);
+    handle->name = NULL;
+  }
+
+  if (handle->flags & UV_HANDLE_PIPESERVER) {
+    for (i = 0; i < handle->pipe.serv.pending_instances; i++) {
+      pipeHandle = handle->pipe.serv.accept_reqs[i].pipeHandle;
+      if (pipeHandle != INVALID_HANDLE_VALUE) {
+        CloseHandle(pipeHandle);
+        handle->pipe.serv.accept_reqs[i].pipeHandle = INVALID_HANDLE_VALUE;
+      }
+    }
+    handle->handle = INVALID_HANDLE_VALUE;
+  }
+
+  if (handle->flags & UV_HANDLE_CONNECTION) {
+    eof_timer_destroy(handle);
+  }
+
+  if ((handle->flags & UV_HANDLE_CONNECTION)
+      && handle->handle != INVALID_HANDLE_VALUE) {
+    /* This will eventually destroy the write queue for us too. */
+    close_pipe(handle);
+  }
+
+  if (handle->reqs_pending == 0)
+    uv__want_endgame(loop, (uv_handle_t*) handle);
+}
+
+
+static void uv__pipe_queue_accept(uv_loop_t* loop, uv_pipe_t* handle,
+    uv_pipe_accept_t* req, BOOL firstInstance) {
+  assert(handle->flags & UV_HANDLE_LISTENING);
+
+  if (!firstInstance && !pipe_alloc_accept(loop, handle, req, FALSE)) {
+    SET_REQ_ERROR(req, GetLastError());
+    uv__insert_pending_req(loop, (uv_req_t*) req);
+    handle->reqs_pending++;
+    return;
+  }
+
+  assert(req->pipeHandle != INVALID_HANDLE_VALUE);
+
+  /* Prepare the overlapped structure. */
+  memset(&(req->u.io.overlapped), 0, sizeof(req->u.io.overlapped));
+
+  if (!ConnectNamedPipe(req->pipeHandle, &req->u.io.overlapped) &&
+      GetLastError() != ERROR_IO_PENDING) {
+    if (GetLastError() == ERROR_PIPE_CONNECTED) {
+      SET_REQ_SUCCESS(req);
+    } else {
+      CloseHandle(req->pipeHandle);
+      req->pipeHandle = INVALID_HANDLE_VALUE;
+      /* Make this req pending reporting an error. */
+      SET_REQ_ERROR(req, GetLastError());
+    }
+    uv__insert_pending_req(loop, (uv_req_t*) req);
+    handle->reqs_pending++;
+    return;
+  }
+
+  /* Wait for completion via IOCP */
+  handle->reqs_pending++;
+}
+
+
+int uv__pipe_accept(uv_pipe_t* server, uv_stream_t* client) {
+  uv_loop_t* loop = server->loop;
+  uv_pipe_t* pipe_client;
+  uv_pipe_accept_t* req;
+  QUEUE* q;
+  uv__ipc_xfer_queue_item_t* item;
+  int err;
+
+  if (server->ipc) {
+    if (QUEUE_EMPTY(&server->pipe.conn.ipc_xfer_queue)) {
+      /* No valid pending sockets. */
+      return WSAEWOULDBLOCK;
+    }
+
+    q = QUEUE_HEAD(&server->pipe.conn.ipc_xfer_queue);
+    QUEUE_REMOVE(q);
+    server->pipe.conn.ipc_xfer_queue_length--;
+    item = QUEUE_DATA(q, uv__ipc_xfer_queue_item_t, member);
+
+    err = uv__tcp_xfer_import(
+        (uv_tcp_t*) client, item->xfer_type, &item->xfer_info);
+    if (err != 0)
+      return err;
+
+    uv__free(item);
+
+  } else {
+    pipe_client = (uv_pipe_t*) client;
+    uv__pipe_connection_init(pipe_client);
+
+    /* Find a connection instance that has been connected, but not yet
+     * accepted. */
+    req = server->pipe.serv.pending_accepts;
+
+    if (!req) {
+      /* No valid connections found, so we error out. */
+      return WSAEWOULDBLOCK;
+    }
+
+    /* Initialize the client handle and copy the pipeHandle to the client */
+    pipe_client->handle = req->pipeHandle;
+    pipe_client->flags |= UV_HANDLE_READABLE | UV_HANDLE_WRITABLE;
+
+    /* Prepare the req to pick up a new connection */
+    server->pipe.serv.pending_accepts = req->next_pending;
+    req->next_pending = NULL;
+    req->pipeHandle = INVALID_HANDLE_VALUE;
+
+    server->handle = INVALID_HANDLE_VALUE;
+    if (!(server->flags & UV_HANDLE_CLOSING)) {
+      uv__pipe_queue_accept(loop, server, req, FALSE);
+    }
+  }
+
+  return 0;
+}
+
+
+/* Starts listening for connections for the given pipe. */
+int uv__pipe_listen(uv_pipe_t* handle, int backlog, uv_connection_cb cb) {
+  uv_loop_t* loop = handle->loop;
+  int i;
+
+  if (handle->flags & UV_HANDLE_LISTENING) {
+    handle->stream.serv.connection_cb = cb;
+  }
+
+  if (!(handle->flags & UV_HANDLE_BOUND)) {
+    return WSAEINVAL;
+  }
+
+  if (handle->flags & UV_HANDLE_READING) {
+    return WSAEISCONN;
+  }
+
+  if (!(handle->flags & UV_HANDLE_PIPESERVER)) {
+    return ERROR_NOT_SUPPORTED;
+  }
+
+  if (handle->ipc) {
+    return WSAEINVAL;
+  }
+
+  handle->flags |= UV_HANDLE_LISTENING;
+  INCREASE_ACTIVE_COUNT(loop, handle);
+  handle->stream.serv.connection_cb = cb;
+
+  /* First pipe handle should have already been created in uv_pipe_bind */
+  assert(handle->pipe.serv.accept_reqs[0].pipeHandle != INVALID_HANDLE_VALUE);
+
+  for (i = 0; i < handle->pipe.serv.pending_instances; i++) {
+    uv__pipe_queue_accept(loop, handle, &handle->pipe.serv.accept_reqs[i], i == 0);
+  }
+
+  return 0;
+}
+
+
+static DWORD WINAPI uv_pipe_zero_readfile_thread_proc(void* arg) {
+  uv_read_t* req = (uv_read_t*) arg;
+  uv_pipe_t* handle = (uv_pipe_t*) req->data;
+  uv_loop_t* loop = handle->loop;
+  volatile HANDLE* thread_ptr = &handle->pipe.conn.readfile_thread_handle;
+  CRITICAL_SECTION* lock = &handle->pipe.conn.readfile_thread_lock;
+  HANDLE thread;
+  DWORD bytes;
+  DWORD err;
+
+  assert(req->type == UV_READ);
+  assert(handle->type == UV_NAMED_PIPE);
+
+  err = 0;
+
+  /* Create a handle to the current thread. */
+  if (!DuplicateHandle(GetCurrentProcess(),
+                       GetCurrentThread(),
+                       GetCurrentProcess(),
+                       &thread,
+                       0,
+                       FALSE,
+                       DUPLICATE_SAME_ACCESS)) {
+    err = GetLastError();
+    goto out1;
+  }
+
+  /* The lock needs to be held when thread handle is modified. */
+  EnterCriticalSection(lock);
+  if (*thread_ptr == INVALID_HANDLE_VALUE) {
+    /* uv__pipe_interrupt_read() cancelled reading before we got here. */
+    err = ERROR_OPERATION_ABORTED;
+  } else {
+    /* Let main thread know which worker thread is doing the blocking read. */
+    assert(*thread_ptr == NULL);
+    *thread_ptr = thread;
+  }
+  LeaveCriticalSection(lock);
+
+  if (err)
+    goto out2;
+
+  /* Block the thread until data is available on the pipe, or the read is
+   * cancelled. */
+  if (!ReadFile(handle->handle, &uv_zero_, 0, &bytes, NULL))
+    err = GetLastError();
+
+  /* Let the main thread know the worker is past the point of blocking. */
+  assert(thread == *thread_ptr);
+  *thread_ptr = INVALID_HANDLE_VALUE;
+
+  /* Briefly acquire the mutex. Since the main thread holds the lock while it
+   * is spinning trying to cancel this thread's I/O, we will block here until
+   * it stops doing that. */
+  EnterCriticalSection(lock);
+  LeaveCriticalSection(lock);
+
+out2:
+  /* Close the handle to the current thread. */
+  CloseHandle(thread);
+
+out1:
+  /* Set request status and post a completion record to the IOCP. */
+  if (err)
+    SET_REQ_ERROR(req, err);
+  else
+    SET_REQ_SUCCESS(req);
+  POST_COMPLETION_FOR_REQ(loop, req);
+
+  return 0;
+}
+
+
+static DWORD WINAPI uv_pipe_writefile_thread_proc(void* parameter) {
+  int result;
+  DWORD bytes;
+  uv_write_t* req = (uv_write_t*) parameter;
+  uv_pipe_t* handle = (uv_pipe_t*) req->handle;
+  uv_loop_t* loop = handle->loop;
+
+  assert(req != NULL);
+  assert(req->type == UV_WRITE);
+  assert(handle->type == UV_NAMED_PIPE);
+
+  result = WriteFile(handle->handle,
+                     req->write_buffer.base,
+                     req->write_buffer.len,
+                     &bytes,
+                     NULL);
+
+  if (!result) {
+    SET_REQ_ERROR(req, GetLastError());
+  }
+
+  POST_COMPLETION_FOR_REQ(loop, req);
+  return 0;
+}
+
+
+static void CALLBACK post_completion_read_wait(void* context, BOOLEAN timed_out) {
+  uv_read_t* req;
+  uv_tcp_t* handle;
+
+  req = (uv_read_t*) context;
+  assert(req != NULL);
+  handle = (uv_tcp_t*)req->data;
+  assert(handle != NULL);
+  assert(!timed_out);
+
+  if (!PostQueuedCompletionStatus(handle->loop->iocp,
+                                  req->u.io.overlapped.InternalHigh,
+                                  0,
+                                  &req->u.io.overlapped)) {
+    uv_fatal_error(GetLastError(), "PostQueuedCompletionStatus");
+  }
+}
+
+
+static void CALLBACK post_completion_write_wait(void* context, BOOLEAN timed_out) {
+  uv_write_t* req;
+  uv_tcp_t* handle;
+
+  req = (uv_write_t*) context;
+  assert(req != NULL);
+  handle = (uv_tcp_t*)req->handle;
+  assert(handle != NULL);
+  assert(!timed_out);
+
+  if (!PostQueuedCompletionStatus(handle->loop->iocp,
+                                  req->u.io.overlapped.InternalHigh,
+                                  0,
+                                  &req->u.io.overlapped)) {
+    uv_fatal_error(GetLastError(), "PostQueuedCompletionStatus");
+  }
+}
+
+
+static void uv__pipe_queue_read(uv_loop_t* loop, uv_pipe_t* handle) {
+  uv_read_t* req;
+  int result;
+
+  assert(handle->flags & UV_HANDLE_READING);
+  assert(!(handle->flags & UV_HANDLE_READ_PENDING));
+
+  assert(handle->handle != INVALID_HANDLE_VALUE);
+
+  req = &handle->read_req;
+
+  if (handle->flags & UV_HANDLE_NON_OVERLAPPED_PIPE) {
+    handle->pipe.conn.readfile_thread_handle = NULL; /* Reset cancellation. */
+    if (!QueueUserWorkItem(&uv_pipe_zero_readfile_thread_proc,
+                           req,
+                           WT_EXECUTELONGFUNCTION)) {
+      /* Make this req pending reporting an error. */
+      SET_REQ_ERROR(req, GetLastError());
+      goto error;
+    }
+  } else {
+    memset(&req->u.io.overlapped, 0, sizeof(req->u.io.overlapped));
+    if (handle->flags & UV_HANDLE_EMULATE_IOCP) {
+      assert(req->event_handle != NULL);
+      req->u.io.overlapped.hEvent = (HANDLE) ((uintptr_t) req->event_handle | 1);
+    }
+
+    /* Do 0-read */
+    result = ReadFile(handle->handle,
+                      &uv_zero_,
+                      0,
+                      NULL,
+                      &req->u.io.overlapped);
+
+    if (!result && GetLastError() != ERROR_IO_PENDING) {
+      /* Make this req pending reporting an error. */
+      SET_REQ_ERROR(req, GetLastError());
+      goto error;
+    }
+
+    if (handle->flags & UV_HANDLE_EMULATE_IOCP) {
+      if (req->wait_handle == INVALID_HANDLE_VALUE) {
+        if (!RegisterWaitForSingleObject(&req->wait_handle,
+            req->event_handle, post_completion_read_wait, (void*) req,
+            INFINITE, WT_EXECUTEINWAITTHREAD)) {
+          SET_REQ_ERROR(req, GetLastError());
+          goto error;
+        }
+      }
+    }
+  }
+
+  /* Start the eof timer if there is one */
+  eof_timer_start(handle);
+  handle->flags |= UV_HANDLE_READ_PENDING;
+  handle->reqs_pending++;
+  return;
+
+error:
+  uv__insert_pending_req(loop, (uv_req_t*)req);
+  handle->flags |= UV_HANDLE_READ_PENDING;
+  handle->reqs_pending++;
+}
+
+
+int uv__pipe_read_start(uv_pipe_t* handle,
+                        uv_alloc_cb alloc_cb,
+                        uv_read_cb read_cb) {
+  uv_loop_t* loop = handle->loop;
+
+  handle->flags |= UV_HANDLE_READING;
+  INCREASE_ACTIVE_COUNT(loop, handle);
+  handle->read_cb = read_cb;
+  handle->alloc_cb = alloc_cb;
+
+  /* If reading was stopped and then started again, there could still be a read
+   * request pending. */
+  if (!(handle->flags & UV_HANDLE_READ_PENDING)) {
+    if (handle->flags & UV_HANDLE_EMULATE_IOCP &&
+        handle->read_req.event_handle == NULL) {
+      handle->read_req.event_handle = CreateEvent(NULL, 0, 0, NULL);
+      if (handle->read_req.event_handle == NULL) {
+        uv_fatal_error(GetLastError(), "CreateEvent");
+      }
+    }
+    uv__pipe_queue_read(loop, handle);
+  }
+
+  return 0;
+}
+
+
+static void uv__insert_non_overlapped_write_req(uv_pipe_t* handle,
+    uv_write_t* req) {
+  req->next_req = NULL;
+  if (handle->pipe.conn.non_overlapped_writes_tail) {
+    req->next_req =
+      handle->pipe.conn.non_overlapped_writes_tail->next_req;
+    handle->pipe.conn.non_overlapped_writes_tail->next_req = (uv_req_t*)req;
+    handle->pipe.conn.non_overlapped_writes_tail = req;
+  } else {
+    req->next_req = (uv_req_t*)req;
+    handle->pipe.conn.non_overlapped_writes_tail = req;
+  }
+}
+
+
+static uv_write_t* uv_remove_non_overlapped_write_req(uv_pipe_t* handle) {
+  uv_write_t* req;
+
+  if (handle->pipe.conn.non_overlapped_writes_tail) {
+    req = (uv_write_t*)handle->pipe.conn.non_overlapped_writes_tail->next_req;
+
+    if (req == handle->pipe.conn.non_overlapped_writes_tail) {
+      handle->pipe.conn.non_overlapped_writes_tail = NULL;
+    } else {
+      handle->pipe.conn.non_overlapped_writes_tail->next_req =
+        req->next_req;
+    }
+
+    return req;
+  } else {
+    /* queue empty */
+    return NULL;
+  }
+}
+
+
+static void uv__queue_non_overlapped_write(uv_pipe_t* handle) {
+  uv_write_t* req = uv_remove_non_overlapped_write_req(handle);
+  if (req) {
+    if (!QueueUserWorkItem(&uv_pipe_writefile_thread_proc,
+                           req,
+                           WT_EXECUTELONGFUNCTION)) {
+      uv_fatal_error(GetLastError(), "QueueUserWorkItem");
+    }
+  }
+}
+
+
+static int uv__build_coalesced_write_req(uv_write_t* user_req,
+                                         const uv_buf_t bufs[],
+                                         size_t nbufs,
+                                         uv_write_t** req_out,
+                                         uv_buf_t* write_buf_out) {
+  /* Pack into a single heap-allocated buffer:
+   *   (a) a uv_write_t structure where libuv stores the actual state.
+   *   (b) a pointer to the original uv_write_t.
+   *   (c) data from all `bufs` entries.
+   */
+  char* heap_buffer;
+  size_t heap_buffer_length, heap_buffer_offset;
+  uv__coalesced_write_t* coalesced_write_req; /* (a) + (b) */
+  char* data_start;                           /* (c) */
+  size_t data_length;
+  unsigned int i;
+
+  /* Compute combined size of all combined buffers from `bufs`. */
+  data_length = 0;
+  for (i = 0; i < nbufs; i++)
+    data_length += bufs[i].len;
+
+  /* The total combined size of data buffers should not exceed UINT32_MAX,
+   * because WriteFile() won't accept buffers larger than that. */
+  if (data_length > UINT32_MAX)
+    return WSAENOBUFS; /* Maps to UV_ENOBUFS. */
+
+  /* Compute heap buffer size. */
+  heap_buffer_length = sizeof *coalesced_write_req + /* (a) + (b) */
+                       data_length;                  /* (c) */
+
+  /* Allocate buffer. */
+  heap_buffer = (char*)uv__malloc(heap_buffer_length);
+  if (heap_buffer == NULL)
+    return ERROR_NOT_ENOUGH_MEMORY; /* Maps to UV_ENOMEM. */
+
+  /* Copy uv_write_t information to the buffer. */
+  coalesced_write_req = (uv__coalesced_write_t*) heap_buffer;
+  coalesced_write_req->req = *user_req; /* copy (a) */
+  coalesced_write_req->req.coalesced = 1;
+  coalesced_write_req->user_req = user_req;         /* copy (b) */
+  heap_buffer_offset = sizeof *coalesced_write_req; /* offset (a) + (b) */
+
+  /* Copy data buffers to the heap buffer. */
+  data_start = &heap_buffer[heap_buffer_offset];
+  for (i = 0; i < nbufs; i++) {
+    memcpy(&heap_buffer[heap_buffer_offset],
+           bufs[i].base,
+           bufs[i].len);               /* copy (c) */
+    heap_buffer_offset += bufs[i].len; /* offset (c) */
+  }
+  assert(heap_buffer_offset == heap_buffer_length);
+
+  /* Set out arguments and return. */
+  *req_out = &coalesced_write_req->req;
+  *write_buf_out = uv_buf_init(data_start, (unsigned int) data_length);
+  return 0;
+}
+
+
+static int uv__pipe_write_data(uv_loop_t* loop,
+                               uv_write_t* req,
+                               uv_pipe_t* handle,
+                               const uv_buf_t bufs[],
+                               size_t nbufs,
+                               uv_write_cb cb,
+                               int copy_always) {
+  int err;
+  int result;
+  uv_buf_t write_buf;
+
+  assert(handle->handle != INVALID_HANDLE_VALUE);
+
+  UV_REQ_INIT(req, UV_WRITE);
+  req->handle = (uv_stream_t*) handle;
+  req->send_handle = NULL;
+  req->cb = cb;
+  /* Private fields. */
+  req->coalesced = 0;
+  req->event_handle = NULL;
+  req->wait_handle = INVALID_HANDLE_VALUE;
+
+  /* Prepare the overlapped structure. */
+  memset(&req->u.io.overlapped, 0, sizeof(req->u.io.overlapped));
+  if (handle->flags & (UV_HANDLE_EMULATE_IOCP | UV_HANDLE_BLOCKING_WRITES)) {
+    req->event_handle = CreateEvent(NULL, 0, 0, NULL);
+    if (req->event_handle == NULL) {
+      uv_fatal_error(GetLastError(), "CreateEvent");
+    }
+    req->u.io.overlapped.hEvent = (HANDLE) ((uintptr_t) req->event_handle | 1);
+  }
+  req->write_buffer = uv_null_buf_;
+
+  if (nbufs == 0) {
+    /* Write empty buffer. */
+    write_buf = uv_null_buf_;
+  } else if (nbufs == 1 && !copy_always) {
+    /* Write directly from bufs[0]. */
+    write_buf = bufs[0];
+  } else {
+    /* Coalesce all `bufs` into one big buffer. This also creates a new
+     * write-request structure that replaces the old one. */
+    err = uv__build_coalesced_write_req(req, bufs, nbufs, &req, &write_buf);
+    if (err != 0)
+      return err;
+  }
+
+  if ((handle->flags &
+      (UV_HANDLE_BLOCKING_WRITES | UV_HANDLE_NON_OVERLAPPED_PIPE)) ==
+      (UV_HANDLE_BLOCKING_WRITES | UV_HANDLE_NON_OVERLAPPED_PIPE)) {
+    DWORD bytes;
+    result =
+        WriteFile(handle->handle, write_buf.base, write_buf.len, &bytes, NULL);
+
+    if (!result) {
+      err = GetLastError();
+      return err;
+    } else {
+      /* Request completed immediately. */
+      req->u.io.queued_bytes = 0;
+    }
+
+    REGISTER_HANDLE_REQ(loop, handle, req);
+    handle->reqs_pending++;
+    handle->stream.conn.write_reqs_pending++;
+    POST_COMPLETION_FOR_REQ(loop, req);
+    return 0;
+  } else if (handle->flags & UV_HANDLE_NON_OVERLAPPED_PIPE) {
+    req->write_buffer = write_buf;
+    uv__insert_non_overlapped_write_req(handle, req);
+    if (handle->stream.conn.write_reqs_pending == 0) {
+      uv__queue_non_overlapped_write(handle);
+    }
+
+    /* Request queued by the kernel. */
+    req->u.io.queued_bytes = write_buf.len;
+    handle->write_queue_size += req->u.io.queued_bytes;
+  } else if (handle->flags & UV_HANDLE_BLOCKING_WRITES) {
+    /* Using overlapped IO, but wait for completion before returning */
+    result = WriteFile(handle->handle,
+                       write_buf.base,
+                       write_buf.len,
+                       NULL,
+                       &req->u.io.overlapped);
+
+    if (!result && GetLastError() != ERROR_IO_PENDING) {
+      err = GetLastError();
+      CloseHandle(req->event_handle);
+      req->event_handle = NULL;
+      return err;
+    }
+
+    if (result) {
+      /* Request completed immediately. */
+      req->u.io.queued_bytes = 0;
+    } else {
+      /* Request queued by the kernel. */
+      req->u.io.queued_bytes = write_buf.len;
+      handle->write_queue_size += req->u.io.queued_bytes;
+      if (WaitForSingleObject(req->event_handle, INFINITE) !=
+          WAIT_OBJECT_0) {
+        err = GetLastError();
+        CloseHandle(req->event_handle);
+        req->event_handle = NULL;
+        return err;
+      }
+    }
+    CloseHandle(req->event_handle);
+    req->event_handle = NULL;
+
+    REGISTER_HANDLE_REQ(loop, handle, req);
+    handle->reqs_pending++;
+    handle->stream.conn.write_reqs_pending++;
+    return 0;
+  } else {
+    result = WriteFile(handle->handle,
+                       write_buf.base,
+                       write_buf.len,
+                       NULL,
+                       &req->u.io.overlapped);
+
+    if (!result && GetLastError() != ERROR_IO_PENDING) {
+      return GetLastError();
+    }
+
+    if (result) {
+      /* Request completed immediately. */
+      req->u.io.queued_bytes = 0;
+    } else {
+      /* Request queued by the kernel. */
+      req->u.io.queued_bytes = write_buf.len;
+      handle->write_queue_size += req->u.io.queued_bytes;
+    }
+
+    if (handle->flags & UV_HANDLE_EMULATE_IOCP) {
+      if (!RegisterWaitForSingleObject(&req->wait_handle,
+          req->event_handle, post_completion_write_wait, (void*) req,
+          INFINITE, WT_EXECUTEINWAITTHREAD)) {
+        return GetLastError();
+      }
+    }
+  }
+
+  REGISTER_HANDLE_REQ(loop, handle, req);
+  handle->reqs_pending++;
+  handle->stream.conn.write_reqs_pending++;
+
+  return 0;
+}
+
+
+static DWORD uv__pipe_get_ipc_remote_pid(uv_pipe_t* handle) {
+  DWORD* pid = &handle->pipe.conn.ipc_remote_pid;
+
+  /* If the both ends of the IPC pipe are owned by the same process,
+   * the remote end pid may not yet be set. If so, do it here.
+   * TODO: this is weird; it'd probably better to use a handshake. */
+  if (*pid == 0)
+    *pid = GetCurrentProcessId();
+
+  return *pid;
+}
+
+
+int uv__pipe_write_ipc(uv_loop_t* loop,
+                       uv_write_t* req,
+                       uv_pipe_t* handle,
+                       const uv_buf_t data_bufs[],
+                       size_t data_buf_count,
+                       uv_stream_t* send_handle,
+                       uv_write_cb cb) {
+  uv_buf_t stack_bufs[6];
+  uv_buf_t* bufs;
+  size_t buf_count, buf_index;
+  uv__ipc_frame_header_t frame_header;
+  uv__ipc_socket_xfer_type_t xfer_type = UV__IPC_SOCKET_XFER_NONE;
+  uv__ipc_socket_xfer_info_t xfer_info;
+  uint64_t data_length;
+  size_t i;
+  int err;
+
+  /* Compute the combined size of data buffers. */
+  data_length = 0;
+  for (i = 0; i < data_buf_count; i++)
+    data_length += data_bufs[i].len;
+  if (data_length > UINT32_MAX)
+    return WSAENOBUFS; /* Maps to UV_ENOBUFS. */
+
+  /* Prepare the frame's socket xfer payload. */
+  if (send_handle != NULL) {
+    uv_tcp_t* send_tcp_handle = (uv_tcp_t*) send_handle;
+
+    /* Verify that `send_handle` it is indeed a tcp handle. */
+    if (send_tcp_handle->type != UV_TCP)
+      return ERROR_NOT_SUPPORTED;
+
+    /* Export the tcp handle. */
+    err = uv__tcp_xfer_export(send_tcp_handle,
+                              uv__pipe_get_ipc_remote_pid(handle),
+                              &xfer_type,
+                              &xfer_info);
+    if (err != 0)
+      return err;
+  }
+
+  /* Compute the number of uv_buf_t's required. */
+  buf_count = 1 + data_buf_count; /* Frame header and data buffers. */
+  if (send_handle != NULL)
+    buf_count += 1; /* One extra for the socket xfer information. */
+
+  /* Use the on-stack buffer array if it is big enough; otherwise allocate
+   * space for it on the heap. */
+  if (buf_count < ARRAY_SIZE(stack_bufs)) {
+    /* Use on-stack buffer array. */
+    bufs = stack_bufs;
+  } else {
+    /* Use heap-allocated buffer array. */
+    bufs = (uv_buf_t*)uv__calloc(buf_count, sizeof(uv_buf_t));
+    if (bufs == NULL)
+      return ERROR_NOT_ENOUGH_MEMORY; /* Maps to UV_ENOMEM. */
+  }
+  buf_index = 0;
+
+  /* Initialize frame header and add it to the buffers list. */
+  memset(&frame_header, 0, sizeof frame_header);
+  bufs[buf_index++] = uv_buf_init((char*) &frame_header, sizeof frame_header);
+
+  if (send_handle != NULL) {
+    /* Add frame header flags. */
+    switch (xfer_type) {
+      case UV__IPC_SOCKET_XFER_TCP_CONNECTION:
+        frame_header.flags |= UV__IPC_FRAME_HAS_SOCKET_XFER |
+                              UV__IPC_FRAME_XFER_IS_TCP_CONNECTION;
+        break;
+      case UV__IPC_SOCKET_XFER_TCP_SERVER:
+        frame_header.flags |= UV__IPC_FRAME_HAS_SOCKET_XFER;
+        break;
+      default:
+        assert(0);  /* Unreachable. */
+    }
+    /* Add xfer info buffer. */
+    bufs[buf_index++] = uv_buf_init((char*) &xfer_info, sizeof xfer_info);
+  }
+
+  if (data_length > 0) {
+    /* Update frame header. */
+    frame_header.flags |= UV__IPC_FRAME_HAS_DATA;
+    frame_header.data_length = (uint32_t) data_length;
+    /* Add data buffers to buffers list. */
+    for (i = 0; i < data_buf_count; i++)
+      bufs[buf_index++] = data_bufs[i];
+  }
+
+  /* Write buffers. We set the `always_copy` flag, so it is not a problem that
+   * some of the written data lives on the stack. */
+  err = uv__pipe_write_data(loop, req, handle, bufs, buf_count, cb, 1);
+
+  /* If we had to heap-allocate the bufs array, free it now. */
+  if (bufs != stack_bufs) {
+    uv__free(bufs);
+  }
+
+  return err;
+}
+
+
+int uv__pipe_write(uv_loop_t* loop,
+                   uv_write_t* req,
+                   uv_pipe_t* handle,
+                   const uv_buf_t bufs[],
+                   size_t nbufs,
+                   uv_stream_t* send_handle,
+                   uv_write_cb cb) {
+  if (handle->ipc) {
+    /* IPC pipe write: use framing protocol. */
+    return uv__pipe_write_ipc(loop, req, handle, bufs, nbufs, send_handle, cb);
+  } else {
+    /* Non-IPC pipe write: put data on the wire directly. */
+    assert(send_handle == NULL);
+    return uv__pipe_write_data(loop, req, handle, bufs, nbufs, cb, 0);
+  }
+}
+
+
+static void uv__pipe_read_eof(uv_loop_t* loop, uv_pipe_t* handle,
+    uv_buf_t buf) {
+  /* If there is an eof timer running, we don't need it any more, so discard
+   * it. */
+  eof_timer_destroy(handle);
+
+  uv_read_stop((uv_stream_t*) handle);
+
+  handle->read_cb((uv_stream_t*) handle, UV_EOF, &buf);
+}
+
+
+static void uv__pipe_read_error(uv_loop_t* loop, uv_pipe_t* handle, int error,
+    uv_buf_t buf) {
+  /* If there is an eof timer running, we don't need it any more, so discard
+   * it. */
+  eof_timer_destroy(handle);
+
+  uv_read_stop((uv_stream_t*) handle);
+
+  handle->read_cb((uv_stream_t*)handle, uv_translate_sys_error(error), &buf);
+}
+
+
+static void uv__pipe_read_error_or_eof(uv_loop_t* loop, uv_pipe_t* handle,
+    int error, uv_buf_t buf) {
+  if (error == ERROR_BROKEN_PIPE) {
+    uv__pipe_read_eof(loop, handle, buf);
+  } else {
+    uv__pipe_read_error(loop, handle, error, buf);
+  }
+}
+
+
+static void uv__pipe_queue_ipc_xfer_info(
+    uv_pipe_t* handle,
+    uv__ipc_socket_xfer_type_t xfer_type,
+    uv__ipc_socket_xfer_info_t* xfer_info) {
+  uv__ipc_xfer_queue_item_t* item;
+
+  item = (uv__ipc_xfer_queue_item_t*) uv__malloc(sizeof(*item));
+  if (item == NULL)
+    uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+
+  item->xfer_type = xfer_type;
+  item->xfer_info = *xfer_info;
+
+  QUEUE_INSERT_TAIL(&handle->pipe.conn.ipc_xfer_queue, &item->member);
+  handle->pipe.conn.ipc_xfer_queue_length++;
+}
+
+
+/* Read an exact number of bytes from a pipe. If an error or end-of-file is
+ * encountered before the requested number of bytes are read, an error is
+ * returned. */
+static int uv__pipe_read_exactly(HANDLE h, void* buffer, DWORD count) {
+  DWORD bytes_read, bytes_read_now;
+
+  bytes_read = 0;
+  while (bytes_read < count) {
+    if (!ReadFile(h,
+                  (char*) buffer + bytes_read,
+                  count - bytes_read,
+                  &bytes_read_now,
+                  NULL)) {
+      return GetLastError();
+    }
+
+    bytes_read += bytes_read_now;
+  }
+
+  assert(bytes_read == count);
+  return 0;
+}
+
+
+static DWORD uv__pipe_read_data(uv_loop_t* loop,
+                                uv_pipe_t* handle,
+                                DWORD suggested_bytes,
+                                DWORD max_bytes) {
+  DWORD bytes_read;
+  uv_buf_t buf;
+
+  /* Ask the user for a buffer to read data into. */
+  buf = uv_buf_init(NULL, 0);
+  handle->alloc_cb((uv_handle_t*) handle, suggested_bytes, &buf);
+  if (buf.base == NULL || buf.len == 0) {
+    handle->read_cb((uv_stream_t*) handle, UV_ENOBUFS, &buf);
+    return 0; /* Break out of read loop. */
+  }
+
+  /* Ensure we read at most the smaller of:
+   *   (a) the length of the user-allocated buffer.
+   *   (b) the maximum data length as specified by the `max_bytes` argument.
+   */
+  if (max_bytes > buf.len)
+    max_bytes = buf.len;
+
+  /* Read into the user buffer. */
+  if (!ReadFile(handle->handle, buf.base, max_bytes, &bytes_read, NULL)) {
+    uv__pipe_read_error_or_eof(loop, handle, GetLastError(), buf);
+    return 0; /* Break out of read loop. */
+  }
+
+  /* Call the read callback. */
+  handle->read_cb((uv_stream_t*) handle, bytes_read, &buf);
+
+  return bytes_read;
+}
+
+
+static DWORD uv__pipe_read_ipc(uv_loop_t* loop, uv_pipe_t* handle) {
+  uint32_t* data_remaining = &handle->pipe.conn.ipc_data_frame.payload_remaining;
+  int err;
+
+  if (*data_remaining > 0) {
+    /* Read frame data payload. */
+    DWORD bytes_read =
+        uv__pipe_read_data(loop, handle, *data_remaining, *data_remaining);
+    *data_remaining -= bytes_read;
+    return bytes_read;
+
+  } else {
+    /* Start of a new IPC frame. */
+    uv__ipc_frame_header_t frame_header;
+    uint32_t xfer_flags;
+    uv__ipc_socket_xfer_type_t xfer_type;
+    uv__ipc_socket_xfer_info_t xfer_info;
+
+    /* Read the IPC frame header. */
+    err = uv__pipe_read_exactly(
+        handle->handle, &frame_header, sizeof frame_header);
+    if (err)
+      goto error;
+
+    /* Validate that flags are valid. */
+    if ((frame_header.flags & ~UV__IPC_FRAME_VALID_FLAGS) != 0)
+      goto invalid;
+    /* Validate that reserved2 is zero. */
+    if (frame_header.reserved2 != 0)
+      goto invalid;
+
+    /* Parse xfer flags. */
+    xfer_flags = frame_header.flags & UV__IPC_FRAME_XFER_FLAGS;
+    if (xfer_flags & UV__IPC_FRAME_HAS_SOCKET_XFER) {
+      /* Socket coming -- determine the type. */
+      xfer_type = xfer_flags & UV__IPC_FRAME_XFER_IS_TCP_CONNECTION
+                      ? UV__IPC_SOCKET_XFER_TCP_CONNECTION
+                      : UV__IPC_SOCKET_XFER_TCP_SERVER;
+    } else if (xfer_flags == 0) {
+      /* No socket. */
+      xfer_type = UV__IPC_SOCKET_XFER_NONE;
+    } else {
+      /* Invalid flags. */
+      goto invalid;
+    }
+
+    /* Parse data frame information. */
+    if (frame_header.flags & UV__IPC_FRAME_HAS_DATA) {
+      *data_remaining = frame_header.data_length;
+    } else if (frame_header.data_length != 0) {
+      /* Data length greater than zero but data flag not set -- invalid. */
+      goto invalid;
+    }
+
+    /* If no socket xfer info follows, return here. Data will be read in a
+     * subsequent invocation of uv__pipe_read_ipc(). */
+    if (xfer_type == UV__IPC_SOCKET_XFER_NONE)
+      return sizeof frame_header; /* Number of bytes read. */
+
+    /* Read transferred socket information. */
+    err = uv__pipe_read_exactly(handle->handle, &xfer_info, sizeof xfer_info);
+    if (err)
+      goto error;
+
+    /* Store the pending socket info. */
+    uv__pipe_queue_ipc_xfer_info(handle, xfer_type, &xfer_info);
+
+    /* Return number of bytes read. */
+    return sizeof frame_header + sizeof xfer_info;
+  }
+
+invalid:
+  /* Invalid frame. */
+  err = WSAECONNABORTED; /* Maps to UV_ECONNABORTED. */
+
+error:
+  uv__pipe_read_error_or_eof(loop, handle, err, uv_null_buf_);
+  return 0; /* Break out of read loop. */
+}
+
+
+void uv__process_pipe_read_req(uv_loop_t* loop,
+                               uv_pipe_t* handle,
+                               uv_req_t* req) {
+  assert(handle->type == UV_NAMED_PIPE);
+
+  handle->flags &= ~(UV_HANDLE_READ_PENDING | UV_HANDLE_CANCELLATION_PENDING);
+  DECREASE_PENDING_REQ_COUNT(handle);
+  eof_timer_stop(handle);
+
+  /* At this point, we're done with bookkeeping. If the user has stopped
+   * reading the pipe in the meantime, there is nothing left to do, since there
+   * is no callback that we can call. */
+  if (!(handle->flags & UV_HANDLE_READING))
+    return;
+
+  if (!REQ_SUCCESS(req)) {
+    /* An error occurred doing the zero-read. */
+    DWORD err = GET_REQ_ERROR(req);
+
+    /* If the read was cancelled by uv__pipe_interrupt_read(), the request may
+     * indicate an ERROR_OPERATION_ABORTED error. This error isn't relevant to
+     * the user; we'll start a new zero-read at the end of this function. */
+    if (err != ERROR_OPERATION_ABORTED)
+      uv__pipe_read_error_or_eof(loop, handle, err, uv_null_buf_);
+
+  } else {
+    /* The zero-read completed without error, indicating there is data
+     * available in the kernel buffer. */
+    DWORD avail;
+
+    /* Get the number of bytes available. */
+    avail = 0;
+    if (!PeekNamedPipe(handle->handle, NULL, 0, NULL, &avail, NULL))
+      uv__pipe_read_error_or_eof(loop, handle, GetLastError(), uv_null_buf_);
+
+    /* Read until we've either read all the bytes available, or the 'reading'
+     * flag is cleared. */
+    while (avail > 0 && handle->flags & UV_HANDLE_READING) {
+      /* Depending on the type of pipe, read either IPC frames or raw data. */
+      DWORD bytes_read =
+          handle->ipc ? uv__pipe_read_ipc(loop, handle)
+                      : uv__pipe_read_data(loop, handle, avail, (DWORD) -1);
+
+      /* If no bytes were read, treat this as an indication that an error
+       * occurred, and break out of the read loop. */
+      if (bytes_read == 0)
+        break;
+
+      /* It is possible that more bytes were read than we thought were
+       * available. To prevent `avail` from underflowing, break out of the loop
+       * if this is the case. */
+      if (bytes_read > avail)
+        break;
+
+      /* Recompute the number of bytes available. */
+      avail -= bytes_read;
+    }
+  }
+
+  /* Start another zero-read request if necessary. */
+  if ((handle->flags & UV_HANDLE_READING) &&
+      !(handle->flags & UV_HANDLE_READ_PENDING)) {
+    uv__pipe_queue_read(loop, handle);
+  }
+}
+
+
+void uv__process_pipe_write_req(uv_loop_t* loop, uv_pipe_t* handle,
+    uv_write_t* req) {
+  int err;
+
+  assert(handle->type == UV_NAMED_PIPE);
+
+  assert(handle->write_queue_size >= req->u.io.queued_bytes);
+  handle->write_queue_size -= req->u.io.queued_bytes;
+
+  UNREGISTER_HANDLE_REQ(loop, handle, req);
+
+  if (handle->flags & UV_HANDLE_EMULATE_IOCP) {
+    if (req->wait_handle != INVALID_HANDLE_VALUE) {
+      UnregisterWait(req->wait_handle);
+      req->wait_handle = INVALID_HANDLE_VALUE;
+    }
+    if (req->event_handle) {
+      CloseHandle(req->event_handle);
+      req->event_handle = NULL;
+    }
+  }
+
+  err = GET_REQ_ERROR(req);
+
+  /* If this was a coalesced write, extract pointer to the user_provided
+   * uv_write_t structure so we can pass the expected pointer to the callback,
+   * then free the heap-allocated write req. */
+  if (req->coalesced) {
+    uv__coalesced_write_t* coalesced_write =
+        container_of(req, uv__coalesced_write_t, req);
+    req = coalesced_write->user_req;
+    uv__free(coalesced_write);
+  }
+  if (req->cb) {
+    req->cb(req, uv_translate_sys_error(err));
+  }
+
+  handle->stream.conn.write_reqs_pending--;
+
+  if (handle->flags & UV_HANDLE_NON_OVERLAPPED_PIPE &&
+      handle->pipe.conn.non_overlapped_writes_tail) {
+    assert(handle->stream.conn.write_reqs_pending > 0);
+    uv__queue_non_overlapped_write(handle);
+  }
+
+  if (handle->stream.conn.write_reqs_pending == 0)
+    if (handle->flags & UV_HANDLE_SHUTTING)
+      uv__pipe_shutdown(loop, handle, handle->stream.conn.shutdown_req);
+
+  DECREASE_PENDING_REQ_COUNT(handle);
+}
+
+
+void uv__process_pipe_accept_req(uv_loop_t* loop, uv_pipe_t* handle,
+    uv_req_t* raw_req) {
+  uv_pipe_accept_t* req = (uv_pipe_accept_t*) raw_req;
+
+  assert(handle->type == UV_NAMED_PIPE);
+
+  if (handle->flags & UV_HANDLE_CLOSING) {
+    /* The req->pipeHandle should be freed already in uv__pipe_close(). */
+    assert(req->pipeHandle == INVALID_HANDLE_VALUE);
+    DECREASE_PENDING_REQ_COUNT(handle);
+    return;
+  }
+
+  if (REQ_SUCCESS(req)) {
+    assert(req->pipeHandle != INVALID_HANDLE_VALUE);
+    req->next_pending = handle->pipe.serv.pending_accepts;
+    handle->pipe.serv.pending_accepts = req;
+
+    if (handle->stream.serv.connection_cb) {
+      handle->stream.serv.connection_cb((uv_stream_t*)handle, 0);
+    }
+  } else {
+    if (req->pipeHandle != INVALID_HANDLE_VALUE) {
+      CloseHandle(req->pipeHandle);
+      req->pipeHandle = INVALID_HANDLE_VALUE;
+    }
+    if (!(handle->flags & UV_HANDLE_CLOSING)) {
+      uv__pipe_queue_accept(loop, handle, req, FALSE);
+    }
+  }
+
+  DECREASE_PENDING_REQ_COUNT(handle);
+}
+
+
+void uv__process_pipe_connect_req(uv_loop_t* loop, uv_pipe_t* handle,
+    uv_connect_t* req) {
+  HANDLE pipeHandle;
+  DWORD duplex_flags;
+  int err;
+
+  assert(handle->type == UV_NAMED_PIPE);
+
+  UNREGISTER_HANDLE_REQ(loop, handle, req);
+
+  err = 0;
+  if (REQ_SUCCESS(req)) {
+    pipeHandle = req->u.connect.pipeHandle;
+    duplex_flags = req->u.connect.duplex_flags;
+    err = uv__set_pipe_handle(loop, handle, pipeHandle, -1, duplex_flags);
+    if (err)
+      CloseHandle(pipeHandle);
+  } else {
+    err = uv_translate_sys_error(GET_REQ_ERROR(req));
+  }
+
+  if (req->cb)
+    req->cb(req, err);
+
+  DECREASE_PENDING_REQ_COUNT(handle);
+}
+
+
+
+void uv__process_pipe_shutdown_req(uv_loop_t* loop, uv_pipe_t* handle,
+    uv_shutdown_t* req) {
+  int err;
+
+  assert(handle->type == UV_NAMED_PIPE);
+
+  /* Clear the shutdown_req field so we don't go here again. */
+  handle->stream.conn.shutdown_req = NULL;
+  handle->flags &= ~UV_HANDLE_SHUTTING;
+  UNREGISTER_HANDLE_REQ(loop, handle, req);
+
+  if (handle->flags & UV_HANDLE_CLOSING) {
+    /* Already closing. Cancel the shutdown. */
+    err = UV_ECANCELED;
+  } else if (!REQ_SUCCESS(req)) {
+    /* An error occurred in trying to shutdown gracefully. */
+    err = uv_translate_sys_error(GET_REQ_ERROR(req));
+  } else {
+    if (handle->flags & UV_HANDLE_READABLE) {
+      /* Initialize and optionally start the eof timer. Only do this if the pipe
+       * is readable and we haven't seen EOF come in ourselves. */
+      eof_timer_init(handle);
+
+      /* If reading start the timer right now. Otherwise uv__pipe_queue_read will
+       * start it. */
+      if (handle->flags & UV_HANDLE_READ_PENDING) {
+        eof_timer_start(handle);
+      }
+
+    } else {
+      /* This pipe is not readable. We can just close it to let the other end
+       * know that we're done writing. */
+      close_pipe(handle);
+    }
+    err = 0;
+  }
+
+  if (req->cb)
+    req->cb(req, err);
+
+  DECREASE_PENDING_REQ_COUNT(handle);
+}
+
+
+static void eof_timer_init(uv_pipe_t* pipe) {
+  int r;
+
+  assert(pipe->pipe.conn.eof_timer == NULL);
+  assert(pipe->flags & UV_HANDLE_CONNECTION);
+
+  pipe->pipe.conn.eof_timer = (uv_timer_t*) uv__malloc(sizeof *pipe->pipe.conn.eof_timer);
+
+  r = uv_timer_init(pipe->loop, pipe->pipe.conn.eof_timer);
+  assert(r == 0);  /* timers can't fail */
+  (void) r;
+  pipe->pipe.conn.eof_timer->data = pipe;
+  uv_unref((uv_handle_t*) pipe->pipe.conn.eof_timer);
+}
+
+
+static void eof_timer_start(uv_pipe_t* pipe) {
+  assert(pipe->flags & UV_HANDLE_CONNECTION);
+
+  if (pipe->pipe.conn.eof_timer != NULL) {
+    uv_timer_start(pipe->pipe.conn.eof_timer, eof_timer_cb, eof_timeout, 0);
+  }
+}
+
+
+static void eof_timer_stop(uv_pipe_t* pipe) {
+  assert(pipe->flags & UV_HANDLE_CONNECTION);
+
+  if (pipe->pipe.conn.eof_timer != NULL) {
+    uv_timer_stop(pipe->pipe.conn.eof_timer);
+  }
+}
+
+
+static void eof_timer_cb(uv_timer_t* timer) {
+  uv_pipe_t* pipe = (uv_pipe_t*) timer->data;
+  uv_loop_t* loop = timer->loop;
+
+  assert(pipe->type == UV_NAMED_PIPE);
+
+  /* This should always be true, since we start the timer only in
+   * uv__pipe_queue_read after successfully calling ReadFile, or in
+   * uv__process_pipe_shutdown_req if a read is pending, and we always
+   * immediately stop the timer in uv__process_pipe_read_req. */
+  assert(pipe->flags & UV_HANDLE_READ_PENDING);
+
+  /* If there are many packets coming off the iocp then the timer callback may
+   * be called before the read request is coming off the queue. Therefore we
+   * check here if the read request has completed but will be processed later.
+   */
+  if ((pipe->flags & UV_HANDLE_READ_PENDING) &&
+      HasOverlappedIoCompleted(&pipe->read_req.u.io.overlapped)) {
+    return;
+  }
+
+  /* Force both ends off the pipe. */
+  close_pipe(pipe);
+
+  /* Stop reading, so the pending read that is going to fail will not be
+   * reported to the user. */
+  uv_read_stop((uv_stream_t*) pipe);
+
+  /* Report the eof and update flags. This will get reported even if the user
+   * stopped reading in the meantime. TODO: is that okay? */
+  uv__pipe_read_eof(loop, pipe, uv_null_buf_);
+}
+
+
+static void eof_timer_destroy(uv_pipe_t* pipe) {
+  assert(pipe->flags & UV_HANDLE_CONNECTION);
+
+  if (pipe->pipe.conn.eof_timer) {
+    uv_close((uv_handle_t*) pipe->pipe.conn.eof_timer, eof_timer_close_cb);
+    pipe->pipe.conn.eof_timer = NULL;
+  }
+}
+
+
+static void eof_timer_close_cb(uv_handle_t* handle) {
+  assert(handle->type == UV_TIMER);
+  uv__free(handle);
+}
+
+
+int uv_pipe_open(uv_pipe_t* pipe, uv_file file) {
+  HANDLE os_handle = uv__get_osfhandle(file);
+  NTSTATUS nt_status;
+  IO_STATUS_BLOCK io_status;
+  FILE_ACCESS_INFORMATION access;
+  DWORD duplex_flags = 0;
+  int err;
+
+  if (os_handle == INVALID_HANDLE_VALUE)
+    return UV_EBADF;
+  if (pipe->flags & UV_HANDLE_PIPESERVER)
+    return UV_EINVAL;
+  if (pipe->flags & UV_HANDLE_CONNECTION)
+    return UV_EBUSY;
+
+  uv__pipe_connection_init(pipe);
+  uv__once_init();
+  /* In order to avoid closing a stdio file descriptor 0-2, duplicate the
+   * underlying OS handle and forget about the original fd.
+   * We could also opt to use the original OS handle and just never close it,
+   * but then there would be no reliable way to cancel pending read operations
+   * upon close.
+   */
+  if (file <= 2) {
+    if (!DuplicateHandle(INVALID_HANDLE_VALUE,
+                         os_handle,
+                         INVALID_HANDLE_VALUE,
+                         &os_handle,
+                         0,
+                         FALSE,
+                         DUPLICATE_SAME_ACCESS))
+      return uv_translate_sys_error(GetLastError());
+    assert(os_handle != INVALID_HANDLE_VALUE);
+    file = -1;
+  }
+
+  /* Determine what kind of permissions we have on this handle.
+   * Cygwin opens the pipe in message mode, but we can support it,
+   * just query the access flags and set the stream flags accordingly.
+   */
+  nt_status = pNtQueryInformationFile(os_handle,
+                                      &io_status,
+                                      &access,
+                                      sizeof(access),
+                                      FileAccessInformation);
+  if (nt_status != STATUS_SUCCESS)
+    return UV_EINVAL;
+
+  if (pipe->ipc) {
+    if (!(access.AccessFlags & FILE_WRITE_DATA) ||
+        !(access.AccessFlags & FILE_READ_DATA)) {
+      return UV_EINVAL;
+    }
+  }
+
+  if (access.AccessFlags & FILE_WRITE_DATA)
+    duplex_flags |= UV_HANDLE_WRITABLE;
+  if (access.AccessFlags & FILE_READ_DATA)
+    duplex_flags |= UV_HANDLE_READABLE;
+
+  err = uv__set_pipe_handle(pipe->loop,
+                            pipe,
+                            os_handle,
+                            file,
+                            duplex_flags);
+  if (err) {
+    if (file == -1)
+      CloseHandle(os_handle);
+    return err;
+  }
+
+  if (pipe->ipc) {
+    assert(!(pipe->flags & UV_HANDLE_NON_OVERLAPPED_PIPE));
+    pipe->pipe.conn.ipc_remote_pid = uv_os_getppid();
+    assert(pipe->pipe.conn.ipc_remote_pid != (DWORD)(uv_pid_t) -1);
+  }
+  return 0;
+}
+
+
+static int uv__pipe_getname(const uv_pipe_t* handle, char* buffer, size_t* size) {
+  NTSTATUS nt_status;
+  IO_STATUS_BLOCK io_status;
+  FILE_NAME_INFORMATION tmp_name_info;
+  FILE_NAME_INFORMATION* name_info;
+  WCHAR* name_buf;
+  unsigned int addrlen;
+  unsigned int name_size;
+  unsigned int name_len;
+  int err;
+
+  uv__once_init();
+  name_info = NULL;
+
+  if (handle->name != NULL) {
+    /* The user might try to query the name before we are connected,
+     * and this is just easier to return the cached value if we have it. */
+    name_buf = handle->name;
+    name_len = wcslen(name_buf);
+
+    /* check how much space we need */
+    addrlen = WideCharToMultiByte(CP_UTF8,
+                                  0,
+                                  name_buf,
+                                  name_len,
+                                  NULL,
+                                  0,
+                                  NULL,
+                                  NULL);
+    if (!addrlen) {
+      *size = 0;
+      err = uv_translate_sys_error(GetLastError());
+      return err;
+    } else if (addrlen >= *size) {
+      *size = addrlen + 1;
+      err = UV_ENOBUFS;
+      goto error;
+    }
+
+    addrlen = WideCharToMultiByte(CP_UTF8,
+                                  0,
+                                  name_buf,
+                                  name_len,
+                                  buffer,
+                                  addrlen,
+                                  NULL,
+                                  NULL);
+    if (!addrlen) {
+      *size = 0;
+      err = uv_translate_sys_error(GetLastError());
+      return err;
+    }
+
+    *size = addrlen;
+    buffer[addrlen] = '\0';
+
+    return 0;
+  }
+
+  if (handle->handle == INVALID_HANDLE_VALUE) {
+    *size = 0;
+    return UV_EINVAL;
+  }
+
+  /* NtQueryInformationFile will block if another thread is performing a
+   * blocking operation on the queried handle. If the pipe handle is
+   * synchronous, there may be a worker thread currently calling ReadFile() on
+   * the pipe handle, which could cause a deadlock. To avoid this, interrupt
+   * the read. */
+  if (handle->flags & UV_HANDLE_CONNECTION &&
+      handle->flags & UV_HANDLE_NON_OVERLAPPED_PIPE) {
+    uv__pipe_interrupt_read((uv_pipe_t*) handle); /* cast away const warning */
+  }
+
+  nt_status = pNtQueryInformationFile(handle->handle,
+                                      &io_status,
+                                      &tmp_name_info,
+                                      sizeof tmp_name_info,
+                                      FileNameInformation);
+  if (nt_status == STATUS_BUFFER_OVERFLOW) {
+    name_size = sizeof(*name_info) + tmp_name_info.FileNameLength;
+    name_info = (FILE_NAME_INFORMATION*)uv__malloc(name_size);
+    if (!name_info) {
+      *size = 0;
+      err = UV_ENOMEM;
+      goto cleanup;
+    }
+
+    nt_status = pNtQueryInformationFile(handle->handle,
+                                        &io_status,
+                                        name_info,
+                                        name_size,
+                                        FileNameInformation);
+  }
+
+  if (nt_status != STATUS_SUCCESS) {
+    *size = 0;
+    err = uv_translate_sys_error(pRtlNtStatusToDosError(nt_status));
+    goto error;
+  }
+
+  if (!name_info) {
+    /* the struct on stack was used */
+    name_buf = tmp_name_info.FileName;
+    name_len = tmp_name_info.FileNameLength;
+  } else {
+    name_buf = name_info->FileName;
+    name_len = name_info->FileNameLength;
+  }
+
+  if (name_len == 0) {
+    *size = 0;
+    err = 0;
+    goto error;
+  }
+
+  name_len /= sizeof(WCHAR);
+
+  /* check how much space we need */
+  addrlen = WideCharToMultiByte(CP_UTF8,
+                                0,
+                                name_buf,
+                                name_len,
+                                NULL,
+                                0,
+                                NULL,
+                                NULL);
+  if (!addrlen) {
+    *size = 0;
+    err = uv_translate_sys_error(GetLastError());
+    goto error;
+  } else if (pipe_prefix_len + addrlen >= *size) {
+    /* "\\\\.\\pipe" + name */
+    *size = pipe_prefix_len + addrlen + 1;
+    err = UV_ENOBUFS;
+    goto error;
+  }
+
+  memcpy(buffer, pipe_prefix, pipe_prefix_len);
+  addrlen = WideCharToMultiByte(CP_UTF8,
+                                0,
+                                name_buf,
+                                name_len,
+                                buffer+pipe_prefix_len,
+                                *size-pipe_prefix_len,
+                                NULL,
+                                NULL);
+  if (!addrlen) {
+    *size = 0;
+    err = uv_translate_sys_error(GetLastError());
+    goto error;
+  }
+
+  addrlen += pipe_prefix_len;
+  *size = addrlen;
+  buffer[addrlen] = '\0';
+
+  err = 0;
+
+error:
+  uv__free(name_info);
+
+cleanup:
+  return err;
+}
+
+
+int uv_pipe_pending_count(uv_pipe_t* handle) {
+  if (!handle->ipc)
+    return 0;
+  return handle->pipe.conn.ipc_xfer_queue_length;
+}
+
+
+int uv_pipe_getsockname(const uv_pipe_t* handle, char* buffer, size_t* size) {
+  if (handle->flags & UV_HANDLE_BOUND)
+    return uv__pipe_getname(handle, buffer, size);
+
+  if (handle->flags & UV_HANDLE_CONNECTION ||
+      handle->handle != INVALID_HANDLE_VALUE) {
+    *size = 0;
+    return 0;
+  }
+
+  return UV_EBADF;
+}
+
+
+int uv_pipe_getpeername(const uv_pipe_t* handle, char* buffer, size_t* size) {
+  /* emulate unix behaviour */
+  if (handle->flags & UV_HANDLE_BOUND)
+    return UV_ENOTCONN;
+
+  if (handle->handle != INVALID_HANDLE_VALUE)
+    return uv__pipe_getname(handle, buffer, size);
+
+  if (handle->flags & UV_HANDLE_CONNECTION) {
+    if (handle->name != NULL)
+      return uv__pipe_getname(handle, buffer, size);
+  }
+
+  return UV_EBADF;
+}
+
+
+uv_handle_type uv_pipe_pending_type(uv_pipe_t* handle) {
+  if (!handle->ipc)
+    return UV_UNKNOWN_HANDLE;
+  if (handle->pipe.conn.ipc_xfer_queue_length == 0)
+    return UV_UNKNOWN_HANDLE;
+  else
+    return UV_TCP;
+}
+
+int uv_pipe_chmod(uv_pipe_t* handle, int mode) {
+  SID_IDENTIFIER_AUTHORITY sid_world = { SECURITY_WORLD_SID_AUTHORITY };
+  PACL old_dacl, new_dacl;
+  PSECURITY_DESCRIPTOR sd;
+  EXPLICIT_ACCESS ea;
+  PSID everyone;
+  int error;
+
+  if (handle == NULL || handle->handle == INVALID_HANDLE_VALUE)
+    return UV_EBADF;
+
+  if (mode != UV_READABLE &&
+      mode != UV_WRITABLE &&
+      mode != (UV_WRITABLE | UV_READABLE))
+    return UV_EINVAL;
+
+  if (!AllocateAndInitializeSid(&sid_world,
+                                1,
+                                SECURITY_WORLD_RID,
+                                0, 0, 0, 0, 0, 0, 0,
+                                &everyone)) {
+    error = GetLastError();
+    goto done;
+  }
+
+  if (GetSecurityInfo(handle->handle,
+                      SE_KERNEL_OBJECT,
+                      DACL_SECURITY_INFORMATION,
+                      NULL,
+                      NULL,
+                      &old_dacl,
+                      NULL,
+                      &sd)) {
+    error = GetLastError();
+    goto clean_sid;
+  }
+
+  memset(&ea, 0, sizeof(EXPLICIT_ACCESS));
+  if (mode & UV_READABLE)
+    ea.grfAccessPermissions |= GENERIC_READ | FILE_WRITE_ATTRIBUTES;
+  if (mode & UV_WRITABLE)
+    ea.grfAccessPermissions |= GENERIC_WRITE | FILE_READ_ATTRIBUTES;
+  ea.grfAccessPermissions |= SYNCHRONIZE;
+  ea.grfAccessMode = SET_ACCESS;
+  ea.grfInheritance = NO_INHERITANCE;
+  ea.Trustee.TrusteeForm = TRUSTEE_IS_SID;
+  ea.Trustee.TrusteeType = TRUSTEE_IS_WELL_KNOWN_GROUP;
+  ea.Trustee.ptstrName = (LPTSTR)everyone;
+
+  if (SetEntriesInAcl(1, &ea, old_dacl, &new_dacl)) {
+    error = GetLastError();
+    goto clean_sd;
+  }
+
+  if (SetSecurityInfo(handle->handle,
+                      SE_KERNEL_OBJECT,
+                      DACL_SECURITY_INFORMATION,
+                      NULL,
+                      NULL,
+                      new_dacl,
+                      NULL)) {
+    error = GetLastError();
+    goto clean_dacl;
+  }
+
+  error = 0;
+
+clean_dacl:
+  LocalFree((HLOCAL) new_dacl);
+clean_sd:
+  LocalFree((HLOCAL) sd);
+clean_sid:
+  FreeSid(everyone);
+done:
+  return uv_translate_sys_error(error);
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/poll.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/poll.cpp
new file mode 100644
index 0000000..bd531b0
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/poll.cpp
@@ -0,0 +1,587 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <assert.h>
+#include <io.h>
+
+#include "uv.h"
+#include "internal.h"
+#include "handle-inl.h"
+#include "req-inl.h"
+
+
+static const GUID uv_msafd_provider_ids[UV_MSAFD_PROVIDER_COUNT] = {
+  {0xe70f1aa0, 0xab8b, 0x11cf,
+      {0x8c, 0xa3, 0x00, 0x80, 0x5f, 0x48, 0xa1, 0x92}},
+  {0xf9eab0c0, 0x26d4, 0x11d0,
+      {0xbb, 0xbf, 0x00, 0xaa, 0x00, 0x6c, 0x34, 0xe4}},
+  {0x9fc48064, 0x7298, 0x43e4,
+      {0xb7, 0xbd, 0x18, 0x1f, 0x20, 0x89, 0x79, 0x2a}},
+  {0xa00943d9, 0x9c2e, 0x4633,
+      {0x9b, 0x59, 0x00, 0x57, 0xa3, 0x16, 0x09, 0x94}}
+};
+
+typedef struct uv_single_fd_set_s {
+  unsigned int fd_count;
+  SOCKET fd_array[1];
+} uv_single_fd_set_t;
+
+
+static OVERLAPPED overlapped_dummy_;
+static uv_once_t overlapped_dummy_init_guard_ = UV_ONCE_INIT;
+
+static AFD_POLL_INFO afd_poll_info_dummy_;
+
+
+static void uv__init_overlapped_dummy(void) {
+  HANDLE event;
+
+  event = CreateEvent(NULL, TRUE, TRUE, NULL);
+  if (event == NULL)
+    uv_fatal_error(GetLastError(), "CreateEvent");
+
+  memset(&overlapped_dummy_, 0, sizeof overlapped_dummy_);
+  overlapped_dummy_.hEvent = (HANDLE) ((uintptr_t) event | 1);
+}
+
+
+static OVERLAPPED* uv__get_overlapped_dummy(void) {
+  uv_once(&overlapped_dummy_init_guard_, uv__init_overlapped_dummy);
+  return &overlapped_dummy_;
+}
+
+
+static AFD_POLL_INFO* uv__get_afd_poll_info_dummy(void) {
+  return &afd_poll_info_dummy_;
+}
+
+
+static void uv__fast_poll_submit_poll_req(uv_loop_t* loop, uv_poll_t* handle) {
+  uv_req_t* req;
+  AFD_POLL_INFO* afd_poll_info;
+  int result;
+
+  /* Find a yet unsubmitted req to submit. */
+  if (handle->submitted_events_1 == 0) {
+    req = &handle->poll_req_1;
+    afd_poll_info = &handle->afd_poll_info_1;
+    handle->submitted_events_1 = handle->events;
+    handle->mask_events_1 = 0;
+    handle->mask_events_2 = handle->events;
+  } else if (handle->submitted_events_2 == 0) {
+    req = &handle->poll_req_2;
+    afd_poll_info = &handle->afd_poll_info_2;
+    handle->submitted_events_2 = handle->events;
+    handle->mask_events_1 = handle->events;
+    handle->mask_events_2 = 0;
+  } else {
+    /* Just wait until there's an unsubmitted req. This will happen almost
+     * immediately as one of the 2 outstanding requests is about to return.
+     * When this happens, uv__fast_poll_process_poll_req will be called, and
+     * the pending events, if needed, will be processed in a subsequent
+     * request. */
+    return;
+  }
+
+  /* Setting Exclusive to TRUE makes the other poll request return if there is
+   * any. */
+  afd_poll_info->Exclusive = TRUE;
+  afd_poll_info->NumberOfHandles = 1;
+  afd_poll_info->Timeout.QuadPart = INT64_MAX;
+  afd_poll_info->Handles[0].Handle = (HANDLE) handle->socket;
+  afd_poll_info->Handles[0].Status = 0;
+  afd_poll_info->Handles[0].Events = 0;
+
+  if (handle->events & UV_READABLE) {
+    afd_poll_info->Handles[0].Events |= AFD_POLL_RECEIVE |
+        AFD_POLL_DISCONNECT | AFD_POLL_ACCEPT | AFD_POLL_ABORT;
+  } else {
+    if (handle->events & UV_DISCONNECT) {
+      afd_poll_info->Handles[0].Events |= AFD_POLL_DISCONNECT;
+    }
+  }
+  if (handle->events & UV_WRITABLE) {
+    afd_poll_info->Handles[0].Events |= AFD_POLL_SEND | AFD_POLL_CONNECT_FAIL;
+  }
+
+  memset(&req->u.io.overlapped, 0, sizeof req->u.io.overlapped);
+
+  result = uv__msafd_poll((SOCKET) handle->peer_socket,
+                          afd_poll_info,
+                          afd_poll_info,
+                          &req->u.io.overlapped);
+  if (result != 0 && WSAGetLastError() != WSA_IO_PENDING) {
+    /* Queue this req, reporting an error. */
+    SET_REQ_ERROR(req, WSAGetLastError());
+    uv__insert_pending_req(loop, req);
+  }
+}
+
+
+static void uv__fast_poll_process_poll_req(uv_loop_t* loop, uv_poll_t* handle,
+    uv_req_t* req) {
+  unsigned char mask_events;
+  AFD_POLL_INFO* afd_poll_info;
+
+  if (req == &handle->poll_req_1) {
+    afd_poll_info = &handle->afd_poll_info_1;
+    handle->submitted_events_1 = 0;
+    mask_events = handle->mask_events_1;
+  } else if (req == &handle->poll_req_2) {
+    afd_poll_info = &handle->afd_poll_info_2;
+    handle->submitted_events_2 = 0;
+    mask_events = handle->mask_events_2;
+  } else {
+    assert(0);
+    return;
+  }
+
+  /* Report an error unless the select was just interrupted. */
+  if (!REQ_SUCCESS(req)) {
+    DWORD error = GET_REQ_SOCK_ERROR(req);
+    if (error != WSAEINTR && handle->events != 0) {
+      handle->events = 0; /* Stop the watcher */
+      handle->poll_cb(handle, uv_translate_sys_error(error), 0);
+    }
+
+  } else if (afd_poll_info->NumberOfHandles >= 1) {
+    unsigned char events = 0;
+
+    if ((afd_poll_info->Handles[0].Events & (AFD_POLL_RECEIVE |
+        AFD_POLL_DISCONNECT | AFD_POLL_ACCEPT | AFD_POLL_ABORT)) != 0) {
+      events |= UV_READABLE;
+      if ((afd_poll_info->Handles[0].Events & AFD_POLL_DISCONNECT) != 0) {
+        events |= UV_DISCONNECT;
+      }
+    }
+    if ((afd_poll_info->Handles[0].Events & (AFD_POLL_SEND |
+        AFD_POLL_CONNECT_FAIL)) != 0) {
+      events |= UV_WRITABLE;
+    }
+
+    events &= handle->events & ~mask_events;
+
+    if (afd_poll_info->Handles[0].Events & AFD_POLL_LOCAL_CLOSE) {
+      /* Stop polling. */
+      handle->events = 0;
+      if (uv__is_active(handle))
+        uv__handle_stop(handle);
+    }
+
+    if (events != 0) {
+      handle->poll_cb(handle, 0, events);
+    }
+  }
+
+  if ((handle->events & ~(handle->submitted_events_1 |
+      handle->submitted_events_2)) != 0) {
+    uv__fast_poll_submit_poll_req(loop, handle);
+  } else if ((handle->flags & UV_HANDLE_CLOSING) &&
+             handle->submitted_events_1 == 0 &&
+             handle->submitted_events_2 == 0) {
+    uv__want_endgame(loop, (uv_handle_t*) handle);
+  }
+}
+
+
+static SOCKET uv__fast_poll_create_peer_socket(HANDLE iocp,
+    WSAPROTOCOL_INFOW* protocol_info) {
+  SOCKET sock = 0;
+
+  sock = WSASocketW(protocol_info->iAddressFamily,
+                    protocol_info->iSocketType,
+                    protocol_info->iProtocol,
+                    protocol_info,
+                    0,
+                    WSA_FLAG_OVERLAPPED);
+  if (sock == INVALID_SOCKET) {
+    return INVALID_SOCKET;
+  }
+
+  if (!SetHandleInformation((HANDLE) sock, HANDLE_FLAG_INHERIT, 0)) {
+    goto error;
+  };
+
+  if (CreateIoCompletionPort((HANDLE) sock,
+                             iocp,
+                             (ULONG_PTR) sock,
+                             0) == NULL) {
+    goto error;
+  }
+
+  return sock;
+
+ error:
+  closesocket(sock);
+  return INVALID_SOCKET;
+}
+
+
+static SOCKET uv__fast_poll_get_peer_socket(uv_loop_t* loop,
+    WSAPROTOCOL_INFOW* protocol_info) {
+  int index, i;
+  SOCKET peer_socket;
+
+  index = -1;
+  for (i = 0; (size_t) i < ARRAY_SIZE(uv_msafd_provider_ids); i++) {
+    if (memcmp((void*) &protocol_info->ProviderId,
+               (void*) &uv_msafd_provider_ids[i],
+               sizeof protocol_info->ProviderId) == 0) {
+      index = i;
+    }
+  }
+
+  /* Check if the protocol uses an msafd socket. */
+  if (index < 0) {
+    return INVALID_SOCKET;
+  }
+
+  /* If we didn't (try) to create a peer socket yet, try to make one. Don't try
+   * again if the peer socket creation failed earlier for the same protocol. */
+  peer_socket = loop->poll_peer_sockets[index];
+  if (peer_socket == 0) {
+    peer_socket = uv__fast_poll_create_peer_socket(loop->iocp, protocol_info);
+    loop->poll_peer_sockets[index] = peer_socket;
+  }
+
+  return peer_socket;
+}
+
+
+static DWORD WINAPI uv__slow_poll_thread_proc(void* arg) {
+  uv_req_t* req = (uv_req_t*) arg;
+  uv_poll_t* handle = (uv_poll_t*) req->data;
+  unsigned char reported_events;
+  int r;
+  uv_single_fd_set_t rfds, wfds, efds;
+  struct timeval timeout;
+
+  assert(handle->type == UV_POLL);
+  assert(req->type == UV_POLL_REQ);
+
+  if (handle->events & UV_READABLE) {
+    rfds.fd_count = 1;
+    rfds.fd_array[0] = handle->socket;
+  } else {
+    rfds.fd_count = 0;
+  }
+
+  if (handle->events & UV_WRITABLE) {
+    wfds.fd_count = 1;
+    wfds.fd_array[0] = handle->socket;
+    efds.fd_count = 1;
+    efds.fd_array[0] = handle->socket;
+  } else {
+    wfds.fd_count = 0;
+    efds.fd_count = 0;
+  }
+
+  /* Make the select() time out after 3 minutes. If select() hangs because the
+   * user closed the socket, we will at least not hang indefinitely. */
+  timeout.tv_sec = 3 * 60;
+  timeout.tv_usec = 0;
+
+  r = select(1, (fd_set*) &rfds, (fd_set*) &wfds, (fd_set*) &efds, &timeout);
+  if (r == SOCKET_ERROR) {
+    /* Queue this req, reporting an error. */
+    SET_REQ_ERROR(&handle->poll_req_1, WSAGetLastError());
+    POST_COMPLETION_FOR_REQ(handle->loop, req);
+    return 0;
+  }
+
+  reported_events = 0;
+
+  if (r > 0) {
+    if (rfds.fd_count > 0) {
+      assert(rfds.fd_count == 1);
+      assert(rfds.fd_array[0] == handle->socket);
+      reported_events |= UV_READABLE;
+    }
+
+    if (wfds.fd_count > 0) {
+      assert(wfds.fd_count == 1);
+      assert(wfds.fd_array[0] == handle->socket);
+      reported_events |= UV_WRITABLE;
+    } else if (efds.fd_count > 0) {
+      assert(efds.fd_count == 1);
+      assert(efds.fd_array[0] == handle->socket);
+      reported_events |= UV_WRITABLE;
+    }
+  }
+
+  SET_REQ_SUCCESS(req);
+  req->u.io.overlapped.InternalHigh = (DWORD) reported_events;
+  POST_COMPLETION_FOR_REQ(handle->loop, req);
+
+  return 0;
+}
+
+
+static void uv__slow_poll_submit_poll_req(uv_loop_t* loop, uv_poll_t* handle) {
+  uv_req_t* req;
+
+  /* Find a yet unsubmitted req to submit. */
+  if (handle->submitted_events_1 == 0) {
+    req = &handle->poll_req_1;
+    handle->submitted_events_1 = handle->events;
+    handle->mask_events_1 = 0;
+    handle->mask_events_2 = handle->events;
+  } else if (handle->submitted_events_2 == 0) {
+    req = &handle->poll_req_2;
+    handle->submitted_events_2 = handle->events;
+    handle->mask_events_1 = handle->events;
+    handle->mask_events_2 = 0;
+  } else {
+    assert(0);
+    return;
+  }
+
+  if (!QueueUserWorkItem(uv__slow_poll_thread_proc,
+                         (void*) req,
+                         WT_EXECUTELONGFUNCTION)) {
+    /* Make this req pending, reporting an error. */
+    SET_REQ_ERROR(req, GetLastError());
+    uv__insert_pending_req(loop, req);
+  }
+}
+
+
+
+static void uv__slow_poll_process_poll_req(uv_loop_t* loop, uv_poll_t* handle,
+    uv_req_t* req) {
+  unsigned char mask_events;
+  int err;
+
+  if (req == &handle->poll_req_1) {
+    handle->submitted_events_1 = 0;
+    mask_events = handle->mask_events_1;
+  } else if (req == &handle->poll_req_2) {
+    handle->submitted_events_2 = 0;
+    mask_events = handle->mask_events_2;
+  } else {
+    assert(0);
+    return;
+  }
+
+  if (!REQ_SUCCESS(req)) {
+    /* Error. */
+    if (handle->events != 0) {
+      err = GET_REQ_ERROR(req);
+      handle->events = 0; /* Stop the watcher */
+      handle->poll_cb(handle, uv_translate_sys_error(err), 0);
+    }
+  } else {
+    /* Got some events. */
+    int events = req->u.io.overlapped.InternalHigh & handle->events & ~mask_events;
+    if (events != 0) {
+      handle->poll_cb(handle, 0, events);
+    }
+  }
+
+  if ((handle->events & ~(handle->submitted_events_1 |
+      handle->submitted_events_2)) != 0) {
+    uv__slow_poll_submit_poll_req(loop, handle);
+  } else if ((handle->flags & UV_HANDLE_CLOSING) &&
+             handle->submitted_events_1 == 0 &&
+             handle->submitted_events_2 == 0) {
+    uv__want_endgame(loop, (uv_handle_t*) handle);
+  }
+}
+
+
+int uv_poll_init(uv_loop_t* loop, uv_poll_t* handle, int fd) {
+  return uv_poll_init_socket(loop, handle, (SOCKET) uv__get_osfhandle(fd));
+}
+
+
+int uv_poll_init_socket(uv_loop_t* loop, uv_poll_t* handle,
+    uv_os_sock_t socket) {
+  WSAPROTOCOL_INFOW protocol_info;
+  int len;
+  SOCKET peer_socket, base_socket;
+  DWORD bytes;
+  DWORD yes = 1;
+
+  /* Set the socket to nonblocking mode */
+  if (ioctlsocket(socket, FIONBIO, &yes) == SOCKET_ERROR)
+    return uv_translate_sys_error(WSAGetLastError());
+
+/* Try to obtain a base handle for the socket. This increases this chances that
+ * we find an AFD handle and are able to use the fast poll mechanism. This will
+ * always fail on windows XP/2k3, since they don't support the. SIO_BASE_HANDLE
+ * ioctl. */
+#ifndef NDEBUG
+  base_socket = INVALID_SOCKET;
+#endif
+
+  if (WSAIoctl(socket,
+               SIO_BASE_HANDLE,
+               NULL,
+               0,
+               &base_socket,
+               sizeof base_socket,
+               &bytes,
+               NULL,
+               NULL) == 0) {
+    assert(base_socket != 0 && base_socket != INVALID_SOCKET);
+    socket = base_socket;
+  }
+
+  uv__handle_init(loop, (uv_handle_t*) handle, UV_POLL);
+  handle->socket = socket;
+  handle->events = 0;
+
+  /* Obtain protocol information about the socket. */
+  len = sizeof protocol_info;
+  if (getsockopt(socket,
+                 SOL_SOCKET,
+                 SO_PROTOCOL_INFOW,
+                 (char*) &protocol_info,
+                 &len) != 0) {
+    return uv_translate_sys_error(WSAGetLastError());
+  }
+
+  /* Get the peer socket that is needed to enable fast poll. If the returned
+   * value is NULL, the protocol is not implemented by MSAFD and we'll have to
+   * use slow mode. */
+  peer_socket = uv__fast_poll_get_peer_socket(loop, &protocol_info);
+
+  if (peer_socket != INVALID_SOCKET) {
+    /* Initialize fast poll specific fields. */
+    handle->peer_socket = peer_socket;
+  } else {
+    /* Initialize slow poll specific fields. */
+    handle->flags |= UV_HANDLE_POLL_SLOW;
+  }
+
+  /* Initialize 2 poll reqs. */
+  handle->submitted_events_1 = 0;
+  UV_REQ_INIT(&handle->poll_req_1, UV_POLL_REQ);
+  handle->poll_req_1.data = handle;
+
+  handle->submitted_events_2 = 0;
+  UV_REQ_INIT(&handle->poll_req_2, UV_POLL_REQ);
+  handle->poll_req_2.data = handle;
+
+  return 0;
+}
+
+
+static int uv__poll_set(uv_poll_t* handle, int events, uv_poll_cb cb) {
+  int submitted_events;
+
+  assert(handle->type == UV_POLL);
+  assert(!(handle->flags & UV_HANDLE_CLOSING));
+  assert((events & ~(UV_READABLE | UV_WRITABLE | UV_DISCONNECT |
+                     UV_PRIORITIZED)) == 0);
+
+  handle->events = events;
+  handle->poll_cb = cb;
+
+  if (handle->events == 0) {
+    uv__handle_stop(handle);
+    return 0;
+  }
+
+  uv__handle_start(handle);
+  submitted_events = handle->submitted_events_1 | handle->submitted_events_2;
+
+  if (handle->events & ~submitted_events) {
+    if (handle->flags & UV_HANDLE_POLL_SLOW) {
+      uv__slow_poll_submit_poll_req(handle->loop, handle);
+    } else {
+      uv__fast_poll_submit_poll_req(handle->loop, handle);
+    }
+  }
+
+  return 0;
+}
+
+
+int uv_poll_start(uv_poll_t* handle, int events, uv_poll_cb cb) {
+  return uv__poll_set(handle, events, cb);
+}
+
+
+int uv_poll_stop(uv_poll_t* handle) {
+  return uv__poll_set(handle, 0, handle->poll_cb);
+}
+
+
+void uv__process_poll_req(uv_loop_t* loop, uv_poll_t* handle, uv_req_t* req) {
+  if (!(handle->flags & UV_HANDLE_POLL_SLOW)) {
+    uv__fast_poll_process_poll_req(loop, handle, req);
+  } else {
+    uv__slow_poll_process_poll_req(loop, handle, req);
+  }
+}
+
+
+int uv__poll_close(uv_loop_t* loop, uv_poll_t* handle) {
+  AFD_POLL_INFO afd_poll_info;
+  DWORD error;
+  int result;
+
+  handle->events = 0;
+  uv__handle_closing(handle);
+
+  if (handle->submitted_events_1 == 0 &&
+      handle->submitted_events_2 == 0) {
+    uv__want_endgame(loop, (uv_handle_t*) handle);
+    return 0;
+  }
+
+  if (handle->flags & UV_HANDLE_POLL_SLOW)
+    return 0;
+
+  /* Cancel outstanding poll requests by executing another, unique poll
+   * request that forces the outstanding ones to return. */
+  afd_poll_info.Exclusive = TRUE;
+  afd_poll_info.NumberOfHandles = 1;
+  afd_poll_info.Timeout.QuadPart = INT64_MAX;
+  afd_poll_info.Handles[0].Handle = (HANDLE) handle->socket;
+  afd_poll_info.Handles[0].Status = 0;
+  afd_poll_info.Handles[0].Events = AFD_POLL_ALL;
+
+  result = uv__msafd_poll(handle->socket,
+                          &afd_poll_info,
+                          uv__get_afd_poll_info_dummy(),
+                          uv__get_overlapped_dummy());
+
+  if (result == SOCKET_ERROR) {
+    error = WSAGetLastError();
+    if (error != WSA_IO_PENDING)
+      return uv_translate_sys_error(error);
+  }
+
+  return 0;
+}
+
+
+void uv__poll_endgame(uv_loop_t* loop, uv_poll_t* handle) {
+  assert(handle->flags & UV_HANDLE_CLOSING);
+  assert(!(handle->flags & UV_HANDLE_CLOSED));
+
+  assert(handle->submitted_events_1 == 0);
+  assert(handle->submitted_events_2 == 0);
+
+  uv__handle_close(handle);
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/process-stdio.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/process-stdio.cpp
new file mode 100644
index 0000000..0db3572
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/process-stdio.cpp
@@ -0,0 +1,416 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <assert.h>
+#include <io.h>
+#include <stdio.h>
+#include <stdlib.h>
+
+#include "uv.h"
+#include "internal.h"
+#include "handle-inl.h"
+
+
+/*
+ * The `child_stdio_buffer` buffer has the following layout:
+ *   int number_of_fds
+ *   unsigned char crt_flags[number_of_fds]
+ *   HANDLE os_handle[number_of_fds]
+ */
+#define CHILD_STDIO_SIZE(count)                     \
+    (sizeof(int) +                                  \
+     sizeof(unsigned char) * (count) +              \
+     sizeof(uintptr_t) * (count))
+
+#define CHILD_STDIO_COUNT(buffer)                   \
+    *((unsigned int*) (buffer))
+
+#define CHILD_STDIO_CRT_FLAGS(buffer, fd)           \
+    *((unsigned char*) (buffer) + sizeof(int) + fd)
+
+#define CHILD_STDIO_HANDLE(buffer, fd)              \
+    *((HANDLE*) ((unsigned char*) (buffer) +        \
+                 sizeof(int) +                      \
+                 sizeof(unsigned char) *            \
+                 CHILD_STDIO_COUNT((buffer)) +      \
+                 sizeof(HANDLE) * (fd)))
+
+
+/* CRT file descriptor mode flags */
+#define FOPEN       0x01
+#define FEOFLAG     0x02
+#define FCRLF       0x04
+#define FPIPE       0x08
+#define FNOINHERIT  0x10
+#define FAPPEND     0x20
+#define FDEV        0x40
+#define FTEXT       0x80
+
+
+/*
+ * Clear the HANDLE_FLAG_INHERIT flag from all HANDLEs that were inherited
+ * the parent process. Don't check for errors - the stdio handles may not be
+ * valid, or may be closed already. There is no guarantee that this function
+ * does a perfect job.
+ */
+void uv_disable_stdio_inheritance(void) {
+  HANDLE handle;
+  STARTUPINFOW si;
+
+  /* Make the windows stdio handles non-inheritable. */
+  handle = GetStdHandle(STD_INPUT_HANDLE);
+  if (handle != NULL && handle != INVALID_HANDLE_VALUE)
+    SetHandleInformation(handle, HANDLE_FLAG_INHERIT, 0);
+
+  handle = GetStdHandle(STD_OUTPUT_HANDLE);
+  if (handle != NULL && handle != INVALID_HANDLE_VALUE)
+    SetHandleInformation(handle, HANDLE_FLAG_INHERIT, 0);
+
+  handle = GetStdHandle(STD_ERROR_HANDLE);
+  if (handle != NULL && handle != INVALID_HANDLE_VALUE)
+    SetHandleInformation(handle, HANDLE_FLAG_INHERIT, 0);
+
+  /* Make inherited CRT FDs non-inheritable. */
+  GetStartupInfoW(&si);
+  if (uv__stdio_verify(si.lpReserved2, si.cbReserved2))
+    uv__stdio_noinherit(si.lpReserved2);
+}
+
+
+static int uv__duplicate_handle(uv_loop_t* loop, HANDLE handle, HANDLE* dup) {
+  HANDLE current_process;
+
+
+  /* _get_osfhandle will sometimes return -2 in case of an error. This seems to
+   * happen when fd <= 2 and the process' corresponding stdio handle is set to
+   * NULL. Unfortunately DuplicateHandle will happily duplicate (HANDLE) -2, so
+   * this situation goes unnoticed until someone tries to use the duplicate.
+   * Therefore we filter out known-invalid handles here. */
+  if (handle == INVALID_HANDLE_VALUE ||
+      handle == NULL ||
+      handle == (HANDLE) -2) {
+    *dup = INVALID_HANDLE_VALUE;
+    return ERROR_INVALID_HANDLE;
+  }
+
+  current_process = GetCurrentProcess();
+
+  if (!DuplicateHandle(current_process,
+                       handle,
+                       current_process,
+                       dup,
+                       0,
+                       TRUE,
+                       DUPLICATE_SAME_ACCESS)) {
+    *dup = INVALID_HANDLE_VALUE;
+    return GetLastError();
+  }
+
+  return 0;
+}
+
+
+static int uv__duplicate_fd(uv_loop_t* loop, int fd, HANDLE* dup) {
+  HANDLE handle;
+
+  if (fd == -1) {
+    *dup = INVALID_HANDLE_VALUE;
+    return ERROR_INVALID_HANDLE;
+  }
+
+  handle = uv__get_osfhandle(fd);
+  return uv__duplicate_handle(loop, handle, dup);
+}
+
+
+int uv__create_nul_handle(HANDLE* handle_ptr,
+    DWORD access) {
+  HANDLE handle;
+  SECURITY_ATTRIBUTES sa;
+
+  sa.nLength = sizeof sa;
+  sa.lpSecurityDescriptor = NULL;
+  sa.bInheritHandle = TRUE;
+
+  handle = CreateFileW(L"NUL",
+                       access,
+                       FILE_SHARE_READ | FILE_SHARE_WRITE,
+                       &sa,
+                       OPEN_EXISTING,
+                       0,
+                       NULL);
+  if (handle == INVALID_HANDLE_VALUE) {
+    return GetLastError();
+  }
+
+  *handle_ptr = handle;
+  return 0;
+}
+
+
+int uv__stdio_create(uv_loop_t* loop,
+                     const uv_process_options_t* options,
+                     BYTE** buffer_ptr) {
+  BYTE* buffer;
+  int count, i;
+  int err;
+
+  count = options->stdio_count;
+
+  if (count < 0 || count > 255) {
+    /* Only support FDs 0-255 */
+    return ERROR_NOT_SUPPORTED;
+  } else if (count < 3) {
+    /* There should always be at least 3 stdio handles. */
+    count = 3;
+  }
+
+  /* Allocate the child stdio buffer */
+  buffer = (BYTE*) uv__malloc(CHILD_STDIO_SIZE(count));
+  if (buffer == NULL) {
+    return ERROR_OUTOFMEMORY;
+  }
+
+  /* Prepopulate the buffer with INVALID_HANDLE_VALUE handles so we can clean
+   * up on failure. */
+  CHILD_STDIO_COUNT(buffer) = count;
+  for (i = 0; i < count; i++) {
+    CHILD_STDIO_CRT_FLAGS(buffer, i) = 0;
+    CHILD_STDIO_HANDLE(buffer, i) = INVALID_HANDLE_VALUE;
+  }
+
+  for (i = 0; i < count; i++) {
+    uv_stdio_container_t fdopt;
+    if (i < options->stdio_count) {
+      fdopt = options->stdio[i];
+    } else {
+      fdopt.flags = UV_IGNORE;
+    }
+
+    switch (fdopt.flags & (UV_IGNORE | UV_CREATE_PIPE | UV_INHERIT_FD |
+            UV_INHERIT_STREAM)) {
+      case UV_IGNORE:
+        /* Starting a process with no stdin/stout/stderr can confuse it. So no
+         * matter what the user specified, we make sure the first three FDs are
+         * always open in their typical modes, e. g. stdin be readable and
+         * stdout/err should be writable. For FDs > 2, don't do anything - all
+         * handles in the stdio buffer are initialized with.
+         * INVALID_HANDLE_VALUE, which should be okay. */
+        if (i <= 2) {
+          DWORD access = (i == 0) ? FILE_GENERIC_READ :
+                                    FILE_GENERIC_WRITE | FILE_READ_ATTRIBUTES;
+
+          err = uv__create_nul_handle(&CHILD_STDIO_HANDLE(buffer, i),
+                                      access);
+          if (err)
+            goto error;
+
+          CHILD_STDIO_CRT_FLAGS(buffer, i) = FOPEN | FDEV;
+        }
+        break;
+
+      case UV_CREATE_PIPE: {
+        /* Create a pair of two connected pipe ends; one end is turned into an
+         * uv_pipe_t for use by the parent. The other one is given to the
+         * child. */
+        uv_pipe_t* parent_pipe = (uv_pipe_t*) fdopt.data.stream;
+        HANDLE child_pipe = INVALID_HANDLE_VALUE;
+
+        /* Create a new, connected pipe pair. stdio[i]. stream should point to
+         * an uninitialized, but not connected pipe handle. */
+        assert(fdopt.data.stream->type == UV_NAMED_PIPE);
+        assert(!(fdopt.data.stream->flags & UV_HANDLE_CONNECTION));
+        assert(!(fdopt.data.stream->flags & UV_HANDLE_PIPESERVER));
+
+        err = uv__create_stdio_pipe_pair(loop,
+                                         parent_pipe,
+                                         &child_pipe,
+                                         fdopt.flags);
+        if (err)
+          goto error;
+
+        CHILD_STDIO_HANDLE(buffer, i) = child_pipe;
+        CHILD_STDIO_CRT_FLAGS(buffer, i) = FOPEN | FPIPE;
+        break;
+      }
+
+      case UV_INHERIT_FD: {
+        /* Inherit a raw FD. */
+        HANDLE child_handle;
+
+        /* Make an inheritable duplicate of the handle. */
+        err = uv__duplicate_fd(loop, fdopt.data.fd, &child_handle);
+        if (err) {
+          /* If fdopt. data. fd is not valid and fd <= 2, then ignore the
+           * error. */
+          if (fdopt.data.fd <= 2 && err == ERROR_INVALID_HANDLE) {
+            CHILD_STDIO_CRT_FLAGS(buffer, i) = 0;
+            CHILD_STDIO_HANDLE(buffer, i) = INVALID_HANDLE_VALUE;
+            break;
+          }
+          goto error;
+        }
+
+        /* Figure out what the type is. */
+        switch (GetFileType(child_handle)) {
+          case FILE_TYPE_DISK:
+            CHILD_STDIO_CRT_FLAGS(buffer, i) = FOPEN;
+            break;
+
+          case FILE_TYPE_PIPE:
+            CHILD_STDIO_CRT_FLAGS(buffer, i) = FOPEN | FPIPE;
+            break;
+
+          case FILE_TYPE_CHAR:
+          case FILE_TYPE_REMOTE:
+            CHILD_STDIO_CRT_FLAGS(buffer, i) = FOPEN | FDEV;
+            break;
+
+          case FILE_TYPE_UNKNOWN:
+            if (GetLastError() != 0) {
+              err = GetLastError();
+              CloseHandle(child_handle);
+              goto error;
+            }
+            CHILD_STDIO_CRT_FLAGS(buffer, i) = FOPEN | FDEV;
+            break;
+
+          default:
+            assert(0);
+            return -1;
+        }
+
+        CHILD_STDIO_HANDLE(buffer, i) = child_handle;
+        break;
+      }
+
+      case UV_INHERIT_STREAM: {
+        /* Use an existing stream as the stdio handle for the child. */
+        HANDLE stream_handle, child_handle;
+        unsigned char crt_flags;
+        uv_stream_t* stream = fdopt.data.stream;
+
+        /* Leech the handle out of the stream. */
+        if (stream->type == UV_TTY) {
+          stream_handle = ((uv_tty_t*) stream)->handle;
+          crt_flags = FOPEN | FDEV;
+        } else if (stream->type == UV_NAMED_PIPE &&
+                   stream->flags & UV_HANDLE_CONNECTION) {
+          stream_handle = ((uv_pipe_t*) stream)->handle;
+          crt_flags = FOPEN | FPIPE;
+        } else {
+          stream_handle = INVALID_HANDLE_VALUE;
+          crt_flags = 0;
+        }
+
+        if (stream_handle == NULL ||
+            stream_handle == INVALID_HANDLE_VALUE) {
+          /* The handle is already closed, or not yet created, or the stream
+           * type is not supported. */
+          err = ERROR_NOT_SUPPORTED;
+          goto error;
+        }
+
+        /* Make an inheritable copy of the handle. */
+        err = uv__duplicate_handle(loop, stream_handle, &child_handle);
+        if (err)
+          goto error;
+
+        CHILD_STDIO_HANDLE(buffer, i) = child_handle;
+        CHILD_STDIO_CRT_FLAGS(buffer, i) = crt_flags;
+        break;
+      }
+
+      default:
+        assert(0);
+        return -1;
+    }
+  }
+
+  *buffer_ptr  = buffer;
+  return 0;
+
+ error:
+  uv__stdio_destroy(buffer);
+  return err;
+}
+
+
+void uv__stdio_destroy(BYTE* buffer) {
+  int i, count;
+
+  count = CHILD_STDIO_COUNT(buffer);
+  for (i = 0; i < count; i++) {
+    HANDLE handle = CHILD_STDIO_HANDLE(buffer, i);
+    if (handle != INVALID_HANDLE_VALUE) {
+      CloseHandle(handle);
+    }
+  }
+
+  uv__free(buffer);
+}
+
+
+void uv__stdio_noinherit(BYTE* buffer) {
+  int i, count;
+
+  count = CHILD_STDIO_COUNT(buffer);
+  for (i = 0; i < count; i++) {
+    HANDLE handle = CHILD_STDIO_HANDLE(buffer, i);
+    if (handle != INVALID_HANDLE_VALUE) {
+      SetHandleInformation(handle, HANDLE_FLAG_INHERIT, 0);
+    }
+  }
+}
+
+
+int uv__stdio_verify(BYTE* buffer, WORD size) {
+  unsigned int count;
+
+  /* Check the buffer pointer. */
+  if (buffer == NULL)
+    return 0;
+
+  /* Verify that the buffer is at least big enough to hold the count. */
+  if (size < CHILD_STDIO_SIZE(0))
+    return 0;
+
+  /* Verify if the count is within range. */
+  count = CHILD_STDIO_COUNT(buffer);
+  if (count > 256)
+    return 0;
+
+  /* Verify that the buffer size is big enough to hold info for N FDs. */
+  if (size < CHILD_STDIO_SIZE(count))
+    return 0;
+
+  return 1;
+}
+
+
+WORD uv__stdio_size(BYTE* buffer) {
+  return (WORD) CHILD_STDIO_SIZE(CHILD_STDIO_COUNT((buffer)));
+}
+
+
+HANDLE uv__stdio_handle(BYTE* buffer, int fd) {
+  return CHILD_STDIO_HANDLE(buffer, fd);
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/process.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/process.cpp
new file mode 100644
index 0000000..8e7835a
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/process.cpp
@@ -0,0 +1,1284 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#define _CRT_NONSTDC_NO_WARNINGS
+
+#include <assert.h>
+#include <io.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <signal.h>
+#include <limits.h>
+#include <wchar.h>
+#include <malloc.h>    /* alloca */
+
+#include "uv.h"
+#include "internal.h"
+#include "handle-inl.h"
+#include "req-inl.h"
+
+#define SIGKILL         9
+
+
+typedef struct env_var {
+  const WCHAR* const wide;
+  const WCHAR* const wide_eq;
+  const size_t len; /* including null or '=' */
+} env_var_t;
+
+#define E_V(str) { L##str, L##str L"=", sizeof(str) }
+
+static const env_var_t required_vars[] = { /* keep me sorted */
+  E_V("HOMEDRIVE"),
+  E_V("HOMEPATH"),
+  E_V("LOGONSERVER"),
+  E_V("PATH"),
+  E_V("SYSTEMDRIVE"),
+  E_V("SYSTEMROOT"),
+  E_V("TEMP"),
+  E_V("USERDOMAIN"),
+  E_V("USERNAME"),
+  E_V("USERPROFILE"),
+  E_V("WINDIR"),
+};
+
+
+static HANDLE uv_global_job_handle_;
+static uv_once_t uv_global_job_handle_init_guard_ = UV_ONCE_INIT;
+
+
+static void uv__init_global_job_handle(void) {
+  /* Create a job object and set it up to kill all contained processes when
+   * it's closed. Since this handle is made non-inheritable and we're not
+   * giving it to anyone, we're the only process holding a reference to it.
+   * That means that if this process exits it is closed and all the processes
+   * it contains are killed. All processes created with uv_spawn that are not
+   * spawned with the UV_PROCESS_DETACHED flag are assigned to this job.
+   *
+   * We're setting the JOB_OBJECT_LIMIT_SILENT_BREAKAWAY_OK flag so only the
+   * processes that we explicitly add are affected, and *their* subprocesses
+   * are not. This ensures that our child processes are not limited in their
+   * ability to use job control on Windows versions that don't deal with
+   * nested jobs (prior to Windows 8 / Server 2012). It also lets our child
+   * processes created detached processes without explicitly breaking away
+   * from job control (which uv_spawn doesn't, either).
+   */
+  SECURITY_ATTRIBUTES attr;
+  JOBOBJECT_EXTENDED_LIMIT_INFORMATION info;
+
+  memset(&attr, 0, sizeof attr);
+  attr.bInheritHandle = FALSE;
+
+  memset(&info, 0, sizeof info);
+  info.BasicLimitInformation.LimitFlags =
+      JOB_OBJECT_LIMIT_BREAKAWAY_OK |
+      JOB_OBJECT_LIMIT_SILENT_BREAKAWAY_OK |
+      JOB_OBJECT_LIMIT_DIE_ON_UNHANDLED_EXCEPTION |
+      JOB_OBJECT_LIMIT_KILL_ON_JOB_CLOSE;
+
+  uv_global_job_handle_ = CreateJobObjectW(&attr, NULL);
+  if (uv_global_job_handle_ == NULL)
+    uv_fatal_error(GetLastError(), "CreateJobObjectW");
+
+  if (!SetInformationJobObject(uv_global_job_handle_,
+                               JobObjectExtendedLimitInformation,
+                               &info,
+                               sizeof info))
+    uv_fatal_error(GetLastError(), "SetInformationJobObject");
+}
+
+
+static int uv__utf8_to_utf16_alloc(const char* s, WCHAR** ws_ptr) {
+  int ws_len, r;
+  WCHAR* ws;
+
+  ws_len = MultiByteToWideChar(CP_UTF8,
+                               0,
+                               s,
+                               -1,
+                               NULL,
+                               0);
+  if (ws_len <= 0) {
+    return GetLastError();
+  }
+
+  ws = (WCHAR*) uv__malloc(ws_len * sizeof(WCHAR));
+  if (ws == NULL) {
+    return ERROR_OUTOFMEMORY;
+  }
+
+  r = MultiByteToWideChar(CP_UTF8,
+                          0,
+                          s,
+                          -1,
+                          ws,
+                          ws_len);
+  assert(r == ws_len);
+
+  *ws_ptr = ws;
+  return 0;
+}
+
+
+static void uv__process_init(uv_loop_t* loop, uv_process_t* handle) {
+  uv__handle_init(loop, (uv_handle_t*) handle, UV_PROCESS);
+  handle->exit_cb = NULL;
+  handle->pid = 0;
+  handle->exit_signal = 0;
+  handle->wait_handle = INVALID_HANDLE_VALUE;
+  handle->process_handle = INVALID_HANDLE_VALUE;
+  handle->child_stdio_buffer = NULL;
+  handle->exit_cb_pending = 0;
+
+  UV_REQ_INIT(&handle->exit_req, UV_PROCESS_EXIT);
+  handle->exit_req.data = handle;
+}
+
+
+/*
+ * Path search functions
+ */
+
+/*
+ * Helper function for search_path
+ */
+static WCHAR* search_path_join_test(const WCHAR* dir,
+                                    size_t dir_len,
+                                    const WCHAR* name,
+                                    size_t name_len,
+                                    const WCHAR* ext,
+                                    size_t ext_len,
+                                    const WCHAR* cwd,
+                                    size_t cwd_len) {
+  WCHAR *result, *result_pos;
+  DWORD attrs;
+  if (dir_len > 2 &&
+      ((dir[0] == L'\\' || dir[0] == L'/') &&
+       (dir[1] == L'\\' || dir[1] == L'/'))) {
+    /* It's a UNC path so ignore cwd */
+    cwd_len = 0;
+  } else if (dir_len >= 1 && (dir[0] == L'/' || dir[0] == L'\\')) {
+    /* It's a full path without drive letter, use cwd's drive letter only */
+    cwd_len = 2;
+  } else if (dir_len >= 2 && dir[1] == L':' &&
+      (dir_len < 3 || (dir[2] != L'/' && dir[2] != L'\\'))) {
+    /* It's a relative path with drive letter (ext.g. D:../some/file)
+     * Replace drive letter in dir by full cwd if it points to the same drive,
+     * otherwise use the dir only.
+     */
+    if (cwd_len < 2 || _wcsnicmp(cwd, dir, 2) != 0) {
+      cwd_len = 0;
+    } else {
+      dir += 2;
+      dir_len -= 2;
+    }
+  } else if (dir_len > 2 && dir[1] == L':') {
+    /* It's an absolute path with drive letter
+     * Don't use the cwd at all
+     */
+    cwd_len = 0;
+  }
+
+  /* Allocate buffer for output */
+  result = result_pos = (WCHAR*)uv__malloc(sizeof(WCHAR) *
+      (cwd_len + 1 + dir_len + 1 + name_len + 1 + ext_len + 1));
+
+  /* Copy cwd */
+  wcsncpy(result_pos, cwd, cwd_len);
+  result_pos += cwd_len;
+
+  /* Add a path separator if cwd didn't end with one */
+  if (cwd_len && wcsrchr(L"\\/:", result_pos[-1]) == NULL) {
+    result_pos[0] = L'\\';
+    result_pos++;
+  }
+
+  /* Copy dir */
+  wcsncpy(result_pos, dir, dir_len);
+  result_pos += dir_len;
+
+  /* Add a separator if the dir didn't end with one */
+  if (dir_len && wcsrchr(L"\\/:", result_pos[-1]) == NULL) {
+    result_pos[0] = L'\\';
+    result_pos++;
+  }
+
+  /* Copy filename */
+  wcsncpy(result_pos, name, name_len);
+  result_pos += name_len;
+
+  if (ext_len) {
+    /* Add a dot if the filename didn't end with one */
+    if (name_len && result_pos[-1] != '.') {
+      result_pos[0] = L'.';
+      result_pos++;
+    }
+
+    /* Copy extension */
+    wcsncpy(result_pos, ext, ext_len);
+    result_pos += ext_len;
+  }
+
+  /* Null terminator */
+  result_pos[0] = L'\0';
+
+  attrs = GetFileAttributesW(result);
+
+  if (attrs != INVALID_FILE_ATTRIBUTES &&
+      !(attrs & FILE_ATTRIBUTE_DIRECTORY)) {
+    return result;
+  }
+
+  uv__free(result);
+  return NULL;
+}
+
+
+/*
+ * Helper function for search_path
+ */
+static WCHAR* path_search_walk_ext(const WCHAR *dir,
+                                   size_t dir_len,
+                                   const WCHAR *name,
+                                   size_t name_len,
+                                   WCHAR *cwd,
+                                   size_t cwd_len,
+                                   int name_has_ext) {
+  WCHAR* result;
+
+  /* If the name itself has a nonempty extension, try this extension first */
+  if (name_has_ext) {
+    result = search_path_join_test(dir, dir_len,
+                                   name, name_len,
+                                   L"", 0,
+                                   cwd, cwd_len);
+    if (result != NULL) {
+      return result;
+    }
+  }
+
+  /* Try .com extension */
+  result = search_path_join_test(dir, dir_len,
+                                 name, name_len,
+                                 L"com", 3,
+                                 cwd, cwd_len);
+  if (result != NULL) {
+    return result;
+  }
+
+  /* Try .exe extension */
+  result = search_path_join_test(dir, dir_len,
+                                 name, name_len,
+                                 L"exe", 3,
+                                 cwd, cwd_len);
+  if (result != NULL) {
+    return result;
+  }
+
+  return NULL;
+}
+
+
+/*
+ * search_path searches the system path for an executable filename -
+ * the windows API doesn't provide this as a standalone function nor as an
+ * option to CreateProcess.
+ *
+ * It tries to return an absolute filename.
+ *
+ * Furthermore, it tries to follow the semantics that cmd.exe, with this
+ * exception that PATHEXT environment variable isn't used. Since CreateProcess
+ * can start only .com and .exe files, only those extensions are tried. This
+ * behavior equals that of msvcrt's spawn functions.
+ *
+ * - Do not search the path if the filename already contains a path (either
+ *   relative or absolute).
+ *
+ * - If there's really only a filename, check the current directory for file,
+ *   then search all path directories.
+ *
+ * - If filename specified has *any* extension, search for the file with the
+ *   specified extension first.
+ *
+ * - If the literal filename is not found in a directory, try *appending*
+ *   (not replacing) .com first and then .exe.
+ *
+ * - The path variable may contain relative paths; relative paths are relative
+ *   to the cwd.
+ *
+ * - Directories in path may or may not end with a trailing backslash.
+ *
+ * - CMD does not trim leading/trailing whitespace from path/pathex entries
+ *   nor from the environment variables as a whole.
+ *
+ * - When cmd.exe cannot read a directory, it will just skip it and go on
+ *   searching. However, unlike posix-y systems, it will happily try to run a
+ *   file that is not readable/executable; if the spawn fails it will not
+ *   continue searching.
+ *
+ * UNC path support: we are dealing with UNC paths in both the path and the
+ * filename. This is a deviation from what cmd.exe does (it does not let you
+ * start a program by specifying an UNC path on the command line) but this is
+ * really a pointless restriction.
+ *
+ */
+static WCHAR* search_path(const WCHAR *file,
+                            WCHAR *cwd,
+                            const WCHAR *path) {
+  int file_has_dir;
+  WCHAR* result = NULL;
+  WCHAR *file_name_start;
+  WCHAR *dot;
+  const WCHAR *dir_start, *dir_end, *dir_path;
+  size_t dir_len;
+  int name_has_ext;
+
+  size_t file_len = wcslen(file);
+  size_t cwd_len = wcslen(cwd);
+
+  /* If the caller supplies an empty filename,
+   * we're not gonna return c:\windows\.exe -- GFY!
+   */
+  if (file_len == 0
+      || (file_len == 1 && file[0] == L'.')) {
+    return NULL;
+  }
+
+  /* Find the start of the filename so we can split the directory from the
+   * name. */
+  for (file_name_start = (WCHAR*)file + file_len;
+       file_name_start > file
+           && file_name_start[-1] != L'\\'
+           && file_name_start[-1] != L'/'
+           && file_name_start[-1] != L':';
+       file_name_start--);
+
+  file_has_dir = file_name_start != file;
+
+  /* Check if the filename includes an extension */
+  dot = wcschr(file_name_start, L'.');
+  name_has_ext = (dot != NULL && dot[1] != L'\0');
+
+  if (file_has_dir) {
+    /* The file has a path inside, don't use path */
+    result = path_search_walk_ext(
+        file, file_name_start - file,
+        file_name_start, file_len - (file_name_start - file),
+        cwd, cwd_len,
+        name_has_ext);
+
+  } else {
+    dir_end = path;
+
+    /* The file is really only a name; look in cwd first, then scan path */
+    result = path_search_walk_ext(L"", 0,
+                                  file, file_len,
+                                  cwd, cwd_len,
+                                  name_has_ext);
+
+    while (result == NULL) {
+      if (*dir_end == L'\0') {
+        break;
+      }
+
+      /* Skip the separator that dir_end now points to */
+      if (dir_end != path || *path == L';') {
+        dir_end++;
+      }
+
+      /* Next slice starts just after where the previous one ended */
+      dir_start = dir_end;
+
+      /* If path is quoted, find quote end */
+      if (*dir_start == L'"' || *dir_start == L'\'') {
+        dir_end = wcschr(dir_start + 1, *dir_start);
+        if (dir_end == NULL) {
+          dir_end = wcschr(dir_start, L'\0');
+        }
+      }
+      /* Slice until the next ; or \0 is found */
+      dir_end = wcschr(dir_end, L';');
+      if (dir_end == NULL) {
+        dir_end = wcschr(dir_start, L'\0');
+      }
+
+      /* If the slice is zero-length, don't bother */
+      if (dir_end - dir_start == 0) {
+        continue;
+      }
+
+      dir_path = dir_start;
+      dir_len = dir_end - dir_start;
+
+      /* Adjust if the path is quoted. */
+      if (dir_path[0] == '"' || dir_path[0] == '\'') {
+        ++dir_path;
+        --dir_len;
+      }
+
+      if (dir_path[dir_len - 1] == '"' || dir_path[dir_len - 1] == '\'') {
+        --dir_len;
+      }
+
+      result = path_search_walk_ext(dir_path, dir_len,
+                                    file, file_len,
+                                    cwd, cwd_len,
+                                    name_has_ext);
+    }
+  }
+
+  return result;
+}
+
+
+/*
+ * Quotes command line arguments
+ * Returns a pointer to the end (next char to be written) of the buffer
+ */
+WCHAR* quote_cmd_arg(const WCHAR *source, WCHAR *target) {
+  size_t len = wcslen(source);
+  size_t i;
+  int quote_hit;
+  WCHAR* start;
+
+  if (len == 0) {
+    /* Need double quotation for empty argument */
+    *(target++) = L'"';
+    *(target++) = L'"';
+    return target;
+  }
+
+  if (NULL == wcspbrk(source, L" \t\"")) {
+    /* No quotation needed */
+    wcsncpy(target, source, len);
+    target += len;
+    return target;
+  }
+
+  if (NULL == wcspbrk(source, L"\"\\")) {
+    /*
+     * No embedded double quotes or backlashes, so I can just wrap
+     * quote marks around the whole thing.
+     */
+    *(target++) = L'"';
+    wcsncpy(target, source, len);
+    target += len;
+    *(target++) = L'"';
+    return target;
+  }
+
+  /*
+   * Expected input/output:
+   *   input : hello"world
+   *   output: "hello\"world"
+   *   input : hello""world
+   *   output: "hello\"\"world"
+   *   input : hello\world
+   *   output: hello\world
+   *   input : hello\\world
+   *   output: hello\\world
+   *   input : hello\"world
+   *   output: "hello\\\"world"
+   *   input : hello\\"world
+   *   output: "hello\\\\\"world"
+   *   input : hello world\
+   *   output: "hello world\\"
+   */
+
+  *(target++) = L'"';
+  start = target;
+  quote_hit = 1;
+
+  for (i = len; i > 0; --i) {
+    *(target++) = source[i - 1];
+
+    if (quote_hit && source[i - 1] == L'\\') {
+      *(target++) = L'\\';
+    } else if(source[i - 1] == L'"') {
+      quote_hit = 1;
+      *(target++) = L'\\';
+    } else {
+      quote_hit = 0;
+    }
+  }
+  target[0] = L'\0';
+  wcsrev(start);
+  *(target++) = L'"';
+  return target;
+}
+
+
+int make_program_args(char** args, int verbatim_arguments, WCHAR** dst_ptr) {
+  char** arg;
+  WCHAR* dst = NULL;
+  WCHAR* temp_buffer = NULL;
+  size_t dst_len = 0;
+  size_t temp_buffer_len = 0;
+  WCHAR* pos;
+  int arg_count = 0;
+  int err = 0;
+
+  /* Count the required size. */
+  for (arg = args; *arg; arg++) {
+    DWORD arg_len;
+
+    arg_len = MultiByteToWideChar(CP_UTF8,
+                                  0,
+                                  *arg,
+                                  -1,
+                                  NULL,
+                                  0);
+    if (arg_len == 0) {
+      return GetLastError();
+    }
+
+    dst_len += arg_len;
+
+    if (arg_len > temp_buffer_len)
+      temp_buffer_len = arg_len;
+
+    arg_count++;
+  }
+
+  /* Adjust for potential quotes. Also assume the worst-case scenario that
+   * every character needs escaping, so we need twice as much space. */
+  dst_len = dst_len * 2 + arg_count * 2;
+
+  /* Allocate buffer for the final command line. */
+  dst = (WCHAR*) uv__malloc(dst_len * sizeof(WCHAR));
+  if (dst == NULL) {
+    err = ERROR_OUTOFMEMORY;
+    goto error;
+  }
+
+  /* Allocate temporary working buffer. */
+  temp_buffer = (WCHAR*) uv__malloc(temp_buffer_len * sizeof(WCHAR));
+  if (temp_buffer == NULL) {
+    err = ERROR_OUTOFMEMORY;
+    goto error;
+  }
+
+  pos = dst;
+  for (arg = args; *arg; arg++) {
+    DWORD arg_len;
+
+    /* Convert argument to wide char. */
+    arg_len = MultiByteToWideChar(CP_UTF8,
+                                  0,
+                                  *arg,
+                                  -1,
+                                  temp_buffer,
+                                  (int) (dst + dst_len - pos));
+    if (arg_len == 0) {
+      err = GetLastError();
+      goto error;
+    }
+
+    if (verbatim_arguments) {
+      /* Copy verbatim. */
+      wcscpy(pos, temp_buffer);
+      pos += arg_len - 1;
+    } else {
+      /* Quote/escape, if needed. */
+      pos = quote_cmd_arg(temp_buffer, pos);
+    }
+
+    *pos++ = *(arg + 1) ? L' ' : L'\0';
+  }
+
+  uv__free(temp_buffer);
+
+  *dst_ptr = dst;
+  return 0;
+
+error:
+  uv__free(dst);
+  uv__free(temp_buffer);
+  return err;
+}
+
+
+int env_strncmp(const wchar_t* a, int na, const wchar_t* b) {
+  const wchar_t* a_eq;
+  const wchar_t* b_eq;
+  wchar_t* A;
+  wchar_t* B;
+  int nb;
+  int r;
+
+  if (na < 0) {
+    a_eq = wcschr(a, L'=');
+    assert(a_eq);
+    na = (int)(long)(a_eq - a);
+  } else {
+    na--;
+  }
+  b_eq = wcschr(b, L'=');
+  assert(b_eq);
+  nb = b_eq - b;
+
+  A = (wchar_t*)alloca((na+1) * sizeof(wchar_t));
+  B = (wchar_t*)alloca((nb+1) * sizeof(wchar_t));
+
+  r = LCMapStringW(LOCALE_INVARIANT, LCMAP_UPPERCASE, a, na, A, na);
+  assert(r==na);
+  A[na] = L'\0';
+  r = LCMapStringW(LOCALE_INVARIANT, LCMAP_UPPERCASE, b, nb, B, nb);
+  assert(r==nb);
+  B[nb] = L'\0';
+
+  for (;;) {
+    wchar_t AA = *A++;
+    wchar_t BB = *B++;
+    if (AA < BB) {
+      return -1;
+    } else if (AA > BB) {
+      return 1;
+    } else if (!AA && !BB) {
+      return 0;
+    }
+  }
+}
+
+
+static int qsort_wcscmp(const void *a, const void *b) {
+  wchar_t* astr = *(wchar_t* const*)a;
+  wchar_t* bstr = *(wchar_t* const*)b;
+  return env_strncmp(astr, -1, bstr);
+}
+
+
+/*
+ * The way windows takes environment variables is different than what C does;
+ * Windows wants a contiguous block of null-terminated strings, terminated
+ * with an additional null.
+ *
+ * Windows has a few "essential" environment variables. winsock will fail
+ * to initialize if SYSTEMROOT is not defined; some APIs make reference to
+ * TEMP. SYSTEMDRIVE is probably also important. We therefore ensure that
+ * these get defined if the input environment block does not contain any
+ * values for them.
+ *
+ * Also add variables known to Cygwin to be required for correct
+ * subprocess operation in many cases:
+ * https://github.com/Alexpux/Cygwin/blob/b266b04fbbd3a595f02ea149e4306d3ab9b1fe3d/winsup/cygwin/environ.cc#L955
+ *
+ */
+int make_program_env(char* env_block[], WCHAR** dst_ptr) {
+  WCHAR* dst;
+  WCHAR* ptr;
+  char** env;
+  size_t env_len = 0;
+  int len;
+  size_t i;
+  DWORD var_size;
+  size_t env_block_count = 1; /* 1 for null-terminator */
+  WCHAR* dst_copy;
+  WCHAR** ptr_copy;
+  WCHAR** env_copy;
+  DWORD required_vars_value_len[ARRAY_SIZE(required_vars)];
+
+  /* first pass: determine size in UTF-16 */
+  for (env = env_block; *env; env++) {
+    int len;
+    if (strchr(*env, '=')) {
+      len = MultiByteToWideChar(CP_UTF8,
+                                0,
+                                *env,
+                                -1,
+                                NULL,
+                                0);
+      if (len <= 0) {
+        return GetLastError();
+      }
+      env_len += len;
+      env_block_count++;
+    }
+  }
+
+  /* second pass: copy to UTF-16 environment block */
+  dst_copy = (WCHAR*)uv__malloc(env_len * sizeof(WCHAR));
+  if (dst_copy == NULL && env_len > 0) {
+    return ERROR_OUTOFMEMORY;
+  }
+  env_copy = (WCHAR**)alloca(env_block_count * sizeof(WCHAR*));
+
+  ptr = dst_copy;
+  ptr_copy = env_copy;
+  for (env = env_block; *env; env++) {
+    if (strchr(*env, '=')) {
+      len = MultiByteToWideChar(CP_UTF8,
+                                0,
+                                *env,
+                                -1,
+                                ptr,
+                                (int) (env_len - (ptr - dst_copy)));
+      if (len <= 0) {
+        DWORD err = GetLastError();
+        uv__free(dst_copy);
+        return err;
+      }
+      *ptr_copy++ = ptr;
+      ptr += len;
+    }
+  }
+  *ptr_copy = NULL;
+  assert(env_len == 0 || env_len == (size_t) (ptr - dst_copy));
+
+  /* sort our (UTF-16) copy */
+  qsort(env_copy, env_block_count-1, sizeof(wchar_t*), qsort_wcscmp);
+
+  /* third pass: check for required variables */
+  for (ptr_copy = env_copy, i = 0; i < ARRAY_SIZE(required_vars); ) {
+    int cmp;
+    if (!*ptr_copy) {
+      cmp = -1;
+    } else {
+      cmp = env_strncmp(required_vars[i].wide_eq,
+                       required_vars[i].len,
+                        *ptr_copy);
+    }
+    if (cmp < 0) {
+      /* missing required var */
+      var_size = GetEnvironmentVariableW(required_vars[i].wide, NULL, 0);
+      required_vars_value_len[i] = var_size;
+      if (var_size != 0) {
+        env_len += required_vars[i].len;
+        env_len += var_size;
+      }
+      i++;
+    } else {
+      ptr_copy++;
+      if (cmp == 0)
+        i++;
+    }
+  }
+
+  /* final pass: copy, in sort order, and inserting required variables */
+  dst = (WCHAR*)uv__malloc((1+env_len) * sizeof(WCHAR));
+  if (!dst) {
+    uv__free(dst_copy);
+    return ERROR_OUTOFMEMORY;
+  }
+
+  for (ptr = dst, ptr_copy = env_copy, i = 0;
+       *ptr_copy || i < ARRAY_SIZE(required_vars);
+       ptr += len) {
+    int cmp;
+    if (i >= ARRAY_SIZE(required_vars)) {
+      cmp = 1;
+    } else if (!*ptr_copy) {
+      cmp = -1;
+    } else {
+      cmp = env_strncmp(required_vars[i].wide_eq,
+                        required_vars[i].len,
+                        *ptr_copy);
+    }
+    if (cmp < 0) {
+      /* missing required var */
+      len = required_vars_value_len[i];
+      if (len) {
+        wcscpy(ptr, required_vars[i].wide_eq);
+        ptr += required_vars[i].len;
+        var_size = GetEnvironmentVariableW(required_vars[i].wide,
+                                           ptr,
+                                           (int) (env_len - (ptr - dst)));
+        if (var_size != (DWORD) (len - 1)) { /* TODO: handle race condition? */
+          uv_fatal_error(GetLastError(), "GetEnvironmentVariableW");
+        }
+      }
+      i++;
+    } else {
+      /* copy var from env_block */
+      len = wcslen(*ptr_copy) + 1;
+      wmemcpy(ptr, *ptr_copy, len);
+      ptr_copy++;
+      if (cmp == 0)
+        i++;
+    }
+  }
+
+  /* Terminate with an extra NULL. */
+  assert(env_len == (size_t) (ptr - dst));
+  *ptr = L'\0';
+
+  uv__free(dst_copy);
+  *dst_ptr = dst;
+  return 0;
+}
+
+/*
+ * Attempt to find the value of the PATH environment variable in the child's
+ * preprocessed environment.
+ *
+ * If found, a pointer into `env` is returned. If not found, NULL is returned.
+ */
+static WCHAR* find_path(WCHAR *env) {
+  for (; env != NULL && *env != 0; env += wcslen(env) + 1) {
+    if ((env[0] == L'P' || env[0] == L'p') &&
+        (env[1] == L'A' || env[1] == L'a') &&
+        (env[2] == L'T' || env[2] == L't') &&
+        (env[3] == L'H' || env[3] == L'h') &&
+        (env[4] == L'=')) {
+      return &env[5];
+    }
+  }
+
+  return NULL;
+}
+
+/*
+ * Called on Windows thread-pool thread to indicate that
+ * a child process has exited.
+ */
+static void CALLBACK exit_wait_callback(void* data, BOOLEAN didTimeout) {
+  uv_process_t* process = (uv_process_t*) data;
+  uv_loop_t* loop = process->loop;
+
+  assert(didTimeout == FALSE);
+  assert(process);
+  assert(!process->exit_cb_pending);
+
+  process->exit_cb_pending = 1;
+
+  /* Post completed */
+  POST_COMPLETION_FOR_REQ(loop, &process->exit_req);
+}
+
+
+/* Called on main thread after a child process has exited. */
+void uv__process_proc_exit(uv_loop_t* loop, uv_process_t* handle) {
+  int64_t exit_code;
+  DWORD status;
+
+  assert(handle->exit_cb_pending);
+  handle->exit_cb_pending = 0;
+
+  /* If we're closing, don't call the exit callback. Just schedule a close
+   * callback now. */
+  if (handle->flags & UV_HANDLE_CLOSING) {
+    uv__want_endgame(loop, (uv_handle_t*) handle);
+    return;
+  }
+
+  /* Unregister from process notification. */
+  if (handle->wait_handle != INVALID_HANDLE_VALUE) {
+    UnregisterWait(handle->wait_handle);
+    handle->wait_handle = INVALID_HANDLE_VALUE;
+  }
+
+  /* Set the handle to inactive: no callbacks will be made after the exit
+   * callback. */
+  uv__handle_stop(handle);
+
+  if (GetExitCodeProcess(handle->process_handle, &status)) {
+    exit_code = status;
+  } else {
+    /* Unable to obtain the exit code. This should never happen. */
+    exit_code = uv_translate_sys_error(GetLastError());
+  }
+
+  /* Fire the exit callback. */
+  if (handle->exit_cb) {
+    handle->exit_cb(handle, exit_code, handle->exit_signal);
+  }
+}
+
+
+void uv__process_close(uv_loop_t* loop, uv_process_t* handle) {
+  uv__handle_closing(handle);
+
+  if (handle->wait_handle != INVALID_HANDLE_VALUE) {
+    /* This blocks until either the wait was cancelled, or the callback has
+     * completed. */
+    BOOL r = UnregisterWaitEx(handle->wait_handle, INVALID_HANDLE_VALUE);
+    if (!r) {
+      /* This should never happen, and if it happens, we can't recover... */
+      uv_fatal_error(GetLastError(), "UnregisterWaitEx");
+    }
+
+    handle->wait_handle = INVALID_HANDLE_VALUE;
+  }
+
+  if (!handle->exit_cb_pending) {
+    uv__want_endgame(loop, (uv_handle_t*)handle);
+  }
+}
+
+
+void uv__process_endgame(uv_loop_t* loop, uv_process_t* handle) {
+  assert(!handle->exit_cb_pending);
+  assert(handle->flags & UV_HANDLE_CLOSING);
+  assert(!(handle->flags & UV_HANDLE_CLOSED));
+
+  /* Clean-up the process handle. */
+  CloseHandle(handle->process_handle);
+
+  uv__handle_close(handle);
+}
+
+
+int uv_spawn(uv_loop_t* loop,
+             uv_process_t* process,
+             const uv_process_options_t* options) {
+  int i;
+  int err = 0;
+  WCHAR* path = NULL, *alloc_path = NULL;
+  BOOL result;
+  WCHAR* application_path = NULL, *application = NULL, *arguments = NULL,
+         *env = NULL, *cwd = NULL;
+  STARTUPINFOW startup;
+  PROCESS_INFORMATION info;
+  DWORD process_flags;
+
+  uv__process_init(loop, process);
+  process->exit_cb = options->exit_cb;
+
+  if (options->flags & (UV_PROCESS_SETGID | UV_PROCESS_SETUID)) {
+    return UV_ENOTSUP;
+  }
+
+  if (options->file == NULL ||
+      options->args == NULL) {
+    return UV_EINVAL;
+  }
+
+  assert(options->file != NULL);
+  assert(!(options->flags & ~(UV_PROCESS_DETACHED |
+                              UV_PROCESS_SETGID |
+                              UV_PROCESS_SETUID |
+                              UV_PROCESS_WINDOWS_HIDE |
+                              UV_PROCESS_WINDOWS_HIDE_CONSOLE |
+                              UV_PROCESS_WINDOWS_HIDE_GUI |
+                              UV_PROCESS_WINDOWS_VERBATIM_ARGUMENTS)));
+
+  err = uv__utf8_to_utf16_alloc(options->file, &application);
+  if (err)
+    goto done;
+
+  err = make_program_args(
+      options->args,
+      options->flags & UV_PROCESS_WINDOWS_VERBATIM_ARGUMENTS,
+      &arguments);
+  if (err)
+    goto done;
+
+  if (options->env) {
+     err = make_program_env(options->env, &env);
+     if (err)
+       goto done;
+  }
+
+  if (options->cwd) {
+    /* Explicit cwd */
+    err = uv__utf8_to_utf16_alloc(options->cwd, &cwd);
+    if (err)
+      goto done;
+
+  } else {
+    /* Inherit cwd */
+    DWORD cwd_len, r;
+
+    cwd_len = GetCurrentDirectoryW(0, NULL);
+    if (!cwd_len) {
+      err = GetLastError();
+      goto done;
+    }
+
+    cwd = (WCHAR*) uv__malloc(cwd_len * sizeof(WCHAR));
+    if (cwd == NULL) {
+      err = ERROR_OUTOFMEMORY;
+      goto done;
+    }
+
+    r = GetCurrentDirectoryW(cwd_len, cwd);
+    if (r == 0 || r >= cwd_len) {
+      err = GetLastError();
+      goto done;
+    }
+  }
+
+  /* Get PATH environment variable. */
+  path = find_path(env);
+  if (path == NULL) {
+    DWORD path_len, r;
+
+    path_len = GetEnvironmentVariableW(L"PATH", NULL, 0);
+    if (path_len == 0) {
+      err = GetLastError();
+      goto done;
+    }
+
+    alloc_path = (WCHAR*) uv__malloc(path_len * sizeof(WCHAR));
+    if (alloc_path == NULL) {
+      err = ERROR_OUTOFMEMORY;
+      goto done;
+    }
+    path = alloc_path;
+
+    r = GetEnvironmentVariableW(L"PATH", path, path_len);
+    if (r == 0 || r >= path_len) {
+      err = GetLastError();
+      goto done;
+    }
+  }
+
+  err = uv__stdio_create(loop, options, &process->child_stdio_buffer);
+  if (err)
+    goto done;
+
+  application_path = search_path(application,
+                                 cwd,
+                                 path);
+  if (application_path == NULL) {
+    /* Not found. */
+    err = ERROR_FILE_NOT_FOUND;
+    goto done;
+  }
+
+  startup.cb = sizeof(startup);
+  startup.lpReserved = NULL;
+  startup.lpDesktop = NULL;
+  startup.lpTitle = NULL;
+  startup.dwFlags = STARTF_USESTDHANDLES | STARTF_USESHOWWINDOW;
+
+  startup.cbReserved2 = uv__stdio_size(process->child_stdio_buffer);
+  startup.lpReserved2 = (BYTE*) process->child_stdio_buffer;
+
+  startup.hStdInput = uv__stdio_handle(process->child_stdio_buffer, 0);
+  startup.hStdOutput = uv__stdio_handle(process->child_stdio_buffer, 1);
+  startup.hStdError = uv__stdio_handle(process->child_stdio_buffer, 2);
+
+  process_flags = CREATE_UNICODE_ENVIRONMENT;
+
+  if ((options->flags & UV_PROCESS_WINDOWS_HIDE_CONSOLE) ||
+      (options->flags & UV_PROCESS_WINDOWS_HIDE)) {
+    /* Avoid creating console window if stdio is not inherited. */
+    for (i = 0; i < options->stdio_count; i++) {
+      if (options->stdio[i].flags & UV_INHERIT_FD)
+        break;
+      if (i == options->stdio_count - 1)
+        process_flags |= CREATE_NO_WINDOW;
+    }
+  }
+  if ((options->flags & UV_PROCESS_WINDOWS_HIDE_GUI) ||
+      (options->flags & UV_PROCESS_WINDOWS_HIDE)) {
+    /* Use SW_HIDE to avoid any potential process window. */
+    startup.wShowWindow = SW_HIDE;
+  } else {
+    startup.wShowWindow = SW_SHOWDEFAULT;
+  }
+
+  if (options->flags & UV_PROCESS_DETACHED) {
+    /* Note that we're not setting the CREATE_BREAKAWAY_FROM_JOB flag. That
+     * means that libuv might not let you create a fully daemonized process
+     * when run under job control. However the type of job control that libuv
+     * itself creates doesn't trickle down to subprocesses so they can still
+     * daemonize.
+     *
+     * A reason to not do this is that CREATE_BREAKAWAY_FROM_JOB makes the
+     * CreateProcess call fail if we're under job control that doesn't allow
+     * breakaway.
+     */
+    process_flags |= DETACHED_PROCESS | CREATE_NEW_PROCESS_GROUP;
+  }
+
+  if (!CreateProcessW(application_path,
+                     arguments,
+                     NULL,
+                     NULL,
+                     1,
+                     process_flags,
+                     env,
+                     cwd,
+                     &startup,
+                     &info)) {
+    /* CreateProcessW failed. */
+    err = GetLastError();
+    goto done;
+  }
+
+  /* Spawn succeeded. Beyond this point, failure is reported asynchronously. */
+
+  process->process_handle = info.hProcess;
+  process->pid = info.dwProcessId;
+
+  /* If the process isn't spawned as detached, assign to the global job object
+   * so windows will kill it when the parent process dies. */
+  if (!(options->flags & UV_PROCESS_DETACHED)) {
+    uv_once(&uv_global_job_handle_init_guard_, uv__init_global_job_handle);
+
+    if (!AssignProcessToJobObject(uv_global_job_handle_, info.hProcess)) {
+      /* AssignProcessToJobObject might fail if this process is under job
+       * control and the job doesn't have the
+       * JOB_OBJECT_LIMIT_SILENT_BREAKAWAY_OK flag set, on a Windows version
+       * that doesn't support nested jobs.
+       *
+       * When that happens we just swallow the error and continue without
+       * establishing a kill-child-on-parent-exit relationship, otherwise
+       * there would be no way for libuv applications run under job control
+       * to spawn processes at all.
+       */
+      DWORD err = GetLastError();
+      if (err != ERROR_ACCESS_DENIED)
+        uv_fatal_error(err, "AssignProcessToJobObject");
+    }
+  }
+
+  /* Set IPC pid to all IPC pipes. */
+  for (i = 0; i < options->stdio_count; i++) {
+    const uv_stdio_container_t* fdopt = &options->stdio[i];
+    if (fdopt->flags & UV_CREATE_PIPE &&
+        fdopt->data.stream->type == UV_NAMED_PIPE &&
+        ((uv_pipe_t*) fdopt->data.stream)->ipc) {
+      ((uv_pipe_t*) fdopt->data.stream)->pipe.conn.ipc_remote_pid =
+          info.dwProcessId;
+    }
+  }
+
+  /* Setup notifications for when the child process exits. */
+  result = RegisterWaitForSingleObject(&process->wait_handle,
+      process->process_handle, exit_wait_callback, (void*)process, INFINITE,
+      WT_EXECUTEINWAITTHREAD | WT_EXECUTEONLYONCE);
+  if (!result) {
+    uv_fatal_error(GetLastError(), "RegisterWaitForSingleObject");
+  }
+
+  CloseHandle(info.hThread);
+
+  assert(!err);
+
+  /* Make the handle active. It will remain active until the exit callback is
+   * made or the handle is closed, whichever happens first. */
+  uv__handle_start(process);
+
+  /* Cleanup, whether we succeeded or failed. */
+ done:
+  uv__free(application);
+  uv__free(application_path);
+  uv__free(arguments);
+  uv__free(cwd);
+  uv__free(env);
+  uv__free(alloc_path);
+
+  if (process->child_stdio_buffer != NULL) {
+    /* Clean up child stdio handles. */
+    uv__stdio_destroy(process->child_stdio_buffer);
+    process->child_stdio_buffer = NULL;
+  }
+
+  return uv_translate_sys_error(err);
+}
+
+
+static int uv__kill(HANDLE process_handle, int signum) {
+  if (signum < 0 || signum >= NSIG) {
+    return UV_EINVAL;
+  }
+
+  switch (signum) {
+    case SIGTERM:
+    case SIGKILL:
+    case SIGINT: {
+      /* Unconditionally terminate the process. On Windows, killed processes
+       * normally return 1. */
+      DWORD status;
+      int err;
+
+      if (TerminateProcess(process_handle, 1))
+        return 0;
+
+      /* If the process already exited before TerminateProcess was called,.
+       * TerminateProcess will fail with ERROR_ACCESS_DENIED. */
+      err = GetLastError();
+      if (err == ERROR_ACCESS_DENIED &&
+          GetExitCodeProcess(process_handle, &status) &&
+          status != STILL_ACTIVE) {
+        return UV_ESRCH;
+      }
+
+      return uv_translate_sys_error(err);
+    }
+
+    case 0: {
+      /* Health check: is the process still alive? */
+      DWORD status;
+
+      if (!GetExitCodeProcess(process_handle, &status))
+        return uv_translate_sys_error(GetLastError());
+
+      if (status != STILL_ACTIVE)
+        return UV_ESRCH;
+
+      return 0;
+    }
+
+    default:
+      /* Unsupported signal. */
+      return UV_ENOSYS;
+  }
+}
+
+
+int uv_process_kill(uv_process_t* process, int signum) {
+  int err;
+
+  if (process->process_handle == INVALID_HANDLE_VALUE) {
+    return UV_EINVAL;
+  }
+
+  err = uv__kill(process->process_handle, signum);
+  if (err) {
+    return err;  /* err is already translated. */
+  }
+
+  process->exit_signal = signum;
+
+  return 0;
+}
+
+
+int uv_kill(int pid, int signum) {
+  int err;
+  HANDLE process_handle;
+
+  if (pid == 0) {
+    process_handle = GetCurrentProcess();
+  } else {
+    process_handle = OpenProcess(PROCESS_TERMINATE | PROCESS_QUERY_INFORMATION,
+                                 FALSE,
+                                 pid);
+  }
+
+  if (process_handle == NULL) {
+    err = GetLastError();
+    if (err == ERROR_INVALID_PARAMETER) {
+      return UV_ESRCH;
+    } else {
+      return uv_translate_sys_error(err);
+    }
+  }
+
+  err = uv__kill(process_handle, signum);
+  CloseHandle(process_handle);
+
+  return err;  /* err is already translated. */
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/req-inl.h b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/req-inl.h
new file mode 100644
index 0000000..9e20759
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/req-inl.h
@@ -0,0 +1,214 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#ifndef UV_WIN_REQ_INL_H_
+#define UV_WIN_REQ_INL_H_
+
+#include <assert.h>
+
+#include "uv.h"
+#include "internal.h"
+
+
+#define SET_REQ_STATUS(req, status)                                     \
+   (req)->u.io.overlapped.Internal = (ULONG_PTR) (status)
+
+#define SET_REQ_ERROR(req, error)                                       \
+  SET_REQ_STATUS((req), NTSTATUS_FROM_WIN32((error)))
+
+/* Note: used open-coded in UV_REQ_INIT() because of a circular dependency
+ * between src/uv-common.h and src/win/internal.h.
+ */
+#define SET_REQ_SUCCESS(req)                                            \
+  SET_REQ_STATUS((req), STATUS_SUCCESS)
+
+#define GET_REQ_STATUS(req)                                             \
+  ((NTSTATUS) (req)->u.io.overlapped.Internal)
+
+#define REQ_SUCCESS(req)                                                \
+  (NT_SUCCESS(GET_REQ_STATUS((req))))
+
+#define GET_REQ_ERROR(req)                                              \
+  (pRtlNtStatusToDosError(GET_REQ_STATUS((req))))
+
+#define GET_REQ_SOCK_ERROR(req)                                         \
+  (uv__ntstatus_to_winsock_error(GET_REQ_STATUS((req))))
+
+
+#define REGISTER_HANDLE_REQ(loop, handle, req)                          \
+  do {                                                                  \
+    INCREASE_ACTIVE_COUNT((loop), (handle));                            \
+    uv__req_register((loop), (req));                                    \
+  } while (0)
+
+#define UNREGISTER_HANDLE_REQ(loop, handle, req)                        \
+  do {                                                                  \
+    DECREASE_ACTIVE_COUNT((loop), (handle));                            \
+    uv__req_unregister((loop), (req));                                  \
+  } while (0)
+
+
+#define UV_SUCCEEDED_WITHOUT_IOCP(result)                               \
+  ((result) && (handle->flags & UV_HANDLE_SYNC_BYPASS_IOCP))
+
+#define UV_SUCCEEDED_WITH_IOCP(result)                                  \
+  ((result) || (GetLastError() == ERROR_IO_PENDING))
+
+
+#define POST_COMPLETION_FOR_REQ(loop, req)                              \
+  if (!PostQueuedCompletionStatus((loop)->iocp,                         \
+                                  0,                                    \
+                                  0,                                    \
+                                  &((req)->u.io.overlapped))) {         \
+    uv_fatal_error(GetLastError(), "PostQueuedCompletionStatus");       \
+  }
+
+
+INLINE static uv_req_t* uv__overlapped_to_req(OVERLAPPED* overlapped) {
+  return CONTAINING_RECORD(overlapped, uv_req_t, u.io.overlapped);
+}
+
+
+INLINE static void uv__insert_pending_req(uv_loop_t* loop, uv_req_t* req) {
+  req->next_req = NULL;
+  if (loop->pending_reqs_tail) {
+#ifdef _DEBUG
+    /* Ensure the request is not already in the queue, or the queue
+     * will get corrupted.
+     */
+    uv_req_t* current = loop->pending_reqs_tail;
+    do {
+      assert(req != current);
+      current = current->next_req;
+    } while(current != loop->pending_reqs_tail);
+#endif
+
+    req->next_req = loop->pending_reqs_tail->next_req;
+    loop->pending_reqs_tail->next_req = req;
+    loop->pending_reqs_tail = req;
+  } else {
+    req->next_req = req;
+    loop->pending_reqs_tail = req;
+  }
+}
+
+
+#define DELEGATE_STREAM_REQ(loop, req, method, handle_at)                     \
+  do {                                                                        \
+    switch (((uv_handle_t*) (req)->handle_at)->type) {                        \
+      case UV_TCP:                                                            \
+        uv__process_tcp_##method##_req(loop,                                  \
+                                      (uv_tcp_t*) ((req)->handle_at),         \
+                                      req);                                   \
+        break;                                                                \
+                                                                              \
+      case UV_NAMED_PIPE:                                                     \
+        uv__process_pipe_##method##_req(loop,                                 \
+                                       (uv_pipe_t*) ((req)->handle_at),       \
+                                       req);                                  \
+        break;                                                                \
+                                                                              \
+      case UV_TTY:                                                            \
+        uv__process_tty_##method##_req(loop,                                  \
+                                      (uv_tty_t*) ((req)->handle_at),         \
+                                      req);                                   \
+        break;                                                                \
+                                                                              \
+      default:                                                                \
+        assert(0);                                                            \
+    }                                                                         \
+  } while (0)
+
+
+INLINE static void uv__process_reqs(uv_loop_t* loop) {
+  uv_req_t* req;
+  uv_req_t* first;
+  uv_req_t* next;
+
+  if (loop->pending_reqs_tail == NULL)
+    return;
+
+  first = loop->pending_reqs_tail->next_req;
+  next = first;
+  loop->pending_reqs_tail = NULL;
+
+  while (next != NULL) {
+    req = next;
+    next = req->next_req != first ? req->next_req : NULL;
+
+    switch (req->type) {
+      case UV_READ:
+        DELEGATE_STREAM_REQ(loop, req, read, data);
+        break;
+
+      case UV_WRITE:
+        DELEGATE_STREAM_REQ(loop, (uv_write_t*) req, write, handle);
+        break;
+
+      case UV_ACCEPT:
+        DELEGATE_STREAM_REQ(loop, req, accept, data);
+        break;
+
+      case UV_CONNECT:
+        DELEGATE_STREAM_REQ(loop, (uv_connect_t*) req, connect, handle);
+        break;
+
+      case UV_SHUTDOWN:
+        DELEGATE_STREAM_REQ(loop, (uv_shutdown_t*) req, shutdown, handle);
+        break;
+
+      case UV_UDP_RECV:
+        uv__process_udp_recv_req(loop, (uv_udp_t*) req->data, req);
+        break;
+
+      case UV_UDP_SEND:
+        uv__process_udp_send_req(loop,
+                                 ((uv_udp_send_t*) req)->handle,
+                                 (uv_udp_send_t*) req);
+        break;
+
+      case UV_WAKEUP:
+        uv__process_async_wakeup_req(loop, (uv_async_t*) req->data, req);
+        break;
+
+      case UV_SIGNAL_REQ:
+        uv__process_signal_req(loop, (uv_signal_t*) req->data, req);
+        break;
+
+      case UV_POLL_REQ:
+        uv__process_poll_req(loop, (uv_poll_t*) req->data, req);
+        break;
+
+      case UV_PROCESS_EXIT:
+        uv__process_proc_exit(loop, (uv_process_t*) req->data);
+        break;
+
+      case UV_FS_EVENT_REQ:
+        uv__process_fs_event_req(loop, req, (uv_fs_event_t*) req->data);
+        break;
+
+      default:
+        assert(0);
+    }
+  }
+}
+
+#endif /* UV_WIN_REQ_INL_H_ */
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/signal.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/signal.cpp
new file mode 100644
index 0000000..8c79871
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/signal.cpp
@@ -0,0 +1,282 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <assert.h>
+#include <signal.h>
+
+#include "uv.h"
+#include "internal.h"
+#include "handle-inl.h"
+#include "req-inl.h"
+
+
+RB_HEAD(uv_signal_tree_s, uv_signal_s);
+
+static struct uv_signal_tree_s uv__signal_tree = RB_INITIALIZER(uv__signal_tree);
+static CRITICAL_SECTION uv__signal_lock;
+
+static BOOL WINAPI uv__signal_control_handler(DWORD type);
+
+int uv__signal_start(uv_signal_t* handle,
+                     uv_signal_cb signal_cb,
+                     int signum,
+                     int oneshot);
+
+void uv__signals_init(void) {
+  InitializeCriticalSection(&uv__signal_lock);
+  if (!SetConsoleCtrlHandler(uv__signal_control_handler, TRUE))
+    abort();
+}
+
+
+void uv__signal_cleanup(void) {
+  /* TODO(bnoordhuis) Undo effects of uv_signal_init()? */
+}
+
+
+static int uv__signal_compare(uv_signal_t* w1, uv_signal_t* w2) {
+  /* Compare signums first so all watchers with the same signnum end up
+   * adjacent. */
+  if (w1->signum < w2->signum) return -1;
+  if (w1->signum > w2->signum) return 1;
+
+  /* Sort by loop pointer, so we can easily look up the first item after
+   * { .signum = x, .loop = NULL }. */
+  if ((uintptr_t) w1->loop < (uintptr_t) w2->loop) return -1;
+  if ((uintptr_t) w1->loop > (uintptr_t) w2->loop) return 1;
+
+  if ((uintptr_t) w1 < (uintptr_t) w2) return -1;
+  if ((uintptr_t) w1 > (uintptr_t) w2) return 1;
+
+  return 0;
+}
+
+
+RB_GENERATE_STATIC(uv_signal_tree_s, uv_signal_s, tree_entry, uv__signal_compare)
+
+
+/*
+ * Dispatches signal {signum} to all active uv_signal_t watchers in all loops.
+ * Returns 1 if the signal was dispatched to any watcher, or 0 if there were
+ * no active signal watchers observing this signal.
+ */
+int uv__signal_dispatch(int signum) {
+  uv_signal_t lookup;
+  uv_signal_t* handle;
+  int dispatched;
+
+  dispatched = 0;
+
+  EnterCriticalSection(&uv__signal_lock);
+
+  lookup.signum = signum;
+  lookup.loop = NULL;
+
+  for (handle = RB_NFIND(uv_signal_tree_s, &uv__signal_tree, &lookup);
+       handle != NULL && handle->signum == signum;
+       handle = RB_NEXT(uv_signal_tree_s, &uv__signal_tree, handle)) {
+    unsigned long previous = InterlockedExchange(
+            (volatile LONG*) &handle->pending_signum, signum);
+
+    if (handle->flags & UV_SIGNAL_ONE_SHOT_DISPATCHED)
+      continue;
+
+    if (!previous) {
+      POST_COMPLETION_FOR_REQ(handle->loop, &handle->signal_req);
+    }
+
+    dispatched = 1;
+    if (handle->flags & UV_SIGNAL_ONE_SHOT)
+      handle->flags |= UV_SIGNAL_ONE_SHOT_DISPATCHED;
+  }
+
+  LeaveCriticalSection(&uv__signal_lock);
+
+  return dispatched;
+}
+
+
+static BOOL WINAPI uv__signal_control_handler(DWORD type) {
+  switch (type) {
+    case CTRL_C_EVENT:
+      return uv__signal_dispatch(SIGINT);
+
+    case CTRL_BREAK_EVENT:
+      return uv__signal_dispatch(SIGBREAK);
+
+    case CTRL_CLOSE_EVENT:
+      if (uv__signal_dispatch(SIGHUP)) {
+        /* Windows will terminate the process after the control handler
+         * returns. After that it will just terminate our process. Therefore
+         * block the signal handler so the main loop has some time to pick up
+         * the signal and do something for a few seconds. */
+        Sleep(INFINITE);
+        return TRUE;
+      }
+      return FALSE;
+
+    case CTRL_LOGOFF_EVENT:
+    case CTRL_SHUTDOWN_EVENT:
+      /* These signals are only sent to services. Services have their own
+       * notification mechanism, so there's no point in handling these. */
+
+    default:
+      /* We don't handle these. */
+      return FALSE;
+  }
+}
+
+
+int uv_signal_init(uv_loop_t* loop, uv_signal_t* handle) {
+  uv__handle_init(loop, (uv_handle_t*) handle, UV_SIGNAL);
+  handle->pending_signum = 0;
+  handle->signum = 0;
+  handle->signal_cb = NULL;
+
+  UV_REQ_INIT(&handle->signal_req, UV_SIGNAL_REQ);
+  handle->signal_req.data = handle;
+
+  return 0;
+}
+
+
+int uv_signal_stop(uv_signal_t* handle) {
+  uv_signal_t* removed_handle;
+
+  /* If the watcher wasn't started, this is a no-op. */
+  if (handle->signum == 0)
+    return 0;
+
+  EnterCriticalSection(&uv__signal_lock);
+
+  removed_handle = RB_REMOVE(uv_signal_tree_s, &uv__signal_tree, handle);
+  assert(removed_handle == handle);
+
+  LeaveCriticalSection(&uv__signal_lock);
+
+  handle->signum = 0;
+  uv__handle_stop(handle);
+
+  return 0;
+}
+
+
+int uv_signal_start(uv_signal_t* handle, uv_signal_cb signal_cb, int signum) {
+  return uv__signal_start(handle, signal_cb, signum, 0);
+}
+
+
+int uv_signal_start_oneshot(uv_signal_t* handle,
+                            uv_signal_cb signal_cb,
+                            int signum) {
+  return uv__signal_start(handle, signal_cb, signum, 1);
+}
+
+
+int uv__signal_start(uv_signal_t* handle,
+                            uv_signal_cb signal_cb,
+                            int signum,
+                            int oneshot) {
+  /* Test for invalid signal values. */
+  if (signum <= 0 || signum >= NSIG)
+    return UV_EINVAL;
+
+  /* Short circuit: if the signal watcher is already watching {signum} don't go
+   * through the process of deregistering and registering the handler.
+   * Additionally, this avoids pending signals getting lost in the (small) time
+   * frame that handle->signum == 0. */
+  if (signum == handle->signum) {
+    handle->signal_cb = signal_cb;
+    return 0;
+  }
+
+  /* If the signal handler was already active, stop it first. */
+  if (handle->signum != 0) {
+    int r = uv_signal_stop(handle);
+    /* uv_signal_stop is infallible. */
+    assert(r == 0);
+  }
+
+  EnterCriticalSection(&uv__signal_lock);
+
+  handle->signum = signum;
+  if (oneshot)
+    handle->flags |= UV_SIGNAL_ONE_SHOT;
+
+  RB_INSERT(uv_signal_tree_s, &uv__signal_tree, handle);
+
+  LeaveCriticalSection(&uv__signal_lock);
+
+  handle->signal_cb = signal_cb;
+  uv__handle_start(handle);
+
+  return 0;
+}
+
+
+void uv__process_signal_req(uv_loop_t* loop, uv_signal_t* handle,
+    uv_req_t* req) {
+  long dispatched_signum;
+
+  assert(handle->type == UV_SIGNAL);
+  assert(req->type == UV_SIGNAL_REQ);
+
+  dispatched_signum = InterlockedExchange(
+          (volatile LONG*) &handle->pending_signum, 0);
+  assert(dispatched_signum != 0);
+
+  /* Check if the pending signal equals the signum that we are watching for.
+   * These can get out of sync when the handler is stopped and restarted while
+   * the signal_req is pending. */
+  if (dispatched_signum == handle->signum)
+    handle->signal_cb(handle, dispatched_signum);
+
+  if (handle->flags & UV_SIGNAL_ONE_SHOT)
+    uv_signal_stop(handle);
+
+  if (handle->flags & UV_HANDLE_CLOSING) {
+    /* When it is closing, it must be stopped at this point. */
+    assert(handle->signum == 0);
+    uv__want_endgame(loop, (uv_handle_t*) handle);
+  }
+}
+
+
+void uv__signal_close(uv_loop_t* loop, uv_signal_t* handle) {
+  uv_signal_stop(handle);
+  uv__handle_closing(handle);
+
+  if (handle->pending_signum == 0) {
+    uv__want_endgame(loop, (uv_handle_t*) handle);
+  }
+}
+
+
+void uv__signal_endgame(uv_loop_t* loop, uv_signal_t* handle) {
+  assert(handle->flags & UV_HANDLE_CLOSING);
+  assert(!(handle->flags & UV_HANDLE_CLOSED));
+
+  assert(handle->signum == 0);
+  assert(handle->pending_signum == 0);
+
+  handle->flags |= UV_HANDLE_CLOSED;
+
+  uv__handle_close(handle);
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/snprintf.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/snprintf.cpp
similarity index 100%
rename from third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/snprintf.cpp
rename to third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/snprintf.cpp
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/stream-inl.h b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/stream-inl.h
new file mode 100644
index 0000000..91b1e78
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/stream-inl.h
@@ -0,0 +1,54 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#ifndef UV_WIN_STREAM_INL_H_
+#define UV_WIN_STREAM_INL_H_
+
+#include <assert.h>
+
+#include "uv.h"
+#include "internal.h"
+#include "handle-inl.h"
+#include "req-inl.h"
+
+
+INLINE static void uv__stream_init(uv_loop_t* loop,
+                                   uv_stream_t* handle,
+                                   uv_handle_type type) {
+  uv__handle_init(loop, (uv_handle_t*) handle, type);
+  handle->write_queue_size = 0;
+  handle->activecnt = 0;
+  handle->stream.conn.shutdown_req = NULL;
+  handle->stream.conn.write_reqs_pending = 0;
+
+  UV_REQ_INIT(&handle->read_req, UV_READ);
+  handle->read_req.event_handle = NULL;
+  handle->read_req.wait_handle = INVALID_HANDLE_VALUE;
+  handle->read_req.data = handle;
+}
+
+
+INLINE static void uv__connection_init(uv_stream_t* handle) {
+  handle->flags |= UV_HANDLE_CONNECTION;
+}
+
+
+#endif /* UV_WIN_STREAM_INL_H_ */
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/stream.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/stream.cpp
new file mode 100644
index 0000000..292bf58
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/stream.cpp
@@ -0,0 +1,253 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <assert.h>
+
+#include "uv.h"
+#include "internal.h"
+#include "handle-inl.h"
+#include "req-inl.h"
+
+
+int uv_listen(uv_stream_t* stream, int backlog, uv_connection_cb cb) {
+  int err;
+  if (uv__is_closing(stream)) {
+    return UV_EINVAL;
+  }
+  err = ERROR_INVALID_PARAMETER;
+  switch (stream->type) {
+    case UV_TCP:
+      err = uv__tcp_listen((uv_tcp_t*)stream, backlog, cb);
+      break;
+    case UV_NAMED_PIPE:
+      err = uv__pipe_listen((uv_pipe_t*)stream, backlog, cb);
+      break;
+    default:
+      assert(0);
+  }
+
+  return uv_translate_sys_error(err);
+}
+
+
+int uv_accept(uv_stream_t* server, uv_stream_t* client) {
+  int err;
+
+  err = ERROR_INVALID_PARAMETER;
+  switch (server->type) {
+    case UV_TCP:
+      err = uv__tcp_accept((uv_tcp_t*)server, (uv_tcp_t*)client);
+      break;
+    case UV_NAMED_PIPE:
+      err = uv__pipe_accept((uv_pipe_t*)server, client);
+      break;
+    default:
+      assert(0);
+  }
+
+  return uv_translate_sys_error(err);
+}
+
+
+int uv__read_start(uv_stream_t* handle,
+                   uv_alloc_cb alloc_cb,
+                   uv_read_cb read_cb) {
+  int err;
+
+  err = ERROR_INVALID_PARAMETER;
+  switch (handle->type) {
+    case UV_TCP:
+      err = uv__tcp_read_start((uv_tcp_t*)handle, alloc_cb, read_cb);
+      break;
+    case UV_NAMED_PIPE:
+      err = uv__pipe_read_start((uv_pipe_t*)handle, alloc_cb, read_cb);
+      break;
+    case UV_TTY:
+      err = uv__tty_read_start((uv_tty_t*) handle, alloc_cb, read_cb);
+      break;
+    default:
+      assert(0);
+  }
+
+  return uv_translate_sys_error(err);
+}
+
+
+int uv_read_stop(uv_stream_t* handle) {
+  int err;
+
+  if (!(handle->flags & UV_HANDLE_READING))
+    return 0;
+
+  err = 0;
+  if (handle->type == UV_TTY) {
+    err = uv__tty_read_stop((uv_tty_t*) handle);
+  } else if (handle->type == UV_NAMED_PIPE) {
+    uv__pipe_read_stop((uv_pipe_t*) handle);
+  } else {
+    handle->flags &= ~UV_HANDLE_READING;
+    DECREASE_ACTIVE_COUNT(handle->loop, handle);
+  }
+
+  return uv_translate_sys_error(err);
+}
+
+
+int uv_write(uv_write_t* req,
+             uv_stream_t* handle,
+             const uv_buf_t bufs[],
+             unsigned int nbufs,
+             uv_write_cb cb) {
+  uv_loop_t* loop = handle->loop;
+  int err;
+
+  if (!(handle->flags & UV_HANDLE_WRITABLE)) {
+    return UV_EPIPE;
+  }
+
+  err = ERROR_INVALID_PARAMETER;
+  switch (handle->type) {
+    case UV_TCP:
+      err = uv__tcp_write(loop, req, (uv_tcp_t*) handle, bufs, nbufs, cb);
+      break;
+    case UV_NAMED_PIPE:
+      err = uv__pipe_write(
+          loop, req, (uv_pipe_t*) handle, bufs, nbufs, NULL, cb);
+      break;
+    case UV_TTY:
+      err = uv__tty_write(loop, req, (uv_tty_t*) handle, bufs, nbufs, cb);
+      break;
+    default:
+      assert(0);
+  }
+
+  return uv_translate_sys_error(err);
+}
+
+
+int uv_write2(uv_write_t* req,
+              uv_stream_t* handle,
+              const uv_buf_t bufs[],
+              unsigned int nbufs,
+              uv_stream_t* send_handle,
+              uv_write_cb cb) {
+  uv_loop_t* loop = handle->loop;
+  int err;
+
+  if (send_handle == NULL) {
+    return uv_write(req, handle, bufs, nbufs, cb);
+  }
+
+  if (handle->type != UV_NAMED_PIPE || !((uv_pipe_t*) handle)->ipc) {
+    return UV_EINVAL;
+  } else if (!(handle->flags & UV_HANDLE_WRITABLE)) {
+    return UV_EPIPE;
+  }
+
+  err = uv__pipe_write(
+      loop, req, (uv_pipe_t*) handle, bufs, nbufs, send_handle, cb);
+  return uv_translate_sys_error(err);
+}
+
+
+int uv_try_write(uv_stream_t* stream,
+                 const uv_buf_t bufs[],
+                 unsigned int nbufs) {
+  if (stream->flags & UV_HANDLE_CLOSING)
+    return UV_EBADF;
+  if (!(stream->flags & UV_HANDLE_WRITABLE))
+    return UV_EPIPE;
+
+  switch (stream->type) {
+    case UV_TCP:
+      return uv__tcp_try_write((uv_tcp_t*) stream, bufs, nbufs);
+    case UV_TTY:
+      return uv__tty_try_write((uv_tty_t*) stream, bufs, nbufs);
+    case UV_NAMED_PIPE:
+      return UV_EAGAIN;
+    default:
+      assert(0);
+      return UV_ENOSYS;
+  }
+}
+
+
+int uv_try_write2(uv_stream_t* stream,
+                  const uv_buf_t bufs[],
+                  unsigned int nbufs,
+                  uv_stream_t* send_handle) {
+  if (send_handle != NULL)
+    return UV_EAGAIN;
+  return uv_try_write(stream, bufs, nbufs);
+}
+
+
+int uv_shutdown(uv_shutdown_t* req, uv_stream_t* handle, uv_shutdown_cb cb) {
+  uv_loop_t* loop = handle->loop;
+
+  if (!(handle->flags & UV_HANDLE_WRITABLE) ||
+      handle->flags & UV_HANDLE_SHUTTING ||
+      uv__is_closing(handle)) {
+    return UV_ENOTCONN;
+  }
+
+  UV_REQ_INIT(req, UV_SHUTDOWN);
+  req->handle = handle;
+  req->cb = cb;
+
+  handle->flags &= ~UV_HANDLE_WRITABLE;
+  handle->flags |= UV_HANDLE_SHUTTING;
+  handle->stream.conn.shutdown_req = req;
+  handle->reqs_pending++;
+  REGISTER_HANDLE_REQ(loop, handle, req);
+
+  if (handle->stream.conn.write_reqs_pending == 0) {
+    if (handle->type == UV_NAMED_PIPE)
+      uv__pipe_shutdown(loop, (uv_pipe_t*) handle, req);
+    else
+      uv__insert_pending_req(loop, (uv_req_t*) req);
+  }
+
+  return 0;
+}
+
+
+int uv_is_readable(const uv_stream_t* handle) {
+  return !!(handle->flags & UV_HANDLE_READABLE);
+}
+
+
+int uv_is_writable(const uv_stream_t* handle) {
+  return !!(handle->flags & UV_HANDLE_WRITABLE);
+}
+
+
+int uv_stream_set_blocking(uv_stream_t* handle, int blocking) {
+  if (handle->type != UV_NAMED_PIPE)
+    return UV_EINVAL;
+
+  if (blocking != 0)
+    handle->flags |= UV_HANDLE_BLOCKING_WRITES;
+  else
+    handle->flags &= ~UV_HANDLE_BLOCKING_WRITES;
+
+  return 0;
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/tcp.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/tcp.cpp
new file mode 100644
index 0000000..4cccee4
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/tcp.cpp
@@ -0,0 +1,1699 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <assert.h>
+#include <stdlib.h>
+
+#include "uv.h"
+#include "internal.h"
+#include "handle-inl.h"
+#include "stream-inl.h"
+#include "req-inl.h"
+
+
+/*
+ * Threshold of active tcp streams for which to preallocate tcp read buffers.
+ * (Due to node slab allocator performing poorly under this pattern,
+ *  the optimization is temporarily disabled (threshold=0).  This will be
+ *  revisited once node allocator is improved.)
+ */
+const unsigned int uv_active_tcp_streams_threshold = 0;
+
+/*
+ * Number of simultaneous pending AcceptEx calls.
+ */
+const unsigned int uv_simultaneous_server_accepts = 32;
+
+/* A zero-size buffer for use by uv_tcp_read */
+static char uv_zero_[] = "";
+
+static int uv__tcp_nodelay(uv_tcp_t* handle, SOCKET socket, int enable) {
+  if (setsockopt(socket,
+                 IPPROTO_TCP,
+                 TCP_NODELAY,
+                 (const char*)&enable,
+                 sizeof enable) == -1) {
+    return WSAGetLastError();
+  }
+  return 0;
+}
+
+
+static int uv__tcp_keepalive(uv_tcp_t* handle, SOCKET socket, int enable, unsigned int delay) {
+  if (setsockopt(socket,
+                 SOL_SOCKET,
+                 SO_KEEPALIVE,
+                 (const char*)&enable,
+                 sizeof enable) == -1) {
+    return WSAGetLastError();
+  }
+
+  if (enable && setsockopt(socket,
+                           IPPROTO_TCP,
+                           TCP_KEEPALIVE,
+                           (const char*)&delay,
+                           sizeof delay) == -1) {
+    return WSAGetLastError();
+  }
+
+  return 0;
+}
+
+
+static int uv__tcp_set_socket(uv_loop_t* loop,
+                              uv_tcp_t* handle,
+                              SOCKET socket,
+                              int family,
+                              int imported) {
+  DWORD yes = 1;
+  int non_ifs_lsp;
+  int err;
+
+  if (handle->socket != INVALID_SOCKET)
+    return UV_EBUSY;
+
+  /* Set the socket to nonblocking mode */
+  if (ioctlsocket(socket, FIONBIO, &yes) == SOCKET_ERROR) {
+    return WSAGetLastError();
+  }
+
+  /* Make the socket non-inheritable */
+  if (!SetHandleInformation((HANDLE) socket, HANDLE_FLAG_INHERIT, 0))
+    return GetLastError();
+
+  /* Associate it with the I/O completion port. Use uv_handle_t pointer as
+   * completion key. */
+  if (CreateIoCompletionPort((HANDLE)socket,
+                             loop->iocp,
+                             (ULONG_PTR)socket,
+                             0) == NULL) {
+    if (imported) {
+      handle->flags |= UV_HANDLE_EMULATE_IOCP;
+    } else {
+      return GetLastError();
+    }
+  }
+
+  if (family == AF_INET6) {
+    non_ifs_lsp = uv_tcp_non_ifs_lsp_ipv6;
+  } else {
+    non_ifs_lsp = uv_tcp_non_ifs_lsp_ipv4;
+  }
+
+  if (!(handle->flags & UV_HANDLE_EMULATE_IOCP) && !non_ifs_lsp) {
+    UCHAR sfcnm_flags =
+        FILE_SKIP_SET_EVENT_ON_HANDLE | FILE_SKIP_COMPLETION_PORT_ON_SUCCESS;
+    if (!SetFileCompletionNotificationModes((HANDLE) socket, sfcnm_flags))
+      return GetLastError();
+    handle->flags |= UV_HANDLE_SYNC_BYPASS_IOCP;
+  }
+
+  if (handle->flags & UV_HANDLE_TCP_NODELAY) {
+    err = uv__tcp_nodelay(handle, socket, 1);
+    if (err)
+      return err;
+  }
+
+  /* TODO: Use stored delay. */
+  if (handle->flags & UV_HANDLE_TCP_KEEPALIVE) {
+    err = uv__tcp_keepalive(handle, socket, 1, 60);
+    if (err)
+      return err;
+  }
+
+  handle->socket = socket;
+
+  if (family == AF_INET6) {
+    handle->flags |= UV_HANDLE_IPV6;
+  } else {
+    assert(!(handle->flags & UV_HANDLE_IPV6));
+  }
+
+  return 0;
+}
+
+
+int uv_tcp_init_ex(uv_loop_t* loop, uv_tcp_t* handle, unsigned int flags) {
+  int domain;
+
+  /* Use the lower 8 bits for the domain */
+  domain = flags & 0xFF;
+  if (domain != AF_INET && domain != AF_INET6 && domain != AF_UNSPEC)
+    return UV_EINVAL;
+
+  if (flags & ~0xFF)
+    return UV_EINVAL;
+
+  uv__stream_init(loop, (uv_stream_t*) handle, UV_TCP);
+  handle->tcp.serv.accept_reqs = NULL;
+  handle->tcp.serv.pending_accepts = NULL;
+  handle->socket = INVALID_SOCKET;
+  handle->reqs_pending = 0;
+  handle->tcp.serv.func_acceptex = NULL;
+  handle->tcp.conn.func_connectex = NULL;
+  handle->tcp.serv.processed_accepts = 0;
+  handle->delayed_error = 0;
+
+  /* If anything fails beyond this point we need to remove the handle from
+   * the handle queue, since it was added by uv__handle_init in uv__stream_init.
+   */
+
+  if (domain != AF_UNSPEC) {
+    SOCKET sock;
+    DWORD err;
+
+    sock = socket(domain, SOCK_STREAM, 0);
+    if (sock == INVALID_SOCKET) {
+      err = WSAGetLastError();
+      QUEUE_REMOVE(&handle->handle_queue);
+      return uv_translate_sys_error(err);
+    }
+
+    err = uv__tcp_set_socket(handle->loop, handle, sock, domain, 0);
+    if (err) {
+      closesocket(sock);
+      QUEUE_REMOVE(&handle->handle_queue);
+      return uv_translate_sys_error(err);
+    }
+
+  }
+
+  return 0;
+}
+
+
+int uv_tcp_init(uv_loop_t* loop, uv_tcp_t* handle) {
+  return uv_tcp_init_ex(loop, handle, AF_UNSPEC);
+}
+
+
+void uv__process_tcp_shutdown_req(uv_loop_t* loop, uv_tcp_t* stream, uv_shutdown_t *req) {
+  int err;
+
+  assert(req);
+  assert(stream->stream.conn.write_reqs_pending == 0);
+  assert(!(stream->flags & UV_HANDLE_SHUT));
+  assert(stream->flags & UV_HANDLE_CONNECTION);
+
+  stream->stream.conn.shutdown_req = NULL;
+  stream->flags &= ~UV_HANDLE_SHUTTING;
+  UNREGISTER_HANDLE_REQ(loop, stream, req);
+
+  err = 0;
+  if (stream->flags & UV_HANDLE_CLOSING)
+   /* The user destroyed the stream before we got to do the shutdown. */
+    err = UV_ECANCELED;
+  else if (shutdown(stream->socket, SD_SEND) == SOCKET_ERROR)
+    err = uv_translate_sys_error(WSAGetLastError());
+  else /* Success. */
+    stream->flags |= UV_HANDLE_SHUT;
+
+  if (req->cb)
+    req->cb(req, err);
+
+  DECREASE_PENDING_REQ_COUNT(stream);
+}
+
+
+void uv__tcp_endgame(uv_loop_t* loop, uv_tcp_t* handle) {
+  unsigned int i;
+  uv_tcp_accept_t* req;
+
+  assert(handle->flags & UV_HANDLE_CLOSING);
+  assert(handle->reqs_pending == 0);
+  assert(!(handle->flags & UV_HANDLE_CLOSED));
+  assert(handle->socket == INVALID_SOCKET);
+
+  if (!(handle->flags & UV_HANDLE_CONNECTION) && handle->tcp.serv.accept_reqs) {
+    if (handle->flags & UV_HANDLE_EMULATE_IOCP) {
+      for (i = 0; i < uv_simultaneous_server_accepts; i++) {
+        req = &handle->tcp.serv.accept_reqs[i];
+        if (req->wait_handle != INVALID_HANDLE_VALUE) {
+          UnregisterWait(req->wait_handle);
+          req->wait_handle = INVALID_HANDLE_VALUE;
+        }
+        if (req->event_handle != NULL) {
+          CloseHandle(req->event_handle);
+          req->event_handle = NULL;
+        }
+      }
+    }
+
+    uv__free(handle->tcp.serv.accept_reqs);
+    handle->tcp.serv.accept_reqs = NULL;
+  }
+
+  if (handle->flags & UV_HANDLE_CONNECTION &&
+      handle->flags & UV_HANDLE_EMULATE_IOCP) {
+    if (handle->read_req.wait_handle != INVALID_HANDLE_VALUE) {
+      UnregisterWait(handle->read_req.wait_handle);
+      handle->read_req.wait_handle = INVALID_HANDLE_VALUE;
+    }
+    if (handle->read_req.event_handle != NULL) {
+      CloseHandle(handle->read_req.event_handle);
+      handle->read_req.event_handle = NULL;
+    }
+  }
+
+  uv__handle_close(handle);
+  loop->active_tcp_streams--;
+}
+
+
+/* Unlike on Unix, here we don't set SO_REUSEADDR, because it doesn't just
+ * allow binding to addresses that are in use by sockets in TIME_WAIT, it
+ * effectively allows 'stealing' a port which is in use by another application.
+ *
+ * SO_EXCLUSIVEADDRUSE is also not good here because it does check all sockets,
+ * regardless of state, so we'd get an error even if the port is in use by a
+ * socket in TIME_WAIT state.
+ *
+ * See issue #1360.
+ *
+ */
+static int uv__tcp_try_bind(uv_tcp_t* handle,
+                            const struct sockaddr* addr,
+                            unsigned int addrlen,
+                            unsigned int flags) {
+  DWORD err;
+  int r;
+
+  if (handle->socket == INVALID_SOCKET) {
+    SOCKET sock;
+
+    /* Cannot set IPv6-only mode on non-IPv6 socket. */
+    if ((flags & UV_TCP_IPV6ONLY) && addr->sa_family != AF_INET6)
+      return ERROR_INVALID_PARAMETER;
+
+    sock = socket(addr->sa_family, SOCK_STREAM, 0);
+    if (sock == INVALID_SOCKET) {
+      return WSAGetLastError();
+    }
+
+    err = uv__tcp_set_socket(handle->loop, handle, sock, addr->sa_family, 0);
+    if (err) {
+      closesocket(sock);
+      return err;
+    }
+  }
+
+#ifdef IPV6_V6ONLY
+  if (addr->sa_family == AF_INET6) {
+    int on;
+
+    on = (flags & UV_TCP_IPV6ONLY) != 0;
+
+    /* TODO: how to handle errors? This may fail if there is no ipv4 stack
+     * available, or when run on XP/2003 which have no support for dualstack
+     * sockets. For now we're silently ignoring the error. */
+    setsockopt(handle->socket,
+               IPPROTO_IPV6,
+               IPV6_V6ONLY,
+               (const char*)&on,
+               sizeof on);
+  }
+#endif
+
+  r = bind(handle->socket, addr, addrlen);
+
+  if (r == SOCKET_ERROR) {
+    err = WSAGetLastError();
+    if (err == WSAEADDRINUSE) {
+      /* Some errors are not to be reported until connect() or listen() */
+      handle->delayed_error = err;
+    } else {
+      return err;
+    }
+  }
+
+  handle->flags |= UV_HANDLE_BOUND;
+
+  return 0;
+}
+
+
+static void CALLBACK post_completion(void* context, BOOLEAN timed_out) {
+  uv_req_t* req;
+  uv_tcp_t* handle;
+
+  req = (uv_req_t*) context;
+  assert(req != NULL);
+  handle = (uv_tcp_t*)req->data;
+  assert(handle != NULL);
+  assert(!timed_out);
+
+  if (!PostQueuedCompletionStatus(handle->loop->iocp,
+                                  req->u.io.overlapped.InternalHigh,
+                                  0,
+                                  &req->u.io.overlapped)) {
+    uv_fatal_error(GetLastError(), "PostQueuedCompletionStatus");
+  }
+}
+
+
+static void CALLBACK post_write_completion(void* context, BOOLEAN timed_out) {
+  uv_write_t* req;
+  uv_tcp_t* handle;
+
+  req = (uv_write_t*) context;
+  assert(req != NULL);
+  handle = (uv_tcp_t*)req->handle;
+  assert(handle != NULL);
+  assert(!timed_out);
+
+  if (!PostQueuedCompletionStatus(handle->loop->iocp,
+                                  req->u.io.overlapped.InternalHigh,
+                                  0,
+                                  &req->u.io.overlapped)) {
+    uv_fatal_error(GetLastError(), "PostQueuedCompletionStatus");
+  }
+}
+
+
+static void uv__tcp_queue_accept(uv_tcp_t* handle, uv_tcp_accept_t* req) {
+  uv_loop_t* loop = handle->loop;
+  BOOL success;
+  DWORD bytes;
+  SOCKET accept_socket;
+  short family;
+
+  assert(handle->flags & UV_HANDLE_LISTENING);
+  assert(req->accept_socket == INVALID_SOCKET);
+
+  /* choose family and extension function */
+  if (handle->flags & UV_HANDLE_IPV6) {
+    family = AF_INET6;
+  } else {
+    family = AF_INET;
+  }
+
+  /* Open a socket for the accepted connection. */
+  accept_socket = socket(family, SOCK_STREAM, 0);
+  if (accept_socket == INVALID_SOCKET) {
+    SET_REQ_ERROR(req, WSAGetLastError());
+    uv__insert_pending_req(loop, (uv_req_t*)req);
+    handle->reqs_pending++;
+    return;
+  }
+
+  /* Make the socket non-inheritable */
+  if (!SetHandleInformation((HANDLE) accept_socket, HANDLE_FLAG_INHERIT, 0)) {
+    SET_REQ_ERROR(req, GetLastError());
+    uv__insert_pending_req(loop, (uv_req_t*)req);
+    handle->reqs_pending++;
+    closesocket(accept_socket);
+    return;
+  }
+
+  /* Prepare the overlapped structure. */
+  memset(&(req->u.io.overlapped), 0, sizeof(req->u.io.overlapped));
+  if (handle->flags & UV_HANDLE_EMULATE_IOCP) {
+    assert(req->event_handle != NULL);
+    req->u.io.overlapped.hEvent = (HANDLE) ((ULONG_PTR) req->event_handle | 1);
+  }
+
+  success = handle->tcp.serv.func_acceptex(handle->socket,
+                                          accept_socket,
+                                          (void*)req->accept_buffer,
+                                          0,
+                                          sizeof(struct sockaddr_storage),
+                                          sizeof(struct sockaddr_storage),
+                                          &bytes,
+                                          &req->u.io.overlapped);
+
+  if (UV_SUCCEEDED_WITHOUT_IOCP(success)) {
+    /* Process the req without IOCP. */
+    req->accept_socket = accept_socket;
+    handle->reqs_pending++;
+    uv__insert_pending_req(loop, (uv_req_t*)req);
+  } else if (UV_SUCCEEDED_WITH_IOCP(success)) {
+    /* The req will be processed with IOCP. */
+    req->accept_socket = accept_socket;
+    handle->reqs_pending++;
+    if (handle->flags & UV_HANDLE_EMULATE_IOCP &&
+        req->wait_handle == INVALID_HANDLE_VALUE &&
+        !RegisterWaitForSingleObject(&req->wait_handle,
+          req->event_handle, post_completion, (void*) req,
+          INFINITE, WT_EXECUTEINWAITTHREAD)) {
+      SET_REQ_ERROR(req, GetLastError());
+      uv__insert_pending_req(loop, (uv_req_t*)req);
+    }
+  } else {
+    /* Make this req pending reporting an error. */
+    SET_REQ_ERROR(req, WSAGetLastError());
+    uv__insert_pending_req(loop, (uv_req_t*)req);
+    handle->reqs_pending++;
+    /* Destroy the preallocated client socket. */
+    closesocket(accept_socket);
+    /* Destroy the event handle */
+    if (handle->flags & UV_HANDLE_EMULATE_IOCP) {
+      CloseHandle(req->event_handle);
+      req->event_handle = NULL;
+    }
+  }
+}
+
+
+static void uv__tcp_queue_read(uv_loop_t* loop, uv_tcp_t* handle) {
+  uv_read_t* req;
+  uv_buf_t buf;
+  int result;
+  DWORD bytes, flags;
+
+  assert(handle->flags & UV_HANDLE_READING);
+  assert(!(handle->flags & UV_HANDLE_READ_PENDING));
+
+  req = &handle->read_req;
+  memset(&req->u.io.overlapped, 0, sizeof(req->u.io.overlapped));
+
+  /*
+   * Preallocate a read buffer if the number of active streams is below
+   * the threshold.
+  */
+  if (loop->active_tcp_streams < uv_active_tcp_streams_threshold) {
+    handle->flags &= ~UV_HANDLE_ZERO_READ;
+    handle->tcp.conn.read_buffer = uv_buf_init(NULL, 0);
+    handle->alloc_cb((uv_handle_t*) handle, 65536, &handle->tcp.conn.read_buffer);
+    if (handle->tcp.conn.read_buffer.base == NULL ||
+        handle->tcp.conn.read_buffer.len == 0) {
+      handle->read_cb((uv_stream_t*) handle, UV_ENOBUFS, &handle->tcp.conn.read_buffer);
+      return;
+    }
+    assert(handle->tcp.conn.read_buffer.base != NULL);
+    buf = handle->tcp.conn.read_buffer;
+  } else {
+    handle->flags |= UV_HANDLE_ZERO_READ;
+    buf.base = (char*) &uv_zero_;
+    buf.len = 0;
+  }
+
+  /* Prepare the overlapped structure. */
+  memset(&(req->u.io.overlapped), 0, sizeof(req->u.io.overlapped));
+  if (handle->flags & UV_HANDLE_EMULATE_IOCP) {
+    assert(req->event_handle != NULL);
+    req->u.io.overlapped.hEvent = (HANDLE) ((ULONG_PTR) req->event_handle | 1);
+  }
+
+  flags = 0;
+  result = WSARecv(handle->socket,
+                   (WSABUF*)&buf,
+                   1,
+                   &bytes,
+                   &flags,
+                   &req->u.io.overlapped,
+                   NULL);
+
+  handle->flags |= UV_HANDLE_READ_PENDING;
+  handle->reqs_pending++;
+
+  if (UV_SUCCEEDED_WITHOUT_IOCP(result == 0)) {
+    /* Process the req without IOCP. */
+    req->u.io.overlapped.InternalHigh = bytes;
+    uv__insert_pending_req(loop, (uv_req_t*)req);
+  } else if (UV_SUCCEEDED_WITH_IOCP(result == 0)) {
+    /* The req will be processed with IOCP. */
+    if (handle->flags & UV_HANDLE_EMULATE_IOCP &&
+        req->wait_handle == INVALID_HANDLE_VALUE &&
+        !RegisterWaitForSingleObject(&req->wait_handle,
+          req->event_handle, post_completion, (void*) req,
+          INFINITE, WT_EXECUTEINWAITTHREAD)) {
+      SET_REQ_ERROR(req, GetLastError());
+      uv__insert_pending_req(loop, (uv_req_t*)req);
+    }
+  } else {
+    /* Make this req pending reporting an error. */
+    SET_REQ_ERROR(req, WSAGetLastError());
+    uv__insert_pending_req(loop, (uv_req_t*)req);
+  }
+}
+
+
+int uv_tcp_close_reset(uv_tcp_t* handle, uv_close_cb close_cb) {
+  struct linger l = { 1, 0 };
+
+  /* Disallow setting SO_LINGER to zero due to some platform inconsistencies */
+  if (handle->flags & UV_HANDLE_SHUTTING)
+    return UV_EINVAL;
+
+  if (0 != setsockopt(handle->socket, SOL_SOCKET, SO_LINGER, (const char*)&l, sizeof(l)))
+    return uv_translate_sys_error(WSAGetLastError());
+
+  uv_close((uv_handle_t*) handle, close_cb);
+  return 0;
+}
+
+
+int uv__tcp_listen(uv_tcp_t* handle, int backlog, uv_connection_cb cb) {
+  unsigned int i, simultaneous_accepts;
+  uv_tcp_accept_t* req;
+  int err;
+
+  assert(backlog > 0);
+
+  if (handle->flags & UV_HANDLE_LISTENING) {
+    handle->stream.serv.connection_cb = cb;
+  }
+
+  if (handle->flags & UV_HANDLE_READING) {
+    return WSAEISCONN;
+  }
+
+  if (handle->delayed_error) {
+    return handle->delayed_error;
+  }
+
+  if (!(handle->flags & UV_HANDLE_BOUND)) {
+    err = uv__tcp_try_bind(handle,
+                           (const struct sockaddr*) &uv_addr_ip4_any_,
+                           sizeof(uv_addr_ip4_any_),
+                           0);
+    if (err)
+      return err;
+    if (handle->delayed_error)
+      return handle->delayed_error;
+  }
+
+  if (!handle->tcp.serv.func_acceptex) {
+    if (!uv__get_acceptex_function(handle->socket, &handle->tcp.serv.func_acceptex)) {
+      return WSAEAFNOSUPPORT;
+    }
+  }
+
+  /* If this flag is set, we already made this listen call in xfer. */
+  if (!(handle->flags & UV_HANDLE_SHARED_TCP_SOCKET) &&
+      listen(handle->socket, backlog) == SOCKET_ERROR) {
+    return WSAGetLastError();
+  }
+
+  handle->flags |= UV_HANDLE_LISTENING;
+  handle->stream.serv.connection_cb = cb;
+  INCREASE_ACTIVE_COUNT(loop, handle);
+
+  simultaneous_accepts = handle->flags & UV_HANDLE_TCP_SINGLE_ACCEPT ? 1
+    : uv_simultaneous_server_accepts;
+
+  if (handle->tcp.serv.accept_reqs == NULL) {
+    handle->tcp.serv.accept_reqs =
+      (uv_tcp_accept_t*)uv__malloc(uv_simultaneous_server_accepts * sizeof(uv_tcp_accept_t));
+    if (!handle->tcp.serv.accept_reqs) {
+      uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+    }
+
+    for (i = 0; i < simultaneous_accepts; i++) {
+      req = &handle->tcp.serv.accept_reqs[i];
+      UV_REQ_INIT(req, UV_ACCEPT);
+      req->accept_socket = INVALID_SOCKET;
+      req->data = handle;
+
+      req->wait_handle = INVALID_HANDLE_VALUE;
+      if (handle->flags & UV_HANDLE_EMULATE_IOCP) {
+        req->event_handle = CreateEvent(NULL, 0, 0, NULL);
+        if (req->event_handle == NULL) {
+          uv_fatal_error(GetLastError(), "CreateEvent");
+        }
+      } else {
+        req->event_handle = NULL;
+      }
+
+      uv__tcp_queue_accept(handle, req);
+    }
+
+    /* Initialize other unused requests too, because uv_tcp_endgame doesn't
+     * know how many requests were initialized, so it will try to clean up
+     * {uv_simultaneous_server_accepts} requests. */
+    for (i = simultaneous_accepts; i < uv_simultaneous_server_accepts; i++) {
+      req = &handle->tcp.serv.accept_reqs[i];
+      UV_REQ_INIT(req, UV_ACCEPT);
+      req->accept_socket = INVALID_SOCKET;
+      req->data = handle;
+      req->wait_handle = INVALID_HANDLE_VALUE;
+      req->event_handle = NULL;
+    }
+  }
+
+  return 0;
+}
+
+
+int uv__tcp_accept(uv_tcp_t* server, uv_tcp_t* client) {
+  uv_loop_t* loop = server->loop;
+  int err = 0;
+  int family;
+
+  uv_tcp_accept_t* req = server->tcp.serv.pending_accepts;
+
+  if (!req) {
+    /* No valid connections found, so we error out. */
+    return WSAEWOULDBLOCK;
+  }
+
+  if (req->accept_socket == INVALID_SOCKET) {
+    return WSAENOTCONN;
+  }
+
+  if (server->flags & UV_HANDLE_IPV6) {
+    family = AF_INET6;
+  } else {
+    family = AF_INET;
+  }
+
+  err = uv__tcp_set_socket(client->loop,
+                          client,
+                          req->accept_socket,
+                          family,
+                          0);
+  if (err) {
+    closesocket(req->accept_socket);
+  } else {
+    uv__connection_init((uv_stream_t*) client);
+    /* AcceptEx() implicitly binds the accepted socket. */
+    client->flags |= UV_HANDLE_BOUND | UV_HANDLE_READABLE | UV_HANDLE_WRITABLE;
+  }
+
+  /* Prepare the req to pick up a new connection */
+  server->tcp.serv.pending_accepts = req->next_pending;
+  req->next_pending = NULL;
+  req->accept_socket = INVALID_SOCKET;
+
+  if (!(server->flags & UV_HANDLE_CLOSING)) {
+    /* Check if we're in a middle of changing the number of pending accepts. */
+    if (!(server->flags & UV_HANDLE_TCP_ACCEPT_STATE_CHANGING)) {
+      uv__tcp_queue_accept(server, req);
+    } else {
+      /* We better be switching to a single pending accept. */
+      assert(server->flags & UV_HANDLE_TCP_SINGLE_ACCEPT);
+
+      server->tcp.serv.processed_accepts++;
+
+      if (server->tcp.serv.processed_accepts >= uv_simultaneous_server_accepts) {
+        server->tcp.serv.processed_accepts = 0;
+        /*
+         * All previously queued accept requests are now processed.
+         * We now switch to queueing just a single accept.
+         */
+        uv__tcp_queue_accept(server, &server->tcp.serv.accept_reqs[0]);
+        server->flags &= ~UV_HANDLE_TCP_ACCEPT_STATE_CHANGING;
+        server->flags |= UV_HANDLE_TCP_SINGLE_ACCEPT;
+      }
+    }
+  }
+
+  loop->active_tcp_streams++;
+
+  return err;
+}
+
+
+int uv__tcp_read_start(uv_tcp_t* handle, uv_alloc_cb alloc_cb,
+    uv_read_cb read_cb) {
+  uv_loop_t* loop = handle->loop;
+
+  handle->flags |= UV_HANDLE_READING;
+  handle->read_cb = read_cb;
+  handle->alloc_cb = alloc_cb;
+  INCREASE_ACTIVE_COUNT(loop, handle);
+
+  /* If reading was stopped and then started again, there could still be a read
+   * request pending. */
+  if (!(handle->flags & UV_HANDLE_READ_PENDING)) {
+    if (handle->flags & UV_HANDLE_EMULATE_IOCP &&
+        handle->read_req.event_handle == NULL) {
+      handle->read_req.event_handle = CreateEvent(NULL, 0, 0, NULL);
+      if (handle->read_req.event_handle == NULL) {
+        uv_fatal_error(GetLastError(), "CreateEvent");
+      }
+    }
+    uv__tcp_queue_read(loop, handle);
+  }
+
+  return 0;
+}
+
+static int uv__is_loopback(const struct sockaddr_storage* storage) {
+  const struct sockaddr_in* in4;
+  const struct sockaddr_in6* in6;
+  int i;
+
+  if (storage->ss_family == AF_INET) {
+    in4 = (const struct sockaddr_in*) storage;
+    return in4->sin_addr.S_un.S_un_b.s_b1 == 127;
+  }
+  if (storage->ss_family == AF_INET6) {
+    in6 = (const struct sockaddr_in6*) storage;
+    for (i = 0; i < 7; ++i) {
+      if (in6->sin6_addr.u.Word[i] != 0)
+        return 0;
+    }
+    return in6->sin6_addr.u.Word[7] == htons(1);
+  }
+  return 0;
+}
+
+// Check if Windows version is 10.0.16299 or later
+static int uv__is_fast_loopback_fail_supported(void) {
+  OSVERSIONINFOW os_info;
+  if (!pRtlGetVersion)
+    return 0;
+  pRtlGetVersion(&os_info);
+  if (os_info.dwMajorVersion < 10)
+    return 0;
+  if (os_info.dwMajorVersion > 10)
+    return 1;
+  if (os_info.dwMinorVersion > 0)
+    return 1;
+  return os_info.dwBuildNumber >= 16299;
+}
+
+static int uv__tcp_try_connect(uv_connect_t* req,
+                              uv_tcp_t* handle,
+                              const struct sockaddr* addr,
+                              unsigned int addrlen,
+                              uv_connect_cb cb) {
+  uv_loop_t* loop = handle->loop;
+  TCP_INITIAL_RTO_PARAMETERS retransmit_ioctl;
+  const struct sockaddr* bind_addr;
+  struct sockaddr_storage converted;
+  BOOL success;
+  DWORD bytes;
+  int err;
+
+  err = uv__convert_to_localhost_if_unspecified(addr, &converted);
+  if (err)
+    return err;
+
+  if (handle->delayed_error != 0)
+    goto out;
+
+  if (!(handle->flags & UV_HANDLE_BOUND)) {
+    if (addrlen == sizeof(uv_addr_ip4_any_)) {
+      bind_addr = (const struct sockaddr*) &uv_addr_ip4_any_;
+    } else if (addrlen == sizeof(uv_addr_ip6_any_)) {
+      bind_addr = (const struct sockaddr*) &uv_addr_ip6_any_;
+    } else {
+      abort();
+    }
+    err = uv__tcp_try_bind(handle, bind_addr, addrlen, 0);
+    if (err)
+      return err;
+    if (handle->delayed_error != 0)
+      goto out;
+  }
+
+  if (!handle->tcp.conn.func_connectex) {
+    if (!uv__get_connectex_function(handle->socket, &handle->tcp.conn.func_connectex)) {
+      return WSAEAFNOSUPPORT;
+    }
+  }
+
+  /* This makes connect() fail instantly if the target port on the localhost
+   * is not reachable, instead of waiting for 2s. We do not care if this fails.
+   * This only works on Windows version 10.0.16299 and later.
+   */
+  if (uv__is_fast_loopback_fail_supported() && uv__is_loopback(&converted)) {
+    memset(&retransmit_ioctl, 0, sizeof(retransmit_ioctl));
+    retransmit_ioctl.Rtt = TCP_INITIAL_RTO_NO_SYN_RETRANSMISSIONS;
+    retransmit_ioctl.MaxSynRetransmissions = TCP_INITIAL_RTO_NO_SYN_RETRANSMISSIONS;
+    WSAIoctl(handle->socket,
+             SIO_TCP_INITIAL_RTO,
+             &retransmit_ioctl,
+             sizeof(retransmit_ioctl),
+             NULL,
+             0,
+             &bytes,
+             NULL,
+             NULL);
+  }
+
+out:
+
+  UV_REQ_INIT(req, UV_CONNECT);
+  req->handle = (uv_stream_t*) handle;
+  req->cb = cb;
+  memset(&req->u.io.overlapped, 0, sizeof(req->u.io.overlapped));
+
+  if (handle->delayed_error != 0) {
+    /* Process the req without IOCP. */
+    handle->reqs_pending++;
+    REGISTER_HANDLE_REQ(loop, handle, req);
+    uv__insert_pending_req(loop, (uv_req_t*)req);
+    return 0;
+  }
+
+  success = handle->tcp.conn.func_connectex(handle->socket,
+                                            (const struct sockaddr*) &converted,
+                                            addrlen,
+                                            NULL,
+                                            0,
+                                            &bytes,
+                                            &req->u.io.overlapped);
+
+  if (UV_SUCCEEDED_WITHOUT_IOCP(success)) {
+    /* Process the req without IOCP. */
+    handle->reqs_pending++;
+    REGISTER_HANDLE_REQ(loop, handle, req);
+    uv__insert_pending_req(loop, (uv_req_t*)req);
+  } else if (UV_SUCCEEDED_WITH_IOCP(success)) {
+    /* The req will be processed with IOCP. */
+    handle->reqs_pending++;
+    REGISTER_HANDLE_REQ(loop, handle, req);
+  } else {
+    return WSAGetLastError();
+  }
+
+  return 0;
+}
+
+
+int uv_tcp_getsockname(const uv_tcp_t* handle,
+                       struct sockaddr* name,
+                       int* namelen) {
+
+  return uv__getsockpeername((const uv_handle_t*) handle,
+                             getsockname,
+                             name,
+                             namelen,
+                             handle->delayed_error);
+}
+
+
+int uv_tcp_getpeername(const uv_tcp_t* handle,
+                       struct sockaddr* name,
+                       int* namelen) {
+
+  return uv__getsockpeername((const uv_handle_t*) handle,
+                             getpeername,
+                             name,
+                             namelen,
+                             handle->delayed_error);
+}
+
+
+int uv__tcp_write(uv_loop_t* loop,
+                 uv_write_t* req,
+                 uv_tcp_t* handle,
+                 const uv_buf_t bufs[],
+                 unsigned int nbufs,
+                 uv_write_cb cb) {
+  int result;
+  DWORD bytes;
+
+  UV_REQ_INIT(req, UV_WRITE);
+  req->handle = (uv_stream_t*) handle;
+  req->cb = cb;
+
+  /* Prepare the overlapped structure. */
+  memset(&(req->u.io.overlapped), 0, sizeof(req->u.io.overlapped));
+  if (handle->flags & UV_HANDLE_EMULATE_IOCP) {
+    req->event_handle = CreateEvent(NULL, 0, 0, NULL);
+    if (req->event_handle == NULL) {
+      uv_fatal_error(GetLastError(), "CreateEvent");
+    }
+    req->u.io.overlapped.hEvent = (HANDLE) ((ULONG_PTR) req->event_handle | 1);
+    req->wait_handle = INVALID_HANDLE_VALUE;
+  }
+
+  result = WSASend(handle->socket,
+                   (WSABUF*) bufs,
+                   nbufs,
+                   &bytes,
+                   0,
+                   &req->u.io.overlapped,
+                   NULL);
+
+  if (UV_SUCCEEDED_WITHOUT_IOCP(result == 0)) {
+    /* Request completed immediately. */
+    req->u.io.queued_bytes = 0;
+    handle->reqs_pending++;
+    handle->stream.conn.write_reqs_pending++;
+    REGISTER_HANDLE_REQ(loop, handle, req);
+    uv__insert_pending_req(loop, (uv_req_t*) req);
+  } else if (UV_SUCCEEDED_WITH_IOCP(result == 0)) {
+    /* Request queued by the kernel. */
+    req->u.io.queued_bytes = uv__count_bufs(bufs, nbufs);
+    handle->reqs_pending++;
+    handle->stream.conn.write_reqs_pending++;
+    REGISTER_HANDLE_REQ(loop, handle, req);
+    handle->write_queue_size += req->u.io.queued_bytes;
+    if (handle->flags & UV_HANDLE_EMULATE_IOCP &&
+        !RegisterWaitForSingleObject(&req->wait_handle,
+          req->event_handle, post_write_completion, (void*) req,
+          INFINITE, WT_EXECUTEINWAITTHREAD | WT_EXECUTEONLYONCE)) {
+      SET_REQ_ERROR(req, GetLastError());
+      uv__insert_pending_req(loop, (uv_req_t*)req);
+    }
+  } else {
+    /* Send failed due to an error, report it later */
+    req->u.io.queued_bytes = 0;
+    handle->reqs_pending++;
+    handle->stream.conn.write_reqs_pending++;
+    REGISTER_HANDLE_REQ(loop, handle, req);
+    SET_REQ_ERROR(req, WSAGetLastError());
+    uv__insert_pending_req(loop, (uv_req_t*) req);
+  }
+
+  return 0;
+}
+
+
+int uv__tcp_try_write(uv_tcp_t* handle,
+                     const uv_buf_t bufs[],
+                     unsigned int nbufs) {
+  int result;
+  DWORD bytes;
+
+  if (handle->stream.conn.write_reqs_pending > 0)
+    return UV_EAGAIN;
+
+  result = WSASend(handle->socket,
+                   (WSABUF*) bufs,
+                   nbufs,
+                   &bytes,
+                   0,
+                   NULL,
+                   NULL);
+
+  if (result == SOCKET_ERROR)
+    return uv_translate_sys_error(WSAGetLastError());
+  else
+    return bytes;
+}
+
+
+void uv__process_tcp_read_req(uv_loop_t* loop, uv_tcp_t* handle,
+    uv_req_t* req) {
+  DWORD bytes, flags, err;
+  uv_buf_t buf;
+  int count;
+
+  assert(handle->type == UV_TCP);
+
+  handle->flags &= ~UV_HANDLE_READ_PENDING;
+
+  if (!REQ_SUCCESS(req)) {
+    /* An error occurred doing the read. */
+    if ((handle->flags & UV_HANDLE_READING) ||
+        !(handle->flags & UV_HANDLE_ZERO_READ)) {
+      handle->flags &= ~UV_HANDLE_READING;
+      DECREASE_ACTIVE_COUNT(loop, handle);
+      buf = (handle->flags & UV_HANDLE_ZERO_READ) ?
+            uv_buf_init(NULL, 0) : handle->tcp.conn.read_buffer;
+
+      err = GET_REQ_SOCK_ERROR(req);
+
+      if (err == WSAECONNABORTED) {
+        /* Turn WSAECONNABORTED into UV_ECONNRESET to be consistent with Unix.
+         */
+        err = WSAECONNRESET;
+      }
+      handle->flags &= ~(UV_HANDLE_READABLE | UV_HANDLE_WRITABLE);
+
+      handle->read_cb((uv_stream_t*)handle,
+                      uv_translate_sys_error(err),
+                      &buf);
+    }
+  } else {
+    if (!(handle->flags & UV_HANDLE_ZERO_READ)) {
+      /* The read was done with a non-zero buffer length. */
+      if (req->u.io.overlapped.InternalHigh > 0) {
+        /* Successful read */
+        handle->read_cb((uv_stream_t*)handle,
+                        req->u.io.overlapped.InternalHigh,
+                        &handle->tcp.conn.read_buffer);
+        /* Read again only if bytes == buf.len */
+        if (req->u.io.overlapped.InternalHigh < handle->tcp.conn.read_buffer.len) {
+          goto done;
+        }
+      } else {
+        /* Connection closed */
+        if (handle->flags & UV_HANDLE_READING) {
+          handle->flags &= ~UV_HANDLE_READING;
+          DECREASE_ACTIVE_COUNT(loop, handle);
+        }
+
+        buf.base = 0;
+        buf.len = 0;
+        handle->read_cb((uv_stream_t*)handle, UV_EOF, &handle->tcp.conn.read_buffer);
+        goto done;
+      }
+    }
+
+    /* Do nonblocking reads until the buffer is empty */
+    count = 32;
+    while ((handle->flags & UV_HANDLE_READING) && (count-- > 0)) {
+      buf = uv_buf_init(NULL, 0);
+      handle->alloc_cb((uv_handle_t*) handle, 65536, &buf);
+      if (buf.base == NULL || buf.len == 0) {
+        handle->read_cb((uv_stream_t*) handle, UV_ENOBUFS, &buf);
+        break;
+      }
+      assert(buf.base != NULL);
+
+      flags = 0;
+      if (WSARecv(handle->socket,
+                  (WSABUF*)&buf,
+                  1,
+                  &bytes,
+                  &flags,
+                  NULL,
+                  NULL) != SOCKET_ERROR) {
+        if (bytes > 0) {
+          /* Successful read */
+          handle->read_cb((uv_stream_t*)handle, bytes, &buf);
+          /* Read again only if bytes == buf.len */
+          if (bytes < buf.len) {
+            break;
+          }
+        } else {
+          /* Connection closed */
+          handle->flags &= ~UV_HANDLE_READING;
+          DECREASE_ACTIVE_COUNT(loop, handle);
+
+          handle->read_cb((uv_stream_t*)handle, UV_EOF, &buf);
+          break;
+        }
+      } else {
+        err = WSAGetLastError();
+        if (err == WSAEWOULDBLOCK) {
+          /* Read buffer was completely empty, report a 0-byte read. */
+          handle->read_cb((uv_stream_t*)handle, 0, &buf);
+        } else {
+          /* Ouch! serious error. */
+          handle->flags &= ~UV_HANDLE_READING;
+          DECREASE_ACTIVE_COUNT(loop, handle);
+
+          if (err == WSAECONNABORTED) {
+            /* Turn WSAECONNABORTED into UV_ECONNRESET to be consistent with
+             * Unix. */
+            err = WSAECONNRESET;
+          }
+          handle->flags &= ~(UV_HANDLE_READABLE | UV_HANDLE_WRITABLE);
+
+          handle->read_cb((uv_stream_t*)handle,
+                          uv_translate_sys_error(err),
+                          &buf);
+        }
+        break;
+      }
+    }
+
+done:
+    /* Post another read if still reading and not closing. */
+    if ((handle->flags & UV_HANDLE_READING) &&
+        !(handle->flags & UV_HANDLE_READ_PENDING)) {
+      uv__tcp_queue_read(loop, handle);
+    }
+  }
+
+  DECREASE_PENDING_REQ_COUNT(handle);
+}
+
+
+void uv__process_tcp_write_req(uv_loop_t* loop, uv_tcp_t* handle,
+    uv_write_t* req) {
+  int err;
+
+  assert(handle->type == UV_TCP);
+
+  assert(handle->write_queue_size >= req->u.io.queued_bytes);
+  handle->write_queue_size -= req->u.io.queued_bytes;
+
+  UNREGISTER_HANDLE_REQ(loop, handle, req);
+
+  if (handle->flags & UV_HANDLE_EMULATE_IOCP) {
+    if (req->wait_handle != INVALID_HANDLE_VALUE) {
+      UnregisterWait(req->wait_handle);
+      req->wait_handle = INVALID_HANDLE_VALUE;
+    }
+    if (req->event_handle != NULL) {
+      CloseHandle(req->event_handle);
+      req->event_handle = NULL;
+    }
+  }
+
+  if (req->cb) {
+    err = uv_translate_sys_error(GET_REQ_SOCK_ERROR(req));
+    if (err == UV_ECONNABORTED) {
+      /* use UV_ECANCELED for consistency with Unix */
+      err = UV_ECANCELED;
+    }
+    req->cb(req, err);
+  }
+
+  handle->stream.conn.write_reqs_pending--;
+  if (handle->stream.conn.write_reqs_pending == 0) {
+    if (handle->flags & UV_HANDLE_CLOSING) {
+      closesocket(handle->socket);
+      handle->socket = INVALID_SOCKET;
+    }
+    if (handle->flags & UV_HANDLE_SHUTTING)
+      uv__process_tcp_shutdown_req(loop,
+                                   handle,
+                                   handle->stream.conn.shutdown_req);
+  }
+
+  DECREASE_PENDING_REQ_COUNT(handle);
+}
+
+
+void uv__process_tcp_accept_req(uv_loop_t* loop, uv_tcp_t* handle,
+    uv_req_t* raw_req) {
+  uv_tcp_accept_t* req = (uv_tcp_accept_t*) raw_req;
+  int err;
+
+  assert(handle->type == UV_TCP);
+
+  /* If handle->accepted_socket is not a valid socket, then uv_queue_accept
+   * must have failed. This is a serious error. We stop accepting connections
+   * and report this error to the connection callback. */
+  if (req->accept_socket == INVALID_SOCKET) {
+    if (handle->flags & UV_HANDLE_LISTENING) {
+      handle->flags &= ~UV_HANDLE_LISTENING;
+      DECREASE_ACTIVE_COUNT(loop, handle);
+      if (handle->stream.serv.connection_cb) {
+        err = GET_REQ_SOCK_ERROR(req);
+        handle->stream.serv.connection_cb((uv_stream_t*)handle,
+                                      uv_translate_sys_error(err));
+      }
+    }
+  } else if (REQ_SUCCESS(req) &&
+      setsockopt(req->accept_socket,
+                  SOL_SOCKET,
+                  SO_UPDATE_ACCEPT_CONTEXT,
+                  (char*)&handle->socket,
+                  sizeof(handle->socket)) == 0) {
+    req->next_pending = handle->tcp.serv.pending_accepts;
+    handle->tcp.serv.pending_accepts = req;
+
+    /* Accept and SO_UPDATE_ACCEPT_CONTEXT were successful. */
+    if (handle->stream.serv.connection_cb) {
+      handle->stream.serv.connection_cb((uv_stream_t*)handle, 0);
+    }
+  } else {
+    /* Error related to accepted socket is ignored because the server socket
+     * may still be healthy. If the server socket is broken uv_queue_accept
+     * will detect it. */
+    closesocket(req->accept_socket);
+    req->accept_socket = INVALID_SOCKET;
+    if (handle->flags & UV_HANDLE_LISTENING) {
+      uv__tcp_queue_accept(handle, req);
+    }
+  }
+
+  DECREASE_PENDING_REQ_COUNT(handle);
+}
+
+
+void uv__process_tcp_connect_req(uv_loop_t* loop, uv_tcp_t* handle,
+    uv_connect_t* req) {
+  int err;
+
+  assert(handle->type == UV_TCP);
+
+  UNREGISTER_HANDLE_REQ(loop, handle, req);
+
+  err = 0;
+  if (handle->delayed_error) {
+    /* To smooth over the differences between unixes errors that
+     * were reported synchronously on the first connect can be delayed
+     * until the next tick--which is now.
+     */
+    err = handle->delayed_error;
+    handle->delayed_error = 0;
+  } else if (REQ_SUCCESS(req)) {
+    if (handle->flags & UV_HANDLE_CLOSING) {
+      /* use UV_ECANCELED for consistency with Unix */
+      err = ERROR_OPERATION_ABORTED;
+    } else if (setsockopt(handle->socket,
+                          SOL_SOCKET,
+                          SO_UPDATE_CONNECT_CONTEXT,
+                          NULL,
+                          0) == 0) {
+      uv__connection_init((uv_stream_t*)handle);
+      handle->flags |= UV_HANDLE_READABLE | UV_HANDLE_WRITABLE;
+      loop->active_tcp_streams++;
+    } else {
+      err = WSAGetLastError();
+    }
+  } else {
+    err = GET_REQ_SOCK_ERROR(req);
+  }
+  req->cb(req, uv_translate_sys_error(err));
+
+  DECREASE_PENDING_REQ_COUNT(handle);
+}
+
+
+int uv__tcp_xfer_export(uv_tcp_t* handle,
+                        int target_pid,
+                        uv__ipc_socket_xfer_type_t* xfer_type,
+                        uv__ipc_socket_xfer_info_t* xfer_info) {
+  if (handle->flags & UV_HANDLE_CONNECTION) {
+    *xfer_type = UV__IPC_SOCKET_XFER_TCP_CONNECTION;
+  } else {
+    *xfer_type = UV__IPC_SOCKET_XFER_TCP_SERVER;
+    /* We're about to share the socket with another process. Because this is a
+     * listening socket, we assume that the other process will be accepting
+     * connections on it. Thus, before sharing the socket with another process,
+     * we call listen here in the parent process. */
+    if (!(handle->flags & UV_HANDLE_LISTENING)) {
+      if (!(handle->flags & UV_HANDLE_BOUND)) {
+        return ERROR_NOT_SUPPORTED;
+      }
+      if (handle->delayed_error == 0 &&
+          listen(handle->socket, SOMAXCONN) == SOCKET_ERROR) {
+        handle->delayed_error = WSAGetLastError();
+      }
+    }
+  }
+
+  if (WSADuplicateSocketW(handle->socket, target_pid, &xfer_info->socket_info))
+    return WSAGetLastError();
+  xfer_info->delayed_error = handle->delayed_error;
+
+  /* Mark the local copy of the handle as 'shared' so we behave in a way that's
+   * friendly to the process(es) that we share the socket with. */
+  handle->flags |= UV_HANDLE_SHARED_TCP_SOCKET;
+
+  return 0;
+}
+
+
+int uv__tcp_xfer_import(uv_tcp_t* tcp,
+                        uv__ipc_socket_xfer_type_t xfer_type,
+                        uv__ipc_socket_xfer_info_t* xfer_info) {
+  int err;
+  SOCKET socket;
+
+  assert(xfer_type == UV__IPC_SOCKET_XFER_TCP_SERVER ||
+         xfer_type == UV__IPC_SOCKET_XFER_TCP_CONNECTION);
+
+  socket = WSASocketW(FROM_PROTOCOL_INFO,
+                      FROM_PROTOCOL_INFO,
+                      FROM_PROTOCOL_INFO,
+                      &xfer_info->socket_info,
+                      0,
+                      WSA_FLAG_OVERLAPPED);
+
+  if (socket == INVALID_SOCKET) {
+    return WSAGetLastError();
+  }
+
+  err = uv__tcp_set_socket(
+      tcp->loop, tcp, socket, xfer_info->socket_info.iAddressFamily, 1);
+  if (err) {
+    closesocket(socket);
+    return err;
+  }
+
+  tcp->delayed_error = xfer_info->delayed_error;
+  tcp->flags |= UV_HANDLE_BOUND | UV_HANDLE_SHARED_TCP_SOCKET;
+
+  if (xfer_type == UV__IPC_SOCKET_XFER_TCP_CONNECTION) {
+    uv__connection_init((uv_stream_t*)tcp);
+    tcp->flags |= UV_HANDLE_READABLE | UV_HANDLE_WRITABLE;
+  }
+
+  tcp->loop->active_tcp_streams++;
+  return 0;
+}
+
+
+int uv_tcp_nodelay(uv_tcp_t* handle, int enable) {
+  int err;
+
+  if (handle->socket != INVALID_SOCKET) {
+    err = uv__tcp_nodelay(handle, handle->socket, enable);
+    if (err)
+      return uv_translate_sys_error(err);
+  }
+
+  if (enable) {
+    handle->flags |= UV_HANDLE_TCP_NODELAY;
+  } else {
+    handle->flags &= ~UV_HANDLE_TCP_NODELAY;
+  }
+
+  return 0;
+}
+
+
+int uv_tcp_keepalive(uv_tcp_t* handle, int enable, unsigned int delay) {
+  int err;
+
+  if (handle->socket != INVALID_SOCKET) {
+    err = uv__tcp_keepalive(handle, handle->socket, enable, delay);
+    if (err)
+      return uv_translate_sys_error(err);
+  }
+
+  if (enable) {
+    handle->flags |= UV_HANDLE_TCP_KEEPALIVE;
+  } else {
+    handle->flags &= ~UV_HANDLE_TCP_KEEPALIVE;
+  }
+
+  /* TODO: Store delay if handle->socket isn't created yet. */
+
+  return 0;
+}
+
+
+int uv_tcp_simultaneous_accepts(uv_tcp_t* handle, int enable) {
+  if (handle->flags & UV_HANDLE_CONNECTION) {
+    return UV_EINVAL;
+  }
+
+  /* Check if we're already in the desired mode. */
+  if ((enable && !(handle->flags & UV_HANDLE_TCP_SINGLE_ACCEPT)) ||
+      (!enable && handle->flags & UV_HANDLE_TCP_SINGLE_ACCEPT)) {
+    return 0;
+  }
+
+  /* Don't allow switching from single pending accept to many. */
+  if (enable) {
+    return UV_ENOTSUP;
+  }
+
+  /* Check if we're in a middle of changing the number of pending accepts. */
+  if (handle->flags & UV_HANDLE_TCP_ACCEPT_STATE_CHANGING) {
+    return 0;
+  }
+
+  handle->flags |= UV_HANDLE_TCP_SINGLE_ACCEPT;
+
+  /* Flip the changing flag if we have already queued multiple accepts. */
+  if (handle->flags & UV_HANDLE_LISTENING) {
+    handle->flags |= UV_HANDLE_TCP_ACCEPT_STATE_CHANGING;
+  }
+
+  return 0;
+}
+
+
+static void uv__tcp_try_cancel_reqs(uv_tcp_t* tcp) {
+  SOCKET socket;
+  int non_ifs_lsp;
+  int reading;
+  int writing;
+
+  socket = tcp->socket;
+  reading = tcp->flags & UV_HANDLE_READ_PENDING;
+  writing = tcp->stream.conn.write_reqs_pending > 0;
+  if (!reading && !writing)
+    return;
+
+  /* TODO: in libuv v2, keep explicit track of write_reqs, so we can cancel
+   * them each explicitly with CancelIoEx (like unix). */
+  if (reading)
+    CancelIoEx((HANDLE) socket, &tcp->read_req.u.io.overlapped);
+  if (writing)
+    CancelIo((HANDLE) socket);
+
+  /* Check if we have any non-IFS LSPs stacked on top of TCP */
+  non_ifs_lsp = (tcp->flags & UV_HANDLE_IPV6) ? uv_tcp_non_ifs_lsp_ipv6 :
+                                                uv_tcp_non_ifs_lsp_ipv4;
+
+  /* If there are non-ifs LSPs then try to obtain a base handle for the socket.
+   * This will always fail on Windows XP/3k. */
+  if (non_ifs_lsp) {
+    DWORD bytes;
+    if (WSAIoctl(socket,
+                 SIO_BASE_HANDLE,
+                 NULL,
+                 0,
+                 &socket,
+                 sizeof socket,
+                 &bytes,
+                 NULL,
+                 NULL) != 0) {
+      /* Failed. We can't do CancelIo. */
+      return;
+    }
+  }
+
+  assert(socket != 0 && socket != INVALID_SOCKET);
+
+  if (socket != tcp->socket) {
+    if (reading)
+      CancelIoEx((HANDLE) socket, &tcp->read_req.u.io.overlapped);
+    if (writing)
+      CancelIo((HANDLE) socket);
+  }
+}
+
+
+void uv__tcp_close(uv_loop_t* loop, uv_tcp_t* tcp) {
+  if (tcp->flags & UV_HANDLE_CONNECTION) {
+    if (tcp->flags & UV_HANDLE_READING) {
+      uv_read_stop((uv_stream_t*) tcp);
+    }
+    uv__tcp_try_cancel_reqs(tcp);
+  } else {
+    if (tcp->tcp.serv.accept_reqs != NULL) {
+      /* First close the incoming sockets to cancel the accept operations before
+       * we free their resources. */
+      unsigned int i;
+      for (i = 0; i < uv_simultaneous_server_accepts; i++) {
+        uv_tcp_accept_t* req = &tcp->tcp.serv.accept_reqs[i];
+        if (req->accept_socket != INVALID_SOCKET) {
+          closesocket(req->accept_socket);
+          req->accept_socket = INVALID_SOCKET;
+        }
+      }
+    }
+    assert(!(tcp->flags & UV_HANDLE_READING));
+  }
+
+  if (tcp->flags & UV_HANDLE_LISTENING) {
+    tcp->flags &= ~UV_HANDLE_LISTENING;
+    DECREASE_ACTIVE_COUNT(loop, tcp);
+  }
+
+  tcp->flags &= ~(UV_HANDLE_READABLE | UV_HANDLE_WRITABLE);
+  uv__handle_closing(tcp);
+
+  /* If any overlapped req failed to cancel, calling `closesocket` now would
+   * cause Win32 to send an RST packet. Try to avoid that for writes, if
+   * possibly applicable, by waiting to process the completion notifications
+   * first (which typically should be cancellations). There's not much we can
+   * do about canceled reads, which also will generate an RST packet. */
+  if (!(tcp->flags & UV_HANDLE_CONNECTION) ||
+      tcp->stream.conn.write_reqs_pending == 0) {
+    closesocket(tcp->socket);
+    tcp->socket = INVALID_SOCKET;
+  }
+
+  if (tcp->reqs_pending == 0)
+    uv__want_endgame(loop, (uv_handle_t*) tcp);
+}
+
+
+int uv_tcp_open(uv_tcp_t* handle, uv_os_sock_t sock) {
+  WSAPROTOCOL_INFOW protocol_info;
+  int opt_len;
+  int err;
+  struct sockaddr_storage saddr;
+  int saddr_len;
+
+  /* Detect the address family of the socket. */
+  opt_len = (int) sizeof protocol_info;
+  if (getsockopt(sock,
+                 SOL_SOCKET,
+                 SO_PROTOCOL_INFOW,
+                 (char*) &protocol_info,
+                 &opt_len) == SOCKET_ERROR) {
+    return uv_translate_sys_error(GetLastError());
+  }
+
+  err = uv__tcp_set_socket(handle->loop,
+                          handle,
+                          sock,
+                          protocol_info.iAddressFamily,
+                          1);
+  if (err) {
+    return uv_translate_sys_error(err);
+  }
+
+  /* Support already active socket. */
+  saddr_len = sizeof(saddr);
+  if (!uv_tcp_getsockname(handle, (struct sockaddr*) &saddr, &saddr_len)) {
+    /* Socket is already bound. */
+    handle->flags |= UV_HANDLE_BOUND;
+    saddr_len = sizeof(saddr);
+    if (!uv_tcp_getpeername(handle, (struct sockaddr*) &saddr, &saddr_len)) {
+      /* Socket is already connected. */
+      uv__connection_init((uv_stream_t*) handle);
+      handle->flags |= UV_HANDLE_READABLE | UV_HANDLE_WRITABLE;
+    }
+  }
+
+  return 0;
+}
+
+
+/* This function is an egress point, i.e. it returns libuv errors rather than
+ * system errors.
+ */
+int uv__tcp_bind(uv_tcp_t* handle,
+                 const struct sockaddr* addr,
+                 unsigned int addrlen,
+                 unsigned int flags) {
+  int err;
+
+  err = uv__tcp_try_bind(handle, addr, addrlen, flags);
+  if (err)
+    return uv_translate_sys_error(err);
+
+  return 0;
+}
+
+
+/* This function is an egress point, i.e. it returns libuv errors rather than
+ * system errors.
+ */
+int uv__tcp_connect(uv_connect_t* req,
+                    uv_tcp_t* handle,
+                    const struct sockaddr* addr,
+                    unsigned int addrlen,
+                    uv_connect_cb cb) {
+  int err;
+
+  err = uv__tcp_try_connect(req, handle, addr, addrlen, cb);
+  if (err)
+    return uv_translate_sys_error(err);
+
+  return 0;
+}
+
+#ifndef WSA_FLAG_NO_HANDLE_INHERIT
+/* Added in Windows 7 SP1. Specify this to avoid race conditions, */
+/* but also manually clear the inherit flag in case this failed. */
+#define WSA_FLAG_NO_HANDLE_INHERIT 0x80
+#endif
+
+int uv_socketpair(int type, int protocol, uv_os_sock_t fds[2], int flags0, int flags1) {
+  SOCKET server = INVALID_SOCKET;
+  SOCKET client0 = INVALID_SOCKET;
+  SOCKET client1 = INVALID_SOCKET;
+  SOCKADDR_IN name;
+  LPFN_ACCEPTEX func_acceptex;
+  WSAOVERLAPPED overlap;
+  char accept_buffer[sizeof(struct sockaddr_storage) * 2 + 32];
+  int namelen;
+  int err;
+  DWORD bytes;
+  DWORD flags;
+  DWORD client0_flags = WSA_FLAG_NO_HANDLE_INHERIT;
+  DWORD client1_flags = WSA_FLAG_NO_HANDLE_INHERIT;
+
+  if (flags0 & UV_NONBLOCK_PIPE)
+      client0_flags |= WSA_FLAG_OVERLAPPED;
+  if (flags1 & UV_NONBLOCK_PIPE)
+      client1_flags |= WSA_FLAG_OVERLAPPED;
+
+  server = WSASocketW(AF_INET, type, protocol, NULL, 0,
+                      WSA_FLAG_OVERLAPPED | WSA_FLAG_NO_HANDLE_INHERIT);
+  if (server == INVALID_SOCKET)
+    goto wsaerror;
+  if (!SetHandleInformation((HANDLE) server, HANDLE_FLAG_INHERIT, 0))
+    goto error;
+  name.sin_family = AF_INET;
+  name.sin_addr.s_addr = htonl(INADDR_LOOPBACK);
+  name.sin_port = 0;
+  if (bind(server, (SOCKADDR*) &name, sizeof(name)) != 0)
+    goto wsaerror;
+  if (listen(server, 1) != 0)
+    goto wsaerror;
+  namelen = sizeof(name);
+  if (getsockname(server, (SOCKADDR*) &name, &namelen) != 0)
+    goto wsaerror;
+  client0 = WSASocketW(AF_INET, type, protocol, NULL, 0, client0_flags);
+  if (client0 == INVALID_SOCKET)
+    goto wsaerror;
+  if (!SetHandleInformation((HANDLE) client0, HANDLE_FLAG_INHERIT, 0))
+    goto error;
+  if (connect(client0, (SOCKADDR*) &name, sizeof(name)) != 0)
+    goto wsaerror;
+  client1 = WSASocketW(AF_INET, type, protocol, NULL, 0, client1_flags);
+  if (client1 == INVALID_SOCKET)
+    goto wsaerror;
+  if (!SetHandleInformation((HANDLE) client1, HANDLE_FLAG_INHERIT, 0))
+    goto error;
+  if (!uv__get_acceptex_function(server, &func_acceptex)) {
+    err = WSAEAFNOSUPPORT;
+    goto cleanup;
+  }
+  memset(&overlap, 0, sizeof(overlap));
+  if (!func_acceptex(server,
+                     client1,
+                     accept_buffer,
+                     0,
+                     sizeof(struct sockaddr_storage),
+                     sizeof(struct sockaddr_storage),
+                     &bytes,
+                     &overlap)) {
+    err = WSAGetLastError();
+    if (err == ERROR_IO_PENDING) {
+      /* Result should complete immediately, since we already called connect,
+       * but empirically, we sometimes have to poll the kernel a couple times
+       * until it notices that. */
+      while (!WSAGetOverlappedResult(client1, &overlap, &bytes, FALSE, &flags)) {
+        err = WSAGetLastError();
+        if (err != WSA_IO_INCOMPLETE)
+          goto cleanup;
+        SwitchToThread();
+      }
+    }
+    else {
+      goto cleanup;
+    }
+  }
+  if (setsockopt(client1, SOL_SOCKET, SO_UPDATE_ACCEPT_CONTEXT,
+                  (char*) &server, sizeof(server)) != 0) {
+    goto wsaerror;
+  }
+
+  closesocket(server);
+
+  fds[0] = client0;
+  fds[1] = client1;
+
+  return 0;
+
+ wsaerror:
+    err = WSAGetLastError();
+    goto cleanup;
+
+ error:
+    err = GetLastError();
+    goto cleanup;
+
+ cleanup:
+    if (server != INVALID_SOCKET)
+      closesocket(server);
+    if (client0 != INVALID_SOCKET)
+      closesocket(client0);
+    if (client1 != INVALID_SOCKET)
+      closesocket(client1);
+
+    assert(err);
+    return uv_translate_sys_error(err);
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/thread.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/thread.cpp
new file mode 100644
index 0000000..9ad60c9
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/thread.cpp
@@ -0,0 +1,479 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <assert.h>
+#include <limits.h>
+#include <stdlib.h>
+
+#if defined(__MINGW64_VERSION_MAJOR)
+/* MemoryBarrier expands to __mm_mfence in some cases (x86+sse2), which may
+ * require this header in some versions of mingw64. */
+#include <intrin.h>
+#endif
+
+#include "uv.h"
+#include "internal.h"
+
+static void uv__once_inner(uv_once_t* guard, void (*callback)(void)) {
+  DWORD result;
+  HANDLE existing_event, created_event;
+
+  created_event = CreateEvent(NULL, 1, 0, NULL);
+  if (created_event == 0) {
+    /* Could fail in a low-memory situation? */
+    uv_fatal_error(GetLastError(), "CreateEvent");
+  }
+
+  existing_event = InterlockedCompareExchangePointer(&guard->event,
+                                                     created_event,
+                                                     NULL);
+
+  if (existing_event == NULL) {
+    /* We won the race */
+    callback();
+
+    result = SetEvent(created_event);
+    assert(result);
+    guard->ran = 1;
+
+  } else {
+    /* We lost the race. Destroy the event we created and wait for the existing
+     * one to become signaled. */
+    CloseHandle(created_event);
+    result = WaitForSingleObject(existing_event, INFINITE);
+    assert(result == WAIT_OBJECT_0);
+  }
+}
+
+
+void uv_once(uv_once_t* guard, void (*callback)(void)) {
+  /* Fast case - avoid WaitForSingleObject. */
+  if (guard->ran) {
+    return;
+  }
+
+  uv__once_inner(guard, callback);
+}
+
+
+/* Verify that uv_thread_t can be stored in a TLS slot. */
+STATIC_ASSERT(sizeof(uv_thread_t) <= sizeof(void*));
+
+static uv_key_t uv__current_thread_key;
+static uv_once_t uv__current_thread_init_guard = UV_ONCE_INIT;
+
+
+static void uv__init_current_thread_key(void) {
+  if (uv_key_create(&uv__current_thread_key))
+    abort();
+}
+
+
+struct thread_ctx {
+  void (*entry)(void* arg);
+  void* arg;
+  uv_thread_t self;
+};
+
+
+static UINT __stdcall uv__thread_start(void* arg) {
+  struct thread_ctx *ctx_p;
+  struct thread_ctx ctx;
+
+  ctx_p = (struct thread_ctx*)arg;
+  ctx = *ctx_p;
+  uv__free(ctx_p);
+
+  uv_once(&uv__current_thread_init_guard, uv__init_current_thread_key);
+  uv_key_set(&uv__current_thread_key, ctx.self);
+
+  ctx.entry(ctx.arg);
+
+  return 0;
+}
+
+
+int uv_thread_create(uv_thread_t *tid, void (*entry)(void *arg), void *arg) {
+  uv_thread_options_t params;
+  params.flags = UV_THREAD_NO_FLAGS;
+  return uv_thread_create_ex(tid, &params, entry, arg);
+}
+
+int uv_thread_create_ex(uv_thread_t* tid,
+                        const uv_thread_options_t* params,
+                        void (*entry)(void *arg),
+                        void *arg) {
+  struct thread_ctx* ctx;
+  int err;
+  HANDLE thread;
+  SYSTEM_INFO sysinfo;
+  size_t stack_size;
+  size_t pagesize;
+
+  stack_size =
+      params->flags & UV_THREAD_HAS_STACK_SIZE ? params->stack_size : 0;
+
+  if (stack_size != 0) {
+    GetNativeSystemInfo(&sysinfo);
+    pagesize = (size_t)sysinfo.dwPageSize;
+    /* Round up to the nearest page boundary. */
+    stack_size = (stack_size + pagesize - 1) &~ (pagesize - 1);
+
+    if ((unsigned)stack_size != stack_size)
+      return UV_EINVAL;
+  }
+
+  ctx = (struct thread_ctx*)uv__malloc(sizeof(*ctx));
+  if (ctx == NULL)
+    return UV_ENOMEM;
+
+  ctx->entry = entry;
+  ctx->arg = arg;
+
+  /* Create the thread in suspended state so we have a chance to pass
+   * its own creation handle to it */
+  thread = (HANDLE) _beginthreadex(NULL,
+                                   (unsigned)stack_size,
+                                   uv__thread_start,
+                                   ctx,
+                                   CREATE_SUSPENDED,
+                                   NULL);
+  if (thread == NULL) {
+    err = errno;
+    uv__free(ctx);
+  } else {
+    err = 0;
+    *tid = thread;
+    ctx->self = thread;
+    ResumeThread(thread);
+  }
+
+  switch (err) {
+    case 0:
+      return 0;
+    case EACCES:
+      return UV_EACCES;
+    case EAGAIN:
+      return UV_EAGAIN;
+    case EINVAL:
+      return UV_EINVAL;
+  }
+
+  return UV_EIO;
+}
+
+
+uv_thread_t uv_thread_self(void) {
+  uv_thread_t key;
+  uv_once(&uv__current_thread_init_guard, uv__init_current_thread_key);
+  key = uv_key_get(&uv__current_thread_key);
+  if (key == NULL) {
+      /* If the thread wasn't started by uv_thread_create (such as the main
+       * thread), we assign an id to it now. */
+      if (!DuplicateHandle(GetCurrentProcess(), GetCurrentThread(),
+                           GetCurrentProcess(), &key, 0,
+                           FALSE, DUPLICATE_SAME_ACCESS)) {
+          uv_fatal_error(GetLastError(), "DuplicateHandle");
+      }
+      uv_key_set(&uv__current_thread_key, key);
+  }
+  return key;
+}
+
+
+int uv_thread_join(uv_thread_t *tid) {
+  if (WaitForSingleObject(*tid, INFINITE))
+    return uv_translate_sys_error(GetLastError());
+  else {
+    CloseHandle(*tid);
+    *tid = 0;
+    MemoryBarrier();  /* For feature parity with pthread_join(). */
+    return 0;
+  }
+}
+
+
+int uv_thread_equal(const uv_thread_t* t1, const uv_thread_t* t2) {
+  return *t1 == *t2;
+}
+
+
+int uv_mutex_init(uv_mutex_t* mutex) {
+  InitializeCriticalSection(mutex);
+  return 0;
+}
+
+
+int uv_mutex_init_recursive(uv_mutex_t* mutex) {
+  return uv_mutex_init(mutex);
+}
+
+
+void uv_mutex_destroy(uv_mutex_t* mutex) {
+  DeleteCriticalSection(mutex);
+}
+
+
+void uv_mutex_lock(uv_mutex_t* mutex) {
+  EnterCriticalSection(mutex);
+}
+
+
+int uv_mutex_trylock(uv_mutex_t* mutex) {
+  if (TryEnterCriticalSection(mutex))
+    return 0;
+  else
+    return UV_EBUSY;
+}
+
+
+void uv_mutex_unlock(uv_mutex_t* mutex) {
+  LeaveCriticalSection(mutex);
+}
+
+/* Ensure that the ABI for this type remains stable in v1.x */
+#ifdef _WIN64
+STATIC_ASSERT(sizeof(uv_rwlock_t) == 80);
+#else
+STATIC_ASSERT(sizeof(uv_rwlock_t) == 48);
+#endif
+
+int uv_rwlock_init(uv_rwlock_t* rwlock) {
+  memset(rwlock, 0, sizeof(*rwlock));
+  InitializeSRWLock(&rwlock->read_write_lock_);
+
+  return 0;
+}
+
+
+void uv_rwlock_destroy(uv_rwlock_t* rwlock) {
+  /* SRWLock does not need explicit destruction so long as there are no waiting threads
+     See: https://docs.microsoft.com/windows/win32/api/synchapi/nf-synchapi-initializesrwlock#remarks */
+}
+
+
+void uv_rwlock_rdlock(uv_rwlock_t* rwlock) {
+  AcquireSRWLockShared(&rwlock->read_write_lock_);
+}
+
+
+int uv_rwlock_tryrdlock(uv_rwlock_t* rwlock) {
+  if (!TryAcquireSRWLockShared(&rwlock->read_write_lock_))
+    return UV_EBUSY;
+
+  return 0;
+}
+
+
+void uv_rwlock_rdunlock(uv_rwlock_t* rwlock) {
+  ReleaseSRWLockShared(&rwlock->read_write_lock_);
+}
+
+
+void uv_rwlock_wrlock(uv_rwlock_t* rwlock) {
+  AcquireSRWLockExclusive(&rwlock->read_write_lock_);
+}
+
+
+int uv_rwlock_trywrlock(uv_rwlock_t* rwlock) {
+  if (!TryAcquireSRWLockExclusive(&rwlock->read_write_lock_))
+    return UV_EBUSY;
+
+  return 0;
+}
+
+
+void uv_rwlock_wrunlock(uv_rwlock_t* rwlock) {
+  ReleaseSRWLockExclusive(&rwlock->read_write_lock_);
+}
+
+
+int uv_sem_init(uv_sem_t* sem, unsigned int value) {
+  *sem = CreateSemaphore(NULL, value, INT_MAX, NULL);
+  if (*sem == NULL)
+    return uv_translate_sys_error(GetLastError());
+  else
+    return 0;
+}
+
+
+void uv_sem_destroy(uv_sem_t* sem) {
+  if (!CloseHandle(*sem))
+    abort();
+}
+
+
+void uv_sem_post(uv_sem_t* sem) {
+  if (!ReleaseSemaphore(*sem, 1, NULL))
+    abort();
+}
+
+
+void uv_sem_wait(uv_sem_t* sem) {
+  if (WaitForSingleObject(*sem, INFINITE) != WAIT_OBJECT_0)
+    abort();
+}
+
+
+int uv_sem_trywait(uv_sem_t* sem) {
+  DWORD r = WaitForSingleObject(*sem, 0);
+
+  if (r == WAIT_OBJECT_0)
+    return 0;
+
+  if (r == WAIT_TIMEOUT)
+    return UV_EAGAIN;
+
+  abort();
+  return -1; /* Satisfy the compiler. */
+}
+
+
+int uv_cond_init(uv_cond_t* cond) {
+  InitializeConditionVariable(&cond->cond_var);
+  return 0;
+}
+
+
+void uv_cond_destroy(uv_cond_t* cond) {
+  /* nothing to do */
+  (void) &cond;
+}
+
+
+void uv_cond_signal(uv_cond_t* cond) {
+  WakeConditionVariable(&cond->cond_var);
+}
+
+
+void uv_cond_broadcast(uv_cond_t* cond) {
+  WakeAllConditionVariable(&cond->cond_var);
+}
+
+
+void uv_cond_wait(uv_cond_t* cond, uv_mutex_t* mutex) {
+  if (!SleepConditionVariableCS(&cond->cond_var, mutex, INFINITE))
+    abort();
+}
+
+int uv_cond_timedwait(uv_cond_t* cond, uv_mutex_t* mutex, uint64_t timeout) {
+  if (SleepConditionVariableCS(&cond->cond_var, mutex, (DWORD)(timeout / 1e6)))
+    return 0;
+  if (GetLastError() != ERROR_TIMEOUT)
+    abort();
+  return UV_ETIMEDOUT;
+}
+
+
+int uv_barrier_init(uv_barrier_t* barrier, unsigned int count) {
+  int err;
+
+  barrier->n = count;
+  barrier->count = 0;
+
+  err = uv_mutex_init(&barrier->mutex);
+  if (err)
+    return err;
+
+  err = uv_sem_init(&barrier->turnstile1, 0);
+  if (err)
+    goto error2;
+
+  err = uv_sem_init(&barrier->turnstile2, 1);
+  if (err)
+    goto error;
+
+  return 0;
+
+error:
+  uv_sem_destroy(&barrier->turnstile1);
+error2:
+  uv_mutex_destroy(&barrier->mutex);
+  return err;
+
+}
+
+
+void uv_barrier_destroy(uv_barrier_t* barrier) {
+  uv_sem_destroy(&barrier->turnstile2);
+  uv_sem_destroy(&barrier->turnstile1);
+  uv_mutex_destroy(&barrier->mutex);
+}
+
+
+int uv_barrier_wait(uv_barrier_t* barrier) {
+  int serial_thread;
+
+  uv_mutex_lock(&barrier->mutex);
+  if (++barrier->count == barrier->n) {
+    uv_sem_wait(&barrier->turnstile2);
+    uv_sem_post(&barrier->turnstile1);
+  }
+  uv_mutex_unlock(&barrier->mutex);
+
+  uv_sem_wait(&barrier->turnstile1);
+  uv_sem_post(&barrier->turnstile1);
+
+  uv_mutex_lock(&barrier->mutex);
+  serial_thread = (--barrier->count == 0);
+  if (serial_thread) {
+    uv_sem_wait(&barrier->turnstile1);
+    uv_sem_post(&barrier->turnstile2);
+  }
+  uv_mutex_unlock(&barrier->mutex);
+
+  uv_sem_wait(&barrier->turnstile2);
+  uv_sem_post(&barrier->turnstile2);
+  return serial_thread;
+}
+
+
+int uv_key_create(uv_key_t* key) {
+  key->tls_index = TlsAlloc();
+  if (key->tls_index == TLS_OUT_OF_INDEXES)
+    return UV_ENOMEM;
+  return 0;
+}
+
+
+void uv_key_delete(uv_key_t* key) {
+  if (TlsFree(key->tls_index) == FALSE)
+    abort();
+  key->tls_index = TLS_OUT_OF_INDEXES;
+}
+
+
+void* uv_key_get(uv_key_t* key) {
+  void* value;
+
+  value = TlsGetValue(key->tls_index);
+  if (value == NULL)
+    if (GetLastError() != ERROR_SUCCESS)
+      abort();
+
+  return value;
+}
+
+
+void uv_key_set(uv_key_t* key, void* value) {
+  if (TlsSetValue(key->tls_index, value) == FALSE)
+    abort();
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/tty.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/tty.cpp
new file mode 100644
index 0000000..9753784
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/tty.cpp
@@ -0,0 +1,2459 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#define _CRT_NONSTDC_NO_WARNINGS
+
+#include <assert.h>
+#include <io.h>
+#include <string.h>
+#include <stdlib.h>
+
+#if defined(_MSC_VER) && _MSC_VER < 1600
+# include "uv/stdint-msvc2008.h"
+#else
+# include <stdint.h>
+#endif
+
+#ifndef COMMON_LVB_REVERSE_VIDEO
+# define COMMON_LVB_REVERSE_VIDEO 0x4000
+#endif
+
+#include "uv.h"
+#include "internal.h"
+#include "handle-inl.h"
+#include "stream-inl.h"
+#include "req-inl.h"
+
+#pragma comment(lib, "User32.lib")
+
+#ifndef InterlockedOr
+# define InterlockedOr _InterlockedOr
+#endif
+
+#define UNICODE_REPLACEMENT_CHARACTER (0xfffd)
+
+#define ANSI_NORMAL           0x0000
+#define ANSI_ESCAPE_SEEN      0x0002
+#define ANSI_CSI              0x0004
+#define ANSI_ST_CONTROL       0x0008
+#define ANSI_IGNORE           0x0010
+#define ANSI_IN_ARG           0x0020
+#define ANSI_IN_STRING        0x0040
+#define ANSI_BACKSLASH_SEEN   0x0080
+#define ANSI_EXTENSION        0x0100
+#define ANSI_DECSCUSR         0x0200
+
+#define MAX_INPUT_BUFFER_LENGTH 8192
+#define MAX_CONSOLE_CHAR 8192
+
+#ifndef ENABLE_VIRTUAL_TERMINAL_PROCESSING
+#define ENABLE_VIRTUAL_TERMINAL_PROCESSING 0x0004
+#endif
+
+#define CURSOR_SIZE_SMALL     25
+#define CURSOR_SIZE_LARGE     100
+
+static void uv__tty_capture_initial_style(
+    CONSOLE_SCREEN_BUFFER_INFO* screen_buffer_info,
+    CONSOLE_CURSOR_INFO* cursor_info);
+static void uv__tty_update_virtual_window(CONSOLE_SCREEN_BUFFER_INFO* info);
+static int uv__cancel_read_console(uv_tty_t* handle);
+
+
+/* Null uv_buf_t */
+static const uv_buf_t uv_null_buf_ = { 0, NULL };
+
+enum uv__read_console_status_e {
+  NOT_STARTED,
+  IN_PROGRESS,
+  TRAP_REQUESTED,
+  COMPLETED
+};
+
+static volatile LONG uv__read_console_status = NOT_STARTED;
+static volatile LONG uv__restore_screen_state;
+static CONSOLE_SCREEN_BUFFER_INFO uv__saved_screen_state;
+
+
+/*
+ * The console virtual window.
+ *
+ * Normally cursor movement in windows is relative to the console screen buffer,
+ * e.g. the application is allowed to overwrite the 'history'. This is very
+ * inconvenient, it makes absolute cursor movement pretty useless. There is
+ * also the concept of 'client rect' which is defined by the actual size of
+ * the console window and the scroll position of the screen buffer, but it's
+ * very volatile because it changes when the user scrolls.
+ *
+ * To make cursor movement behave sensibly we define a virtual window to which
+ * cursor movement is confined. The virtual window is always as wide as the
+ * console screen buffer, but it's height is defined by the size of the
+ * console window. The top of the virtual window aligns with the position
+ * of the caret when the first stdout/err handle is created, unless that would
+ * mean that it would extend beyond the bottom of the screen buffer -  in that
+ * that case it's located as far down as possible.
+ *
+ * When the user writes a long text or many newlines, such that the output
+ * reaches beyond the bottom of the virtual window, the virtual window is
+ * shifted downwards, but not resized.
+ *
+ * Since all tty i/o happens on the same console, this window is shared
+ * between all stdout/stderr handles.
+ */
+
+static int uv_tty_virtual_offset = -1;
+static int uv_tty_virtual_height = -1;
+static int uv_tty_virtual_width = -1;
+
+/* The console window size
+ * We keep this separate from uv_tty_virtual_*. We use those values to only
+ * handle signalling SIGWINCH
+ */
+
+static HANDLE uv__tty_console_handle = INVALID_HANDLE_VALUE;
+static int uv__tty_console_height = -1;
+static int uv__tty_console_width = -1;
+static HANDLE uv__tty_console_resized = INVALID_HANDLE_VALUE;
+static uv_mutex_t uv__tty_console_resize_mutex;
+
+static DWORD WINAPI uv__tty_console_resize_message_loop_thread(void* param);
+static void CALLBACK uv__tty_console_resize_event(HWINEVENTHOOK hWinEventHook,
+                                                  DWORD event,
+                                                  HWND hwnd,
+                                                  LONG idObject,
+                                                  LONG idChild,
+                                                  DWORD dwEventThread,
+                                                  DWORD dwmsEventTime);
+static DWORD WINAPI uv__tty_console_resize_watcher_thread(void* param);
+static void uv__tty_console_signal_resize(void);
+
+/* We use a semaphore rather than a mutex or critical section because in some
+   cases (uv__cancel_read_console) we need take the lock in the main thread and
+   release it in another thread. Using a semaphore ensures that in such
+   scenario the main thread will still block when trying to acquire the lock. */
+static uv_sem_t uv_tty_output_lock;
+
+static WORD uv_tty_default_text_attributes =
+    FOREGROUND_RED | FOREGROUND_GREEN | FOREGROUND_BLUE;
+
+static char uv_tty_default_fg_color = 7;
+static char uv_tty_default_bg_color = 0;
+static char uv_tty_default_fg_bright = 0;
+static char uv_tty_default_bg_bright = 0;
+static char uv_tty_default_inverse = 0;
+
+static CONSOLE_CURSOR_INFO uv_tty_default_cursor_info;
+
+/* Determine whether or not ANSI support is enabled. */
+static BOOL uv__need_check_vterm_state = TRUE;
+static uv_tty_vtermstate_t uv__vterm_state = UV_TTY_UNSUPPORTED;
+static void uv__determine_vterm_state(HANDLE handle);
+
+void uv__console_init(void) {
+  if (uv_sem_init(&uv_tty_output_lock, 1))
+    abort();
+  uv__tty_console_handle = CreateFileW(L"CONOUT$",
+                                       GENERIC_READ | GENERIC_WRITE,
+                                       FILE_SHARE_WRITE,
+                                       0,
+                                       OPEN_EXISTING,
+                                       0,
+                                       0);
+  if (uv__tty_console_handle != INVALID_HANDLE_VALUE) {
+    CONSOLE_SCREEN_BUFFER_INFO sb_info;
+    QueueUserWorkItem(uv__tty_console_resize_message_loop_thread,
+                      NULL,
+                      WT_EXECUTELONGFUNCTION);
+    uv_mutex_init(&uv__tty_console_resize_mutex);
+    if (GetConsoleScreenBufferInfo(uv__tty_console_handle, &sb_info)) {
+      uv__tty_console_width = sb_info.dwSize.X;
+      uv__tty_console_height = sb_info.srWindow.Bottom - sb_info.srWindow.Top + 1;
+    }
+  }
+}
+
+
+int uv_tty_init(uv_loop_t* loop, uv_tty_t* tty, uv_file fd, int unused) {
+  BOOL readable;
+  DWORD NumberOfEvents;
+  HANDLE handle;
+  CONSOLE_SCREEN_BUFFER_INFO screen_buffer_info;
+  CONSOLE_CURSOR_INFO cursor_info;
+  (void)unused;
+
+  uv__once_init();
+  handle = (HANDLE) uv__get_osfhandle(fd);
+  if (handle == INVALID_HANDLE_VALUE)
+    return UV_EBADF;
+
+  if (fd <= 2) {
+    /* In order to avoid closing a stdio file descriptor 0-2, duplicate the
+     * underlying OS handle and forget about the original fd.
+     * We could also opt to use the original OS handle and just never close it,
+     * but then there would be no reliable way to cancel pending read operations
+     * upon close.
+     */
+    if (!DuplicateHandle(INVALID_HANDLE_VALUE,
+                         handle,
+                         INVALID_HANDLE_VALUE,
+                         &handle,
+                         0,
+                         FALSE,
+                         DUPLICATE_SAME_ACCESS))
+      return uv_translate_sys_error(GetLastError());
+    fd = -1;
+  }
+
+  readable = GetNumberOfConsoleInputEvents(handle, &NumberOfEvents);
+  if (!readable) {
+    /* Obtain the screen buffer info with the output handle. */
+    if (!GetConsoleScreenBufferInfo(handle, &screen_buffer_info)) {
+      return uv_translate_sys_error(GetLastError());
+    }
+
+    /* Obtain the cursor info with the output handle. */
+    if (!GetConsoleCursorInfo(handle, &cursor_info)) {
+      return uv_translate_sys_error(GetLastError());
+    }
+
+    /* Obtain the tty_output_lock because the virtual window state is shared
+     * between all uv_tty_t handles. */
+    uv_sem_wait(&uv_tty_output_lock);
+
+    if (uv__need_check_vterm_state)
+      uv__determine_vterm_state(handle);
+
+    /* Remember the original console text attributes and cursor info. */
+    uv__tty_capture_initial_style(&screen_buffer_info, &cursor_info);
+
+    uv__tty_update_virtual_window(&screen_buffer_info);
+
+    uv_sem_post(&uv_tty_output_lock);
+  }
+
+
+  uv__stream_init(loop, (uv_stream_t*) tty, UV_TTY);
+  uv__connection_init((uv_stream_t*) tty);
+
+  tty->handle = handle;
+  tty->u.fd = fd;
+  tty->reqs_pending = 0;
+  tty->flags |= UV_HANDLE_BOUND;
+
+  if (readable) {
+    /* Initialize TTY input specific fields. */
+    tty->flags |= UV_HANDLE_TTY_READABLE | UV_HANDLE_READABLE;
+    /* TODO: remove me in v2.x. */
+    tty->tty.rd.unused_ = NULL;
+    tty->tty.rd.read_line_buffer = uv_null_buf_;
+    tty->tty.rd.read_raw_wait = NULL;
+
+    /* Init keycode-to-vt100 mapper state. */
+    tty->tty.rd.last_key_len = 0;
+    tty->tty.rd.last_key_offset = 0;
+    tty->tty.rd.last_utf16_high_surrogate = 0;
+    memset(&tty->tty.rd.last_input_record, 0, sizeof tty->tty.rd.last_input_record);
+  } else {
+    /* TTY output specific fields. */
+    tty->flags |= UV_HANDLE_WRITABLE;
+
+    /* Init utf8-to-utf16 conversion state. */
+    tty->tty.wr.utf8_bytes_left = 0;
+    tty->tty.wr.utf8_codepoint = 0;
+
+    /* Initialize eol conversion state */
+    tty->tty.wr.previous_eol = 0;
+
+    /* Init ANSI parser state. */
+    tty->tty.wr.ansi_parser_state = ANSI_NORMAL;
+  }
+
+  return 0;
+}
+
+
+/* Set the default console text attributes based on how the console was
+ * configured when libuv started.
+ */
+static void uv__tty_capture_initial_style(
+    CONSOLE_SCREEN_BUFFER_INFO* screen_buffer_info,
+    CONSOLE_CURSOR_INFO* cursor_info) {
+  static int style_captured = 0;
+
+  /* Only do this once.
+     Assumption: Caller has acquired uv_tty_output_lock. */
+  if (style_captured)
+    return;
+
+  /* Save raw win32 attributes. */
+  uv_tty_default_text_attributes = screen_buffer_info->wAttributes;
+
+  /* Convert black text on black background to use white text. */
+  if (uv_tty_default_text_attributes == 0)
+    uv_tty_default_text_attributes = 7;
+
+  /* Convert Win32 attributes to ANSI colors. */
+  uv_tty_default_fg_color = 0;
+  uv_tty_default_bg_color = 0;
+  uv_tty_default_fg_bright = 0;
+  uv_tty_default_bg_bright = 0;
+  uv_tty_default_inverse = 0;
+
+  if (uv_tty_default_text_attributes & FOREGROUND_RED)
+    uv_tty_default_fg_color |= 1;
+
+  if (uv_tty_default_text_attributes & FOREGROUND_GREEN)
+    uv_tty_default_fg_color |= 2;
+
+  if (uv_tty_default_text_attributes & FOREGROUND_BLUE)
+    uv_tty_default_fg_color |= 4;
+
+  if (uv_tty_default_text_attributes & BACKGROUND_RED)
+    uv_tty_default_bg_color |= 1;
+
+  if (uv_tty_default_text_attributes & BACKGROUND_GREEN)
+    uv_tty_default_bg_color |= 2;
+
+  if (uv_tty_default_text_attributes & BACKGROUND_BLUE)
+    uv_tty_default_bg_color |= 4;
+
+  if (uv_tty_default_text_attributes & FOREGROUND_INTENSITY)
+    uv_tty_default_fg_bright = 1;
+
+  if (uv_tty_default_text_attributes & BACKGROUND_INTENSITY)
+    uv_tty_default_bg_bright = 1;
+
+  if (uv_tty_default_text_attributes & COMMON_LVB_REVERSE_VIDEO)
+    uv_tty_default_inverse = 1;
+
+  /* Save the cursor size and the cursor state. */
+  uv_tty_default_cursor_info = *cursor_info;
+
+  style_captured = 1;
+}
+
+
+int uv_tty_set_mode(uv_tty_t* tty, uv_tty_mode_t mode) {
+  DWORD flags;
+  unsigned char was_reading;
+  uv_alloc_cb alloc_cb;
+  uv_read_cb read_cb;
+  int err;
+
+  if (!(tty->flags & UV_HANDLE_TTY_READABLE)) {
+    return UV_EINVAL;
+  }
+
+  if (!!mode == !!(tty->flags & UV_HANDLE_TTY_RAW)) {
+    return 0;
+  }
+
+  switch (mode) {
+    case UV_TTY_MODE_NORMAL:
+      flags = ENABLE_ECHO_INPUT | ENABLE_LINE_INPUT | ENABLE_PROCESSED_INPUT;
+      break;
+    case UV_TTY_MODE_RAW:
+      flags = ENABLE_WINDOW_INPUT;
+      break;
+    case UV_TTY_MODE_IO:
+      return UV_ENOTSUP;
+    default:
+      return UV_EINVAL;
+  }
+
+  /* If currently reading, stop, and restart reading. */
+  if (tty->flags & UV_HANDLE_READING) {
+    was_reading = 1;
+    alloc_cb = tty->alloc_cb;
+    read_cb = tty->read_cb;
+    err = uv__tty_read_stop(tty);
+    if (err) {
+      return uv_translate_sys_error(err);
+    }
+  } else {
+    was_reading = 0;
+    alloc_cb = NULL;
+    read_cb = NULL;
+  }
+
+  uv_sem_wait(&uv_tty_output_lock);
+  if (!SetConsoleMode(tty->handle, flags)) {
+    err = uv_translate_sys_error(GetLastError());
+    uv_sem_post(&uv_tty_output_lock);
+    return err;
+  }
+  uv_sem_post(&uv_tty_output_lock);
+
+  /* Update flag. */
+  tty->flags &= ~UV_HANDLE_TTY_RAW;
+  tty->flags |= mode ? UV_HANDLE_TTY_RAW : 0;
+
+  /* If we just stopped reading, restart. */
+  if (was_reading) {
+    err = uv__tty_read_start(tty, alloc_cb, read_cb);
+    if (err) {
+      return uv_translate_sys_error(err);
+    }
+  }
+
+  return 0;
+}
+
+
+int uv_tty_get_winsize(uv_tty_t* tty, int* width, int* height) {
+  CONSOLE_SCREEN_BUFFER_INFO info;
+
+  if (!GetConsoleScreenBufferInfo(tty->handle, &info)) {
+    return uv_translate_sys_error(GetLastError());
+  }
+
+  uv_sem_wait(&uv_tty_output_lock);
+  uv__tty_update_virtual_window(&info);
+  uv_sem_post(&uv_tty_output_lock);
+
+  *width = uv_tty_virtual_width;
+  *height = uv_tty_virtual_height;
+
+  return 0;
+}
+
+
+static void CALLBACK uv_tty_post_raw_read(void* data, BOOLEAN didTimeout) {
+  uv_loop_t* loop;
+  uv_tty_t* handle;
+  uv_req_t* req;
+
+  assert(data);
+  assert(!didTimeout);
+
+  req = (uv_req_t*) data;
+  handle = (uv_tty_t*) req->data;
+  loop = handle->loop;
+
+  UnregisterWait(handle->tty.rd.read_raw_wait);
+  handle->tty.rd.read_raw_wait = NULL;
+
+  SET_REQ_SUCCESS(req);
+  POST_COMPLETION_FOR_REQ(loop, req);
+}
+
+
+static void uv__tty_queue_read_raw(uv_loop_t* loop, uv_tty_t* handle) {
+  uv_read_t* req;
+  BOOL r;
+
+  assert(handle->flags & UV_HANDLE_READING);
+  assert(!(handle->flags & UV_HANDLE_READ_PENDING));
+
+  assert(handle->handle && handle->handle != INVALID_HANDLE_VALUE);
+
+  handle->tty.rd.read_line_buffer = uv_null_buf_;
+
+  req = &handle->read_req;
+  memset(&req->u.io.overlapped, 0, sizeof(req->u.io.overlapped));
+
+  r = RegisterWaitForSingleObject(&handle->tty.rd.read_raw_wait,
+                                  handle->handle,
+                                  uv_tty_post_raw_read,
+                                  (void*) req,
+                                  INFINITE,
+                                  WT_EXECUTEINWAITTHREAD | WT_EXECUTEONLYONCE);
+  if (!r) {
+    handle->tty.rd.read_raw_wait = NULL;
+    SET_REQ_ERROR(req, GetLastError());
+    uv__insert_pending_req(loop, (uv_req_t*)req);
+  }
+
+  handle->flags |= UV_HANDLE_READ_PENDING;
+  handle->reqs_pending++;
+}
+
+
+static DWORD CALLBACK uv_tty_line_read_thread(void* data) {
+  uv_loop_t* loop;
+  uv_tty_t* handle;
+  uv_req_t* req;
+  DWORD bytes, read_bytes;
+  WCHAR utf16[MAX_INPUT_BUFFER_LENGTH / 3];
+  DWORD chars, read_chars;
+  LONG status;
+  COORD pos;
+  BOOL read_console_success;
+
+  assert(data);
+
+  req = (uv_req_t*) data;
+  handle = (uv_tty_t*) req->data;
+  loop = handle->loop;
+
+  assert(handle->tty.rd.read_line_buffer.base != NULL);
+  assert(handle->tty.rd.read_line_buffer.len > 0);
+
+  /* ReadConsole can't handle big buffers. */
+  if (handle->tty.rd.read_line_buffer.len < MAX_INPUT_BUFFER_LENGTH) {
+    bytes = handle->tty.rd.read_line_buffer.len;
+  } else {
+    bytes = MAX_INPUT_BUFFER_LENGTH;
+  }
+
+  /* At last, unicode! One utf-16 codeunit never takes more than 3 utf-8
+   * codeunits to encode. */
+  chars = bytes / 3;
+
+  status = InterlockedExchange(&uv__read_console_status, IN_PROGRESS);
+  if (status == TRAP_REQUESTED) {
+    SET_REQ_SUCCESS(req);
+    InterlockedExchange(&uv__read_console_status, COMPLETED);
+    req->u.io.overlapped.InternalHigh = 0;
+    POST_COMPLETION_FOR_REQ(loop, req);
+    return 0;
+  }
+
+  read_console_success = ReadConsoleW(handle->handle,
+                                      (void*) utf16,
+                                      chars,
+                                      &read_chars,
+                                      NULL);
+
+  if (read_console_success) {
+    read_bytes = WideCharToMultiByte(CP_UTF8,
+                                     0,
+                                     utf16,
+                                     read_chars,
+                                     handle->tty.rd.read_line_buffer.base,
+                                     bytes,
+                                     NULL,
+                                     NULL);
+    SET_REQ_SUCCESS(req);
+    req->u.io.overlapped.InternalHigh = read_bytes;
+  } else {
+    SET_REQ_ERROR(req, GetLastError());
+  }
+
+  status = InterlockedExchange(&uv__read_console_status, COMPLETED);
+
+  if (status ==  TRAP_REQUESTED) {
+    /* If we canceled the read by sending a VK_RETURN event, restore the
+       screen state to undo the visual effect of the VK_RETURN */
+    if (read_console_success && InterlockedOr(&uv__restore_screen_state, 0)) {
+      HANDLE active_screen_buffer;
+      active_screen_buffer = CreateFileA("conout$",
+                                         GENERIC_READ | GENERIC_WRITE,
+                                         FILE_SHARE_READ | FILE_SHARE_WRITE,
+                                         NULL,
+                                         OPEN_EXISTING,
+                                         FILE_ATTRIBUTE_NORMAL,
+                                         NULL);
+      if (active_screen_buffer != INVALID_HANDLE_VALUE) {
+        pos = uv__saved_screen_state.dwCursorPosition;
+
+        /* If the cursor was at the bottom line of the screen buffer, the
+           VK_RETURN would have caused the buffer contents to scroll up by one
+           line. The right position to reset the cursor to is therefore one line
+           higher */
+        if (pos.Y == uv__saved_screen_state.dwSize.Y - 1)
+          pos.Y--;
+
+        SetConsoleCursorPosition(active_screen_buffer, pos);
+        CloseHandle(active_screen_buffer);
+      }
+    }
+    uv_sem_post(&uv_tty_output_lock);
+  }
+  POST_COMPLETION_FOR_REQ(loop, req);
+  return 0;
+}
+
+
+static void uv__tty_queue_read_line(uv_loop_t* loop, uv_tty_t* handle) {
+  uv_read_t* req;
+  BOOL r;
+
+  assert(handle->flags & UV_HANDLE_READING);
+  assert(!(handle->flags & UV_HANDLE_READ_PENDING));
+  assert(handle->handle && handle->handle != INVALID_HANDLE_VALUE);
+
+  req = &handle->read_req;
+  memset(&req->u.io.overlapped, 0, sizeof(req->u.io.overlapped));
+
+  handle->tty.rd.read_line_buffer = uv_buf_init(NULL, 0);
+  handle->alloc_cb((uv_handle_t*) handle, 8192, &handle->tty.rd.read_line_buffer);
+  if (handle->tty.rd.read_line_buffer.base == NULL ||
+      handle->tty.rd.read_line_buffer.len == 0) {
+    handle->read_cb((uv_stream_t*) handle,
+                    UV_ENOBUFS,
+                    &handle->tty.rd.read_line_buffer);
+    return;
+  }
+  assert(handle->tty.rd.read_line_buffer.base != NULL);
+
+  /* Reset flags  No locking is required since there cannot be a line read
+     in progress. We are also relying on the memory barrier provided by
+     QueueUserWorkItem*/
+  uv__restore_screen_state = FALSE;
+  uv__read_console_status = NOT_STARTED;
+  r = QueueUserWorkItem(uv_tty_line_read_thread,
+                        (void*) req,
+                        WT_EXECUTELONGFUNCTION);
+  if (!r) {
+    SET_REQ_ERROR(req, GetLastError());
+    uv__insert_pending_req(loop, (uv_req_t*)req);
+  }
+
+  handle->flags |= UV_HANDLE_READ_PENDING;
+  handle->reqs_pending++;
+}
+
+
+static void uv__tty_queue_read(uv_loop_t* loop, uv_tty_t* handle) {
+  if (handle->flags & UV_HANDLE_TTY_RAW) {
+    uv__tty_queue_read_raw(loop, handle);
+  } else {
+    uv__tty_queue_read_line(loop, handle);
+  }
+}
+
+
+static const char* get_vt100_fn_key(DWORD code, char shift, char ctrl,
+    size_t* len) {
+#define VK_CASE(vk, normal_str, shift_str, ctrl_str, shift_ctrl_str)          \
+    case (vk):                                                                \
+      if (shift && ctrl) {                                                    \
+        *len = sizeof shift_ctrl_str;                                         \
+        return "\033" shift_ctrl_str;                                         \
+      } else if (shift) {                                                     \
+        *len = sizeof shift_str ;                                             \
+        return "\033" shift_str;                                              \
+      } else if (ctrl) {                                                      \
+        *len = sizeof ctrl_str;                                               \
+        return "\033" ctrl_str;                                               \
+      } else {                                                                \
+        *len = sizeof normal_str;                                             \
+        return "\033" normal_str;                                             \
+      }
+
+  switch (code) {
+    /* These mappings are the same as Cygwin's. Unmodified and alt-modified
+     * keypad keys comply with linux console, modifiers comply with xterm
+     * modifier usage. F1. f12 and shift-f1. f10 comply with linux console, f6.
+     * f12 with and without modifiers comply with rxvt. */
+    VK_CASE(VK_INSERT,  "[2~",  "[2;2~", "[2;5~", "[2;6~")
+    VK_CASE(VK_END,     "[4~",  "[4;2~", "[4;5~", "[4;6~")
+    VK_CASE(VK_DOWN,    "[B",   "[1;2B", "[1;5B", "[1;6B")
+    VK_CASE(VK_NEXT,    "[6~",  "[6;2~", "[6;5~", "[6;6~")
+    VK_CASE(VK_LEFT,    "[D",   "[1;2D", "[1;5D", "[1;6D")
+    VK_CASE(VK_CLEAR,   "[G",   "[1;2G", "[1;5G", "[1;6G")
+    VK_CASE(VK_RIGHT,   "[C",   "[1;2C", "[1;5C", "[1;6C")
+    VK_CASE(VK_UP,      "[A",   "[1;2A", "[1;5A", "[1;6A")
+    VK_CASE(VK_HOME,    "[1~",  "[1;2~", "[1;5~", "[1;6~")
+    VK_CASE(VK_PRIOR,   "[5~",  "[5;2~", "[5;5~", "[5;6~")
+    VK_CASE(VK_DELETE,  "[3~",  "[3;2~", "[3;5~", "[3;6~")
+    VK_CASE(VK_NUMPAD0, "[2~",  "[2;2~", "[2;5~", "[2;6~")
+    VK_CASE(VK_NUMPAD1, "[4~",  "[4;2~", "[4;5~", "[4;6~")
+    VK_CASE(VK_NUMPAD2, "[B",   "[1;2B", "[1;5B", "[1;6B")
+    VK_CASE(VK_NUMPAD3, "[6~",  "[6;2~", "[6;5~", "[6;6~")
+    VK_CASE(VK_NUMPAD4, "[D",   "[1;2D", "[1;5D", "[1;6D")
+    VK_CASE(VK_NUMPAD5, "[G",   "[1;2G", "[1;5G", "[1;6G")
+    VK_CASE(VK_NUMPAD6, "[C",   "[1;2C", "[1;5C", "[1;6C")
+    VK_CASE(VK_NUMPAD7, "[A",   "[1;2A", "[1;5A", "[1;6A")
+    VK_CASE(VK_NUMPAD8, "[1~",  "[1;2~", "[1;5~", "[1;6~")
+    VK_CASE(VK_NUMPAD9, "[5~",  "[5;2~", "[5;5~", "[5;6~")
+    VK_CASE(VK_DECIMAL, "[3~",  "[3;2~", "[3;5~", "[3;6~")
+    VK_CASE(VK_F1,      "[[A",  "[23~",  "[11^",  "[23^" )
+    VK_CASE(VK_F2,      "[[B",  "[24~",  "[12^",  "[24^" )
+    VK_CASE(VK_F3,      "[[C",  "[25~",  "[13^",  "[25^" )
+    VK_CASE(VK_F4,      "[[D",  "[26~",  "[14^",  "[26^" )
+    VK_CASE(VK_F5,      "[[E",  "[28~",  "[15^",  "[28^" )
+    VK_CASE(VK_F6,      "[17~", "[29~",  "[17^",  "[29^" )
+    VK_CASE(VK_F7,      "[18~", "[31~",  "[18^",  "[31^" )
+    VK_CASE(VK_F8,      "[19~", "[32~",  "[19^",  "[32^" )
+    VK_CASE(VK_F9,      "[20~", "[33~",  "[20^",  "[33^" )
+    VK_CASE(VK_F10,     "[21~", "[34~",  "[21^",  "[34^" )
+    VK_CASE(VK_F11,     "[23~", "[23$",  "[23^",  "[23@" )
+    VK_CASE(VK_F12,     "[24~", "[24$",  "[24^",  "[24@" )
+
+    default:
+      *len = 0;
+      return NULL;
+  }
+#undef VK_CASE
+}
+
+
+void uv_process_tty_read_raw_req(uv_loop_t* loop, uv_tty_t* handle,
+    uv_req_t* req) {
+  /* Shortcut for handle->tty.rd.last_input_record.Event.KeyEvent. */
+#define KEV handle->tty.rd.last_input_record.Event.KeyEvent
+
+  DWORD records_left, records_read;
+  uv_buf_t buf;
+  off_t buf_used;
+
+  assert(handle->type == UV_TTY);
+  assert(handle->flags & UV_HANDLE_TTY_READABLE);
+  handle->flags &= ~UV_HANDLE_READ_PENDING;
+
+  if (!(handle->flags & UV_HANDLE_READING) ||
+      !(handle->flags & UV_HANDLE_TTY_RAW)) {
+    goto out;
+  }
+
+  if (!REQ_SUCCESS(req)) {
+    /* An error occurred while waiting for the event. */
+    if ((handle->flags & UV_HANDLE_READING)) {
+      handle->flags &= ~UV_HANDLE_READING;
+      handle->read_cb((uv_stream_t*)handle,
+                      uv_translate_sys_error(GET_REQ_ERROR(req)),
+                      &uv_null_buf_);
+    }
+    goto out;
+  }
+
+  /* Fetch the number of events  */
+  if (!GetNumberOfConsoleInputEvents(handle->handle, &records_left)) {
+    handle->flags &= ~UV_HANDLE_READING;
+    DECREASE_ACTIVE_COUNT(loop, handle);
+    handle->read_cb((uv_stream_t*)handle,
+                    uv_translate_sys_error(GetLastError()),
+                    &uv_null_buf_);
+    goto out;
+  }
+
+  /* Windows sends a lot of events that we're not interested in, so buf will be
+   * allocated on demand, when there's actually something to emit. */
+  buf = uv_null_buf_;
+  buf_used = 0;
+
+  while ((records_left > 0 || handle->tty.rd.last_key_len > 0) &&
+         (handle->flags & UV_HANDLE_READING)) {
+    if (handle->tty.rd.last_key_len == 0) {
+      /* Read the next input record */
+      if (!ReadConsoleInputW(handle->handle,
+                             &handle->tty.rd.last_input_record,
+                             1,
+                             &records_read)) {
+        handle->flags &= ~UV_HANDLE_READING;
+        DECREASE_ACTIVE_COUNT(loop, handle);
+        handle->read_cb((uv_stream_t*) handle,
+                        uv_translate_sys_error(GetLastError()),
+                        &buf);
+        goto out;
+      }
+      records_left--;
+
+      /* We might be not subscribed to EVENT_CONSOLE_LAYOUT or we might be
+       * running under some TTY emulator that does not send those events. */
+      if (handle->tty.rd.last_input_record.EventType == WINDOW_BUFFER_SIZE_EVENT) {
+        uv__tty_console_signal_resize();
+      }
+
+      /* Ignore other events that are not key events. */
+      if (handle->tty.rd.last_input_record.EventType != KEY_EVENT) {
+        continue;
+      }
+
+      /* Ignore keyup events, unless the left alt key was held and a valid
+       * unicode character was emitted. */
+      if (!KEV.bKeyDown &&
+          (KEV.wVirtualKeyCode != VK_MENU ||
+           KEV.uChar.UnicodeChar == 0)) {
+        continue;
+      }
+
+      /* Ignore keypresses to numpad number keys if the left alt is held
+       * because the user is composing a character, or windows simulating this.
+       */
+      if ((KEV.dwControlKeyState & LEFT_ALT_PRESSED) &&
+          !(KEV.dwControlKeyState & ENHANCED_KEY) &&
+          (KEV.wVirtualKeyCode == VK_INSERT ||
+          KEV.wVirtualKeyCode == VK_END ||
+          KEV.wVirtualKeyCode == VK_DOWN ||
+          KEV.wVirtualKeyCode == VK_NEXT ||
+          KEV.wVirtualKeyCode == VK_LEFT ||
+          KEV.wVirtualKeyCode == VK_CLEAR ||
+          KEV.wVirtualKeyCode == VK_RIGHT ||
+          KEV.wVirtualKeyCode == VK_HOME ||
+          KEV.wVirtualKeyCode == VK_UP ||
+          KEV.wVirtualKeyCode == VK_PRIOR ||
+          KEV.wVirtualKeyCode == VK_NUMPAD0 ||
+          KEV.wVirtualKeyCode == VK_NUMPAD1 ||
+          KEV.wVirtualKeyCode == VK_NUMPAD2 ||
+          KEV.wVirtualKeyCode == VK_NUMPAD3 ||
+          KEV.wVirtualKeyCode == VK_NUMPAD4 ||
+          KEV.wVirtualKeyCode == VK_NUMPAD5 ||
+          KEV.wVirtualKeyCode == VK_NUMPAD6 ||
+          KEV.wVirtualKeyCode == VK_NUMPAD7 ||
+          KEV.wVirtualKeyCode == VK_NUMPAD8 ||
+          KEV.wVirtualKeyCode == VK_NUMPAD9)) {
+        continue;
+      }
+
+      if (KEV.uChar.UnicodeChar != 0) {
+        int prefix_len, char_len;
+
+        /* Character key pressed */
+        if (KEV.uChar.UnicodeChar >= 0xD800 &&
+            KEV.uChar.UnicodeChar < 0xDC00) {
+          /* UTF-16 high surrogate */
+          handle->tty.rd.last_utf16_high_surrogate = KEV.uChar.UnicodeChar;
+          continue;
+        }
+
+        /* Prefix with \u033 if alt was held, but alt was not used as part a
+         * compose sequence. */
+        if ((KEV.dwControlKeyState & (LEFT_ALT_PRESSED | RIGHT_ALT_PRESSED))
+            && !(KEV.dwControlKeyState & (LEFT_CTRL_PRESSED |
+            RIGHT_CTRL_PRESSED)) && KEV.bKeyDown) {
+          handle->tty.rd.last_key[0] = '\033';
+          prefix_len = 1;
+        } else {
+          prefix_len = 0;
+        }
+
+        if (KEV.uChar.UnicodeChar >= 0xDC00 &&
+            KEV.uChar.UnicodeChar < 0xE000) {
+          /* UTF-16 surrogate pair */
+          WCHAR utf16_buffer[2];
+          utf16_buffer[0] = handle->tty.rd.last_utf16_high_surrogate;
+          utf16_buffer[1] = KEV.uChar.UnicodeChar;
+          char_len = WideCharToMultiByte(CP_UTF8,
+                                         0,
+                                         utf16_buffer,
+                                         2,
+                                         &handle->tty.rd.last_key[prefix_len],
+                                         sizeof handle->tty.rd.last_key,
+                                         NULL,
+                                         NULL);
+        } else {
+          /* Single UTF-16 character */
+          char_len = WideCharToMultiByte(CP_UTF8,
+                                         0,
+                                         &KEV.uChar.UnicodeChar,
+                                         1,
+                                         &handle->tty.rd.last_key[prefix_len],
+                                         sizeof handle->tty.rd.last_key,
+                                         NULL,
+                                         NULL);
+        }
+
+        /* Whatever happened, the last character wasn't a high surrogate. */
+        handle->tty.rd.last_utf16_high_surrogate = 0;
+
+        /* If the utf16 character(s) couldn't be converted something must be
+         * wrong. */
+        if (!char_len) {
+          handle->flags &= ~UV_HANDLE_READING;
+          DECREASE_ACTIVE_COUNT(loop, handle);
+          handle->read_cb((uv_stream_t*) handle,
+                          uv_translate_sys_error(GetLastError()),
+                          &buf);
+          goto out;
+        }
+
+        handle->tty.rd.last_key_len = (unsigned char) (prefix_len + char_len);
+        handle->tty.rd.last_key_offset = 0;
+        continue;
+
+      } else {
+        /* Function key pressed */
+        const char* vt100;
+        size_t prefix_len, vt100_len;
+
+        vt100 = get_vt100_fn_key(KEV.wVirtualKeyCode,
+                                  !!(KEV.dwControlKeyState & SHIFT_PRESSED),
+                                  !!(KEV.dwControlKeyState & (
+                                    LEFT_CTRL_PRESSED |
+                                    RIGHT_CTRL_PRESSED)),
+                                  &vt100_len);
+
+        /* If we were unable to map to a vt100 sequence, just ignore. */
+        if (!vt100) {
+          continue;
+        }
+
+        /* Prefix with \x033 when the alt key was held. */
+        if (KEV.dwControlKeyState & (LEFT_ALT_PRESSED | RIGHT_ALT_PRESSED)) {
+          handle->tty.rd.last_key[0] = '\033';
+          prefix_len = 1;
+        } else {
+          prefix_len = 0;
+        }
+
+        /* Copy the vt100 sequence to the handle buffer. */
+        assert(prefix_len + vt100_len < sizeof handle->tty.rd.last_key);
+        memcpy(&handle->tty.rd.last_key[prefix_len], vt100, vt100_len);
+
+        handle->tty.rd.last_key_len = (unsigned char) (prefix_len + vt100_len);
+        handle->tty.rd.last_key_offset = 0;
+        continue;
+      }
+    } else {
+      /* Copy any bytes left from the last keypress to the user buffer. */
+      if (handle->tty.rd.last_key_offset < handle->tty.rd.last_key_len) {
+        /* Allocate a buffer if needed */
+        if (buf_used == 0) {
+          buf = uv_buf_init(NULL, 0);
+          handle->alloc_cb((uv_handle_t*) handle, 1024, &buf);
+          if (buf.base == NULL || buf.len == 0) {
+            handle->read_cb((uv_stream_t*) handle, UV_ENOBUFS, &buf);
+            goto out;
+          }
+          assert(buf.base != NULL);
+        }
+
+        buf.base[buf_used++] = handle->tty.rd.last_key[handle->tty.rd.last_key_offset++];
+
+        /* If the buffer is full, emit it */
+        if ((size_t) buf_used == buf.len) {
+          handle->read_cb((uv_stream_t*) handle, buf_used, &buf);
+          buf = uv_null_buf_;
+          buf_used = 0;
+        }
+
+        continue;
+      }
+
+      /* Apply dwRepeat from the last input record. */
+      if (--KEV.wRepeatCount > 0) {
+        handle->tty.rd.last_key_offset = 0;
+        continue;
+      }
+
+      handle->tty.rd.last_key_len = 0;
+      continue;
+    }
+  }
+
+  /* Send the buffer back to the user */
+  if (buf_used > 0) {
+    handle->read_cb((uv_stream_t*) handle, buf_used, &buf);
+  }
+
+ out:
+  /* Wait for more input events. */
+  if ((handle->flags & UV_HANDLE_READING) &&
+      !(handle->flags & UV_HANDLE_READ_PENDING)) {
+    uv__tty_queue_read(loop, handle);
+  }
+
+  DECREASE_PENDING_REQ_COUNT(handle);
+
+#undef KEV
+}
+
+
+
+void uv_process_tty_read_line_req(uv_loop_t* loop, uv_tty_t* handle,
+    uv_req_t* req) {
+  uv_buf_t buf;
+
+  assert(handle->type == UV_TTY);
+  assert(handle->flags & UV_HANDLE_TTY_READABLE);
+
+  buf = handle->tty.rd.read_line_buffer;
+
+  handle->flags &= ~UV_HANDLE_READ_PENDING;
+  handle->tty.rd.read_line_buffer = uv_null_buf_;
+
+  if (!REQ_SUCCESS(req)) {
+    /* Read was not successful */
+    if (handle->flags & UV_HANDLE_READING) {
+      /* Real error */
+      handle->flags &= ~UV_HANDLE_READING;
+      DECREASE_ACTIVE_COUNT(loop, handle);
+      handle->read_cb((uv_stream_t*) handle,
+                      uv_translate_sys_error(GET_REQ_ERROR(req)),
+                      &buf);
+    }
+  } else {
+    if (!(handle->flags & UV_HANDLE_CANCELLATION_PENDING) &&
+        req->u.io.overlapped.InternalHigh != 0) {
+      /* Read successful. TODO: read unicode, convert to utf-8 */
+      DWORD bytes = req->u.io.overlapped.InternalHigh;
+      handle->read_cb((uv_stream_t*) handle, bytes, &buf);
+    }
+    handle->flags &= ~UV_HANDLE_CANCELLATION_PENDING;
+  }
+
+  /* Wait for more input events. */
+  if ((handle->flags & UV_HANDLE_READING) &&
+      !(handle->flags & UV_HANDLE_READ_PENDING)) {
+    uv__tty_queue_read(loop, handle);
+  }
+
+  DECREASE_PENDING_REQ_COUNT(handle);
+}
+
+
+void uv__process_tty_read_req(uv_loop_t* loop, uv_tty_t* handle,
+    uv_req_t* req) {
+  assert(handle->type == UV_TTY);
+  assert(handle->flags & UV_HANDLE_TTY_READABLE);
+
+  /* If the read_line_buffer member is zero, it must have been an raw read.
+   * Otherwise it was a line-buffered read. FIXME: This is quite obscure. Use a
+   * flag or something. */
+  if (handle->tty.rd.read_line_buffer.len == 0) {
+    uv_process_tty_read_raw_req(loop, handle, req);
+  } else {
+    uv_process_tty_read_line_req(loop, handle, req);
+  }
+}
+
+
+int uv__tty_read_start(uv_tty_t* handle, uv_alloc_cb alloc_cb,
+    uv_read_cb read_cb) {
+  uv_loop_t* loop = handle->loop;
+
+  if (!(handle->flags & UV_HANDLE_TTY_READABLE)) {
+    return ERROR_INVALID_PARAMETER;
+  }
+
+  handle->flags |= UV_HANDLE_READING;
+  INCREASE_ACTIVE_COUNT(loop, handle);
+  handle->read_cb = read_cb;
+  handle->alloc_cb = alloc_cb;
+
+  /* If reading was stopped and then started again, there could still be a read
+   * request pending. */
+  if (handle->flags & UV_HANDLE_READ_PENDING) {
+    return 0;
+  }
+
+  /* Maybe the user stopped reading half-way while processing key events.
+   * Short-circuit if this could be the case. */
+  if (handle->tty.rd.last_key_len > 0) {
+    SET_REQ_SUCCESS(&handle->read_req);
+    uv__insert_pending_req(handle->loop, (uv_req_t*) &handle->read_req);
+    /* Make sure no attempt is made to insert it again until it's handled. */
+    handle->flags |= UV_HANDLE_READ_PENDING;
+    handle->reqs_pending++;
+    return 0;
+  }
+
+  uv__tty_queue_read(loop, handle);
+
+  return 0;
+}
+
+
+int uv__tty_read_stop(uv_tty_t* handle) {
+  INPUT_RECORD record;
+  DWORD written, err;
+
+  handle->flags &= ~UV_HANDLE_READING;
+  DECREASE_ACTIVE_COUNT(handle->loop, handle);
+
+  if (!(handle->flags & UV_HANDLE_READ_PENDING))
+    return 0;
+
+  if (handle->flags & UV_HANDLE_TTY_RAW) {
+    /* Cancel raw read. Write some bullshit event to force the console wait to
+     * return. */
+    memset(&record, 0, sizeof record);
+    record.EventType = FOCUS_EVENT;
+    if (!WriteConsoleInputW(handle->handle, &record, 1, &written)) {
+      return GetLastError();
+    }
+  } else if (!(handle->flags & UV_HANDLE_CANCELLATION_PENDING)) {
+    /* Cancel line-buffered read if not already pending */
+    err = uv__cancel_read_console(handle);
+    if (err)
+      return err;
+
+    handle->flags |= UV_HANDLE_CANCELLATION_PENDING;
+  }
+
+  return 0;
+}
+
+static int uv__cancel_read_console(uv_tty_t* handle) {
+  HANDLE active_screen_buffer = INVALID_HANDLE_VALUE;
+  INPUT_RECORD record;
+  DWORD written;
+  DWORD err = 0;
+  LONG status;
+
+  assert(!(handle->flags & UV_HANDLE_CANCELLATION_PENDING));
+
+  /* Hold the output lock during the cancellation, to ensure that further
+     writes don't interfere with the screen state. It will be the ReadConsole
+     thread's responsibility to release the lock. */
+  uv_sem_wait(&uv_tty_output_lock);
+  status = InterlockedExchange(&uv__read_console_status, TRAP_REQUESTED);
+  if (status != IN_PROGRESS) {
+    /* Either we have managed to set a trap for the other thread before
+       ReadConsole is called, or ReadConsole has returned because the user
+       has pressed ENTER. In either case, there is nothing else to do. */
+    uv_sem_post(&uv_tty_output_lock);
+    return 0;
+  }
+
+  /* Save screen state before sending the VK_RETURN event */
+  active_screen_buffer = CreateFileA("conout$",
+                                     GENERIC_READ | GENERIC_WRITE,
+                                     FILE_SHARE_READ | FILE_SHARE_WRITE,
+                                     NULL,
+                                     OPEN_EXISTING,
+                                     FILE_ATTRIBUTE_NORMAL,
+                                     NULL);
+
+  if (active_screen_buffer != INVALID_HANDLE_VALUE &&
+      GetConsoleScreenBufferInfo(active_screen_buffer,
+                                 &uv__saved_screen_state)) {
+    InterlockedOr(&uv__restore_screen_state, 1);
+  }
+
+  /* Write enter key event to force the console wait to return. */
+  record.EventType = KEY_EVENT;
+  record.Event.KeyEvent.bKeyDown = TRUE;
+  record.Event.KeyEvent.wRepeatCount = 1;
+  record.Event.KeyEvent.wVirtualKeyCode = VK_RETURN;
+  record.Event.KeyEvent.wVirtualScanCode =
+    MapVirtualKeyW(VK_RETURN, MAPVK_VK_TO_VSC);
+  record.Event.KeyEvent.uChar.UnicodeChar = L'\r';
+  record.Event.KeyEvent.dwControlKeyState = 0;
+  if (!WriteConsoleInputW(handle->handle, &record, 1, &written))
+    err = GetLastError();
+
+  if (active_screen_buffer != INVALID_HANDLE_VALUE)
+    CloseHandle(active_screen_buffer);
+
+  return err;
+}
+
+
+static void uv__tty_update_virtual_window(CONSOLE_SCREEN_BUFFER_INFO* info) {
+  uv_tty_virtual_width = info->dwSize.X;
+  uv_tty_virtual_height = info->srWindow.Bottom - info->srWindow.Top + 1;
+
+  /* Recompute virtual window offset row. */
+  if (uv_tty_virtual_offset == -1) {
+    uv_tty_virtual_offset = info->dwCursorPosition.Y;
+  } else if (uv_tty_virtual_offset < info->dwCursorPosition.Y -
+             uv_tty_virtual_height + 1) {
+    /* If suddenly find the cursor outside of the virtual window, it must have
+     * somehow scrolled. Update the virtual window offset. */
+    uv_tty_virtual_offset = info->dwCursorPosition.Y -
+                            uv_tty_virtual_height + 1;
+  }
+  if (uv_tty_virtual_offset + uv_tty_virtual_height > info->dwSize.Y) {
+    uv_tty_virtual_offset = info->dwSize.Y - uv_tty_virtual_height;
+  }
+  if (uv_tty_virtual_offset < 0) {
+    uv_tty_virtual_offset = 0;
+  }
+}
+
+
+static COORD uv__tty_make_real_coord(uv_tty_t* handle,
+    CONSOLE_SCREEN_BUFFER_INFO* info, int x, unsigned char x_relative, int y,
+    unsigned char y_relative) {
+  COORD result;
+
+  uv__tty_update_virtual_window(info);
+
+  /* Adjust y position */
+  if (y_relative) {
+    y = info->dwCursorPosition.Y + y;
+  } else {
+    y = uv_tty_virtual_offset + y;
+  }
+  /* Clip y to virtual client rectangle */
+  if (y < uv_tty_virtual_offset) {
+    y = uv_tty_virtual_offset;
+  } else if (y >= uv_tty_virtual_offset + uv_tty_virtual_height) {
+    y = uv_tty_virtual_offset + uv_tty_virtual_height - 1;
+  }
+
+  /* Adjust x */
+  if (x_relative) {
+    x = info->dwCursorPosition.X + x;
+  }
+  /* Clip x */
+  if (x < 0) {
+    x = 0;
+  } else if (x >= uv_tty_virtual_width) {
+    x = uv_tty_virtual_width - 1;
+  }
+
+  result.X = (unsigned short) x;
+  result.Y = (unsigned short) y;
+  return result;
+}
+
+
+static int uv__tty_emit_text(uv_tty_t* handle, WCHAR buffer[], DWORD length,
+    DWORD* error) {
+  DWORD written;
+
+  if (*error != ERROR_SUCCESS) {
+    return -1;
+  }
+
+  if (!WriteConsoleW(handle->handle,
+                     (void*) buffer,
+                     length,
+                     &written,
+                     NULL)) {
+    *error = GetLastError();
+    return -1;
+  }
+
+  return 0;
+}
+
+
+static int uv__tty_move_caret(uv_tty_t* handle, int x, unsigned char x_relative,
+    int y, unsigned char y_relative, DWORD* error) {
+  CONSOLE_SCREEN_BUFFER_INFO info;
+  COORD pos;
+
+  if (*error != ERROR_SUCCESS) {
+    return -1;
+  }
+
+ retry:
+  if (!GetConsoleScreenBufferInfo(handle->handle, &info)) {
+    *error = GetLastError();
+  }
+
+  pos = uv__tty_make_real_coord(handle, &info, x, x_relative, y, y_relative);
+
+  if (!SetConsoleCursorPosition(handle->handle, pos)) {
+    if (GetLastError() == ERROR_INVALID_PARAMETER) {
+      /* The console may be resized - retry */
+      goto retry;
+    } else {
+      *error = GetLastError();
+      return -1;
+    }
+  }
+
+  return 0;
+}
+
+
+static int uv__tty_reset(uv_tty_t* handle, DWORD* error) {
+  const COORD origin = {0, 0};
+  const WORD char_attrs = uv_tty_default_text_attributes;
+  CONSOLE_SCREEN_BUFFER_INFO screen_buffer_info;
+  DWORD count, written;
+
+  if (*error != ERROR_SUCCESS) {
+    return -1;
+  }
+
+  /* Reset original text attributes. */
+  if (!SetConsoleTextAttribute(handle->handle, char_attrs)) {
+    *error = GetLastError();
+    return -1;
+  }
+
+  /* Move the cursor position to (0, 0). */
+  if (!SetConsoleCursorPosition(handle->handle, origin)) {
+    *error = GetLastError();
+    return -1;
+  }
+
+  /* Clear the screen buffer. */
+ retry:
+   if (!GetConsoleScreenBufferInfo(handle->handle, &screen_buffer_info)) {
+     *error = GetLastError();
+     return -1;
+  }
+
+  count = screen_buffer_info.dwSize.X * screen_buffer_info.dwSize.Y;
+
+  if (!(FillConsoleOutputCharacterW(handle->handle,
+                                    L'\x20',
+                                    count,
+                                    origin,
+                                    &written) &&
+        FillConsoleOutputAttribute(handle->handle,
+                                   char_attrs,
+                                   written,
+                                   origin,
+                                   &written))) {
+    if (GetLastError() == ERROR_INVALID_PARAMETER) {
+      /* The console may be resized - retry */
+      goto retry;
+    } else {
+      *error = GetLastError();
+      return -1;
+    }
+  }
+
+  /* Move the virtual window up to the top. */
+  uv_tty_virtual_offset = 0;
+  uv__tty_update_virtual_window(&screen_buffer_info);
+
+  /* Reset the cursor size and the cursor state. */
+  if (!SetConsoleCursorInfo(handle->handle, &uv_tty_default_cursor_info)) {
+    *error = GetLastError();
+    return -1;
+  }
+
+  return 0;
+}
+
+
+static int uv__tty_clear(uv_tty_t* handle, int dir, char entire_screen,
+    DWORD* error) {
+  CONSOLE_SCREEN_BUFFER_INFO info;
+  COORD start, end;
+  DWORD count, written;
+
+  int x1, x2, y1, y2;
+  int x1r, x2r, y1r, y2r;
+
+  if (*error != ERROR_SUCCESS) {
+    return -1;
+  }
+
+  if (dir == 0) {
+    /* Clear from current position */
+    x1 = 0;
+    x1r = 1;
+  } else {
+    /* Clear from column 0 */
+    x1 = 0;
+    x1r = 0;
+  }
+
+  if (dir == 1) {
+    /* Clear to current position */
+    x2 = 0;
+    x2r = 1;
+  } else {
+    /* Clear to end of row. We pretend the console is 65536 characters wide,
+     * uv__tty_make_real_coord will clip it to the actual console width. */
+    x2 = 0xffff;
+    x2r = 0;
+  }
+
+  if (!entire_screen) {
+    /* Stay on our own row */
+    y1 = y2 = 0;
+    y1r = y2r = 1;
+  } else {
+    /* Apply columns direction to row */
+    y1 = x1;
+    y1r = x1r;
+    y2 = x2;
+    y2r = x2r;
+  }
+
+ retry:
+  if (!GetConsoleScreenBufferInfo(handle->handle, &info)) {
+    *error = GetLastError();
+    return -1;
+  }
+
+  start = uv__tty_make_real_coord(handle, &info, x1, x1r, y1, y1r);
+  end = uv__tty_make_real_coord(handle, &info, x2, x2r, y2, y2r);
+  count = (end.Y * info.dwSize.X + end.X) -
+          (start.Y * info.dwSize.X + start.X) + 1;
+
+  if (!(FillConsoleOutputCharacterW(handle->handle,
+                              L'\x20',
+                              count,
+                              start,
+                              &written) &&
+        FillConsoleOutputAttribute(handle->handle,
+                                   info.wAttributes,
+                                   written,
+                                   start,
+                                   &written))) {
+    if (GetLastError() == ERROR_INVALID_PARAMETER) {
+      /* The console may be resized - retry */
+      goto retry;
+    } else {
+      *error = GetLastError();
+      return -1;
+    }
+  }
+
+  return 0;
+}
+
+#define FLIP_FGBG                                                             \
+    do {                                                                      \
+      WORD fg = info.wAttributes & 0xF;                                       \
+      WORD bg = info.wAttributes & 0xF0;                                      \
+      info.wAttributes &= 0xFF00;                                             \
+      info.wAttributes |= fg << 4;                                            \
+      info.wAttributes |= bg >> 4;                                            \
+    } while (0)
+
+static int uv__tty_set_style(uv_tty_t* handle, DWORD* error) {
+  unsigned short argc = handle->tty.wr.ansi_csi_argc;
+  unsigned short* argv = handle->tty.wr.ansi_csi_argv;
+  int i;
+  CONSOLE_SCREEN_BUFFER_INFO info;
+
+  char fg_color = -1, bg_color = -1;
+  char fg_bright = -1, bg_bright = -1;
+  char inverse = -1;
+
+  if (argc == 0) {
+    /* Reset mode */
+    fg_color = uv_tty_default_fg_color;
+    bg_color = uv_tty_default_bg_color;
+    fg_bright = uv_tty_default_fg_bright;
+    bg_bright = uv_tty_default_bg_bright;
+    inverse = uv_tty_default_inverse;
+  }
+
+  for (i = 0; i < argc; i++) {
+    short arg = argv[i];
+
+    if (arg == 0) {
+      /* Reset mode */
+      fg_color = uv_tty_default_fg_color;
+      bg_color = uv_tty_default_bg_color;
+      fg_bright = uv_tty_default_fg_bright;
+      bg_bright = uv_tty_default_bg_bright;
+      inverse = uv_tty_default_inverse;
+
+    } else if (arg == 1) {
+      /* Foreground bright on */
+      fg_bright = 1;
+
+    } else if (arg == 2) {
+      /* Both bright off */
+      fg_bright = 0;
+      bg_bright = 0;
+
+    } else if (arg == 5) {
+      /* Background bright on */
+      bg_bright = 1;
+
+    } else if (arg == 7) {
+      /* Inverse: on */
+      inverse = 1;
+
+    } else if (arg == 21 || arg == 22) {
+      /* Foreground bright off */
+      fg_bright = 0;
+
+    } else if (arg == 25) {
+      /* Background bright off */
+      bg_bright = 0;
+
+    } else if (arg == 27) {
+      /* Inverse: off */
+      inverse = 0;
+
+    } else if (arg >= 30 && arg <= 37) {
+      /* Set foreground color */
+      fg_color = arg - 30;
+
+    } else if (arg == 39) {
+      /* Default text color */
+      fg_color = uv_tty_default_fg_color;
+      fg_bright = uv_tty_default_fg_bright;
+
+    } else if (arg >= 40 && arg <= 47) {
+      /* Set background color */
+      bg_color = arg - 40;
+
+    } else if (arg ==  49) {
+      /* Default background color */
+      bg_color = uv_tty_default_bg_color;
+      bg_bright = uv_tty_default_bg_bright;
+
+    } else if (arg >= 90 && arg <= 97) {
+      /* Set bold foreground color */
+      fg_bright = 1;
+      fg_color = arg - 90;
+
+    } else if (arg >= 100 && arg <= 107) {
+      /* Set bold background color */
+      bg_bright = 1;
+      bg_color = arg - 100;
+
+    }
+  }
+
+  if (fg_color == -1 && bg_color == -1 && fg_bright == -1 &&
+      bg_bright == -1 && inverse == -1) {
+    /* Nothing changed */
+    return 0;
+  }
+
+  if (!GetConsoleScreenBufferInfo(handle->handle, &info)) {
+    *error = GetLastError();
+    return -1;
+  }
+
+  if ((info.wAttributes & COMMON_LVB_REVERSE_VIDEO) > 0) {
+    FLIP_FGBG;
+  }
+
+  if (fg_color != -1) {
+    info.wAttributes &= ~(FOREGROUND_RED | FOREGROUND_GREEN | FOREGROUND_BLUE);
+    if (fg_color & 1) info.wAttributes |= FOREGROUND_RED;
+    if (fg_color & 2) info.wAttributes |= FOREGROUND_GREEN;
+    if (fg_color & 4) info.wAttributes |= FOREGROUND_BLUE;
+  }
+
+  if (fg_bright != -1) {
+    if (fg_bright) {
+      info.wAttributes |= FOREGROUND_INTENSITY;
+    } else {
+      info.wAttributes &= ~FOREGROUND_INTENSITY;
+    }
+  }
+
+  if (bg_color != -1) {
+    info.wAttributes &= ~(BACKGROUND_RED | BACKGROUND_GREEN | BACKGROUND_BLUE);
+    if (bg_color & 1) info.wAttributes |= BACKGROUND_RED;
+    if (bg_color & 2) info.wAttributes |= BACKGROUND_GREEN;
+    if (bg_color & 4) info.wAttributes |= BACKGROUND_BLUE;
+  }
+
+  if (bg_bright != -1) {
+    if (bg_bright) {
+      info.wAttributes |= BACKGROUND_INTENSITY;
+    } else {
+      info.wAttributes &= ~BACKGROUND_INTENSITY;
+    }
+  }
+
+  if (inverse != -1) {
+    if (inverse) {
+      info.wAttributes |= COMMON_LVB_REVERSE_VIDEO;
+    } else {
+      info.wAttributes &= ~COMMON_LVB_REVERSE_VIDEO;
+    }
+  }
+
+  if ((info.wAttributes & COMMON_LVB_REVERSE_VIDEO) > 0) {
+    FLIP_FGBG;
+  }
+
+  if (!SetConsoleTextAttribute(handle->handle, info.wAttributes)) {
+    *error = GetLastError();
+    return -1;
+  }
+
+  return 0;
+}
+
+
+static int uv__tty_save_state(uv_tty_t* handle, unsigned char save_attributes,
+    DWORD* error) {
+  CONSOLE_SCREEN_BUFFER_INFO info;
+
+  if (*error != ERROR_SUCCESS) {
+    return -1;
+  }
+
+  if (!GetConsoleScreenBufferInfo(handle->handle, &info)) {
+    *error = GetLastError();
+    return -1;
+  }
+
+  uv__tty_update_virtual_window(&info);
+
+  handle->tty.wr.saved_position.X = info.dwCursorPosition.X;
+  handle->tty.wr.saved_position.Y = info.dwCursorPosition.Y -
+        uv_tty_virtual_offset;
+  handle->flags |= UV_HANDLE_TTY_SAVED_POSITION;
+
+  if (save_attributes) {
+    handle->tty.wr.saved_attributes = info.wAttributes &
+        (FOREGROUND_INTENSITY | BACKGROUND_INTENSITY);
+    handle->flags |= UV_HANDLE_TTY_SAVED_ATTRIBUTES;
+  }
+
+  return 0;
+}
+
+
+static int uv__tty_restore_state(uv_tty_t* handle,
+    unsigned char restore_attributes, DWORD* error) {
+  CONSOLE_SCREEN_BUFFER_INFO info;
+  WORD new_attributes;
+
+  if (*error != ERROR_SUCCESS) {
+    return -1;
+  }
+
+  if (handle->flags & UV_HANDLE_TTY_SAVED_POSITION) {
+    if (uv__tty_move_caret(handle,
+                          handle->tty.wr.saved_position.X,
+                          0,
+                          handle->tty.wr.saved_position.Y,
+                          0,
+                          error) != 0) {
+      return -1;
+    }
+  }
+
+  if (restore_attributes &&
+      (handle->flags & UV_HANDLE_TTY_SAVED_ATTRIBUTES)) {
+    if (!GetConsoleScreenBufferInfo(handle->handle, &info)) {
+      *error = GetLastError();
+      return -1;
+    }
+
+    new_attributes = info.wAttributes;
+    new_attributes &= ~(FOREGROUND_INTENSITY | BACKGROUND_INTENSITY);
+    new_attributes |= handle->tty.wr.saved_attributes;
+
+    if (!SetConsoleTextAttribute(handle->handle, new_attributes)) {
+      *error = GetLastError();
+      return -1;
+    }
+  }
+
+  return 0;
+}
+
+static int uv__tty_set_cursor_visibility(uv_tty_t* handle,
+                                        BOOL visible,
+                                        DWORD* error) {
+  CONSOLE_CURSOR_INFO cursor_info;
+
+  if (!GetConsoleCursorInfo(handle->handle, &cursor_info)) {
+    *error = GetLastError();
+    return -1;
+  }
+
+  cursor_info.bVisible = visible;
+
+  if (!SetConsoleCursorInfo(handle->handle, &cursor_info)) {
+    *error = GetLastError();
+    return -1;
+  }
+
+  return 0;
+}
+
+static int uv__tty_set_cursor_shape(uv_tty_t* handle, int style, DWORD* error) {
+  CONSOLE_CURSOR_INFO cursor_info;
+
+  if (!GetConsoleCursorInfo(handle->handle, &cursor_info)) {
+    *error = GetLastError();
+    return -1;
+  }
+
+  if (style == 0) {
+    cursor_info.dwSize = uv_tty_default_cursor_info.dwSize;
+  } else if (style <= 2) {
+    cursor_info.dwSize = CURSOR_SIZE_LARGE;
+  } else {
+    cursor_info.dwSize = CURSOR_SIZE_SMALL;
+  }
+
+  if (!SetConsoleCursorInfo(handle->handle, &cursor_info)) {
+    *error = GetLastError();
+    return -1;
+  }
+
+  return 0;
+}
+
+
+static int uv__tty_write_bufs(uv_tty_t* handle,
+                             const uv_buf_t bufs[],
+                             unsigned int nbufs,
+                             DWORD* error) {
+  /* We can only write 8k characters at a time. Windows can't handle much more
+   * characters in a single console write anyway. */
+  WCHAR utf16_buf[MAX_CONSOLE_CHAR];
+  DWORD utf16_buf_used = 0;
+  unsigned int i;
+
+#define FLUSH_TEXT()                                                \
+  do {                                                              \
+    if (utf16_buf_used > 0) {                                       \
+      uv__tty_emit_text(handle, utf16_buf, utf16_buf_used, error);  \
+      utf16_buf_used = 0;                                           \
+    }                                                               \
+  } while (0)
+
+#define ENSURE_BUFFER_SPACE(wchars_needed)                          \
+  if (wchars_needed > ARRAY_SIZE(utf16_buf) - utf16_buf_used) {     \
+    FLUSH_TEXT();                                                   \
+  }
+
+  /* Cache for fast access */
+  unsigned char utf8_bytes_left = handle->tty.wr.utf8_bytes_left;
+  unsigned int utf8_codepoint = handle->tty.wr.utf8_codepoint;
+  unsigned char previous_eol = handle->tty.wr.previous_eol;
+  unsigned short ansi_parser_state = handle->tty.wr.ansi_parser_state;
+
+  /* Store the error here. If we encounter an error, stop trying to do i/o but
+   * keep parsing the buffer so we leave the parser in a consistent state. */
+  *error = ERROR_SUCCESS;
+
+  uv_sem_wait(&uv_tty_output_lock);
+
+  for (i = 0; i < nbufs; i++) {
+    uv_buf_t buf = bufs[i];
+    unsigned int j;
+
+    for (j = 0; j < buf.len; j++) {
+      unsigned char c = buf.base[j];
+
+      /* Run the character through the utf8 decoder We happily accept non
+       * shortest form encodings and invalid code points - there's no real harm
+       * that can be done. */
+      if (utf8_bytes_left == 0) {
+        /* Read utf-8 start byte */
+        DWORD first_zero_bit;
+        unsigned char not_c = ~c;
+#ifdef _MSC_VER /* msvc */
+        if (_BitScanReverse(&first_zero_bit, not_c)) {
+#else /* assume gcc */
+        if (c != 0) {
+          first_zero_bit = (sizeof(int) * 8) - 1 - __builtin_clz(not_c);
+#endif
+          if (first_zero_bit == 7) {
+            /* Ascii - pass right through */
+            utf8_codepoint = (unsigned int) c;
+
+          } else if (first_zero_bit <= 5) {
+            /* Multibyte sequence */
+            utf8_codepoint = (0xff >> (8 - first_zero_bit)) & c;
+            utf8_bytes_left = (char) (6 - first_zero_bit);
+
+          } else {
+            /* Invalid continuation */
+            utf8_codepoint = UNICODE_REPLACEMENT_CHARACTER;
+          }
+
+        } else {
+          /* 0xff -- invalid */
+          utf8_codepoint = UNICODE_REPLACEMENT_CHARACTER;
+        }
+
+      } else if ((c & 0xc0) == 0x80) {
+        /* Valid continuation of utf-8 multibyte sequence */
+        utf8_bytes_left--;
+        utf8_codepoint <<= 6;
+        utf8_codepoint |= ((unsigned int) c & 0x3f);
+
+      } else {
+        /* Start byte where continuation was expected. */
+        utf8_bytes_left = 0;
+        utf8_codepoint = UNICODE_REPLACEMENT_CHARACTER;
+        /* Patch buf offset so this character will be parsed again as a start
+         * byte. */
+        j--;
+      }
+
+      /* Maybe we need to parse more bytes to find a character. */
+      if (utf8_bytes_left != 0) {
+        continue;
+      }
+
+      /* Parse vt100/ansi escape codes */
+      if (uv__vterm_state == UV_TTY_SUPPORTED) {
+        /* Pass through escape codes if conhost supports them. */
+      } else if (ansi_parser_state == ANSI_NORMAL) {
+        switch (utf8_codepoint) {
+          case '\033':
+            ansi_parser_state = ANSI_ESCAPE_SEEN;
+            continue;
+
+          case 0233:
+            ansi_parser_state = ANSI_CSI;
+            handle->tty.wr.ansi_csi_argc = 0;
+            continue;
+        }
+
+      } else if (ansi_parser_state == ANSI_ESCAPE_SEEN) {
+        switch (utf8_codepoint) {
+          case '[':
+            ansi_parser_state = ANSI_CSI;
+            handle->tty.wr.ansi_csi_argc = 0;
+            continue;
+
+          case '^':
+          case '_':
+          case 'P':
+          case ']':
+            /* Not supported, but we'll have to parse until we see a stop code,
+             * e. g. ESC \ or BEL. */
+            ansi_parser_state = ANSI_ST_CONTROL;
+            continue;
+
+          case '\033':
+            /* Ignore double escape. */
+            continue;
+
+          case 'c':
+            /* Full console reset. */
+            FLUSH_TEXT();
+            uv__tty_reset(handle, error);
+            ansi_parser_state = ANSI_NORMAL;
+            continue;
+
+          case '7':
+            /* Save the cursor position and text attributes. */
+            FLUSH_TEXT();
+            uv__tty_save_state(handle, 1, error);
+            ansi_parser_state = ANSI_NORMAL;
+            continue;
+
+          case '8':
+            /* Restore the cursor position and text attributes */
+            FLUSH_TEXT();
+            uv__tty_restore_state(handle, 1, error);
+            ansi_parser_state = ANSI_NORMAL;
+            continue;
+
+          default:
+            if (utf8_codepoint >= '@' && utf8_codepoint <= '_') {
+              /* Single-char control. */
+              ansi_parser_state = ANSI_NORMAL;
+              continue;
+            } else {
+              /* Invalid - proceed as normal, */
+              ansi_parser_state = ANSI_NORMAL;
+            }
+        }
+
+      } else if (ansi_parser_state == ANSI_IGNORE) {
+        /* We're ignoring this command. Stop only on command character. */
+        if (utf8_codepoint >= '@' && utf8_codepoint <= '~') {
+          ansi_parser_state = ANSI_NORMAL;
+        }
+        continue;
+
+      } else if (ansi_parser_state == ANSI_DECSCUSR) {
+        /* So far we've the sequence `ESC [ arg space`, and we're waiting for
+         * the final command byte. */
+        if (utf8_codepoint >= '@' && utf8_codepoint <= '~') {
+          /* Command byte */
+          if (utf8_codepoint == 'q') {
+            /* Change the cursor shape */
+            int style = handle->tty.wr.ansi_csi_argc
+              ? handle->tty.wr.ansi_csi_argv[0] : 1;
+            if (style >= 0 && style <= 6) {
+              FLUSH_TEXT();
+              uv__tty_set_cursor_shape(handle, style, error);
+            }
+          }
+
+          /* Sequence ended - go back to normal state. */
+          ansi_parser_state = ANSI_NORMAL;
+          continue;
+        }
+        /* Unexpected character, but sequence hasn't ended yet. Ignore the rest
+         * of the sequence. */
+        ansi_parser_state = ANSI_IGNORE;
+
+      } else if (ansi_parser_state & ANSI_CSI) {
+        /* So far we've seen `ESC [`, and we may or may not have already parsed
+         * some of the arguments that follow. */
+
+        if (utf8_codepoint >= '0' && utf8_codepoint <= '9') {
+          /* Parse a numerical argument. */
+          if (!(ansi_parser_state & ANSI_IN_ARG)) {
+            /* We were not currently parsing a number, add a new one. */
+            /* Check for that there are too many arguments. */
+            if (handle->tty.wr.ansi_csi_argc >=
+                ARRAY_SIZE(handle->tty.wr.ansi_csi_argv)) {
+              ansi_parser_state = ANSI_IGNORE;
+              continue;
+            }
+            ansi_parser_state |= ANSI_IN_ARG;
+            handle->tty.wr.ansi_csi_argc++;
+            handle->tty.wr.ansi_csi_argv[handle->tty.wr.ansi_csi_argc - 1] =
+                (unsigned short) utf8_codepoint - '0';
+            continue;
+
+          } else {
+            /* We were already parsing a number. Parse next digit. */
+            uint32_t value = 10 *
+                handle->tty.wr.ansi_csi_argv[handle->tty.wr.ansi_csi_argc - 1];
+
+            /* Check for overflow. */
+            if (value > UINT16_MAX) {
+              ansi_parser_state = ANSI_IGNORE;
+              continue;
+            }
+
+            handle->tty.wr.ansi_csi_argv[handle->tty.wr.ansi_csi_argc - 1] =
+                (unsigned short) value + (utf8_codepoint - '0');
+            continue;
+          }
+
+        } else if (utf8_codepoint == ';') {
+          /* Denotes the end of an argument. */
+          if (ansi_parser_state & ANSI_IN_ARG) {
+            ansi_parser_state &= ~ANSI_IN_ARG;
+            continue;
+
+          } else {
+            /* If ANSI_IN_ARG is not set, add another argument and default
+             * it to 0. */
+
+            /* Check for too many arguments */
+            if (handle->tty.wr.ansi_csi_argc >=
+
+                ARRAY_SIZE(handle->tty.wr.ansi_csi_argv)) {
+              ansi_parser_state = ANSI_IGNORE;
+              continue;
+            }
+
+            handle->tty.wr.ansi_csi_argc++;
+            handle->tty.wr.ansi_csi_argv[handle->tty.wr.ansi_csi_argc - 1] = 0;
+            continue;
+          }
+
+        } else if (utf8_codepoint == '?' &&
+                   !(ansi_parser_state & ANSI_IN_ARG) &&
+                   !(ansi_parser_state & ANSI_EXTENSION) &&
+                   handle->tty.wr.ansi_csi_argc == 0) {
+          /* Pass through '?' if it is the first character after CSI */
+          /* This is an extension character from the VT100 codeset */
+          /* that is supported and used by most ANSI terminals today. */
+          ansi_parser_state |= ANSI_EXTENSION;
+          continue;
+
+        } else if (utf8_codepoint == ' ' &&
+                   !(ansi_parser_state & ANSI_EXTENSION)) {
+          /* We expect a command byte to follow after this space. The only
+           * command that we current support is 'set cursor style'. */
+          ansi_parser_state = ANSI_DECSCUSR;
+          continue;
+
+        } else if (utf8_codepoint >= '@' && utf8_codepoint <= '~') {
+          /* Command byte */
+          if (ansi_parser_state & ANSI_EXTENSION) {
+            /* Sequence is `ESC [ ? args command`. */
+            switch (utf8_codepoint) {
+              case 'l':
+                /* Hide the cursor */
+                if (handle->tty.wr.ansi_csi_argc == 1 &&
+                    handle->tty.wr.ansi_csi_argv[0] == 25) {
+                  FLUSH_TEXT();
+                  uv__tty_set_cursor_visibility(handle, 0, error);
+                }
+                break;
+
+              case 'h':
+                /* Show the cursor */
+                if (handle->tty.wr.ansi_csi_argc == 1 &&
+                    handle->tty.wr.ansi_csi_argv[0] == 25) {
+                  FLUSH_TEXT();
+                  uv__tty_set_cursor_visibility(handle, 1, error);
+                }
+                break;
+            }
+
+          } else {
+            /* Sequence is `ESC [ args command`. */
+            int x, y, d;
+            switch (utf8_codepoint) {
+              case 'A':
+                /* cursor up */
+                FLUSH_TEXT();
+                y = -(handle->tty.wr.ansi_csi_argc
+                  ? handle->tty.wr.ansi_csi_argv[0] : 1);
+                uv__tty_move_caret(handle, 0, 1, y, 1, error);
+                break;
+
+              case 'B':
+                /* cursor down */
+                FLUSH_TEXT();
+                y = handle->tty.wr.ansi_csi_argc
+                  ? handle->tty.wr.ansi_csi_argv[0] : 1;
+                uv__tty_move_caret(handle, 0, 1, y, 1, error);
+                break;
+
+              case 'C':
+                /* cursor forward */
+                FLUSH_TEXT();
+                x = handle->tty.wr.ansi_csi_argc
+                  ? handle->tty.wr.ansi_csi_argv[0] : 1;
+                uv__tty_move_caret(handle, x, 1, 0, 1, error);
+                break;
+
+              case 'D':
+                /* cursor back */
+                FLUSH_TEXT();
+                x = -(handle->tty.wr.ansi_csi_argc
+                  ? handle->tty.wr.ansi_csi_argv[0] : 1);
+                uv__tty_move_caret(handle, x, 1, 0, 1, error);
+                break;
+
+              case 'E':
+                /* cursor next line */
+                FLUSH_TEXT();
+                y = handle->tty.wr.ansi_csi_argc
+                  ? handle->tty.wr.ansi_csi_argv[0] : 1;
+                uv__tty_move_caret(handle, 0, 0, y, 1, error);
+                break;
+
+              case 'F':
+                /* cursor previous line */
+                FLUSH_TEXT();
+                y = -(handle->tty.wr.ansi_csi_argc
+                  ? handle->tty.wr.ansi_csi_argv[0] : 1);
+                uv__tty_move_caret(handle, 0, 0, y, 1, error);
+                break;
+
+              case 'G':
+                /* cursor horizontal move absolute */
+                FLUSH_TEXT();
+                x = (handle->tty.wr.ansi_csi_argc >= 1 &&
+                     handle->tty.wr.ansi_csi_argv[0])
+                  ? handle->tty.wr.ansi_csi_argv[0] - 1 : 0;
+                uv__tty_move_caret(handle, x, 0, 0, 1, error);
+                break;
+
+              case 'H':
+              case 'f':
+                /* cursor move absolute */
+                FLUSH_TEXT();
+                y = (handle->tty.wr.ansi_csi_argc >= 1 &&
+                     handle->tty.wr.ansi_csi_argv[0])
+                  ? handle->tty.wr.ansi_csi_argv[0] - 1 : 0;
+                x = (handle->tty.wr.ansi_csi_argc >= 2 &&
+                     handle->tty.wr.ansi_csi_argv[1])
+                  ? handle->tty.wr.ansi_csi_argv[1] - 1 : 0;
+                uv__tty_move_caret(handle, x, 0, y, 0, error);
+                break;
+
+              case 'J':
+                /* Erase screen */
+                FLUSH_TEXT();
+                d = handle->tty.wr.ansi_csi_argc
+                  ? handle->tty.wr.ansi_csi_argv[0] : 0;
+                if (d >= 0 && d <= 2) {
+                  uv__tty_clear(handle, d, 1, error);
+                }
+                break;
+
+              case 'K':
+                /* Erase line */
+                FLUSH_TEXT();
+                d = handle->tty.wr.ansi_csi_argc
+                  ? handle->tty.wr.ansi_csi_argv[0] : 0;
+                if (d >= 0 && d <= 2) {
+                  uv__tty_clear(handle, d, 0, error);
+                }
+                break;
+
+              case 'm':
+                /* Set style */
+                FLUSH_TEXT();
+                uv__tty_set_style(handle, error);
+                break;
+
+              case 's':
+                /* Save the cursor position. */
+                FLUSH_TEXT();
+                uv__tty_save_state(handle, 0, error);
+                break;
+
+              case 'u':
+                /* Restore the cursor position */
+                FLUSH_TEXT();
+                uv__tty_restore_state(handle, 0, error);
+                break;
+            }
+          }
+
+          /* Sequence ended - go back to normal state. */
+          ansi_parser_state = ANSI_NORMAL;
+          continue;
+
+        } else {
+          /* We don't support commands that use private mode characters or
+           * intermediaries. Ignore the rest of the sequence. */
+          ansi_parser_state = ANSI_IGNORE;
+          continue;
+        }
+
+      } else if (ansi_parser_state & ANSI_ST_CONTROL) {
+        /* Unsupported control code.
+         * Ignore everything until we see `BEL` or `ESC \`. */
+        if (ansi_parser_state & ANSI_IN_STRING) {
+          if (!(ansi_parser_state & ANSI_BACKSLASH_SEEN)) {
+            if (utf8_codepoint == '"') {
+              ansi_parser_state &= ~ANSI_IN_STRING;
+            } else if (utf8_codepoint == '\\') {
+              ansi_parser_state |= ANSI_BACKSLASH_SEEN;
+            }
+          } else {
+            ansi_parser_state &= ~ANSI_BACKSLASH_SEEN;
+          }
+        } else {
+          if (utf8_codepoint == '\007' || (utf8_codepoint == '\\' &&
+              (ansi_parser_state & ANSI_ESCAPE_SEEN))) {
+            /* End of sequence */
+            ansi_parser_state = ANSI_NORMAL;
+          } else if (utf8_codepoint == '\033') {
+            /* Escape character */
+            ansi_parser_state |= ANSI_ESCAPE_SEEN;
+          } else if (utf8_codepoint == '"') {
+             /* String starting */
+            ansi_parser_state |= ANSI_IN_STRING;
+            ansi_parser_state &= ~ANSI_ESCAPE_SEEN;
+            ansi_parser_state &= ~ANSI_BACKSLASH_SEEN;
+          } else {
+            ansi_parser_state &= ~ANSI_ESCAPE_SEEN;
+          }
+        }
+        continue;
+      } else {
+        /* Inconsistent state */
+        abort();
+      }
+
+      if (utf8_codepoint == 0x0a || utf8_codepoint == 0x0d) {
+        /* EOL conversion - emit \r\n when we see \n. */
+
+        if (utf8_codepoint == 0x0a && previous_eol != 0x0d) {
+          /* \n was not preceded by \r; print \r\n. */
+          ENSURE_BUFFER_SPACE(2);
+          utf16_buf[utf16_buf_used++] = L'\r';
+          utf16_buf[utf16_buf_used++] = L'\n';
+        } else if (utf8_codepoint == 0x0d && previous_eol == 0x0a) {
+          /* \n was followed by \r; do not print the \r, since the source was
+           * either \r\n\r (so the second \r is redundant) or was \n\r (so the
+           * \n was processed by the last case and an \r automatically
+           * inserted). */
+        } else {
+          /* \r without \n; print \r as-is. */
+          ENSURE_BUFFER_SPACE(1);
+          utf16_buf[utf16_buf_used++] = (WCHAR) utf8_codepoint;
+        }
+
+        previous_eol = (char) utf8_codepoint;
+
+      } else if (utf8_codepoint <= 0xffff) {
+        /* Encode character into utf-16 buffer. */
+        ENSURE_BUFFER_SPACE(1);
+        utf16_buf[utf16_buf_used++] = (WCHAR) utf8_codepoint;
+        previous_eol = 0;
+      } else {
+        ENSURE_BUFFER_SPACE(2);
+        utf8_codepoint -= 0x10000;
+        utf16_buf[utf16_buf_used++] = (WCHAR) (utf8_codepoint / 0x400 + 0xD800);
+        utf16_buf[utf16_buf_used++] = (WCHAR) (utf8_codepoint % 0x400 + 0xDC00);
+        previous_eol = 0;
+      }
+    }
+  }
+
+  /* Flush remaining characters */
+  FLUSH_TEXT();
+
+  /* Copy cached values back to struct. */
+  handle->tty.wr.utf8_bytes_left = utf8_bytes_left;
+  handle->tty.wr.utf8_codepoint = utf8_codepoint;
+  handle->tty.wr.previous_eol = previous_eol;
+  handle->tty.wr.ansi_parser_state = ansi_parser_state;
+
+  uv_sem_post(&uv_tty_output_lock);
+
+  if (*error == STATUS_SUCCESS) {
+    return 0;
+  } else {
+    return -1;
+  }
+
+#undef FLUSH_TEXT
+}
+
+
+int uv__tty_write(uv_loop_t* loop,
+                 uv_write_t* req,
+                 uv_tty_t* handle,
+                 const uv_buf_t bufs[],
+                 unsigned int nbufs,
+                 uv_write_cb cb) {
+  DWORD error;
+
+  UV_REQ_INIT(req, UV_WRITE);
+  req->handle = (uv_stream_t*) handle;
+  req->cb = cb;
+
+  handle->reqs_pending++;
+  handle->stream.conn.write_reqs_pending++;
+  REGISTER_HANDLE_REQ(loop, handle, req);
+
+  req->u.io.queued_bytes = 0;
+
+  if (!uv__tty_write_bufs(handle, bufs, nbufs, &error)) {
+    SET_REQ_SUCCESS(req);
+  } else {
+    SET_REQ_ERROR(req, error);
+  }
+
+  uv__insert_pending_req(loop, (uv_req_t*) req);
+
+  return 0;
+}
+
+
+int uv__tty_try_write(uv_tty_t* handle,
+                      const uv_buf_t bufs[],
+                      unsigned int nbufs) {
+  DWORD error;
+
+  if (handle->stream.conn.write_reqs_pending > 0)
+    return UV_EAGAIN;
+
+  if (uv__tty_write_bufs(handle, bufs, nbufs, &error))
+    return uv_translate_sys_error(error);
+
+  return uv__count_bufs(bufs, nbufs);
+}
+
+
+void uv__process_tty_write_req(uv_loop_t* loop, uv_tty_t* handle,
+  uv_write_t* req) {
+  int err;
+
+  handle->write_queue_size -= req->u.io.queued_bytes;
+  UNREGISTER_HANDLE_REQ(loop, handle, req);
+
+  if (req->cb) {
+    err = GET_REQ_ERROR(req);
+    req->cb(req, uv_translate_sys_error(err));
+  }
+
+
+  handle->stream.conn.write_reqs_pending--;
+  if (handle->stream.conn.write_reqs_pending == 0)
+    if (handle->flags & UV_HANDLE_SHUTTING)
+      uv__process_tty_shutdown_req(loop,
+                                   handle,
+                                   handle->stream.conn.shutdown_req);
+
+  DECREASE_PENDING_REQ_COUNT(handle);
+}
+
+
+void uv__tty_close(uv_tty_t* handle) {
+  assert(handle->u.fd == -1 || handle->u.fd > 2);
+  if (handle->flags & UV_HANDLE_READING)
+    uv__tty_read_stop(handle);
+
+  if (handle->u.fd == -1)
+    CloseHandle(handle->handle);
+  else
+    close(handle->u.fd);
+
+  handle->u.fd = -1;
+  handle->handle = INVALID_HANDLE_VALUE;
+  handle->flags &= ~(UV_HANDLE_READABLE | UV_HANDLE_WRITABLE);
+  uv__handle_closing(handle);
+
+  if (handle->reqs_pending == 0)
+    uv__want_endgame(handle->loop, (uv_handle_t*) handle);
+}
+
+
+void uv__process_tty_shutdown_req(uv_loop_t* loop, uv_tty_t* stream, uv_shutdown_t* req) {
+  assert(stream->stream.conn.write_reqs_pending == 0);
+  assert(req);
+
+  stream->stream.conn.shutdown_req = NULL;
+  stream->flags &= ~UV_HANDLE_SHUTTING;
+  UNREGISTER_HANDLE_REQ(loop, stream, req);
+
+  /* TTY shutdown is really just a no-op */
+  if (req->cb) {
+    if (stream->flags & UV_HANDLE_CLOSING) {
+      req->cb(req, UV_ECANCELED);
+    } else {
+      req->cb(req, 0);
+    }
+  }
+
+  DECREASE_PENDING_REQ_COUNT(stream);
+}
+
+
+void uv__tty_endgame(uv_loop_t* loop, uv_tty_t* handle) {
+  assert(handle->flags & UV_HANDLE_CLOSING);
+  assert(handle->reqs_pending == 0);
+
+  /* The wait handle used for raw reading should be unregistered when the
+   * wait callback runs. */
+  assert(!(handle->flags & UV_HANDLE_TTY_READABLE) ||
+         handle->tty.rd.read_raw_wait == NULL);
+
+  assert(!(handle->flags & UV_HANDLE_CLOSED));
+  uv__handle_close(handle);
+}
+
+
+/*
+ * uv__process_tty_accept_req() is a stub to keep DELEGATE_STREAM_REQ working
+ * TODO: find a way to remove it
+ */
+void uv__process_tty_accept_req(uv_loop_t* loop, uv_tty_t* handle,
+    uv_req_t* raw_req) {
+  abort();
+}
+
+
+/*
+ * uv__process_tty_connect_req() is a stub to keep DELEGATE_STREAM_REQ working
+ * TODO: find a way to remove it
+ */
+void uv__process_tty_connect_req(uv_loop_t* loop, uv_tty_t* handle,
+    uv_connect_t* req) {
+  abort();
+}
+
+
+int uv_tty_reset_mode(void) {
+  /* Not necessary to do anything. */
+  return 0;
+}
+
+/* Determine whether or not this version of windows supports
+ * proper ANSI color codes. Should be supported as of windows
+ * 10 version 1511, build number 10.0.10586.
+ */
+static void uv__determine_vterm_state(HANDLE handle) {
+  DWORD dwMode = 0;
+
+  uv__need_check_vterm_state = FALSE;
+  if (!GetConsoleMode(handle, &dwMode)) {
+    return;
+  }
+
+  dwMode |= ENABLE_VIRTUAL_TERMINAL_PROCESSING;
+  if (!SetConsoleMode(handle, dwMode)) {
+    return;
+  }
+
+  uv__vterm_state = UV_TTY_SUPPORTED;
+}
+
+static DWORD WINAPI uv__tty_console_resize_message_loop_thread(void* param) {
+  NTSTATUS status;
+  ULONG_PTR conhost_pid;
+  MSG msg;
+
+  if (pSetWinEventHook == NULL || pNtQueryInformationProcess == NULL)
+    return 0;
+
+  status = pNtQueryInformationProcess(GetCurrentProcess(),
+                                      ProcessConsoleHostProcess,
+                                      &conhost_pid,
+                                      sizeof(conhost_pid),
+                                      NULL);
+
+  if (!NT_SUCCESS(status)) {
+    /* We couldn't retrieve our console host process, probably because this
+     * is a 32-bit process running on 64-bit Windows. Fall back to receiving
+     * console events from the input stream only. */
+    return 0;
+  }
+
+  /* Ensure the PID is a multiple of 4, which is required by SetWinEventHook */
+  conhost_pid &= ~(ULONG_PTR)0x3;
+
+  uv__tty_console_resized = CreateEvent(NULL, TRUE, FALSE, NULL);
+  if (uv__tty_console_resized == NULL)
+    return 0;
+  if (QueueUserWorkItem(uv__tty_console_resize_watcher_thread,
+                        NULL,
+                        WT_EXECUTELONGFUNCTION) == 0)
+    return 0;
+
+  if (!pSetWinEventHook(EVENT_CONSOLE_LAYOUT,
+                        EVENT_CONSOLE_LAYOUT,
+                        NULL,
+                        uv__tty_console_resize_event,
+                        (DWORD)conhost_pid,
+                        0,
+                        WINEVENT_OUTOFCONTEXT))
+    return 0;
+
+  while (GetMessage(&msg, NULL, 0, 0)) {
+    TranslateMessage(&msg);
+    DispatchMessage(&msg);
+  }
+  return 0;
+}
+
+static void CALLBACK uv__tty_console_resize_event(HWINEVENTHOOK hWinEventHook,
+                                                  DWORD event,
+                                                  HWND hwnd,
+                                                  LONG idObject,
+                                                  LONG idChild,
+                                                  DWORD dwEventThread,
+                                                  DWORD dwmsEventTime) {
+  SetEvent(uv__tty_console_resized);
+}
+
+static DWORD WINAPI uv__tty_console_resize_watcher_thread(void* param) {
+  for (;;) {
+    /* Make sure to not overwhelm the system with resize events */
+    Sleep(33);
+    WaitForSingleObject(uv__tty_console_resized, INFINITE);
+    uv__tty_console_signal_resize();
+    ResetEvent(uv__tty_console_resized);
+  }
+  return 0;
+}
+
+static void uv__tty_console_signal_resize(void) {
+  CONSOLE_SCREEN_BUFFER_INFO sb_info;
+  int width, height;
+
+  if (!GetConsoleScreenBufferInfo(uv__tty_console_handle, &sb_info))
+    return;
+
+  width = sb_info.dwSize.X;
+  height = sb_info.srWindow.Bottom - sb_info.srWindow.Top + 1;
+
+  uv_mutex_lock(&uv__tty_console_resize_mutex);
+  assert(uv__tty_console_width != -1 && uv__tty_console_height != -1);
+  if (width != uv__tty_console_width || height != uv__tty_console_height) {
+    uv__tty_console_width = width;
+    uv__tty_console_height = height;
+    uv_mutex_unlock(&uv__tty_console_resize_mutex);
+    uv__signal_dispatch(SIGWINCH);
+  } else {
+    uv_mutex_unlock(&uv__tty_console_resize_mutex);
+  }
+}
+
+void uv_tty_set_vterm_state(uv_tty_vtermstate_t state) {
+  uv_sem_wait(&uv_tty_output_lock);
+  uv__need_check_vterm_state = FALSE;
+  uv__vterm_state = state;
+  uv_sem_post(&uv_tty_output_lock);
+}
+
+int uv_tty_get_vterm_state(uv_tty_vtermstate_t* state) {
+  uv_sem_wait(&uv_tty_output_lock);
+  *state = uv__vterm_state;
+  uv_sem_post(&uv_tty_output_lock);
+  return 0;
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/udp.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/udp.cpp
new file mode 100644
index 0000000..eaebc1e
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/udp.cpp
@@ -0,0 +1,1182 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <assert.h>
+#include <stdlib.h>
+
+#include "uv.h"
+#include "internal.h"
+#include "handle-inl.h"
+#include "stream-inl.h"
+#include "req-inl.h"
+
+
+/*
+ * Threshold of active udp streams for which to preallocate udp read buffers.
+ */
+const unsigned int uv_active_udp_streams_threshold = 0;
+
+/* A zero-size buffer for use by uv_udp_read */
+static char uv_zero_[] = "";
+int uv_udp_getpeername(const uv_udp_t* handle,
+                       struct sockaddr* name,
+                       int* namelen) {
+
+  return uv__getsockpeername((const uv_handle_t*) handle,
+                             getpeername,
+                             name,
+                             namelen,
+                             0);
+}
+
+
+int uv_udp_getsockname(const uv_udp_t* handle,
+                       struct sockaddr* name,
+                       int* namelen) {
+
+  return uv__getsockpeername((const uv_handle_t*) handle,
+                             getsockname,
+                             name,
+                             namelen,
+                             0);
+}
+
+
+static int uv__udp_set_socket(uv_loop_t* loop, uv_udp_t* handle, SOCKET socket,
+    int family) {
+  DWORD yes = 1;
+  WSAPROTOCOL_INFOW info;
+  int opt_len;
+
+  if (handle->socket != INVALID_SOCKET)
+    return UV_EBUSY;
+
+  /* Set the socket to nonblocking mode */
+  if (ioctlsocket(socket, FIONBIO, &yes) == SOCKET_ERROR) {
+    return WSAGetLastError();
+  }
+
+  /* Make the socket non-inheritable */
+  if (!SetHandleInformation((HANDLE)socket, HANDLE_FLAG_INHERIT, 0)) {
+    return GetLastError();
+  }
+
+  /* Associate it with the I/O completion port. Use uv_handle_t pointer as
+   * completion key. */
+  if (CreateIoCompletionPort((HANDLE)socket,
+                             loop->iocp,
+                             (ULONG_PTR)socket,
+                             0) == NULL) {
+    return GetLastError();
+  }
+
+  /* All known Windows that support SetFileCompletionNotificationModes have a
+   * bug that makes it impossible to use this function in conjunction with
+   * datagram sockets. We can work around that but only if the user is using
+   * the default UDP driver (AFD) and has no other. LSPs stacked on top. Here
+   * we check whether that is the case. */
+  opt_len = (int) sizeof info;
+  if (getsockopt(
+          socket, SOL_SOCKET, SO_PROTOCOL_INFOW, (char*) &info, &opt_len) ==
+      SOCKET_ERROR) {
+    return GetLastError();
+  }
+
+  if (info.ProtocolChain.ChainLen == 1) {
+    if (SetFileCompletionNotificationModes(
+            (HANDLE) socket,
+            FILE_SKIP_SET_EVENT_ON_HANDLE |
+                FILE_SKIP_COMPLETION_PORT_ON_SUCCESS)) {
+      handle->flags |= UV_HANDLE_SYNC_BYPASS_IOCP;
+      handle->func_wsarecv = uv__wsarecv_workaround;
+      handle->func_wsarecvfrom = uv__wsarecvfrom_workaround;
+    } else if (GetLastError() != ERROR_INVALID_FUNCTION) {
+      return GetLastError();
+    }
+  }
+
+  handle->socket = socket;
+
+  if (family == AF_INET6) {
+    handle->flags |= UV_HANDLE_IPV6;
+  } else {
+    assert(!(handle->flags & UV_HANDLE_IPV6));
+  }
+
+  return 0;
+}
+
+
+int uv__udp_init_ex(uv_loop_t* loop,
+                    uv_udp_t* handle,
+                    unsigned flags,
+                    int domain) {
+  uv__handle_init(loop, (uv_handle_t*) handle, UV_UDP);
+  handle->socket = INVALID_SOCKET;
+  handle->reqs_pending = 0;
+  handle->activecnt = 0;
+  handle->func_wsarecv = WSARecv;
+  handle->func_wsarecvfrom = WSARecvFrom;
+  handle->send_queue_size = 0;
+  handle->send_queue_count = 0;
+  UV_REQ_INIT(&handle->recv_req, UV_UDP_RECV);
+  handle->recv_req.data = handle;
+
+  /* If anything fails beyond this point we need to remove the handle from
+   * the handle queue, since it was added by uv__handle_init.
+   */
+
+  if (domain != AF_UNSPEC) {
+    SOCKET sock;
+    DWORD err;
+
+    sock = socket(domain, SOCK_DGRAM, 0);
+    if (sock == INVALID_SOCKET) {
+      err = WSAGetLastError();
+      QUEUE_REMOVE(&handle->handle_queue);
+      return uv_translate_sys_error(err);
+    }
+
+    err = uv__udp_set_socket(handle->loop, handle, sock, domain);
+    if (err) {
+      closesocket(sock);
+      QUEUE_REMOVE(&handle->handle_queue);
+      return uv_translate_sys_error(err);
+    }
+  }
+
+  return 0;
+}
+
+
+void uv__udp_close(uv_loop_t* loop, uv_udp_t* handle) {
+  uv_udp_recv_stop(handle);
+  closesocket(handle->socket);
+  handle->socket = INVALID_SOCKET;
+
+  uv__handle_closing(handle);
+
+  if (handle->reqs_pending == 0) {
+    uv__want_endgame(loop, (uv_handle_t*) handle);
+  }
+}
+
+
+void uv__udp_endgame(uv_loop_t* loop, uv_udp_t* handle) {
+  if (handle->flags & UV_HANDLE_CLOSING &&
+      handle->reqs_pending == 0) {
+    assert(!(handle->flags & UV_HANDLE_CLOSED));
+    uv__handle_close(handle);
+  }
+}
+
+
+int uv_udp_using_recvmmsg(const uv_udp_t* handle) {
+  return 0;
+}
+
+
+static int uv__udp_maybe_bind(uv_udp_t* handle,
+                              const struct sockaddr* addr,
+                              unsigned int addrlen,
+                              unsigned int flags) {
+  int r;
+  int err;
+  DWORD no = 0;
+
+  if (handle->flags & UV_HANDLE_BOUND)
+    return 0;
+
+  if ((flags & UV_UDP_IPV6ONLY) && addr->sa_family != AF_INET6) {
+    /* UV_UDP_IPV6ONLY is supported only for IPV6 sockets */
+    return ERROR_INVALID_PARAMETER;
+  }
+
+  if (handle->socket == INVALID_SOCKET) {
+    SOCKET sock = socket(addr->sa_family, SOCK_DGRAM, 0);
+    if (sock == INVALID_SOCKET) {
+      return WSAGetLastError();
+    }
+
+    err = uv__udp_set_socket(handle->loop, handle, sock, addr->sa_family);
+    if (err) {
+      closesocket(sock);
+      return err;
+    }
+  }
+
+  if (flags & UV_UDP_REUSEADDR) {
+    DWORD yes = 1;
+    /* Set SO_REUSEADDR on the socket. */
+    if (setsockopt(handle->socket,
+                   SOL_SOCKET,
+                   SO_REUSEADDR,
+                   (char*) &yes,
+                   sizeof yes) == SOCKET_ERROR) {
+      err = WSAGetLastError();
+      return err;
+    }
+  }
+
+  if (addr->sa_family == AF_INET6)
+    handle->flags |= UV_HANDLE_IPV6;
+
+  if (addr->sa_family == AF_INET6 && !(flags & UV_UDP_IPV6ONLY)) {
+    /* On windows IPV6ONLY is on by default. If the user doesn't specify it
+     * libuv turns it off. */
+
+    /* TODO: how to handle errors? This may fail if there is no ipv4 stack
+     * available, or when run on XP/2003 which have no support for dualstack
+     * sockets. For now we're silently ignoring the error. */
+    setsockopt(handle->socket,
+               IPPROTO_IPV6,
+               IPV6_V6ONLY,
+               (char*) &no,
+               sizeof no);
+  }
+
+  r = bind(handle->socket, addr, addrlen);
+  if (r == SOCKET_ERROR) {
+    return WSAGetLastError();
+  }
+
+  handle->flags |= UV_HANDLE_BOUND;
+
+  return 0;
+}
+
+
+static void uv__udp_queue_recv(uv_loop_t* loop, uv_udp_t* handle) {
+  uv_req_t* req;
+  uv_buf_t buf;
+  DWORD bytes, flags;
+  int result;
+
+  assert(handle->flags & UV_HANDLE_READING);
+  assert(!(handle->flags & UV_HANDLE_READ_PENDING));
+
+  req = &handle->recv_req;
+  memset(&req->u.io.overlapped, 0, sizeof(req->u.io.overlapped));
+
+  /*
+   * Preallocate a read buffer if the number of active streams is below
+   * the threshold.
+  */
+  if (loop->active_udp_streams < uv_active_udp_streams_threshold) {
+    handle->flags &= ~UV_HANDLE_ZERO_READ;
+
+    handle->recv_buffer = uv_buf_init(NULL, 0);
+    handle->alloc_cb((uv_handle_t*) handle, UV__UDP_DGRAM_MAXSIZE, &handle->recv_buffer);
+    if (handle->recv_buffer.base == NULL || handle->recv_buffer.len == 0) {
+      handle->recv_cb(handle, UV_ENOBUFS, &handle->recv_buffer, NULL, 0);
+      return;
+    }
+    assert(handle->recv_buffer.base != NULL);
+
+    buf = handle->recv_buffer;
+    memset(&handle->recv_from, 0, sizeof handle->recv_from);
+    handle->recv_from_len = sizeof handle->recv_from;
+    flags = 0;
+
+    result = handle->func_wsarecvfrom(handle->socket,
+                                      (WSABUF*) &buf,
+                                      1,
+                                      &bytes,
+                                      &flags,
+                                      (struct sockaddr*) &handle->recv_from,
+                                      &handle->recv_from_len,
+                                      &req->u.io.overlapped,
+                                      NULL);
+
+    if (UV_SUCCEEDED_WITHOUT_IOCP(result == 0)) {
+      /* Process the req without IOCP. */
+      handle->flags |= UV_HANDLE_READ_PENDING;
+      req->u.io.overlapped.InternalHigh = bytes;
+      handle->reqs_pending++;
+      uv__insert_pending_req(loop, req);
+    } else if (UV_SUCCEEDED_WITH_IOCP(result == 0)) {
+      /* The req will be processed with IOCP. */
+      handle->flags |= UV_HANDLE_READ_PENDING;
+      handle->reqs_pending++;
+    } else {
+      /* Make this req pending reporting an error. */
+      SET_REQ_ERROR(req, WSAGetLastError());
+      uv__insert_pending_req(loop, req);
+      handle->reqs_pending++;
+    }
+
+  } else {
+    handle->flags |= UV_HANDLE_ZERO_READ;
+
+    buf.base = (char*) uv_zero_;
+    buf.len = 0;
+    flags = MSG_PEEK;
+
+    result = handle->func_wsarecv(handle->socket,
+                                  (WSABUF*) &buf,
+                                  1,
+                                  &bytes,
+                                  &flags,
+                                  &req->u.io.overlapped,
+                                  NULL);
+
+    if (UV_SUCCEEDED_WITHOUT_IOCP(result == 0)) {
+      /* Process the req without IOCP. */
+      handle->flags |= UV_HANDLE_READ_PENDING;
+      req->u.io.overlapped.InternalHigh = bytes;
+      handle->reqs_pending++;
+      uv__insert_pending_req(loop, req);
+    } else if (UV_SUCCEEDED_WITH_IOCP(result == 0)) {
+      /* The req will be processed with IOCP. */
+      handle->flags |= UV_HANDLE_READ_PENDING;
+      handle->reqs_pending++;
+    } else {
+      /* Make this req pending reporting an error. */
+      SET_REQ_ERROR(req, WSAGetLastError());
+      uv__insert_pending_req(loop, req);
+      handle->reqs_pending++;
+    }
+  }
+}
+
+
+int uv__udp_recv_start(uv_udp_t* handle, uv_alloc_cb alloc_cb,
+    uv_udp_recv_cb recv_cb) {
+  uv_loop_t* loop = handle->loop;
+  int err;
+
+  if (handle->flags & UV_HANDLE_READING) {
+    return UV_EALREADY;
+  }
+
+  err = uv__udp_maybe_bind(handle,
+                           (const struct sockaddr*) &uv_addr_ip4_any_,
+                           sizeof(uv_addr_ip4_any_),
+                           0);
+  if (err)
+    return uv_translate_sys_error(err);
+
+  handle->flags |= UV_HANDLE_READING;
+  INCREASE_ACTIVE_COUNT(loop, handle);
+  loop->active_udp_streams++;
+
+  handle->recv_cb = recv_cb;
+  handle->alloc_cb = alloc_cb;
+
+  /* If reading was stopped and then started again, there could still be a recv
+   * request pending. */
+  if (!(handle->flags & UV_HANDLE_READ_PENDING))
+    uv__udp_queue_recv(loop, handle);
+
+  return 0;
+}
+
+
+int uv__udp_recv_stop(uv_udp_t* handle) {
+  if (handle->flags & UV_HANDLE_READING) {
+    handle->flags &= ~UV_HANDLE_READING;
+    handle->loop->active_udp_streams--;
+    DECREASE_ACTIVE_COUNT(loop, handle);
+  }
+
+  return 0;
+}
+
+
+static int uv__send(uv_udp_send_t* req,
+                    uv_udp_t* handle,
+                    const uv_buf_t bufs[],
+                    unsigned int nbufs,
+                    const struct sockaddr* addr,
+                    unsigned int addrlen,
+                    uv_udp_send_cb cb) {
+  uv_loop_t* loop = handle->loop;
+  DWORD result, bytes;
+
+  UV_REQ_INIT(req, UV_UDP_SEND);
+  req->handle = handle;
+  req->cb = cb;
+  memset(&req->u.io.overlapped, 0, sizeof(req->u.io.overlapped));
+
+  result = WSASendTo(handle->socket,
+                     (WSABUF*)bufs,
+                     nbufs,
+                     &bytes,
+                     0,
+                     addr,
+                     addrlen,
+                     &req->u.io.overlapped,
+                     NULL);
+
+  if (UV_SUCCEEDED_WITHOUT_IOCP(result == 0)) {
+    /* Request completed immediately. */
+    req->u.io.queued_bytes = 0;
+    handle->reqs_pending++;
+    handle->send_queue_size += req->u.io.queued_bytes;
+    handle->send_queue_count++;
+    REGISTER_HANDLE_REQ(loop, handle, req);
+    uv__insert_pending_req(loop, (uv_req_t*)req);
+  } else if (UV_SUCCEEDED_WITH_IOCP(result == 0)) {
+    /* Request queued by the kernel. */
+    req->u.io.queued_bytes = uv__count_bufs(bufs, nbufs);
+    handle->reqs_pending++;
+    handle->send_queue_size += req->u.io.queued_bytes;
+    handle->send_queue_count++;
+    REGISTER_HANDLE_REQ(loop, handle, req);
+  } else {
+    /* Send failed due to an error. */
+    return WSAGetLastError();
+  }
+
+  return 0;
+}
+
+
+void uv__process_udp_recv_req(uv_loop_t* loop, uv_udp_t* handle,
+    uv_req_t* req) {
+  uv_buf_t buf;
+  int partial;
+
+  assert(handle->type == UV_UDP);
+
+  handle->flags &= ~UV_HANDLE_READ_PENDING;
+
+  if (!REQ_SUCCESS(req)) {
+    DWORD err = GET_REQ_SOCK_ERROR(req);
+    if (err == WSAEMSGSIZE) {
+      /* Not a real error, it just indicates that the received packet was
+       * bigger than the receive buffer. */
+    } else if (err == WSAECONNRESET || err == WSAENETRESET) {
+      /* A previous sendto operation failed; ignore this error. If zero-reading
+       * we need to call WSARecv/WSARecvFrom _without_ the. MSG_PEEK flag to
+       * clear out the error queue. For nonzero reads, immediately queue a new
+       * receive. */
+      if (!(handle->flags & UV_HANDLE_ZERO_READ)) {
+        goto done;
+      }
+    } else {
+      /* A real error occurred. Report the error to the user only if we're
+       * currently reading. */
+      if (handle->flags & UV_HANDLE_READING) {
+        uv_udp_recv_stop(handle);
+        buf = (handle->flags & UV_HANDLE_ZERO_READ) ?
+              uv_buf_init(NULL, 0) : handle->recv_buffer;
+        handle->recv_cb(handle, uv_translate_sys_error(err), &buf, NULL, 0);
+      }
+      goto done;
+    }
+  }
+
+  if (!(handle->flags & UV_HANDLE_ZERO_READ)) {
+    /* Successful read */
+    partial = !REQ_SUCCESS(req);
+    handle->recv_cb(handle,
+                    req->u.io.overlapped.InternalHigh,
+                    &handle->recv_buffer,
+                    (const struct sockaddr*) &handle->recv_from,
+                    partial ? UV_UDP_PARTIAL : 0);
+  } else if (handle->flags & UV_HANDLE_READING) {
+    DWORD bytes, err, flags;
+    struct sockaddr_storage from;
+    int from_len;
+
+    /* Do a nonblocking receive.
+     * TODO: try to read multiple datagrams at once. FIONREAD maybe? */
+    buf = uv_buf_init(NULL, 0);
+    handle->alloc_cb((uv_handle_t*) handle, UV__UDP_DGRAM_MAXSIZE, &buf);
+    if (buf.base == NULL || buf.len == 0) {
+      handle->recv_cb(handle, UV_ENOBUFS, &buf, NULL, 0);
+      goto done;
+    }
+    assert(buf.base != NULL);
+
+    memset(&from, 0, sizeof from);
+    from_len = sizeof from;
+
+    flags = 0;
+
+    if (WSARecvFrom(handle->socket,
+                    (WSABUF*)&buf,
+                    1,
+                    &bytes,
+                    &flags,
+                    (struct sockaddr*) &from,
+                    &from_len,
+                    NULL,
+                    NULL) != SOCKET_ERROR) {
+
+      /* Message received */
+      handle->recv_cb(handle, bytes, &buf, (const struct sockaddr*) &from, 0);
+    } else {
+      err = WSAGetLastError();
+      if (err == WSAEMSGSIZE) {
+        /* Message truncated */
+        handle->recv_cb(handle,
+                        bytes,
+                        &buf,
+                        (const struct sockaddr*) &from,
+                        UV_UDP_PARTIAL);
+      } else if (err == WSAEWOULDBLOCK) {
+        /* Kernel buffer empty */
+        handle->recv_cb(handle, 0, &buf, NULL, 0);
+      } else if (err == WSAECONNRESET || err == WSAENETRESET) {
+        /* WSAECONNRESET/WSANETRESET is ignored because this just indicates
+         * that a previous sendto operation failed.
+         */
+        handle->recv_cb(handle, 0, &buf, NULL, 0);
+      } else {
+        /* Any other error that we want to report back to the user. */
+        uv_udp_recv_stop(handle);
+        handle->recv_cb(handle, uv_translate_sys_error(err), &buf, NULL, 0);
+      }
+    }
+  }
+
+done:
+  /* Post another read if still reading and not closing. */
+  if ((handle->flags & UV_HANDLE_READING) &&
+      !(handle->flags & UV_HANDLE_READ_PENDING)) {
+    uv__udp_queue_recv(loop, handle);
+  }
+
+  DECREASE_PENDING_REQ_COUNT(handle);
+}
+
+
+void uv__process_udp_send_req(uv_loop_t* loop, uv_udp_t* handle,
+    uv_udp_send_t* req) {
+  int err;
+
+  assert(handle->type == UV_UDP);
+
+  assert(handle->send_queue_size >= req->u.io.queued_bytes);
+  assert(handle->send_queue_count >= 1);
+  handle->send_queue_size -= req->u.io.queued_bytes;
+  handle->send_queue_count--;
+
+  UNREGISTER_HANDLE_REQ(loop, handle, req);
+
+  if (req->cb) {
+    err = 0;
+    if (!REQ_SUCCESS(req)) {
+      err = GET_REQ_SOCK_ERROR(req);
+    }
+    req->cb(req, uv_translate_sys_error(err));
+  }
+
+  DECREASE_PENDING_REQ_COUNT(handle);
+}
+
+
+static int uv__udp_set_membership4(uv_udp_t* handle,
+                                   const struct sockaddr_in* multicast_addr,
+                                   const char* interface_addr,
+                                   uv_membership membership) {
+  int err;
+  int optname;
+  struct ip_mreq mreq;
+
+  if (handle->flags & UV_HANDLE_IPV6)
+    return UV_EINVAL;
+
+  /* If the socket is unbound, bind to inaddr_any. */
+  err = uv__udp_maybe_bind(handle,
+                           (const struct sockaddr*) &uv_addr_ip4_any_,
+                           sizeof(uv_addr_ip4_any_),
+                           UV_UDP_REUSEADDR);
+  if (err)
+    return uv_translate_sys_error(err);
+
+  memset(&mreq, 0, sizeof mreq);
+
+  if (interface_addr) {
+    err = uv_inet_pton(AF_INET, interface_addr, &mreq.imr_interface.s_addr);
+    if (err)
+      return err;
+  } else {
+    mreq.imr_interface.s_addr = htonl(INADDR_ANY);
+  }
+
+  mreq.imr_multiaddr.s_addr = multicast_addr->sin_addr.s_addr;
+
+  switch (membership) {
+    case UV_JOIN_GROUP:
+      optname = IP_ADD_MEMBERSHIP;
+      break;
+    case UV_LEAVE_GROUP:
+      optname = IP_DROP_MEMBERSHIP;
+      break;
+    default:
+      return UV_EINVAL;
+  }
+
+  if (setsockopt(handle->socket,
+                 IPPROTO_IP,
+                 optname,
+                 (char*) &mreq,
+                 sizeof mreq) == SOCKET_ERROR) {
+    return uv_translate_sys_error(WSAGetLastError());
+  }
+
+  return 0;
+}
+
+
+int uv__udp_set_membership6(uv_udp_t* handle,
+                            const struct sockaddr_in6* multicast_addr,
+                            const char* interface_addr,
+                            uv_membership membership) {
+  int optname;
+  int err;
+  struct ipv6_mreq mreq;
+  struct sockaddr_in6 addr6;
+
+  if ((handle->flags & UV_HANDLE_BOUND) && !(handle->flags & UV_HANDLE_IPV6))
+    return UV_EINVAL;
+
+  err = uv__udp_maybe_bind(handle,
+                           (const struct sockaddr*) &uv_addr_ip6_any_,
+                           sizeof(uv_addr_ip6_any_),
+                           UV_UDP_REUSEADDR);
+
+  if (err)
+    return uv_translate_sys_error(err);
+
+  memset(&mreq, 0, sizeof(mreq));
+
+  if (interface_addr) {
+    if (uv_ip6_addr(interface_addr, 0, &addr6))
+      return UV_EINVAL;
+    mreq.ipv6mr_interface = addr6.sin6_scope_id;
+  } else {
+    mreq.ipv6mr_interface = 0;
+  }
+
+  mreq.ipv6mr_multiaddr = multicast_addr->sin6_addr;
+
+  switch (membership) {
+  case UV_JOIN_GROUP:
+    optname = IPV6_ADD_MEMBERSHIP;
+    break;
+  case UV_LEAVE_GROUP:
+    optname = IPV6_DROP_MEMBERSHIP;
+    break;
+  default:
+    return UV_EINVAL;
+  }
+
+  if (setsockopt(handle->socket,
+                 IPPROTO_IPV6,
+                 optname,
+                 (char*) &mreq,
+                 sizeof mreq) == SOCKET_ERROR) {
+    return uv_translate_sys_error(WSAGetLastError());
+  }
+
+  return 0;
+}
+
+
+static int uv__udp_set_source_membership4(uv_udp_t* handle,
+                                          const struct sockaddr_in* multicast_addr,
+                                          const char* interface_addr,
+                                          const struct sockaddr_in* source_addr,
+                                          uv_membership membership) {
+  struct ip_mreq_source mreq;
+  int optname;
+  int err;
+
+  if (handle->flags & UV_HANDLE_IPV6)
+    return UV_EINVAL;
+
+  /* If the socket is unbound, bind to inaddr_any. */
+  err = uv__udp_maybe_bind(handle,
+                           (const struct sockaddr*) &uv_addr_ip4_any_,
+                           sizeof(uv_addr_ip4_any_),
+                           UV_UDP_REUSEADDR);
+  if (err)
+    return uv_translate_sys_error(err);
+
+  memset(&mreq, 0, sizeof(mreq));
+
+  if (interface_addr != NULL) {
+    err = uv_inet_pton(AF_INET, interface_addr, &mreq.imr_interface.s_addr);
+    if (err)
+      return err;
+  } else {
+    mreq.imr_interface.s_addr = htonl(INADDR_ANY);
+  }
+
+  mreq.imr_multiaddr.s_addr = multicast_addr->sin_addr.s_addr;
+  mreq.imr_sourceaddr.s_addr = source_addr->sin_addr.s_addr;
+
+  if (membership == UV_JOIN_GROUP)
+    optname = IP_ADD_SOURCE_MEMBERSHIP;
+  else if (membership == UV_LEAVE_GROUP)
+    optname = IP_DROP_SOURCE_MEMBERSHIP;
+  else
+    return UV_EINVAL;
+
+  if (setsockopt(handle->socket,
+                 IPPROTO_IP,
+                 optname,
+                 (char*) &mreq,
+                 sizeof(mreq)) == SOCKET_ERROR) {
+    return uv_translate_sys_error(WSAGetLastError());
+  }
+
+  return 0;
+}
+
+
+int uv__udp_set_source_membership6(uv_udp_t* handle,
+                                   const struct sockaddr_in6* multicast_addr,
+                                   const char* interface_addr,
+                                   const struct sockaddr_in6* source_addr,
+                                   uv_membership membership) {
+  struct group_source_req mreq;
+  struct sockaddr_in6 addr6;
+  int optname;
+  int err;
+
+  STATIC_ASSERT(sizeof(mreq.gsr_group) >= sizeof(*multicast_addr));
+  STATIC_ASSERT(sizeof(mreq.gsr_source) >= sizeof(*source_addr));
+
+  if ((handle->flags & UV_HANDLE_BOUND) && !(handle->flags & UV_HANDLE_IPV6))
+    return UV_EINVAL;
+
+  err = uv__udp_maybe_bind(handle,
+                           (const struct sockaddr*) &uv_addr_ip6_any_,
+                           sizeof(uv_addr_ip6_any_),
+                           UV_UDP_REUSEADDR);
+
+  if (err)
+    return uv_translate_sys_error(err);
+
+  memset(&mreq, 0, sizeof(mreq));
+
+  if (interface_addr != NULL) {
+    err = uv_ip6_addr(interface_addr, 0, &addr6);
+    if (err)
+      return err;
+    mreq.gsr_interface = addr6.sin6_scope_id;
+  } else {
+    mreq.gsr_interface = 0;
+  }
+
+  memcpy(&mreq.gsr_group, multicast_addr, sizeof(*multicast_addr));
+  memcpy(&mreq.gsr_source, source_addr, sizeof(*source_addr));
+
+  if (membership == UV_JOIN_GROUP)
+    optname = MCAST_JOIN_SOURCE_GROUP;
+  else if (membership == UV_LEAVE_GROUP)
+    optname = MCAST_LEAVE_SOURCE_GROUP;
+  else
+    return UV_EINVAL;
+
+  if (setsockopt(handle->socket,
+                 IPPROTO_IPV6,
+                 optname,
+                 (char*) &mreq,
+                 sizeof(mreq)) == SOCKET_ERROR) {
+    return uv_translate_sys_error(WSAGetLastError());
+  }
+
+  return 0;
+}
+
+
+int uv_udp_set_membership(uv_udp_t* handle,
+                          const char* multicast_addr,
+                          const char* interface_addr,
+                          uv_membership membership) {
+  struct sockaddr_in addr4;
+  struct sockaddr_in6 addr6;
+
+  if (uv_ip4_addr(multicast_addr, 0, &addr4) == 0)
+    return uv__udp_set_membership4(handle, &addr4, interface_addr, membership);
+  else if (uv_ip6_addr(multicast_addr, 0, &addr6) == 0)
+    return uv__udp_set_membership6(handle, &addr6, interface_addr, membership);
+  else
+    return UV_EINVAL;
+}
+
+
+int uv_udp_set_source_membership(uv_udp_t* handle,
+                                 const char* multicast_addr,
+                                 const char* interface_addr,
+                                 const char* source_addr,
+                                 uv_membership membership) {
+  int err;
+  struct sockaddr_storage mcast_addr;
+  struct sockaddr_in* mcast_addr4;
+  struct sockaddr_in6* mcast_addr6;
+  struct sockaddr_storage src_addr;
+  struct sockaddr_in* src_addr4;
+  struct sockaddr_in6* src_addr6;
+
+  mcast_addr4 = (struct sockaddr_in*)&mcast_addr;
+  mcast_addr6 = (struct sockaddr_in6*)&mcast_addr;
+  src_addr4 = (struct sockaddr_in*)&src_addr;
+  src_addr6 = (struct sockaddr_in6*)&src_addr;
+
+  err = uv_ip4_addr(multicast_addr, 0, mcast_addr4);
+  if (err) {
+    err = uv_ip6_addr(multicast_addr, 0, mcast_addr6);
+    if (err)
+      return err;
+    err = uv_ip6_addr(source_addr, 0, src_addr6);
+    if (err)
+      return err;
+    return uv__udp_set_source_membership6(handle,
+                                          mcast_addr6,
+                                          interface_addr,
+                                          src_addr6,
+                                          membership);
+  }
+  
+  err = uv_ip4_addr(source_addr, 0, src_addr4);
+  if (err)
+    return err;
+  return uv__udp_set_source_membership4(handle,
+                                        mcast_addr4,
+                                        interface_addr,
+                                        src_addr4,
+                                        membership);
+}
+
+
+int uv_udp_set_multicast_interface(uv_udp_t* handle, const char* interface_addr) {
+  struct sockaddr_storage addr_st;
+  struct sockaddr_in* addr4;
+  struct sockaddr_in6* addr6;
+
+  addr4 = (struct sockaddr_in*) &addr_st;
+  addr6 = (struct sockaddr_in6*) &addr_st;
+
+  if (!interface_addr) {
+    memset(&addr_st, 0, sizeof addr_st);
+    if (handle->flags & UV_HANDLE_IPV6) {
+      addr_st.ss_family = AF_INET6;
+      addr6->sin6_scope_id = 0;
+    } else {
+      addr_st.ss_family = AF_INET;
+      addr4->sin_addr.s_addr = htonl(INADDR_ANY);
+    }
+  } else if (uv_ip4_addr(interface_addr, 0, addr4) == 0) {
+    /* nothing, address was parsed */
+  } else if (uv_ip6_addr(interface_addr, 0, addr6) == 0) {
+    /* nothing, address was parsed */
+  } else {
+    return UV_EINVAL;
+  }
+
+  if (handle->socket == INVALID_SOCKET)
+    return UV_EBADF;
+
+  if (addr_st.ss_family == AF_INET) {
+    if (setsockopt(handle->socket,
+                   IPPROTO_IP,
+                   IP_MULTICAST_IF,
+                   (char*) &addr4->sin_addr,
+                   sizeof(addr4->sin_addr)) == SOCKET_ERROR) {
+      return uv_translate_sys_error(WSAGetLastError());
+    }
+  } else if (addr_st.ss_family == AF_INET6) {
+    if (setsockopt(handle->socket,
+                   IPPROTO_IPV6,
+                   IPV6_MULTICAST_IF,
+                   (char*) &addr6->sin6_scope_id,
+                   sizeof(addr6->sin6_scope_id)) == SOCKET_ERROR) {
+      return uv_translate_sys_error(WSAGetLastError());
+    }
+  } else {
+    assert(0 && "unexpected address family");
+    abort();
+  }
+
+  return 0;
+}
+
+
+int uv_udp_set_broadcast(uv_udp_t* handle, int value) {
+  BOOL optval = (BOOL) value;
+
+  if (handle->socket == INVALID_SOCKET)
+    return UV_EBADF;
+
+  if (setsockopt(handle->socket,
+                 SOL_SOCKET,
+                 SO_BROADCAST,
+                 (char*) &optval,
+                 sizeof optval)) {
+    return uv_translate_sys_error(WSAGetLastError());
+  }
+
+  return 0;
+}
+
+
+int uv__udp_is_bound(uv_udp_t* handle) {
+  struct sockaddr_storage addr;
+  int addrlen;
+
+  addrlen = sizeof(addr);
+  if (uv_udp_getsockname(handle, (struct sockaddr*) &addr, &addrlen) != 0)
+    return 0;
+
+  return addrlen > 0;
+}
+
+
+int uv_udp_open(uv_udp_t* handle, uv_os_sock_t sock) {
+  WSAPROTOCOL_INFOW protocol_info;
+  int opt_len;
+  int err;
+
+  /* Detect the address family of the socket. */
+  opt_len = (int) sizeof protocol_info;
+  if (getsockopt(sock,
+                 SOL_SOCKET,
+                 SO_PROTOCOL_INFOW,
+                 (char*) &protocol_info,
+                 &opt_len) == SOCKET_ERROR) {
+    return uv_translate_sys_error(GetLastError());
+  }
+
+  err = uv__udp_set_socket(handle->loop,
+                           handle,
+                           sock,
+                           protocol_info.iAddressFamily);
+  if (err)
+    return uv_translate_sys_error(err);
+
+  if (uv__udp_is_bound(handle))
+    handle->flags |= UV_HANDLE_BOUND;
+
+  if (uv__udp_is_connected(handle))
+    handle->flags |= UV_HANDLE_UDP_CONNECTED;
+
+  return 0;
+}
+
+
+#define SOCKOPT_SETTER(name, option4, option6, validate)                      \
+  int uv_udp_set_##name(uv_udp_t* handle, int value) {                        \
+    DWORD optval = (DWORD) value;                                             \
+                                                                              \
+    if (!(validate(value))) {                                                 \
+      return UV_EINVAL;                                                       \
+    }                                                                         \
+                                                                              \
+    if (handle->socket == INVALID_SOCKET)                                     \
+      return UV_EBADF;                                                        \
+                                                                              \
+    if (!(handle->flags & UV_HANDLE_IPV6)) {                                  \
+      /* Set IPv4 socket option */                                            \
+      if (setsockopt(handle->socket,                                          \
+                     IPPROTO_IP,                                              \
+                     option4,                                                 \
+                     (char*) &optval,                                         \
+                     sizeof optval)) {                                        \
+        return uv_translate_sys_error(WSAGetLastError());                     \
+      }                                                                       \
+    } else {                                                                  \
+      /* Set IPv6 socket option */                                            \
+      if (setsockopt(handle->socket,                                          \
+                     IPPROTO_IPV6,                                            \
+                     option6,                                                 \
+                     (char*) &optval,                                         \
+                     sizeof optval)) {                                        \
+        return uv_translate_sys_error(WSAGetLastError());                     \
+      }                                                                       \
+    }                                                                         \
+    return 0;                                                                 \
+  }
+
+#define VALIDATE_TTL(value) ((value) >= 1 && (value) <= 255)
+#define VALIDATE_MULTICAST_TTL(value) ((value) >= -1 && (value) <= 255)
+#define VALIDATE_MULTICAST_LOOP(value) (1)
+
+SOCKOPT_SETTER(ttl,
+               IP_TTL,
+               IPV6_HOPLIMIT,
+               VALIDATE_TTL)
+SOCKOPT_SETTER(multicast_ttl,
+               IP_MULTICAST_TTL,
+               IPV6_MULTICAST_HOPS,
+               VALIDATE_MULTICAST_TTL)
+SOCKOPT_SETTER(multicast_loop,
+               IP_MULTICAST_LOOP,
+               IPV6_MULTICAST_LOOP,
+               VALIDATE_MULTICAST_LOOP)
+
+#undef SOCKOPT_SETTER
+#undef VALIDATE_TTL
+#undef VALIDATE_MULTICAST_TTL
+#undef VALIDATE_MULTICAST_LOOP
+
+
+/* This function is an egress point, i.e. it returns libuv errors rather than
+ * system errors.
+ */
+int uv__udp_bind(uv_udp_t* handle,
+                 const struct sockaddr* addr,
+                 unsigned int addrlen,
+                 unsigned int flags) {
+  int err;
+
+  err = uv__udp_maybe_bind(handle, addr, addrlen, flags);
+  if (err)
+    return uv_translate_sys_error(err);
+
+  return 0;
+}
+
+
+int uv__udp_connect(uv_udp_t* handle,
+                    const struct sockaddr* addr,
+                    unsigned int addrlen) {
+  const struct sockaddr* bind_addr;
+  int err;
+
+  if (!(handle->flags & UV_HANDLE_BOUND)) {
+    if (addrlen == sizeof(uv_addr_ip4_any_))
+      bind_addr = (const struct sockaddr*) &uv_addr_ip4_any_;
+    else if (addrlen == sizeof(uv_addr_ip6_any_))
+      bind_addr = (const struct sockaddr*) &uv_addr_ip6_any_;
+    else
+      return UV_EINVAL;
+
+    err = uv__udp_maybe_bind(handle, bind_addr, addrlen, 0);
+    if (err)
+      return uv_translate_sys_error(err);
+  }
+
+  err = connect(handle->socket, addr, addrlen);
+  if (err)
+    return uv_translate_sys_error(WSAGetLastError());
+
+  handle->flags |= UV_HANDLE_UDP_CONNECTED;
+
+  return 0;
+}
+
+
+int uv__udp_disconnect(uv_udp_t* handle) {
+    int err;
+    struct sockaddr_storage addr;
+
+    memset(&addr, 0, sizeof(addr));
+
+    err = connect(handle->socket, (struct sockaddr*) &addr, sizeof(addr));
+    if (err)
+      return uv_translate_sys_error(WSAGetLastError());
+
+    handle->flags &= ~UV_HANDLE_UDP_CONNECTED;
+    return 0;
+}
+
+
+/* This function is an egress point, i.e. it returns libuv errors rather than
+ * system errors.
+ */
+int uv__udp_send(uv_udp_send_t* req,
+                 uv_udp_t* handle,
+                 const uv_buf_t bufs[],
+                 unsigned int nbufs,
+                 const struct sockaddr* addr,
+                 unsigned int addrlen,
+                 uv_udp_send_cb send_cb) {
+  const struct sockaddr* bind_addr;
+  int err;
+
+  if (!(handle->flags & UV_HANDLE_BOUND)) {
+    if (addrlen == sizeof(uv_addr_ip4_any_))
+      bind_addr = (const struct sockaddr*) &uv_addr_ip4_any_;
+    else if (addrlen == sizeof(uv_addr_ip6_any_))
+      bind_addr = (const struct sockaddr*) &uv_addr_ip6_any_;
+    else
+      return UV_EINVAL;
+
+    err = uv__udp_maybe_bind(handle, bind_addr, addrlen, 0);
+    if (err)
+      return uv_translate_sys_error(err);
+  }
+
+  err = uv__send(req, handle, bufs, nbufs, addr, addrlen, send_cb);
+  if (err)
+    return uv_translate_sys_error(err);
+
+  return 0;
+}
+
+
+int uv__udp_try_send(uv_udp_t* handle,
+                     const uv_buf_t bufs[],
+                     unsigned int nbufs,
+                     const struct sockaddr* addr,
+                     unsigned int addrlen) {
+  DWORD bytes;
+  const struct sockaddr* bind_addr;
+  struct sockaddr_storage converted;
+  int err;
+
+  assert(nbufs > 0);
+
+  if (addr != NULL) {
+    err = uv__convert_to_localhost_if_unspecified(addr, &converted);
+    if (err)
+      return err;
+    addr = (const struct sockaddr*) &converted;
+  }
+
+  /* Already sending a message.*/
+  if (handle->send_queue_count != 0)
+    return UV_EAGAIN;
+
+  if (!(handle->flags & UV_HANDLE_BOUND)) {
+    if (addrlen == sizeof(uv_addr_ip4_any_))
+      bind_addr = (const struct sockaddr*) &uv_addr_ip4_any_;
+    else if (addrlen == sizeof(uv_addr_ip6_any_))
+      bind_addr = (const struct sockaddr*) &uv_addr_ip6_any_;
+    else
+      return UV_EINVAL;
+    err = uv__udp_maybe_bind(handle, bind_addr, addrlen, 0);
+    if (err)
+      return uv_translate_sys_error(err);
+  }
+
+  err = WSASendTo(handle->socket,
+                  (WSABUF*)bufs,
+                  nbufs,
+                  &bytes,
+                  0,
+                  addr,
+                  addrlen,
+                  NULL,
+                  NULL);
+
+  if (err)
+    return uv_translate_sys_error(WSAGetLastError());
+
+  return bytes;
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/util.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/util.cpp
new file mode 100644
index 0000000..d9888ae
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/util.cpp
@@ -0,0 +1,1918 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <assert.h>
+#include <direct.h>
+#include <limits.h>
+#include <stdio.h>
+#include <string.h>
+#include <time.h>
+#include <wchar.h>
+
+#include "uv.h"
+#include "internal.h"
+
+/* clang-format off */
+#include <winsock2.h>
+#include <winperf.h>
+#include <iphlpapi.h>
+#include <psapi.h>
+#include <tlhelp32.h>
+#include <windows.h>
+/* clang-format on */
+#include <userenv.h>
+#include <math.h>
+
+/*
+ * Max title length; the only thing MSDN tells us about the maximum length
+ * of the console title is that it is smaller than 64K. However in practice
+ * it is much smaller, and there is no way to figure out what the exact length
+ * of the title is or can be, at least not on XP. To make it even more
+ * annoying, GetConsoleTitle fails when the buffer to be read into is bigger
+ * than the actual maximum length. So we make a conservative guess here;
+ * just don't put the novel you're writing in the title, unless the plot
+ * survives truncation.
+ */
+#define MAX_TITLE_LENGTH 8192
+
+/* The number of nanoseconds in one second. */
+#define UV__NANOSEC 1000000000
+
+/* Max user name length, from iphlpapi.h */
+#ifndef UNLEN
+# define UNLEN 256
+#endif
+
+
+/* A RtlGenRandom() by any other name... */
+extern "C" {
+extern BOOLEAN NTAPI SystemFunction036(PVOID Buffer, ULONG BufferLength);
+}
+
+/* Cached copy of the process title, plus a mutex guarding it. */
+static char *process_title;
+static CRITICAL_SECTION process_title_lock;
+
+#pragma comment(lib, "Advapi32.lib")
+#pragma comment(lib, "IPHLPAPI.lib")
+#pragma comment(lib, "Psapi.lib")
+#pragma comment(lib, "Userenv.lib")
+#pragma comment(lib, "kernel32.lib")
+
+/* Frequency of the high-resolution clock. */
+static uint64_t hrtime_frequency_ = 0;
+
+
+/*
+ * One-time initialization code for functionality defined in util.c.
+ */
+void uv__util_init(void) {
+  LARGE_INTEGER perf_frequency;
+
+  /* Initialize process title access mutex. */
+  InitializeCriticalSection(&process_title_lock);
+
+  /* Retrieve high-resolution timer frequency
+   * and precompute its reciprocal.
+   */
+  if (QueryPerformanceFrequency(&perf_frequency)) {
+    hrtime_frequency_ = perf_frequency.QuadPart;
+  } else {
+    uv_fatal_error(GetLastError(), "QueryPerformanceFrequency");
+  }
+}
+
+
+int uv_exepath(char* buffer, size_t* size_ptr) {
+  int utf8_len, utf16_buffer_len, utf16_len;
+  WCHAR* utf16_buffer;
+  int err;
+
+  if (buffer == NULL || size_ptr == NULL || *size_ptr == 0) {
+    return UV_EINVAL;
+  }
+
+  if (*size_ptr > 32768) {
+    /* Windows paths can never be longer than this. */
+    utf16_buffer_len = 32768;
+  } else {
+    utf16_buffer_len = (int) *size_ptr;
+  }
+
+  utf16_buffer = (WCHAR*) uv__malloc(sizeof(WCHAR) * utf16_buffer_len);
+  if (!utf16_buffer) {
+    return UV_ENOMEM;
+  }
+
+  /* Get the path as UTF-16. */
+  utf16_len = GetModuleFileNameW(NULL, utf16_buffer, utf16_buffer_len);
+  if (utf16_len <= 0) {
+    err = GetLastError();
+    goto error;
+  }
+
+  /* utf16_len contains the length, *not* including the terminating null. */
+  utf16_buffer[utf16_len] = L'\0';
+
+  /* Convert to UTF-8 */
+  utf8_len = WideCharToMultiByte(CP_UTF8,
+                                 0,
+                                 utf16_buffer,
+                                 -1,
+                                 buffer,
+                                 (int) *size_ptr,
+                                 NULL,
+                                 NULL);
+  if (utf8_len == 0) {
+    err = GetLastError();
+    goto error;
+  }
+
+  uv__free(utf16_buffer);
+
+  /* utf8_len *does* include the terminating null at this point, but the
+   * returned size shouldn't. */
+  *size_ptr = utf8_len - 1;
+  return 0;
+
+ error:
+  uv__free(utf16_buffer);
+  return uv_translate_sys_error(err);
+}
+
+
+int uv_cwd(char* buffer, size_t* size) {
+  DWORD utf16_len;
+  WCHAR *utf16_buffer;
+  int r;
+
+  if (buffer == NULL || size == NULL) {
+    return UV_EINVAL;
+  }
+
+  utf16_len = GetCurrentDirectoryW(0, NULL);
+  if (utf16_len == 0) {
+    return uv_translate_sys_error(GetLastError());
+  }
+  utf16_buffer = (WCHAR*)uv__malloc(utf16_len * sizeof(WCHAR));
+  if (utf16_buffer == NULL) {
+    return UV_ENOMEM;
+  }
+
+  utf16_len = GetCurrentDirectoryW(utf16_len, utf16_buffer);
+  if (utf16_len == 0) {
+    uv__free(utf16_buffer);
+    return uv_translate_sys_error(GetLastError());
+  }
+
+  /* utf16_len contains the length, *not* including the terminating null. */
+  utf16_buffer[utf16_len] = L'\0';
+
+  /* The returned directory should not have a trailing slash, unless it points
+   * at a drive root, like c:\. Remove it if needed. */
+  if (utf16_buffer[utf16_len - 1] == L'\\' &&
+      !(utf16_len == 3 && utf16_buffer[1] == L':')) {
+    utf16_len--;
+    utf16_buffer[utf16_len] = L'\0';
+  }
+
+  /* Check how much space we need */
+  r = WideCharToMultiByte(CP_UTF8,
+                          0,
+                          utf16_buffer,
+                          -1,
+                          NULL,
+                          0,
+                          NULL,
+                          NULL);
+  if (r == 0) {
+    uv__free(utf16_buffer);
+    return uv_translate_sys_error(GetLastError());
+  } else if (r > (int) *size) {
+    uv__free(utf16_buffer);
+    *size = r;
+    return UV_ENOBUFS;
+  }
+
+  /* Convert to UTF-8 */
+  r = WideCharToMultiByte(CP_UTF8,
+                          0,
+                          utf16_buffer,
+                          -1,
+                          buffer,
+                          *size > INT_MAX ? INT_MAX : (int) *size,
+                          NULL,
+                          NULL);
+  uv__free(utf16_buffer);
+
+  if (r == 0) {
+    return uv_translate_sys_error(GetLastError());
+  }
+
+  *size = r - 1;
+  return 0;
+}
+
+
+int uv_chdir(const char* dir) {
+  WCHAR *utf16_buffer;
+  size_t utf16_len, new_utf16_len;
+  WCHAR drive_letter, env_var[4];
+
+  if (dir == NULL) {
+    return UV_EINVAL;
+  }
+
+  utf16_len = MultiByteToWideChar(CP_UTF8,
+                                  0,
+                                  dir,
+                                  -1,
+                                  NULL,
+                                  0);
+  if (utf16_len == 0) {
+    return uv_translate_sys_error(GetLastError());
+  }
+  utf16_buffer = (WCHAR*)uv__malloc(utf16_len * sizeof(WCHAR));
+  if (utf16_buffer == NULL) {
+    return UV_ENOMEM;
+  }
+
+  if (MultiByteToWideChar(CP_UTF8,
+                          0,
+                          dir,
+                          -1,
+                          utf16_buffer,
+                          utf16_len) == 0) {
+    uv__free(utf16_buffer);
+    return uv_translate_sys_error(GetLastError());
+  }
+
+  if (!SetCurrentDirectoryW(utf16_buffer)) {
+    uv__free(utf16_buffer);
+    return uv_translate_sys_error(GetLastError());
+  }
+
+  /* Windows stores the drive-local path in an "hidden" environment variable,
+   * which has the form "=C:=C:\Windows". SetCurrentDirectory does not update
+   * this, so we'll have to do it. */
+  new_utf16_len = GetCurrentDirectoryW(utf16_len, utf16_buffer);
+  if (new_utf16_len > utf16_len ) {
+    uv__free(utf16_buffer);
+    utf16_buffer = (WCHAR*)uv__malloc(new_utf16_len * sizeof(WCHAR));
+    if (utf16_buffer == NULL) {
+      /* When updating the environment variable fails, return UV_OK anyway.
+       * We did successfully change current working directory, only updating
+       * hidden env variable failed. */
+      return 0;
+    }
+    new_utf16_len = GetCurrentDirectoryW(new_utf16_len, utf16_buffer);
+  }
+  if (utf16_len == 0) {
+    uv__free(utf16_buffer);
+    return 0;
+  }
+
+  /* The returned directory should not have a trailing slash, unless it points
+   * at a drive root, like c:\. Remove it if needed. */
+  if (utf16_buffer[utf16_len - 1] == L'\\' &&
+      !(utf16_len == 3 && utf16_buffer[1] == L':')) {
+    utf16_len--;
+    utf16_buffer[utf16_len] = L'\0';
+  }
+
+  if (utf16_len < 2 || utf16_buffer[1] != L':') {
+    /* Doesn't look like a drive letter could be there - probably an UNC path.
+     * TODO: Need to handle win32 namespaces like \\?\C:\ ? */
+    drive_letter = 0;
+  } else if (utf16_buffer[0] >= L'A' && utf16_buffer[0] <= L'Z') {
+    drive_letter = utf16_buffer[0];
+  } else if (utf16_buffer[0] >= L'a' && utf16_buffer[0] <= L'z') {
+    /* Convert to uppercase. */
+    drive_letter = utf16_buffer[0] - L'a' + L'A';
+  } else {
+    /* Not valid. */
+    drive_letter = 0;
+  }
+
+  if (drive_letter != 0) {
+    /* Construct the environment variable name and set it. */
+    env_var[0] = L'=';
+    env_var[1] = drive_letter;
+    env_var[2] = L':';
+    env_var[3] = L'\0';
+
+    SetEnvironmentVariableW(env_var, utf16_buffer);
+  }
+
+  uv__free(utf16_buffer);
+  return 0;
+}
+
+
+void uv_loadavg(double avg[3]) {
+  /* Can't be implemented */
+  avg[0] = avg[1] = avg[2] = 0;
+}
+
+
+uint64_t uv_get_free_memory(void) {
+  MEMORYSTATUSEX memory_status;
+  memory_status.dwLength = sizeof(memory_status);
+
+  if (!GlobalMemoryStatusEx(&memory_status)) {
+     return -1;
+  }
+
+  return (uint64_t)memory_status.ullAvailPhys;
+}
+
+
+uint64_t uv_get_total_memory(void) {
+  MEMORYSTATUSEX memory_status;
+  memory_status.dwLength = sizeof(memory_status);
+
+  if (!GlobalMemoryStatusEx(&memory_status)) {
+    return -1;
+  }
+
+  return (uint64_t)memory_status.ullTotalPhys;
+}
+
+
+uint64_t uv_get_constrained_memory(void) {
+  return 0;  /* Memory constraints are unknown. */
+}
+
+
+uv_pid_t uv_os_getpid(void) {
+  return GetCurrentProcessId();
+}
+
+
+uv_pid_t uv_os_getppid(void) {
+  int parent_pid = -1;
+  HANDLE handle;
+  PROCESSENTRY32 pe;
+  DWORD current_pid = GetCurrentProcessId();
+
+  pe.dwSize = sizeof(PROCESSENTRY32);
+  handle = CreateToolhelp32Snapshot(TH32CS_SNAPPROCESS, 0);
+
+  if (Process32First(handle, &pe)) {
+    do {
+      if (pe.th32ProcessID == current_pid) {
+        parent_pid = pe.th32ParentProcessID;
+        break;
+      }
+    } while( Process32Next(handle, &pe));
+  }
+
+  CloseHandle(handle);
+  return parent_pid;
+}
+
+
+char** uv_setup_args(int argc, char** argv) {
+  return argv;
+}
+
+
+void uv__process_title_cleanup(void) {
+}
+
+
+int uv_set_process_title(const char* title) {
+  int err;
+  int length;
+  WCHAR* title_w = NULL;
+
+  uv__once_init();
+
+  /* Find out how big the buffer for the wide-char title must be */
+  length = MultiByteToWideChar(CP_UTF8, 0, title, -1, NULL, 0);
+  if (!length) {
+    err = GetLastError();
+    goto done;
+  }
+
+  /* Convert to wide-char string */
+  title_w = (WCHAR*)uv__malloc(sizeof(WCHAR) * length);
+  if (!title_w) {
+    uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+  }
+
+  length = MultiByteToWideChar(CP_UTF8, 0, title, -1, title_w, length);
+  if (!length) {
+    err = GetLastError();
+    goto done;
+  }
+
+  /* If the title must be truncated insert a \0 terminator there */
+  if (length > MAX_TITLE_LENGTH) {
+    title_w[MAX_TITLE_LENGTH - 1] = L'\0';
+  }
+
+  if (!SetConsoleTitleW(title_w)) {
+    err = GetLastError();
+    goto done;
+  }
+
+  EnterCriticalSection(&process_title_lock);
+  uv__free(process_title);
+  process_title = uv__strdup(title);
+  LeaveCriticalSection(&process_title_lock);
+
+  err = 0;
+
+done:
+  uv__free(title_w);
+  return uv_translate_sys_error(err);
+}
+
+
+static int uv__get_process_title(void) {
+  WCHAR title_w[MAX_TITLE_LENGTH];
+
+  if (!GetConsoleTitleW(title_w, sizeof(title_w) / sizeof(WCHAR))) {
+    return -1;
+  }
+
+  if (uv__convert_utf16_to_utf8(title_w, -1, &process_title) != 0)
+    return -1;
+
+  return 0;
+}
+
+
+int uv_get_process_title(char* buffer, size_t size) {
+  size_t len;
+
+  if (buffer == NULL || size == 0)
+    return UV_EINVAL;
+
+  uv__once_init();
+
+  EnterCriticalSection(&process_title_lock);
+  /*
+   * If the process_title was never read before nor explicitly set,
+   * we must query it with getConsoleTitleW
+   */
+  if (!process_title && uv__get_process_title() == -1) {
+    LeaveCriticalSection(&process_title_lock);
+    return uv_translate_sys_error(GetLastError());
+  }
+
+  assert(process_title);
+  len = strlen(process_title) + 1;
+
+  if (size < len) {
+    LeaveCriticalSection(&process_title_lock);
+    return UV_ENOBUFS;
+  }
+
+  memcpy(buffer, process_title, len);
+  LeaveCriticalSection(&process_title_lock);
+
+  return 0;
+}
+
+
+uint64_t uv_hrtime(void) {
+  uv__once_init();
+  return uv__hrtime(UV__NANOSEC);
+}
+
+uint64_t uv__hrtime(unsigned int scale) {
+  LARGE_INTEGER counter;
+  double scaled_freq;
+  double result;
+
+  assert(hrtime_frequency_ != 0);
+  assert(scale != 0);
+  if (!QueryPerformanceCounter(&counter)) {
+    uv_fatal_error(GetLastError(), "QueryPerformanceCounter");
+  }
+  assert(counter.QuadPart != 0);
+
+  /* Because we have no guarantee about the order of magnitude of the
+   * performance counter interval, integer math could cause this computation
+   * to overflow. Therefore we resort to floating point math.
+   */
+  scaled_freq = (double) hrtime_frequency_ / scale;
+  result = (double) counter.QuadPart / scaled_freq;
+  return (uint64_t) result;
+}
+
+
+int uv_resident_set_memory(size_t* rss) {
+  HANDLE current_process;
+  PROCESS_MEMORY_COUNTERS pmc;
+
+  current_process = GetCurrentProcess();
+
+  if (!GetProcessMemoryInfo(current_process, &pmc, sizeof(pmc))) {
+    return uv_translate_sys_error(GetLastError());
+  }
+
+  *rss = pmc.WorkingSetSize;
+
+  return 0;
+}
+
+
+int uv_uptime(double* uptime) {
+  *uptime = GetTickCount64() / 1000.0;
+  return 0;
+}
+
+
+unsigned int uv_available_parallelism(void) {
+  SYSTEM_INFO info;
+  unsigned rc;
+
+  /* TODO(bnoordhuis) Use GetLogicalProcessorInformationEx() to support systems
+   * with > 64 CPUs? See https://github.com/libuv/libuv/pull/3458
+   */
+  GetSystemInfo(&info);
+
+  rc = info.dwNumberOfProcessors;
+  if (rc < 1)
+    rc = 1;
+
+  return rc;
+}
+
+
+int uv_cpu_info(uv_cpu_info_t** cpu_infos_ptr, int* cpu_count_ptr) {
+  uv_cpu_info_t* cpu_infos;
+  SYSTEM_PROCESSOR_PERFORMANCE_INFORMATION* sppi;
+  DWORD sppi_size;
+  SYSTEM_INFO system_info;
+  DWORD cpu_count, i;
+  NTSTATUS status;
+  ULONG result_size;
+  int err;
+  uv_cpu_info_t* cpu_info;
+
+  cpu_infos = NULL;
+  cpu_count = 0;
+  sppi = NULL;
+
+  uv__once_init();
+
+  GetSystemInfo(&system_info);
+  cpu_count = system_info.dwNumberOfProcessors;
+
+  cpu_infos = (uv_cpu_info_t*)uv__calloc(cpu_count, sizeof *cpu_infos);
+  if (cpu_infos == NULL) {
+    err = ERROR_OUTOFMEMORY;
+    goto error;
+  }
+
+  sppi_size = cpu_count * sizeof(*sppi);
+  sppi = (SYSTEM_PROCESSOR_PERFORMANCE_INFORMATION*)uv__malloc(sppi_size);
+  if (sppi == NULL) {
+    err = ERROR_OUTOFMEMORY;
+    goto error;
+  }
+
+  status = pNtQuerySystemInformation(SystemProcessorPerformanceInformation,
+                                     sppi,
+                                     sppi_size,
+                                     &result_size);
+  if (!NT_SUCCESS(status)) {
+    err = pRtlNtStatusToDosError(status);
+    goto error;
+  }
+
+  assert(result_size == sppi_size);
+
+  for (i = 0; i < cpu_count; i++) {
+    WCHAR key_name[128];
+    HKEY processor_key;
+    DWORD cpu_speed;
+    DWORD cpu_speed_size = sizeof(cpu_speed);
+    WCHAR cpu_brand[256];
+    DWORD cpu_brand_size = sizeof(cpu_brand);
+    size_t len;
+
+    len = _snwprintf(key_name,
+                     ARRAY_SIZE(key_name),
+                     L"HARDWARE\\DESCRIPTION\\System\\CentralProcessor\\%d",
+                     i);
+
+    assert(len > 0 && len < ARRAY_SIZE(key_name));
+
+    err = RegOpenKeyExW(HKEY_LOCAL_MACHINE,
+                        key_name,
+                        0,
+                        KEY_QUERY_VALUE,
+                        &processor_key);
+    if (err != ERROR_SUCCESS) {
+      goto error;
+    }
+
+    err = RegQueryValueExW(processor_key,
+                           L"~MHz",
+                           NULL,
+                           NULL,
+                           (BYTE*)&cpu_speed,
+                           &cpu_speed_size);
+    if (err != ERROR_SUCCESS) {
+      RegCloseKey(processor_key);
+      goto error;
+    }
+
+    err = RegQueryValueExW(processor_key,
+                           L"ProcessorNameString",
+                           NULL,
+                           NULL,
+                           (BYTE*)&cpu_brand,
+                           &cpu_brand_size);
+    RegCloseKey(processor_key);
+    if (err != ERROR_SUCCESS)
+      goto error;
+
+    cpu_info = &cpu_infos[i];
+    cpu_info->speed = cpu_speed;
+    cpu_info->cpu_times.user = sppi[i].UserTime.QuadPart / 10000;
+    cpu_info->cpu_times.sys = (sppi[i].KernelTime.QuadPart -
+        sppi[i].IdleTime.QuadPart) / 10000;
+    cpu_info->cpu_times.idle = sppi[i].IdleTime.QuadPart / 10000;
+    cpu_info->cpu_times.irq = sppi[i].InterruptTime.QuadPart / 10000;
+    cpu_info->cpu_times.nice = 0;
+
+    uv__convert_utf16_to_utf8(cpu_brand,
+                              cpu_brand_size / sizeof(WCHAR),
+                              &(cpu_info->model));
+  }
+
+  uv__free(sppi);
+
+  *cpu_count_ptr = cpu_count;
+  *cpu_infos_ptr = cpu_infos;
+
+  return 0;
+
+ error:
+  if (cpu_infos != NULL) {
+    /* This is safe because the cpu_infos array is zeroed on allocation. */
+    for (i = 0; i < cpu_count; i++)
+      uv__free(cpu_infos[i].model);
+  }
+
+  uv__free(cpu_infos);
+  uv__free(sppi);
+
+  return uv_translate_sys_error(err);
+}
+
+
+static int is_windows_version_or_greater(DWORD os_major,
+                                         DWORD os_minor,
+                                         WORD service_pack_major,
+                                         WORD service_pack_minor) {
+  OSVERSIONINFOEX osvi;
+  DWORDLONG condition_mask = 0;
+  int op = VER_GREATER_EQUAL;
+
+  /* Initialize the OSVERSIONINFOEX structure. */
+  ZeroMemory(&osvi, sizeof(OSVERSIONINFOEX));
+  osvi.dwOSVersionInfoSize = sizeof(OSVERSIONINFOEX);
+  osvi.dwMajorVersion = os_major;
+  osvi.dwMinorVersion = os_minor;
+  osvi.wServicePackMajor = service_pack_major;
+  osvi.wServicePackMinor = service_pack_minor;
+
+  /* Initialize the condition mask. */
+  VER_SET_CONDITION(condition_mask, VER_MAJORVERSION, op);
+  VER_SET_CONDITION(condition_mask, VER_MINORVERSION, op);
+  VER_SET_CONDITION(condition_mask, VER_SERVICEPACKMAJOR, op);
+  VER_SET_CONDITION(condition_mask, VER_SERVICEPACKMINOR, op);
+
+  /* Perform the test. */
+  return (int) VerifyVersionInfo(
+    &osvi,
+    VER_MAJORVERSION | VER_MINORVERSION |
+    VER_SERVICEPACKMAJOR | VER_SERVICEPACKMINOR,
+    condition_mask);
+}
+
+
+static int address_prefix_match(int family,
+                                struct sockaddr* address,
+                                struct sockaddr* prefix_address,
+                                int prefix_len) {
+  uint8_t* address_data;
+  uint8_t* prefix_address_data;
+  int i;
+
+  assert(address->sa_family == family);
+  assert(prefix_address->sa_family == family);
+
+  if (family == AF_INET6) {
+    address_data = (uint8_t*) &(((struct sockaddr_in6 *) address)->sin6_addr);
+    prefix_address_data =
+      (uint8_t*) &(((struct sockaddr_in6 *) prefix_address)->sin6_addr);
+  } else {
+    address_data = (uint8_t*) &(((struct sockaddr_in *) address)->sin_addr);
+    prefix_address_data =
+      (uint8_t*) &(((struct sockaddr_in *) prefix_address)->sin_addr);
+  }
+
+  for (i = 0; i < prefix_len >> 3; i++) {
+    if (address_data[i] != prefix_address_data[i])
+      return 0;
+  }
+
+  if (prefix_len % 8)
+    return prefix_address_data[i] ==
+      (address_data[i] & (0xff << (8 - prefix_len % 8)));
+
+  return 1;
+}
+
+
+int uv_interface_addresses(uv_interface_address_t** addresses_ptr,
+    int* count_ptr) {
+  IP_ADAPTER_ADDRESSES* win_address_buf;
+  ULONG win_address_buf_size;
+  IP_ADAPTER_ADDRESSES* adapter;
+
+  uv_interface_address_t* uv_address_buf;
+  char* name_buf;
+  size_t uv_address_buf_size;
+  uv_interface_address_t* uv_address;
+
+  int count;
+
+  int is_vista_or_greater;
+  ULONG flags;
+
+  *addresses_ptr = NULL;
+  *count_ptr = 0;
+
+  is_vista_or_greater = is_windows_version_or_greater(6, 0, 0, 0);
+  if (is_vista_or_greater) {
+    flags = GAA_FLAG_SKIP_ANYCAST | GAA_FLAG_SKIP_MULTICAST |
+      GAA_FLAG_SKIP_DNS_SERVER;
+  } else {
+    /* We need at least XP SP1. */
+    if (!is_windows_version_or_greater(5, 1, 1, 0))
+      return UV_ENOTSUP;
+
+    flags = GAA_FLAG_SKIP_ANYCAST | GAA_FLAG_SKIP_MULTICAST |
+      GAA_FLAG_SKIP_DNS_SERVER | GAA_FLAG_INCLUDE_PREFIX;
+  }
+
+
+  /* Fetch the size of the adapters reported by windows, and then get the list
+   * itself. */
+  win_address_buf_size = 0;
+  win_address_buf = NULL;
+
+  for (;;) {
+    ULONG r;
+
+    /* If win_address_buf is 0, then GetAdaptersAddresses will fail with.
+     * ERROR_BUFFER_OVERFLOW, and the required buffer size will be stored in
+     * win_address_buf_size. */
+    r = GetAdaptersAddresses(AF_UNSPEC,
+                             flags,
+                             NULL,
+                             win_address_buf,
+                             &win_address_buf_size);
+
+    if (r == ERROR_SUCCESS)
+      break;
+
+    uv__free(win_address_buf);
+
+    switch (r) {
+      case ERROR_BUFFER_OVERFLOW:
+        /* This happens when win_address_buf is NULL or too small to hold all
+         * adapters. */
+        win_address_buf =
+            (IP_ADAPTER_ADDRESSES*)uv__malloc(win_address_buf_size);
+        if (win_address_buf == NULL)
+          return UV_ENOMEM;
+
+        continue;
+
+      case ERROR_NO_DATA: {
+        /* No adapters were found. */
+        uv_address_buf = (uv_interface_address_t*)uv__malloc(1);
+        if (uv_address_buf == NULL)
+          return UV_ENOMEM;
+
+        *count_ptr = 0;
+        *addresses_ptr = uv_address_buf;
+
+        return 0;
+      }
+
+      case ERROR_ADDRESS_NOT_ASSOCIATED:
+        return UV_EAGAIN;
+
+      case ERROR_INVALID_PARAMETER:
+        /* MSDN says:
+         *   "This error is returned for any of the following conditions: the
+         *   SizePointer parameter is NULL, the Address parameter is not
+         *   AF_INET, AF_INET6, or AF_UNSPEC, or the address information for
+         *   the parameters requested is greater than ULONG_MAX."
+         * Since the first two conditions are not met, it must be that the
+         * adapter data is too big.
+         */
+        return UV_ENOBUFS;
+
+      default:
+        /* Other (unspecified) errors can happen, but we don't have any special
+         * meaning for them. */
+        assert(r != ERROR_SUCCESS);
+        return uv_translate_sys_error(r);
+    }
+  }
+
+  /* Count the number of enabled interfaces and compute how much space is
+   * needed to store their info. */
+  count = 0;
+  uv_address_buf_size = 0;
+
+  for (adapter = win_address_buf;
+       adapter != NULL;
+       adapter = adapter->Next) {
+    IP_ADAPTER_UNICAST_ADDRESS* unicast_address;
+    int name_size;
+
+    /* Interfaces that are not 'up' should not be reported. Also skip
+     * interfaces that have no associated unicast address, as to avoid
+     * allocating space for the name for this interface. */
+    if (adapter->OperStatus != IfOperStatusUp ||
+        adapter->FirstUnicastAddress == NULL)
+      continue;
+
+    /* Compute the size of the interface name. */
+    name_size = WideCharToMultiByte(CP_UTF8,
+                                    0,
+                                    adapter->FriendlyName,
+                                    -1,
+                                    NULL,
+                                    0,
+                                    NULL,
+                                    FALSE);
+    if (name_size <= 0) {
+      uv__free(win_address_buf);
+      return uv_translate_sys_error(GetLastError());
+    }
+    uv_address_buf_size += name_size;
+
+    /* Count the number of addresses associated with this interface, and
+     * compute the size. */
+    for (unicast_address = (IP_ADAPTER_UNICAST_ADDRESS*)
+                           adapter->FirstUnicastAddress;
+         unicast_address != NULL;
+         unicast_address = unicast_address->Next) {
+      count++;
+      uv_address_buf_size += sizeof(uv_interface_address_t);
+    }
+  }
+
+  /* Allocate space to store interface data plus adapter names. */
+  uv_address_buf = (uv_interface_address_t*)uv__malloc(uv_address_buf_size);
+  if (uv_address_buf == NULL) {
+    uv__free(win_address_buf);
+    return UV_ENOMEM;
+  }
+
+  /* Compute the start of the uv_interface_address_t array, and the place in
+   * the buffer where the interface names will be stored. */
+  uv_address = uv_address_buf;
+  name_buf = (char*) (uv_address_buf + count);
+
+  /* Fill out the output buffer. */
+  for (adapter = win_address_buf;
+       adapter != NULL;
+       adapter = adapter->Next) {
+    IP_ADAPTER_UNICAST_ADDRESS* unicast_address;
+    int name_size;
+    size_t max_name_size;
+
+    if (adapter->OperStatus != IfOperStatusUp ||
+        adapter->FirstUnicastAddress == NULL)
+      continue;
+
+    /* Convert the interface name to UTF8. */
+    max_name_size = (char*) uv_address_buf + uv_address_buf_size - name_buf;
+    if (max_name_size > (size_t) INT_MAX)
+      max_name_size = INT_MAX;
+    name_size = WideCharToMultiByte(CP_UTF8,
+                                    0,
+                                    adapter->FriendlyName,
+                                    -1,
+                                    name_buf,
+                                    (int) max_name_size,
+                                    NULL,
+                                    FALSE);
+    if (name_size <= 0) {
+      uv__free(win_address_buf);
+      uv__free(uv_address_buf);
+      return uv_translate_sys_error(GetLastError());
+    }
+
+    /* Add an uv_interface_address_t element for every unicast address. */
+    for (unicast_address = (IP_ADAPTER_UNICAST_ADDRESS*)
+                           adapter->FirstUnicastAddress;
+         unicast_address != NULL;
+         unicast_address = unicast_address->Next) {
+      struct sockaddr* sa;
+      ULONG prefix_len;
+
+      sa = unicast_address->Address.lpSockaddr;
+
+      /* XP has no OnLinkPrefixLength field. */
+      if (is_vista_or_greater) {
+        prefix_len =
+          ((IP_ADAPTER_UNICAST_ADDRESS_LH*) unicast_address)->OnLinkPrefixLength;
+      } else {
+        /* Prior to Windows Vista the FirstPrefix pointed to the list with
+         * single prefix for each IP address assigned to the adapter.
+         * Order of FirstPrefix does not match order of FirstUnicastAddress,
+         * so we need to find corresponding prefix.
+         */
+        IP_ADAPTER_PREFIX* prefix;
+        prefix_len = 0;
+
+        for (prefix = adapter->FirstPrefix; prefix; prefix = prefix->Next) {
+          /* We want the longest matching prefix. */
+          if (prefix->Address.lpSockaddr->sa_family != sa->sa_family ||
+              prefix->PrefixLength <= prefix_len)
+            continue;
+
+          if (address_prefix_match(sa->sa_family, sa,
+              prefix->Address.lpSockaddr, prefix->PrefixLength)) {
+            prefix_len = prefix->PrefixLength;
+          }
+        }
+
+        /* If there is no matching prefix information, return a single-host
+         * subnet mask (e.g. 255.255.255.255 for IPv4).
+         */
+        if (!prefix_len)
+          prefix_len = (sa->sa_family == AF_INET6) ? 128 : 32;
+      }
+
+      memset(uv_address, 0, sizeof *uv_address);
+
+      uv_address->name = name_buf;
+
+      if (adapter->PhysicalAddressLength == sizeof(uv_address->phys_addr)) {
+        memcpy(uv_address->phys_addr,
+               adapter->PhysicalAddress,
+               sizeof(uv_address->phys_addr));
+      }
+
+      uv_address->is_internal =
+          (adapter->IfType == IF_TYPE_SOFTWARE_LOOPBACK);
+
+      if (sa->sa_family == AF_INET6) {
+        uv_address->address.address6 = *((struct sockaddr_in6 *) sa);
+
+        uv_address->netmask.netmask6.sin6_family = AF_INET6;
+        memset(uv_address->netmask.netmask6.sin6_addr.s6_addr, 0xff, prefix_len >> 3);
+        /* This check ensures that we don't write past the size of the data. */
+        if (prefix_len % 8) {
+          uv_address->netmask.netmask6.sin6_addr.s6_addr[prefix_len >> 3] =
+              0xff << (8 - prefix_len % 8);
+        }
+
+      } else {
+        uv_address->address.address4 = *((struct sockaddr_in *) sa);
+
+        uv_address->netmask.netmask4.sin_family = AF_INET;
+        uv_address->netmask.netmask4.sin_addr.s_addr = (prefix_len > 0) ?
+            htonl(0xffffffff << (32 - prefix_len)) : 0;
+      }
+
+      uv_address++;
+    }
+
+    name_buf += name_size;
+  }
+
+  uv__free(win_address_buf);
+
+  *addresses_ptr = uv_address_buf;
+  *count_ptr = count;
+
+  return 0;
+}
+
+
+void uv_free_interface_addresses(uv_interface_address_t* addresses,
+    int count) {
+  uv__free(addresses);
+}
+
+
+int uv_getrusage(uv_rusage_t *uv_rusage) {
+  FILETIME createTime, exitTime, kernelTime, userTime;
+  SYSTEMTIME kernelSystemTime, userSystemTime;
+  PROCESS_MEMORY_COUNTERS memCounters;
+  IO_COUNTERS ioCounters;
+  int ret;
+
+  ret = GetProcessTimes(GetCurrentProcess(), &createTime, &exitTime, &kernelTime, &userTime);
+  if (ret == 0) {
+    return uv_translate_sys_error(GetLastError());
+  }
+
+  ret = FileTimeToSystemTime(&kernelTime, &kernelSystemTime);
+  if (ret == 0) {
+    return uv_translate_sys_error(GetLastError());
+  }
+
+  ret = FileTimeToSystemTime(&userTime, &userSystemTime);
+  if (ret == 0) {
+    return uv_translate_sys_error(GetLastError());
+  }
+
+  ret = GetProcessMemoryInfo(GetCurrentProcess(),
+                             &memCounters,
+                             sizeof(memCounters));
+  if (ret == 0) {
+    return uv_translate_sys_error(GetLastError());
+  }
+
+  ret = GetProcessIoCounters(GetCurrentProcess(), &ioCounters);
+  if (ret == 0) {
+    return uv_translate_sys_error(GetLastError());
+  }
+
+  memset(uv_rusage, 0, sizeof(*uv_rusage));
+
+  uv_rusage->ru_utime.tv_sec = userSystemTime.wHour * 3600 +
+                               userSystemTime.wMinute * 60 +
+                               userSystemTime.wSecond;
+  uv_rusage->ru_utime.tv_usec = userSystemTime.wMilliseconds * 1000;
+
+  uv_rusage->ru_stime.tv_sec = kernelSystemTime.wHour * 3600 +
+                               kernelSystemTime.wMinute * 60 +
+                               kernelSystemTime.wSecond;
+  uv_rusage->ru_stime.tv_usec = kernelSystemTime.wMilliseconds * 1000;
+
+  uv_rusage->ru_majflt = (uint64_t) memCounters.PageFaultCount;
+  uv_rusage->ru_maxrss = (uint64_t) memCounters.PeakWorkingSetSize / 1024;
+
+  uv_rusage->ru_oublock = (uint64_t) ioCounters.WriteOperationCount;
+  uv_rusage->ru_inblock = (uint64_t) ioCounters.ReadOperationCount;
+
+  return 0;
+}
+
+
+int uv_os_homedir(char* buffer, size_t* size) {
+  uv_passwd_t pwd;
+  size_t len;
+  int r;
+
+  /* Check if the USERPROFILE environment variable is set first. The task of
+     performing input validation on buffer and size is taken care of by
+     uv_os_getenv(). */
+  r = uv_os_getenv("USERPROFILE", buffer, size);
+
+  /* Don't return an error if USERPROFILE was not found. */
+  if (r != UV_ENOENT)
+    return r;
+
+  /* USERPROFILE is not set, so call uv__getpwuid_r() */
+  r = uv__getpwuid_r(&pwd);
+
+  if (r != 0) {
+    return r;
+  }
+
+  len = strlen(pwd.homedir);
+
+  if (len >= *size) {
+    *size = len + 1;
+    uv_os_free_passwd(&pwd);
+    return UV_ENOBUFS;
+  }
+
+  memcpy(buffer, pwd.homedir, len + 1);
+  *size = len;
+  uv_os_free_passwd(&pwd);
+
+  return 0;
+}
+
+
+int uv_os_tmpdir(char* buffer, size_t* size) {
+  wchar_t *path;
+  DWORD bufsize;
+  size_t len;
+
+  if (buffer == NULL || size == NULL || *size == 0)
+    return UV_EINVAL;
+
+  len = 0;
+  len = GetTempPathW(0, NULL);
+  if (len == 0) {
+    return uv_translate_sys_error(GetLastError());
+  }
+  /* Include space for terminating null char. */
+  len += 1;
+  path = (wchar_t*)uv__malloc(len * sizeof(wchar_t));
+  if (path == NULL) {
+    return UV_ENOMEM;
+  }
+  len  = GetTempPathW(len, path);
+
+  if (len == 0) {
+    uv__free(path);
+    return uv_translate_sys_error(GetLastError());
+  }
+
+  /* The returned directory should not have a trailing slash, unless it points
+   * at a drive root, like c:\. Remove it if needed. */
+  if (path[len - 1] == L'\\' &&
+      !(len == 3 && path[1] == L':')) {
+    len--;
+    path[len] = L'\0';
+  }
+
+  /* Check how much space we need */
+  bufsize = WideCharToMultiByte(CP_UTF8, 0, path, -1, NULL, 0, NULL, NULL);
+
+  if (bufsize == 0) {
+    uv__free(path);
+    return uv_translate_sys_error(GetLastError());
+  } else if (bufsize > *size) {
+    uv__free(path);
+    *size = bufsize;
+    return UV_ENOBUFS;
+  }
+
+  /* Convert to UTF-8 */
+  bufsize = WideCharToMultiByte(CP_UTF8,
+                                0,
+                                path,
+                                -1,
+                                buffer,
+                                *size,
+                                NULL,
+                                NULL);
+  uv__free(path);
+
+  if (bufsize == 0)
+    return uv_translate_sys_error(GetLastError());
+
+  *size = bufsize - 1;
+  return 0;
+}
+
+
+void uv_os_free_passwd(uv_passwd_t* pwd) {
+  if (pwd == NULL)
+    return;
+
+  uv__free(pwd->username);
+  uv__free(pwd->homedir);
+  pwd->username = NULL;
+  pwd->homedir = NULL;
+}
+
+
+/*
+ * Converts a UTF-16 string into a UTF-8 one. The resulting string is
+ * null-terminated.
+ *
+ * If utf16 is null terminated, utf16len can be set to -1, otherwise it must
+ * be specified.
+ */
+int uv__convert_utf16_to_utf8(const WCHAR* utf16, int utf16len, char** utf8) {
+  DWORD bufsize;
+
+  if (utf16 == NULL)
+    return UV_EINVAL;
+
+  /* Check how much space we need */
+  bufsize = WideCharToMultiByte(CP_UTF8,
+                                0,
+                                utf16,
+                                utf16len,
+                                NULL,
+                                0,
+                                NULL,
+                                NULL);
+
+  if (bufsize == 0)
+    return uv_translate_sys_error(GetLastError());
+
+  /* Allocate the destination buffer adding an extra byte for the terminating
+   * NULL. If utf16len is not -1 WideCharToMultiByte will not add it, so
+   * we do it ourselves always, just in case. */
+  *utf8 = (char*)uv__malloc(bufsize + 1);
+
+  if (*utf8 == NULL)
+    return UV_ENOMEM;
+
+  /* Convert to UTF-8 */
+  bufsize = WideCharToMultiByte(CP_UTF8,
+                                0,
+                                utf16,
+                                utf16len,
+                                *utf8,
+                                bufsize,
+                                NULL,
+                                NULL);
+
+  if (bufsize == 0) {
+    uv__free(*utf8);
+    *utf8 = NULL;
+    return uv_translate_sys_error(GetLastError());
+  }
+
+  (*utf8)[bufsize] = '\0';
+  return 0;
+}
+
+
+/*
+ * Converts a UTF-8 string into a UTF-16 one. The resulting string is
+ * null-terminated.
+ *
+ * If utf8 is null terminated, utf8len can be set to -1, otherwise it must
+ * be specified.
+ */
+int uv__convert_utf8_to_utf16(const char* utf8, int utf8len, WCHAR** utf16) {
+  int bufsize;
+
+  if (utf8 == NULL)
+    return UV_EINVAL;
+
+  /* Check how much space we need */
+  bufsize = MultiByteToWideChar(CP_UTF8, 0, utf8, utf8len, NULL, 0);
+
+  if (bufsize == 0)
+    return uv_translate_sys_error(GetLastError());
+
+  /* Allocate the destination buffer adding an extra byte for the terminating
+   * NULL. If utf8len is not -1 MultiByteToWideChar will not add it, so
+   * we do it ourselves always, just in case. */
+  *utf16 = (WCHAR*)uv__malloc(sizeof(WCHAR) * (bufsize + 1));
+
+  if (*utf16 == NULL)
+    return UV_ENOMEM;
+
+  /* Convert to UTF-16 */
+  bufsize = MultiByteToWideChar(CP_UTF8, 0, utf8, utf8len, *utf16, bufsize);
+
+  if (bufsize == 0) {
+    uv__free(*utf16);
+    *utf16 = NULL;
+    return uv_translate_sys_error(GetLastError());
+  }
+
+  (*utf16)[bufsize] = L'\0';
+  return 0;
+}
+
+
+int uv__getpwuid_r(uv_passwd_t* pwd) {
+  HANDLE token;
+  wchar_t username[UNLEN + 1];
+  wchar_t *path;
+  DWORD bufsize;
+  int r;
+
+  if (pwd == NULL)
+    return UV_EINVAL;
+
+  /* Get the home directory using GetUserProfileDirectoryW() */
+  if (OpenProcessToken(GetCurrentProcess(), TOKEN_READ, &token) == 0)
+    return uv_translate_sys_error(GetLastError());
+
+  bufsize = 0;
+  GetUserProfileDirectoryW(token, NULL, &bufsize);
+  if (GetLastError() != ERROR_INSUFFICIENT_BUFFER) {
+    r = GetLastError();
+    CloseHandle(token);
+    return uv_translate_sys_error(r);
+  }
+
+  path = (wchar_t*)uv__malloc(bufsize * sizeof(wchar_t));
+  if (path == NULL) {
+    CloseHandle(token);
+    return UV_ENOMEM;
+  }
+
+  if (!GetUserProfileDirectoryW(token, path, &bufsize)) {
+    r = GetLastError();
+    CloseHandle(token);
+    uv__free(path);
+    return uv_translate_sys_error(r);
+  }
+
+  CloseHandle(token);
+
+  /* Get the username using GetUserNameW() */
+  bufsize = ARRAY_SIZE(username);
+  if (!GetUserNameW(username, &bufsize)) {
+    r = GetLastError();
+    uv__free(path);
+
+    /* This should not be possible */
+    if (r == ERROR_INSUFFICIENT_BUFFER)
+      return UV_ENOMEM;
+
+    return uv_translate_sys_error(r);
+  }
+
+  pwd->homedir = NULL;
+  r = uv__convert_utf16_to_utf8(path, -1, &pwd->homedir);
+  uv__free(path);
+
+  if (r != 0)
+    return r;
+
+  pwd->username = NULL;
+  r = uv__convert_utf16_to_utf8(username, -1, &pwd->username);
+
+  if (r != 0) {
+    uv__free(pwd->homedir);
+    return r;
+  }
+
+  pwd->shell = NULL;
+  pwd->uid = -1;
+  pwd->gid = -1;
+
+  return 0;
+}
+
+
+int uv_os_get_passwd(uv_passwd_t* pwd) {
+  return uv__getpwuid_r(pwd);
+}
+
+
+int uv_os_environ(uv_env_item_t** envitems, int* count) {
+  wchar_t* env;
+  wchar_t* penv;
+  int i, cnt;
+  uv_env_item_t* envitem;
+
+  *envitems = NULL;
+  *count = 0;
+
+  env = GetEnvironmentStringsW();
+  if (env == NULL)
+    return 0;
+
+  for (penv = env, i = 0; *penv != L'\0'; penv += wcslen(penv) + 1, i++);
+
+  *envitems = (uv_env_item_t*)uv__calloc(i, sizeof(**envitems));
+  if (*envitems == NULL) {
+    FreeEnvironmentStringsW(env);
+    return UV_ENOMEM;
+  }
+
+  penv = env;
+  cnt = 0;
+
+  while (*penv != L'\0' && cnt < i) {
+    char* buf;
+    char* ptr;
+
+    if (uv__convert_utf16_to_utf8(penv, -1, &buf) != 0)
+      goto fail;
+
+    /* Using buf + 1 here because we know that `buf` has length at least 1,
+     * and some special environment variables on Windows start with a = sign. */
+    ptr = strchr(buf + 1, '=');
+    if (ptr == NULL) {
+      uv__free(buf);
+      goto do_continue;
+    }
+
+    *ptr = '\0';
+
+    envitem = &(*envitems)[cnt];
+    envitem->name = buf;
+    envitem->value = ptr + 1;
+
+    cnt++;
+
+  do_continue:
+    penv += wcslen(penv) + 1;
+  }
+
+  FreeEnvironmentStringsW(env);
+
+  *count = cnt;
+  return 0;
+
+fail:
+  FreeEnvironmentStringsW(env);
+
+  for (i = 0; i < cnt; i++) {
+    envitem = &(*envitems)[cnt];
+    uv__free(envitem->name);
+  }
+  uv__free(*envitems);
+
+  *envitems = NULL;
+  *count = 0;
+  return UV_ENOMEM;
+}
+
+
+int uv_os_getenv(const char* name, char* buffer, size_t* size) {
+  wchar_t fastvar[512];
+  wchar_t* var;
+  DWORD varlen;
+  wchar_t* name_w;
+  DWORD bufsize;
+  size_t len;
+  int r;
+
+  if (name == NULL || buffer == NULL || size == NULL || *size == 0)
+    return UV_EINVAL;
+
+  r = uv__convert_utf8_to_utf16(name, -1, &name_w);
+
+  if (r != 0)
+    return r;
+
+  var = fastvar;
+  varlen = ARRAY_SIZE(fastvar);
+
+  for (;;) {
+    SetLastError(ERROR_SUCCESS);
+    len = GetEnvironmentVariableW(name_w, var, varlen);
+
+    if (len < varlen)
+      break;
+
+    /* Try repeatedly because we might have been preempted by another thread
+     * modifying the environment variable just as we're trying to read it.
+     */
+    if (var != fastvar)
+      uv__free(var);
+
+    varlen = 1 + len;
+    var = (wchar_t*)uv__malloc(varlen * sizeof(*var));
+
+    if (var == NULL) {
+      r = UV_ENOMEM;
+      goto fail;
+    }
+  }
+
+  uv__free(name_w);
+  name_w = NULL;
+
+  if (len == 0) {
+    r = GetLastError();
+    if (r != ERROR_SUCCESS) {
+      r = uv_translate_sys_error(r);
+      goto fail;
+    }
+  }
+
+  /* Check how much space we need */
+  bufsize = WideCharToMultiByte(CP_UTF8, 0, var, -1, NULL, 0, NULL, NULL);
+
+  if (bufsize == 0) {
+    r = uv_translate_sys_error(GetLastError());
+    goto fail;
+  } else if (bufsize > *size) {
+    *size = bufsize;
+    r = UV_ENOBUFS;
+    goto fail;
+  }
+
+  /* Convert to UTF-8 */
+  bufsize = WideCharToMultiByte(CP_UTF8,
+                                0,
+                                var,
+                                -1,
+                                buffer,
+                                *size,
+                                NULL,
+                                NULL);
+
+  if (bufsize == 0) {
+    r = uv_translate_sys_error(GetLastError());
+    goto fail;
+  }
+
+  *size = bufsize - 1;
+  r = 0;
+
+fail:
+
+  if (name_w != NULL)
+    uv__free(name_w);
+
+  if (var != fastvar)
+    uv__free(var);
+
+  return r;
+}
+
+
+int uv_os_setenv(const char* name, const char* value) {
+  wchar_t* name_w;
+  wchar_t* value_w;
+  int r;
+
+  if (name == NULL || value == NULL)
+    return UV_EINVAL;
+
+  r = uv__convert_utf8_to_utf16(name, -1, &name_w);
+
+  if (r != 0)
+    return r;
+
+  r = uv__convert_utf8_to_utf16(value, -1, &value_w);
+
+  if (r != 0) {
+    uv__free(name_w);
+    return r;
+  }
+
+  r = SetEnvironmentVariableW(name_w, value_w);
+  uv__free(name_w);
+  uv__free(value_w);
+
+  if (r == 0)
+    return uv_translate_sys_error(GetLastError());
+
+  return 0;
+}
+
+
+int uv_os_unsetenv(const char* name) {
+  wchar_t* name_w;
+  int r;
+
+  if (name == NULL)
+    return UV_EINVAL;
+
+  r = uv__convert_utf8_to_utf16(name, -1, &name_w);
+
+  if (r != 0)
+    return r;
+
+  r = SetEnvironmentVariableW(name_w, NULL);
+  uv__free(name_w);
+
+  if (r == 0)
+    return uv_translate_sys_error(GetLastError());
+
+  return 0;
+}
+
+
+int uv_os_gethostname(char* buffer, size_t* size) {
+  WCHAR buf[UV_MAXHOSTNAMESIZE];
+  size_t len;
+  char* utf8_str;
+  int convert_result;
+
+  if (buffer == NULL || size == NULL || *size == 0)
+    return UV_EINVAL;
+
+  uv__once_init(); /* Initialize winsock */
+
+  if (pGetHostNameW == NULL)
+    return UV_ENOSYS;
+
+  if (pGetHostNameW(buf, UV_MAXHOSTNAMESIZE) != 0)
+    return uv_translate_sys_error(WSAGetLastError());
+
+  convert_result = uv__convert_utf16_to_utf8(buf, -1, &utf8_str);
+
+  if (convert_result != 0)
+    return convert_result;
+
+  len = strlen(utf8_str);
+  if (len >= *size) {
+    *size = len + 1;
+    uv__free(utf8_str);
+    return UV_ENOBUFS;
+  }
+
+  memcpy(buffer, utf8_str, len + 1);
+  uv__free(utf8_str);
+  *size = len;
+  return 0;
+}
+
+
+static int uv__get_handle(uv_pid_t pid, int access, HANDLE* handle) {
+  int r;
+
+  if (pid == 0)
+    *handle = GetCurrentProcess();
+  else
+    *handle = OpenProcess(access, FALSE, pid);
+
+  if (*handle == NULL) {
+    r = GetLastError();
+
+    if (r == ERROR_INVALID_PARAMETER)
+      return UV_ESRCH;
+    else
+      return uv_translate_sys_error(r);
+  }
+
+  return 0;
+}
+
+
+int uv_os_getpriority(uv_pid_t pid, int* priority) {
+  HANDLE handle;
+  int r;
+
+  if (priority == NULL)
+    return UV_EINVAL;
+
+  r = uv__get_handle(pid, PROCESS_QUERY_LIMITED_INFORMATION, &handle);
+
+  if (r != 0)
+    return r;
+
+  r = GetPriorityClass(handle);
+
+  if (r == 0) {
+    r = uv_translate_sys_error(GetLastError());
+  } else {
+    /* Map Windows priority classes to Unix nice values. */
+    if (r == REALTIME_PRIORITY_CLASS)
+      *priority = UV_PRIORITY_HIGHEST;
+    else if (r == HIGH_PRIORITY_CLASS)
+      *priority = UV_PRIORITY_HIGH;
+    else if (r == ABOVE_NORMAL_PRIORITY_CLASS)
+      *priority = UV_PRIORITY_ABOVE_NORMAL;
+    else if (r == NORMAL_PRIORITY_CLASS)
+      *priority = UV_PRIORITY_NORMAL;
+    else if (r == BELOW_NORMAL_PRIORITY_CLASS)
+      *priority = UV_PRIORITY_BELOW_NORMAL;
+    else  /* IDLE_PRIORITY_CLASS */
+      *priority = UV_PRIORITY_LOW;
+
+    r = 0;
+  }
+
+  CloseHandle(handle);
+  return r;
+}
+
+
+int uv_os_setpriority(uv_pid_t pid, int priority) {
+  HANDLE handle;
+  int priority_class;
+  int r;
+
+  /* Map Unix nice values to Windows priority classes. */
+  if (priority < UV_PRIORITY_HIGHEST || priority > UV_PRIORITY_LOW)
+    return UV_EINVAL;
+  else if (priority < UV_PRIORITY_HIGH)
+    priority_class = REALTIME_PRIORITY_CLASS;
+  else if (priority < UV_PRIORITY_ABOVE_NORMAL)
+    priority_class = HIGH_PRIORITY_CLASS;
+  else if (priority < UV_PRIORITY_NORMAL)
+    priority_class = ABOVE_NORMAL_PRIORITY_CLASS;
+  else if (priority < UV_PRIORITY_BELOW_NORMAL)
+    priority_class = NORMAL_PRIORITY_CLASS;
+  else if (priority < UV_PRIORITY_LOW)
+    priority_class = BELOW_NORMAL_PRIORITY_CLASS;
+  else
+    priority_class = IDLE_PRIORITY_CLASS;
+
+  r = uv__get_handle(pid, PROCESS_SET_INFORMATION, &handle);
+
+  if (r != 0)
+    return r;
+
+  if (SetPriorityClass(handle, priority_class) == 0)
+    r = uv_translate_sys_error(GetLastError());
+
+  CloseHandle(handle);
+  return r;
+}
+
+
+int uv_os_uname(uv_utsname_t* buffer) {
+  /* Implementation loosely based on
+     https://github.com/gagern/gnulib/blob/master/lib/uname.c */
+  OSVERSIONINFOW os_info;
+  SYSTEM_INFO system_info;
+  HKEY registry_key;
+  WCHAR product_name_w[256];
+  DWORD product_name_w_size;
+  int version_size;
+  int processor_level;
+  int r;
+
+  if (buffer == NULL)
+    return UV_EINVAL;
+
+  uv__once_init();
+  os_info.dwOSVersionInfoSize = sizeof(os_info);
+  os_info.szCSDVersion[0] = L'\0';
+
+  /* Try calling RtlGetVersion(), and fall back to the deprecated GetVersionEx()
+     if RtlGetVersion() is not available. */
+  if (pRtlGetVersion) {
+    pRtlGetVersion(&os_info);
+  } else {
+    /* Silence GetVersionEx() deprecation warning. */
+    #ifdef _MSC_VER
+    #pragma warning(disable : 4996)
+    #endif
+    if (GetVersionExW(&os_info) == 0) {
+      r = uv_translate_sys_error(GetLastError());
+      goto error;
+    }
+  }
+
+  /* Populate the version field. */
+  version_size = 0;
+  r = RegOpenKeyExW(HKEY_LOCAL_MACHINE,
+                    L"SOFTWARE\\Microsoft\\Windows NT\\CurrentVersion",
+                    0,
+                    KEY_QUERY_VALUE,
+                    &registry_key);
+
+  if (r == ERROR_SUCCESS) {
+    product_name_w_size = sizeof(product_name_w);
+    r = RegGetValueW(registry_key,
+                     NULL,
+                     L"ProductName",
+                     RRF_RT_REG_SZ,
+                     NULL,
+                     (PVOID) product_name_w,
+                     &product_name_w_size);
+    RegCloseKey(registry_key);
+
+    if (r == ERROR_SUCCESS) {
+      version_size = WideCharToMultiByte(CP_UTF8,
+                                         0,
+                                         product_name_w,
+                                         -1,
+                                         buffer->version,
+                                         sizeof(buffer->version),
+                                         NULL,
+                                         NULL);
+      if (version_size == 0) {
+        r = uv_translate_sys_error(GetLastError());
+        goto error;
+      }
+    }
+  }
+
+  /* Append service pack information to the version if present. */
+  if (os_info.szCSDVersion[0] != L'\0') {
+    if (version_size > 0)
+      buffer->version[version_size - 1] = ' ';
+
+    if (WideCharToMultiByte(CP_UTF8,
+                            0,
+                            os_info.szCSDVersion,
+                            -1,
+                            buffer->version + version_size,
+                            sizeof(buffer->version) - version_size,
+                            NULL,
+                            NULL) == 0) {
+      r = uv_translate_sys_error(GetLastError());
+      goto error;
+    }
+  }
+
+  /* Populate the sysname field. */
+#ifdef __MINGW32__
+  r = snprintf(buffer->sysname,
+               sizeof(buffer->sysname),
+               "MINGW32_NT-%u.%u",
+               (unsigned int) os_info.dwMajorVersion,
+               (unsigned int) os_info.dwMinorVersion);
+  assert((size_t)r < sizeof(buffer->sysname));
+#else
+  uv__strscpy(buffer->sysname, "Windows_NT", sizeof(buffer->sysname));
+#endif
+
+  /* Populate the release field. */
+  r = snprintf(buffer->release,
+               sizeof(buffer->release),
+               "%d.%d.%d",
+               (unsigned int) os_info.dwMajorVersion,
+               (unsigned int) os_info.dwMinorVersion,
+               (unsigned int) os_info.dwBuildNumber);
+  assert((size_t)r < sizeof(buffer->release));
+
+  /* Populate the machine field. */
+  GetSystemInfo(&system_info);
+
+  switch (system_info.wProcessorArchitecture) {
+    case PROCESSOR_ARCHITECTURE_AMD64:
+      uv__strscpy(buffer->machine, "x86_64", sizeof(buffer->machine));
+      break;
+    case PROCESSOR_ARCHITECTURE_IA64:
+      uv__strscpy(buffer->machine, "ia64", sizeof(buffer->machine));
+      break;
+    case PROCESSOR_ARCHITECTURE_INTEL:
+      uv__strscpy(buffer->machine, "i386", sizeof(buffer->machine));
+
+      if (system_info.wProcessorLevel > 3) {
+        processor_level = system_info.wProcessorLevel < 6 ?
+                          system_info.wProcessorLevel : 6;
+        buffer->machine[1] = '0' + processor_level;
+      }
+
+      break;
+    case PROCESSOR_ARCHITECTURE_IA32_ON_WIN64:
+      uv__strscpy(buffer->machine, "i686", sizeof(buffer->machine));
+      break;
+    case PROCESSOR_ARCHITECTURE_MIPS:
+      uv__strscpy(buffer->machine, "mips", sizeof(buffer->machine));
+      break;
+    case PROCESSOR_ARCHITECTURE_ALPHA:
+    case PROCESSOR_ARCHITECTURE_ALPHA64:
+      uv__strscpy(buffer->machine, "alpha", sizeof(buffer->machine));
+      break;
+    case PROCESSOR_ARCHITECTURE_PPC:
+      uv__strscpy(buffer->machine, "powerpc", sizeof(buffer->machine));
+      break;
+    case PROCESSOR_ARCHITECTURE_SHX:
+      uv__strscpy(buffer->machine, "sh", sizeof(buffer->machine));
+      break;
+    case PROCESSOR_ARCHITECTURE_ARM:
+      uv__strscpy(buffer->machine, "arm", sizeof(buffer->machine));
+      break;
+    default:
+      uv__strscpy(buffer->machine, "unknown", sizeof(buffer->machine));
+      break;
+  }
+
+  return 0;
+
+error:
+  buffer->sysname[0] = '\0';
+  buffer->release[0] = '\0';
+  buffer->version[0] = '\0';
+  buffer->machine[0] = '\0';
+  return r;
+}
+
+int uv_gettimeofday(uv_timeval64_t* tv) {
+  /* Based on https://doxygen.postgresql.org/gettimeofday_8c_source.html */
+  const uint64_t epoch = (uint64_t) 116444736000000000ULL;
+  FILETIME file_time;
+  ULARGE_INTEGER ularge;
+
+  if (tv == NULL)
+    return UV_EINVAL;
+
+  GetSystemTimeAsFileTime(&file_time);
+  ularge.LowPart = file_time.dwLowDateTime;
+  ularge.HighPart = file_time.dwHighDateTime;
+  tv->tv_sec = (int64_t) ((ularge.QuadPart - epoch) / 10000000L);
+  tv->tv_usec = (int32_t) (((ularge.QuadPart - epoch) % 10000000L) / 10);
+  return 0;
+}
+
+int uv__random_rtlgenrandom(void* buf, size_t buflen) {
+  if (buflen == 0)
+    return 0;
+
+  if (SystemFunction036(buf, buflen) == FALSE)
+    return UV_EIO;
+
+  return 0;
+}
+
+void uv_sleep(unsigned int msec) {
+  Sleep(msec);
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/winapi.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/winapi.cpp
new file mode 100644
index 0000000..53147b8
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/winapi.cpp
@@ -0,0 +1,147 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <assert.h>
+
+#include "uv.h"
+#include "internal.h"
+
+
+/* Ntdll function pointers */
+sRtlGetVersion pRtlGetVersion;
+sRtlNtStatusToDosError pRtlNtStatusToDosError;
+sNtDeviceIoControlFile pNtDeviceIoControlFile;
+sNtQueryInformationFile pNtQueryInformationFile;
+sNtSetInformationFile pNtSetInformationFile;
+sNtQueryVolumeInformationFile pNtQueryVolumeInformationFile;
+sNtQueryDirectoryFile pNtQueryDirectoryFile;
+sNtQuerySystemInformation pNtQuerySystemInformation;
+sNtQueryInformationProcess pNtQueryInformationProcess;
+
+/* Kernel32 function pointers */
+sGetQueuedCompletionStatusEx pGetQueuedCompletionStatusEx;
+
+/* Powrprof.dll function pointer */
+sPowerRegisterSuspendResumeNotification pPowerRegisterSuspendResumeNotification;
+
+/* User32.dll function pointer */
+sSetWinEventHook pSetWinEventHook;
+
+/* ws2_32.dll function pointer */
+uv_sGetHostNameW pGetHostNameW;
+
+void uv__winapi_init(void) {
+  HMODULE ntdll_module;
+  HMODULE powrprof_module;
+  HMODULE user32_module;
+  HMODULE kernel32_module;
+  HMODULE ws2_32_module;
+
+  ntdll_module = GetModuleHandleA("ntdll.dll");
+  if (ntdll_module == NULL) {
+    uv_fatal_error(GetLastError(), "GetModuleHandleA");
+  }
+
+  pRtlGetVersion = (sRtlGetVersion) GetProcAddress(ntdll_module,
+                                                   "RtlGetVersion");
+
+  pRtlNtStatusToDosError = (sRtlNtStatusToDosError) GetProcAddress(
+      ntdll_module,
+      "RtlNtStatusToDosError");
+  if (pRtlNtStatusToDosError == NULL) {
+    uv_fatal_error(GetLastError(), "GetProcAddress");
+  }
+
+  pNtDeviceIoControlFile = (sNtDeviceIoControlFile) GetProcAddress(
+      ntdll_module,
+      "NtDeviceIoControlFile");
+  if (pNtDeviceIoControlFile == NULL) {
+    uv_fatal_error(GetLastError(), "GetProcAddress");
+  }
+
+  pNtQueryInformationFile = (sNtQueryInformationFile) GetProcAddress(
+      ntdll_module,
+      "NtQueryInformationFile");
+  if (pNtQueryInformationFile == NULL) {
+    uv_fatal_error(GetLastError(), "GetProcAddress");
+  }
+
+  pNtSetInformationFile = (sNtSetInformationFile) GetProcAddress(
+      ntdll_module,
+      "NtSetInformationFile");
+  if (pNtSetInformationFile == NULL) {
+    uv_fatal_error(GetLastError(), "GetProcAddress");
+  }
+
+  pNtQueryVolumeInformationFile = (sNtQueryVolumeInformationFile)
+      GetProcAddress(ntdll_module, "NtQueryVolumeInformationFile");
+  if (pNtQueryVolumeInformationFile == NULL) {
+    uv_fatal_error(GetLastError(), "GetProcAddress");
+  }
+
+  pNtQueryDirectoryFile = (sNtQueryDirectoryFile)
+      GetProcAddress(ntdll_module, "NtQueryDirectoryFile");
+  if (pNtQueryVolumeInformationFile == NULL) {
+    uv_fatal_error(GetLastError(), "GetProcAddress");
+  }
+
+  pNtQuerySystemInformation = (sNtQuerySystemInformation) GetProcAddress(
+      ntdll_module,
+      "NtQuerySystemInformation");
+  if (pNtQuerySystemInformation == NULL) {
+    uv_fatal_error(GetLastError(), "GetProcAddress");
+  }
+
+  pNtQueryInformationProcess = (sNtQueryInformationProcess) GetProcAddress(
+      ntdll_module,
+      "NtQueryInformationProcess");
+  if (pNtQueryInformationProcess == NULL) {
+    uv_fatal_error(GetLastError(), "GetProcAddress");
+  }
+
+  kernel32_module = GetModuleHandleA("kernel32.dll");
+  if (kernel32_module == NULL) {
+    uv_fatal_error(GetLastError(), "GetModuleHandleA");
+  }
+
+  pGetQueuedCompletionStatusEx = (sGetQueuedCompletionStatusEx) GetProcAddress(
+      kernel32_module,
+      "GetQueuedCompletionStatusEx");
+
+  powrprof_module = LoadLibraryExA("powrprof.dll", NULL, LOAD_LIBRARY_SEARCH_SYSTEM32);
+  if (powrprof_module != NULL) {
+    pPowerRegisterSuspendResumeNotification = (sPowerRegisterSuspendResumeNotification)
+      GetProcAddress(powrprof_module, "PowerRegisterSuspendResumeNotification");
+  }
+
+  user32_module = GetModuleHandleA("user32.dll");
+  if (user32_module != NULL) {
+    pSetWinEventHook = (sSetWinEventHook)
+      GetProcAddress(user32_module, "SetWinEventHook");
+  }
+
+  ws2_32_module = GetModuleHandleA("ws2_32.dll");
+  if (ws2_32_module != NULL) {
+    pGetHostNameW = (uv_sGetHostNameW) GetProcAddress(
+        ws2_32_module,
+        "GetHostNameW");
+  }
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/winapi.h b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/winapi.h
new file mode 100644
index 0000000..d380bda
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/winapi.h
@@ -0,0 +1,4769 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#ifndef UV_WIN_WINAPI_H_
+#define UV_WIN_WINAPI_H_
+
+#include <windows.h>
+
+
+/*
+ * Ntdll headers
+ */
+#ifndef STATUS_SEVERITY_SUCCESS
+# define STATUS_SEVERITY_SUCCESS 0x0
+#endif
+
+#ifndef STATUS_SEVERITY_INFORMATIONAL
+# define STATUS_SEVERITY_INFORMATIONAL 0x1
+#endif
+
+#ifndef STATUS_SEVERITY_WARNING
+# define STATUS_SEVERITY_WARNING 0x2
+#endif
+
+#ifndef STATUS_SEVERITY_ERROR
+# define STATUS_SEVERITY_ERROR 0x3
+#endif
+
+#ifndef FACILITY_NTWIN32
+# define FACILITY_NTWIN32 0x7
+#endif
+
+#ifndef NT_SUCCESS
+# define NT_SUCCESS(status) (((NTSTATUS) (status)) >= 0)
+#endif
+
+#ifndef NT_INFORMATION
+# define NT_INFORMATION(status) ((((ULONG) (status)) >> 30) == 1)
+#endif
+
+#ifndef NT_WARNING
+# define NT_WARNING(status) ((((ULONG) (status)) >> 30) == 2)
+#endif
+
+#ifndef NT_ERROR
+# define NT_ERROR(status) ((((ULONG) (status)) >> 30) == 3)
+#endif
+
+#ifndef STATUS_SUCCESS
+# define STATUS_SUCCESS ((NTSTATUS) 0x00000000L)
+#endif
+
+#ifndef STATUS_WAIT_0
+# define STATUS_WAIT_0 ((NTSTATUS) 0x00000000L)
+#endif
+
+#ifndef STATUS_WAIT_1
+# define STATUS_WAIT_1 ((NTSTATUS) 0x00000001L)
+#endif
+
+#ifndef STATUS_WAIT_2
+# define STATUS_WAIT_2 ((NTSTATUS) 0x00000002L)
+#endif
+
+#ifndef STATUS_WAIT_3
+# define STATUS_WAIT_3 ((NTSTATUS) 0x00000003L)
+#endif
+
+#ifndef STATUS_WAIT_63
+# define STATUS_WAIT_63 ((NTSTATUS) 0x0000003FL)
+#endif
+
+#ifndef STATUS_ABANDONED
+# define STATUS_ABANDONED ((NTSTATUS) 0x00000080L)
+#endif
+
+#ifndef STATUS_ABANDONED_WAIT_0
+# define STATUS_ABANDONED_WAIT_0 ((NTSTATUS) 0x00000080L)
+#endif
+
+#ifndef STATUS_ABANDONED_WAIT_63
+# define STATUS_ABANDONED_WAIT_63 ((NTSTATUS) 0x000000BFL)
+#endif
+
+#ifndef STATUS_USER_APC
+# define STATUS_USER_APC ((NTSTATUS) 0x000000C0L)
+#endif
+
+#ifndef STATUS_KERNEL_APC
+# define STATUS_KERNEL_APC ((NTSTATUS) 0x00000100L)
+#endif
+
+#ifndef STATUS_ALERTED
+# define STATUS_ALERTED ((NTSTATUS) 0x00000101L)
+#endif
+
+#ifndef STATUS_TIMEOUT
+# define STATUS_TIMEOUT ((NTSTATUS) 0x00000102L)
+#endif
+
+#ifndef STATUS_PENDING
+# define STATUS_PENDING ((NTSTATUS) 0x00000103L)
+#endif
+
+#ifndef STATUS_REPARSE
+# define STATUS_REPARSE ((NTSTATUS) 0x00000104L)
+#endif
+
+#ifndef STATUS_MORE_ENTRIES
+# define STATUS_MORE_ENTRIES ((NTSTATUS) 0x00000105L)
+#endif
+
+#ifndef STATUS_NOT_ALL_ASSIGNED
+# define STATUS_NOT_ALL_ASSIGNED ((NTSTATUS) 0x00000106L)
+#endif
+
+#ifndef STATUS_SOME_NOT_MAPPED
+# define STATUS_SOME_NOT_MAPPED ((NTSTATUS) 0x00000107L)
+#endif
+
+#ifndef STATUS_OPLOCK_BREAK_IN_PROGRESS
+# define STATUS_OPLOCK_BREAK_IN_PROGRESS ((NTSTATUS) 0x00000108L)
+#endif
+
+#ifndef STATUS_VOLUME_MOUNTED
+# define STATUS_VOLUME_MOUNTED ((NTSTATUS) 0x00000109L)
+#endif
+
+#ifndef STATUS_RXACT_COMMITTED
+# define STATUS_RXACT_COMMITTED ((NTSTATUS) 0x0000010AL)
+#endif
+
+#ifndef STATUS_NOTIFY_CLEANUP
+# define STATUS_NOTIFY_CLEANUP ((NTSTATUS) 0x0000010BL)
+#endif
+
+#ifndef STATUS_NOTIFY_ENUM_DIR
+# define STATUS_NOTIFY_ENUM_DIR ((NTSTATUS) 0x0000010CL)
+#endif
+
+#ifndef STATUS_NO_QUOTAS_FOR_ACCOUNT
+# define STATUS_NO_QUOTAS_FOR_ACCOUNT ((NTSTATUS) 0x0000010DL)
+#endif
+
+#ifndef STATUS_PRIMARY_TRANSPORT_CONNECT_FAILED
+# define STATUS_PRIMARY_TRANSPORT_CONNECT_FAILED ((NTSTATUS) 0x0000010EL)
+#endif
+
+#ifndef STATUS_PAGE_FAULT_TRANSITION
+# define STATUS_PAGE_FAULT_TRANSITION ((NTSTATUS) 0x00000110L)
+#endif
+
+#ifndef STATUS_PAGE_FAULT_DEMAND_ZERO
+# define STATUS_PAGE_FAULT_DEMAND_ZERO ((NTSTATUS) 0x00000111L)
+#endif
+
+#ifndef STATUS_PAGE_FAULT_COPY_ON_WRITE
+# define STATUS_PAGE_FAULT_COPY_ON_WRITE ((NTSTATUS) 0x00000112L)
+#endif
+
+#ifndef STATUS_PAGE_FAULT_GUARD_PAGE
+# define STATUS_PAGE_FAULT_GUARD_PAGE ((NTSTATUS) 0x00000113L)
+#endif
+
+#ifndef STATUS_PAGE_FAULT_PAGING_FILE
+# define STATUS_PAGE_FAULT_PAGING_FILE ((NTSTATUS) 0x00000114L)
+#endif
+
+#ifndef STATUS_CACHE_PAGE_LOCKED
+# define STATUS_CACHE_PAGE_LOCKED ((NTSTATUS) 0x00000115L)
+#endif
+
+#ifndef STATUS_CRASH_DUMP
+# define STATUS_CRASH_DUMP ((NTSTATUS) 0x00000116L)
+#endif
+
+#ifndef STATUS_BUFFER_ALL_ZEROS
+# define STATUS_BUFFER_ALL_ZEROS ((NTSTATUS) 0x00000117L)
+#endif
+
+#ifndef STATUS_REPARSE_OBJECT
+# define STATUS_REPARSE_OBJECT ((NTSTATUS) 0x00000118L)
+#endif
+
+#ifndef STATUS_RESOURCE_REQUIREMENTS_CHANGED
+# define STATUS_RESOURCE_REQUIREMENTS_CHANGED ((NTSTATUS) 0x00000119L)
+#endif
+
+#ifndef STATUS_TRANSLATION_COMPLETE
+# define STATUS_TRANSLATION_COMPLETE ((NTSTATUS) 0x00000120L)
+#endif
+
+#ifndef STATUS_DS_MEMBERSHIP_EVALUATED_LOCALLY
+# define STATUS_DS_MEMBERSHIP_EVALUATED_LOCALLY ((NTSTATUS) 0x00000121L)
+#endif
+
+#ifndef STATUS_NOTHING_TO_TERMINATE
+# define STATUS_NOTHING_TO_TERMINATE ((NTSTATUS) 0x00000122L)
+#endif
+
+#ifndef STATUS_PROCESS_NOT_IN_JOB
+# define STATUS_PROCESS_NOT_IN_JOB ((NTSTATUS) 0x00000123L)
+#endif
+
+#ifndef STATUS_PROCESS_IN_JOB
+# define STATUS_PROCESS_IN_JOB ((NTSTATUS) 0x00000124L)
+#endif
+
+#ifndef STATUS_VOLSNAP_HIBERNATE_READY
+# define STATUS_VOLSNAP_HIBERNATE_READY ((NTSTATUS) 0x00000125L)
+#endif
+
+#ifndef STATUS_FSFILTER_OP_COMPLETED_SUCCESSFULLY
+# define STATUS_FSFILTER_OP_COMPLETED_SUCCESSFULLY ((NTSTATUS) 0x00000126L)
+#endif
+
+#ifndef STATUS_INTERRUPT_VECTOR_ALREADY_CONNECTED
+# define STATUS_INTERRUPT_VECTOR_ALREADY_CONNECTED ((NTSTATUS) 0x00000127L)
+#endif
+
+#ifndef STATUS_INTERRUPT_STILL_CONNECTED
+# define STATUS_INTERRUPT_STILL_CONNECTED ((NTSTATUS) 0x00000128L)
+#endif
+
+#ifndef STATUS_PROCESS_CLONED
+# define STATUS_PROCESS_CLONED ((NTSTATUS) 0x00000129L)
+#endif
+
+#ifndef STATUS_FILE_LOCKED_WITH_ONLY_READERS
+# define STATUS_FILE_LOCKED_WITH_ONLY_READERS ((NTSTATUS) 0x0000012AL)
+#endif
+
+#ifndef STATUS_FILE_LOCKED_WITH_WRITERS
+# define STATUS_FILE_LOCKED_WITH_WRITERS ((NTSTATUS) 0x0000012BL)
+#endif
+
+#ifndef STATUS_RESOURCEMANAGER_READ_ONLY
+# define STATUS_RESOURCEMANAGER_READ_ONLY ((NTSTATUS) 0x00000202L)
+#endif
+
+#ifndef STATUS_RING_PREVIOUSLY_EMPTY
+# define STATUS_RING_PREVIOUSLY_EMPTY ((NTSTATUS) 0x00000210L)
+#endif
+
+#ifndef STATUS_RING_PREVIOUSLY_FULL
+# define STATUS_RING_PREVIOUSLY_FULL ((NTSTATUS) 0x00000211L)
+#endif
+
+#ifndef STATUS_RING_PREVIOUSLY_ABOVE_QUOTA
+# define STATUS_RING_PREVIOUSLY_ABOVE_QUOTA ((NTSTATUS) 0x00000212L)
+#endif
+
+#ifndef STATUS_RING_NEWLY_EMPTY
+# define STATUS_RING_NEWLY_EMPTY ((NTSTATUS) 0x00000213L)
+#endif
+
+#ifndef STATUS_RING_SIGNAL_OPPOSITE_ENDPOINT
+# define STATUS_RING_SIGNAL_OPPOSITE_ENDPOINT ((NTSTATUS) 0x00000214L)
+#endif
+
+#ifndef STATUS_OPLOCK_SWITCHED_TO_NEW_HANDLE
+# define STATUS_OPLOCK_SWITCHED_TO_NEW_HANDLE ((NTSTATUS) 0x00000215L)
+#endif
+
+#ifndef STATUS_OPLOCK_HANDLE_CLOSED
+# define STATUS_OPLOCK_HANDLE_CLOSED ((NTSTATUS) 0x00000216L)
+#endif
+
+#ifndef STATUS_WAIT_FOR_OPLOCK
+# define STATUS_WAIT_FOR_OPLOCK ((NTSTATUS) 0x00000367L)
+#endif
+
+#ifndef STATUS_OBJECT_NAME_EXISTS
+# define STATUS_OBJECT_NAME_EXISTS ((NTSTATUS) 0x40000000L)
+#endif
+
+#ifndef STATUS_THREAD_WAS_SUSPENDED
+# define STATUS_THREAD_WAS_SUSPENDED ((NTSTATUS) 0x40000001L)
+#endif
+
+#ifndef STATUS_WORKING_SET_LIMIT_RANGE
+# define STATUS_WORKING_SET_LIMIT_RANGE ((NTSTATUS) 0x40000002L)
+#endif
+
+#ifndef STATUS_IMAGE_NOT_AT_BASE
+# define STATUS_IMAGE_NOT_AT_BASE ((NTSTATUS) 0x40000003L)
+#endif
+
+#ifndef STATUS_RXACT_STATE_CREATED
+# define STATUS_RXACT_STATE_CREATED ((NTSTATUS) 0x40000004L)
+#endif
+
+#ifndef STATUS_SEGMENT_NOTIFICATION
+# define STATUS_SEGMENT_NOTIFICATION ((NTSTATUS) 0x40000005L)
+#endif
+
+#ifndef STATUS_LOCAL_USER_SESSION_KEY
+# define STATUS_LOCAL_USER_SESSION_KEY ((NTSTATUS) 0x40000006L)
+#endif
+
+#ifndef STATUS_BAD_CURRENT_DIRECTORY
+# define STATUS_BAD_CURRENT_DIRECTORY ((NTSTATUS) 0x40000007L)
+#endif
+
+#ifndef STATUS_SERIAL_MORE_WRITES
+# define STATUS_SERIAL_MORE_WRITES ((NTSTATUS) 0x40000008L)
+#endif
+
+#ifndef STATUS_REGISTRY_RECOVERED
+# define STATUS_REGISTRY_RECOVERED ((NTSTATUS) 0x40000009L)
+#endif
+
+#ifndef STATUS_FT_READ_RECOVERY_FROM_BACKUP
+# define STATUS_FT_READ_RECOVERY_FROM_BACKUP ((NTSTATUS) 0x4000000AL)
+#endif
+
+#ifndef STATUS_FT_WRITE_RECOVERY
+# define STATUS_FT_WRITE_RECOVERY ((NTSTATUS) 0x4000000BL)
+#endif
+
+#ifndef STATUS_SERIAL_COUNTER_TIMEOUT
+# define STATUS_SERIAL_COUNTER_TIMEOUT ((NTSTATUS) 0x4000000CL)
+#endif
+
+#ifndef STATUS_NULL_LM_PASSWORD
+# define STATUS_NULL_LM_PASSWORD ((NTSTATUS) 0x4000000DL)
+#endif
+
+#ifndef STATUS_IMAGE_MACHINE_TYPE_MISMATCH
+# define STATUS_IMAGE_MACHINE_TYPE_MISMATCH ((NTSTATUS) 0x4000000EL)
+#endif
+
+#ifndef STATUS_RECEIVE_PARTIAL
+# define STATUS_RECEIVE_PARTIAL ((NTSTATUS) 0x4000000FL)
+#endif
+
+#ifndef STATUS_RECEIVE_EXPEDITED
+# define STATUS_RECEIVE_EXPEDITED ((NTSTATUS) 0x40000010L)
+#endif
+
+#ifndef STATUS_RECEIVE_PARTIAL_EXPEDITED
+# define STATUS_RECEIVE_PARTIAL_EXPEDITED ((NTSTATUS) 0x40000011L)
+#endif
+
+#ifndef STATUS_EVENT_DONE
+# define STATUS_EVENT_DONE ((NTSTATUS) 0x40000012L)
+#endif
+
+#ifndef STATUS_EVENT_PENDING
+# define STATUS_EVENT_PENDING ((NTSTATUS) 0x40000013L)
+#endif
+
+#ifndef STATUS_CHECKING_FILE_SYSTEM
+# define STATUS_CHECKING_FILE_SYSTEM ((NTSTATUS) 0x40000014L)
+#endif
+
+#ifndef STATUS_FATAL_APP_EXIT
+# define STATUS_FATAL_APP_EXIT ((NTSTATUS) 0x40000015L)
+#endif
+
+#ifndef STATUS_PREDEFINED_HANDLE
+# define STATUS_PREDEFINED_HANDLE ((NTSTATUS) 0x40000016L)
+#endif
+
+#ifndef STATUS_WAS_UNLOCKED
+# define STATUS_WAS_UNLOCKED ((NTSTATUS) 0x40000017L)
+#endif
+
+#ifndef STATUS_SERVICE_NOTIFICATION
+# define STATUS_SERVICE_NOTIFICATION ((NTSTATUS) 0x40000018L)
+#endif
+
+#ifndef STATUS_WAS_LOCKED
+# define STATUS_WAS_LOCKED ((NTSTATUS) 0x40000019L)
+#endif
+
+#ifndef STATUS_LOG_HARD_ERROR
+# define STATUS_LOG_HARD_ERROR ((NTSTATUS) 0x4000001AL)
+#endif
+
+#ifndef STATUS_ALREADY_WIN32
+# define STATUS_ALREADY_WIN32 ((NTSTATUS) 0x4000001BL)
+#endif
+
+#ifndef STATUS_WX86_UNSIMULATE
+# define STATUS_WX86_UNSIMULATE ((NTSTATUS) 0x4000001CL)
+#endif
+
+#ifndef STATUS_WX86_CONTINUE
+# define STATUS_WX86_CONTINUE ((NTSTATUS) 0x4000001DL)
+#endif
+
+#ifndef STATUS_WX86_SINGLE_STEP
+# define STATUS_WX86_SINGLE_STEP ((NTSTATUS) 0x4000001EL)
+#endif
+
+#ifndef STATUS_WX86_BREAKPOINT
+# define STATUS_WX86_BREAKPOINT ((NTSTATUS) 0x4000001FL)
+#endif
+
+#ifndef STATUS_WX86_EXCEPTION_CONTINUE
+# define STATUS_WX86_EXCEPTION_CONTINUE ((NTSTATUS) 0x40000020L)
+#endif
+
+#ifndef STATUS_WX86_EXCEPTION_LASTCHANCE
+# define STATUS_WX86_EXCEPTION_LASTCHANCE ((NTSTATUS) 0x40000021L)
+#endif
+
+#ifndef STATUS_WX86_EXCEPTION_CHAIN
+# define STATUS_WX86_EXCEPTION_CHAIN ((NTSTATUS) 0x40000022L)
+#endif
+
+#ifndef STATUS_IMAGE_MACHINE_TYPE_MISMATCH_EXE
+# define STATUS_IMAGE_MACHINE_TYPE_MISMATCH_EXE ((NTSTATUS) 0x40000023L)
+#endif
+
+#ifndef STATUS_NO_YIELD_PERFORMED
+# define STATUS_NO_YIELD_PERFORMED ((NTSTATUS) 0x40000024L)
+#endif
+
+#ifndef STATUS_TIMER_RESUME_IGNORED
+# define STATUS_TIMER_RESUME_IGNORED ((NTSTATUS) 0x40000025L)
+#endif
+
+#ifndef STATUS_ARBITRATION_UNHANDLED
+# define STATUS_ARBITRATION_UNHANDLED ((NTSTATUS) 0x40000026L)
+#endif
+
+#ifndef STATUS_CARDBUS_NOT_SUPPORTED
+# define STATUS_CARDBUS_NOT_SUPPORTED ((NTSTATUS) 0x40000027L)
+#endif
+
+#ifndef STATUS_WX86_CREATEWX86TIB
+# define STATUS_WX86_CREATEWX86TIB ((NTSTATUS) 0x40000028L)
+#endif
+
+#ifndef STATUS_MP_PROCESSOR_MISMATCH
+# define STATUS_MP_PROCESSOR_MISMATCH ((NTSTATUS) 0x40000029L)
+#endif
+
+#ifndef STATUS_HIBERNATED
+# define STATUS_HIBERNATED ((NTSTATUS) 0x4000002AL)
+#endif
+
+#ifndef STATUS_RESUME_HIBERNATION
+# define STATUS_RESUME_HIBERNATION ((NTSTATUS) 0x4000002BL)
+#endif
+
+#ifndef STATUS_FIRMWARE_UPDATED
+# define STATUS_FIRMWARE_UPDATED ((NTSTATUS) 0x4000002CL)
+#endif
+
+#ifndef STATUS_DRIVERS_LEAKING_LOCKED_PAGES
+# define STATUS_DRIVERS_LEAKING_LOCKED_PAGES ((NTSTATUS) 0x4000002DL)
+#endif
+
+#ifndef STATUS_MESSAGE_RETRIEVED
+# define STATUS_MESSAGE_RETRIEVED ((NTSTATUS) 0x4000002EL)
+#endif
+
+#ifndef STATUS_SYSTEM_POWERSTATE_TRANSITION
+# define STATUS_SYSTEM_POWERSTATE_TRANSITION ((NTSTATUS) 0x4000002FL)
+#endif
+
+#ifndef STATUS_ALPC_CHECK_COMPLETION_LIST
+# define STATUS_ALPC_CHECK_COMPLETION_LIST ((NTSTATUS) 0x40000030L)
+#endif
+
+#ifndef STATUS_SYSTEM_POWERSTATE_COMPLEX_TRANSITION
+# define STATUS_SYSTEM_POWERSTATE_COMPLEX_TRANSITION ((NTSTATUS) 0x40000031L)
+#endif
+
+#ifndef STATUS_ACCESS_AUDIT_BY_POLICY
+# define STATUS_ACCESS_AUDIT_BY_POLICY ((NTSTATUS) 0x40000032L)
+#endif
+
+#ifndef STATUS_ABANDON_HIBERFILE
+# define STATUS_ABANDON_HIBERFILE ((NTSTATUS) 0x40000033L)
+#endif
+
+#ifndef STATUS_BIZRULES_NOT_ENABLED
+# define STATUS_BIZRULES_NOT_ENABLED ((NTSTATUS) 0x40000034L)
+#endif
+
+#ifndef STATUS_GUARD_PAGE_VIOLATION
+# define STATUS_GUARD_PAGE_VIOLATION ((NTSTATUS) 0x80000001L)
+#endif
+
+#ifndef STATUS_DATATYPE_MISALIGNMENT
+# define STATUS_DATATYPE_MISALIGNMENT ((NTSTATUS) 0x80000002L)
+#endif
+
+#ifndef STATUS_BREAKPOINT
+# define STATUS_BREAKPOINT ((NTSTATUS) 0x80000003L)
+#endif
+
+#ifndef STATUS_SINGLE_STEP
+# define STATUS_SINGLE_STEP ((NTSTATUS) 0x80000004L)
+#endif
+
+#ifndef STATUS_BUFFER_OVERFLOW
+# define STATUS_BUFFER_OVERFLOW ((NTSTATUS) 0x80000005L)
+#endif
+
+#ifndef STATUS_NO_MORE_FILES
+# define STATUS_NO_MORE_FILES ((NTSTATUS) 0x80000006L)
+#endif
+
+#ifndef STATUS_WAKE_SYSTEM_DEBUGGER
+# define STATUS_WAKE_SYSTEM_DEBUGGER ((NTSTATUS) 0x80000007L)
+#endif
+
+#ifndef STATUS_HANDLES_CLOSED
+# define STATUS_HANDLES_CLOSED ((NTSTATUS) 0x8000000AL)
+#endif
+
+#ifndef STATUS_NO_INHERITANCE
+# define STATUS_NO_INHERITANCE ((NTSTATUS) 0x8000000BL)
+#endif
+
+#ifndef STATUS_GUID_SUBSTITUTION_MADE
+# define STATUS_GUID_SUBSTITUTION_MADE ((NTSTATUS) 0x8000000CL)
+#endif
+
+#ifndef STATUS_PARTIAL_COPY
+# define STATUS_PARTIAL_COPY ((NTSTATUS) 0x8000000DL)
+#endif
+
+#ifndef STATUS_DEVICE_PAPER_EMPTY
+# define STATUS_DEVICE_PAPER_EMPTY ((NTSTATUS) 0x8000000EL)
+#endif
+
+#ifndef STATUS_DEVICE_POWERED_OFF
+# define STATUS_DEVICE_POWERED_OFF ((NTSTATUS) 0x8000000FL)
+#endif
+
+#ifndef STATUS_DEVICE_OFF_LINE
+# define STATUS_DEVICE_OFF_LINE ((NTSTATUS) 0x80000010L)
+#endif
+
+#ifndef STATUS_DEVICE_BUSY
+# define STATUS_DEVICE_BUSY ((NTSTATUS) 0x80000011L)
+#endif
+
+#ifndef STATUS_NO_MORE_EAS
+# define STATUS_NO_MORE_EAS ((NTSTATUS) 0x80000012L)
+#endif
+
+#ifndef STATUS_INVALID_EA_NAME
+# define STATUS_INVALID_EA_NAME ((NTSTATUS) 0x80000013L)
+#endif
+
+#ifndef STATUS_EA_LIST_INCONSISTENT
+# define STATUS_EA_LIST_INCONSISTENT ((NTSTATUS) 0x80000014L)
+#endif
+
+#ifndef STATUS_INVALID_EA_FLAG
+# define STATUS_INVALID_EA_FLAG ((NTSTATUS) 0x80000015L)
+#endif
+
+#ifndef STATUS_VERIFY_REQUIRED
+# define STATUS_VERIFY_REQUIRED ((NTSTATUS) 0x80000016L)
+#endif
+
+#ifndef STATUS_EXTRANEOUS_INFORMATION
+# define STATUS_EXTRANEOUS_INFORMATION ((NTSTATUS) 0x80000017L)
+#endif
+
+#ifndef STATUS_RXACT_COMMIT_NECESSARY
+# define STATUS_RXACT_COMMIT_NECESSARY ((NTSTATUS) 0x80000018L)
+#endif
+
+#ifndef STATUS_NO_MORE_ENTRIES
+# define STATUS_NO_MORE_ENTRIES ((NTSTATUS) 0x8000001AL)
+#endif
+
+#ifndef STATUS_FILEMARK_DETECTED
+# define STATUS_FILEMARK_DETECTED ((NTSTATUS) 0x8000001BL)
+#endif
+
+#ifndef STATUS_MEDIA_CHANGED
+# define STATUS_MEDIA_CHANGED ((NTSTATUS) 0x8000001CL)
+#endif
+
+#ifndef STATUS_BUS_RESET
+# define STATUS_BUS_RESET ((NTSTATUS) 0x8000001DL)
+#endif
+
+#ifndef STATUS_END_OF_MEDIA
+# define STATUS_END_OF_MEDIA ((NTSTATUS) 0x8000001EL)
+#endif
+
+#ifndef STATUS_BEGINNING_OF_MEDIA
+# define STATUS_BEGINNING_OF_MEDIA ((NTSTATUS) 0x8000001FL)
+#endif
+
+#ifndef STATUS_MEDIA_CHECK
+# define STATUS_MEDIA_CHECK ((NTSTATUS) 0x80000020L)
+#endif
+
+#ifndef STATUS_SETMARK_DETECTED
+# define STATUS_SETMARK_DETECTED ((NTSTATUS) 0x80000021L)
+#endif
+
+#ifndef STATUS_NO_DATA_DETECTED
+# define STATUS_NO_DATA_DETECTED ((NTSTATUS) 0x80000022L)
+#endif
+
+#ifndef STATUS_REDIRECTOR_HAS_OPEN_HANDLES
+# define STATUS_REDIRECTOR_HAS_OPEN_HANDLES ((NTSTATUS) 0x80000023L)
+#endif
+
+#ifndef STATUS_SERVER_HAS_OPEN_HANDLES
+# define STATUS_SERVER_HAS_OPEN_HANDLES ((NTSTATUS) 0x80000024L)
+#endif
+
+#ifndef STATUS_ALREADY_DISCONNECTED
+# define STATUS_ALREADY_DISCONNECTED ((NTSTATUS) 0x80000025L)
+#endif
+
+#ifndef STATUS_LONGJUMP
+# define STATUS_LONGJUMP ((NTSTATUS) 0x80000026L)
+#endif
+
+#ifndef STATUS_CLEANER_CARTRIDGE_INSTALLED
+# define STATUS_CLEANER_CARTRIDGE_INSTALLED ((NTSTATUS) 0x80000027L)
+#endif
+
+#ifndef STATUS_PLUGPLAY_QUERY_VETOED
+# define STATUS_PLUGPLAY_QUERY_VETOED ((NTSTATUS) 0x80000028L)
+#endif
+
+#ifndef STATUS_UNWIND_CONSOLIDATE
+# define STATUS_UNWIND_CONSOLIDATE ((NTSTATUS) 0x80000029L)
+#endif
+
+#ifndef STATUS_REGISTRY_HIVE_RECOVERED
+# define STATUS_REGISTRY_HIVE_RECOVERED ((NTSTATUS) 0x8000002AL)
+#endif
+
+#ifndef STATUS_DLL_MIGHT_BE_INSECURE
+# define STATUS_DLL_MIGHT_BE_INSECURE ((NTSTATUS) 0x8000002BL)
+#endif
+
+#ifndef STATUS_DLL_MIGHT_BE_INCOMPATIBLE
+# define STATUS_DLL_MIGHT_BE_INCOMPATIBLE ((NTSTATUS) 0x8000002CL)
+#endif
+
+#ifndef STATUS_STOPPED_ON_SYMLINK
+# define STATUS_STOPPED_ON_SYMLINK ((NTSTATUS) 0x8000002DL)
+#endif
+
+#ifndef STATUS_CANNOT_GRANT_REQUESTED_OPLOCK
+# define STATUS_CANNOT_GRANT_REQUESTED_OPLOCK ((NTSTATUS) 0x8000002EL)
+#endif
+
+#ifndef STATUS_NO_ACE_CONDITION
+# define STATUS_NO_ACE_CONDITION ((NTSTATUS) 0x8000002FL)
+#endif
+
+#ifndef STATUS_UNSUCCESSFUL
+# define STATUS_UNSUCCESSFUL ((NTSTATUS) 0xC0000001L)
+#endif
+
+#ifndef STATUS_NOT_IMPLEMENTED
+# define STATUS_NOT_IMPLEMENTED ((NTSTATUS) 0xC0000002L)
+#endif
+
+#ifndef STATUS_INVALID_INFO_CLASS
+# define STATUS_INVALID_INFO_CLASS ((NTSTATUS) 0xC0000003L)
+#endif
+
+#ifndef STATUS_INFO_LENGTH_MISMATCH
+# define STATUS_INFO_LENGTH_MISMATCH ((NTSTATUS) 0xC0000004L)
+#endif
+
+#ifndef STATUS_ACCESS_VIOLATION
+# define STATUS_ACCESS_VIOLATION ((NTSTATUS) 0xC0000005L)
+#endif
+
+#ifndef STATUS_IN_PAGE_ERROR
+# define STATUS_IN_PAGE_ERROR ((NTSTATUS) 0xC0000006L)
+#endif
+
+#ifndef STATUS_PAGEFILE_QUOTA
+# define STATUS_PAGEFILE_QUOTA ((NTSTATUS) 0xC0000007L)
+#endif
+
+#ifndef STATUS_INVALID_HANDLE
+# define STATUS_INVALID_HANDLE ((NTSTATUS) 0xC0000008L)
+#endif
+
+#ifndef STATUS_BAD_INITIAL_STACK
+# define STATUS_BAD_INITIAL_STACK ((NTSTATUS) 0xC0000009L)
+#endif
+
+#ifndef STATUS_BAD_INITIAL_PC
+# define STATUS_BAD_INITIAL_PC ((NTSTATUS) 0xC000000AL)
+#endif
+
+#ifndef STATUS_INVALID_CID
+# define STATUS_INVALID_CID ((NTSTATUS) 0xC000000BL)
+#endif
+
+#ifndef STATUS_TIMER_NOT_CANCELED
+# define STATUS_TIMER_NOT_CANCELED ((NTSTATUS) 0xC000000CL)
+#endif
+
+#ifndef STATUS_INVALID_PARAMETER
+# define STATUS_INVALID_PARAMETER ((NTSTATUS) 0xC000000DL)
+#endif
+
+#ifndef STATUS_NO_SUCH_DEVICE
+# define STATUS_NO_SUCH_DEVICE ((NTSTATUS) 0xC000000EL)
+#endif
+
+#ifndef STATUS_NO_SUCH_FILE
+# define STATUS_NO_SUCH_FILE ((NTSTATUS) 0xC000000FL)
+#endif
+
+#ifndef STATUS_INVALID_DEVICE_REQUEST
+# define STATUS_INVALID_DEVICE_REQUEST ((NTSTATUS) 0xC0000010L)
+#endif
+
+#ifndef STATUS_END_OF_FILE
+# define STATUS_END_OF_FILE ((NTSTATUS) 0xC0000011L)
+#endif
+
+#ifndef STATUS_WRONG_VOLUME
+# define STATUS_WRONG_VOLUME ((NTSTATUS) 0xC0000012L)
+#endif
+
+#ifndef STATUS_NO_MEDIA_IN_DEVICE
+# define STATUS_NO_MEDIA_IN_DEVICE ((NTSTATUS) 0xC0000013L)
+#endif
+
+#ifndef STATUS_UNRECOGNIZED_MEDIA
+# define STATUS_UNRECOGNIZED_MEDIA ((NTSTATUS) 0xC0000014L)
+#endif
+
+#ifndef STATUS_NONEXISTENT_SECTOR
+# define STATUS_NONEXISTENT_SECTOR ((NTSTATUS) 0xC0000015L)
+#endif
+
+#ifndef STATUS_MORE_PROCESSING_REQUIRED
+# define STATUS_MORE_PROCESSING_REQUIRED ((NTSTATUS) 0xC0000016L)
+#endif
+
+#ifndef STATUS_NO_MEMORY
+# define STATUS_NO_MEMORY ((NTSTATUS) 0xC0000017L)
+#endif
+
+#ifndef STATUS_CONFLICTING_ADDRESSES
+# define STATUS_CONFLICTING_ADDRESSES ((NTSTATUS) 0xC0000018L)
+#endif
+
+#ifndef STATUS_NOT_MAPPED_VIEW
+# define STATUS_NOT_MAPPED_VIEW ((NTSTATUS) 0xC0000019L)
+#endif
+
+#ifndef STATUS_UNABLE_TO_FREE_VM
+# define STATUS_UNABLE_TO_FREE_VM ((NTSTATUS) 0xC000001AL)
+#endif
+
+#ifndef STATUS_UNABLE_TO_DELETE_SECTION
+# define STATUS_UNABLE_TO_DELETE_SECTION ((NTSTATUS) 0xC000001BL)
+#endif
+
+#ifndef STATUS_INVALID_SYSTEM_SERVICE
+# define STATUS_INVALID_SYSTEM_SERVICE ((NTSTATUS) 0xC000001CL)
+#endif
+
+#ifndef STATUS_ILLEGAL_INSTRUCTION
+# define STATUS_ILLEGAL_INSTRUCTION ((NTSTATUS) 0xC000001DL)
+#endif
+
+#ifndef STATUS_INVALID_LOCK_SEQUENCE
+# define STATUS_INVALID_LOCK_SEQUENCE ((NTSTATUS) 0xC000001EL)
+#endif
+
+#ifndef STATUS_INVALID_VIEW_SIZE
+# define STATUS_INVALID_VIEW_SIZE ((NTSTATUS) 0xC000001FL)
+#endif
+
+#ifndef STATUS_INVALID_FILE_FOR_SECTION
+# define STATUS_INVALID_FILE_FOR_SECTION ((NTSTATUS) 0xC0000020L)
+#endif
+
+#ifndef STATUS_ALREADY_COMMITTED
+# define STATUS_ALREADY_COMMITTED ((NTSTATUS) 0xC0000021L)
+#endif
+
+#ifndef STATUS_ACCESS_DENIED
+# define STATUS_ACCESS_DENIED ((NTSTATUS) 0xC0000022L)
+#endif
+
+#ifndef STATUS_BUFFER_TOO_SMALL
+# define STATUS_BUFFER_TOO_SMALL ((NTSTATUS) 0xC0000023L)
+#endif
+
+#ifndef STATUS_OBJECT_TYPE_MISMATCH
+# define STATUS_OBJECT_TYPE_MISMATCH ((NTSTATUS) 0xC0000024L)
+#endif
+
+#ifndef STATUS_NONCONTINUABLE_EXCEPTION
+# define STATUS_NONCONTINUABLE_EXCEPTION ((NTSTATUS) 0xC0000025L)
+#endif
+
+#ifndef STATUS_INVALID_DISPOSITION
+# define STATUS_INVALID_DISPOSITION ((NTSTATUS) 0xC0000026L)
+#endif
+
+#ifndef STATUS_UNWIND
+# define STATUS_UNWIND ((NTSTATUS) 0xC0000027L)
+#endif
+
+#ifndef STATUS_BAD_STACK
+# define STATUS_BAD_STACK ((NTSTATUS) 0xC0000028L)
+#endif
+
+#ifndef STATUS_INVALID_UNWIND_TARGET
+# define STATUS_INVALID_UNWIND_TARGET ((NTSTATUS) 0xC0000029L)
+#endif
+
+#ifndef STATUS_NOT_LOCKED
+# define STATUS_NOT_LOCKED ((NTSTATUS) 0xC000002AL)
+#endif
+
+#ifndef STATUS_PARITY_ERROR
+# define STATUS_PARITY_ERROR ((NTSTATUS) 0xC000002BL)
+#endif
+
+#ifndef STATUS_UNABLE_TO_DECOMMIT_VM
+# define STATUS_UNABLE_TO_DECOMMIT_VM ((NTSTATUS) 0xC000002CL)
+#endif
+
+#ifndef STATUS_NOT_COMMITTED
+# define STATUS_NOT_COMMITTED ((NTSTATUS) 0xC000002DL)
+#endif
+
+#ifndef STATUS_INVALID_PORT_ATTRIBUTES
+# define STATUS_INVALID_PORT_ATTRIBUTES ((NTSTATUS) 0xC000002EL)
+#endif
+
+#ifndef STATUS_PORT_MESSAGE_TOO_LONG
+# define STATUS_PORT_MESSAGE_TOO_LONG ((NTSTATUS) 0xC000002FL)
+#endif
+
+#ifndef STATUS_INVALID_PARAMETER_MIX
+# define STATUS_INVALID_PARAMETER_MIX ((NTSTATUS) 0xC0000030L)
+#endif
+
+#ifndef STATUS_INVALID_QUOTA_LOWER
+# define STATUS_INVALID_QUOTA_LOWER ((NTSTATUS) 0xC0000031L)
+#endif
+
+#ifndef STATUS_DISK_CORRUPT_ERROR
+# define STATUS_DISK_CORRUPT_ERROR ((NTSTATUS) 0xC0000032L)
+#endif
+
+#ifndef STATUS_OBJECT_NAME_INVALID
+# define STATUS_OBJECT_NAME_INVALID ((NTSTATUS) 0xC0000033L)
+#endif
+
+#ifndef STATUS_OBJECT_NAME_NOT_FOUND
+# define STATUS_OBJECT_NAME_NOT_FOUND ((NTSTATUS) 0xC0000034L)
+#endif
+
+#ifndef STATUS_OBJECT_NAME_COLLISION
+# define STATUS_OBJECT_NAME_COLLISION ((NTSTATUS) 0xC0000035L)
+#endif
+
+#ifndef STATUS_PORT_DISCONNECTED
+# define STATUS_PORT_DISCONNECTED ((NTSTATUS) 0xC0000037L)
+#endif
+
+#ifndef STATUS_DEVICE_ALREADY_ATTACHED
+# define STATUS_DEVICE_ALREADY_ATTACHED ((NTSTATUS) 0xC0000038L)
+#endif
+
+#ifndef STATUS_OBJECT_PATH_INVALID
+# define STATUS_OBJECT_PATH_INVALID ((NTSTATUS) 0xC0000039L)
+#endif
+
+#ifndef STATUS_OBJECT_PATH_NOT_FOUND
+# define STATUS_OBJECT_PATH_NOT_FOUND ((NTSTATUS) 0xC000003AL)
+#endif
+
+#ifndef STATUS_OBJECT_PATH_SYNTAX_BAD
+# define STATUS_OBJECT_PATH_SYNTAX_BAD ((NTSTATUS) 0xC000003BL)
+#endif
+
+#ifndef STATUS_DATA_OVERRUN
+# define STATUS_DATA_OVERRUN ((NTSTATUS) 0xC000003CL)
+#endif
+
+#ifndef STATUS_DATA_LATE_ERROR
+# define STATUS_DATA_LATE_ERROR ((NTSTATUS) 0xC000003DL)
+#endif
+
+#ifndef STATUS_DATA_ERROR
+# define STATUS_DATA_ERROR ((NTSTATUS) 0xC000003EL)
+#endif
+
+#ifndef STATUS_CRC_ERROR
+# define STATUS_CRC_ERROR ((NTSTATUS) 0xC000003FL)
+#endif
+
+#ifndef STATUS_SECTION_TOO_BIG
+# define STATUS_SECTION_TOO_BIG ((NTSTATUS) 0xC0000040L)
+#endif
+
+#ifndef STATUS_PORT_CONNECTION_REFUSED
+# define STATUS_PORT_CONNECTION_REFUSED ((NTSTATUS) 0xC0000041L)
+#endif
+
+#ifndef STATUS_INVALID_PORT_HANDLE
+# define STATUS_INVALID_PORT_HANDLE ((NTSTATUS) 0xC0000042L)
+#endif
+
+#ifndef STATUS_SHARING_VIOLATION
+# define STATUS_SHARING_VIOLATION ((NTSTATUS) 0xC0000043L)
+#endif
+
+#ifndef STATUS_QUOTA_EXCEEDED
+# define STATUS_QUOTA_EXCEEDED ((NTSTATUS) 0xC0000044L)
+#endif
+
+#ifndef STATUS_INVALID_PAGE_PROTECTION
+# define STATUS_INVALID_PAGE_PROTECTION ((NTSTATUS) 0xC0000045L)
+#endif
+
+#ifndef STATUS_MUTANT_NOT_OWNED
+# define STATUS_MUTANT_NOT_OWNED ((NTSTATUS) 0xC0000046L)
+#endif
+
+#ifndef STATUS_SEMAPHORE_LIMIT_EXCEEDED
+# define STATUS_SEMAPHORE_LIMIT_EXCEEDED ((NTSTATUS) 0xC0000047L)
+#endif
+
+#ifndef STATUS_PORT_ALREADY_SET
+# define STATUS_PORT_ALREADY_SET ((NTSTATUS) 0xC0000048L)
+#endif
+
+#ifndef STATUS_SECTION_NOT_IMAGE
+# define STATUS_SECTION_NOT_IMAGE ((NTSTATUS) 0xC0000049L)
+#endif
+
+#ifndef STATUS_SUSPEND_COUNT_EXCEEDED
+# define STATUS_SUSPEND_COUNT_EXCEEDED ((NTSTATUS) 0xC000004AL)
+#endif
+
+#ifndef STATUS_THREAD_IS_TERMINATING
+# define STATUS_THREAD_IS_TERMINATING ((NTSTATUS) 0xC000004BL)
+#endif
+
+#ifndef STATUS_BAD_WORKING_SET_LIMIT
+# define STATUS_BAD_WORKING_SET_LIMIT ((NTSTATUS) 0xC000004CL)
+#endif
+
+#ifndef STATUS_INCOMPATIBLE_FILE_MAP
+# define STATUS_INCOMPATIBLE_FILE_MAP ((NTSTATUS) 0xC000004DL)
+#endif
+
+#ifndef STATUS_SECTION_PROTECTION
+# define STATUS_SECTION_PROTECTION ((NTSTATUS) 0xC000004EL)
+#endif
+
+#ifndef STATUS_EAS_NOT_SUPPORTED
+# define STATUS_EAS_NOT_SUPPORTED ((NTSTATUS) 0xC000004FL)
+#endif
+
+#ifndef STATUS_EA_TOO_LARGE
+# define STATUS_EA_TOO_LARGE ((NTSTATUS) 0xC0000050L)
+#endif
+
+#ifndef STATUS_NONEXISTENT_EA_ENTRY
+# define STATUS_NONEXISTENT_EA_ENTRY ((NTSTATUS) 0xC0000051L)
+#endif
+
+#ifndef STATUS_NO_EAS_ON_FILE
+# define STATUS_NO_EAS_ON_FILE ((NTSTATUS) 0xC0000052L)
+#endif
+
+#ifndef STATUS_EA_CORRUPT_ERROR
+# define STATUS_EA_CORRUPT_ERROR ((NTSTATUS) 0xC0000053L)
+#endif
+
+#ifndef STATUS_FILE_LOCK_CONFLICT
+# define STATUS_FILE_LOCK_CONFLICT ((NTSTATUS) 0xC0000054L)
+#endif
+
+#ifndef STATUS_LOCK_NOT_GRANTED
+# define STATUS_LOCK_NOT_GRANTED ((NTSTATUS) 0xC0000055L)
+#endif
+
+#ifndef STATUS_DELETE_PENDING
+# define STATUS_DELETE_PENDING ((NTSTATUS) 0xC0000056L)
+#endif
+
+#ifndef STATUS_CTL_FILE_NOT_SUPPORTED
+# define STATUS_CTL_FILE_NOT_SUPPORTED ((NTSTATUS) 0xC0000057L)
+#endif
+
+#ifndef STATUS_UNKNOWN_REVISION
+# define STATUS_UNKNOWN_REVISION ((NTSTATUS) 0xC0000058L)
+#endif
+
+#ifndef STATUS_REVISION_MISMATCH
+# define STATUS_REVISION_MISMATCH ((NTSTATUS) 0xC0000059L)
+#endif
+
+#ifndef STATUS_INVALID_OWNER
+# define STATUS_INVALID_OWNER ((NTSTATUS) 0xC000005AL)
+#endif
+
+#ifndef STATUS_INVALID_PRIMARY_GROUP
+# define STATUS_INVALID_PRIMARY_GROUP ((NTSTATUS) 0xC000005BL)
+#endif
+
+#ifndef STATUS_NO_IMPERSONATION_TOKEN
+# define STATUS_NO_IMPERSONATION_TOKEN ((NTSTATUS) 0xC000005CL)
+#endif
+
+#ifndef STATUS_CANT_DISABLE_MANDATORY
+# define STATUS_CANT_DISABLE_MANDATORY ((NTSTATUS) 0xC000005DL)
+#endif
+
+#ifndef STATUS_NO_LOGON_SERVERS
+# define STATUS_NO_LOGON_SERVERS ((NTSTATUS) 0xC000005EL)
+#endif
+
+#ifndef STATUS_NO_SUCH_LOGON_SESSION
+# define STATUS_NO_SUCH_LOGON_SESSION ((NTSTATUS) 0xC000005FL)
+#endif
+
+#ifndef STATUS_NO_SUCH_PRIVILEGE
+# define STATUS_NO_SUCH_PRIVILEGE ((NTSTATUS) 0xC0000060L)
+#endif
+
+#ifndef STATUS_PRIVILEGE_NOT_HELD
+# define STATUS_PRIVILEGE_NOT_HELD ((NTSTATUS) 0xC0000061L)
+#endif
+
+#ifndef STATUS_INVALID_ACCOUNT_NAME
+# define STATUS_INVALID_ACCOUNT_NAME ((NTSTATUS) 0xC0000062L)
+#endif
+
+#ifndef STATUS_USER_EXISTS
+# define STATUS_USER_EXISTS ((NTSTATUS) 0xC0000063L)
+#endif
+
+#ifndef STATUS_NO_SUCH_USER
+# define STATUS_NO_SUCH_USER ((NTSTATUS) 0xC0000064L)
+#endif
+
+#ifndef STATUS_GROUP_EXISTS
+# define STATUS_GROUP_EXISTS ((NTSTATUS) 0xC0000065L)
+#endif
+
+#ifndef STATUS_NO_SUCH_GROUP
+# define STATUS_NO_SUCH_GROUP ((NTSTATUS) 0xC0000066L)
+#endif
+
+#ifndef STATUS_MEMBER_IN_GROUP
+# define STATUS_MEMBER_IN_GROUP ((NTSTATUS) 0xC0000067L)
+#endif
+
+#ifndef STATUS_MEMBER_NOT_IN_GROUP
+# define STATUS_MEMBER_NOT_IN_GROUP ((NTSTATUS) 0xC0000068L)
+#endif
+
+#ifndef STATUS_LAST_ADMIN
+# define STATUS_LAST_ADMIN ((NTSTATUS) 0xC0000069L)
+#endif
+
+#ifndef STATUS_WRONG_PASSWORD
+# define STATUS_WRONG_PASSWORD ((NTSTATUS) 0xC000006AL)
+#endif
+
+#ifndef STATUS_ILL_FORMED_PASSWORD
+# define STATUS_ILL_FORMED_PASSWORD ((NTSTATUS) 0xC000006BL)
+#endif
+
+#ifndef STATUS_PASSWORD_RESTRICTION
+# define STATUS_PASSWORD_RESTRICTION ((NTSTATUS) 0xC000006CL)
+#endif
+
+#ifndef STATUS_LOGON_FAILURE
+# define STATUS_LOGON_FAILURE ((NTSTATUS) 0xC000006DL)
+#endif
+
+#ifndef STATUS_ACCOUNT_RESTRICTION
+# define STATUS_ACCOUNT_RESTRICTION ((NTSTATUS) 0xC000006EL)
+#endif
+
+#ifndef STATUS_INVALID_LOGON_HOURS
+# define STATUS_INVALID_LOGON_HOURS ((NTSTATUS) 0xC000006FL)
+#endif
+
+#ifndef STATUS_INVALID_WORKSTATION
+# define STATUS_INVALID_WORKSTATION ((NTSTATUS) 0xC0000070L)
+#endif
+
+#ifndef STATUS_PASSWORD_EXPIRED
+# define STATUS_PASSWORD_EXPIRED ((NTSTATUS) 0xC0000071L)
+#endif
+
+#ifndef STATUS_ACCOUNT_DISABLED
+# define STATUS_ACCOUNT_DISABLED ((NTSTATUS) 0xC0000072L)
+#endif
+
+#ifndef STATUS_NONE_MAPPED
+# define STATUS_NONE_MAPPED ((NTSTATUS) 0xC0000073L)
+#endif
+
+#ifndef STATUS_TOO_MANY_LUIDS_REQUESTED
+# define STATUS_TOO_MANY_LUIDS_REQUESTED ((NTSTATUS) 0xC0000074L)
+#endif
+
+#ifndef STATUS_LUIDS_EXHAUSTED
+# define STATUS_LUIDS_EXHAUSTED ((NTSTATUS) 0xC0000075L)
+#endif
+
+#ifndef STATUS_INVALID_SUB_AUTHORITY
+# define STATUS_INVALID_SUB_AUTHORITY ((NTSTATUS) 0xC0000076L)
+#endif
+
+#ifndef STATUS_INVALID_ACL
+# define STATUS_INVALID_ACL ((NTSTATUS) 0xC0000077L)
+#endif
+
+#ifndef STATUS_INVALID_SID
+# define STATUS_INVALID_SID ((NTSTATUS) 0xC0000078L)
+#endif
+
+#ifndef STATUS_INVALID_SECURITY_DESCR
+# define STATUS_INVALID_SECURITY_DESCR ((NTSTATUS) 0xC0000079L)
+#endif
+
+#ifndef STATUS_PROCEDURE_NOT_FOUND
+# define STATUS_PROCEDURE_NOT_FOUND ((NTSTATUS) 0xC000007AL)
+#endif
+
+#ifndef STATUS_INVALID_IMAGE_FORMAT
+# define STATUS_INVALID_IMAGE_FORMAT ((NTSTATUS) 0xC000007BL)
+#endif
+
+#ifndef STATUS_NO_TOKEN
+# define STATUS_NO_TOKEN ((NTSTATUS) 0xC000007CL)
+#endif
+
+#ifndef STATUS_BAD_INHERITANCE_ACL
+# define STATUS_BAD_INHERITANCE_ACL ((NTSTATUS) 0xC000007DL)
+#endif
+
+#ifndef STATUS_RANGE_NOT_LOCKED
+# define STATUS_RANGE_NOT_LOCKED ((NTSTATUS) 0xC000007EL)
+#endif
+
+#ifndef STATUS_DISK_FULL
+# define STATUS_DISK_FULL ((NTSTATUS) 0xC000007FL)
+#endif
+
+#ifndef STATUS_SERVER_DISABLED
+# define STATUS_SERVER_DISABLED ((NTSTATUS) 0xC0000080L)
+#endif
+
+#ifndef STATUS_SERVER_NOT_DISABLED
+# define STATUS_SERVER_NOT_DISABLED ((NTSTATUS) 0xC0000081L)
+#endif
+
+#ifndef STATUS_TOO_MANY_GUIDS_REQUESTED
+# define STATUS_TOO_MANY_GUIDS_REQUESTED ((NTSTATUS) 0xC0000082L)
+#endif
+
+#ifndef STATUS_GUIDS_EXHAUSTED
+# define STATUS_GUIDS_EXHAUSTED ((NTSTATUS) 0xC0000083L)
+#endif
+
+#ifndef STATUS_INVALID_ID_AUTHORITY
+# define STATUS_INVALID_ID_AUTHORITY ((NTSTATUS) 0xC0000084L)
+#endif
+
+#ifndef STATUS_AGENTS_EXHAUSTED
+# define STATUS_AGENTS_EXHAUSTED ((NTSTATUS) 0xC0000085L)
+#endif
+
+#ifndef STATUS_INVALID_VOLUME_LABEL
+# define STATUS_INVALID_VOLUME_LABEL ((NTSTATUS) 0xC0000086L)
+#endif
+
+#ifndef STATUS_SECTION_NOT_EXTENDED
+# define STATUS_SECTION_NOT_EXTENDED ((NTSTATUS) 0xC0000087L)
+#endif
+
+#ifndef STATUS_NOT_MAPPED_DATA
+# define STATUS_NOT_MAPPED_DATA ((NTSTATUS) 0xC0000088L)
+#endif
+
+#ifndef STATUS_RESOURCE_DATA_NOT_FOUND
+# define STATUS_RESOURCE_DATA_NOT_FOUND ((NTSTATUS) 0xC0000089L)
+#endif
+
+#ifndef STATUS_RESOURCE_TYPE_NOT_FOUND
+# define STATUS_RESOURCE_TYPE_NOT_FOUND ((NTSTATUS) 0xC000008AL)
+#endif
+
+#ifndef STATUS_RESOURCE_NAME_NOT_FOUND
+# define STATUS_RESOURCE_NAME_NOT_FOUND ((NTSTATUS) 0xC000008BL)
+#endif
+
+#ifndef STATUS_ARRAY_BOUNDS_EXCEEDED
+# define STATUS_ARRAY_BOUNDS_EXCEEDED ((NTSTATUS) 0xC000008CL)
+#endif
+
+#ifndef STATUS_FLOAT_DENORMAL_OPERAND
+# define STATUS_FLOAT_DENORMAL_OPERAND ((NTSTATUS) 0xC000008DL)
+#endif
+
+#ifndef STATUS_FLOAT_DIVIDE_BY_ZERO
+# define STATUS_FLOAT_DIVIDE_BY_ZERO ((NTSTATUS) 0xC000008EL)
+#endif
+
+#ifndef STATUS_FLOAT_INEXACT_RESULT
+# define STATUS_FLOAT_INEXACT_RESULT ((NTSTATUS) 0xC000008FL)
+#endif
+
+#ifndef STATUS_FLOAT_INVALID_OPERATION
+# define STATUS_FLOAT_INVALID_OPERATION ((NTSTATUS) 0xC0000090L)
+#endif
+
+#ifndef STATUS_FLOAT_OVERFLOW
+# define STATUS_FLOAT_OVERFLOW ((NTSTATUS) 0xC0000091L)
+#endif
+
+#ifndef STATUS_FLOAT_STACK_CHECK
+# define STATUS_FLOAT_STACK_CHECK ((NTSTATUS) 0xC0000092L)
+#endif
+
+#ifndef STATUS_FLOAT_UNDERFLOW
+# define STATUS_FLOAT_UNDERFLOW ((NTSTATUS) 0xC0000093L)
+#endif
+
+#ifndef STATUS_INTEGER_DIVIDE_BY_ZERO
+# define STATUS_INTEGER_DIVIDE_BY_ZERO ((NTSTATUS) 0xC0000094L)
+#endif
+
+#ifndef STATUS_INTEGER_OVERFLOW
+# define STATUS_INTEGER_OVERFLOW ((NTSTATUS) 0xC0000095L)
+#endif
+
+#ifndef STATUS_PRIVILEGED_INSTRUCTION
+# define STATUS_PRIVILEGED_INSTRUCTION ((NTSTATUS) 0xC0000096L)
+#endif
+
+#ifndef STATUS_TOO_MANY_PAGING_FILES
+# define STATUS_TOO_MANY_PAGING_FILES ((NTSTATUS) 0xC0000097L)
+#endif
+
+#ifndef STATUS_FILE_INVALID
+# define STATUS_FILE_INVALID ((NTSTATUS) 0xC0000098L)
+#endif
+
+#ifndef STATUS_ALLOTTED_SPACE_EXCEEDED
+# define STATUS_ALLOTTED_SPACE_EXCEEDED ((NTSTATUS) 0xC0000099L)
+#endif
+
+#ifndef STATUS_INSUFFICIENT_RESOURCES
+# define STATUS_INSUFFICIENT_RESOURCES ((NTSTATUS) 0xC000009AL)
+#endif
+
+#ifndef STATUS_DFS_EXIT_PATH_FOUND
+# define STATUS_DFS_EXIT_PATH_FOUND ((NTSTATUS) 0xC000009BL)
+#endif
+
+#ifndef STATUS_DEVICE_DATA_ERROR
+# define STATUS_DEVICE_DATA_ERROR ((NTSTATUS) 0xC000009CL)
+#endif
+
+#ifndef STATUS_DEVICE_NOT_CONNECTED
+# define STATUS_DEVICE_NOT_CONNECTED ((NTSTATUS) 0xC000009DL)
+#endif
+
+#ifndef STATUS_DEVICE_POWER_FAILURE
+# define STATUS_DEVICE_POWER_FAILURE ((NTSTATUS) 0xC000009EL)
+#endif
+
+#ifndef STATUS_FREE_VM_NOT_AT_BASE
+# define STATUS_FREE_VM_NOT_AT_BASE ((NTSTATUS) 0xC000009FL)
+#endif
+
+#ifndef STATUS_MEMORY_NOT_ALLOCATED
+# define STATUS_MEMORY_NOT_ALLOCATED ((NTSTATUS) 0xC00000A0L)
+#endif
+
+#ifndef STATUS_WORKING_SET_QUOTA
+# define STATUS_WORKING_SET_QUOTA ((NTSTATUS) 0xC00000A1L)
+#endif
+
+#ifndef STATUS_MEDIA_WRITE_PROTECTED
+# define STATUS_MEDIA_WRITE_PROTECTED ((NTSTATUS) 0xC00000A2L)
+#endif
+
+#ifndef STATUS_DEVICE_NOT_READY
+# define STATUS_DEVICE_NOT_READY ((NTSTATUS) 0xC00000A3L)
+#endif
+
+#ifndef STATUS_INVALID_GROUP_ATTRIBUTES
+# define STATUS_INVALID_GROUP_ATTRIBUTES ((NTSTATUS) 0xC00000A4L)
+#endif
+
+#ifndef STATUS_BAD_IMPERSONATION_LEVEL
+# define STATUS_BAD_IMPERSONATION_LEVEL ((NTSTATUS) 0xC00000A5L)
+#endif
+
+#ifndef STATUS_CANT_OPEN_ANONYMOUS
+# define STATUS_CANT_OPEN_ANONYMOUS ((NTSTATUS) 0xC00000A6L)
+#endif
+
+#ifndef STATUS_BAD_VALIDATION_CLASS
+# define STATUS_BAD_VALIDATION_CLASS ((NTSTATUS) 0xC00000A7L)
+#endif
+
+#ifndef STATUS_BAD_TOKEN_TYPE
+# define STATUS_BAD_TOKEN_TYPE ((NTSTATUS) 0xC00000A8L)
+#endif
+
+#ifndef STATUS_BAD_MASTER_BOOT_RECORD
+# define STATUS_BAD_MASTER_BOOT_RECORD ((NTSTATUS) 0xC00000A9L)
+#endif
+
+#ifndef STATUS_INSTRUCTION_MISALIGNMENT
+# define STATUS_INSTRUCTION_MISALIGNMENT ((NTSTATUS) 0xC00000AAL)
+#endif
+
+#ifndef STATUS_INSTANCE_NOT_AVAILABLE
+# define STATUS_INSTANCE_NOT_AVAILABLE ((NTSTATUS) 0xC00000ABL)
+#endif
+
+#ifndef STATUS_PIPE_NOT_AVAILABLE
+# define STATUS_PIPE_NOT_AVAILABLE ((NTSTATUS) 0xC00000ACL)
+#endif
+
+#ifndef STATUS_INVALID_PIPE_STATE
+# define STATUS_INVALID_PIPE_STATE ((NTSTATUS) 0xC00000ADL)
+#endif
+
+#ifndef STATUS_PIPE_BUSY
+# define STATUS_PIPE_BUSY ((NTSTATUS) 0xC00000AEL)
+#endif
+
+#ifndef STATUS_ILLEGAL_FUNCTION
+# define STATUS_ILLEGAL_FUNCTION ((NTSTATUS) 0xC00000AFL)
+#endif
+
+#ifndef STATUS_PIPE_DISCONNECTED
+# define STATUS_PIPE_DISCONNECTED ((NTSTATUS) 0xC00000B0L)
+#endif
+
+#ifndef STATUS_PIPE_CLOSING
+# define STATUS_PIPE_CLOSING ((NTSTATUS) 0xC00000B1L)
+#endif
+
+#ifndef STATUS_PIPE_CONNECTED
+# define STATUS_PIPE_CONNECTED ((NTSTATUS) 0xC00000B2L)
+#endif
+
+#ifndef STATUS_PIPE_LISTENING
+# define STATUS_PIPE_LISTENING ((NTSTATUS) 0xC00000B3L)
+#endif
+
+#ifndef STATUS_INVALID_READ_MODE
+# define STATUS_INVALID_READ_MODE ((NTSTATUS) 0xC00000B4L)
+#endif
+
+#ifndef STATUS_IO_TIMEOUT
+# define STATUS_IO_TIMEOUT ((NTSTATUS) 0xC00000B5L)
+#endif
+
+#ifndef STATUS_FILE_FORCED_CLOSED
+# define STATUS_FILE_FORCED_CLOSED ((NTSTATUS) 0xC00000B6L)
+#endif
+
+#ifndef STATUS_PROFILING_NOT_STARTED
+# define STATUS_PROFILING_NOT_STARTED ((NTSTATUS) 0xC00000B7L)
+#endif
+
+#ifndef STATUS_PROFILING_NOT_STOPPED
+# define STATUS_PROFILING_NOT_STOPPED ((NTSTATUS) 0xC00000B8L)
+#endif
+
+#ifndef STATUS_COULD_NOT_INTERPRET
+# define STATUS_COULD_NOT_INTERPRET ((NTSTATUS) 0xC00000B9L)
+#endif
+
+#ifndef STATUS_FILE_IS_A_DIRECTORY
+# define STATUS_FILE_IS_A_DIRECTORY ((NTSTATUS) 0xC00000BAL)
+#endif
+
+#ifndef STATUS_NOT_SUPPORTED
+# define STATUS_NOT_SUPPORTED ((NTSTATUS) 0xC00000BBL)
+#endif
+
+#ifndef STATUS_REMOTE_NOT_LISTENING
+# define STATUS_REMOTE_NOT_LISTENING ((NTSTATUS) 0xC00000BCL)
+#endif
+
+#ifndef STATUS_DUPLICATE_NAME
+# define STATUS_DUPLICATE_NAME ((NTSTATUS) 0xC00000BDL)
+#endif
+
+#ifndef STATUS_BAD_NETWORK_PATH
+# define STATUS_BAD_NETWORK_PATH ((NTSTATUS) 0xC00000BEL)
+#endif
+
+#ifndef STATUS_NETWORK_BUSY
+# define STATUS_NETWORK_BUSY ((NTSTATUS) 0xC00000BFL)
+#endif
+
+#ifndef STATUS_DEVICE_DOES_NOT_EXIST
+# define STATUS_DEVICE_DOES_NOT_EXIST ((NTSTATUS) 0xC00000C0L)
+#endif
+
+#ifndef STATUS_TOO_MANY_COMMANDS
+# define STATUS_TOO_MANY_COMMANDS ((NTSTATUS) 0xC00000C1L)
+#endif
+
+#ifndef STATUS_ADAPTER_HARDWARE_ERROR
+# define STATUS_ADAPTER_HARDWARE_ERROR ((NTSTATUS) 0xC00000C2L)
+#endif
+
+#ifndef STATUS_INVALID_NETWORK_RESPONSE
+# define STATUS_INVALID_NETWORK_RESPONSE ((NTSTATUS) 0xC00000C3L)
+#endif
+
+#ifndef STATUS_UNEXPECTED_NETWORK_ERROR
+# define STATUS_UNEXPECTED_NETWORK_ERROR ((NTSTATUS) 0xC00000C4L)
+#endif
+
+#ifndef STATUS_BAD_REMOTE_ADAPTER
+# define STATUS_BAD_REMOTE_ADAPTER ((NTSTATUS) 0xC00000C5L)
+#endif
+
+#ifndef STATUS_PRINT_QUEUE_FULL
+# define STATUS_PRINT_QUEUE_FULL ((NTSTATUS) 0xC00000C6L)
+#endif
+
+#ifndef STATUS_NO_SPOOL_SPACE
+# define STATUS_NO_SPOOL_SPACE ((NTSTATUS) 0xC00000C7L)
+#endif
+
+#ifndef STATUS_PRINT_CANCELLED
+# define STATUS_PRINT_CANCELLED ((NTSTATUS) 0xC00000C8L)
+#endif
+
+#ifndef STATUS_NETWORK_NAME_DELETED
+# define STATUS_NETWORK_NAME_DELETED ((NTSTATUS) 0xC00000C9L)
+#endif
+
+#ifndef STATUS_NETWORK_ACCESS_DENIED
+# define STATUS_NETWORK_ACCESS_DENIED ((NTSTATUS) 0xC00000CAL)
+#endif
+
+#ifndef STATUS_BAD_DEVICE_TYPE
+# define STATUS_BAD_DEVICE_TYPE ((NTSTATUS) 0xC00000CBL)
+#endif
+
+#ifndef STATUS_BAD_NETWORK_NAME
+# define STATUS_BAD_NETWORK_NAME ((NTSTATUS) 0xC00000CCL)
+#endif
+
+#ifndef STATUS_TOO_MANY_NAMES
+# define STATUS_TOO_MANY_NAMES ((NTSTATUS) 0xC00000CDL)
+#endif
+
+#ifndef STATUS_TOO_MANY_SESSIONS
+# define STATUS_TOO_MANY_SESSIONS ((NTSTATUS) 0xC00000CEL)
+#endif
+
+#ifndef STATUS_SHARING_PAUSED
+# define STATUS_SHARING_PAUSED ((NTSTATUS) 0xC00000CFL)
+#endif
+
+#ifndef STATUS_REQUEST_NOT_ACCEPTED
+# define STATUS_REQUEST_NOT_ACCEPTED ((NTSTATUS) 0xC00000D0L)
+#endif
+
+#ifndef STATUS_REDIRECTOR_PAUSED
+# define STATUS_REDIRECTOR_PAUSED ((NTSTATUS) 0xC00000D1L)
+#endif
+
+#ifndef STATUS_NET_WRITE_FAULT
+# define STATUS_NET_WRITE_FAULT ((NTSTATUS) 0xC00000D2L)
+#endif
+
+#ifndef STATUS_PROFILING_AT_LIMIT
+# define STATUS_PROFILING_AT_LIMIT ((NTSTATUS) 0xC00000D3L)
+#endif
+
+#ifndef STATUS_NOT_SAME_DEVICE
+# define STATUS_NOT_SAME_DEVICE ((NTSTATUS) 0xC00000D4L)
+#endif
+
+#ifndef STATUS_FILE_RENAMED
+# define STATUS_FILE_RENAMED ((NTSTATUS) 0xC00000D5L)
+#endif
+
+#ifndef STATUS_VIRTUAL_CIRCUIT_CLOSED
+# define STATUS_VIRTUAL_CIRCUIT_CLOSED ((NTSTATUS) 0xC00000D6L)
+#endif
+
+#ifndef STATUS_NO_SECURITY_ON_OBJECT
+# define STATUS_NO_SECURITY_ON_OBJECT ((NTSTATUS) 0xC00000D7L)
+#endif
+
+#ifndef STATUS_CANT_WAIT
+# define STATUS_CANT_WAIT ((NTSTATUS) 0xC00000D8L)
+#endif
+
+#ifndef STATUS_PIPE_EMPTY
+# define STATUS_PIPE_EMPTY ((NTSTATUS) 0xC00000D9L)
+#endif
+
+#ifndef STATUS_CANT_ACCESS_DOMAIN_INFO
+# define STATUS_CANT_ACCESS_DOMAIN_INFO ((NTSTATUS) 0xC00000DAL)
+#endif
+
+#ifndef STATUS_CANT_TERMINATE_SELF
+# define STATUS_CANT_TERMINATE_SELF ((NTSTATUS) 0xC00000DBL)
+#endif
+
+#ifndef STATUS_INVALID_SERVER_STATE
+# define STATUS_INVALID_SERVER_STATE ((NTSTATUS) 0xC00000DCL)
+#endif
+
+#ifndef STATUS_INVALID_DOMAIN_STATE
+# define STATUS_INVALID_DOMAIN_STATE ((NTSTATUS) 0xC00000DDL)
+#endif
+
+#ifndef STATUS_INVALID_DOMAIN_ROLE
+# define STATUS_INVALID_DOMAIN_ROLE ((NTSTATUS) 0xC00000DEL)
+#endif
+
+#ifndef STATUS_NO_SUCH_DOMAIN
+# define STATUS_NO_SUCH_DOMAIN ((NTSTATUS) 0xC00000DFL)
+#endif
+
+#ifndef STATUS_DOMAIN_EXISTS
+# define STATUS_DOMAIN_EXISTS ((NTSTATUS) 0xC00000E0L)
+#endif
+
+#ifndef STATUS_DOMAIN_LIMIT_EXCEEDED
+# define STATUS_DOMAIN_LIMIT_EXCEEDED ((NTSTATUS) 0xC00000E1L)
+#endif
+
+#ifndef STATUS_OPLOCK_NOT_GRANTED
+# define STATUS_OPLOCK_NOT_GRANTED ((NTSTATUS) 0xC00000E2L)
+#endif
+
+#ifndef STATUS_INVALID_OPLOCK_PROTOCOL
+# define STATUS_INVALID_OPLOCK_PROTOCOL ((NTSTATUS) 0xC00000E3L)
+#endif
+
+#ifndef STATUS_INTERNAL_DB_CORRUPTION
+# define STATUS_INTERNAL_DB_CORRUPTION ((NTSTATUS) 0xC00000E4L)
+#endif
+
+#ifndef STATUS_INTERNAL_ERROR
+# define STATUS_INTERNAL_ERROR ((NTSTATUS) 0xC00000E5L)
+#endif
+
+#ifndef STATUS_GENERIC_NOT_MAPPED
+# define STATUS_GENERIC_NOT_MAPPED ((NTSTATUS) 0xC00000E6L)
+#endif
+
+#ifndef STATUS_BAD_DESCRIPTOR_FORMAT
+# define STATUS_BAD_DESCRIPTOR_FORMAT ((NTSTATUS) 0xC00000E7L)
+#endif
+
+#ifndef STATUS_INVALID_USER_BUFFER
+# define STATUS_INVALID_USER_BUFFER ((NTSTATUS) 0xC00000E8L)
+#endif
+
+#ifndef STATUS_UNEXPECTED_IO_ERROR
+# define STATUS_UNEXPECTED_IO_ERROR ((NTSTATUS) 0xC00000E9L)
+#endif
+
+#ifndef STATUS_UNEXPECTED_MM_CREATE_ERR
+# define STATUS_UNEXPECTED_MM_CREATE_ERR ((NTSTATUS) 0xC00000EAL)
+#endif
+
+#ifndef STATUS_UNEXPECTED_MM_MAP_ERROR
+# define STATUS_UNEXPECTED_MM_MAP_ERROR ((NTSTATUS) 0xC00000EBL)
+#endif
+
+#ifndef STATUS_UNEXPECTED_MM_EXTEND_ERR
+# define STATUS_UNEXPECTED_MM_EXTEND_ERR ((NTSTATUS) 0xC00000ECL)
+#endif
+
+#ifndef STATUS_NOT_LOGON_PROCESS
+# define STATUS_NOT_LOGON_PROCESS ((NTSTATUS) 0xC00000EDL)
+#endif
+
+#ifndef STATUS_LOGON_SESSION_EXISTS
+# define STATUS_LOGON_SESSION_EXISTS ((NTSTATUS) 0xC00000EEL)
+#endif
+
+#ifndef STATUS_INVALID_PARAMETER_1
+# define STATUS_INVALID_PARAMETER_1 ((NTSTATUS) 0xC00000EFL)
+#endif
+
+#ifndef STATUS_INVALID_PARAMETER_2
+# define STATUS_INVALID_PARAMETER_2 ((NTSTATUS) 0xC00000F0L)
+#endif
+
+#ifndef STATUS_INVALID_PARAMETER_3
+# define STATUS_INVALID_PARAMETER_3 ((NTSTATUS) 0xC00000F1L)
+#endif
+
+#ifndef STATUS_INVALID_PARAMETER_4
+# define STATUS_INVALID_PARAMETER_4 ((NTSTATUS) 0xC00000F2L)
+#endif
+
+#ifndef STATUS_INVALID_PARAMETER_5
+# define STATUS_INVALID_PARAMETER_5 ((NTSTATUS) 0xC00000F3L)
+#endif
+
+#ifndef STATUS_INVALID_PARAMETER_6
+# define STATUS_INVALID_PARAMETER_6 ((NTSTATUS) 0xC00000F4L)
+#endif
+
+#ifndef STATUS_INVALID_PARAMETER_7
+# define STATUS_INVALID_PARAMETER_7 ((NTSTATUS) 0xC00000F5L)
+#endif
+
+#ifndef STATUS_INVALID_PARAMETER_8
+# define STATUS_INVALID_PARAMETER_8 ((NTSTATUS) 0xC00000F6L)
+#endif
+
+#ifndef STATUS_INVALID_PARAMETER_9
+# define STATUS_INVALID_PARAMETER_9 ((NTSTATUS) 0xC00000F7L)
+#endif
+
+#ifndef STATUS_INVALID_PARAMETER_10
+# define STATUS_INVALID_PARAMETER_10 ((NTSTATUS) 0xC00000F8L)
+#endif
+
+#ifndef STATUS_INVALID_PARAMETER_11
+# define STATUS_INVALID_PARAMETER_11 ((NTSTATUS) 0xC00000F9L)
+#endif
+
+#ifndef STATUS_INVALID_PARAMETER_12
+# define STATUS_INVALID_PARAMETER_12 ((NTSTATUS) 0xC00000FAL)
+#endif
+
+#ifndef STATUS_REDIRECTOR_NOT_STARTED
+# define STATUS_REDIRECTOR_NOT_STARTED ((NTSTATUS) 0xC00000FBL)
+#endif
+
+#ifndef STATUS_REDIRECTOR_STARTED
+# define STATUS_REDIRECTOR_STARTED ((NTSTATUS) 0xC00000FCL)
+#endif
+
+#ifndef STATUS_STACK_OVERFLOW
+# define STATUS_STACK_OVERFLOW ((NTSTATUS) 0xC00000FDL)
+#endif
+
+#ifndef STATUS_NO_SUCH_PACKAGE
+# define STATUS_NO_SUCH_PACKAGE ((NTSTATUS) 0xC00000FEL)
+#endif
+
+#ifndef STATUS_BAD_FUNCTION_TABLE
+# define STATUS_BAD_FUNCTION_TABLE ((NTSTATUS) 0xC00000FFL)
+#endif
+
+#ifndef STATUS_VARIABLE_NOT_FOUND
+# define STATUS_VARIABLE_NOT_FOUND ((NTSTATUS) 0xC0000100L)
+#endif
+
+#ifndef STATUS_DIRECTORY_NOT_EMPTY
+# define STATUS_DIRECTORY_NOT_EMPTY ((NTSTATUS) 0xC0000101L)
+#endif
+
+#ifndef STATUS_FILE_CORRUPT_ERROR
+# define STATUS_FILE_CORRUPT_ERROR ((NTSTATUS) 0xC0000102L)
+#endif
+
+#ifndef STATUS_NOT_A_DIRECTORY
+# define STATUS_NOT_A_DIRECTORY ((NTSTATUS) 0xC0000103L)
+#endif
+
+#ifndef STATUS_BAD_LOGON_SESSION_STATE
+# define STATUS_BAD_LOGON_SESSION_STATE ((NTSTATUS) 0xC0000104L)
+#endif
+
+#ifndef STATUS_LOGON_SESSION_COLLISION
+# define STATUS_LOGON_SESSION_COLLISION ((NTSTATUS) 0xC0000105L)
+#endif
+
+#ifndef STATUS_NAME_TOO_LONG
+# define STATUS_NAME_TOO_LONG ((NTSTATUS) 0xC0000106L)
+#endif
+
+#ifndef STATUS_FILES_OPEN
+# define STATUS_FILES_OPEN ((NTSTATUS) 0xC0000107L)
+#endif
+
+#ifndef STATUS_CONNECTION_IN_USE
+# define STATUS_CONNECTION_IN_USE ((NTSTATUS) 0xC0000108L)
+#endif
+
+#ifndef STATUS_MESSAGE_NOT_FOUND
+# define STATUS_MESSAGE_NOT_FOUND ((NTSTATUS) 0xC0000109L)
+#endif
+
+#ifndef STATUS_PROCESS_IS_TERMINATING
+# define STATUS_PROCESS_IS_TERMINATING ((NTSTATUS) 0xC000010AL)
+#endif
+
+#ifndef STATUS_INVALID_LOGON_TYPE
+# define STATUS_INVALID_LOGON_TYPE ((NTSTATUS) 0xC000010BL)
+#endif
+
+#ifndef STATUS_NO_GUID_TRANSLATION
+# define STATUS_NO_GUID_TRANSLATION ((NTSTATUS) 0xC000010CL)
+#endif
+
+#ifndef STATUS_CANNOT_IMPERSONATE
+# define STATUS_CANNOT_IMPERSONATE ((NTSTATUS) 0xC000010DL)
+#endif
+
+#ifndef STATUS_IMAGE_ALREADY_LOADED
+# define STATUS_IMAGE_ALREADY_LOADED ((NTSTATUS) 0xC000010EL)
+#endif
+
+#ifndef STATUS_ABIOS_NOT_PRESENT
+# define STATUS_ABIOS_NOT_PRESENT ((NTSTATUS) 0xC000010FL)
+#endif
+
+#ifndef STATUS_ABIOS_LID_NOT_EXIST
+# define STATUS_ABIOS_LID_NOT_EXIST ((NTSTATUS) 0xC0000110L)
+#endif
+
+#ifndef STATUS_ABIOS_LID_ALREADY_OWNED
+# define STATUS_ABIOS_LID_ALREADY_OWNED ((NTSTATUS) 0xC0000111L)
+#endif
+
+#ifndef STATUS_ABIOS_NOT_LID_OWNER
+# define STATUS_ABIOS_NOT_LID_OWNER ((NTSTATUS) 0xC0000112L)
+#endif
+
+#ifndef STATUS_ABIOS_INVALID_COMMAND
+# define STATUS_ABIOS_INVALID_COMMAND ((NTSTATUS) 0xC0000113L)
+#endif
+
+#ifndef STATUS_ABIOS_INVALID_LID
+# define STATUS_ABIOS_INVALID_LID ((NTSTATUS) 0xC0000114L)
+#endif
+
+#ifndef STATUS_ABIOS_SELECTOR_NOT_AVAILABLE
+# define STATUS_ABIOS_SELECTOR_NOT_AVAILABLE ((NTSTATUS) 0xC0000115L)
+#endif
+
+#ifndef STATUS_ABIOS_INVALID_SELECTOR
+# define STATUS_ABIOS_INVALID_SELECTOR ((NTSTATUS) 0xC0000116L)
+#endif
+
+#ifndef STATUS_NO_LDT
+# define STATUS_NO_LDT ((NTSTATUS) 0xC0000117L)
+#endif
+
+#ifndef STATUS_INVALID_LDT_SIZE
+# define STATUS_INVALID_LDT_SIZE ((NTSTATUS) 0xC0000118L)
+#endif
+
+#ifndef STATUS_INVALID_LDT_OFFSET
+# define STATUS_INVALID_LDT_OFFSET ((NTSTATUS) 0xC0000119L)
+#endif
+
+#ifndef STATUS_INVALID_LDT_DESCRIPTOR
+# define STATUS_INVALID_LDT_DESCRIPTOR ((NTSTATUS) 0xC000011AL)
+#endif
+
+#ifndef STATUS_INVALID_IMAGE_NE_FORMAT
+# define STATUS_INVALID_IMAGE_NE_FORMAT ((NTSTATUS) 0xC000011BL)
+#endif
+
+#ifndef STATUS_RXACT_INVALID_STATE
+# define STATUS_RXACT_INVALID_STATE ((NTSTATUS) 0xC000011CL)
+#endif
+
+#ifndef STATUS_RXACT_COMMIT_FAILURE
+# define STATUS_RXACT_COMMIT_FAILURE ((NTSTATUS) 0xC000011DL)
+#endif
+
+#ifndef STATUS_MAPPED_FILE_SIZE_ZERO
+# define STATUS_MAPPED_FILE_SIZE_ZERO ((NTSTATUS) 0xC000011EL)
+#endif
+
+#ifndef STATUS_TOO_MANY_OPENED_FILES
+# define STATUS_TOO_MANY_OPENED_FILES ((NTSTATUS) 0xC000011FL)
+#endif
+
+#ifndef STATUS_CANCELLED
+# define STATUS_CANCELLED ((NTSTATUS) 0xC0000120L)
+#endif
+
+#ifndef STATUS_CANNOT_DELETE
+# define STATUS_CANNOT_DELETE ((NTSTATUS) 0xC0000121L)
+#endif
+
+#ifndef STATUS_INVALID_COMPUTER_NAME
+# define STATUS_INVALID_COMPUTER_NAME ((NTSTATUS) 0xC0000122L)
+#endif
+
+#ifndef STATUS_FILE_DELETED
+# define STATUS_FILE_DELETED ((NTSTATUS) 0xC0000123L)
+#endif
+
+#ifndef STATUS_SPECIAL_ACCOUNT
+# define STATUS_SPECIAL_ACCOUNT ((NTSTATUS) 0xC0000124L)
+#endif
+
+#ifndef STATUS_SPECIAL_GROUP
+# define STATUS_SPECIAL_GROUP ((NTSTATUS) 0xC0000125L)
+#endif
+
+#ifndef STATUS_SPECIAL_USER
+# define STATUS_SPECIAL_USER ((NTSTATUS) 0xC0000126L)
+#endif
+
+#ifndef STATUS_MEMBERS_PRIMARY_GROUP
+# define STATUS_MEMBERS_PRIMARY_GROUP ((NTSTATUS) 0xC0000127L)
+#endif
+
+#ifndef STATUS_FILE_CLOSED
+# define STATUS_FILE_CLOSED ((NTSTATUS) 0xC0000128L)
+#endif
+
+#ifndef STATUS_TOO_MANY_THREADS
+# define STATUS_TOO_MANY_THREADS ((NTSTATUS) 0xC0000129L)
+#endif
+
+#ifndef STATUS_THREAD_NOT_IN_PROCESS
+# define STATUS_THREAD_NOT_IN_PROCESS ((NTSTATUS) 0xC000012AL)
+#endif
+
+#ifndef STATUS_TOKEN_ALREADY_IN_USE
+# define STATUS_TOKEN_ALREADY_IN_USE ((NTSTATUS) 0xC000012BL)
+#endif
+
+#ifndef STATUS_PAGEFILE_QUOTA_EXCEEDED
+# define STATUS_PAGEFILE_QUOTA_EXCEEDED ((NTSTATUS) 0xC000012CL)
+#endif
+
+#ifndef STATUS_COMMITMENT_LIMIT
+# define STATUS_COMMITMENT_LIMIT ((NTSTATUS) 0xC000012DL)
+#endif
+
+#ifndef STATUS_INVALID_IMAGE_LE_FORMAT
+# define STATUS_INVALID_IMAGE_LE_FORMAT ((NTSTATUS) 0xC000012EL)
+#endif
+
+#ifndef STATUS_INVALID_IMAGE_NOT_MZ
+# define STATUS_INVALID_IMAGE_NOT_MZ ((NTSTATUS) 0xC000012FL)
+#endif
+
+#ifndef STATUS_INVALID_IMAGE_PROTECT
+# define STATUS_INVALID_IMAGE_PROTECT ((NTSTATUS) 0xC0000130L)
+#endif
+
+#ifndef STATUS_INVALID_IMAGE_WIN_16
+# define STATUS_INVALID_IMAGE_WIN_16 ((NTSTATUS) 0xC0000131L)
+#endif
+
+#ifndef STATUS_LOGON_SERVER_CONFLICT
+# define STATUS_LOGON_SERVER_CONFLICT ((NTSTATUS) 0xC0000132L)
+#endif
+
+#ifndef STATUS_TIME_DIFFERENCE_AT_DC
+# define STATUS_TIME_DIFFERENCE_AT_DC ((NTSTATUS) 0xC0000133L)
+#endif
+
+#ifndef STATUS_SYNCHRONIZATION_REQUIRED
+# define STATUS_SYNCHRONIZATION_REQUIRED ((NTSTATUS) 0xC0000134L)
+#endif
+
+#ifndef STATUS_DLL_NOT_FOUND
+# define STATUS_DLL_NOT_FOUND ((NTSTATUS) 0xC0000135L)
+#endif
+
+#ifndef STATUS_OPEN_FAILED
+# define STATUS_OPEN_FAILED ((NTSTATUS) 0xC0000136L)
+#endif
+
+#ifndef STATUS_IO_PRIVILEGE_FAILED
+# define STATUS_IO_PRIVILEGE_FAILED ((NTSTATUS) 0xC0000137L)
+#endif
+
+#ifndef STATUS_ORDINAL_NOT_FOUND
+# define STATUS_ORDINAL_NOT_FOUND ((NTSTATUS) 0xC0000138L)
+#endif
+
+#ifndef STATUS_ENTRYPOINT_NOT_FOUND
+# define STATUS_ENTRYPOINT_NOT_FOUND ((NTSTATUS) 0xC0000139L)
+#endif
+
+#ifndef STATUS_CONTROL_C_EXIT
+# define STATUS_CONTROL_C_EXIT ((NTSTATUS) 0xC000013AL)
+#endif
+
+#ifndef STATUS_LOCAL_DISCONNECT
+# define STATUS_LOCAL_DISCONNECT ((NTSTATUS) 0xC000013BL)
+#endif
+
+#ifndef STATUS_REMOTE_DISCONNECT
+# define STATUS_REMOTE_DISCONNECT ((NTSTATUS) 0xC000013CL)
+#endif
+
+#ifndef STATUS_REMOTE_RESOURCES
+# define STATUS_REMOTE_RESOURCES ((NTSTATUS) 0xC000013DL)
+#endif
+
+#ifndef STATUS_LINK_FAILED
+# define STATUS_LINK_FAILED ((NTSTATUS) 0xC000013EL)
+#endif
+
+#ifndef STATUS_LINK_TIMEOUT
+# define STATUS_LINK_TIMEOUT ((NTSTATUS) 0xC000013FL)
+#endif
+
+#ifndef STATUS_INVALID_CONNECTION
+# define STATUS_INVALID_CONNECTION ((NTSTATUS) 0xC0000140L)
+#endif
+
+#ifndef STATUS_INVALID_ADDRESS
+# define STATUS_INVALID_ADDRESS ((NTSTATUS) 0xC0000141L)
+#endif
+
+#ifndef STATUS_DLL_INIT_FAILED
+# define STATUS_DLL_INIT_FAILED ((NTSTATUS) 0xC0000142L)
+#endif
+
+#ifndef STATUS_MISSING_SYSTEMFILE
+# define STATUS_MISSING_SYSTEMFILE ((NTSTATUS) 0xC0000143L)
+#endif
+
+#ifndef STATUS_UNHANDLED_EXCEPTION
+# define STATUS_UNHANDLED_EXCEPTION ((NTSTATUS) 0xC0000144L)
+#endif
+
+#ifndef STATUS_APP_INIT_FAILURE
+# define STATUS_APP_INIT_FAILURE ((NTSTATUS) 0xC0000145L)
+#endif
+
+#ifndef STATUS_PAGEFILE_CREATE_FAILED
+# define STATUS_PAGEFILE_CREATE_FAILED ((NTSTATUS) 0xC0000146L)
+#endif
+
+#ifndef STATUS_NO_PAGEFILE
+# define STATUS_NO_PAGEFILE ((NTSTATUS) 0xC0000147L)
+#endif
+
+#ifndef STATUS_INVALID_LEVEL
+# define STATUS_INVALID_LEVEL ((NTSTATUS) 0xC0000148L)
+#endif
+
+#ifndef STATUS_WRONG_PASSWORD_CORE
+# define STATUS_WRONG_PASSWORD_CORE ((NTSTATUS) 0xC0000149L)
+#endif
+
+#ifndef STATUS_ILLEGAL_FLOAT_CONTEXT
+# define STATUS_ILLEGAL_FLOAT_CONTEXT ((NTSTATUS) 0xC000014AL)
+#endif
+
+#ifndef STATUS_PIPE_BROKEN
+# define STATUS_PIPE_BROKEN ((NTSTATUS) 0xC000014BL)
+#endif
+
+#ifndef STATUS_REGISTRY_CORRUPT
+# define STATUS_REGISTRY_CORRUPT ((NTSTATUS) 0xC000014CL)
+#endif
+
+#ifndef STATUS_REGISTRY_IO_FAILED
+# define STATUS_REGISTRY_IO_FAILED ((NTSTATUS) 0xC000014DL)
+#endif
+
+#ifndef STATUS_NO_EVENT_PAIR
+# define STATUS_NO_EVENT_PAIR ((NTSTATUS) 0xC000014EL)
+#endif
+
+#ifndef STATUS_UNRECOGNIZED_VOLUME
+# define STATUS_UNRECOGNIZED_VOLUME ((NTSTATUS) 0xC000014FL)
+#endif
+
+#ifndef STATUS_SERIAL_NO_DEVICE_INITED
+# define STATUS_SERIAL_NO_DEVICE_INITED ((NTSTATUS) 0xC0000150L)
+#endif
+
+#ifndef STATUS_NO_SUCH_ALIAS
+# define STATUS_NO_SUCH_ALIAS ((NTSTATUS) 0xC0000151L)
+#endif
+
+#ifndef STATUS_MEMBER_NOT_IN_ALIAS
+# define STATUS_MEMBER_NOT_IN_ALIAS ((NTSTATUS) 0xC0000152L)
+#endif
+
+#ifndef STATUS_MEMBER_IN_ALIAS
+# define STATUS_MEMBER_IN_ALIAS ((NTSTATUS) 0xC0000153L)
+#endif
+
+#ifndef STATUS_ALIAS_EXISTS
+# define STATUS_ALIAS_EXISTS ((NTSTATUS) 0xC0000154L)
+#endif
+
+#ifndef STATUS_LOGON_NOT_GRANTED
+# define STATUS_LOGON_NOT_GRANTED ((NTSTATUS) 0xC0000155L)
+#endif
+
+#ifndef STATUS_TOO_MANY_SECRETS
+# define STATUS_TOO_MANY_SECRETS ((NTSTATUS) 0xC0000156L)
+#endif
+
+#ifndef STATUS_SECRET_TOO_LONG
+# define STATUS_SECRET_TOO_LONG ((NTSTATUS) 0xC0000157L)
+#endif
+
+#ifndef STATUS_INTERNAL_DB_ERROR
+# define STATUS_INTERNAL_DB_ERROR ((NTSTATUS) 0xC0000158L)
+#endif
+
+#ifndef STATUS_FULLSCREEN_MODE
+# define STATUS_FULLSCREEN_MODE ((NTSTATUS) 0xC0000159L)
+#endif
+
+#ifndef STATUS_TOO_MANY_CONTEXT_IDS
+# define STATUS_TOO_MANY_CONTEXT_IDS ((NTSTATUS) 0xC000015AL)
+#endif
+
+#ifndef STATUS_LOGON_TYPE_NOT_GRANTED
+# define STATUS_LOGON_TYPE_NOT_GRANTED ((NTSTATUS) 0xC000015BL)
+#endif
+
+#ifndef STATUS_NOT_REGISTRY_FILE
+# define STATUS_NOT_REGISTRY_FILE ((NTSTATUS) 0xC000015CL)
+#endif
+
+#ifndef STATUS_NT_CROSS_ENCRYPTION_REQUIRED
+# define STATUS_NT_CROSS_ENCRYPTION_REQUIRED ((NTSTATUS) 0xC000015DL)
+#endif
+
+#ifndef STATUS_DOMAIN_CTRLR_CONFIG_ERROR
+# define STATUS_DOMAIN_CTRLR_CONFIG_ERROR ((NTSTATUS) 0xC000015EL)
+#endif
+
+#ifndef STATUS_FT_MISSING_MEMBER
+# define STATUS_FT_MISSING_MEMBER ((NTSTATUS) 0xC000015FL)
+#endif
+
+#ifndef STATUS_ILL_FORMED_SERVICE_ENTRY
+# define STATUS_ILL_FORMED_SERVICE_ENTRY ((NTSTATUS) 0xC0000160L)
+#endif
+
+#ifndef STATUS_ILLEGAL_CHARACTER
+# define STATUS_ILLEGAL_CHARACTER ((NTSTATUS) 0xC0000161L)
+#endif
+
+#ifndef STATUS_UNMAPPABLE_CHARACTER
+# define STATUS_UNMAPPABLE_CHARACTER ((NTSTATUS) 0xC0000162L)
+#endif
+
+#ifndef STATUS_UNDEFINED_CHARACTER
+# define STATUS_UNDEFINED_CHARACTER ((NTSTATUS) 0xC0000163L)
+#endif
+
+#ifndef STATUS_FLOPPY_VOLUME
+# define STATUS_FLOPPY_VOLUME ((NTSTATUS) 0xC0000164L)
+#endif
+
+#ifndef STATUS_FLOPPY_ID_MARK_NOT_FOUND
+# define STATUS_FLOPPY_ID_MARK_NOT_FOUND ((NTSTATUS) 0xC0000165L)
+#endif
+
+#ifndef STATUS_FLOPPY_WRONG_CYLINDER
+# define STATUS_FLOPPY_WRONG_CYLINDER ((NTSTATUS) 0xC0000166L)
+#endif
+
+#ifndef STATUS_FLOPPY_UNKNOWN_ERROR
+# define STATUS_FLOPPY_UNKNOWN_ERROR ((NTSTATUS) 0xC0000167L)
+#endif
+
+#ifndef STATUS_FLOPPY_BAD_REGISTERS
+# define STATUS_FLOPPY_BAD_REGISTERS ((NTSTATUS) 0xC0000168L)
+#endif
+
+#ifndef STATUS_DISK_RECALIBRATE_FAILED
+# define STATUS_DISK_RECALIBRATE_FAILED ((NTSTATUS) 0xC0000169L)
+#endif
+
+#ifndef STATUS_DISK_OPERATION_FAILED
+# define STATUS_DISK_OPERATION_FAILED ((NTSTATUS) 0xC000016AL)
+#endif
+
+#ifndef STATUS_DISK_RESET_FAILED
+# define STATUS_DISK_RESET_FAILED ((NTSTATUS) 0xC000016BL)
+#endif
+
+#ifndef STATUS_SHARED_IRQ_BUSY
+# define STATUS_SHARED_IRQ_BUSY ((NTSTATUS) 0xC000016CL)
+#endif
+
+#ifndef STATUS_FT_ORPHANING
+# define STATUS_FT_ORPHANING ((NTSTATUS) 0xC000016DL)
+#endif
+
+#ifndef STATUS_BIOS_FAILED_TO_CONNECT_INTERRUPT
+# define STATUS_BIOS_FAILED_TO_CONNECT_INTERRUPT ((NTSTATUS) 0xC000016EL)
+#endif
+
+#ifndef STATUS_PARTITION_FAILURE
+# define STATUS_PARTITION_FAILURE ((NTSTATUS) 0xC0000172L)
+#endif
+
+#ifndef STATUS_INVALID_BLOCK_LENGTH
+# define STATUS_INVALID_BLOCK_LENGTH ((NTSTATUS) 0xC0000173L)
+#endif
+
+#ifndef STATUS_DEVICE_NOT_PARTITIONED
+# define STATUS_DEVICE_NOT_PARTITIONED ((NTSTATUS) 0xC0000174L)
+#endif
+
+#ifndef STATUS_UNABLE_TO_LOCK_MEDIA
+# define STATUS_UNABLE_TO_LOCK_MEDIA ((NTSTATUS) 0xC0000175L)
+#endif
+
+#ifndef STATUS_UNABLE_TO_UNLOAD_MEDIA
+# define STATUS_UNABLE_TO_UNLOAD_MEDIA ((NTSTATUS) 0xC0000176L)
+#endif
+
+#ifndef STATUS_EOM_OVERFLOW
+# define STATUS_EOM_OVERFLOW ((NTSTATUS) 0xC0000177L)
+#endif
+
+#ifndef STATUS_NO_MEDIA
+# define STATUS_NO_MEDIA ((NTSTATUS) 0xC0000178L)
+#endif
+
+#ifndef STATUS_NO_SUCH_MEMBER
+# define STATUS_NO_SUCH_MEMBER ((NTSTATUS) 0xC000017AL)
+#endif
+
+#ifndef STATUS_INVALID_MEMBER
+# define STATUS_INVALID_MEMBER ((NTSTATUS) 0xC000017BL)
+#endif
+
+#ifndef STATUS_KEY_DELETED
+# define STATUS_KEY_DELETED ((NTSTATUS) 0xC000017CL)
+#endif
+
+#ifndef STATUS_NO_LOG_SPACE
+# define STATUS_NO_LOG_SPACE ((NTSTATUS) 0xC000017DL)
+#endif
+
+#ifndef STATUS_TOO_MANY_SIDS
+# define STATUS_TOO_MANY_SIDS ((NTSTATUS) 0xC000017EL)
+#endif
+
+#ifndef STATUS_LM_CROSS_ENCRYPTION_REQUIRED
+# define STATUS_LM_CROSS_ENCRYPTION_REQUIRED ((NTSTATUS) 0xC000017FL)
+#endif
+
+#ifndef STATUS_KEY_HAS_CHILDREN
+# define STATUS_KEY_HAS_CHILDREN ((NTSTATUS) 0xC0000180L)
+#endif
+
+#ifndef STATUS_CHILD_MUST_BE_VOLATILE
+# define STATUS_CHILD_MUST_BE_VOLATILE ((NTSTATUS) 0xC0000181L)
+#endif
+
+#ifndef STATUS_DEVICE_CONFIGURATION_ERROR
+# define STATUS_DEVICE_CONFIGURATION_ERROR ((NTSTATUS) 0xC0000182L)
+#endif
+
+#ifndef STATUS_DRIVER_INTERNAL_ERROR
+# define STATUS_DRIVER_INTERNAL_ERROR ((NTSTATUS) 0xC0000183L)
+#endif
+
+#ifndef STATUS_INVALID_DEVICE_STATE
+# define STATUS_INVALID_DEVICE_STATE ((NTSTATUS) 0xC0000184L)
+#endif
+
+#ifndef STATUS_IO_DEVICE_ERROR
+# define STATUS_IO_DEVICE_ERROR ((NTSTATUS) 0xC0000185L)
+#endif
+
+#ifndef STATUS_DEVICE_PROTOCOL_ERROR
+# define STATUS_DEVICE_PROTOCOL_ERROR ((NTSTATUS) 0xC0000186L)
+#endif
+
+#ifndef STATUS_BACKUP_CONTROLLER
+# define STATUS_BACKUP_CONTROLLER ((NTSTATUS) 0xC0000187L)
+#endif
+
+#ifndef STATUS_LOG_FILE_FULL
+# define STATUS_LOG_FILE_FULL ((NTSTATUS) 0xC0000188L)
+#endif
+
+#ifndef STATUS_TOO_LATE
+# define STATUS_TOO_LATE ((NTSTATUS) 0xC0000189L)
+#endif
+
+#ifndef STATUS_NO_TRUST_LSA_SECRET
+# define STATUS_NO_TRUST_LSA_SECRET ((NTSTATUS) 0xC000018AL)
+#endif
+
+#ifndef STATUS_NO_TRUST_SAM_ACCOUNT
+# define STATUS_NO_TRUST_SAM_ACCOUNT ((NTSTATUS) 0xC000018BL)
+#endif
+
+#ifndef STATUS_TRUSTED_DOMAIN_FAILURE
+# define STATUS_TRUSTED_DOMAIN_FAILURE ((NTSTATUS) 0xC000018CL)
+#endif
+
+#ifndef STATUS_TRUSTED_RELATIONSHIP_FAILURE
+# define STATUS_TRUSTED_RELATIONSHIP_FAILURE ((NTSTATUS) 0xC000018DL)
+#endif
+
+#ifndef STATUS_EVENTLOG_FILE_CORRUPT
+# define STATUS_EVENTLOG_FILE_CORRUPT ((NTSTATUS) 0xC000018EL)
+#endif
+
+#ifndef STATUS_EVENTLOG_CANT_START
+# define STATUS_EVENTLOG_CANT_START ((NTSTATUS) 0xC000018FL)
+#endif
+
+#ifndef STATUS_TRUST_FAILURE
+# define STATUS_TRUST_FAILURE ((NTSTATUS) 0xC0000190L)
+#endif
+
+#ifndef STATUS_MUTANT_LIMIT_EXCEEDED
+# define STATUS_MUTANT_LIMIT_EXCEEDED ((NTSTATUS) 0xC0000191L)
+#endif
+
+#ifndef STATUS_NETLOGON_NOT_STARTED
+# define STATUS_NETLOGON_NOT_STARTED ((NTSTATUS) 0xC0000192L)
+#endif
+
+#ifndef STATUS_ACCOUNT_EXPIRED
+# define STATUS_ACCOUNT_EXPIRED ((NTSTATUS) 0xC0000193L)
+#endif
+
+#ifndef STATUS_POSSIBLE_DEADLOCK
+# define STATUS_POSSIBLE_DEADLOCK ((NTSTATUS) 0xC0000194L)
+#endif
+
+#ifndef STATUS_NETWORK_CREDENTIAL_CONFLICT
+# define STATUS_NETWORK_CREDENTIAL_CONFLICT ((NTSTATUS) 0xC0000195L)
+#endif
+
+#ifndef STATUS_REMOTE_SESSION_LIMIT
+# define STATUS_REMOTE_SESSION_LIMIT ((NTSTATUS) 0xC0000196L)
+#endif
+
+#ifndef STATUS_EVENTLOG_FILE_CHANGED
+# define STATUS_EVENTLOG_FILE_CHANGED ((NTSTATUS) 0xC0000197L)
+#endif
+
+#ifndef STATUS_NOLOGON_INTERDOMAIN_TRUST_ACCOUNT
+# define STATUS_NOLOGON_INTERDOMAIN_TRUST_ACCOUNT ((NTSTATUS) 0xC0000198L)
+#endif
+
+#ifndef STATUS_NOLOGON_WORKSTATION_TRUST_ACCOUNT
+# define STATUS_NOLOGON_WORKSTATION_TRUST_ACCOUNT ((NTSTATUS) 0xC0000199L)
+#endif
+
+#ifndef STATUS_NOLOGON_SERVER_TRUST_ACCOUNT
+# define STATUS_NOLOGON_SERVER_TRUST_ACCOUNT ((NTSTATUS) 0xC000019AL)
+#endif
+
+#ifndef STATUS_DOMAIN_TRUST_INCONSISTENT
+# define STATUS_DOMAIN_TRUST_INCONSISTENT ((NTSTATUS) 0xC000019BL)
+#endif
+
+#ifndef STATUS_FS_DRIVER_REQUIRED
+# define STATUS_FS_DRIVER_REQUIRED ((NTSTATUS) 0xC000019CL)
+#endif
+
+#ifndef STATUS_IMAGE_ALREADY_LOADED_AS_DLL
+# define STATUS_IMAGE_ALREADY_LOADED_AS_DLL ((NTSTATUS) 0xC000019DL)
+#endif
+
+#ifndef STATUS_INCOMPATIBLE_WITH_GLOBAL_SHORT_NAME_REGISTRY_SETTING
+# define STATUS_INCOMPATIBLE_WITH_GLOBAL_SHORT_NAME_REGISTRY_SETTING ((NTSTATUS) 0xC000019EL)
+#endif
+
+#ifndef STATUS_SHORT_NAMES_NOT_ENABLED_ON_VOLUME
+# define STATUS_SHORT_NAMES_NOT_ENABLED_ON_VOLUME ((NTSTATUS) 0xC000019FL)
+#endif
+
+#ifndef STATUS_SECURITY_STREAM_IS_INCONSISTENT
+# define STATUS_SECURITY_STREAM_IS_INCONSISTENT ((NTSTATUS) 0xC00001A0L)
+#endif
+
+#ifndef STATUS_INVALID_LOCK_RANGE
+# define STATUS_INVALID_LOCK_RANGE ((NTSTATUS) 0xC00001A1L)
+#endif
+
+#ifndef STATUS_INVALID_ACE_CONDITION
+# define STATUS_INVALID_ACE_CONDITION ((NTSTATUS) 0xC00001A2L)
+#endif
+
+#ifndef STATUS_IMAGE_SUBSYSTEM_NOT_PRESENT
+# define STATUS_IMAGE_SUBSYSTEM_NOT_PRESENT ((NTSTATUS) 0xC00001A3L)
+#endif
+
+#ifndef STATUS_NOTIFICATION_GUID_ALREADY_DEFINED
+# define STATUS_NOTIFICATION_GUID_ALREADY_DEFINED ((NTSTATUS) 0xC00001A4L)
+#endif
+
+#ifndef STATUS_NETWORK_OPEN_RESTRICTION
+# define STATUS_NETWORK_OPEN_RESTRICTION ((NTSTATUS) 0xC0000201L)
+#endif
+
+#ifndef STATUS_NO_USER_SESSION_KEY
+# define STATUS_NO_USER_SESSION_KEY ((NTSTATUS) 0xC0000202L)
+#endif
+
+#ifndef STATUS_USER_SESSION_DELETED
+# define STATUS_USER_SESSION_DELETED ((NTSTATUS) 0xC0000203L)
+#endif
+
+#ifndef STATUS_RESOURCE_LANG_NOT_FOUND
+# define STATUS_RESOURCE_LANG_NOT_FOUND ((NTSTATUS) 0xC0000204L)
+#endif
+
+#ifndef STATUS_INSUFF_SERVER_RESOURCES
+# define STATUS_INSUFF_SERVER_RESOURCES ((NTSTATUS) 0xC0000205L)
+#endif
+
+#ifndef STATUS_INVALID_BUFFER_SIZE
+# define STATUS_INVALID_BUFFER_SIZE ((NTSTATUS) 0xC0000206L)
+#endif
+
+#ifndef STATUS_INVALID_ADDRESS_COMPONENT
+# define STATUS_INVALID_ADDRESS_COMPONENT ((NTSTATUS) 0xC0000207L)
+#endif
+
+#ifndef STATUS_INVALID_ADDRESS_WILDCARD
+# define STATUS_INVALID_ADDRESS_WILDCARD ((NTSTATUS) 0xC0000208L)
+#endif
+
+#ifndef STATUS_TOO_MANY_ADDRESSES
+# define STATUS_TOO_MANY_ADDRESSES ((NTSTATUS) 0xC0000209L)
+#endif
+
+#ifndef STATUS_ADDRESS_ALREADY_EXISTS
+# define STATUS_ADDRESS_ALREADY_EXISTS ((NTSTATUS) 0xC000020AL)
+#endif
+
+#ifndef STATUS_ADDRESS_CLOSED
+# define STATUS_ADDRESS_CLOSED ((NTSTATUS) 0xC000020BL)
+#endif
+
+#ifndef STATUS_CONNECTION_DISCONNECTED
+# define STATUS_CONNECTION_DISCONNECTED ((NTSTATUS) 0xC000020CL)
+#endif
+
+#ifndef STATUS_CONNECTION_RESET
+# define STATUS_CONNECTION_RESET ((NTSTATUS) 0xC000020DL)
+#endif
+
+#ifndef STATUS_TOO_MANY_NODES
+# define STATUS_TOO_MANY_NODES ((NTSTATUS) 0xC000020EL)
+#endif
+
+#ifndef STATUS_TRANSACTION_ABORTED
+# define STATUS_TRANSACTION_ABORTED ((NTSTATUS) 0xC000020FL)
+#endif
+
+#ifndef STATUS_TRANSACTION_TIMED_OUT
+# define STATUS_TRANSACTION_TIMED_OUT ((NTSTATUS) 0xC0000210L)
+#endif
+
+#ifndef STATUS_TRANSACTION_NO_RELEASE
+# define STATUS_TRANSACTION_NO_RELEASE ((NTSTATUS) 0xC0000211L)
+#endif
+
+#ifndef STATUS_TRANSACTION_NO_MATCH
+# define STATUS_TRANSACTION_NO_MATCH ((NTSTATUS) 0xC0000212L)
+#endif
+
+#ifndef STATUS_TRANSACTION_RESPONDED
+# define STATUS_TRANSACTION_RESPONDED ((NTSTATUS) 0xC0000213L)
+#endif
+
+#ifndef STATUS_TRANSACTION_INVALID_ID
+# define STATUS_TRANSACTION_INVALID_ID ((NTSTATUS) 0xC0000214L)
+#endif
+
+#ifndef STATUS_TRANSACTION_INVALID_TYPE
+# define STATUS_TRANSACTION_INVALID_TYPE ((NTSTATUS) 0xC0000215L)
+#endif
+
+#ifndef STATUS_NOT_SERVER_SESSION
+# define STATUS_NOT_SERVER_SESSION ((NTSTATUS) 0xC0000216L)
+#endif
+
+#ifndef STATUS_NOT_CLIENT_SESSION
+# define STATUS_NOT_CLIENT_SESSION ((NTSTATUS) 0xC0000217L)
+#endif
+
+#ifndef STATUS_CANNOT_LOAD_REGISTRY_FILE
+# define STATUS_CANNOT_LOAD_REGISTRY_FILE ((NTSTATUS) 0xC0000218L)
+#endif
+
+#ifndef STATUS_DEBUG_ATTACH_FAILED
+# define STATUS_DEBUG_ATTACH_FAILED ((NTSTATUS) 0xC0000219L)
+#endif
+
+#ifndef STATUS_SYSTEM_PROCESS_TERMINATED
+# define STATUS_SYSTEM_PROCESS_TERMINATED ((NTSTATUS) 0xC000021AL)
+#endif
+
+#ifndef STATUS_DATA_NOT_ACCEPTED
+# define STATUS_DATA_NOT_ACCEPTED ((NTSTATUS) 0xC000021BL)
+#endif
+
+#ifndef STATUS_NO_BROWSER_SERVERS_FOUND
+# define STATUS_NO_BROWSER_SERVERS_FOUND ((NTSTATUS) 0xC000021CL)
+#endif
+
+#ifndef STATUS_VDM_HARD_ERROR
+# define STATUS_VDM_HARD_ERROR ((NTSTATUS) 0xC000021DL)
+#endif
+
+#ifndef STATUS_DRIVER_CANCEL_TIMEOUT
+# define STATUS_DRIVER_CANCEL_TIMEOUT ((NTSTATUS) 0xC000021EL)
+#endif
+
+#ifndef STATUS_REPLY_MESSAGE_MISMATCH
+# define STATUS_REPLY_MESSAGE_MISMATCH ((NTSTATUS) 0xC000021FL)
+#endif
+
+#ifndef STATUS_MAPPED_ALIGNMENT
+# define STATUS_MAPPED_ALIGNMENT ((NTSTATUS) 0xC0000220L)
+#endif
+
+#ifndef STATUS_IMAGE_CHECKSUM_MISMATCH
+# define STATUS_IMAGE_CHECKSUM_MISMATCH ((NTSTATUS) 0xC0000221L)
+#endif
+
+#ifndef STATUS_LOST_WRITEBEHIND_DATA
+# define STATUS_LOST_WRITEBEHIND_DATA ((NTSTATUS) 0xC0000222L)
+#endif
+
+#ifndef STATUS_CLIENT_SERVER_PARAMETERS_INVALID
+# define STATUS_CLIENT_SERVER_PARAMETERS_INVALID ((NTSTATUS) 0xC0000223L)
+#endif
+
+#ifndef STATUS_PASSWORD_MUST_CHANGE
+# define STATUS_PASSWORD_MUST_CHANGE ((NTSTATUS) 0xC0000224L)
+#endif
+
+#ifndef STATUS_NOT_FOUND
+# define STATUS_NOT_FOUND ((NTSTATUS) 0xC0000225L)
+#endif
+
+#ifndef STATUS_NOT_TINY_STREAM
+# define STATUS_NOT_TINY_STREAM ((NTSTATUS) 0xC0000226L)
+#endif
+
+#ifndef STATUS_RECOVERY_FAILURE
+# define STATUS_RECOVERY_FAILURE ((NTSTATUS) 0xC0000227L)
+#endif
+
+#ifndef STATUS_STACK_OVERFLOW_READ
+# define STATUS_STACK_OVERFLOW_READ ((NTSTATUS) 0xC0000228L)
+#endif
+
+#ifndef STATUS_FAIL_CHECK
+# define STATUS_FAIL_CHECK ((NTSTATUS) 0xC0000229L)
+#endif
+
+#ifndef STATUS_DUPLICATE_OBJECTID
+# define STATUS_DUPLICATE_OBJECTID ((NTSTATUS) 0xC000022AL)
+#endif
+
+#ifndef STATUS_OBJECTID_EXISTS
+# define STATUS_OBJECTID_EXISTS ((NTSTATUS) 0xC000022BL)
+#endif
+
+#ifndef STATUS_CONVERT_TO_LARGE
+# define STATUS_CONVERT_TO_LARGE ((NTSTATUS) 0xC000022CL)
+#endif
+
+#ifndef STATUS_RETRY
+# define STATUS_RETRY ((NTSTATUS) 0xC000022DL)
+#endif
+
+#ifndef STATUS_FOUND_OUT_OF_SCOPE
+# define STATUS_FOUND_OUT_OF_SCOPE ((NTSTATUS) 0xC000022EL)
+#endif
+
+#ifndef STATUS_ALLOCATE_BUCKET
+# define STATUS_ALLOCATE_BUCKET ((NTSTATUS) 0xC000022FL)
+#endif
+
+#ifndef STATUS_PROPSET_NOT_FOUND
+# define STATUS_PROPSET_NOT_FOUND ((NTSTATUS) 0xC0000230L)
+#endif
+
+#ifndef STATUS_MARSHALL_OVERFLOW
+# define STATUS_MARSHALL_OVERFLOW ((NTSTATUS) 0xC0000231L)
+#endif
+
+#ifndef STATUS_INVALID_VARIANT
+# define STATUS_INVALID_VARIANT ((NTSTATUS) 0xC0000232L)
+#endif
+
+#ifndef STATUS_DOMAIN_CONTROLLER_NOT_FOUND
+# define STATUS_DOMAIN_CONTROLLER_NOT_FOUND ((NTSTATUS) 0xC0000233L)
+#endif
+
+#ifndef STATUS_ACCOUNT_LOCKED_OUT
+# define STATUS_ACCOUNT_LOCKED_OUT ((NTSTATUS) 0xC0000234L)
+#endif
+
+#ifndef STATUS_HANDLE_NOT_CLOSABLE
+# define STATUS_HANDLE_NOT_CLOSABLE ((NTSTATUS) 0xC0000235L)
+#endif
+
+#ifndef STATUS_CONNECTION_REFUSED
+# define STATUS_CONNECTION_REFUSED ((NTSTATUS) 0xC0000236L)
+#endif
+
+#ifndef STATUS_GRACEFUL_DISCONNECT
+# define STATUS_GRACEFUL_DISCONNECT ((NTSTATUS) 0xC0000237L)
+#endif
+
+#ifndef STATUS_ADDRESS_ALREADY_ASSOCIATED
+# define STATUS_ADDRESS_ALREADY_ASSOCIATED ((NTSTATUS) 0xC0000238L)
+#endif
+
+#ifndef STATUS_ADDRESS_NOT_ASSOCIATED
+# define STATUS_ADDRESS_NOT_ASSOCIATED ((NTSTATUS) 0xC0000239L)
+#endif
+
+#ifndef STATUS_CONNECTION_INVALID
+# define STATUS_CONNECTION_INVALID ((NTSTATUS) 0xC000023AL)
+#endif
+
+#ifndef STATUS_CONNECTION_ACTIVE
+# define STATUS_CONNECTION_ACTIVE ((NTSTATUS) 0xC000023BL)
+#endif
+
+#ifndef STATUS_NETWORK_UNREACHABLE
+# define STATUS_NETWORK_UNREACHABLE ((NTSTATUS) 0xC000023CL)
+#endif
+
+#ifndef STATUS_HOST_UNREACHABLE
+# define STATUS_HOST_UNREACHABLE ((NTSTATUS) 0xC000023DL)
+#endif
+
+#ifndef STATUS_PROTOCOL_UNREACHABLE
+# define STATUS_PROTOCOL_UNREACHABLE ((NTSTATUS) 0xC000023EL)
+#endif
+
+#ifndef STATUS_PORT_UNREACHABLE
+# define STATUS_PORT_UNREACHABLE ((NTSTATUS) 0xC000023FL)
+#endif
+
+#ifndef STATUS_REQUEST_ABORTED
+# define STATUS_REQUEST_ABORTED ((NTSTATUS) 0xC0000240L)
+#endif
+
+#ifndef STATUS_CONNECTION_ABORTED
+# define STATUS_CONNECTION_ABORTED ((NTSTATUS) 0xC0000241L)
+#endif
+
+#ifndef STATUS_BAD_COMPRESSION_BUFFER
+# define STATUS_BAD_COMPRESSION_BUFFER ((NTSTATUS) 0xC0000242L)
+#endif
+
+#ifndef STATUS_USER_MAPPED_FILE
+# define STATUS_USER_MAPPED_FILE ((NTSTATUS) 0xC0000243L)
+#endif
+
+#ifndef STATUS_AUDIT_FAILED
+# define STATUS_AUDIT_FAILED ((NTSTATUS) 0xC0000244L)
+#endif
+
+#ifndef STATUS_TIMER_RESOLUTION_NOT_SET
+# define STATUS_TIMER_RESOLUTION_NOT_SET ((NTSTATUS) 0xC0000245L)
+#endif
+
+#ifndef STATUS_CONNECTION_COUNT_LIMIT
+# define STATUS_CONNECTION_COUNT_LIMIT ((NTSTATUS) 0xC0000246L)
+#endif
+
+#ifndef STATUS_LOGIN_TIME_RESTRICTION
+# define STATUS_LOGIN_TIME_RESTRICTION ((NTSTATUS) 0xC0000247L)
+#endif
+
+#ifndef STATUS_LOGIN_WKSTA_RESTRICTION
+# define STATUS_LOGIN_WKSTA_RESTRICTION ((NTSTATUS) 0xC0000248L)
+#endif
+
+#ifndef STATUS_IMAGE_MP_UP_MISMATCH
+# define STATUS_IMAGE_MP_UP_MISMATCH ((NTSTATUS) 0xC0000249L)
+#endif
+
+#ifndef STATUS_INSUFFICIENT_LOGON_INFO
+# define STATUS_INSUFFICIENT_LOGON_INFO ((NTSTATUS) 0xC0000250L)
+#endif
+
+#ifndef STATUS_BAD_DLL_ENTRYPOINT
+# define STATUS_BAD_DLL_ENTRYPOINT ((NTSTATUS) 0xC0000251L)
+#endif
+
+#ifndef STATUS_BAD_SERVICE_ENTRYPOINT
+# define STATUS_BAD_SERVICE_ENTRYPOINT ((NTSTATUS) 0xC0000252L)
+#endif
+
+#ifndef STATUS_LPC_REPLY_LOST
+# define STATUS_LPC_REPLY_LOST ((NTSTATUS) 0xC0000253L)
+#endif
+
+#ifndef STATUS_IP_ADDRESS_CONFLICT1
+# define STATUS_IP_ADDRESS_CONFLICT1 ((NTSTATUS) 0xC0000254L)
+#endif
+
+#ifndef STATUS_IP_ADDRESS_CONFLICT2
+# define STATUS_IP_ADDRESS_CONFLICT2 ((NTSTATUS) 0xC0000255L)
+#endif
+
+#ifndef STATUS_REGISTRY_QUOTA_LIMIT
+# define STATUS_REGISTRY_QUOTA_LIMIT ((NTSTATUS) 0xC0000256L)
+#endif
+
+#ifndef STATUS_PATH_NOT_COVERED
+# define STATUS_PATH_NOT_COVERED ((NTSTATUS) 0xC0000257L)
+#endif
+
+#ifndef STATUS_NO_CALLBACK_ACTIVE
+# define STATUS_NO_CALLBACK_ACTIVE ((NTSTATUS) 0xC0000258L)
+#endif
+
+#ifndef STATUS_LICENSE_QUOTA_EXCEEDED
+# define STATUS_LICENSE_QUOTA_EXCEEDED ((NTSTATUS) 0xC0000259L)
+#endif
+
+#ifndef STATUS_PWD_TOO_SHORT
+# define STATUS_PWD_TOO_SHORT ((NTSTATUS) 0xC000025AL)
+#endif
+
+#ifndef STATUS_PWD_TOO_RECENT
+# define STATUS_PWD_TOO_RECENT ((NTSTATUS) 0xC000025BL)
+#endif
+
+#ifndef STATUS_PWD_HISTORY_CONFLICT
+# define STATUS_PWD_HISTORY_CONFLICT ((NTSTATUS) 0xC000025CL)
+#endif
+
+#ifndef STATUS_PLUGPLAY_NO_DEVICE
+# define STATUS_PLUGPLAY_NO_DEVICE ((NTSTATUS) 0xC000025EL)
+#endif
+
+#ifndef STATUS_UNSUPPORTED_COMPRESSION
+# define STATUS_UNSUPPORTED_COMPRESSION ((NTSTATUS) 0xC000025FL)
+#endif
+
+#ifndef STATUS_INVALID_HW_PROFILE
+# define STATUS_INVALID_HW_PROFILE ((NTSTATUS) 0xC0000260L)
+#endif
+
+#ifndef STATUS_INVALID_PLUGPLAY_DEVICE_PATH
+# define STATUS_INVALID_PLUGPLAY_DEVICE_PATH ((NTSTATUS) 0xC0000261L)
+#endif
+
+#ifndef STATUS_DRIVER_ORDINAL_NOT_FOUND
+# define STATUS_DRIVER_ORDINAL_NOT_FOUND ((NTSTATUS) 0xC0000262L)
+#endif
+
+#ifndef STATUS_DRIVER_ENTRYPOINT_NOT_FOUND
+# define STATUS_DRIVER_ENTRYPOINT_NOT_FOUND ((NTSTATUS) 0xC0000263L)
+#endif
+
+#ifndef STATUS_RESOURCE_NOT_OWNED
+# define STATUS_RESOURCE_NOT_OWNED ((NTSTATUS) 0xC0000264L)
+#endif
+
+#ifndef STATUS_TOO_MANY_LINKS
+# define STATUS_TOO_MANY_LINKS ((NTSTATUS) 0xC0000265L)
+#endif
+
+#ifndef STATUS_QUOTA_LIST_INCONSISTENT
+# define STATUS_QUOTA_LIST_INCONSISTENT ((NTSTATUS) 0xC0000266L)
+#endif
+
+#ifndef STATUS_FILE_IS_OFFLINE
+# define STATUS_FILE_IS_OFFLINE ((NTSTATUS) 0xC0000267L)
+#endif
+
+#ifndef STATUS_EVALUATION_EXPIRATION
+# define STATUS_EVALUATION_EXPIRATION ((NTSTATUS) 0xC0000268L)
+#endif
+
+#ifndef STATUS_ILLEGAL_DLL_RELOCATION
+# define STATUS_ILLEGAL_DLL_RELOCATION ((NTSTATUS) 0xC0000269L)
+#endif
+
+#ifndef STATUS_LICENSE_VIOLATION
+# define STATUS_LICENSE_VIOLATION ((NTSTATUS) 0xC000026AL)
+#endif
+
+#ifndef STATUS_DLL_INIT_FAILED_LOGOFF
+# define STATUS_DLL_INIT_FAILED_LOGOFF ((NTSTATUS) 0xC000026BL)
+#endif
+
+#ifndef STATUS_DRIVER_UNABLE_TO_LOAD
+# define STATUS_DRIVER_UNABLE_TO_LOAD ((NTSTATUS) 0xC000026CL)
+#endif
+
+#ifndef STATUS_DFS_UNAVAILABLE
+# define STATUS_DFS_UNAVAILABLE ((NTSTATUS) 0xC000026DL)
+#endif
+
+#ifndef STATUS_VOLUME_DISMOUNTED
+# define STATUS_VOLUME_DISMOUNTED ((NTSTATUS) 0xC000026EL)
+#endif
+
+#ifndef STATUS_WX86_INTERNAL_ERROR
+# define STATUS_WX86_INTERNAL_ERROR ((NTSTATUS) 0xC000026FL)
+#endif
+
+#ifndef STATUS_WX86_FLOAT_STACK_CHECK
+# define STATUS_WX86_FLOAT_STACK_CHECK ((NTSTATUS) 0xC0000270L)
+#endif
+
+#ifndef STATUS_VALIDATE_CONTINUE
+# define STATUS_VALIDATE_CONTINUE ((NTSTATUS) 0xC0000271L)
+#endif
+
+#ifndef STATUS_NO_MATCH
+# define STATUS_NO_MATCH ((NTSTATUS) 0xC0000272L)
+#endif
+
+#ifndef STATUS_NO_MORE_MATCHES
+# define STATUS_NO_MORE_MATCHES ((NTSTATUS) 0xC0000273L)
+#endif
+
+#ifndef STATUS_NOT_A_REPARSE_POINT
+# define STATUS_NOT_A_REPARSE_POINT ((NTSTATUS) 0xC0000275L)
+#endif
+
+#ifndef STATUS_IO_REPARSE_TAG_INVALID
+# define STATUS_IO_REPARSE_TAG_INVALID ((NTSTATUS) 0xC0000276L)
+#endif
+
+#ifndef STATUS_IO_REPARSE_TAG_MISMATCH
+# define STATUS_IO_REPARSE_TAG_MISMATCH ((NTSTATUS) 0xC0000277L)
+#endif
+
+#ifndef STATUS_IO_REPARSE_DATA_INVALID
+# define STATUS_IO_REPARSE_DATA_INVALID ((NTSTATUS) 0xC0000278L)
+#endif
+
+#ifndef STATUS_IO_REPARSE_TAG_NOT_HANDLED
+# define STATUS_IO_REPARSE_TAG_NOT_HANDLED ((NTSTATUS) 0xC0000279L)
+#endif
+
+#ifndef STATUS_REPARSE_POINT_NOT_RESOLVED
+# define STATUS_REPARSE_POINT_NOT_RESOLVED ((NTSTATUS) 0xC0000280L)
+#endif
+
+#ifndef STATUS_DIRECTORY_IS_A_REPARSE_POINT
+# define STATUS_DIRECTORY_IS_A_REPARSE_POINT ((NTSTATUS) 0xC0000281L)
+#endif
+
+#ifndef STATUS_RANGE_LIST_CONFLICT
+# define STATUS_RANGE_LIST_CONFLICT ((NTSTATUS) 0xC0000282L)
+#endif
+
+#ifndef STATUS_SOURCE_ELEMENT_EMPTY
+# define STATUS_SOURCE_ELEMENT_EMPTY ((NTSTATUS) 0xC0000283L)
+#endif
+
+#ifndef STATUS_DESTINATION_ELEMENT_FULL
+# define STATUS_DESTINATION_ELEMENT_FULL ((NTSTATUS) 0xC0000284L)
+#endif
+
+#ifndef STATUS_ILLEGAL_ELEMENT_ADDRESS
+# define STATUS_ILLEGAL_ELEMENT_ADDRESS ((NTSTATUS) 0xC0000285L)
+#endif
+
+#ifndef STATUS_MAGAZINE_NOT_PRESENT
+# define STATUS_MAGAZINE_NOT_PRESENT ((NTSTATUS) 0xC0000286L)
+#endif
+
+#ifndef STATUS_REINITIALIZATION_NEEDED
+# define STATUS_REINITIALIZATION_NEEDED ((NTSTATUS) 0xC0000287L)
+#endif
+
+#ifndef STATUS_DEVICE_REQUIRES_CLEANING
+# define STATUS_DEVICE_REQUIRES_CLEANING ((NTSTATUS) 0x80000288L)
+#endif
+
+#ifndef STATUS_DEVICE_DOOR_OPEN
+# define STATUS_DEVICE_DOOR_OPEN ((NTSTATUS) 0x80000289L)
+#endif
+
+#ifndef STATUS_ENCRYPTION_FAILED
+# define STATUS_ENCRYPTION_FAILED ((NTSTATUS) 0xC000028AL)
+#endif
+
+#ifndef STATUS_DECRYPTION_FAILED
+# define STATUS_DECRYPTION_FAILED ((NTSTATUS) 0xC000028BL)
+#endif
+
+#ifndef STATUS_RANGE_NOT_FOUND
+# define STATUS_RANGE_NOT_FOUND ((NTSTATUS) 0xC000028CL)
+#endif
+
+#ifndef STATUS_NO_RECOVERY_POLICY
+# define STATUS_NO_RECOVERY_POLICY ((NTSTATUS) 0xC000028DL)
+#endif
+
+#ifndef STATUS_NO_EFS
+# define STATUS_NO_EFS ((NTSTATUS) 0xC000028EL)
+#endif
+
+#ifndef STATUS_WRONG_EFS
+# define STATUS_WRONG_EFS ((NTSTATUS) 0xC000028FL)
+#endif
+
+#ifndef STATUS_NO_USER_KEYS
+# define STATUS_NO_USER_KEYS ((NTSTATUS) 0xC0000290L)
+#endif
+
+#ifndef STATUS_FILE_NOT_ENCRYPTED
+# define STATUS_FILE_NOT_ENCRYPTED ((NTSTATUS) 0xC0000291L)
+#endif
+
+#ifndef STATUS_NOT_EXPORT_FORMAT
+# define STATUS_NOT_EXPORT_FORMAT ((NTSTATUS) 0xC0000292L)
+#endif
+
+#ifndef STATUS_FILE_ENCRYPTED
+# define STATUS_FILE_ENCRYPTED ((NTSTATUS) 0xC0000293L)
+#endif
+
+#ifndef STATUS_WAKE_SYSTEM
+# define STATUS_WAKE_SYSTEM ((NTSTATUS) 0x40000294L)
+#endif
+
+#ifndef STATUS_WMI_GUID_NOT_FOUND
+# define STATUS_WMI_GUID_NOT_FOUND ((NTSTATUS) 0xC0000295L)
+#endif
+
+#ifndef STATUS_WMI_INSTANCE_NOT_FOUND
+# define STATUS_WMI_INSTANCE_NOT_FOUND ((NTSTATUS) 0xC0000296L)
+#endif
+
+#ifndef STATUS_WMI_ITEMID_NOT_FOUND
+# define STATUS_WMI_ITEMID_NOT_FOUND ((NTSTATUS) 0xC0000297L)
+#endif
+
+#ifndef STATUS_WMI_TRY_AGAIN
+# define STATUS_WMI_TRY_AGAIN ((NTSTATUS) 0xC0000298L)
+#endif
+
+#ifndef STATUS_SHARED_POLICY
+# define STATUS_SHARED_POLICY ((NTSTATUS) 0xC0000299L)
+#endif
+
+#ifndef STATUS_POLICY_OBJECT_NOT_FOUND
+# define STATUS_POLICY_OBJECT_NOT_FOUND ((NTSTATUS) 0xC000029AL)
+#endif
+
+#ifndef STATUS_POLICY_ONLY_IN_DS
+# define STATUS_POLICY_ONLY_IN_DS ((NTSTATUS) 0xC000029BL)
+#endif
+
+#ifndef STATUS_VOLUME_NOT_UPGRADED
+# define STATUS_VOLUME_NOT_UPGRADED ((NTSTATUS) 0xC000029CL)
+#endif
+
+#ifndef STATUS_REMOTE_STORAGE_NOT_ACTIVE
+# define STATUS_REMOTE_STORAGE_NOT_ACTIVE ((NTSTATUS) 0xC000029DL)
+#endif
+
+#ifndef STATUS_REMOTE_STORAGE_MEDIA_ERROR
+# define STATUS_REMOTE_STORAGE_MEDIA_ERROR ((NTSTATUS) 0xC000029EL)
+#endif
+
+#ifndef STATUS_NO_TRACKING_SERVICE
+# define STATUS_NO_TRACKING_SERVICE ((NTSTATUS) 0xC000029FL)
+#endif
+
+#ifndef STATUS_SERVER_SID_MISMATCH
+# define STATUS_SERVER_SID_MISMATCH ((NTSTATUS) 0xC00002A0L)
+#endif
+
+#ifndef STATUS_DS_NO_ATTRIBUTE_OR_VALUE
+# define STATUS_DS_NO_ATTRIBUTE_OR_VALUE ((NTSTATUS) 0xC00002A1L)
+#endif
+
+#ifndef STATUS_DS_INVALID_ATTRIBUTE_SYNTAX
+# define STATUS_DS_INVALID_ATTRIBUTE_SYNTAX ((NTSTATUS) 0xC00002A2L)
+#endif
+
+#ifndef STATUS_DS_ATTRIBUTE_TYPE_UNDEFINED
+# define STATUS_DS_ATTRIBUTE_TYPE_UNDEFINED ((NTSTATUS) 0xC00002A3L)
+#endif
+
+#ifndef STATUS_DS_ATTRIBUTE_OR_VALUE_EXISTS
+# define STATUS_DS_ATTRIBUTE_OR_VALUE_EXISTS ((NTSTATUS) 0xC00002A4L)
+#endif
+
+#ifndef STATUS_DS_BUSY
+# define STATUS_DS_BUSY ((NTSTATUS) 0xC00002A5L)
+#endif
+
+#ifndef STATUS_DS_UNAVAILABLE
+# define STATUS_DS_UNAVAILABLE ((NTSTATUS) 0xC00002A6L)
+#endif
+
+#ifndef STATUS_DS_NO_RIDS_ALLOCATED
+# define STATUS_DS_NO_RIDS_ALLOCATED ((NTSTATUS) 0xC00002A7L)
+#endif
+
+#ifndef STATUS_DS_NO_MORE_RIDS
+# define STATUS_DS_NO_MORE_RIDS ((NTSTATUS) 0xC00002A8L)
+#endif
+
+#ifndef STATUS_DS_INCORRECT_ROLE_OWNER
+# define STATUS_DS_INCORRECT_ROLE_OWNER ((NTSTATUS) 0xC00002A9L)
+#endif
+
+#ifndef STATUS_DS_RIDMGR_INIT_ERROR
+# define STATUS_DS_RIDMGR_INIT_ERROR ((NTSTATUS) 0xC00002AAL)
+#endif
+
+#ifndef STATUS_DS_OBJ_CLASS_VIOLATION
+# define STATUS_DS_OBJ_CLASS_VIOLATION ((NTSTATUS) 0xC00002ABL)
+#endif
+
+#ifndef STATUS_DS_CANT_ON_NON_LEAF
+# define STATUS_DS_CANT_ON_NON_LEAF ((NTSTATUS) 0xC00002ACL)
+#endif
+
+#ifndef STATUS_DS_CANT_ON_RDN
+# define STATUS_DS_CANT_ON_RDN ((NTSTATUS) 0xC00002ADL)
+#endif
+
+#ifndef STATUS_DS_CANT_MOD_OBJ_CLASS
+# define STATUS_DS_CANT_MOD_OBJ_CLASS ((NTSTATUS) 0xC00002AEL)
+#endif
+
+#ifndef STATUS_DS_CROSS_DOM_MOVE_FAILED
+# define STATUS_DS_CROSS_DOM_MOVE_FAILED ((NTSTATUS) 0xC00002AFL)
+#endif
+
+#ifndef STATUS_DS_GC_NOT_AVAILABLE
+# define STATUS_DS_GC_NOT_AVAILABLE ((NTSTATUS) 0xC00002B0L)
+#endif
+
+#ifndef STATUS_DIRECTORY_SERVICE_REQUIRED
+# define STATUS_DIRECTORY_SERVICE_REQUIRED ((NTSTATUS) 0xC00002B1L)
+#endif
+
+#ifndef STATUS_REPARSE_ATTRIBUTE_CONFLICT
+# define STATUS_REPARSE_ATTRIBUTE_CONFLICT ((NTSTATUS) 0xC00002B2L)
+#endif
+
+#ifndef STATUS_CANT_ENABLE_DENY_ONLY
+# define STATUS_CANT_ENABLE_DENY_ONLY ((NTSTATUS) 0xC00002B3L)
+#endif
+
+#ifndef STATUS_FLOAT_MULTIPLE_FAULTS
+# define STATUS_FLOAT_MULTIPLE_FAULTS ((NTSTATUS) 0xC00002B4L)
+#endif
+
+#ifndef STATUS_FLOAT_MULTIPLE_TRAPS
+# define STATUS_FLOAT_MULTIPLE_TRAPS ((NTSTATUS) 0xC00002B5L)
+#endif
+
+#ifndef STATUS_DEVICE_REMOVED
+# define STATUS_DEVICE_REMOVED ((NTSTATUS) 0xC00002B6L)
+#endif
+
+#ifndef STATUS_JOURNAL_DELETE_IN_PROGRESS
+# define STATUS_JOURNAL_DELETE_IN_PROGRESS ((NTSTATUS) 0xC00002B7L)
+#endif
+
+#ifndef STATUS_JOURNAL_NOT_ACTIVE
+# define STATUS_JOURNAL_NOT_ACTIVE ((NTSTATUS) 0xC00002B8L)
+#endif
+
+#ifndef STATUS_NOINTERFACE
+# define STATUS_NOINTERFACE ((NTSTATUS) 0xC00002B9L)
+#endif
+
+#ifndef STATUS_DS_ADMIN_LIMIT_EXCEEDED
+# define STATUS_DS_ADMIN_LIMIT_EXCEEDED ((NTSTATUS) 0xC00002C1L)
+#endif
+
+#ifndef STATUS_DRIVER_FAILED_SLEEP
+# define STATUS_DRIVER_FAILED_SLEEP ((NTSTATUS) 0xC00002C2L)
+#endif
+
+#ifndef STATUS_MUTUAL_AUTHENTICATION_FAILED
+# define STATUS_MUTUAL_AUTHENTICATION_FAILED ((NTSTATUS) 0xC00002C3L)
+#endif
+
+#ifndef STATUS_CORRUPT_SYSTEM_FILE
+# define STATUS_CORRUPT_SYSTEM_FILE ((NTSTATUS) 0xC00002C4L)
+#endif
+
+#ifndef STATUS_DATATYPE_MISALIGNMENT_ERROR
+# define STATUS_DATATYPE_MISALIGNMENT_ERROR ((NTSTATUS) 0xC00002C5L)
+#endif
+
+#ifndef STATUS_WMI_READ_ONLY
+# define STATUS_WMI_READ_ONLY ((NTSTATUS) 0xC00002C6L)
+#endif
+
+#ifndef STATUS_WMI_SET_FAILURE
+# define STATUS_WMI_SET_FAILURE ((NTSTATUS) 0xC00002C7L)
+#endif
+
+#ifndef STATUS_COMMITMENT_MINIMUM
+# define STATUS_COMMITMENT_MINIMUM ((NTSTATUS) 0xC00002C8L)
+#endif
+
+#ifndef STATUS_REG_NAT_CONSUMPTION
+# define STATUS_REG_NAT_CONSUMPTION ((NTSTATUS) 0xC00002C9L)
+#endif
+
+#ifndef STATUS_TRANSPORT_FULL
+# define STATUS_TRANSPORT_FULL ((NTSTATUS) 0xC00002CAL)
+#endif
+
+#ifndef STATUS_DS_SAM_INIT_FAILURE
+# define STATUS_DS_SAM_INIT_FAILURE ((NTSTATUS) 0xC00002CBL)
+#endif
+
+#ifndef STATUS_ONLY_IF_CONNECTED
+# define STATUS_ONLY_IF_CONNECTED ((NTSTATUS) 0xC00002CCL)
+#endif
+
+#ifndef STATUS_DS_SENSITIVE_GROUP_VIOLATION
+# define STATUS_DS_SENSITIVE_GROUP_VIOLATION ((NTSTATUS) 0xC00002CDL)
+#endif
+
+#ifndef STATUS_PNP_RESTART_ENUMERATION
+# define STATUS_PNP_RESTART_ENUMERATION ((NTSTATUS) 0xC00002CEL)
+#endif
+
+#ifndef STATUS_JOURNAL_ENTRY_DELETED
+# define STATUS_JOURNAL_ENTRY_DELETED ((NTSTATUS) 0xC00002CFL)
+#endif
+
+#ifndef STATUS_DS_CANT_MOD_PRIMARYGROUPID
+# define STATUS_DS_CANT_MOD_PRIMARYGROUPID ((NTSTATUS) 0xC00002D0L)
+#endif
+
+#ifndef STATUS_SYSTEM_IMAGE_BAD_SIGNATURE
+# define STATUS_SYSTEM_IMAGE_BAD_SIGNATURE ((NTSTATUS) 0xC00002D1L)
+#endif
+
+#ifndef STATUS_PNP_REBOOT_REQUIRED
+# define STATUS_PNP_REBOOT_REQUIRED ((NTSTATUS) 0xC00002D2L)
+#endif
+
+#ifndef STATUS_POWER_STATE_INVALID
+# define STATUS_POWER_STATE_INVALID ((NTSTATUS) 0xC00002D3L)
+#endif
+
+#ifndef STATUS_DS_INVALID_GROUP_TYPE
+# define STATUS_DS_INVALID_GROUP_TYPE ((NTSTATUS) 0xC00002D4L)
+#endif
+
+#ifndef STATUS_DS_NO_NEST_GLOBALGROUP_IN_MIXEDDOMAIN
+# define STATUS_DS_NO_NEST_GLOBALGROUP_IN_MIXEDDOMAIN ((NTSTATUS) 0xC00002D5L)
+#endif
+
+#ifndef STATUS_DS_NO_NEST_LOCALGROUP_IN_MIXEDDOMAIN
+# define STATUS_DS_NO_NEST_LOCALGROUP_IN_MIXEDDOMAIN ((NTSTATUS) 0xC00002D6L)
+#endif
+
+#ifndef STATUS_DS_GLOBAL_CANT_HAVE_LOCAL_MEMBER
+# define STATUS_DS_GLOBAL_CANT_HAVE_LOCAL_MEMBER ((NTSTATUS) 0xC00002D7L)
+#endif
+
+#ifndef STATUS_DS_GLOBAL_CANT_HAVE_UNIVERSAL_MEMBER
+# define STATUS_DS_GLOBAL_CANT_HAVE_UNIVERSAL_MEMBER ((NTSTATUS) 0xC00002D8L)
+#endif
+
+#ifndef STATUS_DS_UNIVERSAL_CANT_HAVE_LOCAL_MEMBER
+# define STATUS_DS_UNIVERSAL_CANT_HAVE_LOCAL_MEMBER ((NTSTATUS) 0xC00002D9L)
+#endif
+
+#ifndef STATUS_DS_GLOBAL_CANT_HAVE_CROSSDOMAIN_MEMBER
+# define STATUS_DS_GLOBAL_CANT_HAVE_CROSSDOMAIN_MEMBER ((NTSTATUS) 0xC00002DAL)
+#endif
+
+#ifndef STATUS_DS_LOCAL_CANT_HAVE_CROSSDOMAIN_LOCAL_MEMBER
+# define STATUS_DS_LOCAL_CANT_HAVE_CROSSDOMAIN_LOCAL_MEMBER ((NTSTATUS) 0xC00002DBL)
+#endif
+
+#ifndef STATUS_DS_HAVE_PRIMARY_MEMBERS
+# define STATUS_DS_HAVE_PRIMARY_MEMBERS ((NTSTATUS) 0xC00002DCL)
+#endif
+
+#ifndef STATUS_WMI_NOT_SUPPORTED
+# define STATUS_WMI_NOT_SUPPORTED ((NTSTATUS) 0xC00002DDL)
+#endif
+
+#ifndef STATUS_INSUFFICIENT_POWER
+# define STATUS_INSUFFICIENT_POWER ((NTSTATUS) 0xC00002DEL)
+#endif
+
+#ifndef STATUS_SAM_NEED_BOOTKEY_PASSWORD
+# define STATUS_SAM_NEED_BOOTKEY_PASSWORD ((NTSTATUS) 0xC00002DFL)
+#endif
+
+#ifndef STATUS_SAM_NEED_BOOTKEY_FLOPPY
+# define STATUS_SAM_NEED_BOOTKEY_FLOPPY ((NTSTATUS) 0xC00002E0L)
+#endif
+
+#ifndef STATUS_DS_CANT_START
+# define STATUS_DS_CANT_START ((NTSTATUS) 0xC00002E1L)
+#endif
+
+#ifndef STATUS_DS_INIT_FAILURE
+# define STATUS_DS_INIT_FAILURE ((NTSTATUS) 0xC00002E2L)
+#endif
+
+#ifndef STATUS_SAM_INIT_FAILURE
+# define STATUS_SAM_INIT_FAILURE ((NTSTATUS) 0xC00002E3L)
+#endif
+
+#ifndef STATUS_DS_GC_REQUIRED
+# define STATUS_DS_GC_REQUIRED ((NTSTATUS) 0xC00002E4L)
+#endif
+
+#ifndef STATUS_DS_LOCAL_MEMBER_OF_LOCAL_ONLY
+# define STATUS_DS_LOCAL_MEMBER_OF_LOCAL_ONLY ((NTSTATUS) 0xC00002E5L)
+#endif
+
+#ifndef STATUS_DS_NO_FPO_IN_UNIVERSAL_GROUPS
+# define STATUS_DS_NO_FPO_IN_UNIVERSAL_GROUPS ((NTSTATUS) 0xC00002E6L)
+#endif
+
+#ifndef STATUS_DS_MACHINE_ACCOUNT_QUOTA_EXCEEDED
+# define STATUS_DS_MACHINE_ACCOUNT_QUOTA_EXCEEDED ((NTSTATUS) 0xC00002E7L)
+#endif
+
+#ifndef STATUS_MULTIPLE_FAULT_VIOLATION
+# define STATUS_MULTIPLE_FAULT_VIOLATION ((NTSTATUS) 0xC00002E8L)
+#endif
+
+#ifndef STATUS_CURRENT_DOMAIN_NOT_ALLOWED
+# define STATUS_CURRENT_DOMAIN_NOT_ALLOWED ((NTSTATUS) 0xC00002E9L)
+#endif
+
+#ifndef STATUS_CANNOT_MAKE
+# define STATUS_CANNOT_MAKE ((NTSTATUS) 0xC00002EAL)
+#endif
+
+#ifndef STATUS_SYSTEM_SHUTDOWN
+# define STATUS_SYSTEM_SHUTDOWN ((NTSTATUS) 0xC00002EBL)
+#endif
+
+#ifndef STATUS_DS_INIT_FAILURE_CONSOLE
+# define STATUS_DS_INIT_FAILURE_CONSOLE ((NTSTATUS) 0xC00002ECL)
+#endif
+
+#ifndef STATUS_DS_SAM_INIT_FAILURE_CONSOLE
+# define STATUS_DS_SAM_INIT_FAILURE_CONSOLE ((NTSTATUS) 0xC00002EDL)
+#endif
+
+#ifndef STATUS_UNFINISHED_CONTEXT_DELETED
+# define STATUS_UNFINISHED_CONTEXT_DELETED ((NTSTATUS) 0xC00002EEL)
+#endif
+
+#ifndef STATUS_NO_TGT_REPLY
+# define STATUS_NO_TGT_REPLY ((NTSTATUS) 0xC00002EFL)
+#endif
+
+#ifndef STATUS_OBJECTID_NOT_FOUND
+# define STATUS_OBJECTID_NOT_FOUND ((NTSTATUS) 0xC00002F0L)
+#endif
+
+#ifndef STATUS_NO_IP_ADDRESSES
+# define STATUS_NO_IP_ADDRESSES ((NTSTATUS) 0xC00002F1L)
+#endif
+
+#ifndef STATUS_WRONG_CREDENTIAL_HANDLE
+# define STATUS_WRONG_CREDENTIAL_HANDLE ((NTSTATUS) 0xC00002F2L)
+#endif
+
+#ifndef STATUS_CRYPTO_SYSTEM_INVALID
+# define STATUS_CRYPTO_SYSTEM_INVALID ((NTSTATUS) 0xC00002F3L)
+#endif
+
+#ifndef STATUS_MAX_REFERRALS_EXCEEDED
+# define STATUS_MAX_REFERRALS_EXCEEDED ((NTSTATUS) 0xC00002F4L)
+#endif
+
+#ifndef STATUS_MUST_BE_KDC
+# define STATUS_MUST_BE_KDC ((NTSTATUS) 0xC00002F5L)
+#endif
+
+#ifndef STATUS_STRONG_CRYPTO_NOT_SUPPORTED
+# define STATUS_STRONG_CRYPTO_NOT_SUPPORTED ((NTSTATUS) 0xC00002F6L)
+#endif
+
+#ifndef STATUS_TOO_MANY_PRINCIPALS
+# define STATUS_TOO_MANY_PRINCIPALS ((NTSTATUS) 0xC00002F7L)
+#endif
+
+#ifndef STATUS_NO_PA_DATA
+# define STATUS_NO_PA_DATA ((NTSTATUS) 0xC00002F8L)
+#endif
+
+#ifndef STATUS_PKINIT_NAME_MISMATCH
+# define STATUS_PKINIT_NAME_MISMATCH ((NTSTATUS) 0xC00002F9L)
+#endif
+
+#ifndef STATUS_SMARTCARD_LOGON_REQUIRED
+# define STATUS_SMARTCARD_LOGON_REQUIRED ((NTSTATUS) 0xC00002FAL)
+#endif
+
+#ifndef STATUS_KDC_INVALID_REQUEST
+# define STATUS_KDC_INVALID_REQUEST ((NTSTATUS) 0xC00002FBL)
+#endif
+
+#ifndef STATUS_KDC_UNABLE_TO_REFER
+# define STATUS_KDC_UNABLE_TO_REFER ((NTSTATUS) 0xC00002FCL)
+#endif
+
+#ifndef STATUS_KDC_UNKNOWN_ETYPE
+# define STATUS_KDC_UNKNOWN_ETYPE ((NTSTATUS) 0xC00002FDL)
+#endif
+
+#ifndef STATUS_SHUTDOWN_IN_PROGRESS
+# define STATUS_SHUTDOWN_IN_PROGRESS ((NTSTATUS) 0xC00002FEL)
+#endif
+
+#ifndef STATUS_SERVER_SHUTDOWN_IN_PROGRESS
+# define STATUS_SERVER_SHUTDOWN_IN_PROGRESS ((NTSTATUS) 0xC00002FFL)
+#endif
+
+#ifndef STATUS_NOT_SUPPORTED_ON_SBS
+# define STATUS_NOT_SUPPORTED_ON_SBS ((NTSTATUS) 0xC0000300L)
+#endif
+
+#ifndef STATUS_WMI_GUID_DISCONNECTED
+# define STATUS_WMI_GUID_DISCONNECTED ((NTSTATUS) 0xC0000301L)
+#endif
+
+#ifndef STATUS_WMI_ALREADY_DISABLED
+# define STATUS_WMI_ALREADY_DISABLED ((NTSTATUS) 0xC0000302L)
+#endif
+
+#ifndef STATUS_WMI_ALREADY_ENABLED
+# define STATUS_WMI_ALREADY_ENABLED ((NTSTATUS) 0xC0000303L)
+#endif
+
+#ifndef STATUS_MFT_TOO_FRAGMENTED
+# define STATUS_MFT_TOO_FRAGMENTED ((NTSTATUS) 0xC0000304L)
+#endif
+
+#ifndef STATUS_COPY_PROTECTION_FAILURE
+# define STATUS_COPY_PROTECTION_FAILURE ((NTSTATUS) 0xC0000305L)
+#endif
+
+#ifndef STATUS_CSS_AUTHENTICATION_FAILURE
+# define STATUS_CSS_AUTHENTICATION_FAILURE ((NTSTATUS) 0xC0000306L)
+#endif
+
+#ifndef STATUS_CSS_KEY_NOT_PRESENT
+# define STATUS_CSS_KEY_NOT_PRESENT ((NTSTATUS) 0xC0000307L)
+#endif
+
+#ifndef STATUS_CSS_KEY_NOT_ESTABLISHED
+# define STATUS_CSS_KEY_NOT_ESTABLISHED ((NTSTATUS) 0xC0000308L)
+#endif
+
+#ifndef STATUS_CSS_SCRAMBLED_SECTOR
+# define STATUS_CSS_SCRAMBLED_SECTOR ((NTSTATUS) 0xC0000309L)
+#endif
+
+#ifndef STATUS_CSS_REGION_MISMATCH
+# define STATUS_CSS_REGION_MISMATCH ((NTSTATUS) 0xC000030AL)
+#endif
+
+#ifndef STATUS_CSS_RESETS_EXHAUSTED
+# define STATUS_CSS_RESETS_EXHAUSTED ((NTSTATUS) 0xC000030BL)
+#endif
+
+#ifndef STATUS_PKINIT_FAILURE
+# define STATUS_PKINIT_FAILURE ((NTSTATUS) 0xC0000320L)
+#endif
+
+#ifndef STATUS_SMARTCARD_SUBSYSTEM_FAILURE
+# define STATUS_SMARTCARD_SUBSYSTEM_FAILURE ((NTSTATUS) 0xC0000321L)
+#endif
+
+#ifndef STATUS_NO_KERB_KEY
+# define STATUS_NO_KERB_KEY ((NTSTATUS) 0xC0000322L)
+#endif
+
+#ifndef STATUS_HOST_DOWN
+# define STATUS_HOST_DOWN ((NTSTATUS) 0xC0000350L)
+#endif
+
+#ifndef STATUS_UNSUPPORTED_PREAUTH
+# define STATUS_UNSUPPORTED_PREAUTH ((NTSTATUS) 0xC0000351L)
+#endif
+
+#ifndef STATUS_EFS_ALG_BLOB_TOO_BIG
+# define STATUS_EFS_ALG_BLOB_TOO_BIG ((NTSTATUS) 0xC0000352L)
+#endif
+
+#ifndef STATUS_PORT_NOT_SET
+# define STATUS_PORT_NOT_SET ((NTSTATUS) 0xC0000353L)
+#endif
+
+#ifndef STATUS_DEBUGGER_INACTIVE
+# define STATUS_DEBUGGER_INACTIVE ((NTSTATUS) 0xC0000354L)
+#endif
+
+#ifndef STATUS_DS_VERSION_CHECK_FAILURE
+# define STATUS_DS_VERSION_CHECK_FAILURE ((NTSTATUS) 0xC0000355L)
+#endif
+
+#ifndef STATUS_AUDITING_DISABLED
+# define STATUS_AUDITING_DISABLED ((NTSTATUS) 0xC0000356L)
+#endif
+
+#ifndef STATUS_PRENT4_MACHINE_ACCOUNT
+# define STATUS_PRENT4_MACHINE_ACCOUNT ((NTSTATUS) 0xC0000357L)
+#endif
+
+#ifndef STATUS_DS_AG_CANT_HAVE_UNIVERSAL_MEMBER
+# define STATUS_DS_AG_CANT_HAVE_UNIVERSAL_MEMBER ((NTSTATUS) 0xC0000358L)
+#endif
+
+#ifndef STATUS_INVALID_IMAGE_WIN_32
+# define STATUS_INVALID_IMAGE_WIN_32 ((NTSTATUS) 0xC0000359L)
+#endif
+
+#ifndef STATUS_INVALID_IMAGE_WIN_64
+# define STATUS_INVALID_IMAGE_WIN_64 ((NTSTATUS) 0xC000035AL)
+#endif
+
+#ifndef STATUS_BAD_BINDINGS
+# define STATUS_BAD_BINDINGS ((NTSTATUS) 0xC000035BL)
+#endif
+
+#ifndef STATUS_NETWORK_SESSION_EXPIRED
+# define STATUS_NETWORK_SESSION_EXPIRED ((NTSTATUS) 0xC000035CL)
+#endif
+
+#ifndef STATUS_APPHELP_BLOCK
+# define STATUS_APPHELP_BLOCK ((NTSTATUS) 0xC000035DL)
+#endif
+
+#ifndef STATUS_ALL_SIDS_FILTERED
+# define STATUS_ALL_SIDS_FILTERED ((NTSTATUS) 0xC000035EL)
+#endif
+
+#ifndef STATUS_NOT_SAFE_MODE_DRIVER
+# define STATUS_NOT_SAFE_MODE_DRIVER ((NTSTATUS) 0xC000035FL)
+#endif
+
+#ifndef STATUS_ACCESS_DISABLED_BY_POLICY_DEFAULT
+# define STATUS_ACCESS_DISABLED_BY_POLICY_DEFAULT ((NTSTATUS) 0xC0000361L)
+#endif
+
+#ifndef STATUS_ACCESS_DISABLED_BY_POLICY_PATH
+# define STATUS_ACCESS_DISABLED_BY_POLICY_PATH ((NTSTATUS) 0xC0000362L)
+#endif
+
+#ifndef STATUS_ACCESS_DISABLED_BY_POLICY_PUBLISHER
+# define STATUS_ACCESS_DISABLED_BY_POLICY_PUBLISHER ((NTSTATUS) 0xC0000363L)
+#endif
+
+#ifndef STATUS_ACCESS_DISABLED_BY_POLICY_OTHER
+# define STATUS_ACCESS_DISABLED_BY_POLICY_OTHER ((NTSTATUS) 0xC0000364L)
+#endif
+
+#ifndef STATUS_FAILED_DRIVER_ENTRY
+# define STATUS_FAILED_DRIVER_ENTRY ((NTSTATUS) 0xC0000365L)
+#endif
+
+#ifndef STATUS_DEVICE_ENUMERATION_ERROR
+# define STATUS_DEVICE_ENUMERATION_ERROR ((NTSTATUS) 0xC0000366L)
+#endif
+
+#ifndef STATUS_MOUNT_POINT_NOT_RESOLVED
+# define STATUS_MOUNT_POINT_NOT_RESOLVED ((NTSTATUS) 0xC0000368L)
+#endif
+
+#ifndef STATUS_INVALID_DEVICE_OBJECT_PARAMETER
+# define STATUS_INVALID_DEVICE_OBJECT_PARAMETER ((NTSTATUS) 0xC0000369L)
+#endif
+
+#ifndef STATUS_MCA_OCCURED
+# define STATUS_MCA_OCCURED ((NTSTATUS) 0xC000036AL)
+#endif
+
+#ifndef STATUS_DRIVER_BLOCKED_CRITICAL
+# define STATUS_DRIVER_BLOCKED_CRITICAL ((NTSTATUS) 0xC000036BL)
+#endif
+
+#ifndef STATUS_DRIVER_BLOCKED
+# define STATUS_DRIVER_BLOCKED ((NTSTATUS) 0xC000036CL)
+#endif
+
+#ifndef STATUS_DRIVER_DATABASE_ERROR
+# define STATUS_DRIVER_DATABASE_ERROR ((NTSTATUS) 0xC000036DL)
+#endif
+
+#ifndef STATUS_SYSTEM_HIVE_TOO_LARGE
+# define STATUS_SYSTEM_HIVE_TOO_LARGE ((NTSTATUS) 0xC000036EL)
+#endif
+
+#ifndef STATUS_INVALID_IMPORT_OF_NON_DLL
+# define STATUS_INVALID_IMPORT_OF_NON_DLL ((NTSTATUS) 0xC000036FL)
+#endif
+
+#ifndef STATUS_DS_SHUTTING_DOWN
+# define STATUS_DS_SHUTTING_DOWN ((NTSTATUS) 0x40000370L)
+#endif
+
+#ifndef STATUS_NO_SECRETS
+# define STATUS_NO_SECRETS ((NTSTATUS) 0xC0000371L)
+#endif
+
+#ifndef STATUS_ACCESS_DISABLED_NO_SAFER_UI_BY_POLICY
+# define STATUS_ACCESS_DISABLED_NO_SAFER_UI_BY_POLICY ((NTSTATUS) 0xC0000372L)
+#endif
+
+#ifndef STATUS_FAILED_STACK_SWITCH
+# define STATUS_FAILED_STACK_SWITCH ((NTSTATUS) 0xC0000373L)
+#endif
+
+#ifndef STATUS_HEAP_CORRUPTION
+# define STATUS_HEAP_CORRUPTION ((NTSTATUS) 0xC0000374L)
+#endif
+
+#ifndef STATUS_SMARTCARD_WRONG_PIN
+# define STATUS_SMARTCARD_WRONG_PIN ((NTSTATUS) 0xC0000380L)
+#endif
+
+#ifndef STATUS_SMARTCARD_CARD_BLOCKED
+# define STATUS_SMARTCARD_CARD_BLOCKED ((NTSTATUS) 0xC0000381L)
+#endif
+
+#ifndef STATUS_SMARTCARD_CARD_NOT_AUTHENTICATED
+# define STATUS_SMARTCARD_CARD_NOT_AUTHENTICATED ((NTSTATUS) 0xC0000382L)
+#endif
+
+#ifndef STATUS_SMARTCARD_NO_CARD
+# define STATUS_SMARTCARD_NO_CARD ((NTSTATUS) 0xC0000383L)
+#endif
+
+#ifndef STATUS_SMARTCARD_NO_KEY_CONTAINER
+# define STATUS_SMARTCARD_NO_KEY_CONTAINER ((NTSTATUS) 0xC0000384L)
+#endif
+
+#ifndef STATUS_SMARTCARD_NO_CERTIFICATE
+# define STATUS_SMARTCARD_NO_CERTIFICATE ((NTSTATUS) 0xC0000385L)
+#endif
+
+#ifndef STATUS_SMARTCARD_NO_KEYSET
+# define STATUS_SMARTCARD_NO_KEYSET ((NTSTATUS) 0xC0000386L)
+#endif
+
+#ifndef STATUS_SMARTCARD_IO_ERROR
+# define STATUS_SMARTCARD_IO_ERROR ((NTSTATUS) 0xC0000387L)
+#endif
+
+#ifndef STATUS_DOWNGRADE_DETECTED
+# define STATUS_DOWNGRADE_DETECTED ((NTSTATUS) 0xC0000388L)
+#endif
+
+#ifndef STATUS_SMARTCARD_CERT_REVOKED
+# define STATUS_SMARTCARD_CERT_REVOKED ((NTSTATUS) 0xC0000389L)
+#endif
+
+#ifndef STATUS_ISSUING_CA_UNTRUSTED
+# define STATUS_ISSUING_CA_UNTRUSTED ((NTSTATUS) 0xC000038AL)
+#endif
+
+#ifndef STATUS_REVOCATION_OFFLINE_C
+# define STATUS_REVOCATION_OFFLINE_C ((NTSTATUS) 0xC000038BL)
+#endif
+
+#ifndef STATUS_PKINIT_CLIENT_FAILURE
+# define STATUS_PKINIT_CLIENT_FAILURE ((NTSTATUS) 0xC000038CL)
+#endif
+
+#ifndef STATUS_SMARTCARD_CERT_EXPIRED
+# define STATUS_SMARTCARD_CERT_EXPIRED ((NTSTATUS) 0xC000038DL)
+#endif
+
+#ifndef STATUS_DRIVER_FAILED_PRIOR_UNLOAD
+# define STATUS_DRIVER_FAILED_PRIOR_UNLOAD ((NTSTATUS) 0xC000038EL)
+#endif
+
+#ifndef STATUS_SMARTCARD_SILENT_CONTEXT
+# define STATUS_SMARTCARD_SILENT_CONTEXT ((NTSTATUS) 0xC000038FL)
+#endif
+
+#ifndef STATUS_PER_USER_TRUST_QUOTA_EXCEEDED
+# define STATUS_PER_USER_TRUST_QUOTA_EXCEEDED ((NTSTATUS) 0xC0000401L)
+#endif
+
+#ifndef STATUS_ALL_USER_TRUST_QUOTA_EXCEEDED
+# define STATUS_ALL_USER_TRUST_QUOTA_EXCEEDED ((NTSTATUS) 0xC0000402L)
+#endif
+
+#ifndef STATUS_USER_DELETE_TRUST_QUOTA_EXCEEDED
+# define STATUS_USER_DELETE_TRUST_QUOTA_EXCEEDED ((NTSTATUS) 0xC0000403L)
+#endif
+
+#ifndef STATUS_DS_NAME_NOT_UNIQUE
+# define STATUS_DS_NAME_NOT_UNIQUE ((NTSTATUS) 0xC0000404L)
+#endif
+
+#ifndef STATUS_DS_DUPLICATE_ID_FOUND
+# define STATUS_DS_DUPLICATE_ID_FOUND ((NTSTATUS) 0xC0000405L)
+#endif
+
+#ifndef STATUS_DS_GROUP_CONVERSION_ERROR
+# define STATUS_DS_GROUP_CONVERSION_ERROR ((NTSTATUS) 0xC0000406L)
+#endif
+
+#ifndef STATUS_VOLSNAP_PREPARE_HIBERNATE
+# define STATUS_VOLSNAP_PREPARE_HIBERNATE ((NTSTATUS) 0xC0000407L)
+#endif
+
+#ifndef STATUS_USER2USER_REQUIRED
+# define STATUS_USER2USER_REQUIRED ((NTSTATUS) 0xC0000408L)
+#endif
+
+#ifndef STATUS_STACK_BUFFER_OVERRUN
+# define STATUS_STACK_BUFFER_OVERRUN ((NTSTATUS) 0xC0000409L)
+#endif
+
+#ifndef STATUS_NO_S4U_PROT_SUPPORT
+# define STATUS_NO_S4U_PROT_SUPPORT ((NTSTATUS) 0xC000040AL)
+#endif
+
+#ifndef STATUS_CROSSREALM_DELEGATION_FAILURE
+# define STATUS_CROSSREALM_DELEGATION_FAILURE ((NTSTATUS) 0xC000040BL)
+#endif
+
+#ifndef STATUS_REVOCATION_OFFLINE_KDC
+# define STATUS_REVOCATION_OFFLINE_KDC ((NTSTATUS) 0xC000040CL)
+#endif
+
+#ifndef STATUS_ISSUING_CA_UNTRUSTED_KDC
+# define STATUS_ISSUING_CA_UNTRUSTED_KDC ((NTSTATUS) 0xC000040DL)
+#endif
+
+#ifndef STATUS_KDC_CERT_EXPIRED
+# define STATUS_KDC_CERT_EXPIRED ((NTSTATUS) 0xC000040EL)
+#endif
+
+#ifndef STATUS_KDC_CERT_REVOKED
+# define STATUS_KDC_CERT_REVOKED ((NTSTATUS) 0xC000040FL)
+#endif
+
+#ifndef STATUS_PARAMETER_QUOTA_EXCEEDED
+# define STATUS_PARAMETER_QUOTA_EXCEEDED ((NTSTATUS) 0xC0000410L)
+#endif
+
+#ifndef STATUS_HIBERNATION_FAILURE
+# define STATUS_HIBERNATION_FAILURE ((NTSTATUS) 0xC0000411L)
+#endif
+
+#ifndef STATUS_DELAY_LOAD_FAILED
+# define STATUS_DELAY_LOAD_FAILED ((NTSTATUS) 0xC0000412L)
+#endif
+
+#ifndef STATUS_AUTHENTICATION_FIREWALL_FAILED
+# define STATUS_AUTHENTICATION_FIREWALL_FAILED ((NTSTATUS) 0xC0000413L)
+#endif
+
+#ifndef STATUS_VDM_DISALLOWED
+# define STATUS_VDM_DISALLOWED ((NTSTATUS) 0xC0000414L)
+#endif
+
+#ifndef STATUS_HUNG_DISPLAY_DRIVER_THREAD
+# define STATUS_HUNG_DISPLAY_DRIVER_THREAD ((NTSTATUS) 0xC0000415L)
+#endif
+
+#ifndef STATUS_INSUFFICIENT_RESOURCE_FOR_SPECIFIED_SHARED_SECTION_SIZE
+# define STATUS_INSUFFICIENT_RESOURCE_FOR_SPECIFIED_SHARED_SECTION_SIZE ((NTSTATUS) 0xC0000416L)
+#endif
+
+#ifndef STATUS_INVALID_CRUNTIME_PARAMETER
+# define STATUS_INVALID_CRUNTIME_PARAMETER ((NTSTATUS) 0xC0000417L)
+#endif
+
+#ifndef STATUS_NTLM_BLOCKED
+# define STATUS_NTLM_BLOCKED ((NTSTATUS) 0xC0000418L)
+#endif
+
+#ifndef STATUS_DS_SRC_SID_EXISTS_IN_FOREST
+# define STATUS_DS_SRC_SID_EXISTS_IN_FOREST ((NTSTATUS) 0xC0000419L)
+#endif
+
+#ifndef STATUS_DS_DOMAIN_NAME_EXISTS_IN_FOREST
+# define STATUS_DS_DOMAIN_NAME_EXISTS_IN_FOREST ((NTSTATUS) 0xC000041AL)
+#endif
+
+#ifndef STATUS_DS_FLAT_NAME_EXISTS_IN_FOREST
+# define STATUS_DS_FLAT_NAME_EXISTS_IN_FOREST ((NTSTATUS) 0xC000041BL)
+#endif
+
+#ifndef STATUS_INVALID_USER_PRINCIPAL_NAME
+# define STATUS_INVALID_USER_PRINCIPAL_NAME ((NTSTATUS) 0xC000041CL)
+#endif
+
+#ifndef STATUS_FATAL_USER_CALLBACK_EXCEPTION
+# define STATUS_FATAL_USER_CALLBACK_EXCEPTION ((NTSTATUS) 0xC000041DL)
+#endif
+
+#ifndef STATUS_ASSERTION_FAILURE
+# define STATUS_ASSERTION_FAILURE ((NTSTATUS) 0xC0000420L)
+#endif
+
+#ifndef STATUS_VERIFIER_STOP
+# define STATUS_VERIFIER_STOP ((NTSTATUS) 0xC0000421L)
+#endif
+
+#ifndef STATUS_CALLBACK_POP_STACK
+# define STATUS_CALLBACK_POP_STACK ((NTSTATUS) 0xC0000423L)
+#endif
+
+#ifndef STATUS_INCOMPATIBLE_DRIVER_BLOCKED
+# define STATUS_INCOMPATIBLE_DRIVER_BLOCKED ((NTSTATUS) 0xC0000424L)
+#endif
+
+#ifndef STATUS_HIVE_UNLOADED
+# define STATUS_HIVE_UNLOADED ((NTSTATUS) 0xC0000425L)
+#endif
+
+#ifndef STATUS_COMPRESSION_DISABLED
+# define STATUS_COMPRESSION_DISABLED ((NTSTATUS) 0xC0000426L)
+#endif
+
+#ifndef STATUS_FILE_SYSTEM_LIMITATION
+# define STATUS_FILE_SYSTEM_LIMITATION ((NTSTATUS) 0xC0000427L)
+#endif
+
+#ifndef STATUS_INVALID_IMAGE_HASH
+# define STATUS_INVALID_IMAGE_HASH ((NTSTATUS) 0xC0000428L)
+#endif
+
+#ifndef STATUS_NOT_CAPABLE
+# define STATUS_NOT_CAPABLE ((NTSTATUS) 0xC0000429L)
+#endif
+
+#ifndef STATUS_REQUEST_OUT_OF_SEQUENCE
+# define STATUS_REQUEST_OUT_OF_SEQUENCE ((NTSTATUS) 0xC000042AL)
+#endif
+
+#ifndef STATUS_IMPLEMENTATION_LIMIT
+# define STATUS_IMPLEMENTATION_LIMIT ((NTSTATUS) 0xC000042BL)
+#endif
+
+#ifndef STATUS_ELEVATION_REQUIRED
+# define STATUS_ELEVATION_REQUIRED ((NTSTATUS) 0xC000042CL)
+#endif
+
+#ifndef STATUS_NO_SECURITY_CONTEXT
+# define STATUS_NO_SECURITY_CONTEXT ((NTSTATUS) 0xC000042DL)
+#endif
+
+#ifndef STATUS_PKU2U_CERT_FAILURE
+# define STATUS_PKU2U_CERT_FAILURE ((NTSTATUS) 0xC000042FL)
+#endif
+
+#ifndef STATUS_BEYOND_VDL
+# define STATUS_BEYOND_VDL ((NTSTATUS) 0xC0000432L)
+#endif
+
+#ifndef STATUS_ENCOUNTERED_WRITE_IN_PROGRESS
+# define STATUS_ENCOUNTERED_WRITE_IN_PROGRESS ((NTSTATUS) 0xC0000433L)
+#endif
+
+#ifndef STATUS_PTE_CHANGED
+# define STATUS_PTE_CHANGED ((NTSTATUS) 0xC0000434L)
+#endif
+
+#ifndef STATUS_PURGE_FAILED
+# define STATUS_PURGE_FAILED ((NTSTATUS) 0xC0000435L)
+#endif
+
+#ifndef STATUS_CRED_REQUIRES_CONFIRMATION
+# define STATUS_CRED_REQUIRES_CONFIRMATION ((NTSTATUS) 0xC0000440L)
+#endif
+
+#ifndef STATUS_CS_ENCRYPTION_INVALID_SERVER_RESPONSE
+# define STATUS_CS_ENCRYPTION_INVALID_SERVER_RESPONSE ((NTSTATUS) 0xC0000441L)
+#endif
+
+#ifndef STATUS_CS_ENCRYPTION_UNSUPPORTED_SERVER
+# define STATUS_CS_ENCRYPTION_UNSUPPORTED_SERVER ((NTSTATUS) 0xC0000442L)
+#endif
+
+#ifndef STATUS_CS_ENCRYPTION_EXISTING_ENCRYPTED_FILE
+# define STATUS_CS_ENCRYPTION_EXISTING_ENCRYPTED_FILE ((NTSTATUS) 0xC0000443L)
+#endif
+
+#ifndef STATUS_CS_ENCRYPTION_NEW_ENCRYPTED_FILE
+# define STATUS_CS_ENCRYPTION_NEW_ENCRYPTED_FILE ((NTSTATUS) 0xC0000444L)
+#endif
+
+#ifndef STATUS_CS_ENCRYPTION_FILE_NOT_CSE
+# define STATUS_CS_ENCRYPTION_FILE_NOT_CSE ((NTSTATUS) 0xC0000445L)
+#endif
+
+#ifndef STATUS_INVALID_LABEL
+# define STATUS_INVALID_LABEL ((NTSTATUS) 0xC0000446L)
+#endif
+
+#ifndef STATUS_DRIVER_PROCESS_TERMINATED
+# define STATUS_DRIVER_PROCESS_TERMINATED ((NTSTATUS) 0xC0000450L)
+#endif
+
+#ifndef STATUS_AMBIGUOUS_SYSTEM_DEVICE
+# define STATUS_AMBIGUOUS_SYSTEM_DEVICE ((NTSTATUS) 0xC0000451L)
+#endif
+
+#ifndef STATUS_SYSTEM_DEVICE_NOT_FOUND
+# define STATUS_SYSTEM_DEVICE_NOT_FOUND ((NTSTATUS) 0xC0000452L)
+#endif
+
+#ifndef STATUS_RESTART_BOOT_APPLICATION
+# define STATUS_RESTART_BOOT_APPLICATION ((NTSTATUS) 0xC0000453L)
+#endif
+
+#ifndef STATUS_INSUFFICIENT_NVRAM_RESOURCES
+# define STATUS_INSUFFICIENT_NVRAM_RESOURCES ((NTSTATUS) 0xC0000454L)
+#endif
+
+#ifndef STATUS_INVALID_TASK_NAME
+# define STATUS_INVALID_TASK_NAME ((NTSTATUS) 0xC0000500L)
+#endif
+
+#ifndef STATUS_INVALID_TASK_INDEX
+# define STATUS_INVALID_TASK_INDEX ((NTSTATUS) 0xC0000501L)
+#endif
+
+#ifndef STATUS_THREAD_ALREADY_IN_TASK
+# define STATUS_THREAD_ALREADY_IN_TASK ((NTSTATUS) 0xC0000502L)
+#endif
+
+#ifndef STATUS_CALLBACK_BYPASS
+# define STATUS_CALLBACK_BYPASS ((NTSTATUS) 0xC0000503L)
+#endif
+
+#ifndef STATUS_FAIL_FAST_EXCEPTION
+# define STATUS_FAIL_FAST_EXCEPTION ((NTSTATUS) 0xC0000602L)
+#endif
+
+#ifndef STATUS_IMAGE_CERT_REVOKED
+# define STATUS_IMAGE_CERT_REVOKED ((NTSTATUS) 0xC0000603L)
+#endif
+
+#ifndef STATUS_PORT_CLOSED
+# define STATUS_PORT_CLOSED ((NTSTATUS) 0xC0000700L)
+#endif
+
+#ifndef STATUS_MESSAGE_LOST
+# define STATUS_MESSAGE_LOST ((NTSTATUS) 0xC0000701L)
+#endif
+
+#ifndef STATUS_INVALID_MESSAGE
+# define STATUS_INVALID_MESSAGE ((NTSTATUS) 0xC0000702L)
+#endif
+
+#ifndef STATUS_REQUEST_CANCELED
+# define STATUS_REQUEST_CANCELED ((NTSTATUS) 0xC0000703L)
+#endif
+
+#ifndef STATUS_RECURSIVE_DISPATCH
+# define STATUS_RECURSIVE_DISPATCH ((NTSTATUS) 0xC0000704L)
+#endif
+
+#ifndef STATUS_LPC_RECEIVE_BUFFER_EXPECTED
+# define STATUS_LPC_RECEIVE_BUFFER_EXPECTED ((NTSTATUS) 0xC0000705L)
+#endif
+
+#ifndef STATUS_LPC_INVALID_CONNECTION_USAGE
+# define STATUS_LPC_INVALID_CONNECTION_USAGE ((NTSTATUS) 0xC0000706L)
+#endif
+
+#ifndef STATUS_LPC_REQUESTS_NOT_ALLOWED
+# define STATUS_LPC_REQUESTS_NOT_ALLOWED ((NTSTATUS) 0xC0000707L)
+#endif
+
+#ifndef STATUS_RESOURCE_IN_USE
+# define STATUS_RESOURCE_IN_USE ((NTSTATUS) 0xC0000708L)
+#endif
+
+#ifndef STATUS_HARDWARE_MEMORY_ERROR
+# define STATUS_HARDWARE_MEMORY_ERROR ((NTSTATUS) 0xC0000709L)
+#endif
+
+#ifndef STATUS_THREADPOOL_HANDLE_EXCEPTION
+# define STATUS_THREADPOOL_HANDLE_EXCEPTION ((NTSTATUS) 0xC000070AL)
+#endif
+
+#ifndef STATUS_THREADPOOL_SET_EVENT_ON_COMPLETION_FAILED
+# define STATUS_THREADPOOL_SET_EVENT_ON_COMPLETION_FAILED ((NTSTATUS) 0xC000070BL)
+#endif
+
+#ifndef STATUS_THREADPOOL_RELEASE_SEMAPHORE_ON_COMPLETION_FAILED
+# define STATUS_THREADPOOL_RELEASE_SEMAPHORE_ON_COMPLETION_FAILED ((NTSTATUS) 0xC000070CL)
+#endif
+
+#ifndef STATUS_THREADPOOL_RELEASE_MUTEX_ON_COMPLETION_FAILED
+# define STATUS_THREADPOOL_RELEASE_MUTEX_ON_COMPLETION_FAILED ((NTSTATUS) 0xC000070DL)
+#endif
+
+#ifndef STATUS_THREADPOOL_FREE_LIBRARY_ON_COMPLETION_FAILED
+# define STATUS_THREADPOOL_FREE_LIBRARY_ON_COMPLETION_FAILED ((NTSTATUS) 0xC000070EL)
+#endif
+
+#ifndef STATUS_THREADPOOL_RELEASED_DURING_OPERATION
+# define STATUS_THREADPOOL_RELEASED_DURING_OPERATION ((NTSTATUS) 0xC000070FL)
+#endif
+
+#ifndef STATUS_CALLBACK_RETURNED_WHILE_IMPERSONATING
+# define STATUS_CALLBACK_RETURNED_WHILE_IMPERSONATING ((NTSTATUS) 0xC0000710L)
+#endif
+
+#ifndef STATUS_APC_RETURNED_WHILE_IMPERSONATING
+# define STATUS_APC_RETURNED_WHILE_IMPERSONATING ((NTSTATUS) 0xC0000711L)
+#endif
+
+#ifndef STATUS_PROCESS_IS_PROTECTED
+# define STATUS_PROCESS_IS_PROTECTED ((NTSTATUS) 0xC0000712L)
+#endif
+
+#ifndef STATUS_MCA_EXCEPTION
+# define STATUS_MCA_EXCEPTION ((NTSTATUS) 0xC0000713L)
+#endif
+
+#ifndef STATUS_CERTIFICATE_MAPPING_NOT_UNIQUE
+# define STATUS_CERTIFICATE_MAPPING_NOT_UNIQUE ((NTSTATUS) 0xC0000714L)
+#endif
+
+#ifndef STATUS_SYMLINK_CLASS_DISABLED
+# define STATUS_SYMLINK_CLASS_DISABLED ((NTSTATUS) 0xC0000715L)
+#endif
+
+#ifndef STATUS_INVALID_IDN_NORMALIZATION
+# define STATUS_INVALID_IDN_NORMALIZATION ((NTSTATUS) 0xC0000716L)
+#endif
+
+#ifndef STATUS_NO_UNICODE_TRANSLATION
+# define STATUS_NO_UNICODE_TRANSLATION ((NTSTATUS) 0xC0000717L)
+#endif
+
+#ifndef STATUS_ALREADY_REGISTERED
+# define STATUS_ALREADY_REGISTERED ((NTSTATUS) 0xC0000718L)
+#endif
+
+#ifndef STATUS_CONTEXT_MISMATCH
+# define STATUS_CONTEXT_MISMATCH ((NTSTATUS) 0xC0000719L)
+#endif
+
+#ifndef STATUS_PORT_ALREADY_HAS_COMPLETION_LIST
+# define STATUS_PORT_ALREADY_HAS_COMPLETION_LIST ((NTSTATUS) 0xC000071AL)
+#endif
+
+#ifndef STATUS_CALLBACK_RETURNED_THREAD_PRIORITY
+# define STATUS_CALLBACK_RETURNED_THREAD_PRIORITY ((NTSTATUS) 0xC000071BL)
+#endif
+
+#ifndef STATUS_INVALID_THREAD
+# define STATUS_INVALID_THREAD ((NTSTATUS) 0xC000071CL)
+#endif
+
+#ifndef STATUS_CALLBACK_RETURNED_TRANSACTION
+# define STATUS_CALLBACK_RETURNED_TRANSACTION ((NTSTATUS) 0xC000071DL)
+#endif
+
+#ifndef STATUS_CALLBACK_RETURNED_LDR_LOCK
+# define STATUS_CALLBACK_RETURNED_LDR_LOCK ((NTSTATUS) 0xC000071EL)
+#endif
+
+#ifndef STATUS_CALLBACK_RETURNED_LANG
+# define STATUS_CALLBACK_RETURNED_LANG ((NTSTATUS) 0xC000071FL)
+#endif
+
+#ifndef STATUS_CALLBACK_RETURNED_PRI_BACK
+# define STATUS_CALLBACK_RETURNED_PRI_BACK ((NTSTATUS) 0xC0000720L)
+#endif
+
+#ifndef STATUS_CALLBACK_RETURNED_THREAD_AFFINITY
+# define STATUS_CALLBACK_RETURNED_THREAD_AFFINITY ((NTSTATUS) 0xC0000721L)
+#endif
+
+#ifndef STATUS_DISK_REPAIR_DISABLED
+# define STATUS_DISK_REPAIR_DISABLED ((NTSTATUS) 0xC0000800L)
+#endif
+
+#ifndef STATUS_DS_DOMAIN_RENAME_IN_PROGRESS
+# define STATUS_DS_DOMAIN_RENAME_IN_PROGRESS ((NTSTATUS) 0xC0000801L)
+#endif
+
+#ifndef STATUS_DISK_QUOTA_EXCEEDED
+# define STATUS_DISK_QUOTA_EXCEEDED ((NTSTATUS) 0xC0000802L)
+#endif
+
+#ifndef STATUS_DATA_LOST_REPAIR
+# define STATUS_DATA_LOST_REPAIR ((NTSTATUS) 0x80000803L)
+#endif
+
+#ifndef STATUS_CONTENT_BLOCKED
+# define STATUS_CONTENT_BLOCKED ((NTSTATUS) 0xC0000804L)
+#endif
+
+#ifndef STATUS_BAD_CLUSTERS
+# define STATUS_BAD_CLUSTERS ((NTSTATUS) 0xC0000805L)
+#endif
+
+#ifndef STATUS_VOLUME_DIRTY
+# define STATUS_VOLUME_DIRTY ((NTSTATUS) 0xC0000806L)
+#endif
+
+#ifndef STATUS_FILE_CHECKED_OUT
+# define STATUS_FILE_CHECKED_OUT ((NTSTATUS) 0xC0000901L)
+#endif
+
+#ifndef STATUS_CHECKOUT_REQUIRED
+# define STATUS_CHECKOUT_REQUIRED ((NTSTATUS) 0xC0000902L)
+#endif
+
+#ifndef STATUS_BAD_FILE_TYPE
+# define STATUS_BAD_FILE_TYPE ((NTSTATUS) 0xC0000903L)
+#endif
+
+#ifndef STATUS_FILE_TOO_LARGE
+# define STATUS_FILE_TOO_LARGE ((NTSTATUS) 0xC0000904L)
+#endif
+
+#ifndef STATUS_FORMS_AUTH_REQUIRED
+# define STATUS_FORMS_AUTH_REQUIRED ((NTSTATUS) 0xC0000905L)
+#endif
+
+#ifndef STATUS_VIRUS_INFECTED
+# define STATUS_VIRUS_INFECTED ((NTSTATUS) 0xC0000906L)
+#endif
+
+#ifndef STATUS_VIRUS_DELETED
+# define STATUS_VIRUS_DELETED ((NTSTATUS) 0xC0000907L)
+#endif
+
+#ifndef STATUS_BAD_MCFG_TABLE
+# define STATUS_BAD_MCFG_TABLE ((NTSTATUS) 0xC0000908L)
+#endif
+
+#ifndef STATUS_CANNOT_BREAK_OPLOCK
+# define STATUS_CANNOT_BREAK_OPLOCK ((NTSTATUS) 0xC0000909L)
+#endif
+
+#ifndef STATUS_WOW_ASSERTION
+# define STATUS_WOW_ASSERTION ((NTSTATUS) 0xC0009898L)
+#endif
+
+#ifndef STATUS_INVALID_SIGNATURE
+# define STATUS_INVALID_SIGNATURE ((NTSTATUS) 0xC000A000L)
+#endif
+
+#ifndef STATUS_HMAC_NOT_SUPPORTED
+# define STATUS_HMAC_NOT_SUPPORTED ((NTSTATUS) 0xC000A001L)
+#endif
+
+#ifndef STATUS_AUTH_TAG_MISMATCH
+# define STATUS_AUTH_TAG_MISMATCH ((NTSTATUS) 0xC000A002L)
+#endif
+
+#ifndef STATUS_IPSEC_QUEUE_OVERFLOW
+# define STATUS_IPSEC_QUEUE_OVERFLOW ((NTSTATUS) 0xC000A010L)
+#endif
+
+#ifndef STATUS_ND_QUEUE_OVERFLOW
+# define STATUS_ND_QUEUE_OVERFLOW ((NTSTATUS) 0xC000A011L)
+#endif
+
+#ifndef STATUS_HOPLIMIT_EXCEEDED
+# define STATUS_HOPLIMIT_EXCEEDED ((NTSTATUS) 0xC000A012L)
+#endif
+
+#ifndef STATUS_PROTOCOL_NOT_SUPPORTED
+# define STATUS_PROTOCOL_NOT_SUPPORTED ((NTSTATUS) 0xC000A013L)
+#endif
+
+#ifndef STATUS_FASTPATH_REJECTED
+# define STATUS_FASTPATH_REJECTED ((NTSTATUS) 0xC000A014L)
+#endif
+
+#ifndef STATUS_LOST_WRITEBEHIND_DATA_NETWORK_DISCONNECTED
+# define STATUS_LOST_WRITEBEHIND_DATA_NETWORK_DISCONNECTED ((NTSTATUS) 0xC000A080L)
+#endif
+
+#ifndef STATUS_LOST_WRITEBEHIND_DATA_NETWORK_SERVER_ERROR
+# define STATUS_LOST_WRITEBEHIND_DATA_NETWORK_SERVER_ERROR ((NTSTATUS) 0xC000A081L)
+#endif
+
+#ifndef STATUS_LOST_WRITEBEHIND_DATA_LOCAL_DISK_ERROR
+# define STATUS_LOST_WRITEBEHIND_DATA_LOCAL_DISK_ERROR ((NTSTATUS) 0xC000A082L)
+#endif
+
+#ifndef STATUS_XML_PARSE_ERROR
+# define STATUS_XML_PARSE_ERROR ((NTSTATUS) 0xC000A083L)
+#endif
+
+#ifndef STATUS_XMLDSIG_ERROR
+# define STATUS_XMLDSIG_ERROR ((NTSTATUS) 0xC000A084L)
+#endif
+
+#ifndef STATUS_WRONG_COMPARTMENT
+# define STATUS_WRONG_COMPARTMENT ((NTSTATUS) 0xC000A085L)
+#endif
+
+#ifndef STATUS_AUTHIP_FAILURE
+# define STATUS_AUTHIP_FAILURE ((NTSTATUS) 0xC000A086L)
+#endif
+
+#ifndef STATUS_DS_OID_MAPPED_GROUP_CANT_HAVE_MEMBERS
+# define STATUS_DS_OID_MAPPED_GROUP_CANT_HAVE_MEMBERS ((NTSTATUS) 0xC000A087L)
+#endif
+
+#ifndef STATUS_DS_OID_NOT_FOUND
+# define STATUS_DS_OID_NOT_FOUND ((NTSTATUS) 0xC000A088L)
+#endif
+
+#ifndef STATUS_HASH_NOT_SUPPORTED
+# define STATUS_HASH_NOT_SUPPORTED ((NTSTATUS) 0xC000A100L)
+#endif
+
+#ifndef STATUS_HASH_NOT_PRESENT
+# define STATUS_HASH_NOT_PRESENT ((NTSTATUS) 0xC000A101L)
+#endif
+
+/* This is not the NTSTATUS_FROM_WIN32 that the DDK provides, because the DDK
+ * got it wrong! */
+#ifdef NTSTATUS_FROM_WIN32
+# undef NTSTATUS_FROM_WIN32
+#endif
+#define NTSTATUS_FROM_WIN32(error) ((NTSTATUS) (error) <= 0 ? \
+        ((NTSTATUS) (error)) : ((NTSTATUS) (((error) & 0x0000FFFF) | \
+        (FACILITY_NTWIN32 << 16) | ERROR_SEVERITY_WARNING)))
+
+#ifndef JOB_OBJECT_LIMIT_PROCESS_MEMORY
+# define JOB_OBJECT_LIMIT_PROCESS_MEMORY             0x00000100
+#endif
+#ifndef JOB_OBJECT_LIMIT_JOB_MEMORY
+# define JOB_OBJECT_LIMIT_JOB_MEMORY                 0x00000200
+#endif
+#ifndef JOB_OBJECT_LIMIT_DIE_ON_UNHANDLED_EXCEPTION
+# define JOB_OBJECT_LIMIT_DIE_ON_UNHANDLED_EXCEPTION 0x00000400
+#endif
+#ifndef JOB_OBJECT_LIMIT_BREAKAWAY_OK
+# define JOB_OBJECT_LIMIT_BREAKAWAY_OK               0x00000800
+#endif
+#ifndef JOB_OBJECT_LIMIT_SILENT_BREAKAWAY_OK
+# define JOB_OBJECT_LIMIT_SILENT_BREAKAWAY_OK        0x00001000
+#endif
+#ifndef JOB_OBJECT_LIMIT_KILL_ON_JOB_CLOSE
+# define JOB_OBJECT_LIMIT_KILL_ON_JOB_CLOSE          0x00002000
+#endif
+
+#ifndef SYMBOLIC_LINK_FLAG_ALLOW_UNPRIVILEGED_CREATE
+# define SYMBOLIC_LINK_FLAG_ALLOW_UNPRIVILEGED_CREATE 0x00000002
+#endif
+
+/* from winternl.h */
+#if !defined(__UNICODE_STRING_DEFINED) && defined(__MINGW32__)
+#define __UNICODE_STRING_DEFINED
+#endif
+typedef struct _UNICODE_STRING {
+  USHORT Length;
+  USHORT MaximumLength;
+  PWSTR  Buffer;
+} UNICODE_STRING, *PUNICODE_STRING;
+
+typedef const UNICODE_STRING *PCUNICODE_STRING;
+
+/* from ntifs.h */
+#ifndef DEVICE_TYPE
+# define DEVICE_TYPE DWORD
+#endif
+
+/* MinGW already has a definition for REPARSE_DATA_BUFFER, but mingw-w64 does
+ * not.
+ */
+#if defined(_MSC_VER) || defined(__MINGW64_VERSION_MAJOR)
+  typedef struct _REPARSE_DATA_BUFFER {
+    ULONG  ReparseTag;
+    USHORT ReparseDataLength;
+    USHORT Reserved;
+    union {
+      struct {
+        USHORT SubstituteNameOffset;
+        USHORT SubstituteNameLength;
+        USHORT PrintNameOffset;
+        USHORT PrintNameLength;
+        ULONG Flags;
+        WCHAR PathBuffer[1];
+      } SymbolicLinkReparseBuffer;
+      struct {
+        USHORT SubstituteNameOffset;
+        USHORT SubstituteNameLength;
+        USHORT PrintNameOffset;
+        USHORT PrintNameLength;
+        WCHAR PathBuffer[1];
+      } MountPointReparseBuffer;
+      struct {
+        UCHAR  DataBuffer[1];
+      } GenericReparseBuffer;
+      struct {
+        ULONG StringCount;
+        WCHAR StringList[1];
+      } AppExecLinkReparseBuffer;
+    };
+  } REPARSE_DATA_BUFFER, *PREPARSE_DATA_BUFFER;
+#endif
+
+typedef struct _IO_STATUS_BLOCK {
+  union {
+    NTSTATUS Status;
+    PVOID Pointer;
+  };
+  ULONG_PTR Information;
+} IO_STATUS_BLOCK, *PIO_STATUS_BLOCK;
+
+typedef enum _FILE_INFORMATION_CLASS {
+  FileDirectoryInformation = 1,
+  FileFullDirectoryInformation,
+  FileBothDirectoryInformation,
+  FileBasicInformation,
+  FileStandardInformation,
+  FileInternalInformation,
+  FileEaInformation,
+  FileAccessInformation,
+  FileNameInformation,
+  FileRenameInformation,
+  FileLinkInformation,
+  FileNamesInformation,
+  FileDispositionInformation,
+  FilePositionInformation,
+  FileFullEaInformation,
+  FileModeInformation,
+  FileAlignmentInformation,
+  FileAllInformation,
+  FileAllocationInformation,
+  FileEndOfFileInformation,
+  FileAlternateNameInformation,
+  FileStreamInformation,
+  FilePipeInformation,
+  FilePipeLocalInformation,
+  FilePipeRemoteInformation,
+  FileMailslotQueryInformation,
+  FileMailslotSetInformation,
+  FileCompressionInformation,
+  FileObjectIdInformation,
+  FileCompletionInformation,
+  FileMoveClusterInformation,
+  FileQuotaInformation,
+  FileReparsePointInformation,
+  FileNetworkOpenInformation,
+  FileAttributeTagInformation,
+  FileTrackingInformation,
+  FileIdBothDirectoryInformation,
+  FileIdFullDirectoryInformation,
+  FileValidDataLengthInformation,
+  FileShortNameInformation,
+  FileIoCompletionNotificationInformation,
+  FileIoStatusBlockRangeInformation,
+  FileIoPriorityHintInformation,
+  FileSfioReserveInformation,
+  FileSfioVolumeInformation,
+  FileHardLinkInformation,
+  FileProcessIdsUsingFileInformation,
+  FileNormalizedNameInformation,
+  FileNetworkPhysicalNameInformation,
+  FileIdGlobalTxDirectoryInformation,
+  FileIsRemoteDeviceInformation,
+  FileAttributeCacheInformation,
+  FileNumaNodeInformation,
+  FileStandardLinkInformation,
+  FileRemoteProtocolInformation,
+  FileMaximumInformation
+} FILE_INFORMATION_CLASS, *PFILE_INFORMATION_CLASS;
+
+typedef struct _FILE_DIRECTORY_INFORMATION {
+  ULONG NextEntryOffset;
+  ULONG FileIndex;
+  LARGE_INTEGER CreationTime;
+  LARGE_INTEGER LastAccessTime;
+  LARGE_INTEGER LastWriteTime;
+  LARGE_INTEGER ChangeTime;
+  LARGE_INTEGER EndOfFile;
+  LARGE_INTEGER AllocationSize;
+  ULONG FileAttributes;
+  ULONG FileNameLength;
+  WCHAR FileName[1];
+} FILE_DIRECTORY_INFORMATION, *PFILE_DIRECTORY_INFORMATION;
+
+typedef struct _FILE_BOTH_DIR_INFORMATION {
+  ULONG NextEntryOffset;
+  ULONG FileIndex;
+  LARGE_INTEGER CreationTime;
+  LARGE_INTEGER LastAccessTime;
+  LARGE_INTEGER LastWriteTime;
+  LARGE_INTEGER ChangeTime;
+  LARGE_INTEGER EndOfFile;
+  LARGE_INTEGER AllocationSize;
+  ULONG FileAttributes;
+  ULONG FileNameLength;
+  ULONG EaSize;
+  CCHAR ShortNameLength;
+  WCHAR ShortName[12];
+  WCHAR FileName[1];
+} FILE_BOTH_DIR_INFORMATION, *PFILE_BOTH_DIR_INFORMATION;
+
+typedef struct _FILE_BASIC_INFORMATION {
+  LARGE_INTEGER CreationTime;
+  LARGE_INTEGER LastAccessTime;
+  LARGE_INTEGER LastWriteTime;
+  LARGE_INTEGER ChangeTime;
+  DWORD FileAttributes;
+} FILE_BASIC_INFORMATION, *PFILE_BASIC_INFORMATION;
+
+typedef struct _FILE_STANDARD_INFORMATION {
+  LARGE_INTEGER AllocationSize;
+  LARGE_INTEGER EndOfFile;
+  ULONG         NumberOfLinks;
+  BOOLEAN       DeletePending;
+  BOOLEAN       Directory;
+} FILE_STANDARD_INFORMATION, *PFILE_STANDARD_INFORMATION;
+
+typedef struct _FILE_INTERNAL_INFORMATION {
+  LARGE_INTEGER IndexNumber;
+} FILE_INTERNAL_INFORMATION, *PFILE_INTERNAL_INFORMATION;
+
+typedef struct _FILE_EA_INFORMATION {
+  ULONG EaSize;
+} FILE_EA_INFORMATION, *PFILE_EA_INFORMATION;
+
+typedef struct _FILE_ACCESS_INFORMATION {
+  ACCESS_MASK AccessFlags;
+} FILE_ACCESS_INFORMATION, *PFILE_ACCESS_INFORMATION;
+
+typedef struct _FILE_POSITION_INFORMATION {
+  LARGE_INTEGER CurrentByteOffset;
+} FILE_POSITION_INFORMATION, *PFILE_POSITION_INFORMATION;
+
+typedef struct _FILE_MODE_INFORMATION {
+  ULONG Mode;
+} FILE_MODE_INFORMATION, *PFILE_MODE_INFORMATION;
+
+typedef struct _FILE_ALIGNMENT_INFORMATION {
+  ULONG AlignmentRequirement;
+} FILE_ALIGNMENT_INFORMATION, *PFILE_ALIGNMENT_INFORMATION;
+
+typedef struct _FILE_NAME_INFORMATION {
+  ULONG FileNameLength;
+  WCHAR FileName[1];
+} FILE_NAME_INFORMATION, *PFILE_NAME_INFORMATION;
+
+typedef struct _FILE_END_OF_FILE_INFORMATION {
+  LARGE_INTEGER  EndOfFile;
+} FILE_END_OF_FILE_INFORMATION, *PFILE_END_OF_FILE_INFORMATION;
+
+typedef struct _FILE_ALL_INFORMATION {
+  FILE_BASIC_INFORMATION     BasicInformation;
+  FILE_STANDARD_INFORMATION  StandardInformation;
+  FILE_INTERNAL_INFORMATION  InternalInformation;
+  FILE_EA_INFORMATION        EaInformation;
+  FILE_ACCESS_INFORMATION    AccessInformation;
+  FILE_POSITION_INFORMATION  PositionInformation;
+  FILE_MODE_INFORMATION      ModeInformation;
+  FILE_ALIGNMENT_INFORMATION AlignmentInformation;
+  FILE_NAME_INFORMATION      NameInformation;
+} FILE_ALL_INFORMATION, *PFILE_ALL_INFORMATION;
+
+typedef struct _FILE_DISPOSITION_INFORMATION {
+  BOOLEAN DeleteFile;
+} FILE_DISPOSITION_INFORMATION, *PFILE_DISPOSITION_INFORMATION;
+
+typedef struct _FILE_PIPE_LOCAL_INFORMATION {
+  ULONG NamedPipeType;
+  ULONG NamedPipeConfiguration;
+  ULONG MaximumInstances;
+  ULONG CurrentInstances;
+  ULONG InboundQuota;
+  ULONG ReadDataAvailable;
+  ULONG OutboundQuota;
+  ULONG WriteQuotaAvailable;
+  ULONG NamedPipeState;
+  ULONG NamedPipeEnd;
+} FILE_PIPE_LOCAL_INFORMATION, *PFILE_PIPE_LOCAL_INFORMATION;
+
+#define FILE_SYNCHRONOUS_IO_ALERT               0x00000010
+#define FILE_SYNCHRONOUS_IO_NONALERT            0x00000020
+
+typedef enum _FS_INFORMATION_CLASS {
+  FileFsVolumeInformation       = 1,
+  FileFsLabelInformation        = 2,
+  FileFsSizeInformation         = 3,
+  FileFsDeviceInformation       = 4,
+  FileFsAttributeInformation    = 5,
+  FileFsControlInformation      = 6,
+  FileFsFullSizeInformation     = 7,
+  FileFsObjectIdInformation     = 8,
+  FileFsDriverPathInformation   = 9,
+  FileFsVolumeFlagsInformation  = 10,
+  FileFsSectorSizeInformation   = 11
+} FS_INFORMATION_CLASS, *PFS_INFORMATION_CLASS;
+
+typedef struct _FILE_FS_VOLUME_INFORMATION {
+  LARGE_INTEGER VolumeCreationTime;
+  ULONG         VolumeSerialNumber;
+  ULONG         VolumeLabelLength;
+  BOOLEAN       SupportsObjects;
+  WCHAR         VolumeLabel[1];
+} FILE_FS_VOLUME_INFORMATION, *PFILE_FS_VOLUME_INFORMATION;
+
+typedef struct _FILE_FS_LABEL_INFORMATION {
+  ULONG VolumeLabelLength;
+  WCHAR VolumeLabel[1];
+} FILE_FS_LABEL_INFORMATION, *PFILE_FS_LABEL_INFORMATION;
+
+typedef struct _FILE_FS_SIZE_INFORMATION {
+  LARGE_INTEGER TotalAllocationUnits;
+  LARGE_INTEGER AvailableAllocationUnits;
+  ULONG         SectorsPerAllocationUnit;
+  ULONG         BytesPerSector;
+} FILE_FS_SIZE_INFORMATION, *PFILE_FS_SIZE_INFORMATION;
+
+typedef struct _FILE_FS_DEVICE_INFORMATION {
+  DEVICE_TYPE DeviceType;
+  ULONG       Characteristics;
+} FILE_FS_DEVICE_INFORMATION, *PFILE_FS_DEVICE_INFORMATION;
+
+typedef struct _FILE_FS_ATTRIBUTE_INFORMATION {
+  ULONG FileSystemAttributes;
+  LONG  MaximumComponentNameLength;
+  ULONG FileSystemNameLength;
+  WCHAR FileSystemName[1];
+} FILE_FS_ATTRIBUTE_INFORMATION, *PFILE_FS_ATTRIBUTE_INFORMATION;
+
+typedef struct _FILE_FS_CONTROL_INFORMATION {
+  LARGE_INTEGER FreeSpaceStartFiltering;
+  LARGE_INTEGER FreeSpaceThreshold;
+  LARGE_INTEGER FreeSpaceStopFiltering;
+  LARGE_INTEGER DefaultQuotaThreshold;
+  LARGE_INTEGER DefaultQuotaLimit;
+  ULONG         FileSystemControlFlags;
+} FILE_FS_CONTROL_INFORMATION, *PFILE_FS_CONTROL_INFORMATION;
+
+typedef struct _FILE_FS_FULL_SIZE_INFORMATION {
+  LARGE_INTEGER TotalAllocationUnits;
+  LARGE_INTEGER CallerAvailableAllocationUnits;
+  LARGE_INTEGER ActualAvailableAllocationUnits;
+  ULONG         SectorsPerAllocationUnit;
+  ULONG         BytesPerSector;
+} FILE_FS_FULL_SIZE_INFORMATION, *PFILE_FS_FULL_SIZE_INFORMATION;
+
+typedef struct _FILE_FS_OBJECTID_INFORMATION {
+  UCHAR ObjectId[16];
+  UCHAR ExtendedInfo[48];
+} FILE_FS_OBJECTID_INFORMATION, *PFILE_FS_OBJECTID_INFORMATION;
+
+typedef struct _FILE_FS_DRIVER_PATH_INFORMATION {
+  BOOLEAN DriverInPath;
+  ULONG   DriverNameLength;
+  WCHAR   DriverName[1];
+} FILE_FS_DRIVER_PATH_INFORMATION, *PFILE_FS_DRIVER_PATH_INFORMATION;
+
+typedef struct _FILE_FS_VOLUME_FLAGS_INFORMATION {
+  ULONG Flags;
+} FILE_FS_VOLUME_FLAGS_INFORMATION, *PFILE_FS_VOLUME_FLAGS_INFORMATION;
+
+typedef struct _FILE_FS_SECTOR_SIZE_INFORMATION {
+  ULONG LogicalBytesPerSector;
+  ULONG PhysicalBytesPerSectorForAtomicity;
+  ULONG PhysicalBytesPerSectorForPerformance;
+  ULONG FileSystemEffectivePhysicalBytesPerSectorForAtomicity;
+  ULONG Flags;
+  ULONG ByteOffsetForSectorAlignment;
+  ULONG ByteOffsetForPartitionAlignment;
+} FILE_FS_SECTOR_SIZE_INFORMATION, *PFILE_FS_SECTOR_SIZE_INFORMATION;
+
+typedef struct _SYSTEM_PROCESSOR_PERFORMANCE_INFORMATION {
+    LARGE_INTEGER IdleTime;
+    LARGE_INTEGER KernelTime;
+    LARGE_INTEGER UserTime;
+    LARGE_INTEGER DpcTime;
+    LARGE_INTEGER InterruptTime;
+    ULONG InterruptCount;
+} SYSTEM_PROCESSOR_PERFORMANCE_INFORMATION, *PSYSTEM_PROCESSOR_PERFORMANCE_INFORMATION;
+
+#ifndef SystemProcessorPerformanceInformation
+# define SystemProcessorPerformanceInformation 8
+#endif
+
+#ifndef ProcessConsoleHostProcess
+# define ProcessConsoleHostProcess 49
+#endif
+
+#ifndef FILE_DEVICE_FILE_SYSTEM
+# define FILE_DEVICE_FILE_SYSTEM 0x00000009
+#endif
+
+#ifndef FILE_DEVICE_NETWORK
+# define FILE_DEVICE_NETWORK 0x00000012
+#endif
+
+#ifndef METHOD_BUFFERED
+# define METHOD_BUFFERED 0
+#endif
+
+#ifndef METHOD_IN_DIRECT
+# define METHOD_IN_DIRECT 1
+#endif
+
+#ifndef METHOD_OUT_DIRECT
+# define METHOD_OUT_DIRECT 2
+#endif
+
+#ifndef METHOD_NEITHER
+#define METHOD_NEITHER 3
+#endif
+
+#ifndef METHOD_DIRECT_TO_HARDWARE
+# define METHOD_DIRECT_TO_HARDWARE METHOD_IN_DIRECT
+#endif
+
+#ifndef METHOD_DIRECT_FROM_HARDWARE
+# define METHOD_DIRECT_FROM_HARDWARE METHOD_OUT_DIRECT
+#endif
+
+#ifndef FILE_ANY_ACCESS
+# define FILE_ANY_ACCESS 0
+#endif
+
+#ifndef FILE_SPECIAL_ACCESS
+# define FILE_SPECIAL_ACCESS (FILE_ANY_ACCESS)
+#endif
+
+#ifndef FILE_READ_ACCESS
+# define FILE_READ_ACCESS 0x0001
+#endif
+
+#ifndef FILE_WRITE_ACCESS
+# define FILE_WRITE_ACCESS 0x0002
+#endif
+
+#ifndef CTL_CODE
+# define CTL_CODE(device_type, function, method, access)                      \
+    (((device_type) << 16) | ((access) << 14) | ((function) << 2) | (method))
+#endif
+
+#ifndef FSCTL_SET_REPARSE_POINT
+# define FSCTL_SET_REPARSE_POINT CTL_CODE(FILE_DEVICE_FILE_SYSTEM,            \
+                                          41,                                 \
+                                          METHOD_BUFFERED,                    \
+                                          FILE_SPECIAL_ACCESS)
+#endif
+
+#ifndef FSCTL_GET_REPARSE_POINT
+# define FSCTL_GET_REPARSE_POINT CTL_CODE(FILE_DEVICE_FILE_SYSTEM,            \
+                                          42,                                 \
+                                          METHOD_BUFFERED,                    \
+                                          FILE_ANY_ACCESS)
+#endif
+
+#ifndef FSCTL_DELETE_REPARSE_POINT
+# define FSCTL_DELETE_REPARSE_POINT CTL_CODE(FILE_DEVICE_FILE_SYSTEM,         \
+                                             43,                              \
+                                             METHOD_BUFFERED,                 \
+                                             FILE_SPECIAL_ACCESS)
+#endif
+
+#ifndef IO_REPARSE_TAG_SYMLINK
+# define IO_REPARSE_TAG_SYMLINK (0xA000000CL)
+#endif
+#ifndef IO_REPARSE_TAG_APPEXECLINK
+# define IO_REPARSE_TAG_APPEXECLINK (0x8000001BL)
+#endif
+
+typedef VOID (NTAPI *PIO_APC_ROUTINE)
+             (PVOID ApcContext,
+              PIO_STATUS_BLOCK IoStatusBlock,
+              ULONG Reserved);
+
+typedef NTSTATUS (NTAPI *sRtlGetVersion)
+                 (PRTL_OSVERSIONINFOW lpVersionInformation);
+
+typedef ULONG (NTAPI *sRtlNtStatusToDosError)
+              (NTSTATUS Status);
+
+typedef NTSTATUS (NTAPI *sNtDeviceIoControlFile)
+                 (HANDLE FileHandle,
+                  HANDLE Event,
+                  PIO_APC_ROUTINE ApcRoutine,
+                  PVOID ApcContext,
+                  PIO_STATUS_BLOCK IoStatusBlock,
+                  ULONG IoControlCode,
+                  PVOID InputBuffer,
+                  ULONG InputBufferLength,
+                  PVOID OutputBuffer,
+                  ULONG OutputBufferLength);
+
+typedef NTSTATUS (NTAPI *sNtQueryInformationFile)
+                 (HANDLE FileHandle,
+                  PIO_STATUS_BLOCK IoStatusBlock,
+                  PVOID FileInformation,
+                  ULONG Length,
+                  FILE_INFORMATION_CLASS FileInformationClass);
+
+typedef NTSTATUS (NTAPI *sNtSetInformationFile)
+                 (HANDLE FileHandle,
+                  PIO_STATUS_BLOCK IoStatusBlock,
+                  PVOID FileInformation,
+                  ULONG Length,
+                  FILE_INFORMATION_CLASS FileInformationClass);
+
+typedef NTSTATUS (NTAPI *sNtQueryVolumeInformationFile)
+                 (HANDLE FileHandle,
+                  PIO_STATUS_BLOCK IoStatusBlock,
+                  PVOID FsInformation,
+                  ULONG Length,
+                  FS_INFORMATION_CLASS FsInformationClass);
+
+typedef NTSTATUS (NTAPI *sNtQuerySystemInformation)
+                 (UINT SystemInformationClass,
+                  PVOID SystemInformation,
+                  ULONG SystemInformationLength,
+                  PULONG ReturnLength);
+
+typedef NTSTATUS (NTAPI *sNtQueryDirectoryFile)
+                 (HANDLE FileHandle,
+                  HANDLE Event,
+                  PIO_APC_ROUTINE ApcRoutine,
+                  PVOID ApcContext,
+                  PIO_STATUS_BLOCK IoStatusBlock,
+                  PVOID FileInformation,
+                  ULONG Length,
+                  FILE_INFORMATION_CLASS FileInformationClass,
+                  BOOLEAN ReturnSingleEntry,
+                  PUNICODE_STRING FileName,
+                  BOOLEAN RestartScan
+                );
+
+typedef NTSTATUS (NTAPI *sNtQueryInformationProcess)
+                 (HANDLE ProcessHandle,
+                  UINT ProcessInformationClass,
+                  PVOID ProcessInformation,
+                  ULONG Length,
+                  PULONG ReturnLength);
+
+/*
+ * Kernel32 headers
+ */
+#ifndef FILE_SKIP_COMPLETION_PORT_ON_SUCCESS
+# define FILE_SKIP_COMPLETION_PORT_ON_SUCCESS 0x1
+#endif
+
+#ifndef FILE_SKIP_SET_EVENT_ON_HANDLE
+# define FILE_SKIP_SET_EVENT_ON_HANDLE 0x2
+#endif
+
+#ifndef SYMBOLIC_LINK_FLAG_DIRECTORY
+# define SYMBOLIC_LINK_FLAG_DIRECTORY 0x1
+#endif
+
+#if defined(__MINGW32__) && !defined(__MINGW64_VERSION_MAJOR)
+  typedef struct _OVERLAPPED_ENTRY {
+      ULONG_PTR lpCompletionKey;
+      LPOVERLAPPED lpOverlapped;
+      ULONG_PTR Internal;
+      DWORD dwNumberOfBytesTransferred;
+  } OVERLAPPED_ENTRY, *LPOVERLAPPED_ENTRY;
+#endif
+
+/* from wincon.h */
+#ifndef ENABLE_INSERT_MODE
+# define ENABLE_INSERT_MODE 0x20
+#endif
+
+#ifndef ENABLE_QUICK_EDIT_MODE
+# define ENABLE_QUICK_EDIT_MODE 0x40
+#endif
+
+#ifndef ENABLE_EXTENDED_FLAGS
+# define ENABLE_EXTENDED_FLAGS 0x80
+#endif
+
+/* from winerror.h */
+#ifndef ERROR_ELEVATION_REQUIRED
+# define ERROR_ELEVATION_REQUIRED 740
+#endif
+
+#ifndef ERROR_SYMLINK_NOT_SUPPORTED
+# define ERROR_SYMLINK_NOT_SUPPORTED 1464
+#endif
+
+#ifndef ERROR_MUI_FILE_NOT_FOUND
+# define ERROR_MUI_FILE_NOT_FOUND 15100
+#endif
+
+#ifndef ERROR_MUI_INVALID_FILE
+# define ERROR_MUI_INVALID_FILE 15101
+#endif
+
+#ifndef ERROR_MUI_INVALID_RC_CONFIG
+# define ERROR_MUI_INVALID_RC_CONFIG 15102
+#endif
+
+#ifndef ERROR_MUI_INVALID_LOCALE_NAME
+# define ERROR_MUI_INVALID_LOCALE_NAME 15103
+#endif
+
+#ifndef ERROR_MUI_INVALID_ULTIMATEFALLBACK_NAME
+# define ERROR_MUI_INVALID_ULTIMATEFALLBACK_NAME 15104
+#endif
+
+#ifndef ERROR_MUI_FILE_NOT_LOADED
+# define ERROR_MUI_FILE_NOT_LOADED 15105
+#endif
+
+typedef BOOL (WINAPI *sGetQueuedCompletionStatusEx)
+             (HANDLE CompletionPort,
+              LPOVERLAPPED_ENTRY lpCompletionPortEntries,
+              ULONG ulCount,
+              PULONG ulNumEntriesRemoved,
+              DWORD dwMilliseconds,
+              BOOL fAlertable);
+
+/* from powerbase.h */
+#ifndef DEVICE_NOTIFY_CALLBACK
+# define DEVICE_NOTIFY_CALLBACK 2
+#endif
+
+#ifndef PBT_APMRESUMEAUTOMATIC
+# define PBT_APMRESUMEAUTOMATIC 18
+#endif
+
+#ifndef PBT_APMRESUMESUSPEND
+# define PBT_APMRESUMESUSPEND 7
+#endif
+
+typedef ULONG CALLBACK _DEVICE_NOTIFY_CALLBACK_ROUTINE(
+  PVOID Context,
+  ULONG Type,
+  PVOID Setting
+);
+typedef _DEVICE_NOTIFY_CALLBACK_ROUTINE* _PDEVICE_NOTIFY_CALLBACK_ROUTINE;
+
+typedef struct _DEVICE_NOTIFY_SUBSCRIBE_PARAMETERS {
+  _PDEVICE_NOTIFY_CALLBACK_ROUTINE Callback;
+  PVOID Context;
+} _DEVICE_NOTIFY_SUBSCRIBE_PARAMETERS, *_PDEVICE_NOTIFY_SUBSCRIBE_PARAMETERS;
+
+typedef PVOID _HPOWERNOTIFY;
+typedef _HPOWERNOTIFY *_PHPOWERNOTIFY;
+
+typedef DWORD (WINAPI *sPowerRegisterSuspendResumeNotification)
+              (DWORD         Flags,
+               HANDLE        Recipient,
+               _PHPOWERNOTIFY RegistrationHandle);
+
+/* from Winuser.h */
+typedef VOID (CALLBACK* WINEVENTPROC)
+             (HWINEVENTHOOK hWinEventHook,
+              DWORD         event,
+              HWND          hwnd,
+              LONG          idObject,
+              LONG          idChild,
+              DWORD         idEventThread,
+              DWORD         dwmsEventTime);
+
+typedef HWINEVENTHOOK (WINAPI *sSetWinEventHook)
+                      (UINT         eventMin,
+                       UINT         eventMax,
+                       HMODULE      hmodWinEventProc,
+                       WINEVENTPROC lpfnWinEventProc,
+                       DWORD        idProcess,
+                       DWORD        idThread,
+                       UINT         dwflags);
+
+/* From mstcpip.h */
+typedef struct _TCP_INITIAL_RTO_PARAMETERS {
+  USHORT Rtt;
+  UCHAR  MaxSynRetransmissions;
+} TCP_INITIAL_RTO_PARAMETERS, *PTCP_INITIAL_RTO_PARAMETERS;
+
+#ifndef TCP_INITIAL_RTO_NO_SYN_RETRANSMISSIONS
+# define TCP_INITIAL_RTO_NO_SYN_RETRANSMISSIONS ((UCHAR) -2)
+#endif
+#ifndef SIO_TCP_INITIAL_RTO
+# define  SIO_TCP_INITIAL_RTO _WSAIOW(IOC_VENDOR,17)
+#endif
+
+/* Ntdll function pointers */
+extern sRtlGetVersion pRtlGetVersion;
+extern sRtlNtStatusToDosError pRtlNtStatusToDosError;
+extern sNtDeviceIoControlFile pNtDeviceIoControlFile;
+extern sNtQueryInformationFile pNtQueryInformationFile;
+extern sNtSetInformationFile pNtSetInformationFile;
+extern sNtQueryVolumeInformationFile pNtQueryVolumeInformationFile;
+extern sNtQueryDirectoryFile pNtQueryDirectoryFile;
+extern sNtQuerySystemInformation pNtQuerySystemInformation;
+extern sNtQueryInformationProcess pNtQueryInformationProcess;
+
+/* Kernel32 function pointers */
+extern sGetQueuedCompletionStatusEx pGetQueuedCompletionStatusEx;
+
+/* Powrprof.dll function pointer */
+extern sPowerRegisterSuspendResumeNotification pPowerRegisterSuspendResumeNotification;
+
+/* User32.dll function pointer */
+extern sSetWinEventHook pSetWinEventHook;
+
+/* ws2_32.dll function pointer */
+/* mingw doesn't have this definition, so let's declare it here locally */
+typedef int (WINAPI *uv_sGetHostNameW)
+            (PWSTR,
+             int);
+extern uv_sGetHostNameW pGetHostNameW;
+
+#endif /* UV_WIN_WINAPI_H_ */
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/winsock.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/winsock.cpp
new file mode 100644
index 0000000..cda82bc
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/winsock.cpp
@@ -0,0 +1,577 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <assert.h>
+#include <stdlib.h>
+
+#include "uv.h"
+#include "internal.h"
+
+
+#pragma comment(lib, "Ws2_32.lib")
+
+/* Whether there are any non-IFS LSPs stacked on TCP */
+int uv_tcp_non_ifs_lsp_ipv4;
+int uv_tcp_non_ifs_lsp_ipv6;
+
+/* Ip address used to bind to any port at any interface */
+struct sockaddr_in uv_addr_ip4_any_;
+struct sockaddr_in6 uv_addr_ip6_any_;
+
+
+/*
+ * Retrieves the pointer to a winsock extension function.
+ */
+static BOOL uv__get_extension_function(SOCKET socket, GUID guid,
+    void **target) {
+  int result;
+  DWORD bytes;
+
+  result = WSAIoctl(socket,
+                    SIO_GET_EXTENSION_FUNCTION_POINTER,
+                    &guid,
+                    sizeof(guid),
+                    (void*)target,
+                    sizeof(*target),
+                    &bytes,
+                    NULL,
+                    NULL);
+
+  if (result == SOCKET_ERROR) {
+    *target = NULL;
+    return FALSE;
+  } else {
+    return TRUE;
+  }
+}
+
+
+BOOL uv__get_acceptex_function(SOCKET socket, LPFN_ACCEPTEX* target) {
+  const GUID wsaid_acceptex = WSAID_ACCEPTEX;
+  return uv__get_extension_function(socket, wsaid_acceptex, (void**)target);
+}
+
+
+BOOL uv__get_connectex_function(SOCKET socket, LPFN_CONNECTEX* target) {
+  const GUID wsaid_connectex = WSAID_CONNECTEX;
+  return uv__get_extension_function(socket, wsaid_connectex, (void**)target);
+}
+
+
+
+void uv__winsock_init(void) {
+  WSADATA wsa_data;
+  int errorno;
+  SOCKET dummy;
+  WSAPROTOCOL_INFOW protocol_info;
+  int opt_len;
+
+  /* Set implicit binding address used by connectEx */
+  if (uv_ip4_addr("0.0.0.0", 0, &uv_addr_ip4_any_)) {
+    abort();
+  }
+
+  if (uv_ip6_addr("::", 0, &uv_addr_ip6_any_)) {
+    abort();
+  }
+
+  /* Skip initialization in safe mode without network support */
+  if (1 == GetSystemMetrics(SM_CLEANBOOT)) return;
+
+  /* Initialize winsock */
+  errorno = WSAStartup(MAKEWORD(2, 2), &wsa_data);
+  if (errorno != 0) {
+    uv_fatal_error(errorno, "WSAStartup");
+  }
+
+  /* Try to detect non-IFS LSPs */
+  uv_tcp_non_ifs_lsp_ipv4 = 1;
+  dummy = socket(AF_INET, SOCK_STREAM, IPPROTO_IP);
+  if (dummy != INVALID_SOCKET) {
+    opt_len = (int) sizeof protocol_info;
+    if (getsockopt(dummy,
+                   SOL_SOCKET,
+                   SO_PROTOCOL_INFOW,
+                   (char*) &protocol_info,
+                   &opt_len) == 0) {
+      if (protocol_info.dwServiceFlags1 & XP1_IFS_HANDLES)
+        uv_tcp_non_ifs_lsp_ipv4 = 0;
+    }
+    closesocket(dummy);
+  }
+
+  /* Try to detect IPV6 support and non-IFS LSPs */
+  uv_tcp_non_ifs_lsp_ipv6 = 1;
+  dummy = socket(AF_INET6, SOCK_STREAM, IPPROTO_IP);
+  if (dummy != INVALID_SOCKET) {
+    opt_len = (int) sizeof protocol_info;
+    if (getsockopt(dummy,
+                   SOL_SOCKET,
+                   SO_PROTOCOL_INFOW,
+                   (char*) &protocol_info,
+                   &opt_len) == 0) {
+      if (protocol_info.dwServiceFlags1 & XP1_IFS_HANDLES)
+        uv_tcp_non_ifs_lsp_ipv6 = 0;
+    }
+    closesocket(dummy);
+  }
+}
+
+
+int uv__ntstatus_to_winsock_error(NTSTATUS status) {
+  switch (status) {
+    case STATUS_SUCCESS:
+      return ERROR_SUCCESS;
+
+    case STATUS_PENDING:
+      return ERROR_IO_PENDING;
+
+    case STATUS_INVALID_HANDLE:
+    case STATUS_OBJECT_TYPE_MISMATCH:
+      return WSAENOTSOCK;
+
+    case STATUS_INSUFFICIENT_RESOURCES:
+    case STATUS_PAGEFILE_QUOTA:
+    case STATUS_COMMITMENT_LIMIT:
+    case STATUS_WORKING_SET_QUOTA:
+    case STATUS_NO_MEMORY:
+    case STATUS_QUOTA_EXCEEDED:
+    case STATUS_TOO_MANY_PAGING_FILES:
+    case STATUS_REMOTE_RESOURCES:
+      return WSAENOBUFS;
+
+    case STATUS_TOO_MANY_ADDRESSES:
+    case STATUS_SHARING_VIOLATION:
+    case STATUS_ADDRESS_ALREADY_EXISTS:
+      return WSAEADDRINUSE;
+
+    case STATUS_LINK_TIMEOUT:
+    case STATUS_IO_TIMEOUT:
+    case STATUS_TIMEOUT:
+      return WSAETIMEDOUT;
+
+    case STATUS_GRACEFUL_DISCONNECT:
+      return WSAEDISCON;
+
+    case STATUS_REMOTE_DISCONNECT:
+    case STATUS_CONNECTION_RESET:
+    case STATUS_LINK_FAILED:
+    case STATUS_CONNECTION_DISCONNECTED:
+    case STATUS_PORT_UNREACHABLE:
+    case STATUS_HOPLIMIT_EXCEEDED:
+      return WSAECONNRESET;
+
+    case STATUS_LOCAL_DISCONNECT:
+    case STATUS_TRANSACTION_ABORTED:
+    case STATUS_CONNECTION_ABORTED:
+      return WSAECONNABORTED;
+
+    case STATUS_BAD_NETWORK_PATH:
+    case STATUS_NETWORK_UNREACHABLE:
+    case STATUS_PROTOCOL_UNREACHABLE:
+      return WSAENETUNREACH;
+
+    case STATUS_HOST_UNREACHABLE:
+      return WSAEHOSTUNREACH;
+
+    case STATUS_CANCELLED:
+    case STATUS_REQUEST_ABORTED:
+      return WSAEINTR;
+
+    case STATUS_BUFFER_OVERFLOW:
+    case STATUS_INVALID_BUFFER_SIZE:
+      return WSAEMSGSIZE;
+
+    case STATUS_BUFFER_TOO_SMALL:
+    case STATUS_ACCESS_VIOLATION:
+      return WSAEFAULT;
+
+    case STATUS_DEVICE_NOT_READY:
+    case STATUS_REQUEST_NOT_ACCEPTED:
+      return WSAEWOULDBLOCK;
+
+    case STATUS_INVALID_NETWORK_RESPONSE:
+    case STATUS_NETWORK_BUSY:
+    case STATUS_NO_SUCH_DEVICE:
+    case STATUS_NO_SUCH_FILE:
+    case STATUS_OBJECT_PATH_NOT_FOUND:
+    case STATUS_OBJECT_NAME_NOT_FOUND:
+    case STATUS_UNEXPECTED_NETWORK_ERROR:
+      return WSAENETDOWN;
+
+    case STATUS_INVALID_CONNECTION:
+      return WSAENOTCONN;
+
+    case STATUS_REMOTE_NOT_LISTENING:
+    case STATUS_CONNECTION_REFUSED:
+      return WSAECONNREFUSED;
+
+    case STATUS_PIPE_DISCONNECTED:
+      return WSAESHUTDOWN;
+
+    case STATUS_CONFLICTING_ADDRESSES:
+    case STATUS_INVALID_ADDRESS:
+    case STATUS_INVALID_ADDRESS_COMPONENT:
+      return WSAEADDRNOTAVAIL;
+
+    case STATUS_NOT_SUPPORTED:
+    case STATUS_NOT_IMPLEMENTED:
+      return WSAEOPNOTSUPP;
+
+    case STATUS_ACCESS_DENIED:
+      return WSAEACCES;
+
+    default:
+      if ((status & (FACILITY_NTWIN32 << 16)) == (FACILITY_NTWIN32 << 16) &&
+          (status & (ERROR_SEVERITY_ERROR | ERROR_SEVERITY_WARNING))) {
+        /* It's a windows error that has been previously mapped to an ntstatus
+         * code. */
+        return (DWORD) (status & 0xffff);
+      } else {
+        /* The default fallback for unmappable ntstatus codes. */
+        return WSAEINVAL;
+      }
+  }
+}
+
+
+/*
+ * This function provides a workaround for a bug in the winsock implementation
+ * of WSARecv. The problem is that when SetFileCompletionNotificationModes is
+ * used to avoid IOCP notifications of completed reads, WSARecv does not
+ * reliably indicate whether we can expect a completion package to be posted
+ * when the receive buffer is smaller than the received datagram.
+ *
+ * However it is desirable to use SetFileCompletionNotificationModes because
+ * it yields a massive performance increase.
+ *
+ * This function provides a workaround for that bug, but it only works for the
+ * specific case that we need it for. E.g. it assumes that the "avoid iocp"
+ * bit has been set, and supports only overlapped operation. It also requires
+ * the user to use the default msafd driver, doesn't work when other LSPs are
+ * stacked on top of it.
+ */
+int WSAAPI uv__wsarecv_workaround(SOCKET socket, WSABUF* buffers,
+    DWORD buffer_count, DWORD* bytes, DWORD* flags, WSAOVERLAPPED *overlapped,
+    LPWSAOVERLAPPED_COMPLETION_ROUTINE completion_routine) {
+  NTSTATUS status;
+  void* apc_context;
+  IO_STATUS_BLOCK* iosb = (IO_STATUS_BLOCK*) &overlapped->Internal;
+  AFD_RECV_INFO info;
+  DWORD error;
+
+  if (overlapped == NULL || completion_routine != NULL) {
+    WSASetLastError(WSAEINVAL);
+    return SOCKET_ERROR;
+  }
+
+  info.BufferArray = buffers;
+  info.BufferCount = buffer_count;
+  info.AfdFlags = AFD_OVERLAPPED;
+  info.TdiFlags = TDI_RECEIVE_NORMAL;
+
+  if (*flags & MSG_PEEK) {
+    info.TdiFlags |= TDI_RECEIVE_PEEK;
+  }
+
+  if (*flags & MSG_PARTIAL) {
+    info.TdiFlags |= TDI_RECEIVE_PARTIAL;
+  }
+
+  if (!((intptr_t) overlapped->hEvent & 1)) {
+    apc_context = (void*) overlapped;
+  } else {
+    apc_context = NULL;
+  }
+
+  iosb->Status = STATUS_PENDING;
+  iosb->Pointer = 0;
+
+  status = pNtDeviceIoControlFile((HANDLE) socket,
+                                  overlapped->hEvent,
+                                  NULL,
+                                  apc_context,
+                                  iosb,
+                                  IOCTL_AFD_RECEIVE,
+                                  &info,
+                                  sizeof(info),
+                                  NULL,
+                                  0);
+
+  *flags = 0;
+  *bytes = (DWORD) iosb->Information;
+
+  switch (status) {
+    case STATUS_SUCCESS:
+      error = ERROR_SUCCESS;
+      break;
+
+    case STATUS_PENDING:
+      error = WSA_IO_PENDING;
+      break;
+
+    case STATUS_BUFFER_OVERFLOW:
+      error = WSAEMSGSIZE;
+      break;
+
+    case STATUS_RECEIVE_EXPEDITED:
+      error = ERROR_SUCCESS;
+      *flags = MSG_OOB;
+      break;
+
+    case STATUS_RECEIVE_PARTIAL_EXPEDITED:
+      error = ERROR_SUCCESS;
+      *flags = MSG_PARTIAL | MSG_OOB;
+      break;
+
+    case STATUS_RECEIVE_PARTIAL:
+      error = ERROR_SUCCESS;
+      *flags = MSG_PARTIAL;
+      break;
+
+    default:
+      error = uv__ntstatus_to_winsock_error(status);
+      break;
+  }
+
+  WSASetLastError(error);
+
+  if (error == ERROR_SUCCESS) {
+    return 0;
+  } else {
+    return SOCKET_ERROR;
+  }
+}
+
+
+/* See description of uv__wsarecv_workaround. */
+int WSAAPI uv__wsarecvfrom_workaround(SOCKET socket, WSABUF* buffers,
+    DWORD buffer_count, DWORD* bytes, DWORD* flags, struct sockaddr* addr,
+    int* addr_len, WSAOVERLAPPED *overlapped,
+    LPWSAOVERLAPPED_COMPLETION_ROUTINE completion_routine) {
+  NTSTATUS status;
+  void* apc_context;
+  IO_STATUS_BLOCK* iosb = (IO_STATUS_BLOCK*) &overlapped->Internal;
+  AFD_RECV_DATAGRAM_INFO info;
+  DWORD error;
+
+  if (overlapped == NULL || addr == NULL || addr_len == NULL ||
+      completion_routine != NULL) {
+    WSASetLastError(WSAEINVAL);
+    return SOCKET_ERROR;
+  }
+
+  info.BufferArray = buffers;
+  info.BufferCount = buffer_count;
+  info.AfdFlags = AFD_OVERLAPPED;
+  info.TdiFlags = TDI_RECEIVE_NORMAL;
+  info.Address = addr;
+  info.AddressLength = addr_len;
+
+  if (*flags & MSG_PEEK) {
+    info.TdiFlags |= TDI_RECEIVE_PEEK;
+  }
+
+  if (*flags & MSG_PARTIAL) {
+    info.TdiFlags |= TDI_RECEIVE_PARTIAL;
+  }
+
+  if (!((intptr_t) overlapped->hEvent & 1)) {
+    apc_context = (void*) overlapped;
+  } else {
+    apc_context = NULL;
+  }
+
+  iosb->Status = STATUS_PENDING;
+  iosb->Pointer = 0;
+
+  status = pNtDeviceIoControlFile((HANDLE) socket,
+                                  overlapped->hEvent,
+                                  NULL,
+                                  apc_context,
+                                  iosb,
+                                  IOCTL_AFD_RECEIVE_DATAGRAM,
+                                  &info,
+                                  sizeof(info),
+                                  NULL,
+                                  0);
+
+  *flags = 0;
+  *bytes = (DWORD) iosb->Information;
+
+  switch (status) {
+    case STATUS_SUCCESS:
+      error = ERROR_SUCCESS;
+      break;
+
+    case STATUS_PENDING:
+      error = WSA_IO_PENDING;
+      break;
+
+    case STATUS_BUFFER_OVERFLOW:
+      error = WSAEMSGSIZE;
+      break;
+
+    case STATUS_RECEIVE_EXPEDITED:
+      error = ERROR_SUCCESS;
+      *flags = MSG_OOB;
+      break;
+
+    case STATUS_RECEIVE_PARTIAL_EXPEDITED:
+      error = ERROR_SUCCESS;
+      *flags = MSG_PARTIAL | MSG_OOB;
+      break;
+
+    case STATUS_RECEIVE_PARTIAL:
+      error = ERROR_SUCCESS;
+      *flags = MSG_PARTIAL;
+      break;
+
+    default:
+      error = uv__ntstatus_to_winsock_error(status);
+      break;
+  }
+
+  WSASetLastError(error);
+
+  if (error == ERROR_SUCCESS) {
+    return 0;
+  } else {
+    return SOCKET_ERROR;
+  }
+}
+
+
+int WSAAPI uv__msafd_poll(SOCKET socket, AFD_POLL_INFO* info_in,
+    AFD_POLL_INFO* info_out, OVERLAPPED* overlapped) {
+  IO_STATUS_BLOCK iosb;
+  IO_STATUS_BLOCK* iosb_ptr;
+  HANDLE event = NULL;
+  void* apc_context;
+  NTSTATUS status;
+  DWORD error;
+
+  if (overlapped != NULL) {
+    /* Overlapped operation. */
+    iosb_ptr = (IO_STATUS_BLOCK*) &overlapped->Internal;
+    event = overlapped->hEvent;
+
+    /* Do not report iocp completion if hEvent is tagged. */
+    if ((uintptr_t) event & 1) {
+      event = (HANDLE)((uintptr_t) event & ~(uintptr_t) 1);
+      apc_context = NULL;
+    } else {
+      apc_context = overlapped;
+    }
+
+  } else {
+    /* Blocking operation. */
+    iosb_ptr = &iosb;
+    event = CreateEvent(NULL, FALSE, FALSE, NULL);
+    if (event == NULL) {
+      return SOCKET_ERROR;
+    }
+    apc_context = NULL;
+  }
+
+  iosb_ptr->Status = STATUS_PENDING;
+  status = pNtDeviceIoControlFile((HANDLE) socket,
+                                  event,
+                                  NULL,
+                                  apc_context,
+                                  iosb_ptr,
+                                  IOCTL_AFD_POLL,
+                                  info_in,
+                                  sizeof *info_in,
+                                  info_out,
+                                  sizeof *info_out);
+
+  if (overlapped == NULL) {
+    /* If this is a blocking operation, wait for the event to become signaled,
+     * and then grab the real status from the io status block. */
+    if (status == STATUS_PENDING) {
+      DWORD r = WaitForSingleObject(event, INFINITE);
+
+      if (r == WAIT_FAILED) {
+        DWORD saved_error = GetLastError();
+        CloseHandle(event);
+        WSASetLastError(saved_error);
+        return SOCKET_ERROR;
+      }
+
+      status = iosb.Status;
+    }
+
+    CloseHandle(event);
+  }
+
+  switch (status) {
+    case STATUS_SUCCESS:
+      error = ERROR_SUCCESS;
+      break;
+
+    case STATUS_PENDING:
+      error = WSA_IO_PENDING;
+      break;
+
+    default:
+      error = uv__ntstatus_to_winsock_error(status);
+      break;
+  }
+
+  WSASetLastError(error);
+
+  if (error == ERROR_SUCCESS) {
+    return 0;
+  } else {
+    return SOCKET_ERROR;
+  }
+}
+
+int uv__convert_to_localhost_if_unspecified(const struct sockaddr* addr,
+                                            struct sockaddr_storage* storage) {
+  struct sockaddr_in* dest4;
+  struct sockaddr_in6* dest6;
+
+  if (addr == NULL)
+    return UV_EINVAL;
+
+  switch (addr->sa_family) {
+  case AF_INET:
+    dest4 = (struct sockaddr_in*) storage;
+    memcpy(dest4, addr, sizeof(*dest4));
+    if (dest4->sin_addr.s_addr == 0)
+      dest4->sin_addr.s_addr = htonl(INADDR_LOOPBACK);
+    return 0;
+  case AF_INET6:
+    dest6 = (struct sockaddr_in6*) storage;
+    memcpy(dest6, addr, sizeof(*dest6));
+    if (memcmp(&dest6->sin6_addr,
+               &uv_addr_ip6_any_.sin6_addr,
+               sizeof(uv_addr_ip6_any_.sin6_addr)) == 0) {
+      struct in6_addr init_sin6_addr = IN6ADDR_LOOPBACK_INIT;
+      dest6->sin6_addr = init_sin6_addr;
+    }
+    return 0;
+  default:
+    return UV_EINVAL;
+  }
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/winsock.h b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/winsock.h
new file mode 100644
index 0000000..2af9588
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/libuv/src/win/winsock.h
@@ -0,0 +1,201 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#ifndef UV_WIN_WINSOCK_H_
+#define UV_WIN_WINSOCK_H_
+
+#include <winsock2.h>
+#include <iptypes.h>
+#include <mswsock.h>
+#include <ws2tcpip.h>
+#include <windows.h>
+
+#include "winapi.h"
+
+
+/*
+ * MinGW is missing these too
+ */
+#ifndef SO_UPDATE_CONNECT_CONTEXT
+# define SO_UPDATE_CONNECT_CONTEXT 0x7010
+#endif
+
+#ifndef TCP_KEEPALIVE
+# define TCP_KEEPALIVE 3
+#endif
+
+#ifndef IPV6_V6ONLY
+# define IPV6_V6ONLY 27
+#endif
+
+#ifndef IPV6_HOPLIMIT
+# define IPV6_HOPLIMIT 21
+#endif
+
+#ifndef SIO_BASE_HANDLE
+# define SIO_BASE_HANDLE 0x48000022
+#endif
+
+#ifndef MCAST_JOIN_SOURCE_GROUP
+# define MCAST_JOIN_SOURCE_GROUP 45
+#endif
+
+#ifndef MCAST_LEAVE_SOURCE_GROUP
+# define MCAST_LEAVE_SOURCE_GROUP 46
+#endif
+
+/*
+ * TDI defines that are only in the DDK.
+ * We only need receive flags so far.
+ */
+#ifndef TDI_RECEIVE_NORMAL
+  #define TDI_RECEIVE_BROADCAST           0x00000004
+  #define TDI_RECEIVE_MULTICAST           0x00000008
+  #define TDI_RECEIVE_PARTIAL             0x00000010
+  #define TDI_RECEIVE_NORMAL              0x00000020
+  #define TDI_RECEIVE_EXPEDITED           0x00000040
+  #define TDI_RECEIVE_PEEK                0x00000080
+  #define TDI_RECEIVE_NO_RESPONSE_EXP     0x00000100
+  #define TDI_RECEIVE_COPY_LOOKAHEAD      0x00000200
+  #define TDI_RECEIVE_ENTIRE_MESSAGE      0x00000400
+  #define TDI_RECEIVE_AT_DISPATCH_LEVEL   0x00000800
+  #define TDI_RECEIVE_CONTROL_INFO        0x00001000
+  #define TDI_RECEIVE_FORCE_INDICATION    0x00002000
+  #define TDI_RECEIVE_NO_PUSH             0x00004000
+#endif
+
+/*
+ * The "Auxiliary Function Driver" is the windows kernel-mode driver that does
+ * TCP, UDP etc. Winsock is just a layer that dispatches requests to it.
+ * Having these definitions allows us to bypass winsock and make an AFD kernel
+ * call directly, avoiding a bug in winsock's recvfrom implementation.
+ */
+
+#define AFD_NO_FAST_IO   0x00000001
+#define AFD_OVERLAPPED   0x00000002
+#define AFD_IMMEDIATE    0x00000004
+
+#define AFD_POLL_RECEIVE_BIT            0
+#define AFD_POLL_RECEIVE                (1 << AFD_POLL_RECEIVE_BIT)
+#define AFD_POLL_RECEIVE_EXPEDITED_BIT  1
+#define AFD_POLL_RECEIVE_EXPEDITED      (1 << AFD_POLL_RECEIVE_EXPEDITED_BIT)
+#define AFD_POLL_SEND_BIT               2
+#define AFD_POLL_SEND                   (1 << AFD_POLL_SEND_BIT)
+#define AFD_POLL_DISCONNECT_BIT         3
+#define AFD_POLL_DISCONNECT             (1 << AFD_POLL_DISCONNECT_BIT)
+#define AFD_POLL_ABORT_BIT              4
+#define AFD_POLL_ABORT                  (1 << AFD_POLL_ABORT_BIT)
+#define AFD_POLL_LOCAL_CLOSE_BIT        5
+#define AFD_POLL_LOCAL_CLOSE            (1 << AFD_POLL_LOCAL_CLOSE_BIT)
+#define AFD_POLL_CONNECT_BIT            6
+#define AFD_POLL_CONNECT                (1 << AFD_POLL_CONNECT_BIT)
+#define AFD_POLL_ACCEPT_BIT             7
+#define AFD_POLL_ACCEPT                 (1 << AFD_POLL_ACCEPT_BIT)
+#define AFD_POLL_CONNECT_FAIL_BIT       8
+#define AFD_POLL_CONNECT_FAIL           (1 << AFD_POLL_CONNECT_FAIL_BIT)
+#define AFD_POLL_QOS_BIT                9
+#define AFD_POLL_QOS                    (1 << AFD_POLL_QOS_BIT)
+#define AFD_POLL_GROUP_QOS_BIT          10
+#define AFD_POLL_GROUP_QOS              (1 << AFD_POLL_GROUP_QOS_BIT)
+
+#define AFD_NUM_POLL_EVENTS             11
+#define AFD_POLL_ALL                    ((1 << AFD_NUM_POLL_EVENTS) - 1)
+
+typedef struct _AFD_RECV_DATAGRAM_INFO {
+    LPWSABUF BufferArray;
+    ULONG BufferCount;
+    ULONG AfdFlags;
+    ULONG TdiFlags;
+    struct sockaddr* Address;
+    int* AddressLength;
+} AFD_RECV_DATAGRAM_INFO, *PAFD_RECV_DATAGRAM_INFO;
+
+typedef struct _AFD_RECV_INFO {
+    LPWSABUF BufferArray;
+    ULONG BufferCount;
+    ULONG AfdFlags;
+    ULONG TdiFlags;
+} AFD_RECV_INFO, *PAFD_RECV_INFO;
+
+
+#define _AFD_CONTROL_CODE(operation, method) \
+    ((FSCTL_AFD_BASE) << 12 | (operation << 2) | method)
+
+#define FSCTL_AFD_BASE FILE_DEVICE_NETWORK
+
+#define AFD_RECEIVE            5
+#define AFD_RECEIVE_DATAGRAM   6
+#define AFD_POLL               9
+
+#define IOCTL_AFD_RECEIVE \
+    _AFD_CONTROL_CODE(AFD_RECEIVE, METHOD_NEITHER)
+
+#define IOCTL_AFD_RECEIVE_DATAGRAM \
+    _AFD_CONTROL_CODE(AFD_RECEIVE_DATAGRAM, METHOD_NEITHER)
+
+#define IOCTL_AFD_POLL \
+    _AFD_CONTROL_CODE(AFD_POLL, METHOD_BUFFERED)
+
+#if defined(__MINGW32__) && !defined(__MINGW64_VERSION_MAJOR)
+typedef struct _IP_ADAPTER_UNICAST_ADDRESS_XP {
+  /* FIXME: __C89_NAMELESS was removed */
+  /* __C89_NAMELESS */ union {
+    ULONGLONG Alignment;
+    /* __C89_NAMELESS */ struct {
+      ULONG Length;
+      DWORD Flags;
+    };
+  };
+  struct _IP_ADAPTER_UNICAST_ADDRESS_XP *Next;
+  SOCKET_ADDRESS Address;
+  IP_PREFIX_ORIGIN PrefixOrigin;
+  IP_SUFFIX_ORIGIN SuffixOrigin;
+  IP_DAD_STATE DadState;
+  ULONG ValidLifetime;
+  ULONG PreferredLifetime;
+  ULONG LeaseLifetime;
+} IP_ADAPTER_UNICAST_ADDRESS_XP,*PIP_ADAPTER_UNICAST_ADDRESS_XP;
+
+typedef struct _IP_ADAPTER_UNICAST_ADDRESS_LH {
+  union {
+    ULONGLONG Alignment;
+    struct {
+      ULONG Length;
+      DWORD Flags;
+    };
+  };
+  struct _IP_ADAPTER_UNICAST_ADDRESS_LH *Next;
+  SOCKET_ADDRESS Address;
+  IP_PREFIX_ORIGIN PrefixOrigin;
+  IP_SUFFIX_ORIGIN SuffixOrigin;
+  IP_DAD_STATE DadState;
+  ULONG ValidLifetime;
+  ULONG PreferredLifetime;
+  ULONG LeaseLifetime;
+  UINT8 OnLinkPrefixLength;
+} IP_ADAPTER_UNICAST_ADDRESS_LH,*PIP_ADAPTER_UNICAST_ADDRESS_LH;
+
+#endif
+
+int uv__convert_to_localhost_if_unspecified(const struct sockaddr* addr,
+                                            struct sockaddr_storage* storage);
+
+#endif /* UV_WIN_WINSOCK_H_ */
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/tcpsockets/cpp/TCPAcceptor.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/tcpsockets/cpp/TCPAcceptor.cpp
new file mode 100644
index 0000000..fb82ce7
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/tcpsockets/cpp/TCPAcceptor.cpp
@@ -0,0 +1,211 @@
+/*
+   TCPAcceptor.cpp
+
+   TCPAcceptor class definition. TCPAcceptor provides methods to passively
+   establish TCP/IP connections with clients.
+
+   ------------------------------------------
+
+   Copyright (c) 2013 [Vic Hargrave - http://vichargrave.com]
+
+   Licensed under the Apache License, Version 2.0 (the "License");
+   you may not use this file except in compliance with the License.
+   You may obtain a copy of the License at
+
+       http://www.apache.org/licenses/LICENSE-2.0
+
+   Unless required by applicable law or agreed to in writing, software
+   distributed under the License is distributed on an "AS IS" BASIS,
+   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+   See the License for the specific language governing permissions and
+   limitations under the License.
+*/
+
+#include "wpinet/TCPAcceptor.h"
+
+#include <cstdio>
+#include <cstring>
+
+#ifdef _WIN32
+#define _WINSOCK_DEPRECATED_NO_WARNINGS
+#include <WinSock2.h>
+#include <Ws2tcpip.h>
+#pragma comment(lib, "Ws2_32.lib")
+#else
+#include <arpa/inet.h>
+#include <fcntl.h>
+#include <netinet/in.h>
+#include <unistd.h>
+#endif
+
+#include <wpi/Logger.h>
+#include <wpi/SmallString.h>
+
+#include "wpinet/SocketError.h"
+
+using namespace wpi;
+
+TCPAcceptor::TCPAcceptor(int port, std::string_view address, Logger& logger)
+    : m_lsd(0),
+      m_port(port),
+      m_address(address),
+      m_listening(false),
+      m_logger(logger) {
+  m_shutdown = false;
+#ifdef _WIN32
+  WSAData wsaData;
+  WORD wVersionRequested = MAKEWORD(2, 2);
+  (void)WSAStartup(wVersionRequested, &wsaData);
+#endif
+}
+
+TCPAcceptor::~TCPAcceptor() {
+  if (m_lsd > 0) {
+    shutdown();
+#ifdef _WIN32
+    closesocket(m_lsd);
+#else
+    close(m_lsd);
+#endif
+  }
+#ifdef _WIN32
+  WSACleanup();
+#endif
+}
+
+int TCPAcceptor::start() {
+  if (m_listening) {
+    return 0;
+  }
+
+  m_lsd = socket(PF_INET, SOCK_STREAM, 0);
+  if (m_lsd < 0) {
+    WPI_ERROR(m_logger, "could not create socket");
+    return -1;
+  }
+  struct sockaddr_in address;
+
+  std::memset(&address, 0, sizeof(address));
+  address.sin_family = PF_INET;
+  if (m_address.size() > 0) {
+#ifdef _WIN32
+    SmallString<128> addr_copy(m_address);
+    addr_copy.push_back('\0');
+    int res = InetPton(PF_INET, addr_copy.data(), &(address.sin_addr));
+#else
+    int res = inet_pton(PF_INET, m_address.c_str(), &(address.sin_addr));
+#endif
+    if (res != 1) {
+      WPI_ERROR(m_logger, "could not resolve {} address", m_address);
+      return -1;
+    }
+  } else {
+    address.sin_addr.s_addr = INADDR_ANY;
+  }
+  address.sin_port = htons(m_port);
+
+#ifdef _WIN32
+  int optval = 1;
+  setsockopt(m_lsd, SOL_SOCKET, SO_EXCLUSIVEADDRUSE,
+             reinterpret_cast<char*>(&optval), sizeof optval);
+#else
+  int optval = 1;
+  setsockopt(m_lsd, SOL_SOCKET, SO_REUSEADDR, reinterpret_cast<char*>(&optval),
+             sizeof optval);
+#endif
+
+  int result = bind(m_lsd, reinterpret_cast<struct sockaddr*>(&address),
+                    sizeof(address));
+  if (result != 0) {
+    WPI_ERROR(m_logger, "bind() to port {} failed: {}", m_port,
+              SocketStrerror());
+    return result;
+  }
+
+  result = listen(m_lsd, 5);
+  if (result != 0) {
+    WPI_ERROR(m_logger, "listen() on port {} failed: {}", m_port,
+              SocketStrerror());
+    return result;
+  }
+  m_listening = true;
+  return result;
+}
+
+void TCPAcceptor::shutdown() {
+  m_shutdown = true;
+#ifdef _WIN32
+  ::shutdown(m_lsd, SD_BOTH);
+
+  // this is ugly, but the easiest way to do this
+  // force wakeup of accept() with a non-blocking connect to ourselves
+  struct sockaddr_in address;
+
+  std::memset(&address, 0, sizeof(address));
+  address.sin_family = PF_INET;
+  SmallString<128> addr_copy;
+  if (m_address.size() > 0)
+    addr_copy = m_address;
+  else
+    addr_copy = "127.0.0.1";
+  addr_copy.push_back('\0');
+  int size = sizeof(address);
+  if (WSAStringToAddress(addr_copy.data(), PF_INET, nullptr,
+                         (struct sockaddr*)&address, &size) != 0)
+    return;
+  address.sin_port = htons(m_port);
+
+  int result = -1, sd = socket(AF_INET, SOCK_STREAM, 0);
+  if (sd < 0)
+    return;
+
+  // Set socket to non-blocking
+  u_long mode = 1;
+  ioctlsocket(sd, FIONBIO, &mode);
+
+  // Try to connect
+  ::connect(sd, (struct sockaddr*)&address, sizeof(address));
+
+  // Close
+  ::closesocket(sd);
+
+#else
+  ::shutdown(m_lsd, SHUT_RDWR);
+  int nullfd = ::open("/dev/null", O_RDONLY);
+  if (nullfd >= 0) {
+    ::dup2(nullfd, m_lsd);
+    ::close(nullfd);
+  }
+#endif
+}
+
+std::unique_ptr<NetworkStream> TCPAcceptor::accept() {
+  if (!m_listening || m_shutdown) {
+    return nullptr;
+  }
+
+  struct sockaddr_in address;
+#ifdef _WIN32
+  int len = sizeof(address);
+#else
+  socklen_t len = sizeof(address);
+#endif
+  std::memset(&address, 0, sizeof(address));
+  int sd = ::accept(m_lsd, reinterpret_cast<struct sockaddr*>(&address), &len);
+  if (sd < 0) {
+    if (!m_shutdown) {
+      WPI_ERROR(m_logger, "accept() on port {} failed: {}", m_port,
+                SocketStrerror());
+    }
+    return nullptr;
+  }
+  if (m_shutdown) {
+#ifdef _WIN32
+    closesocket(sd);
+#else
+    close(sd);
+#endif
+    return nullptr;
+  }
+  return std::unique_ptr<NetworkStream>(new TCPStream(sd, &address));
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/tcpsockets/cpp/TCPConnector.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/tcpsockets/cpp/TCPConnector.cpp
new file mode 100644
index 0000000..52b9c98
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/tcpsockets/cpp/TCPConnector.cpp
@@ -0,0 +1,219 @@
+/*
+   TCPConnector.h
+
+   TCPConnector class definition. TCPConnector provides methods to actively
+   establish TCP/IP connections with a server.
+
+   ------------------------------------------
+
+   Copyright (c) 2013 [Vic Hargrave - http://vichargrave.com]
+
+   Licensed under the Apache License, Version 2.0 (the "License");
+   you may not use this file except in compliance with the License.
+   You may obtain a copy of the License at
+
+       http://www.apache.org/licenses/LICENSE-2.0
+
+   Unless required by applicable law or agreed to in writing, software
+   distributed under the License is distributed on an "AS IS" BASIS,
+   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+   See the License for the specific language governing permissions and
+   limitations under the License
+*/
+
+#include "wpinet/TCPConnector.h"
+
+#include <fcntl.h>
+
+#include <cerrno>
+#include <cstdio>
+#include <cstring>
+
+#ifdef _WIN32
+#include <WS2tcpip.h>
+#include <WinSock2.h>
+#else
+#include <arpa/inet.h>
+#include <netdb.h>
+#include <netinet/in.h>
+#include <sys/select.h>
+#include <unistd.h>
+#endif
+
+#include <wpi/Logger.h>
+#include <wpi/SmallString.h>
+
+#include "wpinet/SocketError.h"
+#include "wpinet/TCPStream.h"
+
+using namespace wpi;
+
+static int ResolveHostName(const char* hostname, struct in_addr* addr) {
+  struct addrinfo hints;
+  struct addrinfo* res;
+
+  hints.ai_flags = 0;
+  hints.ai_family = AF_INET;
+  hints.ai_socktype = SOCK_STREAM;
+  hints.ai_protocol = 0;
+  hints.ai_addrlen = 0;
+  hints.ai_addr = nullptr;
+  hints.ai_canonname = nullptr;
+  hints.ai_next = nullptr;
+  int result = getaddrinfo(hostname, nullptr, &hints, &res);
+  if (result == 0) {
+    std::memcpy(
+        addr, &(reinterpret_cast<struct sockaddr_in*>(res->ai_addr)->sin_addr),
+        sizeof(struct in_addr));
+    freeaddrinfo(res);
+  }
+  return result;
+}
+
+std::unique_ptr<NetworkStream> TCPConnector::connect(const char* server,
+                                                     int port, Logger& logger,
+                                                     int timeout) {
+#ifdef _WIN32
+  struct WSAHelper {
+    WSAHelper() {
+      WSAData wsaData;
+      WORD wVersionRequested = MAKEWORD(2, 2);
+      WSAStartup(wVersionRequested, &wsaData);
+    }
+    ~WSAHelper() { WSACleanup(); }
+  };
+  static WSAHelper helper;
+#endif
+  struct sockaddr_in address;
+
+  std::memset(&address, 0, sizeof(address));
+  address.sin_family = AF_INET;
+  if (ResolveHostName(server, &(address.sin_addr)) != 0) {
+#ifdef _WIN32
+    SmallString<128> addr_copy(server);
+    addr_copy.push_back('\0');
+    int res = InetPton(PF_INET, addr_copy.data(), &(address.sin_addr));
+#else
+    int res = inet_pton(PF_INET, server, &(address.sin_addr));
+#endif
+    if (res != 1) {
+      WPI_ERROR(logger, "could not resolve {} address", server);
+      return nullptr;
+    }
+  }
+  address.sin_port = htons(port);
+
+  if (timeout == 0) {
+    int sd = socket(AF_INET, SOCK_STREAM, 0);
+    if (sd < 0) {
+      WPI_ERROR(logger, "could not create socket");
+      return nullptr;
+    }
+    if (::connect(sd, reinterpret_cast<struct sockaddr*>(&address),
+                  sizeof(address)) != 0) {
+      WPI_ERROR(logger, "connect() to {} port {} failed: {}", server, port,
+                SocketStrerror());
+#ifdef _WIN32
+      closesocket(sd);
+#else
+      ::close(sd);
+#endif
+      return nullptr;
+    }
+    return std::unique_ptr<NetworkStream>(new TCPStream(sd, &address));
+  }
+
+  fd_set sdset;
+  struct timeval tv;
+  socklen_t len;
+  int result = -1, valopt, sd = socket(AF_INET, SOCK_STREAM, 0);
+  if (sd < 0) {
+    WPI_ERROR(logger, "could not create socket");
+    return nullptr;
+  }
+
+// Set socket to non-blocking
+#ifdef _WIN32
+  u_long mode = 1;
+  if (ioctlsocket(sd, FIONBIO, &mode) == SOCKET_ERROR)
+    WPI_WARNING(logger, "could not set socket to non-blocking: {}",
+                SocketStrerror());
+#else
+  int arg;
+  arg = fcntl(sd, F_GETFL, nullptr);
+  if (arg < 0) {
+    WPI_WARNING(logger, "could not set socket to non-blocking: {}",
+                SocketStrerror());
+  } else {
+    arg |= O_NONBLOCK;
+    if (fcntl(sd, F_SETFL, arg) < 0) {
+      WPI_WARNING(logger, "could not set socket to non-blocking: {}",
+                  SocketStrerror());
+    }
+  }
+#endif
+
+  // Connect with time limit
+  if ((result = ::connect(sd, reinterpret_cast<struct sockaddr*>(&address),
+                          sizeof(address))) < 0) {
+    int my_errno = SocketErrno();
+#ifdef _WIN32
+    if (my_errno == WSAEWOULDBLOCK || my_errno == WSAEINPROGRESS) {
+#else
+    if (my_errno == EWOULDBLOCK || my_errno == EINPROGRESS) {
+#endif
+      tv.tv_sec = timeout;
+      tv.tv_usec = 0;
+      FD_ZERO(&sdset);
+      FD_SET(sd, &sdset);
+      if (select(sd + 1, nullptr, &sdset, nullptr, &tv) > 0) {
+        len = sizeof(int);
+        getsockopt(sd, SOL_SOCKET, SO_ERROR, reinterpret_cast<char*>(&valopt),
+                   &len);
+        if (valopt) {
+          WPI_ERROR(logger, "select() to {} port {} error {} - {}", server,
+                    port, valopt, SocketStrerror(valopt));
+        } else {
+          // connection established
+          result = 0;
+        }
+      } else {
+        WPI_INFO(logger, "connect() to {} port {} timed out", server, port);
+      }
+    } else {
+      WPI_ERROR(logger, "connect() to {} port {} error {} - {}", server, port,
+                SocketErrno(), SocketStrerror());
+    }
+  }
+
+// Return socket to blocking mode
+#ifdef _WIN32
+  mode = 0;
+  if (ioctlsocket(sd, FIONBIO, &mode) == SOCKET_ERROR)
+    WPI_WARNING(logger, "could not set socket to blocking: {}",
+                SocketStrerror());
+#else
+  arg = fcntl(sd, F_GETFL, nullptr);
+  if (arg < 0) {
+    WPI_WARNING(logger, "could not set socket to blocking: {}",
+                SocketStrerror());
+  } else {
+    arg &= (~O_NONBLOCK);
+    if (fcntl(sd, F_SETFL, arg) < 0) {
+      WPI_WARNING(logger, "could not set socket to blocking: {}",
+                  SocketStrerror());
+    }
+  }
+#endif
+
+  // Create stream object if connected, close if not.
+  if (result == -1) {
+#ifdef _WIN32
+    closesocket(sd);
+#else
+    ::close(sd);
+#endif
+    return nullptr;
+  }
+  return std::unique_ptr<NetworkStream>(new TCPStream(sd, &address));
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/tcpsockets/cpp/TCPConnector_parallel.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/tcpsockets/cpp/TCPConnector_parallel.cpp
new file mode 100644
index 0000000..1d979cb
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/tcpsockets/cpp/TCPConnector_parallel.cpp
@@ -0,0 +1,131 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/TCPConnector.h"  // NOLINT(build/include_order)
+
+#include <atomic>
+#include <chrono>
+#include <thread>
+#include <tuple>
+
+#include <wpi/SmallSet.h>
+#include <wpi/condition_variable.h>
+#include <wpi/mutex.h>
+
+using namespace wpi;
+
+// MSVC < 1900 doesn't have support for thread_local
+#if !defined(_MSC_VER) || _MSC_VER >= 1900
+// clang check for availability of thread_local
+#if !defined(__has_feature) || __has_feature(cxx_thread_local)
+#define HAVE_THREAD_LOCAL
+#endif
+#endif
+
+std::unique_ptr<NetworkStream> TCPConnector::connect_parallel(
+    std::span<const std::pair<const char*, int>> servers, Logger& logger,
+    int timeout) {
+  if (servers.empty()) {
+    return nullptr;
+  }
+
+  // structure to make sure we don't start duplicate workers
+  struct GlobalState {
+    wpi::mutex mtx;
+#ifdef HAVE_THREAD_LOCAL
+    SmallSet<std::pair<std::string, int>, 16> active;
+#else
+    SmallSet<std::tuple<std::thread::id, std::string, int>, 16> active;
+#endif
+  };
+#ifdef HAVE_THREAD_LOCAL
+  thread_local auto global = std::make_shared<GlobalState>();
+#else
+  static auto global = std::make_shared<GlobalState>();
+  auto this_id = std::this_thread::get_id();
+#endif
+  auto local = global;  // copy to an automatic variable for lambda capture
+
+  // structure shared between threads and this function
+  struct Result {
+    wpi::mutex mtx;
+    wpi::condition_variable cv;
+    std::unique_ptr<NetworkStream> stream;
+    std::atomic<unsigned int> count{0};
+    std::atomic<bool> done{false};
+  };
+  auto result = std::make_shared<Result>();
+
+  // start worker threads; this is I/O bound so we don't limit to # of procs
+  Logger* plogger = &logger;
+  unsigned int num_workers = 0;
+  for (const auto& server : servers) {
+    std::pair<std::string, int> server_copy{std::string{server.first},
+                                            server.second};
+#ifdef HAVE_THREAD_LOCAL
+    const auto& active_tracker = server_copy;
+#else
+    std::tuple<std::thread::id, std::string, int> active_tracker{
+        this_id, server_copy.first, server_copy.second};
+#endif
+
+    // don't start a new worker if we had a previously still-active connection
+    // attempt to the same server
+    {
+      std::scoped_lock lock(local->mtx);
+      if (local->active.count(active_tracker) > 0) {
+        continue;  // already in set
+      }
+    }
+
+    ++num_workers;
+
+    // start the worker
+    std::thread([=] {
+      if (!result->done) {
+        // add to global state
+        {
+          std::scoped_lock lock(local->mtx);
+          local->active.insert(active_tracker);
+        }
+
+        // try to connect
+        auto stream = connect(server_copy.first.c_str(), server_copy.second,
+                              *plogger, timeout);
+
+        // remove from global state
+        {
+          std::scoped_lock lock(local->mtx);
+          local->active.erase(active_tracker);
+        }
+
+        // successful connection
+        if (stream) {
+          std::scoped_lock lock(result->mtx);
+          if (!result->done.exchange(true)) {
+            result->stream = std::move(stream);
+          }
+        }
+      }
+      ++result->count;
+      result->cv.notify_all();
+    }).detach();
+  }
+
+  // wait for a result, timeout, or all finished
+  std::unique_lock lock(result->mtx);
+  if (timeout == 0) {
+    result->cv.wait(
+        lock, [&] { return result->stream || result->count >= num_workers; });
+  } else {
+    auto timeout_time =
+        std::chrono::steady_clock::now() + std::chrono::seconds(timeout);
+    result->cv.wait_until(lock, timeout_time, [&] {
+      return result->stream || result->count >= num_workers;
+    });
+  }
+
+  // no need to wait for remaining worker threads; shared_ptr will clean up
+  return std::move(result->stream);
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/tcpsockets/cpp/TCPStream.cpp b/third_party/allwpilib/wpinet/src/main/native/thirdparty/tcpsockets/cpp/TCPStream.cpp
new file mode 100644
index 0000000..920f7b1
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/tcpsockets/cpp/TCPStream.cpp
@@ -0,0 +1,230 @@
+/*
+   TCPStream.h
+
+   TCPStream class definition. TCPStream provides methods to transfer
+   data between peers over a TCP/IP connection.
+
+   ------------------------------------------
+
+   Copyright (c) 2013 [Vic Hargrave - http://vichargrave.com]
+
+   Licensed under the Apache License, Version 2.0 (the "License");
+   you may not use this file except in compliance with the License.
+   You may obtain a copy of the License at
+
+       http://www.apache.org/licenses/LICENSE-2.0
+
+   Unless required by applicable law or agreed to in writing, software
+   distributed under the License is distributed on an "AS IS" BASIS,
+   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+   See the License for the specific language governing permissions and
+   limitations under the License.
+*/
+
+#include "wpinet/TCPStream.h"
+
+#include <fcntl.h>
+
+#ifdef _WIN32
+#include <winsock2.h>
+#include <ws2tcpip.h>
+#else
+#include <arpa/inet.h>
+#include <netinet/tcp.h>
+#include <unistd.h>
+#endif
+
+#include <cerrno>
+
+using namespace wpi;
+
+TCPStream::TCPStream(int sd, sockaddr_in* address)
+    : m_sd(sd), m_blocking(true) {
+  char ip[50];
+#ifdef _WIN32
+  InetNtop(PF_INET, &(address->sin_addr.s_addr), ip, sizeof(ip) - 1);
+#else
+  inet_ntop(PF_INET, reinterpret_cast<in_addr*>(&(address->sin_addr.s_addr)),
+            ip, sizeof(ip) - 1);
+#ifdef SO_NOSIGPIPE
+  // disable SIGPIPE on Mac OS X
+  int set = 1;
+  setsockopt(m_sd, SOL_SOCKET, SO_NOSIGPIPE, reinterpret_cast<char*>(&set),
+             sizeof set);
+#endif
+#endif
+  m_peerIP = ip;
+  m_peerPort = ntohs(address->sin_port);
+}
+
+TCPStream::~TCPStream() {
+  close();
+}
+
+size_t TCPStream::send(const char* buffer, size_t len, Error* err) {
+  if (m_sd < 0) {
+    *err = kConnectionClosed;
+    return 0;
+  }
+#ifdef _WIN32
+  WSABUF wsaBuf;
+  wsaBuf.buf = const_cast<char*>(buffer);
+  wsaBuf.len = (ULONG)len;
+  DWORD rv;
+  bool result = true;
+  while (WSASend(m_sd, &wsaBuf, 1, &rv, 0, nullptr, nullptr) == SOCKET_ERROR) {
+    if (WSAGetLastError() != WSAEWOULDBLOCK) {
+      result = false;
+      break;
+    }
+    if (!m_blocking) {
+      *err = kWouldBlock;
+      return 0;
+    }
+    Sleep(1);
+  }
+  if (!result) {
+    char Buffer[128];
+#ifdef _MSC_VER
+    sprintf_s(Buffer, "Send() failed: WSA error=%d\n", WSAGetLastError());
+#else
+    std::snprintf(Buffer, sizeof(Buffer), "Send() failed: WSA error=%d\n",
+                  WSAGetLastError());
+#endif
+    OutputDebugStringA(Buffer);
+    *err = kConnectionReset;
+    return 0;
+  }
+#else
+#ifdef MSG_NOSIGNAL
+  // disable SIGPIPE on Linux
+  ssize_t rv = ::send(m_sd, buffer, len, MSG_NOSIGNAL);
+#else
+  ssize_t rv = ::send(m_sd, buffer, len, 0);
+#endif
+  if (rv < 0) {
+    if (!m_blocking && (errno == EAGAIN || errno == EWOULDBLOCK)) {
+      *err = kWouldBlock;
+    } else {
+      *err = kConnectionReset;
+    }
+    return 0;
+  }
+#endif
+  return static_cast<size_t>(rv);
+}
+
+size_t TCPStream::receive(char* buffer, size_t len, Error* err, int timeout) {
+  if (m_sd < 0) {
+    *err = kConnectionClosed;
+    return 0;
+  }
+#ifdef _WIN32
+  int rv;
+#else
+  ssize_t rv;
+#endif
+  if (timeout <= 0) {
+#ifdef _WIN32
+    rv = recv(m_sd, buffer, len, 0);
+#else
+    rv = read(m_sd, buffer, len);
+#endif
+  } else if (WaitForReadEvent(timeout)) {
+#ifdef _WIN32
+    rv = recv(m_sd, buffer, len, 0);
+#else
+    rv = read(m_sd, buffer, len);
+#endif
+  } else {
+    *err = kConnectionTimedOut;
+    return 0;
+  }
+  if (rv < 0) {
+#ifdef _WIN32
+    if (!m_blocking && WSAGetLastError() == WSAEWOULDBLOCK) {
+#else
+    if (!m_blocking && (errno == EAGAIN || errno == EWOULDBLOCK)) {
+#endif
+      *err = kWouldBlock;
+    } else {
+      *err = kConnectionReset;
+    }
+    return 0;
+  }
+  return static_cast<size_t>(rv);
+}
+
+void TCPStream::close() {
+  if (m_sd >= 0) {
+#ifdef _WIN32
+    ::shutdown(m_sd, SD_BOTH);
+    closesocket(m_sd);
+#else
+    ::shutdown(m_sd, SHUT_RDWR);
+    ::close(m_sd);
+#endif
+  }
+  m_sd = -1;
+}
+
+std::string_view TCPStream::getPeerIP() const {
+  return m_peerIP;
+}
+
+int TCPStream::getPeerPort() const {
+  return m_peerPort;
+}
+
+void TCPStream::setNoDelay() {
+  if (m_sd < 0) {
+    return;
+  }
+  int optval = 1;
+  setsockopt(m_sd, IPPROTO_TCP, TCP_NODELAY, reinterpret_cast<char*>(&optval),
+             sizeof optval);
+}
+
+bool TCPStream::setBlocking(bool enabled) {
+  if (m_sd < 0) {
+    return true;  // silently accept
+  }
+#ifdef _WIN32
+  u_long mode = enabled ? 0 : 1;
+  if (ioctlsocket(m_sd, FIONBIO, &mode) == SOCKET_ERROR) {
+    return false;
+  }
+#else
+  int flags = fcntl(m_sd, F_GETFL, nullptr);
+  if (flags < 0) {
+    return false;
+  }
+  if (enabled) {
+    flags &= ~O_NONBLOCK;
+  } else {
+    flags |= O_NONBLOCK;
+  }
+  if (fcntl(m_sd, F_SETFL, flags) < 0) {
+    return false;
+  }
+#endif
+  return true;
+}
+
+int TCPStream::getNativeHandle() const {
+  return m_sd;
+}
+
+bool TCPStream::WaitForReadEvent(int timeout) {
+  fd_set sdset;
+  struct timeval tv;
+
+  tv.tv_sec = timeout;
+  tv.tv_usec = 0;
+  FD_ZERO(&sdset);
+  FD_SET(m_sd, &sdset);
+  if (select(m_sd + 1, &sdset, nullptr, nullptr, &tv) > 0) {
+    return true;
+  }
+  return false;
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/tcpsockets/include/wpinet/TCPAcceptor.h b/third_party/allwpilib/wpinet/src/main/native/thirdparty/tcpsockets/include/wpinet/TCPAcceptor.h
new file mode 100644
index 0000000..5ba7ce5
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/tcpsockets/include/wpinet/TCPAcceptor.h
@@ -0,0 +1,58 @@
+/*
+   TCPAcceptor.h
+
+   TCPAcceptor class interface. TCPAcceptor provides methods to passively
+   establish TCP/IP connections with clients.
+
+   ------------------------------------------
+
+   Copyright (c) 2013 [Vic Hargrave - http://vichargrave.com]
+
+   Licensed under the Apache License, Version 2.0 (the "License");
+   you may not use this file except in compliance with the License.
+   You may obtain a copy of the License at
+
+       http://www.apache.org/licenses/LICENSE-2.0
+
+   Unless required by applicable law or agreed to in writing, software
+   distributed under the License is distributed on an "AS IS" BASIS,
+   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+   See the License for the specific language governing permissions and
+   limitations under the License.
+*/
+
+#ifndef WPINET_TCPACCEPTOR_H_
+#define WPINET_TCPACCEPTOR_H_
+
+#include <atomic>
+#include <memory>
+#include <string>
+#include <string_view>
+
+#include "wpinet/NetworkAcceptor.h"
+#include "wpinet/TCPStream.h"
+
+namespace wpi {
+
+class Logger;
+
+class TCPAcceptor : public NetworkAcceptor {
+  int m_lsd;
+  int m_port;
+  std::string m_address;
+  bool m_listening;
+  std::atomic_bool m_shutdown;
+  Logger& m_logger;
+
+ public:
+  TCPAcceptor(int port, std::string_view address, Logger& logger);
+  ~TCPAcceptor() override;
+
+  int start() override;
+  void shutdown() final;
+  std::unique_ptr<NetworkStream> accept() override;
+};
+
+}  // namespace wpi
+
+#endif  // WPINET_TCPACCEPTOR_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/tcpsockets/include/wpinet/TCPConnector.h b/third_party/allwpilib/wpinet/src/main/native/thirdparty/tcpsockets/include/wpinet/TCPConnector.h
new file mode 100644
index 0000000..d9c3ad9
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/tcpsockets/include/wpinet/TCPConnector.h
@@ -0,0 +1,49 @@
+/*
+   TCPConnector.h
+
+   TCPConnector class interface. TCPConnector provides methods to actively
+   establish TCP/IP connections with a server.
+
+   ------------------------------------------
+
+   Copyright (c) 2013 [Vic Hargrave - http://vichargrave.com]
+
+   Licensed under the Apache License, Version 2.0 (the "License");
+   you may not use this file except in compliance with the License.
+   You may obtain a copy of the License at
+
+       http://www.apache.org/licenses/LICENSE-2.0
+
+   Unless required by applicable law or agreed to in writing, software
+   distributed under the License is distributed on an "AS IS" BASIS,
+   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+   See the License for the specific language governing permissions and
+   limitations under the License
+*/
+
+#ifndef WPINET_TCPCONNECTOR_H_
+#define WPINET_TCPCONNECTOR_H_
+
+#include <memory>
+#include <span>
+#include <utility>
+
+#include "wpinet/NetworkStream.h"
+
+namespace wpi {
+
+class Logger;
+
+class TCPConnector {
+ public:
+  static std::unique_ptr<NetworkStream> connect(const char* server, int port,
+                                                Logger& logger,
+                                                int timeout = 0);
+  static std::unique_ptr<NetworkStream> connect_parallel(
+      std::span<const std::pair<const char*, int>> servers, Logger& logger,
+      int timeout = 0);
+};
+
+}  // namespace wpi
+
+#endif  // WPINET_TCPCONNECTOR_H_
diff --git a/third_party/allwpilib/wpinet/src/main/native/thirdparty/tcpsockets/include/wpinet/TCPStream.h b/third_party/allwpilib/wpinet/src/main/native/thirdparty/tcpsockets/include/wpinet/TCPStream.h
new file mode 100644
index 0000000..f54da48
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/thirdparty/tcpsockets/include/wpinet/TCPStream.h
@@ -0,0 +1,72 @@
+/*
+   TCPStream.h
+
+   TCPStream class interface. TCPStream provides methods to transfer
+   data between peers over a TCP/IP connection.
+
+   ------------------------------------------
+
+   Copyright (c) 2013 [Vic Hargrave - http://vichargrave.com]
+
+   Licensed under the Apache License, Version 2.0 (the "License");
+   you may not use this file except in compliance with the License.
+   You may obtain a copy of the License at
+
+       http://www.apache.org/licenses/LICENSE-2.0
+
+   Unless required by applicable law or agreed to in writing, software
+   distributed under the License is distributed on an "AS IS" BASIS,
+   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+   See the License for the specific language governing permissions and
+   limitations under the License.
+*/
+
+#ifndef WPINET_TCPSTREAM_H_
+#define WPINET_TCPSTREAM_H_
+
+#include <cstddef>
+#include <string>
+#include <string_view>
+
+#include "wpinet/NetworkStream.h"
+
+struct sockaddr_in;
+
+namespace wpi {
+
+class TCPStream : public NetworkStream {
+  int m_sd;
+  std::string m_peerIP;
+  int m_peerPort;
+  bool m_blocking;
+
+ public:
+  friend class TCPAcceptor;
+  friend class TCPConnector;
+
+  ~TCPStream() override;
+
+  size_t send(const char* buffer, size_t len, Error* err) override;
+  size_t receive(char* buffer, size_t len, Error* err,
+                 int timeout = 0) override;
+  void close() final;
+
+  std::string_view getPeerIP() const override;
+  int getPeerPort() const override;
+  void setNoDelay() override;
+  bool setBlocking(bool enabled) override;
+  int getNativeHandle() const override;
+
+  TCPStream(const TCPStream& stream) = delete;
+  TCPStream& operator=(const TCPStream&) = delete;
+
+ private:
+  bool WaitForReadEvent(int timeout);
+
+  TCPStream(int sd, sockaddr_in* address);
+  TCPStream() = delete;
+};
+
+}  // namespace wpi
+
+#endif  // WPINET_TCPSTREAM_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/windows/DynamicDns.cpp b/third_party/allwpilib/wpinet/src/main/native/windows/DynamicDns.cpp
similarity index 100%
rename from third_party/allwpilib/wpiutil/src/main/native/windows/DynamicDns.cpp
rename to third_party/allwpilib/wpinet/src/main/native/windows/DynamicDns.cpp
diff --git a/third_party/allwpilib/wpiutil/src/main/native/windows/DynamicDns.h b/third_party/allwpilib/wpinet/src/main/native/windows/DynamicDns.h
similarity index 100%
rename from third_party/allwpilib/wpiutil/src/main/native/windows/DynamicDns.h
rename to third_party/allwpilib/wpinet/src/main/native/windows/DynamicDns.h
diff --git a/third_party/allwpilib/wpinet/src/main/native/windows/MulticastServiceAnnouncer.cpp b/third_party/allwpilib/wpinet/src/main/native/windows/MulticastServiceAnnouncer.cpp
new file mode 100644
index 0000000..c1ed58d
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/windows/MulticastServiceAnnouncer.cpp
@@ -0,0 +1,219 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef UNICODE
+#define UNICODE
+#endif
+
+#include "wpinet/MulticastServiceAnnouncer.h"
+
+#include <string>
+#include <vector>
+
+#include <wpi/ConvertUTF.h>
+#include <wpi/SmallString.h>
+#include <wpi/SmallVector.h>
+#include <wpi/StringExtras.h>
+
+#include "DynamicDns.h"
+#include "wpinet/hostname.h"
+
+using namespace wpi;
+
+struct ImplBase {
+  wpi::DynamicDns& dynamicDns = wpi::DynamicDns::GetDynamicDns();
+  PDNS_SERVICE_INSTANCE serviceInstance = nullptr;
+  HANDLE event = nullptr;
+};
+
+struct MulticastServiceAnnouncer::Impl : ImplBase {
+  std::wstring serviceType;
+  std::wstring serviceInstanceName;
+  std::wstring hostName;
+  int port;
+  std::vector<std::wstring> keys;
+  std::vector<PCWSTR> keyPtrs;
+  std::vector<std::wstring> values;
+  std::vector<PCWSTR> valuePtrs;
+
+  template <typename T>
+  Impl(std::string_view serviceName, std::string_view serviceType, int port,
+       std::span<const std::pair<T, T>> txt);
+};
+
+template <typename T>
+MulticastServiceAnnouncer::Impl::Impl(std::string_view serviceName,
+                                      std::string_view serviceType, int port,
+                                      std::span<const std::pair<T, T>> txt) {
+  if (!dynamicDns.CanDnsAnnounce) {
+    return;
+  }
+
+  this->port = port;
+
+  wpi::SmallVector<wchar_t, 128> wideStorage;
+  std::string hostName = wpi::GetHostname() + ".local";
+
+  for (auto&& i : txt) {
+    wideStorage.clear();
+    wpi::sys::windows::UTF8ToUTF16(i.first, wideStorage);
+    this->keys.emplace_back(
+        std::wstring{wideStorage.data(), wideStorage.size()});
+    wideStorage.clear();
+    wpi::sys::windows::UTF8ToUTF16(i.second, wideStorage);
+    this->values.emplace_back(
+        std::wstring{wideStorage.data(), wideStorage.size()});
+  }
+
+  for (size_t i = 0; i < this->keys.size(); i++) {
+    this->keyPtrs.emplace_back(this->keys[i].c_str());
+    this->valuePtrs.emplace_back(this->values[i].c_str());
+  }
+
+  wpi::SmallString<128> storage;
+
+  wideStorage.clear();
+  wpi::sys::windows::UTF8ToUTF16(hostName, wideStorage);
+
+  this->hostName = std::wstring{wideStorage.data(), wideStorage.size()};
+
+  wideStorage.clear();
+  if (wpi::ends_with_lower(serviceType, ".local")) {
+    wpi::sys::windows::UTF8ToUTF16(serviceType, wideStorage);
+  } else {
+    storage.clear();
+    storage.append(serviceType);
+    storage.append(".local");
+    wpi::sys::windows::UTF8ToUTF16(storage.str(), wideStorage);
+  }
+  this->serviceType = std::wstring{wideStorage.data(), wideStorage.size()};
+
+  wideStorage.clear();
+  storage.clear();
+  storage.append(serviceName);
+  storage.append(".");
+  storage.append(serviceType);
+  if (!wpi::ends_with_lower(serviceType, ".local")) {
+    storage.append(".local");
+  }
+
+  wpi::sys::windows::UTF8ToUTF16(storage.str(), wideStorage);
+  this->serviceInstanceName =
+      std::wstring{wideStorage.data(), wideStorage.size()};
+}
+
+MulticastServiceAnnouncer::MulticastServiceAnnouncer(
+    std::string_view serviceName, std::string_view serviceType, int port) {
+  std::span<const std::pair<std::string_view, std::string_view>> txt;
+  pImpl = std::make_unique<Impl>(serviceName, serviceType, port, txt);
+}
+
+MulticastServiceAnnouncer::MulticastServiceAnnouncer(
+    std::string_view serviceName, std::string_view serviceType, int port,
+    std::span<const std::pair<std::string, std::string>> txt) {
+  pImpl = std::make_unique<Impl>(serviceName, serviceType, port, txt);
+}
+
+MulticastServiceAnnouncer::MulticastServiceAnnouncer(
+    std::string_view serviceName, std::string_view serviceType, int port,
+    std::span<const std::pair<std::string_view, std::string_view>> txt) {
+  pImpl = std::make_unique<Impl>(serviceName, serviceType, port, txt);
+}
+
+MulticastServiceAnnouncer::~MulticastServiceAnnouncer() noexcept {
+  Stop();
+}
+
+bool MulticastServiceAnnouncer::HasImplementation() const {
+  return pImpl->dynamicDns.CanDnsAnnounce;
+}
+
+static void WINAPI DnsServiceRegisterCallback(DWORD /*Status*/,
+                                              PVOID pQueryContext,
+                                              PDNS_SERVICE_INSTANCE pInstance) {
+  ImplBase* impl = reinterpret_cast<ImplBase*>(pQueryContext);
+
+  impl->serviceInstance = pInstance;
+
+  SetEvent(impl->event);
+}
+
+void MulticastServiceAnnouncer::Start() {
+  if (pImpl->serviceInstance) {
+    return;
+  }
+
+  if (!pImpl->dynamicDns.CanDnsAnnounce) {
+    return;
+  }
+
+  PDNS_SERVICE_INSTANCE serviceInst =
+      pImpl->dynamicDns.DnsServiceConstructInstancePtr(
+          pImpl->serviceInstanceName.c_str(), pImpl->hostName.c_str(), nullptr,
+          nullptr, pImpl->port, 0, 0, static_cast<DWORD>(pImpl->keyPtrs.size()),
+          pImpl->keyPtrs.data(), pImpl->valuePtrs.data());
+  if (serviceInst == nullptr) {
+    return;
+  }
+
+  DNS_SERVICE_REGISTER_REQUEST registerRequest = {};
+  registerRequest.pQueryContext = static_cast<ImplBase*>(pImpl.get());
+  registerRequest.pRegisterCompletionCallback = DnsServiceRegisterCallback;
+  registerRequest.Version = DNS_QUERY_REQUEST_VERSION1;
+  registerRequest.unicastEnabled = false;
+  registerRequest.pServiceInstance = serviceInst;
+  registerRequest.InterfaceIndex = 0;
+
+  pImpl->event = CreateEvent(NULL, true, false, NULL);
+
+  if (pImpl->dynamicDns.DnsServiceRegisterPtr(&registerRequest, nullptr) ==
+      DNS_REQUEST_PENDING) {
+    WaitForSingleObject(pImpl->event, INFINITE);
+  }
+
+  pImpl->dynamicDns.DnsServiceFreeInstancePtr(serviceInst);
+  CloseHandle(pImpl->event);
+  pImpl->event = nullptr;
+}
+
+static void WINAPI DnsServiceDeRegisterCallback(
+    DWORD /*Status*/, PVOID pQueryContext, PDNS_SERVICE_INSTANCE pInstance) {
+  ImplBase* impl = reinterpret_cast<ImplBase*>(pQueryContext);
+
+  if (pInstance != nullptr) {
+    impl->dynamicDns.DnsServiceFreeInstancePtr(pInstance);
+    pInstance = nullptr;
+  }
+
+  SetEvent(impl->event);
+}
+
+void MulticastServiceAnnouncer::Stop() {
+  if (!pImpl->dynamicDns.CanDnsAnnounce) {
+    return;
+  }
+
+  if (pImpl->serviceInstance == nullptr) {
+    return;
+  }
+
+  pImpl->event = CreateEvent(NULL, true, false, NULL);
+  DNS_SERVICE_REGISTER_REQUEST registerRequest = {};
+  registerRequest.pQueryContext = static_cast<ImplBase*>(pImpl.get());
+  registerRequest.pRegisterCompletionCallback = DnsServiceDeRegisterCallback;
+  registerRequest.Version = DNS_QUERY_REQUEST_VERSION1;
+  registerRequest.unicastEnabled = false;
+  registerRequest.pServiceInstance = pImpl->serviceInstance;
+  registerRequest.InterfaceIndex = 0;
+
+  if (pImpl->dynamicDns.DnsServiceDeRegisterPtr(&registerRequest, nullptr) ==
+      DNS_REQUEST_PENDING) {
+    WaitForSingleObject(pImpl->event, INFINITE);
+  }
+
+  pImpl->dynamicDns.DnsServiceFreeInstancePtr(pImpl->serviceInstance);
+  pImpl->serviceInstance = nullptr;
+  CloseHandle(pImpl->event);
+  pImpl->event = nullptr;
+}
diff --git a/third_party/allwpilib/wpinet/src/main/native/windows/MulticastServiceResolver.cpp b/third_party/allwpilib/wpinet/src/main/native/windows/MulticastServiceResolver.cpp
new file mode 100644
index 0000000..79fc7b5
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/main/native/windows/MulticastServiceResolver.cpp
@@ -0,0 +1,207 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifndef UNICODE
+#define UNICODE
+#endif
+
+#include "wpinet/MulticastServiceResolver.h"
+
+#include <string>
+
+#include <wpi/ConvertUTF.h>
+#include <wpi/SmallString.h>
+#include <wpi/SmallVector.h>
+#include <wpi/StringExtras.h>
+
+#include "DynamicDns.h"
+
+#pragma comment(lib, "dnsapi")
+
+using namespace wpi;
+
+struct MulticastServiceResolver::Impl {
+  wpi::DynamicDns& dynamicDns = wpi::DynamicDns::GetDynamicDns();
+  std::wstring serviceType;
+  DNS_SERVICE_CANCEL serviceCancel{nullptr};
+
+  MulticastServiceResolver* resolver;
+
+  void onFound(ServiceData&& data) {
+    resolver->PushData(std::forward<ServiceData>(data));
+  }
+};
+
+MulticastServiceResolver::MulticastServiceResolver(
+    std::string_view serviceType) {
+  pImpl = std::make_unique<Impl>();
+  pImpl->resolver = this;
+
+  if (!pImpl->dynamicDns.CanDnsResolve) {
+    return;
+  }
+
+  wpi::SmallVector<wchar_t, 128> wideStorage;
+
+  if (wpi::ends_with_lower(serviceType, ".local")) {
+    wpi::sys::windows::UTF8ToUTF16(serviceType, wideStorage);
+  } else {
+    wpi::SmallString<128> storage;
+    storage.append(serviceType);
+    storage.append(".local");
+    wpi::sys::windows::UTF8ToUTF16(storage.str(), wideStorage);
+  }
+  pImpl->serviceType = std::wstring{wideStorage.data(), wideStorage.size()};
+}
+
+MulticastServiceResolver::~MulticastServiceResolver() noexcept {
+  Stop();
+}
+
+bool MulticastServiceResolver::HasImplementation() const {
+  return pImpl->dynamicDns.CanDnsResolve;
+}
+
+static _Function_class_(DNS_QUERY_COMPLETION_ROUTINE) VOID WINAPI
+    DnsCompletion(_In_ PVOID pQueryContext,
+                  _Inout_ PDNS_QUERY_RESULT pQueryResults) {
+  MulticastServiceResolver::Impl* impl =
+      reinterpret_cast<MulticastServiceResolver::Impl*>(pQueryContext);
+
+  wpi::SmallVector<DNS_RECORDW*, 4> PtrRecords;
+  wpi::SmallVector<DNS_RECORDW*, 4> SrvRecords;
+  wpi::SmallVector<DNS_RECORDW*, 4> TxtRecords;
+  wpi::SmallVector<DNS_RECORDW*, 4> ARecords;
+
+  {
+    DNS_RECORDW* current = pQueryResults->pQueryRecords;
+    while (current != nullptr) {
+      switch (current->wType) {
+        case DNS_TYPE_PTR:
+          PtrRecords.push_back(current);
+          break;
+        case DNS_TYPE_SRV:
+          SrvRecords.push_back(current);
+          break;
+        case DNS_TYPE_TEXT:
+          TxtRecords.push_back(current);
+          break;
+        case DNS_TYPE_A:
+          ARecords.push_back(current);
+          break;
+      }
+      current = current->pNext;
+    }
+  }
+
+  for (DNS_RECORDW* Ptr : PtrRecords) {
+    if (std::wstring_view{Ptr->pName} != impl->serviceType) {
+      continue;
+    }
+
+    std::wstring_view nameHost = Ptr->Data.Ptr.pNameHost;
+    DNS_RECORDW* foundSrv = nullptr;
+    for (DNS_RECORDW* Srv : SrvRecords) {
+      if (std::wstring_view{Srv->pName} == nameHost) {
+        foundSrv = Srv;
+        break;
+      }
+    }
+
+    if (!foundSrv) {
+      continue;
+    }
+
+    for (DNS_RECORDW* A : ARecords) {
+      if (std::wstring_view{A->pName} ==
+          std::wstring_view{foundSrv->Data.Srv.pNameTarget}) {
+        MulticastServiceResolver::ServiceData data;
+        wpi::SmallString<128> storage;
+        for (DNS_RECORDW* Txt : TxtRecords) {
+          if (std::wstring_view{Txt->pName} == nameHost) {
+            for (DWORD i = 0; i < Txt->Data.Txt.dwStringCount; i++) {
+              std::wstring_view wideView = Txt->Data.TXT.pStringArray[i];
+              size_t splitIndex = wideView.find(L'=');
+              if (splitIndex == wideView.npos) {
+                // Todo make this just do key
+                continue;
+              }
+              storage.clear();
+              std::span<const wpi::UTF16> wideStr{
+                  reinterpret_cast<const wpi::UTF16*>(wideView.data()),
+                  splitIndex};
+              wpi::convertUTF16ToUTF8String(wideStr, storage);
+              auto& pair =
+                  data.txt.emplace_back(std::pair<std::string, std::string>{
+                      std::string{storage}, {}});
+              storage.clear();
+              wideStr = std::span<const wpi::UTF16>{
+                  reinterpret_cast<const wpi::UTF16*>(wideView.data() +
+                                                      splitIndex + 1),
+                  wideView.size() - splitIndex - 1};
+              wpi::convertUTF16ToUTF8String(wideStr, storage);
+              pair.second = std::string{storage};
+            }
+          }
+        }
+
+        storage.clear();
+        std::span<const wpi::UTF16> wideHostName{
+            reinterpret_cast<const wpi::UTF16*>(A->pName), wcslen(A->pName)};
+        wpi::convertUTF16ToUTF8String(wideHostName, storage);
+        storage.append(".");
+
+        data.hostName = std::string{storage};
+        storage.clear();
+
+        int len = nameHost.find(impl->serviceType.c_str());
+        std::span<const wpi::UTF16> wideServiceName{
+            reinterpret_cast<const wpi::UTF16*>(nameHost.data()),
+            nameHost.size()};
+        if (len != nameHost.npos) {
+          wideServiceName = wideServiceName.subspan(0, len - 1);
+        }
+        wpi::convertUTF16ToUTF8String(wideServiceName, storage);
+
+        data.serviceName = std::string{storage};
+        data.port = foundSrv->Data.Srv.wPort;
+        data.ipv4Address = A->Data.A.IpAddress;
+
+        impl->onFound(std::move(data));
+      }
+    }
+  }
+  DnsFree(pQueryResults->pQueryRecords, DNS_FREE_TYPE::DnsFreeRecordList);
+}
+
+void MulticastServiceResolver::Start() {
+  if (pImpl->serviceCancel.reserved != nullptr) {
+    return;
+  }
+
+  if (!pImpl->dynamicDns.CanDnsResolve) {
+    return;
+  }
+
+  DNS_SERVICE_BROWSE_REQUEST request = {};
+  request.InterfaceIndex = 0;
+  request.pQueryContext = pImpl.get();
+  request.QueryName = pImpl->serviceType.c_str();
+  request.Version = 2;
+  request.pBrowseCallbackV2 = DnsCompletion;
+  pImpl->dynamicDns.DnsServiceBrowsePtr(&request, &pImpl->serviceCancel);
+}
+
+void MulticastServiceResolver::Stop() {
+  if (!pImpl->dynamicDns.CanDnsResolve) {
+    return;
+  }
+
+  if (pImpl->serviceCancel.reserved == nullptr) {
+    return;
+  }
+
+  pImpl->dynamicDns.DnsServiceBrowseCancelPtr(&pImpl->serviceCancel);
+  pImpl->serviceCancel.reserved = nullptr;
+}
diff --git a/third_party/allwpilib/wpinet/src/netconsoleServer/native/cpp/main.cpp b/third_party/allwpilib/wpinet/src/netconsoleServer/native/cpp/main.cpp
new file mode 100644
index 0000000..0271e36
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/netconsoleServer/native/cpp/main.cpp
@@ -0,0 +1,280 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#ifdef __APPLE__
+#include <util.h>
+#elif !defined(_WIN32)
+#include <pty.h>
+#endif
+
+#include <cstdio>
+
+#include <fmt/format.h>
+#include <wpi/MathExtras.h>
+#include <wpi/SmallVector.h>
+#include <wpi/StringExtras.h>
+#include <wpi/timestamp.h>
+
+#include "wpinet/raw_uv_ostream.h"
+#include "wpinet/uv/Loop.h"
+#include "wpinet/uv/Pipe.h"
+#include "wpinet/uv/Process.h"
+#include "wpinet/uv/Signal.h"
+#include "wpinet/uv/Tcp.h"
+#include "wpinet/uv/Tty.h"
+#include "wpinet/uv/Udp.h"
+#include "wpinet/uv/util.h"
+
+namespace uv = wpi::uv;
+
+static uint64_t startTime = wpi::Now();
+
+static bool NewlineBuffer(std::string& rem, uv::Buffer& buf, size_t len,
+                          wpi::SmallVectorImpl<uv::Buffer>& bufs, bool tcp,
+                          uint16_t tcpSeq) {
+  // scan for last newline
+  std::string_view str(buf.base, len);
+  size_t idx = str.rfind('\n');
+  if (idx == std::string_view::npos) {
+    // no newline yet, just keep appending to remainder
+    rem += str;
+    return false;
+  }
+
+  // build output
+  wpi::raw_uv_ostream out(bufs, 4096);
+  std::string_view toCopy = wpi::slice(str, 0, idx + 1);
+  if (tcp) {
+    // Header is 2 byte len, 1 byte type, 4 byte timestamp, 2 byte sequence num
+    uint32_t ts = wpi::FloatToBits((wpi::Now() - startTime) * 1.0e-6);
+    uint16_t len = rem.size() + toCopy.size() + 1 + 4 + 2;
+    const uint8_t header[] = {static_cast<uint8_t>((len >> 8) & 0xff),
+                              static_cast<uint8_t>(len & 0xff),
+                              12,
+                              static_cast<uint8_t>((ts >> 24) & 0xff),
+                              static_cast<uint8_t>((ts >> 16) & 0xff),
+                              static_cast<uint8_t>((ts >> 8) & 0xff),
+                              static_cast<uint8_t>(ts & 0xff),
+                              static_cast<uint8_t>((tcpSeq >> 8) & 0xff),
+                              static_cast<uint8_t>(tcpSeq & 0xff)};
+    out << std::span<const uint8_t>(header);
+  }
+  out << rem << toCopy;
+
+  // reset remainder
+  rem = wpi::slice(str, idx + 1, std::string_view::npos);
+  return true;
+}
+
+static void CopyUdp(uv::Stream& in, std::shared_ptr<uv::Udp> out,
+                    bool broadcast) {
+  sockaddr_in addr;
+  if (broadcast) {
+    out->SetBroadcast(true);
+    uv::NameToAddr("0.0.0.0", 6666, &addr);
+  } else {
+    uv::NameToAddr("127.0.0.1", 6666, &addr);
+  }
+
+  in.data.connect(
+      [rem = std::make_shared<std::string>(), outPtr = out.get(), addr](
+          uv::Buffer& buf, size_t len) {
+        // build buffers
+        wpi::SmallVector<uv::Buffer, 4> bufs;
+        if (!NewlineBuffer(*rem, buf, len, bufs, false, 0)) {
+          return;
+        }
+
+        // send output
+        outPtr->Send(addr, bufs, [](auto bufs2, uv::Error) {
+          for (auto buf : bufs2) {
+            buf.Deallocate();
+          }
+        });
+      },
+      out);
+}
+
+static void CopyTcp(uv::Stream& in, std::shared_ptr<uv::Stream> out) {
+  struct StreamData {
+    std::string rem;
+    uint16_t seq = 0;
+  };
+  in.data.connect(
+      [data = std::make_shared<StreamData>(), outPtr = out.get()](
+          uv::Buffer& buf, size_t len) {
+        // build buffers
+        wpi::SmallVector<uv::Buffer, 4> bufs;
+        if (!NewlineBuffer(data->rem, buf, len, bufs, true, data->seq++)) {
+          return;
+        }
+
+        // send output
+        outPtr->Write(bufs, [](auto bufs2, uv::Error) {
+          for (auto buf : bufs2) {
+            buf.Deallocate();
+          }
+        });
+      },
+      out);
+}
+
+static void CopyStream(uv::Stream& in, std::shared_ptr<uv::Stream> out) {
+  in.data.connect([out](uv::Buffer& buf, size_t len) {
+    uv::Buffer buf2 = buf.Dup();
+    buf2.len = len;
+    out->Write({buf2}, [](auto bufs, uv::Error) {
+      for (auto buf : bufs) {
+        buf.Deallocate();
+      }
+    });
+  });
+}
+
+int main(int argc, char* argv[]) {
+  // parse arguments
+  int programArgc = 1;
+  bool useUdp = false;
+  bool broadcastUdp = false;
+  bool err = false;
+
+  while (programArgc < argc && argv[programArgc][0] == '-') {
+    if (std::string_view(argv[programArgc]) == "-u") {
+      useUdp = true;
+    } else if (std::string_view(argv[programArgc]) == "-b") {
+      useUdp = true;
+      broadcastUdp = true;
+    } else {
+      fmt::print(stderr, "unrecognized command line option {}\n",
+                 argv[programArgc]);
+      err = true;
+    }
+    ++programArgc;
+  }
+
+  if (err || (argc - programArgc) < 1) {
+    std::fputs(argv[0], stderr);
+    std::fputs(
+        " [-ub] program [arguments ...]\n"
+        "  -u  send udp to localhost port 6666 instead of using tcp\n"
+        "  -b  broadcast udp to port 6666 instead of using tcp\n",
+        stderr);
+    return EXIT_FAILURE;
+  }
+
+  uv::Process::DisableStdioInheritance();
+
+  auto loop = uv::Loop::Create();
+  loop->error.connect(
+      [](uv::Error err) { fmt::print(stderr, "uv ERROR: {}\n", err.str()); });
+
+  // create pipes to communicate with child
+  auto stdinPipe = uv::Pipe::Create(loop);
+  auto stdoutPipe = uv::Pipe::Create(loop);
+  auto stderrPipe = uv::Pipe::Create(loop);
+
+  // create tty to pass from our console to child's
+  auto stdinTty = uv::Tty::Create(loop, 0, true);
+  auto stdoutTty = uv::Tty::Create(loop, 1, false);
+  auto stderrTty = uv::Tty::Create(loop, 2, false);
+
+  // pass through our console to child's (bidirectional)
+  if (stdinTty) {
+    CopyStream(*stdinTty, stdinPipe);
+  }
+  if (stdoutTty) {
+    CopyStream(*stdoutPipe, stdoutTty);
+  }
+  if (stderrTty) {
+    CopyStream(*stderrPipe, stderrTty);
+  }
+
+  // when our stdin closes, also close child stdin
+  if (stdinTty) {
+    stdinTty->end.connect([stdinPipe] { stdinPipe->Close(); });
+  }
+
+  if (useUdp) {
+    auto udp = uv::Udp::Create(loop);
+    // tee stdout and stderr
+    CopyUdp(*stdoutPipe, udp, broadcastUdp);
+    CopyUdp(*stderrPipe, udp, broadcastUdp);
+  } else {
+    auto tcp = uv::Tcp::Create(loop);
+
+    // bind to listen address and port
+    tcp->Bind("", 1740);
+
+    // when we get a connection, accept it
+    tcp->connection.connect([srv = tcp.get(), stdoutPipe, stderrPipe] {
+      auto tcp = srv->Accept();
+      if (!tcp) {
+        return;
+      }
+
+      // close on error
+      tcp->error.connect([s = tcp.get()](wpi::uv::Error err) { s->Close(); });
+
+      // tee stdout and stderr
+      CopyTcp(*stdoutPipe, tcp);
+      CopyTcp(*stderrPipe, tcp);
+    });
+
+    // start listening for incoming connections
+    tcp->Listen();
+  }
+
+  // build process options
+  wpi::SmallVector<uv::Process::Option, 8> options;
+
+  // hook up pipes to child
+  options.emplace_back(
+      uv::Process::StdioCreatePipe(0, *stdinPipe, UV_READABLE_PIPE));
+#ifndef _WIN32
+  // create a PTY so the child does unbuffered output
+  int parentfd, childfd;
+  if (openpty(&parentfd, &childfd, nullptr, nullptr, nullptr) == 0) {
+    stdoutPipe->Open(parentfd);
+    options.emplace_back(uv::Process::StdioInherit(1, childfd));
+  } else {
+    options.emplace_back(
+        uv::Process::StdioCreatePipe(1, *stdoutPipe, UV_WRITABLE_PIPE));
+  }
+#else
+  options.emplace_back(
+      uv::Process::StdioCreatePipe(1, *stdoutPipe, UV_WRITABLE_PIPE));
+#endif
+  options.emplace_back(
+      uv::Process::StdioCreatePipe(2, *stderrPipe, UV_WRITABLE_PIPE));
+
+  // pass our args as the child args (argv[1] becomes child argv[0], etc)
+  for (int i = programArgc; i < argc; ++i) {
+    options.emplace_back(argv[i]);
+  }
+
+  auto proc = uv::Process::SpawnArray(loop, argv[programArgc], options);
+  if (!proc) {
+    std::fputs("could not start subprocess\n", stderr);
+    return EXIT_FAILURE;
+  }
+  proc->exited.connect([](int64_t status, int) { std::exit(status); });
+
+  // start reading
+  if (stdinTty) {
+    stdinTty->StartRead();
+  }
+  stdoutPipe->StartRead();
+  stderrPipe->StartRead();
+
+  // pass various signals to child
+  auto sigHandler = [proc](int signum) { proc->Kill(signum); };
+  for (int signum : {SIGINT, SIGHUP, SIGTERM}) {
+    auto sig = uv::Signal::Create(loop);
+    sig->Start(signum);
+    sig->signal.connect(sigHandler);
+  }
+
+  // run the loop!
+  loop->Run();
+}
diff --git a/third_party/allwpilib/wpinet/src/netconsoleTee/native/cpp/main.cpp b/third_party/allwpilib/wpinet/src/netconsoleTee/native/cpp/main.cpp
new file mode 100644
index 0000000..a6bdff4
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/netconsoleTee/native/cpp/main.cpp
@@ -0,0 +1,224 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <cstdio>
+
+#include <fmt/format.h>
+#include <wpi/MathExtras.h>
+#include <wpi/SmallVector.h>
+#include <wpi/StringExtras.h>
+#include <wpi/timestamp.h>
+
+#include "wpinet/raw_uv_ostream.h"
+#include "wpinet/uv/Loop.h"
+#include "wpinet/uv/Tcp.h"
+#include "wpinet/uv/Tty.h"
+#include "wpinet/uv/Udp.h"
+#include "wpinet/uv/util.h"
+
+namespace uv = wpi::uv;
+
+static uint64_t startTime = wpi::Now();
+
+static bool NewlineBuffer(std::string& rem, uv::Buffer& buf, size_t len,
+                          wpi::SmallVectorImpl<uv::Buffer>& bufs, bool tcp,
+                          uint16_t tcpSeq) {
+  // scan for last newline
+  std::string_view str(buf.base, len);
+  size_t idx = str.rfind('\n');
+  if (idx == std::string_view::npos) {
+    // no newline yet, just keep appending to remainder
+    rem += str;
+    return false;
+  }
+
+  // build output
+  wpi::raw_uv_ostream out(bufs, 4096);
+  std::string_view toCopy = wpi::slice(str, 0, idx + 1);
+  if (tcp) {
+    // Header is 2 byte len, 1 byte type, 4 byte timestamp, 2 byte sequence num
+    uint32_t ts = wpi::FloatToBits((wpi::Now() - startTime) * 1.0e-6);
+    uint16_t len = rem.size() + toCopy.size() + 1 + 4 + 2;
+    const uint8_t header[] = {static_cast<uint8_t>((len >> 8) & 0xff),
+                              static_cast<uint8_t>(len & 0xff),
+                              12,
+                              static_cast<uint8_t>((ts >> 24) & 0xff),
+                              static_cast<uint8_t>((ts >> 16) & 0xff),
+                              static_cast<uint8_t>((ts >> 8) & 0xff),
+                              static_cast<uint8_t>(ts & 0xff),
+                              static_cast<uint8_t>((tcpSeq >> 8) & 0xff),
+                              static_cast<uint8_t>(tcpSeq & 0xff)};
+    out << std::span<const uint8_t>(header);
+  }
+  out << rem << toCopy;
+
+  // reset remainder
+  rem = wpi::slice(str, idx + 1, std::string_view::npos);
+  return true;
+}
+
+static void CopyUdp(uv::Stream& in, std::shared_ptr<uv::Udp> out, int port,
+                    bool broadcast) {
+  sockaddr_in addr;
+  if (broadcast) {
+    out->SetBroadcast(true);
+    uv::NameToAddr("0.0.0.0", port, &addr);
+  } else {
+    uv::NameToAddr("127.0.0.1", port, &addr);
+  }
+
+  in.data.connect(
+      [rem = std::make_shared<std::string>(), outPtr = out.get(), addr](
+          uv::Buffer& buf, size_t len) {
+        // build buffers
+        wpi::SmallVector<uv::Buffer, 4> bufs;
+        if (!NewlineBuffer(*rem, buf, len, bufs, false, 0)) {
+          return;
+        }
+
+        // send output
+        outPtr->Send(addr, bufs, [](auto bufs2, uv::Error) {
+          for (auto buf : bufs2) {
+            buf.Deallocate();
+          }
+        });
+      },
+      out);
+}
+
+static void CopyTcp(uv::Stream& in, std::shared_ptr<uv::Stream> out) {
+  struct StreamData {
+    std::string rem;
+    uint16_t seq = 0;
+  };
+  in.data.connect(
+      [data = std::make_shared<StreamData>(), outPtr = out.get()](
+          uv::Buffer& buf, size_t len) {
+        // build buffers
+        wpi::SmallVector<uv::Buffer, 4> bufs;
+        if (!NewlineBuffer(data->rem, buf, len, bufs, true, data->seq++)) {
+          return;
+        }
+
+        // send output
+        outPtr->Write(bufs, [](auto bufs2, uv::Error) {
+          for (auto buf : bufs2) {
+            buf.Deallocate();
+          }
+        });
+      },
+      out);
+}
+
+static void CopyStream(uv::Stream& in, std::shared_ptr<uv::Stream> out) {
+  in.data.connect([out](uv::Buffer& buf, size_t len) {
+    uv::Buffer buf2 = buf.Dup();
+    buf2.len = len;
+    out->Write({buf2}, [](auto bufs, uv::Error) {
+      for (auto buf : bufs) {
+        buf.Deallocate();
+      }
+    });
+  });
+}
+
+int main(int argc, char* argv[]) {
+  // parse arguments
+  int arg = 1;
+  bool useUdp = false;
+  bool broadcastUdp = false;
+  bool err = false;
+  int port = -1;
+
+  while (arg < argc && argv[arg][0] == '-') {
+    if (std::string_view(argv[arg]) == "-u") {
+      useUdp = true;
+    } else if (std::string_view(argv[arg]) == "-b") {
+      useUdp = true;
+      broadcastUdp = true;
+    } else if (std::string_view(argv[arg]) == "-p") {
+      ++arg;
+      std::optional<int> portValue;
+      if (arg >= argc || argv[arg][0] == '-' ||
+          !(portValue = wpi::parse_integer<int>(argv[arg], 10))) {
+        std::fputs("-p must be followed by port number\n", stderr);
+        err = true;
+      } else if (portValue) {
+        port = portValue.value();
+      }
+    } else {
+      fmt::print(stderr, "unrecognized command line option {}\n", argv[arg]);
+      err = true;
+    }
+    ++arg;
+  }
+
+  if (err) {
+    std::fputs(argv[0], stderr);
+    std::fputs(
+        " [-ub] [-p PORT]\n"
+        "  -u       send udp to localhost port 6666 instead of using tcp\n"
+        "  -b       broadcast udp to port 6666 instead of using tcp\n"
+        "  -p PORT  use port PORT instead of 6666 (udp) or 1740 (tcp)\n",
+        stderr);
+    return EXIT_FAILURE;
+  }
+
+  auto loop = uv::Loop::Create();
+  loop->error.connect(
+      [](uv::Error err) { fmt::print(stderr, "uv ERROR: {}\n", err.str()); });
+
+  // create ttys
+  auto stdinTty = uv::Tty::Create(loop, 0, true);
+  auto stdoutTty = uv::Tty::Create(loop, 1, false);
+
+  // don't bother continuing if we don't have a stdin
+  if (!stdinTty) {
+    return EXIT_SUCCESS;
+  }
+
+  // pass through our input to output
+  if (stdoutTty) {
+    CopyStream(*stdinTty, stdoutTty);
+  }
+
+  // when our stdin closes, exit
+  stdinTty->end.connect([] { std::exit(EXIT_SUCCESS); });
+
+  if (useUdp) {
+    auto udp = uv::Udp::Create(loop);
+    // tee
+    CopyUdp(*stdinTty, udp, port < 0 ? 6666 : port, broadcastUdp);
+  } else {
+    auto tcp = uv::Tcp::Create(loop);
+
+    // bind to listen address and port
+    tcp->Bind("", port < 0 ? 1740 : port);
+
+    // when we get a connection, accept it
+    tcp->connection.connect([srv = tcp.get(), stdinTty] {
+      auto tcp = srv->Accept();
+      if (!tcp) {
+        return;
+      }
+
+      // close on error
+      tcp->error.connect([s = tcp.get()](wpi::uv::Error err) { s->Close(); });
+
+      // tee
+      CopyTcp(*stdinTty, tcp);
+    });
+
+    // start listening for incoming connections
+    tcp->Listen();
+  }
+
+  // start reading
+  if (stdinTty) {
+    stdinTty->StartRead();
+  }
+
+  // run the loop!
+  loop->Run();
+}
diff --git a/third_party/allwpilib/wpinet/src/test/java/edu/wpi/first/net/WPINetJNITest.java b/third_party/allwpilib/wpinet/src/test/java/edu/wpi/first/net/WPINetJNITest.java
new file mode 100644
index 0000000..dfa6d4d
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/test/java/edu/wpi/first/net/WPINetJNITest.java
@@ -0,0 +1,15 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.net;
+
+import java.io.IOException;
+import org.junit.jupiter.api.Test;
+
+public class WPINetJNITest {
+  @Test
+  void jniLinkTest() throws IOException {
+    WPINetJNI.forceLoad();
+  }
+}
diff --git a/third_party/allwpilib/wpinet/src/test/native/cpp/HttpParserTest.cpp b/third_party/allwpilib/wpinet/src/test/native/cpp/HttpParserTest.cpp
new file mode 100644
index 0000000..a9d927a
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/test/native/cpp/HttpParserTest.cpp
@@ -0,0 +1,206 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/HttpParser.h"  // NOLINT(build/include_order)
+
+#include "gtest/gtest.h"
+
+namespace wpi {
+
+TEST(HttpParserTest, UrlMethodHeadersComplete) {
+  HttpParser p{HttpParser::kRequest};
+  int callbacks = 0;
+  p.url.connect([&](std::string_view path) {
+    ASSERT_EQ(path, "/foo/bar");
+    ASSERT_EQ(p.GetUrl(), "/foo/bar");
+    ++callbacks;
+  });
+  p.Execute("GET /foo");
+  p.Execute("/bar");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute(" HTTP/1.1\r\n\r\n");
+  ASSERT_EQ(callbacks, 1);
+  ASSERT_EQ(p.GetUrl(), "/foo/bar");
+  ASSERT_EQ(p.GetMethod(), HTTP_GET);
+  ASSERT_FALSE(p.HasError());
+}
+
+TEST(HttpParserTest, UrlMethodHeader) {
+  HttpParser p{HttpParser::kRequest};
+  int callbacks = 0;
+  p.url.connect([&](std::string_view path) {
+    ASSERT_EQ(path, "/foo/bar");
+    ASSERT_EQ(p.GetUrl(), "/foo/bar");
+    ++callbacks;
+  });
+  p.Execute("GET /foo");
+  p.Execute("/bar");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute(" HTTP/1.1\r\n");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("F");
+  ASSERT_EQ(callbacks, 1);
+  ASSERT_EQ(p.GetUrl(), "/foo/bar");
+  ASSERT_EQ(p.GetMethod(), HTTP_GET);
+  ASSERT_FALSE(p.HasError());
+}
+
+TEST(HttpParserTest, StatusHeadersComplete) {
+  HttpParser p{HttpParser::kResponse};
+  int callbacks = 0;
+  p.status.connect([&](std::string_view status) {
+    ASSERT_EQ(status, "OK");
+    ASSERT_EQ(p.GetStatusCode(), 200u);
+    ++callbacks;
+  });
+  p.Execute("HTTP/1.1 200");
+  p.Execute(" OK");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("\r\n\r\n");
+  ASSERT_EQ(callbacks, 1);
+  ASSERT_EQ(p.GetStatusCode(), 200u);
+  ASSERT_FALSE(p.HasError());
+}
+
+TEST(HttpParserTest, StatusHeader) {
+  HttpParser p{HttpParser::kResponse};
+  int callbacks = 0;
+  p.status.connect([&](std::string_view status) {
+    ASSERT_EQ(status, "OK");
+    ASSERT_EQ(p.GetStatusCode(), 200u);
+    ++callbacks;
+  });
+  p.Execute("HTTP/1.1 200");
+  p.Execute(" OK\r\n");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("F");
+  ASSERT_EQ(callbacks, 1);
+  ASSERT_EQ(p.GetStatusCode(), 200u);
+  ASSERT_FALSE(p.HasError());
+}
+
+TEST(HttpParserTest, HeaderFieldComplete) {
+  HttpParser p{HttpParser::kRequest};
+  int callbacks = 0;
+  p.header.connect([&](std::string_view name, std::string_view value) {
+    ASSERT_EQ(name, "Foo");
+    ASSERT_EQ(value, "Bar");
+    ++callbacks;
+  });
+  p.Execute("GET / HTTP/1.1\r\n");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("Fo");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("o: ");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("Bar");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("\r\n");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("\r\n");
+  ASSERT_EQ(callbacks, 1);
+  ASSERT_FALSE(p.HasError());
+}
+
+TEST(HttpParserTest, HeaderFieldNext) {
+  HttpParser p{HttpParser::kRequest};
+  int callbacks = 0;
+  p.header.connect([&](std::string_view name, std::string_view value) {
+    ASSERT_EQ(name, "Foo");
+    ASSERT_EQ(value, "Bar");
+    ++callbacks;
+  });
+  p.Execute("GET / HTTP/1.1\r\n");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("Fo");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("o: ");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("Bar");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("\r\n");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("F");
+  ASSERT_EQ(callbacks, 1);
+  ASSERT_FALSE(p.HasError());
+}
+
+TEST(HttpParserTest, HeadersComplete) {
+  HttpParser p{HttpParser::kRequest};
+  int callbacks = 0;
+  p.headersComplete.connect([&](bool keepAlive) {
+    ASSERT_EQ(keepAlive, false);
+    ++callbacks;
+  });
+  p.Execute("GET / HTTP/1.0\r\n");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("\r\n");
+  ASSERT_EQ(callbacks, 1);
+  ASSERT_FALSE(p.HasError());
+}
+
+TEST(HttpParserTest, HeadersCompleteHTTP11) {
+  HttpParser p{HttpParser::kRequest};
+  int callbacks = 0;
+  p.headersComplete.connect([&](bool keepAlive) {
+    ASSERT_EQ(keepAlive, true);
+    ++callbacks;
+  });
+  p.Execute("GET / HTTP/1.1\r\n");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("\r\n");
+  ASSERT_EQ(callbacks, 1);
+  ASSERT_FALSE(p.HasError());
+}
+
+TEST(HttpParserTest, HeadersCompleteKeepAlive) {
+  HttpParser p{HttpParser::kRequest};
+  int callbacks = 0;
+  p.headersComplete.connect([&](bool keepAlive) {
+    ASSERT_EQ(keepAlive, true);
+    ++callbacks;
+  });
+  p.Execute("GET / HTTP/1.0\r\n");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("Connection: Keep-Alive\r\n");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("\r\n");
+  ASSERT_EQ(callbacks, 1);
+  ASSERT_FALSE(p.HasError());
+}
+
+TEST(HttpParserTest, HeadersCompleteUpgrade) {
+  HttpParser p{HttpParser::kRequest};
+  int callbacks = 0;
+  p.headersComplete.connect([&](bool) {
+    ASSERT_TRUE(p.IsUpgrade());
+    ++callbacks;
+  });
+  p.Execute("GET / HTTP/1.0\r\n");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("Connection: Upgrade\r\n");
+  p.Execute("Upgrade: websocket\r\n");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("\r\n");
+  ASSERT_EQ(callbacks, 1);
+  ASSERT_FALSE(p.HasError());
+}
+
+TEST(HttpParserTest, Reset) {
+  HttpParser p{HttpParser::kRequest};
+  int callbacks = 0;
+  p.headersComplete.connect([&](bool) { ++callbacks; });
+  p.Execute("GET / HTTP/1.1\r\n");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("\r\n");
+  ASSERT_EQ(callbacks, 1);
+  p.Reset(HttpParser::kRequest);
+  p.Execute("GET / HTTP/1.1\r\n");
+  ASSERT_EQ(callbacks, 1);
+  p.Execute("\r\n");
+  ASSERT_EQ(callbacks, 2);
+  ASSERT_FALSE(p.HasError());
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib/wpinet/src/test/native/cpp/HttpUtilTest.cpp b/third_party/allwpilib/wpinet/src/test/native/cpp/HttpUtilTest.cpp
new file mode 100644
index 0000000..4417b7c
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/test/native/cpp/HttpUtilTest.cpp
@@ -0,0 +1,102 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/HttpUtil.h"  // NOLINT(build/include_order)
+
+#include "gtest/gtest.h"
+
+namespace wpi {
+
+TEST(HttpMultipartScannerTest, ExecuteExact) {
+  HttpMultipartScanner scanner("foo");
+  EXPECT_TRUE(scanner.Execute("abcdefg---\r\n--foo\r\n").empty());
+  EXPECT_TRUE(scanner.IsDone());
+  EXPECT_TRUE(scanner.GetSkipped().empty());
+}
+
+TEST(HttpMultipartScannerTest, ExecutePartial) {
+  HttpMultipartScanner scanner("foo");
+  EXPECT_TRUE(scanner.Execute("abcdefg--").empty());
+  EXPECT_FALSE(scanner.IsDone());
+  EXPECT_TRUE(scanner.Execute("-\r\n").empty());
+  EXPECT_FALSE(scanner.IsDone());
+  EXPECT_TRUE(scanner.Execute("--foo\r").empty());
+  EXPECT_FALSE(scanner.IsDone());
+  EXPECT_TRUE(scanner.Execute("\n").empty());
+  EXPECT_TRUE(scanner.IsDone());
+}
+
+TEST(HttpMultipartScannerTest, ExecuteTrailing) {
+  HttpMultipartScanner scanner("foo");
+  EXPECT_EQ(scanner.Execute("abcdefg---\r\n--foo\r\nxyz"), "xyz");
+}
+
+TEST(HttpMultipartScannerTest, ExecutePadding) {
+  HttpMultipartScanner scanner("foo");
+  EXPECT_EQ(scanner.Execute("abcdefg---\r\n--foo    \r\nxyz"), "xyz");
+  EXPECT_TRUE(scanner.IsDone());
+}
+
+TEST(HttpMultipartScannerTest, SaveSkipped) {
+  HttpMultipartScanner scanner("foo", true);
+  scanner.Execute("abcdefg---\r\n--foo\r\n");
+  EXPECT_EQ(scanner.GetSkipped(), "abcdefg---\r\n--foo\r\n");
+}
+
+TEST(HttpMultipartScannerTest, Reset) {
+  HttpMultipartScanner scanner("foo", true);
+
+  scanner.Execute("abcdefg---\r\n--foo\r\n");
+  EXPECT_TRUE(scanner.IsDone());
+  EXPECT_EQ(scanner.GetSkipped(), "abcdefg---\r\n--foo\r\n");
+
+  scanner.Reset(true);
+  EXPECT_FALSE(scanner.IsDone());
+  scanner.SetBoundary("bar");
+
+  scanner.Execute("--foo\r\n--bar\r\n");
+  EXPECT_TRUE(scanner.IsDone());
+  EXPECT_EQ(scanner.GetSkipped(), "--foo\r\n--bar\r\n");
+}
+
+TEST(HttpMultipartScannerTest, WithoutDashes) {
+  HttpMultipartScanner scanner("foo", true);
+
+  EXPECT_TRUE(scanner.Execute("--\r\nfoo\r\n").empty());
+  EXPECT_TRUE(scanner.IsDone());
+}
+
+TEST(HttpMultipartScannerTest, SeqDashesDashes) {
+  HttpMultipartScanner scanner("foo", true);
+  EXPECT_TRUE(scanner.Execute("\r\n--foo\r\n").empty());
+  EXPECT_TRUE(scanner.IsDone());
+  EXPECT_TRUE(scanner.Execute("\r\n--foo\r\n").empty());
+  EXPECT_TRUE(scanner.IsDone());
+}
+
+TEST(HttpMultipartScannerTest, SeqDashesNoDashes) {
+  HttpMultipartScanner scanner("foo", true);
+  EXPECT_TRUE(scanner.Execute("\r\n--foo\r\n").empty());
+  EXPECT_TRUE(scanner.IsDone());
+  EXPECT_TRUE(scanner.Execute("\r\nfoo\r\n").empty());
+  EXPECT_FALSE(scanner.IsDone());
+}
+
+TEST(HttpMultipartScannerTest, SeqNoDashesDashes) {
+  HttpMultipartScanner scanner("foo", true);
+  EXPECT_TRUE(scanner.Execute("\r\nfoo\r\n").empty());
+  EXPECT_TRUE(scanner.IsDone());
+  EXPECT_TRUE(scanner.Execute("\r\n--foo\r\n").empty());
+  EXPECT_FALSE(scanner.IsDone());
+}
+
+TEST(HttpMultipartScannerTest, SeqNoDashesNoDashes) {
+  HttpMultipartScanner scanner("foo", true);
+  EXPECT_TRUE(scanner.Execute("\r\nfoo\r\n").empty());
+  EXPECT_TRUE(scanner.IsDone());
+  EXPECT_TRUE(scanner.Execute("\r\nfoo\r\n").empty());
+  EXPECT_TRUE(scanner.IsDone());
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib/wpinet/src/test/native/cpp/HttpWebSocketServerConnectionTest.cpp b/third_party/allwpilib/wpinet/src/test/native/cpp/HttpWebSocketServerConnectionTest.cpp
new file mode 100644
index 0000000..9c2d874
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/test/native/cpp/HttpWebSocketServerConnectionTest.cpp
@@ -0,0 +1,25 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/HttpWebSocketServerConnection.h"  // NOLINT(build/include_order)
+
+#include <gtest/gtest.h>
+
+namespace wpi {
+
+class HttpWebSocketServerConnectionTest
+    : public HttpWebSocketServerConnection<HttpWebSocketServerConnectionTest> {
+ public:
+  HttpWebSocketServerConnectionTest(std::shared_ptr<uv::Stream> stream,
+                                    std::span<const std::string_view> protocols)
+      : HttpWebSocketServerConnection{stream, protocols} {}
+
+  void ProcessRequest() override { ++gotRequest; }
+  void ProcessWsUpgrade() override { ++gotUpgrade; }
+
+  int gotRequest = 0;
+  int gotUpgrade = 0;
+};
+
+}  // namespace wpi
diff --git a/third_party/allwpilib/wpinet/src/test/native/cpp/MulticastTest.cpp b/third_party/allwpilib/wpinet/src/test/native/cpp/MulticastTest.cpp
new file mode 100644
index 0000000..bbec538
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/test/native/cpp/MulticastTest.cpp
@@ -0,0 +1,52 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <wpinet/MulticastServiceAnnouncer.h>
+#include <wpinet/MulticastServiceResolver.h>
+
+#include <array>
+#include <chrono>
+#include <string>
+#include <string_view>
+#include <thread>
+#include <utility>
+
+#include <wpi/timestamp.h>
+
+#include "gtest/gtest.h"
+
+TEST(MulticastServiceAnnouncerTest, EmptyText) {
+  const std::string_view serviceName = "TestServiceNoText";
+  const std::string_view serviceType = "_wpinotxt";
+  const int port = std::rand();
+  wpi::MulticastServiceAnnouncer announcer(serviceName, serviceType, port);
+  wpi::MulticastServiceResolver resolver(serviceType);
+
+  if (announcer.HasImplementation() && resolver.HasImplementation()) {
+    announcer.Start();
+    resolver.Start();
+
+    std::this_thread::sleep_for(std::chrono::seconds(1));
+
+    resolver.Stop();
+    announcer.Stop();
+  }
+}
+
+TEST(MulticastServiceAnnouncerTest, SingleText) {
+  const std::string_view serviceName = "TestServiceSingle";
+  const std::string_view serviceType = "_wpitxt";
+  const int port = std::rand();
+  std::array<std::pair<std::string, std::string>, 1> txt = {
+      std::make_pair("hello", "world")};
+  wpi::MulticastServiceAnnouncer announcer(serviceName, serviceType, port, txt);
+  wpi::MulticastServiceResolver resolver(serviceType);
+
+  if (announcer.HasImplementation() && resolver.HasImplementation()) {
+    announcer.Start();
+    resolver.Start();
+
+    std::this_thread::sleep_for(std::chrono::seconds(1));
+  }
+}
diff --git a/third_party/allwpilib/wpinet/src/test/native/cpp/WebSocketClientTest.cpp b/third_party/allwpilib/wpinet/src/test/native/cpp/WebSocketClientTest.cpp
new file mode 100644
index 0000000..a603d9c
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/test/native/cpp/WebSocketClientTest.cpp
@@ -0,0 +1,320 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/WebSocket.h"  // NOLINT(build/include_order)
+
+#include <wpi/Base64.h>
+#include <wpi/SmallString.h>
+#include <wpi/StringExtras.h>
+#include <wpi/sha1.h>
+
+#include "WebSocketTest.h"
+#include "wpinet/HttpParser.h"
+#include "wpinet/raw_uv_ostream.h"
+
+namespace wpi {
+
+class WebSocketClientTest : public WebSocketTest {
+ public:
+  WebSocketClientTest() {
+    // Bare bones server
+    req.header.connect([this](std::string_view name, std::string_view value) {
+      // save key (required for valid response)
+      if (equals_lower(name, "sec-websocket-key")) {
+        clientKey = value;
+      }
+    });
+    req.headersComplete.connect([this](bool) {
+      // send response
+      SmallVector<uv::Buffer, 4> bufs;
+      raw_uv_ostream os{bufs, 4096};
+      os << "HTTP/1.1 101 Switching Protocols\r\n";
+      os << "Upgrade: websocket\r\n";
+      os << "Connection: Upgrade\r\n";
+
+      // accept hash
+      SHA1 hash;
+      hash.Update(clientKey);
+      hash.Update("258EAFA5-E914-47DA-95CA-C5AB0DC85B11");
+      if (mockBadAccept) {
+        hash.Update("1");
+      }
+      SmallString<64> hashBuf;
+      SmallString<64> acceptBuf;
+      os << "Sec-WebSocket-Accept: "
+         << Base64Encode(hash.RawFinal(hashBuf), acceptBuf) << "\r\n";
+
+      if (!mockProtocol.empty()) {
+        os << "Sec-WebSocket-Protocol: " << mockProtocol << "\r\n";
+      }
+
+      os << "\r\n";
+
+      conn->Write(bufs, [](auto bufs, uv::Error) {
+        for (auto& buf : bufs) {
+          buf.Deallocate();
+        }
+      });
+
+      serverHeadersDone = true;
+      if (connected) {
+        connected();
+      }
+    });
+
+    serverPipe->Listen([this] {
+      conn = serverPipe->Accept();
+      conn->StartRead();
+      conn->data.connect([this](uv::Buffer& buf, size_t size) {
+        std::string_view data{buf.base, size};
+        if (!serverHeadersDone) {
+          data = req.Execute(data);
+          if (req.HasError()) {
+            Finish();
+          }
+          ASSERT_EQ(req.GetError(), HPE_OK) << http_errno_name(req.GetError());
+          if (data.empty()) {
+            return;
+          }
+        }
+        wireData.insert(wireData.end(), data.begin(), data.end());
+      });
+      conn->end.connect([this] { Finish(); });
+    });
+  }
+
+  bool mockBadAccept = false;
+  std::vector<uint8_t> wireData;
+  std::shared_ptr<uv::Pipe> conn;
+  HttpParser req{HttpParser::kRequest};
+  SmallString<64> clientKey;
+  std::string mockProtocol;
+  bool serverHeadersDone = false;
+  std::function<void()> connected;
+};
+
+TEST_F(WebSocketClientTest, Open) {
+  int gotOpen = 0;
+
+  clientPipe->Connect(pipeName, [&] {
+    auto ws = WebSocket::CreateClient(*clientPipe, "/test", pipeName);
+    ws->closed.connect([&](uint16_t code, std::string_view reason) {
+      Finish();
+      if (code != 1005 && code != 1006) {
+        FAIL() << "Code: " << code << " Reason: " << reason;
+      }
+    });
+    ws->open.connect([&](std::string_view protocol) {
+      ++gotOpen;
+      Finish();
+      ASSERT_TRUE(protocol.empty());
+    });
+  });
+
+  loop->Run();
+
+  if (HasFatalFailure()) {
+    return;
+  }
+  ASSERT_EQ(gotOpen, 1);
+}
+
+TEST_F(WebSocketClientTest, BadAccept) {
+  int gotClosed = 0;
+
+  mockBadAccept = true;
+
+  clientPipe->Connect(pipeName, [&] {
+    auto ws = WebSocket::CreateClient(*clientPipe, "/test", pipeName);
+    ws->closed.connect([&](uint16_t code, std::string_view msg) {
+      Finish();
+      ++gotClosed;
+      ASSERT_EQ(code, 1002) << "Message: " << msg;
+    });
+    ws->open.connect([&](std::string_view protocol) {
+      Finish();
+      FAIL() << "Got open";
+    });
+  });
+
+  loop->Run();
+
+  if (HasFatalFailure()) {
+    return;
+  }
+  ASSERT_EQ(gotClosed, 1);
+}
+
+TEST_F(WebSocketClientTest, ProtocolGood) {
+  int gotOpen = 0;
+
+  mockProtocol = "myProtocol";
+
+  clientPipe->Connect(pipeName, [&] {
+    auto ws = WebSocket::CreateClient(*clientPipe, "/test", pipeName,
+                                      {"myProtocol", "myProtocol2"});
+    ws->closed.connect([&](uint16_t code, std::string_view msg) {
+      Finish();
+      if (code != 1005 && code != 1006) {
+        FAIL() << "Code: " << code << "Message: " << msg;
+      }
+    });
+    ws->open.connect([&](std::string_view protocol) {
+      ++gotOpen;
+      Finish();
+      ASSERT_EQ(protocol, "myProtocol");
+    });
+  });
+
+  loop->Run();
+
+  if (HasFatalFailure()) {
+    return;
+  }
+  ASSERT_EQ(gotOpen, 1);
+}
+
+TEST_F(WebSocketClientTest, ProtocolRespNotReq) {
+  int gotClosed = 0;
+
+  mockProtocol = "myProtocol";
+
+  clientPipe->Connect(pipeName, [&] {
+    auto ws = WebSocket::CreateClient(*clientPipe, "/test", pipeName);
+    ws->closed.connect([&](uint16_t code, std::string_view msg) {
+      Finish();
+      ++gotClosed;
+      ASSERT_EQ(code, 1003) << "Message: " << msg;
+    });
+    ws->open.connect([&](std::string_view protocol) {
+      Finish();
+      FAIL() << "Got open";
+    });
+  });
+
+  loop->Run();
+
+  if (HasFatalFailure()) {
+    return;
+  }
+  ASSERT_EQ(gotClosed, 1);
+}
+
+TEST_F(WebSocketClientTest, ProtocolReqNotResp) {
+  int gotClosed = 0;
+
+  clientPipe->Connect(pipeName, [&] {
+    auto ws = WebSocket::CreateClient(*clientPipe, "/test", pipeName,
+                                      {{"myProtocol"}});
+    ws->closed.connect([&](uint16_t code, std::string_view msg) {
+      Finish();
+      ++gotClosed;
+      ASSERT_EQ(code, 1002) << "Message: " << msg;
+    });
+    ws->open.connect([&](std::string_view protocol) {
+      Finish();
+      FAIL() << "Got open";
+    });
+  });
+
+  loop->Run();
+
+  if (HasFatalFailure()) {
+    return;
+  }
+  ASSERT_EQ(gotClosed, 1);
+}
+
+//
+// Send and receive data.  Most of these cases are tested in
+// WebSocketServerTest, so only spot check differences like masking.
+//
+
+class WebSocketClientDataTest : public WebSocketClientTest,
+                                public ::testing::WithParamInterface<size_t> {
+ public:
+  WebSocketClientDataTest() {
+    clientPipe->Connect(pipeName, [&] {
+      ws = WebSocket::CreateClient(*clientPipe, "/test", pipeName);
+      if (setupWebSocket) {
+        setupWebSocket();
+      }
+    });
+  }
+
+  std::function<void()> setupWebSocket;
+  std::shared_ptr<WebSocket> ws;
+};
+
+INSTANTIATE_TEST_SUITE_P(WebSocketClientDataTests, WebSocketClientDataTest,
+                         ::testing::Values(0, 1, 125, 126, 65535, 65536));
+
+TEST_P(WebSocketClientDataTest, SendBinary) {
+  int gotCallback = 0;
+  std::vector<uint8_t> data(GetParam(), 0x03u);
+  setupWebSocket = [&] {
+    ws->open.connect([&](std::string_view) {
+      ws->SendBinary({{data}}, [&](auto bufs, uv::Error) {
+        ++gotCallback;
+        ws->Terminate();
+        ASSERT_FALSE(bufs.empty());
+        ASSERT_EQ(bufs[0].base, reinterpret_cast<const char*>(data.data()));
+      });
+    });
+  };
+
+  loop->Run();
+
+  auto expectData = BuildMessage(0x02, true, true, data);
+  AdjustMasking(wireData);
+  ASSERT_EQ(wireData, expectData);
+  ASSERT_EQ(gotCallback, 1);
+}
+
+TEST_P(WebSocketClientDataTest, ReceiveBinary) {
+  int gotCallback = 0;
+  std::vector<uint8_t> data(GetParam(), 0x03u);
+  setupWebSocket = [&] {
+    ws->binary.connect([&](auto inData, bool fin) {
+      ++gotCallback;
+      ws->Terminate();
+      ASSERT_TRUE(fin);
+      std::vector<uint8_t> recvData{inData.begin(), inData.end()};
+      ASSERT_EQ(data, recvData);
+    });
+  };
+  auto message = BuildMessage(0x02, true, false, data);
+  connected = [&] { conn->Write({{message}}, [&](auto bufs, uv::Error) {}); };
+
+  loop->Run();
+
+  ASSERT_EQ(gotCallback, 1);
+}
+
+//
+// The client must close the connection if a masked frame is received.
+//
+
+TEST_P(WebSocketClientDataTest, ReceiveMasked) {
+  int gotCallback = 0;
+  std::vector<uint8_t> data(GetParam(), ' ');
+  setupWebSocket = [&] {
+    ws->text.connect([&](std::string_view, bool) {
+      ws->Terminate();
+      FAIL() << "Should not have gotten masked message";
+    });
+    ws->closed.connect([&](uint16_t code, std::string_view reason) {
+      ++gotCallback;
+      ASSERT_EQ(code, 1002) << "reason: " << reason;
+    });
+  };
+  auto message = BuildMessage(0x01, true, true, data);
+  connected = [&] { conn->Write({{message}}, [&](auto bufs, uv::Error) {}); };
+
+  loop->Run();
+
+  ASSERT_EQ(gotCallback, 1);
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib/wpinet/src/test/native/cpp/WebSocketIntegrationTest.cpp b/third_party/allwpilib/wpinet/src/test/native/cpp/WebSocketIntegrationTest.cpp
new file mode 100644
index 0000000..5f6c8a5
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/test/native/cpp/WebSocketIntegrationTest.cpp
@@ -0,0 +1,150 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/WebSocketServer.h"  // NOLINT(build/include_order)
+
+#include <wpi/SmallString.h>
+
+#include "WebSocketTest.h"
+#include "wpinet/HttpParser.h"
+
+namespace wpi {
+
+class WebSocketIntegrationTest : public WebSocketTest {};
+
+TEST_F(WebSocketIntegrationTest, Open) {
+  int gotServerOpen = 0;
+  int gotClientOpen = 0;
+
+  serverPipe->Listen([&]() {
+    auto conn = serverPipe->Accept();
+    auto server = WebSocketServer::Create(*conn);
+    server->connected.connect([&](std::string_view url, WebSocket&) {
+      ++gotServerOpen;
+      ASSERT_EQ(url, "/test");
+    });
+  });
+
+  clientPipe->Connect(pipeName, [&] {
+    auto ws = WebSocket::CreateClient(*clientPipe, "/test", pipeName);
+    ws->closed.connect([&](uint16_t code, std::string_view reason) {
+      Finish();
+      if (code != 1005 && code != 1006) {
+        FAIL() << "Code: " << code << " Reason: " << reason;
+      }
+    });
+    ws->open.connect([&, s = ws.get()](std::string_view) {
+      ++gotClientOpen;
+      s->Close();
+    });
+  });
+
+  loop->Run();
+
+  ASSERT_EQ(gotServerOpen, 1);
+  ASSERT_EQ(gotClientOpen, 1);
+}
+
+TEST_F(WebSocketIntegrationTest, Protocol) {
+  int gotServerOpen = 0;
+  int gotClientOpen = 0;
+
+  serverPipe->Listen([&]() {
+    auto conn = serverPipe->Accept();
+    auto server = WebSocketServer::Create(*conn, {"proto1", "proto2"});
+    server->connected.connect([&](std::string_view, WebSocket& ws) {
+      ++gotServerOpen;
+      ASSERT_EQ(ws.GetProtocol(), "proto1");
+    });
+  });
+
+  clientPipe->Connect(pipeName, [&] {
+    auto ws =
+        WebSocket::CreateClient(*clientPipe, "/test", pipeName, {"proto1"});
+    ws->closed.connect([&](uint16_t code, std::string_view reason) {
+      Finish();
+      if (code != 1005 && code != 1006) {
+        FAIL() << "Code: " << code << " Reason: " << reason;
+      }
+    });
+    ws->open.connect([&, s = ws.get()](std::string_view protocol) {
+      ++gotClientOpen;
+      s->Close();
+      ASSERT_EQ(protocol, "proto1");
+    });
+  });
+
+  loop->Run();
+
+  ASSERT_EQ(gotServerOpen, 1);
+  ASSERT_EQ(gotClientOpen, 1);
+}
+
+TEST_F(WebSocketIntegrationTest, ServerSendBinary) {
+  int gotData = 0;
+
+  serverPipe->Listen([&]() {
+    auto conn = serverPipe->Accept();
+    auto server = WebSocketServer::Create(*conn);
+    server->connected.connect([&](std::string_view, WebSocket& ws) {
+      ws.SendBinary({uv::Buffer{"\x03\x04", 2}}, [&](auto, uv::Error) {});
+      ws.Close();
+    });
+  });
+
+  clientPipe->Connect(pipeName, [&] {
+    auto ws = WebSocket::CreateClient(*clientPipe, "/test", pipeName);
+    ws->closed.connect([&](uint16_t code, std::string_view reason) {
+      Finish();
+      if (code != 1005 && code != 1006) {
+        FAIL() << "Code: " << code << " Reason: " << reason;
+      }
+    });
+    ws->binary.connect([&](auto data, bool) {
+      ++gotData;
+      std::vector<uint8_t> recvData{data.begin(), data.end()};
+      std::vector<uint8_t> expectData{0x03, 0x04};
+      ASSERT_EQ(recvData, expectData);
+    });
+  });
+
+  loop->Run();
+
+  ASSERT_EQ(gotData, 1);
+}
+
+TEST_F(WebSocketIntegrationTest, ClientSendText) {
+  int gotData = 0;
+
+  serverPipe->Listen([&]() {
+    auto conn = serverPipe->Accept();
+    auto server = WebSocketServer::Create(*conn);
+    server->connected.connect([&](std::string_view, WebSocket& ws) {
+      ws.text.connect([&](std::string_view data, bool) {
+        ++gotData;
+        ASSERT_EQ(data, "hello");
+      });
+    });
+  });
+
+  clientPipe->Connect(pipeName, [&] {
+    auto ws = WebSocket::CreateClient(*clientPipe, "/test", pipeName);
+    ws->closed.connect([&](uint16_t code, std::string_view reason) {
+      Finish();
+      if (code != 1005 && code != 1006) {
+        FAIL() << "Code: " << code << " Reason: " << reason;
+      }
+    });
+    ws->open.connect([&, s = ws.get()](std::string_view) {
+      s->SendText({{"hello"}}, [&](auto, uv::Error) {});
+      s->Close();
+    });
+  });
+
+  loop->Run();
+
+  ASSERT_EQ(gotData, 1);
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib/wpinet/src/test/native/cpp/WebSocketServerTest.cpp b/third_party/allwpilib/wpinet/src/test/native/cpp/WebSocketServerTest.cpp
new file mode 100644
index 0000000..18dd50b
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/test/native/cpp/WebSocketServerTest.cpp
@@ -0,0 +1,737 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/WebSocket.h"  // NOLINT(build/include_order)
+
+#include <wpi/Base64.h>
+#include <wpi/SmallString.h>
+#include <wpi/sha1.h>
+
+#include "WebSocketTest.h"
+#include "wpinet/HttpParser.h"
+#include "wpinet/raw_uv_ostream.h"
+
+namespace wpi {
+
+class WebSocketServerTest : public WebSocketTest {
+ public:
+  WebSocketServerTest() {
+    resp.headersComplete.connect([this](bool) { headersDone = true; });
+
+    serverPipe->Listen([this]() {
+      auto conn = serverPipe->Accept();
+      ws = WebSocket::CreateServer(*conn, "foo", "13");
+      if (setupWebSocket) {
+        setupWebSocket();
+      }
+    });
+    clientPipe->Connect(pipeName, [this]() {
+      clientPipe->StartRead();
+      clientPipe->data.connect([this](uv::Buffer& buf, size_t size) {
+        std::string_view data{buf.base, size};
+        if (!headersDone) {
+          data = resp.Execute(data);
+          if (resp.HasError()) {
+            Finish();
+          }
+          ASSERT_EQ(resp.GetError(), HPE_OK)
+              << http_errno_name(resp.GetError());
+          if (data.empty()) {
+            return;
+          }
+        }
+        wireData.insert(wireData.end(), data.begin(), data.end());
+        if (handleData) {
+          handleData(data);
+        }
+      });
+      clientPipe->end.connect([this]() { Finish(); });
+    });
+  }
+
+  std::function<void()> setupWebSocket;
+  std::function<void(std::string_view)> handleData;
+  std::vector<uint8_t> wireData;
+  std::shared_ptr<WebSocket> ws;
+  HttpParser resp{HttpParser::kResponse};
+  bool headersDone = false;
+};
+
+//
+// Terminate closes the endpoint but doesn't send a close frame.
+//
+
+TEST_F(WebSocketServerTest, Terminate) {
+  int gotClosed = 0;
+  setupWebSocket = [&] {
+    ws->open.connect([&](std::string_view) { ws->Terminate(); });
+    ws->closed.connect([&](uint16_t code, std::string_view reason) {
+      ++gotClosed;
+      ASSERT_EQ(code, 1006) << "reason: " << reason;
+    });
+  };
+
+  loop->Run();
+
+  ASSERT_TRUE(wireData.empty());  // terminate doesn't send data
+  ASSERT_EQ(gotClosed, 1);
+}
+
+TEST_F(WebSocketServerTest, TerminateCode) {
+  int gotClosed = 0;
+  setupWebSocket = [&] {
+    ws->open.connect([&](std::string_view) { ws->Terminate(1000); });
+    ws->closed.connect([&](uint16_t code, std::string_view reason) {
+      ++gotClosed;
+      ASSERT_EQ(code, 1000) << "reason: " << reason;
+    });
+  };
+
+  loop->Run();
+
+  ASSERT_TRUE(wireData.empty());  // terminate doesn't send data
+  ASSERT_EQ(gotClosed, 1);
+}
+
+TEST_F(WebSocketServerTest, TerminateReason) {
+  int gotClosed = 0;
+  setupWebSocket = [&] {
+    ws->open.connect([&](std::string_view) { ws->Terminate(1000, "reason"); });
+    ws->closed.connect([&](uint16_t code, std::string_view reason) {
+      ++gotClosed;
+      ASSERT_EQ(code, 1000);
+      ASSERT_EQ(reason, "reason");
+    });
+  };
+
+  loop->Run();
+
+  ASSERT_TRUE(wireData.empty());  // terminate doesn't send data
+  ASSERT_EQ(gotClosed, 1);
+}
+
+//
+// Close() sends a close frame.
+//
+
+TEST_F(WebSocketServerTest, CloseBasic) {
+  int gotClosed = 0;
+  setupWebSocket = [&] {
+    ws->open.connect([&](std::string_view) { ws->Close(); });
+    ws->closed.connect([&](uint16_t code, std::string_view reason) {
+      ++gotClosed;
+      ASSERT_EQ(code, 1005) << "reason: " << reason;
+    });
+  };
+  // need to respond with close for server to finish shutdown
+  auto message = BuildMessage(0x08, true, true, {});
+  handleData = [&](std::string_view) {
+    clientPipe->Write({{message}}, [&](auto bufs, uv::Error) {});
+  };
+
+  loop->Run();
+
+  auto expectData = BuildMessage(0x08, true, false, {});
+  ASSERT_EQ(wireData, expectData);
+  ASSERT_EQ(gotClosed, 1);
+}
+
+TEST_F(WebSocketServerTest, CloseCode) {
+  int gotClosed = 0;
+  setupWebSocket = [&] {
+    ws->open.connect([&](std::string_view) { ws->Close(1000); });
+    ws->closed.connect([&](uint16_t code, std::string_view reason) {
+      ++gotClosed;
+      ASSERT_EQ(code, 1000) << "reason: " << reason;
+    });
+  };
+  // need to respond with close for server to finish shutdown
+  const uint8_t contents[] = {0x03u, 0xe8u};
+  auto message = BuildMessage(0x08, true, true, contents);
+  handleData = [&](std::string_view) {
+    clientPipe->Write({{message}}, [&](auto bufs, uv::Error) {});
+  };
+
+  loop->Run();
+
+  auto expectData = BuildMessage(0x08, true, false, contents);
+  ASSERT_EQ(wireData, expectData);
+  ASSERT_EQ(gotClosed, 1);
+}
+
+TEST_F(WebSocketServerTest, CloseReason) {
+  int gotClosed = 0;
+  setupWebSocket = [&] {
+    ws->open.connect([&](std::string_view) { ws->Close(1000, "hangup"); });
+    ws->closed.connect([&](uint16_t code, std::string_view reason) {
+      ++gotClosed;
+      ASSERT_EQ(code, 1000);
+      ASSERT_EQ(reason, "hangup");
+    });
+  };
+  // need to respond with close for server to finish shutdown
+  const uint8_t contents[] = {0x03u, 0xe8u, 'h', 'a', 'n', 'g', 'u', 'p'};
+  auto message = BuildMessage(0x08, true, true, contents);
+  handleData = [&](std::string_view) {
+    clientPipe->Write({{message}}, [&](auto bufs, uv::Error) {});
+  };
+
+  loop->Run();
+
+  auto expectData = BuildMessage(0x08, true, false, contents);
+  ASSERT_EQ(wireData, expectData);
+  ASSERT_EQ(gotClosed, 1);
+}
+
+//
+// Receiving a close frame results in closure and echoing the close frame.
+//
+
+TEST_F(WebSocketServerTest, ReceiveCloseBasic) {
+  int gotClosed = 0;
+  setupWebSocket = [&] {
+    ws->closed.connect([&](uint16_t code, std::string_view reason) {
+      ++gotClosed;
+      ASSERT_EQ(code, 1005) << "reason: " << reason;
+    });
+  };
+  auto message = BuildMessage(0x08, true, true, {});
+  resp.headersComplete.connect([&](bool) {
+    clientPipe->Write({{message}}, [&](auto bufs, uv::Error) {});
+  });
+
+  loop->Run();
+
+  // the endpoint should echo the message
+  auto expectData = BuildMessage(0x08, true, false, {});
+  ASSERT_EQ(wireData, expectData);
+  ASSERT_EQ(gotClosed, 1);
+}
+
+TEST_F(WebSocketServerTest, ReceiveCloseCode) {
+  int gotClosed = 0;
+  setupWebSocket = [&] {
+    ws->closed.connect([&](uint16_t code, std::string_view reason) {
+      ++gotClosed;
+      ASSERT_EQ(code, 1000) << "reason: " << reason;
+    });
+  };
+  const uint8_t contents[] = {0x03u, 0xe8u};
+  auto message = BuildMessage(0x08, true, true, contents);
+  resp.headersComplete.connect([&](bool) {
+    clientPipe->Write({{message}}, [&](auto bufs, uv::Error) {});
+  });
+
+  loop->Run();
+
+  // the endpoint should echo the message
+  auto expectData = BuildMessage(0x08, true, false, contents);
+  ASSERT_EQ(wireData, expectData);
+  ASSERT_EQ(gotClosed, 1);
+}
+
+TEST_F(WebSocketServerTest, ReceiveCloseReason) {
+  int gotClosed = 0;
+  setupWebSocket = [&] {
+    ws->closed.connect([&](uint16_t code, std::string_view reason) {
+      ++gotClosed;
+      ASSERT_EQ(code, 1000);
+      ASSERT_EQ(reason, "hangup");
+    });
+  };
+  const uint8_t contents[] = {0x03u, 0xe8u, 'h', 'a', 'n', 'g', 'u', 'p'};
+  auto message = BuildMessage(0x08, true, true, contents);
+  resp.headersComplete.connect([&](bool) {
+    clientPipe->Write({{message}}, [&](auto bufs, uv::Error) {});
+  });
+
+  loop->Run();
+
+  // the endpoint should echo the message
+  auto expectData = BuildMessage(0x08, true, false, contents);
+  ASSERT_EQ(wireData, expectData);
+  ASSERT_EQ(gotClosed, 1);
+}
+
+//
+// If an unknown opcode is received, the receiving endpoint MUST _Fail the
+// WebSocket Connection_.
+//
+
+class WebSocketServerBadOpcodeTest
+    : public WebSocketServerTest,
+      public ::testing::WithParamInterface<uint8_t> {};
+
+INSTANTIATE_TEST_SUITE_P(WebSocketServerBadOpcodeTests,
+                         WebSocketServerBadOpcodeTest,
+                         ::testing::Values(3, 4, 5, 6, 7, 0xb, 0xc, 0xd, 0xe,
+                                           0xf));
+
+TEST_P(WebSocketServerBadOpcodeTest, Receive) {
+  int gotCallback = 0;
+  std::vector<uint8_t> data(4, 0x03);
+  setupWebSocket = [&] {
+    ws->closed.connect([&](uint16_t code, std::string_view reason) {
+      ++gotCallback;
+      ASSERT_EQ(code, 1002) << "reason: " << reason;
+    });
+  };
+  auto message = BuildMessage(GetParam(), true, true, data);
+  resp.headersComplete.connect([&](bool) {
+    clientPipe->Write({{message}}, [&](auto bufs, uv::Error) {});
+  });
+
+  loop->Run();
+
+  ASSERT_EQ(gotCallback, 1);
+}
+
+//
+// Control frames themselves MUST NOT be fragmented.
+//
+
+class WebSocketServerControlFrameTest
+    : public WebSocketServerTest,
+      public ::testing::WithParamInterface<uint8_t> {};
+
+INSTANTIATE_TEST_SUITE_P(WebSocketServerControlFrameTests,
+                         WebSocketServerControlFrameTest,
+                         ::testing::Values(0x8, 0x9, 0xa));
+
+TEST_P(WebSocketServerControlFrameTest, ReceiveFragment) {
+  int gotCallback = 0;
+  std::vector<uint8_t> data(4, 0x03);
+  setupWebSocket = [&] {
+    ws->closed.connect([&](uint16_t code, std::string_view reason) {
+      ++gotCallback;
+      ASSERT_EQ(code, 1002) << "reason: " << reason;
+    });
+  };
+  auto message = BuildMessage(GetParam(), false, true, data);
+  resp.headersComplete.connect([&](bool) {
+    clientPipe->Write({{message}}, [&](auto bufs, uv::Error) {});
+  });
+
+  loop->Run();
+
+  ASSERT_EQ(gotCallback, 1);
+}
+
+//
+// A fragmented message consists of a single frame with the FIN bit
+// clear and an opcode other than 0, followed by zero or more frames
+// with the FIN bit clear and the opcode set to 0, and terminated by
+// a single frame with the FIN bit set and an opcode of 0.
+//
+
+// No previous message
+TEST_F(WebSocketServerTest, ReceiveFragmentInvalidNoPrevFrame) {
+  int gotCallback = 0;
+  std::vector<uint8_t> data(4, 0x03);
+  setupWebSocket = [&] {
+    ws->closed.connect([&](uint16_t code, std::string_view reason) {
+      ++gotCallback;
+      ASSERT_EQ(code, 1002) << "reason: " << reason;
+    });
+  };
+  auto message = BuildMessage(0x00, false, true, data);
+  resp.headersComplete.connect([&](bool) {
+    clientPipe->Write({{message}}, [&](auto bufs, uv::Error) {});
+  });
+
+  loop->Run();
+
+  ASSERT_EQ(gotCallback, 1);
+}
+
+// No previous message with FIN=1.
+TEST_F(WebSocketServerTest, ReceiveFragmentInvalidNoPrevFragment) {
+  int gotCallback = 0;
+  std::vector<uint8_t> data(4, 0x03);
+  setupWebSocket = [&] {
+    ws->closed.connect([&](uint16_t code, std::string_view reason) {
+      ++gotCallback;
+      ASSERT_EQ(code, 1002) << "reason: " << reason;
+    });
+  };
+  auto message = BuildMessage(0x01, true, true, {});  // FIN=1
+  auto message2 = BuildMessage(0x00, false, true, data);
+  resp.headersComplete.connect([&](bool) {
+    clientPipe->Write({{message}, {message2}}, [&](auto bufs, uv::Error) {});
+  });
+
+  loop->Run();
+
+  ASSERT_EQ(gotCallback, 1);
+}
+
+// Incomplete fragment
+TEST_F(WebSocketServerTest, ReceiveFragmentInvalidIncomplete) {
+  int gotCallback = 0;
+  setupWebSocket = [&] {
+    ws->closed.connect([&](uint16_t code, std::string_view reason) {
+      ++gotCallback;
+      ASSERT_EQ(code, 1002) << "reason: " << reason;
+    });
+  };
+  auto message = BuildMessage(0x01, false, true, {});
+  auto message2 = BuildMessage(0x00, false, true, {});
+  auto message3 = BuildMessage(0x01, true, true, {});
+  resp.headersComplete.connect([&](bool) {
+    clientPipe->Write({{message}, {message2}, {message3}},
+                      [&](auto bufs, uv::Error) {});
+  });
+
+  loop->Run();
+
+  ASSERT_EQ(gotCallback, 1);
+}
+
+// Normally fragments are combined into a single callback
+TEST_F(WebSocketServerTest, ReceiveFragment) {
+  int gotCallback = 0;
+
+  std::vector<uint8_t> data(4, 0x03);
+  std::vector<uint8_t> data2(4, 0x04);
+  std::vector<uint8_t> data3(4, 0x05);
+  std::vector<uint8_t> combData{data};
+  combData.insert(combData.end(), data2.begin(), data2.end());
+  combData.insert(combData.end(), data3.begin(), data3.end());
+
+  setupWebSocket = [&] {
+    ws->binary.connect([&](auto inData, bool fin) {
+      ++gotCallback;
+      ws->Terminate();
+      ASSERT_TRUE(fin);
+      std::vector<uint8_t> recvData{inData.begin(), inData.end()};
+      ASSERT_EQ(combData, recvData);
+    });
+  };
+
+  auto message = BuildMessage(0x02, false, true, data);
+  auto message2 = BuildMessage(0x00, false, true, data2);
+  auto message3 = BuildMessage(0x00, true, true, data3);
+  resp.headersComplete.connect([&](bool) {
+    clientPipe->Write({{message}, {message2}, {message3}},
+                      [&](auto bufs, uv::Error) {});
+  });
+
+  loop->Run();
+
+  ASSERT_EQ(gotCallback, 1);
+}
+
+// But can be configured for multiple callbacks
+TEST_F(WebSocketServerTest, ReceiveFragmentSeparate) {
+  int gotCallback = 0;
+
+  std::vector<uint8_t> data(4, 0x03);
+  std::vector<uint8_t> data2(4, 0x04);
+  std::vector<uint8_t> data3(4, 0x05);
+  std::vector<uint8_t> combData{data};
+  combData.insert(combData.end(), data2.begin(), data2.end());
+  combData.insert(combData.end(), data3.begin(), data3.end());
+
+  setupWebSocket = [&] {
+    ws->SetCombineFragments(false);
+    ws->binary.connect([&](auto inData, bool fin) {
+      std::vector<uint8_t> recvData{inData.begin(), inData.end()};
+      switch (++gotCallback) {
+        case 1:
+          ASSERT_FALSE(fin);
+          ASSERT_EQ(data, recvData);
+          break;
+        case 2:
+          ASSERT_FALSE(fin);
+          ASSERT_EQ(data2, recvData);
+          break;
+        case 3:
+          ws->Terminate();
+          ASSERT_TRUE(fin);
+          ASSERT_EQ(data3, recvData);
+          break;
+        default:
+          FAIL() << "too many callbacks";
+          break;
+      }
+    });
+  };
+
+  auto message = BuildMessage(0x02, false, true, data);
+  auto message2 = BuildMessage(0x00, false, true, data2);
+  auto message3 = BuildMessage(0x00, true, true, data3);
+  resp.headersComplete.connect([&](bool) {
+    clientPipe->Write({{message}, {message2}, {message3}},
+                      [&](auto bufs, uv::Error) {});
+  });
+
+  loop->Run();
+
+  ASSERT_EQ(gotCallback, 3);
+}
+
+//
+// Maximum message size is limited.
+//
+
+// Single message
+TEST_F(WebSocketServerTest, ReceiveTooLarge) {
+  int gotCallback = 0;
+  std::vector<uint8_t> data(2048, 0x03u);
+  setupWebSocket = [&] {
+    ws->SetMaxMessageSize(1024);
+    ws->binary.connect([&](auto, bool) {
+      ws->Terminate();
+      FAIL() << "Should not have gotten unmasked message";
+    });
+    ws->closed.connect([&](uint16_t code, std::string_view reason) {
+      ++gotCallback;
+      ASSERT_EQ(code, 1009) << "reason: " << reason;
+    });
+  };
+  auto message = BuildMessage(0x01, true, true, data);
+  resp.headersComplete.connect([&](bool) {
+    clientPipe->Write({{message}}, [&](auto bufs, uv::Error) {});
+  });
+
+  loop->Run();
+
+  ASSERT_EQ(gotCallback, 1);
+}
+
+// Applied across fragments if combining
+TEST_F(WebSocketServerTest, ReceiveTooLargeFragmented) {
+  int gotCallback = 0;
+  std::vector<uint8_t> data(768, 0x03u);
+  setupWebSocket = [&] {
+    ws->SetMaxMessageSize(1024);
+    ws->binary.connect([&](auto, bool) {
+      ws->Terminate();
+      FAIL() << "Should not have gotten unmasked message";
+    });
+    ws->closed.connect([&](uint16_t code, std::string_view reason) {
+      ++gotCallback;
+      ASSERT_EQ(code, 1009) << "reason: " << reason;
+    });
+  };
+  auto message = BuildMessage(0x01, false, true, data);
+  auto message2 = BuildMessage(0x00, true, true, data);
+  resp.headersComplete.connect([&](bool) {
+    clientPipe->Write({{message}, {message2}}, [&](auto bufs, uv::Error) {});
+  });
+
+  loop->Run();
+
+  ASSERT_EQ(gotCallback, 1);
+}
+
+//
+// Send and receive data.
+//
+
+class WebSocketServerDataTest : public WebSocketServerTest,
+                                public ::testing::WithParamInterface<size_t> {};
+
+INSTANTIATE_TEST_SUITE_P(WebSocketServerDataTests, WebSocketServerDataTest,
+                         ::testing::Values(0, 1, 125, 126, 65535, 65536));
+
+TEST_P(WebSocketServerDataTest, SendText) {
+  int gotCallback = 0;
+  std::vector<uint8_t> data(GetParam(), ' ');
+  setupWebSocket = [&] {
+    ws->open.connect([&](std::string_view) {
+      ws->SendText({{data}}, [&](auto bufs, uv::Error) {
+        ++gotCallback;
+        ws->Terminate();
+        ASSERT_FALSE(bufs.empty());
+        ASSERT_EQ(bufs[0].base, reinterpret_cast<const char*>(data.data()));
+      });
+    });
+  };
+
+  loop->Run();
+
+  auto expectData = BuildMessage(0x01, true, false, data);
+  ASSERT_EQ(wireData, expectData);
+  ASSERT_EQ(gotCallback, 1);
+}
+
+TEST_P(WebSocketServerDataTest, SendBinary) {
+  int gotCallback = 0;
+  std::vector<uint8_t> data(GetParam(), 0x03u);
+  setupWebSocket = [&] {
+    ws->open.connect([&](std::string_view) {
+      ws->SendBinary({{data}}, [&](auto bufs, uv::Error) {
+        ++gotCallback;
+        ws->Terminate();
+        ASSERT_FALSE(bufs.empty());
+        ASSERT_EQ(bufs[0].base, reinterpret_cast<const char*>(data.data()));
+      });
+    });
+  };
+
+  loop->Run();
+
+  auto expectData = BuildMessage(0x02, true, false, data);
+  ASSERT_EQ(wireData, expectData);
+  ASSERT_EQ(gotCallback, 1);
+}
+
+TEST_P(WebSocketServerDataTest, SendPing) {
+  int gotCallback = 0;
+  std::vector<uint8_t> data(GetParam(), 0x03u);
+  setupWebSocket = [&] {
+    ws->open.connect([&](std::string_view) {
+      ws->SendPing({{data}}, [&](auto bufs, uv::Error) {
+        ++gotCallback;
+        ws->Terminate();
+        ASSERT_FALSE(bufs.empty());
+        ASSERT_EQ(bufs[0].base, reinterpret_cast<const char*>(data.data()));
+      });
+    });
+  };
+
+  loop->Run();
+
+  auto expectData = BuildMessage(0x09, true, false, data);
+  ASSERT_EQ(wireData, expectData);
+  ASSERT_EQ(gotCallback, 1);
+}
+
+TEST_P(WebSocketServerDataTest, SendPong) {
+  int gotCallback = 0;
+  std::vector<uint8_t> data(GetParam(), 0x03u);
+  setupWebSocket = [&] {
+    ws->open.connect([&](std::string_view) {
+      ws->SendPong({{data}}, [&](auto bufs, uv::Error) {
+        ++gotCallback;
+        ws->Terminate();
+        ASSERT_FALSE(bufs.empty());
+        ASSERT_EQ(bufs[0].base, reinterpret_cast<const char*>(data.data()));
+      });
+    });
+  };
+
+  loop->Run();
+
+  auto expectData = BuildMessage(0x0a, true, false, data);
+  ASSERT_EQ(wireData, expectData);
+  ASSERT_EQ(gotCallback, 1);
+}
+
+TEST_P(WebSocketServerDataTest, ReceiveText) {
+  int gotCallback = 0;
+  std::vector<uint8_t> data(GetParam(), ' ');
+  setupWebSocket = [&] {
+    ws->text.connect([&](std::string_view inData, bool fin) {
+      ++gotCallback;
+      ws->Terminate();
+      ASSERT_TRUE(fin);
+      std::vector<uint8_t> recvData;
+      recvData.insert(recvData.end(), inData.begin(), inData.end());
+      ASSERT_EQ(data, recvData);
+    });
+  };
+  auto message = BuildMessage(0x01, true, true, data);
+  resp.headersComplete.connect([&](bool) {
+    clientPipe->Write({{message}}, [&](auto bufs, uv::Error) {});
+  });
+
+  loop->Run();
+
+  ASSERT_EQ(gotCallback, 1);
+}
+
+TEST_P(WebSocketServerDataTest, ReceiveBinary) {
+  int gotCallback = 0;
+  std::vector<uint8_t> data(GetParam(), 0x03u);
+  setupWebSocket = [&] {
+    ws->binary.connect([&](auto inData, bool fin) {
+      ++gotCallback;
+      ws->Terminate();
+      ASSERT_TRUE(fin);
+      std::vector<uint8_t> recvData{inData.begin(), inData.end()};
+      ASSERT_EQ(data, recvData);
+    });
+  };
+  auto message = BuildMessage(0x02, true, true, data);
+  resp.headersComplete.connect([&](bool) {
+    clientPipe->Write({{message}}, [&](auto bufs, uv::Error) {});
+  });
+
+  loop->Run();
+
+  ASSERT_EQ(gotCallback, 1);
+}
+
+TEST_P(WebSocketServerDataTest, ReceivePing) {
+  int gotCallback = 0;
+  std::vector<uint8_t> data(GetParam(), 0x03u);
+  setupWebSocket = [&] {
+    ws->ping.connect([&](auto inData) {
+      ++gotCallback;
+      ws->Terminate();
+      std::vector<uint8_t> recvData{inData.begin(), inData.end()};
+      ASSERT_EQ(data, recvData);
+    });
+  };
+  auto message = BuildMessage(0x09, true, true, data);
+  resp.headersComplete.connect([&](bool) {
+    clientPipe->Write({{message}}, [&](auto bufs, uv::Error) {});
+  });
+
+  loop->Run();
+
+  ASSERT_EQ(gotCallback, 1);
+}
+
+TEST_P(WebSocketServerDataTest, ReceivePong) {
+  int gotCallback = 0;
+  std::vector<uint8_t> data(GetParam(), 0x03u);
+  setupWebSocket = [&] {
+    ws->pong.connect([&](auto inData) {
+      ++gotCallback;
+      ws->Terminate();
+      std::vector<uint8_t> recvData{inData.begin(), inData.end()};
+      ASSERT_EQ(data, recvData);
+    });
+  };
+  auto message = BuildMessage(0x0a, true, true, data);
+  resp.headersComplete.connect([&](bool) {
+    clientPipe->Write({{message}}, [&](auto bufs, uv::Error) {});
+  });
+
+  loop->Run();
+
+  ASSERT_EQ(gotCallback, 1);
+}
+
+//
+// The server must close the connection if an unmasked frame is received.
+//
+
+TEST_P(WebSocketServerDataTest, ReceiveUnmasked) {
+  int gotCallback = 0;
+  std::vector<uint8_t> data(GetParam(), ' ');
+  setupWebSocket = [&] {
+    ws->text.connect([&](std::string_view, bool) {
+      ws->Terminate();
+      FAIL() << "Should not have gotten unmasked message";
+    });
+    ws->closed.connect([&](uint16_t code, std::string_view reason) {
+      ++gotCallback;
+      ASSERT_EQ(code, 1002) << "reason: " << reason;
+    });
+  };
+  auto message = BuildMessage(0x01, true, false, data);
+  resp.headersComplete.connect([&](bool) {
+    clientPipe->Write({{message}}, [&](auto bufs, uv::Error) {});
+  });
+
+  loop->Run();
+
+  ASSERT_EQ(gotCallback, 1);
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib/wpinet/src/test/native/cpp/WebSocketTest.cpp b/third_party/allwpilib/wpinet/src/test/native/cpp/WebSocketTest.cpp
new file mode 100644
index 0000000..e5f03de
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/test/native/cpp/WebSocketTest.cpp
@@ -0,0 +1,379 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/WebSocket.h"  // NOLINT(build/include_order)
+
+#include "WebSocketTest.h"
+
+#include <wpi/StringExtras.h>
+
+#include "wpinet/HttpParser.h"
+
+namespace wpi {
+
+#ifdef _WIN32
+const char* WebSocketTest::pipeName = "\\\\.\\pipe\\websocket-unit-test";
+#else
+const char* WebSocketTest::pipeName = "/tmp/websocket-unit-test";
+#endif
+const uint8_t WebSocketTest::testMask[4] = {0x11, 0x22, 0x33, 0x44};
+
+void WebSocketTest::SetUpTestCase() {
+#ifndef _WIN32
+  unlink(pipeName);
+#endif
+}
+
+std::vector<uint8_t> WebSocketTest::BuildHeader(uint8_t opcode, bool fin,
+                                                bool masking, uint64_t len) {
+  std::vector<uint8_t> data;
+  data.push_back(opcode | (fin ? 0x80u : 0x00u));
+  if (len < 126) {
+    data.push_back(len | (masking ? 0x80 : 0x00u));
+  } else if (len < 65536) {
+    data.push_back(126u | (masking ? 0x80 : 0x00u));
+    data.push_back(len >> 8);
+    data.push_back(len & 0xff);
+  } else {
+    data.push_back(127u | (masking ? 0x80u : 0x00u));
+    for (int i = 56; i >= 0; i -= 8) {
+      data.push_back((len >> i) & 0xff);
+    }
+  }
+  if (masking) {
+    data.insert(data.end(), &testMask[0], &testMask[4]);
+  }
+  return data;
+}
+
+std::vector<uint8_t> WebSocketTest::BuildMessage(
+    uint8_t opcode, bool fin, bool masking, std::span<const uint8_t> data) {
+  auto finalData = BuildHeader(opcode, fin, masking, data.size());
+  size_t headerSize = finalData.size();
+  finalData.insert(finalData.end(), data.begin(), data.end());
+  if (masking) {
+    uint8_t mask[4] = {finalData[headerSize - 4], finalData[headerSize - 3],
+                       finalData[headerSize - 2], finalData[headerSize - 1]};
+    int n = 0;
+    for (size_t i = headerSize, end = finalData.size(); i < end; ++i) {
+      finalData[i] ^= mask[n++];
+      if (n >= 4) {
+        n = 0;
+      }
+    }
+  }
+  return finalData;
+}
+
+// If the message is masked, changes the mask to match the mask set by
+// BuildHeader() by unmasking and remasking.
+void WebSocketTest::AdjustMasking(std::span<uint8_t> message) {
+  if (message.size() < 2) {
+    return;
+  }
+  if ((message[1] & 0x80) == 0) {
+    return;  // not masked
+  }
+  size_t maskPos;
+  uint8_t len = message[1] & 0x7f;
+  if (len == 126) {
+    maskPos = 4;
+  } else if (len == 127) {
+    maskPos = 10;
+  } else {
+    maskPos = 2;
+  }
+  uint8_t mask[4] = {message[maskPos], message[maskPos + 1],
+                     message[maskPos + 2], message[maskPos + 3]};
+  message[maskPos] = testMask[0];
+  message[maskPos + 1] = testMask[1];
+  message[maskPos + 2] = testMask[2];
+  message[maskPos + 3] = testMask[3];
+  int n = 0;
+  for (auto& ch : message.subspan(maskPos + 4)) {
+    ch ^= mask[n] ^ testMask[n];
+    if (++n >= 4) {
+      n = 0;
+    }
+  }
+}
+
+TEST_F(WebSocketTest, CreateClientBasic) {
+  int gotHost = 0;
+  int gotUpgrade = 0;
+  int gotConnection = 0;
+  int gotKey = 0;
+  int gotVersion = 0;
+
+  HttpParser req{HttpParser::kRequest};
+  req.url.connect([](std::string_view url) { ASSERT_EQ(url, "/test"); });
+  req.header.connect([&](std::string_view name, std::string_view value) {
+    if (equals_lower(name, "host")) {
+      ASSERT_EQ(value, pipeName);
+      ++gotHost;
+    } else if (equals_lower(name, "upgrade")) {
+      ASSERT_EQ(value, "websocket");
+      ++gotUpgrade;
+    } else if (equals_lower(name, "connection")) {
+      ASSERT_EQ(value, "Upgrade");
+      ++gotConnection;
+    } else if (equals_lower(name, "sec-websocket-key")) {
+      ++gotKey;
+    } else if (equals_lower(name, "sec-websocket-version")) {
+      ASSERT_EQ(value, "13");
+      ++gotVersion;
+    } else {
+      FAIL() << "unexpected header " << name;
+    }
+  });
+  req.headersComplete.connect([&](bool) { Finish(); });
+
+  serverPipe->Listen([&]() {
+    auto conn = serverPipe->Accept();
+    conn->StartRead();
+    conn->data.connect([&](uv::Buffer& buf, size_t size) {
+      req.Execute(std::string_view{buf.base, size});
+      if (req.HasError()) {
+        Finish();
+      }
+      ASSERT_EQ(req.GetError(), HPE_OK) << http_errno_name(req.GetError());
+    });
+  });
+  clientPipe->Connect(pipeName, [&]() {
+    auto ws = WebSocket::CreateClient(*clientPipe, "/test", pipeName);
+  });
+
+  loop->Run();
+
+  if (HasFatalFailure()) {
+    return;
+  }
+  ASSERT_EQ(gotHost, 1);
+  ASSERT_EQ(gotUpgrade, 1);
+  ASSERT_EQ(gotConnection, 1);
+  ASSERT_EQ(gotKey, 1);
+  ASSERT_EQ(gotVersion, 1);
+}
+
+TEST_F(WebSocketTest, CreateClientExtraHeaders) {
+  int gotExtra1 = 0;
+  int gotExtra2 = 0;
+  HttpParser req{HttpParser::kRequest};
+  req.header.connect([&](std::string_view name, std::string_view value) {
+    if (equals(name, "Extra1")) {
+      ASSERT_EQ(value, "Data1");
+      ++gotExtra1;
+    } else if (equals(name, "Extra2")) {
+      ASSERT_EQ(value, "Data2");
+      ++gotExtra2;
+    }
+  });
+  req.headersComplete.connect([&](bool) { Finish(); });
+
+  serverPipe->Listen([&]() {
+    auto conn = serverPipe->Accept();
+    conn->StartRead();
+    conn->data.connect([&](uv::Buffer& buf, size_t size) {
+      req.Execute(std::string_view{buf.base, size});
+      if (req.HasError()) {
+        Finish();
+      }
+      ASSERT_EQ(req.GetError(), HPE_OK) << http_errno_name(req.GetError());
+    });
+  });
+  clientPipe->Connect(pipeName, [&]() {
+    WebSocket::ClientOptions options;
+    SmallVector<std::pair<std::string_view, std::string_view>, 4> extraHeaders;
+    extraHeaders.emplace_back("Extra1", "Data1");
+    extraHeaders.emplace_back("Extra2", "Data2");
+    options.extraHeaders = extraHeaders;
+    auto ws =
+        WebSocket::CreateClient(*clientPipe, "/test", pipeName, {}, options);
+  });
+
+  loop->Run();
+
+  if (HasFatalFailure()) {
+    return;
+  }
+  ASSERT_EQ(gotExtra1, 1);
+  ASSERT_EQ(gotExtra2, 1);
+}
+
+TEST_F(WebSocketTest, CreateClientTimeout) {
+  int gotClosed = 0;
+  serverPipe->Listen([&]() { auto conn = serverPipe->Accept(); });
+  clientPipe->Connect(pipeName, [&]() {
+    WebSocket::ClientOptions options;
+    options.handshakeTimeout = uv::Timer::Time{100};
+    auto ws =
+        WebSocket::CreateClient(*clientPipe, "/test", pipeName, {}, options);
+    ws->closed.connect([&](uint16_t code, std::string_view) {
+      Finish();
+      ++gotClosed;
+      ASSERT_EQ(code, 1006);
+    });
+  });
+
+  loop->Run();
+
+  if (HasFatalFailure()) {
+    return;
+  }
+  ASSERT_EQ(gotClosed, 1);
+}
+
+TEST_F(WebSocketTest, CreateServerBasic) {
+  int gotStatus = 0;
+  int gotUpgrade = 0;
+  int gotConnection = 0;
+  int gotAccept = 0;
+  int gotOpen = 0;
+
+  HttpParser resp{HttpParser::kResponse};
+  resp.status.connect([&](std::string_view status) {
+    ++gotStatus;
+    ASSERT_EQ(resp.GetStatusCode(), 101u) << "status: " << status;
+  });
+  resp.header.connect([&](std::string_view name, std::string_view value) {
+    if (equals_lower(name, "upgrade")) {
+      ASSERT_EQ(value, "websocket");
+      ++gotUpgrade;
+    } else if (equals_lower(name, "connection")) {
+      ASSERT_EQ(value, "Upgrade");
+      ++gotConnection;
+    } else if (equals_lower(name, "sec-websocket-accept")) {
+      ASSERT_EQ(value, "s3pPLMBiTxaQ9kYGzzhZRbK+xOo=");
+      ++gotAccept;
+    } else {
+      FAIL() << "unexpected header " << name;
+    }
+  });
+  resp.headersComplete.connect([&](bool) { Finish(); });
+
+  serverPipe->Listen([&]() {
+    auto conn = serverPipe->Accept();
+    auto ws = WebSocket::CreateServer(*conn, "dGhlIHNhbXBsZSBub25jZQ==", "13");
+    ws->open.connect([&](std::string_view protocol) {
+      ++gotOpen;
+      ASSERT_TRUE(protocol.empty());
+    });
+  });
+  clientPipe->Connect(pipeName, [&] {
+    clientPipe->StartRead();
+    clientPipe->data.connect([&](uv::Buffer& buf, size_t size) {
+      resp.Execute(std::string_view{buf.base, size});
+      if (resp.HasError()) {
+        Finish();
+      }
+      ASSERT_EQ(resp.GetError(), HPE_OK) << http_errno_name(resp.GetError());
+    });
+  });
+
+  loop->Run();
+
+  if (HasFatalFailure()) {
+    return;
+  }
+  ASSERT_EQ(gotStatus, 1);
+  ASSERT_EQ(gotUpgrade, 1);
+  ASSERT_EQ(gotConnection, 1);
+  ASSERT_EQ(gotAccept, 1);
+  ASSERT_EQ(gotOpen, 1);
+}
+
+TEST_F(WebSocketTest, CreateServerProtocol) {
+  int gotProtocol = 0;
+  int gotOpen = 0;
+
+  HttpParser resp{HttpParser::kResponse};
+  resp.header.connect([&](std::string_view name, std::string_view value) {
+    if (equals_lower(name, "sec-websocket-protocol")) {
+      ++gotProtocol;
+      ASSERT_EQ(value, "myProtocol");
+    }
+  });
+  resp.headersComplete.connect([&](bool) { Finish(); });
+
+  serverPipe->Listen([&]() {
+    auto conn = serverPipe->Accept();
+    auto ws = WebSocket::CreateServer(*conn, "foo", "13", "myProtocol");
+    ws->open.connect([&](std::string_view protocol) {
+      ++gotOpen;
+      ASSERT_EQ(protocol, "myProtocol");
+    });
+  });
+  clientPipe->Connect(pipeName, [&] {
+    clientPipe->StartRead();
+    clientPipe->data.connect([&](uv::Buffer& buf, size_t size) {
+      resp.Execute(std::string_view{buf.base, size});
+      if (resp.HasError()) {
+        Finish();
+      }
+      ASSERT_EQ(resp.GetError(), HPE_OK) << http_errno_name(resp.GetError());
+    });
+  });
+
+  loop->Run();
+
+  if (HasFatalFailure()) {
+    return;
+  }
+  ASSERT_EQ(gotProtocol, 1);
+  ASSERT_EQ(gotOpen, 1);
+}
+
+TEST_F(WebSocketTest, CreateServerBadVersion) {
+  int gotStatus = 0;
+  int gotVersion = 0;
+  int gotUpgrade = 0;
+
+  HttpParser resp{HttpParser::kResponse};
+  resp.status.connect([&](std::string_view status) {
+    ++gotStatus;
+    ASSERT_EQ(resp.GetStatusCode(), 426u) << "status: " << status;
+  });
+  resp.header.connect([&](std::string_view name, std::string_view value) {
+    if (equals_lower(name, "sec-websocket-version")) {
+      ++gotVersion;
+      ASSERT_EQ(value, "13");
+    } else if (equals_lower(name, "upgrade")) {
+      ++gotUpgrade;
+      ASSERT_EQ(value, "WebSocket");
+    } else {
+      FAIL() << "unexpected header " << name;
+    }
+  });
+  resp.headersComplete.connect([&](bool) { Finish(); });
+
+  serverPipe->Listen([&] {
+    auto conn = serverPipe->Accept();
+    auto ws = WebSocket::CreateServer(*conn, "foo", "14");
+    ws->open.connect([&](std::string_view) {
+      Finish();
+      FAIL();
+    });
+  });
+  clientPipe->Connect(pipeName, [&] {
+    clientPipe->StartRead();
+    clientPipe->data.connect([&](uv::Buffer& buf, size_t size) {
+      resp.Execute(std::string_view{buf.base, size});
+      if (resp.HasError()) {
+        Finish();
+      }
+      ASSERT_EQ(resp.GetError(), HPE_OK) << http_errno_name(resp.GetError());
+    });
+  });
+
+  loop->Run();
+
+  if (HasFatalFailure()) {
+    return;
+  }
+  ASSERT_EQ(gotStatus, 1);
+  ASSERT_EQ(gotVersion, 1);
+  ASSERT_EQ(gotUpgrade, 1);
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib/wpinet/src/test/native/cpp/WebSocketTest.h b/third_party/allwpilib/wpinet/src/test/native/cpp/WebSocketTest.h
new file mode 100644
index 0000000..903ce00
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/test/native/cpp/WebSocketTest.h
@@ -0,0 +1,72 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <cstdio>
+#include <memory>
+#include <span>
+#include <vector>
+
+#include "gtest/gtest.h"
+#include "wpinet/uv/Loop.h"
+#include "wpinet/uv/Pipe.h"
+#include "wpinet/uv/Timer.h"
+
+namespace wpi {
+
+class WebSocketTest : public ::testing::Test {
+ public:
+  static const char* pipeName;
+
+  static void SetUpTestCase();
+
+  WebSocketTest() {
+    loop = uv::Loop::Create();
+    clientPipe = uv::Pipe::Create(loop);
+    serverPipe = uv::Pipe::Create(loop);
+
+    serverPipe->Bind(pipeName);
+
+#if 0
+    auto debugTimer = uv::Timer::Create(loop);
+    debugTimer->timeout.connect([this] {
+      std::printf("Active handles:\n");
+      uv_print_active_handles(loop->GetRaw(), stdout);
+    });
+    debugTimer->Start(uv::Timer::Time{100}, uv::Timer::Time{100});
+    debugTimer->Unreference();
+#endif
+
+    auto failTimer = uv::Timer::Create(loop);
+    failTimer->timeout.connect([this] {
+      loop->Stop();
+      FAIL() << "loop failed to terminate";
+    });
+    failTimer->Start(uv::Timer::Time{1000});
+    failTimer->Unreference();
+  }
+
+  ~WebSocketTest() override {
+    Finish();
+  }
+
+  void Finish() {
+    loop->Walk([](uv::Handle& it) { it.Close(); });
+  }
+
+  static std::vector<uint8_t> BuildHeader(uint8_t opcode, bool fin,
+                                          bool masking, uint64_t len);
+  static std::vector<uint8_t> BuildMessage(uint8_t opcode, bool fin,
+                                           bool masking,
+                                           std::span<const uint8_t> data);
+  static void AdjustMasking(std::span<uint8_t> message);
+  static const uint8_t testMask[4];
+
+  std::shared_ptr<uv::Loop> loop;
+  std::shared_ptr<uv::Pipe> clientPipe;
+  std::shared_ptr<uv::Pipe> serverPipe;
+};
+
+}  // namespace wpi
diff --git a/third_party/allwpilib/wpinet/src/test/native/cpp/WorkerThreadTest.cpp b/third_party/allwpilib/wpinet/src/test/native/cpp/WorkerThreadTest.cpp
new file mode 100644
index 0000000..8279cb1
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/test/native/cpp/WorkerThreadTest.cpp
@@ -0,0 +1,86 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/WorkerThread.h"  // NOLINT(build/include_order)
+
+#include "gtest/gtest.h"  // NOLINT(build/include_order)
+
+#include <thread>
+
+#include <wpi/condition_variable.h>
+#include <wpi/mutex.h>
+
+#include "wpinet/EventLoopRunner.h"
+#include "wpinet/uv/Loop.h"
+
+namespace wpi {
+
+TEST(WorkerThreadTest, Future) {
+  WorkerThread<int(bool)> worker;
+  future<int> f =
+      worker.QueueWork([](bool v) -> int { return v ? 1 : 2; }, true);
+  ASSERT_EQ(f.get(), 1);
+}
+
+TEST(WorkerThreadTest, FutureVoid) {
+  int callbacks = 0;
+  WorkerThread<void(int)> worker;
+  future<void> f = worker.QueueWork(
+      [&](int v) {
+        ++callbacks;
+        ASSERT_EQ(v, 3);
+      },
+      3);
+  f.get();
+  ASSERT_EQ(callbacks, 1);
+}
+
+TEST(WorkerThreadTest, Loop) {
+  mutex m;
+  condition_variable cv;
+  int callbacks = 0;
+
+  WorkerThread<int(bool)> worker;
+  EventLoopRunner runner;
+  runner.ExecSync([&](uv::Loop& loop) { worker.SetLoop(loop); });
+  worker.QueueWorkThen([](bool v) -> int { return v ? 1 : 2; },
+                       [&](int v2) {
+                         std::scoped_lock lock{m};
+                         ++callbacks;
+                         cv.notify_all();
+                         ASSERT_EQ(v2, 1);
+                       },
+                       true);
+  auto f = worker.QueueWork([&](bool) -> int { return 2; }, true);
+  ASSERT_EQ(f.get(), 2);
+
+  std::unique_lock lock{m};
+  cv.wait(lock, [&] { return callbacks == 1; });
+  ASSERT_EQ(callbacks, 1);
+}
+
+TEST(WorkerThreadTest, LoopVoid) {
+  mutex m;
+  condition_variable cv;
+  int callbacks = 0;
+
+  WorkerThread<void(bool)> worker;
+  EventLoopRunner runner;
+  runner.ExecSync([&](uv::Loop& loop) { worker.SetLoop(loop); });
+  worker.QueueWorkThen([](bool) {},
+                       [&]() {
+                         std::scoped_lock lock{m};
+                         ++callbacks;
+                         cv.notify_all();
+                       },
+                       true);
+  auto f = worker.QueueWork([](bool) {}, true);
+  f.get();
+
+  std::unique_lock lock{m};
+  cv.wait(lock, [&] { return callbacks == 1; });
+  ASSERT_EQ(callbacks, 1);
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib/wpinet/src/test/native/cpp/hostname.cpp b/third_party/allwpilib/wpinet/src/test/native/cpp/hostname.cpp
new file mode 100644
index 0000000..51a29a2
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/test/native/cpp/hostname.cpp
@@ -0,0 +1,24 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/hostname.h"
+
+#include <wpi/SmallString.h>
+#include <wpi/SmallVector.h>
+
+#include "gtest/gtest.h"
+
+namespace wpi {
+TEST(HostNameTest, HostNameNotEmpty) {
+  ASSERT_NE(GetHostname(), "");
+}
+TEST(HostNameTest, HostNameNotEmptySmallVector) {
+  SmallVector<char, 256> name;
+  ASSERT_NE(GetHostname(name), "");
+}
+TEST(HostNameTest, HostNameEq) {
+  SmallVector<char, 256> nameBuf;
+  ASSERT_EQ(GetHostname(nameBuf), GetHostname());
+}
+}  // namespace wpi
diff --git a/third_party/allwpilib/wpinet/src/test/native/cpp/main.cpp b/third_party/allwpilib/wpinet/src/test/native/cpp/main.cpp
new file mode 100644
index 0000000..09072ee
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/test/native/cpp/main.cpp
@@ -0,0 +1,11 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "gtest/gtest.h"
+
+int main(int argc, char** argv) {
+  ::testing::InitGoogleTest(&argc, argv);
+  int ret = RUN_ALL_TESTS();
+  return ret;
+}
diff --git a/third_party/allwpilib/wpinet/src/test/native/cpp/raw_uv_stream_test.cpp b/third_party/allwpilib/wpinet/src/test/native/cpp/raw_uv_stream_test.cpp
new file mode 100644
index 0000000..541da5a
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/test/native/cpp/raw_uv_stream_test.cpp
@@ -0,0 +1,71 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/raw_uv_ostream.h"  // NOLINT(build/include_order)
+
+#include "gtest/gtest.h"
+
+namespace wpi {
+
+TEST(RawUvStreamTest, BasicWrite) {
+  SmallVector<uv::Buffer, 4> bufs;
+  raw_uv_ostream os(bufs, 1024);
+  os << "12";
+  os << "34";
+  ASSERT_EQ(bufs.size(), 1u);
+  ASSERT_EQ(bufs[0].len, 4u);
+  ASSERT_EQ(bufs[0].base[0], '1');
+  ASSERT_EQ(bufs[0].base[1], '2');
+  ASSERT_EQ(bufs[0].base[2], '3');
+  ASSERT_EQ(bufs[0].base[3], '4');
+
+  for (auto& buf : bufs) {
+    buf.Deallocate();
+  }
+}
+
+TEST(RawUvStreamTest, BoundaryWrite) {
+  SmallVector<uv::Buffer, 4> bufs;
+  raw_uv_ostream os(bufs, 4);
+  ASSERT_EQ(bufs.size(), 0u);
+  os << "12";
+  ASSERT_EQ(bufs.size(), 1u);
+  os << "34";
+  ASSERT_EQ(bufs.size(), 1u);
+  os << "56";
+  ASSERT_EQ(bufs.size(), 2u);
+
+  for (auto& buf : bufs) {
+    buf.Deallocate();
+  }
+}
+
+TEST(RawUvStreamTest, LargeWrite) {
+  SmallVector<uv::Buffer, 4> bufs;
+  raw_uv_ostream os(bufs, 4);
+  os << "123456";
+  ASSERT_EQ(bufs.size(), 2u);
+  ASSERT_EQ(bufs[1].len, 2u);
+  ASSERT_EQ(bufs[1].base[0], '5');
+
+  for (auto& buf : bufs) {
+    buf.Deallocate();
+  }
+}
+
+TEST(RawUvStreamTest, PrevDataWrite) {
+  SmallVector<uv::Buffer, 4> bufs;
+  bufs.emplace_back(uv::Buffer::Allocate(1024));
+  raw_uv_ostream os(bufs, 1024);
+  os << "1234";
+  ASSERT_EQ(bufs.size(), 2u);
+  ASSERT_EQ(bufs[0].len, 1024u);
+  ASSERT_EQ(bufs[1].len, 4u);
+
+  for (auto& buf : bufs) {
+    buf.Deallocate();
+  }
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib/wpinet/src/test/native/cpp/uv/UvAsyncFunctionTest.cpp b/third_party/allwpilib/wpinet/src/test/native/cpp/uv/UvAsyncFunctionTest.cpp
new file mode 100644
index 0000000..19c1faf
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/test/native/cpp/uv/UvAsyncFunctionTest.cpp
@@ -0,0 +1,264 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/uv/AsyncFunction.h"  // NOLINT(build/include_order)
+
+#include "gtest/gtest.h"  // NOLINT(build/include_order)
+
+#include <thread>
+
+#include "wpinet/uv/Loop.h"
+#include "wpinet/uv/Prepare.h"
+
+namespace wpi::uv {
+
+TEST(UvAsyncFunctionTest, Basic) {
+  int prepare_cb_called = 0;
+  int async_cb_called[2] = {0, 0};
+  int close_cb_called = 0;
+
+  std::thread theThread;
+
+  auto loop = Loop::Create();
+  auto async = AsyncFunction<int(int)>::Create(loop);
+  auto prepare = Prepare::Create(loop);
+
+  loop->error.connect([](Error) { FAIL(); });
+
+  prepare->error.connect([](Error) { FAIL(); });
+  prepare->prepare.connect([&] {
+    if (prepare_cb_called++) {
+      return;
+    }
+    theThread = std::thread([&] {
+      auto call0 = async->Call(0);
+      auto call1 = async->Call(1);
+      ASSERT_EQ(call0.get(), 1);
+      ASSERT_EQ(call1.get(), 2);
+    });
+  });
+  prepare->Start();
+
+  async->error.connect([](Error) { FAIL(); });
+  async->closed.connect([&] { close_cb_called++; });
+  async->wakeup = [&](promise<int> out, int v) {
+    ++async_cb_called[v];
+    if (v == 1) {
+      async->Close();
+      prepare->Close();
+    }
+    out.set_value(v + 1);
+  };
+
+  loop->Run();
+
+  ASSERT_EQ(async_cb_called[0], 1);
+  ASSERT_EQ(async_cb_called[1], 1);
+  ASSERT_EQ(close_cb_called, 1);
+
+  if (theThread.joinable()) {
+    theThread.join();
+  }
+}
+
+TEST(UvAsyncFunctionTest, Ref) {
+  int prepare_cb_called = 0;
+  int val = 0;
+
+  std::thread theThread;
+
+  auto loop = Loop::Create();
+  auto async = AsyncFunction<int(int, int&)>::Create(loop);
+  auto prepare = Prepare::Create(loop);
+
+  prepare->prepare.connect([&] {
+    if (prepare_cb_called++) {
+      return;
+    }
+    theThread = std::thread([&] { ASSERT_EQ(async->Call(1, val).get(), 2); });
+  });
+  prepare->Start();
+
+  async->wakeup = [&](promise<int> out, int v, int& r) {
+    r = v;
+    async->Close();
+    prepare->Close();
+    out.set_value(v + 1);
+  };
+
+  loop->Run();
+
+  ASSERT_EQ(val, 1);
+
+  if (theThread.joinable()) {
+    theThread.join();
+  }
+}
+
+TEST(UvAsyncFunctionTest, Movable) {
+  int prepare_cb_called = 0;
+
+  std::thread theThread;
+
+  auto loop = Loop::Create();
+  auto async =
+      AsyncFunction<std::unique_ptr<int>(std::unique_ptr<int>)>::Create(loop);
+  auto prepare = Prepare::Create(loop);
+
+  prepare->prepare.connect([&] {
+    if (prepare_cb_called++) {
+      return;
+    }
+    theThread = std::thread([&] {
+      auto val = std::make_unique<int>(1);
+      auto val2 = async->Call(std::move(val)).get();
+      ASSERT_NE(val2, nullptr);
+      ASSERT_EQ(*val2, 1);
+    });
+  });
+  prepare->Start();
+
+  async->wakeup = [&](promise<std::unique_ptr<int>> out,
+                      std::unique_ptr<int> v) {
+    async->Close();
+    prepare->Close();
+    out.set_value(std::move(v));
+  };
+
+  loop->Run();
+
+  if (theThread.joinable()) {
+    theThread.join();
+  }
+}
+
+TEST(UvAsyncFunctionTest, CallIgnoreResult) {
+  int prepare_cb_called = 0;
+
+  std::thread theThread;
+
+  auto loop = Loop::Create();
+  auto async =
+      AsyncFunction<std::unique_ptr<int>(std::unique_ptr<int>)>::Create(loop);
+  auto prepare = Prepare::Create(loop);
+
+  prepare->prepare.connect([&] {
+    if (prepare_cb_called++) {
+      return;
+    }
+    theThread = std::thread([&] { async->Call(std::make_unique<int>(1)); });
+  });
+  prepare->Start();
+
+  async->wakeup = [&](promise<std::unique_ptr<int>> out,
+                      std::unique_ptr<int> v) {
+    async->Close();
+    prepare->Close();
+    out.set_value(std::move(v));
+  };
+
+  loop->Run();
+
+  if (theThread.joinable()) {
+    theThread.join();
+  }
+}
+
+TEST(UvAsyncFunctionTest, VoidCall) {
+  int prepare_cb_called = 0;
+
+  std::thread theThread;
+
+  auto loop = Loop::Create();
+  auto async = AsyncFunction<void()>::Create(loop);
+  auto prepare = Prepare::Create(loop);
+
+  prepare->prepare.connect([&] {
+    if (prepare_cb_called++) {
+      return;
+    }
+    theThread = std::thread([&] { async->Call(); });
+  });
+  prepare->Start();
+
+  async->wakeup = [&](promise<void> out) {
+    async->Close();
+    prepare->Close();
+    out.set_value();
+  };
+
+  loop->Run();
+
+  if (theThread.joinable()) {
+    theThread.join();
+  }
+}
+
+TEST(UvAsyncFunctionTest, WaitFor) {
+  int prepare_cb_called = 0;
+
+  std::thread theThread;
+
+  auto loop = Loop::Create();
+  auto async = AsyncFunction<int()>::Create(loop);
+  auto prepare = Prepare::Create(loop);
+
+  prepare->prepare.connect([&] {
+    if (prepare_cb_called++) {
+      return;
+    }
+    theThread = std::thread([&] {
+      ASSERT_FALSE(async->Call().wait_for(std::chrono::milliseconds(10)));
+    });
+  });
+  prepare->Start();
+
+  async->wakeup = [&](promise<int> out) {
+    async->Close();
+    prepare->Close();
+    std::this_thread::sleep_for(std::chrono::milliseconds(100));
+    out.set_value(1);
+  };
+
+  loop->Run();
+
+  if (theThread.joinable()) {
+    theThread.join();
+  }
+}
+
+TEST(UvAsyncFunctionTest, VoidWaitFor) {
+  int prepare_cb_called = 0;
+
+  std::thread theThread;
+
+  auto loop = Loop::Create();
+  auto async = AsyncFunction<void()>::Create(loop);
+  auto prepare = Prepare::Create(loop);
+
+  prepare->prepare.connect([&] {
+    if (prepare_cb_called++) {
+      return;
+    }
+    theThread = std::thread([&] {
+      ASSERT_FALSE(async->Call().wait_for(std::chrono::milliseconds(10)));
+    });
+  });
+  prepare->Start();
+
+  async->wakeup = [&](promise<void> out) {
+    async->Close();
+    prepare->Close();
+    std::this_thread::sleep_for(std::chrono::milliseconds(100));
+    out.set_value();
+  };
+
+  loop->Run();
+
+  if (theThread.joinable()) {
+    theThread.join();
+  }
+}
+
+}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpinet/src/test/native/cpp/uv/UvAsyncTest.cpp b/third_party/allwpilib/wpinet/src/test/native/cpp/uv/UvAsyncTest.cpp
new file mode 100644
index 0000000..5dd0f76
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/test/native/cpp/uv/UvAsyncTest.cpp
@@ -0,0 +1,186 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "wpinet/uv/Async.h"  // NOLINT(build/include_order)
+
+#include "gtest/gtest.h"  // NOLINT(build/include_order)
+
+#include <atomic>
+#include <thread>
+
+#include <wpi/mutex.h>
+
+#include "wpinet/uv/Loop.h"
+#include "wpinet/uv/Prepare.h"
+
+namespace wpi::uv {
+
+TEST(UvAsyncTest, CallbackOnly) {
+  std::atomic_int async_cb_called{0};
+  int prepare_cb_called = 0;
+  int close_cb_called = 0;
+
+  wpi::mutex mutex;
+  mutex.lock();
+
+  std::thread theThread;
+
+  auto loop = Loop::Create();
+  auto async = Async<>::Create(loop);
+  auto prepare = Prepare::Create(loop);
+
+  loop->error.connect([](Error) { FAIL(); });
+
+  prepare->error.connect([](Error) { FAIL(); });
+  prepare->closed.connect([&] { close_cb_called++; });
+  prepare->prepare.connect([&] {
+    if (prepare_cb_called++) {
+      return;
+    }
+    theThread = std::thread([&] {
+      for (;;) {
+        mutex.lock();
+        int n = async_cb_called;
+        mutex.unlock();
+
+        if (n == 3) {
+          break;
+        }
+
+        async->Send();
+
+        std::this_thread::yield();
+      }
+    });
+    mutex.unlock();
+  });
+  prepare->Start();
+
+  async->error.connect([](Error) { FAIL(); });
+  async->closed.connect([&] { close_cb_called++; });
+  async->wakeup.connect([&] {
+    mutex.lock();
+    int n = ++async_cb_called;
+    mutex.unlock();
+
+    if (n == 3) {
+      async->Close();
+      prepare->Close();
+    }
+  });
+
+  loop->Run();
+
+  ASSERT_GT(prepare_cb_called, 0);
+  ASSERT_EQ(async_cb_called, 3);
+  ASSERT_EQ(close_cb_called, 2);
+
+  if (theThread.joinable()) {
+    theThread.join();
+  }
+}
+
+TEST(UvAsyncTest, Data) {
+  int prepare_cb_called = 0;
+  int async_cb_called[2] = {0, 0};
+  int close_cb_called = 0;
+
+  std::thread theThread;
+
+  auto loop = Loop::Create();
+  auto async = Async<int, std::function<void(int)>>::Create(loop);
+  auto prepare = Prepare::Create(loop);
+
+  loop->error.connect([](Error) { FAIL(); });
+
+  prepare->error.connect([](Error) { FAIL(); });
+  prepare->prepare.connect([&] {
+    if (prepare_cb_called++) {
+      return;
+    }
+    theThread = std::thread([&] {
+      async->Send(0, [&](int v) {
+        ASSERT_EQ(v, 0);
+        ++async_cb_called[0];
+      });
+      async->Send(1, [&](int v) {
+        ASSERT_EQ(v, 1);
+        ++async_cb_called[1];
+        async->Close();
+        prepare->Close();
+      });
+    });
+  });
+  prepare->Start();
+
+  async->error.connect([](Error) { FAIL(); });
+  async->closed.connect([&] { close_cb_called++; });
+  async->wakeup.connect([&](int v, std::function<void(int)> f) { f(v); });
+
+  loop->Run();
+
+  ASSERT_EQ(async_cb_called[0], 1);
+  ASSERT_EQ(async_cb_called[1], 1);
+  ASSERT_EQ(close_cb_called, 1);
+
+  if (theThread.joinable()) {
+    theThread.join();
+  }
+}
+
+TEST(UvAsyncTest, DataRef) {
+  int prepare_cb_called = 0;
+  int val = 0;
+
+  std::thread theThread;
+
+  auto loop = Loop::Create();
+  auto async = Async<int, int&>::Create(loop);
+  auto prepare = Prepare::Create(loop);
+
+  prepare->prepare.connect([&] {
+    if (prepare_cb_called++) {
+      return;
+    }
+    theThread = std::thread([&] { async->Send(1, val); });
+  });
+  prepare->Start();
+
+  async->wakeup.connect([&](int v, int& r) {
+    r = v;
+    async->Close();
+    prepare->Close();
+  });
+
+  loop->Run();
+
+  ASSERT_EQ(val, 1);
+
+  if (theThread.joinable()) {
+    theThread.join();
+  }
+}
+
+}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpinet/src/test/native/cpp/uv/UvBufferTest.cpp b/third_party/allwpilib/wpinet/src/test/native/cpp/uv/UvBufferTest.cpp
new file mode 100644
index 0000000..da6a63c
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/test/native/cpp/uv/UvBufferTest.cpp
@@ -0,0 +1,48 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/uv/Buffer.h"  // NOLINT(build/include_order)
+
+#include "gtest/gtest.h"  // NOLINT(build/include_order)
+
+namespace wpi::uv {
+
+TEST(UvSimpleBufferPoolTest, ConstructDefault) {
+  SimpleBufferPool<> pool;
+  auto buf1 = pool.Allocate();
+  ASSERT_EQ(buf1.len, 4096u);  // NOLINT
+  pool.Release({&buf1, 1});
+}
+
+TEST(UvSimpleBufferPoolTest, ConstructSize) {
+  SimpleBufferPool<4> pool{8192};
+  auto buf1 = pool.Allocate();
+  ASSERT_EQ(buf1.len, 8192u);  // NOLINT
+  pool.Release({&buf1, 1});
+}
+
+TEST(UvSimpleBufferPoolTest, ReleaseReuse) {
+  SimpleBufferPool<4> pool;
+  auto buf1 = pool.Allocate();
+  auto buf1copy = buf1;
+  auto origSize = buf1.len;
+  buf1.len = 8;
+  pool.Release({&buf1, 1});
+  ASSERT_EQ(buf1.base, nullptr);
+  auto buf2 = pool.Allocate();
+  ASSERT_EQ(buf1copy.base, buf2.base);
+  ASSERT_EQ(buf2.len, origSize);
+  pool.Release({&buf2, 1});
+}
+
+TEST(UvSimpleBufferPoolTest, ClearRemaining) {
+  SimpleBufferPool<4> pool;
+  auto buf1 = pool.Allocate();
+  pool.Release({&buf1, 1});
+  ASSERT_EQ(pool.Remaining(), 1u);
+  pool.Clear();
+  ASSERT_EQ(pool.Remaining(), 0u);
+}
+
+}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpinet/src/test/native/cpp/uv/UvGetAddrInfoTest.cpp b/third_party/allwpilib/wpinet/src/test/native/cpp/uv/UvGetAddrInfoTest.cpp
new file mode 100644
index 0000000..5ad33b2
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/test/native/cpp/uv/UvGetAddrInfoTest.cpp
@@ -0,0 +1,109 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "wpinet/uv/GetAddrInfo.h"  // NOLINT(build/include_order)
+
+#include "gtest/gtest.h"  // NOLINT(build/include_order)
+
+#include "wpinet/uv/Loop.h"
+
+#define CONCURRENT_COUNT 10
+
+namespace wpi::uv {
+
+TEST(UvGetAddrInfoTest, BothNull) {
+  int fail_cb_called = 0;
+
+  auto loop = Loop::Create();
+  loop->error.connect([&](Error err) {
+    ASSERT_EQ(err.code(), UV_EINVAL);
+    fail_cb_called++;
+  });
+
+  GetAddrInfo(
+      loop, [](const addrinfo&) { FAIL(); }, "");
+  loop->Run();
+  ASSERT_EQ(fail_cb_called, 1);
+}
+
+TEST(UvGetAddrInfoTest, FailedLookup) {
+  int fail_cb_called = 0;
+
+  auto loop = Loop::Create();
+  loop->error.connect([&](Error err) {
+    ASSERT_EQ(fail_cb_called, 0);
+    ASSERT_LT(err.code(), 0);
+    fail_cb_called++;
+  });
+
+  // Use a FQDN by ending in a period
+  GetAddrInfo(
+      loop, [](const addrinfo&) { FAIL(); }, "xyzzy.xyzzy.xyzzy.");
+  loop->Run();
+  ASSERT_EQ(fail_cb_called, 1);
+}
+
+TEST(UvGetAddrInfoTest, Basic) {
+  int getaddrinfo_cbs = 0;
+
+  auto loop = Loop::Create();
+  loop->error.connect([](Error) { FAIL(); });
+
+  GetAddrInfo(
+      loop, [&](const addrinfo&) { getaddrinfo_cbs++; }, "localhost");
+
+  loop->Run();
+
+  ASSERT_EQ(getaddrinfo_cbs, 1);
+}
+
+#ifndef _WIN32
+TEST(UvGetAddrInfoTest, Concurrent) {
+  int getaddrinfo_cbs = 0;
+  int callback_counts[CONCURRENT_COUNT];
+
+  auto loop = Loop::Create();
+  loop->error.connect([](Error) { FAIL(); });
+
+  for (int i = 0; i < CONCURRENT_COUNT; i++) {
+    callback_counts[i] = 0;
+    GetAddrInfo(
+        loop,
+        [i, &callback_counts, &getaddrinfo_cbs](const addrinfo&) {
+          callback_counts[i]++;
+          getaddrinfo_cbs++;
+        },
+        "localhost");
+  }
+
+  loop->Run();
+
+  for (int i = 0; i < CONCURRENT_COUNT; i++) {
+    ASSERT_EQ(callback_counts[i], 1);
+  }
+}
+#endif
+
+}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpinet/src/test/native/cpp/uv/UvGetNameInfoTest.cpp b/third_party/allwpilib/wpinet/src/test/native/cpp/uv/UvGetNameInfoTest.cpp
new file mode 100644
index 0000000..707f037
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/test/native/cpp/uv/UvGetNameInfoTest.cpp
@@ -0,0 +1,74 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "wpinet/uv/GetNameInfo.h"  // NOLINT(build/include_order)
+
+#include "gtest/gtest.h"  // NOLINT(build/include_order)
+
+#include "wpinet/uv/Loop.h"
+
+namespace wpi::uv {
+
+TEST(UvGetNameInfoTest, BasicIp4) {
+  int getnameinfo_cbs = 0;
+
+  auto loop = Loop::Create();
+  loop->error.connect([](Error) { FAIL(); });
+
+  GetNameInfo4(
+      loop,
+      [&](const char* hostname, const char* service) {
+        ASSERT_NE(hostname, nullptr);
+        ASSERT_NE(service, nullptr);
+        getnameinfo_cbs++;
+      },
+      "127.0.0.1", 80);
+
+  loop->Run();
+
+  ASSERT_EQ(getnameinfo_cbs, 1);
+}
+
+TEST(UvGetNameInfoTest, BasicIp6) {
+  int getnameinfo_cbs = 0;
+
+  auto loop = Loop::Create();
+  loop->error.connect([](Error) { FAIL(); });
+
+  GetNameInfo6(
+      loop,
+      [&](const char* hostname, const char* service) {
+        ASSERT_NE(hostname, nullptr);
+        ASSERT_NE(service, nullptr);
+        getnameinfo_cbs++;
+      },
+      "::1", 80);
+
+  loop->Run();
+
+  ASSERT_EQ(getnameinfo_cbs, 1);
+}
+
+}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpinet/src/test/native/cpp/uv/UvLoopWalkTest.cpp b/third_party/allwpilib/wpinet/src/test/native/cpp/uv/UvLoopWalkTest.cpp
new file mode 100644
index 0000000..eee0f99
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/test/native/cpp/uv/UvLoopWalkTest.cpp
@@ -0,0 +1,69 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "wpinet/uv/Loop.h"  // NOLINT(build/include_order)
+
+#include "gtest/gtest.h"  // NOLINT(build/include_order)
+
+#include "wpinet/uv/Timer.h"
+
+namespace wpi::uv {
+
+TEST(UvLoopTest, Walk) {
+  int seen_timer_handle = 0;
+
+  auto loop = Loop::Create();
+  auto timer = Timer::Create(loop);
+
+  loop->error.connect([](Error) { FAIL(); });
+
+  timer->error.connect([](Error) { FAIL(); });
+
+  timer->timeout.connect([&, theTimer = timer.get()] {
+    theTimer->GetLoopRef().Walk([&](Handle& it) {
+      if (&it == timer.get()) {
+        seen_timer_handle++;
+      }
+    });
+    theTimer->Close();
+  });
+  timer->Start(Timer::Time{1});
+
+  // Start event loop, expect to see the timer handle
+  ASSERT_EQ(seen_timer_handle, 0);
+  loop->Run();
+  ASSERT_EQ(seen_timer_handle, 1);
+
+  // Loop is finished, should not see our timer handle
+  seen_timer_handle = 0;
+  loop->Walk([&](Handle& it) {
+    if (&it == timer.get()) {
+      seen_timer_handle++;
+    }
+  });
+  ASSERT_EQ(seen_timer_handle, 0);
+}
+
+}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpinet/src/test/native/cpp/uv/UvTimerTest.cpp b/third_party/allwpilib/wpinet/src/test/native/cpp/uv/UvTimerTest.cpp
new file mode 100644
index 0000000..7377ab1
--- /dev/null
+++ b/third_party/allwpilib/wpinet/src/test/native/cpp/uv/UvTimerTest.cpp
@@ -0,0 +1,69 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpinet/uv/Timer.h"  // NOLINT(build/include_order)
+
+#include "gtest/gtest.h"
+
+namespace wpi::uv {
+
+TEST(UvTimerTest, StartAndStop) {
+  auto loop = Loop::Create();
+  auto handleNoRepeat = Timer::Create(loop);
+  auto handleRepeat = Timer::Create(loop);
+
+  bool checkTimerNoRepeatEvent = false;
+  bool checkTimerRepeatEvent = false;
+
+  handleNoRepeat->error.connect([](Error) { FAIL(); });
+  handleRepeat->error.connect([](Error) { FAIL(); });
+
+  handleNoRepeat->timeout.connect(
+      [&checkTimerNoRepeatEvent, handle = handleNoRepeat.get()] {
+        ASSERT_FALSE(checkTimerNoRepeatEvent);
+        checkTimerNoRepeatEvent = true;
+        handle->Stop();
+        handle->Close();
+        ASSERT_TRUE(handle->IsClosing());
+      });
+
+  handleRepeat->timeout.connect(
+      [&checkTimerRepeatEvent, handle = handleRepeat.get()] {
+        if (checkTimerRepeatEvent) {
+          handle->Stop();
+          handle->Close();
+          ASSERT_TRUE(handle->IsClosing());
+        } else {
+          checkTimerRepeatEvent = true;
+          ASSERT_FALSE(handle->IsClosing());
+        }
+      });
+
+  handleNoRepeat->Start(Timer::Time{0}, Timer::Time{0});
+  handleRepeat->Start(Timer::Time{0}, Timer::Time{1});
+
+  ASSERT_TRUE(handleNoRepeat->IsActive());
+  ASSERT_FALSE(handleNoRepeat->IsClosing());
+
+  ASSERT_TRUE(handleRepeat->IsActive());
+  ASSERT_FALSE(handleRepeat->IsClosing());
+
+  loop->Run();
+
+  ASSERT_TRUE(checkTimerNoRepeatEvent);
+  ASSERT_TRUE(checkTimerRepeatEvent);
+}
+
+TEST(UvTimerTest, Repeat) {
+  auto loop = Loop::Create();
+  auto handle = Timer::Create(loop);
+
+  handle->SetRepeat(Timer::Time{42});
+  ASSERT_EQ(handle->GetRepeat(), Timer::Time{42});
+  handle->Close();
+
+  loop->Run();  // forces close callback to run
+}
+
+}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpinet/wpinet-config.cmake.in b/third_party/allwpilib/wpinet/wpinet-config.cmake.in
new file mode 100644
index 0000000..f54fe45
--- /dev/null
+++ b/third_party/allwpilib/wpinet/wpinet-config.cmake.in
@@ -0,0 +1,7 @@
+include(CMakeFindDependencyMacro)
+@FILENAME_DEP_REPLACE@
+@LIBUV_SYSTEM_REPLACE@
+@WPIUTIL_DEP_REPLACE@
+
+@FILENAME_DEP_REPLACE@
+include(${SELF_DIR}/wpinet.cmake)
diff --git a/third_party/allwpilib/wpiutil/.styleguide b/third_party/allwpilib/wpiutil/.styleguide
index f0ae065..9c1196e 100644
--- a/third_party/allwpilib/wpiutil/.styleguide
+++ b/third_party/allwpilib/wpiutil/.styleguide
@@ -1,97 +1,38 @@
 cppHeaderFileInclude {
   \.h$
+  \.hpp$
   \.inc$
   \.inl$
   math$
   numbers$
+  scope$
 }
 
 cppSrcFileInclude {
   \.cpp$
 }
 
+modifiableFileExclude {
+  src/main/native/include/wpi/MulticastServiceAnnouncer\.h$
+}
+
 generatedFileExclude {
-  src/main/native/cpp/http_parser\.cpp$
-  src/main/native/cpp/llvm/
-  src/main/native/include/llvm/
-  src/main/native/include/wpi/AlignOf\.h$
-  src/main/native/include/wpi/ArrayRef\.h$
-  src/main/native/include/wpi/Chrono\.h$
-  src/main/native/include/wpi/Compiler\.h$
-  src/main/native/include/wpi/ConvertUTF\.h$
-  src/main/native/include/wpi/DenseMap\.h$
-  src/main/native/include/wpi/DenseMapInfo\.h$
-  src/main/native/include/wpi/EpochTracker\.h$
-  src/main/native/include/wpi/Endian\.h$
-  src/main/native/include/wpi/Errc\.h$
-  src/main/native/include/wpi/Errno\.h$
-  src/main/native/include/wpi/Error\.h$
-  src/main/native/include/wpi/ErrorHandling\.h$
-  src/main/native/include/wpi/ErrorOr\.h$
-  src/main/native/include/wpi/FileSystem\.h$
-  src/main/native/include/wpi/Format\.h$
-  src/main/native/include/wpi/FunctionExtras\.h$
-  src/main/native/include/wpi/Hashing\.h$
-  src/main/native/include/wpi/IntrusiveRefCntPtr\.h$
-  src/main/native/include/wpi/ManagedStatic\.h$
-  src/main/native/include/wpi/MapVector\.h$
-  src/main/native/include/wpi/MathExtras\.h$
-  src/main/native/include/wpi/MemAlloc\.h$
-  src/main/native/include/wpi/NativeFormatting\.h$
-  src/main/native/include/wpi/Path\.h$
-  src/main/native/include/wpi/PointerIntPair\.h$
-  src/main/native/include/wpi/PointerLikeTypeTraits\.h$
-  src/main/native/include/wpi/PointerUnion\.h$
-  src/main/native/include/wpi/STLExtras\.h$
-  src/main/native/include/wpi/Signal\.h$
-  src/main/native/include/wpi/SmallPtrSet\.h$
-  src/main/native/include/wpi/SmallSet\.h$
-  src/main/native/include/wpi/SmallString\.h$
-  src/main/native/include/wpi/SmallVector\.h$
-  src/main/native/include/wpi/StringMap\.h$
-  src/main/native/include/wpi/StringRef\.h$
-  src/main/native/include/wpi/SwapByteOrder\.h$
-  src/main/native/include/wpi/Twine\.h$
-  src/main/native/include/wpi/VersionTuple\.h$
-  src/main/native/include/wpi/WindowsError\.h$
-  src/main/native/include/wpi/http_parser\.h$
-  src/main/native/include/wpi/iterator\.h$
-  src/main/native/include/wpi/iterator_range\.h$
-  src/main/native/include/wpi/raw_os_ostream\.h$
-  src/main/native/include/wpi/raw_ostream\.h$
-  src/main/native/include/wpi/span\.h$
+  src/main/native/thirdparty/
+
   src/main/native/include/wpi/fs\.h$
-  src/main/native/include/wpi/mpack\.h$
   src/main/native/cpp/fs\.cpp$
-  src/main/native/cpp/mpack\.cpp$
-  src/main/native/include/wpi/ghc/
-  src/test/native/cpp/span/
-  src/main/native/include/wpi/type_traits\.h$
-  src/main/native/cpp/json
-  src/main/native/include/wpi/json
-  src/test/native/cpp/json/
-  src/main/native/include/uv\.h$
-  src/main/native/include/uv/
-  src/main/native/libuv/
-  src/main/native/fmtlib/
   src/main/native/resources/
-  src/test/native/cpp/llvm/
   src/main/native/windows/StackWalker
-  src/main/native/linux/AvahiClient
+  src/test/native/cpp/llvm/
+  src/test/native/cpp/span/
+  src/test/native/cpp/json/
 }
 
 licenseUpdateExclude {
   src/main/native/cpp/Base64\.cpp$
   src/main/native/cpp/sha1\.cpp$
-  src/main/native/cpp/TCPAcceptor\.cpp$
-  src/main/native/cpp/TCPConnector\.cpp$
-  src/main/native/cpp/TCPStream\.cpp$
   src/main/native/include/wpi/ConcurrentQueue\.h$
-  src/main/native/include/wpi/Path\.h$
   src/main/native/include/wpi/sha1\.h$
-  src/main/native/include/wpi/TCPAcceptor\.h$
-  src/main/native/include/wpi/TCPConnector\.h$
-  src/main/native/include/wpi/TCPStream\.h$
 }
 
 repoRootNameOverride {
diff --git a/third_party/allwpilib/wpiutil/BUILD b/third_party/allwpilib/wpiutil/BUILD
index 58b9918..d85ccbc 100644
--- a/third_party/allwpilib/wpiutil/BUILD
+++ b/third_party/allwpilib/wpiutil/BUILD
@@ -4,17 +4,21 @@
     name = "wpiutil",
     srcs = glob(
         [
-            "src/main/native/cpp/llvm/*.cpp",
-            "src/main/native/fmtlib/src/*.cpp",
+            "src/main/native/thirdparty/llvm/cpp/llvm/*.cpp",
+            "src/main/native/thirdparty/fmtlib/src/*.cpp",
         ],
     ) + [
         "src/main/native/cpp/timestamp.cpp",
+        "src/main/native/cpp/Synchronization.cpp",
+        "src/main/native/cpp/fs.cpp",
+        "src/main/native/cpp/MappedFileRegion.cpp",
         "src/main/native/cpp/SafeThread.cpp",
     ],
     hdrs = glob(
         [
             "src/main/native/include/**",
-            "src/main/native/fmtlib/include/**",
+            "src/main/native/thirdparty/fmtlib/include/**",
+            "src/main/native/thirdparty/llvm/include/**",
         ],
         exclude = ["STLExtras.h"],
     ),
@@ -23,7 +27,8 @@
     ],
     includes = [
         "src/main/native/include",
-        "src/main/native/fmtlib/include",
+        "src/main/native/thirdparty/fmtlib/include",
+        "src/main/native/thirdparty/llvm/include",
     ],
     target_compatible_with = ["//tools/platforms/hardware:roborio"],
     visibility = ["//visibility:public"],
diff --git a/third_party/allwpilib/wpiutil/CMakeLists.txt b/third_party/allwpilib/wpiutil/CMakeLists.txt
index a301772..9b86e14 100644
--- a/third_party/allwpilib/wpiutil/CMakeLists.txt
+++ b/third_party/allwpilib/wpiutil/CMakeLists.txt
@@ -5,7 +5,7 @@
 include(CompileWarnings)
 include(AddTest)
 
-file(GLOB wpiutil_jni_src src/main/native/cpp/jni/WPIUtilJNI.cpp)
+file(GLOB wpiutil_jni_src src/main/native/cpp/jni/WPIUtilJNI.cpp src/main/native/cpp/jni/DataLogJNI.cpp)
 
 # Java bindings
 if (WITH_JAVA)
@@ -76,117 +76,59 @@
 set(THREADS_PREFER_PTHREAD_FLAG ON)
 find_package(Threads REQUIRED)
 
-if (NOT MSVC AND NOT APPLE)
+if (NOT MSVC AND NOT APPLE AND NOT ANDROID)
     find_library(ATOMIC NAMES atomic libatomic.so.1)
     if (ATOMIC)
         message(STATUS "Found libatomic: ${ATOMIC}")
+    else()
+        message(STATUS "libatomic not found. If build fails, install libatomic")
     endif()
 endif()
 
 GENERATE_RESOURCES(src/main/native/resources generated/main/cpp WPI wpi wpiutil_resources_src)
 
-file(GLOB_RECURSE wpiutil_native_src src/main/native/cpp/*.cpp)
+file(GLOB_RECURSE wpiutil_native_src src/main/native/cpp/*.cpp
+                                     src/main/native/thirdparty/json/cpp/*.cpp
+                                     src/main/native/thirdparty/llvm/cpp/*.cpp
+                                     src/main/native/thirdparty/mpack/src/*.cpp)
 list(REMOVE_ITEM wpiutil_native_src ${wpiutil_jni_src})
 file(GLOB_RECURSE wpiutil_unix_src src/main/native/unix/*.cpp)
 file(GLOB_RECURSE wpiutil_linux_src src/main/native/linux/*.cpp)
 file(GLOB_RECURSE wpiutil_macos_src src/main/native/macOS/*.cpp)
 file(GLOB_RECURSE wpiutil_windows_src src/main/native/windows/*.cpp)
 
-file(GLOB fmtlib_native_src src/main/native/fmtlib/src/*.cpp)
+file(GLOB fmtlib_native_src src/main/native/thirdparty/fmtlib/src/*.cpp)
+file(GLOB_RECURSE memory_native_src src/main/native/thirdparty/memory/src/*.cpp)
 
-file(GLOB uv_native_src src/main/native/libuv/src/*.cpp)
-
-file(GLOB uv_windows_src src/main/native/libuv/src/win/*.cpp)
-
-set(uv_unix_src
-    src/main/native/libuv/src/unix/async.cpp
-    src/main/native/libuv/src/unix/core.cpp
-    src/main/native/libuv/src/unix/dl.cpp
-    src/main/native/libuv/src/unix/fs.cpp
-    src/main/native/libuv/src/unix/getaddrinfo.cpp
-    src/main/native/libuv/src/unix/getnameinfo.cpp
-    src/main/native/libuv/src/unix/loop-watcher.cpp
-    src/main/native/libuv/src/unix/loop.cpp
-    src/main/native/libuv/src/unix/pipe.cpp
-    src/main/native/libuv/src/unix/poll.cpp
-    src/main/native/libuv/src/unix/process.cpp
-    src/main/native/libuv/src/unix/signal.cpp
-    src/main/native/libuv/src/unix/stream.cpp
-    src/main/native/libuv/src/unix/tcp.cpp
-    src/main/native/libuv/src/unix/thread.cpp
-    src/main/native/libuv/src/unix/tty.cpp
-    src/main/native/libuv/src/unix/udp.cpp
-)
-
-set(uv_darwin_src
-    src/main/native/libuv/src/unix/bsd-ifaddrs.cpp
-    src/main/native/libuv/src/unix/darwin.cpp
-    src/main/native/libuv/src/unix/darwin-proctitle.cpp
-    src/main/native/libuv/src/unix/fsevents.cpp
-    src/main/native/libuv/src/unix/kqueue.cpp
-    src/main/native/libuv/src/unix/proctitle.cpp
-)
-
-set(uv_linux_src
-    src/main/native/libuv/src/unix/linux-core.cpp
-    src/main/native/libuv/src/unix/linux-inotify.cpp
-    src/main/native/libuv/src/unix/linux-syscalls.cpp
-    src/main/native/libuv/src/unix/procfs-exepath.cpp
-    src/main/native/libuv/src/unix/proctitle.cpp
-    src/main/native/libuv/src/unix/sysinfo-loadavg.cpp
-)
-
-add_library(wpiutil ${wpiutil_native_src} ${fmtlib_native_src} ${wpiutil_resources_src})
+add_library(wpiutil ${wpiutil_native_src} ${fmtlib_native_src} ${memory_native_src} ${wpiutil_resources_src})
 set_target_properties(wpiutil PROPERTIES DEBUG_POSTFIX "d")
 
 set_property(TARGET wpiutil PROPERTY FOLDER "libraries")
 
-target_compile_features(wpiutil PUBLIC cxx_std_17)
+target_compile_features(wpiutil PUBLIC cxx_std_20)
 if (MSVC)
     target_compile_options(wpiutil PUBLIC /permissive- /Zc:throwingNew /MP /bigobj)
     target_compile_definitions(wpiutil PRIVATE -D_CRT_SECURE_NO_WARNINGS)
 endif()
 wpilib_target_warnings(wpiutil)
-target_link_libraries(wpiutil Threads::Threads ${CMAKE_DL_LIBS} ${ATOMIC})
+target_link_libraries(wpiutil Threads::Threads ${CMAKE_DL_LIBS})
 
-if (NOT USE_VCPKG_FMTLIB)
+if (ATOMIC)
+    target_link_libraries(wpiutil ${ATOMIC})
+endif()
+
+
+if (NOT USE_SYSTEM_FMTLIB)
     target_sources(wpiutil PRIVATE ${fmtlib_native_src})
-    install(DIRECTORY src/main/native/fmtlib/include/ DESTINATION "${include_dest}/wpiutil")
+    install(DIRECTORY src/main/native/thirdparty/fmtlib/include/ DESTINATION "${include_dest}/wpiutil")
     target_include_directories(wpiutil PUBLIC
-                            $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/src/main/native/fmtlib/include>
+                            $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/src/main/native/thirdparty/fmtlib/include>
                             $<INSTALL_INTERFACE:${include_dest}/wpiutil>)
 else()
     find_package(fmt CONFIG REQUIRED)
     target_link_libraries(wpiutil fmt::fmt)
 endif()
 
-if (NOT USE_VCPKG_LIBUV)
-    target_sources(wpiutil PRIVATE ${uv_native_src})
-    install(DIRECTORY src/main/native/libuv/include/ DESTINATION "${include_dest}/wpiutil")
-    target_include_directories(wpiutil PRIVATE
-        src/main/native/libuv/src)
-    target_include_directories(wpiutil PUBLIC
-                            $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/src/main/native/libuv/include>
-                            $<INSTALL_INTERFACE:${include_dest}/wpiutil>)
-    if(NOT MSVC)
-        target_sources(wpiutil PRIVATE ${uv_unix_src})
-        if (APPLE)
-            target_sources(wpiutil PRIVATE ${uv_darwin_src})
-        else()
-            target_sources(wpiutil PRIVATE ${uv_linux_src})
-        endif()
-        target_compile_definitions(wpiutil PRIVATE -D_GNU_SOURCE)
-    else()
-        target_sources(wpiutil PRIVATE ${uv_windows_src})
-        if(BUILD_SHARED_LIBS)
-            target_compile_definitions(wpiutil PRIVATE -DBUILDING_UV_SHARED)
-        endif()
-    endif()
-else()
-    find_package(unofficial-libuv CONFIG REQUIRED)
-    target_link_libraries(wpiutil unofficial::libuv::libuv)
-endif()
-
 if (MSVC)
     target_sources(wpiutil PRIVATE ${wpiutil_windows_src})
 else ()
@@ -198,12 +140,43 @@
     endif()
 endif()
 
+install(DIRECTORY src/main/native/thirdparty/memory/include/ DESTINATION "${include_dest}/wpiutil")
+target_include_directories(wpiutil PUBLIC
+                            $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/src/main/native/include>
+                            $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/src/main/native/thirdparty/memory/include>
+                            $<INSTALL_INTERFACE:${include_dest}/wpiutil>)
+
+install(DIRECTORY src/main/native/thirdparty/ghc/include/ DESTINATION "${include_dest}/wpiutil")
+target_include_directories(wpiutil PUBLIC
+                            $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/src/main/native/thirdparty/ghc/include>
+                            $<INSTALL_INTERFACE:${include_dest}/wpiutil>)
+
+install(DIRECTORY src/main/native/thirdparty/json/include/ DESTINATION "${include_dest}/wpiutil")
+target_include_directories(wpiutil PUBLIC
+                            $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/src/main/native/thirdparty/json/include>
+                            $<INSTALL_INTERFACE:${include_dest}/wpiutil>)
+
+install(DIRECTORY src/main/native/thirdparty/llvm/include/ DESTINATION "${include_dest}/wpiutil")
+target_include_directories(wpiutil PUBLIC
+                            $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/src/main/native/thirdparty/llvm/include>
+                            $<INSTALL_INTERFACE:${include_dest}/wpiutil>)
+
+install(DIRECTORY src/main/native/thirdparty/mpack/include/ DESTINATION "${include_dest}/wpiutil")
+target_include_directories(wpiutil PUBLIC
+                            $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/src/main/native/thirdparty/mpack/include>
+                            $<INSTALL_INTERFACE:${include_dest}/wpiutil>)
+
+install(DIRECTORY src/main/native/thirdparty/sigslot/include/ DESTINATION "${include_dest}/wpiutil")
+target_include_directories(wpiutil PUBLIC
+                            $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/src/main/native/thirdparty/sigslot/include>
+                            $<INSTALL_INTERFACE:${include_dest}/wpiutil>)
+
+install(DIRECTORY src/main/native/include/ DESTINATION "${include_dest}/wpiutil")
 target_include_directories(wpiutil PUBLIC
                             $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/src/main/native/include>
                             $<INSTALL_INTERFACE:${include_dest}/wpiutil>)
 
 install(TARGETS wpiutil EXPORT wpiutil DESTINATION "${main_lib_dest}")
-install(DIRECTORY src/main/native/include/ DESTINATION "${include_dest}/wpiutil")
 
 if (WITH_JAVA AND MSVC)
     install(TARGETS wpiutil RUNTIME DESTINATION "${jni_lib_dest}" COMPONENT Runtime)
@@ -230,27 +203,8 @@
     endif()
 endforeach()
 
-if (UNIX AND NOT APPLE)
-    set (LIBUTIL -lutil)
-else()
-    set (LIBUTIL)
-endif()
-
-file(GLOB netconsoleServer_src src/netconsoleServer/native/cpp/*.cpp)
-add_executable(netconsoleServer ${netconsoleServer_src})
-wpilib_target_warnings(netconsoleServer)
-target_link_libraries(netconsoleServer wpiutil ${LIBUTIL})
-
-file(GLOB netconsoleTee_src src/netconsoleTee/native/cpp/*.cpp)
-add_executable(netconsoleTee ${netconsoleTee_src})
-wpilib_target_warnings(netconsoleTee)
-target_link_libraries(netconsoleTee wpiutil)
-
-set_property(TARGET netconsoleServer PROPERTY FOLDER "examples")
-set_property(TARGET netconsoleTee PROPERTY FOLDER "examples")
-
 if (WITH_TESTS)
     wpilib_add_test(wpiutil src/test/native/cpp)
     target_include_directories(wpiutil_test PRIVATE src/test/native/include)
-    target_link_libraries(wpiutil_test wpiutil ${LIBUTIL} gmock_main)
+    target_link_libraries(wpiutil_test wpiutil gmock_main)
 endif()
diff --git a/third_party/allwpilib/wpiutil/build.gradle b/third_party/allwpilib/wpiutil/build.gradle
index 3168723..501176a 100644
--- a/third_party/allwpilib/wpiutil/build.gradle
+++ b/third_party/allwpilib/wpiutil/build.gradle
@@ -2,7 +2,9 @@
 
 ext {
     noWpiutil = true
-    skipJniCheck = true
+    skipJniSymbols = [
+        'Java_edu_wpi_first_util_CombinedRuntimeLoader_setDllDirectory'
+    ]
     baseId = 'wpiutil'
     groupId = 'edu.wpi.first.wpiutil'
 
@@ -15,22 +17,69 @@
             dependsOn generateTask
         }
         it.sources {
-            libuvCpp(CppSourceSet) {
-                source {
-                    srcDirs 'src/main/native/libuv/src'
-                    include '*.cpp'
-                }
-                exportedHeaders {
-                    srcDirs 'src/main/native/include', 'src/main/native/libuv/include', 'src/main/native/libuv/src'
-                }
-            }
             fmtlibCpp(CppSourceSet) {
                 source {
-                    srcDirs 'src/main/native/fmtlib/src'
+                    srcDirs 'src/main/native/thirdparty/fmtlib/src'
                     include '*.cpp'
                 }
                 exportedHeaders {
-                    srcDirs 'src/main/native/fmtlib/include'
+                    srcDirs 'src/main/native/thirdparty/fmtlib/include'
+                }
+            }
+            ghcCpp(CppSourceSet) {
+                exportedHeaders {
+                    srcDirs 'src/main/native/thirdparty/ghc/include'
+                }
+            }
+            jsonCpp(CppSourceSet) {
+                source {
+                    srcDirs 'src/main/native/thirdparty/json/cpp'
+                    include '*.cpp'
+                }
+                exportedHeaders {
+                    srcDirs 'src/main/native/include', 'src/main/native/thirdparty/llvm/include', 'src/main/native/thirdparty/json/include', 'src/main/native/thirdparty/tcb_span/include', 'src/main/native/thirdparty/fmtlib/include'
+                }
+            }
+            llvmCpp(CppSourceSet) {
+                source {
+                    srcDirs 'src/main/native/thirdparty/llvm/cpp'
+                    include '**/*.cpp'
+                }
+                exportedHeaders {
+                    srcDirs 'src/main/native/include', 'src/main/native/thirdparty/llvm/include', 'src/main/native/thirdparty/tcb_span/include', 'src/main/native/thirdparty/fmtlib/include', 'src/main/native/thirdparty/ghc/include'
+                }
+            }
+            mpackCpp(CppSourceSet) {
+                source {
+                    srcDirs 'src/main/native/thirdparty/mpack/src'
+                    include '*.cpp'
+                }
+                exportedHeaders {
+                    srcDirs 'src/main/native/thirdparty/mpack/include'
+                }
+            }
+            sigslotCpp(CppSourceSet) {
+                source {
+                    srcDirs 'src/main/native/thirdparty/sigslot/src'
+                    include '*.cpp'
+                }
+                exportedHeaders {
+                    srcDirs 'src/main/native/thirdparty/sigslot/include'
+                }
+            }
+            tcbSpanCpp(CppSourceSet) {
+                exportedHeaders {
+                    srcDirs 'src/main/native/thirdparty/tcb_span/include'
+                }
+            }
+            memoryCpp(CppSourceSet) {
+                source {
+                    srcDirs 'src/main/native/thirdparty/memory/src', 'src/main/native/thirdparty/memory/include/wpi/memory'
+                    include '**/*.cpp'
+                }
+                exportedHeaders {
+                    srcDirs 'src/main/native/thirdparty/memory/include'
+                    include '**/*.hpp'
                 }
             }
             resourcesCpp(CppSourceSet) {
@@ -46,125 +95,53 @@
         if (!it.targetPlatform.operatingSystem.isWindows()) {
             it.cppCompiler.define '_GNU_SOURCE'
             it.sources {
-                libuvUnixCpp(CppSourceSet) {
-                    source {
-                        srcDirs 'src/main/native/libuv/src/unix'
-                        includes = [
-                            'async.cpp',
-                            'core.cpp',
-                            'dl.cpp',
-                            'fs.cpp',
-                            'getaddrinfo.cpp',
-                            'getnameinfo.cpp',
-                            'loop-watcher.cpp',
-                            'loop.cpp',
-                            'pipe.cpp',
-                            'poll.cpp',
-                            'process.cpp',
-                            'signal.cpp',
-                            'stream.cpp',
-                            'tcp.cpp',
-                            'thread.cpp',
-                            'timer.cpp',
-                            'tty.cpp',
-                            'udp.cpp',
-                        ]
-                    }
-                    exportedHeaders {
-                        srcDirs 'src/main/native/include', 'src/main/native/libuv/include', 'src/main/native/libuv/src'
-                    }
-                }
                 wpiutilUnixCpp(CppSourceSet) {
                     source {
                         srcDirs 'src/main/native/unix'
                         include '**/*.cpp'
                     }
                     exportedHeaders {
-                        srcDirs 'src/main/native/include', 'src/main/native/cpp'
+                        srcDirs 'src/main/native/include', 'src/main/native/cpp', 'src/main/native/thirdparty/llvm/include', 'src/main/native/thirdparty/sigslot/include', 'src/main/native/thirdparty/tcb_span/include', 'src/main/native/thirdparty/mpack/include'
                         include '**/*.h'
                     }
                 }
             }
         }
         if (it.targetPlatform.operatingSystem.isWindows()) {
-            if (it in SharedLibraryBinarySpec) {
-                it.cppCompiler.define 'BUILDING_UV_SHARED'
-            }
             it.sources {
-                libuvWindowsCpp(CppSourceSet) {
-                    source {
-                        srcDirs 'src/main/native/libuv/src/win'
-                        include '*.cpp'
-                    }
-                    exportedHeaders {
-                        srcDirs 'src/main/native/include', 'src/main/native/libuv/include', 'src/main/native/libuv/src'
-                    }
-                }
                 wpiutilWindowsCpp(CppSourceSet) {
                     source {
-                        srcDirs 'src/main/native/windows'
+                        srcDirs 'src/main/native/windows', 'src/main/native/llvm/cpp/llvm', 'src/main/native/json/cpp'
                         include '**/*.cpp'
                     }
                     exportedHeaders {
-                        srcDirs 'src/main/native/include', 'src/main/native/cpp'
+                        srcDirs 'src/main/native/include', 'src/main/native/cpp', 'src/main/native/thirdparty/llvm/include', 'src/main/native/thirdparty/fmtlib/include', 'src/main/native/thirdparty/sigslot/include', 'src/main/native/thirdparty/json/include', 'src/main/native/thirdparty/tcb_span/include', 'src/main/native/thirdparty/mpack/include'
                         include '**/*.h'
                     }
                 }
             }
         } else if (it.targetPlatform.operatingSystem.isMacOsX()) {
             it.sources {
-                libuvMacCpp(CppSourceSet) {
-                    source {
-                        srcDirs 'src/main/native/libuv/src/unix'
-                        includes = [
-                            'bsd-ifaddrs.cpp',
-                            'darwin.cpp',
-                            'darwin-proctitle.cpp',
-                            'fsevents.cpp',
-                            'kqueue.cpp',
-                            'proctitle.cpp'
-                        ]
-                    }
-                    exportedHeaders {
-                        srcDirs 'src/main/native/include', 'src/main/native/libuv/include', 'src/main/native/libuv/src'
-                    }
-                }
                 wpiutilmacOSCpp(CppSourceSet) {
                     source {
-                        srcDirs 'src/main/native/macOS'
+                        srcDirs 'src/main/native/macOS', 'src/main/native/llvm/cpp/llvm', 'src/main/native/json/cpp'
                         include '**/*.cpp'
                     }
                     exportedHeaders {
-                        srcDirs 'src/main/native/include', 'src/main/native/cpp'
+                        srcDirs 'src/main/native/include', 'src/main/native/cpp', 'src/main/native/thirdparty/llvm/include', 'src/main/native/thirdparty/fmtlib/include', 'src/main/native/thirdparty/sigslot/include', 'src/main/native/thirdparty/json/include', 'src/main/native/thirdparty/tcb_span/include', 'src/main/native/thirdparty/mpack/include'
                         include '**/*.h'
                     }
                 }
             }
         } else {
             it.sources {
-                libuvLinuxCpp(CppSourceSet) {
-                    source {
-                        srcDirs 'src/main/native/libuv/src/unix'
-                        includes = [
-                            'linux-core.cpp',
-                            'linux-inotify.cpp',
-                            'linux-syscalls.cpp',
-                            'procfs-exepath.cpp',
-                            'proctitle.cpp',
-                            'sysinfo-loadavg.cpp',
-                        ]
-                    }
-                    exportedHeaders {
-                        srcDirs 'src/main/native/include', 'src/main/native/libuv/include', 'src/main/native/libuv/src'
-                    }
-                }
                 wpiutilLinuxCpp(CppSourceSet) {
                     source {
-                        srcDirs 'src/main/native/linux'
+                        srcDirs 'src/main/native/linux', 'src/main/native/llvm/cpp/llvm', 'src/main/native/json/cpp'
                         include '**/*.cpp'
                     }
                     exportedHeaders {
-                        srcDirs 'src/main/native/include', 'src/main/native/cpp', 'src/main/native/fmtlib/include'
+                        srcDirs 'src/main/native/include', 'src/main/native/cpp', 'src/main/native/thirdparty/llvm/include', 'src/main/native/thirdparty/fmtlib/include', 'src/main/native/thirdparty/sigslot/include', 'src/main/native/thirdparty/json/include', 'src/main/native/thirdparty/tcb_span/include', 'src/main/native/thirdparty/mpack/include'
                         include '**/*.h'
                     }
                 }
@@ -187,19 +164,6 @@
 
 nativeUtils.exportsConfigs {
     wpiutil {
-        x86ExcludeSymbols = [
-            '_CT??_R0?AV_System_error',
-            '_CT??_R0?AVexception',
-            '_CT??_R0?AVfailure',
-            '_CT??_R0?AVruntime_error',
-            '_CT??_R0?AVsystem_error',
-            '_CTA5?AVfailure',
-            '_TI5?AVfailure',
-            '_CT??_R0?AVout_of_range',
-            '_CTA3?AVout_of_range',
-            '_TI3?AVout_of_range',
-            '_CT??_R0?AVbad_cast'
-        ]
         x64ExcludeSymbols = [
             '_CT??_R0?AV_System_error',
             '_CT??_R0?AVexception',
@@ -217,10 +181,49 @@
 }
 
 cppHeadersZip {
-    from('src/main/native/libuv/include') {
+    from('src/main/native/thirdparty/fmtlib/include') {
         into '/'
     }
-    from('src/main/native/fmtlib/include') {
+    from('src/main/native/thirdparty/ghc/include') {
+        into '/'
+    }
+    from('src/main/native/thirdparty/json/include') {
+        into '/'
+    }
+    from('src/main/native/thirdparty/llvm/include') {
+        into '/'
+    }
+    from('src/main/native/thirdparty/mpack/include') {
+        into '/'
+    }
+    from('src/main/native/thirdparty/sigslot/include') {
+        into '/'
+    }
+    from('src/main/native/thirdparty/tcb_span/include') {
+        into '/'
+    }
+    from('src/main/native/thirdparty/memory/include') {
+        into '/'
+    }
+}
+
+cppSourcesZip {
+    from('src/main/native/thirdparty/fmtlib/src') {
+        into '/'
+    }
+    from('src/main/native/thirdparty/json/cpp') {
+        into '/'
+    }
+    from('src/main/native/thirdparty/llvm/cpp') {
+        into '/'
+    }
+    from('src/main/native/thirdparty/memory/src') {
+        into '/'
+    }
+    from('src/main/native/thirdparty/mpack/src') {
+        into '/'
+    }
+    from('src/main/native/thirdparty/sigslot/src') {
         into '/'
     }
 }
@@ -230,7 +233,7 @@
         all {
             it.sources.each {
                 it.exportedHeaders {
-                    srcDirs 'src/main/native/include', 'src/main/native/libuv/include', 'src/main/native/libuv/src', 'src/main/native/fmtlib/include'
+                    srcDirs 'src/main/native/include', 'src/main/native/thirdparty/fmtlib/include', 'src/main/native/thirdparty/llvm/include', 'src/main/native/thirdparty/sigslot/include', 'src/main/native/thirdparty/json/include', 'src/main/native/thirdparty/tcb_span/include', 'src/main/native/thirdparty/ghc/include', 'src/main/native/thirdparty/memory/include', 'src/main/native/thirdparty/mpack/include'
                 }
             }
         }
@@ -255,46 +258,23 @@
                 }
             }
         }
-        netconsoleServer(NativeExecutableSpec) {
-            targetBuildTypes 'release'
-            sources {
-                cpp {
-                    source {
-                        srcDirs = [
-                            'src/netconsoleServer/native/cpp'
-                        ]
-                        includes = ['**/*.cpp']
-                    }
-                }
-            }
-            binaries.all { binary ->
-                lib project: ':wpiutil', library: 'wpiutil', linkage: 'static'
-                if (binary.targetPlatform.operatingSystem.isLinux()) {
-                    linker.args "-lutil"
-                }
-            }
-        }
-        netconsoleTee(NativeExecutableSpec) {
-            targetBuildTypes 'release'
-            sources {
-                cpp {
-                    source {
-                        srcDirs = [
-                            'src/netconsoleTee/native/cpp'
-                        ]
-                        includes = ['**/*.cpp']
-                    }
-                }
-            }
-            binaries.all { binary ->
-                lib project: ':wpiutil', library: 'wpiutil', linkage: 'static'
-            }
-        }
     }
 }
 
+sourceSets {
+    printlog
+}
+
+task runPrintLog(type: JavaExec) {
+    classpath = sourceSets.printlog.runtimeClasspath
+
+    mainClass = 'printlog.PrintLog'
+}
+
 dependencies {
     api "com.fasterxml.jackson.core:jackson-annotations:2.12.4"
     api "com.fasterxml.jackson.core:jackson-core:2.12.4"
     api "com.fasterxml.jackson.core:jackson-databind:2.12.4"
+
+    printlogImplementation sourceSets.main.output
 }
diff --git a/third_party/allwpilib/wpiutil/doc/datalog.adoc b/third_party/allwpilib/wpiutil/doc/datalog.adoc
new file mode 100644
index 0000000..9fd6f6f
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/doc/datalog.adoc
@@ -0,0 +1,192 @@
+= WPILib Data Log File Format Specification, Version 1.0
+WPILib Developers <wpilib@wpi.edu>
+Revision 1.0 (0x0100), 1/2/2022
+:toc:
+:toc-placement: preamble
+:sectanchors:
+
+A simple binary logging format designed for high speed logging of timestamped data values (e.g. numeric sensor values).
+
+[[motivation]]
+== Motivation
+
+FRC robots generate a lot of real-time data of various data types (most typically numeric values, but also strings and more complex data such as camera images). While there is good support in the WPILib software ecosystem for real-time display of this data on dashboards (via NetworkTables), there is no current standard for logging of timestamped data values for offline analysis. In the absence of a standard, teams have developed various ad-hoc solutions, including CSV files.
+
+Similar to how the NetworkTables standard protocol enabled ecosystem development of multiple dashboards, it is expected that a standard format for data logging, in combination with built-in library support for easy on-robot logging of robot data, will facilitate ecosystem development of offline data analysis tools.
+
+Standard logging facilities currently available (e.g. in Java) are generally designed for string messages, not for binary data. As a binary format, this will be faster with less overhead for the typical data (e.g. numbers) coming from a robot in real time (at least dozens, if not hundreds, of data points every ~20 ms). String formatting is significantly more expensive than just copying the binary number, and is more difficult to read back into analysis tools. Latency of the actual logging to the main program is also critical in the FRC application. WPILib also needs a common logging format and implementation across both C++ and Java.
+
+[[references]]
+== References
+
+[[rfc7159,RFC7159,JSON]]
+* RFC 7159, The JavaScript Object Notation (JSON) Data Interchange Format, https://tools.ietf.org/html/rfc7159
+
+[[definitions]]
+== Definitions
+
+[[def-entry]]
+Entry:: A data channel identified by an integer ID and a string name. Entries have a specified type and may have associated metadata.
+
+[[def-entry-id]]
+Entry ID:: An unsigned 4-byte ID by which records in the log refer to an Entry, instead of using the full string key for the Entry. Entry ID 0 is reserved for control records.
+
+[[def-record]]
+Record:: Storage of a single timestamped data item in the log. A record consists of the entry ID, the data length, a 64-bit integer timestamp, and the data contents.
+
+[[def-timestamp]]
+Timestamp:: 64-bit integer microseconds. The zero time is not specified by the data format, but on an FRC robot is typically the time the robot program started.
+
+[[design]]
+== Design
+
+A data log starts with an 8-byte header, followed by 0 or more records. There is no padding between records. Each record in the file has an arbitrary length payload, is timestamped, and is associated to a particular entry (via its entry ID).
+
+Entries in the log are started using a <<control-start,Start>> control record to associate an entry ID with its name, <<data-types,type>>, and <<metadata,metadata>>. Following the Start control record, records referencing that entry ID can follow in any order (and can be mixed with records with other entry IDs). A <<control-finish,Finish>> control record may be used to indicate no further records with that entry ID will follow. Following a Finish control record, an entry ID may be reused by another Start control record. Multiple Start control records for a single entry ID without an intervening Finish control record have unspecified behavior.
+
+Entry metadata may be updated with a <<control-set-metadata,Set Metadata>> control record. This control record is only valid for a particular entry ID in between Start and Finish control records for that entry ID. The Set Metadata control record should be interpreted as completely replacing the entry's metadata contents.
+
+There is no timestamp ordering requirement for records. This is true for control records as well--a Start control record with a later timestamp may be followed by data records for that entry with earlier timestamps.
+
+Duplicate entry names should be avoided, but there is nothing in the data format itself that requires this.
+
+All values are stored in little endian order.
+
+[[header]]
+=== Header
+
+The header consists of:
+
+* 6-byte ASCII string, containing "WPILOG"
+* 2-byte (16-bit) version number
+* 4-byte (32-bit) length of extra header string
+* extra header string (arbitrary length)
+
+The most significant byte of the version indicates the major version and the least significant byte indicates the minor version. For this version of the data format, the value is thus 0x0100, indicating version 1.0.
+
+The extra header string has arbitrary contents (e.g. the contents are set by the application that wrote the data log) but it must be UTF-8 encoded.
+
+The entire header for a version 1.0 file with no extra header string will be `57 50 49 4c 4f 47 00 01 00 00 00 00`.
+
+[[record]]
+=== Records
+
+Each record consists of:
+
+* 1-byte header length bitfield
+* 1 to 4-byte (32-bit) entry ID
+* 1 to 4-byte (32-bit) payload size (in bytes)
+* 1 to 8-byte (64-bit) timestamp (in integer microseconds)
+* payload data (arbitrary length)
+
+The header length bitfield encodes the length of each header field as follows (starting from the least significant bit):
+
+* 2-bit entry ID length (00 = 1 byte, 01 = 2 bytes, 10 = 3 bytes, 11 = 4 bytes)
+* 2-bit payload size length (00 = 1 byte, to 11 = 4 bytes)
+* 3-bit timestamp length (000 = 1 byte, to 111 = 8 bytes)
+* 1-bit spare (zero)
+
+An example record for a integer entry (ID=1) value 3 at timestamp 1 second would be 14 bytes in total length:
+
+* `20` (ID length = 1 byte, payload size length = 1 byte, timestamp length = 3 bytes)
+* `01` (entry ID = 1)
+* `08` (payload size = 8 bytes)
+* `40 42 0f` (timestamp = 1,000,000 us)
+* `03 00 00 00 00 00 00 00` (value = 3)
+
+[[control-record]]
+=== Control Records
+
+Entry ID 0 is used to indicate a record is a control record. There are 3 control record types: Start, Finish, and Set metadata. The first 4 bytes of the payload data indicates the control record type.
+
+[[control-start]]
+==== Start
+
+The Start control record provides information about the specified entry ID. It must appear prior to any records using that entry ID. The format of the Start control record's payload data is as follows:
+
+* 1-byte control record type (0 for Start control records)
+* 4-byte (32-bit) entry ID of entry being started
+* 4-byte (32-bit) length of entry name string
+* entry name UTF-8 string data (arbitrary length)
+* 4-byte (32-bit) length of entry type string
+* entry <<data-types,type>> UTF-8 string data (arbitrary length)
+* 4-byte (32-bit) length of entry metadata string
+* entry <<metadata,metadata>> UTF-8 string data (arbitrary length)
+
+An example start control record for an integer entry named `test` with ID=1 is 32 bytes:
+
+* `20` (ID length = 1 byte, payload size length = 1 byte, timestamp length = 3 bytes)
+* `00` (entry ID = 0)
+* `1a` (payload size = 26 bytes)
+* `40 42 0f` (timestamp = 1,000,000 us)
+* `00` (control record type = Start (0))
+* `01 00 00 00` (entry ID 1 being started)
+* `04 00 00 00` (length of name string = 4)
+* `74 65 73 74` (entry name = `test`)
+* `05 00 00 00` (length of type string = 5)
+* `69 6e 74 66 64` (type string = `int64`)
+* `00 00 00 00` (length of metadata string = 0)
+
+[[control-finish]]
+==== Finish
+
+The Finish control record indicates the entry ID is no longer valid.  The format of the Finish control record's payload data is as follows:
+
+* 1-byte control record type (1 for Finish control records)
+* 4-byte (32-bit) entry ID of entry being completed
+
+An example finish control record for ID=1 is 11 bytes:
+
+* `20` (ID length = 1 byte, payload size length = 1 byte, timestamp length = 3 bytes)
+* `00` (entry ID = 0)
+* `05` (payload size = 5 bytes)
+* `40 42 0f` (timestamp = 1,000,000 us)
+* `01` (control record type = Finish (1))
+* `01 00 00 00` (entry ID 1 being finished)
+
+[[control-set-metadata]]
+==== Set Metadata
+
+The Set metadata control record updates the <<metadata,metadata>> for an entry. The format of the record's payload data is as follows:
+
+* 1-byte control record type (2 for Set metadata control records)
+* 4-byte (32-bit) entry ID of entry whose metadata is being updated
+* 4-byte (32-bit) length of entry metadata string
+* entry metadata string data (arbitrary length)
+
+An example set metadata control record to set metadata for ID=1 is 30 bytes:
+
+* `20` (ID length = 1 byte, payload size length = 1 byte, timestamp length = 3 bytes)
+* `00` (entry ID = 0)
+* `18` (payload size = 24 bytes)
+* `40 42 0f` (timestamp = 1,000,000 us)
+* `02` (control record type = Set Metadata (2))
+* `01 00 00 00` (setting metadata for entry ID 1)
+* `0f 00 00 00` (length of metadata string = 15)
+* `7b 22 73 6f 75 72 63 65 22 3a 22 4e 54 22 7d` (metadata string = `{"source":"NT"}`)
+
+[[data-types]]
+=== Data Types
+
+Each entry's data type is an arbitrary string. The following data types are standard and should be supported by all implementations, but other data type strings are allowed and may be supported by some implementations.
+
+[cols="1,1,3", options="header"]
+|===
+|Type String|Description|Payload Data Contents
+|`raw`|raw data|the raw data
+|`boolean`|boolean|single byte (0=false, 1=true)
+|`int64`|integer|8-byte (64-bit) signed value
+|`float`|float|4-byte (32-bit) IEEE-754 value
+|`double`|double|8-byte (64-bit) IEEE-754 value
+|`string`|string|UTF-8 encoded string data
+|`boolean[]`|array of boolean|a single byte (0=false, 1=true) for each entry in the arrayfootnote:arraylength[the array length is not stored, but is instead determined by the payload length]
+|`int64[]`|array of integer|8-byte (64-bit) signed value for each entry in the arrayfootnote:arraylength[]
+|`float[]`|array of float|4-byte (32-bit) value for each entry in the arrayfootnote:arraylength[]
+|`double[]`|array of double|8-byte (64-bit) value for each entry in the arrayfootnote:arraylength[]
+|`string[]`|array of strings|Starts with a 4-byte (32-bit) array length. Each string is stored as a 4-byte (32-bit) length followed by the UTF-8 string data
+|===
+
+[[metadata]]
+=== Metadata
+
+Each entry has an associated metadata string. If not blank, the metadata should be <<JSON,JSON>>, but may be arbitrary text. Metadata is intended to convey additional information about the entry beyond what the type conveys--for example the source of the data.
diff --git a/third_party/allwpilib/wpiutil/examples/dsclient/dsclient.cpp b/third_party/allwpilib/wpiutil/examples/dsclient/dsclient.cpp
deleted file mode 100644
index 69c1061..0000000
--- a/third_party/allwpilib/wpiutil/examples/dsclient/dsclient.cpp
+++ /dev/null
@@ -1,35 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include <cstdio>
-
-#include "fmt/format.h"
-#include "wpi/DsClient.h"
-#include "wpi/EventLoopRunner.h"
-#include "wpi/Logger.h"
-#include "wpi/uv/Error.h"
-
-namespace uv = wpi::uv;
-
-static void logfunc(unsigned int level, const char* file, unsigned int line,
-                    const char* msg) {
-  std::fprintf(stderr, "(%d) %s:%d: %s\n", level, file, line, msg);
-}
-
-int main() {
-  wpi::Logger logger{logfunc, 0};
-
-  // Kick off the event loop on a separate thread
-  wpi::EventLoopRunner loop;
-  std::shared_ptr<wpi::DsClient> client;
-  loop.ExecAsync([&](uv::Loop& loop) {
-    client = wpi::DsClient::Create(loop, logger);
-    client->setIp.connect(
-        [](std::string_view ip) { fmt::print("got IP: {}\n", ip); });
-    client->clearIp.connect([] { std::fputs("cleared IP\n", stdout); });
-  });
-
-  // wait for a keypress to terminate
-  std::getchar();
-}
diff --git a/third_party/allwpilib/wpiutil/examples/parallelconnect/parallelconnect.cpp b/third_party/allwpilib/wpiutil/examples/parallelconnect/parallelconnect.cpp
deleted file mode 100644
index 929c847..0000000
--- a/third_party/allwpilib/wpiutil/examples/parallelconnect/parallelconnect.cpp
+++ /dev/null
@@ -1,50 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include <cstdio>
-
-#include "wpi/EventLoopRunner.h"
-#include "wpi/Logger.h"
-#include "wpi/ParallelTcpConnector.h"
-#include "wpi/uv/Error.h"
-#include "wpi/uv/Tcp.h"
-
-namespace uv = wpi::uv;
-
-static void logfunc(unsigned int level, const char* file, unsigned int line,
-                    const char* msg) {
-  std::fprintf(stderr, "(%d) %s:%d: %s\n", level, file, line, msg);
-}
-
-int main() {
-  wpi::Logger logger{logfunc, 0};
-
-  // Kick off the event loop on a separate thread
-  wpi::EventLoopRunner loop;
-  std::shared_ptr<wpi::ParallelTcpConnector> connect;
-  loop.ExecAsync([&](uv::Loop& loop) {
-    connect = wpi::ParallelTcpConnector::Create(
-        loop, uv::Timer::Time{2000}, logger, [&](uv::Tcp& tcp) {
-          std::fputs("Got connection, accepting!\n", stdout);
-          tcp.StartRead();
-          connect->Succeeded(tcp);
-          tcp.end.connect([&] {
-            std::fputs("TCP connection ended, disconnecting!\n", stdout);
-            tcp.Close();
-            connect->Disconnected();
-          });
-          tcp.error.connect([&](uv::Error) {
-            std::fputs("TCP error, disconnecting!\n", stdout);
-            connect->Disconnected();
-          });
-        });
-    connect->SetServers({{{"roborio-294-frc.local", 8080},
-                          {"roborio-294-frc.frc-field.local", 8080},
-                          {"10.2.94.2", 8080},
-                          {"127.0.0.1", 8080}}});
-  });
-
-  // wait for a keypress to terminate
-  std::getchar();
-}
diff --git a/third_party/allwpilib/wpiutil/examples/printlog/datalog.py b/third_party/allwpilib/wpiutil/examples/printlog/datalog.py
new file mode 100755
index 0000000..b1035dd
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/examples/printlog/datalog.py
@@ -0,0 +1,347 @@
+#! /usr/bin/env python3
+# Copyright (c) FIRST and other WPILib contributors.
+# Open Source Software; you can modify and/or share it under the terms of
+# the WPILib BSD license file in the root directory of this project.
+
+import array
+import struct
+from typing import List, SupportsBytes
+
+__all__ = ["StartRecordData", "MetadataRecordData", "DataLogRecord", "DataLogReader"]
+
+floatStruct = struct.Struct("<f")
+doubleStruct = struct.Struct("<d")
+
+kControlStart = 0
+kControlFinish = 1
+kControlSetMetadata = 2
+
+
+class StartRecordData:
+    """Data contained in a start control record as created by DataLog.start() when
+    writing the log. This can be read by calling DataLogRecord.getStartData().
+
+    entry: Entry ID; this will be used for this entry in future records.
+    name: Entry name.
+    type: Type of the stored data for this entry, as a string, e.g. "double".
+    metadata: Initial metadata.
+    """
+
+    def __init__(self, entry: int, name: str, type: str, metadata: str):
+        self.entry = entry
+        self.name = name
+        self.type = type
+        self.metadata = metadata
+
+
+class MetadataRecordData:
+    """Data contained in a set metadata control record as created by
+    DataLog.setMetadata(). This can be read by calling
+    DataLogRecord.getSetMetadataData().
+
+    entry: Entry ID.
+    metadata: New metadata for the entry.
+    """
+
+    def __init__(self, entry: int, metadata: str):
+        self.entry = entry
+        self.metadata = metadata
+
+
+class DataLogRecord:
+    """A record in the data log. May represent either a control record
+    (entry == 0) or a data record."""
+
+    def __init__(self, entry: int, timestamp: int, data: SupportsBytes):
+        self.entry = entry
+        self.timestamp = timestamp
+        self.data = data
+
+    def isControl(self) -> bool:
+        return self.entry == 0
+
+    def _getControlType(self) -> int:
+        return self.data[0]
+
+    def isStart(self) -> bool:
+        return (
+            self.entry == 0
+            and len(self.data) >= 17
+            and self._getControlType() == kControlStart
+        )
+
+    def isFinish(self) -> bool:
+        return (
+            self.entry == 0
+            and len(self.data) == 5
+            and self._getControlType() == kControlFinish
+        )
+
+    def isSetMetadata(self) -> bool:
+        return (
+            self.entry == 0
+            and len(self.data) >= 9
+            and self._getControlType() == kControlSetMetadata
+        )
+
+    def getStartData(self) -> StartRecordData:
+        if not self.isStart():
+            raise TypeError("not a start record")
+        entry = int.from_bytes(self.data[1:5], byteorder="little", signed=False)
+        name, pos = self._readInnerString(5)
+        type, pos = self._readInnerString(pos)
+        metadata = self._readInnerString(pos)[0]
+        return StartRecordData(entry, name, type, metadata)
+
+    def getFinishEntry(self) -> int:
+        if not self.isFinish():
+            raise TypeError("not a finish record")
+        return int.from_bytes(self.data[1:5], byteorder="little", signed=False)
+
+    def getSetMetadataData(self) -> MetadataRecordData:
+        if not self.isSetMetadata():
+            raise TypeError("not a finish record")
+        entry = int.from_bytes(self.data[1:5], byteorder="little", signed=False)
+        metadata = self._readInnerString(5)[0]
+        return MetadataRecordData(entry, metadata)
+
+    def getBoolean(self) -> bool:
+        if len(self.data) != 1:
+            raise TypeError("not a boolean")
+        return self.data[0] != 0
+
+    def getInteger(self) -> int:
+        if len(self.data) != 8:
+            raise TypeError("not an integer")
+        return int.from_bytes(self.data, byteorder="little", signed=True)
+
+    def getFloat(self) -> float:
+        if len(self.data) != 4:
+            raise TypeError("not a float")
+        return floatStruct.unpack(self.data)[0]
+
+    def getDouble(self) -> float:
+        if len(self.data) != 8:
+            raise TypeError("not a double")
+        return doubleStruct.unpack(self.data)[0]
+
+    def getString(self) -> str:
+        return str(self.data, encoding="utf-8")
+
+    def getBooleanArray(self) -> List[bool]:
+        return [x != 0 for x in self.data]
+
+    def getIntegerArray(self) -> array.array:
+        if (len(self.data) % 8) != 0:
+            raise TypeError("not an integer array")
+        arr = array.array("l")
+        arr.frombytes(self.data)
+        return arr
+
+    def getFloatArray(self) -> array.array:
+        if (len(self.data) % 4) != 0:
+            raise TypeError("not a float array")
+        arr = array.array("f")
+        arr.frombytes(self.data)
+        return arr
+
+    def getDoubleArray(self) -> array.array:
+        if (len(self.data) % 8) != 0:
+            raise TypeError("not a double array")
+        arr = array.array("d")
+        arr.frombytes(self.data)
+        return arr
+
+    def getStringArray(self) -> List[str]:
+        size = int.from_bytes(self.data[:4], byteorder="little", signed=False)
+        if size > ((len(self.data) - 4) / 4):
+            raise TypeError("not a string array")
+        arr = []
+        pos = 4
+        for _ in range(size):
+            val, pos = self._readInnerString(pos)
+            arr.append(val)
+        return arr
+
+    def _readInnerString(self, pos: int) -> tuple[str, int]:
+        size = int.from_bytes(
+            self.data[pos : pos + 4], byteorder="little", signed=False
+        )
+        end = pos + 4 + size
+        if end > len(self.data):
+            raise TypeError("invalid string size")
+        return str(self.data[pos + 4 : end], encoding="utf-8"), end
+
+
+class DataLogIterator:
+    """DataLogReader iterator."""
+
+    def __init__(self, buf: SupportsBytes, pos: int):
+        self.buf = buf
+        self.pos = pos
+
+    def __iter__(self):
+        return self
+
+    def _readVarInt(self, pos: int, len: int) -> int:
+        val = 0
+        for i in range(len):
+            val |= self.buf[pos + i] << (i * 8)
+        return val
+
+    def __next__(self) -> DataLogRecord:
+        if len(self.buf) < (self.pos + 4):
+            raise StopIteration
+        entryLen = (self.buf[self.pos] & 0x3) + 1
+        sizeLen = ((self.buf[self.pos] >> 2) & 0x3) + 1
+        timestampLen = ((self.buf[self.pos] >> 4) & 0x7) + 1
+        headerLen = 1 + entryLen + sizeLen + timestampLen
+        if len(self.buf) < (self.pos + headerLen):
+            raise StopIteration
+        entry = self._readVarInt(self.pos + 1, entryLen)
+        size = self._readVarInt(self.pos + 1 + entryLen, sizeLen)
+        timestamp = self._readVarInt(self.pos + 1 + entryLen + sizeLen, timestampLen)
+        if len(self.buf) < (self.pos + headerLen + size):
+            raise StopIteration
+        record = DataLogRecord(
+            entry,
+            timestamp,
+            self.buf[self.pos + headerLen : self.pos + headerLen + size],
+        )
+        self.pos += headerLen + size
+        return record
+
+
+class DataLogReader:
+    """Data log reader (reads logs written by the DataLog class)."""
+
+    def __init__(self, buf: SupportsBytes):
+        self.buf = buf
+
+    def __bool__(self):
+        return self.isValid()
+
+    def isValid(self) -> bool:
+        """Returns true if the data log is valid (e.g. has a valid header)."""
+        return (
+            len(self.buf) >= 12
+            and self.buf[:6] == b"WPILOG"
+            and self.getVersion() >= 0x0100
+        )
+
+    def getVersion(self) -> int:
+        """Gets the data log version. Returns 0 if data log is invalid.
+
+        @return Version number; most significant byte is major, least significant is
+            minor (so version 1.0 will be 0x0100)"""
+        if len(self.buf) < 12:
+            return 0
+        return int.from_bytes(self.buf[6:8], byteorder="little", signed=False)
+
+    def getExtraHeader(self) -> str:
+        """Gets the extra header data.
+
+        @return Extra header data
+        """
+        if len(self.buf) < 12:
+            return ""
+        size = int.from_bytes(self.buf[8:12], byteorder="little", signed=False)
+        return str(self.buf[12 : 12 + size], encoding="utf-8")
+
+    def __iter__(self) -> DataLogIterator:
+        extraHeaderSize = int.from_bytes(
+            self.buf[8:12], byteorder="little", signed=False
+        )
+        return DataLogIterator(self.buf, 12 + extraHeaderSize)
+
+
+if __name__ == "__main__":
+    from datetime import datetime
+    import mmap
+    import sys
+
+    if len(sys.argv) != 2:
+        print("Usage: datalog.py <file>", file=sys.stderr)
+        sys.exit(1)
+
+    with open(sys.argv[1], "r") as f:
+        mm = mmap.mmap(f.fileno(), 0, access=mmap.ACCESS_READ)
+        reader = DataLogReader(mm)
+        if not reader:
+            print("not a log file", file=sys.stderr)
+            sys.exit(1)
+
+        entries = {}
+        for record in reader:
+            timestamp = record.timestamp / 1000000
+            if record.isStart():
+                try:
+                    data = record.getStartData()
+                    print(
+                        f"Start({data.entry}, name='{data.name}', type='{data.type}', metadata='{data.metadata}') [{timestamp}]"
+                    )
+                    if data.entry in entries:
+                        print("...DUPLICATE entry ID, overriding")
+                    entries[data.entry] = data
+                except TypeError as e:
+                    print("Start(INVALID)")
+            elif record.isFinish():
+                try:
+                    entry = record.getFinishEntry()
+                    print(f"Finish({entry}) [{timestamp}]")
+                    if entry not in entries:
+                        print("...ID not found")
+                    else:
+                        del entries[entry]
+                except TypeError as e:
+                    print("Finish(INVALID)")
+            elif record.isSetMetadata():
+                try:
+                    data = record.getSetMetadataData()
+                    print(f"SetMetadata({data.entry}, '{data.metadata}') [{timestamp}]")
+                    if data.entry not in entries:
+                        print("...ID not found")
+                except TypeError as e:
+                    print("SetMetadata(INVALID)")
+            elif record.isControl():
+                print("Unrecognized control record")
+            else:
+                print(f"Data({record.entry}, size={len(record.data)}) ", end="")
+                entry = entries.get(record.entry)
+                if entry is None:
+                    print("<ID not found>")
+                    continue
+                print(f"<name='{entry.name}', type='{entry.type}'> [{timestamp}]")
+
+                try:
+                    # handle systemTime specially
+                    if entry.name == "systemTime" and entry.type == "int64":
+                        dt = datetime.fromtimestamp(record.getInteger() / 1000000)
+                        print("  {:%Y-%m-%d %H:%M:%S.%f}".format(dt))
+                        continue
+
+                    if entry.type == "double":
+                        print(f"  {record.getDouble()}")
+                    elif entry.type == "int64":
+                        print(f"  {record.getInteger()}")
+                    elif entry.type in ("string", "json"):
+                        print(f"  '{record.getString()}'")
+                    elif entry.type == "boolean":
+                        print(f"  {record.getBoolean()}")
+                    elif entry.type == "boolean[]":
+                        arr = record.getBooleanArray()
+                        print(f"  {arr}")
+                    elif entry.type == "double[]":
+                        arr = record.getDoubleArray()
+                        print(f"  {arr}")
+                    elif entry.type == "float[]":
+                        arr = record.getFloatArray()
+                        print(f"  {arr}")
+                    elif entry.type == "int64[]":
+                        arr = record.getIntegerArray()
+                        print(f"  {arr}")
+                    elif entry.type == "string[]":
+                        arr = record.getStringArray()
+                        print(f"  {arr}")
+                except TypeError as e:
+                    print("  invalid")
diff --git a/third_party/allwpilib/wpiutil/examples/printlog/printlog.cpp b/third_party/allwpilib/wpiutil/examples/printlog/printlog.cpp
new file mode 100644
index 0000000..073a247
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/examples/printlog/printlog.cpp
@@ -0,0 +1,161 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <ctime>
+
+#include "fmt/chrono.h"
+#include "fmt/format.h"
+#include "wpi/DataLogReader.h"
+#include "wpi/DenseMap.h"
+#include "wpi/MemoryBuffer.h"
+
+int main(int argc, const char** argv) {
+  if (argc != 2) {
+    fmt::print(stderr, "Usage: printlog <file>\n");
+    return EXIT_FAILURE;
+  }
+  std::error_code ec;
+  wpi::log::DataLogReader reader{wpi::MemoryBuffer::GetFile(argv[1], ec)};
+  if (ec) {
+    fmt::print(stderr, "could not open file: {}\n", ec.message());
+    return EXIT_FAILURE;
+  }
+  if (!reader) {
+    fmt::print(stderr, "not a log file\n");
+    return EXIT_FAILURE;
+  }
+
+  wpi::DenseMap<int, wpi::log::StartRecordData> entries;
+  for (auto&& record : reader) {
+    if (record.IsStart()) {
+      wpi::log::StartRecordData data;
+      if (record.GetStartData(&data)) {
+        fmt::print("Start({}, name='{}', type='{}', metadata='{}') [{}]\n",
+                   data.entry, data.name, data.type, data.metadata,
+                   record.GetTimestamp() / 1000000.0);
+        if (entries.find(data.entry) != entries.end()) {
+          fmt::print("...DUPLICATE entry ID, overriding\n");
+        }
+        entries[data.entry] = data;
+      } else {
+        fmt::print("Start(INVALID)\n");
+      }
+    } else if (record.IsFinish()) {
+      int entry;
+      if (record.GetFinishEntry(&entry)) {
+        fmt::print("Finish({}) [{}]\n", entry,
+                   record.GetTimestamp() / 1000000.0);
+        auto it = entries.find(entry);
+        if (it == entries.end()) {
+          fmt::print("...ID not found\n");
+        } else {
+          entries.erase(it);
+        }
+      } else {
+        fmt::print("Finish(INVALID)\n");
+      }
+    } else if (record.IsSetMetadata()) {
+      wpi::log::MetadataRecordData data;
+      if (record.GetSetMetadataData(&data)) {
+        fmt::print("SetMetadata({}, '{}') [{}]\n", data.entry, data.metadata,
+                   record.GetTimestamp() / 1000000.0);
+        auto it = entries.find(data.entry);
+        if (it == entries.end()) {
+          fmt::print("...ID not found\n");
+        } else {
+          it->second.metadata = data.metadata;
+        }
+      } else {
+        fmt::print("SetMetadata(INVALID)\n");
+      }
+    } else if (record.IsControl()) {
+      fmt::print("Unrecognized control record\n");
+    } else {
+      fmt::print("Data({}, size={}) ", record.GetEntry(), record.GetSize());
+      auto entry = entries.find(record.GetEntry());
+      if (entry == entries.end()) {
+        fmt::print("<ID not found>\n");
+        continue;
+      }
+      fmt::print("<name='{}', type='{}'> [{}]\n", entry->second.name,
+                 entry->second.type, record.GetTimestamp() / 1000000.0);
+
+      // handle systemTime specially
+      if (entry->second.name == "systemTime" && entry->second.type == "int64") {
+        int64_t val;
+        if (record.GetInteger(&val)) {
+          std::time_t timeval = val / 1000000;
+          fmt::print("  {:%Y-%m-%d %H:%M:%S}.{:06}\n",
+                     *std::localtime(&timeval), val % 1000000);
+        } else {
+          fmt::print("  invalid\n");
+        }
+        continue;
+      }
+
+      if (entry->second.type == "double") {
+        double val;
+        if (record.GetDouble(&val)) {
+          fmt::print("  {}\n", val);
+        } else {
+          fmt::print("  invalid\n");
+        }
+      } else if (entry->second.type == "int64") {
+        int64_t val;
+        if (record.GetInteger(&val)) {
+          fmt::print("  {}\n", val);
+        } else {
+          fmt::print("  invalid\n");
+        }
+      } else if (entry->second.type == "string" ||
+                 entry->second.type == "json") {
+        std::string_view val;
+        record.GetString(&val);
+        fmt::print("  '{}'\n", val);
+      } else if (entry->second.type == "boolean") {
+        bool val;
+        if (record.GetBoolean(&val)) {
+          fmt::print("  {}\n", val);
+        } else {
+          fmt::print("  invalid\n");
+        }
+      } else if (entry->second.type == "boolean[]") {
+        std::vector<int> val;
+        if (record.GetBooleanArray(&val)) {
+          fmt::print("  {}\n", fmt::join(val, ", "));
+        } else {
+          fmt::print("  invalid\n");
+        }
+      } else if (entry->second.type == "double[]") {
+        std::vector<double> val;
+        if (record.GetDoubleArray(&val)) {
+          fmt::print("  {}\n", fmt::join(val, ", "));
+        } else {
+          fmt::print("  invalid\n");
+        }
+      } else if (entry->second.type == "float[]") {
+        std::vector<float> val;
+        if (record.GetFloatArray(&val)) {
+          fmt::print("  {}\n", fmt::join(val, ", "));
+        } else {
+          fmt::print("  invalid\n");
+        }
+      } else if (entry->second.type == "int64[]") {
+        std::vector<int64_t> val;
+        if (record.GetIntegerArray(&val)) {
+          fmt::print("  {}\n", fmt::join(val, ", "));
+        } else {
+          fmt::print("  invalid\n");
+        }
+      } else if (entry->second.type == "string[]") {
+        std::vector<std::string_view> val;
+        if (record.GetStringArray(&val)) {
+          fmt::print("  {}\n", fmt::join(val, ", "));
+        } else {
+          fmt::print("  invalid\n");
+        }
+      }
+    }
+  }
+}
diff --git a/third_party/allwpilib/wpiutil/examples/webserver/webserver.cpp b/third_party/allwpilib/wpiutil/examples/webserver/webserver.cpp
deleted file mode 100644
index 503405f..0000000
--- a/third_party/allwpilib/wpiutil/examples/webserver/webserver.cpp
+++ /dev/null
@@ -1,87 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include <cstdio>
-
-#include "fmt/format.h"
-#include "wpi/EventLoopRunner.h"
-#include "wpi/HttpServerConnection.h"
-#include "wpi/UrlParser.h"
-#include "wpi/uv/Loop.h"
-#include "wpi/uv/Tcp.h"
-
-namespace uv = wpi::uv;
-
-class MyHttpServerConnection : public wpi::HttpServerConnection {
- public:
-  explicit MyHttpServerConnection(std::shared_ptr<uv::Stream> stream)
-      : HttpServerConnection(stream) {}
-
- protected:
-  void ProcessRequest() override;
-};
-
-void MyHttpServerConnection::ProcessRequest() {
-  fmt::print(stderr, "HTTP request: '{}'\n", m_request.GetUrl());
-  wpi::UrlParser url{m_request.GetUrl(),
-                     m_request.GetMethod() == wpi::HTTP_CONNECT};
-  if (!url.IsValid()) {
-    // failed to parse URL
-    SendError(400);
-    return;
-  }
-
-  std::string_view path;
-  if (url.HasPath()) {
-    path = url.GetPath();
-  }
-  fmt::print(stderr, "path: \"{}\"\n", path);
-
-  std::string_view query;
-  if (url.HasQuery()) {
-    query = url.GetQuery();
-  }
-  fmt::print(stderr, "query: \"{}\"\n", query);
-
-  const bool isGET = m_request.GetMethod() == wpi::HTTP_GET;
-  if (isGET && path == "/") {
-    // build HTML root page
-    SendResponse(200, "OK", "text/html",
-                 "<html><head><title>WebServer Example</title></head>"
-                 "<body><p>This is an example root page from the webserver."
-                 "</body></html>");
-  } else {
-    SendError(404, "Resource not found");
-  }
-}
-
-int main() {
-  // Kick off the event loop on a separate thread
-  wpi::EventLoopRunner loop;
-  loop.ExecAsync([](uv::Loop& loop) {
-    auto tcp = uv::Tcp::Create(loop);
-
-    // bind to listen address and port
-    tcp->Bind("", 8080);
-
-    // when we get a connection, accept it and start reading
-    tcp->connection.connect([srv = tcp.get()] {
-      auto tcp = srv->Accept();
-      if (!tcp) {
-        return;
-      }
-      std::fputs("Got a connection\n", stderr);
-      auto conn = std::make_shared<MyHttpServerConnection>(tcp);
-      tcp->SetData(conn);
-    });
-
-    // start listening for incoming connections
-    tcp->Listen();
-
-    std::fputs("Listening on port 8080\n", stderr);
-  });
-
-  // wait for a keypress to terminate
-  std::getchar();
-}
diff --git a/third_party/allwpilib/wpiutil/examples/writelog/writelog.cpp b/third_party/allwpilib/wpiutil/examples/writelog/writelog.cpp
new file mode 100644
index 0000000..6fdf763
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/examples/writelog/writelog.cpp
@@ -0,0 +1,82 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <array>
+#include <chrono>
+#include <numeric>
+#include <string>
+#include <vector>
+
+#include "fmt/format.h"
+#include "wpi/DataLog.h"
+
+int main(int argc, char** argv) {
+  using std::chrono::duration_cast;
+  using std::chrono::high_resolution_clock;
+  using std::chrono::microseconds;
+
+  int kNumRuns = 10;
+
+  if (argc == 2) {
+    kNumRuns = std::stoi(argv[1]);
+  }
+
+  wpi::log::DataLog log;
+  log.SetFilename("test.wpilog");
+
+  auto testVec =
+      std::vector<std::pair<std::string, void (*)(wpi::log::DataLog&)>>();
+
+  testVec.push_back({"50 double append", [](auto& log) {
+                       wpi::log::DoubleLogEntry entry{log, "fifty", 1};
+                       for (int i = 0; i < 50; ++i) {
+                         entry.Append(1.3 * i, 20000 * i);
+                       }
+                     }});
+#if 0
+  testVec.push_back({"500k double append", [](auto& log) {
+                       wpi::log::DoubleLogEntry entry{log, "500k", 1};
+                       for (uint64_t i = 0; i < 500000; ++i) {
+                         entry.Append(1.3 * i, 20000 * i);
+                       }
+                     }});
+#endif
+  testVec.push_back({"50 string append", [](auto& log) {
+                       wpi::log::StringLogEntry entry{log, "string", 1};
+                       for (int i = 0; i < 50; ++i) {
+                         entry.Append("hello", 20000 * i);
+                       }
+                     }});
+
+  testVec.push_back(
+      {"Double array append", [](auto& log) {
+         wpi::log::DoubleArrayLogEntry entry{log, "double_array", 1};
+         entry.Append({1, 2, 3}, 20000);
+         entry.Append({4, 5}, 30000);
+       }});
+
+  testVec.push_back(
+      {"String array append", [](auto& log) {
+         wpi::log::StringArrayLogEntry entry{log, "string_array", 1};
+         entry.Append({"Hello", "World"}, 20000);
+         entry.Append({"This", "Is", "Fun"}, 30000);
+       }});
+
+  for (const auto& [name, fn] : testVec) {
+    auto resVec = std::vector<microseconds::rep>();
+    fmt::print("{}: ", name);
+
+    for (int i = 0; i < kNumRuns; ++i) {
+      auto start = high_resolution_clock::now();
+      fn(log);
+      auto stop = high_resolution_clock::now();
+      resVec.push_back(duration_cast<microseconds>(stop - start).count());
+    }
+
+    fmt::print("{}us\n",
+               std::accumulate(resVec.begin(), resVec.end(), 0) / kNumRuns);
+  }
+
+  return EXIT_SUCCESS;
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/CircularBuffer.java b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/CircularBuffer.java
index f9129c7..729c8b1 100644
--- a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/CircularBuffer.java
+++ b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/CircularBuffer.java
@@ -4,6 +4,8 @@
 
 package edu.wpi.first.util;
 
+import java.util.Arrays;
+
 /** This is a simple circular buffer so we don't need to "bucket brigade" copy old values. */
 public class CircularBuffer {
   private double[] m_data;
@@ -21,9 +23,7 @@
    */
   public CircularBuffer(int size) {
     m_data = new double[size];
-    for (int i = 0; i < m_data.length; i++) {
-      m_data[i] = 0.0;
-    }
+    Arrays.fill(m_data, 0.0);
   }
 
   /**
@@ -31,7 +31,7 @@
    *
    * @return number of elements in buffer
    */
-  double size() {
+  public int size() {
     return m_length;
   }
 
@@ -40,7 +40,7 @@
    *
    * @return value at front of buffer
    */
-  double getFirst() {
+  public double getFirst() {
     return m_data[m_front];
   }
 
@@ -49,7 +49,7 @@
    *
    * @return value at back of buffer
    */
-  double getLast() {
+  public double getLast() {
     // If there are no elements in the buffer, do nothing
     if (m_length == 0) {
       return 0.0;
@@ -138,7 +138,7 @@
    *
    * @param size New buffer size.
    */
-  void resize(int size) {
+  public void resize(int size) {
     double[] newBuffer = new double[size];
     m_length = Math.min(m_length, size);
     for (int i = 0; i < m_length; i++) {
@@ -150,9 +150,7 @@
 
   /** Sets internal buffer contents to zero. */
   public void clear() {
-    for (int i = 0; i < m_data.length; i++) {
-      m_data[i] = 0.0;
-    }
+    Arrays.fill(m_data, 0.0);
     m_front = 0;
     m_length = 0;
   }
diff --git a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/CombinedRuntimeLoader.java b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/CombinedRuntimeLoader.java
index 9b23144..09e739d 100644
--- a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/CombinedRuntimeLoader.java
+++ b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/CombinedRuntimeLoader.java
@@ -56,7 +56,7 @@
    * @return List of all libraries that were extracted
    * @throws IOException Thrown if resource not found or file could not be extracted
    */
-  @SuppressWarnings({"PMD.UnnecessaryCastRule", "unchecked"})
+  @SuppressWarnings("unchecked")
   public static <T> List<String> extractLibraries(Class<T> clazz, String resourceName)
       throws IOException {
     TypeReference<HashMap<String, Object>> typeRef =
diff --git a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/EventVector.java b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/EventVector.java
new file mode 100644
index 0000000..a85379e
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/EventVector.java
@@ -0,0 +1,54 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.util;
+
+import java.util.ArrayList;
+import java.util.List;
+import java.util.concurrent.locks.ReentrantLock;
+
+public class EventVector {
+  private ReentrantLock m_lock = new ReentrantLock();
+  private List<Integer> m_events = new ArrayList<>();
+
+  /**
+   * Adds an event to the event vector.
+   *
+   * @param handle The event to add
+   */
+  public void add(int handle) {
+    m_lock.lock();
+    try {
+      m_events.add(handle);
+    } finally {
+      m_lock.unlock();
+    }
+  }
+
+  /**
+   * Removes an event from the event vector.
+   *
+   * @param handle The event to remove
+   */
+  public void remove(int handle) {
+    m_lock.lock();
+    try {
+      m_events.removeIf(x -> x == handle);
+    } finally {
+      m_lock.unlock();
+    }
+  }
+
+  /** Wakes up all events in the event vector. */
+  public void wakeup() {
+    m_lock.lock();
+    try {
+      for (Integer eventHandle : m_events) {
+        WPIUtilJNI.setEvent(eventHandle);
+      }
+    } finally {
+      m_lock.unlock();
+    }
+  }
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/InterpolatingTreeMap.java b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/InterpolatingTreeMap.java
new file mode 100644
index 0000000..ade2e5a
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/InterpolatingTreeMap.java
@@ -0,0 +1,96 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.util;
+
+import java.util.TreeMap;
+
+/**
+ * Interpolating Tree Maps are used to get values at points that are not defined by making a guess
+ * from points that are defined. This uses linear interpolation.
+ */
+public class InterpolatingTreeMap<K extends Number, V extends Number> {
+  private final TreeMap<K, V> m_map = new TreeMap<>();
+
+  /**
+   * Inserts a key-value pair.
+   *
+   * @param key The key.
+   * @param value The value.
+   */
+  public void put(K key, V value) {
+    m_map.put(key, value);
+  }
+
+  /**
+   * Returns the value associated with a given key.
+   *
+   * <p>If there's no matching key, the value returned will be a linear interpolation between the
+   * keys before and after the provided one.
+   *
+   * @param key The key.
+   * @return The value associated with the given key.
+   */
+  public Double get(K key) {
+    V val = m_map.get(key);
+    if (val == null) {
+      K ceilingKey = m_map.ceilingKey(key);
+      K floorKey = m_map.floorKey(key);
+
+      if (ceilingKey == null && floorKey == null) {
+        return null;
+      }
+      if (ceilingKey == null) {
+        return m_map.get(floorKey).doubleValue();
+      }
+      if (floorKey == null) {
+        return m_map.get(ceilingKey).doubleValue();
+      }
+      V floor = m_map.get(floorKey);
+      V ceiling = m_map.get(ceilingKey);
+
+      return interpolate(floor, ceiling, inverseInterpolate(ceilingKey, key, floorKey));
+    } else {
+      return val.doubleValue();
+    }
+  }
+
+  /** Clears the contents. */
+  public void clear() {
+    m_map.clear();
+  }
+
+  /**
+   * Return the value interpolated between val1 and val2 by the interpolant d.
+   *
+   * @param val1 The lower part of the interpolation range.
+   * @param val2 The upper part of the interpolation range.
+   * @param d The interpolant in the range [0, 1].
+   * @return The interpolated value.
+   */
+  private double interpolate(V val1, V val2, double d) {
+    double dydx = val2.doubleValue() - val1.doubleValue();
+    return dydx * d + val1.doubleValue();
+  }
+
+  /**
+   * Return where within interpolation range [0, 1] q is between down and up.
+   *
+   * @param up Upper part of interpolation range.
+   * @param q Query.
+   * @param down Lower part of interpolation range.
+   * @return Interpolant in range [0, 1].
+   */
+  private double inverseInterpolate(K up, K q, K down) {
+    double upperToLower = up.doubleValue() - down.doubleValue();
+    if (upperToLower <= 0) {
+      return 0.0;
+    }
+    double queryToLower = q.doubleValue() - down.doubleValue();
+    if (queryToLower <= 0) {
+      return 0.0;
+    }
+    return queryToLower / upperToLower;
+  }
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/MulticastServiceAnnouncer.java b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/MulticastServiceAnnouncer.java
deleted file mode 100644
index 1c4b2ac..0000000
--- a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/MulticastServiceAnnouncer.java
+++ /dev/null
@@ -1,45 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.util;
-
-import java.util.Map;
-
-/** Class to announce over mDNS that a service is available. */
-public class MulticastServiceAnnouncer implements AutoCloseable {
-  private final int m_handle;
-
-  /**
-   * Creates a MulticastServiceAnnouncer.
-   *
-   * @param serviceName service name
-   * @param serviceType service type
-   * @param port port
-   * @param txt txt
-   */
-  public MulticastServiceAnnouncer(
-      String serviceName, String serviceType, int port, Map<String, String> txt) {
-    String[] keys = txt.keySet().toArray(String[]::new);
-    String[] values = txt.values().toArray(String[]::new);
-    m_handle =
-        WPIUtilJNI.createMulticastServiceAnnouncer(serviceName, serviceType, port, keys, values);
-  }
-
-  @Override
-  public void close() {
-    WPIUtilJNI.freeMulticastServiceAnnouncer(m_handle);
-  }
-
-  public void start() {
-    WPIUtilJNI.startMulticastServiceAnnouncer(m_handle);
-  }
-
-  public void stop() {
-    WPIUtilJNI.stopMulticastServiceAnnouncer(m_handle);
-  }
-
-  public boolean hasImplementation() {
-    return WPIUtilJNI.getMulticastServiceAnnouncerHasImplementation(m_handle);
-  }
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/MulticastServiceResolver.java b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/MulticastServiceResolver.java
deleted file mode 100644
index 3e331f2..0000000
--- a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/MulticastServiceResolver.java
+++ /dev/null
@@ -1,44 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.util;
-
-/** Class to resolve a service over mDNS. */
-public class MulticastServiceResolver implements AutoCloseable {
-  private final int m_handle;
-
-  /**
-   * Creates a MulticastServiceResolver.
-   *
-   * @param serviceType service type to look for
-   */
-  public MulticastServiceResolver(String serviceType) {
-    m_handle = WPIUtilJNI.createMulticastServiceResolver(serviceType);
-  }
-
-  @Override
-  public void close() {
-    WPIUtilJNI.freeMulticastServiceResolver(m_handle);
-  }
-
-  public void start() {
-    WPIUtilJNI.startMulticastServiceResolver(m_handle);
-  }
-
-  public void stop() {
-    WPIUtilJNI.stopMulticastServiceResolver(m_handle);
-  }
-
-  public boolean hasImplementation() {
-    return WPIUtilJNI.getMulticastServiceResolverHasImplementation(m_handle);
-  }
-
-  public int getEventHandle() {
-    return WPIUtilJNI.getMulticastServiceResolverEventHandle(m_handle);
-  }
-
-  public ServiceData[] getData() {
-    return WPIUtilJNI.getMulticastServiceResolverData(m_handle);
-  }
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/RuntimeDetector.java b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/RuntimeDetector.java
index d4ad833..550339e 100644
--- a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/RuntimeDetector.java
+++ b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/RuntimeDetector.java
@@ -4,11 +4,7 @@
 
 package edu.wpi.first.util;
 
-import java.io.BufferedReader;
 import java.io.File;
-import java.io.IOException;
-import java.nio.file.Files;
-import java.nio.file.Paths;
 
 public final class RuntimeDetector {
   private static String filePrefix;
@@ -22,6 +18,7 @@
 
     boolean intel32 = is32BitIntel();
     boolean intel64 = is64BitIntel();
+    boolean arm64 = isArm64();
 
     if (isWindows()) {
       filePrefix = "";
@@ -34,11 +31,7 @@
     } else if (isMac()) {
       filePrefix = "lib";
       fileExtension = ".dylib";
-      if (intel32) {
-        filePath = "/osx/x86";
-      } else {
-        filePath = "/osx/x86-64/";
-      }
+      filePath = "/osx/universal/";
     } else if (isLinux()) {
       filePrefix = "lib";
       fileExtension = ".so";
@@ -48,10 +41,10 @@
         filePath = "/linux/x86-64/";
       } else if (isAthena()) {
         filePath = "/linux/athena/";
-      } else if (isRaspbian()) {
-        filePath = "/linux/raspbian/";
-      } else if (isAarch64()) {
-        filePath = "/linux/aarch64bionic/";
+      } else if (isArm32()) {
+        filePath = "/linux/arm32/";
+      } else if (arm64) {
+        filePath = "/linux/arm64/";
       } else {
         filePath = "/linux/nativearm/";
       }
@@ -128,29 +121,23 @@
   }
 
   /**
-   * Check if OS is Raspbian.
+   * Check if OS is Arm32.
    *
-   * @return True if OS is Raspbian.
+   * @return True if OS is Arm32.
    */
-  public static boolean isRaspbian() {
-    try (BufferedReader reader = Files.newBufferedReader(Paths.get("/etc/os-release"))) {
-      String value = reader.readLine();
-      if (value == null) {
-        return false;
-      }
-      return value.contains("Raspbian");
-    } catch (IOException ex) {
-      return false;
-    }
+  public static boolean isArm32() {
+    String arch = System.getProperty("os.arch");
+    return "arm".equals(arch) || "arm32".equals(arch);
   }
 
   /**
-   * check if architecture is aarch64.
+   * check if architecture is Arm64.
    *
-   * @return if architecture is aarch64
+   * @return if architecture is Arm64
    */
-  public static boolean isAarch64() {
-    return "aarch64".equals(System.getProperty("os.arch"));
+  public static boolean isArm64() {
+    String arch = System.getProperty("os.arch");
+    return "aarch64".equals(arch) || "arm64".equals(arch);
   }
 
   public static boolean isLinux() {
diff --git a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/RuntimeLoader.java b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/RuntimeLoader.java
index 942055a..f24ace3 100644
--- a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/RuntimeLoader.java
+++ b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/RuntimeLoader.java
@@ -21,7 +21,7 @@
   private static String defaultExtractionRoot;
 
   /**
-   * Gets the default extration root location (~/.wpilib/nativecache).
+   * Gets the default extraction root location (~/.wpilib/nativecache).
    *
    * @return The default extraction root location.
    */
@@ -80,7 +80,6 @@
    *
    * @throws IOException if the library fails to load
    */
-  @SuppressWarnings("PMD.PreserveStackTrace")
   public void loadLibrary() throws IOException {
     try {
       // First, try loading path
@@ -88,20 +87,20 @@
     } catch (UnsatisfiedLinkError ule) {
       // Then load the hash from the resources
       String hashName = RuntimeDetector.getHashLibraryResource(m_libraryName);
-      String resname = RuntimeDetector.getLibraryResource(m_libraryName);
+      String resName = RuntimeDetector.getLibraryResource(m_libraryName);
       try (InputStream hashIs = m_loadClass.getResourceAsStream(hashName)) {
         if (hashIs == null) {
           throw new IOException(getLoadErrorMessage(ule));
         }
-        try (Scanner scanner = new Scanner(hashIs, StandardCharsets.UTF_8.name())) {
+        try (Scanner scanner = new Scanner(hashIs, StandardCharsets.UTF_8)) {
           String hash = scanner.nextLine();
-          File jniLibrary = new File(m_extractionRoot, resname + "." + hash);
+          File jniLibrary = new File(m_extractionRoot, resName + "." + hash);
           try {
             // Try to load from an already extracted hash
             System.load(jniLibrary.getAbsolutePath());
           } catch (UnsatisfiedLinkError ule2) {
             // If extraction failed, extract
-            try (InputStream resIs = m_loadClass.getResourceAsStream(resname)) {
+            try (InputStream resIs = m_loadClass.getResourceAsStream(resName)) {
               if (resIs == null) {
                 throw new IOException(getLoadErrorMessage(ule));
               }
@@ -132,16 +131,15 @@
    *
    * @throws IOException if the library failed to load
    */
-  @SuppressWarnings({"PMD.PreserveStackTrace", "PMD.EmptyWhileStmt"})
   public void loadLibraryHashed() throws IOException {
     try {
       // First, try loading path
       System.loadLibrary(m_libraryName);
     } catch (UnsatisfiedLinkError ule) {
       // Then load the hash from the input file
-      String resname = RuntimeDetector.getLibraryResource(m_libraryName);
+      String resName = RuntimeDetector.getLibraryResource(m_libraryName);
       String hash;
-      try (InputStream is = m_loadClass.getResourceAsStream(resname)) {
+      try (InputStream is = m_loadClass.getResourceAsStream(resName)) {
         if (is == null) {
           throw new IOException(getLoadErrorMessage(ule));
         }
@@ -167,13 +165,13 @@
       if (hash == null) {
         throw new IOException("Weird Hash?");
       }
-      File jniLibrary = new File(m_extractionRoot, resname + "." + hash);
+      File jniLibrary = new File(m_extractionRoot, resName + "." + hash);
       try {
         // Try to load from an already extracted hash
         System.load(jniLibrary.getAbsolutePath());
       } catch (UnsatisfiedLinkError ule2) {
         // If extraction failed, extract
-        try (InputStream resIs = m_loadClass.getResourceAsStream(resname)) {
+        try (InputStream resIs = m_loadClass.getResourceAsStream(resName)) {
           if (resIs == null) {
             throw new IOException(getLoadErrorMessage(ule));
           }
diff --git a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/ServiceData.java b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/ServiceData.java
deleted file mode 100644
index 0e56010..0000000
--- a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/ServiceData.java
+++ /dev/null
@@ -1,66 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.util;
-
-import java.util.HashMap;
-import java.util.Map;
-
-/** Service data for MulticastServiceResolver. */
-public class ServiceData {
-  /**
-   * Constructs a ServiceData.
-   *
-   * @param ipv4Address ipv4Address
-   * @param port port
-   * @param serviceName found service name
-   * @param hostName found host name
-   * @param keys txt keys
-   * @param values txt values
-   */
-  public ServiceData(
-      long ipv4Address,
-      int port,
-      String serviceName,
-      String hostName,
-      String[] keys,
-      String[] values) {
-    this.m_serviceName = serviceName;
-    this.m_hostName = hostName;
-    this.m_port = port;
-    this.m_ipv4Address = ipv4Address;
-
-    m_txt = new HashMap<>();
-
-    for (int i = 0; i < keys.length; i++) {
-      m_txt.put(keys[i], values[i]);
-    }
-  }
-
-  public Map<String, String> getTxt() {
-    return m_txt;
-  }
-
-  public String getHostName() {
-    return m_hostName;
-  }
-
-  public String getServiceName() {
-    return m_serviceName;
-  }
-
-  public int getPort() {
-    return m_port;
-  }
-
-  public long getIpv4Address() {
-    return m_ipv4Address;
-  }
-
-  private final Map<String, String> m_txt;
-  private final long m_ipv4Address;
-  private final int m_port;
-  private final String m_serviceName;
-  private final String m_hostName;
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/WPIUtilJNI.java b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/WPIUtilJNI.java
index c79f458..9929b48 100644
--- a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/WPIUtilJNI.java
+++ b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/WPIUtilJNI.java
@@ -7,7 +7,7 @@
 import java.io.IOException;
 import java.util.concurrent.atomic.AtomicBoolean;
 
-public final class WPIUtilJNI {
+public class WPIUtilJNI {
   static boolean libraryLoaded = false;
   static RuntimeLoader<WPIUtilJNI> loader = null;
 
@@ -54,6 +54,8 @@
     libraryLoaded = true;
   }
 
+  public static native void writeStderr(String str);
+
   public static native void enableMockTime();
 
   public static native void disableMockTime();
@@ -64,10 +66,6 @@
 
   public static native long getSystemTime();
 
-  public static native void addPortForwarder(int port, String remoteHost, int remotePort);
-
-  public static native void removePortForwarder(int port);
-
   public static native int createEvent(boolean manualReset, boolean initialState);
 
   public static native void destroyEvent(int eventHandle);
@@ -83,7 +81,7 @@
   public static native boolean releaseSemaphore(int semHandle, int releaseCount);
 
   /**
-   * Waits for an handle to be signaled.
+   * Waits for a handle to be signaled.
    *
    * @param handle handle to wait on
    * @throws InterruptedException on failure (e.g. object was destroyed)
@@ -91,7 +89,7 @@
   public static native void waitForObject(int handle) throws InterruptedException;
 
   /**
-   * Waits for an handle to be signaled, with timeout.
+   * Waits for a handle to be signaled, with timeout.
    *
    * @param handle handle to wait on
    * @param timeout timeout in seconds
@@ -126,29 +124,4 @@
    */
   public static native int[] waitForObjectsTimeout(int[] handles, double timeout)
       throws InterruptedException;
-
-  public static native int createMulticastServiceAnnouncer(
-      String serviceName, String serviceType, int port, String[] keys, String[] values);
-
-  public static native void freeMulticastServiceAnnouncer(int handle);
-
-  public static native void startMulticastServiceAnnouncer(int handle);
-
-  public static native void stopMulticastServiceAnnouncer(int handle);
-
-  public static native boolean getMulticastServiceAnnouncerHasImplementation(int handle);
-
-  public static native int createMulticastServiceResolver(String serviceType);
-
-  public static native void freeMulticastServiceResolver(int handle);
-
-  public static native void startMulticastServiceResolver(int handle);
-
-  public static native void stopMulticastServiceResolver(int handle);
-
-  public static native boolean getMulticastServiceResolverHasImplementation(int handle);
-
-  public static native int getMulticastServiceResolverEventHandle(int handle);
-
-  public static native ServiceData[] getMulticastServiceResolverData(int handle);
 }
diff --git a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/concurrent/Semaphore.java b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/concurrent/Semaphore.java
index 4e9e85f..66c28a2 100644
--- a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/concurrent/Semaphore.java
+++ b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/concurrent/Semaphore.java
@@ -18,7 +18,7 @@
    * Constructor.
    *
    * @param initialCount initial value for the semaphore's internal counter
-   * @param maximumCount maximum value for the samephore's internal counter
+   * @param maximumCount maximum value for the semaphore's internal counter
    */
   public Semaphore(int initialCount, int maximumCount) {
     m_handle = WPIUtilJNI.createSemaphore(initialCount, maximumCount);
diff --git a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/BooleanArrayLogEntry.java b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/BooleanArrayLogEntry.java
new file mode 100644
index 0000000..718d460
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/BooleanArrayLogEntry.java
@@ -0,0 +1,45 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.util.datalog;
+
+/** Log array of boolean values. */
+public class BooleanArrayLogEntry extends DataLogEntry {
+  public static final String kDataType = "boolean[]";
+
+  public BooleanArrayLogEntry(DataLog log, String name, String metadata, long timestamp) {
+    super(log, name, kDataType, metadata, timestamp);
+  }
+
+  public BooleanArrayLogEntry(DataLog log, String name, String metadata) {
+    this(log, name, metadata, 0);
+  }
+
+  public BooleanArrayLogEntry(DataLog log, String name, long timestamp) {
+    this(log, name, "", timestamp);
+  }
+
+  public BooleanArrayLogEntry(DataLog log, String name) {
+    this(log, name, 0);
+  }
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param value Value to record
+   * @param timestamp Time stamp (0 to indicate now)
+   */
+  public void append(boolean[] value, long timestamp) {
+    m_log.appendBooleanArray(m_entry, value, timestamp);
+  }
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param value Value to record
+   */
+  public void append(boolean[] value) {
+    m_log.appendBooleanArray(m_entry, value, 0);
+  }
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/BooleanLogEntry.java b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/BooleanLogEntry.java
new file mode 100644
index 0000000..503b83b
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/BooleanLogEntry.java
@@ -0,0 +1,45 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.util.datalog;
+
+/** Log boolean values. */
+public class BooleanLogEntry extends DataLogEntry {
+  public static final String kDataType = "boolean";
+
+  public BooleanLogEntry(DataLog log, String name, String metadata, long timestamp) {
+    super(log, name, kDataType, metadata, timestamp);
+  }
+
+  public BooleanLogEntry(DataLog log, String name, String metadata) {
+    this(log, name, metadata, 0);
+  }
+
+  public BooleanLogEntry(DataLog log, String name, long timestamp) {
+    this(log, name, "", timestamp);
+  }
+
+  public BooleanLogEntry(DataLog log, String name) {
+    this(log, name, 0);
+  }
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param value Value to record
+   * @param timestamp Time stamp (0 to indicate now)
+   */
+  public void append(boolean value, long timestamp) {
+    m_log.appendBoolean(m_entry, value, timestamp);
+  }
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param value Value to record
+   */
+  public void append(boolean value) {
+    m_log.appendBoolean(m_entry, value, 0);
+  }
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/DataLog.java b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/DataLog.java
new file mode 100644
index 0000000..784b8d6
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/DataLog.java
@@ -0,0 +1,252 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.util.datalog;
+
+/**
+ * A data log. The log file is created immediately upon construction with a temporary filename. The
+ * file may be renamed at any time using the setFilename() function.
+ *
+ * <p>The data log is periodically flushed to disk. It can also be explicitly flushed to disk by
+ * using the flush() function.
+ *
+ * <p>The finish() function is needed only to indicate in the log that a particular entry is no
+ * longer being used (it releases the name to ID mapping). The finish() function is not required to
+ * be called for data to be flushed to disk; entries in the log are written as append() calls are
+ * being made. In fact, finish() does not need to be called at all.
+ *
+ * <p>DataLog calls are thread safe. DataLog uses a typical multiple-supplier, single-consumer
+ * setup. Writes to the log are atomic, but there is no guaranteed order in the log when multiple
+ * threads are writing to it; whichever thread grabs the write mutex first will get written first.
+ * For this reason (as well as the fact that timestamps can be set to arbitrary values), records in
+ * the log are not guaranteed to be sorted by timestamp.
+ */
+public final class DataLog implements AutoCloseable {
+  /**
+   * Construct a new Data Log. The log will be initially created with a temporary filename.
+   *
+   * @param dir directory to store the log
+   * @param filename filename to use; if none provided, a random filename is generated of the form
+   *     "wpilog_{}.wpilog"
+   * @param period time between automatic flushes to disk, in seconds; this is a time/storage
+   *     tradeoff
+   * @param extraHeader extra header data
+   */
+  public DataLog(String dir, String filename, double period, String extraHeader) {
+    m_impl = DataLogJNI.create(dir, filename, period, extraHeader);
+  }
+
+  /**
+   * Construct a new Data Log. The log will be initially created with a temporary filename.
+   *
+   * @param dir directory to store the log
+   * @param filename filename to use; if none provided, a random filename is generated of the form
+   *     "wpilog_{}.wpilog"
+   * @param period time between automatic flushes to disk, in seconds; this is a time/storage
+   *     tradeoff
+   */
+  public DataLog(String dir, String filename, double period) {
+    this(dir, filename, period, "");
+  }
+
+  /**
+   * Construct a new Data Log. The log will be initially created with a temporary filename.
+   *
+   * @param dir directory to store the log
+   * @param filename filename to use; if none provided, a random filename is generated of the form
+   *     "wpilog_{}.wpilog"
+   */
+  public DataLog(String dir, String filename) {
+    this(dir, filename, 0.25);
+  }
+
+  /**
+   * Construct a new Data Log. The log will be initially created with a temporary filename.
+   *
+   * @param dir directory to store the log
+   */
+  public DataLog(String dir) {
+    this(dir, "", 0.25);
+  }
+
+  /** Construct a new Data Log. The log will be initially created with a temporary filename. */
+  public DataLog() {
+    this("");
+  }
+
+  /**
+   * Change log filename.
+   *
+   * @param filename filename
+   */
+  public void setFilename(String filename) {
+    DataLogJNI.setFilename(m_impl, filename);
+  }
+
+  /** Explicitly flushes the log data to disk. */
+  public void flush() {
+    DataLogJNI.flush(m_impl);
+  }
+
+  /**
+   * Pauses appending of data records to the log. While paused, no data records are saved (e.g.
+   * AppendX is a no-op). Has no effect on entry starts / finishes / metadata changes.
+   */
+  public void pause() {
+    DataLogJNI.pause(m_impl);
+  }
+
+  /** Resumes appending of data records to the log. */
+  public void resume() {
+    DataLogJNI.resume(m_impl);
+  }
+
+  /**
+   * Start an entry. Duplicate names are allowed (with the same type), and result in the same index
+   * being returned (start/finish are reference counted). A duplicate name with a different type
+   * will result in an error message being printed to the console and 0 being returned (which will
+   * be ignored by the append functions).
+   *
+   * @param name Name
+   * @param type Data type
+   * @param metadata Initial metadata (e.g. data properties)
+   * @param timestamp Time stamp (0 to indicate now)
+   * @return Entry index
+   */
+  public int start(String name, String type, String metadata, long timestamp) {
+    return DataLogJNI.start(m_impl, name, type, metadata, timestamp);
+  }
+
+  /**
+   * Start an entry. Duplicate names are allowed (with the same type), and result in the same index
+   * being returned (start/finish are reference counted). A duplicate name with a different type
+   * will result in an error message being printed to the console and 0 being returned (which will
+   * be ignored by the append functions).
+   *
+   * @param name Name
+   * @param type Data type
+   * @param metadata Initial metadata (e.g. data properties)
+   * @return Entry index
+   */
+  public int start(String name, String type, String metadata) {
+    return start(name, type, metadata, 0);
+  }
+
+  /**
+   * Start an entry. Duplicate names are allowed (with the same type), and result in the same index
+   * being returned (start/finish are reference counted). A duplicate name with a different type
+   * will result in an error message being printed to the console and 0 being returned (which will
+   * be ignored by the append functions).
+   *
+   * @param name Name
+   * @param type Data type
+   * @return Entry index
+   */
+  public int start(String name, String type) {
+    return start(name, type, "");
+  }
+
+  /**
+   * Finish an entry.
+   *
+   * @param entry Entry index
+   * @param timestamp Time stamp (0 to indicate now)
+   */
+  public void finish(int entry, long timestamp) {
+    DataLogJNI.finish(m_impl, entry, timestamp);
+  }
+
+  /**
+   * Finish an entry.
+   *
+   * @param entry Entry index
+   */
+  public void finish(int entry) {
+    finish(entry, 0);
+  }
+
+  /**
+   * Updates the metadata for an entry.
+   *
+   * @param entry Entry index
+   * @param metadata New metadata for the entry
+   * @param timestamp Time stamp (0 to indicate now)
+   */
+  public void setMetadata(int entry, String metadata, long timestamp) {
+    DataLogJNI.setMetadata(m_impl, entry, metadata, timestamp);
+  }
+
+  /**
+   * Updates the metadata for an entry.
+   *
+   * @param entry Entry index
+   * @param metadata New metadata for the entry
+   */
+  public void setMetadata(int entry, String metadata) {
+    setMetadata(entry, metadata, 0);
+  }
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param entry Entry index, as returned by Start()
+   * @param data Data to record
+   * @param timestamp Time stamp (0 to indicate now)
+   */
+  public void appendRaw(int entry, byte[] data, long timestamp) {
+    DataLogJNI.appendRaw(m_impl, entry, data, timestamp);
+  }
+
+  @Override
+  public void close() {
+    DataLogJNI.close(m_impl);
+    m_impl = 0;
+  }
+
+  public void appendBoolean(int entry, boolean value, long timestamp) {
+    DataLogJNI.appendBoolean(m_impl, entry, value, timestamp);
+  }
+
+  public void appendInteger(int entry, long value, long timestamp) {
+    DataLogJNI.appendInteger(m_impl, entry, value, timestamp);
+  }
+
+  public void appendFloat(int entry, float value, long timestamp) {
+    DataLogJNI.appendFloat(m_impl, entry, value, timestamp);
+  }
+
+  public void appendDouble(int entry, double value, long timestamp) {
+    DataLogJNI.appendDouble(m_impl, entry, value, timestamp);
+  }
+
+  public void appendString(int entry, String value, long timestamp) {
+    DataLogJNI.appendString(m_impl, entry, value, timestamp);
+  }
+
+  public void appendBooleanArray(int entry, boolean[] arr, long timestamp) {
+    DataLogJNI.appendBooleanArray(m_impl, entry, arr, timestamp);
+  }
+
+  public void appendIntegerArray(int entry, long[] arr, long timestamp) {
+    DataLogJNI.appendIntegerArray(m_impl, entry, arr, timestamp);
+  }
+
+  public void appendFloatArray(int entry, float[] arr, long timestamp) {
+    DataLogJNI.appendFloatArray(m_impl, entry, arr, timestamp);
+  }
+
+  public void appendDoubleArray(int entry, double[] arr, long timestamp) {
+    DataLogJNI.appendDoubleArray(m_impl, entry, arr, timestamp);
+  }
+
+  public void appendStringArray(int entry, String[] arr, long timestamp) {
+    DataLogJNI.appendStringArray(m_impl, entry, arr, timestamp);
+  }
+
+  public long getImpl() {
+    return m_impl;
+  }
+
+  private long m_impl;
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/DataLogEntry.java b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/DataLogEntry.java
new file mode 100644
index 0000000..4beaff2
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/DataLogEntry.java
@@ -0,0 +1,57 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.util.datalog;
+
+/** Log entry base class. */
+public class DataLogEntry {
+  protected DataLogEntry(DataLog log, String name, String type, String metadata, long timestamp) {
+    m_log = log;
+    m_entry = log.start(name, type, metadata, timestamp);
+  }
+
+  protected DataLogEntry(DataLog log, String name, String type, String metadata) {
+    this(log, name, type, metadata, 0);
+  }
+
+  protected DataLogEntry(DataLog log, String name, String type) {
+    this(log, name, type, "");
+  }
+
+  /**
+   * Updates the metadata for the entry.
+   *
+   * @param metadata New metadata for the entry
+   * @param timestamp Time stamp (0 to indicate now)
+   */
+  public void setMetadata(String metadata, long timestamp) {
+    m_log.setMetadata(m_entry, metadata, timestamp);
+  }
+
+  /**
+   * Updates the metadata for the entry.
+   *
+   * @param metadata New metadata for the entry
+   */
+  public void setMetadata(String metadata) {
+    setMetadata(metadata, 0);
+  }
+
+  /**
+   * Finishes the entry.
+   *
+   * @param timestamp Time stamp (0 to indicate now)
+   */
+  public void finish(long timestamp) {
+    m_log.finish(m_entry, timestamp);
+  }
+
+  /** Finishes the entry. */
+  public void finish() {
+    finish(0);
+  }
+
+  protected final DataLog m_log;
+  protected final int m_entry;
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/DataLogIterator.java b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/DataLogIterator.java
new file mode 100644
index 0000000..3f1d66e
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/DataLogIterator.java
@@ -0,0 +1,46 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.util.datalog;
+
+import java.util.Iterator;
+import java.util.NoSuchElementException;
+import java.util.function.Consumer;
+
+/** DataLogReader iterator. */
+public class DataLogIterator implements Iterator<DataLogRecord> {
+  DataLogIterator(DataLogReader reader, int pos) {
+    m_reader = reader;
+    m_pos = pos;
+  }
+
+  @Override
+  public void forEachRemaining(Consumer<? super DataLogRecord> action) {
+    int size = m_reader.size();
+    for (; m_pos < size; m_pos = m_reader.getNextRecord(m_pos)) {
+      DataLogRecord record;
+      try {
+        record = m_reader.getRecord(m_pos);
+      } catch (NoSuchElementException ex) {
+        break;
+      }
+      action.accept(record);
+    }
+  }
+
+  @Override
+  public boolean hasNext() {
+    return (m_pos + 16) <= m_reader.size();
+  }
+
+  @Override
+  public DataLogRecord next() {
+    DataLogRecord record = m_reader.getRecord(m_pos);
+    m_pos = m_reader.getNextRecord(m_pos);
+    return record;
+  }
+
+  private final DataLogReader m_reader;
+  private int m_pos;
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/DataLogJNI.java b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/DataLogJNI.java
new file mode 100644
index 0000000..724b3d9
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/DataLogJNI.java
@@ -0,0 +1,49 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.util.datalog;
+
+import edu.wpi.first.util.WPIUtilJNI;
+
+public class DataLogJNI extends WPIUtilJNI {
+  static native long create(String dir, String filename, double period, String extraHeader);
+
+  static native void setFilename(long impl, String filename);
+
+  static native void flush(long impl);
+
+  static native void pause(long impl);
+
+  static native void resume(long impl);
+
+  static native int start(long impl, String name, String type, String metadata, long timestamp);
+
+  static native void finish(long impl, int entry, long timestamp);
+
+  static native void setMetadata(long impl, int entry, String metadata, long timestamp);
+
+  static native void close(long impl);
+
+  static native void appendRaw(long impl, int entry, byte[] data, long timestamp);
+
+  static native void appendBoolean(long impl, int entry, boolean value, long timestamp);
+
+  static native void appendInteger(long impl, int entry, long value, long timestamp);
+
+  static native void appendFloat(long impl, int entry, float value, long timestamp);
+
+  static native void appendDouble(long impl, int entry, double value, long timestamp);
+
+  static native void appendString(long impl, int entry, String value, long timestamp);
+
+  static native void appendBooleanArray(long impl, int entry, boolean[] value, long timestamp);
+
+  static native void appendIntegerArray(long impl, int entry, long[] value, long timestamp);
+
+  static native void appendFloatArray(long impl, int entry, float[] value, long timestamp);
+
+  static native void appendDoubleArray(long impl, int entry, double[] value, long timestamp);
+
+  static native void appendStringArray(long impl, int entry, String[] value, long timestamp);
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/DataLogReader.java b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/DataLogReader.java
new file mode 100644
index 0000000..55eabf3
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/DataLogReader.java
@@ -0,0 +1,154 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.util.datalog;
+
+import java.io.IOException;
+import java.io.RandomAccessFile;
+import java.nio.BufferUnderflowException;
+import java.nio.ByteBuffer;
+import java.nio.ByteOrder;
+import java.nio.channels.FileChannel;
+import java.nio.charset.StandardCharsets;
+import java.util.NoSuchElementException;
+import java.util.function.Consumer;
+
+/** Data log reader (reads logs written by the DataLog class). */
+public class DataLogReader implements Iterable<DataLogRecord> {
+  /**
+   * Constructs from a byte buffer.
+   *
+   * @param buffer byte buffer
+   */
+  public DataLogReader(ByteBuffer buffer) {
+    m_buf = buffer;
+    m_buf.order(ByteOrder.LITTLE_ENDIAN);
+  }
+
+  /**
+   * Constructs from a file.
+   *
+   * @param filename filename
+   * @throws IOException if unable to open/read file
+   */
+  public DataLogReader(String filename) throws IOException {
+    RandomAccessFile f = new RandomAccessFile(filename, "r");
+    FileChannel channel = f.getChannel();
+    m_buf = channel.map(FileChannel.MapMode.READ_ONLY, 0, channel.size());
+    m_buf.order(ByteOrder.LITTLE_ENDIAN);
+    channel.close();
+    f.close();
+  }
+
+  /**
+   * Returns true if the data log is valid (e.g. has a valid header).
+   *
+   * @return True if valid, false otherwise
+   */
+  public boolean isValid() {
+    return m_buf.remaining() >= 12
+        && m_buf.get(0) == 'W'
+        && m_buf.get(1) == 'P'
+        && m_buf.get(2) == 'I'
+        && m_buf.get(3) == 'L'
+        && m_buf.get(4) == 'O'
+        && m_buf.get(5) == 'G'
+        && m_buf.getShort(6) >= 0x0100;
+  }
+
+  /**
+   * Gets the data log version. Returns 0 if data log is invalid.
+   *
+   * @return Version number; most significant byte is major, least significant is minor (so version
+   *     1.0 will be 0x0100)
+   */
+  public short getVersion() {
+    if (m_buf.remaining() < 12) {
+      return 0;
+    }
+    return m_buf.getShort(6);
+  }
+
+  /**
+   * Gets the extra header data.
+   *
+   * @return Extra header data
+   */
+  public String getExtraHeader() {
+    ByteBuffer buf = m_buf.duplicate();
+    buf.order(ByteOrder.LITTLE_ENDIAN);
+    buf.position(8);
+    int size = buf.getInt();
+    byte[] arr = new byte[size];
+    buf.get(arr);
+    return new String(arr, StandardCharsets.UTF_8);
+  }
+
+  @Override
+  public void forEach(Consumer<? super DataLogRecord> action) {
+    int size = m_buf.remaining();
+    for (int pos = 12 + m_buf.getInt(8); pos < size; pos = getNextRecord(pos)) {
+      DataLogRecord record;
+      try {
+        record = getRecord(pos);
+      } catch (NoSuchElementException ex) {
+        break;
+      }
+      action.accept(record);
+    }
+  }
+
+  @Override
+  public DataLogIterator iterator() {
+    return new DataLogIterator(this, 12 + m_buf.getInt(8));
+  }
+
+  private long readVarInt(int pos, int len) {
+    long val = 0;
+    for (int i = 0; i < len; i++) {
+      val |= ((long) (m_buf.get(pos + i) & 0xff)) << (i * 8);
+    }
+    return val;
+  }
+
+  DataLogRecord getRecord(int pos) {
+    try {
+      int lenbyte = m_buf.get(pos) & 0xff;
+      int entryLen = (lenbyte & 0x3) + 1;
+      int sizeLen = ((lenbyte >> 2) & 0x3) + 1;
+      int timestampLen = ((lenbyte >> 4) & 0x7) + 1;
+      int headerLen = 1 + entryLen + sizeLen + timestampLen;
+      int entry = (int) readVarInt(pos + 1, entryLen);
+      int size = (int) readVarInt(pos + 1 + entryLen, sizeLen);
+      long timestamp = readVarInt(pos + 1 + entryLen + sizeLen, timestampLen);
+      // build a slice of the data contents
+      ByteBuffer data = m_buf.duplicate();
+      data.position(pos + headerLen);
+      data.limit(pos + headerLen + size);
+      return new DataLogRecord(entry, timestamp, data.slice());
+    } catch (BufferUnderflowException | IndexOutOfBoundsException ex) {
+      throw new NoSuchElementException();
+    }
+  }
+
+  int getNextRecord(int pos) {
+    int lenbyte = m_buf.get(pos) & 0xff;
+    int entryLen = (lenbyte & 0x3) + 1;
+    int sizeLen = ((lenbyte >> 2) & 0x3) + 1;
+    int timestampLen = ((lenbyte >> 4) & 0x7) + 1;
+    int headerLen = 1 + entryLen + sizeLen + timestampLen;
+
+    int size = 0;
+    for (int i = 0; i < sizeLen; i++) {
+      size |= (m_buf.get(pos + 1 + entryLen + i) & 0xff) << (i * 8);
+    }
+    return pos + headerLen + size;
+  }
+
+  int size() {
+    return m_buf.remaining();
+  }
+
+  private final ByteBuffer m_buf;
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/DataLogRecord.java b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/DataLogRecord.java
new file mode 100644
index 0000000..5e3965b
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/DataLogRecord.java
@@ -0,0 +1,430 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.util.datalog;
+
+import java.nio.BufferUnderflowException;
+import java.nio.ByteBuffer;
+import java.nio.ByteOrder;
+import java.nio.DoubleBuffer;
+import java.nio.FloatBuffer;
+import java.nio.LongBuffer;
+import java.nio.charset.StandardCharsets;
+import java.util.InputMismatchException;
+
+/**
+ * A record in the data log. May represent either a control record (entry == 0) or a data record.
+ * Used only for reading (e.g. with DataLogReader).
+ */
+public class DataLogRecord {
+  private static final int kControlStart = 0;
+  private static final int kControlFinish = 1;
+  private static final int kControlSetMetadata = 2;
+
+  DataLogRecord(int entry, long timestamp, ByteBuffer data) {
+    m_entry = entry;
+    m_timestamp = timestamp;
+    m_data = data;
+    m_data.order(ByteOrder.LITTLE_ENDIAN);
+  }
+
+  /**
+   * Gets the entry ID.
+   *
+   * @return entry ID
+   */
+  public int getEntry() {
+    return m_entry;
+  }
+
+  /**
+   * Gets the record timestamp.
+   *
+   * @return Timestamp, in integer microseconds
+   */
+  public long getTimestamp() {
+    return m_timestamp;
+  }
+
+  /**
+   * Gets the size of the raw data.
+   *
+   * @return size
+   */
+  public int getSize() {
+    return m_data.remaining();
+  }
+
+  /**
+   * Gets the raw data. Use the GetX functions to decode based on the data type in the entry's start
+   * record.
+   *
+   * @return byte array
+   */
+  public byte[] getRaw() {
+    ByteBuffer buf = getRawBuffer();
+    byte[] arr = new byte[buf.remaining()];
+    buf.get(arr);
+    return arr;
+  }
+
+  /**
+   * Gets the raw data. Use the GetX functions to decode based on the data type in the entry's start
+   * record.
+   *
+   * @return byte buffer
+   */
+  public ByteBuffer getRawBuffer() {
+    ByteBuffer buf = m_data.duplicate();
+    buf.order(ByteOrder.LITTLE_ENDIAN);
+    return buf;
+  }
+
+  /**
+   * Returns true if the record is a control record.
+   *
+   * @return True if control record, false if normal data record.
+   */
+  public boolean isControl() {
+    return m_entry == 0;
+  }
+
+  /**
+   * Returns true if the record is a start control record. Use GetStartData() to decode the
+   * contents.
+   *
+   * @return True if start control record, false otherwise.
+   */
+  public boolean isStart() {
+    return m_entry == 0 && m_data.remaining() >= 17 && m_data.get(0) == kControlStart;
+  }
+
+  /**
+   * Returns true if the record is a finish control record. Use GetFinishEntry() to decode the
+   * contents.
+   *
+   * @return True if finish control record, false otherwise.
+   */
+  public boolean isFinish() {
+    return m_entry == 0 && m_data.remaining() == 5 && m_data.get(0) == kControlFinish;
+  }
+
+  /**
+   * Returns true if the record is a set metadata control record. Use GetSetMetadataData() to decode
+   * the contents.
+   *
+   * @return True if set metadata control record, false otherwise.
+   */
+  public boolean isSetMetadata() {
+    return m_entry == 0 && m_data.remaining() >= 9 && m_data.get(0) == kControlSetMetadata;
+  }
+
+  /**
+   * Data contained in a start control record as created by DataLog.start() when writing the log.
+   * This can be read by calling getStartData().
+   */
+  @SuppressWarnings("MemberName")
+  public static class StartRecordData {
+    StartRecordData(int entry, String name, String type, String metadata) {
+      this.entry = entry;
+      this.name = name;
+      this.type = type;
+      this.metadata = metadata;
+    }
+
+    /** Entry ID; this will be used for this entry in future records. */
+    public final int entry;
+
+    /** Entry name. */
+    public final String name;
+
+    /** Type of the stored data for this entry, as a string, e.g. "double". */
+    public final String type;
+
+    /** Initial metadata. */
+    public final String metadata;
+  }
+
+  /**
+   * Decodes a start control record.
+   *
+   * @return start record decoded data
+   * @throws InputMismatchException on error
+   */
+  public StartRecordData getStartData() {
+    if (!isStart()) {
+      throw new InputMismatchException("not a start record");
+    }
+    ByteBuffer buf = getRawBuffer();
+    buf.position(1); // skip over control type
+    int entry = buf.getInt();
+    String name = readInnerString(buf);
+    String type = readInnerString(buf);
+    String metadata = readInnerString(buf);
+    return new StartRecordData(entry, name, type, metadata);
+  }
+
+  /**
+   * Data contained in a set metadata control record as created by DataLog.setMetadata(). This can
+   * be read by calling getSetMetadataData().
+   */
+  @SuppressWarnings("MemberName")
+  public static class MetadataRecordData {
+    MetadataRecordData(int entry, String metadata) {
+      this.entry = entry;
+      this.metadata = metadata;
+    }
+
+    /** Entry ID. */
+    public final int entry;
+
+    /** New metadata for the entry. */
+    public final String metadata;
+  }
+
+  /**
+   * Decodes a finish control record.
+   *
+   * @return finish record entry ID
+   * @throws InputMismatchException on error
+   */
+  public int getFinishEntry() {
+    if (!isFinish()) {
+      throw new InputMismatchException("not a finish record");
+    }
+    return m_data.getInt(1);
+  }
+
+  /**
+   * Decodes a set metadata control record.
+   *
+   * @return set metadata record decoded data
+   * @throws InputMismatchException on error
+   */
+  public MetadataRecordData getSetMetadataData() {
+    if (!isSetMetadata()) {
+      throw new InputMismatchException("not a set metadata record");
+    }
+    ByteBuffer buf = getRawBuffer();
+    buf.position(1); // skip over control type
+    int entry = buf.getInt();
+    String metadata = readInnerString(buf);
+    return new MetadataRecordData(entry, metadata);
+  }
+
+  /**
+   * Decodes a data record as a boolean. Note if the data type (as indicated in the corresponding
+   * start control record for this entry) is not "boolean", invalid results may be returned.
+   *
+   * @return boolean value
+   * @throws InputMismatchException on error
+   */
+  public boolean getBoolean() {
+    try {
+      return m_data.get(0) != 0;
+    } catch (IndexOutOfBoundsException ex) {
+      throw new InputMismatchException();
+    }
+  }
+
+  /**
+   * Decodes a data record as an integer. Note if the data type (as indicated in the corresponding
+   * start control record for this entry) is not "int64", invalid results may be returned.
+   *
+   * @return integer value
+   * @throws InputMismatchException on error
+   */
+  public long getInteger() {
+    try {
+      return m_data.getLong(0);
+    } catch (BufferUnderflowException | IndexOutOfBoundsException ex) {
+      throw new InputMismatchException();
+    }
+  }
+
+  /**
+   * Decodes a data record as a float. Note if the data type (as indicated in the corresponding
+   * start control record for this entry) is not "float", invalid results may be returned.
+   *
+   * @return float value
+   * @throws InputMismatchException on error
+   */
+  public float getFloat() {
+    try {
+      return m_data.getFloat(0);
+    } catch (BufferUnderflowException | IndexOutOfBoundsException ex) {
+      throw new InputMismatchException();
+    }
+  }
+
+  /**
+   * Decodes a data record as a double. Note if the data type (as indicated in the corresponding
+   * start control record for this entry) is not "double", invalid results may be returned.
+   *
+   * @return double value
+   * @throws InputMismatchException on error
+   */
+  public double getDouble() {
+    try {
+      return m_data.getDouble(0);
+    } catch (BufferUnderflowException | IndexOutOfBoundsException ex) {
+      throw new InputMismatchException();
+    }
+  }
+
+  /**
+   * Decodes a data record as a string. Note if the data type (as indicated in the corresponding
+   * start control record for this entry) is not "string", invalid results may be returned.
+   *
+   * @return string value
+   */
+  public String getString() {
+    return new String(getRaw(), StandardCharsets.UTF_8);
+  }
+
+  /**
+   * Decodes a data record as a boolean array. Note if the data type (as indicated in the
+   * corresponding start control record for this entry) is not "boolean[]", invalid results may be
+   * returned.
+   *
+   * @return boolean array
+   */
+  public boolean[] getBooleanArray() {
+    boolean[] arr = new boolean[m_data.remaining()];
+    for (int i = 0; i < m_data.remaining(); i++) {
+      arr[i] = m_data.get(i) != 0;
+    }
+    return arr;
+  }
+
+  /**
+   * Decodes a data record as an integer array. Note if the data type (as indicated in the
+   * corresponding start control record for this entry) is not "int64[]", invalid results may be
+   * returned.
+   *
+   * @return integer array
+   * @throws InputMismatchException on error
+   */
+  public long[] getIntegerArray() {
+    LongBuffer buf = getIntegerBuffer();
+    long[] arr = new long[buf.remaining()];
+    buf.get(arr);
+    return arr;
+  }
+
+  /**
+   * Decodes a data record as an integer array. Note if the data type (as indicated in the
+   * corresponding start control record for this entry) is not "int64[]", invalid results may be
+   * returned.
+   *
+   * @return integer buffer
+   * @throws InputMismatchException on error
+   */
+  public LongBuffer getIntegerBuffer() {
+    if ((m_data.limit() % 8) != 0) {
+      throw new InputMismatchException("data size is not a multiple of 8");
+    }
+    return m_data.asLongBuffer();
+  }
+
+  /**
+   * Decodes a data record as a float array. Note if the data type (as indicated in the
+   * corresponding start control record for this entry) is not "float[]", invalid results may be
+   * returned.
+   *
+   * @return float array
+   * @throws InputMismatchException on error
+   */
+  public float[] getFloatArray() {
+    FloatBuffer buf = getFloatBuffer();
+    float[] arr = new float[buf.remaining()];
+    buf.get(arr);
+    return arr;
+  }
+
+  /**
+   * Decodes a data record as a float array. Note if the data type (as indicated in the
+   * corresponding start control record for this entry) is not "float[]", invalid results may be
+   * returned.
+   *
+   * @return float buffer
+   * @throws InputMismatchException on error
+   */
+  public FloatBuffer getFloatBuffer() {
+    if ((m_data.limit() % 4) != 0) {
+      throw new InputMismatchException("data size is not a multiple of 4");
+    }
+    return m_data.asFloatBuffer();
+  }
+
+  /**
+   * Decodes a data record as a double array. Note if the data type (as indicated in the
+   * corresponding start control record for this entry) is not "double[]", invalid results may be
+   * returned.
+   *
+   * @return double array
+   * @throws InputMismatchException on error
+   */
+  public double[] getDoubleArray() {
+    DoubleBuffer buf = getDoubleBuffer();
+    double[] arr = new double[buf.remaining()];
+    buf.get(arr);
+    return arr;
+  }
+
+  /**
+   * Decodes a data record as a double array. Note if the data type (as indicated in the
+   * corresponding start control record for this entry) is not "double[]", invalid results may be
+   * returned.
+   *
+   * @return double buffer
+   * @throws InputMismatchException on error
+   */
+  public DoubleBuffer getDoubleBuffer() {
+    if ((m_data.limit() % 8) != 0) {
+      throw new InputMismatchException("data size is not a multiple of 8");
+    }
+    return m_data.asDoubleBuffer();
+  }
+
+  /**
+   * Decodes a data record as a string array. Note if the data type (as indicated in the
+   * corresponding start control record for this entry) is not "string[]", invalid results may be
+   * returned.
+   *
+   * @return string array
+   * @throws InputMismatchException on error
+   */
+  public String[] getStringArray() {
+    ByteBuffer buf = getRawBuffer();
+    try {
+      int size = buf.getInt();
+      // sanity check size
+      if (size > (buf.remaining() / 4)) {
+        throw new InputMismatchException("invalid size");
+      }
+      String[] arr = new String[size];
+      for (int i = 0; i < size; i++) {
+        arr[i] = readInnerString(buf);
+      }
+      return arr;
+    } catch (BufferUnderflowException | IndexOutOfBoundsException ex) {
+      throw new InputMismatchException();
+    }
+  }
+
+  private String readInnerString(ByteBuffer buf) {
+    int size = buf.getInt();
+    if (size > buf.remaining()) {
+      throw new InputMismatchException("invalid string size");
+    }
+    byte[] arr = new byte[size];
+    buf.get(arr);
+    return new String(arr, StandardCharsets.UTF_8);
+  }
+
+  private final int m_entry;
+  private final long m_timestamp;
+  private final ByteBuffer m_data;
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/DoubleArrayLogEntry.java b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/DoubleArrayLogEntry.java
new file mode 100644
index 0000000..67ef8c3
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/DoubleArrayLogEntry.java
@@ -0,0 +1,45 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.util.datalog;
+
+/** Log array of double values. */
+public class DoubleArrayLogEntry extends DataLogEntry {
+  public static final String kDataType = "double[]";
+
+  public DoubleArrayLogEntry(DataLog log, String name, String metadata, long timestamp) {
+    super(log, name, kDataType, metadata, timestamp);
+  }
+
+  public DoubleArrayLogEntry(DataLog log, String name, String metadata) {
+    this(log, name, metadata, 0);
+  }
+
+  public DoubleArrayLogEntry(DataLog log, String name, long timestamp) {
+    this(log, name, "", timestamp);
+  }
+
+  public DoubleArrayLogEntry(DataLog log, String name) {
+    this(log, name, 0);
+  }
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param value Value to record
+   * @param timestamp Time stamp (0 to indicate now)
+   */
+  public void append(double[] value, long timestamp) {
+    m_log.appendDoubleArray(m_entry, value, timestamp);
+  }
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param value Value to record
+   */
+  public void append(double[] value) {
+    m_log.appendDoubleArray(m_entry, value, 0);
+  }
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/DoubleLogEntry.java b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/DoubleLogEntry.java
new file mode 100644
index 0000000..f16c27e
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/DoubleLogEntry.java
@@ -0,0 +1,45 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.util.datalog;
+
+/** Log double values. */
+public class DoubleLogEntry extends DataLogEntry {
+  public static final String kDataType = "double";
+
+  public DoubleLogEntry(DataLog log, String name, String metadata, long timestamp) {
+    super(log, name, kDataType, metadata, timestamp);
+  }
+
+  public DoubleLogEntry(DataLog log, String name, String metadata) {
+    this(log, name, metadata, 0);
+  }
+
+  public DoubleLogEntry(DataLog log, String name, long timestamp) {
+    this(log, name, "", timestamp);
+  }
+
+  public DoubleLogEntry(DataLog log, String name) {
+    this(log, name, 0);
+  }
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param value Value to record
+   * @param timestamp Time stamp (0 to indicate now)
+   */
+  public void append(double value, long timestamp) {
+    m_log.appendDouble(m_entry, value, timestamp);
+  }
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param value Value to record
+   */
+  public void append(double value) {
+    m_log.appendDouble(m_entry, value, 0);
+  }
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/FloatArrayLogEntry.java b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/FloatArrayLogEntry.java
new file mode 100644
index 0000000..3a0b7e0
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/FloatArrayLogEntry.java
@@ -0,0 +1,45 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.util.datalog;
+
+/** Log array of float values. */
+public class FloatArrayLogEntry extends DataLogEntry {
+  public static final String kDataType = "float[]";
+
+  public FloatArrayLogEntry(DataLog log, String name, String metadata, long timestamp) {
+    super(log, name, kDataType, metadata, timestamp);
+  }
+
+  public FloatArrayLogEntry(DataLog log, String name, String metadata) {
+    this(log, name, metadata, 0);
+  }
+
+  public FloatArrayLogEntry(DataLog log, String name, long timestamp) {
+    this(log, name, "", timestamp);
+  }
+
+  public FloatArrayLogEntry(DataLog log, String name) {
+    this(log, name, 0);
+  }
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param value Value to record
+   * @param timestamp Time stamp (0 to indicate now)
+   */
+  public void append(float[] value, long timestamp) {
+    m_log.appendFloatArray(m_entry, value, timestamp);
+  }
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param value Value to record
+   */
+  public void append(float[] value) {
+    m_log.appendFloatArray(m_entry, value, 0);
+  }
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/FloatLogEntry.java b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/FloatLogEntry.java
new file mode 100644
index 0000000..28adc34
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/FloatLogEntry.java
@@ -0,0 +1,45 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.util.datalog;
+
+/** Log float values. */
+public class FloatLogEntry extends DataLogEntry {
+  public static final String kDataType = "float";
+
+  public FloatLogEntry(DataLog log, String name, String metadata, long timestamp) {
+    super(log, name, kDataType, metadata, timestamp);
+  }
+
+  public FloatLogEntry(DataLog log, String name, String metadata) {
+    this(log, name, metadata, 0);
+  }
+
+  public FloatLogEntry(DataLog log, String name, long timestamp) {
+    this(log, name, "", timestamp);
+  }
+
+  public FloatLogEntry(DataLog log, String name) {
+    this(log, name, 0);
+  }
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param value Value to record
+   * @param timestamp Time stamp (0 to indicate now)
+   */
+  public void append(float value, long timestamp) {
+    m_log.appendFloat(m_entry, value, timestamp);
+  }
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param value Value to record
+   */
+  public void append(float value) {
+    m_log.appendFloat(m_entry, value, 0);
+  }
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/IntegerArrayLogEntry.java b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/IntegerArrayLogEntry.java
new file mode 100644
index 0000000..2cffc8d
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/IntegerArrayLogEntry.java
@@ -0,0 +1,45 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.util.datalog;
+
+/** Log array of integer values. */
+public class IntegerArrayLogEntry extends DataLogEntry {
+  public static final String kDataType = "int64[]";
+
+  public IntegerArrayLogEntry(DataLog log, String name, String metadata, long timestamp) {
+    super(log, name, kDataType, metadata, timestamp);
+  }
+
+  public IntegerArrayLogEntry(DataLog log, String name, String metadata) {
+    this(log, name, metadata, 0);
+  }
+
+  public IntegerArrayLogEntry(DataLog log, String name, long timestamp) {
+    this(log, name, "", timestamp);
+  }
+
+  public IntegerArrayLogEntry(DataLog log, String name) {
+    this(log, name, 0);
+  }
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param value Value to record
+   * @param timestamp Time stamp (0 to indicate now)
+   */
+  public void append(long[] value, long timestamp) {
+    m_log.appendIntegerArray(m_entry, value, timestamp);
+  }
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param value Value to record
+   */
+  public void append(long[] value) {
+    m_log.appendIntegerArray(m_entry, value, 0);
+  }
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/IntegerLogEntry.java b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/IntegerLogEntry.java
new file mode 100644
index 0000000..142ca5d
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/IntegerLogEntry.java
@@ -0,0 +1,45 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.util.datalog;
+
+/** Log integer values. */
+public class IntegerLogEntry extends DataLogEntry {
+  public static final String kDataType = "int64";
+
+  public IntegerLogEntry(DataLog log, String name, String metadata, long timestamp) {
+    super(log, name, kDataType, metadata, timestamp);
+  }
+
+  public IntegerLogEntry(DataLog log, String name, String metadata) {
+    this(log, name, metadata, 0);
+  }
+
+  public IntegerLogEntry(DataLog log, String name, long timestamp) {
+    this(log, name, "", timestamp);
+  }
+
+  public IntegerLogEntry(DataLog log, String name) {
+    this(log, name, 0);
+  }
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param value Value to record
+   * @param timestamp Time stamp (0 to indicate now)
+   */
+  public void append(long value, long timestamp) {
+    m_log.appendInteger(m_entry, value, timestamp);
+  }
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param value Value to record
+   */
+  public void append(long value) {
+    m_log.appendInteger(m_entry, value, 0);
+  }
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/RawLogEntry.java b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/RawLogEntry.java
new file mode 100644
index 0000000..160f734
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/RawLogEntry.java
@@ -0,0 +1,53 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.util.datalog;
+
+/** Log raw byte array values. */
+public class RawLogEntry extends DataLogEntry {
+  public static final String kDataType = "raw";
+
+  public RawLogEntry(DataLog log, String name, String metadata, String type, long timestamp) {
+    super(log, name, type, metadata, timestamp);
+  }
+
+  public RawLogEntry(DataLog log, String name, String metadata, String type) {
+    this(log, name, metadata, type, 0);
+  }
+
+  public RawLogEntry(DataLog log, String name, String metadata, long timestamp) {
+    this(log, name, metadata, kDataType, timestamp);
+  }
+
+  public RawLogEntry(DataLog log, String name, String metadata) {
+    this(log, name, metadata, 0);
+  }
+
+  public RawLogEntry(DataLog log, String name, long timestamp) {
+    this(log, name, "", timestamp);
+  }
+
+  public RawLogEntry(DataLog log, String name) {
+    this(log, name, 0);
+  }
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param value Value to record
+   * @param timestamp Time stamp (0 to indicate now)
+   */
+  public void append(byte[] value, long timestamp) {
+    m_log.appendRaw(m_entry, value, timestamp);
+  }
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param value Value to record
+   */
+  public void append(byte[] value) {
+    m_log.appendRaw(m_entry, value, 0);
+  }
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/StringArrayLogEntry.java b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/StringArrayLogEntry.java
new file mode 100644
index 0000000..37bdeb1
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/StringArrayLogEntry.java
@@ -0,0 +1,45 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.util.datalog;
+
+/** Log array of string values. */
+public class StringArrayLogEntry extends DataLogEntry {
+  public static final String kDataType = "string[]";
+
+  public StringArrayLogEntry(DataLog log, String name, String metadata, long timestamp) {
+    super(log, name, kDataType, metadata, timestamp);
+  }
+
+  public StringArrayLogEntry(DataLog log, String name, String metadata) {
+    this(log, name, metadata, 0);
+  }
+
+  public StringArrayLogEntry(DataLog log, String name, long timestamp) {
+    this(log, name, "", timestamp);
+  }
+
+  public StringArrayLogEntry(DataLog log, String name) {
+    this(log, name, 0);
+  }
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param value Value to record
+   * @param timestamp Time stamp (0 to indicate now)
+   */
+  public void append(String[] value, long timestamp) {
+    m_log.appendStringArray(m_entry, value, timestamp);
+  }
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param value Value to record
+   */
+  public void append(String[] value) {
+    m_log.appendStringArray(m_entry, value, 0);
+  }
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/StringLogEntry.java b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/StringLogEntry.java
new file mode 100644
index 0000000..0722dc0
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/datalog/StringLogEntry.java
@@ -0,0 +1,53 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.util.datalog;
+
+/** Log string values. */
+public class StringLogEntry extends DataLogEntry {
+  public static final String kDataType = "string";
+
+  public StringLogEntry(DataLog log, String name, String metadata, String type, long timestamp) {
+    super(log, name, type, metadata, timestamp);
+  }
+
+  public StringLogEntry(DataLog log, String name, String metadata, String type) {
+    this(log, name, metadata, type, 0);
+  }
+
+  public StringLogEntry(DataLog log, String name, String metadata, long timestamp) {
+    this(log, name, metadata, kDataType, timestamp);
+  }
+
+  public StringLogEntry(DataLog log, String name, String metadata) {
+    this(log, name, metadata, 0);
+  }
+
+  public StringLogEntry(DataLog log, String name, long timestamp) {
+    this(log, name, "", timestamp);
+  }
+
+  public StringLogEntry(DataLog log, String name) {
+    this(log, name, 0);
+  }
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param value Value to record
+   * @param timestamp Time stamp (0 to indicate now)
+   */
+  public void append(String value, long timestamp) {
+    m_log.appendString(m_entry, value, timestamp);
+  }
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param value Value to record
+   */
+  public void append(String value) {
+    m_log.appendString(m_entry, value, 0);
+  }
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/function/BooleanConsumer.java b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/function/BooleanConsumer.java
index 98fd6a2..5c357e8 100644
--- a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/function/BooleanConsumer.java
+++ b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/function/BooleanConsumer.java
@@ -7,7 +7,7 @@
 /**
  * Represents an operation that accepts a single boolean-valued argument and returns no result. This
  * is the primitive type specialization of {@link java.util.function.Consumer} for boolean. Unlike
- * most other functional interfaces, BooleanConsumer is expected to operate via side-effects.
+ * most other functional interfaces, BooleanConsumer is expected to operate via side effects.
  *
  * <p>This is a functional interface whose functional method is {@link #accept(boolean)}.
  */
diff --git a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/function/FloatConsumer.java b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/function/FloatConsumer.java
index 0fc7ff7..77970d8 100644
--- a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/function/FloatConsumer.java
+++ b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/function/FloatConsumer.java
@@ -7,7 +7,7 @@
 /**
  * Represents an operation that accepts a single float-valued argument and returns no result. This
  * is the primitive type specialization of {@link java.util.function.Consumer} for float. Unlike
- * most other functional interfaces, BooleanConsumer is expected to operate via side-effects.
+ * most other functional interfaces, BooleanConsumer is expected to operate via side effects.
  *
  * <p>This is a functional interface whose functional method is {@link #accept(float)}.
  */
diff --git a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/net/PortForwarder.java b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/net/PortForwarder.java
deleted file mode 100644
index 5c4c20a..0000000
--- a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/net/PortForwarder.java
+++ /dev/null
@@ -1,38 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.util.net;
-
-import edu.wpi.first.util.WPIUtilJNI;
-
-/**
- * Forward ports to another host. This is primarily useful for accessing Ethernet-connected devices
- * from a computer tethered to the RoboRIO USB port.
- */
-public final class PortForwarder {
-  private PortForwarder() {
-    throw new UnsupportedOperationException("This is a utility class!");
-  }
-
-  /**
-   * Forward a local TCP port to a remote host and port. Note that local ports less than 1024 won't
-   * work as a normal user.
-   *
-   * @param port local port number
-   * @param remoteHost remote IP address / DNS name
-   * @param remotePort remote port number
-   */
-  public static void add(int port, String remoteHost, int remotePort) {
-    WPIUtilJNI.addPortForwarder(port, remoteHost, remotePort);
-  }
-
-  /**
-   * Stop TCP forwarding on a port.
-   *
-   * @param port local port number
-   */
-  public static void remove(int port) {
-    WPIUtilJNI.removePortForwarder(port);
-  }
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/sendable/SendableBuilder.java b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/sendable/SendableBuilder.java
index 35d98fa..a58c3a3 100644
--- a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/sendable/SendableBuilder.java
+++ b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/sendable/SendableBuilder.java
@@ -5,13 +5,17 @@
 package edu.wpi.first.util.sendable;
 
 import edu.wpi.first.util.function.BooleanConsumer;
+import edu.wpi.first.util.function.FloatConsumer;
+import edu.wpi.first.util.function.FloatSupplier;
 import java.util.function.BooleanSupplier;
 import java.util.function.Consumer;
 import java.util.function.DoubleConsumer;
 import java.util.function.DoubleSupplier;
+import java.util.function.LongConsumer;
+import java.util.function.LongSupplier;
 import java.util.function.Supplier;
 
-public interface SendableBuilder {
+public interface SendableBuilder extends AutoCloseable {
   /** The backend kinds used for the sendable builder. */
   enum BackendKind {
     kUnknown,
@@ -27,7 +31,7 @@
   void setSmartDashboardType(String type);
 
   /**
-   * Set a flag indicating if this sendable should be treated as an actuator. By default this flag
+   * Set a flag indicating if this Sendable should be treated as an actuator. By default, this flag
    * is false.
    *
    * @param value true if actuator, false if not
@@ -52,6 +56,24 @@
   void addBooleanProperty(String key, BooleanSupplier getter, BooleanConsumer setter);
 
   /**
+   * Add an integer property.
+   *
+   * @param key property name
+   * @param getter getter function (returns current value)
+   * @param setter setter function (sets new value)
+   */
+  void addIntegerProperty(String key, LongSupplier getter, LongConsumer setter);
+
+  /**
+   * Add a float property.
+   *
+   * @param key property name
+   * @param getter getter function (returns current value)
+   * @param setter setter function (sets new value)
+   */
+  void addFloatProperty(String key, FloatSupplier getter, FloatConsumer setter);
+
+  /**
    * Add a double property.
    *
    * @param key property name
@@ -79,6 +101,24 @@
   void addBooleanArrayProperty(String key, Supplier<boolean[]> getter, Consumer<boolean[]> setter);
 
   /**
+   * Add an integer array property.
+   *
+   * @param key property name
+   * @param getter getter function (returns current value)
+   * @param setter setter function (sets new value)
+   */
+  void addIntegerArrayProperty(String key, Supplier<long[]> getter, Consumer<long[]> setter);
+
+  /**
+   * Add a float array property.
+   *
+   * @param key property name
+   * @param getter getter function (returns current value)
+   * @param setter setter function (sets new value)
+   */
+  void addFloatArrayProperty(String key, Supplier<float[]> getter, Consumer<float[]> setter);
+
+  /**
    * Add a double array property.
    *
    * @param key property name
@@ -100,10 +140,12 @@
    * Add a raw property.
    *
    * @param key property name
+   * @param typeString type string
    * @param getter getter function (returns current value)
    * @param setter setter function (sets new value)
    */
-  void addRawProperty(String key, Supplier<byte[]> getter, Consumer<byte[]> setter);
+  void addRawProperty(
+      String key, String typeString, Supplier<byte[]> getter, Consumer<byte[]> setter);
 
   /**
    * Gets the kind of backend being used.
@@ -124,4 +166,11 @@
 
   /** Clear properties. */
   void clearProperties();
+
+  /**
+   * Adds a closeable. The closeable.close() will be called when close() is called.
+   *
+   * @param closeable closeable object
+   */
+  void addCloseable(AutoCloseable closeable);
 }
diff --git a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/sendable/SendableRegistry.java b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/sendable/SendableRegistry.java
index 2a4c2c9..6f0ad41 100644
--- a/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/sendable/SendableRegistry.java
+++ b/third_party/allwpilib/wpiutil/src/main/java/edu/wpi/first/util/sendable/SendableRegistry.java
@@ -17,21 +17,32 @@
  * The SendableRegistry class is the public interface for registering sensors and actuators for use
  * on dashboards and LiveWindow.
  */
-public class SendableRegistry {
-  private static class Component {
+@SuppressWarnings("PMD.AvoidCatchingGenericException")
+public final class SendableRegistry {
+  private static class Component implements AutoCloseable {
     Component() {}
 
     Component(Sendable sendable) {
       m_sendable = new WeakReference<>(sendable);
     }
 
+    @Override
+    public void close() throws Exception {
+      m_builder.close();
+      for (AutoCloseable data : m_data) {
+        if (data != null) {
+          data.close();
+        }
+      }
+    }
+
     WeakReference<Sendable> m_sendable;
     SendableBuilder m_builder;
     String m_name;
     String m_subsystem = "Ungrouped";
     WeakReference<Sendable> m_parent;
     boolean m_liveWindow;
-    Object[] m_data;
+    AutoCloseable[] m_data;
 
     void setName(String moduleType, int channel) {
       m_name = moduleType + "[" + channel + "]";
@@ -131,6 +142,13 @@
   public static synchronized void addLW(Sendable sendable, String name) {
     Component comp = getOrAdd(sendable);
     if (liveWindowFactory != null) {
+      if (comp.m_builder != null) {
+        try {
+          comp.m_builder.close();
+        } catch (Exception e) {
+          // ignore
+        }
+      }
       comp.m_builder = liveWindowFactory.get();
     }
     comp.m_liveWindow = true;
@@ -147,6 +165,13 @@
   public static synchronized void addLW(Sendable sendable, String moduleType, int channel) {
     Component comp = getOrAdd(sendable);
     if (liveWindowFactory != null) {
+      if (comp.m_builder != null) {
+        try {
+          comp.m_builder.close();
+        } catch (Exception e) {
+          // ignore
+        }
+      }
       comp.m_builder = liveWindowFactory.get();
     }
     comp.m_liveWindow = true;
@@ -165,6 +190,13 @@
       Sendable sendable, String moduleType, int moduleNumber, int channel) {
     Component comp = getOrAdd(sendable);
     if (liveWindowFactory != null) {
+      if (comp.m_builder != null) {
+        try {
+          comp.m_builder.close();
+        } catch (Exception e) {
+          // ignore
+        }
+      }
       comp.m_builder = liveWindowFactory.get();
     }
     comp.m_liveWindow = true;
@@ -181,6 +213,13 @@
   public static synchronized void addLW(Sendable sendable, String subsystem, String name) {
     Component comp = getOrAdd(sendable);
     if (liveWindowFactory != null) {
+      if (comp.m_builder != null) {
+        try {
+          comp.m_builder.close();
+        } catch (Exception e) {
+          // ignore
+        }
+      }
       comp.m_builder = liveWindowFactory.get();
     }
     comp.m_liveWindow = true;
@@ -211,7 +250,15 @@
    * @return true if the object was removed; false if it was not present
    */
   public static synchronized boolean remove(Sendable sendable) {
-    return components.remove(sendable) != null;
+    Component comp = components.remove(sendable);
+    if (comp != null) {
+      try {
+        comp.close();
+      } catch (Exception e) {
+        // ignore
+      }
+    }
+    return comp != null;
   }
 
   /**
@@ -338,22 +385,33 @@
    * @param sendable object
    * @param handle data handle returned by getDataHandle()
    * @param data data to set
-   * @return Previous data (may be null)
+   * @return Previous data (may be null). If non-null, caller is responsible for calling close().
    */
-  public static synchronized Object setData(Sendable sendable, int handle, Object data) {
+  @SuppressWarnings("PMD.CompareObjectsWithEquals")
+  public static synchronized AutoCloseable setData(
+      Sendable sendable, int handle, AutoCloseable data) {
     Component comp = components.get(sendable);
     if (comp == null) {
       return null;
     }
-    Object rv = null;
+    AutoCloseable rv = null;
     if (comp.m_data == null) {
-      comp.m_data = new Object[handle + 1];
+      comp.m_data = new AutoCloseable[handle + 1];
     } else if (handle < comp.m_data.length) {
       rv = comp.m_data[handle];
     } else {
       comp.m_data = Arrays.copyOf(comp.m_data, handle + 1);
     }
-    comp.m_data[handle] = data;
+    if (comp.m_data[handle] != data) {
+      if (comp.m_data[handle] != null) {
+        try {
+          comp.m_data[handle].close();
+        } catch (Exception e) {
+          // ignore
+        }
+      }
+      comp.m_data[handle] = data;
+    }
     return rv;
   }
 
@@ -405,7 +463,11 @@
   public static synchronized void publish(Sendable sendable, SendableBuilder builder) {
     Component comp = getOrAdd(sendable);
     if (comp.m_builder != null) {
-      comp.m_builder.clearProperties();
+      try {
+        comp.m_builder.close();
+      } catch (Exception e) {
+        // ignore
+      }
     }
     comp.m_builder = builder; // clear any current builder
     sendable.initSendable(comp.m_builder);
@@ -425,29 +487,24 @@
   }
 
   /** Data passed to foreachLiveWindow() callback function. */
+  @SuppressWarnings("MemberName")
   public static class CallbackData {
     /** Sendable object. */
-    @SuppressWarnings("MemberName")
     public Sendable sendable;
 
     /** Name. */
-    @SuppressWarnings("MemberName")
     public String name;
 
     /** Subsystem. */
-    @SuppressWarnings("MemberName")
     public String subsystem;
 
     /** Parent sendable object. */
-    @SuppressWarnings("MemberName")
     public Sendable parent;
 
     /** Data stored in object with setData(). Update this to change the data. */
-    @SuppressWarnings("MemberName")
-    public Object data;
+    public AutoCloseable data;
 
     /** Sendable builder for the sendable. */
-    @SuppressWarnings("MemberName")
     public SendableBuilder builder;
   }
 
@@ -462,7 +519,7 @@
    * @param dataHandle data handle to get data object passed to callback
    * @param callback function to call for each object
    */
-  @SuppressWarnings({"PMD.AvoidCatchingThrowable", "PMD.AvoidReassigningCatchVariables"})
+  @SuppressWarnings("PMD.CompareObjectsWithEquals")
   public static synchronized void foreachLiveWindow(
       int dataHandle, Consumer<CallbackData> callback) {
     CallbackData cbdata = new CallbackData();
@@ -500,11 +557,20 @@
         }
         if (cbdata.data != null) {
           if (comp.m_data == null) {
-            comp.m_data = new Object[dataHandle + 1];
+            comp.m_data = new AutoCloseable[dataHandle + 1];
           } else if (dataHandle >= comp.m_data.length) {
             comp.m_data = Arrays.copyOf(comp.m_data, dataHandle + 1);
           }
-          comp.m_data[dataHandle] = cbdata.data;
+          if (comp.m_data[dataHandle] != cbdata.data) {
+            if (comp.m_data[dataHandle] != null) {
+              try {
+                comp.m_data[dataHandle].close();
+              } catch (Exception e) {
+                // ignore
+              }
+            }
+            comp.m_data[dataHandle] = cbdata.data;
+          }
         }
       }
     }
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/Base64.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/Base64.cpp
index 8f1f810..bc1d3ba 100644
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/Base64.cpp
+++ b/third_party/allwpilib/wpiutil/src/main/native/cpp/Base64.cpp
@@ -138,8 +138,8 @@
   return Base64Decode(os, encoded);
 }
 
-span<uint8_t> Base64Decode(std::string_view encoded, size_t* num_read,
-                           SmallVectorImpl<uint8_t>& buf) {
+std::span<uint8_t> Base64Decode(std::string_view encoded, size_t* num_read,
+                                SmallVectorImpl<uint8_t>& buf) {
   buf.clear();
   raw_usvector_ostream os(buf);
   *num_read = Base64Decode(os, encoded);
@@ -193,19 +193,19 @@
   return os.str();
 }
 
-void Base64Encode(raw_ostream& os, span<const uint8_t> plain) {
+void Base64Encode(raw_ostream& os, std::span<const uint8_t> plain) {
   Base64Encode(os, std::string_view{reinterpret_cast<const char*>(plain.data()),
                                     plain.size()});
 }
 
-void Base64Encode(span<const uint8_t> plain, std::string* encoded) {
+void Base64Encode(std::span<const uint8_t> plain, std::string* encoded) {
   encoded->resize(0);
   raw_string_ostream os(*encoded);
   Base64Encode(os, plain);
   os.flush();
 }
 
-std::string_view Base64Encode(span<const uint8_t> plain,
+std::string_view Base64Encode(std::span<const uint8_t> plain,
                               SmallVectorImpl<char>& buf) {
   buf.clear();
   raw_svector_ostream os(buf);
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/DataLog.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/DataLog.cpp
new file mode 100644
index 0000000..7009628
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/cpp/DataLog.cpp
@@ -0,0 +1,821 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpi/DataLog.h"
+
+#include "wpi/Synchronization.h"
+
+#ifndef _WIN32
+#include <unistd.h>
+#endif
+
+#ifdef _WIN32
+#ifndef WIN32_LEAN_AND_MEAN
+#define WIN32_LEAN_AND_MEAN
+#endif
+
+#include <windows.h>  // NOLINT(build/include_order)
+
+#endif
+
+#include <atomic>
+#include <cstdio>
+#include <cstdlib>
+#include <cstring>
+#include <random>
+#include <vector>
+
+#include "fmt/format.h"
+#include "wpi/Endian.h"
+#include "wpi/Logger.h"
+#include "wpi/MathExtras.h"
+#include "wpi/fs.h"
+#include "wpi/timestamp.h"
+
+using namespace wpi::log;
+
+static constexpr size_t kBlockSize = 16 * 1024;
+static constexpr size_t kRecordMaxHeaderSize = 17;
+
+template <typename T>
+static unsigned int WriteVarInt(uint8_t* buf, T val) {
+  unsigned int len = 0;
+  do {
+    *buf++ = static_cast<unsigned int>(val) & 0xff;
+    ++len;
+    val >>= 8;
+  } while (val != 0);
+  return len;
+}
+
+// min size: 4, max size: 17
+static unsigned int WriteRecordHeader(uint8_t* buf, uint32_t entry,
+                                      uint64_t timestamp,
+                                      uint32_t payloadSize) {
+  uint8_t* origbuf = buf++;
+
+  unsigned int entryLen = WriteVarInt(buf, entry);
+  buf += entryLen;
+  unsigned int payloadLen = WriteVarInt(buf, payloadSize);
+  buf += payloadLen;
+  unsigned int timestampLen =
+      WriteVarInt(buf, timestamp == 0 ? wpi::Now() : timestamp);
+  buf += timestampLen;
+  *origbuf =
+      ((timestampLen - 1) << 4) | ((payloadLen - 1) << 2) | (entryLen - 1);
+  return buf - origbuf;
+}
+
+class DataLog::Buffer {
+ public:
+  explicit Buffer(size_t alloc = kBlockSize)
+      : m_buf{new uint8_t[alloc]}, m_maxLen{alloc} {}
+  ~Buffer() { delete[] m_buf; }
+
+  Buffer(const Buffer&) = delete;
+  Buffer& operator=(const Buffer&) = delete;
+
+  Buffer(Buffer&& oth)
+      : m_buf{oth.m_buf}, m_len{oth.m_len}, m_maxLen{oth.m_maxLen} {
+    oth.m_buf = nullptr;
+    oth.m_len = 0;
+    oth.m_maxLen = 0;
+  }
+
+  Buffer& operator=(Buffer&& oth) {
+    if (m_buf) {
+      delete[] m_buf;
+    }
+    m_buf = oth.m_buf;
+    m_len = oth.m_len;
+    m_maxLen = oth.m_maxLen;
+    oth.m_buf = nullptr;
+    oth.m_len = 0;
+    oth.m_maxLen = 0;
+    return *this;
+  }
+
+  uint8_t* Reserve(size_t size) {
+    assert(size <= GetRemaining());
+    uint8_t* rv = m_buf + m_len;
+    m_len += size;
+    return rv;
+  }
+
+  void Unreserve(size_t size) { m_len -= size; }
+
+  void Clear() { m_len = 0; }
+
+  size_t GetRemaining() const { return m_maxLen - m_len; }
+
+  std::span<uint8_t> GetData() { return {m_buf, m_len}; }
+  std::span<const uint8_t> GetData() const { return {m_buf, m_len}; }
+
+ private:
+  uint8_t* m_buf;
+  size_t m_len = 0;
+  size_t m_maxLen;
+};
+
+static void DefaultLog(unsigned int level, const char* file, unsigned int line,
+                       const char* msg) {
+  if (level > wpi::WPI_LOG_INFO) {
+    fmt::print(stderr, "DataLog: {}\n", msg);
+  } else if (level == wpi::WPI_LOG_INFO) {
+    fmt::print("DataLog: {}\n", msg);
+  }
+}
+
+static wpi::Logger defaultMessageLog{DefaultLog};
+
+DataLog::DataLog(std::string_view dir, std::string_view filename, double period,
+                 std::string_view extraHeader)
+    : DataLog{defaultMessageLog, dir, filename, period, extraHeader} {}
+
+DataLog::DataLog(wpi::Logger& msglog, std::string_view dir,
+                 std::string_view filename, double period,
+                 std::string_view extraHeader)
+    : m_msglog{msglog},
+      m_period{period},
+      m_extraHeader{extraHeader},
+      m_newFilename{filename},
+      m_thread{[this, dir = std::string{dir}] { WriterThreadMain(dir); }} {}
+
+DataLog::DataLog(std::function<void(std::span<const uint8_t> data)> write,
+                 double period, std::string_view extraHeader)
+    : DataLog{defaultMessageLog, std::move(write), period, extraHeader} {}
+
+DataLog::DataLog(wpi::Logger& msglog,
+                 std::function<void(std::span<const uint8_t> data)> write,
+                 double period, std::string_view extraHeader)
+    : m_msglog{msglog},
+      m_period{period},
+      m_extraHeader{extraHeader},
+      m_thread{[this, write = std::move(write)] {
+        WriterThreadMain(std::move(write));
+      }} {}
+
+DataLog::~DataLog() {
+  {
+    std::scoped_lock lock{m_mutex};
+    m_active = false;
+    m_doFlush = true;
+  }
+  m_cond.notify_all();
+  m_thread.join();
+}
+
+void DataLog::SetFilename(std::string_view filename) {
+  {
+    std::scoped_lock lock{m_mutex};
+    m_newFilename = filename;
+  }
+  m_cond.notify_all();
+}
+
+void DataLog::Flush() {
+  {
+    std::scoped_lock lock{m_mutex};
+    m_doFlush = true;
+  }
+  m_cond.notify_all();
+}
+
+void DataLog::Pause() {
+  std::scoped_lock lock{m_mutex};
+  m_paused = true;
+}
+
+void DataLog::Resume() {
+  std::scoped_lock lock{m_mutex};
+  m_paused = false;
+}
+
+static void WriteToFile(fs::file_t f, std::span<const uint8_t> data,
+                        std::string_view filename, wpi::Logger& msglog) {
+  do {
+#ifdef _WIN32
+    DWORD ret;
+    if (!WriteFile(f, data.data(), data.size(), &ret, nullptr)) {
+      WPI_ERROR(msglog, "Error writing to log file '{}': {}", filename,
+                GetLastError());
+      break;
+    }
+#else
+    ssize_t ret = ::write(f, data.data(), data.size());
+    if (ret < 0) {
+      // If it's a recoverable error, swallow it and retry the write
+      if (errno == EINTR || errno == EAGAIN || errno == EWOULDBLOCK) {
+        continue;
+      }
+
+      // Otherwise it's a non-recoverable error; quit trying
+      WPI_ERROR(msglog, "Error writing to log file '{}': {}", filename,
+                std::strerror(errno));
+      break;
+    }
+#endif
+
+    // The write may have written some or all of the data
+    data = data.subspan(ret);
+  } while (data.size() > 0);
+}
+
+static std::string MakeRandomFilename() {
+  // build random filename
+  static std::random_device dev;
+  static std::mt19937 rng(dev());
+  std::uniform_int_distribution<int> dist(0, 15);
+  const char* v = "0123456789abcdef";
+  std::string filename = "wpilog_";
+  for (int i = 0; i < 16; i++) {
+    filename += v[dist(rng)];
+  }
+  filename += ".wpilog";
+  return filename;
+}
+
+void DataLog::WriterThreadMain(std::string_view dir) {
+  std::chrono::duration<double> periodTime{m_period};
+
+  std::error_code ec;
+  fs::path dirPath{dir};
+  std::string filename;
+
+  {
+    std::scoped_lock lock{m_mutex};
+    filename = std::move(m_newFilename);
+    m_newFilename.clear();
+  }
+
+  if (filename.empty()) {
+    filename = MakeRandomFilename();
+  }
+
+  // try preferred filename, or randomize it a few times, before giving up
+  fs::file_t f;
+  for (int i = 0; i < 5; ++i) {
+    // open file for append
+#ifdef _WIN32
+    // WIN32 doesn't allow combination of CreateNew and Append
+    f = fs::OpenFileForWrite(dirPath / filename, ec, fs::CD_CreateNew,
+                             fs::OF_None);
+#else
+    f = fs::OpenFileForWrite(dirPath / filename, ec, fs::CD_CreateNew,
+                             fs::OF_Append);
+#endif
+    if (ec) {
+      WPI_ERROR(m_msglog, "Could not open log file '{}': {}",
+                (dirPath / filename).string(), ec.message());
+      // try again with random filename
+      filename = MakeRandomFilename();
+    } else {
+      break;
+    }
+  }
+
+  if (f == fs::kInvalidFile) {
+    WPI_ERROR(m_msglog, "Could not open log file, no log being saved");
+  } else {
+    WPI_INFO(m_msglog, "Logging to '{}'", (dirPath / filename).string());
+  }
+
+  // write header (version 1.0)
+  if (f != fs::kInvalidFile) {
+    const uint8_t header[] = {'W', 'P', 'I', 'L', 'O', 'G', 0, 1};
+    WriteToFile(f, header, filename, m_msglog);
+    uint8_t extraLen[4];
+    support::endian::write32le(extraLen, m_extraHeader.size());
+    WriteToFile(f, extraLen, filename, m_msglog);
+    if (m_extraHeader.size() > 0) {
+      WriteToFile(f,
+                  {reinterpret_cast<const uint8_t*>(m_extraHeader.data()),
+                   m_extraHeader.size()},
+                  filename, m_msglog);
+    }
+  }
+
+  std::vector<Buffer> toWrite;
+
+  std::unique_lock lock{m_mutex};
+  while (m_active) {
+    bool doFlush = false;
+    auto timeoutTime = std::chrono::steady_clock::now() + periodTime;
+    if (m_cond.wait_until(lock, timeoutTime) == std::cv_status::timeout) {
+      doFlush = true;
+    }
+
+    if (!m_newFilename.empty()) {
+      auto newFilename = std::move(m_newFilename);
+      m_newFilename.clear();
+      lock.unlock();
+      // rename
+      if (filename != newFilename) {
+        fs::rename(dirPath / filename, dirPath / newFilename, ec);
+      }
+      if (ec) {
+        WPI_ERROR(m_msglog, "Could not rename log file from '{}' to '{}': {}",
+                  filename, newFilename, ec.message());
+      } else {
+        WPI_INFO(m_msglog, "Renamed log file from '{}' to '{}'", filename,
+                 newFilename);
+      }
+      filename = std::move(newFilename);
+      lock.lock();
+    }
+
+    if (doFlush || m_doFlush) {
+      // flush to file
+      m_doFlush = false;
+      if (m_outgoing.empty()) {
+        continue;
+      }
+      // swap outgoing with empty vector
+      toWrite.swap(m_outgoing);
+
+      if (f != fs::kInvalidFile) {
+        lock.unlock();
+        // write buffers to file
+        for (auto&& buf : toWrite) {
+          WriteToFile(f, buf.GetData(), filename, m_msglog);
+        }
+
+        // sync to storage
+#if defined(__linux__)
+        ::fdatasync(f);
+#elif defined(__APPLE__)
+        ::fsync(f);
+#endif
+        lock.lock();
+      }
+
+      // release buffers back to free list
+      for (auto&& buf : toWrite) {
+        buf.Clear();
+        m_free.emplace_back(std::move(buf));
+      }
+      toWrite.resize(0);
+    }
+  }
+
+  if (f != fs::kInvalidFile) {
+    fs::CloseFile(f);
+  }
+}
+
+void DataLog::WriterThreadMain(
+    std::function<void(std::span<const uint8_t> data)> write) {
+  std::chrono::duration<double> periodTime{m_period};
+
+  // write header (version 1.0)
+  {
+    const uint8_t header[] = {'W', 'P', 'I', 'L', 'O', 'G', 0, 1};
+    write(header);
+    uint8_t extraLen[4];
+    support::endian::write32le(extraLen, m_extraHeader.size());
+    write(extraLen);
+    if (m_extraHeader.size() > 0) {
+      write({reinterpret_cast<const uint8_t*>(m_extraHeader.data()),
+             m_extraHeader.size()});
+    }
+  }
+
+  std::vector<Buffer> toWrite;
+
+  std::unique_lock lock{m_mutex};
+  while (m_active) {
+    bool doFlush = false;
+    auto timeoutTime = std::chrono::steady_clock::now() + periodTime;
+    if (m_cond.wait_until(lock, timeoutTime) == std::cv_status::timeout) {
+      doFlush = true;
+    }
+
+    if (doFlush || m_doFlush) {
+      // flush to file
+      m_doFlush = false;
+      if (m_outgoing.empty()) {
+        continue;
+      }
+      // swap outgoing with empty vector
+      toWrite.swap(m_outgoing);
+
+      lock.unlock();
+      // write buffers
+      for (auto&& buf : toWrite) {
+        if (!buf.GetData().empty()) {
+          write(buf.GetData());
+        }
+      }
+      lock.lock();
+
+      // release buffers back to free list
+      for (auto&& buf : toWrite) {
+        buf.Clear();
+        m_free.emplace_back(std::move(buf));
+      }
+      toWrite.resize(0);
+    }
+  }
+
+  write({});  // indicate EOF
+}
+
+// Control records use the following format:
+// 1-byte type
+// 4-byte entry
+// rest of data (depending on type)
+
+int DataLog::Start(std::string_view name, std::string_view type,
+                   std::string_view metadata, int64_t timestamp) {
+  std::scoped_lock lock{m_mutex};
+  auto& entryInfo = m_entries[name];
+  if (entryInfo.id == 0) {
+    entryInfo.id = ++m_lastId;
+  }
+  auto& savedCount = m_entryCounts[entryInfo.id];
+  ++savedCount;
+  if (savedCount > 1) {
+    if (entryInfo.type != type) {
+      WPI_ERROR(m_msglog,
+                "type mismatch for '{}': was '{}', requested '{}'; ignoring",
+                name, entryInfo.type, type);
+      return 0;
+    }
+    return entryInfo.id;
+  }
+  entryInfo.type = type;
+  size_t strsize = name.size() + type.size() + metadata.size();
+  uint8_t* buf = StartRecord(0, timestamp, 5 + 12 + strsize, 5);
+  *buf++ = impl::kControlStart;
+  wpi::support::endian::write32le(buf, entryInfo.id);
+  AppendStringImpl(name);
+  AppendStringImpl(type);
+  AppendStringImpl(metadata);
+
+  return entryInfo.id;
+}
+
+void DataLog::Finish(int entry, int64_t timestamp) {
+  if (entry <= 0) {
+    return;
+  }
+  std::scoped_lock lock{m_mutex};
+  auto& savedCount = m_entryCounts[entry];
+  if (savedCount == 0) {
+    return;
+  }
+  --savedCount;
+  if (savedCount != 0) {
+    return;
+  }
+  m_entryCounts.erase(entry);
+  uint8_t* buf = StartRecord(0, timestamp, 5, 5);
+  *buf++ = impl::kControlFinish;
+  wpi::support::endian::write32le(buf, entry);
+}
+
+void DataLog::SetMetadata(int entry, std::string_view metadata,
+                          int64_t timestamp) {
+  if (entry <= 0) {
+    return;
+  }
+  std::scoped_lock lock{m_mutex};
+  uint8_t* buf = StartRecord(0, timestamp, 5 + 4 + metadata.size(), 5);
+  *buf++ = impl::kControlSetMetadata;
+  wpi::support::endian::write32le(buf, entry);
+  AppendStringImpl(metadata);
+}
+
+uint8_t* DataLog::Reserve(size_t size) {
+  assert(size <= kBlockSize);
+  if (m_outgoing.empty() || size > m_outgoing.back().GetRemaining()) {
+    if (m_free.empty()) {
+      m_outgoing.emplace_back();
+    } else {
+      m_outgoing.emplace_back(std::move(m_free.back()));
+      m_free.pop_back();
+    }
+  }
+  return m_outgoing.back().Reserve(size);
+}
+
+uint8_t* DataLog::StartRecord(uint32_t entry, uint64_t timestamp,
+                              uint32_t payloadSize, size_t reserveSize) {
+  uint8_t* buf = Reserve(kRecordMaxHeaderSize + reserveSize);
+  auto headerLen = WriteRecordHeader(buf, entry, timestamp, payloadSize);
+  m_outgoing.back().Unreserve(kRecordMaxHeaderSize - headerLen);
+  buf += headerLen;
+  return buf;
+}
+
+void DataLog::AppendImpl(std::span<const uint8_t> data) {
+  while (data.size() > kBlockSize) {
+    uint8_t* buf = Reserve(kBlockSize);
+    std::memcpy(buf, data.data(), kBlockSize);
+    data = data.subspan(kBlockSize);
+  }
+  uint8_t* buf = Reserve(data.size());
+  std::memcpy(buf, data.data(), data.size());
+}
+
+void DataLog::AppendStringImpl(std::string_view str) {
+  uint8_t* buf = Reserve(4);
+  wpi::support::endian::write32le(buf, str.size());
+  AppendImpl({reinterpret_cast<const uint8_t*>(str.data()), str.size()});
+}
+
+void DataLog::AppendRaw(int entry, std::span<const uint8_t> data,
+                        int64_t timestamp) {
+  if (entry <= 0) {
+    return;
+  }
+  std::scoped_lock lock{m_mutex};
+  if (m_paused) {
+    return;
+  }
+  StartRecord(entry, timestamp, data.size(), 0);
+  AppendImpl(data);
+}
+
+void DataLog::AppendRaw2(int entry,
+                         std::span<const std::span<const uint8_t>> data,
+                         int64_t timestamp) {
+  if (entry <= 0) {
+    return;
+  }
+  std::scoped_lock lock{m_mutex};
+  if (m_paused) {
+    return;
+  }
+  size_t size = 0;
+  for (auto&& chunk : data) {
+    size += chunk.size();
+  }
+  StartRecord(entry, timestamp, size, 0);
+  for (auto chunk : data) {
+    AppendImpl(chunk);
+  }
+}
+
+void DataLog::AppendBoolean(int entry, bool value, int64_t timestamp) {
+  if (entry <= 0) {
+    return;
+  }
+  std::scoped_lock lock{m_mutex};
+  if (m_paused) {
+    return;
+  }
+  uint8_t* buf = StartRecord(entry, timestamp, 1, 1);
+  buf[0] = value ? 1 : 0;
+}
+
+void DataLog::AppendInteger(int entry, int64_t value, int64_t timestamp) {
+  if (entry <= 0) {
+    return;
+  }
+  std::scoped_lock lock{m_mutex};
+  if (m_paused) {
+    return;
+  }
+  uint8_t* buf = StartRecord(entry, timestamp, 8, 8);
+  wpi::support::endian::write64le(buf, value);
+}
+
+void DataLog::AppendFloat(int entry, float value, int64_t timestamp) {
+  if (entry <= 0) {
+    return;
+  }
+  std::scoped_lock lock{m_mutex};
+  if (m_paused) {
+    return;
+  }
+  uint8_t* buf = StartRecord(entry, timestamp, 4, 4);
+  if constexpr (wpi::support::endian::system_endianness() ==
+                wpi::support::little) {
+    std::memcpy(buf, &value, 4);
+  } else {
+    wpi::support::endian::write32le(buf, wpi::FloatToBits(value));
+  }
+}
+
+void DataLog::AppendDouble(int entry, double value, int64_t timestamp) {
+  if (entry <= 0) {
+    return;
+  }
+  std::scoped_lock lock{m_mutex};
+  if (m_paused) {
+    return;
+  }
+  uint8_t* buf = StartRecord(entry, timestamp, 8, 8);
+  if constexpr (wpi::support::endian::system_endianness() ==
+                wpi::support::little) {
+    std::memcpy(buf, &value, 8);
+  } else {
+    wpi::support::endian::write64le(buf, wpi::DoubleToBits(value));
+  }
+}
+
+void DataLog::AppendString(int entry, std::string_view value,
+                           int64_t timestamp) {
+  AppendRaw(entry,
+            {reinterpret_cast<const uint8_t*>(value.data()), value.size()},
+            timestamp);
+}
+
+void DataLog::AppendBooleanArray(int entry, std::span<const bool> arr,
+                                 int64_t timestamp) {
+  if (entry <= 0) {
+    return;
+  }
+  std::scoped_lock lock{m_mutex};
+  if (m_paused) {
+    return;
+  }
+  StartRecord(entry, timestamp, arr.size(), 0);
+  uint8_t* buf;
+  while (arr.size() > kBlockSize) {
+    buf = Reserve(kBlockSize);
+    for (auto val : arr.subspan(0, kBlockSize)) {
+      *buf++ = val ? 1 : 0;
+    }
+    arr = arr.subspan(kBlockSize);
+  }
+  buf = Reserve(arr.size());
+  for (auto val : arr) {
+    *buf++ = val ? 1 : 0;
+  }
+}
+
+void DataLog::AppendBooleanArray(int entry, std::span<const int> arr,
+                                 int64_t timestamp) {
+  if (entry <= 0) {
+    return;
+  }
+  std::scoped_lock lock{m_mutex};
+  if (m_paused) {
+    return;
+  }
+  StartRecord(entry, timestamp, arr.size(), 0);
+  uint8_t* buf;
+  while (arr.size() > kBlockSize) {
+    buf = Reserve(kBlockSize);
+    for (auto val : arr.subspan(0, kBlockSize)) {
+      *buf++ = val & 1;
+    }
+    arr = arr.subspan(kBlockSize);
+  }
+  buf = Reserve(arr.size());
+  for (auto val : arr) {
+    *buf++ = val & 1;
+  }
+}
+
+void DataLog::AppendBooleanArray(int entry, std::span<const uint8_t> arr,
+                                 int64_t timestamp) {
+  AppendRaw(entry, arr, timestamp);
+}
+
+void DataLog::AppendIntegerArray(int entry, std::span<const int64_t> arr,
+                                 int64_t timestamp) {
+  if constexpr (wpi::support::endian::system_endianness() ==
+                wpi::support::little) {
+    AppendRaw(entry,
+              {reinterpret_cast<const uint8_t*>(arr.data()), arr.size() * 8},
+              timestamp);
+  } else {
+    if (entry <= 0) {
+      return;
+    }
+    std::scoped_lock lock{m_mutex};
+    if (m_paused) {
+      return;
+    }
+    StartRecord(entry, timestamp, arr.size() * 8, 0);
+    uint8_t* buf;
+    while ((arr.size() * 8) > kBlockSize) {
+      buf = Reserve(kBlockSize);
+      for (auto val : arr.subspan(0, kBlockSize / 8)) {
+        wpi::support::endian::write64le(buf, val);
+        buf += 8;
+      }
+      arr = arr.subspan(kBlockSize / 8);
+    }
+    buf = Reserve(arr.size() * 8);
+    for (auto val : arr) {
+      wpi::support::endian::write64le(buf, val);
+      buf += 8;
+    }
+  }
+}
+
+void DataLog::AppendFloatArray(int entry, std::span<const float> arr,
+                               int64_t timestamp) {
+  if constexpr (wpi::support::endian::system_endianness() ==
+                wpi::support::little) {
+    AppendRaw(entry,
+              {reinterpret_cast<const uint8_t*>(arr.data()), arr.size() * 4},
+              timestamp);
+  } else {
+    if (entry <= 0) {
+      return;
+    }
+    std::scoped_lock lock{m_mutex};
+    if (m_paused) {
+      return;
+    }
+    StartRecord(entry, timestamp, arr.size() * 4, 0);
+    uint8_t* buf;
+    while ((arr.size() * 4) > kBlockSize) {
+      buf = Reserve(kBlockSize);
+      for (auto val : arr.subspan(0, kBlockSize / 4)) {
+        wpi::support::endian::write32le(buf, wpi::FloatToBits(val));
+        buf += 4;
+      }
+      arr = arr.subspan(kBlockSize / 4);
+    }
+    buf = Reserve(arr.size() * 4);
+    for (auto val : arr) {
+      wpi::support::endian::write32le(buf, wpi::FloatToBits(val));
+      buf += 4;
+    }
+  }
+}
+
+void DataLog::AppendDoubleArray(int entry, std::span<const double> arr,
+                                int64_t timestamp) {
+  if constexpr (wpi::support::endian::system_endianness() ==
+                wpi::support::little) {
+    AppendRaw(entry,
+              {reinterpret_cast<const uint8_t*>(arr.data()), arr.size() * 8},
+              timestamp);
+  } else {
+    if (entry <= 0) {
+      return;
+    }
+    std::scoped_lock lock{m_mutex};
+    if (m_paused) {
+      return;
+    }
+    StartRecord(entry, timestamp, arr.size() * 8, 0);
+    uint8_t* buf;
+    while ((arr.size() * 8) > kBlockSize) {
+      buf = Reserve(kBlockSize);
+      for (auto val : arr.subspan(0, kBlockSize / 8)) {
+        wpi::support::endian::write64le(buf, wpi::DoubleToBits(val));
+        buf += 8;
+      }
+      arr = arr.subspan(kBlockSize / 8);
+    }
+    buf = Reserve(arr.size() * 8);
+    for (auto val : arr) {
+      wpi::support::endian::write64le(buf, wpi::DoubleToBits(val));
+      buf += 8;
+    }
+  }
+}
+
+void DataLog::AppendStringArray(int entry, std::span<const std::string> arr,
+                                int64_t timestamp) {
+  if (entry <= 0) {
+    return;
+  }
+  // storage: 4-byte array length, each string prefixed by 4-byte length
+  // calculate total size
+  size_t size = 4;
+  for (auto&& str : arr) {
+    size += 4 + str.size();
+  }
+  std::scoped_lock lock{m_mutex};
+  if (m_paused) {
+    return;
+  }
+  uint8_t* buf = StartRecord(entry, timestamp, size, 4);
+  wpi::support::endian::write32le(buf, arr.size());
+  for (auto&& str : arr) {
+    AppendStringImpl(str);
+  }
+}
+
+void DataLog::AppendStringArray(int entry,
+                                std::span<const std::string_view> arr,
+                                int64_t timestamp) {
+  if (entry <= 0) {
+    return;
+  }
+  // storage: 4-byte array length, each string prefixed by 4-byte length
+  // calculate total size
+  size_t size = 4;
+  for (auto&& str : arr) {
+    size += 4 + str.size();
+  }
+  std::scoped_lock lock{m_mutex};
+  if (m_paused) {
+    return;
+  }
+  uint8_t* buf = StartRecord(entry, timestamp, size, 4);
+  wpi::support::endian::write32le(buf, arr.size());
+  for (auto sv : arr) {
+    AppendStringImpl(sv);
+  }
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/DataLogReader.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/DataLogReader.cpp
new file mode 100644
index 0000000..96f6689
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/cpp/DataLogReader.cpp
@@ -0,0 +1,307 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpi/DataLogReader.h"
+
+#include "wpi/DataLog.h"
+#include "wpi/Endian.h"
+#include "wpi/MathExtras.h"
+
+using namespace wpi::log;
+
+static bool ReadString(std::span<const uint8_t>* buf, std::string_view* str) {
+  if (buf->size() < 4) {
+    *str = {};
+    return false;
+  }
+  uint32_t len = wpi::support::endian::read32le(buf->data());
+  if (len > (buf->size() - 4)) {
+    *str = {};
+    return false;
+  }
+  *str = {reinterpret_cast<const char*>(buf->data() + 4), len};
+  *buf = buf->subspan(len + 4);
+  return true;
+}
+
+bool DataLogRecord::IsStart() const {
+  return m_entry == 0 && m_data.size() >= 17 &&
+         m_data[0] == impl::kControlStart;
+}
+
+bool DataLogRecord::IsFinish() const {
+  return m_entry == 0 && m_data.size() == 5 &&
+         m_data[0] == impl::kControlFinish;
+}
+
+bool DataLogRecord::IsSetMetadata() const {
+  return m_entry == 0 && m_data.size() >= 9 &&
+         m_data[0] == impl::kControlSetMetadata;
+}
+
+bool DataLogRecord::GetStartData(StartRecordData* out) const {
+  if (!IsStart()) {
+    return false;
+  }
+  out->entry = wpi::support::endian::read32le(&m_data[1]);
+  auto buf = m_data.subspan(5);
+  if (!ReadString(&buf, &out->name)) {
+    return false;
+  }
+  if (!ReadString(&buf, &out->type)) {
+    return false;
+  }
+  if (!ReadString(&buf, &out->metadata)) {
+    return false;
+  }
+  return true;
+}
+
+bool DataLogRecord::GetFinishEntry(int* out) const {
+  if (!IsFinish()) {
+    return false;
+  }
+  *out = wpi::support::endian::read32le(&m_data[1]);
+  return true;
+}
+
+bool DataLogRecord::GetSetMetadataData(MetadataRecordData* out) const {
+  if (!IsSetMetadata()) {
+    return false;
+  }
+  out->entry = wpi::support::endian::read32le(&m_data[1]);
+  auto buf = m_data.subspan(5);
+  return ReadString(&buf, &out->metadata);
+}
+
+bool DataLogRecord::GetBoolean(bool* value) const {
+  if (m_data.size() != 1) {
+    return false;
+  }
+  *value = m_data[0] != 0;
+  return true;
+}
+
+bool DataLogRecord::GetInteger(int64_t* value) const {
+  if (m_data.size() != 8) {
+    return false;
+  }
+  *value = wpi::support::endian::read64le(m_data.data());
+  return true;
+}
+
+bool DataLogRecord::GetFloat(float* value) const {
+  if (m_data.size() != 4) {
+    return false;
+  }
+  *value = wpi::BitsToFloat(wpi::support::endian::read32le(m_data.data()));
+  return true;
+}
+
+bool DataLogRecord::GetDouble(double* value) const {
+  if (m_data.size() != 8) {
+    return false;
+  }
+  *value = wpi::BitsToDouble(wpi::support::endian::read64le(m_data.data()));
+  return true;
+}
+
+bool DataLogRecord::GetString(std::string_view* value) const {
+  *value = {reinterpret_cast<const char*>(m_data.data()), m_data.size()};
+  return true;
+}
+
+bool DataLogRecord::GetBooleanArray(std::vector<int>* arr) const {
+  arr->clear();
+  arr->reserve(m_data.size());
+  for (auto v : m_data) {
+    arr->push_back(v);
+  }
+  return true;
+}
+
+bool DataLogRecord::GetIntegerArray(std::vector<int64_t>* arr) const {
+  arr->clear();
+  if ((m_data.size() % 8) != 0) {
+    return false;
+  }
+  arr->reserve(m_data.size() / 8);
+  for (size_t pos = 0; pos < m_data.size(); pos += 8) {
+    arr->push_back(wpi::support::endian::read64le(&m_data[pos]));
+  }
+  return true;
+}
+
+bool DataLogRecord::GetFloatArray(std::vector<float>* arr) const {
+  arr->clear();
+  if ((m_data.size() % 4) != 0) {
+    return false;
+  }
+  arr->reserve(m_data.size() / 4);
+  for (size_t pos = 0; pos < m_data.size(); pos += 4) {
+    arr->push_back(
+        wpi::BitsToFloat(wpi::support::endian::read32le(&m_data[pos])));
+  }
+  return true;
+}
+
+bool DataLogRecord::GetDoubleArray(std::vector<double>* arr) const {
+  arr->clear();
+  if ((m_data.size() % 8) != 0) {
+    return false;
+  }
+  arr->reserve(m_data.size() / 8);
+  for (size_t pos = 0; pos < m_data.size(); pos += 8) {
+    arr->push_back(
+        wpi::BitsToDouble(wpi::support::endian::read64le(&m_data[pos])));
+  }
+  return true;
+}
+
+bool DataLogRecord::GetStringArray(std::vector<std::string_view>* arr) const {
+  arr->clear();
+  if (m_data.size() < 4) {
+    return false;
+  }
+  uint32_t size = wpi::support::endian::read32le(m_data.data());
+  // sanity check size
+  if (size > ((m_data.size() - 4) / 4)) {
+    return false;
+  }
+  auto buf = m_data.subspan(4);
+  arr->reserve(size);
+  for (uint32_t i = 0; i < size; ++i) {
+    std::string_view str;
+    if (!ReadString(&buf, &str)) {
+      arr->clear();
+      return false;
+    }
+    arr->push_back(str);
+  }
+  // any left over?  treat as corrupt
+  if (!buf.empty()) {
+    arr->clear();
+    return false;
+  }
+  return true;
+}
+
+DataLogReader::DataLogReader(std::unique_ptr<MemoryBuffer> buffer)
+    : m_buf{std::move(buffer)} {}
+
+bool DataLogReader::IsValid() const {
+  if (!m_buf) {
+    return false;
+  }
+  auto buf = m_buf->GetBuffer();
+  return buf.size() >= 12 &&
+         std::string_view{reinterpret_cast<const char*>(buf.data()), 6} ==
+             "WPILOG" &&
+         wpi::support::endian::read16le(&buf[6]) >= 0x0100;
+}
+
+uint16_t DataLogReader::GetVersion() const {
+  if (!m_buf) {
+    return 0;
+  }
+  auto buf = m_buf->GetBuffer();
+  if (buf.size() < 12) {
+    return 0;
+  }
+  return wpi::support::endian::read16le(&buf[6]);
+}
+
+std::string_view DataLogReader::GetExtraHeader() const {
+  if (!m_buf) {
+    return {};
+  }
+  auto buf = m_buf->GetBuffer();
+  if (buf.size() < 8) {
+    return {};
+  }
+  std::string_view rv;
+  buf = buf.subspan(8);
+  ReadString(&buf, &rv);
+  return rv;
+}
+
+DataLogReader::iterator DataLogReader::begin() const {
+  if (!m_buf) {
+    return end();
+  }
+  auto buf = m_buf->GetBuffer();
+  if (buf.size() < 12) {
+    return end();
+  }
+  uint32_t size = wpi::support::endian::read32le(&buf[8]);
+  if (buf.size() < (12 + size)) {
+    return end();
+  }
+  return DataLogIterator{this, 12 + size};
+}
+
+static uint64_t ReadVarInt(std::span<const uint8_t> buf) {
+  uint64_t val = 0;
+  int shift = 0;
+  for (auto v : buf) {
+    val |= static_cast<uint64_t>(v) << shift;
+    shift += 8;
+  }
+  return val;
+}
+
+bool DataLogReader::GetRecord(size_t* pos, DataLogRecord* out) const {
+  if (!m_buf) {
+    return false;
+  }
+  auto buf = m_buf->GetBuffer();
+  if (*pos >= buf.size()) {
+    return false;
+  }
+  buf = buf.subspan(*pos);
+  if (buf.size() < 4) {  // minimum header length
+    return false;
+  }
+  unsigned int entryLen = (buf[0] & 0x3) + 1;
+  unsigned int sizeLen = ((buf[0] >> 2) & 0x3) + 1;
+  unsigned int timestampLen = ((buf[0] >> 4) & 0x7) + 1;
+  unsigned int headerLen = 1 + entryLen + sizeLen + timestampLen;
+  if (buf.size() < headerLen) {
+    return false;
+  }
+  int entry = ReadVarInt(buf.subspan(1, entryLen));
+  uint32_t size = ReadVarInt(buf.subspan(1 + entryLen, sizeLen));
+  if (size > (buf.size() - headerLen)) {
+    return false;
+  }
+  int64_t timestamp =
+      ReadVarInt(buf.subspan(1 + entryLen + sizeLen, timestampLen));
+  *out = DataLogRecord{entry, timestamp, buf.subspan(headerLen, size)};
+  *pos += headerLen + size;
+  return true;
+}
+
+bool DataLogReader::GetNextRecord(size_t* pos) const {
+  if (!m_buf) {
+    return false;
+  }
+  auto buf = m_buf->GetBuffer();
+  if (buf.size() < (*pos + 4)) {  // minimum header length
+    return false;
+  }
+  unsigned int entryLen = (buf[*pos] & 0x3) + 1;
+  unsigned int sizeLen = ((buf[*pos] >> 2) & 0x3) + 1;
+  unsigned int timestampLen = ((buf[*pos] >> 4) & 0x7) + 1;
+  unsigned int headerLen = 1 + entryLen + sizeLen + timestampLen;
+  if (buf.size() < (*pos + headerLen)) {
+    return false;
+  }
+  uint32_t size = ReadVarInt(buf.subspan(*pos + 1 + entryLen, sizeLen));
+  // check this way to avoid overflow
+  if (size >= (buf.size() - *pos - headerLen)) {
+    return false;
+  }
+  *pos += headerLen + size;
+  return true;
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/DsClient.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/DsClient.cpp
deleted file mode 100644
index 455f10c..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/DsClient.cpp
+++ /dev/null
@@ -1,107 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/DsClient.h"
-
-#include <fmt/format.h>
-#include <wpi/StringExtras.h>
-#include <wpi/json.h>
-#include <wpi/uv/Tcp.h>
-#include <wpi/uv/Timer.h>
-
-#include "wpi/Logger.h"
-
-using namespace wpi;
-
-static constexpr uv::Timer::Time kReconnectTime{500};
-
-DsClient::DsClient(wpi::uv::Loop& loop, wpi::Logger& logger,
-                   const private_init&)
-    : m_logger{logger},
-      m_tcp{uv::Tcp::Create(loop)},
-      m_timer{uv::Timer::Create(loop)} {
-  m_tcp->end.connect([this] {
-    WPI_DEBUG4(m_logger, "{}", "DS connection closed");
-    clearIp();
-    // try to connect again
-    m_tcp->Reuse([this] { m_timer->Start(kReconnectTime); });
-  });
-  m_tcp->data.connect([this](wpi::uv::Buffer buf, size_t len) {
-    HandleIncoming({buf.base, len});
-  });
-  m_timer->timeout.connect([this] { Connect(); });
-  Connect();
-}
-
-DsClient::~DsClient() = default;
-
-void DsClient::Close() {
-  m_tcp->Close();
-  m_timer->Close();
-  clearIp();
-}
-
-void DsClient::Connect() {
-  auto connreq = std::make_shared<uv::TcpConnectReq>();
-  connreq->connected.connect([this] {
-    m_json.clear();
-    m_tcp->StopRead();
-    m_tcp->StartRead();
-  });
-
-  connreq->error = [this](uv::Error err) {
-    WPI_DEBUG4(m_logger, "DS connect failure: {}", err.str());
-    // try to connect again
-    m_tcp->Reuse([this] { m_timer->Start(kReconnectTime); });
-  };
-
-  WPI_DEBUG4(m_logger, "{}", "Starting DS connection attempt");
-  m_tcp->Connect("127.0.0.1", 1742, connreq);
-}
-
-void DsClient::HandleIncoming(std::string_view in) {
-  // this is very bare-bones, as there are never nested {} in these messages
-  while (!in.empty()) {
-    // if json is empty, look for the first { (and discard)
-    if (m_json.empty()) {
-      auto start = in.find('{');
-      in = wpi::slice(in, start, std::string_view::npos);
-    }
-
-    // look for the terminating } (and save)
-    auto end = in.find('}');
-    if (end == std::string_view::npos) {
-      m_json.append(in);
-      return;  // nothing left to read
-    }
-
-    // have complete json message
-    ++end;
-    m_json.append(wpi::slice(in, 0, end));
-    in = wpi::slice(in, end, std::string_view::npos);
-    ParseJson();
-    m_json.clear();
-  }
-}
-
-void DsClient::ParseJson() {
-  WPI_DEBUG4(m_logger, "DsClient JSON: {}", m_json);
-  unsigned int ip = 0;
-  try {
-    ip = wpi::json::parse(m_json).at("robotIP").get<unsigned int>();
-  } catch (wpi::json::exception& e) {
-    WPI_INFO(m_logger, "DsClient JSON error: {}", e.what());
-    return;
-  }
-
-  if (ip == 0) {
-    clearIp();
-  } else {
-    // Convert number into dotted quad
-    auto newip = fmt::format("{}.{}.{}.{}", (ip >> 24) & 0xff,
-                             (ip >> 16) & 0xff, (ip >> 8) & 0xff, ip & 0xff);
-    WPI_INFO(m_logger, "DS received server IP: {}", newip);
-    setIp(newip);
-  }
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/EventLoopRunner.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/EventLoopRunner.cpp
deleted file mode 100644
index c86176e..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/EventLoopRunner.cpp
+++ /dev/null
@@ -1,90 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/EventLoopRunner.h"
-
-#include "wpi/SmallVector.h"
-#include "wpi/condition_variable.h"
-#include "wpi/mutex.h"
-#include "wpi/uv/AsyncFunction.h"
-#include "wpi/uv/Loop.h"
-
-using namespace wpi;
-
-class EventLoopRunner::Thread : public SafeThread {
- public:
-  using UvExecFunc = uv::AsyncFunction<void(LoopFunc)>;
-
-  Thread() : m_loop(uv::Loop::Create()) {
-    // set up async handles
-    if (!m_loop) {
-      return;
-    }
-
-    // run function
-    m_doExec = UvExecFunc::Create(
-        m_loop, [loop = m_loop.get()](auto out, LoopFunc func) {
-          func(*loop);
-          out.set_value();
-        });
-  }
-
-  void Main() override {
-    if (m_loop) {
-      m_loop->Run();
-    }
-  }
-
-  // the loop
-  std::shared_ptr<uv::Loop> m_loop;
-
-  // run function
-  std::weak_ptr<UvExecFunc> m_doExec;
-};
-
-EventLoopRunner::EventLoopRunner() {
-  m_owner.Start();
-}
-
-EventLoopRunner::~EventLoopRunner() {
-  Stop();
-}
-
-void EventLoopRunner::Stop() {
-  ExecAsync([](uv::Loop& loop) {
-    // close all handles; this will (eventually) stop the loop
-    loop.Walk([](uv::Handle& h) {
-      h.SetLoopClosing(true);
-      h.Close();
-    });
-  });
-  m_owner.Join();
-}
-
-void EventLoopRunner::ExecAsync(LoopFunc func) {
-  if (auto thr = m_owner.GetThread()) {
-    if (auto doExec = thr->m_doExec.lock()) {
-      doExec->Call(std::move(func));
-    }
-  }
-}
-
-void EventLoopRunner::ExecSync(LoopFunc func) {
-  wpi::future<void> f;
-  if (auto thr = m_owner.GetThread()) {
-    if (auto doExec = thr->m_doExec.lock()) {
-      f = doExec->Call(std::move(func));
-    }
-  }
-  if (f.valid()) {
-    f.wait();
-  }
-}
-
-std::shared_ptr<uv::Loop> EventLoopRunner::GetLoop() {
-  if (auto thr = m_owner.GetThread()) {
-    return thr->m_loop;
-  }
-  return nullptr;
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/HttpParser.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/HttpParser.cpp
deleted file mode 100644
index 3c18e0f..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/HttpParser.cpp
+++ /dev/null
@@ -1,193 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/HttpParser.h"
-
-using namespace wpi;
-
-uint32_t HttpParser::GetParserVersion() {
-  return static_cast<uint32_t>(http_parser_version());
-}
-
-HttpParser::HttpParser(Type type) {
-  http_parser_init(&m_parser,
-                   static_cast<http_parser_type>(static_cast<int>(type)));
-  m_parser.data = this;
-
-  http_parser_settings_init(&m_settings);
-
-  // Unlike the underlying http_parser library, we don't perform callbacks
-  // (other than body) with partial data; instead we buffer and call the user
-  // callback only when the data is complete.
-
-  // on_message_begin: initialize our state, call user callback
-  m_settings.on_message_begin = [](http_parser* p) -> int {
-    auto& self = *static_cast<HttpParser*>(p->data);
-    self.m_urlBuf.clear();
-    self.m_state = kStart;
-    self.messageBegin();
-    return self.m_aborted;
-  };
-
-  // on_url: collect into buffer
-  m_settings.on_url = [](http_parser* p, const char* at, size_t length) -> int {
-    auto& self = *static_cast<HttpParser*>(p->data);
-    // append to buffer
-    if ((self.m_urlBuf.size() + length) > self.m_maxLength) {
-      return 1;
-    }
-    self.m_urlBuf += std::string_view{at, length};
-    self.m_state = kUrl;
-    return 0;
-  };
-
-  // on_status: collect into buffer, call user URL callback
-  m_settings.on_status = [](http_parser* p, const char* at,
-                            size_t length) -> int {
-    auto& self = *static_cast<HttpParser*>(p->data);
-    // use valueBuf for the status
-    if ((self.m_valueBuf.size() + length) > self.m_maxLength) {
-      return 1;
-    }
-    self.m_valueBuf += std::string_view{at, length};
-    self.m_state = kStatus;
-    return 0;
-  };
-
-  // on_header_field: collect into buffer, call user header/status callback
-  m_settings.on_header_field = [](http_parser* p, const char* at,
-                                  size_t length) -> int {
-    auto& self = *static_cast<HttpParser*>(p->data);
-
-    // once we're in header, we know the URL is complete
-    if (self.m_state == kUrl) {
-      self.url(self.m_urlBuf);
-      if (self.m_aborted) {
-        return 1;
-      }
-    }
-
-    // once we're in header, we know the status is complete
-    if (self.m_state == kStatus) {
-      self.status(self.m_valueBuf);
-      if (self.m_aborted) {
-        return 1;
-      }
-    }
-
-    // if we previously were in value state, that means we finished a header
-    if (self.m_state == kValue) {
-      self.header(self.m_fieldBuf, self.m_valueBuf);
-      if (self.m_aborted) {
-        return 1;
-      }
-    }
-
-    // clear field and value when we enter this state
-    if (self.m_state != kField) {
-      self.m_state = kField;
-      self.m_fieldBuf.clear();
-      self.m_valueBuf.clear();
-    }
-
-    // append data to field buffer
-    if ((self.m_fieldBuf.size() + length) > self.m_maxLength) {
-      return 1;
-    }
-    self.m_fieldBuf += std::string_view{at, length};
-    return 0;
-  };
-
-  // on_header_field: collect into buffer
-  m_settings.on_header_value = [](http_parser* p, const char* at,
-                                  size_t length) -> int {
-    auto& self = *static_cast<HttpParser*>(p->data);
-
-    // if we weren't previously in value state, clear the buffer
-    if (self.m_state != kValue) {
-      self.m_state = kValue;
-      self.m_valueBuf.clear();
-    }
-
-    // append data to value buffer
-    if ((self.m_valueBuf.size() + length) > self.m_maxLength) {
-      return 1;
-    }
-    self.m_valueBuf += std::string_view{at, length};
-    return 0;
-  };
-
-  // on_headers_complete: call user status/header/complete callback
-  m_settings.on_headers_complete = [](http_parser* p) -> int {
-    auto& self = *static_cast<HttpParser*>(p->data);
-
-    // if we previously were in url state, that means we finished the url
-    if (self.m_state == kUrl) {
-      self.url(self.m_urlBuf);
-      if (self.m_aborted) {
-        return 1;
-      }
-    }
-
-    // if we previously were in status state, that means we finished the status
-    if (self.m_state == kStatus) {
-      self.status(self.m_valueBuf);
-      if (self.m_aborted) {
-        return 1;
-      }
-    }
-
-    // if we previously were in value state, that means we finished a header
-    if (self.m_state == kValue) {
-      self.header(self.m_fieldBuf, self.m_valueBuf);
-      if (self.m_aborted) {
-        return 1;
-      }
-    }
-
-    self.headersComplete(self.ShouldKeepAlive());
-    return self.m_aborted;
-  };
-
-  // on_body: call user callback
-  m_settings.on_body = [](http_parser* p, const char* at,
-                          size_t length) -> int {
-    auto& self = *static_cast<HttpParser*>(p->data);
-    self.body(std::string_view{at, length}, self.IsBodyFinal());
-    return self.m_aborted;
-  };
-
-  // on_message_complete: call user callback
-  m_settings.on_message_complete = [](http_parser* p) -> int {
-    auto& self = *static_cast<HttpParser*>(p->data);
-    self.messageComplete(self.ShouldKeepAlive());
-    return self.m_aborted;
-  };
-
-  // on_chunk_header: call user callback
-  m_settings.on_chunk_header = [](http_parser* p) -> int {
-    auto& self = *static_cast<HttpParser*>(p->data);
-    self.chunkHeader(p->content_length);
-    return self.m_aborted;
-  };
-
-  // on_chunk_complete: call user callback
-  m_settings.on_chunk_complete = [](http_parser* p) -> int {
-    auto& self = *static_cast<HttpParser*>(p->data);
-    self.chunkComplete();
-    return self.m_aborted;
-  };
-}
-
-void HttpParser::Reset(Type type) {
-  http_parser_init(&m_parser,
-                   static_cast<http_parser_type>(static_cast<int>(type)));
-  m_parser.data = this;
-  m_maxLength = 1024;
-  m_state = kStart;
-  m_urlBuf.clear();
-  m_fieldBuf.clear();
-  m_valueBuf.clear();
-  m_aborted = false;
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/HttpServerConnection.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/HttpServerConnection.cpp
deleted file mode 100644
index 716d2af..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/HttpServerConnection.cpp
+++ /dev/null
@@ -1,178 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/HttpServerConnection.h"
-
-#include "fmt/format.h"
-#include "wpi/SmallString.h"
-#include "wpi/SmallVector.h"
-#include "wpi/SpanExtras.h"
-#include "wpi/StringExtras.h"
-#include "wpi/fmt/raw_ostream.h"
-#include "wpi/raw_uv_ostream.h"
-
-using namespace wpi;
-
-HttpServerConnection::HttpServerConnection(std::shared_ptr<uv::Stream> stream)
-    : m_stream(*stream) {
-  // process HTTP messages
-  m_messageCompleteConn =
-      m_request.messageComplete.connect_connection([this](bool keepAlive) {
-        m_keepAlive = keepAlive;
-        ProcessRequest();
-      });
-
-  // look for Accept-Encoding headers to determine if gzip is acceptable
-  m_request.messageBegin.connect([this] { m_acceptGzip = false; });
-  m_request.header.connect(
-      [this](std::string_view name, std::string_view value) {
-        if (wpi::equals_lower(name, "accept-encoding") &&
-            wpi::contains(value, "gzip")) {
-          m_acceptGzip = true;
-        }
-      });
-
-  // pass incoming data to HTTP parser
-  m_dataConn =
-      stream->data.connect_connection([this](uv::Buffer& buf, size_t size) {
-        m_request.Execute({buf.base, size});
-        if (m_request.HasError()) {
-          // could not parse; just close the connection
-          m_stream.Close();
-        }
-      });
-
-  // close when remote side closes
-  m_endConn =
-      stream->end.connect_connection([h = stream.get()] { h->Close(); });
-
-  // start reading
-  stream->StartRead();
-}
-
-void HttpServerConnection::BuildCommonHeaders(raw_ostream& os) {
-  os << "Server: WebServer/1.0\r\n"
-        "Cache-Control: no-store, no-cache, must-revalidate, pre-check=0, "
-        "post-check=0, max-age=0\r\n"
-        "Pragma: no-cache\r\n"
-        "Expires: Mon, 3 Jan 2000 12:34:56 GMT\r\n";
-}
-
-void HttpServerConnection::BuildHeader(raw_ostream& os, int code,
-                                       std::string_view codeText,
-                                       std::string_view contentType,
-                                       uint64_t contentLength,
-                                       std::string_view extra) {
-  fmt::print(os, "HTTP/{}.{} {} {}\r\n", m_request.GetMajor(),
-             m_request.GetMinor(), code, codeText);
-  if (contentLength == 0) {
-    m_keepAlive = false;
-  }
-  if (!m_keepAlive) {
-    os << "Connection: close\r\n";
-  }
-  BuildCommonHeaders(os);
-  os << "Content-Type: " << contentType << "\r\n";
-  if (contentLength != 0) {
-    fmt::print(os, "Content-Length: {}\r\n", contentLength);
-  }
-  os << "Access-Control-Allow-Origin: *\r\nAccess-Control-Allow-Methods: *\r\n";
-  if (!extra.empty()) {
-    os << extra;
-  }
-  os << "\r\n";  // header ends with a blank line
-}
-
-void HttpServerConnection::SendData(span<const uv::Buffer> bufs,
-                                    bool closeAfter) {
-  m_stream.Write(bufs, [closeAfter, stream = &m_stream](auto bufs, uv::Error) {
-    for (auto&& buf : bufs) {
-      buf.Deallocate();
-    }
-    if (closeAfter) {
-      stream->Close();
-    }
-  });
-}
-
-void HttpServerConnection::SendResponse(int code, std::string_view codeText,
-                                        std::string_view contentType,
-                                        std::string_view content,
-                                        std::string_view extraHeader) {
-  SmallVector<uv::Buffer, 4> toSend;
-  raw_uv_ostream os{toSend, 4096};
-  BuildHeader(os, code, codeText, contentType, content.size(), extraHeader);
-  os << content;
-  // close after write completes if we aren't keeping alive
-  SendData(os.bufs(), !m_keepAlive);
-}
-
-void HttpServerConnection::SendStaticResponse(
-    int code, std::string_view codeText, std::string_view contentType,
-    std::string_view content, bool gzipped, std::string_view extraHeader) {
-  // TODO: handle remote side not accepting gzip (very rare)
-
-  std::string_view contentEncodingHeader;
-  if (gzipped /* && m_acceptGzip*/) {
-    contentEncodingHeader = "Content-Encoding: gzip\r\n";
-  }
-
-  SmallVector<uv::Buffer, 4> bufs;
-  raw_uv_ostream os{bufs, 4096};
-  BuildHeader(os, code, codeText, contentType, content.size(),
-              fmt::format("{}{}", extraHeader, contentEncodingHeader));
-  // can send content without copying
-  bufs.emplace_back(content);
-
-  m_stream.Write(bufs, [closeAfter = !m_keepAlive, stream = &m_stream](
-                           auto bufs, uv::Error) {
-    // don't deallocate the static content
-    for (auto&& buf : wpi::drop_back(bufs)) {
-      buf.Deallocate();
-    }
-    if (closeAfter) {
-      stream->Close();
-    }
-  });
-}
-
-void HttpServerConnection::SendError(int code, std::string_view message) {
-  std::string_view codeText, extra, baseMessage;
-  switch (code) {
-    case 401:
-      codeText = "Unauthorized";
-      extra = "WWW-Authenticate: Basic realm=\"CameraServer\"";
-      baseMessage = "401: Not Authenticated!";
-      break;
-    case 404:
-      codeText = "Not Found";
-      baseMessage = "404: Not Found!";
-      break;
-    case 500:
-      codeText = "Internal Server Error";
-      baseMessage = "500: Internal Server Error!";
-      break;
-    case 400:
-      codeText = "Bad Request";
-      baseMessage = "400: Not Found!";
-      break;
-    case 403:
-      codeText = "Forbidden";
-      baseMessage = "403: Forbidden!";
-      break;
-    case 503:
-      codeText = "Service Unavailable";
-      baseMessage = "503: Service Unavailable";
-      break;
-    default:
-      code = 501;
-      codeText = "Not Implemented";
-      baseMessage = "501: Not Implemented!";
-      break;
-  }
-  SmallString<256> content{baseMessage};
-  content += "\r\n";
-  content += message;
-  SendResponse(code, codeText, "text/plain", content.str(), extra);
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/HttpUtil.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/HttpUtil.cpp
deleted file mode 100644
index b8b7cc8..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/HttpUtil.cpp
+++ /dev/null
@@ -1,493 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/HttpUtil.h"
-
-#include <cctype>
-
-#include "fmt/format.h"
-#include "wpi/Base64.h"
-#include "wpi/StringExtras.h"
-#include "wpi/TCPConnector.h"
-#include "wpi/raw_ostream.h"
-
-namespace wpi {
-
-std::string_view UnescapeURI(std::string_view str, SmallVectorImpl<char>& buf,
-                             bool* error) {
-  buf.clear();
-  for (auto i = str.begin(), end = str.end(); i != end; ++i) {
-    // pass non-escaped characters to output
-    if (*i != '%') {
-      // decode + to space
-      if (*i == '+') {
-        buf.push_back(' ');
-      } else {
-        buf.push_back(*i);
-      }
-      continue;
-    }
-
-    // are there enough characters left?
-    if (i + 2 >= end) {
-      *error = true;
-      return {};
-    }
-
-    // replace %xx with the corresponding character
-    unsigned val1 = hexDigitValue(*++i);
-    if (val1 == -1U) {
-      *error = true;
-      return {};
-    }
-    unsigned val2 = hexDigitValue(*++i);
-    if (val2 == -1U) {
-      *error = true;
-      return {};
-    }
-    buf.push_back((val1 << 4) | val2);
-  }
-
-  *error = false;
-  return {buf.data(), buf.size()};
-}
-
-std::string_view EscapeURI(std::string_view str, SmallVectorImpl<char>& buf,
-                           bool spacePlus) {
-  static const char* const hexLut = "0123456789ABCDEF";
-
-  buf.clear();
-  for (auto i = str.begin(), end = str.end(); i != end; ++i) {
-    // pass unreserved characters to output
-    if (std::isalnum(*i) || *i == '-' || *i == '_' || *i == '.' || *i == '~') {
-      buf.push_back(*i);
-      continue;
-    }
-
-    // encode space to +
-    if (spacePlus && *i == ' ') {
-      buf.push_back('+');
-      continue;
-    }
-
-    // convert others to %xx
-    buf.push_back('%');
-    buf.push_back(hexLut[((*i) >> 4) & 0x0f]);
-    buf.push_back(hexLut[(*i) & 0x0f]);
-  }
-
-  return {buf.data(), buf.size()};
-}
-
-HttpQueryMap::HttpQueryMap(std::string_view query) {
-  SmallVector<std::string_view, 16> queryElems;
-  split(query, queryElems, '&', 100, false);
-  for (auto elem : queryElems) {
-    auto [nameEsc, valueEsc] = split(elem, '=');
-    SmallString<64> nameBuf;
-    bool err = false;
-    auto name = wpi::UnescapeURI(nameEsc, nameBuf, &err);
-    // note: ignores duplicates
-    if (!err) {
-      m_elems.try_emplace(name, valueEsc);
-    }
-  }
-}
-
-std::optional<std::string_view> HttpQueryMap::Get(
-    std::string_view name, wpi::SmallVectorImpl<char>& buf) const {
-  auto it = m_elems.find(name);
-  if (it == m_elems.end()) {
-    return {};
-  }
-  bool err = false;
-  auto val = wpi::UnescapeURI(it->second, buf, &err);
-  if (err) {
-    return {};
-  }
-  return val;
-}
-
-HttpPath::HttpPath(std::string_view path) {
-  // special-case root path to be a single empty element
-  if (path == "/") {
-    m_pathEnds.emplace_back(0);
-    return;
-  }
-  wpi::SmallVector<std::string_view, 16> pathElems;
-  split(path, pathElems, '/', 100, false);
-  for (auto elem : pathElems) {
-    SmallString<64> buf;
-    bool err = false;
-    auto val = wpi::UnescapeURI(elem, buf, &err);
-    if (err) {
-      m_pathEnds.clear();
-      return;
-    }
-    m_pathBuf += val;
-    m_pathEnds.emplace_back(m_pathBuf.size());
-  }
-}
-
-bool HttpPath::startswith(size_t start,
-                          span<const std::string_view> match) const {
-  if (m_pathEnds.size() < (start + match.size())) {
-    return false;
-  }
-  bool first = start == 0;
-  auto p = m_pathEnds.begin() + start;
-  for (auto m : match) {
-    auto val = slice(m_pathBuf, first ? 0 : *(p - 1), *p);
-    if (val != m) {
-      return false;
-    }
-    first = false;
-    ++p;
-  }
-  return true;
-}
-
-std::string_view HttpPath::operator[](size_t n) const {
-  return slice(m_pathBuf, n == 0 ? 0 : m_pathEnds[n - 1], m_pathEnds[n]);
-}
-
-bool ParseHttpHeaders(raw_istream& is, SmallVectorImpl<char>* contentType,
-                      SmallVectorImpl<char>* contentLength) {
-  if (contentType) {
-    contentType->clear();
-  }
-  if (contentLength) {
-    contentLength->clear();
-  }
-
-  bool inContentType = false;
-  bool inContentLength = false;
-  SmallString<64> lineBuf;
-  for (;;) {
-    std::string_view line = rtrim(is.getline(lineBuf, 1024));
-    if (is.has_error()) {
-      return false;
-    }
-    if (line.empty()) {
-      return true;  // empty line signals end of headers
-    }
-
-    // header fields start at the beginning of the line
-    if (!std::isspace(line[0])) {
-      inContentType = false;
-      inContentLength = false;
-      std::string_view field;
-      std::tie(field, line) = split(line, ':');
-      field = rtrim(field);
-      if (equals_lower(field, "content-type")) {
-        inContentType = true;
-      } else if (equals_lower(field, "content-length")) {
-        inContentLength = true;
-      } else {
-        continue;  // ignore other fields
-      }
-    }
-
-    // collapse whitespace
-    line = ltrim(line);
-
-    // save field data
-    if (inContentType && contentType) {
-      contentType->append(line.begin(), line.end());
-    } else if (inContentLength && contentLength) {
-      contentLength->append(line.begin(), line.end());
-    }
-  }
-}
-
-bool FindMultipartBoundary(raw_istream& is, std::string_view boundary,
-                           std::string* saveBuf) {
-  SmallString<64> searchBuf;
-  searchBuf.resize(boundary.size() + 2);
-  size_t searchPos = 0;
-
-  // Per the spec, the --boundary should be preceded by \r\n, so do a first
-  // pass of 1-byte reads to throw those away (common case) and keep the
-  // last non-\r\n character in searchBuf.
-  if (!saveBuf) {
-    do {
-      is.read(searchBuf.data(), 1);
-      if (is.has_error()) {
-        return false;
-      }
-    } while (searchBuf[0] == '\r' || searchBuf[0] == '\n');
-    searchPos = 1;
-  }
-
-  // Look for --boundary.  Read boundarysize+2 bytes at a time
-  // during the search to speed up the reads, then fast-scan for -,
-  // and only then match the entire boundary.  This will be slow if
-  // there's a bunch of continuous -'s in the output, but that's unlikely.
-  for (;;) {
-    is.read(searchBuf.data() + searchPos, searchBuf.size() - searchPos);
-    if (is.has_error()) {
-      return false;
-    }
-
-    // Did we find the boundary?
-    if (searchBuf[0] == '-' && searchBuf[1] == '-' &&
-        wpi::substr(searchBuf, 2) == boundary) {
-      return true;
-    }
-
-    // Fast-scan for '-'
-    size_t pos = searchBuf.find('-', searchBuf[0] == '-' ? 1 : 0);
-    if (pos == std::string_view::npos) {
-      if (saveBuf) {
-        saveBuf->append(searchBuf.data(), searchBuf.size());
-      }
-    } else {
-      if (saveBuf) {
-        saveBuf->append(searchBuf.data(), pos);
-      }
-
-      // move '-' and following to start of buffer (next read will fill)
-      std::memmove(searchBuf.data(), searchBuf.data() + pos,
-                   searchBuf.size() - pos);
-      searchPos = searchBuf.size() - pos;
-    }
-  }
-}
-
-HttpLocation::HttpLocation(std::string_view url_, bool* error,
-                           std::string* errorMsg)
-    : url{url_} {
-  // Split apart into components
-  std::string_view query{url};
-
-  // scheme:
-  std::string_view scheme;
-  std::tie(scheme, query) = split(query, ':');
-  if (!equals_lower(scheme, "http")) {
-    *errorMsg = "only supports http URLs";
-    *error = true;
-    return;
-  }
-
-  // "//"
-  if (!starts_with(query, "//")) {
-    *errorMsg = "expected http://...";
-    *error = true;
-    return;
-  }
-  query.remove_prefix(2);
-
-  // user:password@host:port/
-  std::string_view authority;
-  std::tie(authority, query) = split(query, '/');
-
-  auto [userpass, hostport] = split(authority, '@');
-  // split leaves the RHS empty if the split char isn't present...
-  if (hostport.empty()) {
-    hostport = userpass;
-    userpass = {};
-  }
-
-  if (!userpass.empty()) {
-    auto [rawUser, rawPassword] = split(userpass, ':');
-    SmallString<64> userBuf, passBuf;
-    user = UnescapeURI(rawUser, userBuf, error);
-    if (*error) {
-      *errorMsg = fmt::format("could not unescape user \"{}\"", rawUser);
-      return;
-    }
-    password = UnescapeURI(rawPassword, passBuf, error);
-    if (*error) {
-      *errorMsg =
-          fmt::format("could not unescape password \"{}\"", rawPassword);
-      return;
-    }
-  }
-
-  std::string_view portStr;
-  std::tie(host, portStr) = rsplit(hostport, ':');
-  if (host.empty()) {
-    *errorMsg = "host is empty";
-    *error = true;
-    return;
-  }
-  if (portStr.empty()) {
-    port = 80;
-  } else if (auto p = parse_integer<int>(portStr, 10)) {
-    port = p.value();
-  } else {
-    *errorMsg = fmt::format("port \"{}\" is not an integer", portStr);
-    *error = true;
-    return;
-  }
-
-  // path?query#fragment
-  std::tie(query, fragment) = split(query, '#');
-  std::tie(path, query) = split(query, '?');
-
-  // Split query string into parameters
-  while (!query.empty()) {
-    // split out next param and value
-    std::string_view rawParam, rawValue;
-    std::tie(rawParam, query) = split(query, '&');
-    if (rawParam.empty()) {
-      continue;  // ignore "&&"
-    }
-    std::tie(rawParam, rawValue) = split(rawParam, '=');
-
-    // unescape param
-    *error = false;
-    SmallString<64> paramBuf;
-    std::string_view param = UnescapeURI(rawParam, paramBuf, error);
-    if (*error) {
-      *errorMsg = fmt::format("could not unescape parameter \"{}\"", rawParam);
-      return;
-    }
-
-    // unescape value
-    SmallString<64> valueBuf;
-    std::string_view value = UnescapeURI(rawValue, valueBuf, error);
-    if (*error) {
-      *errorMsg = fmt::format("could not unescape value \"{}\"", rawValue);
-      return;
-    }
-
-    params.emplace_back(std::make_pair(param, value));
-  }
-
-  *error = false;
-}
-
-void HttpRequest::SetAuth(const HttpLocation& loc) {
-  if (!loc.user.empty()) {
-    SmallString<64> userpass;
-    userpass += loc.user;
-    userpass += ':';
-    userpass += loc.password;
-    Base64Encode(userpass.str(), &auth);
-  }
-}
-
-bool HttpConnection::Handshake(const HttpRequest& request,
-                               std::string* warnMsg) {
-  // send GET request
-  os << "GET /" << request.path << " HTTP/1.1\r\n";
-  os << "Host: " << request.host << "\r\n";
-  if (!request.auth.empty()) {
-    os << "Authorization: Basic " << request.auth << "\r\n";
-  }
-  os << "\r\n";
-  os.flush();
-
-  // read first line of response
-  SmallString<64> lineBuf;
-  std::string_view line = rtrim(is.getline(lineBuf, 1024));
-  if (is.has_error()) {
-    *warnMsg = "disconnected before response";
-    return false;
-  }
-
-  // see if we got a HTTP 200 response
-  std::string_view httpver, code, codeText;
-  std::tie(httpver, line) = split(line, ' ');
-  std::tie(code, codeText) = split(line, ' ');
-  if (!starts_with(httpver, "HTTP")) {
-    *warnMsg = "did not receive HTTP response";
-    return false;
-  }
-  if (code != "200") {
-    *warnMsg = fmt::format("received {} {} response", code, codeText);
-    return false;
-  }
-
-  // Parse headers
-  if (!ParseHttpHeaders(is, &contentType, &contentLength)) {
-    *warnMsg = "disconnected during headers";
-    return false;
-  }
-
-  return true;
-}
-
-void HttpMultipartScanner::SetBoundary(std::string_view boundary) {
-  m_boundaryWith = "\n--";
-  m_boundaryWith += boundary;
-  m_boundaryWithout = "\n";
-  m_boundaryWithout += boundary;
-  m_dashes = kUnknown;
-}
-
-void HttpMultipartScanner::Reset(bool saveSkipped) {
-  m_saveSkipped = saveSkipped;
-  m_state = kBoundary;
-  m_posWith = 0;
-  m_posWithout = 0;
-  m_buf.resize(0);
-}
-
-std::string_view HttpMultipartScanner::Execute(std::string_view in) {
-  if (m_state == kDone) {
-    Reset(m_saveSkipped);
-  }
-  if (m_saveSkipped) {
-    m_buf += in;
-  }
-
-  size_t pos = 0;
-  if (m_state == kBoundary) {
-    for (char ch : in) {
-      ++pos;
-      if (m_dashes != kWithout) {
-        if (ch == m_boundaryWith[m_posWith]) {
-          ++m_posWith;
-          if (m_posWith == m_boundaryWith.size()) {
-            // Found the boundary; transition to padding
-            m_state = kPadding;
-            m_dashes = kWith;  // no longer accept plain 'boundary'
-            break;
-          }
-        } else if (ch == m_boundaryWith[0]) {
-          m_posWith = 1;
-        } else {
-          m_posWith = 0;
-        }
-      }
-
-      if (m_dashes != kWith) {
-        if (ch == m_boundaryWithout[m_posWithout]) {
-          ++m_posWithout;
-          if (m_posWithout == m_boundaryWithout.size()) {
-            // Found the boundary; transition to padding
-            m_state = kPadding;
-            m_dashes = kWithout;  // no longer accept '--boundary'
-            break;
-          }
-        } else if (ch == m_boundaryWithout[0]) {
-          m_posWithout = 1;
-        } else {
-          m_posWithout = 0;
-        }
-      }
-    }
-  }
-
-  if (m_state == kPadding) {
-    for (char ch : drop_front(in, pos)) {
-      ++pos;
-      if (ch == '\n') {
-        // Found the LF; return remaining input buffer (following it)
-        m_state = kDone;
-        if (m_saveSkipped) {
-          m_buf.resize(m_buf.size() - in.size() + pos);
-        }
-        return drop_front(in, pos);
-      }
-    }
-  }
-
-  // We consumed the entire input
-  return {};
-}
-
-}  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/MappedFileRegion.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/MappedFileRegion.cpp
new file mode 100644
index 0000000..006e395
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/cpp/MappedFileRegion.cpp
@@ -0,0 +1,133 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpi/MappedFileRegion.h"
+
+#include <sys/types.h>
+
+#ifdef _WIN32
+#ifndef WIN32_LEAN_AND_MEAN
+#define WIN32_LEAN_AND_MEAN
+#endif
+
+#include <windows.h>  // NOLINT(build/include_order)
+
+#include <memoryapi.h>
+#include <sysinfoapi.h>
+
+#else  // _WIN32
+
+#include <sys/mman.h>
+#include <unistd.h>
+
+#endif  // _WIN32
+
+#ifdef _MSC_VER
+#include <io.h>
+#endif
+
+#ifdef _WIN32
+#include "wpi/WindowsError.h"
+#endif
+
+using namespace wpi;
+
+MappedFileRegion::MappedFileRegion(fs::file_t f, uint64_t length,
+                                   uint64_t offset, MapMode mapMode,
+                                   std::error_code& ec)
+    : m_size(length) {
+#ifdef _WIN32
+  if (f == INVALID_HANDLE_VALUE) {
+    ec = std::make_error_code(std::errc::bad_file_descriptor);
+    return;
+  }
+
+  HANDLE fileMappingHandle = ::CreateFileMappingW(
+      f, 0, mapMode == kReadOnly ? PAGE_READONLY : PAGE_READWRITE, length >> 32,
+      length & 0xffffffff, 0);
+  if (fileMappingHandle == nullptr) {
+    ec = wpi::mapWindowsError(GetLastError());
+    return;
+  }
+
+  DWORD dwDesiredAccess = 0;
+  switch (mapMode) {
+    case kReadOnly:
+      dwDesiredAccess = FILE_MAP_READ;
+      break;
+    case kReadWrite:
+      dwDesiredAccess = FILE_MAP_WRITE;
+      break;
+    case kPriv:
+      dwDesiredAccess = FILE_MAP_WRITE | FILE_MAP_COPY;
+      break;
+  }
+  m_mapping = ::MapViewOfFile(fileMappingHandle, dwDesiredAccess, offset >> 32,
+                              offset & 0xffffffff, length);
+  if (m_mapping == nullptr) {
+    ec = wpi::mapWindowsError(GetLastError());
+    ::CloseHandle(fileMappingHandle);
+    return;
+  }
+
+  // Close the file mapping handle, as it's kept alive by the file mapping. But
+  // neither the file mapping nor the file mapping handle keep the file handle
+  // alive, so we need to keep a reference to the file in case all other handles
+  // are closed and the file is deleted, which may cause invalid data to be read
+  // from the file.
+  ::CloseHandle(fileMappingHandle);
+  if (!::DuplicateHandle(::GetCurrentProcess(), f, ::GetCurrentProcess(),
+                         &m_fileHandle, 0, 0, DUPLICATE_SAME_ACCESS)) {
+    ec = wpi::mapWindowsError(GetLastError());
+    ::UnmapViewOfFile(m_mapping);
+    m_mapping = nullptr;
+    return;
+  }
+#else
+  m_mapping =
+      ::mmap(nullptr, length,
+             mapMode == kReadOnly ? PROT_READ : (PROT_READ | PROT_WRITE),
+             mapMode == kPriv ? MAP_PRIVATE : MAP_SHARED, f, offset);
+  if (m_mapping == MAP_FAILED) {
+    ec = std::error_code(errno, std::generic_category());
+    m_mapping = nullptr;
+  }
+#endif
+}
+
+void MappedFileRegion::Flush() {
+#ifdef _WIN32
+  ::FlushViewOfFile(m_mapping, 0);
+  ::FlushFileBuffers(m_fileHandle);
+#else
+  ::msync(m_mapping, m_size, MS_ASYNC);
+#endif
+}
+
+void MappedFileRegion::Unmap() {
+  if (!m_mapping) {
+    return;
+  }
+#ifdef _WIN32
+  ::UnmapViewOfFile(m_mapping);
+  ::CloseHandle(m_fileHandle);
+#else
+  ::munmap(m_mapping, m_size);
+#endif
+  m_mapping = nullptr;
+}
+
+size_t MappedFileRegion::GetAlignment() {
+#ifdef _WIN32
+  SYSTEM_INFO SysInfo;
+  ::GetSystemInfo(&SysInfo);
+  return SysInfo.dwAllocationGranularity;
+#else
+  static long pageSize = ::getpagesize();  // NOLINT
+  if (pageSize < 0) {
+    pageSize = 4096;
+  }
+  return pageSize;
+#endif
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/MessagePack.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/MessagePack.cpp
new file mode 100644
index 0000000..60a2f01
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/cpp/MessagePack.cpp
@@ -0,0 +1,45 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpi/MessagePack.h"
+
+using namespace mpack;
+
+mpack_error_t mpack::mpack_expect_str(mpack_reader_t* reader, std::string* out,
+                                      uint32_t maxLen) {
+  uint32_t count = mpack_expect_str_max(reader, maxLen);
+  mpack_error_t err = mpack_reader_error(reader);
+  if (err != mpack_ok) {
+    return err;
+  }
+  const char* bytes = mpack_read_bytes_inplace(reader, count);
+  if (bytes) {
+    out->assign(bytes, count);
+  } else {
+    return mpack_reader_error(reader);
+  }
+  mpack_done_str(reader);
+  return mpack_ok;
+}
+
+mpack_error_t mpack::mpack_read_str(mpack_reader_t* reader, mpack_tag_t* tag,
+                                    std::string* out, uint32_t maxLen) {
+  uint32_t count = mpack_tag_str_length(tag);
+  mpack_error_t err = mpack_reader_error(reader);
+  if (err != mpack_ok) {
+    return err;
+  }
+  if (count > maxLen) {
+    mpack_reader_flag_error(reader, mpack_error_too_big);
+    return mpack_error_too_big;
+  }
+  const char* bytes = mpack_read_bytes_inplace(reader, count);
+  if (bytes) {
+    out->assign(bytes, count);
+  } else {
+    return mpack_reader_error(reader);
+  }
+  mpack_done_str(reader);
+  return mpack_ok;
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/MimeTypes.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/MimeTypes.cpp
deleted file mode 100644
index 5f5bf59..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/MimeTypes.cpp
+++ /dev/null
@@ -1,69 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/MimeTypes.h"
-
-#include "wpi/StringExtras.h"
-#include "wpi/StringMap.h"
-
-namespace wpi {
-
-// derived partially from
-// https://github.com/DEGoodmanWilson/libmime/blob/stable/0.1.2/mime/mime.cpp
-std::string_view MimeTypeFromPath(std::string_view path) {
-  // https://developer.mozilla.org/en-US/docs/Web/HTTP/Basics_of_HTTP/MIME_types
-  static StringMap<const char*> mimeTypes{
-      // text
-      {"css", "text/css"},
-      {"csv", "text/csv"},
-      {"htm", "text/html"},
-      {"html", "text/html"},
-      {"js", "text/javascript"},
-      {"json", "application/json"},
-      {"map", "application/json"},
-      {"md", "text/markdown"},
-      {"txt", "text/plain"},
-      {"xml", "text/xml"},
-
-      // images
-      {"apng", "image/apng"},
-      {"bmp", "image/bmp"},
-      {"gif", "image/gif"},
-      {"cur", "image/x-icon"},
-      {"ico", "image/x-icon"},
-      {"jpg", "image/jpeg"},
-      {"jpeg", "image/jpeg"},
-      {"png", "image/png"},
-      {"svg", "image/svg+xml"},
-      {"tif", "image/tiff"},
-      {"tiff", "image/tiff"},
-      {"webp", "image/webp"},
-
-      // fonts
-      {"otf", "font/otf"},
-      {"ttf", "font/ttf"},
-      {"woff", "font/woff"},
-
-      // misc
-      {"pdf", "application/pdf"},
-      {"zip", "application/zip"},
-  };
-
-  static const char* defaultType = "application/octet-stream";
-
-  auto pos = path.find_last_of("/");
-  if (pos != std::string_view::npos) {
-    path = wpi::substr(path, pos + 1);
-  }
-  auto dot_pos = path.find_last_of(".");
-  if (dot_pos > 0 && dot_pos != std::string_view::npos) {
-    auto type = mimeTypes.find(wpi::substr(path, dot_pos + 1));
-    if (type != mimeTypes.end()) {
-      return type->getValue();
-    }
-  }
-  return defaultType;
-}
-
-}  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/MulticastHandleManager.h b/third_party/allwpilib/wpiutil/src/main/native/cpp/MulticastHandleManager.h
deleted file mode 100644
index be8d061..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/MulticastHandleManager.h
+++ /dev/null
@@ -1,25 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <memory>
-
-#include "wpi/DenseMap.h"
-#include "wpi/MulticastServiceAnnouncer.h"
-#include "wpi/MulticastServiceResolver.h"
-#include "wpi/UidVector.h"
-
-namespace wpi {
-struct MulticastHandleManager {
-  wpi::mutex mutex;
-  wpi::UidVector<int, 8> handleIds;
-  wpi::DenseMap<size_t, std::unique_ptr<wpi::MulticastServiceResolver>>
-      resolvers;
-  wpi::DenseMap<size_t, std::unique_ptr<wpi::MulticastServiceAnnouncer>>
-      announcers;
-};
-
-MulticastHandleManager& GetMulticastManager();
-}  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/MulticastServiceAnnouncer.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/MulticastServiceAnnouncer.cpp
deleted file mode 100644
index 736a03d..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/MulticastServiceAnnouncer.cpp
+++ /dev/null
@@ -1,67 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/MulticastServiceAnnouncer.h"
-
-#include <wpi/SmallVector.h>
-
-#include "MulticastHandleManager.h"
-
-extern "C" {
-WPI_MulticastServiceAnnouncerHandle WPI_CreateMulticastServiceAnnouncer(
-    const char* serviceName, const char* serviceType, int32_t port,
-    int32_t txtCount, const char** keys, const char** values)
-
-{
-  auto& manager = wpi::GetMulticastManager();
-  std::scoped_lock lock{manager.mutex};
-
-  wpi::SmallVector<std::pair<std::string_view, std::string_view>, 8> txts;
-
-  for (int32_t i = 0; i < txtCount; i++) {
-    txts.emplace_back(
-        std::pair<std::string_view, std::string_view>{keys[i], values[i]});
-  }
-
-  auto announcer = std::make_unique<wpi::MulticastServiceAnnouncer>(
-      serviceName, serviceType, port, txts);
-
-  size_t index = manager.handleIds.emplace_back(3);
-  manager.announcers[index] = std::move(announcer);
-
-  return index;
-}
-
-void WPI_FreeMulticastServiceAnnouncer(
-    WPI_MulticastServiceAnnouncerHandle handle) {
-  auto& manager = wpi::GetMulticastManager();
-  std::scoped_lock lock{manager.mutex};
-  manager.announcers[handle] = nullptr;
-  manager.handleIds.erase(handle);
-}
-
-void WPI_StartMulticastServiceAnnouncer(
-    WPI_MulticastServiceAnnouncerHandle handle) {
-  auto& manager = wpi::GetMulticastManager();
-  std::scoped_lock lock{manager.mutex};
-  auto& announcer = manager.announcers[handle];
-  announcer->Start();
-}
-
-void WPI_StopMulticastServiceAnnouncer(
-    WPI_MulticastServiceAnnouncerHandle handle) {
-  auto& manager = wpi::GetMulticastManager();
-  std::scoped_lock lock{manager.mutex};
-  auto& announcer = manager.announcers[handle];
-  announcer->Stop();
-}
-
-int32_t WPI_GetMulticastServiceAnnouncerHasImplementation(
-    WPI_MulticastServiceAnnouncerHandle handle) {
-  auto& manager = wpi::GetMulticastManager();
-  std::scoped_lock lock{manager.mutex};
-  auto& announcer = manager.announcers[handle];
-  return announcer->HasImplementation();
-}
-}  // extern "C"
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/MulticastServiceResolver.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/MulticastServiceResolver.cpp
deleted file mode 100644
index b834f17..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/MulticastServiceResolver.cpp
+++ /dev/null
@@ -1,148 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/MulticastServiceResolver.h"
-
-#include "MulticastHandleManager.h"
-#include "wpi/MemAlloc.h"
-
-extern "C" {
-WPI_MulticastServiceResolverHandle WPI_CreateMulticastServiceResolver(
-    const char* serviceType)
-
-{
-  auto& manager = wpi::GetMulticastManager();
-  std::scoped_lock lock{manager.mutex};
-
-  auto resolver = std::make_unique<wpi::MulticastServiceResolver>(serviceType);
-
-  size_t index = manager.handleIds.emplace_back(2);
-  manager.resolvers[index] = std::move(resolver);
-
-  return index;
-}
-
-void WPI_FreeMulticastServiceResolver(
-    WPI_MulticastServiceResolverHandle handle) {
-  auto& manager = wpi::GetMulticastManager();
-  std::scoped_lock lock{manager.mutex};
-  manager.resolvers[handle] = nullptr;
-  manager.handleIds.erase(handle);
-}
-
-void WPI_StartMulticastServiceResolver(
-    WPI_MulticastServiceResolverHandle handle) {
-  auto& manager = wpi::GetMulticastManager();
-  std::scoped_lock lock{manager.mutex};
-  auto& resolver = manager.resolvers[handle];
-  resolver->Start();
-}
-
-void WPI_StopMulticastServiceResolver(
-    WPI_MulticastServiceResolverHandle handle) {
-  auto& manager = wpi::GetMulticastManager();
-  std::scoped_lock lock{manager.mutex};
-  auto& resolver = manager.resolvers[handle];
-  resolver->Stop();
-}
-
-int32_t WPI_GetMulticastServiceResolverHasImplementation(
-    WPI_MulticastServiceResolverHandle handle) {
-  auto& manager = wpi::GetMulticastManager();
-  std::scoped_lock lock{manager.mutex};
-  auto& resolver = manager.resolvers[handle];
-  return resolver->HasImplementation();
-}
-
-WPI_EventHandle WPI_GetMulticastServiceResolverEventHandle(
-    WPI_MulticastServiceResolverHandle handle) {
-  auto& manager = wpi::GetMulticastManager();
-  std::scoped_lock lock{manager.mutex};
-  auto& resolver = manager.resolvers[handle];
-  return resolver->GetEventHandle();
-}
-
-WPI_ServiceData* WPI_GetMulticastServiceResolverData(
-    WPI_MulticastServiceResolverHandle handle, int32_t* dataCount) {
-  std::vector<wpi::MulticastServiceResolver::ServiceData> allData;
-  {
-    auto& manager = wpi::GetMulticastManager();
-    std::scoped_lock lock{manager.mutex};
-    auto& resolver = manager.resolvers[handle];
-    allData = resolver->GetData();
-  }
-  if (allData.empty()) {
-    *dataCount = 0;
-    return nullptr;
-  }
-  size_t allocSize = sizeof(WPI_ServiceData) * allData.size();
-
-  for (auto&& data : allData) {
-    // Include space for hostName and serviceType (+ terminators)
-    allocSize += data.hostName.size() + data.serviceName.size() + 2;
-
-    size_t keysTotalLength = 0;
-    size_t valuesTotalLength = 0;
-    // Include space for all keys and values, and pointer array
-    for (auto&& t : data.txt) {
-      allocSize += sizeof(const char*);
-      keysTotalLength += (t.first.size() + 1);
-      allocSize += sizeof(const char*);
-      valuesTotalLength += (t.second.size() + 1);
-    }
-    allocSize += keysTotalLength;
-    allocSize += valuesTotalLength;
-  }
-
-  uint8_t* cDataRaw = reinterpret_cast<uint8_t*>(wpi::safe_malloc(allocSize));
-  if (!cDataRaw) {
-    return nullptr;
-  }
-  WPI_ServiceData* rootArray = reinterpret_cast<WPI_ServiceData*>(cDataRaw);
-  cDataRaw += (sizeof(WPI_ServiceData) + allData.size());
-  WPI_ServiceData* currentData = rootArray;
-
-  for (auto&& data : allData) {
-    currentData->ipv4Address = data.ipv4Address;
-    currentData->port = data.port;
-    currentData->txtCount = data.txt.size();
-
-    std::memcpy(cDataRaw, data.hostName.c_str(), data.hostName.size() + 1);
-    currentData->hostName = reinterpret_cast<const char*>(cDataRaw);
-    cDataRaw += data.hostName.size() + 1;
-
-    std::memcpy(cDataRaw, data.serviceName.c_str(),
-                data.serviceName.size() + 1);
-    currentData->serviceName = reinterpret_cast<const char*>(cDataRaw);
-    cDataRaw += data.serviceName.size() + 1;
-
-    char** valuesPtrArr = reinterpret_cast<char**>(cDataRaw);
-    cDataRaw += (sizeof(char**) * data.txt.size());
-    char** keysPtrArr = reinterpret_cast<char**>(cDataRaw);
-    cDataRaw += (sizeof(char**) * data.txt.size());
-
-    currentData->txtKeys = const_cast<const char**>(keysPtrArr);
-    currentData->txtValues = const_cast<const char**>(valuesPtrArr);
-
-    for (size_t i = 0; i < data.txt.size(); i++) {
-      keysPtrArr[i] = reinterpret_cast<char*>(cDataRaw);
-      std::memcpy(keysPtrArr[i], data.txt[i].first.c_str(),
-                  data.txt[i].first.size() + 1);
-      cDataRaw += (data.txt[i].first.size() + 1);
-
-      valuesPtrArr[i] = reinterpret_cast<char*>(cDataRaw);
-      std::memcpy(valuesPtrArr[i], data.txt[i].second.c_str(),
-                  data.txt[i].second.size() + 1);
-      cDataRaw += (data.txt[i].second.size() + 1);
-    }
-    currentData++;
-  }
-
-  return rootArray;
-}
-
-void WPI_FreeServiceData(WPI_ServiceData* serviceData, int32_t length) {
-  std::free(serviceData);
-}
-}  // extern "C"
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/ParallelTcpConnector.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/ParallelTcpConnector.cpp
deleted file mode 100644
index 5a8394a..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/ParallelTcpConnector.cpp
+++ /dev/null
@@ -1,177 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/ParallelTcpConnector.h"
-
-#include <fmt/format.h>
-
-#include "wpi/Logger.h"
-#include "wpi/uv/GetAddrInfo.h"
-#include "wpi/uv/Loop.h"
-#include "wpi/uv/Tcp.h"
-#include "wpi/uv/Timer.h"
-#include "wpi/uv/util.h"
-
-using namespace wpi;
-
-ParallelTcpConnector::ParallelTcpConnector(
-    wpi::uv::Loop& loop, wpi::uv::Timer::Time reconnectRate,
-    wpi::Logger& logger, std::function<void(wpi::uv::Tcp& tcp)> connected,
-    const private_init&)
-    : m_loop{loop},
-      m_logger{logger},
-      m_reconnectRate{reconnectRate},
-      m_connected{std::move(connected)},
-      m_reconnectTimer{uv::Timer::Create(loop)} {
-  m_reconnectTimer->timeout.connect([this] {
-    if (!IsConnected()) {
-      WPI_DEBUG1(m_logger, "{}", "timed out, reconnecting");
-      Connect();
-    }
-  });
-}
-
-ParallelTcpConnector::~ParallelTcpConnector() = default;
-
-void ParallelTcpConnector::Close() {
-  CancelAll();
-  m_reconnectTimer->Close();
-}
-
-void ParallelTcpConnector::SetServers(
-    wpi::span<const std::pair<std::string, unsigned int>> servers) {
-  m_servers.assign(servers.begin(), servers.end());
-  if (!IsConnected()) {
-    Connect();
-  }
-}
-
-void ParallelTcpConnector::Disconnected() {
-  if (m_isConnected) {
-    m_isConnected = false;
-    Connect();
-  }
-}
-
-void ParallelTcpConnector::Succeeded(uv::Tcp& tcp) {
-  if (!m_isConnected) {
-    m_isConnected = true;
-    m_reconnectTimer->Stop();
-    CancelAll(&tcp);
-  }
-}
-
-void ParallelTcpConnector::Connect() {
-  if (IsConnected()) {
-    return;
-  }
-
-  CancelAll();
-  m_reconnectTimer->Start(m_reconnectRate);
-
-  WPI_DEBUG3(m_logger, "{}", "starting new connection attempts");
-
-  // kick off parallel lookups
-  for (auto&& server : m_servers) {
-    auto req = std::make_shared<uv::GetAddrInfoReq>();
-    m_resolvers.emplace_back(req);
-
-    req->resolved.connect(
-        [this, req = req.get()](const addrinfo& addrinfo) {
-          if (IsConnected()) {
-            return;
-          }
-
-          // kick off parallel connection attempts
-          for (auto ai = &addrinfo; ai; ai = ai->ai_next) {
-            auto tcp = uv::Tcp::Create(m_loop);
-            m_attempts.emplace_back(tcp);
-
-            auto connreq = std::make_shared<uv::TcpConnectReq>();
-            connreq->connected.connect(
-                [this, tcp = tcp.get()] {
-                  if (m_logger.min_level() <= wpi::WPI_LOG_DEBUG4) {
-                    std::string ip;
-                    unsigned int port = 0;
-                    uv::AddrToName(tcp->GetPeer(), &ip, &port);
-                    WPI_DEBUG4(m_logger,
-                               "successful connection ({}) to {} port {}",
-                               static_cast<void*>(tcp), ip, port);
-                  }
-                  if (IsConnected()) {
-                    tcp->Shutdown([tcp] { tcp->Close(); });
-                    return;
-                  }
-                  if (m_connected) {
-                    m_connected(*tcp);
-                  }
-                },
-                shared_from_this());
-
-            connreq->error = [selfWeak = weak_from_this(),
-                              tcp = tcp.get()](uv::Error err) {
-              if (auto self = selfWeak.lock()) {
-                WPI_DEBUG1(self->m_logger, "connect failure ({}): {}",
-                           static_cast<void*>(tcp), err.str());
-              }
-            };
-
-            if (m_logger.min_level() <= wpi::WPI_LOG_DEBUG4) {
-              std::string ip;
-              unsigned int port = 0;
-              uv::AddrToName(*reinterpret_cast<sockaddr_storage*>(ai->ai_addr),
-                             &ip, &port);
-              WPI_DEBUG4(
-                  m_logger,
-                  "Info({}) starting connection attempt ({}) to {} port {}",
-                  static_cast<void*>(req), static_cast<void*>(tcp.get()), ip,
-                  port);
-            }
-            tcp->Connect(*ai->ai_addr, connreq);
-          }
-        },
-        shared_from_this());
-
-    req->error = [req = req.get(), selfWeak = weak_from_this()](uv::Error err) {
-      if (auto self = selfWeak.lock()) {
-        WPI_DEBUG1(self->m_logger, "GetAddrInfo({}) failure: {}",
-                   static_cast<void*>(req), err.str());
-      }
-    };
-
-    WPI_DEBUG4(m_logger, "starting GetAddrInfo({}) for {} port {}",
-               static_cast<void*>(req.get()), server.first, server.second);
-    addrinfo hints;
-    std::memset(&hints, 0, sizeof(hints));
-    hints.ai_family = AF_UNSPEC;
-    hints.ai_socktype = SOCK_STREAM;
-    hints.ai_protocol = IPPROTO_TCP;
-    hints.ai_flags = AI_NUMERICSERV | AI_ADDRCONFIG;
-    uv::GetAddrInfo(m_loop, req, server.first, fmt::format("{}", server.second),
-                    &hints);
-  }
-}
-
-void ParallelTcpConnector::CancelAll(wpi::uv::Tcp* except) {
-  WPI_DEBUG4(m_logger, "{}", "canceling previous attempts");
-  for (auto&& resolverWeak : m_resolvers) {
-    if (auto resolver = resolverWeak.lock()) {
-      WPI_DEBUG4(m_logger, "canceling GetAddrInfo({})",
-                 static_cast<void*>(resolver.get()));
-      resolver->Cancel();
-    }
-  }
-  m_resolvers.clear();
-
-  for (auto&& tcpWeak : m_attempts) {
-    if (auto tcp = tcpWeak.lock()) {
-      if (tcp.get() != except) {
-        WPI_DEBUG4(m_logger, "canceling connection attempt ({})",
-                   static_cast<void*>(tcp.get()));
-        tcp->Close();
-      }
-    }
-  }
-  m_attempts.clear();
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/PortForwarder.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/PortForwarder.cpp
deleted file mode 100644
index a423d48..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/PortForwarder.cpp
+++ /dev/null
@@ -1,157 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/PortForwarder.h"
-
-#include "fmt/format.h"
-#include "wpi/DenseMap.h"
-#include "wpi/EventLoopRunner.h"
-#include "wpi/uv/GetAddrInfo.h"
-#include "wpi/uv/Tcp.h"
-#include "wpi/uv/Timer.h"
-
-using namespace wpi;
-
-struct PortForwarder::Impl {
- public:
-  EventLoopRunner runner;
-  DenseMap<unsigned int, std::weak_ptr<uv::Tcp>> servers;
-};
-
-PortForwarder::PortForwarder() : m_impl{new Impl} {}
-
-PortForwarder& PortForwarder::GetInstance() {
-  static PortForwarder instance;
-  return instance;
-}
-
-static void CopyStream(uv::Stream& in, std::weak_ptr<uv::Stream> outWeak) {
-  in.data.connect([&in, outWeak](uv::Buffer& buf, size_t len) {
-    uv::Buffer buf2 = buf.Dup();
-    buf2.len = len;
-    auto out = outWeak.lock();
-    if (!out) {
-      buf2.Deallocate();
-      in.Close();
-      return;
-    }
-    out->Write({buf2}, [](auto bufs, uv::Error) {
-      for (auto buf : bufs) {
-        buf.Deallocate();
-      }
-    });
-  });
-}
-
-void PortForwarder::Add(unsigned int port, std::string_view remoteHost,
-                        unsigned int remotePort) {
-  m_impl->runner.ExecSync([&](uv::Loop& loop) {
-    auto server = uv::Tcp::Create(loop);
-
-    // bind to local port
-    server->Bind("", port);
-
-    // when we get a connection, accept it
-    server->connection.connect([serverPtr = server.get(),
-                                host = std::string{remoteHost}, remotePort] {
-      auto& loop = serverPtr->GetLoopRef();
-      auto client = serverPtr->Accept();
-      if (!client) {
-        return;
-      }
-
-      // close on error
-      client->error.connect(
-          [clientPtr = client.get()](uv::Error err) { clientPtr->Close(); });
-
-      // connected flag
-      auto connected = std::make_shared<bool>(false);
-      client->SetData(connected);
-
-      auto remote = uv::Tcp::Create(loop);
-      remote->error.connect(
-          [remotePtr = remote.get(),
-           clientWeak = std::weak_ptr<uv::Tcp>(client)](uv::Error err) {
-            remotePtr->Close();
-            if (auto client = clientWeak.lock()) {
-              client->Close();
-            }
-          });
-
-      // resolve address
-      uv::GetAddrInfo(
-          loop,
-          [clientWeak = std::weak_ptr<uv::Tcp>(client),
-           remoteWeak = std::weak_ptr<uv::Tcp>(remote)](const addrinfo& addr) {
-            auto remote = remoteWeak.lock();
-            if (!remote) {
-              return;
-            }
-
-            // connect to remote address/port
-            remote->Connect(*addr.ai_addr, [remotePtr = remote.get(),
-                                            remoteWeak, clientWeak] {
-              auto client = clientWeak.lock();
-              if (!client) {
-                remotePtr->Close();
-                return;
-              }
-              *(client->GetData<bool>()) = true;
-
-              // close both when either side closes
-              client->end.connect([clientPtr = client.get(), remoteWeak] {
-                clientPtr->Close();
-                if (auto remote = remoteWeak.lock()) {
-                  remote->Close();
-                }
-              });
-              remotePtr->end.connect([remotePtr, clientWeak] {
-                remotePtr->Close();
-                if (auto client = clientWeak.lock()) {
-                  client->Close();
-                }
-              });
-
-              // copy bidirectionally
-              client->StartRead();
-              remotePtr->StartRead();
-              CopyStream(*client, remoteWeak);
-              CopyStream(*remotePtr, clientWeak);
-            });
-          },
-          host, fmt::to_string(remotePort));
-
-      // time out for connection
-      uv::Timer::SingleShot(loop, uv::Timer::Time{500},
-                            [connectedWeak = std::weak_ptr<bool>(connected),
-                             clientWeak = std::weak_ptr<uv::Tcp>(client),
-                             remoteWeak = std::weak_ptr<uv::Tcp>(remote)] {
-                              if (auto connected = connectedWeak.lock()) {
-                                if (!*connected) {
-                                  if (auto client = clientWeak.lock()) {
-                                    client->Close();
-                                  }
-                                  if (auto remote = remoteWeak.lock()) {
-                                    remote->Close();
-                                  }
-                                }
-                              }
-                            });
-    });
-
-    // start listening for incoming connections
-    server->Listen();
-
-    m_impl->servers[port] = server;
-  });
-}
-
-void PortForwarder::Remove(unsigned int port) {
-  m_impl->runner.ExecSync([&](uv::Loop& loop) {
-    if (auto server = m_impl->servers.lookup(port).lock()) {
-      server->Close();
-      m_impl->servers.erase(port);
-    }
-  });
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/SafeThread.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/SafeThread.cpp
index bbecc5c..ba1eba3 100644
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/SafeThread.cpp
+++ b/third_party/allwpilib/wpiutil/src/main/native/cpp/SafeThread.cpp
@@ -4,10 +4,50 @@
 
 #include "wpi/SafeThread.h"
 
+#include <atomic>
+
 using namespace wpi;
 
+// thread start/stop notifications for bindings that need to set up
+// per-thread state
+
+static void* DefaultOnThreadStart() {
+  return nullptr;
+}
+static void DefaultOnThreadEnd(void*) {}
+
+using OnThreadStartFn = void* (*)();
+using OnThreadEndFn = void (*)(void*);
+static std::atomic<int> gSafeThreadRefcount;
+static std::atomic<OnThreadStartFn> gOnSafeThreadStart{DefaultOnThreadStart};
+static std::atomic<OnThreadEndFn> gOnSafeThreadEnd{DefaultOnThreadEnd};
+
+namespace wpi::impl {
+void SetSafeThreadNotifiers(OnThreadStartFn OnStart, OnThreadEndFn OnEnd) {
+  if (gSafeThreadRefcount != 0) {
+    throw std::runtime_error(
+        "cannot set notifier while safe threads are running");
+  }
+  // Note: there's a race here, but if you're not calling this function on
+  // the main thread before you start anything else, you're using this function
+  // incorrectly
+  gOnSafeThreadStart = OnStart ? OnStart : DefaultOnThreadStart;
+  gOnSafeThreadEnd = OnEnd ? OnEnd : DefaultOnThreadEnd;
+}
+}  // namespace wpi::impl
+
+void SafeThread::Stop() {
+  m_active = false;
+  m_cond.notify_all();
+}
+
+void SafeThreadEvent::Stop() {
+  m_active = false;
+  m_stopEvent.Set();
+}
+
 detail::SafeThreadProxyBase::SafeThreadProxyBase(
-    std::shared_ptr<SafeThread> thr)
+    std::shared_ptr<SafeThreadBase> thr)
     : m_thread(std::move(thr)) {
   if (!m_thread) {
     return;
@@ -28,12 +68,18 @@
   }
 }
 
-void detail::SafeThreadOwnerBase::Start(std::shared_ptr<SafeThread> thr) {
+void detail::SafeThreadOwnerBase::Start(std::shared_ptr<SafeThreadBase> thr) {
   std::scoped_lock lock(m_mutex);
   if (auto thr = m_thread.lock()) {
     return;
   }
-  m_stdThread = std::thread([=] { thr->Main(); });
+  m_stdThread = std::thread([=] {
+    gSafeThreadRefcount++;
+    void* opaque = (gOnSafeThreadStart.load())();
+    thr->Main();
+    (gOnSafeThreadEnd.load())(opaque);
+    gSafeThreadRefcount--;
+  });
   thr->m_threadId = m_stdThread.get_id();
   m_thread = thr;
 }
@@ -41,8 +87,7 @@
 void detail::SafeThreadOwnerBase::Stop() {
   std::scoped_lock lock(m_mutex);
   if (auto thr = m_thread.lock()) {
-    thr->m_active = false;
-    thr->m_cond.notify_all();
+    thr->Stop();
     m_thread.reset();
   }
   if (m_stdThread.joinable()) {
@@ -56,8 +101,7 @@
     auto stdThread = std::move(m_stdThread);
     m_thread.reset();
     lock.unlock();
-    thr->m_active = false;
-    thr->m_cond.notify_all();
+    thr->Stop();
     stdThread.join();
   } else if (m_stdThread.joinable()) {
     m_stdThread.detach();
@@ -85,8 +129,8 @@
   return m_stdThread.native_handle();
 }
 
-std::shared_ptr<SafeThread> detail::SafeThreadOwnerBase::GetThreadSharedPtr()
-    const {
+std::shared_ptr<SafeThreadBase>
+detail::SafeThreadOwnerBase::GetThreadSharedPtr() const {
   std::scoped_lock lock(m_mutex);
   return m_thread.lock();
 }
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/SocketError.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/SocketError.cpp
deleted file mode 100644
index 3f08d1e..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/SocketError.cpp
+++ /dev/null
@@ -1,37 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/SocketError.h"
-
-#ifdef _WIN32
-#include <winsock2.h>
-#else
-#include <cerrno>
-#include <cstring>
-#endif
-
-namespace wpi {
-
-int SocketErrno() {
-#ifdef _WIN32
-  return WSAGetLastError();
-#else
-  return errno;
-#endif
-}
-
-std::string SocketStrerror(int code) {
-#ifdef _WIN32
-  LPSTR errstr = nullptr;
-  FormatMessage(FORMAT_MESSAGE_ALLOCATE_BUFFER | FORMAT_MESSAGE_FROM_SYSTEM, 0,
-                code, 0, (LPSTR)&errstr, 0, 0);
-  std::string rv(errstr);
-  LocalFree(errstr);
-  return rv;
-#else
-  return std::strerror(code);
-#endif
-}
-
-}  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/StringExtras.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/StringExtras.cpp
deleted file mode 100644
index 968ffc3..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/StringExtras.cpp
+++ /dev/null
@@ -1,360 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-//===-- StringExtras.cpp - Implement the StringExtras header --------------===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-//
-// This file implements the StringExtras.h header
-//
-//===----------------------------------------------------------------------===//
-
-#include "wpi/StringExtras.h"
-
-#include <algorithm>
-#include <cstdlib>
-#include <string_view>
-
-#include "wpi/SmallString.h"
-#include "wpi/SmallVector.h"
-
-// strncasecmp() is not available on non-POSIX systems, so define an
-// alternative function here.
-static int ascii_strncasecmp(const char* lhs, const char* rhs,
-                             size_t length) noexcept {
-  for (size_t i = 0; i < length; ++i) {
-    unsigned char lhc = wpi::toLower(lhs[i]);
-    unsigned char rhc = wpi::toLower(rhs[i]);
-    if (lhc != rhc) {
-      return lhc < rhc ? -1 : 1;
-    }
-  }
-  return 0;
-}
-
-int wpi::compare_lower(std::string_view lhs, std::string_view rhs) noexcept {
-  if (int Res = ascii_strncasecmp(lhs.data(), rhs.data(),
-                                  (std::min)(lhs.size(), rhs.size()))) {
-    return Res;
-  }
-  if (lhs.size() == rhs.size()) {
-    return 0;
-  }
-  return lhs.size() < rhs.size() ? -1 : 1;
-}
-
-std::string_view::size_type wpi::find_lower(
-    std::string_view str, char ch, std::string_view::size_type from) noexcept {
-  char lch = toLower(ch);
-  auto s = drop_front(str, from);
-  while (!s.empty()) {
-    if (toLower(s.front()) == lch) {
-      return str.size() - s.size();
-    }
-    s.remove_prefix(1);
-  }
-  return std::string_view::npos;
-}
-
-std::string_view::size_type wpi::find_lower(
-    std::string_view str, std::string_view other,
-    std::string_view::size_type from) noexcept {
-  auto s = substr(str, from);
-  while (s.size() >= other.size()) {
-    if (starts_with_lower(s, other)) {
-      return from;
-    }
-    s.remove_prefix(1);
-    ++from;
-  }
-  return std::string_view::npos;
-}
-
-std::string_view::size_type wpi::rfind_lower(
-    std::string_view str, char ch, std::string_view::size_type from) noexcept {
-  from = (std::min)(from, str.size());
-  auto data = str.data();
-  std::string_view::size_type i = from;
-  while (i != 0) {
-    --i;
-    if (toLower(data[i]) == toLower(ch)) {
-      return i;
-    }
-  }
-  return std::string_view::npos;
-}
-
-std::string_view::size_type wpi::rfind_lower(std::string_view str,
-                                             std::string_view other) noexcept {
-  std::string_view::size_type n = other.size();
-  if (n > str.size()) {
-    return std::string_view::npos;
-  }
-  for (size_t i = str.size() - n + 1, e = 0; i != e;) {
-    --i;
-    if (equals_lower(substr(str, i, n), other)) {
-      return i;
-    }
-  }
-  return std::string_view::npos;
-}
-
-bool wpi::starts_with_lower(std::string_view str,
-                            std::string_view prefix) noexcept {
-  return str.size() >= prefix.size() &&
-         ascii_strncasecmp(str.data(), prefix.data(), prefix.size()) == 0;
-}
-
-bool wpi::ends_with_lower(std::string_view str,
-                          std::string_view suffix) noexcept {
-  return str.size() >= suffix.size() &&
-         ascii_strncasecmp(str.data() + str.size() - suffix.size(),
-                           suffix.data(), suffix.size()) == 0;
-}
-
-void wpi::split(std::string_view str, SmallVectorImpl<std::string_view>& arr,
-                std::string_view separator, int maxSplit,
-                bool keepEmpty) noexcept {
-  std::string_view s = str;
-
-  // Count down from maxSplit. When maxSplit is -1, this will just split
-  // "forever". This doesn't support splitting more than 2^31 times
-  // intentionally; if we ever want that we can make maxSplit a 64-bit integer
-  // but that seems unlikely to be useful.
-  while (maxSplit-- != 0) {
-    auto idx = s.find(separator);
-    if (idx == std::string_view::npos) {
-      break;
-    }
-
-    // Push this split.
-    if (keepEmpty || idx > 0) {
-      arr.push_back(slice(s, 0, idx));
-    }
-
-    // Jump forward.
-    s = slice(s, idx + separator.size(), std::string_view::npos);
-  }
-
-  // Push the tail.
-  if (keepEmpty || !s.empty()) {
-    arr.push_back(s);
-  }
-}
-
-void wpi::split(std::string_view str, SmallVectorImpl<std::string_view>& arr,
-                char separator, int maxSplit, bool keepEmpty) noexcept {
-  std::string_view s = str;
-
-  // Count down from maxSplit. When maxSplit is -1, this will just split
-  // "forever". This doesn't support splitting more than 2^31 times
-  // intentionally; if we ever want that we can make maxSplit a 64-bit integer
-  // but that seems unlikely to be useful.
-  while (maxSplit-- != 0) {
-    size_t idx = s.find(separator);
-    if (idx == std::string_view::npos) {
-      break;
-    }
-
-    // Push this split.
-    if (keepEmpty || idx > 0) {
-      arr.push_back(slice(s, 0, idx));
-    }
-
-    // Jump forward.
-    s = slice(s, idx + 1, std::string_view::npos);
-  }
-
-  // Push the tail.
-  if (keepEmpty || !s.empty()) {
-    arr.push_back(s);
-  }
-}
-
-static unsigned GetAutoSenseRadix(std::string_view& str) noexcept {
-  if (str.empty()) {
-    return 10;
-  }
-
-  if (wpi::starts_with(str, "0x") || wpi::starts_with(str, "0X")) {
-    str.remove_prefix(2);
-    return 16;
-  }
-
-  if (wpi::starts_with(str, "0b") || wpi::starts_with(str, "0B")) {
-    str.remove_prefix(2);
-    return 2;
-  }
-
-  if (wpi::starts_with(str, "0o")) {
-    str.remove_prefix(2);
-    return 8;
-  }
-
-  if (str[0] == '0' && str.size() > 1 && wpi::isDigit(str[1])) {
-    str.remove_prefix(1);
-    return 8;
-  }
-
-  return 10;
-}
-
-bool wpi::detail::ConsumeUnsignedInteger(
-    std::string_view& str, unsigned radix,
-    unsigned long long& result) noexcept {  // NOLINT(runtime/int)
-  // Autosense radix if not specified.
-  if (radix == 0) {
-    radix = GetAutoSenseRadix(str);
-  }
-
-  // Empty strings (after the radix autosense) are invalid.
-  if (str.empty()) {
-    return true;
-  }
-
-  // Parse all the bytes of the string given this radix.  Watch for overflow.
-  std::string_view str2 = str;
-  result = 0;
-  while (!str2.empty()) {
-    unsigned charVal;
-    if (str2[0] >= '0' && str2[0] <= '9') {
-      charVal = str2[0] - '0';
-    } else if (str2[0] >= 'a' && str2[0] <= 'z') {
-      charVal = str2[0] - 'a' + 10;
-    } else if (str2[0] >= 'A' && str2[0] <= 'Z') {
-      charVal = str2[0] - 'A' + 10;
-    } else {
-      break;
-    }
-
-    // If the parsed value is larger than the integer radix, we cannot
-    // consume any more characters.
-    if (charVal >= radix) {
-      break;
-    }
-
-    // Add in this character.
-    unsigned long long prevResult = result;  // NOLINT(runtime/int)
-    result = result * radix + charVal;
-
-    // Check for overflow by shifting back and seeing if bits were lost.
-    if (result / radix < prevResult) {
-      return true;
-    }
-
-    str2.remove_prefix(1);
-  }
-
-  // We consider the operation a failure if no characters were consumed
-  // successfully.
-  if (str.size() == str2.size()) {
-    return true;
-  }
-
-  str = str2;
-  return false;
-}
-
-bool wpi::detail::ConsumeSignedInteger(
-    std::string_view& str, unsigned radix,
-    long long& result) noexcept {  // NOLINT(runtime/int)
-  unsigned long long ullVal;       // NOLINT(runtime/int)
-
-  // Handle positive strings first.
-  if (str.empty() || str.front() != '-') {
-    if (wpi::detail::ConsumeUnsignedInteger(str, radix, ullVal) ||
-        // Check for value so large it overflows a signed value.
-        static_cast<long long>(ullVal) < 0) {  // NOLINT(runtime/int)
-      return true;
-    }
-    result = ullVal;
-    return false;
-  }
-
-  // Get the positive part of the value.
-  std::string_view str2 = wpi::drop_front(str, 1);
-  if (wpi::detail::ConsumeUnsignedInteger(str2, radix, ullVal) ||
-      // Reject values so large they'd overflow as negative signed, but allow
-      // "-0".  This negates the unsigned so that the negative isn't undefined
-      // on signed overflow.
-      static_cast<long long>(-ullVal) > 0) {  // NOLINT(runtime/int)
-    return true;
-  }
-
-  str = str2;
-  result = -ullVal;
-  return false;
-}
-
-bool wpi::detail::GetAsUnsignedInteger(
-    std::string_view str, unsigned radix,
-    unsigned long long& result) noexcept {  // NOLINT(runtime/int)
-  if (wpi::detail::ConsumeUnsignedInteger(str, radix, result)) {
-    return true;
-  }
-
-  // For getAsUnsignedInteger, we require the whole string to be consumed or
-  // else we consider it a failure.
-  return !str.empty();
-}
-
-bool wpi::detail::GetAsSignedInteger(
-    std::string_view str, unsigned radix,
-    long long& result) noexcept {  // NOLINT(runtime/int)
-  if (wpi::detail::ConsumeSignedInteger(str, radix, result)) {
-    return true;
-  }
-
-  // For getAsSignedInteger, we require the whole string to be consumed or else
-  // we consider it a failure.
-  return !str.empty();
-}
-
-template <>
-std::optional<float> wpi::parse_float<float>(std::string_view str) noexcept {
-  if (str.empty()) {
-    return std::nullopt;
-  }
-  wpi::SmallString<32> storage{str};
-  char* end;
-  float val = std::strtof(storage.c_str(), &end);
-  if (*end != '\0') {
-    return std::nullopt;
-  }
-  return val;
-}
-
-template <>
-std::optional<double> wpi::parse_float<double>(std::string_view str) noexcept {
-  if (str.empty()) {
-    return std::nullopt;
-  }
-  wpi::SmallString<32> storage{str};
-  char* end;
-  double val = std::strtod(storage.c_str(), &end);
-  if (*end != '\0') {
-    return std::nullopt;
-  }
-  return val;
-}
-
-template <>
-std::optional<long double> wpi::parse_float<long double>(
-    std::string_view str) noexcept {
-  if (str.empty()) {
-    return std::nullopt;
-  }
-  wpi::SmallString<32> storage{str};
-  char* end;
-  long double val = std::strtold(storage.c_str(), &end);
-  if (*end != '\0') {
-    return std::nullopt;
-  }
-  return val;
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/Synchronization.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/Synchronization.cpp
index da97897..f9ac75b 100644
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/Synchronization.cpp
+++ b/third_party/allwpilib/wpiutil/src/main/native/cpp/Synchronization.cpp
@@ -5,6 +5,7 @@
 #include "wpi/Synchronization.h"
 
 #include <algorithm>
+#include <atomic>
 #include <cstring>
 #include <mutex>
 
@@ -16,6 +17,8 @@
 
 using namespace wpi;
 
+static std::atomic_bool gShutdown{false};
+
 namespace {
 
 struct State {
@@ -25,6 +28,8 @@
 };
 
 struct HandleManager {
+  ~HandleManager() { gShutdown = true; }
+
   wpi::mutex mutex;
   wpi::UidVector<int, 8> eventIds;
   wpi::UidVector<int, 8> semaphoreIds;
@@ -40,6 +45,9 @@
 
 WPI_EventHandle wpi::CreateEvent(bool manualReset, bool initialState) {
   auto& manager = GetManager();
+  if (gShutdown) {
+    return {};
+  }
   std::scoped_lock lock{manager.mutex};
 
   auto index = manager.eventIds.emplace_back(0);
@@ -61,6 +69,9 @@
   DestroySignalObject(handle);
 
   auto& manager = GetManager();
+  if (gShutdown) {
+    return;
+  }
   std::scoped_lock lock{manager.mutex};
   manager.eventIds.erase(handle & 0xffffff);
 }
@@ -83,6 +94,9 @@
 
 WPI_SemaphoreHandle wpi::CreateSemaphore(int initialCount, int maximumCount) {
   auto& manager = GetManager();
+  if (gShutdown) {
+    return {};
+  }
   std::scoped_lock lock{manager.mutex};
 
   auto index = manager.semaphoreIds.emplace_back(maximumCount);
@@ -104,6 +118,9 @@
   DestroySignalObject(handle);
 
   auto& manager = GetManager();
+  if (gShutdown) {
+    return;
+  }
   std::scoped_lock lock{manager.mutex};
   manager.eventIds.erase(handle & 0xffffff);
 }
@@ -119,6 +136,9 @@
   int index = handle & 0xffffff;
 
   auto& manager = GetManager();
+  if (gShutdown) {
+    return true;
+  }
   std::scoped_lock lock{manager.mutex};
   auto it = manager.states.find(handle);
   if (it == manager.states.end()) {
@@ -146,22 +166,26 @@
 bool wpi::WaitForObject(WPI_Handle handle, double timeout, bool* timedOut) {
   WPI_Handle signaledValue;
   auto signaled = WaitForObjects(
-      wpi::span(&handle, 1), wpi::span(&signaledValue, 1), timeout, timedOut);
+      std::span(&handle, 1), std::span(&signaledValue, 1), timeout, timedOut);
   if (signaled.empty()) {
     return false;
   }
   return (signaled[0] & 0x80000000ul) == 0;
 }
 
-wpi::span<WPI_Handle> wpi::WaitForObjects(wpi::span<const WPI_Handle> handles,
-                                          wpi::span<WPI_Handle> signaled) {
+std::span<WPI_Handle> wpi::WaitForObjects(std::span<const WPI_Handle> handles,
+                                          std::span<WPI_Handle> signaled) {
   return WaitForObjects(handles, signaled, -1, nullptr);
 }
 
-wpi::span<WPI_Handle> wpi::WaitForObjects(wpi::span<const WPI_Handle> handles,
-                                          wpi::span<WPI_Handle> signaled,
+std::span<WPI_Handle> wpi::WaitForObjects(std::span<const WPI_Handle> handles,
+                                          std::span<WPI_Handle> signaled,
                                           double timeout, bool* timedOut) {
   auto& manager = GetManager();
+  if (gShutdown) {
+    *timedOut = false;
+    return {};
+  }
   std::unique_lock lock{manager.mutex};
   wpi::condition_variable cv;
   bool addedWaiters = false;
@@ -240,6 +264,9 @@
 void wpi::CreateSignalObject(WPI_Handle handle, bool manualReset,
                              bool initialState) {
   auto& manager = GetManager();
+  if (gShutdown) {
+    return;
+  }
   std::scoped_lock lock{manager.mutex};
   auto& state = manager.states[handle];
   state.signaled = initialState ? 1 : 0;
@@ -248,6 +275,9 @@
 
 void wpi::SetSignalObject(WPI_Handle handle) {
   auto& manager = GetManager();
+  if (gShutdown) {
+    return;
+  }
   std::scoped_lock lock{manager.mutex};
   auto it = manager.states.find(handle);
   if (it == manager.states.end()) {
@@ -266,6 +296,9 @@
 
 void wpi::ResetSignalObject(WPI_Handle handle) {
   auto& manager = GetManager();
+  if (gShutdown) {
+    return;
+  }
   std::scoped_lock lock{manager.mutex};
   auto it = manager.states.find(handle);
   if (it != manager.states.end()) {
@@ -275,6 +308,9 @@
 
 void wpi::DestroySignalObject(WPI_Handle handle) {
   auto& manager = GetManager();
+  if (gShutdown) {
+    return;
+  }
   std::scoped_lock lock{manager.mutex};
 
   auto it = manager.states.find(handle);
@@ -332,8 +368,8 @@
 
 int WPI_WaitForObjects(const WPI_Handle* handles, int handles_count,
                        WPI_Handle* signaled) {
-  return wpi::WaitForObjects(wpi::span(handles, handles_count),
-                             wpi::span(signaled, handles_count))
+  return wpi::WaitForObjects(std::span(handles, handles_count),
+                             std::span(signaled, handles_count))
       .size();
 }
 
@@ -341,8 +377,8 @@
                               WPI_Handle* signaled, double timeout,
                               int* timed_out) {
   bool timedOutBool;
-  auto signaledResult = wpi::WaitForObjects(wpi::span(handles, handles_count),
-                                            wpi::span(signaled, handles_count),
+  auto signaledResult = wpi::WaitForObjects(std::span(handles, handles_count),
+                                            std::span(signaled, handles_count),
                                             timeout, &timedOutBool);
   *timed_out = timedOutBool ? 1 : 0;
   return signaledResult.size();
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/TCPAcceptor.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/TCPAcceptor.cpp
deleted file mode 100644
index 8d12ac3..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/TCPAcceptor.cpp
+++ /dev/null
@@ -1,210 +0,0 @@
-/*
-   TCPAcceptor.cpp
-
-   TCPAcceptor class definition. TCPAcceptor provides methods to passively
-   establish TCP/IP connections with clients.
-
-   ------------------------------------------
-
-   Copyright (c) 2013 [Vic Hargrave - http://vichargrave.com]
-
-   Licensed under the Apache License, Version 2.0 (the "License");
-   you may not use this file except in compliance with the License.
-   You may obtain a copy of the License at
-
-       http://www.apache.org/licenses/LICENSE-2.0
-
-   Unless required by applicable law or agreed to in writing, software
-   distributed under the License is distributed on an "AS IS" BASIS,
-   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-   See the License for the specific language governing permissions and
-   limitations under the License.
-*/
-
-#include "wpi/TCPAcceptor.h"
-
-#include <cstdio>
-#include <cstring>
-
-#ifdef _WIN32
-#define _WINSOCK_DEPRECATED_NO_WARNINGS
-#include <WinSock2.h>
-#include <Ws2tcpip.h>
-#pragma comment(lib, "Ws2_32.lib")
-#else
-#include <arpa/inet.h>
-#include <fcntl.h>
-#include <netinet/in.h>
-#include <unistd.h>
-#endif
-
-#include "wpi/Logger.h"
-#include "wpi/SmallString.h"
-#include "wpi/SocketError.h"
-
-using namespace wpi;
-
-TCPAcceptor::TCPAcceptor(int port, std::string_view address, Logger& logger)
-    : m_lsd(0),
-      m_port(port),
-      m_address(address),
-      m_listening(false),
-      m_logger(logger) {
-  m_shutdown = false;
-#ifdef _WIN32
-  WSAData wsaData;
-  WORD wVersionRequested = MAKEWORD(2, 2);
-  (void)WSAStartup(wVersionRequested, &wsaData);
-#endif
-}
-
-TCPAcceptor::~TCPAcceptor() {
-  if (m_lsd > 0) {
-    shutdown();
-#ifdef _WIN32
-    closesocket(m_lsd);
-#else
-    close(m_lsd);
-#endif
-  }
-#ifdef _WIN32
-  WSACleanup();
-#endif
-}
-
-int TCPAcceptor::start() {
-  if (m_listening) {
-    return 0;
-  }
-
-  m_lsd = socket(PF_INET, SOCK_STREAM, 0);
-  if (m_lsd < 0) {
-    WPI_ERROR(m_logger, "{}", "could not create socket");
-    return -1;
-  }
-  struct sockaddr_in address;
-
-  std::memset(&address, 0, sizeof(address));
-  address.sin_family = PF_INET;
-  if (m_address.size() > 0) {
-#ifdef _WIN32
-    SmallString<128> addr_copy(m_address);
-    addr_copy.push_back('\0');
-    int res = InetPton(PF_INET, addr_copy.data(), &(address.sin_addr));
-#else
-    int res = inet_pton(PF_INET, m_address.c_str(), &(address.sin_addr));
-#endif
-    if (res != 1) {
-      WPI_ERROR(m_logger, "could not resolve {} address", m_address);
-      return -1;
-    }
-  } else {
-    address.sin_addr.s_addr = INADDR_ANY;
-  }
-  address.sin_port = htons(m_port);
-
-#ifdef _WIN32
-  int optval = 1;
-  setsockopt(m_lsd, SOL_SOCKET, SO_EXCLUSIVEADDRUSE,
-             reinterpret_cast<char*>(&optval), sizeof optval);
-#else
-  int optval = 1;
-  setsockopt(m_lsd, SOL_SOCKET, SO_REUSEADDR, reinterpret_cast<char*>(&optval),
-             sizeof optval);
-#endif
-
-  int result = bind(m_lsd, reinterpret_cast<struct sockaddr*>(&address),
-                    sizeof(address));
-  if (result != 0) {
-    WPI_ERROR(m_logger, "bind() to port {} failed: {}", m_port,
-              SocketStrerror());
-    return result;
-  }
-
-  result = listen(m_lsd, 5);
-  if (result != 0) {
-    WPI_ERROR(m_logger, "listen() on port {} failed: {}", m_port,
-              SocketStrerror());
-    return result;
-  }
-  m_listening = true;
-  return result;
-}
-
-void TCPAcceptor::shutdown() {
-  m_shutdown = true;
-#ifdef _WIN32
-  ::shutdown(m_lsd, SD_BOTH);
-
-  // this is ugly, but the easiest way to do this
-  // force wakeup of accept() with a non-blocking connect to ourselves
-  struct sockaddr_in address;
-
-  std::memset(&address, 0, sizeof(address));
-  address.sin_family = PF_INET;
-  SmallString<128> addr_copy;
-  if (m_address.size() > 0)
-    addr_copy = m_address;
-  else
-    addr_copy = "127.0.0.1";
-  addr_copy.push_back('\0');
-  int size = sizeof(address);
-  if (WSAStringToAddress(addr_copy.data(), PF_INET, nullptr,
-                         (struct sockaddr*)&address, &size) != 0)
-    return;
-  address.sin_port = htons(m_port);
-
-  int result = -1, sd = socket(AF_INET, SOCK_STREAM, 0);
-  if (sd < 0)
-    return;
-
-  // Set socket to non-blocking
-  u_long mode = 1;
-  ioctlsocket(sd, FIONBIO, &mode);
-
-  // Try to connect
-  ::connect(sd, (struct sockaddr*)&address, sizeof(address));
-
-  // Close
-  ::closesocket(sd);
-
-#else
-  ::shutdown(m_lsd, SHUT_RDWR);
-  int nullfd = ::open("/dev/null", O_RDONLY);
-  if (nullfd >= 0) {
-    ::dup2(nullfd, m_lsd);
-    ::close(nullfd);
-  }
-#endif
-}
-
-std::unique_ptr<NetworkStream> TCPAcceptor::accept() {
-  if (!m_listening || m_shutdown) {
-    return nullptr;
-  }
-
-  struct sockaddr_in address;
-#ifdef _WIN32
-  int len = sizeof(address);
-#else
-  socklen_t len = sizeof(address);
-#endif
-  std::memset(&address, 0, sizeof(address));
-  int sd = ::accept(m_lsd, reinterpret_cast<struct sockaddr*>(&address), &len);
-  if (sd < 0) {
-    if (!m_shutdown) {
-      WPI_ERROR(m_logger, "accept() on port {} failed: {}", m_port,
-                SocketStrerror());
-    }
-    return nullptr;
-  }
-  if (m_shutdown) {
-#ifdef _WIN32
-    closesocket(sd);
-#else
-    close(sd);
-#endif
-    return nullptr;
-  }
-  return std::unique_ptr<NetworkStream>(new TCPStream(sd, &address));
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/TCPConnector.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/TCPConnector.cpp
deleted file mode 100644
index ed97962..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/TCPConnector.cpp
+++ /dev/null
@@ -1,218 +0,0 @@
-/*
-   TCPConnector.h
-
-   TCPConnector class definition. TCPConnector provides methods to actively
-   establish TCP/IP connections with a server.
-
-   ------------------------------------------
-
-   Copyright (c) 2013 [Vic Hargrave - http://vichargrave.com]
-
-   Licensed under the Apache License, Version 2.0 (the "License");
-   you may not use this file except in compliance with the License.
-   You may obtain a copy of the License at
-
-       http://www.apache.org/licenses/LICENSE-2.0
-
-   Unless required by applicable law or agreed to in writing, software
-   distributed under the License is distributed on an "AS IS" BASIS,
-   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-   See the License for the specific language governing permissions and
-   limitations under the License
-*/
-
-#include "wpi/TCPConnector.h"
-
-#include <fcntl.h>
-
-#include <cerrno>
-#include <cstdio>
-#include <cstring>
-
-#ifdef _WIN32
-#include <WS2tcpip.h>
-#include <WinSock2.h>
-#else
-#include <arpa/inet.h>
-#include <netdb.h>
-#include <netinet/in.h>
-#include <sys/select.h>
-#include <unistd.h>
-#endif
-
-#include "wpi/Logger.h"
-#include "wpi/SmallString.h"
-#include "wpi/SocketError.h"
-#include "wpi/TCPStream.h"
-
-using namespace wpi;
-
-static int ResolveHostName(const char* hostname, struct in_addr* addr) {
-  struct addrinfo hints;
-  struct addrinfo* res;
-
-  hints.ai_flags = 0;
-  hints.ai_family = AF_INET;
-  hints.ai_socktype = SOCK_STREAM;
-  hints.ai_protocol = 0;
-  hints.ai_addrlen = 0;
-  hints.ai_addr = nullptr;
-  hints.ai_canonname = nullptr;
-  hints.ai_next = nullptr;
-  int result = getaddrinfo(hostname, nullptr, &hints, &res);
-  if (result == 0) {
-    std::memcpy(
-        addr, &(reinterpret_cast<struct sockaddr_in*>(res->ai_addr)->sin_addr),
-        sizeof(struct in_addr));
-    freeaddrinfo(res);
-  }
-  return result;
-}
-
-std::unique_ptr<NetworkStream> TCPConnector::connect(const char* server,
-                                                     int port, Logger& logger,
-                                                     int timeout) {
-#ifdef _WIN32
-  struct WSAHelper {
-    WSAHelper() {
-      WSAData wsaData;
-      WORD wVersionRequested = MAKEWORD(2, 2);
-      WSAStartup(wVersionRequested, &wsaData);
-    }
-    ~WSAHelper() { WSACleanup(); }
-  };
-  static WSAHelper helper;
-#endif
-  struct sockaddr_in address;
-
-  std::memset(&address, 0, sizeof(address));
-  address.sin_family = AF_INET;
-  if (ResolveHostName(server, &(address.sin_addr)) != 0) {
-#ifdef _WIN32
-    SmallString<128> addr_copy(server);
-    addr_copy.push_back('\0');
-    int res = InetPton(PF_INET, addr_copy.data(), &(address.sin_addr));
-#else
-    int res = inet_pton(PF_INET, server, &(address.sin_addr));
-#endif
-    if (res != 1) {
-      WPI_ERROR(logger, "could not resolve {} address", server);
-      return nullptr;
-    }
-  }
-  address.sin_port = htons(port);
-
-  if (timeout == 0) {
-    int sd = socket(AF_INET, SOCK_STREAM, 0);
-    if (sd < 0) {
-      WPI_ERROR(logger, "{}", "could not create socket");
-      return nullptr;
-    }
-    if (::connect(sd, reinterpret_cast<struct sockaddr*>(&address),
-                  sizeof(address)) != 0) {
-      WPI_ERROR(logger, "connect() to {} port {} failed: {}", server, port,
-                SocketStrerror());
-#ifdef _WIN32
-      closesocket(sd);
-#else
-      ::close(sd);
-#endif
-      return nullptr;
-    }
-    return std::unique_ptr<NetworkStream>(new TCPStream(sd, &address));
-  }
-
-  fd_set sdset;
-  struct timeval tv;
-  socklen_t len;
-  int result = -1, valopt, sd = socket(AF_INET, SOCK_STREAM, 0);
-  if (sd < 0) {
-    WPI_ERROR(logger, "{}", "could not create socket");
-    return nullptr;
-  }
-
-// Set socket to non-blocking
-#ifdef _WIN32
-  u_long mode = 1;
-  if (ioctlsocket(sd, FIONBIO, &mode) == SOCKET_ERROR)
-    WPI_WARNING(logger, "could not set socket to non-blocking: {}",
-                SocketStrerror());
-#else
-  int arg;
-  arg = fcntl(sd, F_GETFL, nullptr);
-  if (arg < 0) {
-    WPI_WARNING(logger, "could not set socket to non-blocking: {}",
-                SocketStrerror());
-  } else {
-    arg |= O_NONBLOCK;
-    if (fcntl(sd, F_SETFL, arg) < 0) {
-      WPI_WARNING(logger, "could not set socket to non-blocking: {}",
-                  SocketStrerror());
-    }
-  }
-#endif
-
-  // Connect with time limit
-  if ((result = ::connect(sd, reinterpret_cast<struct sockaddr*>(&address),
-                          sizeof(address))) < 0) {
-    int my_errno = SocketErrno();
-#ifdef _WIN32
-    if (my_errno == WSAEWOULDBLOCK || my_errno == WSAEINPROGRESS) {
-#else
-    if (my_errno == EWOULDBLOCK || my_errno == EINPROGRESS) {
-#endif
-      tv.tv_sec = timeout;
-      tv.tv_usec = 0;
-      FD_ZERO(&sdset);
-      FD_SET(sd, &sdset);
-      if (select(sd + 1, nullptr, &sdset, nullptr, &tv) > 0) {
-        len = sizeof(int);
-        getsockopt(sd, SOL_SOCKET, SO_ERROR, reinterpret_cast<char*>(&valopt),
-                   &len);
-        if (valopt) {
-          WPI_ERROR(logger, "select() to {} port {} error {} - {}", server,
-                    port, valopt, SocketStrerror(valopt));
-        } else {
-          // connection established
-          result = 0;
-        }
-      } else {
-        WPI_INFO(logger, "connect() to {} port {} timed out", server, port);
-      }
-    } else {
-      WPI_ERROR(logger, "connect() to {} port {} error {} - {}", server, port,
-                SocketErrno(), SocketStrerror());
-    }
-  }
-
-// Return socket to blocking mode
-#ifdef _WIN32
-  mode = 0;
-  if (ioctlsocket(sd, FIONBIO, &mode) == SOCKET_ERROR)
-    WPI_WARNING(logger, "could not set socket to blocking: {}",
-                SocketStrerror());
-#else
-  arg = fcntl(sd, F_GETFL, nullptr);
-  if (arg < 0) {
-    WPI_WARNING(logger, "could not set socket to blocking: {}",
-                SocketStrerror());
-  } else {
-    arg &= (~O_NONBLOCK);
-    if (fcntl(sd, F_SETFL, arg) < 0) {
-      WPI_WARNING(logger, "could not set socket to blocking: {}",
-                  SocketStrerror());
-    }
-  }
-#endif
-
-  // Create stream object if connected, close if not.
-  if (result == -1) {
-#ifdef _WIN32
-    closesocket(sd);
-#else
-    ::close(sd);
-#endif
-    return nullptr;
-  }
-  return std::unique_ptr<NetworkStream>(new TCPStream(sd, &address));
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/TCPConnector_parallel.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/TCPConnector_parallel.cpp
deleted file mode 100644
index 26258cf..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/TCPConnector_parallel.cpp
+++ /dev/null
@@ -1,131 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/TCPConnector.h"  // NOLINT(build/include_order)
-
-#include <atomic>
-#include <chrono>
-#include <thread>
-#include <tuple>
-
-#include "wpi/SmallSet.h"
-#include "wpi/condition_variable.h"
-#include "wpi/mutex.h"
-
-using namespace wpi;
-
-// MSVC < 1900 doesn't have support for thread_local
-#if !defined(_MSC_VER) || _MSC_VER >= 1900
-// clang check for availability of thread_local
-#if !defined(__has_feature) || __has_feature(cxx_thread_local)
-#define HAVE_THREAD_LOCAL
-#endif
-#endif
-
-std::unique_ptr<NetworkStream> TCPConnector::connect_parallel(
-    span<const std::pair<const char*, int>> servers, Logger& logger,
-    int timeout) {
-  if (servers.empty()) {
-    return nullptr;
-  }
-
-  // structure to make sure we don't start duplicate workers
-  struct GlobalState {
-    wpi::mutex mtx;
-#ifdef HAVE_THREAD_LOCAL
-    SmallSet<std::pair<std::string, int>, 16> active;
-#else
-    SmallSet<std::tuple<std::thread::id, std::string, int>, 16> active;
-#endif
-  };
-#ifdef HAVE_THREAD_LOCAL
-  thread_local auto global = std::make_shared<GlobalState>();
-#else
-  static auto global = std::make_shared<GlobalState>();
-  auto this_id = std::this_thread::get_id();
-#endif
-  auto local = global;  // copy to an automatic variable for lambda capture
-
-  // structure shared between threads and this function
-  struct Result {
-    wpi::mutex mtx;
-    wpi::condition_variable cv;
-    std::unique_ptr<NetworkStream> stream;
-    std::atomic<unsigned int> count{0};
-    std::atomic<bool> done{false};
-  };
-  auto result = std::make_shared<Result>();
-
-  // start worker threads; this is I/O bound so we don't limit to # of procs
-  Logger* plogger = &logger;
-  unsigned int num_workers = 0;
-  for (const auto& server : servers) {
-    std::pair<std::string, int> server_copy{std::string{server.first},
-                                            server.second};
-#ifdef HAVE_THREAD_LOCAL
-    const auto& active_tracker = server_copy;
-#else
-    std::tuple<std::thread::id, std::string, int> active_tracker{
-        this_id, server_copy.first, server_copy.second};
-#endif
-
-    // don't start a new worker if we had a previously still-active connection
-    // attempt to the same server
-    {
-      std::scoped_lock lock(local->mtx);
-      if (local->active.count(active_tracker) > 0) {
-        continue;  // already in set
-      }
-    }
-
-    ++num_workers;
-
-    // start the worker
-    std::thread([=] {
-      if (!result->done) {
-        // add to global state
-        {
-          std::scoped_lock lock(local->mtx);
-          local->active.insert(active_tracker);
-        }
-
-        // try to connect
-        auto stream = connect(server_copy.first.c_str(), server_copy.second,
-                              *plogger, timeout);
-
-        // remove from global state
-        {
-          std::scoped_lock lock(local->mtx);
-          local->active.erase(active_tracker);
-        }
-
-        // successful connection
-        if (stream) {
-          std::scoped_lock lock(result->mtx);
-          if (!result->done.exchange(true)) {
-            result->stream = std::move(stream);
-          }
-        }
-      }
-      ++result->count;
-      result->cv.notify_all();
-    }).detach();
-  }
-
-  // wait for a result, timeout, or all finished
-  std::unique_lock lock(result->mtx);
-  if (timeout == 0) {
-    result->cv.wait(
-        lock, [&] { return result->stream || result->count >= num_workers; });
-  } else {
-    auto timeout_time =
-        std::chrono::steady_clock::now() + std::chrono::seconds(timeout);
-    result->cv.wait_until(lock, timeout_time, [&] {
-      return result->stream || result->count >= num_workers;
-    });
-  }
-
-  // no need to wait for remaining worker threads; shared_ptr will clean up
-  return std::move(result->stream);
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/TCPStream.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/TCPStream.cpp
deleted file mode 100644
index 4567161..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/TCPStream.cpp
+++ /dev/null
@@ -1,230 +0,0 @@
-/*
-   TCPStream.h
-
-   TCPStream class definition. TCPStream provides methods to transfer
-   data between peers over a TCP/IP connection.
-
-   ------------------------------------------
-
-   Copyright (c) 2013 [Vic Hargrave - http://vichargrave.com]
-
-   Licensed under the Apache License, Version 2.0 (the "License");
-   you may not use this file except in compliance with the License.
-   You may obtain a copy of the License at
-
-       http://www.apache.org/licenses/LICENSE-2.0
-
-   Unless required by applicable law or agreed to in writing, software
-   distributed under the License is distributed on an "AS IS" BASIS,
-   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-   See the License for the specific language governing permissions and
-   limitations under the License.
-*/
-
-#include "wpi/TCPStream.h"
-
-#include <fcntl.h>
-
-#ifdef _WIN32
-#include <winsock2.h>
-#include <ws2tcpip.h>
-#else
-#include <arpa/inet.h>
-#include <netinet/tcp.h>
-#include <unistd.h>
-#endif
-
-#include <cerrno>
-
-using namespace wpi;
-
-TCPStream::TCPStream(int sd, sockaddr_in* address)
-    : m_sd(sd), m_blocking(true) {
-  char ip[50];
-#ifdef _WIN32
-  InetNtop(PF_INET, &(address->sin_addr.s_addr), ip, sizeof(ip) - 1);
-#else
-  inet_ntop(PF_INET, reinterpret_cast<in_addr*>(&(address->sin_addr.s_addr)),
-            ip, sizeof(ip) - 1);
-#ifdef SO_NOSIGPIPE
-  // disable SIGPIPE on Mac OS X
-  int set = 1;
-  setsockopt(m_sd, SOL_SOCKET, SO_NOSIGPIPE, reinterpret_cast<char*>(&set),
-             sizeof set);
-#endif
-#endif
-  m_peerIP = ip;
-  m_peerPort = ntohs(address->sin_port);
-}
-
-TCPStream::~TCPStream() {
-  close();
-}
-
-size_t TCPStream::send(const char* buffer, size_t len, Error* err) {
-  if (m_sd < 0) {
-    *err = kConnectionClosed;
-    return 0;
-  }
-#ifdef _WIN32
-  WSABUF wsaBuf;
-  wsaBuf.buf = const_cast<char*>(buffer);
-  wsaBuf.len = (ULONG)len;
-  DWORD rv;
-  bool result = true;
-  while (WSASend(m_sd, &wsaBuf, 1, &rv, 0, nullptr, nullptr) == SOCKET_ERROR) {
-    if (WSAGetLastError() != WSAEWOULDBLOCK) {
-      result = false;
-      break;
-    }
-    if (!m_blocking) {
-      *err = kWouldBlock;
-      return 0;
-    }
-    Sleep(1);
-  }
-  if (!result) {
-    char Buffer[128];
-#ifdef _MSC_VER
-    sprintf_s(Buffer, "Send() failed: WSA error=%d\n", WSAGetLastError());
-#else
-    std::snprintf(Buffer, sizeof(Buffer), "Send() failed: WSA error=%d\n",
-                  WSAGetLastError());
-#endif
-    OutputDebugStringA(Buffer);
-    *err = kConnectionReset;
-    return 0;
-  }
-#else
-#ifdef MSG_NOSIGNAL
-  // disable SIGPIPE on Linux
-  ssize_t rv = ::send(m_sd, buffer, len, MSG_NOSIGNAL);
-#else
-  ssize_t rv = ::send(m_sd, buffer, len, 0);
-#endif
-  if (rv < 0) {
-    if (!m_blocking && (errno == EAGAIN || errno == EWOULDBLOCK)) {
-      *err = kWouldBlock;
-    } else {
-      *err = kConnectionReset;
-    }
-    return 0;
-  }
-#endif
-  return static_cast<size_t>(rv);
-}
-
-size_t TCPStream::receive(char* buffer, size_t len, Error* err, int timeout) {
-  if (m_sd < 0) {
-    *err = kConnectionClosed;
-    return 0;
-  }
-#ifdef _WIN32
-  int rv;
-#else
-  ssize_t rv;
-#endif
-  if (timeout <= 0) {
-#ifdef _WIN32
-    rv = recv(m_sd, buffer, len, 0);
-#else
-    rv = read(m_sd, buffer, len);
-#endif
-  } else if (WaitForReadEvent(timeout)) {
-#ifdef _WIN32
-    rv = recv(m_sd, buffer, len, 0);
-#else
-    rv = read(m_sd, buffer, len);
-#endif
-  } else {
-    *err = kConnectionTimedOut;
-    return 0;
-  }
-  if (rv < 0) {
-#ifdef _WIN32
-    if (!m_blocking && WSAGetLastError() == WSAEWOULDBLOCK) {
-#else
-    if (!m_blocking && (errno == EAGAIN || errno == EWOULDBLOCK)) {
-#endif
-      *err = kWouldBlock;
-    } else {
-      *err = kConnectionReset;
-    }
-    return 0;
-  }
-  return static_cast<size_t>(rv);
-}
-
-void TCPStream::close() {
-  if (m_sd >= 0) {
-#ifdef _WIN32
-    ::shutdown(m_sd, SD_BOTH);
-    closesocket(m_sd);
-#else
-    ::shutdown(m_sd, SHUT_RDWR);
-    ::close(m_sd);
-#endif
-  }
-  m_sd = -1;
-}
-
-std::string_view TCPStream::getPeerIP() const {
-  return m_peerIP;
-}
-
-int TCPStream::getPeerPort() const {
-  return m_peerPort;
-}
-
-void TCPStream::setNoDelay() {
-  if (m_sd < 0) {
-    return;
-  }
-  int optval = 1;
-  setsockopt(m_sd, IPPROTO_TCP, TCP_NODELAY, reinterpret_cast<char*>(&optval),
-             sizeof optval);
-}
-
-bool TCPStream::setBlocking(bool enabled) {
-  if (m_sd < 0) {
-    return true;  // silently accept
-  }
-#ifdef _WIN32
-  u_long mode = enabled ? 0 : 1;
-  if (ioctlsocket(m_sd, FIONBIO, &mode) == SOCKET_ERROR) {
-    return false;
-  }
-#else
-  int flags = fcntl(m_sd, F_GETFL, nullptr);
-  if (flags < 0) {
-    return false;
-  }
-  if (enabled) {
-    flags &= ~O_NONBLOCK;
-  } else {
-    flags |= O_NONBLOCK;
-  }
-  if (fcntl(m_sd, F_SETFL, flags) < 0) {
-    return false;
-  }
-#endif
-  return true;
-}
-
-int TCPStream::getNativeHandle() const {
-  return m_sd;
-}
-
-bool TCPStream::WaitForReadEvent(int timeout) {
-  fd_set sdset;
-  struct timeval tv;
-
-  tv.tv_sec = timeout;
-  tv.tv_usec = 0;
-  FD_ZERO(&sdset);
-  FD_SET(m_sd, &sdset);
-  if (select(m_sd + 1, &sdset, nullptr, nullptr, &tv) > 0) {
-    return true;
-  }
-  return false;
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/UDPClient.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/UDPClient.cpp
deleted file mode 100644
index 108ef54..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/UDPClient.cpp
+++ /dev/null
@@ -1,248 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/UDPClient.h"
-
-#ifdef _WIN32
-#include <WinSock2.h>
-#include <Ws2tcpip.h>
-#pragma comment(lib, "Ws2_32.lib")
-#else
-#include <arpa/inet.h>
-#include <fcntl.h>
-#include <netinet/in.h>
-#include <unistd.h>
-#endif
-
-#include "wpi/Logger.h"
-#include "wpi/SmallString.h"
-#include "wpi/SocketError.h"
-
-using namespace wpi;
-
-UDPClient::UDPClient(Logger& logger) : UDPClient("", logger) {}
-
-UDPClient::UDPClient(std::string_view address, Logger& logger)
-    : m_lsd(0), m_port(0), m_address(address), m_logger(logger) {}
-
-UDPClient::UDPClient(UDPClient&& other)
-    : m_lsd(other.m_lsd),
-      m_port(other.m_port),
-      m_address(std::move(other.m_address)),
-      m_logger(other.m_logger) {
-  other.m_lsd = 0;
-  other.m_port = 0;
-}
-
-UDPClient::~UDPClient() {
-  if (m_lsd > 0) {
-    shutdown();
-  }
-}
-
-UDPClient& UDPClient::operator=(UDPClient&& other) {
-  if (this == &other) {
-    return *this;
-  }
-  shutdown();
-  m_logger = other.m_logger;
-  m_lsd = other.m_lsd;
-  m_address = std::move(other.m_address);
-  m_port = other.m_port;
-  other.m_lsd = 0;
-  other.m_port = 0;
-  return *this;
-}
-
-int UDPClient::start() {
-  return start(0);
-}
-
-int UDPClient::start(int port) {
-  if (m_lsd > 0) {
-    return 0;
-  }
-
-#ifdef _WIN32
-  WSAData wsaData;
-  WORD wVersionRequested = MAKEWORD(2, 2);
-  WSAStartup(wVersionRequested, &wsaData);
-#endif
-
-  m_lsd = socket(AF_INET, SOCK_DGRAM, 0);
-
-  if (m_lsd < 0) {
-    WPI_ERROR(m_logger, "{}", "could not create socket");
-    return -1;
-  }
-
-  struct sockaddr_in addr;
-  std::memset(&addr, 0, sizeof(addr));
-  addr.sin_family = AF_INET;
-  if (m_address.size() > 0) {
-#ifdef _WIN32
-    SmallString<128> addr_copy(m_address);
-    addr_copy.push_back('\0');
-    int res = InetPton(PF_INET, addr_copy.data(), &(addr.sin_addr));
-#else
-    int res = inet_pton(PF_INET, m_address.c_str(), &(addr.sin_addr));
-#endif
-    if (res != 1) {
-      WPI_ERROR(m_logger, "could not resolve {} address", m_address);
-      return -1;
-    }
-  } else {
-    addr.sin_addr.s_addr = INADDR_ANY;
-  }
-  addr.sin_port = htons(port);
-
-  if (port != 0) {
-#ifdef _WIN32
-    int optval = 1;
-    setsockopt(m_lsd, SOL_SOCKET, SO_EXCLUSIVEADDRUSE,
-               reinterpret_cast<char*>(&optval), sizeof optval);
-#else
-    int optval = 1;
-    setsockopt(m_lsd, SOL_SOCKET, SO_REUSEADDR,
-               reinterpret_cast<char*>(&optval), sizeof optval);
-#endif
-  }
-
-  int result = bind(m_lsd, reinterpret_cast<sockaddr*>(&addr), sizeof(addr));
-  if (result != 0) {
-    WPI_ERROR(m_logger, "bind() failed: {}", SocketStrerror());
-    return result;
-  }
-  m_port = port;
-  return 0;
-}
-
-void UDPClient::shutdown() {
-  if (m_lsd > 0) {
-#ifdef _WIN32
-    ::shutdown(m_lsd, SD_BOTH);
-    closesocket(m_lsd);
-    WSACleanup();
-#else
-    ::shutdown(m_lsd, SHUT_RDWR);
-    close(m_lsd);
-#endif
-    m_lsd = 0;
-    m_port = 0;
-  }
-}
-
-int UDPClient::send(span<const uint8_t> data, std::string_view server,
-                    int port) {
-  // server must be a resolvable IP address
-  struct sockaddr_in addr;
-  std::memset(&addr, 0, sizeof(addr));
-  addr.sin_family = AF_INET;
-  SmallString<128> remoteAddr{server};
-  if (remoteAddr.empty()) {
-    WPI_ERROR(m_logger, "{}", "server must be passed");
-    return -1;
-  }
-
-#ifdef _WIN32
-  int res = InetPton(AF_INET, remoteAddr.c_str(), &(addr.sin_addr));
-#else
-  int res = inet_pton(AF_INET, remoteAddr.c_str(), &(addr.sin_addr));
-#endif
-  if (res != 1) {
-    WPI_ERROR(m_logger, "could not resolve {} address", server);
-    return -1;
-  }
-  addr.sin_port = htons(port);
-
-  // sendto should not block
-  int result =
-      sendto(m_lsd, reinterpret_cast<const char*>(data.data()), data.size(), 0,
-             reinterpret_cast<sockaddr*>(&addr), sizeof(addr));
-  return result;
-}
-
-int UDPClient::send(std::string_view data, std::string_view server, int port) {
-  // server must be a resolvable IP address
-  struct sockaddr_in addr;
-  std::memset(&addr, 0, sizeof(addr));
-  addr.sin_family = AF_INET;
-  SmallString<128> remoteAddr{server};
-  if (remoteAddr.empty()) {
-    WPI_ERROR(m_logger, "{}", "server must be passed");
-    return -1;
-  }
-
-#ifdef _WIN32
-  int res = InetPton(AF_INET, remoteAddr.c_str(), &(addr.sin_addr));
-#else
-  int res = inet_pton(AF_INET, remoteAddr.c_str(), &(addr.sin_addr));
-#endif
-  if (res != 1) {
-    WPI_ERROR(m_logger, "could not resolve {} address", server);
-    return -1;
-  }
-  addr.sin_port = htons(port);
-
-  // sendto should not block
-  int result = sendto(m_lsd, data.data(), data.size(), 0,
-                      reinterpret_cast<sockaddr*>(&addr), sizeof(addr));
-  return result;
-}
-
-int UDPClient::receive(uint8_t* data_received, int receive_len) {
-  if (m_port == 0) {
-    return -1;  // return if not receiving
-  }
-  return recv(m_lsd, reinterpret_cast<char*>(data_received), receive_len, 0);
-}
-
-int UDPClient::receive(uint8_t* data_received, int receive_len,
-                       SmallVectorImpl<char>* addr_received,
-                       int* port_received) {
-  if (m_port == 0) {
-    return -1;  // return if not receiving
-  }
-
-  struct sockaddr_in remote;
-  socklen_t remote_len = sizeof(remote);
-  std::memset(&remote, 0, sizeof(remote));
-
-  int result =
-      recvfrom(m_lsd, reinterpret_cast<char*>(data_received), receive_len, 0,
-               reinterpret_cast<sockaddr*>(&remote), &remote_len);
-
-  char ip[50];
-#ifdef _WIN32
-  InetNtop(PF_INET, &(remote.sin_addr.s_addr), ip, sizeof(ip) - 1);
-#else
-  inet_ntop(PF_INET, reinterpret_cast<in_addr*>(&(remote.sin_addr.s_addr)), ip,
-            sizeof(ip) - 1);
-#endif
-
-  ip[49] = '\0';
-  int addr_len = std::strlen(ip);
-  addr_received->clear();
-  addr_received->append(&ip[0], &ip[addr_len]);
-
-  *port_received = ntohs(remote.sin_port);
-
-  return result;
-}
-
-int UDPClient::set_timeout(double timeout) {
-  if (timeout < 0) {
-    return -1;
-  }
-  struct timeval tv;
-  tv.tv_sec = timeout;             // truncating will give seconds
-  timeout -= tv.tv_sec;            // remove seconds portion
-  tv.tv_usec = timeout * 1000000;  // fractions of a second to us
-  int ret = setsockopt(m_lsd, SOL_SOCKET, SO_RCVTIMEO,
-                       reinterpret_cast<char*>(&tv), sizeof(tv));
-  if (ret < 0) {
-    WPI_ERROR(m_logger, "{}", "set timeout failed");
-  }
-  return ret;
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/WebSocket.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/WebSocket.cpp
deleted file mode 100644
index 4bb49d3..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/WebSocket.cpp
+++ /dev/null
@@ -1,656 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/WebSocket.h"
-
-#include <random>
-
-#include "fmt/format.h"
-#include "wpi/Base64.h"
-#include "wpi/HttpParser.h"
-#include "wpi/SmallString.h"
-#include "wpi/SmallVector.h"
-#include "wpi/StringExtras.h"
-#include "wpi/raw_uv_ostream.h"
-#include "wpi/sha1.h"
-#include "wpi/uv/Stream.h"
-
-using namespace wpi;
-
-namespace {
-class WebSocketWriteReq : public uv::WriteReq {
- public:
-  explicit WebSocketWriteReq(
-      std::function<void(span<uv::Buffer>, uv::Error)> callback)
-      : m_callback{std::move(callback)} {
-    finish.connect([this](uv::Error err) {
-      span<uv::Buffer> bufs{m_bufs};
-      for (auto&& buf : bufs.subspan(0, m_startUser)) {
-        buf.Deallocate();
-      }
-      m_callback(bufs.subspan(m_startUser), err);
-    });
-  }
-
-  std::function<void(span<uv::Buffer>, uv::Error)> m_callback;
-  SmallVector<uv::Buffer, 4> m_bufs;
-  size_t m_startUser;
-};
-}  // namespace
-
-class WebSocket::ClientHandshakeData {
- public:
-  ClientHandshakeData() {
-    // key is a random nonce
-    static std::random_device rd;
-    static std::default_random_engine gen{rd()};
-    std::uniform_int_distribution<unsigned int> dist(0, 255);
-    char nonce[16];  // the nonce sent to the server
-    for (char& v : nonce) {
-      v = static_cast<char>(dist(gen));
-    }
-    raw_svector_ostream os(key);
-    Base64Encode(os, {nonce, 16});
-  }
-  ~ClientHandshakeData() {
-    if (auto t = timer.lock()) {
-      t->Stop();
-      t->Close();
-    }
-  }
-
-  SmallString<64> key;                       // the key sent to the server
-  SmallVector<std::string, 2> protocols;     // valid protocols
-  HttpParser parser{HttpParser::kResponse};  // server response parser
-  bool hasUpgrade = false;
-  bool hasConnection = false;
-  bool hasAccept = false;
-  bool hasProtocol = false;
-
-  std::weak_ptr<uv::Timer> timer;
-};
-
-static std::string_view AcceptHash(std::string_view key,
-                                   SmallVectorImpl<char>& buf) {
-  SHA1 hash;
-  hash.Update(key);
-  hash.Update("258EAFA5-E914-47DA-95CA-C5AB0DC85B11");
-  SmallString<64> hashBuf;
-  return Base64Encode(hash.RawFinal(hashBuf), buf);
-}
-
-WebSocket::WebSocket(uv::Stream& stream, bool server, const private_init&)
-    : m_stream{stream}, m_server{server} {
-  // Connect closed and error signals to ourselves
-  m_stream.closed.connect([this]() { SetClosed(1006, "handle closed"); });
-  m_stream.error.connect([this](uv::Error err) {
-    Terminate(1006, fmt::format("stream error: {}", err.name()));
-  });
-
-  // Start reading
-  m_stream.StopRead();  // we may have been reading
-  m_stream.StartRead();
-  m_stream.data.connect(
-      [this](uv::Buffer& buf, size_t size) { HandleIncoming(buf, size); });
-  m_stream.end.connect(
-      [this]() { Terminate(1006, "remote end closed connection"); });
-}
-
-WebSocket::~WebSocket() = default;
-
-std::shared_ptr<WebSocket> WebSocket::CreateClient(
-    uv::Stream& stream, std::string_view uri, std::string_view host,
-    span<const std::string_view> protocols, const ClientOptions& options) {
-  auto ws = std::make_shared<WebSocket>(stream, false, private_init{});
-  stream.SetData(ws);
-  ws->StartClient(uri, host, protocols, options);
-  return ws;
-}
-
-std::shared_ptr<WebSocket> WebSocket::CreateServer(uv::Stream& stream,
-                                                   std::string_view key,
-                                                   std::string_view version,
-                                                   std::string_view protocol) {
-  auto ws = std::make_shared<WebSocket>(stream, true, private_init{});
-  stream.SetData(ws);
-  ws->StartServer(key, version, protocol);
-  return ws;
-}
-
-void WebSocket::Close(uint16_t code, std::string_view reason) {
-  SendClose(code, reason);
-  if (m_state != FAILED && m_state != CLOSED) {
-    m_state = CLOSING;
-  }
-}
-
-void WebSocket::Fail(uint16_t code, std::string_view reason) {
-  if (m_state == FAILED || m_state == CLOSED) {
-    return;
-  }
-  SendClose(code, reason);
-  SetClosed(code, reason, true);
-  Shutdown();
-}
-
-void WebSocket::Terminate(uint16_t code, std::string_view reason) {
-  if (m_state == FAILED || m_state == CLOSED) {
-    return;
-  }
-  SetClosed(code, reason);
-  Shutdown();
-}
-
-void WebSocket::StartClient(std::string_view uri, std::string_view host,
-                            span<const std::string_view> protocols,
-                            const ClientOptions& options) {
-  // Create client handshake data
-  m_clientHandshake = std::make_unique<ClientHandshakeData>();
-
-  // Build client request
-  SmallVector<uv::Buffer, 4> bufs;
-  raw_uv_ostream os{bufs, 4096};
-
-  os << "GET " << uri << " HTTP/1.1\r\n";
-  os << "Host: " << host << "\r\n";
-  os << "Upgrade: websocket\r\n";
-  os << "Connection: Upgrade\r\n";
-  os << "Sec-WebSocket-Key: " << m_clientHandshake->key << "\r\n";
-  os << "Sec-WebSocket-Version: 13\r\n";
-
-  // protocols (if provided)
-  if (!protocols.empty()) {
-    os << "Sec-WebSocket-Protocol: ";
-    bool first = true;
-    for (auto protocol : protocols) {
-      if (!first) {
-        os << ", ";
-      } else {
-        first = false;
-      }
-      os << protocol;
-      // also save for later checking against server response
-      m_clientHandshake->protocols.emplace_back(protocol);
-    }
-    os << "\r\n";
-  }
-
-  // other headers
-  for (auto&& header : options.extraHeaders) {
-    os << header.first << ": " << header.second << "\r\n";
-  }
-
-  // finish headers
-  os << "\r\n";
-
-  // Send client request
-  m_stream.Write(bufs, [](auto bufs, uv::Error) {
-    for (auto& buf : bufs) {
-      buf.Deallocate();
-    }
-  });
-
-  // Set up client response handling
-  m_clientHandshake->parser.status.connect([this](std::string_view status) {
-    unsigned int code = m_clientHandshake->parser.GetStatusCode();
-    if (code != 101) {
-      Terminate(code, status);
-    }
-  });
-  m_clientHandshake->parser.header.connect(
-      [this](std::string_view name, std::string_view value) {
-        value = trim(value);
-        if (equals_lower(name, "upgrade")) {
-          if (!equals_lower(value, "websocket")) {
-            return Terminate(1002, "invalid upgrade response value");
-          }
-          m_clientHandshake->hasUpgrade = true;
-        } else if (equals_lower(name, "connection")) {
-          if (!equals_lower(value, "upgrade")) {
-            return Terminate(1002, "invalid connection response value");
-          }
-          m_clientHandshake->hasConnection = true;
-        } else if (equals_lower(name, "sec-websocket-accept")) {
-          // Check against expected response
-          SmallString<64> acceptBuf;
-          if (!equals(value, AcceptHash(m_clientHandshake->key, acceptBuf))) {
-            return Terminate(1002, "invalid accept key");
-          }
-          m_clientHandshake->hasAccept = true;
-        } else if (equals_lower(name, "sec-websocket-extensions")) {
-          // No extensions are supported
-          if (!value.empty()) {
-            return Terminate(1010, "unsupported extension");
-          }
-        } else if (equals_lower(name, "sec-websocket-protocol")) {
-          // Make sure it was one of the provided protocols
-          bool match = false;
-          for (auto&& protocol : m_clientHandshake->protocols) {
-            if (equals_lower(value, protocol)) {
-              match = true;
-              break;
-            }
-          }
-          if (!match) {
-            return Terminate(1003, "unsupported protocol");
-          }
-          m_clientHandshake->hasProtocol = true;
-          m_protocol = value;
-        }
-      });
-  m_clientHandshake->parser.headersComplete.connect([this](bool) {
-    if (!m_clientHandshake->hasUpgrade || !m_clientHandshake->hasConnection ||
-        !m_clientHandshake->hasAccept ||
-        (!m_clientHandshake->hasProtocol &&
-         !m_clientHandshake->protocols.empty())) {
-      return Terminate(1002, "invalid response");
-    }
-    if (m_state == CONNECTING) {
-      m_state = OPEN;
-      open(m_protocol);
-    }
-  });
-
-  // Start handshake timer if a timeout was specified
-  if (options.handshakeTimeout != (uv::Timer::Time::max)()) {
-    auto timer = uv::Timer::Create(m_stream.GetLoopRef());
-    timer->timeout.connect(
-        [this]() { Terminate(1006, "connection timed out"); });
-    timer->Start(options.handshakeTimeout);
-    m_clientHandshake->timer = timer;
-  }
-}
-
-void WebSocket::StartServer(std::string_view key, std::string_view version,
-                            std::string_view protocol) {
-  m_protocol = protocol;
-
-  // Build server response
-  SmallVector<uv::Buffer, 4> bufs;
-  raw_uv_ostream os{bufs, 4096};
-
-  // Handle unsupported version
-  if (version != "13") {
-    os << "HTTP/1.1 426 Upgrade Required\r\n";
-    os << "Upgrade: WebSocket\r\n";
-    os << "Sec-WebSocket-Version: 13\r\n\r\n";
-    m_stream.Write(bufs, [this](auto bufs, uv::Error) {
-      for (auto& buf : bufs) {
-        buf.Deallocate();
-      }
-      // XXX: Should we support sending a new handshake on the same connection?
-      // XXX: "this->" is required by GCC 5.5 (bug)
-      this->Terminate(1003, "unsupported protocol version");
-    });
-    return;
-  }
-
-  os << "HTTP/1.1 101 Switching Protocols\r\n";
-  os << "Upgrade: websocket\r\n";
-  os << "Connection: Upgrade\r\n";
-
-  // accept hash
-  SmallString<64> acceptBuf;
-  os << "Sec-WebSocket-Accept: " << AcceptHash(key, acceptBuf) << "\r\n";
-
-  if (!protocol.empty()) {
-    os << "Sec-WebSocket-Protocol: " << protocol << "\r\n";
-  }
-
-  // end headers
-  os << "\r\n";
-
-  // Send server response
-  m_stream.Write(bufs, [this](auto bufs, uv::Error) {
-    for (auto& buf : bufs) {
-      buf.Deallocate();
-    }
-    if (m_state == CONNECTING) {
-      m_state = OPEN;
-      open(m_protocol);
-    }
-  });
-}
-
-void WebSocket::SendClose(uint16_t code, std::string_view reason) {
-  SmallVector<uv::Buffer, 4> bufs;
-  if (code != 1005) {
-    raw_uv_ostream os{bufs, 4096};
-    const uint8_t codeMsb[] = {static_cast<uint8_t>((code >> 8) & 0xff),
-                               static_cast<uint8_t>(code & 0xff)};
-    os << span{codeMsb};
-    os << reason;
-  }
-  Send(kFlagFin | kOpClose, bufs, [](auto bufs, uv::Error) {
-    for (auto&& buf : bufs) {
-      buf.Deallocate();
-    }
-  });
-}
-
-void WebSocket::SetClosed(uint16_t code, std::string_view reason, bool failed) {
-  if (m_state == FAILED || m_state == CLOSED) {
-    return;
-  }
-  m_state = failed ? FAILED : CLOSED;
-  closed(code, reason);
-}
-
-void WebSocket::Shutdown() {
-  m_stream.Shutdown([this] { m_stream.Close(); });
-}
-
-void WebSocket::HandleIncoming(uv::Buffer& buf, size_t size) {
-  // ignore incoming data if we're failed or closed
-  if (m_state == FAILED || m_state == CLOSED) {
-    return;
-  }
-
-  std::string_view data{buf.base, size};
-
-  // Handle connecting state (mainly on client)
-  if (m_state == CONNECTING) {
-    if (m_clientHandshake) {
-      data = m_clientHandshake->parser.Execute(data);
-      // check for parser failure
-      if (m_clientHandshake->parser.HasError()) {
-        return Terminate(1003, "invalid response");
-      }
-      if (m_state != OPEN) {
-        return;  // not done with handshake yet
-      }
-
-      // we're done with the handshake, so release its memory
-      m_clientHandshake.reset();
-
-      // fall through to process additional data after handshake
-    } else {
-      return Terminate(1003, "got data on server before response");
-    }
-  }
-
-  // Message processing
-  while (!data.empty()) {
-    if (m_frameSize == UINT64_MAX) {
-      // Need at least two bytes to determine header length
-      if (m_header.size() < 2u) {
-        size_t toCopy = (std::min)(2u - m_header.size(), data.size());
-        m_header.append(data.data(), data.data() + toCopy);
-        data.remove_prefix(toCopy);
-        if (m_header.size() < 2u) {
-          return;  // need more data
-        }
-
-        // Validate RSV bits are zero
-        if ((m_header[0] & 0x70) != 0) {
-          return Fail(1002, "nonzero RSV");
-        }
-      }
-
-      // Once we have first two bytes, we can calculate the header size
-      if (m_headerSize == 0) {
-        m_headerSize = 2;
-        uint8_t len = m_header[1] & kLenMask;
-        if (len == 126) {
-          m_headerSize += 2;
-        } else if (len == 127) {
-          m_headerSize += 8;
-        }
-        bool masking = (m_header[1] & kFlagMasking) != 0;
-        if (masking) {
-          m_headerSize += 4;  // masking key
-        }
-        // On server side, incoming messages MUST be masked
-        // On client side, incoming messages MUST NOT be masked
-        if (m_server && !masking) {
-          return Fail(1002, "client data not masked");
-        }
-        if (!m_server && masking) {
-          return Fail(1002, "server data masked");
-        }
-      }
-
-      // Need to complete header to calculate message size
-      if (m_header.size() < m_headerSize) {
-        size_t toCopy = (std::min)(m_headerSize - m_header.size(), data.size());
-        m_header.append(data.data(), data.data() + toCopy);
-        data.remove_prefix(toCopy);
-        if (m_header.size() < m_headerSize) {
-          return;  // need more data
-        }
-      }
-
-      if (m_header.size() >= m_headerSize) {
-        // get payload length
-        uint8_t len = m_header[1] & kLenMask;
-        if (len == 126) {
-          m_frameSize = (static_cast<uint16_t>(m_header[2]) << 8) |
-                        static_cast<uint16_t>(m_header[3]);
-        } else if (len == 127) {
-          m_frameSize = (static_cast<uint64_t>(m_header[2]) << 56) |
-                        (static_cast<uint64_t>(m_header[3]) << 48) |
-                        (static_cast<uint64_t>(m_header[4]) << 40) |
-                        (static_cast<uint64_t>(m_header[5]) << 32) |
-                        (static_cast<uint64_t>(m_header[6]) << 24) |
-                        (static_cast<uint64_t>(m_header[7]) << 16) |
-                        (static_cast<uint64_t>(m_header[8]) << 8) |
-                        static_cast<uint64_t>(m_header[9]);
-        } else {
-          m_frameSize = len;
-        }
-
-        // limit maximum size
-        if ((m_payload.size() + m_frameSize) > m_maxMessageSize) {
-          return Fail(1009, "message too large");
-        }
-      }
-    }
-
-    if (m_frameSize != UINT64_MAX) {
-      size_t need = m_frameStart + m_frameSize - m_payload.size();
-      size_t toCopy = (std::min)(need, data.size());
-      m_payload.append(data.data(), data.data() + toCopy);
-      data.remove_prefix(toCopy);
-      need -= toCopy;
-      if (need == 0) {
-        // We have a complete frame
-        // If the message had masking, unmask it
-        if ((m_header[1] & kFlagMasking) != 0) {
-          uint8_t key[4] = {
-              m_header[m_headerSize - 4], m_header[m_headerSize - 3],
-              m_header[m_headerSize - 2], m_header[m_headerSize - 1]};
-          int n = 0;
-          for (uint8_t& ch : span{m_payload}.subspan(m_frameStart)) {
-            ch ^= key[n++];
-            if (n >= 4) {
-              n = 0;
-            }
-          }
-        }
-
-        // Handle message
-        bool fin = (m_header[0] & kFlagFin) != 0;
-        uint8_t opcode = m_header[0] & kOpMask;
-        switch (opcode) {
-          case kOpCont:
-            switch (m_fragmentOpcode) {
-              case kOpText:
-                if (!m_combineFragments || fin) {
-                  text(std::string_view{reinterpret_cast<char*>(
-                                            m_payload.data()),
-                                        m_payload.size()},
-                       fin);
-                }
-                break;
-              case kOpBinary:
-                if (!m_combineFragments || fin) {
-                  binary(m_payload, fin);
-                }
-                break;
-              default:
-                // no preceding message?
-                return Fail(1002, "invalid continuation message");
-            }
-            if (fin) {
-              m_fragmentOpcode = 0;
-            }
-            break;
-          case kOpText:
-            if (m_fragmentOpcode != 0) {
-              return Fail(1002, "incomplete fragment");
-            }
-            if (!m_combineFragments || fin) {
-              text(std::string_view{reinterpret_cast<char*>(m_payload.data()),
-                                    m_payload.size()},
-                   fin);
-            }
-            if (!fin) {
-              m_fragmentOpcode = opcode;
-            }
-            break;
-          case kOpBinary:
-            if (m_fragmentOpcode != 0) {
-              return Fail(1002, "incomplete fragment");
-            }
-            if (!m_combineFragments || fin) {
-              binary(m_payload, fin);
-            }
-            if (!fin) {
-              m_fragmentOpcode = opcode;
-            }
-            break;
-          case kOpClose: {
-            uint16_t code;
-            std::string_view reason;
-            if (!fin) {
-              code = 1002;
-              reason = "cannot fragment control frames";
-            } else if (m_payload.size() < 2) {
-              code = 1005;
-            } else {
-              code = (static_cast<uint16_t>(m_payload[0]) << 8) |
-                     static_cast<uint16_t>(m_payload[1]);
-              reason = drop_front(
-                  {reinterpret_cast<char*>(m_payload.data()), m_payload.size()},
-                  2);
-            }
-            // Echo the close if we didn't previously send it
-            if (m_state != CLOSING) {
-              SendClose(code, reason);
-            }
-            SetClosed(code, reason);
-            // If we're the server, shutdown the connection.
-            if (m_server) {
-              Shutdown();
-            }
-            break;
-          }
-          case kOpPing:
-            if (!fin) {
-              return Fail(1002, "cannot fragment control frames");
-            }
-            ping(m_payload);
-            break;
-          case kOpPong:
-            if (!fin) {
-              return Fail(1002, "cannot fragment control frames");
-            }
-            pong(m_payload);
-            break;
-          default:
-            return Fail(1002, "invalid message opcode");
-        }
-
-        // Prepare for next message
-        m_header.clear();
-        m_headerSize = 0;
-        if (!m_combineFragments || fin) {
-          m_payload.clear();
-        }
-        m_frameStart = m_payload.size();
-        m_frameSize = UINT64_MAX;
-      }
-    }
-  }
-}
-
-void WebSocket::Send(
-    uint8_t opcode, span<const uv::Buffer> data,
-    std::function<void(span<uv::Buffer>, uv::Error)> callback) {
-  // If we're not open, emit an error and don't send the data
-  if (m_state != OPEN) {
-    int err;
-    if (m_state == CONNECTING) {
-      err = UV_EAGAIN;
-    } else {
-      err = UV_ESHUTDOWN;
-    }
-    SmallVector<uv::Buffer, 4> bufs{data.begin(), data.end()};
-    callback(bufs, uv::Error{err});
-    return;
-  }
-
-  auto req = std::make_shared<WebSocketWriteReq>(std::move(callback));
-  raw_uv_ostream os{req->m_bufs, 4096};
-
-  // opcode (includes FIN bit)
-  os << static_cast<unsigned char>(opcode);
-
-  // payload length
-  uint64_t size = 0;
-  for (auto&& buf : data) {
-    size += buf.len;
-  }
-  if (size < 126) {
-    os << static_cast<unsigned char>((m_server ? 0x00 : kFlagMasking) | size);
-  } else if (size <= 0xffff) {
-    os << static_cast<unsigned char>((m_server ? 0x00 : kFlagMasking) | 126);
-    const uint8_t sizeMsb[] = {static_cast<uint8_t>((size >> 8) & 0xff),
-                               static_cast<uint8_t>(size & 0xff)};
-    os << span{sizeMsb};
-  } else {
-    os << static_cast<unsigned char>((m_server ? 0x00 : kFlagMasking) | 127);
-    const uint8_t sizeMsb[] = {static_cast<uint8_t>((size >> 56) & 0xff),
-                               static_cast<uint8_t>((size >> 48) & 0xff),
-                               static_cast<uint8_t>((size >> 40) & 0xff),
-                               static_cast<uint8_t>((size >> 32) & 0xff),
-                               static_cast<uint8_t>((size >> 24) & 0xff),
-                               static_cast<uint8_t>((size >> 16) & 0xff),
-                               static_cast<uint8_t>((size >> 8) & 0xff),
-                               static_cast<uint8_t>(size & 0xff)};
-    os << span{sizeMsb};
-  }
-
-  // clients need to mask the input data
-  if (!m_server) {
-    // generate masking key
-    static std::random_device rd;
-    static std::default_random_engine gen{rd()};
-    std::uniform_int_distribution<unsigned int> dist(0, 255);
-    uint8_t key[4];
-    for (uint8_t& v : key) {
-      v = dist(gen);
-    }
-    os << span<const uint8_t>{key, 4};
-    // copy and mask data
-    int n = 0;
-    for (auto&& buf : data) {
-      for (auto&& ch : buf.data()) {
-        os << static_cast<unsigned char>(static_cast<uint8_t>(ch) ^ key[n++]);
-        if (n >= 4) {
-          n = 0;
-        }
-      }
-    }
-    req->m_startUser = req->m_bufs.size();
-    req->m_bufs.append(data.begin(), data.end());
-    // don't send the user bufs as we copied their data
-    m_stream.Write(span{req->m_bufs}.subspan(0, req->m_startUser), req);
-  } else {
-    // servers can just send the buffers directly without masking
-    req->m_startUser = req->m_bufs.size();
-    req->m_bufs.append(data.begin(), data.end());
-    m_stream.Write(req->m_bufs, req);
-  }
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/WebSocketServer.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/WebSocketServer.cpp
deleted file mode 100644
index 1562f3b..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/WebSocketServer.cpp
+++ /dev/null
@@ -1,171 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/WebSocketServer.h"
-
-#include <utility>
-
-#include "wpi/StringExtras.h"
-#include "wpi/fmt/raw_ostream.h"
-#include "wpi/raw_uv_ostream.h"
-#include "wpi/uv/Buffer.h"
-#include "wpi/uv/Stream.h"
-
-using namespace wpi;
-
-WebSocketServerHelper::WebSocketServerHelper(HttpParser& req) {
-  req.header.connect([this](std::string_view name, std::string_view value) {
-    if (equals_lower(name, "host")) {
-      m_gotHost = true;
-    } else if (equals_lower(name, "upgrade")) {
-      if (equals_lower(value, "websocket")) {
-        m_websocket = true;
-      }
-    } else if (equals_lower(name, "sec-websocket-key")) {
-      m_key = value;
-    } else if (equals_lower(name, "sec-websocket-version")) {
-      m_version = value;
-    } else if (equals_lower(name, "sec-websocket-protocol")) {
-      // Protocols are comma delimited, repeated headers add to list
-      SmallVector<std::string_view, 2> protocols;
-      split(value, protocols, ",", -1, false);
-      for (auto protocol : protocols) {
-        protocol = trim(protocol);
-        if (!protocol.empty()) {
-          m_protocols.emplace_back(protocol);
-        }
-      }
-    }
-  });
-  req.headersComplete.connect([&req, this](bool) {
-    if (req.IsUpgrade() && IsUpgrade()) {
-      upgrade();
-    }
-  });
-}
-
-std::pair<bool, std::string_view> WebSocketServerHelper::MatchProtocol(
-    span<const std::string_view> protocols) {
-  if (protocols.empty() && m_protocols.empty()) {
-    return {true, {}};
-  }
-  for (auto protocol : protocols) {
-    for (auto&& clientProto : m_protocols) {
-      if (protocol == clientProto) {
-        return {true, protocol};
-      }
-    }
-  }
-  return {false, {}};
-}
-
-WebSocketServer::WebSocketServer(uv::Stream& stream,
-                                 span<const std::string_view> protocols,
-                                 ServerOptions options, const private_init&)
-    : m_stream{stream},
-      m_helper{m_req},
-      m_protocols{protocols.begin(), protocols.end()},
-      m_options{std::move(options)} {
-  // Header handling
-  m_req.header.connect([this](std::string_view name, std::string_view value) {
-    if (equals_lower(name, "host")) {
-      if (m_options.checkHost) {
-        if (!m_options.checkHost(value)) {
-          Abort(401, "Unrecognized Host");
-        }
-      }
-    }
-  });
-  m_req.url.connect([this](std::string_view name) {
-    if (m_options.checkUrl) {
-      if (!m_options.checkUrl(name)) {
-        Abort(404, "Not Found");
-      }
-    }
-  });
-  m_req.headersComplete.connect([this](bool) {
-    // We only accept websocket connections
-    if (!m_helper.IsUpgrade() || !m_req.IsUpgrade()) {
-      Abort(426, "Upgrade Required");
-    }
-  });
-
-  // Handle upgrade event
-  m_helper.upgrade.connect([this] {
-    if (m_aborted) {
-      return;
-    }
-
-    // Negotiate sub-protocol
-    SmallVector<std::string_view, 2> protocols{m_protocols.begin(),
-                                               m_protocols.end()};
-    std::string_view protocol = m_helper.MatchProtocol(protocols).second;
-
-    // Disconnect our header reader
-    m_dataConn.disconnect();
-
-    // Accepting the stream may destroy this (as it replaces the stream user
-    // data), so grab a shared pointer first.
-    auto self = shared_from_this();
-
-    // Accept the upgrade
-    auto ws = m_helper.Accept(m_stream, protocol);
-
-    // Connect the websocket open event to our connected event.
-    ws->open.connect_extended(
-        [self, s = ws.get()](auto conn, std::string_view) {
-          self->connected(self->m_req.GetUrl(), *s);
-          conn.disconnect();  // one-shot
-        });
-  });
-
-  // Set up stream
-  stream.StartRead();
-  m_dataConn =
-      stream.data.connect_connection([this](uv::Buffer& buf, size_t size) {
-        if (m_aborted) {
-          return;
-        }
-        m_req.Execute(std::string_view{buf.base, size});
-        if (m_req.HasError()) {
-          Abort(400, "Bad Request");
-        }
-      });
-  m_errorConn =
-      stream.error.connect_connection([this](uv::Error) { m_stream.Close(); });
-  m_endConn = stream.end.connect_connection([this] { m_stream.Close(); });
-}
-
-std::shared_ptr<WebSocketServer> WebSocketServer::Create(
-    uv::Stream& stream, span<const std::string_view> protocols,
-    const ServerOptions& options) {
-  auto server = std::make_shared<WebSocketServer>(stream, protocols, options,
-                                                  private_init{});
-  stream.SetData(server);
-  return server;
-}
-
-void WebSocketServer::Abort(uint16_t code, std::string_view reason) {
-  if (m_aborted) {
-    return;
-  }
-  m_aborted = true;
-
-  // Build response
-  SmallVector<uv::Buffer, 4> bufs;
-  raw_uv_ostream os{bufs, 1024};
-
-  // Handle unsupported version
-  fmt::print(os, "HTTP/1.1 {} {}\r\n", code, reason);
-  if (code == 426) {
-    os << "Upgrade: WebSocket\r\n";
-  }
-  os << "\r\n";
-  m_stream.Write(bufs, [this](auto bufs, uv::Error) {
-    for (auto& buf : bufs) {
-      buf.Deallocate();
-    }
-    m_stream.Shutdown([this] { m_stream.Close(); });
-  });
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/fs.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/fs.cpp
index 34d6cca..fad6a66 100644
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/fs.cpp
+++ b/third_party/allwpilib/wpiutil/src/main/native/cpp/fs.cpp
@@ -82,17 +82,6 @@
 const file_t kInvalidFile = INVALID_HANDLE_VALUE;
 
 static DWORD nativeDisposition(CreationDisposition Disp, OpenFlags Flags) {
-  // This is a compatibility hack.  Really we should respect the creation
-  // disposition, but a lot of old code relied on the implicit assumption that
-  // OF_Append implied it would open an existing file.  Since the disposition is
-  // now explicit and defaults to CD_CreateAlways, this assumption would cause
-  // any usage of OF_Append to append to a new file, even if the file already
-  // existed.  A better solution might have two new creation dispositions:
-  // CD_AppendAlways and CD_AppendNew.  This would also address the problem of
-  // OF_Append being used on a read-only descriptor, which doesn't make sense.
-  if (Flags & OF_Append)
-    return OPEN_ALWAYS;
-
   switch (Disp) {
     case CD_CreateAlways:
       return CREATE_ALWAYS;
@@ -251,12 +240,6 @@
     Result |= O_RDWR;
   }
 
-  // This is for compatibility with old code that assumed F_Append implied
-  // would open an existing file.  See Windows/Path.inc for a longer comment.
-  if (Flags & F_Append) {
-    Disp = CD_OpenAlways;
-  }
-
   if (Disp == CD_CreateNew) {
     Result |= O_CREAT;  // Create if it doesn't exist.
     Result |= O_EXCL;   // Fail if it does.
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/hostname.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/hostname.cpp
deleted file mode 100644
index d907023..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/hostname.cpp
+++ /dev/null
@@ -1,57 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/hostname.h"
-
-#include <cstdlib>
-#include <string>
-#include <string_view>
-
-#include "uv.h"
-#include "wpi/SmallVector.h"
-
-namespace wpi {
-
-std::string GetHostname() {
-  std::string rv;
-  char name[256];
-  size_t size = sizeof(name);
-
-  int err = uv_os_gethostname(name, &size);
-  if (err == 0) {
-    rv.assign(name, size);
-  } else if (err == UV_ENOBUFS) {
-    char* name2 = static_cast<char*>(std::malloc(size));
-    err = uv_os_gethostname(name2, &size);
-    if (err == 0) {
-      rv.assign(name2, size);
-    }
-    std::free(name2);
-  }
-
-  return rv;
-}
-
-std::string_view GetHostname(SmallVectorImpl<char>& name) {
-  // Use a tmp array to not require the SmallVector to be too large.
-  char tmpName[256];
-  size_t size = sizeof(tmpName);
-
-  name.clear();
-
-  int err = uv_os_gethostname(tmpName, &size);
-  if (err == 0) {
-    name.append(tmpName, tmpName + size);
-  } else if (err == UV_ENOBUFS) {
-    name.resize(size);
-    err = uv_os_gethostname(name.data(), &size);
-    if (err != 0) {
-      size = 0;
-    }
-  }
-
-  return {name.data(), size};
-}
-
-}  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/http_parser.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/http_parser.cpp
deleted file mode 100644
index bc442b2..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/http_parser.cpp
+++ /dev/null
@@ -1,2475 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-#include "wpi/http_parser.h"
-#include <assert.h>
-#include <stddef.h>
-#include <ctype.h>
-#include <string.h>
-#include <limits.h>
-
-#ifdef _WIN32
-#pragma warning(disable : 4018 26451)
-#endif
-
-#ifndef ULLONG_MAX
-# define ULLONG_MAX ((uint64_t) -1) /* 2^64-1 */
-#endif
-
-#ifndef MIN
-# define MIN(a,b) ((a) < (b) ? (a) : (b))
-#endif
-
-#ifndef ARRAY_SIZE
-# define ARRAY_SIZE(a) (sizeof(a) / sizeof((a)[0]))
-#endif
-
-#ifndef BIT_AT
-# define BIT_AT(a, i)                                                \
-  (!!((unsigned int) (a)[(unsigned int) (i) >> 3] &                  \
-   (1 << ((unsigned int) (i) & 7))))
-#endif
-
-#ifndef ELEM_AT
-# define ELEM_AT(a, i, v) ((unsigned int) (i) < ARRAY_SIZE(a) ? (a)[(i)] : (v))
-#endif
-
-#define SET_ERRNO(e)                                                 \
-do {                                                                 \
-  parser->nread = nread;                                             \
-  parser->http_errno = (e);                                          \
-} while(0)
-
-#define CURRENT_STATE() p_state
-#define UPDATE_STATE(V) p_state = (enum state) (V);
-#define RETURN(V)                                                    \
-do {                                                                 \
-  parser->nread = nread;                                             \
-  parser->state = CURRENT_STATE();                                   \
-  return (V);                                                        \
-} while (0);
-#define REEXECUTE()                                                  \
-  goto reexecute;                                                    \
-
-
-#ifdef __GNUC__
-# define LIKELY(X) __builtin_expect(!!(X), 1)
-# define UNLIKELY(X) __builtin_expect(!!(X), 0)
-#else
-# define LIKELY(X) (X)
-# define UNLIKELY(X) (X)
-#endif
-
-
-/* Run the notify callback FOR, returning ER if it fails */
-#define CALLBACK_NOTIFY_(FOR, ER)                                    \
-do {                                                                 \
-  assert(HTTP_PARSER_ERRNO(parser) == HPE_OK);                       \
-                                                                     \
-  if (LIKELY(settings->on_##FOR)) {                                  \
-    parser->state = CURRENT_STATE();                                 \
-    if (UNLIKELY(0 != settings->on_##FOR(parser))) {                 \
-      SET_ERRNO(HPE_CB_##FOR);                                       \
-    }                                                                \
-    UPDATE_STATE(parser->state);                                     \
-                                                                     \
-    /* We either errored above or got paused; get out */             \
-    if (UNLIKELY(HTTP_PARSER_ERRNO(parser) != HPE_OK)) {             \
-      return (ER);                                                   \
-    }                                                                \
-  }                                                                  \
-} while (0)
-
-/* Run the notify callback FOR and consume the current byte */
-#define CALLBACK_NOTIFY(FOR)            CALLBACK_NOTIFY_(FOR, p - data + 1)
-
-/* Run the notify callback FOR and don't consume the current byte */
-#define CALLBACK_NOTIFY_NOADVANCE(FOR)  CALLBACK_NOTIFY_(FOR, p - data)
-
-/* Run data callback FOR with LEN bytes, returning ER if it fails */
-#define CALLBACK_DATA_(FOR, LEN, ER)                                 \
-do {                                                                 \
-  assert(HTTP_PARSER_ERRNO(parser) == HPE_OK);                       \
-                                                                     \
-  if (FOR##_mark) {                                                  \
-    if (LIKELY(settings->on_##FOR)) {                                \
-      parser->state = CURRENT_STATE();                               \
-      if (UNLIKELY(0 !=                                              \
-                   settings->on_##FOR(parser, FOR##_mark, (LEN)))) { \
-        SET_ERRNO(HPE_CB_##FOR);                                     \
-      }                                                              \
-      UPDATE_STATE(parser->state);                                   \
-                                                                     \
-      /* We either errored above or got paused; get out */           \
-      if (UNLIKELY(HTTP_PARSER_ERRNO(parser) != HPE_OK)) {           \
-        return (ER);                                                 \
-      }                                                              \
-    }                                                                \
-    FOR##_mark = NULL;                                               \
-  }                                                                  \
-} while (0)
-
-/* Run the data callback FOR and consume the current byte */
-#define CALLBACK_DATA(FOR)                                           \
-    CALLBACK_DATA_(FOR, p - FOR##_mark, p - data + 1)
-
-/* Run the data callback FOR and don't consume the current byte */
-#define CALLBACK_DATA_NOADVANCE(FOR)                                 \
-    CALLBACK_DATA_(FOR, p - FOR##_mark, p - data)
-
-/* Set the mark FOR; non-destructive if mark is already set */
-#define MARK(FOR)                                                    \
-do {                                                                 \
-  if (!FOR##_mark) {                                                 \
-    FOR##_mark = p;                                                  \
-  }                                                                  \
-} while (0)
-
-/* Don't allow the total size of the HTTP headers (including the status
- * line) to exceed HTTP_MAX_HEADER_SIZE.  This check is here to protect
- * embedders against denial-of-service attacks where the attacker feeds
- * us a never-ending header that the embedder keeps buffering.
- *
- * This check is arguably the responsibility of embedders but we're doing
- * it on the embedder's behalf because most won't bother and this way we
- * make the web a little safer.  HTTP_MAX_HEADER_SIZE is still far bigger
- * than any reasonable request or response so this should never affect
- * day-to-day operation.
- */
-#define COUNT_HEADER_SIZE(V)                                         \
-do {                                                                 \
-  nread += (V);                                                      \
-  if (UNLIKELY(nread > (HTTP_MAX_HEADER_SIZE))) {                    \
-    SET_ERRNO(HPE_HEADER_OVERFLOW);                                  \
-    goto error;                                                      \
-  }                                                                  \
-} while (0)
-
-
-#define PROXY_CONNECTION "proxy-connection"
-#define CONNECTION "connection"
-#define CONTENT_LENGTH "content-length"
-#define TRANSFER_ENCODING "transfer-encoding"
-#define UPGRADE "upgrade"
-#define CHUNKED "chunked"
-#define KEEP_ALIVE "keep-alive"
-#define CLOSE "close"
-
-namespace wpi {
-
-
-static const char *method_strings[] =
-  {
-#define XX(num, name, string) #string,
-  HTTP_METHOD_MAP(XX)
-#undef XX
-  };
-
-
-/* Tokens as defined by rfc 2616. Also lowercases them.
- *        token       = 1*<any CHAR except CTLs or separators>
- *     separators     = "(" | ")" | "<" | ">" | "@"
- *                    | "," | ";" | ":" | "\" | <">
- *                    | "/" | "[" | "]" | "?" | "="
- *                    | "{" | "}" | SP | HT
- */
-static const char tokens[256] = {
-/*   0 nul    1 soh    2 stx    3 etx    4 eot    5 enq    6 ack    7 bel  */
-        0,       0,       0,       0,       0,       0,       0,       0,
-/*   8 bs     9 ht    10 nl    11 vt    12 np    13 cr    14 so    15 si   */
-        0,       0,       0,       0,       0,       0,       0,       0,
-/*  16 dle   17 dc1   18 dc2   19 dc3   20 dc4   21 nak   22 syn   23 etb */
-        0,       0,       0,       0,       0,       0,       0,       0,
-/*  24 can   25 em    26 sub   27 esc   28 fs    29 gs    30 rs    31 us  */
-        0,       0,       0,       0,       0,       0,       0,       0,
-/*  32 sp    33  !    34  "    35  #    36  $    37  %    38  &    39  '  */
-       ' ',     '!',      0,      '#',     '$',     '%',     '&',    '\'',
-/*  40  (    41  )    42  *    43  +    44  ,    45  -    46  .    47  /  */
-        0,       0,      '*',     '+',      0,      '-',     '.',      0,
-/*  48  0    49  1    50  2    51  3    52  4    53  5    54  6    55  7  */
-       '0',     '1',     '2',     '3',     '4',     '5',     '6',     '7',
-/*  56  8    57  9    58  :    59  ;    60  <    61  =    62  >    63  ?  */
-       '8',     '9',      0,       0,       0,       0,       0,       0,
-/*  64  @    65  A    66  B    67  C    68  D    69  E    70  F    71  G  */
-        0,      'a',     'b',     'c',     'd',     'e',     'f',     'g',
-/*  72  H    73  I    74  J    75  K    76  L    77  M    78  N    79  O  */
-       'h',     'i',     'j',     'k',     'l',     'm',     'n',     'o',
-/*  80  P    81  Q    82  R    83  S    84  T    85  U    86  V    87  W  */
-       'p',     'q',     'r',     's',     't',     'u',     'v',     'w',
-/*  88  X    89  Y    90  Z    91  [    92  \    93  ]    94  ^    95  _  */
-       'x',     'y',     'z',      0,       0,       0,      '^',     '_',
-/*  96  `    97  a    98  b    99  c   100  d   101  e   102  f   103  g  */
-       '`',     'a',     'b',     'c',     'd',     'e',     'f',     'g',
-/* 104  h   105  i   106  j   107  k   108  l   109  m   110  n   111  o  */
-       'h',     'i',     'j',     'k',     'l',     'm',     'n',     'o',
-/* 112  p   113  q   114  r   115  s   116  t   117  u   118  v   119  w  */
-       'p',     'q',     'r',     's',     't',     'u',     'v',     'w',
-/* 120  x   121  y   122  z   123  {   124  |   125  }   126  ~   127 del */
-       'x',     'y',     'z',      0,      '|',      0,      '~',       0 };
-
-
-static const int8_t unhex[256] =
-  {-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1
-  ,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1
-  ,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1
-  , 0, 1, 2, 3, 4, 5, 6, 7, 8, 9,-1,-1,-1,-1,-1,-1
-  ,-1,10,11,12,13,14,15,-1,-1,-1,-1,-1,-1,-1,-1,-1
-  ,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1
-  ,-1,10,11,12,13,14,15,-1,-1,-1,-1,-1,-1,-1,-1,-1
-  ,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1
-  };
-
-
-#if HTTP_PARSER_STRICT
-# define T(v) 0
-#else
-# define T(v) v
-#endif
-
-
-static const uint8_t normal_url_char[32] = {
-/*   0 nul    1 soh    2 stx    3 etx    4 eot    5 enq    6 ack    7 bel  */
-        0    |   0    |   0    |   0    |   0    |   0    |   0    |   0,
-/*   8 bs     9 ht    10 nl    11 vt    12 np    13 cr    14 so    15 si   */
-        0    | T(2)   |   0    |   0    | T(16)  |   0    |   0    |   0,
-/*  16 dle   17 dc1   18 dc2   19 dc3   20 dc4   21 nak   22 syn   23 etb */
-        0    |   0    |   0    |   0    |   0    |   0    |   0    |   0,
-/*  24 can   25 em    26 sub   27 esc   28 fs    29 gs    30 rs    31 us  */
-        0    |   0    |   0    |   0    |   0    |   0    |   0    |   0,
-/*  32 sp    33  !    34  "    35  #    36  $    37  %    38  &    39  '  */
-        0    |   2    |   4    |   0    |   16   |   32   |   64   |  128,
-/*  40  (    41  )    42  *    43  +    44  ,    45  -    46  .    47  /  */
-        1    |   2    |   4    |   8    |   16   |   32   |   64   |  128,
-/*  48  0    49  1    50  2    51  3    52  4    53  5    54  6    55  7  */
-        1    |   2    |   4    |   8    |   16   |   32   |   64   |  128,
-/*  56  8    57  9    58  :    59  ;    60  <    61  =    62  >    63  ?  */
-        1    |   2    |   4    |   8    |   16   |   32   |   64   |   0,
-/*  64  @    65  A    66  B    67  C    68  D    69  E    70  F    71  G  */
-        1    |   2    |   4    |   8    |   16   |   32   |   64   |  128,
-/*  72  H    73  I    74  J    75  K    76  L    77  M    78  N    79  O  */
-        1    |   2    |   4    |   8    |   16   |   32   |   64   |  128,
-/*  80  P    81  Q    82  R    83  S    84  T    85  U    86  V    87  W  */
-        1    |   2    |   4    |   8    |   16   |   32   |   64   |  128,
-/*  88  X    89  Y    90  Z    91  [    92  \    93  ]    94  ^    95  _  */
-        1    |   2    |   4    |   8    |   16   |   32   |   64   |  128,
-/*  96  `    97  a    98  b    99  c   100  d   101  e   102  f   103  g  */
-        1    |   2    |   4    |   8    |   16   |   32   |   64   |  128,
-/* 104  h   105  i   106  j   107  k   108  l   109  m   110  n   111  o  */
-        1    |   2    |   4    |   8    |   16   |   32   |   64   |  128,
-/* 112  p   113  q   114  r   115  s   116  t   117  u   118  v   119  w  */
-        1    |   2    |   4    |   8    |   16   |   32   |   64   |  128,
-/* 120  x   121  y   122  z   123  {   124  |   125  }   126  ~   127 del */
-        1    |   2    |   4    |   8    |   16   |   32   |   64   |   0, };
-
-#undef T
-
-enum state
-  { s_dead = 1 /* important that this is > 0 */
-
-  , s_start_req_or_res
-  , s_res_or_resp_H
-  , s_start_res
-  , s_res_H
-  , s_res_HT
-  , s_res_HTT
-  , s_res_HTTP
-  , s_res_http_major
-  , s_res_http_dot
-  , s_res_http_minor
-  , s_res_http_end
-  , s_res_first_status_code
-  , s_res_status_code
-  , s_res_status_start
-  , s_res_status
-  , s_res_line_almost_done
-
-  , s_start_req
-
-  , s_req_method
-  , s_req_spaces_before_url
-  , s_req_schema
-  , s_req_schema_slash
-  , s_req_schema_slash_slash
-  , s_req_server_start
-  , s_req_server
-  , s_req_server_with_at
-  , s_req_path
-  , s_req_query_string_start
-  , s_req_query_string
-  , s_req_fragment_start
-  , s_req_fragment
-  , s_req_http_start
-  , s_req_http_H
-  , s_req_http_HT
-  , s_req_http_HTT
-  , s_req_http_HTTP
-  , s_req_http_major
-  , s_req_http_dot
-  , s_req_http_minor
-  , s_req_http_end
-  , s_req_line_almost_done
-
-  , s_header_field_start
-  , s_header_field
-  , s_header_value_discard_ws
-  , s_header_value_discard_ws_almost_done
-  , s_header_value_discard_lws
-  , s_header_value_start
-  , s_header_value
-  , s_header_value_lws
-
-  , s_header_almost_done
-
-  , s_chunk_size_start
-  , s_chunk_size
-  , s_chunk_parameters
-  , s_chunk_size_almost_done
-
-  , s_headers_almost_done
-  , s_headers_done
-
-  /* Important: 's_headers_done' must be the last 'header' state. All
-   * states beyond this must be 'body' states. It is used for overflow
-   * checking. See the PARSING_HEADER() macro.
-   */
-
-  , s_chunk_data
-  , s_chunk_data_almost_done
-  , s_chunk_data_done
-
-  , s_body_identity
-  , s_body_identity_eof
-
-  , s_message_done
-  };
-
-
-#define PARSING_HEADER(state) (state <= s_headers_done)
-
-
-enum header_states
-  { h_general = 0
-  , h_C
-  , h_CO
-  , h_CON
-
-  , h_matching_connection
-  , h_matching_proxy_connection
-  , h_matching_content_length
-  , h_matching_transfer_encoding
-  , h_matching_upgrade
-
-  , h_connection
-  , h_content_length
-  , h_content_length_num
-  , h_content_length_ws
-  , h_transfer_encoding
-  , h_upgrade
-
-  , h_matching_transfer_encoding_chunked
-  , h_matching_connection_token_start
-  , h_matching_connection_keep_alive
-  , h_matching_connection_close
-  , h_matching_connection_upgrade
-  , h_matching_connection_token
-
-  , h_transfer_encoding_chunked
-  , h_connection_keep_alive
-  , h_connection_close
-  , h_connection_upgrade
-  };
-
-enum http_host_state
-  {
-    s_http_host_dead = 1
-  , s_http_userinfo_start
-  , s_http_userinfo
-  , s_http_host_start
-  , s_http_host_v6_start
-  , s_http_host
-  , s_http_host_v6
-  , s_http_host_v6_end
-  , s_http_host_v6_zone_start
-  , s_http_host_v6_zone
-  , s_http_host_port_start
-  , s_http_host_port
-};
-
-/* Macros for character classes; depends on strict-mode  */
-#define CR                  '\r'
-#define LF                  '\n'
-#define LOWER(c)            (unsigned char)(c | 0x20)
-#define IS_ALPHA(c)         (LOWER(c) >= 'a' && LOWER(c) <= 'z')
-#define IS_NUM(c)           ((c) >= '0' && (c) <= '9')
-#define IS_ALPHANUM(c)      (IS_ALPHA(c) || IS_NUM(c))
-#define IS_HEX(c)           (IS_NUM(c) || (LOWER(c) >= 'a' && LOWER(c) <= 'f'))
-#define IS_MARK(c)          ((c) == '-' || (c) == '_' || (c) == '.' || \
-  (c) == '!' || (c) == '~' || (c) == '*' || (c) == '\'' || (c) == '(' || \
-  (c) == ')')
-#define IS_USERINFO_CHAR(c) (IS_ALPHANUM(c) || IS_MARK(c) || (c) == '%' || \
-  (c) == ';' || (c) == ':' || (c) == '&' || (c) == '=' || (c) == '+' || \
-  (c) == '$' || (c) == ',')
-
-#define STRICT_TOKEN(c)     ((c == ' ') ? 0 : tokens[(unsigned char)c])
-
-#if HTTP_PARSER_STRICT
-#define TOKEN(c)            STRICT_TOKEN(c)
-#define IS_URL_CHAR(c)      (BIT_AT(normal_url_char, (unsigned char)c))
-#define IS_HOST_CHAR(c)     (IS_ALPHANUM(c) || (c) == '.' || (c) == '-')
-#else
-#define TOKEN(c)            tokens[(unsigned char)c]
-#define IS_URL_CHAR(c)                                                         \
-  (BIT_AT(normal_url_char, (unsigned char)c) || ((c) & 0x80))
-#define IS_HOST_CHAR(c)                                                        \
-  (IS_ALPHANUM(c) || (c) == '.' || (c) == '-' || (c) == '_')
-#endif
-
-/**
- * Verify that a char is a valid visible (printable) US-ASCII
- * character or %x80-FF
- **/
-#define IS_HEADER_CHAR(ch)                                                     \
-  (ch == CR || ch == LF || ch == 9 || ((unsigned char)ch > 31 && ch != 127))
-
-#define start_state (parser->type == HTTP_REQUEST ? s_start_req : s_start_res)
-
-
-#if HTTP_PARSER_STRICT
-# define STRICT_CHECK(cond)                                          \
-do {                                                                 \
-  if (cond) {                                                        \
-    SET_ERRNO(HPE_STRICT);                                           \
-    goto error;                                                      \
-  }                                                                  \
-} while (0)
-# define NEW_MESSAGE() (http_should_keep_alive(parser) ? start_state : s_dead)
-#else
-# define STRICT_CHECK(cond)
-# define NEW_MESSAGE() start_state
-#endif
-
-
-/* Map errno values to strings for human-readable output */
-#define HTTP_STRERROR_GEN(n, s) { "HPE_" #n, s },
-static struct {
-  const char *name;
-  const char *description;
-} http_strerror_tab[] = {
-  HTTP_ERRNO_MAP(HTTP_STRERROR_GEN)
-};
-#undef HTTP_STRERROR_GEN
-
-int http_message_needs_eof(const http_parser *parser);
-
-/* Our URL parser.
- *
- * This is designed to be shared by http_parser_execute() for URL validation,
- * hence it has a state transition + byte-for-byte interface. In addition, it
- * is meant to be embedded in http_parser_parse_url(), which does the dirty
- * work of turning state transitions URL components for its API.
- *
- * This function should only be invoked with non-space characters. It is
- * assumed that the caller cares about (and can detect) the transition between
- * URL and non-URL states by looking for these.
- */
-static enum state
-parse_url_char(enum state s, const char ch)
-{
-  if (ch == ' ' || ch == '\r' || ch == '\n') {
-    return s_dead;
-  }
-
-#if HTTP_PARSER_STRICT
-  if (ch == '\t' || ch == '\f') {
-    return s_dead;
-  }
-#endif
-
-  switch (s) {
-    case s_req_spaces_before_url:
-      /* Proxied requests are followed by scheme of an absolute URI (alpha).
-       * All methods except CONNECT are followed by '/' or '*'.
-       */
-
-      if (ch == '/' || ch == '*') {
-        return s_req_path;
-      }
-
-      if (IS_ALPHA(ch)) {
-        return s_req_schema;
-      }
-
-      break;
-
-    case s_req_schema:
-      if (IS_ALPHA(ch)) {
-        return s;
-      }
-
-      if (ch == ':') {
-        return s_req_schema_slash;
-      }
-
-      break;
-
-    case s_req_schema_slash:
-      if (ch == '/') {
-        return s_req_schema_slash_slash;
-      }
-
-      break;
-
-    case s_req_schema_slash_slash:
-      if (ch == '/') {
-        return s_req_server_start;
-      }
-
-      break;
-
-    case s_req_server_with_at:
-      if (ch == '@') {
-        return s_dead;
-      }
-
-    /* fall through */
-    case s_req_server_start:
-    case s_req_server:
-      if (ch == '/') {
-        return s_req_path;
-      }
-
-      if (ch == '?') {
-        return s_req_query_string_start;
-      }
-
-      if (ch == '@') {
-        return s_req_server_with_at;
-      }
-
-      if (IS_USERINFO_CHAR(ch) || ch == '[' || ch == ']') {
-        return s_req_server;
-      }
-
-      break;
-
-    case s_req_path:
-      if (IS_URL_CHAR(ch)) {
-        return s;
-      }
-
-      switch (ch) {
-        case '?':
-          return s_req_query_string_start;
-
-        case '#':
-          return s_req_fragment_start;
-      }
-
-      break;
-
-    case s_req_query_string_start:
-    case s_req_query_string:
-      if (IS_URL_CHAR(ch)) {
-        return s_req_query_string;
-      }
-
-      switch (ch) {
-        case '?':
-          /* allow extra '?' in query string */
-          return s_req_query_string;
-
-        case '#':
-          return s_req_fragment_start;
-      }
-
-      break;
-
-    case s_req_fragment_start:
-      if (IS_URL_CHAR(ch)) {
-        return s_req_fragment;
-      }
-
-      switch (ch) {
-        case '?':
-          return s_req_fragment;
-
-        case '#':
-          return s;
-      }
-
-      break;
-
-    case s_req_fragment:
-      if (IS_URL_CHAR(ch)) {
-        return s;
-      }
-
-      switch (ch) {
-        case '?':
-        case '#':
-          return s;
-      }
-
-      break;
-
-    default:
-      break;
-  }
-
-  /* We should never fall out of the switch above unless there's an error */
-  return s_dead;
-}
-
-size_t http_parser_execute (http_parser *parser,
-                            const http_parser_settings *settings,
-                            const char *data,
-                            size_t len)
-{
-  char c, ch;
-  int8_t unhex_val;
-  const char *p = data;
-  const char *header_field_mark = 0;
-  const char *header_value_mark = 0;
-  const char *url_mark = 0;
-  const char *body_mark = 0;
-  const char *status_mark = 0;
-  enum state p_state = (enum state) parser->state;
-  const unsigned int lenient = parser->lenient_http_headers;
-  uint32_t nread = parser->nread;
-
-  /* We're in an error state. Don't bother doing anything. */
-  if (HTTP_PARSER_ERRNO(parser) != HPE_OK) {
-    return 0;
-  }
-
-  if (len == 0) {
-    switch (CURRENT_STATE()) {
-      case s_body_identity_eof:
-        /* Use of CALLBACK_NOTIFY() here would erroneously return 1 byte read if
-         * we got paused.
-         */
-        CALLBACK_NOTIFY_NOADVANCE(message_complete);
-        return 0;
-
-      case s_dead:
-      case s_start_req_or_res:
-      case s_start_res:
-      case s_start_req:
-        return 0;
-
-      default:
-        SET_ERRNO(HPE_INVALID_EOF_STATE);
-        return 1;
-    }
-  }
-
-
-  if (CURRENT_STATE() == s_header_field)
-    header_field_mark = data;
-  if (CURRENT_STATE() == s_header_value)
-    header_value_mark = data;
-  switch (CURRENT_STATE()) {
-  case s_req_path:
-  case s_req_schema:
-  case s_req_schema_slash:
-  case s_req_schema_slash_slash:
-  case s_req_server_start:
-  case s_req_server:
-  case s_req_server_with_at:
-  case s_req_query_string_start:
-  case s_req_query_string:
-  case s_req_fragment_start:
-  case s_req_fragment:
-    url_mark = data;
-    break;
-  case s_res_status:
-    status_mark = data;
-    break;
-  default:
-    break;
-  }
-
-  for (p=data; p != data + len; p++) {
-    ch = *p;
-
-    if (PARSING_HEADER(CURRENT_STATE()))
-      COUNT_HEADER_SIZE(1);
-
-reexecute:
-    switch (CURRENT_STATE()) {
-
-      case s_dead:
-        /* this state is used after a 'Connection: close' message
-         * the parser will error out if it reads another message
-         */
-        if (LIKELY(ch == CR || ch == LF))
-          break;
-
-        SET_ERRNO(HPE_CLOSED_CONNECTION);
-        goto error;
-
-      case s_start_req_or_res:
-      {
-        if (ch == CR || ch == LF)
-          break;
-        parser->flags = 0;
-        parser->content_length = ULLONG_MAX;
-
-        if (ch == 'H') {
-          UPDATE_STATE(s_res_or_resp_H);
-
-          CALLBACK_NOTIFY(message_begin);
-        } else {
-          parser->type = HTTP_REQUEST;
-          UPDATE_STATE(s_start_req);
-          REEXECUTE();
-        }
-
-        break;
-      }
-
-      case s_res_or_resp_H:
-        if (ch == 'T') {
-          parser->type = HTTP_RESPONSE;
-          UPDATE_STATE(s_res_HT);
-        } else {
-          if (UNLIKELY(ch != 'E')) {
-            SET_ERRNO(HPE_INVALID_CONSTANT);
-            goto error;
-          }
-
-          parser->type = HTTP_REQUEST;
-          parser->method = HTTP_HEAD;
-          parser->index = 2;
-          UPDATE_STATE(s_req_method);
-        }
-        break;
-
-      case s_start_res:
-      {
-        parser->flags = 0;
-        parser->content_length = ULLONG_MAX;
-
-        switch (ch) {
-          case 'H':
-            UPDATE_STATE(s_res_H);
-            break;
-
-          case CR:
-          case LF:
-            break;
-
-          default:
-            SET_ERRNO(HPE_INVALID_CONSTANT);
-            goto error;
-        }
-
-        CALLBACK_NOTIFY(message_begin);
-        break;
-      }
-
-      case s_res_H:
-        STRICT_CHECK(ch != 'T');
-        UPDATE_STATE(s_res_HT);
-        break;
-
-      case s_res_HT:
-        STRICT_CHECK(ch != 'T');
-        UPDATE_STATE(s_res_HTT);
-        break;
-
-      case s_res_HTT:
-        STRICT_CHECK(ch != 'P');
-        UPDATE_STATE(s_res_HTTP);
-        break;
-
-      case s_res_HTTP:
-        STRICT_CHECK(ch != '/');
-        UPDATE_STATE(s_res_http_major);
-        break;
-
-      case s_res_http_major:
-        if (UNLIKELY(!IS_NUM(ch))) {
-          SET_ERRNO(HPE_INVALID_VERSION);
-          goto error;
-        }
-
-        parser->http_major = ch - '0';
-        UPDATE_STATE(s_res_http_dot);
-        break;
-
-      case s_res_http_dot:
-      {
-        if (UNLIKELY(ch != '.')) {
-          SET_ERRNO(HPE_INVALID_VERSION);
-          goto error;
-        }
-
-        UPDATE_STATE(s_res_http_minor);
-        break;
-      }
-
-      case s_res_http_minor:
-        if (UNLIKELY(!IS_NUM(ch))) {
-          SET_ERRNO(HPE_INVALID_VERSION);
-          goto error;
-        }
-
-        parser->http_minor = ch - '0';
-        UPDATE_STATE(s_res_http_end);
-        break;
-
-      case s_res_http_end:
-      {
-        if (UNLIKELY(ch != ' ')) {
-          SET_ERRNO(HPE_INVALID_VERSION);
-          goto error;
-        }
-
-        UPDATE_STATE(s_res_first_status_code);
-        break;
-      }
-
-      case s_res_first_status_code:
-      {
-        if (!IS_NUM(ch)) {
-          if (ch == ' ') {
-            break;
-          }
-
-          SET_ERRNO(HPE_INVALID_STATUS);
-          goto error;
-        }
-        parser->status_code = ch - '0';
-        UPDATE_STATE(s_res_status_code);
-        break;
-      }
-
-      case s_res_status_code:
-      {
-        if (!IS_NUM(ch)) {
-          switch (ch) {
-            case ' ':
-              UPDATE_STATE(s_res_status_start);
-              break;
-            case CR:
-            case LF:
-              UPDATE_STATE(s_res_status_start);
-              REEXECUTE();
-              break;
-            default:
-              SET_ERRNO(HPE_INVALID_STATUS);
-              goto error;
-          }
-          break;
-        }
-
-        parser->status_code *= 10;
-        parser->status_code += ch - '0';
-
-        if (UNLIKELY(parser->status_code > 999)) {
-          SET_ERRNO(HPE_INVALID_STATUS);
-          goto error;
-        }
-
-        break;
-      }
-
-      case s_res_status_start:
-      {
-        MARK(status);
-        UPDATE_STATE(s_res_status);
-        parser->index = 0;
-
-        if (ch == CR || ch == LF)
-          REEXECUTE();
-
-        break;
-      }
-
-      case s_res_status:
-        if (ch == CR) {
-          UPDATE_STATE(s_res_line_almost_done);
-          CALLBACK_DATA(status);
-          break;
-        }
-
-        if (ch == LF) {
-          UPDATE_STATE(s_header_field_start);
-          CALLBACK_DATA(status);
-          break;
-        }
-
-        break;
-
-      case s_res_line_almost_done:
-        STRICT_CHECK(ch != LF);
-        UPDATE_STATE(s_header_field_start);
-        break;
-
-      case s_start_req:
-      {
-        if (ch == CR || ch == LF)
-          break;
-        parser->flags = 0;
-        parser->content_length = ULLONG_MAX;
-
-        if (UNLIKELY(!IS_ALPHA(ch))) {
-          SET_ERRNO(HPE_INVALID_METHOD);
-          goto error;
-        }
-
-        parser->method = (enum http_method) 0;
-        parser->index = 1;
-        switch (ch) {
-          case 'A': parser->method = HTTP_ACL; break;
-          case 'B': parser->method = HTTP_BIND; break;
-          case 'C': parser->method = HTTP_CONNECT; /* or COPY, CHECKOUT */ break;
-          case 'D': parser->method = HTTP_DELETE; break;
-          case 'G': parser->method = HTTP_GET; break;
-          case 'H': parser->method = HTTP_HEAD; break;
-          case 'L': parser->method = HTTP_LOCK; /* or LINK */ break;
-          case 'M': parser->method = HTTP_MKCOL; /* or MOVE, MKACTIVITY, MERGE, M-SEARCH, MKCALENDAR */ break;
-          case 'N': parser->method = HTTP_NOTIFY; break;
-          case 'O': parser->method = HTTP_OPTIONS; break;
-          case 'P': parser->method = HTTP_POST;
-            /* or PROPFIND|PROPPATCH|PUT|PATCH|PURGE */
-            break;
-          case 'R': parser->method = HTTP_REPORT; /* or REBIND */ break;
-          case 'S': parser->method = HTTP_SUBSCRIBE; /* or SEARCH, SOURCE */ break;
-          case 'T': parser->method = HTTP_TRACE; break;
-          case 'U': parser->method = HTTP_UNLOCK; /* or UNSUBSCRIBE, UNBIND, UNLINK */ break;
-          default:
-            SET_ERRNO(HPE_INVALID_METHOD);
-            goto error;
-        }
-        UPDATE_STATE(s_req_method);
-
-        CALLBACK_NOTIFY(message_begin);
-
-        break;
-      }
-
-      case s_req_method:
-      {
-        const char *matcher;
-        if (UNLIKELY(ch == '\0')) {
-          SET_ERRNO(HPE_INVALID_METHOD);
-          goto error;
-        }
-
-        matcher = method_strings[parser->method];
-        if (ch == ' ' && matcher[parser->index] == '\0') {
-          UPDATE_STATE(s_req_spaces_before_url);
-        } else if (ch == matcher[parser->index]) {
-          ; /* nada */
-        } else if ((ch >= 'A' && ch <= 'Z') || ch == '-') {
-
-          switch (parser->method << 16 | parser->index << 8 | ch) {
-#define XX(meth, pos, ch, new_meth) \
-            case (HTTP_##meth << 16 | pos << 8 | ch): \
-              parser->method = HTTP_##new_meth; break;
-
-            XX(POST,      1, 'U', PUT)
-            XX(POST,      1, 'A', PATCH)
-            XX(POST,      1, 'R', PROPFIND)
-            XX(PUT,       2, 'R', PURGE)
-            XX(CONNECT,   1, 'H', CHECKOUT)
-            XX(CONNECT,   2, 'P', COPY)
-            XX(MKCOL,     1, 'O', MOVE)
-            XX(MKCOL,     1, 'E', MERGE)
-            XX(MKCOL,     1, '-', MSEARCH)
-            XX(MKCOL,     2, 'A', MKACTIVITY)
-            XX(MKCOL,     3, 'A', MKCALENDAR)
-            XX(SUBSCRIBE, 1, 'E', SEARCH)
-            XX(SUBSCRIBE, 1, 'O', SOURCE)
-            XX(REPORT,    2, 'B', REBIND)
-            XX(PROPFIND,  4, 'P', PROPPATCH)
-            XX(LOCK,      1, 'I', LINK)
-            XX(UNLOCK,    2, 'S', UNSUBSCRIBE)
-            XX(UNLOCK,    2, 'B', UNBIND)
-            XX(UNLOCK,    3, 'I', UNLINK)
-#undef XX
-            default:
-              SET_ERRNO(HPE_INVALID_METHOD);
-              goto error;
-          }
-        } else {
-          SET_ERRNO(HPE_INVALID_METHOD);
-          goto error;
-        }
-
-        ++parser->index;
-        break;
-      }
-
-      case s_req_spaces_before_url:
-      {
-        if (ch == ' ') break;
-
-        MARK(url);
-        if (parser->method == HTTP_CONNECT) {
-          UPDATE_STATE(s_req_server_start);
-        }
-
-        UPDATE_STATE(parse_url_char(CURRENT_STATE(), ch));
-        if (UNLIKELY(CURRENT_STATE() == s_dead)) {
-          SET_ERRNO(HPE_INVALID_URL);
-          goto error;
-        }
-
-        break;
-      }
-
-      case s_req_schema:
-      case s_req_schema_slash:
-      case s_req_schema_slash_slash:
-      case s_req_server_start:
-      {
-        switch (ch) {
-          /* No whitespace allowed here */
-          case ' ':
-          case CR:
-          case LF:
-            SET_ERRNO(HPE_INVALID_URL);
-            goto error;
-          default:
-            UPDATE_STATE(parse_url_char(CURRENT_STATE(), ch));
-            if (UNLIKELY(CURRENT_STATE() == s_dead)) {
-              SET_ERRNO(HPE_INVALID_URL);
-              goto error;
-            }
-        }
-
-        break;
-      }
-
-      case s_req_server:
-      case s_req_server_with_at:
-      case s_req_path:
-      case s_req_query_string_start:
-      case s_req_query_string:
-      case s_req_fragment_start:
-      case s_req_fragment:
-      {
-        switch (ch) {
-          case ' ':
-            UPDATE_STATE(s_req_http_start);
-            CALLBACK_DATA(url);
-            break;
-          case CR:
-          case LF:
-            parser->http_major = 0;
-            parser->http_minor = 9;
-            UPDATE_STATE((ch == CR) ?
-              s_req_line_almost_done :
-              s_header_field_start);
-            CALLBACK_DATA(url);
-            break;
-          default:
-            UPDATE_STATE(parse_url_char(CURRENT_STATE(), ch));
-            if (UNLIKELY(CURRENT_STATE() == s_dead)) {
-              SET_ERRNO(HPE_INVALID_URL);
-              goto error;
-            }
-        }
-        break;
-      }
-
-      case s_req_http_start:
-        switch (ch) {
-          case 'H':
-            UPDATE_STATE(s_req_http_H);
-            break;
-          case ' ':
-            break;
-          default:
-            SET_ERRNO(HPE_INVALID_CONSTANT);
-            goto error;
-        }
-        break;
-
-      case s_req_http_H:
-        STRICT_CHECK(ch != 'T');
-        UPDATE_STATE(s_req_http_HT);
-        break;
-
-      case s_req_http_HT:
-        STRICT_CHECK(ch != 'T');
-        UPDATE_STATE(s_req_http_HTT);
-        break;
-
-      case s_req_http_HTT:
-        STRICT_CHECK(ch != 'P');
-        UPDATE_STATE(s_req_http_HTTP);
-        break;
-
-      case s_req_http_HTTP:
-        STRICT_CHECK(ch != '/');
-        UPDATE_STATE(s_req_http_major);
-        break;
-
-      case s_req_http_major:
-        if (UNLIKELY(!IS_NUM(ch))) {
-          SET_ERRNO(HPE_INVALID_VERSION);
-          goto error;
-        }
-
-        parser->http_major = ch - '0';
-        UPDATE_STATE(s_req_http_dot);
-        break;
-
-      case s_req_http_dot:
-      {
-        if (UNLIKELY(ch != '.')) {
-          SET_ERRNO(HPE_INVALID_VERSION);
-          goto error;
-        }
-
-        UPDATE_STATE(s_req_http_minor);
-        break;
-      }
-
-      case s_req_http_minor:
-        if (UNLIKELY(!IS_NUM(ch))) {
-          SET_ERRNO(HPE_INVALID_VERSION);
-          goto error;
-        }
-
-        parser->http_minor = ch - '0';
-        UPDATE_STATE(s_req_http_end);
-        break;
-
-      case s_req_http_end:
-      {
-        if (ch == CR) {
-          UPDATE_STATE(s_req_line_almost_done);
-          break;
-        }
-
-        if (ch == LF) {
-          UPDATE_STATE(s_header_field_start);
-          break;
-        }
-
-        SET_ERRNO(HPE_INVALID_VERSION);
-        goto error;
-        break;
-      }
-
-      /* end of request line */
-      case s_req_line_almost_done:
-      {
-        if (UNLIKELY(ch != LF)) {
-          SET_ERRNO(HPE_LF_EXPECTED);
-          goto error;
-        }
-
-        UPDATE_STATE(s_header_field_start);
-        break;
-      }
-
-      case s_header_field_start:
-      {
-        if (ch == CR) {
-          UPDATE_STATE(s_headers_almost_done);
-          break;
-        }
-
-        if (ch == LF) {
-          /* they might be just sending \n instead of \r\n so this would be
-           * the second \n to denote the end of headers*/
-          UPDATE_STATE(s_headers_almost_done);
-          REEXECUTE();
-        }
-
-        c = TOKEN(ch);
-
-        if (UNLIKELY(!c)) {
-          SET_ERRNO(HPE_INVALID_HEADER_TOKEN);
-          goto error;
-        }
-
-        MARK(header_field);
-
-        parser->index = 0;
-        UPDATE_STATE(s_header_field);
-
-        switch (c) {
-          case 'c':
-            parser->header_state = h_C;
-            break;
-
-          case 'p':
-            parser->header_state = h_matching_proxy_connection;
-            break;
-
-          case 't':
-            parser->header_state = h_matching_transfer_encoding;
-            break;
-
-          case 'u':
-            parser->header_state = h_matching_upgrade;
-            break;
-
-          default:
-            parser->header_state = h_general;
-            break;
-        }
-        break;
-      }
-
-      case s_header_field:
-      {
-        const char* start = p;
-        for (; p != data + len; p++) {
-          ch = *p;
-          c = TOKEN(ch);
-
-          if (!c)
-            break;
-
-          switch (parser->header_state) {
-            case h_general: {
-              size_t limit = data + len - p;
-              limit = MIN(limit, HTTP_MAX_HEADER_SIZE);
-              while (p+1 < data + limit && TOKEN(p[1])) {
-                p++;
-              }
-              break;
-            }
-
-            case h_C:
-              parser->index++;
-              parser->header_state = (c == 'o' ? h_CO : h_general);
-              break;
-
-            case h_CO:
-              parser->index++;
-              parser->header_state = (c == 'n' ? h_CON : h_general);
-              break;
-
-            case h_CON:
-              parser->index++;
-              switch (c) {
-                case 'n':
-                  parser->header_state = h_matching_connection;
-                  break;
-                case 't':
-                  parser->header_state = h_matching_content_length;
-                  break;
-                default:
-                  parser->header_state = h_general;
-                  break;
-              }
-              break;
-
-            /* connection */
-
-            case h_matching_connection:
-              parser->index++;
-              if (parser->index > sizeof(CONNECTION)-1
-                  || c != CONNECTION[parser->index]) {
-                parser->header_state = h_general;
-              } else if (parser->index == sizeof(CONNECTION)-2) {
-                parser->header_state = h_connection;
-              }
-              break;
-
-            /* proxy-connection */
-
-            case h_matching_proxy_connection:
-              parser->index++;
-              if (parser->index > sizeof(PROXY_CONNECTION)-1
-                  || c != PROXY_CONNECTION[parser->index]) {
-                parser->header_state = h_general;
-              } else if (parser->index == sizeof(PROXY_CONNECTION)-2) {
-                parser->header_state = h_connection;
-              }
-              break;
-
-            /* content-length */
-
-            case h_matching_content_length:
-              parser->index++;
-              if (parser->index > sizeof(CONTENT_LENGTH)-1
-                  || c != CONTENT_LENGTH[parser->index]) {
-                parser->header_state = h_general;
-              } else if (parser->index == sizeof(CONTENT_LENGTH)-2) {
-                parser->header_state = h_content_length;
-              }
-              break;
-
-            /* transfer-encoding */
-
-            case h_matching_transfer_encoding:
-              parser->index++;
-              if (parser->index > sizeof(TRANSFER_ENCODING)-1
-                  || c != TRANSFER_ENCODING[parser->index]) {
-                parser->header_state = h_general;
-              } else if (parser->index == sizeof(TRANSFER_ENCODING)-2) {
-                parser->header_state = h_transfer_encoding;
-              }
-              break;
-
-            /* upgrade */
-
-            case h_matching_upgrade:
-              parser->index++;
-              if (parser->index > sizeof(UPGRADE)-1
-                  || c != UPGRADE[parser->index]) {
-                parser->header_state = h_general;
-              } else if (parser->index == sizeof(UPGRADE)-2) {
-                parser->header_state = h_upgrade;
-              }
-              break;
-
-            case h_connection:
-            case h_content_length:
-            case h_transfer_encoding:
-            case h_upgrade:
-              if (ch != ' ') parser->header_state = h_general;
-              break;
-
-            default:
-              assert(0 && "Unknown header_state");
-              break;
-          }
-        }
-
-        if (p == data + len) {
-          --p;
-          COUNT_HEADER_SIZE(p - start);
-          break;
-        }
-
-        COUNT_HEADER_SIZE(p - start);
-
-        if (ch == ':') {
-          UPDATE_STATE(s_header_value_discard_ws);
-          CALLBACK_DATA(header_field);
-          break;
-        }
-
-        SET_ERRNO(HPE_INVALID_HEADER_TOKEN);
-        goto error;
-      }
-
-      case s_header_value_discard_ws:
-        if (ch == ' ' || ch == '\t') break;
-
-        if (ch == CR) {
-          UPDATE_STATE(s_header_value_discard_ws_almost_done);
-          break;
-        }
-
-        if (ch == LF) {
-          UPDATE_STATE(s_header_value_discard_lws);
-          break;
-        }
-
-        /* fall through */
-
-      case s_header_value_start:
-      {
-        MARK(header_value);
-
-        UPDATE_STATE(s_header_value);
-        parser->index = 0;
-
-        c = LOWER(ch);
-
-        switch (parser->header_state) {
-          case h_upgrade:
-            parser->flags |= F_UPGRADE;
-            parser->header_state = h_general;
-            break;
-
-          case h_transfer_encoding:
-            /* looking for 'Transfer-Encoding: chunked' */
-            if ('c' == c) {
-              parser->header_state = h_matching_transfer_encoding_chunked;
-            } else {
-              parser->header_state = h_general;
-            }
-            break;
-
-          case h_content_length:
-            if (UNLIKELY(!IS_NUM(ch))) {
-              SET_ERRNO(HPE_INVALID_CONTENT_LENGTH);
-              goto error;
-            }
-
-            if (parser->flags & F_CONTENTLENGTH) {
-              SET_ERRNO(HPE_UNEXPECTED_CONTENT_LENGTH);
-              goto error;
-            }
-
-            parser->flags |= F_CONTENTLENGTH;
-            parser->content_length = ch - '0';
-            parser->header_state = h_content_length_num;
-            break;
-
-          case h_connection:
-            /* looking for 'Connection: keep-alive' */
-            if (c == 'k') {
-              parser->header_state = h_matching_connection_keep_alive;
-            /* looking for 'Connection: close' */
-            } else if (c == 'c') {
-              parser->header_state = h_matching_connection_close;
-            } else if (c == 'u') {
-              parser->header_state = h_matching_connection_upgrade;
-            } else {
-              parser->header_state = h_matching_connection_token;
-            }
-            break;
-
-          /* Multi-value `Connection` header */
-          case h_matching_connection_token_start:
-            break;
-
-          default:
-            parser->header_state = h_general;
-            break;
-        }
-        break;
-      }
-
-      case s_header_value:
-      {
-        const char* start = p;
-        enum header_states h_state = (enum header_states) parser->header_state;
-        for (; p != data + len; p++) {
-          ch = *p;
-          if (ch == CR) {
-            UPDATE_STATE(s_header_almost_done);
-            parser->header_state = h_state;
-            CALLBACK_DATA(header_value);
-            break;
-          }
-
-          if (ch == LF) {
-            UPDATE_STATE(s_header_almost_done);
-            COUNT_HEADER_SIZE(p - start);
-            parser->header_state = h_state;
-            CALLBACK_DATA_NOADVANCE(header_value);
-            REEXECUTE();
-          }
-
-          if (!lenient && !IS_HEADER_CHAR(ch)) {
-            SET_ERRNO(HPE_INVALID_HEADER_TOKEN);
-            goto error;
-          }
-
-          c = LOWER(ch);
-
-          switch (h_state) {
-            case h_general:
-            {
-              const char* p_cr;
-              const char* p_lf;
-              size_t limit = data + len - p;
-
-              limit = MIN(limit, HTTP_MAX_HEADER_SIZE);
-
-              p_cr = (const char*) memchr(p, CR, limit);
-              p_lf = (const char*) memchr(p, LF, limit);
-              if (p_cr != NULL) {
-                if (p_lf != NULL && p_cr >= p_lf)
-                  p = p_lf;
-                else
-                  p = p_cr;
-              } else if (UNLIKELY(p_lf != NULL)) {
-                p = p_lf;
-              } else {
-                p = data + len;
-              }
-              --p;
-              break;
-            }
-
-            case h_connection:
-            case h_transfer_encoding:
-              assert(0 && "Shouldn't get here.");
-              break;
-
-            case h_content_length:
-              if (ch == ' ') break;
-              h_state = h_content_length_num;
-              /* fall through */
-
-            case h_content_length_num:
-            {
-              uint64_t t;
-
-              if (ch == ' ') {
-                h_state = h_content_length_ws;
-                break;
-              }
-
-              if (UNLIKELY(!IS_NUM(ch))) {
-                SET_ERRNO(HPE_INVALID_CONTENT_LENGTH);
-                parser->header_state = h_state;
-                goto error;
-              }
-
-              t = parser->content_length;
-              t *= 10;
-              t += ch - '0';
-
-              /* Overflow? Test against a conservative limit for simplicity. */
-              if (UNLIKELY((ULLONG_MAX - 10) / 10 < parser->content_length)) {
-                SET_ERRNO(HPE_INVALID_CONTENT_LENGTH);
-                parser->header_state = h_state;
-                goto error;
-              }
-
-              parser->content_length = t;
-              break;
-            }
-
-            case h_content_length_ws:
-              if (ch == ' ') break;
-              SET_ERRNO(HPE_INVALID_CONTENT_LENGTH);
-              parser->header_state = h_state;
-              goto error;
-
-            /* Transfer-Encoding: chunked */
-            case h_matching_transfer_encoding_chunked:
-              parser->index++;
-              if (parser->index > sizeof(CHUNKED)-1
-                  || c != CHUNKED[parser->index]) {
-                h_state = h_general;
-              } else if (parser->index == sizeof(CHUNKED)-2) {
-                h_state = h_transfer_encoding_chunked;
-              }
-              break;
-
-            case h_matching_connection_token_start:
-              /* looking for 'Connection: keep-alive' */
-              if (c == 'k') {
-                h_state = h_matching_connection_keep_alive;
-              /* looking for 'Connection: close' */
-              } else if (c == 'c') {
-                h_state = h_matching_connection_close;
-              } else if (c == 'u') {
-                h_state = h_matching_connection_upgrade;
-              } else if (STRICT_TOKEN(c)) {
-                h_state = h_matching_connection_token;
-              } else if (c == ' ' || c == '\t') {
-                /* Skip lws */
-              } else {
-                h_state = h_general;
-              }
-              break;
-
-            /* looking for 'Connection: keep-alive' */
-            case h_matching_connection_keep_alive:
-              parser->index++;
-              if (parser->index > sizeof(KEEP_ALIVE)-1
-                  || c != KEEP_ALIVE[parser->index]) {
-                h_state = h_matching_connection_token;
-              } else if (parser->index == sizeof(KEEP_ALIVE)-2) {
-                h_state = h_connection_keep_alive;
-              }
-              break;
-
-            /* looking for 'Connection: close' */
-            case h_matching_connection_close:
-              parser->index++;
-              if (parser->index > sizeof(CLOSE)-1 || c != CLOSE[parser->index]) {
-                h_state = h_matching_connection_token;
-              } else if (parser->index == sizeof(CLOSE)-2) {
-                h_state = h_connection_close;
-              }
-              break;
-
-            /* looking for 'Connection: upgrade' */
-            case h_matching_connection_upgrade:
-              parser->index++;
-              if (parser->index > sizeof(UPGRADE) - 1 ||
-                  c != UPGRADE[parser->index]) {
-                h_state = h_matching_connection_token;
-              } else if (parser->index == sizeof(UPGRADE)-2) {
-                h_state = h_connection_upgrade;
-              }
-              break;
-
-            case h_matching_connection_token:
-              if (ch == ',') {
-                h_state = h_matching_connection_token_start;
-                parser->index = 0;
-              }
-              break;
-
-            case h_transfer_encoding_chunked:
-              if (ch != ' ') h_state = h_general;
-              break;
-
-            case h_connection_keep_alive:
-            case h_connection_close:
-            case h_connection_upgrade:
-              if (ch == ',') {
-                if (h_state == h_connection_keep_alive) {
-                  parser->flags |= F_CONNECTION_KEEP_ALIVE;
-                } else if (h_state == h_connection_close) {
-                  parser->flags |= F_CONNECTION_CLOSE;
-                } else if (h_state == h_connection_upgrade) {
-                  parser->flags |= F_CONNECTION_UPGRADE;
-                }
-                h_state = h_matching_connection_token_start;
-                parser->index = 0;
-              } else if (ch != ' ') {
-                h_state = h_matching_connection_token;
-              }
-              break;
-
-            default:
-              UPDATE_STATE(s_header_value);
-              h_state = h_general;
-              break;
-          }
-        }
-        parser->header_state = h_state;
-
-        if (p == data + len)
-          --p;
-
-        COUNT_HEADER_SIZE(p - start);
-        break;
-      }
-
-      case s_header_almost_done:
-      {
-        if (UNLIKELY(ch != LF)) {
-          SET_ERRNO(HPE_LF_EXPECTED);
-          goto error;
-        }
-
-        UPDATE_STATE(s_header_value_lws);
-        break;
-      }
-
-      case s_header_value_lws:
-      {
-        if (ch == ' ' || ch == '\t') {
-          UPDATE_STATE(s_header_value_start);
-          REEXECUTE();
-        }
-
-        /* finished the header */
-        switch (parser->header_state) {
-          case h_connection_keep_alive:
-            parser->flags |= F_CONNECTION_KEEP_ALIVE;
-            break;
-          case h_connection_close:
-            parser->flags |= F_CONNECTION_CLOSE;
-            break;
-          case h_transfer_encoding_chunked:
-            parser->flags |= F_CHUNKED;
-            break;
-          case h_connection_upgrade:
-            parser->flags |= F_CONNECTION_UPGRADE;
-            break;
-          default:
-            break;
-        }
-
-        UPDATE_STATE(s_header_field_start);
-        REEXECUTE();
-      }
-
-      case s_header_value_discard_ws_almost_done:
-      {
-        STRICT_CHECK(ch != LF);
-        UPDATE_STATE(s_header_value_discard_lws);
-        break;
-      }
-
-      case s_header_value_discard_lws:
-      {
-        if (ch == ' ' || ch == '\t') {
-          UPDATE_STATE(s_header_value_discard_ws);
-          break;
-        } else {
-          switch (parser->header_state) {
-            case h_connection_keep_alive:
-              parser->flags |= F_CONNECTION_KEEP_ALIVE;
-              break;
-            case h_connection_close:
-              parser->flags |= F_CONNECTION_CLOSE;
-              break;
-            case h_connection_upgrade:
-              parser->flags |= F_CONNECTION_UPGRADE;
-              break;
-            case h_transfer_encoding_chunked:
-              parser->flags |= F_CHUNKED;
-              break;
-            default:
-              break;
-          }
-
-          /* header value was empty */
-          MARK(header_value);
-          UPDATE_STATE(s_header_field_start);
-          CALLBACK_DATA_NOADVANCE(header_value);
-          REEXECUTE();
-        }
-      }
-
-      case s_headers_almost_done:
-      {
-        STRICT_CHECK(ch != LF);
-
-        if (parser->flags & F_TRAILING) {
-          /* End of a chunked request */
-          UPDATE_STATE(s_message_done);
-          CALLBACK_NOTIFY_NOADVANCE(chunk_complete);
-          REEXECUTE();
-        }
-
-        /* Cannot use chunked encoding and a content-length header together
-           per the HTTP specification. */
-        if ((parser->flags & F_CHUNKED) &&
-            (parser->flags & F_CONTENTLENGTH)) {
-          SET_ERRNO(HPE_UNEXPECTED_CONTENT_LENGTH);
-          goto error;
-        }
-
-        UPDATE_STATE(s_headers_done);
-
-        /* Set this here so that on_headers_complete() callbacks can see it */
-        if ((parser->flags & F_UPGRADE) &&
-            (parser->flags & F_CONNECTION_UPGRADE)) {
-          /* For responses, "Upgrade: foo" and "Connection: upgrade" are
-           * mandatory only when it is a 101 Switching Protocols response,
-           * otherwise it is purely informational, to announce support.
-           */
-          parser->upgrade =
-              (parser->type == HTTP_REQUEST || parser->status_code == 101);
-        } else {
-          parser->upgrade = (parser->method == HTTP_CONNECT);
-        }
-
-        /* Here we call the headers_complete callback. This is somewhat
-         * different than other callbacks because if the user returns 1, we
-         * will interpret that as saying that this message has no body. This
-         * is needed for the annoying case of receiving a response to a HEAD
-         * request.
-         *
-         * We'd like to use CALLBACK_NOTIFY_NOADVANCE() here but we cannot, so
-         * we have to simulate it by handling a change in errno below.
-         */
-        if (settings->on_headers_complete) {
-          switch (settings->on_headers_complete(parser)) {
-            case 0:
-              break;
-
-            case 2:
-              parser->upgrade = 1;
-
-              /* fall through */
-            case 1:
-              parser->flags |= F_SKIPBODY;
-              break;
-
-            default:
-              SET_ERRNO(HPE_CB_headers_complete);
-              RETURN(p - data); /* Error */
-          }
-        }
-
-        if (HTTP_PARSER_ERRNO(parser) != HPE_OK) {
-          RETURN(p - data);
-        }
-
-        REEXECUTE();
-      }
-
-      case s_headers_done:
-      {
-        int hasBody;
-        STRICT_CHECK(ch != LF);
-
-        parser->nread = 0;
-        nread = 0;
-
-        hasBody = parser->flags & F_CHUNKED ||
-          (parser->content_length > 0 && parser->content_length != ULLONG_MAX);
-        if (parser->upgrade && (parser->method == HTTP_CONNECT ||
-                                (parser->flags & F_SKIPBODY) || !hasBody)) {
-          /* Exit, the rest of the message is in a different protocol. */
-          UPDATE_STATE(NEW_MESSAGE());
-          CALLBACK_NOTIFY(message_complete);
-          RETURN((p - data) + 1);
-        }
-
-        if (parser->flags & F_SKIPBODY) {
-          UPDATE_STATE(NEW_MESSAGE());
-          CALLBACK_NOTIFY(message_complete);
-        } else if (parser->flags & F_CHUNKED) {
-          /* chunked encoding - ignore Content-Length header */
-          UPDATE_STATE(s_chunk_size_start);
-        } else {
-          if (parser->content_length == 0) {
-            /* Content-Length header given but zero: Content-Length: 0\r\n */
-            UPDATE_STATE(NEW_MESSAGE());
-            CALLBACK_NOTIFY(message_complete);
-          } else if (parser->content_length != ULLONG_MAX) {
-            /* Content-Length header given and non-zero */
-            UPDATE_STATE(s_body_identity);
-          } else {
-            if (!http_message_needs_eof(parser)) {
-              /* Assume content-length 0 - read the next */
-              UPDATE_STATE(NEW_MESSAGE());
-              CALLBACK_NOTIFY(message_complete);
-            } else {
-              /* Read body until EOF */
-              UPDATE_STATE(s_body_identity_eof);
-            }
-          }
-        }
-
-        break;
-      }
-
-      case s_body_identity:
-      {
-        uint64_t to_read = MIN(parser->content_length,
-                               (uint64_t) ((data + len) - p));
-
-        assert(parser->content_length != 0
-            && parser->content_length != ULLONG_MAX);
-
-        /* The difference between advancing content_length and p is because
-         * the latter will automaticaly advance on the next loop iteration.
-         * Further, if content_length ends up at 0, we want to see the last
-         * byte again for our message complete callback.
-         */
-        MARK(body);
-        parser->content_length -= to_read;
-        p += to_read - 1;
-
-        if (parser->content_length == 0) {
-          UPDATE_STATE(s_message_done);
-
-          /* Mimic CALLBACK_DATA_NOADVANCE() but with one extra byte.
-           *
-           * The alternative to doing this is to wait for the next byte to
-           * trigger the data callback, just as in every other case. The
-           * problem with this is that this makes it difficult for the test
-           * harness to distinguish between complete-on-EOF and
-           * complete-on-length. It's not clear that this distinction is
-           * important for applications, but let's keep it for now.
-           */
-          CALLBACK_DATA_(body, p - body_mark + 1, p - data);
-          REEXECUTE();
-        }
-
-        break;
-      }
-
-      /* read until EOF */
-      case s_body_identity_eof:
-        MARK(body);
-        p = data + len - 1;
-
-        break;
-
-      case s_message_done:
-        UPDATE_STATE(NEW_MESSAGE());
-        CALLBACK_NOTIFY(message_complete);
-        if (parser->upgrade) {
-          /* Exit, the rest of the message is in a different protocol. */
-          RETURN((p - data) + 1);
-        }
-        break;
-
-      case s_chunk_size_start:
-      {
-        assert(nread == 1);
-        assert(parser->flags & F_CHUNKED);
-
-        unhex_val = unhex[(unsigned char)ch];
-        if (UNLIKELY(unhex_val == -1)) {
-          SET_ERRNO(HPE_INVALID_CHUNK_SIZE);
-          goto error;
-        }
-
-        parser->content_length = unhex_val;
-        UPDATE_STATE(s_chunk_size);
-        break;
-      }
-
-      case s_chunk_size:
-      {
-        uint64_t t;
-
-        assert(parser->flags & F_CHUNKED);
-
-        if (ch == CR) {
-          UPDATE_STATE(s_chunk_size_almost_done);
-          break;
-        }
-
-        unhex_val = unhex[(unsigned char)ch];
-
-        if (unhex_val == -1) {
-          if (ch == ';' || ch == ' ') {
-            UPDATE_STATE(s_chunk_parameters);
-            break;
-          }
-
-          SET_ERRNO(HPE_INVALID_CHUNK_SIZE);
-          goto error;
-        }
-
-        t = parser->content_length;
-        t *= 16;
-        t += unhex_val;
-
-        /* Overflow? Test against a conservative limit for simplicity. */
-        if (UNLIKELY((ULLONG_MAX - 16) / 16 < parser->content_length)) {
-          SET_ERRNO(HPE_INVALID_CONTENT_LENGTH);
-          goto error;
-        }
-
-        parser->content_length = t;
-        break;
-      }
-
-      case s_chunk_parameters:
-      {
-        assert(parser->flags & F_CHUNKED);
-        /* just ignore this shit. TODO check for overflow */
-        if (ch == CR) {
-          UPDATE_STATE(s_chunk_size_almost_done);
-          break;
-        }
-        break;
-      }
-
-      case s_chunk_size_almost_done:
-      {
-        assert(parser->flags & F_CHUNKED);
-        STRICT_CHECK(ch != LF);
-
-        parser->nread = 0;
-        nread = 0;
-
-        if (parser->content_length == 0) {
-          parser->flags |= F_TRAILING;
-          UPDATE_STATE(s_header_field_start);
-        } else {
-          UPDATE_STATE(s_chunk_data);
-        }
-        CALLBACK_NOTIFY(chunk_header);
-        break;
-      }
-
-      case s_chunk_data:
-      {
-        uint64_t to_read = MIN(parser->content_length,
-                               (uint64_t) ((data + len) - p));
-
-        assert(parser->flags & F_CHUNKED);
-        assert(parser->content_length != 0
-            && parser->content_length != ULLONG_MAX);
-
-        /* See the explanation in s_body_identity for why the content
-         * length and data pointers are managed this way.
-         */
-        MARK(body);
-        parser->content_length -= to_read;
-        p += to_read - 1;
-
-        if (parser->content_length == 0) {
-          UPDATE_STATE(s_chunk_data_almost_done);
-        }
-
-        break;
-      }
-
-      case s_chunk_data_almost_done:
-        assert(parser->flags & F_CHUNKED);
-        assert(parser->content_length == 0);
-        STRICT_CHECK(ch != CR);
-        UPDATE_STATE(s_chunk_data_done);
-        CALLBACK_DATA(body);
-        break;
-
-      case s_chunk_data_done:
-        assert(parser->flags & F_CHUNKED);
-        STRICT_CHECK(ch != LF);
-        parser->nread = 0;
-        nread = 0;
-        UPDATE_STATE(s_chunk_size_start);
-        CALLBACK_NOTIFY(chunk_complete);
-        break;
-
-      default:
-        assert(0 && "unhandled state");
-        SET_ERRNO(HPE_INVALID_INTERNAL_STATE);
-        goto error;
-    }
-  }
-
-  /* Run callbacks for any marks that we have leftover after we ran our of
-   * bytes. There should be at most one of these set, so it's OK to invoke
-   * them in series (unset marks will not result in callbacks).
-   *
-   * We use the NOADVANCE() variety of callbacks here because 'p' has already
-   * overflowed 'data' and this allows us to correct for the off-by-one that
-   * we'd otherwise have (since CALLBACK_DATA() is meant to be run with a 'p'
-   * value that's in-bounds).
-   */
-
-  assert(((header_field_mark ? 1 : 0) +
-          (header_value_mark ? 1 : 0) +
-          (url_mark ? 1 : 0)  +
-          (body_mark ? 1 : 0) +
-          (status_mark ? 1 : 0)) <= 1);
-
-  CALLBACK_DATA_NOADVANCE(header_field);
-  CALLBACK_DATA_NOADVANCE(header_value);
-  CALLBACK_DATA_NOADVANCE(url);
-  CALLBACK_DATA_NOADVANCE(body);
-  CALLBACK_DATA_NOADVANCE(status);
-
-  RETURN(len);
-
-error:
-  if (HTTP_PARSER_ERRNO(parser) == HPE_OK) {
-    SET_ERRNO(HPE_UNKNOWN);
-  }
-
-  RETURN(p - data);
-}
-
-
-/* Does the parser need to see an EOF to find the end of the message? */
-int
-http_message_needs_eof (const http_parser *parser)
-{
-  if (parser->type == HTTP_REQUEST) {
-    return 0;
-  }
-
-  /* See RFC 2616 section 4.4 */
-  if (parser->status_code / 100 == 1 || /* 1xx e.g. Continue */
-      parser->status_code == 204 ||     /* No Content */
-      parser->status_code == 304 ||     /* Not Modified */
-      parser->flags & F_SKIPBODY) {     /* response to a HEAD request */
-    return 0;
-  }
-
-  if ((parser->flags & F_CHUNKED) || parser->content_length != ULLONG_MAX) {
-    return 0;
-  }
-
-  return 1;
-}
-
-
-int
-http_should_keep_alive (const http_parser *parser)
-{
-  if (parser->http_major > 0 && parser->http_minor > 0) {
-    /* HTTP/1.1 */
-    if (parser->flags & F_CONNECTION_CLOSE) {
-      return 0;
-    }
-  } else {
-    /* HTTP/1.0 or earlier */
-    if (!(parser->flags & F_CONNECTION_KEEP_ALIVE)) {
-      return 0;
-    }
-  }
-
-  return !http_message_needs_eof(parser);
-}
-
-
-const char *
-http_method_str (enum http_method m)
-{
-  return ELEM_AT(method_strings, m, "<unknown>");
-}
-
-const char *
-http_status_str (enum http_status s)
-{
-  switch (s) {
-#define XX(num, name, string) case HTTP_STATUS_##name: return #string;
-    HTTP_STATUS_MAP(XX)
-#undef XX
-    default: return "<unknown>";
-  }
-}
-
-void
-http_parser_init (http_parser *parser, enum http_parser_type t)
-{
-  void *data = parser->data; /* preserve application data */
-  memset(parser, 0, sizeof(*parser));
-  parser->data = data;
-  parser->type = t;
-  parser->state = (t == HTTP_REQUEST ? s_start_req : (t == HTTP_RESPONSE ? s_start_res : s_start_req_or_res));
-  parser->http_errno = HPE_OK;
-}
-
-void
-http_parser_settings_init(http_parser_settings *settings)
-{
-  memset(settings, 0, sizeof(*settings));
-}
-
-const char *
-http_errno_name(enum http_errno err) {
-  assert(((size_t) err) < ARRAY_SIZE(http_strerror_tab));
-  return http_strerror_tab[err].name;
-}
-
-const char *
-http_errno_description(enum http_errno err) {
-  assert(((size_t) err) < ARRAY_SIZE(http_strerror_tab));
-  return http_strerror_tab[err].description;
-}
-
-static enum http_host_state
-http_parse_host_char(enum http_host_state s, const char ch) {
-  switch(s) {
-    case s_http_userinfo:
-    case s_http_userinfo_start:
-      if (ch == '@') {
-        return s_http_host_start;
-      }
-
-      if (IS_USERINFO_CHAR(ch)) {
-        return s_http_userinfo;
-      }
-      break;
-
-    case s_http_host_start:
-      if (ch == '[') {
-        return s_http_host_v6_start;
-      }
-
-      if (IS_HOST_CHAR(ch)) {
-        return s_http_host;
-      }
-
-      break;
-
-    case s_http_host:
-      if (IS_HOST_CHAR(ch)) {
-        return s_http_host;
-      }
-
-    /* fall through */
-    case s_http_host_v6_end:
-      if (ch == ':') {
-        return s_http_host_port_start;
-      }
-
-      break;
-
-    case s_http_host_v6:
-      if (ch == ']') {
-        return s_http_host_v6_end;
-      }
-
-    /* fall through */
-    case s_http_host_v6_start:
-      if (IS_HEX(ch) || ch == ':' || ch == '.') {
-        return s_http_host_v6;
-      }
-
-      if (s == s_http_host_v6 && ch == '%') {
-        return s_http_host_v6_zone_start;
-      }
-      break;
-
-    case s_http_host_v6_zone:
-      if (ch == ']') {
-        return s_http_host_v6_end;
-      }
-
-    /* fall through */
-    case s_http_host_v6_zone_start:
-      /* RFC 6874 Zone ID consists of 1*( unreserved / pct-encoded) */
-      if (IS_ALPHANUM(ch) || ch == '%' || ch == '.' || ch == '-' || ch == '_' ||
-          ch == '~') {
-        return s_http_host_v6_zone;
-      }
-      break;
-
-    case s_http_host_port:
-    case s_http_host_port_start:
-      if (IS_NUM(ch)) {
-        return s_http_host_port;
-      }
-
-      break;
-
-    default:
-      break;
-  }
-  return s_http_host_dead;
-}
-
-static int
-http_parse_host(const char * buf, struct http_parser_url *u, int found_at) {
-  enum http_host_state s;
-
-  const char *p;
-  size_t buflen = u->field_data[UF_HOST].off + u->field_data[UF_HOST].len;
-
-  assert(u->field_set & (1 << UF_HOST));
-
-  u->field_data[UF_HOST].len = 0;
-
-  s = found_at ? s_http_userinfo_start : s_http_host_start;
-
-  for (p = buf + u->field_data[UF_HOST].off; p < buf + buflen; p++) {
-    enum http_host_state new_s = http_parse_host_char(s, *p);
-
-    if (new_s == s_http_host_dead) {
-      return 1;
-    }
-
-    switch(new_s) {
-      case s_http_host:
-        if (s != s_http_host) {
-          u->field_data[UF_HOST].off = p - buf;
-        }
-        u->field_data[UF_HOST].len++;
-        break;
-
-      case s_http_host_v6:
-        if (s != s_http_host_v6) {
-          u->field_data[UF_HOST].off = p - buf;
-        }
-        u->field_data[UF_HOST].len++;
-        break;
-
-      case s_http_host_v6_zone_start:
-      case s_http_host_v6_zone:
-        u->field_data[UF_HOST].len++;
-        break;
-
-      case s_http_host_port:
-        if (s != s_http_host_port) {
-          u->field_data[UF_PORT].off = p - buf;
-          u->field_data[UF_PORT].len = 0;
-          u->field_set |= (1 << UF_PORT);
-        }
-        u->field_data[UF_PORT].len++;
-        break;
-
-      case s_http_userinfo:
-        if (s != s_http_userinfo) {
-          u->field_data[UF_USERINFO].off = p - buf ;
-          u->field_data[UF_USERINFO].len = 0;
-          u->field_set |= (1 << UF_USERINFO);
-        }
-        u->field_data[UF_USERINFO].len++;
-        break;
-
-      default:
-        break;
-    }
-    s = new_s;
-  }
-
-  /* Make sure we don't end somewhere unexpected */
-  switch (s) {
-    case s_http_host_start:
-    case s_http_host_v6_start:
-    case s_http_host_v6:
-    case s_http_host_v6_zone_start:
-    case s_http_host_v6_zone:
-    case s_http_host_port_start:
-    case s_http_userinfo:
-    case s_http_userinfo_start:
-      return 1;
-    default:
-      break;
-  }
-
-  return 0;
-}
-
-void
-http_parser_url_init(struct http_parser_url *u) {
-  memset(u, 0, sizeof(*u));
-}
-
-int
-http_parser_parse_url(const char *buf, size_t buflen, int is_connect,
-                      struct http_parser_url *u)
-{
-  enum state s;
-  const char *p;
-  enum http_parser_url_fields uf, old_uf;
-  int found_at = 0;
-
-  if (buflen == 0) {
-    return 1;
-  }
-
-  u->port = u->field_set = 0;
-  s = is_connect ? s_req_server_start : s_req_spaces_before_url;
-  old_uf = UF_MAX;
-
-  for (p = buf; p < buf + buflen; p++) {
-    s = parse_url_char(s, *p);
-
-    /* Figure out the next field that we're operating on */
-    switch (s) {
-      case s_dead:
-        return 1;
-
-      /* Skip delimeters */
-      case s_req_schema_slash:
-      case s_req_schema_slash_slash:
-      case s_req_server_start:
-      case s_req_query_string_start:
-      case s_req_fragment_start:
-        continue;
-
-      case s_req_schema:
-        uf = UF_SCHEMA;
-        break;
-
-      case s_req_server_with_at:
-        found_at = 1;
-
-      /* fall through */
-      case s_req_server:
-        uf = UF_HOST;
-        break;
-
-      case s_req_path:
-        uf = UF_PATH;
-        break;
-
-      case s_req_query_string:
-        uf = UF_QUERY;
-        break;
-
-      case s_req_fragment:
-        uf = UF_FRAGMENT;
-        break;
-
-      default:
-        assert(!"Unexpected state");
-        return 1;
-    }
-
-    /* Nothing's changed; soldier on */
-    if (uf == old_uf) {
-      u->field_data[uf].len++;
-      continue;
-    }
-
-    u->field_data[uf].off = p - buf;
-    u->field_data[uf].len = 1;
-
-    u->field_set |= (1 << uf);
-    old_uf = uf;
-  }
-
-  /* host must be present if there is a schema */
-  /* parsing http:///toto will fail */
-  if ((u->field_set & (1 << UF_SCHEMA)) &&
-      (u->field_set & (1 << UF_HOST)) == 0) {
-    return 1;
-  }
-
-  if (u->field_set & (1 << UF_HOST)) {
-    if (http_parse_host(buf, u, found_at) != 0) {
-      return 1;
-    }
-  }
-
-  /* CONNECT requests can only contain "hostname:port" */
-  if (is_connect && u->field_set != ((1 << UF_HOST)|(1 << UF_PORT))) {
-    return 1;
-  }
-
-  if (u->field_set & (1 << UF_PORT)) {
-    uint16_t off;
-    uint16_t len;
-    const char* p;
-    const char* end;
-    unsigned long v;
-
-    off = u->field_data[UF_PORT].off;
-    len = u->field_data[UF_PORT].len;
-    end = buf + off + len;
-
-    /* NOTE: The characters are already validated and are in the [0-9] range */
-    assert(off + len <= buflen && "Port number overflow");
-    v = 0;
-    for (p = buf + off; p < end; p++) {
-      v *= 10;
-      v += *p - '0';
-
-      /* Ports have a max value of 2^16 */
-      if (v > 0xffff) {
-        return 1;
-      }
-    }
-
-    u->port = (uint16_t) v;
-  }
-
-  return 0;
-}
-
-void
-http_parser_pause(http_parser *parser, int paused) {
-  /* Users should only be pausing/unpausing a parser that is not in an error
-   * state. In non-debug builds, there's not much that we can do about this
-   * other than ignore it.
-   */
-  if (HTTP_PARSER_ERRNO(parser) == HPE_OK ||
-      HTTP_PARSER_ERRNO(parser) == HPE_PAUSED) {
-    uint32_t nread = parser->nread; /* used by the SET_ERRNO macro */
-    SET_ERRNO((paused) ? HPE_PAUSED : HPE_OK);
-  } else {
-    assert(0 && "Attempting to pause parser in error state");
-  }
-}
-
-int
-http_body_is_final(const struct http_parser *parser) {
-    return parser->state == s_message_done;
-}
-
-unsigned long
-http_parser_version(void) {
-  return HTTP_PARSER_VERSION_MAJOR * 0x10000 |
-         HTTP_PARSER_VERSION_MINOR * 0x00100 |
-         HTTP_PARSER_VERSION_PATCH * 0x00001;
-}
-
-}  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/jni/DataLogJNI.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/jni/DataLogJNI.cpp
new file mode 100644
index 0000000..997b90b
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/cpp/jni/DataLogJNI.cpp
@@ -0,0 +1,357 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <jni.h>
+
+#include "edu_wpi_first_util_datalog_DataLogJNI.h"
+#include "wpi/DataLog.h"
+#include "wpi/jni_util.h"
+
+using namespace wpi::java;
+using namespace wpi::log;
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_util_datalog_DataLogJNI
+ * Method:    create
+ * Signature: (Ljava/lang/String;Ljava/lang/String;DLjava/lang/String;)J
+ */
+JNIEXPORT jlong JNICALL
+Java_edu_wpi_first_util_datalog_DataLogJNI_create
+  (JNIEnv* env, jclass, jstring dir, jstring filename, jdouble period,
+   jstring extraHeader)
+{
+  return reinterpret_cast<jlong>(new DataLog{JStringRef{env, dir},
+                                             JStringRef{env, filename}, period,
+                                             JStringRef{env, extraHeader}});
+}
+
+/*
+ * Class:     edu_wpi_first_util_datalog_DataLogJNI
+ * Method:    setFilename
+ * Signature: (JLjava/lang/String;)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_util_datalog_DataLogJNI_setFilename
+  (JNIEnv* env, jclass, jlong impl, jstring filename)
+{
+  if (impl == 0) {
+    return;
+  }
+  reinterpret_cast<DataLog*>(impl)->SetFilename(JStringRef{env, filename});
+}
+
+/*
+ * Class:     edu_wpi_first_util_datalog_DataLogJNI
+ * Method:    flush
+ * Signature: (J)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_util_datalog_DataLogJNI_flush
+  (JNIEnv*, jclass, jlong impl)
+{
+  if (impl == 0) {
+    return;
+  }
+  reinterpret_cast<DataLog*>(impl)->Flush();
+}
+
+/*
+ * Class:     edu_wpi_first_util_datalog_DataLogJNI
+ * Method:    pause
+ * Signature: (J)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_util_datalog_DataLogJNI_pause
+  (JNIEnv*, jclass, jlong impl)
+{
+  if (impl == 0) {
+    return;
+  }
+  reinterpret_cast<DataLog*>(impl)->Pause();
+}
+
+/*
+ * Class:     edu_wpi_first_util_datalog_DataLogJNI
+ * Method:    resume
+ * Signature: (J)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_util_datalog_DataLogJNI_resume
+  (JNIEnv*, jclass, jlong impl)
+{
+  if (impl == 0) {
+    return;
+  }
+  reinterpret_cast<DataLog*>(impl)->Resume();
+}
+
+/*
+ * Class:     edu_wpi_first_util_datalog_DataLogJNI
+ * Method:    start
+ * Signature: (JLjava/lang/String;Ljava/lang/String;Ljava/lang/String;J)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_util_datalog_DataLogJNI_start
+  (JNIEnv* env, jclass, jlong impl, jstring name, jstring type,
+   jstring metadata, jlong timestamp)
+{
+  if (impl == 0) {
+    return 0;
+  }
+  return reinterpret_cast<DataLog*>(impl)->Start(
+      JStringRef{env, name}, JStringRef{env, type}, JStringRef{env, metadata},
+      timestamp);
+}
+
+/*
+ * Class:     edu_wpi_first_util_datalog_DataLogJNI
+ * Method:    finish
+ * Signature: (JIJ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_util_datalog_DataLogJNI_finish
+  (JNIEnv*, jclass, jlong impl, jint entry, jlong timestamp)
+{
+  if (impl == 0) {
+    return;
+  }
+  reinterpret_cast<DataLog*>(impl)->Finish(entry, timestamp);
+}
+
+/*
+ * Class:     edu_wpi_first_util_datalog_DataLogJNI
+ * Method:    setMetadata
+ * Signature: (JILjava/lang/String;J)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_util_datalog_DataLogJNI_setMetadata
+  (JNIEnv* env, jclass, jlong impl, jint entry, jstring metadata,
+   jlong timestamp)
+{
+  if (impl == 0) {
+    return;
+  }
+  reinterpret_cast<DataLog*>(impl)->SetMetadata(
+      entry, JStringRef{env, metadata}, timestamp);
+}
+
+/*
+ * Class:     edu_wpi_first_util_datalog_DataLogJNI
+ * Method:    close
+ * Signature: (J)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_util_datalog_DataLogJNI_close
+  (JNIEnv*, jclass, jlong impl)
+{
+  delete reinterpret_cast<DataLog*>(impl);
+}
+
+/*
+ * Class:     edu_wpi_first_util_datalog_DataLogJNI
+ * Method:    appendRaw
+ * Signature: (JI[BJ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_util_datalog_DataLogJNI_appendRaw
+  (JNIEnv* env, jclass, jlong impl, jint entry, jbyteArray value,
+   jlong timestamp)
+{
+  if (impl == 0) {
+    return;
+  }
+  JByteArrayRef cvalue{env, value};
+  reinterpret_cast<DataLog*>(impl)->AppendRaw(
+      entry,
+      {reinterpret_cast<const uint8_t*>(cvalue.array().data()), cvalue.size()},
+      timestamp);
+}
+
+/*
+ * Class:     edu_wpi_first_util_datalog_DataLogJNI
+ * Method:    appendBoolean
+ * Signature: (JIZJ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_util_datalog_DataLogJNI_appendBoolean
+  (JNIEnv*, jclass, jlong impl, jint entry, jboolean value, jlong timestamp)
+{
+  if (impl == 0) {
+    return;
+  }
+  reinterpret_cast<DataLog*>(impl)->AppendBoolean(entry, value, timestamp);
+}
+
+/*
+ * Class:     edu_wpi_first_util_datalog_DataLogJNI
+ * Method:    appendInteger
+ * Signature: (JIJJ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_util_datalog_DataLogJNI_appendInteger
+  (JNIEnv*, jclass, jlong impl, jint entry, jlong value, jlong timestamp)
+{
+  if (impl == 0) {
+    return;
+  }
+  reinterpret_cast<DataLog*>(impl)->AppendInteger(entry, value, timestamp);
+}
+
+/*
+ * Class:     edu_wpi_first_util_datalog_DataLogJNI
+ * Method:    appendFloat
+ * Signature: (JIFJ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_util_datalog_DataLogJNI_appendFloat
+  (JNIEnv*, jclass, jlong impl, jint entry, jfloat value, jlong timestamp)
+{
+  if (impl == 0) {
+    return;
+  }
+  reinterpret_cast<DataLog*>(impl)->AppendFloat(entry, value, timestamp);
+}
+
+/*
+ * Class:     edu_wpi_first_util_datalog_DataLogJNI
+ * Method:    appendDouble
+ * Signature: (JIDJ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_util_datalog_DataLogJNI_appendDouble
+  (JNIEnv*, jclass, jlong impl, jint entry, jdouble value, jlong timestamp)
+{
+  if (impl == 0) {
+    return;
+  }
+  reinterpret_cast<DataLog*>(impl)->AppendDouble(entry, value, timestamp);
+}
+
+/*
+ * Class:     edu_wpi_first_util_datalog_DataLogJNI
+ * Method:    appendString
+ * Signature: (JILjava/lang/String;J)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_util_datalog_DataLogJNI_appendString
+  (JNIEnv* env, jclass, jlong impl, jint entry, jstring value, jlong timestamp)
+{
+  if (impl == 0) {
+    return;
+  }
+  reinterpret_cast<DataLog*>(impl)->AppendString(entry, JStringRef{env, value},
+                                                 timestamp);
+}
+
+/*
+ * Class:     edu_wpi_first_util_datalog_DataLogJNI
+ * Method:    appendBooleanArray
+ * Signature: (JI[ZJ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_util_datalog_DataLogJNI_appendBooleanArray
+  (JNIEnv* env, jclass, jlong impl, jint entry, jbooleanArray value,
+   jlong timestamp)
+{
+  if (impl == 0) {
+    return;
+  }
+  reinterpret_cast<DataLog*>(impl)->AppendBooleanArray(
+      entry, JBooleanArrayRef{env, value}, timestamp);
+}
+
+/*
+ * Class:     edu_wpi_first_util_datalog_DataLogJNI
+ * Method:    appendIntegerArray
+ * Signature: (JI[JJ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_util_datalog_DataLogJNI_appendIntegerArray
+  (JNIEnv* env, jclass, jlong impl, jint entry, jlongArray value,
+   jlong timestamp)
+{
+  if (impl == 0) {
+    return;
+  }
+  JLongArrayRef jarr{env, value};
+  if constexpr (sizeof(jlong) == sizeof(int64_t)) {
+    reinterpret_cast<DataLog*>(impl)->AppendIntegerArray(
+        entry,
+        {reinterpret_cast<const int64_t*>(jarr.array().data()),
+         jarr.array().size()},
+        timestamp);
+  } else {
+    wpi::SmallVector<int64_t, 16> arr;
+    arr.reserve(jarr.size());
+    for (auto v : jarr.array()) {
+      arr.push_back(v);
+    }
+    reinterpret_cast<DataLog*>(impl)->AppendIntegerArray(entry, arr, timestamp);
+  }
+}
+
+/*
+ * Class:     edu_wpi_first_util_datalog_DataLogJNI
+ * Method:    appendFloatArray
+ * Signature: (JI[FJ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_util_datalog_DataLogJNI_appendFloatArray
+  (JNIEnv* env, jclass, jlong impl, jint entry, jfloatArray value,
+   jlong timestamp)
+{
+  if (impl == 0) {
+    return;
+  }
+  reinterpret_cast<DataLog*>(impl)->AppendFloatArray(
+      entry, JFloatArrayRef{env, value}, timestamp);
+}
+
+/*
+ * Class:     edu_wpi_first_util_datalog_DataLogJNI
+ * Method:    appendDoubleArray
+ * Signature: (JI[DJ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_util_datalog_DataLogJNI_appendDoubleArray
+  (JNIEnv* env, jclass, jlong impl, jint entry, jdoubleArray value,
+   jlong timestamp)
+{
+  if (impl == 0) {
+    return;
+  }
+  reinterpret_cast<DataLog*>(impl)->AppendDoubleArray(
+      entry, JDoubleArrayRef{env, value}, timestamp);
+}
+
+/*
+ * Class:     edu_wpi_first_util_datalog_DataLogJNI
+ * Method:    appendStringArray
+ * Signature: (JI[Ljava/lang/Object;J)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_util_datalog_DataLogJNI_appendStringArray
+  (JNIEnv* env, jclass, jlong impl, jint entry, jobjectArray value,
+   jlong timestamp)
+{
+  if (impl == 0) {
+    return;
+  }
+  size_t len = env->GetArrayLength(value);
+  std::vector<std::string> arr;
+  arr.reserve(len);
+  for (size_t i = 0; i < len; ++i) {
+    JLocal<jstring> elem{
+        env, static_cast<jstring>(env->GetObjectArrayElement(value, i))};
+    if (!elem) {
+      return;
+    }
+    arr.emplace_back(JStringRef{env, elem}.str());
+  }
+  reinterpret_cast<DataLog*>(impl)->AppendStringArray(entry, arr, timestamp);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/jni/WPIUtilJNI.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/jni/WPIUtilJNI.cpp
index e876d9c..5fa4ddf 100644
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/jni/WPIUtilJNI.cpp
+++ b/third_party/allwpilib/wpiutil/src/main/native/cpp/jni/WPIUtilJNI.cpp
@@ -4,14 +4,9 @@
 
 #include <jni.h>
 
-#include "../MulticastHandleManager.h"
 #include "edu_wpi_first_util_WPIUtilJNI.h"
-#include "wpi/DenseMap.h"
-#include "wpi/MulticastServiceAnnouncer.h"
-#include "wpi/MulticastServiceResolver.h"
-#include "wpi/PortForwarder.h"
+#include "fmt/format.h"
 #include "wpi/Synchronization.h"
-#include "wpi/UidVector.h"
 #include "wpi/jni_util.h"
 #include "wpi/timestamp.h"
 
@@ -21,8 +16,6 @@
 static uint64_t mockNow = 0;
 
 static JException interruptedEx;
-static JClass serviceDataCls;
-static JGlobal<jobjectArray> serviceDataEmptyArray;
 
 extern "C" {
 
@@ -37,17 +30,6 @@
     return JNI_ERR;
   }
 
-  serviceDataCls = JClass{env, "edu/wpi/first/util/ServiceData"};
-  if (!serviceDataCls) {
-    return JNI_ERR;
-  }
-
-  serviceDataEmptyArray = JGlobal<jobjectArray>{
-      env, env->NewObjectArray(0, serviceDataCls, nullptr)};
-  if (serviceDataEmptyArray == nullptr) {
-    return JNI_ERR;
-  }
-
   return JNI_VERSION_1_6;
 }
 
@@ -57,13 +39,23 @@
     return;
   }
 
-  serviceDataEmptyArray.free(env);
-  serviceDataCls.free(env);
   interruptedEx.free(env);
 }
 
 /*
  * Class:     edu_wpi_first_util_WPIUtilJNI
+ * Method:    writeStderr
+ * Signature: (Ljava/lang/String;)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_util_WPIUtilJNI_writeStderr
+  (JNIEnv* env, jclass, jstring str)
+{
+  fmt::print(stderr, "{}", JStringRef{env, str});
+}
+
+/*
+ * Class:     edu_wpi_first_util_WPIUtilJNI
  * Method:    enableMockTime
  * Signature: ()V
  */
@@ -130,32 +122,6 @@
 
 /*
  * Class:     edu_wpi_first_util_WPIUtilJNI
- * Method:    addPortForwarder
- * Signature: (ILjava/lang/String;I)V
- */
-JNIEXPORT void JNICALL
-Java_edu_wpi_first_util_WPIUtilJNI_addPortForwarder
-  (JNIEnv* env, jclass, jint port, jstring remoteHost, jint remotePort)
-{
-  wpi::PortForwarder::GetInstance().Add(static_cast<unsigned int>(port),
-                                        JStringRef{env, remoteHost}.str(),
-                                        static_cast<unsigned int>(remotePort));
-}
-
-/*
- * Class:     edu_wpi_first_util_WPIUtilJNI
- * Method:    removePortForwarder
- * Signature: (I)V
- */
-JNIEXPORT void JNICALL
-Java_edu_wpi_first_util_WPIUtilJNI_removePortForwarder
-  (JNIEnv* env, jclass, jint port)
-{
-  wpi::PortForwarder::GetInstance().Remove(port);
-}
-
-/*
- * Class:     edu_wpi_first_util_WPIUtilJNI
  * Method:    createEvent
  * Signature: (ZZ)I
  */
@@ -281,7 +247,7 @@
   JIntArrayRef handlesArr{env, handles};
   wpi::SmallVector<WPI_Handle, 8> signaledBuf;
   signaledBuf.resize(handlesArr.size());
-  wpi::span<const WPI_Handle> handlesArr2{
+  std::span<const WPI_Handle> handlesArr2{
       reinterpret_cast<const WPI_Handle*>(handlesArr.array().data()),
       handlesArr.size()};
 
@@ -305,7 +271,7 @@
   JIntArrayRef handlesArr{env, handles};
   wpi::SmallVector<WPI_Handle, 8> signaledBuf;
   signaledBuf.resize(handlesArr.size());
-  wpi::span<const WPI_Handle> handlesArr2{
+  std::span<const WPI_Handle> handlesArr2{
       reinterpret_cast<const WPI_Handle*>(handlesArr.array().data()),
       handlesArr.size()};
 
@@ -319,257 +285,4 @@
   return MakeJIntArray(env, signaled);
 }
 
-/*
- * Class:     edu_wpi_first_util_WPIUtilJNI
- * Method:    createMulticastServiceAnnouncer
- * Signature: (Ljava/lang/String;Ljava/lang/String;I[Ljava/lang/Object;[Ljava/lang/Object;)I
- */
-JNIEXPORT jint JNICALL
-Java_edu_wpi_first_util_WPIUtilJNI_createMulticastServiceAnnouncer
-  (JNIEnv* env, jclass, jstring serviceName, jstring serviceType, jint port,
-   jobjectArray keys, jobjectArray values)
-{
-  auto& manager = wpi::GetMulticastManager();
-  std::scoped_lock lock{manager.mutex};
-
-  JStringRef serviceNameRef{env, serviceName};
-  JStringRef serviceTypeRef{env, serviceType};
-
-  size_t keysLen = env->GetArrayLength(keys);
-  wpi::SmallVector<std::pair<std::string, std::string>, 8> txtVec;
-  txtVec.reserve(keysLen);
-  for (size_t i = 0; i < keysLen; i++) {
-    JLocal<jstring> key{
-        env, static_cast<jstring>(env->GetObjectArrayElement(keys, i))};
-    JLocal<jstring> value{
-        env, static_cast<jstring>(env->GetObjectArrayElement(values, i))};
-
-    txtVec.emplace_back(std::pair<std::string, std::string>{
-        JStringRef{env, key}.str(), JStringRef{env, value}.str()});
-  }
-
-  auto announcer = std::make_unique<wpi::MulticastServiceAnnouncer>(
-      serviceNameRef.str(), serviceTypeRef.str(), port, txtVec);
-
-  size_t index = manager.handleIds.emplace_back(1);
-
-  manager.announcers[index] = std::move(announcer);
-
-  return static_cast<jint>(index);
-}
-
-/*
- * Class:     edu_wpi_first_util_WPIUtilJNI
- * Method:    freeMulticastServiceAnnouncer
- * Signature: (I)V
- */
-JNIEXPORT void JNICALL
-Java_edu_wpi_first_util_WPIUtilJNI_freeMulticastServiceAnnouncer
-  (JNIEnv* env, jclass, jint handle)
-{
-  auto& manager = wpi::GetMulticastManager();
-  std::scoped_lock lock{manager.mutex};
-  manager.announcers[handle] = nullptr;
-  manager.handleIds.erase(handle);
-}
-
-/*
- * Class:     edu_wpi_first_util_WPIUtilJNI
- * Method:    startMulticastServiceAnnouncer
- * Signature: (I)V
- */
-JNIEXPORT void JNICALL
-Java_edu_wpi_first_util_WPIUtilJNI_startMulticastServiceAnnouncer
-  (JNIEnv* env, jclass, jint handle)
-{
-  auto& manager = wpi::GetMulticastManager();
-  std::scoped_lock lock{manager.mutex};
-  auto& announcer = manager.announcers[handle];
-  announcer->Start();
-}
-
-/*
- * Class:     edu_wpi_first_util_WPIUtilJNI
- * Method:    stopMulticastServiceAnnouncer
- * Signature: (I)V
- */
-JNIEXPORT void JNICALL
-Java_edu_wpi_first_util_WPIUtilJNI_stopMulticastServiceAnnouncer
-  (JNIEnv* env, jclass, jint handle)
-{
-  auto& manager = wpi::GetMulticastManager();
-  std::scoped_lock lock{manager.mutex};
-  auto& announcer = manager.announcers[handle];
-  announcer->Stop();
-}
-
-/*
- * Class:     edu_wpi_first_util_WPIUtilJNI
- * Method:    getMulticastServiceAnnouncerHasImplementation
- * Signature: (I)Z
- */
-JNIEXPORT jboolean JNICALL
-Java_edu_wpi_first_util_WPIUtilJNI_getMulticastServiceAnnouncerHasImplementation
-  (JNIEnv* env, jclass, jint handle)
-{
-  auto& manager = wpi::GetMulticastManager();
-  std::scoped_lock lock{manager.mutex};
-  auto& announcer = manager.announcers[handle];
-  return announcer->HasImplementation();
-}
-
-/*
- * Class:     edu_wpi_first_util_WPIUtilJNI
- * Method:    createMulticastServiceResolver
- * Signature: (Ljava/lang/String;)I
- */
-JNIEXPORT jint JNICALL
-Java_edu_wpi_first_util_WPIUtilJNI_createMulticastServiceResolver
-  (JNIEnv* env, jclass, jstring serviceType)
-{
-  auto& manager = wpi::GetMulticastManager();
-  std::scoped_lock lock{manager.mutex};
-  JStringRef serviceTypeRef{env, serviceType};
-
-  auto resolver =
-      std::make_unique<wpi::MulticastServiceResolver>(serviceTypeRef.str());
-
-  size_t index = manager.handleIds.emplace_back(2);
-
-  manager.resolvers[index] = std::move(resolver);
-
-  return static_cast<jint>(index);
-}
-
-/*
- * Class:     edu_wpi_first_util_WPIUtilJNI
- * Method:    freeMulticastServiceResolver
- * Signature: (I)V
- */
-JNIEXPORT void JNICALL
-Java_edu_wpi_first_util_WPIUtilJNI_freeMulticastServiceResolver
-  (JNIEnv* env, jclass, jint handle)
-{
-  auto& manager = wpi::GetMulticastManager();
-  std::scoped_lock lock{manager.mutex};
-  manager.resolvers[handle] = nullptr;
-  manager.handleIds.erase(handle);
-}
-
-/*
- * Class:     edu_wpi_first_util_WPIUtilJNI
- * Method:    startMulticastServiceResolver
- * Signature: (I)V
- */
-JNIEXPORT void JNICALL
-Java_edu_wpi_first_util_WPIUtilJNI_startMulticastServiceResolver
-  (JNIEnv* env, jclass, jint handle)
-{
-  auto& manager = wpi::GetMulticastManager();
-  std::scoped_lock lock{manager.mutex};
-  auto& resolver = manager.resolvers[handle];
-  resolver->Start();
-}
-
-/*
- * Class:     edu_wpi_first_util_WPIUtilJNI
- * Method:    stopMulticastServiceResolver
- * Signature: (I)V
- */
-JNIEXPORT void JNICALL
-Java_edu_wpi_first_util_WPIUtilJNI_stopMulticastServiceResolver
-  (JNIEnv* env, jclass, jint handle)
-{
-  auto& manager = wpi::GetMulticastManager();
-  std::scoped_lock lock{manager.mutex};
-  auto& resolver = manager.resolvers[handle];
-  resolver->Stop();
-}
-
-/*
- * Class:     edu_wpi_first_util_WPIUtilJNI
- * Method:    getMulticastServiceResolverHasImplementation
- * Signature: (I)Z
- */
-JNIEXPORT jboolean JNICALL
-Java_edu_wpi_first_util_WPIUtilJNI_getMulticastServiceResolverHasImplementation
-  (JNIEnv* env, jclass, jint handle)
-{
-  auto& manager = wpi::GetMulticastManager();
-  std::scoped_lock lock{manager.mutex};
-  auto& resolver = manager.resolvers[handle];
-  return resolver->HasImplementation();
-}
-
-/*
- * Class:     edu_wpi_first_util_WPIUtilJNI
- * Method:    getMulticastServiceResolverEventHandle
- * Signature: (I)I
- */
-JNIEXPORT jint JNICALL
-Java_edu_wpi_first_util_WPIUtilJNI_getMulticastServiceResolverEventHandle
-  (JNIEnv* env, jclass, jint handle)
-{
-  auto& manager = wpi::GetMulticastManager();
-  std::scoped_lock lock{manager.mutex};
-  auto& resolver = manager.resolvers[handle];
-  return resolver->GetEventHandle();
-}
-
-/*
- * Class:     edu_wpi_first_util_WPIUtilJNI
- * Method:    getMulticastServiceResolverData
- * Signature: (I)[Ljava/lang/Object;
- */
-JNIEXPORT jobjectArray JNICALL
-Java_edu_wpi_first_util_WPIUtilJNI_getMulticastServiceResolverData
-  (JNIEnv* env, jclass, jint handle)
-{
-  static jmethodID constructor =
-      env->GetMethodID(serviceDataCls, "<init>",
-                       "(JILjava/lang/String;Ljava/lang/String;[Ljava/lang/"
-                       "String;[Ljava/lang/String;)V");
-  auto& manager = wpi::GetMulticastManager();
-  std::vector<wpi::MulticastServiceResolver::ServiceData> allData;
-  {
-    std::scoped_lock lock{manager.mutex};
-    auto& resolver = manager.resolvers[handle];
-    allData = resolver->GetData();
-  }
-  if (allData.empty()) {
-    return serviceDataEmptyArray;
-  }
-
-  JLocal<jobjectArray> returnData{
-      env, env->NewObjectArray(allData.size(), serviceDataCls, nullptr)};
-
-  for (auto&& data : allData) {
-    JLocal<jstring> serviceName{env, MakeJString(env, data.serviceName)};
-    JLocal<jstring> hostName{env, MakeJString(env, data.hostName)};
-
-    wpi::SmallVector<std::string_view, 8> keysRef;
-    wpi::SmallVector<std::string_view, 8> valuesRef;
-
-    size_t index = 0;
-    for (auto&& txt : data.txt) {
-      keysRef.emplace_back(txt.first);
-      valuesRef.emplace_back(txt.second);
-    }
-
-    JLocal<jobjectArray> keys{env, MakeJStringArray(env, keysRef)};
-    JLocal<jobjectArray> values{env, MakeJStringArray(env, valuesRef)};
-
-    JLocal<jobject> dataItem{
-        env, env->NewObject(serviceDataCls, constructor,
-                            static_cast<jlong>(data.ipv4Address),
-                            static_cast<jint>(data.port), serviceName.obj(),
-                            hostName.obj(), keys.obj(), values.obj())};
-
-    env->SetObjectArrayElement(returnData, index, dataItem);
-    index++;
-  }
-
-  return returnData;
-}
-
 }  // extern "C"
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/json_binary_reader.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/json_binary_reader.cpp
deleted file mode 100644
index cee5e39..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/json_binary_reader.cpp
+++ /dev/null
@@ -1,1415 +0,0 @@
-/*----------------------------------------------------------------------------*/
-/* Modifications Copyright (c) 2017-2018 FIRST. All Rights Reserved.          */
-/* Open Source Software - may be modified and shared by FRC teams. The code   */
-/* must be accompanied by the FIRST BSD license file in the root directory of */
-/* the project.                                                               */
-/*----------------------------------------------------------------------------*/
-/*
-    __ _____ _____ _____
- __|  |   __|     |   | |  JSON for Modern C++
-|  |  |__   |  |  | | | |  version 3.1.2
-|_____|_____|_____|_|___|  https://github.com/nlohmann/json
-
-Licensed under the MIT License <http://opensource.org/licenses/MIT>.
-Copyright (c) 2013-2018 Niels Lohmann <http://nlohmann.me>.
-
-Permission is hereby  granted, free of charge, to any  person obtaining a copy
-of this software and associated  documentation files (the "Software"), to deal
-in the Software  without restriction, including without  limitation the rights
-to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
-copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
-furnished to do so, subject to the following conditions:
-
-The above copyright notice and this permission notice shall be included in all
-copies or substantial portions of the Software.
-
-THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
-IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
-FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
-AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
-LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
-OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
-SOFTWARE.
-*/
-#define WPI_JSON_IMPLEMENTATION
-#include "wpi/json.h"
-
-#include <cmath>  // ldexp
-
-#include "fmt/format.h"
-#include "wpi/raw_istream.h"
-
-namespace wpi {
-
-/*!
-@brief deserialization of CBOR and MessagePack values
-*/
-class json::binary_reader
-{
-  public:
-    /*!
-    @brief create a binary reader
-
-    @param[in] adapter  input adapter to read from
-    */
-    explicit binary_reader(raw_istream& s) : is(s)
-    {
-    }
-
-    /*!
-    @brief create a JSON value from CBOR input
-
-    @param[in] strict  whether to expect the input to be consumed completed
-    @return JSON value created from CBOR input
-
-    @throw parse_error.110 if input ended unexpectedly or the end of file was
-                           not reached when @a strict was set to true
-    @throw parse_error.112 if unsupported byte was read
-    */
-    json parse_cbor(const bool strict)
-    {
-        const auto res = parse_cbor_internal();
-        if (strict)
-        {
-            get();
-            expect_eof();
-        }
-        return res;
-    }
-
-    /*!
-    @brief create a JSON value from MessagePack input
-
-    @param[in] strict  whether to expect the input to be consumed completed
-    @return JSON value created from MessagePack input
-
-    @throw parse_error.110 if input ended unexpectedly or the end of file was
-                           not reached when @a strict was set to true
-    @throw parse_error.112 if unsupported byte was read
-    */
-    json parse_msgpack(const bool strict)
-    {
-        const auto res = parse_msgpack_internal();
-        if (strict)
-        {
-            get();
-            expect_eof();
-        }
-        return res;
-    }
-
-    /*!
-    @brief create a JSON value from UBJSON input
-
-    @param[in] strict  whether to expect the input to be consumed completed
-    @return JSON value created from UBJSON input
-
-    @throw parse_error.110 if input ended unexpectedly or the end of file was
-                           not reached when @a strict was set to true
-    @throw parse_error.112 if unsupported byte was read
-    */
-    json parse_ubjson(const bool strict)
-    {
-        const auto res = parse_ubjson_internal();
-        if (strict)
-        {
-            get_ignore_noop();
-            expect_eof();
-        }
-        return res;
-    }
-
-    /*!
-    @brief determine system byte order
-
-    @return true if and only if system's byte order is little endian
-
-    @note from http://stackoverflow.com/a/1001328/266378
-    */
-    static bool little_endianess(int num = 1) noexcept
-    {
-        return (*reinterpret_cast<char*>(&num) == 1);
-    }
-
-  private:
-    /*!
-    @param[in] get_char  whether a new character should be retrieved from the
-                         input (true, default) or whether the last read
-                         character should be considered instead
-    */
-    json parse_cbor_internal(const bool get_char = true);
-
-    json parse_msgpack_internal();
-
-    /*!
-    @param[in] get_char  whether a new character should be retrieved from the
-                         input (true, default) or whether the last read
-                         character should be considered instead
-    */
-    json parse_ubjson_internal(const bool get_char = true)
-    {
-        return get_ubjson_value(get_char ? get_ignore_noop() : current);
-    }
-
-    /*!
-    @brief get next character from the input
-
-    This function provides the interface to the used input adapter. It does
-    not throw in case the input reached EOF, but returns a -'ve valued
-    `std::char_traits<char>::eof()` in that case.
-
-    @return character read from the input
-    */
-    int get()
-    {
-        ++chars_read;
-        unsigned char c;
-        is.read(c);
-        if (is.has_error())
-        {
-            current = std::char_traits<char>::eof();
-        }
-        else
-        {
-            current = c;
-        }
-        return current;
-    }
-
-    /*!
-    @return character read from the input after ignoring all 'N' entries
-    */
-    int get_ignore_noop()
-    {
-        do
-        {
-            get();
-        }
-        while (current == 'N');
-
-        return current;
-    }
-
-    /*
-    @brief read a number from the input
-
-    @tparam NumberType the type of the number
-
-    @return number of type @a NumberType
-
-    @note This function needs to respect the system's endianess, because
-          bytes in CBOR and MessagePack are stored in network order (big
-          endian) and therefore need reordering on little endian systems.
-
-    @throw parse_error.110 if input has less than `sizeof(NumberType)` bytes
-    */
-    template<typename NumberType> NumberType get_number()
-    {
-        // step 1: read input into array with system's byte order
-        std::array<uint8_t, sizeof(NumberType)> vec;
-        for (std::size_t i = 0; i < sizeof(NumberType); ++i)
-        {
-            get();
-            unexpect_eof();
-
-            // reverse byte order prior to conversion if necessary
-            if (is_little_endian)
-            {
-                vec[sizeof(NumberType) - i - 1] = static_cast<uint8_t>(current);
-            }
-            else
-            {
-                vec[i] = static_cast<uint8_t>(current); // LCOV_EXCL_LINE
-            }
-        }
-
-        // step 2: convert array into number of type T and return
-        NumberType result;
-        std::memcpy(&result, vec.data(), sizeof(NumberType));
-        return result;
-    }
-
-    /*!
-    @brief create a string by reading characters from the input
-
-    @param[in] len number of bytes to read
-
-    @note We can not reserve @a len bytes for the result, because @a len
-          may be too large. Usually, @ref unexpect_eof() detects the end of
-          the input before we run out of string memory.
-
-    @return string created by reading @a len bytes
-
-    @throw parse_error.110 if input has less than @a len bytes
-    */
-    template<typename NumberType>
-    std::string get_string(const NumberType len)
-    {
-        std::string result;
-        std::generate_n(std::back_inserter(result), len, [this]()
-        {
-            get();
-            unexpect_eof();
-            return static_cast<char>(current);
-        });
-        return result;
-    }
-
-    /*!
-    @brief reads a CBOR string
-
-    This function first reads starting bytes to determine the expected
-    string length and then copies this number of bytes into a string.
-    Additionally, CBOR's strings with indefinite lengths are supported.
-
-    @return string
-
-    @throw parse_error.110 if input ended
-    @throw parse_error.113 if an unexpected byte is read
-    */
-    std::string get_cbor_string();
-
-    template<typename NumberType>
-    json get_cbor_array(const NumberType len)
-    {
-        json result = value_t::array;
-        std::generate_n(std::back_inserter(*result.m_value.array), len, [this]()
-        {
-            return parse_cbor_internal();
-        });
-        return result;
-    }
-
-    template<typename NumberType>
-    json get_cbor_object(const NumberType len)
-    {
-        json result = value_t::object;
-        for (NumberType i = 0; i < len; ++i)
-        {
-            get();
-            auto key = get_cbor_string();
-            (*result.m_value.object)[key] = parse_cbor_internal();
-        }
-        return result;
-    }
-
-    /*!
-    @brief reads a MessagePack string
-
-    This function first reads starting bytes to determine the expected
-    string length and then copies this number of bytes into a string.
-
-    @return string
-
-    @throw parse_error.110 if input ended
-    @throw parse_error.113 if an unexpected byte is read
-    */
-    std::string get_msgpack_string();
-
-    template<typename NumberType>
-    json get_msgpack_array(const NumberType len)
-    {
-        json result = value_t::array;
-        std::generate_n(std::back_inserter(*result.m_value.array), len, [this]()
-        {
-            return parse_msgpack_internal();
-        });
-        return result;
-    }
-
-    template<typename NumberType>
-    json get_msgpack_object(const NumberType len)
-    {
-        json result = value_t::object;
-        for (NumberType i = 0; i < len; ++i)
-        {
-            get();
-            auto key = get_msgpack_string();
-            (*result.m_value.object)[key] = parse_msgpack_internal();
-        }
-        return result;
-    }
-
-    /*!
-    @brief reads a UBJSON string
-
-    This function is either called after reading the 'S' byte explicitly
-    indicating a string, or in case of an object key where the 'S' byte can be
-    left out.
-
-    @param[in] get_char  whether a new character should be retrieved from the
-                         input (true, default) or whether the last read
-                         character should be considered instead
-
-    @return string
-
-    @throw parse_error.110 if input ended
-    @throw parse_error.113 if an unexpected byte is read
-    */
-    std::string get_ubjson_string(const bool get_char = true);
-
-    /*!
-    @brief determine the type and size for a container
-
-    In the optimized UBJSON format, a type and a size can be provided to allow
-    for a more compact representation.
-
-    @return pair of the size and the type
-    */
-    std::pair<std::size_t, int> get_ubjson_size_type();
-
-    json get_ubjson_value(const int prefix);
-
-    json get_ubjson_array();
-
-    json get_ubjson_object();
-
-    /*!
-    @brief throw if end of input is not reached
-    @throw parse_error.110 if input not ended
-    */
-    void expect_eof() const
-    {
-        if (JSON_UNLIKELY(current != std::char_traits<char>::eof()))
-        {
-            JSON_THROW(parse_error::create(110, chars_read, "expected end of input"));
-        }
-    }
-
-    /*!
-    @briefthrow if end of input is reached
-    @throw parse_error.110 if input ended
-    */
-    void unexpect_eof() const
-    {
-        if (JSON_UNLIKELY(current == std::char_traits<char>::eof()))
-        {
-            JSON_THROW(parse_error::create(110, chars_read, "unexpected end of input"));
-        }
-    }
-
-  private:
-    /// input adapter
-    raw_istream& is;
-
-    /// the current character
-    int current = std::char_traits<char>::eof();
-
-    /// the number of characters read
-    std::size_t chars_read = 0;
-
-    /// whether we can assume little endianess
-    const bool is_little_endian = little_endianess();
-};
-
-json json::binary_reader::parse_cbor_internal(const bool get_char)
-{
-    switch (get_char ? get() : current)
-    {
-        // EOF
-        case std::char_traits<char>::eof():
-            JSON_THROW(parse_error::create(110, chars_read, "unexpected end of input"));
-
-        // Integer 0x00..0x17 (0..23)
-        case 0x00:
-        case 0x01:
-        case 0x02:
-        case 0x03:
-        case 0x04:
-        case 0x05:
-        case 0x06:
-        case 0x07:
-        case 0x08:
-        case 0x09:
-        case 0x0A:
-        case 0x0B:
-        case 0x0C:
-        case 0x0D:
-        case 0x0E:
-        case 0x0F:
-        case 0x10:
-        case 0x11:
-        case 0x12:
-        case 0x13:
-        case 0x14:
-        case 0x15:
-        case 0x16:
-        case 0x17:
-            return static_cast<uint64_t>(current);
-
-        case 0x18: // Unsigned integer (one-byte uint8_t follows)
-            return get_number<uint8_t>();
-
-        case 0x19: // Unsigned integer (two-byte uint16_t follows)
-            return get_number<uint16_t>();
-
-        case 0x1A: // Unsigned integer (four-byte uint32_t follows)
-            return get_number<uint32_t>();
-
-        case 0x1B: // Unsigned integer (eight-byte uint64_t follows)
-            return get_number<uint64_t>();
-
-        // Negative integer -1-0x00..-1-0x17 (-1..-24)
-        case 0x20:
-        case 0x21:
-        case 0x22:
-        case 0x23:
-        case 0x24:
-        case 0x25:
-        case 0x26:
-        case 0x27:
-        case 0x28:
-        case 0x29:
-        case 0x2A:
-        case 0x2B:
-        case 0x2C:
-        case 0x2D:
-        case 0x2E:
-        case 0x2F:
-        case 0x30:
-        case 0x31:
-        case 0x32:
-        case 0x33:
-        case 0x34:
-        case 0x35:
-        case 0x36:
-        case 0x37:
-            return static_cast<int8_t>(0x20 - 1 - current);
-
-        case 0x38: // Negative integer (one-byte uint8_t follows)
-        {
-            return static_cast<int64_t>(-1) - get_number<uint8_t>();
-        }
-
-        case 0x39: // Negative integer -1-n (two-byte uint16_t follows)
-        {
-            return static_cast<int64_t>(-1) - get_number<uint16_t>();
-        }
-
-        case 0x3A: // Negative integer -1-n (four-byte uint32_t follows)
-        {
-            return static_cast<int64_t>(-1) - get_number<uint32_t>();
-        }
-
-        case 0x3B: // Negative integer -1-n (eight-byte uint64_t follows)
-        {
-            return static_cast<int64_t>(-1) -
-                   static_cast<int64_t>(get_number<uint64_t>());
-        }
-
-        // UTF-8 string (0x00..0x17 bytes follow)
-        case 0x60:
-        case 0x61:
-        case 0x62:
-        case 0x63:
-        case 0x64:
-        case 0x65:
-        case 0x66:
-        case 0x67:
-        case 0x68:
-        case 0x69:
-        case 0x6A:
-        case 0x6B:
-        case 0x6C:
-        case 0x6D:
-        case 0x6E:
-        case 0x6F:
-        case 0x70:
-        case 0x71:
-        case 0x72:
-        case 0x73:
-        case 0x74:
-        case 0x75:
-        case 0x76:
-        case 0x77:
-        case 0x78: // UTF-8 string (one-byte uint8_t for n follows)
-        case 0x79: // UTF-8 string (two-byte uint16_t for n follow)
-        case 0x7A: // UTF-8 string (four-byte uint32_t for n follow)
-        case 0x7B: // UTF-8 string (eight-byte uint64_t for n follow)
-        case 0x7F: // UTF-8 string (indefinite length)
-        {
-            return get_cbor_string();
-        }
-
-        // array (0x00..0x17 data items follow)
-        case 0x80:
-        case 0x81:
-        case 0x82:
-        case 0x83:
-        case 0x84:
-        case 0x85:
-        case 0x86:
-        case 0x87:
-        case 0x88:
-        case 0x89:
-        case 0x8A:
-        case 0x8B:
-        case 0x8C:
-        case 0x8D:
-        case 0x8E:
-        case 0x8F:
-        case 0x90:
-        case 0x91:
-        case 0x92:
-        case 0x93:
-        case 0x94:
-        case 0x95:
-        case 0x96:
-        case 0x97:
-        {
-            return get_cbor_array(current & 0x1F);
-        }
-
-        case 0x98: // array (one-byte uint8_t for n follows)
-        {
-            return get_cbor_array(get_number<uint8_t>());
-        }
-
-        case 0x99: // array (two-byte uint16_t for n follow)
-        {
-            return get_cbor_array(get_number<uint16_t>());
-        }
-
-        case 0x9A: // array (four-byte uint32_t for n follow)
-        {
-            return get_cbor_array(get_number<uint32_t>());
-        }
-
-        case 0x9B: // array (eight-byte uint64_t for n follow)
-        {
-            return get_cbor_array(get_number<uint64_t>());
-        }
-
-        case 0x9F: // array (indefinite length)
-        {
-            json result = value_t::array;
-            while (get() != 0xFF)
-            {
-                result.push_back(parse_cbor_internal(false));
-            }
-            return result;
-        }
-
-        // map (0x00..0x17 pairs of data items follow)
-        case 0xA0:
-        case 0xA1:
-        case 0xA2:
-        case 0xA3:
-        case 0xA4:
-        case 0xA5:
-        case 0xA6:
-        case 0xA7:
-        case 0xA8:
-        case 0xA9:
-        case 0xAA:
-        case 0xAB:
-        case 0xAC:
-        case 0xAD:
-        case 0xAE:
-        case 0xAF:
-        case 0xB0:
-        case 0xB1:
-        case 0xB2:
-        case 0xB3:
-        case 0xB4:
-        case 0xB5:
-        case 0xB6:
-        case 0xB7:
-        {
-            return get_cbor_object(current & 0x1F);
-        }
-
-        case 0xB8: // map (one-byte uint8_t for n follows)
-        {
-            return get_cbor_object(get_number<uint8_t>());
-        }
-
-        case 0xB9: // map (two-byte uint16_t for n follow)
-        {
-            return get_cbor_object(get_number<uint16_t>());
-        }
-
-        case 0xBA: // map (four-byte uint32_t for n follow)
-        {
-            return get_cbor_object(get_number<uint32_t>());
-        }
-
-        case 0xBB: // map (eight-byte uint64_t for n follow)
-        {
-            return get_cbor_object(get_number<uint64_t>());
-        }
-
-        case 0xBF: // map (indefinite length)
-        {
-            json result = value_t::object;
-            while (get() != 0xFF)
-            {
-                auto key = get_cbor_string();
-                result[key] = parse_cbor_internal();
-            }
-            return result;
-        }
-
-        case 0xF4: // false
-        {
-            return false;
-        }
-
-        case 0xF5: // true
-        {
-            return true;
-        }
-
-        case 0xF6: // null
-        {
-            return value_t::null;
-        }
-
-        case 0xF9: // Half-Precision Float (two-byte IEEE 754)
-        {
-            const int byte1 = get();
-            unexpect_eof();
-            const int byte2 = get();
-            unexpect_eof();
-
-            // code from RFC 7049, Appendix D, Figure 3:
-            // As half-precision floating-point numbers were only added
-            // to IEEE 754 in 2008, today's programming platforms often
-            // still only have limited support for them. It is very
-            // easy to include at least decoding support for them even
-            // without such support. An example of a small decoder for
-            // half-precision floating-point numbers in the C language
-            // is shown in Fig. 3.
-            const int half = (byte1 << 8) + byte2;
-            const int exp = (half >> 10) & 0x1F;
-            const int mant = half & 0x3FF;
-            double val;
-            if (exp == 0)
-            {
-                val = std::ldexp(mant, -24);
-            }
-            else if (exp != 31)
-            {
-                val = std::ldexp(mant + 1024, exp - 25);
-            }
-            else
-            {
-                val = (mant == 0) ? std::numeric_limits<double>::infinity()
-                      : std::numeric_limits<double>::quiet_NaN();
-            }
-            return (half & 0x8000) != 0 ? -val : val;
-        }
-
-        case 0xFA: // Single-Precision Float (four-byte IEEE 754)
-        {
-            return get_number<float>();
-        }
-
-        case 0xFB: // Double-Precision Float (eight-byte IEEE 754)
-        {
-            return get_number<double>();
-        }
-
-        default: // anything else (0xFF is handled inside the other types)
-        {
-            JSON_THROW(parse_error::create(112, chars_read, fmt::format("error reading CBOR; last byte: {:#02x}", current)));
-        }
-    }
-}
-
-json json::binary_reader::parse_msgpack_internal()
-{
-    switch (get())
-    {
-        // EOF
-        case std::char_traits<char>::eof():
-            JSON_THROW(parse_error::create(110, chars_read, "unexpected end of input"));
-
-        // positive fixint
-        case 0x00:
-        case 0x01:
-        case 0x02:
-        case 0x03:
-        case 0x04:
-        case 0x05:
-        case 0x06:
-        case 0x07:
-        case 0x08:
-        case 0x09:
-        case 0x0A:
-        case 0x0B:
-        case 0x0C:
-        case 0x0D:
-        case 0x0E:
-        case 0x0F:
-        case 0x10:
-        case 0x11:
-        case 0x12:
-        case 0x13:
-        case 0x14:
-        case 0x15:
-        case 0x16:
-        case 0x17:
-        case 0x18:
-        case 0x19:
-        case 0x1A:
-        case 0x1B:
-        case 0x1C:
-        case 0x1D:
-        case 0x1E:
-        case 0x1F:
-        case 0x20:
-        case 0x21:
-        case 0x22:
-        case 0x23:
-        case 0x24:
-        case 0x25:
-        case 0x26:
-        case 0x27:
-        case 0x28:
-        case 0x29:
-        case 0x2A:
-        case 0x2B:
-        case 0x2C:
-        case 0x2D:
-        case 0x2E:
-        case 0x2F:
-        case 0x30:
-        case 0x31:
-        case 0x32:
-        case 0x33:
-        case 0x34:
-        case 0x35:
-        case 0x36:
-        case 0x37:
-        case 0x38:
-        case 0x39:
-        case 0x3A:
-        case 0x3B:
-        case 0x3C:
-        case 0x3D:
-        case 0x3E:
-        case 0x3F:
-        case 0x40:
-        case 0x41:
-        case 0x42:
-        case 0x43:
-        case 0x44:
-        case 0x45:
-        case 0x46:
-        case 0x47:
-        case 0x48:
-        case 0x49:
-        case 0x4A:
-        case 0x4B:
-        case 0x4C:
-        case 0x4D:
-        case 0x4E:
-        case 0x4F:
-        case 0x50:
-        case 0x51:
-        case 0x52:
-        case 0x53:
-        case 0x54:
-        case 0x55:
-        case 0x56:
-        case 0x57:
-        case 0x58:
-        case 0x59:
-        case 0x5A:
-        case 0x5B:
-        case 0x5C:
-        case 0x5D:
-        case 0x5E:
-        case 0x5F:
-        case 0x60:
-        case 0x61:
-        case 0x62:
-        case 0x63:
-        case 0x64:
-        case 0x65:
-        case 0x66:
-        case 0x67:
-        case 0x68:
-        case 0x69:
-        case 0x6A:
-        case 0x6B:
-        case 0x6C:
-        case 0x6D:
-        case 0x6E:
-        case 0x6F:
-        case 0x70:
-        case 0x71:
-        case 0x72:
-        case 0x73:
-        case 0x74:
-        case 0x75:
-        case 0x76:
-        case 0x77:
-        case 0x78:
-        case 0x79:
-        case 0x7A:
-        case 0x7B:
-        case 0x7C:
-        case 0x7D:
-        case 0x7E:
-        case 0x7F:
-            return static_cast<uint64_t>(current);
-
-        // fixmap
-        case 0x80:
-        case 0x81:
-        case 0x82:
-        case 0x83:
-        case 0x84:
-        case 0x85:
-        case 0x86:
-        case 0x87:
-        case 0x88:
-        case 0x89:
-        case 0x8A:
-        case 0x8B:
-        case 0x8C:
-        case 0x8D:
-        case 0x8E:
-        case 0x8F:
-        {
-            return get_msgpack_object(current & 0x0F);
-        }
-
-        // fixarray
-        case 0x90:
-        case 0x91:
-        case 0x92:
-        case 0x93:
-        case 0x94:
-        case 0x95:
-        case 0x96:
-        case 0x97:
-        case 0x98:
-        case 0x99:
-        case 0x9A:
-        case 0x9B:
-        case 0x9C:
-        case 0x9D:
-        case 0x9E:
-        case 0x9F:
-        {
-            return get_msgpack_array(current & 0x0F);
-        }
-
-        // fixstr
-        case 0xA0:
-        case 0xA1:
-        case 0xA2:
-        case 0xA3:
-        case 0xA4:
-        case 0xA5:
-        case 0xA6:
-        case 0xA7:
-        case 0xA8:
-        case 0xA9:
-        case 0xAA:
-        case 0xAB:
-        case 0xAC:
-        case 0xAD:
-        case 0xAE:
-        case 0xAF:
-        case 0xB0:
-        case 0xB1:
-        case 0xB2:
-        case 0xB3:
-        case 0xB4:
-        case 0xB5:
-        case 0xB6:
-        case 0xB7:
-        case 0xB8:
-        case 0xB9:
-        case 0xBA:
-        case 0xBB:
-        case 0xBC:
-        case 0xBD:
-        case 0xBE:
-        case 0xBF:
-            return get_msgpack_string();
-
-        case 0xC0: // nil
-            return value_t::null;
-
-        case 0xC2: // false
-            return false;
-
-        case 0xC3: // true
-            return true;
-
-        case 0xCA: // float 32
-            return get_number<float>();
-
-        case 0xCB: // float 64
-            return get_number<double>();
-
-        case 0xCC: // uint 8
-            return get_number<uint8_t>();
-
-        case 0xCD: // uint 16
-            return get_number<uint16_t>();
-
-        case 0xCE: // uint 32
-            return get_number<uint32_t>();
-
-        case 0xCF: // uint 64
-            return get_number<uint64_t>();
-
-        case 0xD0: // int 8
-            return get_number<int8_t>();
-
-        case 0xD1: // int 16
-            return get_number<int16_t>();
-
-        case 0xD2: // int 32
-            return get_number<int32_t>();
-
-        case 0xD3: // int 64
-            return get_number<int64_t>();
-
-        case 0xD9: // str 8
-        case 0xDA: // str 16
-        case 0xDB: // str 32
-            return get_msgpack_string();
-
-        case 0xDC: // array 16
-        {
-            return get_msgpack_array(get_number<uint16_t>());
-        }
-
-        case 0xDD: // array 32
-        {
-            return get_msgpack_array(get_number<uint32_t>());
-        }
-
-        case 0xDE: // map 16
-        {
-            return get_msgpack_object(get_number<uint16_t>());
-        }
-
-        case 0xDF: // map 32
-        {
-            return get_msgpack_object(get_number<uint32_t>());
-        }
-
-        // positive fixint
-        case 0xE0:
-        case 0xE1:
-        case 0xE2:
-        case 0xE3:
-        case 0xE4:
-        case 0xE5:
-        case 0xE6:
-        case 0xE7:
-        case 0xE8:
-        case 0xE9:
-        case 0xEA:
-        case 0xEB:
-        case 0xEC:
-        case 0xED:
-        case 0xEE:
-        case 0xEF:
-        case 0xF0:
-        case 0xF1:
-        case 0xF2:
-        case 0xF3:
-        case 0xF4:
-        case 0xF5:
-        case 0xF6:
-        case 0xF7:
-        case 0xF8:
-        case 0xF9:
-        case 0xFA:
-        case 0xFB:
-        case 0xFC:
-        case 0xFD:
-        case 0xFE:
-        case 0xFF:
-            return static_cast<int8_t>(current);
-
-        default: // anything else
-        {
-            JSON_THROW(parse_error::create(112, chars_read,
-                fmt::format("error reading MessagePack; last byte: {:#02x}", current)));
-        }
-    }
-}
-
-std::string json::binary_reader::get_cbor_string()
-{
-    unexpect_eof();
-
-    switch (current)
-    {
-        // UTF-8 string (0x00..0x17 bytes follow)
-        case 0x60:
-        case 0x61:
-        case 0x62:
-        case 0x63:
-        case 0x64:
-        case 0x65:
-        case 0x66:
-        case 0x67:
-        case 0x68:
-        case 0x69:
-        case 0x6A:
-        case 0x6B:
-        case 0x6C:
-        case 0x6D:
-        case 0x6E:
-        case 0x6F:
-        case 0x70:
-        case 0x71:
-        case 0x72:
-        case 0x73:
-        case 0x74:
-        case 0x75:
-        case 0x76:
-        case 0x77:
-        {
-            return get_string(current & 0x1F);
-        }
-
-        case 0x78: // UTF-8 string (one-byte uint8_t for n follows)
-        {
-            return get_string(get_number<uint8_t>());
-        }
-
-        case 0x79: // UTF-8 string (two-byte uint16_t for n follow)
-        {
-            return get_string(get_number<uint16_t>());
-        }
-
-        case 0x7A: // UTF-8 string (four-byte uint32_t for n follow)
-        {
-            return get_string(get_number<uint32_t>());
-        }
-
-        case 0x7B: // UTF-8 string (eight-byte uint64_t for n follow)
-        {
-            return get_string(get_number<uint64_t>());
-        }
-
-        case 0x7F: // UTF-8 string (indefinite length)
-        {
-            std::string result;
-            while (get() != 0xFF)
-            {
-                result.append(get_cbor_string());
-            }
-            return result;
-        }
-
-        default:
-        {
-            JSON_THROW(parse_error::create(113, chars_read,
-                fmt::format("expected a CBOR string; last byte: {:#02x}", current)));
-        }
-    }
-}
-
-std::string json::binary_reader::get_msgpack_string()
-{
-    unexpect_eof();
-
-    switch (current)
-    {
-        // fixstr
-        case 0xA0:
-        case 0xA1:
-        case 0xA2:
-        case 0xA3:
-        case 0xA4:
-        case 0xA5:
-        case 0xA6:
-        case 0xA7:
-        case 0xA8:
-        case 0xA9:
-        case 0xAA:
-        case 0xAB:
-        case 0xAC:
-        case 0xAD:
-        case 0xAE:
-        case 0xAF:
-        case 0xB0:
-        case 0xB1:
-        case 0xB2:
-        case 0xB3:
-        case 0xB4:
-        case 0xB5:
-        case 0xB6:
-        case 0xB7:
-        case 0xB8:
-        case 0xB9:
-        case 0xBA:
-        case 0xBB:
-        case 0xBC:
-        case 0xBD:
-        case 0xBE:
-        case 0xBF:
-        {
-            return get_string(current & 0x1F);
-        }
-
-        case 0xD9: // str 8
-        {
-            return get_string(get_number<uint8_t>());
-        }
-
-        case 0xDA: // str 16
-        {
-            return get_string(get_number<uint16_t>());
-        }
-
-        case 0xDB: // str 32
-        {
-            return get_string(get_number<uint32_t>());
-        }
-
-        default:
-        {
-            JSON_THROW(parse_error::create(113, chars_read,
-                fmt::format("expected a MessagePack string; last byte: {:#02x}", current)));
-        }
-    }
-}
-
-std::string json::binary_reader::get_ubjson_string(const bool get_char)
-{
-    if (get_char)
-    {
-        get();  // TODO: may we ignore N here?
-    }
-
-    unexpect_eof();
-
-    switch (current)
-    {
-        case 'U':
-            return get_string(get_number<uint8_t>());
-        case 'i':
-            return get_string(get_number<int8_t>());
-        case 'I':
-            return get_string(get_number<int16_t>());
-        case 'l':
-            return get_string(get_number<int32_t>());
-        case 'L':
-            return get_string(get_number<int64_t>());
-        default:
-            JSON_THROW(parse_error::create(113, chars_read,
-                fmt::format("expected a UBJSON string; last byte: {:#02x}", current)));
-    }
-}
-
-std::pair<std::size_t, int> json::binary_reader::get_ubjson_size_type()
-{
-    std::size_t sz = std::string::npos;
-    int tc = 0;
-
-    get_ignore_noop();
-
-    if (current == '$')
-    {
-        tc = get();  // must not ignore 'N', because 'N' maybe the type
-        unexpect_eof();
-
-        get_ignore_noop();
-        if (current != '#')
-        {
-            JSON_THROW(parse_error::create(112, chars_read,
-                fmt::format("expected '#' after UBJSON type information; last byte: {:#02x}", current)));
-        }
-        sz = parse_ubjson_internal();
-    }
-    else if (current == '#')
-    {
-        sz = parse_ubjson_internal();
-    }
-
-    return std::make_pair(sz, tc);
-}
-
-json json::binary_reader::get_ubjson_value(const int prefix)
-{
-    switch (prefix)
-    {
-        case std::char_traits<char>::eof():  // EOF
-            JSON_THROW(parse_error::create(110, chars_read, "unexpected end of input"));
-
-        case 'T':  // true
-            return true;
-        case 'F':  // false
-            return false;
-
-        case 'Z':  // null
-            return nullptr;
-
-        case 'U':
-            return get_number<uint8_t>();
-        case 'i':
-            return get_number<int8_t>();
-        case 'I':
-            return get_number<int16_t>();
-        case 'l':
-            return get_number<int32_t>();
-        case 'L':
-            return get_number<int64_t>();
-        case 'd':
-            return get_number<float>();
-        case 'D':
-            return get_number<double>();
-
-        case 'C':  // char
-        {
-            get();
-            unexpect_eof();
-            if (JSON_UNLIKELY(current > 127))
-            {
-                JSON_THROW(parse_error::create(113, chars_read,
-                    fmt::format("byte after 'C' must be in range 0x00..0x7F; last byte: {:#02x}", current)));
-            }
-            return std::string(1, static_cast<char>(current));
-        }
-
-        case 'S':  // string
-            return get_ubjson_string();
-
-        case '[':  // array
-            return get_ubjson_array();
-
-        case '{':  // object
-            return get_ubjson_object();
-
-        default: // anything else
-            JSON_THROW(parse_error::create(112, chars_read,
-                fmt::format("error reading UBJSON; last byte: {:#02x}", current)));
-    }
-}
-
-json json::binary_reader::get_ubjson_array()
-{
-    json result = value_t::array;
-    const auto size_and_type = get_ubjson_size_type();
-
-    if (size_and_type.first != std::string::npos)
-    {
-        if (JSON_UNLIKELY(size_and_type.first > result.max_size()))
-        {
-            JSON_THROW(out_of_range::create(408,
-                fmt::format("excessive array size: {}", size_and_type.first)));
-        }
-
-        if (size_and_type.second != 0)
-        {
-            if (size_and_type.second != 'N')
-            {
-                std::generate_n(std::back_inserter(*result.m_value.array),
-                                size_and_type.first, [this, size_and_type]()
-                {
-                    return get_ubjson_value(size_and_type.second);
-                });
-            }
-        }
-        else
-        {
-            std::generate_n(std::back_inserter(*result.m_value.array),
-                            size_and_type.first, [this]()
-            {
-                return parse_ubjson_internal();
-            });
-        }
-    }
-    else
-    {
-        while (current != ']')
-        {
-            result.push_back(parse_ubjson_internal(false));
-            get_ignore_noop();
-        }
-    }
-
-    return result;
-}
-
-json json::binary_reader::get_ubjson_object()
-{
-    json result = value_t::object;
-    const auto size_and_type = get_ubjson_size_type();
-
-    if (size_and_type.first != std::string::npos)
-    {
-        if (JSON_UNLIKELY(size_and_type.first > result.max_size()))
-        {
-            JSON_THROW(out_of_range::create(408,
-                fmt::format("excessive object size: {}", size_and_type.first)));
-        }
-
-        if (size_and_type.second != 0)
-        {
-            for (size_t i = 0; i < size_and_type.first; ++i)
-            {
-                auto key = get_ubjson_string();
-                (*result.m_value.object)[key] = get_ubjson_value(size_and_type.second);
-            }
-        }
-        else
-        {
-            for (size_t i = 0; i < size_and_type.first; ++i)
-            {
-                auto key = get_ubjson_string();
-                (*result.m_value.object)[key] = parse_ubjson_internal();
-            }
-        }
-    }
-    else
-    {
-        while (current != '}')
-        {
-            auto key = get_ubjson_string(false);
-            result[std::move(key)] = parse_ubjson_internal();
-            get_ignore_noop();
-        }
-    }
-
-    return result;
-}
-
-json json::from_cbor(raw_istream& is, const bool strict)
-{
-    return binary_reader(is).parse_cbor(strict);
-}
-
-json json::from_cbor(span<const uint8_t> arr, const bool strict)
-{
-    raw_mem_istream is(arr);
-    return from_cbor(is, strict);
-}
-
-json json::from_msgpack(raw_istream& is, const bool strict)
-{
-    return binary_reader(is).parse_msgpack(strict);
-}
-
-json json::from_msgpack(span<const uint8_t> arr, const bool strict)
-{
-    raw_mem_istream is(arr);
-    return from_msgpack(is, strict);
-}
-
-json json::from_ubjson(raw_istream& is, const bool strict)
-{
-    return binary_reader(is).parse_ubjson(strict);
-}
-
-json json::from_ubjson(span<const uint8_t> arr, const bool strict)
-{
-    raw_mem_istream is(arr);
-    return from_ubjson(is, strict);
-}
-
-}  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/json_binary_writer.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/json_binary_writer.cpp
deleted file mode 100644
index db23f8d..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/json_binary_writer.cpp
+++ /dev/null
@@ -1,1091 +0,0 @@
-/*----------------------------------------------------------------------------*/
-/* Modifications Copyright (c) 2017-2018 FIRST. All Rights Reserved.          */
-/* Open Source Software - may be modified and shared by FRC teams. The code   */
-/* must be accompanied by the FIRST BSD license file in the root directory of */
-/* the project.                                                               */
-/*----------------------------------------------------------------------------*/
-/*
-    __ _____ _____ _____
- __|  |   __|     |   | |  JSON for Modern C++
-|  |  |__   |  |  | | | |  version 3.1.2
-|_____|_____|_____|_|___|  https://github.com/nlohmann/json
-
-Licensed under the MIT License <http://opensource.org/licenses/MIT>.
-Copyright (c) 2013-2018 Niels Lohmann <http://nlohmann.me>.
-
-Permission is hereby  granted, free of charge, to any  person obtaining a copy
-of this software and associated  documentation files (the "Software"), to deal
-in the Software  without restriction, including without  limitation the rights
-to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
-copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
-furnished to do so, subject to the following conditions:
-
-The above copyright notice and this permission notice shall be included in all
-copies or substantial portions of the Software.
-
-THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
-IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
-FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
-AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
-LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
-OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
-SOFTWARE.
-*/
-#define WPI_JSON_IMPLEMENTATION
-#include "wpi/json.h"
-
-#include "fmt/format.h"
-#include "wpi/raw_ostream.h"
-
-namespace wpi {
-
-/*!
-@brief serialization to CBOR and MessagePack values
-*/
-class json::binary_writer
-{
-    using CharType = unsigned char;
-
-  public:
-    /*!
-    @brief create a binary writer
-
-    @param[in] adapter  output adapter to write to
-    */
-    explicit binary_writer(raw_ostream& s) : o(s)
-    {
-    }
-
-    /*!
-    @brief[in] j  JSON value to serialize
-    */
-    void write_cbor(const json& j);
-
-    /*!
-    @brief[in] j  JSON value to serialize
-    */
-    void write_msgpack(const json& j);
-
-    /*!
-    @param[in] j  JSON value to serialize
-    @param[in] use_count   whether to use '#' prefixes (optimized format)
-    @param[in] use_type    whether to use '$' prefixes (optimized format)
-    @param[in] add_prefix  whether prefixes need to be used for this value
-    */
-    void write_ubjson(const json& j, const bool use_count,
-                      const bool use_type, const bool add_prefix = true);
-
-  private:
-    void write_cbor_string(std::string_view str);
-
-    void write_msgpack_string(std::string_view str);
-
-    /*
-    @brief write a number to output input
-
-    @param[in] n number of type @a NumberType
-    @tparam NumberType the type of the number
-
-    @note This function needs to respect the system's endianess, because bytes
-          in CBOR, MessagePack, and UBJSON are stored in network order (big
-          endian) and therefore need reordering on little endian systems.
-    */
-    template<typename NumberType>
-    void write_number(const NumberType n);
-
-    // UBJSON: write number (floating point)
-    template<typename NumberType, typename std::enable_if<
-                 std::is_floating_point<NumberType>::value, int>::type = 0>
-    void write_number_with_ubjson_prefix(const NumberType n,
-                                         const bool add_prefix)
-    {
-        if (add_prefix)
-        {
-            o << get_ubjson_float_prefix(n);
-        }
-        write_number(n);
-    }
-
-    // UBJSON: write number (unsigned integer)
-    template<typename NumberType, typename std::enable_if<
-                 std::is_unsigned<NumberType>::value, int>::type = 0>
-    void write_number_with_ubjson_prefix(const NumberType n,
-                                         const bool add_prefix);
-
-    // UBJSON: write number (signed integer)
-    template<typename NumberType, typename std::enable_if<
-                 std::is_signed<NumberType>::value and
-                 not std::is_floating_point<NumberType>::value, int>::type = 0>
-    void write_number_with_ubjson_prefix(const NumberType n,
-                                         const bool add_prefix);
-
-    /*!
-    @brief determine the type prefix of container values
-
-    @note This function does not need to be 100% accurate when it comes to
-          integer limits. In case a number exceeds the limits of int64_t,
-          this will be detected by a later call to function
-          write_number_with_ubjson_prefix. Therefore, we return 'L' for any
-          value that does not fit the previous limits.
-    */
-    CharType ubjson_prefix(const json& j) const noexcept;
-
-    static constexpr CharType get_cbor_float_prefix(float)
-    {
-        return static_cast<CharType>(0xFA);  // Single-Precision Float
-    }
-
-    static constexpr CharType get_cbor_float_prefix(double)
-    {
-        return static_cast<CharType>(0xFB);  // Double-Precision Float
-    }
-
-    static constexpr CharType get_msgpack_float_prefix(float)
-    {
-        return static_cast<CharType>(0xCA);  // float 32
-    }
-
-    static constexpr CharType get_msgpack_float_prefix(double)
-    {
-        return static_cast<CharType>(0xCB);  // float 64
-    }
-
-    static constexpr CharType get_ubjson_float_prefix(float)
-    {
-        return 'd';  // float 32
-    }
-
-    static constexpr CharType get_ubjson_float_prefix(double)
-    {
-        return 'D';  // float 64
-    }
-
-  private:
-    static bool little_endianess(int num = 1) noexcept
-    {
-        return (*reinterpret_cast<char*>(&num) == 1);
-    }
-
-    /// whether we can assume little endianess
-    const bool is_little_endian = little_endianess();
-
-    /// the output
-    raw_ostream& o;
-};
-
-void json::binary_writer::write_cbor(const json& j)
-{
-    switch (j.type())
-    {
-        case value_t::null:
-        {
-            o << static_cast<CharType>(0xF6);
-            break;
-        }
-
-        case value_t::boolean:
-        {
-            o << static_cast<CharType>(j.m_value.boolean ? 0xF5 : 0xF4);
-            break;
-        }
-
-        case value_t::number_integer:
-        {
-            if (j.m_value.number_integer >= 0)
-            {
-                // CBOR does not differentiate between positive signed
-                // integers and unsigned integers. Therefore, we used the
-                // code from the value_t::number_unsigned case here.
-                if (j.m_value.number_integer <= 0x17)
-                {
-                    write_number(static_cast<uint8_t>(j.m_value.number_integer));
-                }
-                else if (j.m_value.number_integer <= (std::numeric_limits<uint8_t>::max)())
-                {
-                    o << static_cast<CharType>(0x18);
-                    write_number(static_cast<uint8_t>(j.m_value.number_integer));
-                }
-                else if (j.m_value.number_integer <= (std::numeric_limits<uint16_t>::max)())
-                {
-                    o << static_cast<CharType>(0x19);
-                    write_number(static_cast<uint16_t>(j.m_value.number_integer));
-                }
-                else if (j.m_value.number_integer <= (std::numeric_limits<uint32_t>::max)())
-                {
-                    o << static_cast<CharType>(0x1A);
-                    write_number(static_cast<uint32_t>(j.m_value.number_integer));
-                }
-                else
-                {
-                    o << static_cast<CharType>(0x1B);
-                    write_number(static_cast<uint64_t>(j.m_value.number_integer));
-                }
-            }
-            else
-            {
-                // The conversions below encode the sign in the first
-                // byte, and the value is converted to a positive number.
-                const auto positive_number = -1 - j.m_value.number_integer;
-                if (j.m_value.number_integer >= -24)
-                {
-                    write_number(static_cast<uint8_t>(0x20 + positive_number));
-                }
-                else if (positive_number <= (std::numeric_limits<uint8_t>::max)())
-                {
-                    o << static_cast<CharType>(0x38);
-                    write_number(static_cast<uint8_t>(positive_number));
-                }
-                else if (positive_number <= (std::numeric_limits<uint16_t>::max)())
-                {
-                    o << static_cast<CharType>(0x39);
-                    write_number(static_cast<uint16_t>(positive_number));
-                }
-                else if (positive_number <= (std::numeric_limits<uint32_t>::max)())
-                {
-                    o << static_cast<CharType>(0x3A);
-                    write_number(static_cast<uint32_t>(positive_number));
-                }
-                else
-                {
-                    o << static_cast<CharType>(0x3B);
-                    write_number(static_cast<uint64_t>(positive_number));
-                }
-            }
-            break;
-        }
-
-        case value_t::number_unsigned:
-        {
-            if (j.m_value.number_unsigned <= 0x17)
-            {
-                write_number(static_cast<uint8_t>(j.m_value.number_unsigned));
-            }
-            else if (j.m_value.number_unsigned <= (std::numeric_limits<uint8_t>::max)())
-            {
-                o << static_cast<CharType>(0x18);
-                write_number(static_cast<uint8_t>(j.m_value.number_unsigned));
-            }
-            else if (j.m_value.number_unsigned <= (std::numeric_limits<uint16_t>::max)())
-            {
-                o << static_cast<CharType>(0x19);
-                write_number(static_cast<uint16_t>(j.m_value.number_unsigned));
-            }
-            else if (j.m_value.number_unsigned <= (std::numeric_limits<uint32_t>::max)())
-            {
-                o << static_cast<CharType>(0x1A);
-                write_number(static_cast<uint32_t>(j.m_value.number_unsigned));
-            }
-            else
-            {
-                o << static_cast<CharType>(0x1B);
-                write_number(static_cast<uint64_t>(j.m_value.number_unsigned));
-            }
-            break;
-        }
-
-        case value_t::number_float:
-        {
-            o << get_cbor_float_prefix(j.m_value.number_float);
-            write_number(j.m_value.number_float);
-            break;
-        }
-
-        case value_t::string:
-        {
-            write_cbor_string(*j.m_value.string);
-            break;
-        }
-
-        case value_t::array:
-        {
-            // step 1: write control byte and the array size
-            const auto N = j.m_value.array->size();
-            if (N <= 0x17)
-            {
-                write_number(static_cast<uint8_t>(0x80 + N));
-            }
-            else if (N <= (std::numeric_limits<uint8_t>::max)())
-            {
-                o << static_cast<CharType>(0x98);
-                write_number(static_cast<uint8_t>(N));
-            }
-            else if (N <= (std::numeric_limits<uint16_t>::max)())
-            {
-                o << static_cast<CharType>(0x99);
-                write_number(static_cast<uint16_t>(N));
-            }
-            else if (N <= (std::numeric_limits<uint32_t>::max)())
-            {
-                o << static_cast<CharType>(0x9A);
-                write_number(static_cast<uint32_t>(N));
-            }
-            // LCOV_EXCL_START
-            else if (N <= (std::numeric_limits<uint64_t>::max)())
-            {
-                o << static_cast<CharType>(0x9B);
-                write_number(static_cast<uint64_t>(N));
-            }
-            // LCOV_EXCL_STOP
-
-            // step 2: write each element
-            for (const auto& el : *j.m_value.array)
-            {
-                write_cbor(el);
-            }
-            break;
-        }
-
-        case value_t::object:
-        {
-            // step 1: write control byte and the object size
-            const auto N = j.m_value.object->size();
-            if (N <= 0x17)
-            {
-                write_number(static_cast<uint8_t>(0xA0 + N));
-            }
-            else if (N <= (std::numeric_limits<uint8_t>::max)())
-            {
-                o << static_cast<CharType>(0xB8);
-                write_number(static_cast<uint8_t>(N));
-            }
-            else if (N <= (std::numeric_limits<uint16_t>::max)())
-            {
-                o << static_cast<CharType>(0xB9);
-                write_number(static_cast<uint16_t>(N));
-            }
-            else if (N <= (std::numeric_limits<uint32_t>::max)())
-            {
-                o << static_cast<CharType>(0xBA);
-                write_number(static_cast<uint32_t>(N));
-            }
-            // LCOV_EXCL_START
-            else /*if (N <= (std::numeric_limits<uint64_t>::max)())*/
-            {
-                o << static_cast<CharType>(0xBB);
-                write_number(static_cast<uint64_t>(N));
-            }
-            // LCOV_EXCL_STOP
-
-            // step 2: write each element
-            for (const auto& el : *j.m_value.object)
-            {
-                write_cbor_string(el.first());
-                write_cbor(el.second);
-            }
-            break;
-        }
-
-        default:
-            break;
-    }
-}
-
-void json::binary_writer::write_msgpack(const json& j)
-{
-    switch (j.type())
-    {
-        case value_t::null: // nil
-        {
-            o << static_cast<CharType>(0xC0);
-            break;
-        }
-
-        case value_t::boolean: // true and false
-        {
-            o << static_cast<CharType>(j.m_value.boolean ? 0xC3 : 0xC2);
-            break;
-        }
-
-        case value_t::number_integer:
-        {
-            if (j.m_value.number_integer >= 0)
-            {
-                // MessagePack does not differentiate between positive
-                // signed integers and unsigned integers. Therefore, we used
-                // the code from the value_t::number_unsigned case here.
-                if (j.m_value.number_unsigned < 128)
-                {
-                    // positive fixnum
-                    write_number(static_cast<uint8_t>(j.m_value.number_integer));
-                }
-                else if (j.m_value.number_unsigned <= (std::numeric_limits<uint8_t>::max)())
-                {
-                    // uint 8
-                    o << static_cast<CharType>(0xCC);
-                    write_number(static_cast<uint8_t>(j.m_value.number_integer));
-                }
-                else if (j.m_value.number_unsigned <= (std::numeric_limits<uint16_t>::max)())
-                {
-                    // uint 16
-                    o << static_cast<CharType>(0xCD);
-                    write_number(static_cast<uint16_t>(j.m_value.number_integer));
-                }
-                else if (j.m_value.number_unsigned <= (std::numeric_limits<uint32_t>::max)())
-                {
-                    // uint 32
-                    o << static_cast<CharType>(0xCE);
-                    write_number(static_cast<uint32_t>(j.m_value.number_integer));
-                }
-                else if (j.m_value.number_unsigned <= (std::numeric_limits<uint64_t>::max)())
-                {
-                    // uint 64
-                    o << static_cast<CharType>(0xCF);
-                    write_number(static_cast<uint64_t>(j.m_value.number_integer));
-                }
-            }
-            else
-            {
-                if (j.m_value.number_integer >= -32)
-                {
-                    // negative fixnum
-                    write_number(static_cast<int8_t>(j.m_value.number_integer));
-                }
-                else if (j.m_value.number_integer >= (std::numeric_limits<int8_t>::min)() and
-                         j.m_value.number_integer <= (std::numeric_limits<int8_t>::max)())
-                {
-                    // int 8
-                    o << static_cast<CharType>(0xD0);
-                    write_number(static_cast<int8_t>(j.m_value.number_integer));
-                }
-                else if (j.m_value.number_integer >= (std::numeric_limits<int16_t>::min)() and
-                         j.m_value.number_integer <= (std::numeric_limits<int16_t>::max)())
-                {
-                    // int 16
-                    o << static_cast<CharType>(0xD1);
-                    write_number(static_cast<int16_t>(j.m_value.number_integer));
-                }
-                else if (j.m_value.number_integer >= (std::numeric_limits<int32_t>::min)() and
-                         j.m_value.number_integer <= (std::numeric_limits<int32_t>::max)())
-                {
-                    // int 32
-                    o << static_cast<CharType>(0xD2);
-                    write_number(static_cast<int32_t>(j.m_value.number_integer));
-                }
-                else if (j.m_value.number_integer >= (std::numeric_limits<int64_t>::min)() and
-                         j.m_value.number_integer <= (std::numeric_limits<int64_t>::max)())
-                {
-                    // int 64
-                    o << static_cast<CharType>(0xD3);
-                    write_number(static_cast<int64_t>(j.m_value.number_integer));
-                }
-            }
-            break;
-        }
-
-        case value_t::number_unsigned:
-        {
-            if (j.m_value.number_unsigned < 128)
-            {
-                // positive fixnum
-                write_number(static_cast<uint8_t>(j.m_value.number_integer));
-            }
-            else if (j.m_value.number_unsigned <= (std::numeric_limits<uint8_t>::max)())
-            {
-                // uint 8
-                o << static_cast<CharType>(0xCC);
-                write_number(static_cast<uint8_t>(j.m_value.number_integer));
-            }
-            else if (j.m_value.number_unsigned <= (std::numeric_limits<uint16_t>::max)())
-            {
-                // uint 16
-                o << static_cast<CharType>(0xCD);
-                write_number(static_cast<uint16_t>(j.m_value.number_integer));
-            }
-            else if (j.m_value.number_unsigned <= (std::numeric_limits<uint32_t>::max)())
-            {
-                // uint 32
-                o << static_cast<CharType>(0xCE);
-                write_number(static_cast<uint32_t>(j.m_value.number_integer));
-            }
-            else if (j.m_value.number_unsigned <= (std::numeric_limits<uint64_t>::max)())
-            {
-                // uint 64
-                o << static_cast<CharType>(0xCF);
-                write_number(static_cast<uint64_t>(j.m_value.number_integer));
-            }
-            break;
-        }
-
-        case value_t::number_float:
-        {
-            o << get_msgpack_float_prefix(j.m_value.number_float);
-            write_number(j.m_value.number_float);
-            break;
-        }
-
-        case value_t::string:
-        {
-            write_msgpack_string(*j.m_value.string);
-            break;
-        }
-
-        case value_t::array:
-        {
-            // step 1: write control byte and the array size
-            const auto N = j.m_value.array->size();
-            if (N <= 15)
-            {
-                // fixarray
-                write_number(static_cast<uint8_t>(0x90 | N));
-            }
-            else if (N <= (std::numeric_limits<uint16_t>::max)())
-            {
-                // array 16
-                o << static_cast<CharType>(0xDC);
-                write_number(static_cast<uint16_t>(N));
-            }
-            else if (N <= (std::numeric_limits<uint32_t>::max)())
-            {
-                // array 32
-                o << static_cast<CharType>(0xDD);
-                write_number(static_cast<uint32_t>(N));
-            }
-
-            // step 2: write each element
-            for (const auto& el : *j.m_value.array)
-            {
-                write_msgpack(el);
-            }
-            break;
-        }
-
-        case value_t::object:
-        {
-            // step 1: write control byte and the object size
-            const auto N = j.m_value.object->size();
-            if (N <= 15)
-            {
-                // fixmap
-                write_number(static_cast<uint8_t>(0x80 | (N & 0xF)));
-            }
-            else if (N <= (std::numeric_limits<uint16_t>::max)())
-            {
-                // map 16
-                o << static_cast<CharType>(0xDE);
-                write_number(static_cast<uint16_t>(N));
-            }
-            else if (N <= (std::numeric_limits<uint32_t>::max)())
-            {
-                // map 32
-                o << static_cast<CharType>(0xDF);
-                write_number(static_cast<uint32_t>(N));
-            }
-
-            // step 2: write each element
-            for (const auto& el : *j.m_value.object)
-            {
-                write_msgpack_string(el.first());
-                write_msgpack(el.second);
-            }
-            break;
-        }
-
-        default:
-            break;
-    }
-}
-
-void json::binary_writer::write_ubjson(const json& j, const bool use_count,
-                  const bool use_type, const bool add_prefix)
-{
-    switch (j.type())
-    {
-        case value_t::null:
-        {
-            if (add_prefix)
-            {
-                o << static_cast<CharType>('Z');
-            }
-            break;
-        }
-
-        case value_t::boolean:
-        {
-            if (add_prefix)
-                o << static_cast<CharType>(j.m_value.boolean ? 'T' : 'F');
-            break;
-        }
-
-        case value_t::number_integer:
-        {
-            write_number_with_ubjson_prefix(j.m_value.number_integer, add_prefix);
-            break;
-        }
-
-        case value_t::number_unsigned:
-        {
-            write_number_with_ubjson_prefix(j.m_value.number_unsigned, add_prefix);
-            break;
-        }
-
-        case value_t::number_float:
-        {
-            write_number_with_ubjson_prefix(j.m_value.number_float, add_prefix);
-            break;
-        }
-
-        case value_t::string:
-        {
-            if (add_prefix)
-            {
-                o << static_cast<CharType>('S');
-            }
-            write_number_with_ubjson_prefix(j.m_value.string->size(), true);
-            o << *j.m_value.string;
-            break;
-        }
-
-        case value_t::array:
-        {
-            if (add_prefix)
-            {
-                o << static_cast<CharType>('[');
-            }
-
-            bool prefix_required = true;
-            if (use_type and not j.m_value.array->empty())
-            {
-                assert(use_count);
-                const CharType first_prefix = ubjson_prefix(j.front());
-                const bool same_prefix = std::all_of(j.begin() + 1, j.end(),
-                                                     [this, first_prefix](const json & v)
-                {
-                    return ubjson_prefix(v) == first_prefix;
-                });
-
-                if (same_prefix)
-                {
-                    prefix_required = false;
-                    o << static_cast<CharType>('$');
-                    o << first_prefix;
-                }
-            }
-
-            if (use_count)
-            {
-                o << static_cast<CharType>('#');
-                write_number_with_ubjson_prefix(j.m_value.array->size(), true);
-            }
-
-            for (const auto& el : *j.m_value.array)
-            {
-                write_ubjson(el, use_count, use_type, prefix_required);
-            }
-
-            if (not use_count)
-            {
-                o << static_cast<CharType>(']');
-            }
-
-            break;
-        }
-
-        case value_t::object:
-        {
-            if (add_prefix)
-            {
-                o << static_cast<CharType>('{');
-            }
-
-            bool prefix_required = true;
-            if (use_type and not j.m_value.object->empty())
-            {
-                assert(use_count);
-                const CharType first_prefix = ubjson_prefix(j.front());
-                const bool same_prefix = std::all_of(j.begin(), j.end(),
-                                                     [this, first_prefix](const json & v)
-                {
-                    return ubjson_prefix(v) == first_prefix;
-                });
-
-                if (same_prefix)
-                {
-                    prefix_required = false;
-                    o << static_cast<CharType>('$');
-                    o << first_prefix;
-                }
-            }
-
-            if (use_count)
-            {
-                o << static_cast<CharType>('#');
-                write_number_with_ubjson_prefix(j.m_value.object->size(), true);
-            }
-
-            for (const auto& el : *j.m_value.object)
-            {
-                write_number_with_ubjson_prefix(el.first().size(), true);
-                o << el.first();
-                write_ubjson(el.second, use_count, use_type, prefix_required);
-            }
-
-            if (not use_count)
-            {
-                o << static_cast<CharType>('}');
-            }
-
-            break;
-        }
-
-        default:
-            break;
-    }
-}
-
-void json::binary_writer::write_cbor_string(std::string_view str)
-{
-    // step 1: write control byte and the string length
-    const auto N = str.size();
-    if (N <= 0x17)
-    {
-        write_number(static_cast<uint8_t>(0x60 + N));
-    }
-    else if (N <= (std::numeric_limits<uint8_t>::max)())
-    {
-        o << static_cast<CharType>(0x78);
-        write_number(static_cast<uint8_t>(N));
-    }
-    else if (N <= (std::numeric_limits<uint16_t>::max)())
-    {
-        o << static_cast<CharType>(0x79);
-        write_number(static_cast<uint16_t>(N));
-    }
-    else if (N <= (std::numeric_limits<uint32_t>::max)())
-    {
-        o << static_cast<CharType>(0x7A);
-        write_number(static_cast<uint32_t>(N));
-    }
-    // LCOV_EXCL_START
-    else if (N <= (std::numeric_limits<uint64_t>::max)())
-    {
-        o << static_cast<CharType>(0x7B);
-        write_number(static_cast<uint64_t>(N));
-    }
-    // LCOV_EXCL_STOP
-
-    // step 2: write the string
-    o << str;
-}
-
-void json::binary_writer::write_msgpack_string(std::string_view str)
-{
-    // step 1: write control byte and the string length
-    const auto N = str.size();
-    if (N <= 31)
-    {
-        // fixstr
-        write_number(static_cast<uint8_t>(0xA0 | N));
-    }
-    else if (N <= (std::numeric_limits<uint8_t>::max)())
-    {
-        // str 8
-        o << static_cast<CharType>(0xD9);
-        write_number(static_cast<uint8_t>(N));
-    }
-    else if (N <= (std::numeric_limits<uint16_t>::max)())
-    {
-        // str 16
-        o << static_cast<CharType>(0xDA);
-        write_number(static_cast<uint16_t>(N));
-    }
-    else if (N <= (std::numeric_limits<uint32_t>::max)())
-    {
-        // str 32
-        o << static_cast<CharType>(0xDB);
-        write_number(static_cast<uint32_t>(N));
-    }
-
-    // step 2: write the string
-    o << str;
-}
-
-template<typename NumberType>
-void json::binary_writer::write_number(const NumberType n)
-{
-    // step 1: write number to array of length NumberType
-    std::array<uint8_t, sizeof(NumberType)> vec;
-    std::memcpy(vec.data(), &n, sizeof(NumberType));
-
-    // step 2: write array to output (with possible reordering)
-    if (is_little_endian)
-    {
-        // reverse byte order prior to conversion if necessary
-        std::reverse(vec.begin(), vec.end());
-    }
-
-    o << span{vec.data(), sizeof(NumberType)};
-}
-
-template<typename NumberType, typename std::enable_if<
-             std::is_unsigned<NumberType>::value, int>::type>
-void json::binary_writer::write_number_with_ubjson_prefix(const NumberType n,
-                                     const bool add_prefix)
-{
-    if (n <= static_cast<uint64_t>((std::numeric_limits<int8_t>::max)()))
-    {
-        if (add_prefix)
-        {
-            o << static_cast<CharType>('i');  // int8
-        }
-        write_number(static_cast<uint8_t>(n));
-    }
-    else if (n <= (std::numeric_limits<uint8_t>::max)())
-    {
-        if (add_prefix)
-        {
-            o << static_cast<CharType>('U');  // uint8
-        }
-        write_number(static_cast<uint8_t>(n));
-    }
-    else if (n <= static_cast<uint64_t>((std::numeric_limits<int16_t>::max)()))
-    {
-        if (add_prefix)
-        {
-            o << static_cast<CharType>('I');  // int16
-        }
-        write_number(static_cast<int16_t>(n));
-    }
-    else if (n <= static_cast<uint64_t>((std::numeric_limits<int32_t>::max)()))
-    {
-        if (add_prefix)
-        {
-            o << static_cast<CharType>('l');  // int32
-        }
-        write_number(static_cast<int32_t>(n));
-    }
-    else if (n <= static_cast<uint64_t>((std::numeric_limits<int64_t>::max)()))
-    {
-        if (add_prefix)
-        {
-            o << static_cast<CharType>('L');  // int64
-        }
-        write_number(static_cast<int64_t>(n));
-    }
-    else
-    {
-        JSON_THROW(out_of_range::create(407, fmt::format("number overflow serializing {}", n)));
-    }
-}
-
-template<typename NumberType, typename std::enable_if<
-             std::is_signed<NumberType>::value and
-             not std::is_floating_point<NumberType>::value, int>::type>
-void json::binary_writer::write_number_with_ubjson_prefix(const NumberType n,
-                                     const bool add_prefix)
-{
-    if ((std::numeric_limits<int8_t>::min)() <= n and n <= (std::numeric_limits<int8_t>::max)())
-    {
-        if (add_prefix)
-        {
-            o << static_cast<CharType>('i');  // int8
-        }
-        write_number(static_cast<int8_t>(n));
-    }
-    else if (static_cast<int64_t>((std::numeric_limits<uint8_t>::min)()) <= n and n <= static_cast<int64_t>((std::numeric_limits<uint8_t>::max)()))
-    {
-        if (add_prefix)
-        {
-            o << static_cast<CharType>('U');  // uint8
-        }
-        write_number(static_cast<uint8_t>(n));
-    }
-    else if ((std::numeric_limits<int16_t>::min)() <= n and n <= (std::numeric_limits<int16_t>::max)())
-    {
-        if (add_prefix)
-        {
-            o << static_cast<CharType>('I');  // int16
-        }
-        write_number(static_cast<int16_t>(n));
-    }
-    else if ((std::numeric_limits<int32_t>::min)() <= n and n <= (std::numeric_limits<int32_t>::max)())
-    {
-        if (add_prefix)
-        {
-            o << static_cast<CharType>('l');  // int32
-        }
-        write_number(static_cast<int32_t>(n));
-    }
-    else if ((std::numeric_limits<int64_t>::min)() <= n and n <= (std::numeric_limits<int64_t>::max)())
-    {
-        if (add_prefix)
-        {
-            o << static_cast<CharType>('L');  // int64
-        }
-        write_number(static_cast<int64_t>(n));
-    }
-    // LCOV_EXCL_START
-    else
-    {
-        JSON_THROW(out_of_range::create(407, fmt::format("number overflow serializing {}", n)));
-    }
-    // LCOV_EXCL_STOP
-}
-
-json::binary_writer::CharType json::binary_writer::ubjson_prefix(const json& j) const noexcept
-{
-    switch (j.type())
-    {
-        case value_t::null:
-            return 'Z';
-
-        case value_t::boolean:
-            return j.m_value.boolean ? 'T' : 'F';
-
-        case value_t::number_integer:
-        {
-            if ((std::numeric_limits<int8_t>::min)() <= j.m_value.number_integer and j.m_value.number_integer <= (std::numeric_limits<int8_t>::max)())
-            {
-                return 'i';
-            }
-            else if ((std::numeric_limits<uint8_t>::min)() <= j.m_value.number_integer and j.m_value.number_integer <= (std::numeric_limits<uint8_t>::max)())
-            {
-                return 'U';
-            }
-            else if ((std::numeric_limits<int16_t>::min)() <= j.m_value.number_integer and j.m_value.number_integer <= (std::numeric_limits<int16_t>::max)())
-            {
-                return 'I';
-            }
-            else if ((std::numeric_limits<int32_t>::min)() <= j.m_value.number_integer and j.m_value.number_integer <= (std::numeric_limits<int32_t>::max)())
-            {
-                return 'l';
-            }
-            else  // no check and assume int64_t (see note above)
-            {
-                return 'L';
-            }
-        }
-
-        case value_t::number_unsigned:
-        {
-            if (j.m_value.number_unsigned <= static_cast<uint64_t>((std::numeric_limits<int8_t>::max)()))
-            {
-                return 'i';
-            }
-            else if (j.m_value.number_unsigned <= (std::numeric_limits<uint8_t>::max)())
-            {
-                return 'U';
-            }
-            else if (j.m_value.number_unsigned <= static_cast<uint64_t>((std::numeric_limits<int16_t>::max)()))
-            {
-                return 'I';
-            }
-            else if (j.m_value.number_unsigned <= static_cast<uint64_t>((std::numeric_limits<int32_t>::max)()))
-            {
-                return 'l';
-            }
-            else  // no check and assume int64_t (see note above)
-            {
-                return 'L';
-            }
-        }
-
-        case value_t::number_float:
-            return get_ubjson_float_prefix(j.m_value.number_float);
-
-        case value_t::string:
-            return 'S';
-
-        case value_t::array:
-            return '[';
-
-        case value_t::object:
-            return '{';
-
-        default:  // discarded values
-            return 'N';
-    }
-}
-
-std::vector<uint8_t> json::to_cbor(const json& j)
-{
-    std::vector<uint8_t> result;
-    raw_uvector_ostream os(result);
-    to_cbor(os, j);
-    return result;
-}
-
-span<uint8_t> json::to_cbor(const json& j, std::vector<uint8_t>& buf)
-{
-    buf.clear();
-    raw_uvector_ostream os(buf);
-    to_cbor(os, j);
-    return os.array();
-}
-
-span<uint8_t> json::to_cbor(const json& j, SmallVectorImpl<uint8_t>& buf)
-{
-    buf.clear();
-    raw_usvector_ostream os(buf);
-    to_cbor(os, j);
-    return os.array();
-}
-
-void json::to_cbor(raw_ostream& os, const json& j)
-{
-    binary_writer(os).write_cbor(j);
-}
-
-std::vector<uint8_t> json::to_msgpack(const json& j)
-{
-    std::vector<uint8_t> result;
-    raw_uvector_ostream os(result);
-    to_msgpack(os, j);
-    return result;
-}
-
-span<uint8_t> json::to_msgpack(const json& j, std::vector<uint8_t>& buf)
-{
-    buf.clear();
-    raw_uvector_ostream os(buf);
-    to_msgpack(os, j);
-    return os.array();
-}
-
-span<uint8_t> json::to_msgpack(const json& j, SmallVectorImpl<uint8_t>& buf)
-{
-    buf.clear();
-    raw_usvector_ostream os(buf);
-    to_msgpack(os, j);
-    return os.array();
-}
-
-void json::to_msgpack(raw_ostream& os, const json& j)
-{
-    binary_writer(os).write_msgpack(j);
-}
-
-std::vector<uint8_t> json::to_ubjson(const json& j,
-                                     const bool use_size,
-                                     const bool use_type)
-{
-    std::vector<uint8_t> result;
-    raw_uvector_ostream os(result);
-    to_ubjson(os, j, use_size, use_type);
-    return result;
-}
-
-span<uint8_t> json::to_ubjson(const json& j, std::vector<uint8_t>& buf,
-                              const bool use_size, const bool use_type)
-{
-    buf.clear();
-    raw_uvector_ostream os(buf);
-    to_ubjson(os, j, use_size, use_type);
-    return os.array();
-}
-
-span<uint8_t> json::to_ubjson(const json& j, SmallVectorImpl<uint8_t>& buf,
-                              const bool use_size, const bool use_type)
-{
-    buf.clear();
-    raw_usvector_ostream os(buf);
-    to_ubjson(os, j, use_size, use_type);
-    return os.array();
-}
-
-void json::to_ubjson(raw_ostream& os, const json& j,
-                     const bool use_size, const bool use_type)
-{
-    binary_writer(os).write_ubjson(j, use_size, use_type);
-}
-
-}  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/json_parser.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/json_parser.cpp
deleted file mode 100644
index db1ed11..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/json_parser.cpp
+++ /dev/null
@@ -1,1968 +0,0 @@
-/*----------------------------------------------------------------------------*/
-/* Modifications Copyright (c) 2017-2018 FIRST. All Rights Reserved.          */
-/* Open Source Software - may be modified and shared by FRC teams. The code   */
-/* must be accompanied by the FIRST BSD license file in the root directory of */
-/* the project.                                                               */
-/*----------------------------------------------------------------------------*/
-/*
-    __ _____ _____ _____
- __|  |   __|     |   | |  JSON for Modern C++
-|  |  |__   |  |  | | | |  version 3.1.2
-|_____|_____|_____|_|___|  https://github.com/nlohmann/json
-
-Licensed under the MIT License <http://opensource.org/licenses/MIT>.
-Copyright (c) 2013-2018 Niels Lohmann <http://nlohmann.me>.
-
-Permission is hereby  granted, free of charge, to any  person obtaining a copy
-of this software and associated  documentation files (the "Software"), to deal
-in the Software  without restriction, including without  limitation the rights
-to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
-copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
-furnished to do so, subject to the following conditions:
-
-The above copyright notice and this permission notice shall be included in all
-copies or substantial portions of the Software.
-
-THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
-IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
-FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
-AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
-LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
-OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
-SOFTWARE.
-*/
-#define WPI_JSON_IMPLEMENTATION
-#include "wpi/json.h"
-
-#include <clocale>
-#include <cmath>
-#include <cstdlib>
-
-#include "fmt/format.h"
-#include "wpi/SmallString.h"
-#include "wpi/raw_istream.h"
-#include "wpi/raw_ostream.h"
-
-namespace wpi {
-
-/*!
-@brief lexical analysis
-
-This class organizes the lexical analysis during JSON deserialization.
-*/
-class json::lexer
-{
-  public:
-    /// token types for the parser
-    enum class token_type
-    {
-        uninitialized,    ///< indicating the scanner is uninitialized
-        literal_true,     ///< the `true` literal
-        literal_false,    ///< the `false` literal
-        literal_null,     ///< the `null` literal
-        value_string,     ///< a string -- use get_string() for actual value
-        value_unsigned,   ///< an unsigned integer -- use get_number_unsigned() for actual value
-        value_integer,    ///< a signed integer -- use get_number_integer() for actual value
-        value_float,      ///< an floating point number -- use get_number_float() for actual value
-        begin_array,      ///< the character for array begin `[`
-        begin_object,     ///< the character for object begin `{`
-        end_array,        ///< the character for array end `]`
-        end_object,       ///< the character for object end `}`
-        name_separator,   ///< the name separator `:`
-        value_separator,  ///< the value separator `,`
-        parse_error,      ///< indicating a parse error
-        end_of_input,     ///< indicating the end of the input buffer
-        literal_or_value  ///< a literal or the begin of a value (only for diagnostics)
-    };
-
-    /// return name of values of type token_type (only used for errors)
-    static const char* token_type_name(const token_type t) noexcept;
-
-    explicit lexer(raw_istream& s);
-
-    // delete because of pointer members
-    lexer(const lexer&) = delete;
-    lexer& operator=(lexer&) = delete;
-
-  private:
-    /////////////////////
-    // locales
-    /////////////////////
-
-    /// return the locale-dependent decimal point
-    static char get_decimal_point() noexcept
-    {
-        const auto loc = localeconv();
-        assert(loc != nullptr);
-        return (loc->decimal_point == nullptr) ? '.' : *(loc->decimal_point);
-    }
-
-    /////////////////////
-    // scan functions
-    /////////////////////
-
-    /*!
-    @brief get codepoint from 4 hex characters following `\u`
-
-    For input "\u c1 c2 c3 c4" the codepoint is:
-      (c1 * 0x1000) + (c2 * 0x0100) + (c3 * 0x0010) + c4
-    = (c1 << 12) + (c2 << 8) + (c3 << 4) + (c4 << 0)
-
-    Furthermore, the possible characters '0'..'9', 'A'..'F', and 'a'..'f'
-    must be converted to the integers 0x0..0x9, 0xA..0xF, 0xA..0xF, resp. The
-    conversion is done by subtracting the offset (0x30, 0x37, and 0x57)
-    between the ASCII value of the character and the desired integer value.
-
-    @return codepoint (0x0000..0xFFFF) or -1 in case of an error (e.g. EOF or
-            non-hex character)
-    */
-    int get_codepoint();
-
-    /*!
-    @brief check if the next byte(s) are inside a given range
-
-    Adds the current byte and, for each passed range, reads a new byte and
-    checks if it is inside the range. If a violation was detected, set up an
-    error message and return false. Otherwise, return true.
-
-    @param[in] ranges  list of integers; interpreted as list of pairs of
-                       inclusive lower and upper bound, respectively
-
-    @pre The passed list @a ranges must have 2, 4, or 6 elements; that is,
-         1, 2, or 3 pairs. This precondition is enforced by an assertion.
-
-    @return true if and only if no range violation was detected
-    */
-    bool next_byte_in_range(std::initializer_list<int> ranges)
-    {
-        assert(ranges.size() == 2 or ranges.size() == 4 or ranges.size() == 6);
-        add(current);
-
-        for (auto range = ranges.begin(); range != ranges.end(); ++range)
-        {
-            get();
-            if (JSON_LIKELY(*range <= current and current <= *(++range)))
-            {
-                add(current);
-            }
-            else
-            {
-                error_message = "invalid string: ill-formed UTF-8 byte";
-                return false;
-            }
-        }
-
-        return true;
-    }
-
-    /*!
-    @brief scan a string literal
-
-    This function scans a string according to Sect. 7 of RFC 7159. While
-    scanning, bytes are escaped and copied into buffer token_buffer. Then the
-    function returns successfully, token_buffer is *not* null-terminated (as it
-    may contain \0 bytes), and token_buffer.size() is the number of bytes in the
-    string.
-
-    @return token_type::value_string if string could be successfully scanned,
-            token_type::parse_error otherwise
-
-    @note In case of errors, variable error_message contains a textual
-          description.
-    */
-    token_type scan_string();
-
-    static void strtof(float& f, const char* str, char** endptr) noexcept
-    {
-        f = std::strtof(str, endptr);
-    }
-
-    static void strtof(double& f, const char* str, char** endptr) noexcept
-    {
-        f = std::strtod(str, endptr);
-    }
-
-    static void strtof(long double& f, const char* str, char** endptr) noexcept
-    {
-        f = std::strtold(str, endptr);
-    }
-
-    /*!
-    @brief scan a number literal
-
-    This function scans a string according to Sect. 6 of RFC 7159.
-
-    The function is realized with a deterministic finite state machine derived
-    from the grammar described in RFC 7159. Starting in state "init", the
-    input is read and used to determined the next state. Only state "done"
-    accepts the number. State "error" is a trap state to model errors. In the
-    table below, "anything" means any character but the ones listed before.
-
-    state    | 0        | 1-9      | e E      | +       | -       | .        | anything
-    ---------|----------|----------|----------|---------|---------|----------|-----------
-    init     | zero     | any1     | [error]  | [error] | minus   | [error]  | [error]
-    minus    | zero     | any1     | [error]  | [error] | [error] | [error]  | [error]
-    zero     | done     | done     | exponent | done    | done    | decimal1 | done
-    any1     | any1     | any1     | exponent | done    | done    | decimal1 | done
-    decimal1 | decimal2 | [error]  | [error]  | [error] | [error] | [error]  | [error]
-    decimal2 | decimal2 | decimal2 | exponent | done    | done    | done     | done
-    exponent | any2     | any2     | [error]  | sign    | sign    | [error]  | [error]
-    sign     | any2     | any2     | [error]  | [error] | [error] | [error]  | [error]
-    any2     | any2     | any2     | done     | done    | done    | done     | done
-
-    The state machine is realized with one label per state (prefixed with
-    "scan_number_") and `goto` statements between them. The state machine
-    contains cycles, but any cycle can be left when EOF is read. Therefore,
-    the function is guaranteed to terminate.
-
-    During scanning, the read bytes are stored in token_buffer. This string is
-    then converted to a signed integer, an unsigned integer, or a
-    floating-point number.
-
-    @return token_type::value_unsigned, token_type::value_integer, or
-            token_type::value_float if number could be successfully scanned,
-            token_type::parse_error otherwise
-
-    @note The scanner is independent of the current locale. Internally, the
-          locale's decimal point is used instead of `.` to work with the
-          locale-dependent converters.
-    */
-    token_type scan_number();
-
-    /*!
-    @param[in] literal_text  the literal text to expect
-    @param[in] length        the length of the passed literal text
-    @param[in] return_type   the token type to return on success
-    */
-    token_type scan_literal(const char* literal_text, const std::size_t length,
-                            token_type return_type);
-
-    /////////////////////
-    // input management
-    /////////////////////
-
-    /// reset token_buffer; current character is beginning of token
-    void reset() noexcept
-    {
-        token_buffer.clear();
-        token_string.clear();
-        token_string.push_back(std::char_traits<char>::to_char_type(current));
-    }
-
-    /*
-    @brief get next character from the input
-
-    This function provides the interface to the used input adapter. It does
-    not throw in case the input reached EOF, but returns a
-    `std::char_traits<char>::eof()` in that case.  Stores the scanned characters
-    for use in error messages.
-
-    @return character read from the input
-    */
-    std::char_traits<char>::int_type get()
-    {
-        ++chars_read;
-        if (JSON_UNLIKELY(!unget_chars.empty()))
-        {
-            current = unget_chars.back();
-            unget_chars.pop_back();
-            token_string.push_back(current);
-            return current;
-        }
-        char c;
-        is.read(c);
-        if (JSON_UNLIKELY(is.has_error()))
-        {
-            current = std::char_traits<char>::eof();
-        }
-        else
-        {
-            current = std::char_traits<char>::to_int_type(c);
-            token_string.push_back(c);
-        }
-        return current;
-    }
-
-    /// unget current character (return it again on next get)
-    void unget()
-    {
-        --chars_read;
-        if (JSON_LIKELY(current != std::char_traits<char>::eof()))
-        {
-            unget_chars.emplace_back(current);
-            assert(token_string.size() != 0);
-            token_string.pop_back();
-            if (!token_string.empty())
-            {
-                current = token_string.back();
-            }
-        }
-    }
-
-    /// put back character (returned on next get)
-    void putback(std::char_traits<char>::int_type c)
-    {
-        --chars_read;
-        unget_chars.emplace_back(c);
-    }
-
-    /// add a character to token_buffer
-    void add(int c)
-    {
-        token_buffer.push_back(std::char_traits<char>::to_char_type(c));
-    }
-
-  public:
-    /////////////////////
-    // value getters
-    /////////////////////
-
-    /// return integer value
-    int64_t get_number_integer() const noexcept
-    {
-        return value_integer;
-    }
-
-    /// return unsigned integer value
-    uint64_t get_number_unsigned() const noexcept
-    {
-        return value_unsigned;
-    }
-
-    /// return floating-point value
-    double get_number_float() const noexcept
-    {
-        return value_float;
-    }
-
-    /// return current string value
-    std::string_view get_string()
-    {
-        return token_buffer;
-    }
-
-    /////////////////////
-    // diagnostics
-    /////////////////////
-
-    /// return position of last read token
-    std::size_t get_position() const noexcept
-    {
-        return chars_read;
-    }
-
-    /// return the last read token (for errors only).  Will never contain EOF
-    /// (an arbitrary value that is not a valid char value, often -1), because
-    /// 255 may legitimately occur.  May contain NUL, which should be escaped.
-    std::string get_token_string() const;
-
-    /// return syntax error message
-    const char* get_error_message() const noexcept
-    {
-        return error_message;
-    }
-
-    /////////////////////
-    // actual scanner
-    /////////////////////
-
-    token_type scan();
-
-  private:
-    /// input adapter
-    raw_istream& is;
-
-    /// the current character
-    std::char_traits<char>::int_type current = std::char_traits<char>::eof();
-
-    /// unget characters
-    SmallVector<std::char_traits<char>::int_type, 4> unget_chars;
-
-    /// the number of characters read
-    std::size_t chars_read = 0;
-
-    /// raw input token string (for error messages)
-    SmallString<128> token_string {};
-
-    /// buffer for variable-length tokens (numbers, strings)
-    SmallString<128> token_buffer {};
-
-    /// a description of occurred lexer errors
-    const char* error_message = "";
-
-    // number values
-    int64_t value_integer = 0;
-    uint64_t value_unsigned = 0;
-    double value_float = 0;
-
-    /// the decimal point
-    const char decimal_point_char = '.';
-};
-
-////////////
-// parser //
-////////////
-
-/*!
-@brief syntax analysis
-
-This class implements a recursive decent parser.
-*/
-class json::parser
-{
-    using lexer_t = json::lexer;
-    using token_type = typename lexer_t::token_type;
-
-  public:
-    /// a parser reading from an input adapter
-    explicit parser(raw_istream& s,
-                    const parser_callback_t cb = nullptr,
-                    const bool allow_exceptions_ = true)
-        : callback(cb), m_lexer(s), allow_exceptions(allow_exceptions_)
-    {}
-
-    /*!
-    @brief public parser interface
-
-    @param[in] strict      whether to expect the last token to be EOF
-    @param[in,out] result  parsed JSON value
-
-    @throw parse_error.101 in case of an unexpected token
-    @throw parse_error.102 if to_unicode fails or surrogate error
-    @throw parse_error.103 if to_unicode fails
-    */
-    void parse(const bool strict, json& result);
-
-    /*!
-    @brief public accept interface
-
-    @param[in] strict  whether to expect the last token to be EOF
-    @return whether the input is a proper JSON text
-    */
-    bool accept(const bool strict = true)
-    {
-        // read first token
-        get_token();
-
-        if (not accept_internal())
-        {
-            return false;
-        }
-
-        // strict => last token must be EOF
-        return not strict or (get_token() == token_type::end_of_input);
-    }
-
-  private:
-    /*!
-    @brief the actual parser
-    @throw parse_error.101 in case of an unexpected token
-    @throw parse_error.102 if to_unicode fails or surrogate error
-    @throw parse_error.103 if to_unicode fails
-    */
-    void parse_internal(bool keep, json& result);
-
-    /*!
-    @brief the actual acceptor
-
-    @invariant 1. The last token is not yet processed. Therefore, the caller
-                  of this function must make sure a token has been read.
-               2. When this function returns, the last token is processed.
-                  That is, the last read character was already considered.
-
-    This invariant makes sure that no token needs to be "unput".
-    */
-    bool accept_internal();
-
-    /// get next token from lexer
-    token_type get_token()
-    {
-        return (last_token = m_lexer.scan());
-    }
-
-    /*!
-    @throw parse_error.101 if expected token did not occur
-    */
-    bool expect(token_type t)
-    {
-        if (JSON_UNLIKELY(t != last_token))
-        {
-            errored = true;
-            expected = t;
-            if (allow_exceptions)
-            {
-                throw_exception();
-            }
-            else
-            {
-                return false;
-            }
-        }
-
-        return true;
-    }
-
-    [[noreturn]] void throw_exception() const;
-
-  private:
-    /// current level of recursion
-    int depth = 0;
-    /// callback function
-    const parser_callback_t callback = nullptr;
-    /// the type of the last read token
-    token_type last_token = token_type::uninitialized;
-    /// the lexer
-    lexer_t m_lexer;
-    /// whether a syntax error occurred
-    bool errored = false;
-    /// possible reason for the syntax error
-    token_type expected = token_type::uninitialized;
-    /// whether to throw exceptions in case of errors
-    const bool allow_exceptions = true;
-};
-
-const char* json::lexer::token_type_name(const token_type t) noexcept
-{
-    switch (t)
-    {
-        case token_type::uninitialized:
-            return "<uninitialized>";
-        case token_type::literal_true:
-            return "true literal";
-        case token_type::literal_false:
-            return "false literal";
-        case token_type::literal_null:
-            return "null literal";
-        case token_type::value_string:
-            return "string literal";
-        case lexer::token_type::value_unsigned:
-        case lexer::token_type::value_integer:
-        case lexer::token_type::value_float:
-            return "number literal";
-        case token_type::begin_array:
-            return "'['";
-        case token_type::begin_object:
-            return "'{'";
-        case token_type::end_array:
-            return "']'";
-        case token_type::end_object:
-            return "'}'";
-        case token_type::name_separator:
-            return "':'";
-        case token_type::value_separator:
-            return "','";
-        case token_type::parse_error:
-            return "<parse error>";
-        case token_type::end_of_input:
-            return "end of input";
-        case token_type::literal_or_value:
-            return "'[', '{', or a literal";
-        default: // catch non-enum values
-            return "unknown token"; // LCOV_EXCL_LINE
-    }
-}
-
-json::lexer::lexer(raw_istream& s)
-    : is(s), decimal_point_char(get_decimal_point())
-{
-    // skip byte order mark
-    std::char_traits<char>::int_type c;
-    if ((c = get()) == 0xEF)
-    {
-        if ((c = get()) == 0xBB)
-        {
-            if ((c = get()) == 0xBF)
-            {
-                chars_read = 0;
-                return; // Ignore BOM
-            }
-            else if (c != std::char_traits<char>::eof())
-            {
-                unget();
-            }
-            putback('\xBB');
-        }
-        else if (c != std::char_traits<char>::eof())
-        {
-            unget();
-        }
-        putback('\xEF');
-    }
-    unget(); // no byte order mark; process as usual
-}
-
-int json::lexer::get_codepoint()
-{
-    // this function only makes sense after reading `\u`
-    assert(current == 'u');
-    int codepoint = 0;
-
-    const auto factors = { 12, 8, 4, 0 };
-    for (const auto factor : factors)
-    {
-        get();
-
-        if (current >= '0' and current <= '9')
-        {
-            codepoint += ((current - 0x30) << factor);
-        }
-        else if (current >= 'A' and current <= 'F')
-        {
-            codepoint += ((current - 0x37) << factor);
-        }
-        else if (current >= 'a' and current <= 'f')
-        {
-            codepoint += ((current - 0x57) << factor);
-        }
-        else
-        {
-            return -1;
-        }
-    }
-
-    assert(0x0000 <= codepoint and codepoint <= 0xFFFF);
-    return codepoint;
-}
-
-json::lexer::token_type json::lexer::scan_string()
-{
-    // reset token_buffer (ignore opening quote)
-    reset();
-
-    // we entered the function by reading an open quote
-    assert(current == '\"');
-
-    while (true)
-    {
-        // get next character
-        switch (get())
-        {
-            // end of file while parsing string
-            case std::char_traits<char>::eof():
-            {
-                error_message = "invalid string: missing closing quote";
-                return token_type::parse_error;
-            }
-
-            // closing quote
-            case '\"':
-            {
-                return token_type::value_string;
-            }
-
-            // escapes
-            case '\\':
-            {
-                switch (get())
-                {
-                    // quotation mark
-                    case '\"':
-                        add('\"');
-                        break;
-                    // reverse solidus
-                    case '\\':
-                        add('\\');
-                        break;
-                    // solidus
-                    case '/':
-                        add('/');
-                        break;
-                    // backspace
-                    case 'b':
-                        add('\b');
-                        break;
-                    // form feed
-                    case 'f':
-                        add('\f');
-                        break;
-                    // line feed
-                    case 'n':
-                        add('\n');
-                        break;
-                    // carriage return
-                    case 'r':
-                        add('\r');
-                        break;
-                    // tab
-                    case 't':
-                        add('\t');
-                        break;
-
-                    // unicode escapes
-                    case 'u':
-                    {
-                        const int codepoint1 = get_codepoint();
-                        int codepoint = codepoint1; // start with codepoint1
-
-                        if (JSON_UNLIKELY(codepoint1 == -1))
-                        {
-                            error_message = "invalid string: '\\u' must be followed by 4 hex digits";
-                            return token_type::parse_error;
-                        }
-
-                        // check if code point is a high surrogate
-                        if (0xD800 <= codepoint1 and codepoint1 <= 0xDBFF)
-                        {
-                            // expect next \uxxxx entry
-                            if (JSON_LIKELY(get() == '\\' and get() == 'u'))
-                            {
-                                const int codepoint2 = get_codepoint();
-
-                                if (JSON_UNLIKELY(codepoint2 == -1))
-                                {
-                                    error_message = "invalid string: '\\u' must be followed by 4 hex digits";
-                                    return token_type::parse_error;
-                                }
-
-                                // check if codepoint2 is a low surrogate
-                                if (JSON_LIKELY(0xDC00 <= codepoint2 and codepoint2 <= 0xDFFF))
-                                {
-                                    // overwrite codepoint
-                                    codepoint =
-                                        // high surrogate occupies the most significant 22 bits
-                                        (codepoint1 << 10)
-                                        // low surrogate occupies the least significant 15 bits
-                                        + codepoint2
-                                        // there is still the 0xD800, 0xDC00 and 0x10000 noise
-                                        // in the result so we have to subtract with:
-                                        // (0xD800 << 10) + DC00 - 0x10000 = 0x35FDC00
-                                        - 0x35FDC00;
-                                }
-                                else
-                                {
-                                    error_message = "invalid string: surrogate U+DC00..U+DFFF must be followed by U+DC00..U+DFFF";
-                                    return token_type::parse_error;
-                                }
-                            }
-                            else
-                            {
-                                error_message = "invalid string: surrogate U+DC00..U+DFFF must be followed by U+DC00..U+DFFF";
-                                return token_type::parse_error;
-                            }
-                        }
-                        else
-                        {
-                            if (JSON_UNLIKELY(0xDC00 <= codepoint1 and codepoint1 <= 0xDFFF))
-                            {
-                                error_message = "invalid string: surrogate U+DC00..U+DFFF must follow U+D800..U+DBFF";
-                                return token_type::parse_error;
-                            }
-                        }
-
-                        // result of the above calculation yields a proper codepoint
-                        assert(0x00 <= codepoint and codepoint <= 0x10FFFF);
-
-                        // translate codepoint into bytes
-                        if (codepoint < 0x80)
-                        {
-                            // 1-byte characters: 0xxxxxxx (ASCII)
-                            add(codepoint);
-                        }
-                        else if (codepoint <= 0x7FF)
-                        {
-                            // 2-byte characters: 110xxxxx 10xxxxxx
-                            add(0xC0 | (codepoint >> 6));
-                            add(0x80 | (codepoint & 0x3F));
-                        }
-                        else if (codepoint <= 0xFFFF)
-                        {
-                            // 3-byte characters: 1110xxxx 10xxxxxx 10xxxxxx
-                            add(0xE0 | (codepoint >> 12));
-                            add(0x80 | ((codepoint >> 6) & 0x3F));
-                            add(0x80 | (codepoint & 0x3F));
-                        }
-                        else
-                        {
-                            // 4-byte characters: 11110xxx 10xxxxxx 10xxxxxx 10xxxxxx
-                            add(0xF0 | (codepoint >> 18));
-                            add(0x80 | ((codepoint >> 12) & 0x3F));
-                            add(0x80 | ((codepoint >> 6) & 0x3F));
-                            add(0x80 | (codepoint & 0x3F));
-                        }
-
-                        break;
-                    }
-
-                    // other characters after escape
-                    default:
-                        error_message = "invalid string: forbidden character after backslash";
-                        return token_type::parse_error;
-                }
-
-                break;
-            }
-
-            // invalid control characters
-            case 0x00:
-            case 0x01:
-            case 0x02:
-            case 0x03:
-            case 0x04:
-            case 0x05:
-            case 0x06:
-            case 0x07:
-            case 0x08:
-            case 0x09:
-            case 0x0A:
-            case 0x0B:
-            case 0x0C:
-            case 0x0D:
-            case 0x0E:
-            case 0x0F:
-            case 0x10:
-            case 0x11:
-            case 0x12:
-            case 0x13:
-            case 0x14:
-            case 0x15:
-            case 0x16:
-            case 0x17:
-            case 0x18:
-            case 0x19:
-            case 0x1A:
-            case 0x1B:
-            case 0x1C:
-            case 0x1D:
-            case 0x1E:
-            case 0x1F:
-            {
-                error_message = "invalid string: control character must be escaped";
-                return token_type::parse_error;
-            }
-
-            // U+0020..U+007F (except U+0022 (quote) and U+005C (backspace))
-            case 0x20:
-            case 0x21:
-            case 0x23:
-            case 0x24:
-            case 0x25:
-            case 0x26:
-            case 0x27:
-            case 0x28:
-            case 0x29:
-            case 0x2A:
-            case 0x2B:
-            case 0x2C:
-            case 0x2D:
-            case 0x2E:
-            case 0x2F:
-            case 0x30:
-            case 0x31:
-            case 0x32:
-            case 0x33:
-            case 0x34:
-            case 0x35:
-            case 0x36:
-            case 0x37:
-            case 0x38:
-            case 0x39:
-            case 0x3A:
-            case 0x3B:
-            case 0x3C:
-            case 0x3D:
-            case 0x3E:
-            case 0x3F:
-            case 0x40:
-            case 0x41:
-            case 0x42:
-            case 0x43:
-            case 0x44:
-            case 0x45:
-            case 0x46:
-            case 0x47:
-            case 0x48:
-            case 0x49:
-            case 0x4A:
-            case 0x4B:
-            case 0x4C:
-            case 0x4D:
-            case 0x4E:
-            case 0x4F:
-            case 0x50:
-            case 0x51:
-            case 0x52:
-            case 0x53:
-            case 0x54:
-            case 0x55:
-            case 0x56:
-            case 0x57:
-            case 0x58:
-            case 0x59:
-            case 0x5A:
-            case 0x5B:
-            case 0x5D:
-            case 0x5E:
-            case 0x5F:
-            case 0x60:
-            case 0x61:
-            case 0x62:
-            case 0x63:
-            case 0x64:
-            case 0x65:
-            case 0x66:
-            case 0x67:
-            case 0x68:
-            case 0x69:
-            case 0x6A:
-            case 0x6B:
-            case 0x6C:
-            case 0x6D:
-            case 0x6E:
-            case 0x6F:
-            case 0x70:
-            case 0x71:
-            case 0x72:
-            case 0x73:
-            case 0x74:
-            case 0x75:
-            case 0x76:
-            case 0x77:
-            case 0x78:
-            case 0x79:
-            case 0x7A:
-            case 0x7B:
-            case 0x7C:
-            case 0x7D:
-            case 0x7E:
-            case 0x7F:
-            {
-                add(current);
-                break;
-            }
-
-            // U+0080..U+07FF: bytes C2..DF 80..BF
-            case 0xC2:
-            case 0xC3:
-            case 0xC4:
-            case 0xC5:
-            case 0xC6:
-            case 0xC7:
-            case 0xC8:
-            case 0xC9:
-            case 0xCA:
-            case 0xCB:
-            case 0xCC:
-            case 0xCD:
-            case 0xCE:
-            case 0xCF:
-            case 0xD0:
-            case 0xD1:
-            case 0xD2:
-            case 0xD3:
-            case 0xD4:
-            case 0xD5:
-            case 0xD6:
-            case 0xD7:
-            case 0xD8:
-            case 0xD9:
-            case 0xDA:
-            case 0xDB:
-            case 0xDC:
-            case 0xDD:
-            case 0xDE:
-            case 0xDF:
-            {
-                if (JSON_UNLIKELY(not next_byte_in_range({0x80, 0xBF})))
-                {
-                    return token_type::parse_error;
-                }
-                break;
-            }
-
-            // U+0800..U+0FFF: bytes E0 A0..BF 80..BF
-            case 0xE0:
-            {
-                if (JSON_UNLIKELY(not (next_byte_in_range({0xA0, 0xBF, 0x80, 0xBF}))))
-                {
-                    return token_type::parse_error;
-                }
-                break;
-            }
-
-            // U+1000..U+CFFF: bytes E1..EC 80..BF 80..BF
-            // U+E000..U+FFFF: bytes EE..EF 80..BF 80..BF
-            case 0xE1:
-            case 0xE2:
-            case 0xE3:
-            case 0xE4:
-            case 0xE5:
-            case 0xE6:
-            case 0xE7:
-            case 0xE8:
-            case 0xE9:
-            case 0xEA:
-            case 0xEB:
-            case 0xEC:
-            case 0xEE:
-            case 0xEF:
-            {
-                if (JSON_UNLIKELY(not (next_byte_in_range({0x80, 0xBF, 0x80, 0xBF}))))
-                {
-                    return token_type::parse_error;
-                }
-                break;
-            }
-
-            // U+D000..U+D7FF: bytes ED 80..9F 80..BF
-            case 0xED:
-            {
-                if (JSON_UNLIKELY(not (next_byte_in_range({0x80, 0x9F, 0x80, 0xBF}))))
-                {
-                    return token_type::parse_error;
-                }
-                break;
-            }
-
-            // U+10000..U+3FFFF F0 90..BF 80..BF 80..BF
-            case 0xF0:
-            {
-                if (JSON_UNLIKELY(not (next_byte_in_range({0x90, 0xBF, 0x80, 0xBF, 0x80, 0xBF}))))
-                {
-                    return token_type::parse_error;
-                }
-                break;
-            }
-
-            // U+40000..U+FFFFF F1..F3 80..BF 80..BF 80..BF
-            case 0xF1:
-            case 0xF2:
-            case 0xF3:
-            {
-                if (JSON_UNLIKELY(not (next_byte_in_range({0x80, 0xBF, 0x80, 0xBF, 0x80, 0xBF}))))
-                {
-                    return token_type::parse_error;
-                }
-                break;
-            }
-
-            // U+100000..U+10FFFF F4 80..8F 80..BF 80..BF
-            case 0xF4:
-            {
-                if (JSON_UNLIKELY(not (next_byte_in_range({0x80, 0x8F, 0x80, 0xBF, 0x80, 0xBF}))))
-                {
-                    return token_type::parse_error;
-                }
-                break;
-            }
-
-            // remaining bytes (80..C1 and F5..FF) are ill-formed
-            default:
-            {
-                error_message = "invalid string: ill-formed UTF-8 byte";
-                return token_type::parse_error;
-            }
-        }
-    }
-}
-
-json::lexer::token_type json::lexer::scan_number()
-{
-    // reset token_buffer to store the number's bytes
-    reset();
-
-    // the type of the parsed number; initially set to unsigned; will be
-    // changed if minus sign, decimal point or exponent is read
-    token_type number_type = token_type::value_unsigned;
-
-    // state (init): we just found out we need to scan a number
-    switch (current)
-    {
-        case '-':
-        {
-            add(current);
-            goto scan_number_minus;
-        }
-
-        case '0':
-        {
-            add(current);
-            goto scan_number_zero;
-        }
-
-        case '1':
-        case '2':
-        case '3':
-        case '4':
-        case '5':
-        case '6':
-        case '7':
-        case '8':
-        case '9':
-        {
-            add(current);
-            goto scan_number_any1;
-        }
-
-        default:
-        {
-            // all other characters are rejected outside scan_number()
-            assert(false); // LCOV_EXCL_LINE
-        }
-    }
-
-scan_number_minus:
-    // state: we just parsed a leading minus sign
-    number_type = token_type::value_integer;
-    switch (get())
-    {
-        case '0':
-        {
-            add(current);
-            goto scan_number_zero;
-        }
-
-        case '1':
-        case '2':
-        case '3':
-        case '4':
-        case '5':
-        case '6':
-        case '7':
-        case '8':
-        case '9':
-        {
-            add(current);
-            goto scan_number_any1;
-        }
-
-        default:
-        {
-            error_message = "invalid number; expected digit after '-'";
-            return token_type::parse_error;
-        }
-    }
-
-scan_number_zero:
-    // state: we just parse a zero (maybe with a leading minus sign)
-    switch (get())
-    {
-        case '.':
-        {
-            add(decimal_point_char);
-            goto scan_number_decimal1;
-        }
-
-        case 'e':
-        case 'E':
-        {
-            add(current);
-            goto scan_number_exponent;
-        }
-
-        default:
-            goto scan_number_done;
-    }
-
-scan_number_any1:
-    // state: we just parsed a number 0-9 (maybe with a leading minus sign)
-    switch (get())
-    {
-        case '0':
-        case '1':
-        case '2':
-        case '3':
-        case '4':
-        case '5':
-        case '6':
-        case '7':
-        case '8':
-        case '9':
-        {
-            add(current);
-            goto scan_number_any1;
-        }
-
-        case '.':
-        {
-            add(decimal_point_char);
-            goto scan_number_decimal1;
-        }
-
-        case 'e':
-        case 'E':
-        {
-            add(current);
-            goto scan_number_exponent;
-        }
-
-        default:
-            goto scan_number_done;
-    }
-
-scan_number_decimal1:
-    // state: we just parsed a decimal point
-    number_type = token_type::value_float;
-    switch (get())
-    {
-        case '0':
-        case '1':
-        case '2':
-        case '3':
-        case '4':
-        case '5':
-        case '6':
-        case '7':
-        case '8':
-        case '9':
-        {
-            add(current);
-            goto scan_number_decimal2;
-        }
-
-        default:
-        {
-            error_message = "invalid number; expected digit after '.'";
-            return token_type::parse_error;
-        }
-    }
-
-scan_number_decimal2:
-    // we just parsed at least one number after a decimal point
-    switch (get())
-    {
-        case '0':
-        case '1':
-        case '2':
-        case '3':
-        case '4':
-        case '5':
-        case '6':
-        case '7':
-        case '8':
-        case '9':
-        {
-            add(current);
-            goto scan_number_decimal2;
-        }
-
-        case 'e':
-        case 'E':
-        {
-            add(current);
-            goto scan_number_exponent;
-        }
-
-        default:
-            goto scan_number_done;
-    }
-
-scan_number_exponent:
-    // we just parsed an exponent
-    number_type = token_type::value_float;
-    switch (get())
-    {
-        case '+':
-        case '-':
-        {
-            add(current);
-            goto scan_number_sign;
-        }
-
-        case '0':
-        case '1':
-        case '2':
-        case '3':
-        case '4':
-        case '5':
-        case '6':
-        case '7':
-        case '8':
-        case '9':
-        {
-            add(current);
-            goto scan_number_any2;
-        }
-
-        default:
-        {
-            error_message =
-                "invalid number; expected '+', '-', or digit after exponent";
-            return token_type::parse_error;
-        }
-    }
-
-scan_number_sign:
-    // we just parsed an exponent sign
-    switch (get())
-    {
-        case '0':
-        case '1':
-        case '2':
-        case '3':
-        case '4':
-        case '5':
-        case '6':
-        case '7':
-        case '8':
-        case '9':
-        {
-            add(current);
-            goto scan_number_any2;
-        }
-
-        default:
-        {
-            error_message = "invalid number; expected digit after exponent sign";
-            return token_type::parse_error;
-        }
-    }
-
-scan_number_any2:
-    // we just parsed a number after the exponent or exponent sign
-    switch (get())
-    {
-        case '0':
-        case '1':
-        case '2':
-        case '3':
-        case '4':
-        case '5':
-        case '6':
-        case '7':
-        case '8':
-        case '9':
-        {
-            add(current);
-            goto scan_number_any2;
-        }
-
-        default:
-            goto scan_number_done;
-    }
-
-scan_number_done:
-    // unget the character after the number (we only read it to know that
-    // we are done scanning a number)
-    unget();
-
-    char* endptr = nullptr;
-    errno = 0;
-
-    // try to parse integers first and fall back to floats
-    if (number_type == token_type::value_unsigned)
-    {
-        const auto x = std::strtoull(token_buffer.c_str(), &endptr, 10);
-
-        // we checked the number format before
-        assert(endptr == token_buffer.data() + token_buffer.size());
-
-        if (errno == 0)
-        {
-            value_unsigned = static_cast<uint64_t>(x);
-            if (value_unsigned == x)
-            {
-                return token_type::value_unsigned;
-            }
-        }
-    }
-    else if (number_type == token_type::value_integer)
-    {
-        const auto x = std::strtoll(token_buffer.c_str(), &endptr, 10);
-
-        // we checked the number format before
-        assert(endptr == token_buffer.data() + token_buffer.size());
-
-        if (errno == 0)
-        {
-            value_integer = static_cast<int64_t>(x);
-            if (value_integer == x)
-            {
-                return token_type::value_integer;
-            }
-        }
-    }
-
-    // this code is reached if we parse a floating-point number or if an
-    // integer conversion above failed
-    strtof(value_float, token_buffer.c_str(), &endptr);
-
-    // we checked the number format before
-    assert(endptr == token_buffer.data() + token_buffer.size());
-
-    return token_type::value_float;
-}
-
-json::lexer::token_type json::lexer::scan_literal(const char* literal_text, const std::size_t length,
-                        token_type return_type)
-{
-    assert(current == literal_text[0]);
-    for (std::size_t i = 1; i < length; ++i)
-    {
-        if (JSON_UNLIKELY(get() != literal_text[i]))
-        {
-            error_message = "invalid literal";
-            return token_type::parse_error;
-        }
-    }
-    return return_type;
-}
-
-std::string json::lexer::get_token_string() const
-{
-    // escape control characters
-    std::string result;
-    raw_string_ostream ss(result);
-    for (const unsigned char c : token_string)
-    {
-        if (c <= '\x1F')
-        {
-            // escape control characters
-            ss << fmt::format("<U+{:04X}>", c);
-        }
-        else
-        {
-            // add character as is
-            ss << c;
-        }
-    }
-
-    ss.flush();
-    return result;
-}
-
-json::lexer::token_type json::lexer::scan()
-{
-    // read next character and ignore whitespace
-    do
-    {
-        get();
-    }
-    while (current == ' ' or current == '\t' or current == '\n' or current == '\r');
-
-    switch (current)
-    {
-        // structural characters
-        case '[':
-            return token_type::begin_array;
-        case ']':
-            return token_type::end_array;
-        case '{':
-            return token_type::begin_object;
-        case '}':
-            return token_type::end_object;
-        case ':':
-            return token_type::name_separator;
-        case ',':
-            return token_type::value_separator;
-
-        // literals
-        case 't':
-            return scan_literal("true", 4, token_type::literal_true);
-        case 'f':
-            return scan_literal("false", 5, token_type::literal_false);
-        case 'n':
-            return scan_literal("null", 4, token_type::literal_null);
-
-        // string
-        case '\"':
-            return scan_string();
-
-        // number
-        case '-':
-        case '0':
-        case '1':
-        case '2':
-        case '3':
-        case '4':
-        case '5':
-        case '6':
-        case '7':
-        case '8':
-        case '9':
-            return scan_number();
-
-        // end of input (the null byte is needed when parsing from
-        // string literals)
-        case '\0':
-        case std::char_traits<char>::eof():
-            return token_type::end_of_input;
-
-        // error
-        default:
-            error_message = "invalid literal";
-            return token_type::parse_error;
-    }
-}
-
-void json::parser::parse(const bool strict, json& result)
-{
-    // read first token
-    get_token();
-
-    parse_internal(true, result);
-    result.assert_invariant();
-
-    // in strict mode, input must be completely read
-    if (strict)
-    {
-        get_token();
-        expect(token_type::end_of_input);
-    }
-
-    // in case of an error, return discarded value
-    if (errored)
-    {
-        result = value_t::discarded;
-        return;
-    }
-
-    // set top-level value to null if it was discarded by the callback
-    // function
-    if (result.is_discarded())
-    {
-        result = nullptr;
-    }
-}
-
-void json::parser::parse_internal(bool keep, json& result)
-{
-    // never parse after a parse error was detected
-    assert(not errored);
-
-    // start with a discarded value
-    if (not result.is_discarded())
-    {
-        result.m_value.destroy(result.m_type);
-        result.m_type = value_t::discarded;
-    }
-
-    switch (last_token)
-    {
-        case token_type::begin_object:
-        {
-            if (keep)
-            {
-                if (callback)
-                {
-                    keep = callback(depth++, parse_event_t::object_start, result);
-                }
-
-                if (not callback or keep)
-                {
-                    // explicitly set result to object to cope with {}
-                    result.m_type = value_t::object;
-                    result.m_value = value_t::object;
-                }
-            }
-
-            // read next token
-            get_token();
-
-            // closing } -> we are done
-            if (last_token == token_type::end_object)
-            {
-                if (keep and callback and not callback(--depth, parse_event_t::object_end, result))
-                {
-                    result.m_value.destroy(result.m_type);
-                    result.m_type = value_t::discarded;
-                }
-                break;
-            }
-
-            // parse values
-            SmallString<128> key;
-            json value;
-            while (true)
-            {
-                // store key
-                if (not expect(token_type::value_string))
-                {
-                    return;
-                }
-                key = m_lexer.get_string();
-
-                bool keep_tag = false;
-                if (keep)
-                {
-                    if (callback)
-                    {
-                        json k(key);
-                        keep_tag = callback(depth, parse_event_t::key, k);
-                    }
-                    else
-                    {
-                        keep_tag = true;
-                    }
-                }
-
-                // parse separator (:)
-                get_token();
-                if (not expect(token_type::name_separator))
-                {
-                    return;
-                }
-
-                // parse and add value
-                get_token();
-                value.m_value.destroy(value.m_type);
-                value.m_type = value_t::discarded;
-                parse_internal(keep, value);
-
-                if (JSON_UNLIKELY(errored))
-                {
-                    return;
-                }
-
-                if (keep and keep_tag and not value.is_discarded())
-                {
-                    result.m_value.object->try_emplace(std::string_view(key.data(), key.size()), std::move(value));
-                }
-
-                // comma -> next value
-                get_token();
-                if (last_token == token_type::value_separator)
-                {
-                    get_token();
-                    continue;
-                }
-
-                // closing }
-                if (not expect(token_type::end_object))
-                {
-                    return;
-                }
-                break;
-            }
-
-            if (keep and callback and not callback(--depth, parse_event_t::object_end, result))
-            {
-                result.m_value.destroy(result.m_type);
-                result.m_type = value_t::discarded;
-            }
-            break;
-        }
-
-        case token_type::begin_array:
-        {
-            if (keep)
-            {
-                if (callback)
-                {
-                    keep = callback(depth++, parse_event_t::array_start, result);
-                }
-
-                if (not callback or keep)
-                {
-                    // explicitly set result to array to cope with []
-                    result.m_type = value_t::array;
-                    result.m_value = value_t::array;
-                }
-            }
-
-            // read next token
-            get_token();
-
-            // closing ] -> we are done
-            if (last_token == token_type::end_array)
-            {
-                if (callback and not callback(--depth, parse_event_t::array_end, result))
-                {
-                    result.m_value.destroy(result.m_type);
-                    result.m_type = value_t::discarded;
-                }
-                break;
-            }
-
-            // parse values
-            json value;
-            while (true)
-            {
-                // parse value
-                value.m_value.destroy(value.m_type);
-                value.m_type = value_t::discarded;
-                parse_internal(keep, value);
-
-                if (JSON_UNLIKELY(errored))
-                {
-                    return;
-                }
-
-                if (keep and not value.is_discarded())
-                {
-                    result.m_value.array->push_back(std::move(value));
-                }
-
-                // comma -> next value
-                get_token();
-                if (last_token == token_type::value_separator)
-                {
-                    get_token();
-                    continue;
-                }
-
-                // closing ]
-                if (not expect(token_type::end_array))
-                {
-                    return;
-                }
-                break;
-            }
-
-            if (keep and callback and not callback(--depth, parse_event_t::array_end, result))
-            {
-                result.m_value.destroy(result.m_type);
-                result.m_type = value_t::discarded;
-            }
-            break;
-        }
-
-        case token_type::literal_null:
-        {
-            result.m_type = value_t::null;
-            break;
-        }
-
-        case token_type::value_string:
-        {
-            result.m_type = value_t::string;
-            result.m_value = m_lexer.get_string();
-            break;
-        }
-
-        case token_type::literal_true:
-        {
-            result.m_type = value_t::boolean;
-            result.m_value = true;
-            break;
-        }
-
-        case token_type::literal_false:
-        {
-            result.m_type = value_t::boolean;
-            result.m_value = false;
-            break;
-        }
-
-        case token_type::value_unsigned:
-        {
-            result.m_type = value_t::number_unsigned;
-            result.m_value = m_lexer.get_number_unsigned();
-            break;
-        }
-
-        case token_type::value_integer:
-        {
-            result.m_type = value_t::number_integer;
-            result.m_value = m_lexer.get_number_integer();
-            break;
-        }
-
-        case token_type::value_float:
-        {
-            result.m_type = value_t::number_float;
-            result.m_value = m_lexer.get_number_float();
-
-            // throw in case of infinity or NAN
-            if (JSON_UNLIKELY(not std::isfinite(result.m_value.number_float)))
-            {
-                if (allow_exceptions)
-                {
-                    JSON_THROW(out_of_range::create(406,
-                        fmt::format("number overflow parsing '{}'", m_lexer.get_token_string())));
-                }
-                expect(token_type::uninitialized);
-            }
-            break;
-        }
-
-        case token_type::parse_error:
-        {
-            // using "uninitialized" to avoid "expected" message
-            if (not expect(token_type::uninitialized))
-            {
-                return;
-            }
-            break; // LCOV_EXCL_LINE
-        }
-
-        default:
-        {
-            // the last token was unexpected; we expected a value
-            if (not expect(token_type::literal_or_value))
-            {
-                return;
-            }
-            break; // LCOV_EXCL_LINE
-        }
-    }
-
-    if (keep and callback and not callback(depth, parse_event_t::value, result))
-    {
-        result.m_value.destroy(result.m_type);
-        result.m_type = value_t::discarded;
-    }
-}
-
-bool json::parser::accept_internal()
-{
-    switch (last_token)
-    {
-        case token_type::begin_object:
-        {
-            // read next token
-            get_token();
-
-            // closing } -> we are done
-            if (last_token == token_type::end_object)
-            {
-                return true;
-            }
-
-            // parse values
-            while (true)
-            {
-                // parse key
-                if (last_token != token_type::value_string)
-                {
-                    return false;
-                }
-
-                // parse separator (:)
-                get_token();
-                if (last_token != token_type::name_separator)
-                {
-                    return false;
-                }
-
-                // parse value
-                get_token();
-                if (not accept_internal())
-                {
-                    return false;
-                }
-
-                // comma -> next value
-                get_token();
-                if (last_token == token_type::value_separator)
-                {
-                    get_token();
-                    continue;
-                }
-
-                // closing }
-                return (last_token == token_type::end_object);
-            }
-        }
-
-        case token_type::begin_array:
-        {
-            // read next token
-            get_token();
-
-            // closing ] -> we are done
-            if (last_token == token_type::end_array)
-            {
-                return true;
-            }
-
-            // parse values
-            while (true)
-            {
-                // parse value
-                if (not accept_internal())
-                {
-                    return false;
-                }
-
-                // comma -> next value
-                get_token();
-                if (last_token == token_type::value_separator)
-                {
-                    get_token();
-                    continue;
-                }
-
-                // closing ]
-                return (last_token == token_type::end_array);
-            }
-        }
-
-        case token_type::value_float:
-        {
-            // reject infinity or NAN
-            return std::isfinite(m_lexer.get_number_float());
-        }
-
-        case token_type::literal_false:
-        case token_type::literal_null:
-        case token_type::literal_true:
-        case token_type::value_integer:
-        case token_type::value_string:
-        case token_type::value_unsigned:
-            return true;
-
-        default: // the last token was unexpected
-            return false;
-    }
-}
-
-void json::parser::throw_exception() const
-{
-    std::string error_msg = "syntax error - ";
-    if (last_token == token_type::parse_error)
-    {
-        error_msg += std::string(m_lexer.get_error_message()) + "; last read: '" +
-                     m_lexer.get_token_string() + "'";
-    }
-    else
-    {
-        error_msg += "unexpected " + std::string(lexer_t::token_type_name(last_token));
-    }
-
-    if (expected != token_type::uninitialized)
-    {
-        error_msg += "; expected " + std::string(lexer_t::token_type_name(expected));
-    }
-
-    JSON_THROW(parse_error::create(101, m_lexer.get_position(), error_msg));
-}
-
-json json::parse(std::string_view s,
-                        const parser_callback_t cb,
-                        const bool allow_exceptions)
-{
-    raw_mem_istream is(span<const char>(s.data(), s.size()));
-    return parse(is, cb, allow_exceptions);
-}
-
-json json::parse(span<const uint8_t> arr,
-                        const parser_callback_t cb,
-                        const bool allow_exceptions)
-{
-    raw_mem_istream is(arr);
-    return parse(is, cb, allow_exceptions);
-}
-
-json json::parse(raw_istream& i,
-                        const parser_callback_t cb,
-                        const bool allow_exceptions)
-{
-    json result;
-    parser(i, cb, allow_exceptions).parse(true, result);
-    return result;
-}
-
-bool json::accept(std::string_view s)
-{
-    raw_mem_istream is(span<const char>(s.data(), s.size()));
-    return parser(is).accept(true);
-}
-
-bool json::accept(span<const uint8_t> arr)
-{
-    raw_mem_istream is(arr);
-    return parser(is).accept(true);
-}
-
-bool json::accept(raw_istream& i)
-{
-    return parser(i).accept(true);
-}
-
-raw_istream& operator>>(raw_istream& i, json& j)
-{
-    json::parser(i).parse(false, j);
-    return i;
-}
-
-}  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/leb128.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/leb128.cpp
index 9657883..17fbeb9 100644
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/leb128.cpp
+++ b/third_party/allwpilib/wpiutil/src/main/native/cpp/leb128.cpp
@@ -7,7 +7,6 @@
 #include "wpi/SpanExtras.h"
 #include "wpi/raw_istream.h"
 #include "wpi/raw_ostream.h"
-#include "wpi/span.h"
 
 namespace wpi {
 
@@ -98,7 +97,7 @@
   return true;
 }
 
-std::optional<uint64_t> Uleb128Reader::ReadOne(span<const uint8_t>* in) {
+std::optional<uint64_t> Uleb128Reader::ReadOne(std::span<const uint8_t>* in) {
   while (!in->empty()) {
     uint8_t byte = in->front();
     *in = wpi::drop_front(*in);
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/llvm/ConvertUTF.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/llvm/ConvertUTF.cpp
deleted file mode 100644
index 3050e63..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/llvm/ConvertUTF.cpp
+++ /dev/null
@@ -1,834 +0,0 @@
-/*===--- ConvertUTF.c - Universal Character Names conversions ---------------===
- *
- *                     The LLVM Compiler Infrastructure
- *
- * This file is distributed under the University of Illinois Open Source
- * License. See LICENSE.TXT for details.
- *
- *===------------------------------------------------------------------------=*/
-/*
- * Copyright 2001-2004 Unicode, Inc.
- *
- * Disclaimer
- *
- * This source code is provided as is by Unicode, Inc. No claims are
- * made as to fitness for any particular purpose. No warranties of any
- * kind are expressed or implied. The recipient agrees to determine
- * applicability of information provided. If this file has been
- * purchased on magnetic or optical media from Unicode, Inc., the
- * sole remedy for any claim will be exchange of defective media
- * within 90 days of receipt.
- *
- * Limitations on Rights to Redistribute This Code
- *
- * Unicode, Inc. hereby grants the right to freely use the information
- * supplied in this file in the creation of products supporting the
- * Unicode Standard, and to make copies of this file in any form
- * for internal or external distribution as long as this notice
- * remains attached.
- */
-
-/* ---------------------------------------------------------------------
-
-    Conversions between UTF32, UTF-16, and UTF-8. Source code file.
-    Author: Mark E. Davis, 1994.
-    Rev History: Rick McGowan, fixes & updates May 2001.
-    Sept 2001: fixed const & error conditions per
-        mods suggested by S. Parent & A. Lillich.
-    June 2002: Tim Dodd added detection and handling of incomplete
-        source sequences, enhanced error detection, added casts
-        to eliminate compiler warnings.
-    July 2003: slight mods to back out aggressive FFFE detection.
-    Jan 2004: updated switches in from-UTF8 conversions.
-    Oct 2004: updated to use UNI_MAX_LEGAL_UTF32 in UTF-32 conversions.
-
-    See the header file "ConvertUTF.h" for complete documentation.
-
------------------------------------------------------------------------- */
-
-#include "wpi/ConvertUTF.h"
-#ifdef CVTUTF_DEBUG
-#include <stdio.h>
-#endif
-#include <assert.h>
-
-#ifdef _WIN32
-#include "wpi/WindowsError.h"
-#include "Windows/WindowsSupport.h"
-#endif
-
-/*
- * This code extensively uses fall-through switches.
- * Keep the compiler from warning about that.
- */
-#if defined(__clang__) && defined(__has_warning)
-# if __has_warning("-Wimplicit-fallthrough")
-#  define ConvertUTF_DISABLE_WARNINGS \
-    _Pragma("clang diagnostic push")  \
-    _Pragma("clang diagnostic ignored \"-Wimplicit-fallthrough\"")
-#  define ConvertUTF_RESTORE_WARNINGS \
-    _Pragma("clang diagnostic pop")
-# endif
-#elif defined(__GNUC__) && __GNUC__ > 6
-# define ConvertUTF_DISABLE_WARNINGS \
-   _Pragma("GCC diagnostic push")    \
-   _Pragma("GCC diagnostic ignored \"-Wimplicit-fallthrough\"")
-# define ConvertUTF_RESTORE_WARNINGS \
-   _Pragma("GCC diagnostic pop")
-#endif
-#ifndef ConvertUTF_DISABLE_WARNINGS
-# define ConvertUTF_DISABLE_WARNINGS
-#endif
-#ifndef ConvertUTF_RESTORE_WARNINGS
-# define ConvertUTF_RESTORE_WARNINGS
-#endif
-
-ConvertUTF_DISABLE_WARNINGS
-
-namespace wpi {
-
-static const int halfShift  = 10; /* used for shifting by 10 bits */
-
-static const UTF32 halfBase = 0x0010000UL;
-static const UTF32 halfMask = 0x3FFUL;
-
-#define UNI_SUR_HIGH_START  (UTF32)0xD800
-#define UNI_SUR_HIGH_END    (UTF32)0xDBFF
-#define UNI_SUR_LOW_START   (UTF32)0xDC00
-#define UNI_SUR_LOW_END     (UTF32)0xDFFF
-
-/* --------------------------------------------------------------------- */
-
-/*
- * Index into the table below with the first byte of a UTF-8 sequence to
- * get the number of trailing bytes that are supposed to follow it.
- * Note that *legal* UTF-8 values can't have 4 or 5-bytes. The table is
- * left as-is for anyone who may want to do such conversion, which was
- * allowed in earlier algorithms.
- */
-static const char trailingBytesForUTF8[256] = {
-    0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,
-    0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,
-    0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,
-    0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,
-    0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,
-    0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,
-    1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,
-    2,2,2,2,2,2,2,2,2,2,2,2,2,2,2,2, 3,3,3,3,3,3,3,3,4,4,4,4,5,5,5,5
-};
-
-/*
- * Magic values subtracted from a buffer value during UTF8 conversion.
- * This table contains as many values as there might be trailing bytes
- * in a UTF-8 sequence.
- */
-static const UTF32 offsetsFromUTF8[6] = { 0x00000000UL, 0x00003080UL, 0x000E2080UL,
-                     0x03C82080UL, 0xFA082080UL, 0x82082080UL };
-
-/*
- * Once the bits are split out into bytes of UTF-8, this is a mask OR-ed
- * into the first byte, depending on how many bytes follow.  There are
- * as many entries in this table as there are UTF-8 sequence types.
- * (I.e., one byte sequence, two byte... etc.). Remember that sequencs
- * for *legal* UTF-8 will be 4 or fewer bytes total.
- */
-static const UTF8 firstByteMark[7] = { 0x00, 0x00, 0xC0, 0xE0, 0xF0, 0xF8, 0xFC };
-
-/* --------------------------------------------------------------------- */
-
-/* The interface converts a whole buffer to avoid function-call overhead.
- * Constants have been gathered. Loops & conditionals have been removed as
- * much as possible for efficiency, in favor of drop-through switches.
- * (See "Note A" at the bottom of the file for equivalent code.)
- * If your compiler supports it, the "isLegalUTF8" call can be turned
- * into an inline function.
- */
-
-
-/* --------------------------------------------------------------------- */
-
-ConversionResult ConvertUTF32toUTF16 (
-        const UTF32** sourceStart, const UTF32* sourceEnd,
-        UTF16** targetStart, UTF16* targetEnd, ConversionFlags flags) {
-    ConversionResult result = conversionOK;
-    const UTF32* source = *sourceStart;
-    UTF16* target = *targetStart;
-    while (source < sourceEnd) {
-        UTF32 ch;
-        if (target >= targetEnd) {
-            result = targetExhausted; break;
-        }
-        ch = *source++;
-        if (ch <= UNI_MAX_BMP) { /* Target is a character <= 0xFFFF */
-            /* UTF-16 surrogate values are illegal in UTF-32; 0xffff or 0xfffe are both reserved values */
-            if (ch >= UNI_SUR_HIGH_START && ch <= UNI_SUR_LOW_END) {
-                if (flags == strictConversion) {
-                    --source; /* return to the illegal value itself */
-                    result = sourceIllegal;
-                    break;
-                } else {
-                    *target++ = UNI_REPLACEMENT_CHAR;
-                }
-            } else {
-                *target++ = (UTF16)ch; /* normal case */
-            }
-        } else if (ch > UNI_MAX_LEGAL_UTF32) {
-            if (flags == strictConversion) {
-                result = sourceIllegal;
-            } else {
-                *target++ = UNI_REPLACEMENT_CHAR;
-            }
-        } else {
-            /* target is a character in range 0xFFFF - 0x10FFFF. */
-            if (target + 1 >= targetEnd) {
-                --source; /* Back up source pointer! */
-                result = targetExhausted; break;
-            }
-            ch -= halfBase;
-            *target++ = (UTF16)((ch >> halfShift) + UNI_SUR_HIGH_START);
-            *target++ = (UTF16)((ch & halfMask) + UNI_SUR_LOW_START);
-        }
-    }
-    *sourceStart = source;
-    *targetStart = target;
-    return result;
-}
-
-/* --------------------------------------------------------------------- */
-
-ConversionResult ConvertUTF16toUTF32 (
-        const UTF16** sourceStart, const UTF16* sourceEnd,
-        UTF32** targetStart, UTF32* targetEnd, ConversionFlags flags) {
-    ConversionResult result = conversionOK;
-    const UTF16* source = *sourceStart;
-    UTF32* target = *targetStart;
-    UTF32 ch, ch2;
-    while (source < sourceEnd) {
-        const UTF16* oldSource = source; /*  In case we have to back up because of target overflow. */
-        ch = *source++;
-        /* If we have a surrogate pair, convert to UTF32 first. */
-        if (ch >= UNI_SUR_HIGH_START && ch <= UNI_SUR_HIGH_END) {
-            /* If the 16 bits following the high surrogate are in the source buffer... */
-            if (source < sourceEnd) {
-                ch2 = *source;
-                /* If it's a low surrogate, convert to UTF32. */
-                if (ch2 >= UNI_SUR_LOW_START && ch2 <= UNI_SUR_LOW_END) {
-                    ch = ((ch - UNI_SUR_HIGH_START) << halfShift)
-                        + (ch2 - UNI_SUR_LOW_START) + halfBase;
-                    ++source;
-                } else if (flags == strictConversion) { /* it's an unpaired high surrogate */
-                    --source; /* return to the illegal value itself */
-                    result = sourceIllegal;
-                    break;
-                }
-            } else { /* We don't have the 16 bits following the high surrogate. */
-                --source; /* return to the high surrogate */
-                result = sourceExhausted;
-                break;
-            }
-        } else if (flags == strictConversion) {
-            /* UTF-16 surrogate values are illegal in UTF-32 */
-            if (ch >= UNI_SUR_LOW_START && ch <= UNI_SUR_LOW_END) {
-                --source; /* return to the illegal value itself */
-                result = sourceIllegal;
-                break;
-            }
-        }
-        if (target >= targetEnd) {
-            source = oldSource; /* Back up source pointer! */
-            result = targetExhausted; break;
-        }
-        *target++ = ch;
-    }
-    *sourceStart = source;
-    *targetStart = target;
-#ifdef CVTUTF_DEBUG
-if (result == sourceIllegal) {
-    fprintf(stderr, "ConvertUTF16toUTF32 illegal seq 0x%04x,%04x\n", ch, ch2);
-    fflush(stderr);
-}
-#endif
-    return result;
-}
-ConversionResult ConvertUTF16toUTF8 (
-        const UTF16** sourceStart, const UTF16* sourceEnd,
-        UTF8** targetStart, UTF8* targetEnd, ConversionFlags flags) {
-    ConversionResult result = conversionOK;
-    const UTF16* source = *sourceStart;
-    UTF8* target = *targetStart;
-    while (source < sourceEnd) {
-        UTF32 ch;
-        unsigned short bytesToWrite = 0;
-        const UTF32 byteMask = 0xBF;
-        const UTF32 byteMark = 0x80;
-        const UTF16* oldSource = source; /* In case we have to back up because of target overflow. */
-        ch = *source++;
-        /* If we have a surrogate pair, convert to UTF32 first. */
-        if (ch >= UNI_SUR_HIGH_START && ch <= UNI_SUR_HIGH_END) {
-            /* If the 16 bits following the high surrogate are in the source buffer... */
-            if (source < sourceEnd) {
-                UTF32 ch2 = *source;
-                /* If it's a low surrogate, convert to UTF32. */
-                if (ch2 >= UNI_SUR_LOW_START && ch2 <= UNI_SUR_LOW_END) {
-                    ch = ((ch - UNI_SUR_HIGH_START) << halfShift)
-                        + (ch2 - UNI_SUR_LOW_START) + halfBase;
-                    ++source;
-                } else if (flags == strictConversion) { /* it's an unpaired high surrogate */
-                    --source; /* return to the illegal value itself */
-                    result = sourceIllegal;
-                    break;
-                }
-            } else { /* We don't have the 16 bits following the high surrogate. */
-                --source; /* return to the high surrogate */
-                result = sourceExhausted;
-                break;
-            }
-        } else if (flags == strictConversion) {
-            /* UTF-16 surrogate values are illegal in UTF-32 */
-            if (ch >= UNI_SUR_LOW_START && ch <= UNI_SUR_LOW_END) {
-                --source; /* return to the illegal value itself */
-                result = sourceIllegal;
-                break;
-            }
-        }
-        /* Figure out how many bytes the result will require */
-        if (ch < (UTF32)0x80) {      bytesToWrite = 1;
-        } else if (ch < (UTF32)0x800) {     bytesToWrite = 2;
-        } else if (ch < (UTF32)0x10000) {   bytesToWrite = 3;
-        } else if (ch < (UTF32)0x110000) {  bytesToWrite = 4;
-        } else {                            bytesToWrite = 3;
-                                            ch = UNI_REPLACEMENT_CHAR;
-        }
-
-        target += bytesToWrite;
-        if (target > targetEnd) {
-            source = oldSource; /* Back up source pointer! */
-            target -= bytesToWrite; result = targetExhausted; break;
-        }
-        switch (bytesToWrite) { /* note: everything falls through. */
-            case 4: *--target = (UTF8)((ch | byteMark) & byteMask); ch >>= 6;
-            case 3: *--target = (UTF8)((ch | byteMark) & byteMask); ch >>= 6;
-            case 2: *--target = (UTF8)((ch | byteMark) & byteMask); ch >>= 6;
-            case 1: *--target =  (UTF8)(ch | firstByteMark[bytesToWrite]);
-        }
-        target += bytesToWrite;
-    }
-    *sourceStart = source;
-    *targetStart = target;
-    return result;
-}
-
-/* --------------------------------------------------------------------- */
-
-ConversionResult ConvertUTF32toUTF8 (
-        const UTF32** sourceStart, const UTF32* sourceEnd,
-        UTF8** targetStart, UTF8* targetEnd, ConversionFlags flags) {
-    ConversionResult result = conversionOK;
-    const UTF32* source = *sourceStart;
-    UTF8* target = *targetStart;
-    while (source < sourceEnd) {
-        UTF32 ch;
-        unsigned short bytesToWrite = 0;
-        const UTF32 byteMask = 0xBF;
-        const UTF32 byteMark = 0x80;
-        ch = *source++;
-        if (flags == strictConversion ) {
-            /* UTF-16 surrogate values are illegal in UTF-32 */
-            if (ch >= UNI_SUR_HIGH_START && ch <= UNI_SUR_LOW_END) {
-                --source; /* return to the illegal value itself */
-                result = sourceIllegal;
-                break;
-            }
-        }
-        /*
-         * Figure out how many bytes the result will require. Turn any
-         * illegally large UTF32 things (> Plane 17) into replacement chars.
-         */
-        if (ch < (UTF32)0x80) {      bytesToWrite = 1;
-        } else if (ch < (UTF32)0x800) {     bytesToWrite = 2;
-        } else if (ch < (UTF32)0x10000) {   bytesToWrite = 3;
-        } else if (ch <= UNI_MAX_LEGAL_UTF32) {  bytesToWrite = 4;
-        } else {                            bytesToWrite = 3;
-                                            ch = UNI_REPLACEMENT_CHAR;
-                                            result = sourceIllegal;
-        }
-
-        target += bytesToWrite;
-        if (target > targetEnd) {
-            --source; /* Back up source pointer! */
-            target -= bytesToWrite; result = targetExhausted; break;
-        }
-        switch (bytesToWrite) { /* note: everything falls through. */
-            case 4: *--target = (UTF8)((ch | byteMark) & byteMask); ch >>= 6;
-            case 3: *--target = (UTF8)((ch | byteMark) & byteMask); ch >>= 6;
-            case 2: *--target = (UTF8)((ch | byteMark) & byteMask); ch >>= 6;
-            case 1: *--target = (UTF8) (ch | firstByteMark[bytesToWrite]);
-        }
-        target += bytesToWrite;
-    }
-    *sourceStart = source;
-    *targetStart = target;
-    return result;
-}
-
-/* --------------------------------------------------------------------- */
-
-/*
- * Utility routine to tell whether a sequence of bytes is legal UTF-8.
- * This must be called with the length pre-determined by the first byte.
- * If not calling this from ConvertUTF8to*, then the length can be set by:
- *  length = trailingBytesForUTF8[*source]+1;
- * and the sequence is illegal right away if there aren't that many bytes
- * available.
- * If presented with a length > 4, this returns false.  The Unicode
- * definition of UTF-8 goes up to 4-byte sequences.
- */
-
-static Boolean isLegalUTF8(const UTF8 *source, int length) {
-    UTF8 a;
-    const UTF8 *srcptr = source+length;
-    switch (length) {
-    default: return false;
-        /* Everything else falls through when "true"... */
-    case 4: if ((a = (*--srcptr)) < 0x80 || a > 0xBF) return false;
-    case 3: if ((a = (*--srcptr)) < 0x80 || a > 0xBF) return false;
-    case 2: if ((a = (*--srcptr)) < 0x80 || a > 0xBF) return false;
-
-        switch (*source) {
-            /* no fall-through in this inner switch */
-            case 0xE0: if (a < 0xA0) return false; break;
-            case 0xED: if (a > 0x9F) return false; break;
-            case 0xF0: if (a < 0x90) return false; break;
-            case 0xF4: if (a > 0x8F) return false; break;
-            default:   if (a < 0x80) return false;
-        }
-
-    case 1: if (*source >= 0x80 && *source < 0xC2) return false;
-    }
-    if (*source > 0xF4) return false;
-    return true;
-}
-
-/* --------------------------------------------------------------------- */
-
-/*
- * Exported function to return whether a UTF-8 sequence is legal or not.
- * This is not used here; it's just exported.
- */
-Boolean isLegalUTF8Sequence(const UTF8 *source, const UTF8 *sourceEnd) {
-    int length = trailingBytesForUTF8[*source]+1;
-    if (length > sourceEnd - source) {
-        return false;
-    }
-    return isLegalUTF8(source, length);
-}
-
-/* --------------------------------------------------------------------- */
-
-static unsigned
-findMaximalSubpartOfIllFormedUTF8Sequence(const UTF8 *source,
-                                          const UTF8 *sourceEnd) {
-  UTF8 b1, b2, b3;
-
-  assert(!isLegalUTF8Sequence(source, sourceEnd));
-
-  /*
-   * Unicode 6.3.0, D93b:
-   *
-   *   Maximal subpart of an ill-formed subsequence: The longest code unit
-   *   subsequence starting at an unconvertible offset that is either:
-   *   a. the initial subsequence of a well-formed code unit sequence, or
-   *   b. a subsequence of length one.
-   */
-
-  if (source == sourceEnd)
-    return 0;
-
-  /*
-   * Perform case analysis.  See Unicode 6.3.0, Table 3-7. Well-Formed UTF-8
-   * Byte Sequences.
-   */
-
-  b1 = *source;
-  ++source;
-  if (b1 >= 0xC2 && b1 <= 0xDF) {
-    /*
-     * First byte is valid, but we know that this code unit sequence is
-     * invalid, so the maximal subpart has to end after the first byte.
-     */
-    return 1;
-  }
-
-  if (source == sourceEnd)
-    return 1;
-
-  b2 = *source;
-  ++source;
-
-  if (b1 == 0xE0) {
-    return (b2 >= 0xA0 && b2 <= 0xBF) ? 2 : 1;
-  }
-  if (b1 >= 0xE1 && b1 <= 0xEC) {
-    return (b2 >= 0x80 && b2 <= 0xBF) ? 2 : 1;
-  }
-  if (b1 == 0xED) {
-    return (b2 >= 0x80 && b2 <= 0x9F) ? 2 : 1;
-  }
-  if (b1 >= 0xEE && b1 <= 0xEF) {
-    return (b2 >= 0x80 && b2 <= 0xBF) ? 2 : 1;
-  }
-  if (b1 == 0xF0) {
-    if (b2 >= 0x90 && b2 <= 0xBF) {
-      if (source == sourceEnd)
-        return 2;
-
-      b3 = *source;
-      return (b3 >= 0x80 && b3 <= 0xBF) ? 3 : 2;
-    }
-    return 1;
-  }
-  if (b1 >= 0xF1 && b1 <= 0xF3) {
-    if (b2 >= 0x80 && b2 <= 0xBF) {
-      if (source == sourceEnd)
-        return 2;
-
-      b3 = *source;
-      return (b3 >= 0x80 && b3 <= 0xBF) ? 3 : 2;
-    }
-    return 1;
-  }
-  if (b1 == 0xF4) {
-    if (b2 >= 0x80 && b2 <= 0x8F) {
-      if (source == sourceEnd)
-        return 2;
-
-      b3 = *source;
-      return (b3 >= 0x80 && b3 <= 0xBF) ? 3 : 2;
-    }
-    return 1;
-  }
-
-  assert((b1 >= 0x80 && b1 <= 0xC1) || b1 >= 0xF5);
-  /*
-   * There are no valid sequences that start with these bytes.  Maximal subpart
-   * is defined to have length 1 in these cases.
-   */
-  return 1;
-}
-
-/* --------------------------------------------------------------------- */
-
-/*
- * Exported function to return the total number of bytes in a codepoint
- * represented in UTF-8, given the value of the first byte.
- */
-unsigned getNumBytesForUTF8(UTF8 first) {
-  return trailingBytesForUTF8[first] + 1;
-}
-
-/* --------------------------------------------------------------------- */
-
-/*
- * Exported function to return whether a UTF-8 string is legal or not.
- * This is not used here; it's just exported.
- */
-Boolean isLegalUTF8String(const UTF8 **source, const UTF8 *sourceEnd) {
-    while (*source != sourceEnd) {
-        int length = trailingBytesForUTF8[**source] + 1;
-        if (length > sourceEnd - *source || !isLegalUTF8(*source, length))
-            return false;
-        *source += length;
-    }
-    return true;
-}
-
-/* --------------------------------------------------------------------- */
-
-ConversionResult ConvertUTF8toUTF16 (
-        const UTF8** sourceStart, const UTF8* sourceEnd,
-        UTF16** targetStart, UTF16* targetEnd, ConversionFlags flags) {
-    ConversionResult result = conversionOK;
-    const UTF8* source = *sourceStart;
-    UTF16* target = *targetStart;
-    while (source < sourceEnd) {
-        UTF32 ch = 0;
-        unsigned short extraBytesToRead = trailingBytesForUTF8[*source];
-        if (extraBytesToRead >= sourceEnd - source) {
-            result = sourceExhausted; break;
-        }
-        /* Do this check whether lenient or strict */
-        if (!isLegalUTF8(source, extraBytesToRead+1)) {
-            result = sourceIllegal;
-            break;
-        }
-        /*
-         * The cases all fall through. See "Note A" below.
-         */
-        switch (extraBytesToRead) {
-            case 5: ch += *source++; ch <<= 6; /* remember, illegal UTF-8 */
-            case 4: ch += *source++; ch <<= 6; /* remember, illegal UTF-8 */
-            case 3: ch += *source++; ch <<= 6;
-            case 2: ch += *source++; ch <<= 6;
-            case 1: ch += *source++; ch <<= 6;
-            case 0: ch += *source++;
-        }
-        ch -= offsetsFromUTF8[extraBytesToRead];
-
-        if (target >= targetEnd) {
-            source -= (extraBytesToRead+1); /* Back up source pointer! */
-            result = targetExhausted; break;
-        }
-        if (ch <= UNI_MAX_BMP) { /* Target is a character <= 0xFFFF */
-            /* UTF-16 surrogate values are illegal in UTF-32 */
-            if (ch >= UNI_SUR_HIGH_START && ch <= UNI_SUR_LOW_END) {
-                if (flags == strictConversion) {
-                    source -= (extraBytesToRead+1); /* return to the illegal value itself */
-                    result = sourceIllegal;
-                    break;
-                } else {
-                    *target++ = UNI_REPLACEMENT_CHAR;
-                }
-            } else {
-                *target++ = (UTF16)ch; /* normal case */
-            }
-        } else if (ch > UNI_MAX_UTF16) {
-            if (flags == strictConversion) {
-                result = sourceIllegal;
-                source -= (extraBytesToRead+1); /* return to the start */
-                break; /* Bail out; shouldn't continue */
-            } else {
-                *target++ = UNI_REPLACEMENT_CHAR;
-            }
-        } else {
-            /* target is a character in range 0xFFFF - 0x10FFFF. */
-            if (target + 1 >= targetEnd) {
-                source -= (extraBytesToRead+1); /* Back up source pointer! */
-                result = targetExhausted; break;
-            }
-            ch -= halfBase;
-            *target++ = (UTF16)((ch >> halfShift) + UNI_SUR_HIGH_START);
-            *target++ = (UTF16)((ch & halfMask) + UNI_SUR_LOW_START);
-        }
-    }
-    *sourceStart = source;
-    *targetStart = target;
-    return result;
-}
-
-/* --------------------------------------------------------------------- */
-
-static ConversionResult ConvertUTF8toUTF32Impl(
-        const UTF8** sourceStart, const UTF8* sourceEnd,
-        UTF32** targetStart, UTF32* targetEnd, ConversionFlags flags,
-        Boolean InputIsPartial) {
-    ConversionResult result = conversionOK;
-    const UTF8* source = *sourceStart;
-    UTF32* target = *targetStart;
-    while (source < sourceEnd) {
-        UTF32 ch = 0;
-        unsigned short extraBytesToRead = trailingBytesForUTF8[*source];
-        if (extraBytesToRead >= sourceEnd - source) {
-            if (flags == strictConversion || InputIsPartial) {
-                result = sourceExhausted;
-                break;
-            } else {
-                result = sourceIllegal;
-
-                /*
-                 * Replace the maximal subpart of ill-formed sequence with
-                 * replacement character.
-                 */
-                source += findMaximalSubpartOfIllFormedUTF8Sequence(source,
-                                                                    sourceEnd);
-                *target++ = UNI_REPLACEMENT_CHAR;
-                continue;
-            }
-        }
-        if (target >= targetEnd) {
-            result = targetExhausted; break;
-        }
-
-        /* Do this check whether lenient or strict */
-        if (!isLegalUTF8(source, extraBytesToRead+1)) {
-            result = sourceIllegal;
-            if (flags == strictConversion) {
-                /* Abort conversion. */
-                break;
-            } else {
-                /*
-                 * Replace the maximal subpart of ill-formed sequence with
-                 * replacement character.
-                 */
-                source += findMaximalSubpartOfIllFormedUTF8Sequence(source,
-                                                                    sourceEnd);
-                *target++ = UNI_REPLACEMENT_CHAR;
-                continue;
-            }
-        }
-        /*
-         * The cases all fall through. See "Note A" below.
-         */
-        switch (extraBytesToRead) {
-            case 5: ch += *source++; ch <<= 6;
-            case 4: ch += *source++; ch <<= 6;
-            case 3: ch += *source++; ch <<= 6;
-            case 2: ch += *source++; ch <<= 6;
-            case 1: ch += *source++; ch <<= 6;
-            case 0: ch += *source++;
-        }
-        ch -= offsetsFromUTF8[extraBytesToRead];
-
-        if (ch <= UNI_MAX_LEGAL_UTF32) {
-            /*
-             * UTF-16 surrogate values are illegal in UTF-32, and anything
-             * over Plane 17 (> 0x10FFFF) is illegal.
-             */
-            if (ch >= UNI_SUR_HIGH_START && ch <= UNI_SUR_LOW_END) {
-                if (flags == strictConversion) {
-                    source -= (extraBytesToRead+1); /* return to the illegal value itself */
-                    result = sourceIllegal;
-                    break;
-                } else {
-                    *target++ = UNI_REPLACEMENT_CHAR;
-                }
-            } else {
-                *target++ = ch;
-            }
-        } else { /* i.e., ch > UNI_MAX_LEGAL_UTF32 */
-            result = sourceIllegal;
-            *target++ = UNI_REPLACEMENT_CHAR;
-        }
-    }
-    *sourceStart = source;
-    *targetStart = target;
-    return result;
-}
-
-ConversionResult ConvertUTF8toUTF32Partial(const UTF8 **sourceStart,
-                                           const UTF8 *sourceEnd,
-                                           UTF32 **targetStart,
-                                           UTF32 *targetEnd,
-                                           ConversionFlags flags) {
-  return ConvertUTF8toUTF32Impl(sourceStart, sourceEnd, targetStart, targetEnd,
-                                flags, /*InputIsPartial=*/true);
-}
-
-ConversionResult ConvertUTF8toUTF32(const UTF8 **sourceStart,
-                                    const UTF8 *sourceEnd, UTF32 **targetStart,
-                                    UTF32 *targetEnd, ConversionFlags flags) {
-  return ConvertUTF8toUTF32Impl(sourceStart, sourceEnd, targetStart, targetEnd,
-                                flags, /*InputIsPartial=*/false);
-}
-
-/* ---------------------------------------------------------------------
-
-    Note A.
-    The fall-through switches in UTF-8 reading code save a
-    temp variable, some decrements & conditionals.  The switches
-    are equivalent to the following loop:
-        {
-            int tmpBytesToRead = extraBytesToRead+1;
-            do {
-                ch += *source++;
-                --tmpBytesToRead;
-                if (tmpBytesToRead) ch <<= 6;
-            } while (tmpBytesToRead > 0);
-        }
-    In UTF-8 writing code, the switches on "bytesToWrite" are
-    similarly unrolled loops.
-
-   --------------------------------------------------------------------- */
-
-#ifdef _WIN32
-
-namespace sys {
-namespace windows {
-std::error_code CodePageToUTF16(unsigned codepage,
-                                std::string_view original,
-                                wpi::SmallVectorImpl<wchar_t> &utf16) {
-  if (!original.empty()) {
-    int len = ::MultiByteToWideChar(codepage, MB_ERR_INVALID_CHARS, original.data(),
-                                    original.size(), utf16.begin(), 0);
-
-    if (len == 0) {
-      return mapWindowsError(::GetLastError());
-    }
-
-    utf16.reserve(len + 1);
-    utf16.set_size(len);
-
-    len = ::MultiByteToWideChar(codepage, MB_ERR_INVALID_CHARS, original.data(),
-                                original.size(), utf16.begin(), utf16.size());
-
-    if (len == 0) {
-      return mapWindowsError(::GetLastError());
-    }
-  }
-
-  // Make utf16 null terminated.
-  utf16.push_back(0);
-  utf16.pop_back();
-
-  return std::error_code();
-}
-
-std::error_code UTF8ToUTF16(std::string_view utf8,
-                            wpi::SmallVectorImpl<wchar_t> &utf16) {
-  return CodePageToUTF16(CP_UTF8, utf8, utf16);
-}
-
-std::error_code CurCPToUTF16(std::string_view curcp,
-                            wpi::SmallVectorImpl<wchar_t> &utf16) {
-  return CodePageToUTF16(CP_ACP, curcp, utf16);
-}
-
-static
-std::error_code UTF16ToCodePage(unsigned codepage, const wchar_t *utf16,
-                                size_t utf16_len,
-                                wpi::SmallVectorImpl<char> &converted) {
-  if (utf16_len) {
-    // Get length.
-    int len = ::WideCharToMultiByte(codepage, 0, utf16, utf16_len, converted.begin(),
-                                    0, NULL, NULL);
-
-    if (len == 0) {
-      return mapWindowsError(::GetLastError());
-    }
-
-    converted.reserve(len);
-    converted.set_size(len);
-
-    // Now do the actual conversion.
-    len = ::WideCharToMultiByte(codepage, 0, utf16, utf16_len, converted.data(),
-                                converted.size(), NULL, NULL);
-
-    if (len == 0) {
-      return mapWindowsError(::GetLastError());
-    }
-  }
-
-  // Make the new string null terminated.
-  converted.push_back(0);
-  converted.pop_back();
-
-  return std::error_code();
-}
-
-std::error_code UTF16ToUTF8(const wchar_t *utf16, size_t utf16_len,
-                            wpi::SmallVectorImpl<char> &utf8) {
-  return UTF16ToCodePage(CP_UTF8, utf16, utf16_len, utf8);
-}
-
-std::error_code UTF16ToCurCP(const wchar_t *utf16, size_t utf16_len,
-                             wpi::SmallVectorImpl<char> &curcp) {
-  return UTF16ToCodePage(CP_ACP, utf16, utf16_len, curcp);
-}
-
-} // end namespace windows
-} // end namespace sys
-
-#endif  // _WIN32
-
-} // namespace llvm
-
-ConvertUTF_RESTORE_WARNINGS
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/llvm/ConvertUTFWrapper.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/llvm/ConvertUTFWrapper.cpp
deleted file mode 100644
index db190d0..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/llvm/ConvertUTFWrapper.cpp
+++ /dev/null
@@ -1,123 +0,0 @@
-//===-- ConvertUTFWrapper.cpp - Wrap ConvertUTF.h with clang data types -----===
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-
-#include "wpi/ConvertUTF.h"
-#include "wpi/SmallVector.h"
-#include <string>
-#include <vector>
-
-namespace wpi {
-
-bool ConvertCodePointToUTF8(unsigned Source, char *&ResultPtr) {
-  const UTF32 *SourceStart = &Source;
-  const UTF32 *SourceEnd = SourceStart + 1;
-  UTF8 *TargetStart = reinterpret_cast<UTF8 *>(ResultPtr);
-  UTF8 *TargetEnd = TargetStart + 4;
-  ConversionResult CR = ConvertUTF32toUTF8(&SourceStart, SourceEnd,
-                                           &TargetStart, TargetEnd,
-                                           strictConversion);
-  if (CR != conversionOK)
-    return false;
-
-  ResultPtr = reinterpret_cast<char*>(TargetStart);
-  return true;
-}
-
-bool hasUTF16ByteOrderMark(span<const char> S) {
-  return (S.size() >= 2 &&
-          ((S[0] == '\xff' && S[1] == '\xfe') ||
-           (S[0] == '\xfe' && S[1] == '\xff')));
-}
-
-bool convertUTF16ToUTF8String(span<const UTF16> SrcUTF16,
-                              SmallVectorImpl<char> &DstUTF8) {
-  assert(DstUTF8.empty());
-
-  // Avoid OOB by returning early on empty input.
-  if (SrcUTF16.empty())
-    return true;
-
-  const UTF16 *Src = SrcUTF16.begin();
-  const UTF16 *SrcEnd = SrcUTF16.end();
-
-  // Byteswap if necessary.
-  std::vector<UTF16> ByteSwapped;
-  if (Src[0] == UNI_UTF16_BYTE_ORDER_MARK_SWAPPED) {
-    ByteSwapped.insert(ByteSwapped.end(), Src, SrcEnd);
-    for (unsigned I = 0, E = ByteSwapped.size(); I != E; ++I)
-      ByteSwapped[I] = (ByteSwapped[I] << 8) | (ByteSwapped[I] >> 8);
-    Src = &ByteSwapped[0];
-    SrcEnd = &ByteSwapped[ByteSwapped.size() - 1] + 1;
-  }
-
-  // Skip the BOM for conversion.
-  if (Src[0] == UNI_UTF16_BYTE_ORDER_MARK_NATIVE)
-    Src++;
-
-  // Just allocate enough space up front.  We'll shrink it later.  Allocate
-  // enough that we can fit a null terminator without reallocating.
-  DstUTF8.resize(SrcUTF16.size() * UNI_MAX_UTF8_BYTES_PER_CODE_POINT + 1);
-  UTF8 *Dst = reinterpret_cast<UTF8*>(&DstUTF8[0]);
-  UTF8 *DstEnd = Dst + DstUTF8.size();
-
-  ConversionResult CR =
-      ConvertUTF16toUTF8(&Src, SrcEnd, &Dst, DstEnd, strictConversion);
-  assert(CR != targetExhausted);
-
-  if (CR != conversionOK) {
-    DstUTF8.clear();
-    return false;
-  }
-
-  DstUTF8.resize(reinterpret_cast<char*>(Dst) - &DstUTF8[0]);
-  DstUTF8.push_back(0);
-  DstUTF8.pop_back();
-  return true;
-}
-
-bool convertUTF8ToUTF16String(std::string_view SrcUTF8,
-                              SmallVectorImpl<UTF16> &DstUTF16) {
-  assert(DstUTF16.empty());
-
-  // Avoid OOB by returning early on empty input.
-  if (SrcUTF8.empty()) {
-    DstUTF16.push_back(0);
-    DstUTF16.pop_back();
-    return true;
-  }
-
-  const UTF8 *Src = reinterpret_cast<const UTF8 *>(SrcUTF8.data());
-  const UTF8 *SrcEnd = reinterpret_cast<const UTF8 *>(SrcUTF8.data() + SrcUTF8.size());
-
-  // Allocate the same number of UTF-16 code units as UTF-8 code units. Encoding
-  // as UTF-16 should always require the same amount or less code units than the
-  // UTF-8 encoding.  Allocate one extra byte for the null terminator though,
-  // so that someone calling DstUTF16.data() gets a null terminated string.
-  // We resize down later so we don't have to worry that this over allocates.
-  DstUTF16.resize(SrcUTF8.size()+1);
-  UTF16 *Dst = &DstUTF16[0];
-  UTF16 *DstEnd = Dst + DstUTF16.size();
-
-  ConversionResult CR =
-      ConvertUTF8toUTF16(&Src, SrcEnd, &Dst, DstEnd, strictConversion);
-  assert(CR != targetExhausted);
-
-  if (CR != conversionOK) {
-    DstUTF16.clear();
-    return false;
-  }
-
-  DstUTF16.resize(Dst - &DstUTF16[0]);
-  DstUTF16.push_back(0);
-  DstUTF16.pop_back();
-  return true;
-}
-
-} // end namespace wpi
-
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/llvm/ErrorHandling.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/llvm/ErrorHandling.cpp
deleted file mode 100644
index 22ae636..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/llvm/ErrorHandling.cpp
+++ /dev/null
@@ -1,250 +0,0 @@
-//===- lib/Support/ErrorHandling.cpp - Callbacks for errors ---------------===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-//
-// This file defines an API used to indicate fatal error conditions.  Non-fatal
-// errors (most of them) should be handled through LLVMContext.
-//
-//===----------------------------------------------------------------------===//
-
-#include "wpi/ErrorHandling.h"
-#include "wpi/SmallVector.h"
-#include "wpi/WindowsError.h"
-#include "fmt/format.h"
-#include <cassert>
-#include <cstdio>
-#include <cstdlib>
-#include <mutex>
-#include <new>
-
-#ifndef _WIN32
-#include <unistd.h>
-#endif
-
-#if defined(_MSC_VER)
-#include <io.h>
-#endif
-
-using namespace wpi;
-
-static fatal_error_handler_t ErrorHandler = nullptr;
-static void *ErrorHandlerUserData = nullptr;
-
-static fatal_error_handler_t BadAllocErrorHandler = nullptr;
-static void *BadAllocErrorHandlerUserData = nullptr;
-
-// Mutexes to synchronize installing error handlers and calling error handlers.
-// Do not use ManagedStatic, or that may allocate memory while attempting to
-// report an OOM.
-//
-// This usage of std::mutex has to be conditionalized behind ifdefs because
-// of this script:
-//   compiler-rt/lib/sanitizer_common/symbolizer/scripts/build_symbolizer.sh
-// That script attempts to statically link the LLVM symbolizer library with the
-// STL and hide all of its symbols with 'opt -internalize'. To reduce size, it
-// cuts out the threading portions of the hermetic copy of libc++ that it
-// builds. We can remove these ifdefs if that script goes away.
-static std::mutex ErrorHandlerMutex;
-static std::mutex BadAllocErrorHandlerMutex;
-
-void wpi::install_fatal_error_handler(fatal_error_handler_t handler,
-                                      void *user_data) {
-  std::scoped_lock Lock(ErrorHandlerMutex);
-  assert(!ErrorHandler && "Error handler already registered!\n");
-  ErrorHandler = handler;
-  ErrorHandlerUserData = user_data;
-}
-
-void wpi::remove_fatal_error_handler() {
-  std::scoped_lock Lock(ErrorHandlerMutex);
-  ErrorHandler = nullptr;
-  ErrorHandlerUserData = nullptr;
-}
-
-void wpi::report_fatal_error(const char *Reason, bool GenCrashDiag) {
-  report_fatal_error(std::string_view(Reason), GenCrashDiag);
-}
-
-void wpi::report_fatal_error(const std::string &Reason, bool GenCrashDiag) {
-  report_fatal_error(std::string_view(Reason), GenCrashDiag);
-}
-
-void wpi::report_fatal_error(std::string_view Reason, bool GenCrashDiag) {
-  wpi::fatal_error_handler_t handler = nullptr;
-  void* handlerData = nullptr;
-  {
-    // Only acquire the mutex while reading the handler, so as not to invoke a
-    // user-supplied callback under a lock.
-    std::scoped_lock Lock(ErrorHandlerMutex);
-    handler = ErrorHandler;
-    handlerData = ErrorHandlerUserData;
-  }
-
-  if (handler) {
-    handler(handlerData, std::string{Reason}, GenCrashDiag);
-  } else {
-    fmt::print(stderr, "LLVM ERROR: {}\n", Reason);
-  }
-
-  exit(1);
-}
-
-void wpi::install_bad_alloc_error_handler(fatal_error_handler_t handler,
-                                          void *user_data) {
-  std::scoped_lock Lock(BadAllocErrorHandlerMutex);
-  assert(!ErrorHandler && "Bad alloc error handler already registered!\n");
-  BadAllocErrorHandler = handler;
-  BadAllocErrorHandlerUserData = user_data;
-}
-
-void wpi::remove_bad_alloc_error_handler() {
-  std::scoped_lock Lock(BadAllocErrorHandlerMutex);
-  BadAllocErrorHandler = nullptr;
-  BadAllocErrorHandlerUserData = nullptr;
-}
-
-void wpi::report_bad_alloc_error(const char *Reason, bool GenCrashDiag) {
-  fatal_error_handler_t Handler = nullptr;
-  void *HandlerData = nullptr;
-  {
-    // Only acquire the mutex while reading the handler, so as not to invoke a
-    // user-supplied callback under a lock.
-    std::scoped_lock Lock(BadAllocErrorHandlerMutex);
-    Handler = BadAllocErrorHandler;
-    HandlerData = BadAllocErrorHandlerUserData;
-  }
-
-  if (Handler) {
-    Handler(HandlerData, Reason, GenCrashDiag);
-    wpi_unreachable("bad alloc handler should not return");
-  }
-
-  // Don't call the normal error handler. It may allocate memory. Directly write
-  // an OOM to stderr and abort.
-  char OOMMessage[] = "LLVM ERROR: out of memory\n";
-#ifdef _WIN32
-  int written = ::_write(2, OOMMessage, strlen(OOMMessage));
-#else
-  ssize_t written = ::write(2, OOMMessage, strlen(OOMMessage));
-#endif
-  (void)written;
-  abort();
-}
-
-// Causes crash on allocation failure. It is called prior to the handler set by
-// 'install_bad_alloc_error_handler'.
-static void out_of_memory_new_handler() {
-  wpi::report_bad_alloc_error("Allocation failed");
-}
-
-// Installs new handler that causes crash on allocation failure. It does not
-// need to be called explicitly, if this file is linked to application, because
-// in this case it is called during construction of 'new_handler_installer'.
-void wpi::install_out_of_memory_new_handler() {
-  static bool out_of_memory_new_handler_installed = false;
-  if (!out_of_memory_new_handler_installed) {
-    std::set_new_handler(out_of_memory_new_handler);
-    out_of_memory_new_handler_installed = true;
-  }
-}
-
-// Static object that causes installation of 'out_of_memory_new_handler' before
-// execution of 'main'.
-static class NewHandlerInstaller {
-public:
-  NewHandlerInstaller() {
-    install_out_of_memory_new_handler();
-  }
-} new_handler_installer;
-
-void wpi::wpi_unreachable_internal(const char *msg, const char *file,
-                                   unsigned line) {
-  // This code intentionally doesn't call the ErrorHandler callback, because
-  // wpi_unreachable is intended to be used to indicate "impossible"
-  // situations, and not legitimate runtime errors.
-  if (msg)
-    fmt::print(stderr, "{}\n", msg);
-  std::fputs("UNREACHABLE executed", stderr);
-  if (file)
-    fmt::print(stderr, " at {}:{}", file, line);
-  fmt::print(stderr, "{}", "!\n");
-  abort();
-#ifdef LLVM_BUILTIN_UNREACHABLE
-  // Windows systems and possibly others don't declare abort() to be noreturn,
-  // so use the unreachable builtin to avoid a Clang self-host warning.
-  LLVM_BUILTIN_UNREACHABLE;
-#endif
-}
-
-#ifdef _WIN32
-
-#include <system_error>
-#include <winerror.h>
-
-// I'd rather not double the line count of the following.
-#define MAP_ERR_TO_COND(x, y)                                                  \
-  case x:                                                                      \
-    return std::make_error_code(std::errc::y)
-
-std::error_code wpi::mapWindowsError(unsigned EV) {
-  switch (EV) {
-    MAP_ERR_TO_COND(ERROR_ACCESS_DENIED, permission_denied);
-    MAP_ERR_TO_COND(ERROR_ALREADY_EXISTS, file_exists);
-    MAP_ERR_TO_COND(ERROR_BAD_UNIT, no_such_device);
-    MAP_ERR_TO_COND(ERROR_BUFFER_OVERFLOW, filename_too_long);
-    MAP_ERR_TO_COND(ERROR_BUSY, device_or_resource_busy);
-    MAP_ERR_TO_COND(ERROR_BUSY_DRIVE, device_or_resource_busy);
-    MAP_ERR_TO_COND(ERROR_CANNOT_MAKE, permission_denied);
-    MAP_ERR_TO_COND(ERROR_CANTOPEN, io_error);
-    MAP_ERR_TO_COND(ERROR_CANTREAD, io_error);
-    MAP_ERR_TO_COND(ERROR_CANTWRITE, io_error);
-    MAP_ERR_TO_COND(ERROR_CURRENT_DIRECTORY, permission_denied);
-    MAP_ERR_TO_COND(ERROR_DEV_NOT_EXIST, no_such_device);
-    MAP_ERR_TO_COND(ERROR_DEVICE_IN_USE, device_or_resource_busy);
-    MAP_ERR_TO_COND(ERROR_DIR_NOT_EMPTY, directory_not_empty);
-    MAP_ERR_TO_COND(ERROR_DIRECTORY, invalid_argument);
-    MAP_ERR_TO_COND(ERROR_DISK_FULL, no_space_on_device);
-    MAP_ERR_TO_COND(ERROR_FILE_EXISTS, file_exists);
-    MAP_ERR_TO_COND(ERROR_FILE_NOT_FOUND, no_such_file_or_directory);
-    MAP_ERR_TO_COND(ERROR_HANDLE_DISK_FULL, no_space_on_device);
-    MAP_ERR_TO_COND(ERROR_INVALID_ACCESS, permission_denied);
-    MAP_ERR_TO_COND(ERROR_INVALID_DRIVE, no_such_device);
-    MAP_ERR_TO_COND(ERROR_INVALID_FUNCTION, function_not_supported);
-    MAP_ERR_TO_COND(ERROR_INVALID_HANDLE, invalid_argument);
-    MAP_ERR_TO_COND(ERROR_INVALID_NAME, invalid_argument);
-    MAP_ERR_TO_COND(ERROR_LOCK_VIOLATION, no_lock_available);
-    MAP_ERR_TO_COND(ERROR_LOCKED, no_lock_available);
-    MAP_ERR_TO_COND(ERROR_NEGATIVE_SEEK, invalid_argument);
-    MAP_ERR_TO_COND(ERROR_NOACCESS, permission_denied);
-    MAP_ERR_TO_COND(ERROR_NOT_ENOUGH_MEMORY, not_enough_memory);
-    MAP_ERR_TO_COND(ERROR_NOT_READY, resource_unavailable_try_again);
-    MAP_ERR_TO_COND(ERROR_OPEN_FAILED, io_error);
-    MAP_ERR_TO_COND(ERROR_OPEN_FILES, device_or_resource_busy);
-    MAP_ERR_TO_COND(ERROR_OUTOFMEMORY, not_enough_memory);
-    MAP_ERR_TO_COND(ERROR_PATH_NOT_FOUND, no_such_file_or_directory);
-    MAP_ERR_TO_COND(ERROR_BAD_NETPATH, no_such_file_or_directory);
-    MAP_ERR_TO_COND(ERROR_READ_FAULT, io_error);
-    MAP_ERR_TO_COND(ERROR_RETRY, resource_unavailable_try_again);
-    MAP_ERR_TO_COND(ERROR_SEEK, io_error);
-    MAP_ERR_TO_COND(ERROR_SHARING_VIOLATION, permission_denied);
-    MAP_ERR_TO_COND(ERROR_TOO_MANY_OPEN_FILES, too_many_files_open);
-    MAP_ERR_TO_COND(ERROR_WRITE_FAULT, io_error);
-    MAP_ERR_TO_COND(ERROR_WRITE_PROTECT, permission_denied);
-    MAP_ERR_TO_COND(WSAEACCES, permission_denied);
-    MAP_ERR_TO_COND(WSAEBADF, bad_file_descriptor);
-    MAP_ERR_TO_COND(WSAEFAULT, bad_address);
-    MAP_ERR_TO_COND(WSAEINTR, interrupted);
-    MAP_ERR_TO_COND(WSAEINVAL, invalid_argument);
-    MAP_ERR_TO_COND(WSAEMFILE, too_many_files_open);
-    MAP_ERR_TO_COND(WSAENAMETOOLONG, filename_too_long);
-  default:
-    return std::error_code(EV, std::system_category());
-  }
-}
-
-#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/llvm/Hashing.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/llvm/Hashing.cpp
deleted file mode 100644
index e916751..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/llvm/Hashing.cpp
+++ /dev/null
@@ -1,29 +0,0 @@
-//===-------------- lib/Support/Hashing.cpp -------------------------------===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-//
-// This file provides implementation bits for the LLVM common hashing
-// infrastructure. Documentation and most of the other information is in the
-// header file.
-//
-//===----------------------------------------------------------------------===//
-
-#include "wpi/Hashing.h"
-
-using namespace wpi;
-
-// Provide a definition and static initializer for the fixed seed. This
-// initializer should always be zero to ensure its value can never appear to be
-// non-zero, even during dynamic initialization.
-uint64_t wpi::hashing::detail::fixed_seed_override = 0;
-
-// Implement the function for forced setting of the fixed seed.
-// FIXME: Use atomic operations here so that there is no data race.
-void wpi::set_fixed_execution_hash_seed(uint64_t fixed_value) {
-  hashing::detail::fixed_seed_override = fixed_value;
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/llvm/ManagedStatic.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/llvm/ManagedStatic.cpp
deleted file mode 100644
index a8c82bf..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/llvm/ManagedStatic.cpp
+++ /dev/null
@@ -1,88 +0,0 @@
-//===-- ManagedStatic.cpp - Static Global wrapper -------------------------===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-//
-// This file implements the ManagedStatic class and wpi_shutdown().
-//
-//===----------------------------------------------------------------------===//
-
-#include "wpi/ManagedStatic.h"
-#include "wpi/mutex.h"
-#include <cassert>
-#include <mutex>
-using namespace wpi;
-
-static const ManagedStaticBase *StaticList = nullptr;
-static wpi::mutex *ManagedStaticMutex = nullptr;
-static std::once_flag mutex_init_flag;
-
-static void initializeMutex() {
-  ManagedStaticMutex = new wpi::mutex();
-}
-
-static wpi::mutex* getManagedStaticMutex() {
-  std::call_once(mutex_init_flag, initializeMutex);
-  return ManagedStaticMutex;
-}
-
-void ManagedStaticBase::RegisterManagedStatic(void* created,
-                                              void (*Deleter)(void*)) const {
-  std::scoped_lock Lock(*getManagedStaticMutex());
-
-  if (!Ptr.load(std::memory_order_relaxed)) {
-    void *Tmp = created;
-
-    Ptr.store(Tmp, std::memory_order_release);
-    DeleterFn = Deleter;
-
-    // Add to list of managed statics.
-    Next = StaticList;
-    StaticList = this;
-  }
-}
-
-void ManagedStaticBase::RegisterManagedStatic(void *(*Creator)(),
-                                              void (*Deleter)(void*)) const {
-  assert(Creator);
-  std::scoped_lock Lock(*getManagedStaticMutex());
-
-  if (!Ptr.load(std::memory_order_relaxed)) {
-    void *Tmp = Creator();
-
-    Ptr.store(Tmp, std::memory_order_release);
-    DeleterFn = Deleter;
-
-    // Add to list of managed statics.
-    Next = StaticList;
-    StaticList = this;
-  }
-}
-
-void ManagedStaticBase::destroy() const {
-  assert(DeleterFn && "ManagedStatic not initialized correctly!");
-  assert(StaticList == this &&
-         "Not destroyed in reverse order of construction?");
-  // Unlink from list.
-  StaticList = Next;
-  Next = nullptr;
-
-  // Destroy memory.
-  DeleterFn(Ptr);
-
-  // Cleanup.
-  Ptr = nullptr;
-  DeleterFn = nullptr;
-}
-
-/// wpi_shutdown - Deallocate and destroy all ManagedStatic variables.
-void wpi::wpi_shutdown() {
-  std::scoped_lock Lock(*getManagedStaticMutex());
-
-  while (StaticList)
-    StaticList->destroy();
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/llvm/SmallPtrSet.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/llvm/SmallPtrSet.cpp
deleted file mode 100644
index 1b33f4c..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/llvm/SmallPtrSet.cpp
+++ /dev/null
@@ -1,271 +0,0 @@
-//===- llvm/ADT/SmallPtrSet.cpp - 'Normally small' pointer set ------------===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-//
-// This file implements the SmallPtrSet class.  See SmallPtrSet.h for an
-// overview of the algorithm.
-//
-//===----------------------------------------------------------------------===//
-
-#include "wpi/SmallPtrSet.h"
-#include "wpi/DenseMapInfo.h"
-#include "wpi/MathExtras.h"
-#include "wpi/MemAlloc.h"
-#include "wpi/ErrorHandling.h"
-#include <algorithm>
-#include <cassert>
-#include <cstdlib>
-
-using namespace wpi;
-
-void SmallPtrSetImplBase::shrink_and_clear() {
-  assert(!isSmall() && "Can't shrink a small set!");
-  free(CurArray);
-
-  // Reduce the number of buckets.
-  unsigned Size = size();
-  CurArraySize = Size > 16 ? 1 << (Log2_32_Ceil(Size) + 1) : 32;
-  NumNonEmpty = NumTombstones = 0;
-
-  // Install the new array.  Clear all the buckets to empty.
-  CurArray = (const void**)safe_malloc(sizeof(void*) * CurArraySize);
-
-  memset(CurArray, -1, CurArraySize*sizeof(void*));
-}
-
-std::pair<const void *const *, bool>
-SmallPtrSetImplBase::insert_imp_big(const void *Ptr) {
-  if (LLVM_UNLIKELY(size() * 4 >= CurArraySize * 3)) {
-    // If more than 3/4 of the array is full, grow.
-    Grow(CurArraySize < 64 ? 128 : CurArraySize * 2);
-  } else if (LLVM_UNLIKELY(CurArraySize - NumNonEmpty < CurArraySize / 8)) {
-    // If fewer of 1/8 of the array is empty (meaning that many are filled with
-    // tombstones), rehash.
-    Grow(CurArraySize);
-  }
-
-  // Okay, we know we have space.  Find a hash bucket.
-  const void **Bucket = const_cast<const void**>(FindBucketFor(Ptr));
-  if (*Bucket == Ptr)
-    return std::make_pair(Bucket, false); // Already inserted, good.
-
-  // Otherwise, insert it!
-  if (*Bucket == getTombstoneMarker())
-    --NumTombstones;
-  else
-    ++NumNonEmpty; // Track density.
-  *Bucket = Ptr;
-  return std::make_pair(Bucket, true);
-}
-
-const void * const *SmallPtrSetImplBase::FindBucketFor(const void *Ptr) const {
-  unsigned Bucket = DenseMapInfo<void *>::getHashValue(Ptr) & (CurArraySize-1);
-  unsigned ArraySize = CurArraySize;
-  unsigned ProbeAmt = 1;
-  const void *const *Array = CurArray;
-  const void *const *Tombstone = nullptr;
-  while (true) {
-    // If we found an empty bucket, the pointer doesn't exist in the set.
-    // Return a tombstone if we've seen one so far, or the empty bucket if
-    // not.
-    if (LLVM_LIKELY(Array[Bucket] == getEmptyMarker()))
-      return Tombstone ? Tombstone : Array+Bucket;
-
-    // Found Ptr's bucket?
-    if (LLVM_LIKELY(Array[Bucket] == Ptr))
-      return Array+Bucket;
-
-    // If this is a tombstone, remember it.  If Ptr ends up not in the set, we
-    // prefer to return it than something that would require more probing.
-    if (Array[Bucket] == getTombstoneMarker() && !Tombstone)
-      Tombstone = Array+Bucket;  // Remember the first tombstone found.
-
-    // It's a hash collision or a tombstone. Reprobe.
-    Bucket = (Bucket + ProbeAmt++) & (ArraySize-1);
-  }
-}
-
-/// Grow - Allocate a larger backing store for the buckets and move it over.
-///
-void SmallPtrSetImplBase::Grow(unsigned NewSize) {
-  const void **OldBuckets = CurArray;
-  const void **OldEnd = EndPointer();
-  bool WasSmall = isSmall();
-
-  // Install the new array.  Clear all the buckets to empty.
-  const void **NewBuckets = (const void**) safe_malloc(sizeof(void*) * NewSize);
-
-  // Reset member only if memory was allocated successfully
-  CurArray = NewBuckets;
-  CurArraySize = NewSize;
-  memset(CurArray, -1, NewSize*sizeof(void*));
-
-  // Copy over all valid entries.
-  for (const void **BucketPtr = OldBuckets; BucketPtr != OldEnd; ++BucketPtr) {
-    // Copy over the element if it is valid.
-    const void *Elt = *BucketPtr;
-    if (Elt != getTombstoneMarker() && Elt != getEmptyMarker())
-      *const_cast<void**>(FindBucketFor(Elt)) = const_cast<void*>(Elt);
-  }
-
-  if (!WasSmall)
-    free(OldBuckets);
-  NumNonEmpty -= NumTombstones;
-  NumTombstones = 0;
-}
-
-SmallPtrSetImplBase::SmallPtrSetImplBase(const void **SmallStorage,
-                                         const SmallPtrSetImplBase &that) {
-  SmallArray = SmallStorage;
-
-  // If we're becoming small, prepare to insert into our stack space
-  if (that.isSmall()) {
-    CurArray = SmallArray;
-  // Otherwise, allocate new heap space (unless we were the same size)
-  } else {
-    CurArray = (const void**)safe_malloc(sizeof(void*) * that.CurArraySize);
-  }
-
-  // Copy over the that array.
-  CopyHelper(that);
-}
-
-SmallPtrSetImplBase::SmallPtrSetImplBase(const void **SmallStorage,
-                                         unsigned SmallSize,
-                                         SmallPtrSetImplBase &&that) {
-  SmallArray = SmallStorage;
-  MoveHelper(SmallSize, std::move(that));
-}
-
-void SmallPtrSetImplBase::CopyFrom(const SmallPtrSetImplBase &RHS) {
-  assert(&RHS != this && "Self-copy should be handled by the caller.");
-
-  if (isSmall() && RHS.isSmall())
-    assert(CurArraySize == RHS.CurArraySize &&
-           "Cannot assign sets with different small sizes");
-
-  // If we're becoming small, prepare to insert into our stack space
-  if (RHS.isSmall()) {
-    if (!isSmall())
-      free(CurArray);
-    CurArray = SmallArray;
-  // Otherwise, allocate new heap space (unless we were the same size)
-  } else if (CurArraySize != RHS.CurArraySize) {
-    if (isSmall())
-      CurArray = (const void**)safe_malloc(sizeof(void*) * RHS.CurArraySize);
-    else {
-      const void **T = (const void**)safe_realloc(CurArray,
-                                             sizeof(void*) * RHS.CurArraySize);
-      CurArray = T;
-    }
-  }
-
-  CopyHelper(RHS);
-}
-
-void SmallPtrSetImplBase::CopyHelper(const SmallPtrSetImplBase &RHS) {
-  // Copy over the new array size
-  CurArraySize = RHS.CurArraySize;
-
-  // Copy over the contents from the other set
-  std::copy(RHS.CurArray, RHS.EndPointer(), CurArray);
-
-  NumNonEmpty = RHS.NumNonEmpty;
-  NumTombstones = RHS.NumTombstones;
-}
-
-void SmallPtrSetImplBase::MoveFrom(unsigned SmallSize,
-                                   SmallPtrSetImplBase &&RHS) {
-  if (!isSmall())
-    free(CurArray);
-  MoveHelper(SmallSize, std::move(RHS));
-}
-
-void SmallPtrSetImplBase::MoveHelper(unsigned SmallSize,
-                                     SmallPtrSetImplBase &&RHS) {
-  assert(&RHS != this && "Self-move should be handled by the caller.");
-
-  if (RHS.isSmall()) {
-    // Copy a small RHS rather than moving.
-    CurArray = SmallArray;
-    std::copy(RHS.CurArray, RHS.CurArray + RHS.NumNonEmpty, CurArray);
-  } else {
-    CurArray = RHS.CurArray;
-    RHS.CurArray = RHS.SmallArray;
-  }
-
-  // Copy the rest of the trivial members.
-  CurArraySize = RHS.CurArraySize;
-  NumNonEmpty = RHS.NumNonEmpty;
-  NumTombstones = RHS.NumTombstones;
-
-  // Make the RHS small and empty.
-  RHS.CurArraySize = SmallSize;
-  assert(RHS.CurArray == RHS.SmallArray);
-  RHS.NumNonEmpty = 0;
-  RHS.NumTombstones = 0;
-}
-
-void SmallPtrSetImplBase::swap(SmallPtrSetImplBase &RHS) {
-  if (this == &RHS) return;
-
-  // We can only avoid copying elements if neither set is small.
-  if (!this->isSmall() && !RHS.isSmall()) {
-    std::swap(this->CurArray, RHS.CurArray);
-    std::swap(this->CurArraySize, RHS.CurArraySize);
-    std::swap(this->NumNonEmpty, RHS.NumNonEmpty);
-    std::swap(this->NumTombstones, RHS.NumTombstones);
-    return;
-  }
-
-  // FIXME: From here on we assume that both sets have the same small size.
-
-  // If only RHS is small, copy the small elements into LHS and move the pointer
-  // from LHS to RHS.
-  if (!this->isSmall() && RHS.isSmall()) {
-    assert(RHS.CurArray == RHS.SmallArray);
-    std::copy(RHS.CurArray, RHS.CurArray + RHS.NumNonEmpty, this->SmallArray);
-    std::swap(RHS.CurArraySize, this->CurArraySize);
-    std::swap(this->NumNonEmpty, RHS.NumNonEmpty);
-    std::swap(this->NumTombstones, RHS.NumTombstones);
-    RHS.CurArray = this->CurArray;
-    this->CurArray = this->SmallArray;
-    return;
-  }
-
-  // If only LHS is small, copy the small elements into RHS and move the pointer
-  // from RHS to LHS.
-  if (this->isSmall() && !RHS.isSmall()) {
-    assert(this->CurArray == this->SmallArray);
-    std::copy(this->CurArray, this->CurArray + this->NumNonEmpty,
-              RHS.SmallArray);
-    std::swap(RHS.CurArraySize, this->CurArraySize);
-    std::swap(RHS.NumNonEmpty, this->NumNonEmpty);
-    std::swap(RHS.NumTombstones, this->NumTombstones);
-    this->CurArray = RHS.CurArray;
-    RHS.CurArray = RHS.SmallArray;
-    return;
-  }
-
-  // Both a small, just swap the small elements.
-  assert(this->isSmall() && RHS.isSmall());
-  unsigned MinNonEmpty = std::min(this->NumNonEmpty, RHS.NumNonEmpty);
-  std::swap_ranges(this->SmallArray, this->SmallArray + MinNonEmpty,
-                   RHS.SmallArray);
-  if (this->NumNonEmpty > MinNonEmpty) {
-    std::copy(this->SmallArray + MinNonEmpty,
-              this->SmallArray + this->NumNonEmpty,
-              RHS.SmallArray + MinNonEmpty);
-  } else {
-    std::copy(RHS.SmallArray + MinNonEmpty, RHS.SmallArray + RHS.NumNonEmpty,
-              this->SmallArray + MinNonEmpty);
-  }
-  assert(this->CurArraySize == RHS.CurArraySize);
-  std::swap(this->NumNonEmpty, RHS.NumNonEmpty);
-  std::swap(this->NumTombstones, RHS.NumTombstones);
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/llvm/SmallVector.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/llvm/SmallVector.cpp
deleted file mode 100644
index 974fec9..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/llvm/SmallVector.cpp
+++ /dev/null
@@ -1,43 +0,0 @@
-//===- llvm/ADT/SmallVector.cpp - 'Normally small' vectors ----------------===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-//
-// This file implements the SmallVector class.
-//
-//===----------------------------------------------------------------------===//
-
-#include "wpi/SmallVector.h"
-#include "wpi/MemAlloc.h"
-using namespace wpi;
-
-/// grow_pod - This is an implementation of the grow() method which only works
-/// on POD-like datatypes and is out of line to reduce code duplication.
-void SmallVectorBase::grow_pod(void *FirstEl, size_t MinCapacity,
-                               size_t TSize) {
-  // Ensure we can fit the new capacity in 32 bits.
-  if (MinCapacity > UINT32_MAX)
-    report_bad_alloc_error("SmallVector capacity overflow during allocation");
-
-  size_t NewCapacity = 2 * capacity() + 1; // Always grow.
-  NewCapacity =
-      std::min(std::max(NewCapacity, MinCapacity), size_t(UINT32_MAX));
-
-  void *NewElts;
-  if (BeginX == FirstEl) {
-    NewElts = safe_malloc(NewCapacity * TSize);
-
-    // Copy the elements over.  No need to run dtors on PODs.
-    memcpy(NewElts, this->BeginX, size() * TSize);
-  } else {
-    // If this wasn't grown from the inline copy, grow the allocated space.
-    NewElts = safe_realloc(this->BeginX, NewCapacity * TSize);
-  }
-
-  this->BeginX = NewElts;
-  this->Capacity = NewCapacity;
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/llvm/StringMap.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/llvm/StringMap.cpp
deleted file mode 100644
index 768801d..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/llvm/StringMap.cpp
+++ /dev/null
@@ -1,276 +0,0 @@
-//===--- StringMap.cpp - String Hash table map implementation -------------===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-//
-// This file implements the StringMap class.
-//
-//===----------------------------------------------------------------------===//
-
-#include "wpi/StringMap.h"
-#include "wpi/StringExtras.h"
-#include "wpi/Compiler.h"
-#include "wpi/MathExtras.h"
-#include <cassert>
-
-using namespace wpi;
-
-/// HashString - Hash function for strings.
-///
-/// This is the Bernstein hash function.
-//
-// FIXME: Investigate whether a modified bernstein hash function performs
-// better: http://eternallyconfuzzled.com/tuts/algorithms/jsw_tut_hashing.aspx
-//   X*33+c -> X*33^c
-static inline unsigned HashString(std::string_view str,
-                                  unsigned result = 0) noexcept {
-  for (std::string_view::size_type i = 0, e = str.size(); i != e; ++i) {
-    result = result * 33 + static_cast<unsigned char>(str[i]);
-  }
-  return result;
-}
-
-/// Returns the number of buckets to allocate to ensure that the DenseMap can
-/// accommodate \p NumEntries without need to grow().
-static unsigned getMinBucketToReserveForEntries(unsigned NumEntries) {
-  // Ensure that "NumEntries * 4 < NumBuckets * 3"
-  if (NumEntries == 0)
-    return 0;
-  // +1 is required because of the strict equality.
-  // For example if NumEntries is 48, we need to return 401.
-  return NextPowerOf2(NumEntries * 4 / 3 + 1);
-}
-
-StringMapImpl::StringMapImpl(unsigned InitSize, unsigned itemSize) {
-  ItemSize = itemSize;
-
-  // If a size is specified, initialize the table with that many buckets.
-  if (InitSize) {
-    // The table will grow when the number of entries reach 3/4 of the number of
-    // buckets. To guarantee that "InitSize" number of entries can be inserted
-    // in the table without growing, we allocate just what is needed here.
-    init(getMinBucketToReserveForEntries(InitSize));
-    return;
-  }
-
-  // Otherwise, initialize it with zero buckets to avoid the allocation.
-  TheTable = nullptr;
-  NumBuckets = 0;
-  NumItems = 0;
-  NumTombstones = 0;
-}
-
-void StringMapImpl::init(unsigned InitSize) {
-  assert((InitSize & (InitSize-1)) == 0 &&
-         "Init Size must be a power of 2 or zero!");
-
-  unsigned NewNumBuckets = InitSize ? InitSize : 16;
-  NumItems = 0;
-  NumTombstones = 0;
-
-  TheTable = static_cast<StringMapEntryBase **>(
-      safe_calloc(NewNumBuckets+1,
-                  sizeof(StringMapEntryBase **) + sizeof(unsigned)));
-
-  // Set the member only if TheTable was successfully allocated
-  NumBuckets = NewNumBuckets;
-
-  // Allocate one extra bucket, set it to look filled so the iterators stop at
-  // end.
-  TheTable[NumBuckets] = (StringMapEntryBase*)2;
-}
-
-/// LookupBucketFor - Look up the bucket that the specified string should end
-/// up in.  If it already exists as a key in the map, the Item pointer for the
-/// specified bucket will be non-null.  Otherwise, it will be null.  In either
-/// case, the FullHashValue field of the bucket will be set to the hash value
-/// of the string.
-unsigned StringMapImpl::LookupBucketFor(std::string_view Name) {
-  unsigned HTSize = NumBuckets;
-  if (HTSize == 0) {  // Hash table unallocated so far?
-    init(16);
-    HTSize = NumBuckets;
-  }
-  unsigned FullHashValue = HashString(Name);
-  unsigned BucketNo = FullHashValue & (HTSize-1);
-  unsigned *HashTable = (unsigned *)(TheTable + NumBuckets + 1);
-
-  unsigned ProbeAmt = 1;
-  int FirstTombstone = -1;
-  while (true) {
-    StringMapEntryBase *BucketItem = TheTable[BucketNo];
-    // If we found an empty bucket, this key isn't in the table yet, return it.
-    if (LLVM_LIKELY(!BucketItem)) {
-      // If we found a tombstone, we want to reuse the tombstone instead of an
-      // empty bucket.  This reduces probing.
-      if (FirstTombstone != -1) {
-        HashTable[FirstTombstone] = FullHashValue;
-        return FirstTombstone;
-      }
-
-      HashTable[BucketNo] = FullHashValue;
-      return BucketNo;
-    }
-
-    if (BucketItem == getTombstoneVal()) {
-      // Skip over tombstones.  However, remember the first one we see.
-      if (FirstTombstone == -1) FirstTombstone = BucketNo;
-    } else if (LLVM_LIKELY(HashTable[BucketNo] == FullHashValue)) {
-      // If the full hash value matches, check deeply for a match.  The common
-      // case here is that we are only looking at the buckets (for item info
-      // being non-null and for the full hash value) not at the items.  This
-      // is important for cache locality.
-
-      // Do the comparison like this because Name isn't necessarily
-      // null-terminated!
-      char *ItemStr = (char*)BucketItem+ItemSize;
-      if (Name == std::string_view(ItemStr, BucketItem->getKeyLength())) {
-        // We found a match!
-        return BucketNo;
-      }
-    }
-
-    // Okay, we didn't find the item.  Probe to the next bucket.
-    BucketNo = (BucketNo+ProbeAmt) & (HTSize-1);
-
-    // Use quadratic probing, it has fewer clumping artifacts than linear
-    // probing and has good cache behavior in the common case.
-    ++ProbeAmt;
-  }
-}
-
-/// FindKey - Look up the bucket that contains the specified key. If it exists
-/// in the map, return the bucket number of the key.  Otherwise return -1.
-/// This does not modify the map.
-int StringMapImpl::FindKey(std::string_view Key) const {
-  unsigned HTSize = NumBuckets;
-  if (HTSize == 0) return -1;  // Really empty table?
-  unsigned FullHashValue = HashString(Key);
-  unsigned BucketNo = FullHashValue & (HTSize-1);
-  unsigned *HashTable = (unsigned *)(TheTable + NumBuckets + 1);
-
-  unsigned ProbeAmt = 1;
-  while (true) {
-    StringMapEntryBase *BucketItem = TheTable[BucketNo];
-    // If we found an empty bucket, this key isn't in the table yet, return.
-    if (LLVM_LIKELY(!BucketItem))
-      return -1;
-
-    if (BucketItem == getTombstoneVal()) {
-      // Ignore tombstones.
-    } else if (LLVM_LIKELY(HashTable[BucketNo] == FullHashValue)) {
-      // If the full hash value matches, check deeply for a match.  The common
-      // case here is that we are only looking at the buckets (for item info
-      // being non-null and for the full hash value) not at the items.  This
-      // is important for cache locality.
-
-      // Do the comparison like this because NameStart isn't necessarily
-      // null-terminated!
-      char *ItemStr = (char*)BucketItem+ItemSize;
-      if (Key == std::string_view(ItemStr, BucketItem->getKeyLength())) {
-        // We found a match!
-        return BucketNo;
-      }
-    }
-
-    // Okay, we didn't find the item.  Probe to the next bucket.
-    BucketNo = (BucketNo+ProbeAmt) & (HTSize-1);
-
-    // Use quadratic probing, it has fewer clumping artifacts than linear
-    // probing and has good cache behavior in the common case.
-    ++ProbeAmt;
-  }
-}
-
-/// RemoveKey - Remove the specified StringMapEntry from the table, but do not
-/// delete it.  This aborts if the value isn't in the table.
-void StringMapImpl::RemoveKey(StringMapEntryBase *V) {
-  const char *VStr = (char*)V + ItemSize;
-  StringMapEntryBase *V2 = RemoveKey(std::string_view(VStr, V->getKeyLength()));
-  (void)V2;
-  assert(V == V2 && "Didn't find key?");
-}
-
-/// RemoveKey - Remove the StringMapEntry for the specified key from the
-/// table, returning it.  If the key is not in the table, this returns null.
-StringMapEntryBase *StringMapImpl::RemoveKey(std::string_view Key) {
-  int Bucket = FindKey(Key);
-  if (Bucket == -1) return nullptr;
-
-  StringMapEntryBase *Result = TheTable[Bucket];
-  TheTable[Bucket] = getTombstoneVal();
-  --NumItems;
-  ++NumTombstones;
-  assert(NumItems + NumTombstones <= NumBuckets);
-
-  return Result;
-}
-
-/// RehashTable - Grow the table, redistributing values into the buckets with
-/// the appropriate mod-of-hashtable-size.
-unsigned StringMapImpl::RehashTable(unsigned BucketNo) {
-  unsigned NewSize;
-  unsigned *HashTable = (unsigned *)(TheTable + NumBuckets + 1);
-
-  // If the hash table is now more than 3/4 full, or if fewer than 1/8 of
-  // the buckets are empty (meaning that many are filled with tombstones),
-  // grow/rehash the table.
-  if (LLVM_UNLIKELY(NumItems * 4 > NumBuckets * 3)) {
-    NewSize = NumBuckets*2;
-  } else if (LLVM_UNLIKELY(NumBuckets - (NumItems + NumTombstones) <=
-                           NumBuckets / 8)) {
-    NewSize = NumBuckets;
-  } else {
-    return BucketNo;
-  }
-
-  unsigned NewBucketNo = BucketNo;
-  // Allocate one extra bucket which will always be non-empty.  This allows the
-  // iterators to stop at end.
-  auto NewTableArray = static_cast<StringMapEntryBase **>(
-      safe_calloc(NewSize+1, sizeof(StringMapEntryBase *) + sizeof(unsigned)));
-
-  unsigned *NewHashArray = (unsigned *)(NewTableArray + NewSize + 1);
-  NewTableArray[NewSize] = (StringMapEntryBase*)2;
-
-  // Rehash all the items into their new buckets.  Luckily :) we already have
-  // the hash values available, so we don't have to rehash any strings.
-  for (unsigned I = 0, E = NumBuckets; I != E; ++I) {
-    StringMapEntryBase *Bucket = TheTable[I];
-    if (Bucket && Bucket != getTombstoneVal()) {
-      // Fast case, bucket available.
-      unsigned FullHash = HashTable[I];
-      unsigned NewBucket = FullHash & (NewSize-1);
-      if (!NewTableArray[NewBucket]) {
-        NewTableArray[FullHash & (NewSize-1)] = Bucket;
-        NewHashArray[FullHash & (NewSize-1)] = FullHash;
-        if (I == BucketNo)
-          NewBucketNo = NewBucket;
-        continue;
-      }
-
-      // Otherwise probe for a spot.
-      unsigned ProbeSize = 1;
-      do {
-        NewBucket = (NewBucket + ProbeSize++) & (NewSize-1);
-      } while (NewTableArray[NewBucket]);
-
-      // Finally found a slot.  Fill it in.
-      NewTableArray[NewBucket] = Bucket;
-      NewHashArray[NewBucket] = FullHash;
-      if (I == BucketNo)
-        NewBucketNo = NewBucket;
-    }
-  }
-
-  free(TheTable);
-
-  TheTable = NewTableArray;
-  NumBuckets = NewSize;
-  NumTombstones = 0;
-  return NewBucketNo;
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/llvm/Windows/WindowsSupport.h b/third_party/allwpilib/wpiutil/src/main/native/cpp/llvm/Windows/WindowsSupport.h
deleted file mode 100644
index 7307337..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/llvm/Windows/WindowsSupport.h
+++ /dev/null
@@ -1,245 +0,0 @@
-//===- WindowsSupport.h - Common Windows Include File -----------*- C++ -*-===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-//
-// This file defines things specific to Windows implementations.  In addition to
-// providing some helpers for working with win32 APIs, this header wraps
-// <windows.h> with some portability macros.  Always include WindowsSupport.h
-// instead of including <windows.h> directly.
-//
-//===----------------------------------------------------------------------===//
-
-//===----------------------------------------------------------------------===//
-//=== WARNING: Implementation here must contain only generic Win32 code that
-//===          is guaranteed to work on *all* Win32 variants.
-//===----------------------------------------------------------------------===//
-
-#ifndef LLVM_SUPPORT_WINDOWSSUPPORT_H
-#define LLVM_SUPPORT_WINDOWSSUPPORT_H
-
-// mingw-w64 tends to define it as 0x0502 in its headers.
-#undef _WIN32_WINNT
-#undef _WIN32_IE
-
-// Require at least Windows 7 API.
-#define _WIN32_WINNT 0x0601
-#define _WIN32_IE    0x0800 // MinGW at it again. FIXME: verify if still needed.
-#define WIN32_LEAN_AND_MEAN
-#ifndef NOMINMAX
-#define NOMINMAX
-#endif
-
-#include "wpi/SmallVector.h"
-#include "wpi/StringExtras.h"
-#include "wpi/Chrono.h"
-#include "wpi/Compiler.h"
-#include "wpi/VersionTuple.h"
-#include <cassert>
-#include <string>
-#include <string_view>
-#include <system_error>
-#define WIN32_NO_STATUS
-#include <windows.h>
-#undef WIN32_NO_STATUS
-#include <winternl.h>
-#include <ntstatus.h>
-
-namespace wpi {
-
-/// Returns the Windows version as Major.Minor.0.BuildNumber. Uses
-/// RtlGetVersion or GetVersionEx under the hood depending on what is available.
-/// GetVersionEx is deprecated, but this API exposes the build number which can
-/// be useful for working around certain kernel bugs.
-inline wpi::VersionTuple GetWindowsOSVersion() {
-  typedef NTSTATUS(WINAPI* RtlGetVersionPtr)(PRTL_OSVERSIONINFOW);
-  HMODULE hMod = ::GetModuleHandleW(L"ntdll.dll");
-  if (hMod) {
-    auto getVer = (RtlGetVersionPtr)::GetProcAddress(hMod, "RtlGetVersion");
-    if (getVer) {
-      RTL_OSVERSIONINFOEXW info{};
-      info.dwOSVersionInfoSize = sizeof(info);
-      if (getVer((PRTL_OSVERSIONINFOW)&info) == ((NTSTATUS)0x00000000L)) {
-        return wpi::VersionTuple(info.dwMajorVersion, info.dwMinorVersion, 0,
-                                  info.dwBuildNumber);
-      }
-    }
-  }
-  return wpi::VersionTuple(0, 0, 0, 0);
-}
-
-/// Determines if the program is running on Windows 8 or newer. This
-/// reimplements one of the helpers in the Windows 8.1 SDK, which are intended
-/// to supercede raw calls to GetVersionEx. Old SDKs, Cygwin, and MinGW don't
-/// yet have VersionHelpers.h, so we have our own helper.
-inline bool RunningWindows8OrGreater() {
-  // Windows 8 is version 6.2, service pack 0.
-  return GetWindowsOSVersion() >= wpi::VersionTuple(6, 2, 0, 0);
-}
-
-inline bool MakeErrMsg(std::string *ErrMsg, const std::string &prefix) {
-  if (!ErrMsg)
-    return true;
-  char *buffer = NULL;
-  DWORD LastError = GetLastError();
-  DWORD R = FormatMessageA(FORMAT_MESSAGE_ALLOCATE_BUFFER |
-                               FORMAT_MESSAGE_FROM_SYSTEM |
-                               FORMAT_MESSAGE_MAX_WIDTH_MASK,
-                           NULL, LastError, 0, (LPSTR)&buffer, 1, NULL);
-  if (R)
-    *ErrMsg = prefix + ": " + buffer;
-  else
-    *ErrMsg = prefix + ": Unknown error";
-  *ErrMsg += " (0x" + wpi::utohexstr(LastError) + ")";
-
-  LocalFree(buffer);
-  return R != 0;
-}
-
-template <typename HandleTraits>
-class ScopedHandle {
-  typedef typename HandleTraits::handle_type handle_type;
-  handle_type Handle;
-
-  ScopedHandle(const ScopedHandle &other) = delete;
-  void operator=(const ScopedHandle &other) = delete;
-public:
-  ScopedHandle()
-    : Handle(HandleTraits::GetInvalid()) {}
-
-  explicit ScopedHandle(handle_type h)
-    : Handle(h) {}
-
-  ~ScopedHandle() {
-    if (HandleTraits::IsValid(Handle))
-      HandleTraits::Close(Handle);
-  }
-
-  handle_type take() {
-    handle_type t = Handle;
-    Handle = HandleTraits::GetInvalid();
-    return t;
-  }
-
-  ScopedHandle &operator=(handle_type h) {
-    if (HandleTraits::IsValid(Handle))
-      HandleTraits::Close(Handle);
-    Handle = h;
-    return *this;
-  }
-
-  // True if Handle is valid.
-  explicit operator bool() const {
-    return HandleTraits::IsValid(Handle) ? true : false;
-  }
-
-  operator handle_type() const {
-    return Handle;
-  }
-};
-
-struct CommonHandleTraits {
-  typedef HANDLE handle_type;
-
-  static handle_type GetInvalid() {
-    return INVALID_HANDLE_VALUE;
-  }
-
-  static void Close(handle_type h) {
-    ::CloseHandle(h);
-  }
-
-  static bool IsValid(handle_type h) {
-    return h != GetInvalid();
-  }
-};
-
-struct JobHandleTraits : CommonHandleTraits {
-  static handle_type GetInvalid() {
-    return NULL;
-  }
-};
-
-struct RegTraits : CommonHandleTraits {
-  typedef HKEY handle_type;
-
-  static handle_type GetInvalid() {
-    return NULL;
-  }
-
-  static void Close(handle_type h) {
-    ::RegCloseKey(h);
-  }
-
-  static bool IsValid(handle_type h) {
-    return h != GetInvalid();
-  }
-};
-
-struct FindHandleTraits : CommonHandleTraits {
-  static void Close(handle_type h) {
-    ::FindClose(h);
-  }
-};
-
-struct FileHandleTraits : CommonHandleTraits {};
-
-typedef ScopedHandle<CommonHandleTraits> ScopedCommonHandle;
-typedef ScopedHandle<FileHandleTraits>   ScopedFileHandle;
-typedef ScopedHandle<RegTraits>          ScopedRegHandle;
-typedef ScopedHandle<FindHandleTraits>   ScopedFindHandle;
-typedef ScopedHandle<JobHandleTraits>    ScopedJobHandle;
-
-template <class T>
-class SmallVectorImpl;
-
-template <class T>
-typename SmallVectorImpl<T>::const_pointer
-c_str(SmallVectorImpl<T> &str) {
-  str.push_back(0);
-  str.pop_back();
-  return str.data();
-}
-
-namespace sys {
-
-inline std::chrono::nanoseconds toDuration(FILETIME Time) {
-  ULARGE_INTEGER TimeInteger;
-  TimeInteger.LowPart = Time.dwLowDateTime;
-  TimeInteger.HighPart = Time.dwHighDateTime;
-
-  // FILETIME's are # of 100 nanosecond ticks (1/10th of a microsecond)
-  return std::chrono::nanoseconds(100 * TimeInteger.QuadPart);
-}
-
-inline TimePoint<> toTimePoint(FILETIME Time) {
-  ULARGE_INTEGER TimeInteger;
-  TimeInteger.LowPart = Time.dwLowDateTime;
-  TimeInteger.HighPart = Time.dwHighDateTime;
-
-  // Adjust for different epoch
-  TimeInteger.QuadPart -= 11644473600ll * 10000000;
-
-  // FILETIME's are # of 100 nanosecond ticks (1/10th of a microsecond)
-  return TimePoint<>(std::chrono::nanoseconds(100 * TimeInteger.QuadPart));
-}
-
-inline FILETIME toFILETIME(TimePoint<> TP) {
-  ULARGE_INTEGER TimeInteger;
-  TimeInteger.QuadPart = TP.time_since_epoch().count() / 100;
-  TimeInteger.QuadPart += 11644473600ll * 10000000;
-
-  FILETIME Time;
-  Time.dwLowDateTime = TimeInteger.LowPart;
-  Time.dwHighDateTime = TimeInteger.HighPart;
-  return Time;
-}
-
-} // end namespace sys
-} // end namespace wpi.
-
-#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/llvm/raw_os_ostream.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/llvm/raw_os_ostream.cpp
deleted file mode 100644
index 1fb6c51..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/llvm/raw_os_ostream.cpp
+++ /dev/null
@@ -1,30 +0,0 @@
-//===--- raw_os_ostream.cpp - Implement the raw_os_ostream class ----------===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-//
-// This implements support adapting raw_ostream to std::ostream.
-//
-//===----------------------------------------------------------------------===//
-
-#include "wpi/raw_os_ostream.h"
-#include <ostream>
-using namespace wpi;
-
-//===----------------------------------------------------------------------===//
-//  raw_os_ostream
-//===----------------------------------------------------------------------===//
-
-raw_os_ostream::~raw_os_ostream() {
-  flush();
-}
-
-void raw_os_ostream::write_impl(const char *Ptr, size_t Size) {
-  OS.write(Ptr, Size);
-}
-
-uint64_t raw_os_ostream::current_pos() const { return OS.tellp(); }
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/llvm/raw_ostream.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/llvm/raw_ostream.cpp
deleted file mode 100644
index 622e0bf..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/llvm/raw_ostream.cpp
+++ /dev/null
@@ -1,705 +0,0 @@
-//===--- raw_ostream.cpp - Implement the raw_ostream classes --------------===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-//
-// This implements support for bulk buffered stream output.
-//
-//===----------------------------------------------------------------------===//
-
-#ifdef _WIN32
-#define _CRT_NONSTDC_NO_WARNINGS
-#endif
-
-#include "wpi/raw_ostream.h"
-#include "wpi/SmallString.h"
-#include "wpi/SmallVector.h"
-#include "wpi/StringExtras.h"
-#include "wpi/Compiler.h"
-#include "wpi/ErrorHandling.h"
-#include "wpi/MathExtras.h"
-#include "wpi/WindowsError.h"
-#include "wpi/fs.h"
-#include <algorithm>
-#include <cctype>
-#include <cerrno>
-#include <cstdio>
-#include <iterator>
-#include <sys/stat.h>
-#include <system_error>
-
-// <fcntl.h> may provide O_BINARY.
-#include <fcntl.h>
-
-#ifndef _WIN32
-#include <unistd.h>
-#include <sys/uio.h>
-#endif
-
-#if defined(__CYGWIN__)
-#include <io.h>
-#endif
-
-#if defined(_MSC_VER)
-#include <io.h>
-#ifndef STDIN_FILENO
-# define STDIN_FILENO 0
-#endif
-#ifndef STDOUT_FILENO
-# define STDOUT_FILENO 1
-#endif
-#ifndef STDERR_FILENO
-# define STDERR_FILENO 2
-#endif
-#endif
-
-#ifdef _WIN32
-#include "wpi/ConvertUTF.h"
-#include "Windows/WindowsSupport.h"
-#endif
-
-using namespace wpi;
-
-namespace {
-// Find the length of an array.
-template <class T, std::size_t N>
-constexpr inline size_t array_lengthof(T (&)[N]) {
-  return N;
-}
-}  // namespace
-
-raw_ostream::~raw_ostream() {
-  // raw_ostream's subclasses should take care to flush the buffer
-  // in their destructors.
-  assert(OutBufCur == OutBufStart &&
-         "raw_ostream destructor called with non-empty buffer!");
-
-  if (BufferMode == InternalBuffer)
-    delete [] OutBufStart;
-}
-
-// An out of line virtual method to provide a home for the class vtable.
-void raw_ostream::handle() {}
-
-size_t raw_ostream::preferred_buffer_size() const {
-  // BUFSIZ is intended to be a reasonable default.
-  return BUFSIZ;
-}
-
-void raw_ostream::SetBuffered() {
-  // Ask the subclass to determine an appropriate buffer size.
-  if (size_t Size = preferred_buffer_size())
-    SetBufferSize(Size);
-  else
-    // It may return 0, meaning this stream should be unbuffered.
-    SetUnbuffered();
-}
-
-void raw_ostream::SetBufferAndMode(char *BufferStart, size_t Size,
-                                   BufferKind Mode) {
-  assert(((Mode == Unbuffered && !BufferStart && Size == 0) ||
-          (Mode != Unbuffered && BufferStart && Size != 0)) &&
-         "stream must be unbuffered or have at least one byte");
-  // Make sure the current buffer is free of content (we can't flush here; the
-  // child buffer management logic will be in write_impl).
-  assert(GetNumBytesInBuffer() == 0 && "Current buffer is non-empty!");
-
-  if (BufferMode == InternalBuffer)
-    delete [] OutBufStart;
-  OutBufStart = BufferStart;
-  OutBufEnd = OutBufStart+Size;
-  OutBufCur = OutBufStart;
-  BufferMode = Mode;
-
-  assert(OutBufStart <= OutBufEnd && "Invalid size!");
-}
-
-raw_ostream &raw_ostream::write_escaped(std::string_view Str,
-                                        bool UseHexEscapes) {
-  for (unsigned char c : Str) {
-    switch (c) {
-    case '\\':
-      *this << '\\' << '\\';
-      break;
-    case '\t':
-      *this << '\\' << 't';
-      break;
-    case '\n':
-      *this << '\\' << 'n';
-      break;
-    case '"':
-      *this << '\\' << '"';
-      break;
-    default:
-      if (isPrint(c)) {
-        *this << c;
-        break;
-      }
-
-      // Write out the escaped representation.
-      if (UseHexEscapes) {
-        *this << '\\' << 'x';
-        *this << hexdigit((c >> 4 & 0xF));
-        *this << hexdigit((c >> 0) & 0xF);
-      } else {
-        // Always use a full 3-character octal escape.
-        *this << '\\';
-        *this << char('0' + ((c >> 6) & 7));
-        *this << char('0' + ((c >> 3) & 7));
-        *this << char('0' + ((c >> 0) & 7));
-      }
-    }
-  }
-
-  return *this;
-}
-
-void raw_ostream::flush_nonempty() {
-  assert(OutBufCur > OutBufStart && "Invalid call to flush_nonempty.");
-  size_t Length = OutBufCur - OutBufStart;
-  OutBufCur = OutBufStart;
-  write_impl(OutBufStart, Length);
-}
-
-raw_ostream &raw_ostream::write(unsigned char C) {
-  // Group exceptional cases into a single branch.
-  if (LLVM_UNLIKELY(OutBufCur >= OutBufEnd)) {
-    if (LLVM_UNLIKELY(!OutBufStart)) {
-      if (BufferMode == Unbuffered) {
-        write_impl(reinterpret_cast<char*>(&C), 1);
-        return *this;
-      }
-      // Set up a buffer and start over.
-      SetBuffered();
-      return write(C);
-    }
-
-    flush_nonempty();
-  }
-
-  *OutBufCur++ = C;
-  return *this;
-}
-
-raw_ostream &raw_ostream::write(const char *Ptr, size_t Size) {
-  // Group exceptional cases into a single branch.
-  if (LLVM_UNLIKELY(size_t(OutBufEnd - OutBufCur) < Size)) {
-    if (LLVM_UNLIKELY(!OutBufStart)) {
-      if (BufferMode == Unbuffered) {
-        write_impl(Ptr, Size);
-        return *this;
-      }
-      // Set up a buffer and start over.
-      SetBuffered();
-      return write(Ptr, Size);
-    }
-
-    size_t NumBytes = OutBufEnd - OutBufCur;
-
-    // If the buffer is empty at this point we have a string that is larger
-    // than the buffer. Directly write the chunk that is a multiple of the
-    // preferred buffer size and put the remainder in the buffer.
-    if (LLVM_UNLIKELY(OutBufCur == OutBufStart)) {
-      assert(NumBytes != 0 && "undefined behavior");
-      size_t BytesToWrite = Size - (Size % NumBytes);
-      write_impl(Ptr, BytesToWrite);
-      size_t BytesRemaining = Size - BytesToWrite;
-      if (BytesRemaining > size_t(OutBufEnd - OutBufCur)) {
-        // Too much left over to copy into our buffer.
-        return write(Ptr + BytesToWrite, BytesRemaining);
-      }
-      copy_to_buffer(Ptr + BytesToWrite, BytesRemaining);
-      return *this;
-    }
-
-    // We don't have enough space in the buffer to fit the string in. Insert as
-    // much as possible, flush and start over with the remainder.
-    copy_to_buffer(Ptr, NumBytes);
-    flush_nonempty();
-    return write(Ptr + NumBytes, Size - NumBytes);
-  }
-
-  copy_to_buffer(Ptr, Size);
-
-  return *this;
-}
-
-void raw_ostream::copy_to_buffer(const char *Ptr, size_t Size) {
-  assert(Size <= size_t(OutBufEnd - OutBufCur) && "Buffer overrun!");
-
-  // Handle short strings specially, memcpy isn't very good at very short
-  // strings.
-  switch (Size) {
-  case 4: OutBufCur[3] = Ptr[3]; LLVM_FALLTHROUGH;
-  case 3: OutBufCur[2] = Ptr[2]; LLVM_FALLTHROUGH;
-  case 2: OutBufCur[1] = Ptr[1]; LLVM_FALLTHROUGH;
-  case 1: OutBufCur[0] = Ptr[0]; LLVM_FALLTHROUGH;
-  case 0: break;
-  default:
-    memcpy(OutBufCur, Ptr, Size);
-    break;
-  }
-
-  OutBufCur += Size;
-}
-
-template <char C>
-static raw_ostream &write_padding(raw_ostream &OS, unsigned NumChars) {
-  static const char Chars[] = {C, C, C, C, C, C, C, C, C, C, C, C, C, C, C, C,
-                               C, C, C, C, C, C, C, C, C, C, C, C, C, C, C, C,
-                               C, C, C, C, C, C, C, C, C, C, C, C, C, C, C, C,
-                               C, C, C, C, C, C, C, C, C, C, C, C, C, C, C, C,
-                               C, C, C, C, C, C, C, C, C, C, C, C, C, C, C, C};
-
-  // Usually the indentation is small, handle it with a fastpath.
-  if (NumChars < array_lengthof(Chars))
-    return OS.write(Chars, NumChars);
-
-  while (NumChars) {
-    unsigned NumToWrite = std::min(NumChars,
-                                   (unsigned)array_lengthof(Chars)-1);
-    OS.write(Chars, NumToWrite);
-    NumChars -= NumToWrite;
-  }
-  return OS;
-}
-
-/// indent - Insert 'NumSpaces' spaces.
-raw_ostream &raw_ostream::indent(unsigned NumSpaces) {
-  return write_padding<' '>(*this, NumSpaces);
-}
-
-/// write_zeros - Insert 'NumZeros' nulls.
-raw_ostream &raw_ostream::write_zeros(unsigned NumZeros) {
-  return write_padding<'\0'>(*this, NumZeros);
-}
-
-void raw_ostream::anchor() {}
-
-//===----------------------------------------------------------------------===//
-//  raw_fd_ostream
-//===----------------------------------------------------------------------===//
-
-static int getFD(std::string_view Filename, std::error_code &EC,
-                 fs::CreationDisposition Disp, fs::FileAccess Access,
-                 fs::OpenFlags Flags) {
-  assert((Access & fs::FA_Write) &&
-         "Cannot make a raw_ostream from a read-only descriptor!");
-
-  // Handle "-" as stdout. Note that when we do this, we consider ourself
-  // the owner of stdout and may set the "binary" flag globally based on Flags.
-  if (Filename == "-") {
-    EC = std::error_code();
-    // If user requested binary then put stdout into binary mode if
-    // possible.
-    if (!(Flags & fs::OF_Text)) {
-#if defined(_WIN32)
-      _setmode(_fileno(stdout), _O_BINARY);
-#endif
-    }
-    return STDOUT_FILENO;
-  }
-
-  fs::file_t F;
-  if (Access & fs::FA_Read) {
-    F = fs::OpenFileForReadWrite(fs::path{std::string_view{Filename.data(), Filename.size()}}, EC, Disp, Flags);
-  } else {
-    F = fs::OpenFileForWrite(fs::path{std::string_view{Filename.data(), Filename.size()}}, EC, Disp, Flags);
-  }
-  if (EC)
-    return -1;
-  int FD = fs::FileToFd(F, EC, Flags);
-  if (EC)
-    return -1;
-
-  return FD;
-}
-
-raw_fd_ostream::raw_fd_ostream(std::string_view Filename, std::error_code &EC)
-    : raw_fd_ostream(Filename, EC, fs::CD_CreateAlways, fs::FA_Write,
-                     fs::OF_None) {}
-
-raw_fd_ostream::raw_fd_ostream(std::string_view Filename, std::error_code &EC,
-                               fs::CreationDisposition Disp)
-    : raw_fd_ostream(Filename, EC, Disp, fs::FA_Write, fs::OF_None) {}
-
-raw_fd_ostream::raw_fd_ostream(std::string_view Filename, std::error_code &EC,
-                               fs::FileAccess Access)
-    : raw_fd_ostream(Filename, EC, fs::CD_CreateAlways, Access,
-                     fs::OF_None) {}
-
-raw_fd_ostream::raw_fd_ostream(std::string_view Filename, std::error_code &EC,
-                               fs::OpenFlags Flags)
-    : raw_fd_ostream(Filename, EC, fs::CD_CreateAlways, fs::FA_Write,
-                     Flags) {}
-
-raw_fd_ostream::raw_fd_ostream(std::string_view Filename, std::error_code &EC,
-                               fs::CreationDisposition Disp,
-                               fs::FileAccess Access,
-                               fs::OpenFlags Flags)
-    : raw_fd_ostream(getFD(Filename, EC, Disp, Access, Flags), true) {}
-
-/// FD is the file descriptor that this writes to.  If ShouldClose is true, this
-/// closes the file when the stream is destroyed.
-raw_fd_ostream::raw_fd_ostream(int fd, bool shouldClose, bool unbuffered)
-    : raw_pwrite_stream(unbuffered), FD(fd), ShouldClose(shouldClose) {
-  if (FD < 0 ) {
-    ShouldClose = false;
-    return;
-  }
-
-  // Do not attempt to close stdout or stderr. We used to try to maintain the
-  // property that tools that support writing file to stdout should not also
-  // write informational output to stdout, but in practice we were never able to
-  // maintain this invariant. Many features have been added to LLVM and clang
-  // (-fdump-record-layouts, optimization remarks, etc) that print to stdout, so
-  // users must simply be aware that mixed output and remarks is a possibility.
-  if (FD <= STDERR_FILENO)
-    ShouldClose = false;
-
-#ifdef _WIN32
-  // Check if this is a console device. This is not equivalent to isatty.
-  IsWindowsConsole =
-      ::GetFileType((HANDLE)::_get_osfhandle(fd)) == FILE_TYPE_CHAR;
-#endif
-
-  // Get the starting position.
-  off_t loc = ::lseek(FD, 0, SEEK_CUR);
-#ifdef _WIN32
-  // MSVCRT's _lseek(SEEK_CUR) doesn't return -1 for pipes.
-  SupportsSeeking = loc != (off_t)-1 && ::GetFileType(reinterpret_cast<HANDLE>(::_get_osfhandle(FD))) != FILE_TYPE_PIPE;
-#else
-  SupportsSeeking = loc != (off_t)-1;
-#endif
-  if (!SupportsSeeking)
-    pos = 0;
-  else
-    pos = static_cast<uint64_t>(loc);
-}
-
-raw_fd_ostream::~raw_fd_ostream() {
-  if (FD >= 0) {
-    flush();
-    if (ShouldClose && ::close(FD) < 0)
-      error_detected(std::error_code(errno, std::generic_category()));
-  }
-
-#ifdef __MINGW32__
-  // On mingw, global dtors should not call exit().
-  // report_fatal_error() invokes exit(). We know report_fatal_error()
-  // might not write messages to stderr when any errors were detected
-  // on FD == 2.
-  if (FD == 2) return;
-#endif
-
-  // If there are any pending errors, report them now. Clients wishing
-  // to avoid report_fatal_error calls should check for errors with
-  // has_error() and clear the error flag with clear_error() before
-  // destructing raw_ostream objects which may have errors.
-  if (has_error())
-    report_fatal_error("IO failure on output stream: " + error().message(),
-                       /*GenCrashDiag=*/false);
-}
-
-#if defined(_WIN32)
-// The most reliable way to print unicode in a Windows console is with
-// WriteConsoleW. To use that, first transcode from UTF-8 to UTF-16. This
-// assumes that LLVM programs always print valid UTF-8 to the console. The data
-// might not be UTF-8 for two major reasons:
-// 1. The program is printing binary (-filetype=obj -o -), in which case it
-// would have been gibberish anyway.
-// 2. The program is printing text in a semi-ascii compatible codepage like
-// shift-jis or cp1252.
-//
-// Most LLVM programs don't produce non-ascii text unless they are quoting
-// user source input. A well-behaved LLVM program should either validate that
-// the input is UTF-8 or transcode from the local codepage to UTF-8 before
-// quoting it. If they don't, this may mess up the encoding, but this is still
-// probably the best compromise we can make.
-static bool write_console_impl(int FD, std::string_view Data) {
-  SmallVector<wchar_t, 256> WideText;
-
-  // Fall back to ::write if it wasn't valid UTF-8.
-  if (auto EC = sys::windows::UTF8ToUTF16(Data, WideText))
-    return false;
-
-  // On Windows 7 and earlier, WriteConsoleW has a low maximum amount of data
-  // that can be written to the console at a time.
-  size_t MaxWriteSize = WideText.size();
-  if (!RunningWindows8OrGreater())
-    MaxWriteSize = 32767;
-
-  size_t WCharsWritten = 0;
-  do {
-    size_t WCharsToWrite =
-        std::min(MaxWriteSize, WideText.size() - WCharsWritten);
-    DWORD ActuallyWritten;
-    bool Success =
-        ::WriteConsoleW((HANDLE)::_get_osfhandle(FD), &WideText[WCharsWritten],
-                        WCharsToWrite, &ActuallyWritten,
-                        /*Reserved=*/nullptr);
-
-    // The most likely reason for WriteConsoleW to fail is that FD no longer
-    // points to a console. Fall back to ::write. If this isn't the first loop
-    // iteration, something is truly wrong.
-    if (!Success)
-      return false;
-
-    WCharsWritten += ActuallyWritten;
-  } while (WCharsWritten != WideText.size());
-  return true;
-}
-#endif
-
-void raw_fd_ostream::write_impl(const char *Ptr, size_t Size) {
-  assert(FD >= 0 && "File already closed.");
-  pos += Size;
-
-#if defined(_WIN32)
-  // If this is a Windows console device, try re-encoding from UTF-8 to UTF-16
-  // and using WriteConsoleW. If that fails, fall back to plain write().
-  if (IsWindowsConsole)
-    if (write_console_impl(FD, std::string_view(Ptr, Size)))
-      return;
-#endif
-
-  // The maximum write size is limited to INT32_MAX. A write
-  // greater than SSIZE_MAX is implementation-defined in POSIX,
-  // and Windows _write requires 32 bit input.
-  size_t MaxWriteSize = INT32_MAX;
-
-#if defined(__linux__)
-  // It is observed that Linux returns EINVAL for a very large write (>2G).
-  // Make it a reasonably small value.
-  MaxWriteSize = 1024 * 1024 * 1024;
-#endif
-
-  do {
-    size_t ChunkSize = std::min(Size, MaxWriteSize);
-#ifdef _WIN32
-    int ret = ::_write(FD, Ptr, ChunkSize);
-#else
-    ssize_t ret = ::write(FD, Ptr, ChunkSize);
-#endif
-
-    if (ret < 0) {
-      // If it's a recoverable error, swallow it and retry the write.
-      //
-      // Ideally we wouldn't ever see EAGAIN or EWOULDBLOCK here, since
-      // raw_ostream isn't designed to do non-blocking I/O. However, some
-      // programs, such as old versions of bjam, have mistakenly used
-      // O_NONBLOCK. For compatibility, emulate blocking semantics by
-      // spinning until the write succeeds. If you don't want spinning,
-      // don't use O_NONBLOCK file descriptors with raw_ostream.
-      if (errno == EINTR || errno == EAGAIN
-#ifdef EWOULDBLOCK
-          || errno == EWOULDBLOCK
-#endif
-          )
-        continue;
-
-      // Otherwise it's a non-recoverable error. Note it and quit.
-      error_detected(std::error_code(errno, std::generic_category()));
-      break;
-    }
-
-    // The write may have written some or all of the data. Update the
-    // size and buffer pointer to reflect the remainder that needs
-    // to be written. If there are no bytes left, we're done.
-    Ptr += ret;
-    Size -= ret;
-  } while (Size > 0);
-}
-
-void raw_fd_ostream::close() {
-  assert(ShouldClose);
-  ShouldClose = false;
-  flush();
-  if (::close(FD) < 0)
-    error_detected(std::error_code(errno, std::generic_category()));
-  FD = -1;
-}
-
-uint64_t raw_fd_ostream::seek(uint64_t off) {
-  assert(SupportsSeeking && "Stream does not support seeking!");
-  flush();
-#ifdef _WIN32
-  pos = ::_lseeki64(FD, off, SEEK_SET);
-#else
-  pos = ::lseek(FD, off, SEEK_SET);
-#endif
-  if (pos == (uint64_t)-1)
-    error_detected(std::error_code(errno, std::generic_category()));
-  return pos;
-}
-
-void raw_fd_ostream::pwrite_impl(const char *Ptr, size_t Size,
-                                 uint64_t Offset) {
-  uint64_t Pos = tell();
-  seek(Offset);
-  write(Ptr, Size);
-  seek(Pos);
-}
-
-size_t raw_fd_ostream::preferred_buffer_size() const {
-#if defined(_WIN32)
-  // Disable buffering for console devices. Console output is re-encoded from
-  // UTF-8 to UTF-16 on Windows, and buffering it would require us to split the
-  // buffer on a valid UTF-8 codepoint boundary. Terminal buffering is disabled
-  // below on most other OSs, so do the same thing on Windows and avoid that
-  // complexity.
-  if (IsWindowsConsole)
-    return 0;
-  return raw_ostream::preferred_buffer_size();
-#elif !defined(__minix)
-  // Minix has no st_blksize.
-  assert(FD >= 0 && "File not yet open!");
-  struct stat statbuf;
-  if (fstat(FD, &statbuf) != 0)
-    return 0;
-
-  // If this is a terminal, don't use buffering. Line buffering
-  // would be a more traditional thing to do, but it's not worth
-  // the complexity.
-  if (S_ISCHR(statbuf.st_mode) && isatty(FD))
-    return 0;
-  // Return the preferred block size.
-  return statbuf.st_blksize;
-#else
-  return raw_ostream::preferred_buffer_size();
-#endif
-}
-
-void raw_fd_ostream::anchor() {}
-
-//===----------------------------------------------------------------------===//
-//  outs(), errs(), nulls()
-//===----------------------------------------------------------------------===//
-
-/// outs() - This returns a reference to a raw_ostream for standard output.
-/// Use it like: outs() << "foo" << "bar";
-raw_ostream &wpi::outs() {
-  // Set buffer settings to model stdout behavior.
-  std::error_code EC;
-  static raw_fd_ostream* S = new raw_fd_ostream("-", EC, fs::F_None);
-  assert(!EC);
-  return *S;
-}
-
-/// errs() - This returns a reference to a raw_ostream for standard error.
-/// Use it like: errs() << "foo" << "bar";
-raw_ostream &wpi::errs() {
-  // Set standard error to be unbuffered by default.
-  static raw_fd_ostream* S = new raw_fd_ostream(STDERR_FILENO, false, true);
-  return *S;
-}
-
-/// nulls() - This returns a reference to a raw_ostream which discards output.
-raw_ostream &wpi::nulls() {
-  static raw_null_ostream* S = new raw_null_ostream;
-  return *S;
-}
-
-//===----------------------------------------------------------------------===//
-//  raw_string_ostream
-//===----------------------------------------------------------------------===//
-
-raw_string_ostream::~raw_string_ostream() {
-  flush();
-}
-
-void raw_string_ostream::write_impl(const char *Ptr, size_t Size) {
-  OS.append(Ptr, Size);
-}
-
-//===----------------------------------------------------------------------===//
-//  raw_svector_ostream
-//===----------------------------------------------------------------------===//
-
-uint64_t raw_svector_ostream::current_pos() const { return OS.size(); }
-
-void raw_svector_ostream::write_impl(const char *Ptr, size_t Size) {
-  OS.append(Ptr, Ptr + Size);
-}
-
-void raw_svector_ostream::pwrite_impl(const char *Ptr, size_t Size,
-                                      uint64_t Offset) {
-  memcpy(OS.data() + Offset, Ptr, Size);
-}
-
-//===----------------------------------------------------------------------===//
-//  raw_vector_ostream
-//===----------------------------------------------------------------------===//
-
-uint64_t raw_vector_ostream::current_pos() const { return OS.size(); }
-
-void raw_vector_ostream::write_impl(const char *Ptr, size_t Size) {
-  OS.insert(OS.end(), Ptr, Ptr + Size);
-}
-
-void raw_vector_ostream::pwrite_impl(const char *Ptr, size_t Size,
-                                     uint64_t Offset) {
-  memcpy(OS.data() + Offset, Ptr, Size);
-}
-
-//===----------------------------------------------------------------------===//
-//  raw_usvector_ostream
-//===----------------------------------------------------------------------===//
-
-uint64_t raw_usvector_ostream::current_pos() const { return OS.size(); }
-
-void raw_usvector_ostream::write_impl(const char *Ptr, size_t Size) {
-  OS.append(reinterpret_cast<const uint8_t *>(Ptr),
-            reinterpret_cast<const uint8_t *>(Ptr) + Size);
-}
-
-void raw_usvector_ostream::pwrite_impl(const char *Ptr, size_t Size,
-                                       uint64_t Offset) {
-  memcpy(OS.data() + Offset, Ptr, Size);
-}
-
-//===----------------------------------------------------------------------===//
-//  raw_uvector_ostream
-//===----------------------------------------------------------------------===//
-
-uint64_t raw_uvector_ostream::current_pos() const { return OS.size(); }
-
-void raw_uvector_ostream::write_impl(const char *Ptr, size_t Size) {
-  OS.insert(OS.end(), reinterpret_cast<const uint8_t *>(Ptr),
-            reinterpret_cast<const uint8_t *>(Ptr) + Size);
-}
-
-void raw_uvector_ostream::pwrite_impl(const char *Ptr, size_t Size,
-                                      uint64_t Offset) {
-  memcpy(OS.data() + Offset, Ptr, Size);
-}
-
-//===----------------------------------------------------------------------===//
-//  raw_null_ostream
-//===----------------------------------------------------------------------===//
-
-raw_null_ostream::~raw_null_ostream() {
-#ifndef NDEBUG
-  // ~raw_ostream asserts that the buffer is empty. This isn't necessary
-  // with raw_null_ostream, but it's better to have raw_null_ostream follow
-  // the rules than to change the rules just for raw_null_ostream.
-  flush();
-#endif
-}
-
-void raw_null_ostream::write_impl(const char * /*Ptr*/, size_t /*Size*/) {}
-
-uint64_t raw_null_ostream::current_pos() const {
-  return 0;
-}
-
-void raw_null_ostream::pwrite_impl(const char * /*Ptr*/, size_t /*Size*/,
-                                   uint64_t /*Offset*/) {}
-
-void raw_pwrite_stream::anchor() {}
-
-void buffer_ostream::anchor() {}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/mpack.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/mpack.cpp
deleted file mode 100644
index fbcb6a4..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/mpack.cpp
+++ /dev/null
@@ -1,7251 +0,0 @@
-/**
- * The MIT License (MIT)
- * 
- * Copyright (c) 2015-2021 Nicholas Fraser and the MPack authors
- * 
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- * 
- * The above copyright notice and this permission notice shall be included in all
- * copies or substantial portions of the Software.
- * 
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
- * SOFTWARE.
- * 
- */
-
-/*
- * This is the MPack 1.1 amalgamation package.
- *
- * http://github.com/ludocode/mpack
- */
-
-#define MPACK_INTERNAL 1
-#define MPACK_EMIT_INLINE_DEFS 0
-
-#include "wpi/mpack.h"
-
-
-/* mpack/mpack-platform.c.c */
-
-
-// We define MPACK_EMIT_INLINE_DEFS and include mpack.h to emit
-// standalone definitions of all (non-static) inline functions in MPack.
-
-#define MPACK_INTERNAL 1
-#define MPACK_EMIT_INLINE_DEFS 0
-
-/* #include "mpack-platform.h" */
-/* #include "mpack.h" */
-
-MPACK_SILENCE_WARNINGS_BEGIN
-namespace mpack {
-
-#if MPACK_DEBUG
-
-#if MPACK_STDIO
-void mpack_assert_fail_format(const char* format, ...) {
-    char buffer[512];
-    va_list args;
-    va_start(args, format);
-    vsnprintf(buffer, sizeof(buffer), format, args);
-    va_end(args);
-    buffer[sizeof(buffer) - 1] = 0;
-    mpack_assert_fail_wrapper(buffer);
-}
-
-void mpack_break_hit_format(const char* format, ...) {
-    char buffer[512];
-    va_list args;
-    va_start(args, format);
-    vsnprintf(buffer, sizeof(buffer), format, args);
-    va_end(args);
-    buffer[sizeof(buffer) - 1] = 0;
-    mpack_break_hit(buffer);
-}
-#endif
-
-#if !MPACK_CUSTOM_ASSERT
-void mpack_assert_fail(const char* message) {
-    MPACK_UNUSED(message);
-
-    #if MPACK_STDIO
-    fprintf(stderr, "%s\n", message);
-    #endif
-}
-#endif
-
-// We split the assert failure from the wrapper so that a
-// custom assert function can return.
-void mpack_assert_fail_wrapper(const char* message) {
-
-    #ifdef MPACK_GCOV
-    // gcov marks even __builtin_unreachable() as an uncovered line. this
-    // silences it.
-    (mpack_assert_fail(message), __builtin_unreachable());
-
-    #else
-    mpack_assert_fail(message);
-
-    // mpack_assert_fail() is not supposed to return. in case it does, we
-    // abort.
-
-    #if !MPACK_NO_BUILTINS
-    #if defined(__GNUC__) || defined(__clang__)
-    __builtin_trap();
-    #elif defined(WIN32)
-    __debugbreak();
-    #endif
-    #endif
-
-    #if (defined(__GNUC__) || defined(__clang__)) && !MPACK_NO_BUILTINS
-    __builtin_abort();
-    #elif MPACK_STDLIB
-    abort();
-    #endif
-
-    MPACK_UNREACHABLE;
-    #endif
-}
-
-#if !MPACK_CUSTOM_BREAK
-
-// If we have a custom assert handler, break wraps it by default.
-// This allows users of MPack to only implement mpack_assert_fail() without
-// having to worry about the difference between assert and break.
-//
-// MPACK_CUSTOM_BREAK is available to define a separate break handler
-// (which is needed by the unit test suite), but this is not offered in
-// mpack-config.h for simplicity.
-
-#if MPACK_CUSTOM_ASSERT
-void mpack_break_hit(const char* message) {
-    mpack_assert_fail_wrapper(message);
-}
-#else
-void mpack_break_hit(const char* message) {
-    MPACK_UNUSED(message);
-
-    #if MPACK_STDIO
-    fprintf(stderr, "%s\n", message);
-    #endif
-
-    #if defined(__GNUC__) || defined(__clang__) && !MPACK_NO_BUILTINS
-    __builtin_trap();
-    #elif defined(WIN32) && !MPACK_NO_BUILTINS
-    __debugbreak();
-    #elif MPACK_STDLIB
-    abort();
-    #endif
-}
-#endif
-
-#endif
-
-#endif
-
-
-
-// The below are adapted from the C wikibook:
-//     https://en.wikibooks.org/wiki/C_Programming/Strings
-
-#ifndef mpack_memcmp
-int mpack_memcmp(const void* s1, const void* s2, size_t n) {
-     const unsigned char *us1 = (const unsigned char *) s1;
-     const unsigned char *us2 = (const unsigned char *) s2;
-     while (n-- != 0) {
-         if (*us1 != *us2)
-             return (*us1 < *us2) ? -1 : +1;
-         us1++;
-         us2++;
-     }
-     return 0;
-}
-#endif
-
-#ifndef mpack_memcpy
-void* mpack_memcpy(void* MPACK_RESTRICT s1, const void* MPACK_RESTRICT s2, size_t n) {
-    char* MPACK_RESTRICT dst = (char *)s1;
-    const char* MPACK_RESTRICT src = (const char *)s2;
-    while (n-- != 0)
-        *dst++ = *src++;
-    return s1;
-}
-#endif
-
-#ifndef mpack_memmove
-void* mpack_memmove(void* s1, const void* s2, size_t n) {
-    char *p1 = (char *)s1;
-    const char *p2 = (const char *)s2;
-    if (p2 < p1 && p1 < p2 + n) {
-        p2 += n;
-        p1 += n;
-        while (n-- != 0)
-            *--p1 = *--p2;
-    } else
-        while (n-- != 0)
-            *p1++ = *p2++;
-    return s1;
-}
-#endif
-
-#ifndef mpack_memset
-void* mpack_memset(void* s, int c, size_t n) {
-    unsigned char *us = (unsigned char *)s;
-    unsigned char uc = (unsigned char)c;
-    while (n-- != 0)
-        *us++ = uc;
-    return s;
-}
-#endif
-
-#ifndef mpack_strlen
-size_t mpack_strlen(const char* s) {
-    const char* p = s;
-    while (*p != '\0')
-        p++;
-    return (size_t)(p - s);
-}
-#endif
-
-
-
-#if defined(MPACK_MALLOC) && !defined(MPACK_REALLOC)
-void* mpack_realloc(void* old_ptr, size_t used_size, size_t new_size) {
-    if (new_size == 0) {
-        if (old_ptr)
-            MPACK_FREE(old_ptr);
-        return NULL;
-    }
-
-    void* new_ptr = MPACK_MALLOC(new_size);
-    if (new_ptr == NULL)
-        return NULL;
-
-    mpack_memcpy(new_ptr, old_ptr, used_size);
-    MPACK_FREE(old_ptr);
-    return new_ptr;
-}
-#endif
-
-MPACK_SILENCE_WARNINGS_END
-
-/* mpack/mpack-common.c.c */
-
-#define MPACK_INTERNAL 1
-
-/* #include "mpack-common.h" */
-
-MPACK_SILENCE_WARNINGS_BEGIN
-
-const char* mpack_error_to_string(mpack_error_t error) {
-    #if MPACK_STRINGS
-    switch (error) {
-        #define MPACK_ERROR_STRING_CASE(e) case e: return #e
-        MPACK_ERROR_STRING_CASE(mpack_ok);
-        MPACK_ERROR_STRING_CASE(mpack_error_io);
-        MPACK_ERROR_STRING_CASE(mpack_error_invalid);
-        MPACK_ERROR_STRING_CASE(mpack_error_unsupported);
-        MPACK_ERROR_STRING_CASE(mpack_error_type);
-        MPACK_ERROR_STRING_CASE(mpack_error_too_big);
-        MPACK_ERROR_STRING_CASE(mpack_error_memory);
-        MPACK_ERROR_STRING_CASE(mpack_error_bug);
-        MPACK_ERROR_STRING_CASE(mpack_error_data);
-        MPACK_ERROR_STRING_CASE(mpack_error_eof);
-        #undef MPACK_ERROR_STRING_CASE
-    }
-    mpack_assert(0, "unrecognized error %i", (int)error);
-    return "(unknown mpack_error_t)";
-    #else
-    MPACK_UNUSED(error);
-    return "";
-    #endif
-}
-
-const char* mpack_type_to_string(mpack_type_t type) {
-    #if MPACK_STRINGS
-    switch (type) {
-        #define MPACK_TYPE_STRING_CASE(e) case e: return #e
-        MPACK_TYPE_STRING_CASE(mpack_type_missing);
-        MPACK_TYPE_STRING_CASE(mpack_type_nil);
-        MPACK_TYPE_STRING_CASE(mpack_type_bool);
-        MPACK_TYPE_STRING_CASE(mpack_type_float);
-        MPACK_TYPE_STRING_CASE(mpack_type_double);
-        MPACK_TYPE_STRING_CASE(mpack_type_int);
-        MPACK_TYPE_STRING_CASE(mpack_type_uint);
-        MPACK_TYPE_STRING_CASE(mpack_type_str);
-        MPACK_TYPE_STRING_CASE(mpack_type_bin);
-        MPACK_TYPE_STRING_CASE(mpack_type_array);
-        MPACK_TYPE_STRING_CASE(mpack_type_map);
-        #if MPACK_EXTENSIONS
-        MPACK_TYPE_STRING_CASE(mpack_type_ext);
-        #endif
-        #undef MPACK_TYPE_STRING_CASE
-    }
-    mpack_assert(0, "unrecognized type %i", (int)type);
-    return "(unknown mpack_type_t)";
-    #else
-    MPACK_UNUSED(type);
-    return "";
-    #endif
-}
-
-int mpack_tag_cmp(mpack_tag_t left, mpack_tag_t right) {
-
-    // positive numbers may be stored as int; convert to uint
-    if (left.type == mpack_type_int && left.v.i >= 0) {
-        left.type = mpack_type_uint;
-        left.v.u = (uint64_t)left.v.i;
-    }
-    if (right.type == mpack_type_int && right.v.i >= 0) {
-        right.type = mpack_type_uint;
-        right.v.u = (uint64_t)right.v.i;
-    }
-
-    if (left.type != right.type)
-        return ((int)left.type < (int)right.type) ? -1 : 1;
-
-    switch (left.type) {
-        case mpack_type_missing: // fallthrough
-        case mpack_type_nil:
-            return 0;
-
-        case mpack_type_bool:
-            return (int)left.v.b - (int)right.v.b;
-
-        case mpack_type_int:
-            if (left.v.i == right.v.i)
-                return 0;
-            return (left.v.i < right.v.i) ? -1 : 1;
-
-        case mpack_type_uint:
-            if (left.v.u == right.v.u)
-                return 0;
-            return (left.v.u < right.v.u) ? -1 : 1;
-
-        case mpack_type_array:
-        case mpack_type_map:
-            if (left.v.n == right.v.n)
-                return 0;
-            return (left.v.n < right.v.n) ? -1 : 1;
-
-        case mpack_type_str:
-        case mpack_type_bin:
-            if (left.v.l == right.v.l)
-                return 0;
-            return (left.v.l < right.v.l) ? -1 : 1;
-
-        #if MPACK_EXTENSIONS
-        case mpack_type_ext:
-            if (left.exttype == right.exttype) {
-                if (left.v.l == right.v.l)
-                    return 0;
-                return (left.v.l < right.v.l) ? -1 : 1;
-            }
-            return (int)left.exttype - (int)right.exttype;
-        #endif
-
-        // floats should not normally be compared for equality. we compare
-        // with memcmp() to silence compiler warnings, but this will return
-        // equal if both are NaNs with the same representation (though we may
-        // want this, for instance if you are for some bizarre reason using
-        // floats as map keys.) i'm not sure what the right thing to
-        // do is here. check for NaN first? always return false if the type
-        // is float? use operator== and pragmas to silence compiler warning?
-        // please send me your suggestions.
-        // note also that we don't convert floats to doubles, so when this is
-        // used for ordering purposes, all floats are ordered before all
-        // doubles.
-        case mpack_type_float:
-            return mpack_memcmp(&left.v.f, &right.v.f, sizeof(left.v.f));
-        case mpack_type_double:
-            return mpack_memcmp(&left.v.d, &right.v.d, sizeof(left.v.d));
-    }
-
-    mpack_assert(0, "unrecognized type %i", (int)left.type);
-    return false;
-}
-
-#if MPACK_DEBUG && MPACK_STDIO
-static char mpack_hex_char(uint8_t hex_value) {
-    // Older compilers (e.g. GCC 4.4.7) promote the result of this ternary to
-    // int and warn under -Wconversion, so we have to cast it back to char.
-    return (char)((hex_value < 10) ? (char)('0' + hex_value) : (char)('a' + (hex_value - 10)));
-}
-
-static void mpack_tag_debug_complete_bin_ext(mpack_tag_t tag, size_t string_length, char* buffer, size_t buffer_size,
-        const char* prefix, size_t prefix_size)
-{
-    // If at any point in this function we run out of space in the buffer, we
-    // bail out. The outer tag print wrapper will make sure we have a
-    // null-terminator.
-
-    if (string_length == 0 || string_length >= buffer_size)
-        return;
-    buffer += string_length;
-    buffer_size -= string_length;
-
-    size_t total = mpack_tag_bytes(&tag);
-    if (total == 0) {
-        strncpy(buffer, ">", buffer_size);
-        return;
-    }
-
-    strncpy(buffer, ": ", buffer_size);
-    if (buffer_size < 2)
-        return;
-    buffer += 2;
-    buffer_size -= 2;
-
-    size_t hex_bytes = 0;
-    size_t i;
-    for (i = 0; i < MPACK_PRINT_BYTE_COUNT && i < prefix_size && buffer_size > 2; ++i) {
-        uint8_t byte = (uint8_t)prefix[i];
-        buffer[0] = mpack_hex_char((uint8_t)(byte >> 4));
-        buffer[1] = mpack_hex_char((uint8_t)(byte & 0xfu));
-        buffer += 2;
-        buffer_size -= 2;
-        ++hex_bytes;
-    }
-
-    if (buffer_size != 0)
-        mpack_snprintf(buffer, buffer_size, "%s>", (total > hex_bytes) ? "..." : "");
-}
-
-static void mpack_tag_debug_pseudo_json_bin(mpack_tag_t tag, char* buffer, size_t buffer_size,
-        const char* prefix, size_t prefix_size)
-{
-    mpack_assert(mpack_tag_type(&tag) == mpack_type_bin);
-    size_t length = (size_t)mpack_snprintf(buffer, buffer_size, "<binary data of length %u", tag.v.l);
-    mpack_tag_debug_complete_bin_ext(tag, length, buffer, buffer_size, prefix, prefix_size);
-}
-
-#if MPACK_EXTENSIONS
-static void mpack_tag_debug_pseudo_json_ext(mpack_tag_t tag, char* buffer, size_t buffer_size,
-        const char* prefix, size_t prefix_size)
-{
-    mpack_assert(mpack_tag_type(&tag) == mpack_type_ext);
-    size_t length = (size_t)mpack_snprintf(buffer, buffer_size, "<ext data of type %i and length %u",
-            mpack_tag_ext_exttype(&tag), mpack_tag_ext_length(&tag));
-    mpack_tag_debug_complete_bin_ext(tag, length, buffer, buffer_size, prefix, prefix_size);
-}
-#endif
-
-static void mpack_tag_debug_pseudo_json_impl(mpack_tag_t tag, char* buffer, size_t buffer_size,
-        const char* prefix, size_t prefix_size)
-{
-    switch (tag.type) {
-        case mpack_type_missing:
-            mpack_snprintf(buffer, buffer_size, "<missing!>");
-            return;
-        case mpack_type_nil:
-            mpack_snprintf(buffer, buffer_size, "null");
-            return;
-        case mpack_type_bool:
-            mpack_snprintf(buffer, buffer_size, tag.v.b ? "true" : "false");
-            return;
-        case mpack_type_int:
-            mpack_snprintf(buffer, buffer_size, "%" PRIi64, tag.v.i);
-            return;
-        case mpack_type_uint:
-            mpack_snprintf(buffer, buffer_size, "%" PRIu64, tag.v.u);
-            return;
-        case mpack_type_float:
-            #if MPACK_FLOAT
-            mpack_snprintf(buffer, buffer_size, "%f", tag.v.f);
-            #else
-            mpack_snprintf(buffer, buffer_size, "<float>");
-            #endif
-            return;
-        case mpack_type_double:
-            #if MPACK_DOUBLE
-            mpack_snprintf(buffer, buffer_size, "%f", tag.v.d);
-            #else
-            mpack_snprintf(buffer, buffer_size, "<double>");
-            #endif
-            return;
-
-        case mpack_type_str:
-            mpack_snprintf(buffer, buffer_size, "<string of %u bytes>", tag.v.l);
-            return;
-        case mpack_type_bin:
-            mpack_tag_debug_pseudo_json_bin(tag, buffer, buffer_size, prefix, prefix_size);
-            return;
-        #if MPACK_EXTENSIONS
-        case mpack_type_ext:
-            mpack_tag_debug_pseudo_json_ext(tag, buffer, buffer_size, prefix, prefix_size);
-            return;
-        #endif
-
-        case mpack_type_array:
-            mpack_snprintf(buffer, buffer_size, "<array of %u elements>", tag.v.n);
-            return;
-        case mpack_type_map:
-            mpack_snprintf(buffer, buffer_size, "<map of %u key-value pairs>", tag.v.n);
-            return;
-    }
-
-    mpack_snprintf(buffer, buffer_size, "<unknown!>");
-}
-
-void mpack_tag_debug_pseudo_json(mpack_tag_t tag, char* buffer, size_t buffer_size,
-        const char* prefix, size_t prefix_size)
-{
-    mpack_assert(buffer_size > 0, "buffer size cannot be zero!");
-    buffer[0] = 0;
-
-    mpack_tag_debug_pseudo_json_impl(tag, buffer, buffer_size, prefix, prefix_size);
-
-    // We always null-terminate the buffer manually just in case the snprintf()
-    // function doesn't null-terminate when the string doesn't fit.
-    buffer[buffer_size - 1] = 0;
-}
-
-static void mpack_tag_debug_describe_impl(mpack_tag_t tag, char* buffer, size_t buffer_size) {
-    switch (tag.type) {
-        case mpack_type_missing:
-            mpack_snprintf(buffer, buffer_size, "missing");
-            return;
-        case mpack_type_nil:
-            mpack_snprintf(buffer, buffer_size, "nil");
-            return;
-        case mpack_type_bool:
-            mpack_snprintf(buffer, buffer_size, tag.v.b ? "true" : "false");
-            return;
-        case mpack_type_int:
-            mpack_snprintf(buffer, buffer_size, "int %" PRIi64, tag.v.i);
-            return;
-        case mpack_type_uint:
-            mpack_snprintf(buffer, buffer_size, "uint %" PRIu64, tag.v.u);
-            return;
-        case mpack_type_float:
-            #if MPACK_FLOAT
-            mpack_snprintf(buffer, buffer_size, "float %f", tag.v.f);
-            #else
-            mpack_snprintf(buffer, buffer_size, "float");
-            #endif
-            return;
-        case mpack_type_double:
-            #if MPACK_DOUBLE
-            mpack_snprintf(buffer, buffer_size, "double %f", tag.v.d);
-            #else
-            mpack_snprintf(buffer, buffer_size, "double");
-            #endif
-            return;
-        case mpack_type_str:
-            mpack_snprintf(buffer, buffer_size, "str of %u bytes", tag.v.l);
-            return;
-        case mpack_type_bin:
-            mpack_snprintf(buffer, buffer_size, "bin of %u bytes", tag.v.l);
-            return;
-        #if MPACK_EXTENSIONS
-        case mpack_type_ext:
-            mpack_snprintf(buffer, buffer_size, "ext of type %i, %u bytes",
-                    mpack_tag_ext_exttype(&tag), mpack_tag_ext_length(&tag));
-            return;
-        #endif
-        case mpack_type_array:
-            mpack_snprintf(buffer, buffer_size, "array of %u elements", tag.v.n);
-            return;
-        case mpack_type_map:
-            mpack_snprintf(buffer, buffer_size, "map of %u key-value pairs", tag.v.n);
-            return;
-    }
-
-    mpack_snprintf(buffer, buffer_size, "unknown!");
-}
-
-void mpack_tag_debug_describe(mpack_tag_t tag, char* buffer, size_t buffer_size) {
-    mpack_assert(buffer_size > 0, "buffer size cannot be zero!");
-    buffer[0] = 0;
-
-    mpack_tag_debug_describe_impl(tag, buffer, buffer_size);
-
-    // We always null-terminate the buffer manually just in case the snprintf()
-    // function doesn't null-terminate when the string doesn't fit.
-    buffer[buffer_size - 1] = 0;
-}
-#endif
-
-
-
-#if MPACK_READ_TRACKING || MPACK_WRITE_TRACKING
-
-#ifndef MPACK_TRACKING_INITIAL_CAPACITY
-// seems like a reasonable number. we grow by doubling, and it only
-// needs to be as long as the maximum depth of the message.
-#define MPACK_TRACKING_INITIAL_CAPACITY 8
-#endif
-
-mpack_error_t mpack_track_init(mpack_track_t* track) {
-    track->count = 0;
-    track->capacity = MPACK_TRACKING_INITIAL_CAPACITY;
-    track->elements = (mpack_track_element_t*)MPACK_MALLOC(sizeof(mpack_track_element_t) * track->capacity);
-    if (track->elements == NULL)
-        return mpack_error_memory;
-    return mpack_ok;
-}
-
-mpack_error_t mpack_track_grow(mpack_track_t* track) {
-    mpack_assert(track->elements, "null track elements!");
-    mpack_assert(track->count == track->capacity, "incorrect growing?");
-
-    size_t new_capacity = track->capacity * 2;
-
-    mpack_track_element_t* new_elements = (mpack_track_element_t*)mpack_realloc(track->elements,
-            sizeof(mpack_track_element_t) * track->count, sizeof(mpack_track_element_t) * new_capacity);
-    if (new_elements == NULL)
-        return mpack_error_memory;
-
-    track->elements = new_elements;
-    track->capacity = new_capacity;
-    return mpack_ok;
-}
-
-mpack_error_t mpack_track_push(mpack_track_t* track, mpack_type_t type, uint32_t count) {
-    mpack_assert(track->elements, "null track elements!");
-    mpack_log("track pushing %s count %i\n", mpack_type_to_string(type), (int)count);
-
-    // grow if needed
-    if (track->count == track->capacity) {
-        mpack_error_t error = mpack_track_grow(track);
-        if (error != mpack_ok)
-            return error;
-    }
-
-    // insert new track
-    track->elements[track->count].type = type;
-    track->elements[track->count].left = count;
-    track->elements[track->count].builder = false;
-    track->elements[track->count].key_needs_value = false;
-    ++track->count;
-    return mpack_ok;
-}
-
-// TODO dedupe this
-mpack_error_t mpack_track_push_builder(mpack_track_t* track, mpack_type_t type) {
-    mpack_assert(track->elements, "null track elements!");
-    mpack_log("track pushing %s builder\n", mpack_type_to_string(type));
-
-    // grow if needed
-    if (track->count == track->capacity) {
-        mpack_error_t error = mpack_track_grow(track);
-        if (error != mpack_ok)
-            return error;
-    }
-
-    // insert new track
-    track->elements[track->count].type = type;
-    track->elements[track->count].left = 0;
-    track->elements[track->count].builder = true;
-    track->elements[track->count].key_needs_value = false;
-    ++track->count;
-    return mpack_ok;
-}
-
-static mpack_error_t mpack_track_pop_impl(mpack_track_t* track, mpack_type_t type, bool builder) {
-    mpack_assert(track->elements, "null track elements!");
-    mpack_log("track popping %s\n", mpack_type_to_string(type));
-
-    if (track->count == 0) {
-        mpack_break("attempting to close a %s but nothing was opened!", mpack_type_to_string(type));
-        return mpack_error_bug;
-    }
-
-    mpack_track_element_t* element = &track->elements[track->count - 1];
-
-    if (element->type != type) {
-        mpack_break("attempting to close a %s but the open element is a %s!",
-                mpack_type_to_string(type), mpack_type_to_string(element->type));
-        return mpack_error_bug;
-    }
-
-    if (element->key_needs_value) {
-        mpack_assert(type == mpack_type_map, "key_needs_value can only be true for maps!");
-        mpack_break("attempting to close a %s but an odd number of elements were written",
-                mpack_type_to_string(type));
-        return mpack_error_bug;
-    }
-
-    if (element->left != 0) {
-        mpack_break("attempting to close a %s but there are %i %s left",
-                mpack_type_to_string(type), element->left,
-                (type == mpack_type_map || type == mpack_type_array) ? "elements" : "bytes");
-        return mpack_error_bug;
-    }
-
-    if (element->builder != builder) {
-        mpack_break("attempting to pop a %sbuilder but the open element is %sa builder",
-                builder ? "" : "non-",
-                element->builder ? "" : "not ");
-        return mpack_error_bug;
-    }
-
-    --track->count;
-    return mpack_ok;
-}
-
-mpack_error_t mpack_track_pop(mpack_track_t* track, mpack_type_t type) {
-    return mpack_track_pop_impl(track, type, false);
-}
-
-mpack_error_t mpack_track_pop_builder(mpack_track_t* track, mpack_type_t type) {
-    return mpack_track_pop_impl(track, type, true);
-}
-
-mpack_error_t mpack_track_peek_element(mpack_track_t* track, bool read) {
-    MPACK_UNUSED(read);
-    mpack_assert(track->elements, "null track elements!");
-
-    // if there are no open elements, that's fine, we can read/write elements at will
-    if (track->count == 0)
-        return mpack_ok;
-
-    mpack_track_element_t* element = &track->elements[track->count - 1];
-
-    if (element->type != mpack_type_map && element->type != mpack_type_array) {
-        mpack_break("elements cannot be %s within an %s", read ? "read" : "written",
-                mpack_type_to_string(element->type));
-        return mpack_error_bug;
-    }
-
-    if (!element->builder && element->left == 0 && !element->key_needs_value) {
-        mpack_break("too many elements %s for %s", read ? "read" : "written",
-                mpack_type_to_string(element->type));
-        return mpack_error_bug;
-    }
-
-    return mpack_ok;
-}
-
-mpack_error_t mpack_track_element(mpack_track_t* track, bool read) {
-    mpack_error_t error = mpack_track_peek_element(track, read);
-    if (track->count == 0 || error != mpack_ok)
-        return error;
-
-    mpack_track_element_t* element = &track->elements[track->count - 1];
-
-    if (element->type == mpack_type_map) {
-        if (!element->key_needs_value) {
-            element->key_needs_value = true;
-            return mpack_ok; // don't decrement
-        }
-        element->key_needs_value = false;
-    }
-
-    if (!element->builder)
-        --element->left;
-    return mpack_ok;
-}
-
-mpack_error_t mpack_track_bytes(mpack_track_t* track, bool read, size_t count) {
-    MPACK_UNUSED(read);
-    mpack_assert(track->elements, "null track elements!");
-
-    if (count > MPACK_UINT32_MAX) {
-        mpack_break("%s more bytes than could possibly fit in a str/bin/ext!",
-                read ? "reading" : "writing");
-        return mpack_error_bug;
-    }
-
-    if (track->count == 0) {
-        mpack_break("bytes cannot be %s with no open bin, str or ext", read ? "read" : "written");
-        return mpack_error_bug;
-    }
-
-    mpack_track_element_t* element = &track->elements[track->count - 1];
-
-    if (element->type == mpack_type_map || element->type == mpack_type_array) {
-        mpack_break("bytes cannot be %s within an %s", read ? "read" : "written",
-                mpack_type_to_string(element->type));
-        return mpack_error_bug;
-    }
-
-    if (element->left < count) {
-        mpack_break("too many bytes %s for %s", read ? "read" : "written",
-                mpack_type_to_string(element->type));
-        return mpack_error_bug;
-    }
-
-    element->left -= (uint32_t)count;
-    return mpack_ok;
-}
-
-mpack_error_t mpack_track_str_bytes_all(mpack_track_t* track, bool read, size_t count) {
-    mpack_error_t error = mpack_track_bytes(track, read, count);
-    if (error != mpack_ok)
-        return error;
-
-    mpack_track_element_t* element = &track->elements[track->count - 1];
-
-    if (element->type != mpack_type_str) {
-        mpack_break("the open type must be a string, not a %s", mpack_type_to_string(element->type));
-        return mpack_error_bug;
-    }
-
-    if (element->left != 0) {
-        mpack_break("not all bytes were read; the wrong byte count was requested for a string read.");
-        return mpack_error_bug;
-    }
-
-    return mpack_ok;
-}
-
-mpack_error_t mpack_track_check_empty(mpack_track_t* track) {
-    if (track->count != 0) {
-        mpack_break("unclosed %s", mpack_type_to_string(track->elements[0].type));
-        return mpack_error_bug;
-    }
-    return mpack_ok;
-}
-
-mpack_error_t mpack_track_destroy(mpack_track_t* track, bool cancel) {
-    mpack_error_t error = cancel ? mpack_ok : mpack_track_check_empty(track);
-    if (track->elements) {
-        MPACK_FREE(track->elements);
-        track->elements = NULL;
-    }
-    return error;
-}
-#endif
-
-
-
-static bool mpack_utf8_check_impl(const uint8_t* str, size_t count, bool allow_null) {
-    while (count > 0) {
-        uint8_t lead = str[0];
-
-        // NUL
-        if (!allow_null && lead == '\0') // we don't allow NUL bytes in MPack C-strings
-            return false;
-
-        // ASCII
-        if (lead <= 0x7F) {
-            ++str;
-            --count;
-
-        // 2-byte sequence
-        } else if ((lead & 0xE0) == 0xC0) {
-            if (count < 2) // truncated sequence
-                return false;
-
-            uint8_t cont = str[1];
-            if ((cont & 0xC0) != 0x80) // not a continuation byte
-                return false;
-
-            str += 2;
-            count -= 2;
-
-            uint32_t z = ((uint32_t)(lead & ~0xE0) << 6) |
-                          (uint32_t)(cont & ~0xC0);
-
-            if (z < 0x80) // overlong sequence
-                return false;
-
-        // 3-byte sequence
-        } else if ((lead & 0xF0) == 0xE0) {
-            if (count < 3) // truncated sequence
-                return false;
-
-            uint8_t cont1 = str[1];
-            if ((cont1 & 0xC0) != 0x80) // not a continuation byte
-                return false;
-            uint8_t cont2 = str[2];
-            if ((cont2 & 0xC0) != 0x80) // not a continuation byte
-                return false;
-
-            str += 3;
-            count -= 3;
-
-            uint32_t z = ((uint32_t)(lead  & ~0xF0) << 12) |
-                         ((uint32_t)(cont1 & ~0xC0) <<  6) |
-                          (uint32_t)(cont2 & ~0xC0);
-
-            if (z < 0x800) // overlong sequence
-                return false;
-            if (z >= 0xD800 && z <= 0xDFFF) // surrogate
-                return false;
-
-        // 4-byte sequence
-        } else if ((lead & 0xF8) == 0xF0) {
-            if (count < 4) // truncated sequence
-                return false;
-
-            uint8_t cont1 = str[1];
-            if ((cont1 & 0xC0) != 0x80) // not a continuation byte
-                return false;
-            uint8_t cont2 = str[2];
-            if ((cont2 & 0xC0) != 0x80) // not a continuation byte
-                return false;
-            uint8_t cont3 = str[3];
-            if ((cont3 & 0xC0) != 0x80) // not a continuation byte
-                return false;
-
-            str += 4;
-            count -= 4;
-
-            uint32_t z = ((uint32_t)(lead  & ~0xF8) << 18) |
-                         ((uint32_t)(cont1 & ~0xC0) << 12) |
-                         ((uint32_t)(cont2 & ~0xC0) <<  6) |
-                          (uint32_t)(cont3 & ~0xC0);
-
-            if (z < 0x10000) // overlong sequence
-                return false;
-            if (z > 0x10FFFF) // codepoint limit
-                return false;
-
-        } else {
-            return false; // continuation byte without a lead, or lead for a 5-byte sequence or longer
-        }
-    }
-    return true;
-}
-
-bool mpack_utf8_check(const char* str, size_t bytes) {
-    return mpack_utf8_check_impl((const uint8_t*)str, bytes, true);
-}
-
-bool mpack_utf8_check_no_null(const char* str, size_t bytes) {
-    return mpack_utf8_check_impl((const uint8_t*)str, bytes, false);
-}
-
-bool mpack_str_check_no_null(const char* str, size_t bytes) {
-    size_t i;
-    for (i = 0; i < bytes; ++i)
-        if (str[i] == '\0')
-            return false;
-    return true;
-}
-
-#if MPACK_DEBUG && MPACK_STDIO
-void mpack_print_append(mpack_print_t* print, const char* data, size_t count) {
-
-    // copy whatever fits into the buffer
-    size_t copy = print->size - print->count;
-    if (copy > count)
-        copy = count;
-    mpack_memcpy(print->buffer + print->count, data, copy);
-    print->count += copy;
-    data += copy;
-    count -= copy;
-
-    // if we don't need to flush or can't flush there's nothing else to do
-    if (count == 0 || print->callback == NULL)
-        return;
-
-    // flush the buffer
-    print->callback(print->context, print->buffer, print->count);
-
-    if (count > print->size / 2) {
-        // flush the rest of the data
-        print->count = 0;
-        print->callback(print->context, data, count);
-    } else {
-        // copy the rest of the data into the buffer
-        mpack_memcpy(print->buffer, data, count);
-        print->count = count;
-    }
-
-}
-
-void mpack_print_flush(mpack_print_t* print) {
-    if (print->count > 0 && print->callback != NULL) {
-        print->callback(print->context, print->buffer, print->count);
-        print->count = 0;
-    }
-}
-
-void mpack_print_file_callback(void* context, const char* data, size_t count) {
-    FILE* file = (FILE*)context;
-    fwrite(data, 1, count, file);
-}
-#endif
-
-MPACK_SILENCE_WARNINGS_END
-
-/* mpack/mpack-writer.c.c */
-
-#define MPACK_INTERNAL 1
-
-/* #include "mpack-writer.h" */
-
-MPACK_SILENCE_WARNINGS_BEGIN
-
-#if MPACK_WRITER
-
-#if MPACK_BUILDER
-static void mpack_builder_flush(mpack_writer_t* writer);
-#endif
-
-#if MPACK_WRITE_TRACKING
-static void mpack_writer_flag_if_error(mpack_writer_t* writer, mpack_error_t error) {
-    if (error != mpack_ok)
-        mpack_writer_flag_error(writer, error);
-}
-
-void mpack_writer_track_push(mpack_writer_t* writer, mpack_type_t type, uint32_t count) {
-    if (writer->error == mpack_ok)
-        mpack_writer_flag_if_error(writer, mpack_track_push(&writer->track, type, count));
-}
-
-void mpack_writer_track_push_builder(mpack_writer_t* writer, mpack_type_t type) {
-    if (writer->error == mpack_ok)
-        mpack_writer_flag_if_error(writer, mpack_track_push_builder(&writer->track, type));
-}
-
-void mpack_writer_track_pop(mpack_writer_t* writer, mpack_type_t type) {
-    if (writer->error == mpack_ok)
-        mpack_writer_flag_if_error(writer, mpack_track_pop(&writer->track, type));
-}
-
-void mpack_writer_track_pop_builder(mpack_writer_t* writer, mpack_type_t type) {
-    if (writer->error == mpack_ok)
-        mpack_writer_flag_if_error(writer, mpack_track_pop_builder(&writer->track, type));
-}
-
-void mpack_writer_track_bytes(mpack_writer_t* writer, size_t count) {
-    if (writer->error == mpack_ok)
-        mpack_writer_flag_if_error(writer, mpack_track_bytes(&writer->track, false, count));
-}
-#endif
-
-// This should probably be renamed. It's not solely used for tracking.
-static inline void mpack_writer_track_element(mpack_writer_t* writer) {
-    (void)writer;
-
-    #if MPACK_WRITE_TRACKING
-    if (writer->error == mpack_ok)
-        mpack_writer_flag_if_error(writer, mpack_track_element(&writer->track, false));
-    #endif
-
-    #if MPACK_BUILDER
-    if (writer->builder.current_build != NULL) {
-        mpack_build_t* build = writer->builder.current_build;
-        // We only track this write if it's not nested within another non-build
-        // map or array.
-        if (build->nested_compound_elements == 0) {
-            if (build->type != mpack_type_map) {
-                ++build->count;
-                mpack_log("adding element to build %p, now %u elements\n", (void*)build, build->count);
-            } else if (build->key_needs_value) {
-                build->key_needs_value = false;
-                ++build->count;
-            } else {
-                build->key_needs_value = true;
-            }
-        }
-    }
-    #endif
-}
-
-static void mpack_writer_clear(mpack_writer_t* writer) {
-    #if MPACK_COMPATIBILITY
-    writer->version = mpack_version_current;
-    #endif
-    writer->flush = NULL;
-    writer->error_fn = NULL;
-    writer->teardown = NULL;
-    writer->context = NULL;
-
-    writer->buffer = NULL;
-    writer->position = NULL;
-    writer->end = NULL;
-    writer->error = mpack_ok;
-
-    #if MPACK_WRITE_TRACKING
-    mpack_memset(&writer->track, 0, sizeof(writer->track));
-    #endif
-
-    #if MPACK_BUILDER
-    writer->builder.current_build = NULL;
-    writer->builder.latest_build = NULL;
-    writer->builder.current_page = NULL;
-    writer->builder.pages = NULL;
-    writer->builder.stash_buffer = NULL;
-    writer->builder.stash_position = NULL;
-    writer->builder.stash_end = NULL;
-    #endif
-}
-
-void mpack_writer_init(mpack_writer_t* writer, char* buffer, size_t size) {
-    mpack_assert(buffer != NULL, "cannot initialize writer with empty buffer");
-    mpack_writer_clear(writer);
-    writer->buffer = buffer;
-    writer->position = buffer;
-    writer->end = writer->buffer + size;
-
-    #if MPACK_WRITE_TRACKING
-    mpack_writer_flag_if_error(writer, mpack_track_init(&writer->track));
-    #endif
-
-    mpack_log("===========================\n");
-    mpack_log("initializing writer with buffer size %i\n", (int)size);
-}
-
-void mpack_writer_init_error(mpack_writer_t* writer, mpack_error_t error) {
-    mpack_writer_clear(writer);
-    writer->error = error;
-
-    mpack_log("===========================\n");
-    mpack_log("initializing writer in error state %i\n", (int)error);
-}
-
-void mpack_writer_set_flush(mpack_writer_t* writer, mpack_writer_flush_t flush) {
-    MPACK_STATIC_ASSERT(MPACK_WRITER_MINIMUM_BUFFER_SIZE >= MPACK_MAXIMUM_TAG_SIZE,
-            "minimum buffer size must fit any tag!");
-    MPACK_STATIC_ASSERT(31 + MPACK_TAG_SIZE_FIXSTR >= MPACK_WRITER_MINIMUM_BUFFER_SIZE,
-            "minimum buffer size must fit the largest possible fixstr!");
-
-    if (mpack_writer_buffer_size(writer) < MPACK_WRITER_MINIMUM_BUFFER_SIZE) {
-        mpack_break("buffer size is %i, but minimum buffer size for flush is %i",
-                (int)mpack_writer_buffer_size(writer), MPACK_WRITER_MINIMUM_BUFFER_SIZE);
-        mpack_writer_flag_error(writer, mpack_error_bug);
-        return;
-    }
-
-    writer->flush = flush;
-}
-
-#ifdef MPACK_MALLOC
-typedef struct mpack_growable_writer_t {
-    char** target_data;
-    size_t* target_size;
-} mpack_growable_writer_t;
-
-static char* mpack_writer_get_reserved(mpack_writer_t* writer) {
-    // This is in a separate function in order to avoid false strict aliasing
-    // warnings. We aren't actually violating strict aliasing (the reserved
-    // space is only ever dereferenced as an mpack_growable_writer_t.)
-    return (char*)writer->reserved;
-}
-
-static void mpack_growable_writer_flush(mpack_writer_t* writer, const char* data, size_t count) {
-
-    // This is an intrusive flush function which modifies the writer's buffer
-    // in response to a flush instead of emptying it in order to add more
-    // capacity for data. This removes the need to copy data from a fixed buffer
-    // into a growable one, improving performance.
-    //
-    // There are three ways flush can be called:
-    //   - flushing the buffer during writing (used is zero, count is all data, data is buffer)
-    //   - flushing extra data during writing (used is all flushed data, count is extra data, data is not buffer)
-    //   - flushing during teardown (used and count are both all flushed data, data is buffer)
-    //
-    // In the first two cases, we grow the buffer by at least double, enough
-    // to ensure that new data will fit. We ignore the teardown flush.
-
-    if (data == writer->buffer) {
-
-        // teardown, do nothing
-        if (mpack_writer_buffer_used(writer) == count)
-            return;
-
-        // otherwise leave the data in the buffer and just grow
-        writer->position = writer->buffer + count;
-        count = 0;
-    }
-
-    size_t used = mpack_writer_buffer_used(writer);
-    size_t size = mpack_writer_buffer_size(writer);
-
-    mpack_log("flush size %i used %i data %p buffer %p\n",
-            (int)count, (int)used, data, writer->buffer);
-
-    mpack_assert(data == writer->buffer || used + count > size,
-            "extra flush for %i but there is %i space left in the buffer! (%i/%i)",
-            (int)count, (int)mpack_writer_buffer_left(writer), (int)used, (int)size);
-
-    // grow to fit the data
-    // TODO: this really needs to correctly test for overflow
-    size_t new_size = size * 2;
-    while (new_size < used + count)
-        new_size *= 2;
-
-    mpack_log("flush growing buffer size from %i to %i\n", (int)size, (int)new_size);
-
-    // grow the buffer
-    char* new_buffer = (char*)mpack_realloc(writer->buffer, used, new_size);
-    if (new_buffer == NULL) {
-        mpack_writer_flag_error(writer, mpack_error_memory);
-        return;
-    }
-    writer->position = new_buffer + used;
-    writer->buffer = new_buffer;
-    writer->end = writer->buffer + new_size;
-
-    // append the extra data
-    if (count > 0) {
-        mpack_memcpy(writer->position, data, count);
-        writer->position += count;
-    }
-
-    mpack_log("new buffer %p, used %i\n", new_buffer, (int)mpack_writer_buffer_used(writer));
-}
-
-static void mpack_growable_writer_teardown(mpack_writer_t* writer) {
-    mpack_growable_writer_t* growable_writer = (mpack_growable_writer_t*)mpack_writer_get_reserved(writer);
-
-    if (mpack_writer_error(writer) == mpack_ok) {
-
-        // shrink the buffer to an appropriate size if the data is
-        // much smaller than the buffer
-        if (mpack_writer_buffer_used(writer) < mpack_writer_buffer_size(writer) / 2) {
-            size_t used = mpack_writer_buffer_used(writer);
-
-            // We always return a non-null pointer that must be freed, even if
-            // nothing was written. malloc() and realloc() do not necessarily
-            // do this so we enforce it ourselves.
-            size_t size = (used != 0) ? used : 1;
-
-            char* buffer = (char*)mpack_realloc(writer->buffer, used, size);
-            if (!buffer) {
-                MPACK_FREE(writer->buffer);
-                mpack_writer_flag_error(writer, mpack_error_memory);
-                return;
-            }
-            writer->buffer = buffer;
-            writer->end = (writer->position = writer->buffer + used);
-        }
-
-        *growable_writer->target_data = writer->buffer;
-        *growable_writer->target_size = mpack_writer_buffer_used(writer);
-        writer->buffer = NULL;
-
-    } else if (writer->buffer) {
-        MPACK_FREE(writer->buffer);
-        writer->buffer = NULL;
-    }
-
-    writer->context = NULL;
-}
-
-void mpack_writer_init_growable(mpack_writer_t* writer, char** target_data, size_t* target_size) {
-    mpack_assert(target_data != NULL, "cannot initialize writer without a destination for the data");
-    mpack_assert(target_size != NULL, "cannot initialize writer without a destination for the size");
-
-    *target_data = NULL;
-    *target_size = 0;
-
-    MPACK_STATIC_ASSERT(sizeof(mpack_growable_writer_t) <= sizeof(writer->reserved),
-            "not enough reserved space for growable writer!");
-    mpack_growable_writer_t* growable_writer = (mpack_growable_writer_t*)mpack_writer_get_reserved(writer);
-
-    growable_writer->target_data = target_data;
-    growable_writer->target_size = target_size;
-
-    size_t capacity = MPACK_BUFFER_SIZE;
-    char* buffer = (char*)MPACK_MALLOC(capacity);
-    if (buffer == NULL) {
-        mpack_writer_init_error(writer, mpack_error_memory);
-        return;
-    }
-
-    mpack_writer_init(writer, buffer, capacity);
-    mpack_writer_set_flush(writer, mpack_growable_writer_flush);
-    mpack_writer_set_teardown(writer, mpack_growable_writer_teardown);
-}
-#endif
-
-#if MPACK_STDIO
-static void mpack_file_writer_flush(mpack_writer_t* writer, const char* buffer, size_t count) {
-    FILE* file = (FILE*)writer->context;
-    size_t written = fwrite((const void*)buffer, 1, count, file);
-    if (written != count)
-        mpack_writer_flag_error(writer, mpack_error_io);
-}
-
-static void mpack_file_writer_teardown(mpack_writer_t* writer) {
-    MPACK_FREE(writer->buffer);
-    writer->buffer = NULL;
-    writer->context = NULL;
-}
-
-static void mpack_file_writer_teardown_close(mpack_writer_t* writer) {
-    FILE* file = (FILE*)writer->context;
-
-    if (file) {
-        int ret = fclose(file);
-        if (ret != 0)
-            mpack_writer_flag_error(writer, mpack_error_io);
-    }
-
-    mpack_file_writer_teardown(writer);
-}
-
-void mpack_writer_init_stdfile(mpack_writer_t* writer, FILE* file, bool close_when_done) {
-    mpack_assert(file != NULL, "file is NULL");
-
-    size_t capacity = MPACK_BUFFER_SIZE;
-    char* buffer = (char*)MPACK_MALLOC(capacity);
-    if (buffer == NULL) {
-        mpack_writer_init_error(writer, mpack_error_memory);
-        if (close_when_done) {
-            fclose(file);
-        }
-        return;
-    }
-
-    mpack_writer_init(writer, buffer, capacity);
-    mpack_writer_set_context(writer, file);
-    mpack_writer_set_flush(writer, mpack_file_writer_flush);
-    mpack_writer_set_teardown(writer, close_when_done ?
-            mpack_file_writer_teardown_close :
-            mpack_file_writer_teardown);
-}
-
-void mpack_writer_init_filename(mpack_writer_t* writer, const char* filename) {
-    mpack_assert(filename != NULL, "filename is NULL");
-
-    FILE* file = fopen(filename, "wb");
-    if (file == NULL) {
-        mpack_writer_init_error(writer, mpack_error_io);
-        return;
-    }
-
-    mpack_writer_init_stdfile(writer, file, true);
-}
-#endif
-
-void mpack_writer_flag_error(mpack_writer_t* writer, mpack_error_t error) {
-    mpack_log("writer %p setting error %i: %s\n", (void*)writer, (int)error, mpack_error_to_string(error));
-
-    if (writer->error == mpack_ok) {
-        writer->error = error;
-        if (writer->error_fn)
-            writer->error_fn(writer, writer->error);
-    }
-}
-
-MPACK_STATIC_INLINE void mpack_writer_flush_unchecked(mpack_writer_t* writer) {
-    // This is a bit ugly; we reset used before calling flush so that
-    // a flush function can distinguish between flushing the buffer
-    // versus flushing external data. see mpack_growable_writer_flush()
-    size_t used = mpack_writer_buffer_used(writer);
-    writer->position = writer->buffer;
-    writer->flush(writer, writer->buffer, used);
-}
-
-void mpack_writer_flush_message(mpack_writer_t* writer) {
-    if (writer->error != mpack_ok)
-        return;
-
-    #if MPACK_WRITE_TRACKING
-    // You cannot flush while there are elements open.
-    mpack_writer_flag_if_error(writer, mpack_track_check_empty(&writer->track));
-    if (writer->error != mpack_ok)
-        return;
-    #endif
-
-    #if MPACK_BUILDER
-    if (writer->builder.current_build != NULL) {
-        mpack_break("cannot call mpack_writer_flush_message() while there are elements open!");
-        mpack_writer_flag_error(writer, mpack_error_bug);
-        return;
-    }
-    #endif
-
-    if (writer->flush == NULL) {
-        mpack_break("cannot call mpack_writer_flush_message() without a flush function!");
-        mpack_writer_flag_error(writer, mpack_error_bug);
-        return;
-    }
-
-    if (mpack_writer_buffer_used(writer) > 0)
-        mpack_writer_flush_unchecked(writer);
-}
-
-// Ensures there are at least count bytes free in the buffer. This
-// will flag an error if the flush function fails to make enough
-// room in the buffer.
-MPACK_NOINLINE static bool mpack_writer_ensure(mpack_writer_t* writer, size_t count) {
-    mpack_assert(count != 0, "cannot ensure zero bytes!");
-    mpack_assert(count <= MPACK_WRITER_MINIMUM_BUFFER_SIZE,
-            "cannot ensure %i bytes, this is more than the minimum buffer size %i!",
-            (int)count, (int)MPACK_WRITER_MINIMUM_BUFFER_SIZE);
-    mpack_assert(count > mpack_writer_buffer_left(writer),
-            "request to ensure %i bytes but there are already %i left in the buffer!",
-            (int)count, (int)mpack_writer_buffer_left(writer));
-
-    mpack_log("ensuring %i bytes, %i left\n", (int)count, (int)mpack_writer_buffer_left(writer));
-
-    if (mpack_writer_error(writer) != mpack_ok)
-        return false;
-
-    #if MPACK_BUILDER
-    // if we have a build in progress, we just ask the builder for a page.
-    // either it will have space for a tag, or it will flag a memory error.
-    if (writer->builder.current_build != NULL) {
-        mpack_builder_flush(writer);
-        return mpack_writer_error(writer) == mpack_ok;
-    }
-    #endif
-
-    if (writer->flush == NULL) {
-        mpack_writer_flag_error(writer, mpack_error_too_big);
-        return false;
-    }
-
-    mpack_writer_flush_unchecked(writer);
-    if (mpack_writer_error(writer) != mpack_ok)
-        return false;
-
-    if (mpack_writer_buffer_left(writer) >= count)
-        return true;
-
-    mpack_writer_flag_error(writer, mpack_error_io);
-    return false;
-}
-
-// Writes encoded bytes to the buffer when we already know the data
-// does not fit in the buffer (i.e. it straddles the edge of the
-// buffer.) If there is a flush function, it is guaranteed to be
-// called; otherwise mpack_error_too_big is raised.
-MPACK_NOINLINE static void mpack_write_native_straddle(mpack_writer_t* writer, const char* p, size_t count) {
-    mpack_assert(count == 0 || p != NULL, "data pointer for %i bytes is NULL", (int)count);
-
-    if (mpack_writer_error(writer) != mpack_ok)
-        return;
-    mpack_log("big write for %i bytes from %p, %i space left in buffer\n",
-            (int)count, p, (int)mpack_writer_buffer_left(writer));
-    mpack_assert(count > mpack_writer_buffer_left(writer),
-            "big write requested for %i bytes, but there is %i available "
-            "space in buffer. should have called mpack_write_native() instead",
-            (int)count, (int)(mpack_writer_buffer_left(writer)));
-
-    #if MPACK_BUILDER
-    // if we have a build in progress, we can't flush. we need to copy all
-    // bytes into as many build buffer pages as it takes.
-    if (writer->builder.current_build != NULL) {
-        while (true) {
-            size_t step = (size_t)(writer->end - writer->position);
-            if (step > count)
-                step = count;
-            mpack_memcpy(writer->position, p, step);
-            writer->position += step;
-            p += step;
-            count -= step;
-
-            if (count == 0)
-                return;
-
-            mpack_builder_flush(writer);
-            if (mpack_writer_error(writer) != mpack_ok)
-                return;
-            mpack_assert(writer->position != writer->end);
-        }
-    }
-    #endif
-
-    // we'll need a flush function
-    if (!writer->flush) {
-        mpack_writer_flag_error(writer, mpack_error_too_big);
-        return;
-    }
-
-    // flush the buffer
-    mpack_writer_flush_unchecked(writer);
-    if (mpack_writer_error(writer) != mpack_ok)
-        return;
-
-    // note that an intrusive flush function (such as mpack_growable_writer_flush())
-    // may have changed size and/or reset used to a non-zero value. we treat both as
-    // though they may have changed, and there may still be data in the buffer.
-
-    // flush the extra data directly if it doesn't fit in the buffer
-    if (count > mpack_writer_buffer_left(writer)) {
-        writer->flush(writer, p, count);
-        if (mpack_writer_error(writer) != mpack_ok)
-            return;
-    } else {
-        mpack_memcpy(writer->position, p, count);
-        writer->position += count;
-    }
-}
-
-// Writes encoded bytes to the buffer, flushing if necessary.
-MPACK_STATIC_INLINE void mpack_write_native(mpack_writer_t* writer, const char* p, size_t count) {
-    mpack_assert(count == 0 || p != NULL, "data pointer for %i bytes is NULL", (int)count);
-
-    if (mpack_writer_buffer_left(writer) < count) {
-        mpack_write_native_straddle(writer, p, count);
-    } else {
-        mpack_memcpy(writer->position, p, count);
-        writer->position += count;
-    }
-}
-
-mpack_error_t mpack_writer_destroy(mpack_writer_t* writer) {
-
-    // clean up tracking, asserting if we're not already in an error state
-    #if MPACK_WRITE_TRACKING
-    mpack_track_destroy(&writer->track, writer->error != mpack_ok);
-    #endif
-
-    // flush any outstanding data
-    if (mpack_writer_error(writer) == mpack_ok && mpack_writer_buffer_used(writer) != 0 && writer->flush != NULL) {
-        writer->flush(writer, writer->buffer, mpack_writer_buffer_used(writer));
-        writer->flush = NULL;
-    }
-
-    if (writer->teardown) {
-        writer->teardown(writer);
-        writer->teardown = NULL;
-    }
-
-    return writer->error;
-}
-
-void mpack_write_tag(mpack_writer_t* writer, mpack_tag_t value) {
-    switch (value.type) {
-        case mpack_type_missing:
-            mpack_break("cannot write a missing value!");
-            mpack_writer_flag_error(writer, mpack_error_bug);
-            return;
-
-        case mpack_type_nil:    mpack_write_nil   (writer);            return;
-        case mpack_type_bool:   mpack_write_bool  (writer, value.v.b); return;
-        case mpack_type_int:    mpack_write_int   (writer, value.v.i); return;
-        case mpack_type_uint:   mpack_write_uint  (writer, value.v.u); return;
-
-        case mpack_type_float:
-            #if MPACK_FLOAT
-            mpack_write_float
-            #else
-            mpack_write_raw_float
-            #endif
-                (writer, value.v.f);
-            return;
-        case mpack_type_double:
-            #if MPACK_DOUBLE
-            mpack_write_double
-            #else
-            mpack_write_raw_double
-            #endif
-                (writer, value.v.d);
-            return;
-
-        case mpack_type_str: mpack_start_str(writer, value.v.l); return;
-        case mpack_type_bin: mpack_start_bin(writer, value.v.l); return;
-
-        #if MPACK_EXTENSIONS
-        case mpack_type_ext:
-            mpack_start_ext(writer, mpack_tag_ext_exttype(&value), mpack_tag_ext_length(&value));
-            return;
-        #endif
-
-        case mpack_type_array: mpack_start_array(writer, value.v.n); return;
-        case mpack_type_map:   mpack_start_map(writer, value.v.n);   return;
-    }
-
-    mpack_break("unrecognized type %i", (int)value.type);
-    mpack_writer_flag_error(writer, mpack_error_bug);
-}
-
-MPACK_STATIC_INLINE void mpack_write_byte_element(mpack_writer_t* writer, char value) {
-    mpack_writer_track_element(writer);
-    if (MPACK_LIKELY(mpack_writer_buffer_left(writer) >= 1) || mpack_writer_ensure(writer, 1))
-        *(writer->position++) = value;
-}
-
-void mpack_write_nil(mpack_writer_t* writer) {
-    mpack_write_byte_element(writer, (char)0xc0);
-}
-
-void mpack_write_bool(mpack_writer_t* writer, bool value) {
-    mpack_write_byte_element(writer, (char)(0xc2 | (value ? 1 : 0)));
-}
-
-void mpack_write_true(mpack_writer_t* writer) {
-    mpack_write_byte_element(writer, (char)0xc3);
-}
-
-void mpack_write_false(mpack_writer_t* writer) {
-    mpack_write_byte_element(writer, (char)0xc2);
-}
-
-void mpack_write_object_bytes(mpack_writer_t* writer, const char* data, size_t bytes) {
-    mpack_writer_track_element(writer);
-    mpack_write_native(writer, data, bytes);
-}
-
-/*
- * Encode functions
- */
-
-MPACK_STATIC_INLINE void mpack_encode_fixuint(char* p, uint8_t value) {
-    mpack_assert(value <= 127);
-    mpack_store_u8(p, value);
-}
-
-MPACK_STATIC_INLINE void mpack_encode_u8(char* p, uint8_t value) {
-    mpack_assert(value > 127);
-    mpack_store_u8(p, 0xcc);
-    mpack_store_u8(p + 1, value);
-}
-
-MPACK_STATIC_INLINE void mpack_encode_u16(char* p, uint16_t value) {
-    mpack_assert(value > MPACK_UINT8_MAX);
-    mpack_store_u8(p, 0xcd);
-    mpack_store_u16(p + 1, value);
-}
-
-MPACK_STATIC_INLINE void mpack_encode_u32(char* p, uint32_t value) {
-    mpack_assert(value > MPACK_UINT16_MAX);
-    mpack_store_u8(p, 0xce);
-    mpack_store_u32(p + 1, value);
-}
-
-MPACK_STATIC_INLINE void mpack_encode_u64(char* p, uint64_t value) {
-    mpack_assert(value > MPACK_UINT32_MAX);
-    mpack_store_u8(p, 0xcf);
-    mpack_store_u64(p + 1, value);
-}
-
-MPACK_STATIC_INLINE void mpack_encode_fixint(char* p, int8_t value) {
-    // this can encode positive or negative fixints
-    mpack_assert(value >= -32);
-    mpack_store_i8(p, value);
-}
-
-MPACK_STATIC_INLINE void mpack_encode_i8(char* p, int8_t value) {
-    mpack_assert(value < -32);
-    mpack_store_u8(p, 0xd0);
-    mpack_store_i8(p + 1, value);
-}
-
-MPACK_STATIC_INLINE void mpack_encode_i16(char* p, int16_t value) {
-    mpack_assert(value < MPACK_INT8_MIN);
-    mpack_store_u8(p, 0xd1);
-    mpack_store_i16(p + 1, value);
-}
-
-MPACK_STATIC_INLINE void mpack_encode_i32(char* p, int32_t value) {
-    mpack_assert(value < MPACK_INT16_MIN);
-    mpack_store_u8(p, 0xd2);
-    mpack_store_i32(p + 1, value);
-}
-
-MPACK_STATIC_INLINE void mpack_encode_i64(char* p, int64_t value) {
-    mpack_assert(value < MPACK_INT32_MIN);
-    mpack_store_u8(p, 0xd3);
-    mpack_store_i64(p + 1, value);
-}
-
-#if MPACK_FLOAT
-MPACK_STATIC_INLINE void mpack_encode_float(char* p, float value) {
-    mpack_store_u8(p, 0xca);
-    mpack_store_float(p + 1, value);
-}
-#else
-MPACK_STATIC_INLINE void mpack_encode_raw_float(char* p, uint32_t value) {
-    mpack_store_u8(p, 0xca);
-    mpack_store_u32(p + 1, value);
-}
-#endif
-
-#if MPACK_DOUBLE
-MPACK_STATIC_INLINE void mpack_encode_double(char* p, double value) {
-    mpack_store_u8(p, 0xcb);
-    mpack_store_double(p + 1, value);
-}
-#else
-MPACK_STATIC_INLINE void mpack_encode_raw_double(char* p, uint64_t value) {
-    mpack_store_u8(p, 0xcb);
-    mpack_store_u64(p + 1, value);
-}
-#endif
-
-MPACK_STATIC_INLINE void mpack_encode_fixarray(char* p, uint8_t count) {
-    mpack_assert(count <= 15);
-    mpack_store_u8(p, (uint8_t)(0x90 | count));
-}
-
-MPACK_STATIC_INLINE void mpack_encode_array16(char* p, uint16_t count) {
-    mpack_assert(count > 15);
-    mpack_store_u8(p, 0xdc);
-    mpack_store_u16(p + 1, count);
-}
-
-MPACK_STATIC_INLINE void mpack_encode_array32(char* p, uint32_t count) {
-    mpack_assert(count > MPACK_UINT16_MAX);
-    mpack_store_u8(p, 0xdd);
-    mpack_store_u32(p + 1, count);
-}
-
-MPACK_STATIC_INLINE void mpack_encode_fixmap(char* p, uint8_t count) {
-    mpack_assert(count <= 15);
-    mpack_store_u8(p, (uint8_t)(0x80 | count));
-}
-
-MPACK_STATIC_INLINE void mpack_encode_map16(char* p, uint16_t count) {
-    mpack_assert(count > 15);
-    mpack_store_u8(p, 0xde);
-    mpack_store_u16(p + 1, count);
-}
-
-MPACK_STATIC_INLINE void mpack_encode_map32(char* p, uint32_t count) {
-    mpack_assert(count > MPACK_UINT16_MAX);
-    mpack_store_u8(p, 0xdf);
-    mpack_store_u32(p + 1, count);
-}
-
-MPACK_STATIC_INLINE void mpack_encode_fixstr(char* p, uint8_t count) {
-    mpack_assert(count <= 31);
-    mpack_store_u8(p, (uint8_t)(0xa0 | count));
-}
-
-MPACK_STATIC_INLINE void mpack_encode_str8(char* p, uint8_t count) {
-    mpack_assert(count > 31);
-    mpack_store_u8(p, 0xd9);
-    mpack_store_u8(p + 1, count);
-}
-
-MPACK_STATIC_INLINE void mpack_encode_str16(char* p, uint16_t count) {
-    // we might be encoding a raw in compatibility mode, so we
-    // allow count to be in the range [32, MPACK_UINT8_MAX].
-    mpack_assert(count > 31);
-    mpack_store_u8(p, 0xda);
-    mpack_store_u16(p + 1, count);
-}
-
-MPACK_STATIC_INLINE void mpack_encode_str32(char* p, uint32_t count) {
-    mpack_assert(count > MPACK_UINT16_MAX);
-    mpack_store_u8(p, 0xdb);
-    mpack_store_u32(p + 1, count);
-}
-
-MPACK_STATIC_INLINE void mpack_encode_bin8(char* p, uint8_t count) {
-    mpack_store_u8(p, 0xc4);
-    mpack_store_u8(p + 1, count);
-}
-
-MPACK_STATIC_INLINE void mpack_encode_bin16(char* p, uint16_t count) {
-    mpack_assert(count > MPACK_UINT8_MAX);
-    mpack_store_u8(p, 0xc5);
-    mpack_store_u16(p + 1, count);
-}
-
-MPACK_STATIC_INLINE void mpack_encode_bin32(char* p, uint32_t count) {
-    mpack_assert(count > MPACK_UINT16_MAX);
-    mpack_store_u8(p, 0xc6);
-    mpack_store_u32(p + 1, count);
-}
-
-#if MPACK_EXTENSIONS
-MPACK_STATIC_INLINE void mpack_encode_fixext1(char* p, int8_t exttype) {
-    mpack_store_u8(p, 0xd4);
-    mpack_store_i8(p + 1, exttype);
-}
-
-MPACK_STATIC_INLINE void mpack_encode_fixext2(char* p, int8_t exttype) {
-    mpack_store_u8(p, 0xd5);
-    mpack_store_i8(p + 1, exttype);
-}
-
-MPACK_STATIC_INLINE void mpack_encode_fixext4(char* p, int8_t exttype) {
-    mpack_store_u8(p, 0xd6);
-    mpack_store_i8(p + 1, exttype);
-}
-
-MPACK_STATIC_INLINE void mpack_encode_fixext8(char* p, int8_t exttype) {
-    mpack_store_u8(p, 0xd7);
-    mpack_store_i8(p + 1, exttype);
-}
-
-MPACK_STATIC_INLINE void mpack_encode_fixext16(char* p, int8_t exttype) {
-    mpack_store_u8(p, 0xd8);
-    mpack_store_i8(p + 1, exttype);
-}
-
-MPACK_STATIC_INLINE void mpack_encode_ext8(char* p, int8_t exttype, uint8_t count) {
-    mpack_assert(count != 1 && count != 2 && count != 4 && count != 8 && count != 16);
-    mpack_store_u8(p, 0xc7);
-    mpack_store_u8(p + 1, count);
-    mpack_store_i8(p + 2, exttype);
-}
-
-MPACK_STATIC_INLINE void mpack_encode_ext16(char* p, int8_t exttype, uint16_t count) {
-    mpack_assert(count > MPACK_UINT8_MAX);
-    mpack_store_u8(p, 0xc8);
-    mpack_store_u16(p + 1, count);
-    mpack_store_i8(p + 3, exttype);
-}
-
-MPACK_STATIC_INLINE void mpack_encode_ext32(char* p, int8_t exttype, uint32_t count) {
-    mpack_assert(count > MPACK_UINT16_MAX);
-    mpack_store_u8(p, 0xc9);
-    mpack_store_u32(p + 1, count);
-    mpack_store_i8(p + 5, exttype);
-}
-
-MPACK_STATIC_INLINE void mpack_encode_timestamp_4(char* p, uint32_t seconds) {
-    mpack_encode_fixext4(p, MPACK_EXTTYPE_TIMESTAMP);
-    mpack_store_u32(p + MPACK_TAG_SIZE_FIXEXT4, seconds);
-}
-
-MPACK_STATIC_INLINE void mpack_encode_timestamp_8(char* p, int64_t seconds, uint32_t nanoseconds) {
-    mpack_assert(nanoseconds <= MPACK_TIMESTAMP_NANOSECONDS_MAX);
-    mpack_encode_fixext8(p, MPACK_EXTTYPE_TIMESTAMP);
-    uint64_t encoded = ((uint64_t)nanoseconds << 34) | (uint64_t)seconds;
-    mpack_store_u64(p + MPACK_TAG_SIZE_FIXEXT8, encoded);
-}
-
-MPACK_STATIC_INLINE void mpack_encode_timestamp_12(char* p, int64_t seconds, uint32_t nanoseconds) {
-    mpack_assert(nanoseconds <= MPACK_TIMESTAMP_NANOSECONDS_MAX);
-    mpack_encode_ext8(p, MPACK_EXTTYPE_TIMESTAMP, 12);
-    mpack_store_u32(p + MPACK_TAG_SIZE_EXT8, nanoseconds);
-    mpack_store_i64(p + MPACK_TAG_SIZE_EXT8 + 4, seconds);
-}
-#endif
-
-
-
-/*
- * Write functions
- */
-
-// This is a macro wrapper to the encode functions to encode
-// directly into the buffer. If mpack_writer_ensure() fails
-// it will flag an error so we don't have to do anything.
-#define MPACK_WRITE_ENCODED(encode_fn, size, ...) do {                                                 \
-    if (MPACK_LIKELY(mpack_writer_buffer_left(writer) >= size) || mpack_writer_ensure(writer, size)) { \
-        MPACK_EXPAND(encode_fn(writer->position, __VA_ARGS__));                                        \
-        writer->position += size;                                                                      \
-    }                                                                                                  \
-} while (0)
-
-void mpack_write_u8(mpack_writer_t* writer, uint8_t value) {
-    #if MPACK_OPTIMIZE_FOR_SIZE
-    mpack_write_u64(writer, value);
-    #else
-    mpack_writer_track_element(writer);
-    if (value <= 127) {
-        MPACK_WRITE_ENCODED(mpack_encode_fixuint, MPACK_TAG_SIZE_FIXUINT, value);
-    } else {
-        MPACK_WRITE_ENCODED(mpack_encode_u8, MPACK_TAG_SIZE_U8, value);
-    }
-    #endif
-}
-
-void mpack_write_u16(mpack_writer_t* writer, uint16_t value) {
-    #if MPACK_OPTIMIZE_FOR_SIZE
-    mpack_write_u64(writer, value);
-    #else
-    mpack_writer_track_element(writer);
-    if (value <= 127) {
-        MPACK_WRITE_ENCODED(mpack_encode_fixuint, MPACK_TAG_SIZE_FIXUINT, (uint8_t)value);
-    } else if (value <= MPACK_UINT8_MAX) {
-        MPACK_WRITE_ENCODED(mpack_encode_u8, MPACK_TAG_SIZE_U8, (uint8_t)value);
-    } else {
-        MPACK_WRITE_ENCODED(mpack_encode_u16, MPACK_TAG_SIZE_U16, value);
-    }
-    #endif
-}
-
-void mpack_write_u32(mpack_writer_t* writer, uint32_t value) {
-    #if MPACK_OPTIMIZE_FOR_SIZE
-    mpack_write_u64(writer, value);
-    #else
-    mpack_writer_track_element(writer);
-    if (value <= 127) {
-        MPACK_WRITE_ENCODED(mpack_encode_fixuint, MPACK_TAG_SIZE_FIXUINT, (uint8_t)value);
-    } else if (value <= MPACK_UINT8_MAX) {
-        MPACK_WRITE_ENCODED(mpack_encode_u8, MPACK_TAG_SIZE_U8, (uint8_t)value);
-    } else if (value <= MPACK_UINT16_MAX) {
-        MPACK_WRITE_ENCODED(mpack_encode_u16, MPACK_TAG_SIZE_U16, (uint16_t)value);
-    } else {
-        MPACK_WRITE_ENCODED(mpack_encode_u32, MPACK_TAG_SIZE_U32, value);
-    }
-    #endif
-}
-
-void mpack_write_u64(mpack_writer_t* writer, uint64_t value) {
-    mpack_writer_track_element(writer);
-
-    if (value <= 127) {
-        MPACK_WRITE_ENCODED(mpack_encode_fixuint, MPACK_TAG_SIZE_FIXUINT, (uint8_t)value);
-    } else if (value <= MPACK_UINT8_MAX) {
-        MPACK_WRITE_ENCODED(mpack_encode_u8, MPACK_TAG_SIZE_U8, (uint8_t)value);
-    } else if (value <= MPACK_UINT16_MAX) {
-        MPACK_WRITE_ENCODED(mpack_encode_u16, MPACK_TAG_SIZE_U16, (uint16_t)value);
-    } else if (value <= MPACK_UINT32_MAX) {
-        MPACK_WRITE_ENCODED(mpack_encode_u32, MPACK_TAG_SIZE_U32, (uint32_t)value);
-    } else {
-        MPACK_WRITE_ENCODED(mpack_encode_u64, MPACK_TAG_SIZE_U64, value);
-    }
-}
-
-void mpack_write_i8(mpack_writer_t* writer, int8_t value) {
-    #if MPACK_OPTIMIZE_FOR_SIZE
-    mpack_write_i64(writer, value);
-    #else
-    mpack_writer_track_element(writer);
-    if (value >= -32) {
-        // we encode positive and negative fixints together
-        MPACK_WRITE_ENCODED(mpack_encode_fixint, MPACK_TAG_SIZE_FIXINT, (int8_t)value);
-    } else {
-        MPACK_WRITE_ENCODED(mpack_encode_i8, MPACK_TAG_SIZE_I8, (int8_t)value);
-    }
-    #endif
-}
-
-void mpack_write_i16(mpack_writer_t* writer, int16_t value) {
-    #if MPACK_OPTIMIZE_FOR_SIZE
-    mpack_write_i64(writer, value);
-    #else
-    mpack_writer_track_element(writer);
-    if (value >= -32) {
-        if (value <= 127) {
-            // we encode positive and negative fixints together
-            MPACK_WRITE_ENCODED(mpack_encode_fixint, MPACK_TAG_SIZE_FIXINT, (int8_t)value);
-        } else if (value <= MPACK_UINT8_MAX) {
-            MPACK_WRITE_ENCODED(mpack_encode_u8, MPACK_TAG_SIZE_U8, (uint8_t)value);
-        } else {
-            MPACK_WRITE_ENCODED(mpack_encode_u16, MPACK_TAG_SIZE_U16, (uint16_t)value);
-        }
-    } else if (value >= MPACK_INT8_MIN) {
-        MPACK_WRITE_ENCODED(mpack_encode_i8, MPACK_TAG_SIZE_I8, (int8_t)value);
-    } else {
-        MPACK_WRITE_ENCODED(mpack_encode_i16, MPACK_TAG_SIZE_I16, (int16_t)value);
-    }
-    #endif
-}
-
-void mpack_write_i32(mpack_writer_t* writer, int32_t value) {
-    #if MPACK_OPTIMIZE_FOR_SIZE
-    mpack_write_i64(writer, value);
-    #else
-    mpack_writer_track_element(writer);
-    if (value >= -32) {
-        if (value <= 127) {
-            // we encode positive and negative fixints together
-            MPACK_WRITE_ENCODED(mpack_encode_fixint, MPACK_TAG_SIZE_FIXINT, (int8_t)value);
-        } else if (value <= MPACK_UINT8_MAX) {
-            MPACK_WRITE_ENCODED(mpack_encode_u8, MPACK_TAG_SIZE_U8, (uint8_t)value);
-        } else if (value <= MPACK_UINT16_MAX) {
-            MPACK_WRITE_ENCODED(mpack_encode_u16, MPACK_TAG_SIZE_U16, (uint16_t)value);
-        } else {
-            MPACK_WRITE_ENCODED(mpack_encode_u32, MPACK_TAG_SIZE_U32, (uint32_t)value);
-        }
-    } else if (value >= MPACK_INT8_MIN) {
-        MPACK_WRITE_ENCODED(mpack_encode_i8, MPACK_TAG_SIZE_I8, (int8_t)value);
-    } else if (value >= MPACK_INT16_MIN) {
-        MPACK_WRITE_ENCODED(mpack_encode_i16, MPACK_TAG_SIZE_I16, (int16_t)value);
-    } else {
-        MPACK_WRITE_ENCODED(mpack_encode_i32, MPACK_TAG_SIZE_I32, value);
-    }
-    #endif
-}
-
-void mpack_write_i64(mpack_writer_t* writer, int64_t value) {
-    #if MPACK_OPTIMIZE_FOR_SIZE
-    if (value > 127) {
-        // for non-fix positive ints we call the u64 writer to save space
-        mpack_write_u64(writer, (uint64_t)value);
-        return;
-    }
-    #endif
-
-    mpack_writer_track_element(writer);
-    if (value >= -32) {
-        #if MPACK_OPTIMIZE_FOR_SIZE
-        MPACK_WRITE_ENCODED(mpack_encode_fixint, MPACK_TAG_SIZE_FIXINT, (int8_t)value);
-        #else
-        if (value <= 127) {
-            MPACK_WRITE_ENCODED(mpack_encode_fixint, MPACK_TAG_SIZE_FIXINT, (int8_t)value);
-        } else if (value <= MPACK_UINT8_MAX) {
-            MPACK_WRITE_ENCODED(mpack_encode_u8, MPACK_TAG_SIZE_U8, (uint8_t)value);
-        } else if (value <= MPACK_UINT16_MAX) {
-            MPACK_WRITE_ENCODED(mpack_encode_u16, MPACK_TAG_SIZE_U16, (uint16_t)value);
-        } else if (value <= MPACK_UINT32_MAX) {
-            MPACK_WRITE_ENCODED(mpack_encode_u32, MPACK_TAG_SIZE_U32, (uint32_t)value);
-        } else {
-            MPACK_WRITE_ENCODED(mpack_encode_u64, MPACK_TAG_SIZE_U64, (uint64_t)value);
-        }
-        #endif
-    } else if (value >= MPACK_INT8_MIN) {
-        MPACK_WRITE_ENCODED(mpack_encode_i8, MPACK_TAG_SIZE_I8, (int8_t)value);
-    } else if (value >= MPACK_INT16_MIN) {
-        MPACK_WRITE_ENCODED(mpack_encode_i16, MPACK_TAG_SIZE_I16, (int16_t)value);
-    } else if (value >= MPACK_INT32_MIN) {
-        MPACK_WRITE_ENCODED(mpack_encode_i32, MPACK_TAG_SIZE_I32, (int32_t)value);
-    } else {
-        MPACK_WRITE_ENCODED(mpack_encode_i64, MPACK_TAG_SIZE_I64, value);
-    }
-}
-
-#if MPACK_FLOAT
-void mpack_write_float(mpack_writer_t* writer, float value) {
-    mpack_writer_track_element(writer);
-    MPACK_WRITE_ENCODED(mpack_encode_float, MPACK_TAG_SIZE_FLOAT, value);
-}
-#else
-void mpack_write_raw_float(mpack_writer_t* writer, uint32_t value) {
-    mpack_writer_track_element(writer);
-    MPACK_WRITE_ENCODED(mpack_encode_raw_float, MPACK_TAG_SIZE_FLOAT, value);
-}
-#endif
-
-#if MPACK_DOUBLE
-void mpack_write_double(mpack_writer_t* writer, double value) {
-    mpack_writer_track_element(writer);
-    MPACK_WRITE_ENCODED(mpack_encode_double, MPACK_TAG_SIZE_DOUBLE, value);
-}
-#else
-void mpack_write_raw_double(mpack_writer_t* writer, uint64_t value) {
-    mpack_writer_track_element(writer);
-    MPACK_WRITE_ENCODED(mpack_encode_raw_double, MPACK_TAG_SIZE_DOUBLE, value);
-}
-#endif
-
-#if MPACK_EXTENSIONS
-void mpack_write_timestamp(mpack_writer_t* writer, int64_t seconds, uint32_t nanoseconds) {
-    #if MPACK_COMPATIBILITY
-    if (writer->version <= mpack_version_v4) {
-        mpack_break("Timestamps require spec version v5 or later. This writer is in v%i mode.", (int)writer->version);
-        mpack_writer_flag_error(writer, mpack_error_bug);
-        return;
-    }
-    #endif
-
-    if (nanoseconds > MPACK_TIMESTAMP_NANOSECONDS_MAX) {
-        mpack_break("timestamp nanoseconds out of bounds: %u", nanoseconds);
-        mpack_writer_flag_error(writer, mpack_error_bug);
-        return;
-    }
-
-    mpack_writer_track_element(writer);
-
-    if (seconds < 0 || seconds >= (MPACK_INT64_C(1) << 34)) {
-        MPACK_WRITE_ENCODED(mpack_encode_timestamp_12, MPACK_EXT_SIZE_TIMESTAMP12, seconds, nanoseconds);
-    } else if (seconds > MPACK_UINT32_MAX || nanoseconds > 0) {
-        MPACK_WRITE_ENCODED(mpack_encode_timestamp_8, MPACK_EXT_SIZE_TIMESTAMP8, seconds, nanoseconds);
-    } else {
-        MPACK_WRITE_ENCODED(mpack_encode_timestamp_4, MPACK_EXT_SIZE_TIMESTAMP4, (uint32_t)seconds);
-    }
-}
-#endif
-
-static void mpack_write_array_notrack(mpack_writer_t* writer, uint32_t count) {
-    if (count <= 15) {
-        MPACK_WRITE_ENCODED(mpack_encode_fixarray, MPACK_TAG_SIZE_FIXARRAY, (uint8_t)count);
-    } else if (count <= MPACK_UINT16_MAX) {
-        MPACK_WRITE_ENCODED(mpack_encode_array16, MPACK_TAG_SIZE_ARRAY16, (uint16_t)count);
-    } else {
-        MPACK_WRITE_ENCODED(mpack_encode_array32, MPACK_TAG_SIZE_ARRAY32, (uint32_t)count);
-    }
-}
-
-static void mpack_write_map_notrack(mpack_writer_t* writer, uint32_t count) {
-    if (count <= 15) {
-        MPACK_WRITE_ENCODED(mpack_encode_fixmap, MPACK_TAG_SIZE_FIXMAP, (uint8_t)count);
-    } else if (count <= MPACK_UINT16_MAX) {
-        MPACK_WRITE_ENCODED(mpack_encode_map16, MPACK_TAG_SIZE_MAP16, (uint16_t)count);
-    } else {
-        MPACK_WRITE_ENCODED(mpack_encode_map32, MPACK_TAG_SIZE_MAP32, (uint32_t)count);
-    }
-}
-
-void mpack_start_array(mpack_writer_t* writer, uint32_t count) {
-    mpack_writer_track_element(writer);
-    mpack_write_array_notrack(writer, count);
-    mpack_writer_track_push(writer, mpack_type_array, count);
-    mpack_builder_compound_push(writer);
-}
-
-void mpack_start_map(mpack_writer_t* writer, uint32_t count) {
-    mpack_writer_track_element(writer);
-    mpack_write_map_notrack(writer, count);
-    mpack_writer_track_push(writer, mpack_type_map, count);
-    mpack_builder_compound_push(writer);
-}
-
-static void mpack_start_str_notrack(mpack_writer_t* writer, uint32_t count) {
-    if (count <= 31) {
-        MPACK_WRITE_ENCODED(mpack_encode_fixstr, MPACK_TAG_SIZE_FIXSTR, (uint8_t)count);
-
-    // str8 is only supported in v5 or later.
-    } else if (count <= MPACK_UINT8_MAX
-            #if MPACK_COMPATIBILITY
-            && writer->version >= mpack_version_v5
-            #endif
-            ) {
-        MPACK_WRITE_ENCODED(mpack_encode_str8, MPACK_TAG_SIZE_STR8, (uint8_t)count);
-
-    } else if (count <= MPACK_UINT16_MAX) {
-        MPACK_WRITE_ENCODED(mpack_encode_str16, MPACK_TAG_SIZE_STR16, (uint16_t)count);
-    } else {
-        MPACK_WRITE_ENCODED(mpack_encode_str32, MPACK_TAG_SIZE_STR32, (uint32_t)count);
-    }
-}
-
-static void mpack_start_bin_notrack(mpack_writer_t* writer, uint32_t count) {
-    #if MPACK_COMPATIBILITY
-    // In the v4 spec, there was only the raw type for any kind of
-    // variable-length data. In v4 mode, we support the bin functions,
-    // but we produce an old-style raw.
-    if (writer->version <= mpack_version_v4) {
-        mpack_start_str_notrack(writer, count);
-        return;
-    }
-    #endif
-
-    if (count <= MPACK_UINT8_MAX) {
-        MPACK_WRITE_ENCODED(mpack_encode_bin8, MPACK_TAG_SIZE_BIN8, (uint8_t)count);
-    } else if (count <= MPACK_UINT16_MAX) {
-        MPACK_WRITE_ENCODED(mpack_encode_bin16, MPACK_TAG_SIZE_BIN16, (uint16_t)count);
-    } else {
-        MPACK_WRITE_ENCODED(mpack_encode_bin32, MPACK_TAG_SIZE_BIN32, (uint32_t)count);
-    }
-}
-
-void mpack_start_str(mpack_writer_t* writer, uint32_t count) {
-    mpack_writer_track_element(writer);
-    mpack_start_str_notrack(writer, count);
-    mpack_writer_track_push(writer, mpack_type_str, count);
-}
-
-void mpack_start_bin(mpack_writer_t* writer, uint32_t count) {
-    mpack_writer_track_element(writer);
-    mpack_start_bin_notrack(writer, count);
-    mpack_writer_track_push(writer, mpack_type_bin, count);
-}
-
-#if MPACK_EXTENSIONS
-void mpack_start_ext(mpack_writer_t* writer, int8_t exttype, uint32_t count) {
-    #if MPACK_COMPATIBILITY
-    if (writer->version <= mpack_version_v4) {
-        mpack_break("Ext types require spec version v5 or later. This writer is in v%i mode.", (int)writer->version);
-        mpack_writer_flag_error(writer, mpack_error_bug);
-        return;
-    }
-    #endif
-
-    mpack_writer_track_element(writer);
-
-    if (count == 1) {
-        MPACK_WRITE_ENCODED(mpack_encode_fixext1, MPACK_TAG_SIZE_FIXEXT1, exttype);
-    } else if (count == 2) {
-        MPACK_WRITE_ENCODED(mpack_encode_fixext2, MPACK_TAG_SIZE_FIXEXT2, exttype);
-    } else if (count == 4) {
-        MPACK_WRITE_ENCODED(mpack_encode_fixext4, MPACK_TAG_SIZE_FIXEXT4, exttype);
-    } else if (count == 8) {
-        MPACK_WRITE_ENCODED(mpack_encode_fixext8, MPACK_TAG_SIZE_FIXEXT8, exttype);
-    } else if (count == 16) {
-        MPACK_WRITE_ENCODED(mpack_encode_fixext16, MPACK_TAG_SIZE_FIXEXT16, exttype);
-    } else if (count <= MPACK_UINT8_MAX) {
-        MPACK_WRITE_ENCODED(mpack_encode_ext8, MPACK_TAG_SIZE_EXT8, exttype, (uint8_t)count);
-    } else if (count <= MPACK_UINT16_MAX) {
-        MPACK_WRITE_ENCODED(mpack_encode_ext16, MPACK_TAG_SIZE_EXT16, exttype, (uint16_t)count);
-    } else {
-        MPACK_WRITE_ENCODED(mpack_encode_ext32, MPACK_TAG_SIZE_EXT32, exttype, (uint32_t)count);
-    }
-
-    mpack_writer_track_push(writer, mpack_type_ext, count);
-}
-#endif
-
-
-
-/*
- * Compound helpers and other functions
- */
-
-void mpack_write_str(mpack_writer_t* writer, const char* data, uint32_t count) {
-    mpack_assert(data != NULL, "data for string of length %i is NULL", (int)count);
-
-    #if MPACK_OPTIMIZE_FOR_SIZE
-    mpack_writer_track_element(writer);
-    mpack_start_str_notrack(writer, count);
-    mpack_write_native(writer, data, count);
-    #else
-
-    mpack_writer_track_element(writer);
-
-    if (count <= 31) {
-        // The minimum buffer size when using a flush function is guaranteed to
-        // fit the largest possible fixstr.
-        size_t size = count + MPACK_TAG_SIZE_FIXSTR;
-        if (MPACK_LIKELY(mpack_writer_buffer_left(writer) >= size) || mpack_writer_ensure(writer, size)) {
-            char* MPACK_RESTRICT p = writer->position;
-            mpack_encode_fixstr(p, (uint8_t)count);
-            mpack_memcpy(p + MPACK_TAG_SIZE_FIXSTR, data, count);
-            writer->position += count + MPACK_TAG_SIZE_FIXSTR;
-        }
-        return;
-    }
-
-    if (count <= MPACK_UINT8_MAX
-            #if MPACK_COMPATIBILITY
-            && writer->version >= mpack_version_v5
-            #endif
-            ) {
-        if (count + MPACK_TAG_SIZE_STR8 <= mpack_writer_buffer_left(writer)) {
-            char* MPACK_RESTRICT p = writer->position;
-            mpack_encode_str8(p, (uint8_t)count);
-            mpack_memcpy(p + MPACK_TAG_SIZE_STR8, data, count);
-            writer->position += count + MPACK_TAG_SIZE_STR8;
-        } else {
-            MPACK_WRITE_ENCODED(mpack_encode_str8, MPACK_TAG_SIZE_STR8, (uint8_t)count);
-            mpack_write_native(writer, data, count);
-        }
-        return;
-    }
-
-    // str16 and str32 are likely to be a significant fraction of the buffer
-    // size, so we don't bother with a combined space check in order to
-    // minimize code size.
-    if (count <= MPACK_UINT16_MAX) {
-        MPACK_WRITE_ENCODED(mpack_encode_str16, MPACK_TAG_SIZE_STR16, (uint16_t)count);
-        mpack_write_native(writer, data, count);
-    } else {
-        MPACK_WRITE_ENCODED(mpack_encode_str32, MPACK_TAG_SIZE_STR32, (uint32_t)count);
-        mpack_write_native(writer, data, count);
-    }
-
-    #endif
-}
-
-void mpack_write_bin(mpack_writer_t* writer, const char* data, uint32_t count) {
-    mpack_assert(data != NULL, "data pointer for bin of %i bytes is NULL", (int)count);
-    mpack_start_bin(writer, count);
-    mpack_write_bytes(writer, data, count);
-    mpack_finish_bin(writer);
-}
-
-#if MPACK_EXTENSIONS
-void mpack_write_ext(mpack_writer_t* writer, int8_t exttype, const char* data, uint32_t count) {
-    mpack_assert(data != NULL, "data pointer for ext of type %i and %i bytes is NULL", exttype, (int)count);
-    mpack_start_ext(writer, exttype, count);
-    mpack_write_bytes(writer, data, count);
-    mpack_finish_ext(writer);
-}
-#endif
-
-void mpack_write_bytes(mpack_writer_t* writer, const char* data, size_t count) {
-    mpack_assert(data != NULL, "data pointer for %i bytes is NULL", (int)count);
-    mpack_writer_track_bytes(writer, count);
-    mpack_write_native(writer, data, count);
-}
-
-void mpack_write_cstr(mpack_writer_t* writer, const char* cstr) {
-    mpack_assert(cstr != NULL, "cstr pointer is NULL");
-    size_t length = mpack_strlen(cstr);
-    if (length > MPACK_UINT32_MAX)
-        mpack_writer_flag_error(writer, mpack_error_invalid);
-    mpack_write_str(writer, cstr, (uint32_t)length);
-}
-
-void mpack_write_cstr_or_nil(mpack_writer_t* writer, const char* cstr) {
-    if (cstr)
-        mpack_write_cstr(writer, cstr);
-    else
-        mpack_write_nil(writer);
-}
-
-void mpack_write_utf8(mpack_writer_t* writer, const char* str, uint32_t length) {
-    mpack_assert(str != NULL, "data for string of length %i is NULL", (int)length);
-    if (!mpack_utf8_check(str, length)) {
-        mpack_writer_flag_error(writer, mpack_error_invalid);
-        return;
-    }
-    mpack_write_str(writer, str, length);
-}
-
-void mpack_write_utf8_cstr(mpack_writer_t* writer, const char* cstr) {
-    mpack_assert(cstr != NULL, "cstr pointer is NULL");
-    size_t length = mpack_strlen(cstr);
-    if (length > MPACK_UINT32_MAX) {
-        mpack_writer_flag_error(writer, mpack_error_invalid);
-        return;
-    }
-    mpack_write_utf8(writer, cstr, (uint32_t)length);
-}
-
-void mpack_write_utf8_cstr_or_nil(mpack_writer_t* writer, const char* cstr) {
-    if (cstr)
-        mpack_write_utf8_cstr(writer, cstr);
-    else
-        mpack_write_nil(writer);
-}
-
-/*
- * Builder implementation
- *
- * When a writer is in build mode, it diverts writes to an internal growable
- * buffer. All elements other than builder start tags are encoded as normal
- * into the builder buffer (even nested maps and arrays of known size, e.g.
- * `mpack_start_array()`.) But for compound elements of unknown size, an
- * mpack_build_t is written to the buffer instead.
- *
- * The mpack_build_t tracks everything needed to re-constitute the final
- * message once all sizes are known. When the last build element is completed,
- * the builder resolves the build by walking through the builds, outputting the
- * final encoded tag, and copying everything in between to the writer's true
- * buffer.
- *
- * To make things extra complicated, the builder buffer is not contiguous. It's
- * allocated in pages, where the first page may be an internal page in the
- * writer. But, each mpack_build_t must itself be contiguous and aligned
- * properly within the buffer. This means bytes can be skipped (and wasted)
- * before the builds or at the end of pages.
- *
- * To keep track of this, builds store both their element count and the number
- * of encoded bytes that follow, and pages store the number of bytes used. As
- * elements are written, each element adds to the count in the current open
- * build, and the number of bytes written adds to the current page and the byte
- * count in the last started build (whether or not it is completed.)
- */
-
-#if MPACK_BUILDER
-
-#ifdef MPACK_ALIGNOF
-    #define MPACK_BUILD_ALIGNMENT MPACK_ALIGNOF(mpack_build_t)
-#else
-    // without alignof, we just align to the greater of size_t, void* and uint64_t.
-    // (we do this even though we don't have uint64_t in it in case we add it later.)
-    #define MPACK_BUILD_ALIGNMENT_MAX(x, y) ((x) > (y) ? (x) : (y))
-    #define MPACK_BUILD_ALIGNMENT (MPACK_BUILD_ALIGNMENT_MAX(sizeof(void*), \
-                MPACK_BUILD_ALIGNMENT_MAX(sizeof(size_t), sizeof(uint64_t))))
-#endif
-
-static inline void mpack_builder_check_sizes(mpack_writer_t* writer) {
-
-    // We check internal and page sizes here so that we don't have to check
-    // them again. A new page with a build in it will have a page header,
-    // build, and minimum space for a tag. This will perform horribly and waste
-    // tons of memory if the page size is small, so you're best off just
-    // sticking with the defaults.
-    //
-    // These are all known at compile time, so if they are large
-    // enough this function should trivially optimize to a no-op.
-
-    #if MPACK_BUILDER_INTERNAL_STORAGE
-    // make sure the internal storage is big enough to be useful
-    MPACK_STATIC_ASSERT(MPACK_BUILDER_INTERNAL_STORAGE_SIZE >= (sizeof(mpack_builder_page_t) +
-            sizeof(mpack_build_t) + MPACK_WRITER_MINIMUM_BUFFER_SIZE),
-            "MPACK_BUILDER_INTERNAL_STORAGE_SIZE is too small to be useful!");
-    if (MPACK_BUILDER_INTERNAL_STORAGE_SIZE < (sizeof(mpack_builder_page_t) +
-            sizeof(mpack_build_t) + MPACK_WRITER_MINIMUM_BUFFER_SIZE))
-    {
-        mpack_break("MPACK_BUILDER_INTERNAL_STORAGE_SIZE is too small to be useful!");
-        mpack_writer_flag_error(writer, mpack_error_bug);
-    }
-    #endif
-
-    // make sure the builder page size is big enough to be useful
-    MPACK_STATIC_ASSERT(MPACK_BUILDER_PAGE_SIZE >= (sizeof(mpack_builder_page_t) +
-            sizeof(mpack_build_t) + MPACK_WRITER_MINIMUM_BUFFER_SIZE),
-            "MPACK_BUILDER_PAGE_SIZE is too small to be useful!");
-    if (MPACK_BUILDER_PAGE_SIZE < (sizeof(mpack_builder_page_t) +
-            sizeof(mpack_build_t) + MPACK_WRITER_MINIMUM_BUFFER_SIZE))
-    {
-        mpack_break("MPACK_BUILDER_PAGE_SIZE is too small to be useful!");
-        mpack_writer_flag_error(writer, mpack_error_bug);
-    }
-}
-
-static inline size_t mpack_builder_page_size(mpack_writer_t* writer, mpack_builder_page_t* page) {
-    #if MPACK_BUILDER_INTERNAL_STORAGE
-    if ((char*)page == writer->builder.internal)
-        return sizeof(writer->builder.internal);
-    #else
-    (void)writer;
-    (void)page;
-    #endif
-    return MPACK_BUILDER_PAGE_SIZE;
-}
-
-static inline size_t mpack_builder_align_build(size_t bytes_used) {
-    size_t offset = bytes_used;
-    offset += MPACK_BUILD_ALIGNMENT - 1;
-    offset -= offset % MPACK_BUILD_ALIGNMENT;
-    mpack_log("aligned %zi to %zi\n", bytes_used, offset);
-    return offset;
-}
-
-static inline void mpack_builder_free_page(mpack_writer_t* writer, mpack_builder_page_t* page) {
-    mpack_log("freeing page %p\n", (void*)page);
-    #if MPACK_BUILDER_INTERNAL_STORAGE
-    if ((char*)page == writer->builder.internal)
-        return;
-    #else
-    (void)writer;
-    #endif
-    MPACK_FREE(page);
-}
-
-static inline size_t mpack_builder_page_remaining(mpack_writer_t* writer, mpack_builder_page_t* page) {
-    return mpack_builder_page_size(writer, page) - page->bytes_used;
-}
-
-static void mpack_builder_configure_buffer(mpack_writer_t* writer) {
-    if (mpack_writer_error(writer) != mpack_ok)
-        return;
-    mpack_builder_t* builder = &writer->builder;
-
-    mpack_builder_page_t* page = builder->current_page;
-    mpack_assert(page != NULL, "page is null??");
-
-    // This diverts the writer into the remainder of the current page of our
-    // build buffer.
-    writer->buffer = (char*)page + page->bytes_used;
-    writer->position = (char*)page + page->bytes_used;
-    writer->end = (char*)page + mpack_builder_page_size(writer, page);
-    mpack_log("configuring buffer from %p to %p\n", (void*)writer->position, (void*)writer->end);
-}
-
-static void mpack_builder_add_page(mpack_writer_t* writer) {
-    mpack_builder_t* builder = &writer->builder;
-    mpack_assert(writer->error == mpack_ok);
-
-    mpack_log("adding a page.\n");
-    mpack_builder_page_t* page = (mpack_builder_page_t*)MPACK_MALLOC(MPACK_BUILDER_PAGE_SIZE);
-    if (page == NULL) {
-        mpack_writer_flag_error(writer, mpack_error_memory);
-        return;
-    }
-
-    page->next = NULL;
-    page->bytes_used = sizeof(mpack_builder_page_t);
-    builder->current_page->next = page;
-    builder->current_page = page;
-}
-
-// Checks how many bytes the writer wrote to the page, adding it to the page's
-// bytes_used. This must be followed up with mpack_builder_configure_buffer()
-// (after adding a new page, build, etc) to reset the writer's buffer pointers.
-static void mpack_builder_apply_writes(mpack_writer_t* writer) {
-    mpack_assert(writer->error == mpack_ok);
-    mpack_builder_t* builder = &writer->builder;
-    mpack_log("latest build is %p\n", (void*)builder->latest_build);
-
-    // The difference between buffer and current is the number of bytes that
-    // were written to the page.
-    size_t bytes_written = (size_t)(writer->position - writer->buffer);
-    mpack_log("applying write of %zi bytes to build %p\n", bytes_written, (void*)builder->latest_build);
-
-    mpack_assert(builder->current_page != NULL);
-    mpack_assert(builder->latest_build != NULL);
-    builder->current_page->bytes_used += bytes_written;
-    builder->latest_build->bytes += bytes_written;
-    mpack_log("latest build %p now has %zi bytes\n", (void*)builder->latest_build, builder->latest_build->bytes);
-}
-
-static void mpack_builder_flush(mpack_writer_t* writer) {
-    mpack_assert(writer->error == mpack_ok);
-    mpack_builder_apply_writes(writer);
-    mpack_builder_add_page(writer);
-    mpack_builder_configure_buffer(writer);
-}
-
-MPACK_NOINLINE static void mpack_builder_begin(mpack_writer_t* writer) {
-    mpack_builder_t* builder = &writer->builder;
-    mpack_assert(writer->error == mpack_ok);
-    mpack_assert(builder->current_build == NULL);
-    mpack_assert(builder->latest_build == NULL);
-    mpack_assert(builder->pages == NULL);
-
-    // If this is the first build, we need to stash the real buffer backing our
-    // writer. We'll be diverting the writer to our build buffer.
-    builder->stash_buffer = writer->buffer;
-    builder->stash_position = writer->position;
-    builder->stash_end = writer->end;
-
-    mpack_builder_page_t* page;
-
-    // we've checked that both these sizes are large enough above.
-    #if MPACK_BUILDER_INTERNAL_STORAGE
-    page = (mpack_builder_page_t*)builder->internal;
-    mpack_log("beginning builder with internal storage %p\n", (void*)page);
-    #else
-    page = (mpack_builder_page_t*)MPACK_MALLOC(MPACK_BUILDER_PAGE_SIZE);
-    if (page == NULL) {
-        mpack_writer_flag_error(writer, mpack_error_memory);
-        return;
-    }
-    mpack_log("beginning builder with allocated page %p\n", (void*)page);
-    #endif
-
-    page->next = NULL;
-    page->bytes_used = sizeof(mpack_builder_page_t);
-    builder->pages = page;
-    builder->current_page = page;
-}
-
-static void mpack_builder_build(mpack_writer_t* writer, mpack_type_t type) {
-    mpack_builder_check_sizes(writer);
-    if (mpack_writer_error(writer) != mpack_ok)
-        return;
-
-    mpack_writer_track_element(writer);
-    mpack_writer_track_push_builder(writer, type);
-
-    mpack_builder_t* builder = &writer->builder;
-
-    if (builder->current_build == NULL) {
-        mpack_builder_begin(writer);
-    } else {
-        mpack_builder_apply_writes(writer);
-    }
-    if (mpack_writer_error(writer) != mpack_ok)
-        return;
-
-    // find aligned space for a new build. if there isn't enough space in the
-    // current page, we discard the remaining space in it and allocate a new
-    // page.
-    size_t offset = mpack_builder_align_build(builder->current_page->bytes_used);
-    if (offset + sizeof(mpack_build_t) > mpack_builder_page_size(writer, builder->current_page)) {
-        mpack_log("not enough space for a build. %zi bytes used of %zi in this page\n",
-                builder->current_page->bytes_used, mpack_builder_page_size(writer, builder->current_page));
-        mpack_builder_add_page(writer);
-        // there is always enough space in a fresh page.
-        offset = mpack_builder_align_build(builder->current_page->bytes_used);
-    }
-
-    // allocate the build within the page. note that we don't keep track of the
-    // space wasted due to the offset. instead the previous build has stored
-    // how many bytes follow it, and we'll redo this offset calculation to find
-    // this build after it.
-    mpack_builder_page_t* page = builder->current_page;
-    page->bytes_used = offset + sizeof(mpack_build_t);
-    mpack_assert(page->bytes_used <= mpack_builder_page_size(writer, page));
-    mpack_build_t* build = (mpack_build_t*)((char*)page + offset);
-    mpack_log("created new build %p within page %p, which now has %zi bytes used\n",
-            (void*)build, (void*)page, page->bytes_used);
-
-    // configure the new build
-    build->parent = builder->current_build;
-    build->bytes = 0;
-    build->count = 0;
-    build->type = type;
-    build->key_needs_value = false;
-    build->nested_compound_elements = 0;
-
-    mpack_log("setting current and latest build to new build %p\n", (void*)build);
-    builder->current_build = build;
-    builder->latest_build = build;
-
-    // we always need to provide a buffer that meets the minimum buffer size.
-    // if there isn't enough space, we discard the remaining space in the
-    // current page and allocate a new one.
-    if (mpack_builder_page_remaining(writer, page) < MPACK_WRITER_MINIMUM_BUFFER_SIZE) {
-        mpack_log("less than minimum buffer size in current page. %zi bytes used of %zi in this page\n",
-                builder->current_page->bytes_used, mpack_builder_page_size(writer, builder->current_page));
-        mpack_builder_add_page(writer);
-        if (mpack_writer_error(writer) != mpack_ok)
-            return;
-    }
-    mpack_assert(mpack_builder_page_remaining(writer, builder->current_page) >= MPACK_WRITER_MINIMUM_BUFFER_SIZE);
-    mpack_builder_configure_buffer(writer);
-}
-
-MPACK_NOINLINE
-static void mpack_builder_resolve(mpack_writer_t* writer) {
-    mpack_builder_t* builder = &writer->builder;
-
-    // The starting page is the internal storage (if we have it), otherwise
-    // it's the first page in the array
-    mpack_builder_page_t* page =
-        #if MPACK_BUILDER_INTERNAL_STORAGE
-        (mpack_builder_page_t*)builder->internal
-        #else
-        builder->pages
-        #endif
-        ;
-
-    // We start by restoring the writer's original buffer so we can write the
-    // data for real.
-    writer->buffer = builder->stash_buffer;
-    writer->position = builder->stash_position;
-    writer->end = builder->stash_end;
-
-    // We can also close out the build now.
-    builder->current_build = NULL;
-    builder->latest_build = NULL;
-    builder->current_page = NULL;
-    builder->pages = NULL;
-
-    // the starting page always starts with the first build
-    size_t offset = mpack_builder_align_build(sizeof(mpack_builder_page_t));
-    mpack_build_t* build = (mpack_build_t*)((char*)page + offset);
-    mpack_log("starting resolve with build %p in page %p\n", (void*)build, (void*)page);
-
-    // encoded data immediately follows the build
-    offset += sizeof(mpack_build_t);
-
-    // Walk the list of builds, writing everything out in the buffer. Note that
-    // we don't check for errors anywhere. The lower-level write functions will
-    // all check for errors. We need to walk all pages anyway to free them, so
-    // there's not much point in optimizing an error path at the expense of the
-    // normal path.
-    while (true) {
-
-        // write out the container tag
-        mpack_log("writing out an %s with count %u followed by %zi bytes\n",
-                mpack_type_to_string(build->type), build->count, build->bytes);
-        switch (build->type) {
-            case mpack_type_map:
-                mpack_write_map_notrack(writer, build->count);
-                break;
-            case mpack_type_array:
-                mpack_write_array_notrack(writer, build->count);
-                break;
-            default:
-                mpack_break("invalid type in builder?");
-                mpack_writer_flag_error(writer, mpack_error_bug);
-                return;
-        }
-
-        // figure out how many bytes follow this container. we're going to be
-        // freeing pages as we write, so we need to be done with this build.
-        size_t left = build->bytes;
-        build = NULL;
-
-        // write out all bytes following this container
-        while (left > 0) {
-            size_t bytes_used = page->bytes_used;
-            if (offset < bytes_used) {
-                size_t step = bytes_used - offset;
-                if (step > left)
-                    step = left;
-                mpack_log("writing out %zi bytes starting at %p in page %p\n",
-                        step, (void*)((char*)page + offset), (void*)page);
-                mpack_write_native(writer, (char*)page + offset, step);
-                offset += step;
-                left -= step;
-            }
-
-            if (left == 0) {
-                mpack_log("done writing bytes for this build\n");
-                break;
-            }
-
-            // still need to write more bytes. free this page and jump to the
-            // next one.
-            mpack_builder_page_t* next_page = page->next;
-            mpack_builder_free_page(writer, page);
-            page = next_page;
-            // bytes on the next page immediately follow the header.
-            offset = sizeof(mpack_builder_page_t);
-        }
-
-        // now see if we can find another build.
-        offset = mpack_builder_align_build(offset);
-        if (offset + sizeof(mpack_build_t) >= mpack_builder_page_size(writer, page)) {
-            mpack_log("not enough room in this page for another build\n");
-            mpack_builder_page_t* next_page = page->next;
-            mpack_builder_free_page(writer, page);
-            page = next_page;
-            if (page == NULL) {
-                mpack_log("no more pages\n");
-                // there are no more pages. we're done.
-                break;
-            }
-            offset = mpack_builder_align_build(sizeof(mpack_builder_page_t));
-        }
-        if (offset + sizeof(mpack_build_t) > page->bytes_used) {
-            // there is no more data. we're done.
-            mpack_log("no more data\n");
-            mpack_builder_free_page(writer, page);
-            break;
-        }
-
-        // we've found another build. loop around!
-        build = (mpack_build_t*)((char*)page + offset);
-        offset += sizeof(mpack_build_t);
-        mpack_log("found build %p\n", (void*)build);
-    }
-
-    mpack_log("done resolve.\n");
-}
-
-static void mpack_builder_complete(mpack_writer_t* writer, mpack_type_t type) {
-    if (mpack_writer_error(writer) != mpack_ok)
-        return;
-
-    mpack_writer_track_pop_builder(writer, type);
-    mpack_builder_t* builder = &writer->builder;
-    mpack_assert(builder->current_build != NULL, "no build in progress!");
-    mpack_assert(builder->latest_build != NULL, "missing latest build!");
-    mpack_assert(builder->current_build->type == type, "completing wrong type!");
-    mpack_log("completing build %p\n", (void*)builder->current_build);
-
-    if (builder->current_build->key_needs_value) {
-        mpack_break("an odd number of elements were written in a map!");
-        mpack_writer_flag_error(writer, mpack_error_bug);
-        return;
-    }
-
-    if (builder->current_build->nested_compound_elements != 0) {
-        mpack_break("there is a nested unfinished non-build map or array in this build.");
-        mpack_writer_flag_error(writer, mpack_error_bug);
-        return;
-    }
-
-    // We need to apply whatever writes have been made to the current build
-    // before popping it.
-    mpack_builder_apply_writes(writer);
-
-    // For a nested build, we just switch the current build back to its parent.
-    if (builder->current_build->parent != NULL) {
-        mpack_log("setting current build to parent build %p. latest is still %p.\n",
-                (void*)builder->current_build->parent, (void*)builder->latest_build);
-        builder->current_build = builder->current_build->parent;
-        mpack_builder_configure_buffer(writer);
-    } else {
-        // We're completing the final build.
-        mpack_builder_resolve(writer);
-    }
-}
-
-void mpack_build_map(mpack_writer_t* writer) {
-    mpack_builder_build(writer, mpack_type_map);
-}
-
-void mpack_build_array(mpack_writer_t* writer) {
-    mpack_builder_build(writer, mpack_type_array);
-}
-
-void mpack_complete_map(mpack_writer_t* writer) {
-    mpack_builder_complete(writer, mpack_type_map);
-}
-
-void mpack_complete_array(mpack_writer_t* writer) {
-    mpack_builder_complete(writer, mpack_type_array);
-}
-
-#endif // MPACK_BUILDER
-#endif // MPACK_WRITER
-
-MPACK_SILENCE_WARNINGS_END
-
-/* mpack/mpack-reader.c.c */
-
-#define MPACK_INTERNAL 1
-
-/* #include "mpack-reader.h" */
-
-MPACK_SILENCE_WARNINGS_BEGIN
-
-#if MPACK_READER
-
-static void mpack_reader_skip_using_fill(mpack_reader_t* reader, size_t count);
-
-void mpack_reader_init(mpack_reader_t* reader, char* buffer, size_t size, size_t count) {
-    mpack_assert(buffer != NULL, "buffer is NULL");
-
-    mpack_memset(reader, 0, sizeof(*reader));
-    reader->buffer = buffer;
-    reader->size = size;
-    reader->data = buffer;
-    reader->end = buffer + count;
-
-    #if MPACK_READ_TRACKING
-    mpack_reader_flag_if_error(reader, mpack_track_init(&reader->track));
-    #endif
-
-    mpack_log("===========================\n");
-    mpack_log("initializing reader with buffer size %i\n", (int)size);
-}
-
-void mpack_reader_init_error(mpack_reader_t* reader, mpack_error_t error) {
-    mpack_memset(reader, 0, sizeof(*reader));
-    reader->error = error;
-
-    mpack_log("===========================\n");
-    mpack_log("initializing reader error state %i\n", (int)error);
-}
-
-void mpack_reader_init_data(mpack_reader_t* reader, const char* data, size_t count) {
-    mpack_assert(data != NULL, "data is NULL");
-
-    mpack_memset(reader, 0, sizeof(*reader));
-    reader->data = data;
-    reader->end = data + count;
-
-    #if MPACK_READ_TRACKING
-    mpack_reader_flag_if_error(reader, mpack_track_init(&reader->track));
-    #endif
-
-    mpack_log("===========================\n");
-    mpack_log("initializing reader with data size %i\n", (int)count);
-}
-
-void mpack_reader_set_fill(mpack_reader_t* reader, mpack_reader_fill_t fill) {
-    MPACK_STATIC_ASSERT(MPACK_READER_MINIMUM_BUFFER_SIZE >= MPACK_MAXIMUM_TAG_SIZE,
-            "minimum buffer size must fit any tag!");
-
-    if (reader->size == 0) {
-        mpack_break("cannot use fill function without a writeable buffer!");
-        mpack_reader_flag_error(reader, mpack_error_bug);
-        return;
-    }
-
-    if (reader->size < MPACK_READER_MINIMUM_BUFFER_SIZE) {
-        mpack_break("buffer size is %i, but minimum buffer size for fill is %i",
-                (int)reader->size, MPACK_READER_MINIMUM_BUFFER_SIZE);
-        mpack_reader_flag_error(reader, mpack_error_bug);
-        return;
-    }
-
-    reader->fill = fill;
-}
-
-void mpack_reader_set_skip(mpack_reader_t* reader, mpack_reader_skip_t skip) {
-    mpack_assert(reader->size != 0, "cannot use skip function without a writeable buffer!");
-    reader->skip = skip;
-}
-
-#if MPACK_STDIO
-static size_t mpack_file_reader_fill(mpack_reader_t* reader, char* buffer, size_t count) {
-    if (feof((FILE *)reader->context)) {
-       mpack_reader_flag_error(reader, mpack_error_eof);
-       return 0;
-    }
-    return fread((void*)buffer, 1, count, (FILE*)reader->context);
-}
-
-static void mpack_file_reader_skip(mpack_reader_t* reader, size_t count) {
-    if (mpack_reader_error(reader) != mpack_ok)
-        return;
-    FILE* file = (FILE*)reader->context;
-
-    // We call ftell() to test whether the stream is seekable
-    // without causing a file error.
-    if (ftell(file) >= 0) {
-        mpack_log("seeking forward %i bytes\n", (int)count);
-        if (fseek(file, (long int)count, SEEK_CUR) == 0)
-            return;
-        mpack_log("fseek() didn't return zero!\n");
-        if (ferror(file)) {
-            mpack_reader_flag_error(reader, mpack_error_io);
-            return;
-        }
-    }
-
-    // If the stream is not seekable, fall back to the fill function.
-    mpack_reader_skip_using_fill(reader, count);
-}
-
-static void mpack_file_reader_teardown(mpack_reader_t* reader) {
-    MPACK_FREE(reader->buffer);
-    reader->buffer = NULL;
-    reader->context = NULL;
-    reader->size = 0;
-    reader->fill = NULL;
-    reader->skip = NULL;
-    reader->teardown = NULL;
-}
-
-static void mpack_file_reader_teardown_close(mpack_reader_t* reader) {
-    FILE* file = (FILE*)reader->context;
-
-    if (file) {
-        int ret = fclose(file);
-        if (ret != 0)
-            mpack_reader_flag_error(reader, mpack_error_io);
-    }
-
-    mpack_file_reader_teardown(reader);
-}
-
-void mpack_reader_init_stdfile(mpack_reader_t* reader, FILE* file, bool close_when_done) {
-    mpack_assert(file != NULL, "file is NULL");
-
-    size_t capacity = MPACK_BUFFER_SIZE;
-    char* buffer = (char*)MPACK_MALLOC(capacity);
-    if (buffer == NULL) {
-        mpack_reader_init_error(reader, mpack_error_memory);
-        if (close_when_done) {
-            fclose(file);
-        }
-        return;
-    }
-
-    mpack_reader_init(reader, buffer, capacity, 0);
-    mpack_reader_set_context(reader, file);
-    mpack_reader_set_fill(reader, mpack_file_reader_fill);
-    mpack_reader_set_skip(reader, mpack_file_reader_skip);
-    mpack_reader_set_teardown(reader, close_when_done ?
-            mpack_file_reader_teardown_close :
-            mpack_file_reader_teardown);
-}
-
-void mpack_reader_init_filename(mpack_reader_t* reader, const char* filename) {
-    mpack_assert(filename != NULL, "filename is NULL");
-
-    FILE* file = fopen(filename, "rb");
-    if (file == NULL) {
-        mpack_reader_init_error(reader, mpack_error_io);
-        return;
-    }
-
-    mpack_reader_init_stdfile(reader, file, true);
-}
-#endif
-
-mpack_error_t mpack_reader_destroy(mpack_reader_t* reader) {
-
-    // clean up tracking, asserting if we're not already in an error state
-    #if MPACK_READ_TRACKING
-    mpack_reader_flag_if_error(reader, mpack_track_destroy(&reader->track, mpack_reader_error(reader) != mpack_ok));
-    #endif
-
-    if (reader->teardown)
-        reader->teardown(reader);
-    reader->teardown = NULL;
-
-    return reader->error;
-}
-
-size_t mpack_reader_remaining(mpack_reader_t* reader, const char** data) {
-    if (mpack_reader_error(reader) != mpack_ok)
-        return 0;
-
-    #if MPACK_READ_TRACKING
-    if (mpack_reader_flag_if_error(reader, mpack_track_check_empty(&reader->track)) != mpack_ok)
-        return 0;
-    #endif
-
-    if (data)
-        *data = reader->data;
-    return (size_t)(reader->end - reader->data);
-}
-
-void mpack_reader_flag_error(mpack_reader_t* reader, mpack_error_t error) {
-    mpack_log("reader %p setting error %i: %s\n", (void*)reader, (int)error, mpack_error_to_string(error));
-
-    if (reader->error == mpack_ok) {
-        reader->error = error;
-        reader->end = reader->data;
-        if (reader->error_fn)
-            reader->error_fn(reader, error);
-    }
-}
-
-// Loops on the fill function, reading between the minimum and
-// maximum number of bytes and flagging an error if it fails.
-MPACK_NOINLINE static size_t mpack_fill_range(mpack_reader_t* reader, char* p, size_t min_bytes, size_t max_bytes) {
-    mpack_assert(reader->fill != NULL, "mpack_fill_range() called with no fill function?");
-    mpack_assert(min_bytes > 0, "cannot fill zero bytes!");
-    mpack_assert(max_bytes >= min_bytes, "min_bytes %i cannot be larger than max_bytes %i!",
-            (int)min_bytes, (int)max_bytes);
-
-    size_t count = 0;
-    while (count < min_bytes) {
-        size_t read = reader->fill(reader, p + count, max_bytes - count);
-
-        // Reader fill functions can flag an error or return 0 on failure. We
-        // also guard against functions that return -1 just in case.
-        if (mpack_reader_error(reader) != mpack_ok)
-            return 0;
-        if (read == 0 || read == ((size_t)(-1))) {
-            mpack_reader_flag_error(reader, mpack_error_io);
-            return 0;
-        }
-
-        count += read;
-    }
-    return count;
-}
-
-MPACK_NOINLINE bool mpack_reader_ensure_straddle(mpack_reader_t* reader, size_t count) {
-    mpack_assert(count != 0, "cannot ensure zero bytes!");
-    mpack_assert(reader->error == mpack_ok, "reader cannot be in an error state!");
-
-    mpack_assert(count > (size_t)(reader->end - reader->data),
-            "straddling ensure requested for %i bytes, but there are %i bytes "
-            "left in buffer. call mpack_reader_ensure() instead",
-            (int)count, (int)(reader->end - reader->data));
-
-    // we'll need a fill function to get more data. if there's no
-    // fill function, the buffer should contain an entire MessagePack
-    // object, so we raise mpack_error_invalid instead of mpack_error_io
-    // on truncated data.
-    if (reader->fill == NULL) {
-        mpack_reader_flag_error(reader, mpack_error_invalid);
-        return false;
-    }
-
-    // we need enough space in the buffer. if the buffer is not
-    // big enough, we return mpack_error_too_big (since this is
-    // for an in-place read larger than the buffer size.)
-    if (count > reader->size) {
-        mpack_reader_flag_error(reader, mpack_error_too_big);
-        return false;
-    }
-
-    // move the existing data to the start of the buffer
-    size_t left = (size_t)(reader->end - reader->data);
-    mpack_memmove(reader->buffer, reader->data, left);
-    reader->end -= reader->data - reader->buffer;
-    reader->data = reader->buffer;
-
-    // read at least the necessary number of bytes, accepting up to the
-    // buffer size
-    size_t read = mpack_fill_range(reader, reader->buffer + left,
-            count - left, reader->size - left);
-    if (mpack_reader_error(reader) != mpack_ok)
-        return false;
-    reader->end += read;
-    return true;
-}
-
-// Reads count bytes into p. Used when there are not enough bytes
-// left in the buffer to satisfy a read.
-MPACK_NOINLINE void mpack_read_native_straddle(mpack_reader_t* reader, char* p, size_t count) {
-    mpack_assert(count == 0 || p != NULL, "data pointer for %i bytes is NULL", (int)count);
-
-    if (mpack_reader_error(reader) != mpack_ok) {
-        mpack_memset(p, 0, count);
-        return;
-    }
-
-    size_t left = (size_t)(reader->end - reader->data);
-    mpack_log("big read for %i bytes into %p, %i left in buffer, buffer size %i\n",
-            (int)count, p, (int)left, (int)reader->size);
-
-    if (count <= left) {
-        mpack_assert(0,
-                "big read requested for %i bytes, but there are %i bytes "
-                "left in buffer. call mpack_read_native() instead",
-                (int)count, (int)left);
-        mpack_reader_flag_error(reader, mpack_error_bug);
-        mpack_memset(p, 0, count);
-        return;
-    }
-
-    // we'll need a fill function to get more data. if there's no
-    // fill function, the buffer should contain an entire MessagePack
-    // object, so we raise mpack_error_invalid instead of mpack_error_io
-    // on truncated data.
-    if (reader->fill == NULL) {
-        mpack_reader_flag_error(reader, mpack_error_invalid);
-        mpack_memset(p, 0, count);
-        return;
-    }
-
-    if (reader->size == 0) {
-        // somewhat debatable what error should be returned here. when
-        // initializing a reader with an in-memory buffer it's not
-        // necessarily a bug if the data is blank; it might just have
-        // been truncated to zero. for this reason we return the same
-        // error as if the data was truncated.
-        mpack_reader_flag_error(reader, mpack_error_io);
-        mpack_memset(p, 0, count);
-        return;
-    }
-
-    // flush what's left of the buffer
-    if (left > 0) {
-        mpack_log("flushing %i bytes remaining in buffer\n", (int)left);
-        mpack_memcpy(p, reader->data, left);
-        count -= left;
-        p += left;
-        reader->data += left;
-    }
-
-    // if the remaining data needed is some small fraction of the
-    // buffer size, we'll try to fill the buffer as much as possible
-    // and copy the needed data out.
-    if (count <= reader->size / MPACK_READER_SMALL_FRACTION_DENOMINATOR) {
-        size_t read = mpack_fill_range(reader, reader->buffer, count, reader->size);
-        if (mpack_reader_error(reader) != mpack_ok)
-            return;
-        mpack_memcpy(p, reader->buffer, count);
-        reader->data = reader->buffer + count;
-        reader->end = reader->buffer + read;
-
-    // otherwise we read the remaining data directly into the target.
-    } else {
-        mpack_log("reading %i additional bytes\n", (int)count);
-        mpack_fill_range(reader, p, count, count);
-    }
-}
-
-MPACK_NOINLINE static void mpack_skip_bytes_straddle(mpack_reader_t* reader, size_t count) {
-
-    // we'll need at least a fill function to skip more data. if there's
-    // no fill function, the buffer should contain an entire MessagePack
-    // object, so we raise mpack_error_invalid instead of mpack_error_io
-    // on truncated data. (see mpack_read_native_straddle())
-    if (reader->fill == NULL) {
-        mpack_log("reader has no fill function!\n");
-        mpack_reader_flag_error(reader, mpack_error_invalid);
-        return;
-    }
-
-    // discard whatever's left in the buffer
-    size_t left = (size_t)(reader->end - reader->data);
-    mpack_log("discarding %i bytes still in buffer\n", (int)left);
-    count -= left;
-    reader->data = reader->end;
-
-    // use the skip function if we've got one, and if we're trying
-    // to skip a lot of data. if we only need to skip some tiny
-    // fraction of the buffer size, it's probably better to just
-    // fill the buffer and skip from it instead of trying to seek.
-    if (reader->skip && count > reader->size / 16) {
-        mpack_log("calling skip function for %i bytes\n", (int)count);
-        reader->skip(reader, count);
-        return;
-    }
-
-    mpack_reader_skip_using_fill(reader, count);
-}
-
-void mpack_skip_bytes(mpack_reader_t* reader, size_t count) {
-    if (mpack_reader_error(reader) != mpack_ok)
-        return;
-    mpack_log("skip requested for %i bytes\n", (int)count);
-
-    mpack_reader_track_bytes(reader, count);
-
-    // check if we have enough in the buffer already
-    size_t left = (size_t)(reader->end - reader->data);
-    if (left >= count) {
-        mpack_log("skipping %u bytes still in buffer\n", (uint32_t)count);
-        reader->data += count;
-        return;
-    }
-
-    mpack_skip_bytes_straddle(reader, count);
-}
-
-MPACK_NOINLINE static void mpack_reader_skip_using_fill(mpack_reader_t* reader, size_t count) {
-    mpack_assert(reader->fill != NULL, "missing fill function!");
-    mpack_assert(reader->data == reader->end, "there are bytes left in the buffer!");
-    mpack_assert(reader->error == mpack_ok, "should not have called this in an error state (%i)", reader->error);
-    mpack_log("skip using fill for %i bytes\n", (int)count);
-
-    // fill and discard multiples of the buffer size
-    while (count > reader->size) {
-        mpack_log("filling and discarding buffer of %i bytes\n", (int)reader->size);
-        if (mpack_fill_range(reader, reader->buffer, reader->size, reader->size) < reader->size) {
-            mpack_reader_flag_error(reader, mpack_error_io);
-            return;
-        }
-        count -= reader->size;
-    }
-
-    // fill the buffer as much as possible
-    reader->data = reader->buffer;
-    size_t read = mpack_fill_range(reader, reader->buffer, count, reader->size);
-    if (read < count) {
-        mpack_reader_flag_error(reader, mpack_error_io);
-        return;
-    }
-    reader->end = reader->data + read;
-    mpack_log("filled %i bytes into buffer; discarding %i bytes\n", (int)read, (int)count);
-    reader->data += count;
-}
-
-void mpack_read_bytes(mpack_reader_t* reader, char* p, size_t count) {
-    mpack_assert(p != NULL, "destination for read of %i bytes is NULL", (int)count);
-    mpack_reader_track_bytes(reader, count);
-    mpack_read_native(reader, p, count);
-}
-
-void mpack_read_utf8(mpack_reader_t* reader, char* p, size_t byte_count) {
-    mpack_assert(p != NULL, "destination for read of %i bytes is NULL", (int)byte_count);
-    mpack_reader_track_str_bytes_all(reader, byte_count);
-    mpack_read_native(reader, p, byte_count);
-
-    if (mpack_reader_error(reader) == mpack_ok && !mpack_utf8_check(p, byte_count))
-        mpack_reader_flag_error(reader, mpack_error_type);
-}
-
-static void mpack_read_cstr_unchecked(mpack_reader_t* reader, char* buf, size_t buffer_size, size_t byte_count) {
-    mpack_assert(buf != NULL, "destination for read of %i bytes is NULL", (int)byte_count);
-    mpack_assert(buffer_size >= 1, "buffer size is zero; you must have room for at least a null-terminator");
-
-    if (mpack_reader_error(reader)) {
-        buf[0] = 0;
-        return;
-    }
-
-    if (byte_count > buffer_size - 1) {
-        mpack_reader_flag_error(reader, mpack_error_too_big);
-        buf[0] = 0;
-        return;
-    }
-
-    mpack_reader_track_str_bytes_all(reader, byte_count);
-    mpack_read_native(reader, buf, byte_count);
-    buf[byte_count] = 0;
-}
-
-void mpack_read_cstr(mpack_reader_t* reader, char* buf, size_t buffer_size, size_t byte_count) {
-    mpack_read_cstr_unchecked(reader, buf, buffer_size, byte_count);
-
-    // check for null bytes
-    if (mpack_reader_error(reader) == mpack_ok && !mpack_str_check_no_null(buf, byte_count)) {
-        buf[0] = 0;
-        mpack_reader_flag_error(reader, mpack_error_type);
-    }
-}
-
-void mpack_read_utf8_cstr(mpack_reader_t* reader, char* buf, size_t buffer_size, size_t byte_count) {
-    mpack_read_cstr_unchecked(reader, buf, buffer_size, byte_count);
-
-    // check encoding
-    if (mpack_reader_error(reader) == mpack_ok && !mpack_utf8_check_no_null(buf, byte_count)) {
-        buf[0] = 0;
-        mpack_reader_flag_error(reader, mpack_error_type);
-    }
-}
-
-#ifdef MPACK_MALLOC
-// Reads native bytes with error callback disabled. This allows MPack reader functions
-// to hold an allocated buffer and read native data into it without leaking it in
-// case of a non-local jump (longjmp, throw) out of an error handler.
-static void mpack_read_native_noerrorfn(mpack_reader_t* reader, char* p, size_t count) {
-    mpack_assert(reader->error == mpack_ok, "cannot call if an error is already flagged!");
-    mpack_reader_error_t error_fn = reader->error_fn;
-    reader->error_fn = NULL;
-    mpack_read_native(reader, p, count);
-    reader->error_fn = error_fn;
-}
-
-char* mpack_read_bytes_alloc_impl(mpack_reader_t* reader, size_t count, bool null_terminated) {
-
-    // track the bytes first in case it jumps
-    mpack_reader_track_bytes(reader, count);
-    if (mpack_reader_error(reader) != mpack_ok)
-        return NULL;
-
-    // cannot allocate zero bytes. this is not an error.
-    if (count == 0 && null_terminated == false)
-        return NULL;
-
-    // allocate data
-    char* data = (char*)MPACK_MALLOC(count + (null_terminated ? 1 : 0)); // TODO: can this overflow?
-    if (data == NULL) {
-        mpack_reader_flag_error(reader, mpack_error_memory);
-        return NULL;
-    }
-
-    // read with error callback disabled so we don't leak our buffer
-    mpack_read_native_noerrorfn(reader, data, count);
-
-    // report flagged errors
-    if (mpack_reader_error(reader) != mpack_ok) {
-        MPACK_FREE(data);
-        if (reader->error_fn)
-            reader->error_fn(reader, mpack_reader_error(reader));
-        return NULL;
-    }
-
-    if (null_terminated)
-        data[count] = '\0';
-    return data;
-}
-#endif
-
-// read inplace without tracking (since there are different
-// tracking modes for different inplace readers)
-static const char* mpack_read_bytes_inplace_notrack(mpack_reader_t* reader, size_t count) {
-    if (mpack_reader_error(reader) != mpack_ok)
-        return NULL;
-
-    // if we have enough bytes already in the buffer, we can return it directly.
-    if ((size_t)(reader->end - reader->data) >= count) {
-        const char* bytes = reader->data;
-        reader->data += count;
-        return bytes;
-    }
-
-    if (!mpack_reader_ensure(reader, count))
-        return NULL;
-
-    const char* bytes = reader->data;
-    reader->data += count;
-    return bytes;
-}
-
-const char* mpack_read_bytes_inplace(mpack_reader_t* reader, size_t count) {
-    mpack_reader_track_bytes(reader, count);
-    return mpack_read_bytes_inplace_notrack(reader, count);
-}
-
-const char* mpack_read_utf8_inplace(mpack_reader_t* reader, size_t count) {
-    mpack_reader_track_str_bytes_all(reader, count);
-    const char* str = mpack_read_bytes_inplace_notrack(reader, count);
-
-    if (mpack_reader_error(reader) == mpack_ok && !mpack_utf8_check(str, count)) {
-        mpack_reader_flag_error(reader, mpack_error_type);
-        return NULL;
-    }
-
-    return str;
-}
-
-static size_t mpack_parse_tag(mpack_reader_t* reader, mpack_tag_t* tag) {
-    mpack_assert(reader->error == mpack_ok, "reader cannot be in an error state!");
-
-    if (!mpack_reader_ensure(reader, 1))
-        return 0;
-    uint8_t type = mpack_load_u8(reader->data);
-
-    // unfortunately, by far the fastest way to parse a tag is to switch
-    // on the first byte, and to explicitly list every possible byte. so for
-    // infix types, the list of cases is quite large.
-    //
-    // in size-optimized builds, we switch on the top four bits first to
-    // handle most infix types with a smaller jump table to save space.
-
-    #if MPACK_OPTIMIZE_FOR_SIZE
-    switch (type >> 4) {
-
-        // positive fixnum
-        case 0x0: case 0x1: case 0x2: case 0x3:
-        case 0x4: case 0x5: case 0x6: case 0x7:
-            *tag = mpack_tag_make_uint(type);
-            return 1;
-
-        // negative fixnum
-        case 0xe: case 0xf:
-            *tag = mpack_tag_make_int((int8_t)type);
-            return 1;
-
-        // fixmap
-        case 0x8:
-            *tag = mpack_tag_make_map(type & ~0xf0u);
-            return 1;
-
-        // fixarray
-        case 0x9:
-            *tag = mpack_tag_make_array(type & ~0xf0u);
-            return 1;
-
-        // fixstr
-        case 0xa: case 0xb:
-            *tag = mpack_tag_make_str(type & ~0xe0u);
-            return 1;
-
-        // not one of the common infix types
-        default:
-            break;
-
-    }
-    #endif
-
-    // handle individual type tags
-    switch (type) {
-
-        #if !MPACK_OPTIMIZE_FOR_SIZE
-        // positive fixnum
-        case 0x00: case 0x01: case 0x02: case 0x03: case 0x04: case 0x05: case 0x06: case 0x07:
-        case 0x08: case 0x09: case 0x0a: case 0x0b: case 0x0c: case 0x0d: case 0x0e: case 0x0f:
-        case 0x10: case 0x11: case 0x12: case 0x13: case 0x14: case 0x15: case 0x16: case 0x17:
-        case 0x18: case 0x19: case 0x1a: case 0x1b: case 0x1c: case 0x1d: case 0x1e: case 0x1f:
-        case 0x20: case 0x21: case 0x22: case 0x23: case 0x24: case 0x25: case 0x26: case 0x27:
-        case 0x28: case 0x29: case 0x2a: case 0x2b: case 0x2c: case 0x2d: case 0x2e: case 0x2f:
-        case 0x30: case 0x31: case 0x32: case 0x33: case 0x34: case 0x35: case 0x36: case 0x37:
-        case 0x38: case 0x39: case 0x3a: case 0x3b: case 0x3c: case 0x3d: case 0x3e: case 0x3f:
-        case 0x40: case 0x41: case 0x42: case 0x43: case 0x44: case 0x45: case 0x46: case 0x47:
-        case 0x48: case 0x49: case 0x4a: case 0x4b: case 0x4c: case 0x4d: case 0x4e: case 0x4f:
-        case 0x50: case 0x51: case 0x52: case 0x53: case 0x54: case 0x55: case 0x56: case 0x57:
-        case 0x58: case 0x59: case 0x5a: case 0x5b: case 0x5c: case 0x5d: case 0x5e: case 0x5f:
-        case 0x60: case 0x61: case 0x62: case 0x63: case 0x64: case 0x65: case 0x66: case 0x67:
-        case 0x68: case 0x69: case 0x6a: case 0x6b: case 0x6c: case 0x6d: case 0x6e: case 0x6f:
-        case 0x70: case 0x71: case 0x72: case 0x73: case 0x74: case 0x75: case 0x76: case 0x77:
-        case 0x78: case 0x79: case 0x7a: case 0x7b: case 0x7c: case 0x7d: case 0x7e: case 0x7f:
-            *tag = mpack_tag_make_uint(type);
-            return 1;
-
-        // negative fixnum
-        case 0xe0: case 0xe1: case 0xe2: case 0xe3: case 0xe4: case 0xe5: case 0xe6: case 0xe7:
-        case 0xe8: case 0xe9: case 0xea: case 0xeb: case 0xec: case 0xed: case 0xee: case 0xef:
-        case 0xf0: case 0xf1: case 0xf2: case 0xf3: case 0xf4: case 0xf5: case 0xf6: case 0xf7:
-        case 0xf8: case 0xf9: case 0xfa: case 0xfb: case 0xfc: case 0xfd: case 0xfe: case 0xff:
-            *tag = mpack_tag_make_int((int8_t)type);
-            return 1;
-
-        // fixmap
-        case 0x80: case 0x81: case 0x82: case 0x83: case 0x84: case 0x85: case 0x86: case 0x87:
-        case 0x88: case 0x89: case 0x8a: case 0x8b: case 0x8c: case 0x8d: case 0x8e: case 0x8f:
-            *tag = mpack_tag_make_map(type & ~0xf0u);
-            return 1;
-
-        // fixarray
-        case 0x90: case 0x91: case 0x92: case 0x93: case 0x94: case 0x95: case 0x96: case 0x97:
-        case 0x98: case 0x99: case 0x9a: case 0x9b: case 0x9c: case 0x9d: case 0x9e: case 0x9f:
-            *tag = mpack_tag_make_array(type & ~0xf0u);
-            return 1;
-
-        // fixstr
-        case 0xa0: case 0xa1: case 0xa2: case 0xa3: case 0xa4: case 0xa5: case 0xa6: case 0xa7:
-        case 0xa8: case 0xa9: case 0xaa: case 0xab: case 0xac: case 0xad: case 0xae: case 0xaf:
-        case 0xb0: case 0xb1: case 0xb2: case 0xb3: case 0xb4: case 0xb5: case 0xb6: case 0xb7:
-        case 0xb8: case 0xb9: case 0xba: case 0xbb: case 0xbc: case 0xbd: case 0xbe: case 0xbf:
-            *tag = mpack_tag_make_str(type & ~0xe0u);
-            return 1;
-        #endif
-
-        // nil
-        case 0xc0:
-            *tag = mpack_tag_make_nil();
-            return 1;
-
-        // bool
-        case 0xc2: case 0xc3:
-            *tag = mpack_tag_make_bool((bool)(type & 1));
-            return 1;
-
-        // bin8
-        case 0xc4:
-            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_BIN8))
-                return 0;
-            *tag = mpack_tag_make_bin(mpack_load_u8(reader->data + 1));
-            return MPACK_TAG_SIZE_BIN8;
-
-        // bin16
-        case 0xc5:
-            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_BIN16))
-                return 0;
-            *tag = mpack_tag_make_bin(mpack_load_u16(reader->data + 1));
-            return MPACK_TAG_SIZE_BIN16;
-
-        // bin32
-        case 0xc6:
-            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_BIN32))
-                return 0;
-            *tag = mpack_tag_make_bin(mpack_load_u32(reader->data + 1));
-            return MPACK_TAG_SIZE_BIN32;
-
-        #if MPACK_EXTENSIONS
-        // ext8
-        case 0xc7:
-            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_EXT8))
-                return 0;
-            *tag = mpack_tag_make_ext(mpack_load_i8(reader->data + 2), mpack_load_u8(reader->data + 1));
-            return MPACK_TAG_SIZE_EXT8;
-
-        // ext16
-        case 0xc8:
-            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_EXT16))
-                return 0;
-            *tag = mpack_tag_make_ext(mpack_load_i8(reader->data + 3), mpack_load_u16(reader->data + 1));
-            return MPACK_TAG_SIZE_EXT16;
-
-        // ext32
-        case 0xc9:
-            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_EXT32))
-                return 0;
-            *tag = mpack_tag_make_ext(mpack_load_i8(reader->data + 5), mpack_load_u32(reader->data + 1));
-            return MPACK_TAG_SIZE_EXT32;
-        #endif
-
-        // float
-        case 0xca:
-            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_FLOAT))
-                return 0;
-            #if MPACK_FLOAT
-            *tag = mpack_tag_make_float(mpack_load_float(reader->data + 1));
-            #else
-            *tag = mpack_tag_make_raw_float(mpack_load_u32(reader->data + 1));
-            #endif
-            return MPACK_TAG_SIZE_FLOAT;
-
-        // double
-        case 0xcb:
-            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_DOUBLE))
-                return 0;
-            #if MPACK_DOUBLE
-            *tag = mpack_tag_make_double(mpack_load_double(reader->data + 1));
-            #else
-            *tag = mpack_tag_make_raw_double(mpack_load_u64(reader->data + 1));
-            #endif
-            return MPACK_TAG_SIZE_DOUBLE;
-
-        // uint8
-        case 0xcc:
-            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_U8))
-                return 0;
-            *tag = mpack_tag_make_uint(mpack_load_u8(reader->data + 1));
-            return MPACK_TAG_SIZE_U8;
-
-        // uint16
-        case 0xcd:
-            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_U16))
-                return 0;
-            *tag = mpack_tag_make_uint(mpack_load_u16(reader->data + 1));
-            return MPACK_TAG_SIZE_U16;
-
-        // uint32
-        case 0xce:
-            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_U32))
-                return 0;
-            *tag = mpack_tag_make_uint(mpack_load_u32(reader->data + 1));
-            return MPACK_TAG_SIZE_U32;
-
-        // uint64
-        case 0xcf:
-            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_U64))
-                return 0;
-            *tag = mpack_tag_make_uint(mpack_load_u64(reader->data + 1));
-            return MPACK_TAG_SIZE_U64;
-
-        // int8
-        case 0xd0:
-            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_I8))
-                return 0;
-            *tag = mpack_tag_make_int(mpack_load_i8(reader->data + 1));
-            return MPACK_TAG_SIZE_I8;
-
-        // int16
-        case 0xd1:
-            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_I16))
-                return 0;
-            *tag = mpack_tag_make_int(mpack_load_i16(reader->data + 1));
-            return MPACK_TAG_SIZE_I16;
-
-        // int32
-        case 0xd2:
-            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_I32))
-                return 0;
-            *tag = mpack_tag_make_int(mpack_load_i32(reader->data + 1));
-            return MPACK_TAG_SIZE_I32;
-
-        // int64
-        case 0xd3:
-            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_I64))
-                return 0;
-            *tag = mpack_tag_make_int(mpack_load_i64(reader->data + 1));
-            return MPACK_TAG_SIZE_I64;
-
-        #if MPACK_EXTENSIONS
-        // fixext1
-        case 0xd4:
-            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_FIXEXT1))
-                return 0;
-            *tag = mpack_tag_make_ext(mpack_load_i8(reader->data + 1), 1);
-            return MPACK_TAG_SIZE_FIXEXT1;
-
-        // fixext2
-        case 0xd5:
-            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_FIXEXT2))
-                return 0;
-            *tag = mpack_tag_make_ext(mpack_load_i8(reader->data + 1), 2);
-            return MPACK_TAG_SIZE_FIXEXT2;
-
-        // fixext4
-        case 0xd6:
-            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_FIXEXT4))
-                return 0;
-            *tag = mpack_tag_make_ext(mpack_load_i8(reader->data + 1), 4);
-            return 2;
-
-        // fixext8
-        case 0xd7:
-            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_FIXEXT8))
-                return 0;
-            *tag = mpack_tag_make_ext(mpack_load_i8(reader->data + 1), 8);
-            return MPACK_TAG_SIZE_FIXEXT8;
-
-        // fixext16
-        case 0xd8:
-            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_FIXEXT16))
-                return 0;
-            *tag = mpack_tag_make_ext(mpack_load_i8(reader->data + 1), 16);
-            return MPACK_TAG_SIZE_FIXEXT16;
-        #endif
-
-        // str8
-        case 0xd9:
-            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_STR8))
-                return 0;
-            *tag = mpack_tag_make_str(mpack_load_u8(reader->data + 1));
-            return MPACK_TAG_SIZE_STR8;
-
-        // str16
-        case 0xda:
-            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_STR16))
-                return 0;
-            *tag = mpack_tag_make_str(mpack_load_u16(reader->data + 1));
-            return MPACK_TAG_SIZE_STR16;
-
-        // str32
-        case 0xdb:
-            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_STR32))
-                return 0;
-            *tag = mpack_tag_make_str(mpack_load_u32(reader->data + 1));
-            return MPACK_TAG_SIZE_STR32;
-
-        // array16
-        case 0xdc:
-            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_ARRAY16))
-                return 0;
-            *tag = mpack_tag_make_array(mpack_load_u16(reader->data + 1));
-            return MPACK_TAG_SIZE_ARRAY16;
-
-        // array32
-        case 0xdd:
-            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_ARRAY32))
-                return 0;
-            *tag = mpack_tag_make_array(mpack_load_u32(reader->data + 1));
-            return MPACK_TAG_SIZE_ARRAY32;
-
-        // map16
-        case 0xde:
-            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_MAP16))
-                return 0;
-            *tag = mpack_tag_make_map(mpack_load_u16(reader->data + 1));
-            return MPACK_TAG_SIZE_MAP16;
-
-        // map32
-        case 0xdf:
-            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_MAP32))
-                return 0;
-            *tag = mpack_tag_make_map(mpack_load_u32(reader->data + 1));
-            return MPACK_TAG_SIZE_MAP32;
-
-        // reserved
-        case 0xc1:
-            mpack_reader_flag_error(reader, mpack_error_invalid);
-            return 0;
-
-        #if !MPACK_EXTENSIONS
-        // ext
-        case 0xc7: // fallthrough
-        case 0xc8: // fallthrough
-        case 0xc9: // fallthrough
-        // fixext
-        case 0xd4: // fallthrough
-        case 0xd5: // fallthrough
-        case 0xd6: // fallthrough
-        case 0xd7: // fallthrough
-        case 0xd8:
-            mpack_reader_flag_error(reader, mpack_error_unsupported);
-            return 0;
-        #endif
-
-        #if MPACK_OPTIMIZE_FOR_SIZE
-        // any other bytes should have been handled by the infix switch
-        default:
-            break;
-        #endif
-    }
-
-    mpack_assert(0, "unreachable");
-    return 0;
-}
-
-mpack_tag_t mpack_read_tag(mpack_reader_t* reader) {
-    mpack_log("reading tag\n");
-
-    // make sure we can read a tag
-    if (mpack_reader_error(reader) != mpack_ok)
-        return mpack_tag_nil();
-    if (mpack_reader_track_element(reader) != mpack_ok)
-        return mpack_tag_nil();
-
-    mpack_tag_t tag = MPACK_TAG_ZERO;
-    size_t count = mpack_parse_tag(reader, &tag);
-    if (count == 0)
-        return mpack_tag_nil();
-
-    #if MPACK_READ_TRACKING
-    mpack_error_t track_error = mpack_ok;
-
-    switch (tag.type) {
-        case mpack_type_map:
-        case mpack_type_array:
-            track_error = mpack_track_push(&reader->track, tag.type, tag.v.n);
-            break;
-        #if MPACK_EXTENSIONS
-        case mpack_type_ext:
-        #endif
-        case mpack_type_str:
-        case mpack_type_bin:
-            track_error = mpack_track_push(&reader->track, tag.type, tag.v.l);
-            break;
-        default:
-            break;
-    }
-
-    if (track_error != mpack_ok) {
-        mpack_reader_flag_error(reader, track_error);
-        return mpack_tag_nil();
-    }
-    #endif
-
-    reader->data += count;
-    return tag;
-}
-
-mpack_tag_t mpack_peek_tag(mpack_reader_t* reader) {
-    mpack_log("peeking tag\n");
-
-    // make sure we can peek a tag
-    if (mpack_reader_error(reader) != mpack_ok)
-        return mpack_tag_nil();
-    if (mpack_reader_track_peek_element(reader) != mpack_ok)
-        return mpack_tag_nil();
-
-    mpack_tag_t tag = MPACK_TAG_ZERO;
-    if (mpack_parse_tag(reader, &tag) == 0)
-        return mpack_tag_nil();
-    return tag;
-}
-
-void mpack_discard(mpack_reader_t* reader) {
-    mpack_tag_t var = mpack_read_tag(reader);
-    if (mpack_reader_error(reader))
-        return;
-    switch (var.type) {
-        case mpack_type_str:
-            mpack_skip_bytes(reader, var.v.l);
-            mpack_done_str(reader);
-            break;
-        case mpack_type_bin:
-            mpack_skip_bytes(reader, var.v.l);
-            mpack_done_bin(reader);
-            break;
-        #if MPACK_EXTENSIONS
-        case mpack_type_ext:
-            mpack_skip_bytes(reader, var.v.l);
-            mpack_done_ext(reader);
-            break;
-        #endif
-        case mpack_type_array: {
-            for (; var.v.n > 0; --var.v.n) {
-                mpack_discard(reader);
-                if (mpack_reader_error(reader))
-                    break;
-            }
-            mpack_done_array(reader);
-            break;
-        }
-        case mpack_type_map: {
-            for (; var.v.n > 0; --var.v.n) {
-                mpack_discard(reader);
-                mpack_discard(reader);
-                if (mpack_reader_error(reader))
-                    break;
-            }
-            mpack_done_map(reader);
-            break;
-        }
-        default:
-            break;
-    }
-}
-
-#if MPACK_EXTENSIONS
-mpack_timestamp_t mpack_read_timestamp(mpack_reader_t* reader, size_t size) {
-    mpack_timestamp_t timestamp = {0, 0};
-
-    if (size != 4 && size != 8 && size != 12) {
-        mpack_reader_flag_error(reader, mpack_error_invalid);
-        return timestamp;
-    }
-
-    char buf[12];
-    mpack_read_bytes(reader, buf, size);
-    mpack_done_ext(reader);
-    if (mpack_reader_error(reader) != mpack_ok)
-        return timestamp;
-
-    switch (size) {
-        case 4:
-            timestamp.seconds = (int64_t)(uint64_t)mpack_load_u32(buf);
-            break;
-
-        case 8: {
-            uint64_t packed = mpack_load_u64(buf);
-            timestamp.seconds = (int64_t)(packed & ((MPACK_UINT64_C(1) << 34) - 1));
-            timestamp.nanoseconds = (uint32_t)(packed >> 34);
-            break;
-        }
-
-        case 12:
-            timestamp.nanoseconds = mpack_load_u32(buf);
-            timestamp.seconds = mpack_load_i64(buf + 4);
-            break;
-
-        default:
-            mpack_assert(false, "unreachable");
-            break;
-    }
-
-    if (timestamp.nanoseconds > MPACK_TIMESTAMP_NANOSECONDS_MAX) {
-        mpack_reader_flag_error(reader, mpack_error_invalid);
-        mpack_timestamp_t zero = {0, 0};
-        return zero;
-    }
-
-    return timestamp;
-}
-#endif
-
-#if MPACK_READ_TRACKING
-void mpack_done_type(mpack_reader_t* reader, mpack_type_t type) {
-    if (mpack_reader_error(reader) == mpack_ok)
-        mpack_reader_flag_if_error(reader, mpack_track_pop(&reader->track, type));
-}
-#endif
-
-#if MPACK_DEBUG && MPACK_STDIO
-static size_t mpack_print_read_prefix(mpack_reader_t* reader, size_t length, char* buffer, size_t buffer_size) {
-    if (length == 0)
-        return 0;
-
-    size_t read = (length < buffer_size) ? length : buffer_size;
-    mpack_read_bytes(reader, buffer, read);
-    if (mpack_reader_error(reader) != mpack_ok)
-        return 0;
-
-    mpack_skip_bytes(reader, length - read);
-    return read;
-}
-
-static void mpack_print_element(mpack_reader_t* reader, mpack_print_t* print, size_t depth) {
-    mpack_tag_t val = mpack_read_tag(reader);
-    if (mpack_reader_error(reader) != mpack_ok)
-        return;
-
-    // We read some bytes from bin and ext so we can print its prefix in hex.
-    char buffer[MPACK_PRINT_BYTE_COUNT];
-    size_t count = 0;
-    size_t i, j;
-
-    switch (val.type) {
-        case mpack_type_str:
-            mpack_print_append_cstr(print, "\"");
-            for (i = 0; i < val.v.l; ++i) {
-                char c;
-                mpack_read_bytes(reader, &c, 1);
-                if (mpack_reader_error(reader) != mpack_ok)
-                    return;
-                switch (c) {
-                    case '\n': mpack_print_append_cstr(print, "\\n"); break;
-                    case '\\': mpack_print_append_cstr(print, "\\\\"); break;
-                    case '"': mpack_print_append_cstr(print, "\\\""); break;
-                    default: mpack_print_append(print, &c, 1); break;
-                }
-            }
-            mpack_print_append_cstr(print, "\"");
-            mpack_done_str(reader);
-            return;
-
-        case mpack_type_array:
-            mpack_print_append_cstr(print, "[\n");
-            for (i = 0; i < val.v.n; ++i) {
-                for (j = 0; j < depth + 1; ++j)
-                    mpack_print_append_cstr(print, "    ");
-                mpack_print_element(reader, print, depth + 1);
-                if (mpack_reader_error(reader) != mpack_ok)
-                    return;
-                if (i != val.v.n - 1)
-                    mpack_print_append_cstr(print, ",");
-                mpack_print_append_cstr(print, "\n");
-            }
-            for (i = 0; i < depth; ++i)
-                mpack_print_append_cstr(print, "    ");
-            mpack_print_append_cstr(print, "]");
-            mpack_done_array(reader);
-            return;
-
-        case mpack_type_map:
-            mpack_print_append_cstr(print, "{\n");
-            for (i = 0; i < val.v.n; ++i) {
-                for (j = 0; j < depth + 1; ++j)
-                    mpack_print_append_cstr(print, "    ");
-                mpack_print_element(reader, print, depth + 1);
-                if (mpack_reader_error(reader) != mpack_ok)
-                    return;
-                mpack_print_append_cstr(print, ": ");
-                mpack_print_element(reader, print, depth + 1);
-                if (mpack_reader_error(reader) != mpack_ok)
-                    return;
-                if (i != val.v.n - 1)
-                    mpack_print_append_cstr(print, ",");
-                mpack_print_append_cstr(print, "\n");
-            }
-            for (i = 0; i < depth; ++i)
-                mpack_print_append_cstr(print, "    ");
-            mpack_print_append_cstr(print, "}");
-            mpack_done_map(reader);
-            return;
-
-        // The above cases return so as not to print a pseudo-json value. The
-        // below cases break and print pseudo-json.
-
-        case mpack_type_bin:
-            count = mpack_print_read_prefix(reader, mpack_tag_bin_length(&val), buffer, sizeof(buffer));
-            mpack_done_bin(reader);
-            break;
-
-        #if MPACK_EXTENSIONS
-        case mpack_type_ext:
-            count = mpack_print_read_prefix(reader, mpack_tag_ext_length(&val), buffer, sizeof(buffer));
-            mpack_done_ext(reader);
-            break;
-        #endif
-
-        default:
-            break;
-    }
-
-    char buf[256];
-    mpack_tag_debug_pseudo_json(val, buf, sizeof(buf), buffer, count);
-    mpack_print_append_cstr(print, buf);
-}
-
-static void mpack_print_and_destroy(mpack_reader_t* reader, mpack_print_t* print, size_t depth) {
-    size_t i;
-    for (i = 0; i < depth; ++i)
-        mpack_print_append_cstr(print, "    ");
-    mpack_print_element(reader, print, depth);
-
-    size_t remaining = mpack_reader_remaining(reader, NULL);
-
-    char buf[256];
-    if (mpack_reader_destroy(reader) != mpack_ok) {
-        mpack_snprintf(buf, sizeof(buf), "\n<mpack parsing error %s>", mpack_error_to_string(mpack_reader_error(reader)));
-        buf[sizeof(buf) - 1] = '\0';
-        mpack_print_append_cstr(print, buf);
-    } else if (remaining > 0) {
-        mpack_snprintf(buf, sizeof(buf), "\n<%i extra bytes at end of message>", (int)remaining);
-        buf[sizeof(buf) - 1] = '\0';
-        mpack_print_append_cstr(print, buf);
-    }
-}
-
-static void mpack_print_data(const char* data, size_t len, mpack_print_t* print, size_t depth) {
-    mpack_reader_t reader;
-    mpack_reader_init_data(&reader, data, len);
-    mpack_print_and_destroy(&reader, print, depth);
-}
-
-void mpack_print_data_to_buffer(const char* data, size_t data_size, char* buffer, size_t buffer_size) {
-    if (buffer_size == 0) {
-        mpack_assert(false, "buffer size is zero!");
-        return;
-    }
-
-    mpack_print_t print;
-    mpack_memset(&print, 0, sizeof(print));
-    print.buffer = buffer;
-    print.size = buffer_size;
-    mpack_print_data(data, data_size, &print, 0);
-    mpack_print_append(&print, "",  1); // null-terminator
-    mpack_print_flush(&print);
-
-    // we always make sure there's a null-terminator at the end of the buffer
-    // in case we ran out of space.
-    print.buffer[print.size - 1] = '\0';
-}
-
-void mpack_print_data_to_callback(const char* data, size_t size, mpack_print_callback_t callback, void* context) {
-    char buffer[1024];
-    mpack_print_t print;
-    mpack_memset(&print, 0, sizeof(print));
-    print.buffer = buffer;
-    print.size = sizeof(buffer);
-    print.callback = callback;
-    print.context = context;
-    mpack_print_data(data, size, &print, 0);
-    mpack_print_flush(&print);
-}
-
-void mpack_print_data_to_file(const char* data, size_t len, FILE* file) {
-    mpack_assert(data != NULL, "data is NULL");
-    mpack_assert(file != NULL, "file is NULL");
-
-    char buffer[1024];
-    mpack_print_t print;
-    mpack_memset(&print, 0, sizeof(print));
-    print.buffer = buffer;
-    print.size = sizeof(buffer);
-    print.callback = &mpack_print_file_callback;
-    print.context = file;
-
-    mpack_print_data(data, len, &print, 2);
-    mpack_print_append_cstr(&print, "\n");
-    mpack_print_flush(&print);
-}
-
-void mpack_print_stdfile_to_callback(FILE* file, mpack_print_callback_t callback, void* context) {
-    char buffer[1024];
-    mpack_print_t print;
-    mpack_memset(&print, 0, sizeof(print));
-    print.buffer = buffer;
-    print.size = sizeof(buffer);
-    print.callback = callback;
-    print.context = context;
-
-    mpack_reader_t reader;
-    mpack_reader_init_stdfile(&reader, file, false);
-    mpack_print_and_destroy(&reader, &print, 0);
-    mpack_print_flush(&print);
-}
-#endif
-
-#endif
-
-MPACK_SILENCE_WARNINGS_END
-
-/* mpack/mpack-expect.c.c */
-
-#define MPACK_INTERNAL 1
-
-/* #include "mpack-expect.h" */
-
-MPACK_SILENCE_WARNINGS_BEGIN
-
-#if MPACK_EXPECT
-
-
-// Helpers
-
-MPACK_STATIC_INLINE uint8_t mpack_expect_native_u8(mpack_reader_t* reader) {
-    if (mpack_reader_error(reader) != mpack_ok)
-        return 0;
-    uint8_t type;
-    if (!mpack_reader_ensure(reader, sizeof(type)))
-        return 0;
-    type = mpack_load_u8(reader->data);
-    reader->data += sizeof(type);
-    return type;
-}
-
-#if !MPACK_OPTIMIZE_FOR_SIZE
-MPACK_STATIC_INLINE uint16_t mpack_expect_native_u16(mpack_reader_t* reader) {
-    if (mpack_reader_error(reader) != mpack_ok)
-        return 0;
-    uint16_t type;
-    if (!mpack_reader_ensure(reader, sizeof(type)))
-        return 0;
-    type = mpack_load_u16(reader->data);
-    reader->data += sizeof(type);
-    return type;
-}
-
-MPACK_STATIC_INLINE uint32_t mpack_expect_native_u32(mpack_reader_t* reader) {
-    if (mpack_reader_error(reader) != mpack_ok)
-        return 0;
-    uint32_t type;
-    if (!mpack_reader_ensure(reader, sizeof(type)))
-        return 0;
-    type = mpack_load_u32(reader->data);
-    reader->data += sizeof(type);
-    return type;
-}
-#endif
-
-MPACK_STATIC_INLINE uint8_t mpack_expect_type_byte(mpack_reader_t* reader) {
-    mpack_reader_track_element(reader);
-    return mpack_expect_native_u8(reader);
-}
-
-
-// Basic Number Functions
-
-uint8_t mpack_expect_u8(mpack_reader_t* reader) {
-    mpack_tag_t var = mpack_read_tag(reader);
-    if (var.type == mpack_type_uint) {
-        if (var.v.u <= MPACK_UINT8_MAX)
-            return (uint8_t)var.v.u;
-    } else if (var.type == mpack_type_int) {
-        if (var.v.i >= 0 && var.v.i <= MPACK_UINT8_MAX)
-            return (uint8_t)var.v.i;
-    }
-    mpack_reader_flag_error(reader, mpack_error_type);
-    return 0;
-}
-
-uint16_t mpack_expect_u16(mpack_reader_t* reader) {
-    mpack_tag_t var = mpack_read_tag(reader);
-    if (var.type == mpack_type_uint) {
-        if (var.v.u <= MPACK_UINT16_MAX)
-            return (uint16_t)var.v.u;
-    } else if (var.type == mpack_type_int) {
-        if (var.v.i >= 0 && var.v.i <= MPACK_UINT16_MAX)
-            return (uint16_t)var.v.i;
-    }
-    mpack_reader_flag_error(reader, mpack_error_type);
-    return 0;
-}
-
-uint32_t mpack_expect_u32(mpack_reader_t* reader) {
-    mpack_tag_t var = mpack_read_tag(reader);
-    if (var.type == mpack_type_uint) {
-        if (var.v.u <= MPACK_UINT32_MAX)
-            return (uint32_t)var.v.u;
-    } else if (var.type == mpack_type_int) {
-        if (var.v.i >= 0 && var.v.i <= MPACK_UINT32_MAX)
-            return (uint32_t)var.v.i;
-    }
-    mpack_reader_flag_error(reader, mpack_error_type);
-    return 0;
-}
-
-uint64_t mpack_expect_u64(mpack_reader_t* reader) {
-    mpack_tag_t var = mpack_read_tag(reader);
-    if (var.type == mpack_type_uint) {
-        return var.v.u;
-    } else if (var.type == mpack_type_int) {
-        if (var.v.i >= 0)
-            return (uint64_t)var.v.i;
-    }
-    mpack_reader_flag_error(reader, mpack_error_type);
-    return 0;
-}
-
-int8_t mpack_expect_i8(mpack_reader_t* reader) {
-    mpack_tag_t var = mpack_read_tag(reader);
-    if (var.type == mpack_type_uint) {
-        if (var.v.u <= MPACK_INT8_MAX)
-            return (int8_t)var.v.u;
-    } else if (var.type == mpack_type_int) {
-        if (var.v.i >= MPACK_INT8_MIN && var.v.i <= MPACK_INT8_MAX)
-            return (int8_t)var.v.i;
-    }
-    mpack_reader_flag_error(reader, mpack_error_type);
-    return 0;
-}
-
-int16_t mpack_expect_i16(mpack_reader_t* reader) {
-    mpack_tag_t var = mpack_read_tag(reader);
-    if (var.type == mpack_type_uint) {
-        if (var.v.u <= MPACK_INT16_MAX)
-            return (int16_t)var.v.u;
-    } else if (var.type == mpack_type_int) {
-        if (var.v.i >= MPACK_INT16_MIN && var.v.i <= MPACK_INT16_MAX)
-            return (int16_t)var.v.i;
-    }
-    mpack_reader_flag_error(reader, mpack_error_type);
-    return 0;
-}
-
-int32_t mpack_expect_i32(mpack_reader_t* reader) {
-    mpack_tag_t var = mpack_read_tag(reader);
-    if (var.type == mpack_type_uint) {
-        if (var.v.u <= MPACK_INT32_MAX)
-            return (int32_t)var.v.u;
-    } else if (var.type == mpack_type_int) {
-        if (var.v.i >= MPACK_INT32_MIN && var.v.i <= MPACK_INT32_MAX)
-            return (int32_t)var.v.i;
-    }
-    mpack_reader_flag_error(reader, mpack_error_type);
-    return 0;
-}
-
-int64_t mpack_expect_i64(mpack_reader_t* reader) {
-    mpack_tag_t var = mpack_read_tag(reader);
-    if (var.type == mpack_type_uint) {
-        if (var.v.u <= MPACK_INT64_MAX)
-            return (int64_t)var.v.u;
-    } else if (var.type == mpack_type_int) {
-        return var.v.i;
-    }
-    mpack_reader_flag_error(reader, mpack_error_type);
-    return 0;
-}
-
-#if MPACK_FLOAT
-float mpack_expect_float(mpack_reader_t* reader) {
-    mpack_tag_t var = mpack_read_tag(reader);
-    if (var.type == mpack_type_uint)
-        return (float)var.v.u;
-    if (var.type == mpack_type_int)
-        return (float)var.v.i;
-    if (var.type == mpack_type_float)
-        return var.v.f;
-
-    if (var.type == mpack_type_double) {
-        #if MPACK_DOUBLE
-        return (float)var.v.d;
-        #else
-        return mpack_shorten_raw_double_to_float(var.v.d);
-        #endif
-    }
-
-    mpack_reader_flag_error(reader, mpack_error_type);
-    return 0.0f;
-}
-#endif
-
-#if MPACK_DOUBLE
-double mpack_expect_double(mpack_reader_t* reader) {
-    mpack_tag_t var = mpack_read_tag(reader);
-    if (var.type == mpack_type_uint)
-        return (double)var.v.u;
-    else if (var.type == mpack_type_int)
-        return (double)var.v.i;
-    else if (var.type == mpack_type_float)
-        return (double)var.v.f;
-    else if (var.type == mpack_type_double)
-        return var.v.d;
-    mpack_reader_flag_error(reader, mpack_error_type);
-    return 0.0;
-}
-#endif
-
-#if MPACK_FLOAT
-float mpack_expect_float_strict(mpack_reader_t* reader) {
-    mpack_tag_t var = mpack_read_tag(reader);
-    if (var.type == mpack_type_float)
-        return var.v.f;
-    mpack_reader_flag_error(reader, mpack_error_type);
-    return 0.0f;
-}
-#endif
-
-#if MPACK_DOUBLE
-double mpack_expect_double_strict(mpack_reader_t* reader) {
-    mpack_tag_t var = mpack_read_tag(reader);
-    if (var.type == mpack_type_float)
-        return (double)var.v.f;
-    else if (var.type == mpack_type_double)
-        return var.v.d;
-    mpack_reader_flag_error(reader, mpack_error_type);
-    return 0.0;
-}
-#endif
-
-#if !MPACK_FLOAT
-uint32_t mpack_expect_raw_float(mpack_reader_t* reader) {
-    mpack_tag_t var = mpack_read_tag(reader);
-    if (var.type == mpack_type_float)
-        return var.v.f;
-    mpack_reader_flag_error(reader, mpack_error_type);
-    return 0;
-}
-#endif
-
-#if !MPACK_DOUBLE
-uint64_t mpack_expect_raw_double(mpack_reader_t* reader) {
-    mpack_tag_t var = mpack_read_tag(reader);
-    if (var.type == mpack_type_double)
-        return var.v.d;
-    mpack_reader_flag_error(reader, mpack_error_type);
-    return 0;
-}
-#endif
-
-
-// Ranged Number Functions
-//
-// All ranged functions are identical other than the type, so we
-// define their content with a macro. The prototypes are still written
-// out in full to support ctags/IDE tools.
-
-#define MPACK_EXPECT_RANGE_IMPL(name, type_t)                           \
-                                                                        \
-    /* make sure the range is sensible */                               \
-    mpack_assert(min_value <= max_value,                                \
-            "min_value %i must be less than or equal to max_value %i",  \
-            min_value, max_value);                                      \
-                                                                        \
-    /* read the value */                                                \
-    type_t val = mpack_expect_##name(reader);                           \
-    if (mpack_reader_error(reader) != mpack_ok)                         \
-        return min_value;                                               \
-                                                                        \
-    /* make sure it fits */                                             \
-    if (val < min_value || val > max_value) {                           \
-        mpack_reader_flag_error(reader, mpack_error_type);              \
-        return min_value;                                               \
-    }                                                                   \
-                                                                        \
-    return val;
-
-uint8_t mpack_expect_u8_range(mpack_reader_t* reader, uint8_t min_value, uint8_t max_value) {MPACK_EXPECT_RANGE_IMPL(u8, uint8_t)}
-uint16_t mpack_expect_u16_range(mpack_reader_t* reader, uint16_t min_value, uint16_t max_value) {MPACK_EXPECT_RANGE_IMPL(u16, uint16_t)}
-uint32_t mpack_expect_u32_range(mpack_reader_t* reader, uint32_t min_value, uint32_t max_value) {MPACK_EXPECT_RANGE_IMPL(u32, uint32_t)}
-uint64_t mpack_expect_u64_range(mpack_reader_t* reader, uint64_t min_value, uint64_t max_value) {MPACK_EXPECT_RANGE_IMPL(u64, uint64_t)}
-
-int8_t mpack_expect_i8_range(mpack_reader_t* reader, int8_t min_value, int8_t max_value) {MPACK_EXPECT_RANGE_IMPL(i8, int8_t)}
-int16_t mpack_expect_i16_range(mpack_reader_t* reader, int16_t min_value, int16_t max_value) {MPACK_EXPECT_RANGE_IMPL(i16, int16_t)}
-int32_t mpack_expect_i32_range(mpack_reader_t* reader, int32_t min_value, int32_t max_value) {MPACK_EXPECT_RANGE_IMPL(i32, int32_t)}
-int64_t mpack_expect_i64_range(mpack_reader_t* reader, int64_t min_value, int64_t max_value) {MPACK_EXPECT_RANGE_IMPL(i64, int64_t)}
-
-#if MPACK_FLOAT
-float mpack_expect_float_range(mpack_reader_t* reader, float min_value, float max_value) {MPACK_EXPECT_RANGE_IMPL(float, float)}
-#endif
-#if MPACK_DOUBLE
-double mpack_expect_double_range(mpack_reader_t* reader, double min_value, double max_value) {MPACK_EXPECT_RANGE_IMPL(double, double)}
-#endif
-
-uint32_t mpack_expect_map_range(mpack_reader_t* reader, uint32_t min_value, uint32_t max_value) {MPACK_EXPECT_RANGE_IMPL(map, uint32_t)}
-uint32_t mpack_expect_array_range(mpack_reader_t* reader, uint32_t min_value, uint32_t max_value) {MPACK_EXPECT_RANGE_IMPL(array, uint32_t)}
-
-
-// Matching Number Functions
-
-void mpack_expect_uint_match(mpack_reader_t* reader, uint64_t value) {
-    if (mpack_expect_u64(reader) != value)
-        mpack_reader_flag_error(reader, mpack_error_type);
-}
-
-void mpack_expect_int_match(mpack_reader_t* reader, int64_t value) {
-    if (mpack_expect_i64(reader) != value)
-        mpack_reader_flag_error(reader, mpack_error_type);
-}
-
-
-// Other Basic Types
-
-void mpack_expect_nil(mpack_reader_t* reader) {
-    if (mpack_expect_type_byte(reader) != 0xc0)
-        mpack_reader_flag_error(reader, mpack_error_type);
-}
-
-bool mpack_expect_bool(mpack_reader_t* reader) {
-    uint8_t type = mpack_expect_type_byte(reader);
-    if ((type & ~1) != 0xc2)
-        mpack_reader_flag_error(reader, mpack_error_type);
-    return (bool)(type & 1);
-}
-
-void mpack_expect_true(mpack_reader_t* reader) {
-    if (mpack_expect_bool(reader) != true)
-        mpack_reader_flag_error(reader, mpack_error_type);
-}
-
-void mpack_expect_false(mpack_reader_t* reader) {
-    if (mpack_expect_bool(reader) != false)
-        mpack_reader_flag_error(reader, mpack_error_type);
-}
-
-#if MPACK_EXTENSIONS
-mpack_timestamp_t mpack_expect_timestamp(mpack_reader_t* reader) {
-    mpack_timestamp_t zero = {0, 0};
-
-    mpack_tag_t tag = mpack_read_tag(reader);
-    if (tag.type != mpack_type_ext) {
-        mpack_reader_flag_error(reader, mpack_error_type);
-        return zero;
-    }
-    if (mpack_tag_ext_exttype(&tag) != MPACK_EXTTYPE_TIMESTAMP) {
-        mpack_reader_flag_error(reader, mpack_error_type);
-        return zero;
-    }
-
-    return mpack_read_timestamp(reader, mpack_tag_ext_length(&tag));
-}
-
-int64_t mpack_expect_timestamp_truncate(mpack_reader_t* reader) {
-    return mpack_expect_timestamp(reader).seconds;
-}
-#endif
-
-
-// Compound Types
-
-uint32_t mpack_expect_map(mpack_reader_t* reader) {
-    mpack_tag_t var = mpack_read_tag(reader);
-    if (var.type == mpack_type_map)
-        return var.v.n;
-    mpack_reader_flag_error(reader, mpack_error_type);
-    return 0;
-}
-
-void mpack_expect_map_match(mpack_reader_t* reader, uint32_t count) {
-    if (mpack_expect_map(reader) != count)
-        mpack_reader_flag_error(reader, mpack_error_type);
-}
-
-bool mpack_expect_map_or_nil(mpack_reader_t* reader, uint32_t* count) {
-    mpack_assert(count != NULL, "count cannot be NULL");
-
-    mpack_tag_t var = mpack_read_tag(reader);
-    if (var.type == mpack_type_nil) {
-        *count = 0;
-        return false;
-    }
-    if (var.type == mpack_type_map) {
-        *count = var.v.n;
-        return true;
-    }
-    mpack_reader_flag_error(reader, mpack_error_type);
-    *count = 0;
-    return false;
-}
-
-bool mpack_expect_map_max_or_nil(mpack_reader_t* reader, uint32_t max_count, uint32_t* count) {
-    mpack_assert(count != NULL, "count cannot be NULL");
-
-    bool has_map = mpack_expect_map_or_nil(reader, count);
-    if (has_map && *count > max_count) {
-        *count = 0;
-        mpack_reader_flag_error(reader, mpack_error_type);
-        return false;
-    }
-    return has_map;
-}
-
-uint32_t mpack_expect_array(mpack_reader_t* reader) {
-    mpack_tag_t var = mpack_read_tag(reader);
-    if (var.type == mpack_type_array)
-        return var.v.n;
-    mpack_reader_flag_error(reader, mpack_error_type);
-    return 0;
-}
-
-void mpack_expect_array_match(mpack_reader_t* reader, uint32_t count) {
-    if (mpack_expect_array(reader) != count)
-        mpack_reader_flag_error(reader, mpack_error_type);
-}
-
-bool mpack_expect_array_or_nil(mpack_reader_t* reader, uint32_t* count) {
-    mpack_assert(count != NULL, "count cannot be NULL");
-
-    mpack_tag_t var = mpack_read_tag(reader);
-    if (var.type == mpack_type_nil) {
-        *count = 0;
-        return false;
-    }
-    if (var.type == mpack_type_array) {
-        *count = var.v.n;
-        return true;
-    }
-    mpack_reader_flag_error(reader, mpack_error_type);
-    *count = 0;
-    return false;
-}
-
-bool mpack_expect_array_max_or_nil(mpack_reader_t* reader, uint32_t max_count, uint32_t* count) {
-    mpack_assert(count != NULL, "count cannot be NULL");
-
-    bool has_array = mpack_expect_array_or_nil(reader, count);
-    if (has_array && *count > max_count) {
-        *count = 0;
-        mpack_reader_flag_error(reader, mpack_error_type);
-        return false;
-    }
-    return has_array;
-}
-
-#ifdef MPACK_MALLOC
-void* mpack_expect_array_alloc_impl(mpack_reader_t* reader, size_t element_size, uint32_t max_count, uint32_t* out_count, bool allow_nil) {
-    mpack_assert(out_count != NULL, "out_count cannot be NULL");
-    *out_count = 0;
-
-    uint32_t count;
-    bool has_array = true;
-    if (allow_nil)
-        has_array = mpack_expect_array_max_or_nil(reader, max_count, &count);
-    else
-        count = mpack_expect_array_max(reader, max_count);
-    if (mpack_reader_error(reader))
-        return NULL;
-
-    // size 0 is not an error; we return NULL for no elements.
-    if (count == 0) {
-        // we call mpack_done_array() automatically ONLY if we are using
-        // the _or_nil variant. this is the only way to allow nil and empty
-        // to work the same way.
-        if (allow_nil && has_array)
-            mpack_done_array(reader);
-        return NULL;
-    }
-
-    void* p = MPACK_MALLOC(element_size * count);
-    if (p == NULL) {
-        mpack_reader_flag_error(reader, mpack_error_memory);
-        return NULL;
-    }
-
-    *out_count = count;
-    return p;
-}
-#endif
-
-
-// Str, Bin and Ext Functions
-
-uint32_t mpack_expect_str(mpack_reader_t* reader) {
-    #if MPACK_OPTIMIZE_FOR_SIZE
-    mpack_tag_t var = mpack_read_tag(reader);
-    if (var.type == mpack_type_str)
-        return var.v.l;
-    mpack_reader_flag_error(reader, mpack_error_type);
-    return 0;
-    #else
-    uint8_t type = mpack_expect_type_byte(reader);
-    uint32_t count;
-
-    if ((type >> 5) == 5) {
-        count = type & (uint8_t)~0xe0;
-    } else if (type == 0xd9) {
-        count = mpack_expect_native_u8(reader);
-    } else if (type == 0xda) {
-        count = mpack_expect_native_u16(reader);
-    } else if (type == 0xdb) {
-        count = mpack_expect_native_u32(reader);
-    } else {
-        mpack_reader_flag_error(reader, mpack_error_type);
-        return 0;
-    }
-
-    #if MPACK_READ_TRACKING
-    mpack_reader_flag_if_error(reader, mpack_track_push(&reader->track, mpack_type_str, count));
-    #endif
-    return count;
-    #endif
-}
-
-size_t mpack_expect_str_buf(mpack_reader_t* reader, char* buf, size_t bufsize) {
-    mpack_assert(buf != NULL, "buf cannot be NULL");
-
-    size_t length = mpack_expect_str(reader);
-    if (mpack_reader_error(reader))
-        return 0;
-
-    if (length > bufsize) {
-        mpack_reader_flag_error(reader, mpack_error_too_big);
-        return 0;
-    }
-
-    mpack_read_bytes(reader, buf, length);
-    if (mpack_reader_error(reader))
-        return 0;
-
-    mpack_done_str(reader);
-    return length;
-}
-
-size_t mpack_expect_utf8(mpack_reader_t* reader, char* buf, size_t size) {
-    mpack_assert(buf != NULL, "buf cannot be NULL");
-
-    size_t length = mpack_expect_str_buf(reader, buf, size);
-
-    if (!mpack_utf8_check(buf, length)) {
-        mpack_reader_flag_error(reader, mpack_error_type);
-        return 0;
-    }
-
-    return length;
-}
-
-uint32_t mpack_expect_bin(mpack_reader_t* reader) {
-    mpack_tag_t var = mpack_read_tag(reader);
-    if (var.type == mpack_type_bin)
-        return var.v.l;
-    mpack_reader_flag_error(reader, mpack_error_type);
-    return 0;
-}
-
-size_t mpack_expect_bin_buf(mpack_reader_t* reader, char* buf, size_t bufsize) {
-    mpack_assert(buf != NULL, "buf cannot be NULL");
-
-    size_t binsize = mpack_expect_bin(reader);
-    if (mpack_reader_error(reader))
-        return 0;
-    if (binsize > bufsize) {
-        mpack_reader_flag_error(reader, mpack_error_too_big);
-        return 0;
-    }
-    mpack_read_bytes(reader, buf, binsize);
-    if (mpack_reader_error(reader))
-        return 0;
-    mpack_done_bin(reader);
-    return binsize;
-}
-
-void mpack_expect_bin_size_buf(mpack_reader_t* reader, char* buf, uint32_t size) {
-    mpack_assert(buf != NULL, "buf cannot be NULL");
-    mpack_expect_bin_size(reader, size);
-    mpack_read_bytes(reader, buf, size);
-    mpack_done_bin(reader);
-}
-
-#if MPACK_EXTENSIONS
-uint32_t mpack_expect_ext(mpack_reader_t* reader, int8_t* type) {
-    mpack_tag_t var = mpack_read_tag(reader);
-    if (var.type == mpack_type_ext) {
-        *type = mpack_tag_ext_exttype(&var);
-        return mpack_tag_ext_length(&var);
-    }
-    *type = 0;
-    mpack_reader_flag_error(reader, mpack_error_type);
-    return 0;
-}
-
-size_t mpack_expect_ext_buf(mpack_reader_t* reader, int8_t* type, char* buf, size_t bufsize) {
-    mpack_assert(buf != NULL, "buf cannot be NULL");
-
-    size_t extsize = mpack_expect_ext(reader, type);
-    if (mpack_reader_error(reader))
-        return 0;
-    if (extsize > bufsize) {
-        *type = 0;
-        mpack_reader_flag_error(reader, mpack_error_too_big);
-        return 0;
-    }
-    mpack_read_bytes(reader, buf, extsize);
-    if (mpack_reader_error(reader)) {
-        *type = 0;
-        return 0;
-    }
-    mpack_done_ext(reader);
-    return extsize;
-}
-#endif
-
-void mpack_expect_cstr(mpack_reader_t* reader, char* buf, size_t bufsize) {
-    uint32_t length = mpack_expect_str(reader);
-    mpack_read_cstr(reader, buf, bufsize, length);
-    mpack_done_str(reader);
-}
-
-void mpack_expect_utf8_cstr(mpack_reader_t* reader, char* buf, size_t bufsize) {
-    uint32_t length = mpack_expect_str(reader);
-    mpack_read_utf8_cstr(reader, buf, bufsize, length);
-    mpack_done_str(reader);
-}
-
-#ifdef MPACK_MALLOC
-static char* mpack_expect_cstr_alloc_unchecked(mpack_reader_t* reader, size_t maxsize, size_t* out_length) {
-    mpack_assert(out_length != NULL, "out_length cannot be NULL");
-    *out_length = 0;
-
-    // make sure argument makes sense
-    if (maxsize < 1) {
-        mpack_break("maxsize is zero; you must have room for at least a null-terminator");
-        mpack_reader_flag_error(reader, mpack_error_bug);
-        return NULL;
-    }
-
-    if (SIZE_MAX < MPACK_UINT32_MAX) {
-        if (maxsize > SIZE_MAX)
-            maxsize = SIZE_MAX;
-    } else {
-        if (maxsize > (size_t)MPACK_UINT32_MAX)
-            maxsize = (size_t)MPACK_UINT32_MAX;
-    }
-
-    size_t length = mpack_expect_str_max(reader, (uint32_t)maxsize - 1);
-    char* str = mpack_read_bytes_alloc_impl(reader, length, true);
-    mpack_done_str(reader);
-
-    if (str)
-        *out_length = length;
-    return str;
-}
-
-char* mpack_expect_cstr_alloc(mpack_reader_t* reader, size_t maxsize) {
-    size_t length;
-    char* str = mpack_expect_cstr_alloc_unchecked(reader, maxsize, &length);
-
-    if (str && !mpack_str_check_no_null(str, length)) {
-        MPACK_FREE(str);
-        mpack_reader_flag_error(reader, mpack_error_type);
-        return NULL;
-    }
-
-    return str;
-}
-
-char* mpack_expect_utf8_cstr_alloc(mpack_reader_t* reader, size_t maxsize) {
-    size_t length;
-    char* str = mpack_expect_cstr_alloc_unchecked(reader, maxsize, &length);
-
-    if (str && !mpack_utf8_check_no_null(str, length)) {
-        MPACK_FREE(str);
-        mpack_reader_flag_error(reader, mpack_error_type);
-        return NULL;
-    }
-
-    return str;
-}
-#endif
-
-void mpack_expect_str_match(mpack_reader_t* reader, const char* str, size_t len) {
-    mpack_assert(str != NULL, "str cannot be NULL");
-
-    // expect a str the correct length
-    if (len > MPACK_UINT32_MAX)
-        mpack_reader_flag_error(reader, mpack_error_type);
-    mpack_expect_str_length(reader, (uint32_t)len);
-    if (mpack_reader_error(reader))
-        return;
-    mpack_reader_track_bytes(reader, (uint32_t)len);
-
-    // check each byte one by one (matched strings are likely to be very small)
-    for (; len > 0; --len) {
-        if (mpack_expect_native_u8(reader) != *str++) {
-            mpack_reader_flag_error(reader, mpack_error_type);
-            return;
-        }
-    }
-
-    mpack_done_str(reader);
-}
-
-void mpack_expect_tag(mpack_reader_t* reader, mpack_tag_t expected) {
-    mpack_tag_t actual = mpack_read_tag(reader);
-    if (!mpack_tag_equal(actual, expected))
-        mpack_reader_flag_error(reader, mpack_error_type);
-}
-
-#ifdef MPACK_MALLOC
-char* mpack_expect_bin_alloc(mpack_reader_t* reader, size_t maxsize, size_t* size) {
-    mpack_assert(size != NULL, "size cannot be NULL");
-    *size = 0;
-
-    if (SIZE_MAX < MPACK_UINT32_MAX) {
-        if (maxsize > SIZE_MAX)
-            maxsize = SIZE_MAX;
-    } else {
-        if (maxsize > (size_t)MPACK_UINT32_MAX)
-            maxsize = (size_t)MPACK_UINT32_MAX;
-    }
-
-    size_t length = mpack_expect_bin_max(reader, (uint32_t)maxsize);
-    if (mpack_reader_error(reader))
-        return NULL;
-
-    char* data = mpack_read_bytes_alloc(reader, length);
-    mpack_done_bin(reader);
-
-    if (data)
-        *size = length;
-    return data;
-}
-#endif
-
-#if MPACK_EXTENSIONS && defined(MPACK_MALLOC)
-char* mpack_expect_ext_alloc(mpack_reader_t* reader, int8_t* type, size_t maxsize, size_t* size) {
-    mpack_assert(size != NULL, "size cannot be NULL");
-    *size = 0;
-
-    if (SIZE_MAX < MPACK_UINT32_MAX) {
-        if (maxsize > SIZE_MAX)
-            maxsize = SIZE_MAX;
-    } else {
-        if (maxsize > (size_t)MPACK_UINT32_MAX)
-            maxsize = (size_t)MPACK_UINT32_MAX;
-    }
-
-    size_t length = mpack_expect_ext_max(reader, type, (uint32_t)maxsize);
-    if (mpack_reader_error(reader))
-        return NULL;
-
-    char* data = mpack_read_bytes_alloc(reader, length);
-    mpack_done_ext(reader);
-
-    if (data) {
-        *size = length;
-    } else {
-        *type = 0;
-    }
-    return data;
-}
-#endif
-
-size_t mpack_expect_enum(mpack_reader_t* reader, const char* strings[], size_t count) {
-
-    // read the string in-place
-    size_t keylen = mpack_expect_str(reader);
-    const char* key = mpack_read_bytes_inplace(reader, keylen);
-    mpack_done_str(reader);
-    if (mpack_reader_error(reader) != mpack_ok)
-        return count;
-
-    // find what key it matches
-    size_t i;
-    for (i = 0; i < count; ++i) {
-        const char* other = strings[i];
-        size_t otherlen = mpack_strlen(other);
-        if (keylen == otherlen && mpack_memcmp(key, other, keylen) == 0)
-            return i;
-    }
-
-    // no matches
-    mpack_reader_flag_error(reader, mpack_error_type);
-    return count;
-}
-
-size_t mpack_expect_enum_optional(mpack_reader_t* reader, const char* strings[], size_t count) {
-    if (mpack_reader_error(reader) != mpack_ok)
-        return count;
-
-    mpack_assert(count != 0, "count cannot be zero; no strings are valid!");
-    mpack_assert(strings != NULL, "strings cannot be NULL");
-
-    // the key is only recognized if it is a string
-    if (mpack_peek_tag(reader).type != mpack_type_str) {
-        mpack_discard(reader);
-        return count;
-    }
-
-    // read the string in-place
-    size_t keylen = mpack_expect_str(reader);
-    const char* key = mpack_read_bytes_inplace(reader, keylen);
-    mpack_done_str(reader);
-    if (mpack_reader_error(reader) != mpack_ok)
-        return count;
-
-    // find what key it matches
-    size_t i;
-    for (i = 0; i < count; ++i) {
-        const char* other = strings[i];
-        size_t otherlen = mpack_strlen(other);
-        if (keylen == otherlen && mpack_memcmp(key, other, keylen) == 0)
-            return i;
-    }
-
-    // no matches
-    return count;
-}
-
-size_t mpack_expect_key_uint(mpack_reader_t* reader, bool found[], size_t count) {
-    if (mpack_reader_error(reader) != mpack_ok)
-        return count;
-
-    if (count == 0) {
-        mpack_break("count cannot be zero; no keys are valid!");
-        mpack_reader_flag_error(reader, mpack_error_bug);
-        return count;
-    }
-    mpack_assert(found != NULL, "found cannot be NULL");
-
-    // the key is only recognized if it is an unsigned int
-    if (mpack_peek_tag(reader).type != mpack_type_uint) {
-        mpack_discard(reader);
-        return count;
-    }
-
-    // read the key
-    uint64_t value = mpack_expect_u64(reader);
-    if (mpack_reader_error(reader) != mpack_ok)
-        return count;
-
-    // unrecognized keys are fine, we just return count
-    if (value >= count)
-        return count;
-
-    // check if this key is a duplicate
-    if (found[value]) {
-        mpack_reader_flag_error(reader, mpack_error_invalid);
-        return count;
-    }
-
-    found[value] = true;
-    return (size_t)value;
-}
-
-size_t mpack_expect_key_cstr(mpack_reader_t* reader, const char* keys[], bool found[], size_t count) {
-    size_t i = mpack_expect_enum_optional(reader, keys, count);
-
-    // unrecognized keys are fine, we just return count
-    if (i == count)
-        return count;
-
-    // check if this key is a duplicate
-    mpack_assert(found != NULL, "found cannot be NULL");
-    if (found[i]) {
-        mpack_reader_flag_error(reader, mpack_error_invalid);
-        return count;
-    }
-
-    found[i] = true;
-    return i;
-}
-
-#endif
-
-MPACK_SILENCE_WARNINGS_END
-
-/* mpack/mpack-node.c.c */
-
-#define MPACK_INTERNAL 1
-
-/* #include "mpack-node.h" */
-
-MPACK_SILENCE_WARNINGS_BEGIN
-
-#if MPACK_NODE
-
-MPACK_STATIC_INLINE const char* mpack_node_data_unchecked(mpack_node_t node) {
-    mpack_assert(mpack_node_error(node) == mpack_ok, "tree is in an error state!");
-
-    mpack_type_t type = node.data->type;
-    MPACK_UNUSED(type);
-    #if MPACK_EXTENSIONS
-    mpack_assert(type == mpack_type_str || type == mpack_type_bin || type == mpack_type_ext,
-            "node of type %i (%s) is not a data type!", type, mpack_type_to_string(type));
-    #else
-    mpack_assert(type == mpack_type_str || type == mpack_type_bin,
-            "node of type %i (%s) is not a data type!", type, mpack_type_to_string(type));
-    #endif
-
-    return node.tree->data + node.data->value.offset;
-}
-
-#if MPACK_EXTENSIONS
-MPACK_STATIC_INLINE int8_t mpack_node_exttype_unchecked(mpack_node_t node) {
-    mpack_assert(mpack_node_error(node) == mpack_ok, "tree is in an error state!");
-
-    mpack_type_t type = node.data->type;
-    MPACK_UNUSED(type);
-    mpack_assert(type == mpack_type_ext, "node of type %i (%s) is not an ext type!",
-            type, mpack_type_to_string(type));
-
-    // the exttype of an ext node is stored in the byte preceding the data
-    return mpack_load_i8(mpack_node_data_unchecked(node) - 1);
-}
-#endif
-
-
-
-/*
- * Tree Parsing
- */
-
-#ifdef MPACK_MALLOC
-
-// fix up the alloc size to make sure it exactly fits the
-// maximum number of nodes it can contain (the allocator will
-// waste it back anyway, but we round it down just in case)
-
-#define MPACK_NODES_PER_PAGE \
-    ((MPACK_NODE_PAGE_SIZE - sizeof(mpack_tree_page_t)) / sizeof(mpack_node_data_t) + 1)
-
-#define MPACK_PAGE_ALLOC_SIZE \
-    (sizeof(mpack_tree_page_t) + sizeof(mpack_node_data_t) * (MPACK_NODES_PER_PAGE - 1))
-
-#endif
-
-#ifdef MPACK_MALLOC
-/*
- * Fills the tree until we have at least enough bytes for the current node.
- */
-static bool mpack_tree_reserve_fill(mpack_tree_t* tree) {
-    mpack_assert(tree->parser.state == mpack_tree_parse_state_in_progress);
-
-    size_t bytes = tree->parser.current_node_reserved;
-    mpack_assert(bytes > tree->parser.possible_nodes_left,
-            "there are already enough bytes! call mpack_tree_ensure() instead.");
-    mpack_log("filling to reserve %i bytes\n", (int)bytes);
-
-    // if the necessary bytes would put us over the maximum tree
-    // size, fail right away.
-    // TODO: check for overflow?
-    if (tree->data_length + bytes > tree->max_size) {
-        mpack_tree_flag_error(tree, mpack_error_too_big);
-        return false;
-    }
-
-    // we'll need a read function to fetch more data. if there's
-    // no read function, the data should contain an entire message
-    // (or messages), so we flag it as invalid.
-    if (tree->read_fn == NULL) {
-        mpack_log("tree has no read function!\n");
-        mpack_tree_flag_error(tree, mpack_error_invalid);
-        return false;
-    }
-
-    // expand the buffer if needed
-    if (tree->data_length + bytes > tree->buffer_capacity) {
-
-        // TODO: check for overflow?
-        size_t new_capacity = (tree->buffer_capacity == 0) ? MPACK_BUFFER_SIZE : tree->buffer_capacity;
-        while (new_capacity < tree->data_length + bytes)
-            new_capacity *= 2;
-        if (new_capacity > tree->max_size)
-            new_capacity = tree->max_size;
-
-        mpack_log("expanding buffer from %i to %i\n", (int)tree->buffer_capacity, (int)new_capacity);
-
-        char* new_buffer;
-        if (tree->buffer == NULL)
-            new_buffer = (char*)MPACK_MALLOC(new_capacity);
-        else
-            new_buffer = (char*)mpack_realloc(tree->buffer, tree->data_length, new_capacity);
-
-        if (new_buffer == NULL) {
-            mpack_tree_flag_error(tree, mpack_error_memory);
-            return false;
-        }
-
-        tree->data = new_buffer;
-        tree->buffer = new_buffer;
-        tree->buffer_capacity = new_capacity;
-    }
-
-    // request as much data as possible, looping until we have
-    // all the data we need
-    do {
-        size_t read = tree->read_fn(tree, tree->buffer + tree->data_length, tree->buffer_capacity - tree->data_length);
-
-        // If the fill function encounters an error, it should flag an error on
-        // the tree.
-        if (mpack_tree_error(tree) != mpack_ok)
-            return false;
-
-        // We guard against fill functions that return -1 just in case.
-        if (read == (size_t)(-1)) {
-            mpack_tree_flag_error(tree, mpack_error_io);
-            return false;
-        }
-
-        // If the fill function returns 0, the data is not available yet. We
-        // return false to stop parsing the current node.
-        if (read == 0) {
-            mpack_log("not enough data.\n");
-            return false;
-        }
-
-        mpack_log("read %u more bytes\n", (uint32_t)read);
-        tree->data_length += read;
-        tree->parser.possible_nodes_left += read;
-    } while (tree->parser.possible_nodes_left < bytes);
-
-    return true;
-}
-#endif
-
-/*
- * Ensures there are enough additional bytes in the tree for the current node
- * (including reserved bytes for the children of this node, and in addition to
- * the reserved bytes for children of previous compound nodes), reading more
- * data if needed.
- *
- * extra_bytes is the number of additional bytes to reserve for the current
- * node beyond the type byte (since one byte is already reserved for each node
- * by its parent array or map.)
- *
- * This may reallocate the tree, which means the tree->data pointer may change!
- *
- * Returns false if not enough bytes could be read.
- */
-MPACK_STATIC_INLINE bool mpack_tree_reserve_bytes(mpack_tree_t* tree, size_t extra_bytes) {
-    mpack_assert(tree->parser.state == mpack_tree_parse_state_in_progress);
-
-    // We guard against overflow here. A compound type could declare more than
-    // MPACK_UINT32_MAX contents which overflows SIZE_MAX on 32-bit platforms. We
-    // flag mpack_error_invalid instead of mpack_error_too_big since it's far
-    // more likely that the message is corrupt than that the data is valid but
-    // not parseable on this architecture (see test_read_node_possible() in
-    // test-node.c .)
-    if ((uint64_t)tree->parser.current_node_reserved + (uint64_t)extra_bytes > SIZE_MAX) {
-        mpack_tree_flag_error(tree, mpack_error_invalid);
-        return false;
-    }
-
-    tree->parser.current_node_reserved += extra_bytes;
-
-    // Note that possible_nodes_left already accounts for reserved bytes for
-    // children of previous compound nodes. So even if there are hundreds of
-    // bytes left in the buffer, we might need to read anyway.
-    if (tree->parser.current_node_reserved <= tree->parser.possible_nodes_left)
-        return true;
-
-    #ifdef MPACK_MALLOC
-    return mpack_tree_reserve_fill(tree);
-    #else
-    return false;
-    #endif
-}
-
-MPACK_STATIC_INLINE size_t mpack_tree_parser_stack_capacity(mpack_tree_t* tree) {
-    #ifdef MPACK_MALLOC
-    return tree->parser.stack_capacity;
-    #else
-    return sizeof(tree->parser.stack) / sizeof(tree->parser.stack[0]);
-    #endif
-}
-
-static bool mpack_tree_push_stack(mpack_tree_t* tree, mpack_node_data_t* first_child, size_t total) {
-    mpack_tree_parser_t* parser = &tree->parser;
-    mpack_assert(parser->state == mpack_tree_parse_state_in_progress);
-
-    // No need to push empty containers
-    if (total == 0)
-        return true;
-
-    // Make sure we have enough room in the stack
-    if (parser->level + 1 == mpack_tree_parser_stack_capacity(tree)) {
-        #ifdef MPACK_MALLOC
-        size_t new_capacity = parser->stack_capacity * 2;
-        mpack_log("growing parse stack to capacity %i\n", (int)new_capacity);
-
-        // Replace the stack-allocated parsing stack
-        if (!parser->stack_owned) {
-            mpack_level_t* new_stack = (mpack_level_t*)MPACK_MALLOC(sizeof(mpack_level_t) * new_capacity);
-            if (!new_stack) {
-                mpack_tree_flag_error(tree, mpack_error_memory);
-                return false;
-            }
-            mpack_memcpy(new_stack, parser->stack, sizeof(mpack_level_t) * parser->stack_capacity);
-            parser->stack = new_stack;
-            parser->stack_owned = true;
-
-        // Realloc the allocated parsing stack
-        } else {
-            mpack_level_t* new_stack = (mpack_level_t*)mpack_realloc(parser->stack,
-                    sizeof(mpack_level_t) * parser->stack_capacity, sizeof(mpack_level_t) * new_capacity);
-            if (!new_stack) {
-                mpack_tree_flag_error(tree, mpack_error_memory);
-                return false;
-            }
-            parser->stack = new_stack;
-        }
-        parser->stack_capacity = new_capacity;
-        #else
-        mpack_tree_flag_error(tree, mpack_error_too_big);
-        return false;
-        #endif
-    }
-
-    // Push the contents of this node onto the parsing stack
-    ++parser->level;
-    parser->stack[parser->level].child = first_child;
-    parser->stack[parser->level].left = total;
-    return true;
-}
-
-static bool mpack_tree_parse_children(mpack_tree_t* tree, mpack_node_data_t* node) {
-    mpack_tree_parser_t* parser = &tree->parser;
-    mpack_assert(parser->state == mpack_tree_parse_state_in_progress);
-
-    mpack_type_t type = node->type;
-    size_t total = node->len;
-
-    // Calculate total elements to read
-    if (type == mpack_type_map) {
-        if ((uint64_t)total * 2 > SIZE_MAX) {
-            mpack_tree_flag_error(tree, mpack_error_too_big);
-            return false;
-        }
-        total *= 2;
-    }
-
-    // Make sure we are under our total node limit (TODO can this overflow?)
-    tree->node_count += total;
-    if (tree->node_count > tree->max_nodes) {
-        mpack_tree_flag_error(tree, mpack_error_too_big);
-        return false;
-    }
-
-    // Each node is at least one byte. Count these bytes now to make
-    // sure there is enough data left.
-    if (!mpack_tree_reserve_bytes(tree, total))
-        return false;
-
-    // If there are enough nodes left in the current page, no need to grow
-    if (total <= parser->nodes_left) {
-        node->value.children = parser->nodes;
-        parser->nodes += total;
-        parser->nodes_left -= total;
-
-    } else {
-
-        #ifdef MPACK_MALLOC
-
-        // We can't grow if we're using a fixed pool (i.e. we didn't start with a page)
-        if (!tree->next) {
-            mpack_tree_flag_error(tree, mpack_error_too_big);
-            return false;
-        }
-
-        // Otherwise we need to grow, and the node's children need to be contiguous.
-        // This is a heuristic to decide whether we should waste the remaining space
-        // in the current page and start a new one, or give the children their
-        // own page. With a fraction of 1/8, this causes at most 12% additional
-        // waste. Note that reducing this too much causes less cache coherence and
-        // more malloc() overhead due to smaller allocations, so there's a tradeoff
-        // here. This heuristic could use some improvement, especially with custom
-        // page sizes.
-
-        mpack_tree_page_t* page;
-
-        if (total > MPACK_NODES_PER_PAGE || parser->nodes_left > MPACK_NODES_PER_PAGE / 8) {
-            // TODO: this should check for overflow
-            page = (mpack_tree_page_t*)MPACK_MALLOC(
-                    sizeof(mpack_tree_page_t) + sizeof(mpack_node_data_t) * (total - 1));
-            if (page == NULL) {
-                mpack_tree_flag_error(tree, mpack_error_memory);
-                return false;
-            }
-            mpack_log("allocated seperate page %p for %i children, %i left in page of %i total\n",
-                    (void*)page, (int)total, (int)parser->nodes_left, (int)MPACK_NODES_PER_PAGE);
-
-            node->value.children = page->nodes;
-
-        } else {
-            page = (mpack_tree_page_t*)MPACK_MALLOC(MPACK_PAGE_ALLOC_SIZE);
-            if (page == NULL) {
-                mpack_tree_flag_error(tree, mpack_error_memory);
-                return false;
-            }
-            mpack_log("allocated new page %p for %i children, wasting %i in page of %i total\n",
-                    (void*)page, (int)total, (int)parser->nodes_left, (int)MPACK_NODES_PER_PAGE);
-
-            node->value.children = page->nodes;
-            parser->nodes = page->nodes + total;
-            parser->nodes_left = MPACK_NODES_PER_PAGE - total;
-        }
-
-        page->next = tree->next;
-        tree->next = page;
-
-        #else
-        // We can't grow if we don't have an allocator
-        mpack_tree_flag_error(tree, mpack_error_too_big);
-        return false;
-        #endif
-    }
-
-    return mpack_tree_push_stack(tree, node->value.children, total);
-}
-
-static bool mpack_tree_parse_bytes(mpack_tree_t* tree, mpack_node_data_t* node) {
-    node->value.offset = tree->size + tree->parser.current_node_reserved + 1;
-    return mpack_tree_reserve_bytes(tree, node->len);
-}
-
-#if MPACK_EXTENSIONS
-static bool mpack_tree_parse_ext(mpack_tree_t* tree, mpack_node_data_t* node) {
-    // reserve space for exttype
-    tree->parser.current_node_reserved += sizeof(int8_t);
-    node->type = mpack_type_ext;
-    return mpack_tree_parse_bytes(tree, node);
-}
-#endif
-
-static bool mpack_tree_parse_node_contents(mpack_tree_t* tree, mpack_node_data_t* node) {
-    mpack_assert(tree->parser.state == mpack_tree_parse_state_in_progress);
-    mpack_assert(node != NULL, "null node?");
-
-    // read the type. we've already accounted for this byte in
-    // possible_nodes_left, so we already know it is in bounds, and we don't
-    // need to reserve it for this node.
-    mpack_assert(tree->data_length > tree->size);
-    uint8_t type = mpack_load_u8(tree->data + tree->size);
-    mpack_log("node type %x\n", type);
-    tree->parser.current_node_reserved = 0;
-
-    // as with mpack_read_tag(), the fastest way to parse a node is to switch
-    // on the first byte, and to explicitly list every possible byte. we switch
-    // on the first four bits in size-optimized builds.
-
-    #if MPACK_OPTIMIZE_FOR_SIZE
-    switch (type >> 4) {
-
-        // positive fixnum
-        case 0x0: case 0x1: case 0x2: case 0x3:
-        case 0x4: case 0x5: case 0x6: case 0x7:
-            node->type = mpack_type_uint;
-            node->value.u = type;
-            return true;
-
-        // negative fixnum
-        case 0xe: case 0xf:
-            node->type = mpack_type_int;
-            node->value.i = (int8_t)type;
-            return true;
-
-        // fixmap
-        case 0x8:
-            node->type = mpack_type_map;
-            node->len = (uint32_t)(type & ~0xf0);
-            return mpack_tree_parse_children(tree, node);
-
-        // fixarray
-        case 0x9:
-            node->type = mpack_type_array;
-            node->len = (uint32_t)(type & ~0xf0);
-            return mpack_tree_parse_children(tree, node);
-
-        // fixstr
-        case 0xa: case 0xb:
-            node->type = mpack_type_str;
-            node->len = (uint32_t)(type & ~0xe0);
-            return mpack_tree_parse_bytes(tree, node);
-
-        // not one of the common infix types
-        default:
-            break;
-    }
-    #endif
-
-    switch (type) {
-
-        #if !MPACK_OPTIMIZE_FOR_SIZE
-        // positive fixnum
-        case 0x00: case 0x01: case 0x02: case 0x03: case 0x04: case 0x05: case 0x06: case 0x07:
-        case 0x08: case 0x09: case 0x0a: case 0x0b: case 0x0c: case 0x0d: case 0x0e: case 0x0f:
-        case 0x10: case 0x11: case 0x12: case 0x13: case 0x14: case 0x15: case 0x16: case 0x17:
-        case 0x18: case 0x19: case 0x1a: case 0x1b: case 0x1c: case 0x1d: case 0x1e: case 0x1f:
-        case 0x20: case 0x21: case 0x22: case 0x23: case 0x24: case 0x25: case 0x26: case 0x27:
-        case 0x28: case 0x29: case 0x2a: case 0x2b: case 0x2c: case 0x2d: case 0x2e: case 0x2f:
-        case 0x30: case 0x31: case 0x32: case 0x33: case 0x34: case 0x35: case 0x36: case 0x37:
-        case 0x38: case 0x39: case 0x3a: case 0x3b: case 0x3c: case 0x3d: case 0x3e: case 0x3f:
-        case 0x40: case 0x41: case 0x42: case 0x43: case 0x44: case 0x45: case 0x46: case 0x47:
-        case 0x48: case 0x49: case 0x4a: case 0x4b: case 0x4c: case 0x4d: case 0x4e: case 0x4f:
-        case 0x50: case 0x51: case 0x52: case 0x53: case 0x54: case 0x55: case 0x56: case 0x57:
-        case 0x58: case 0x59: case 0x5a: case 0x5b: case 0x5c: case 0x5d: case 0x5e: case 0x5f:
-        case 0x60: case 0x61: case 0x62: case 0x63: case 0x64: case 0x65: case 0x66: case 0x67:
-        case 0x68: case 0x69: case 0x6a: case 0x6b: case 0x6c: case 0x6d: case 0x6e: case 0x6f:
-        case 0x70: case 0x71: case 0x72: case 0x73: case 0x74: case 0x75: case 0x76: case 0x77:
-        case 0x78: case 0x79: case 0x7a: case 0x7b: case 0x7c: case 0x7d: case 0x7e: case 0x7f:
-            node->type = mpack_type_uint;
-            node->value.u = type;
-            return true;
-
-        // negative fixnum
-        case 0xe0: case 0xe1: case 0xe2: case 0xe3: case 0xe4: case 0xe5: case 0xe6: case 0xe7:
-        case 0xe8: case 0xe9: case 0xea: case 0xeb: case 0xec: case 0xed: case 0xee: case 0xef:
-        case 0xf0: case 0xf1: case 0xf2: case 0xf3: case 0xf4: case 0xf5: case 0xf6: case 0xf7:
-        case 0xf8: case 0xf9: case 0xfa: case 0xfb: case 0xfc: case 0xfd: case 0xfe: case 0xff:
-            node->type = mpack_type_int;
-            node->value.i = (int8_t)type;
-            return true;
-
-        // fixmap
-        case 0x80: case 0x81: case 0x82: case 0x83: case 0x84: case 0x85: case 0x86: case 0x87:
-        case 0x88: case 0x89: case 0x8a: case 0x8b: case 0x8c: case 0x8d: case 0x8e: case 0x8f:
-            node->type = mpack_type_map;
-            node->len = (uint32_t)(type & ~0xf0);
-            return mpack_tree_parse_children(tree, node);
-
-        // fixarray
-        case 0x90: case 0x91: case 0x92: case 0x93: case 0x94: case 0x95: case 0x96: case 0x97:
-        case 0x98: case 0x99: case 0x9a: case 0x9b: case 0x9c: case 0x9d: case 0x9e: case 0x9f:
-            node->type = mpack_type_array;
-            node->len = (uint32_t)(type & ~0xf0);
-            return mpack_tree_parse_children(tree, node);
-
-        // fixstr
-        case 0xa0: case 0xa1: case 0xa2: case 0xa3: case 0xa4: case 0xa5: case 0xa6: case 0xa7:
-        case 0xa8: case 0xa9: case 0xaa: case 0xab: case 0xac: case 0xad: case 0xae: case 0xaf:
-        case 0xb0: case 0xb1: case 0xb2: case 0xb3: case 0xb4: case 0xb5: case 0xb6: case 0xb7:
-        case 0xb8: case 0xb9: case 0xba: case 0xbb: case 0xbc: case 0xbd: case 0xbe: case 0xbf:
-            node->type = mpack_type_str;
-            node->len = (uint32_t)(type & ~0xe0);
-            return mpack_tree_parse_bytes(tree, node);
-        #endif
-
-        // nil
-        case 0xc0:
-            node->type = mpack_type_nil;
-            return true;
-
-        // bool
-        case 0xc2: case 0xc3:
-            node->type = mpack_type_bool;
-            node->value.b = type & 1;
-            return true;
-
-        // bin8
-        case 0xc4:
-            node->type = mpack_type_bin;
-            if (!mpack_tree_reserve_bytes(tree, sizeof(uint8_t)))
-                return false;
-            node->len = mpack_load_u8(tree->data + tree->size + 1);
-            return mpack_tree_parse_bytes(tree, node);
-
-        // bin16
-        case 0xc5:
-            node->type = mpack_type_bin;
-            if (!mpack_tree_reserve_bytes(tree, sizeof(uint16_t)))
-                return false;
-            node->len = mpack_load_u16(tree->data + tree->size + 1);
-            return mpack_tree_parse_bytes(tree, node);
-
-        // bin32
-        case 0xc6:
-            node->type = mpack_type_bin;
-            if (!mpack_tree_reserve_bytes(tree, sizeof(uint32_t)))
-                return false;
-            node->len = mpack_load_u32(tree->data + tree->size + 1);
-            return mpack_tree_parse_bytes(tree, node);
-
-        #if MPACK_EXTENSIONS
-        // ext8
-        case 0xc7:
-            if (!mpack_tree_reserve_bytes(tree, sizeof(uint8_t)))
-                return false;
-            node->len = mpack_load_u8(tree->data + tree->size + 1);
-            return mpack_tree_parse_ext(tree, node);
-
-        // ext16
-        case 0xc8:
-            if (!mpack_tree_reserve_bytes(tree, sizeof(uint16_t)))
-                return false;
-            node->len = mpack_load_u16(tree->data + tree->size + 1);
-            return mpack_tree_parse_ext(tree, node);
-
-        // ext32
-        case 0xc9:
-            if (!mpack_tree_reserve_bytes(tree, sizeof(uint32_t)))
-                return false;
-            node->len = mpack_load_u32(tree->data + tree->size + 1);
-            return mpack_tree_parse_ext(tree, node);
-        #endif
-
-        // float
-        case 0xca:
-            #if MPACK_FLOAT
-            if (!mpack_tree_reserve_bytes(tree, sizeof(float)))
-                return false;
-            node->value.f = mpack_load_float(tree->data + tree->size + 1);
-            #else
-            if (!mpack_tree_reserve_bytes(tree, sizeof(uint32_t)))
-                return false;
-            node->value.f = mpack_load_u32(tree->data + tree->size + 1);
-            #endif
-            node->type = mpack_type_float;
-            return true;
-
-        // double
-        case 0xcb:
-            #if MPACK_DOUBLE
-            if (!mpack_tree_reserve_bytes(tree, sizeof(double)))
-                return false;
-            node->value.d = mpack_load_double(tree->data + tree->size + 1);
-            #else
-            if (!mpack_tree_reserve_bytes(tree, sizeof(uint64_t)))
-                return false;
-            node->value.d = mpack_load_u64(tree->data + tree->size + 1);
-            #endif
-            node->type = mpack_type_double;
-            return true;
-
-        // uint8
-        case 0xcc:
-            node->type = mpack_type_uint;
-            if (!mpack_tree_reserve_bytes(tree, sizeof(uint8_t)))
-                return false;
-            node->value.u = mpack_load_u8(tree->data + tree->size + 1);
-            return true;
-
-        // uint16
-        case 0xcd:
-            node->type = mpack_type_uint;
-            if (!mpack_tree_reserve_bytes(tree, sizeof(uint16_t)))
-                return false;
-            node->value.u = mpack_load_u16(tree->data + tree->size + 1);
-            return true;
-
-        // uint32
-        case 0xce:
-            node->type = mpack_type_uint;
-            if (!mpack_tree_reserve_bytes(tree, sizeof(uint32_t)))
-                return false;
-            node->value.u = mpack_load_u32(tree->data + tree->size + 1);
-            return true;
-
-        // uint64
-        case 0xcf:
-            node->type = mpack_type_uint;
-            if (!mpack_tree_reserve_bytes(tree, sizeof(uint64_t)))
-                return false;
-            node->value.u = mpack_load_u64(tree->data + tree->size + 1);
-            return true;
-
-        // int8
-        case 0xd0:
-            node->type = mpack_type_int;
-            if (!mpack_tree_reserve_bytes(tree, sizeof(int8_t)))
-                return false;
-            node->value.i = mpack_load_i8(tree->data + tree->size + 1);
-            return true;
-
-        // int16
-        case 0xd1:
-            node->type = mpack_type_int;
-            if (!mpack_tree_reserve_bytes(tree, sizeof(int16_t)))
-                return false;
-            node->value.i = mpack_load_i16(tree->data + tree->size + 1);
-            return true;
-
-        // int32
-        case 0xd2:
-            node->type = mpack_type_int;
-            if (!mpack_tree_reserve_bytes(tree, sizeof(int32_t)))
-                return false;
-            node->value.i = mpack_load_i32(tree->data + tree->size + 1);
-            return true;
-
-        // int64
-        case 0xd3:
-            node->type = mpack_type_int;
-            if (!mpack_tree_reserve_bytes(tree, sizeof(int64_t)))
-                return false;
-            node->value.i = mpack_load_i64(tree->data + tree->size + 1);
-            return true;
-
-        #if MPACK_EXTENSIONS
-        // fixext1
-        case 0xd4:
-            node->len = 1;
-            return mpack_tree_parse_ext(tree, node);
-
-        // fixext2
-        case 0xd5:
-            node->len = 2;
-            return mpack_tree_parse_ext(tree, node);
-
-        // fixext4
-        case 0xd6:
-            node->len = 4;
-            return mpack_tree_parse_ext(tree, node);
-
-        // fixext8
-        case 0xd7:
-            node->len = 8;
-            return mpack_tree_parse_ext(tree, node);
-
-        // fixext16
-        case 0xd8:
-            node->len = 16;
-            return mpack_tree_parse_ext(tree, node);
-        #endif
-
-        // str8
-        case 0xd9:
-            if (!mpack_tree_reserve_bytes(tree, sizeof(uint8_t)))
-                return false;
-            node->len = mpack_load_u8(tree->data + tree->size + 1);
-            node->type = mpack_type_str;
-            return mpack_tree_parse_bytes(tree, node);
-
-        // str16
-        case 0xda:
-            if (!mpack_tree_reserve_bytes(tree, sizeof(uint16_t)))
-                return false;
-            node->len = mpack_load_u16(tree->data + tree->size + 1);
-            node->type = mpack_type_str;
-            return mpack_tree_parse_bytes(tree, node);
-
-        // str32
-        case 0xdb:
-            if (!mpack_tree_reserve_bytes(tree, sizeof(uint32_t)))
-                return false;
-            node->len = mpack_load_u32(tree->data + tree->size + 1);
-            node->type = mpack_type_str;
-            return mpack_tree_parse_bytes(tree, node);
-
-        // array16
-        case 0xdc:
-            if (!mpack_tree_reserve_bytes(tree, sizeof(uint16_t)))
-                return false;
-            node->len = mpack_load_u16(tree->data + tree->size + 1);
-            node->type = mpack_type_array;
-            return mpack_tree_parse_children(tree, node);
-
-        // array32
-        case 0xdd:
-            if (!mpack_tree_reserve_bytes(tree, sizeof(uint32_t)))
-                return false;
-            node->len = mpack_load_u32(tree->data + tree->size + 1);
-            node->type = mpack_type_array;
-            return mpack_tree_parse_children(tree, node);
-
-        // map16
-        case 0xde:
-            if (!mpack_tree_reserve_bytes(tree, sizeof(uint16_t)))
-                return false;
-            node->len = mpack_load_u16(tree->data + tree->size + 1);
-            node->type = mpack_type_map;
-            return mpack_tree_parse_children(tree, node);
-
-        // map32
-        case 0xdf:
-            if (!mpack_tree_reserve_bytes(tree, sizeof(uint32_t)))
-                return false;
-            node->len = mpack_load_u32(tree->data + tree->size + 1);
-            node->type = mpack_type_map;
-            return mpack_tree_parse_children(tree, node);
-
-        // reserved
-        case 0xc1:
-            mpack_tree_flag_error(tree, mpack_error_invalid);
-            return false;
-
-        #if !MPACK_EXTENSIONS
-        // ext
-        case 0xc7: // fallthrough
-        case 0xc8: // fallthrough
-        case 0xc9: // fallthrough
-        // fixext
-        case 0xd4: // fallthrough
-        case 0xd5: // fallthrough
-        case 0xd6: // fallthrough
-        case 0xd7: // fallthrough
-        case 0xd8:
-            mpack_tree_flag_error(tree, mpack_error_unsupported);
-            return false;
-        #endif
-
-        #if MPACK_OPTIMIZE_FOR_SIZE
-        // any other bytes should have been handled by the infix switch
-        default:
-            break;
-        #endif
-    }
-
-    mpack_assert(0, "unreachable");
-    return false;
-}
-
-static bool mpack_tree_parse_node(mpack_tree_t* tree, mpack_node_data_t* node) {
-    mpack_log("parsing a node at position %i in level %i\n",
-            (int)tree->size, (int)tree->parser.level);
-
-    if (!mpack_tree_parse_node_contents(tree, node)) {
-        mpack_log("node parsing returned false\n");
-        return false;
-    }
-
-    tree->parser.possible_nodes_left -= tree->parser.current_node_reserved;
-
-    // The reserve for the current node does not include the initial byte
-    // previously reserved as part of its parent.
-    size_t node_size = tree->parser.current_node_reserved + 1;
-
-    // If the parsed type is a map or array, the reserve includes one byte for
-    // each child. We want to subtract these out of possible_nodes_left, but
-    // not out of the current size of the tree.
-    if (node->type == mpack_type_array)
-        node_size -= node->len;
-    else if (node->type == mpack_type_map)
-        node_size -= node->len * 2;
-    tree->size += node_size;
-
-    mpack_log("parsed a node of type %s of %i bytes and "
-            "%i additional bytes reserved for children.\n",
-            mpack_type_to_string(node->type), (int)node_size,
-            (int)tree->parser.current_node_reserved + 1 - (int)node_size);
-
-    return true;
-}
-
-/*
- * We read nodes in a loop instead of recursively for maximum performance. The
- * stack holds the amount of children left to read in each level of the tree.
- * Parsing can pause and resume when more data becomes available.
- */
-static bool mpack_tree_continue_parsing(mpack_tree_t* tree) {
-    if (mpack_tree_error(tree) != mpack_ok)
-        return false;
-
-    mpack_tree_parser_t* parser = &tree->parser;
-    mpack_assert(parser->state == mpack_tree_parse_state_in_progress);
-    mpack_log("parsing tree elements, %i bytes in buffer\n", (int)tree->data_length);
-
-    // we loop parsing nodes until the parse stack is empty. we break
-    // by returning out of the function.
-    while (true) {
-        mpack_node_data_t* node = parser->stack[parser->level].child;
-        size_t level = parser->level;
-        if (!mpack_tree_parse_node(tree, node))
-            return false;
-        --parser->stack[level].left;
-        ++parser->stack[level].child;
-
-        mpack_assert(mpack_tree_error(tree) == mpack_ok,
-                "mpack_tree_parse_node() should have returned false due to error!");
-
-        // pop empty stack levels, exiting the outer loop when the stack is empty.
-        // (we could tail-optimize containers by pre-emptively popping empty
-        // stack levels before reading the new element, this way we wouldn't
-        // have to loop. but we eventually want to use the parse stack to give
-        // better error messages that contain the location of the error, so
-        // it needs to be complete.)
-        while (parser->stack[parser->level].left == 0) {
-            if (parser->level == 0)
-                return true;
-            --parser->level;
-        }
-    }
-}
-
-static void mpack_tree_cleanup(mpack_tree_t* tree) {
-    MPACK_UNUSED(tree);
-
-    #ifdef MPACK_MALLOC
-    if (tree->parser.stack_owned) {
-        MPACK_FREE(tree->parser.stack);
-        tree->parser.stack = NULL;
-        tree->parser.stack_owned = false;
-    }
-
-    mpack_tree_page_t* page = tree->next;
-    while (page != NULL) {
-        mpack_tree_page_t* next = page->next;
-        mpack_log("freeing page %p\n", (void*)page);
-        MPACK_FREE(page);
-        page = next;
-    }
-    tree->next = NULL;
-    #endif
-}
-
-static bool mpack_tree_parse_start(mpack_tree_t* tree) {
-    if (mpack_tree_error(tree) != mpack_ok)
-        return false;
-
-    mpack_tree_parser_t* parser = &tree->parser;
-    mpack_assert(parser->state != mpack_tree_parse_state_in_progress,
-            "previous parsing was not finished!");
-
-    if (parser->state == mpack_tree_parse_state_parsed)
-        mpack_tree_cleanup(tree);
-
-    mpack_log("starting parse\n");
-    tree->parser.state = mpack_tree_parse_state_in_progress;
-    tree->parser.current_node_reserved = 0;
-
-    // check if we previously parsed a tree
-    if (tree->size > 0) {
-        #ifdef MPACK_MALLOC
-        // if we're buffered, move the remaining data back to the
-        // start of the buffer
-        // TODO: This is not ideal performance-wise. We should only move data
-        // when we need to call the fill function.
-        // TODO: We could consider shrinking the buffer here, especially if we
-        // determine that the fill function is providing less than a quarter of
-        // the buffer size or if messages take up less than a quarter of the
-        // buffer size. Maybe this should be configurable.
-        if (tree->buffer != NULL) {
-            mpack_memmove(tree->buffer, tree->buffer + tree->size, tree->data_length - tree->size);
-        }
-        else
-        #endif
-        // otherwise advance past the parsed data
-        {
-            tree->data += tree->size;
-        }
-        tree->data_length -= tree->size;
-        tree->size = 0;
-        tree->node_count = 0;
-    }
-
-    // make sure we have at least one byte available before allocating anything
-    parser->possible_nodes_left = tree->data_length;
-    if (!mpack_tree_reserve_bytes(tree, sizeof(uint8_t))) {
-        tree->parser.state = mpack_tree_parse_state_not_started;
-        return false;
-    }
-    mpack_log("parsing tree at %p starting with byte %x\n", tree->data, (uint8_t)tree->data[0]);
-    parser->possible_nodes_left -= 1;
-    tree->node_count = 1;
-
-    #ifdef MPACK_MALLOC
-    parser->stack = parser->stack_local;
-    parser->stack_owned = false;
-    parser->stack_capacity = sizeof(parser->stack_local) / sizeof(*parser->stack_local);
-
-    if (tree->pool == NULL) {
-
-        // allocate first page
-        mpack_tree_page_t* page = (mpack_tree_page_t*)MPACK_MALLOC(MPACK_PAGE_ALLOC_SIZE);
-        mpack_log("allocated initial page %p of size %i count %i\n",
-                (void*)page, (int)MPACK_PAGE_ALLOC_SIZE, (int)MPACK_NODES_PER_PAGE);
-        if (page == NULL) {
-            tree->error = mpack_error_memory;
-            return false;
-        }
-        page->next = NULL;
-        tree->next = page;
-
-        parser->nodes = page->nodes;
-        parser->nodes_left = MPACK_NODES_PER_PAGE;
-    }
-    else
-    #endif
-    {
-        // otherwise use the provided pool
-        mpack_assert(tree->pool != NULL, "no pool provided?");
-        parser->nodes = tree->pool;
-        parser->nodes_left = tree->pool_count;
-    }
-
-    tree->root = parser->nodes;
-    ++parser->nodes;
-    --parser->nodes_left;
-
-    parser->level = 0;
-    parser->stack[0].child = tree->root;
-    parser->stack[0].left = 1;
-
-    return true;
-}
-
-void mpack_tree_parse(mpack_tree_t* tree) {
-    if (mpack_tree_error(tree) != mpack_ok)
-        return;
-
-    if (tree->parser.state != mpack_tree_parse_state_in_progress) {
-        if (!mpack_tree_parse_start(tree)) {
-            mpack_tree_flag_error(tree, (tree->read_fn == NULL) ?
-                    mpack_error_invalid : mpack_error_io);
-            return;
-        }
-    }
-
-    if (!mpack_tree_continue_parsing(tree)) {
-        if (mpack_tree_error(tree) != mpack_ok)
-            return;
-
-        // We're parsing synchronously on a blocking fill function. If we
-        // didn't completely finish parsing the tree, it's an error.
-        mpack_log("tree parsing incomplete. flagging error.\n");
-        mpack_tree_flag_error(tree, (tree->read_fn == NULL) ?
-                mpack_error_invalid : mpack_error_io);
-        return;
-    }
-
-    mpack_assert(mpack_tree_error(tree) == mpack_ok);
-    mpack_assert(tree->parser.level == 0);
-    tree->parser.state = mpack_tree_parse_state_parsed;
-    mpack_log("parsed tree of %i bytes, %i bytes left\n", (int)tree->size, (int)tree->parser.possible_nodes_left);
-    mpack_log("%i nodes in final page\n", (int)tree->parser.nodes_left);
-}
-
-bool mpack_tree_try_parse(mpack_tree_t* tree) {
-    if (mpack_tree_error(tree) != mpack_ok)
-        return false;
-
-    if (tree->parser.state != mpack_tree_parse_state_in_progress)
-        if (!mpack_tree_parse_start(tree))
-            return false;
-
-    if (!mpack_tree_continue_parsing(tree))
-        return false;
-
-    mpack_assert(mpack_tree_error(tree) == mpack_ok);
-    mpack_assert(tree->parser.level == 0);
-    tree->parser.state = mpack_tree_parse_state_parsed;
-    return true;
-}
-
-
-
-/*
- * Tree functions
- */
-
-mpack_node_t mpack_tree_root(mpack_tree_t* tree) {
-    if (mpack_tree_error(tree) != mpack_ok)
-        return mpack_tree_nil_node(tree);
-
-    // We check that a tree was parsed successfully and assert if not. You must
-    // call mpack_tree_parse() (or mpack_tree_try_parse() with a success
-    // result) in order to access the root node.
-    if (tree->parser.state != mpack_tree_parse_state_parsed) {
-        mpack_break("Tree has not been parsed! "
-                "Did you call mpack_tree_parse() or mpack_tree_try_parse()?");
-        mpack_tree_flag_error(tree, mpack_error_bug);
-        return mpack_tree_nil_node(tree);
-    }
-
-    return mpack_node(tree, tree->root);
-}
-
-static void mpack_tree_init_clear(mpack_tree_t* tree) {
-    mpack_memset(tree, 0, sizeof(*tree));
-    tree->nil_node.type = mpack_type_nil;
-    tree->missing_node.type = mpack_type_missing;
-    tree->max_size = SIZE_MAX;
-    tree->max_nodes = SIZE_MAX;
-}
-
-#ifdef MPACK_MALLOC
-void mpack_tree_init_data(mpack_tree_t* tree, const char* data, size_t length) {
-    mpack_tree_init_clear(tree);
-
-    MPACK_STATIC_ASSERT(MPACK_NODE_PAGE_SIZE >= sizeof(mpack_tree_page_t),
-            "MPACK_NODE_PAGE_SIZE is too small");
-
-    MPACK_STATIC_ASSERT(MPACK_PAGE_ALLOC_SIZE <= MPACK_NODE_PAGE_SIZE,
-            "incorrect page rounding?");
-
-    tree->data = data;
-    tree->data_length = length;
-    tree->pool = NULL;
-    tree->pool_count = 0;
-    tree->next = NULL;
-
-    mpack_log("===========================\n");
-    mpack_log("initializing tree with data of size %i\n", (int)length);
-}
-#endif
-
-void mpack_tree_init_pool(mpack_tree_t* tree, const char* data, size_t length,
-        mpack_node_data_t* node_pool, size_t node_pool_count)
-{
-    mpack_tree_init_clear(tree);
-    #ifdef MPACK_MALLOC
-    tree->next = NULL;
-    #endif
-
-    if (node_pool_count == 0) {
-        mpack_break("initial page has no nodes!");
-        mpack_tree_flag_error(tree, mpack_error_bug);
-        return;
-    }
-
-    tree->data = data;
-    tree->data_length = length;
-    tree->pool = node_pool;
-    tree->pool_count = node_pool_count;
-
-    mpack_log("===========================\n");
-    mpack_log("initializing tree with data of size %i and pool of count %i\n",
-            (int)length, (int)node_pool_count);
-}
-
-void mpack_tree_init_error(mpack_tree_t* tree, mpack_error_t error) {
-    mpack_tree_init_clear(tree);
-    tree->error = error;
-
-    mpack_log("===========================\n");
-    mpack_log("initializing tree error state %i\n", (int)error);
-}
-
-#ifdef MPACK_MALLOC
-void mpack_tree_init_stream(mpack_tree_t* tree, mpack_tree_read_t read_fn, void* context,
-        size_t max_message_size, size_t max_message_nodes) {
-    mpack_tree_init_clear(tree);
-
-    tree->read_fn = read_fn;
-    tree->context = context;
-
-    mpack_tree_set_limits(tree, max_message_size, max_message_nodes);
-    tree->max_size = max_message_size;
-    tree->max_nodes = max_message_nodes;
-
-    mpack_log("===========================\n");
-    mpack_log("initializing tree with stream, max size %i max nodes %i\n",
-            (int)max_message_size, (int)max_message_nodes);
-}
-#endif
-
-void mpack_tree_set_limits(mpack_tree_t* tree, size_t max_message_size, size_t max_message_nodes) {
-    mpack_assert(max_message_size > 0);
-    mpack_assert(max_message_nodes > 0);
-    tree->max_size = max_message_size;
-    tree->max_nodes = max_message_nodes;
-}
-
-#if MPACK_STDIO
-typedef struct mpack_file_tree_t {
-    char* data;
-    size_t size;
-    char buffer[MPACK_BUFFER_SIZE];
-} mpack_file_tree_t;
-
-static void mpack_file_tree_teardown(mpack_tree_t* tree) {
-    mpack_file_tree_t* file_tree = (mpack_file_tree_t*)tree->context;
-    MPACK_FREE(file_tree->data);
-    MPACK_FREE(file_tree);
-}
-
-static bool mpack_file_tree_read(mpack_tree_t* tree, mpack_file_tree_t* file_tree, FILE* file, size_t max_bytes) {
-
-    // get the file size
-    errno = 0;
-    int error = 0;
-    fseek(file, 0, SEEK_END);
-    error |= errno;
-    long size = ftell(file);
-    error |= errno;
-    fseek(file, 0, SEEK_SET);
-    error |= errno;
-
-    // check for errors
-    if (error != 0 || size < 0) {
-        mpack_tree_init_error(tree, mpack_error_io);
-        return false;
-    }
-    if (size == 0) {
-        mpack_tree_init_error(tree, mpack_error_invalid);
-        return false;
-    }
-
-    // make sure the size is less than max_bytes
-    // (this mess exists to safely convert between long and size_t regardless of their widths)
-    if (max_bytes != 0 && (((uint64_t)LONG_MAX > (uint64_t)SIZE_MAX && size > (long)SIZE_MAX) || (size_t)size > max_bytes)) {
-        mpack_tree_init_error(tree, mpack_error_too_big);
-        return false;
-    }
-
-    // allocate data
-    file_tree->data = (char*)MPACK_MALLOC((size_t)size);
-    if (file_tree->data == NULL) {
-        mpack_tree_init_error(tree, mpack_error_memory);
-        return false;
-    }
-
-    // read the file
-    long total = 0;
-    while (total < size) {
-        size_t read = fread(file_tree->data + total, 1, (size_t)(size - total), file);
-        if (read <= 0) {
-            mpack_tree_init_error(tree, mpack_error_io);
-            MPACK_FREE(file_tree->data);
-            return false;
-        }
-        total += (long)read;
-    }
-
-    file_tree->size = (size_t)size;
-    return true;
-}
-
-static bool mpack_tree_file_check_max_bytes(mpack_tree_t* tree, size_t max_bytes) {
-
-    // the C STDIO family of file functions use long (e.g. ftell)
-    if (max_bytes > LONG_MAX) {
-        mpack_break("max_bytes of %" PRIu64 " is invalid, maximum is LONG_MAX", (uint64_t)max_bytes);
-        mpack_tree_init_error(tree, mpack_error_bug);
-        return false;
-    }
-
-    return true;
-}
-
-static void mpack_tree_init_stdfile_noclose(mpack_tree_t* tree, FILE* stdfile, size_t max_bytes) {
-
-    // allocate file tree
-    mpack_file_tree_t* file_tree = (mpack_file_tree_t*) MPACK_MALLOC(sizeof(mpack_file_tree_t));
-    if (file_tree == NULL) {
-        mpack_tree_init_error(tree, mpack_error_memory);
-        return;
-    }
-
-    // read all data
-    if (!mpack_file_tree_read(tree, file_tree, stdfile, max_bytes)) {
-        MPACK_FREE(file_tree);
-        return;
-    }
-
-    mpack_tree_init_data(tree, file_tree->data, file_tree->size);
-    mpack_tree_set_context(tree, file_tree);
-    mpack_tree_set_teardown(tree, mpack_file_tree_teardown);
-}
-
-void mpack_tree_init_stdfile(mpack_tree_t* tree, FILE* stdfile, size_t max_bytes, bool close_when_done) {
-    if (!mpack_tree_file_check_max_bytes(tree, max_bytes))
-        return;
-
-    mpack_tree_init_stdfile_noclose(tree, stdfile, max_bytes);
-
-    if (close_when_done)
-        fclose(stdfile);
-}
-
-void mpack_tree_init_filename(mpack_tree_t* tree, const char* filename, size_t max_bytes) {
-    if (!mpack_tree_file_check_max_bytes(tree, max_bytes))
-        return;
-
-    // open the file
-    FILE* file = fopen(filename, "rb");
-    if (!file) {
-        mpack_tree_init_error(tree, mpack_error_io);
-        return;
-    }
-
-    mpack_tree_init_stdfile(tree, file, max_bytes, true);
-}
-#endif
-
-mpack_error_t mpack_tree_destroy(mpack_tree_t* tree) {
-    mpack_tree_cleanup(tree);
-
-    #ifdef MPACK_MALLOC
-    if (tree->buffer)
-        MPACK_FREE(tree->buffer);
-    #endif
-
-    if (tree->teardown)
-        tree->teardown(tree);
-    tree->teardown = NULL;
-
-    return tree->error;
-}
-
-void mpack_tree_flag_error(mpack_tree_t* tree, mpack_error_t error) {
-    if (tree->error == mpack_ok) {
-        mpack_log("tree %p setting error %i: %s\n", (void*)tree, (int)error, mpack_error_to_string(error));
-        tree->error = error;
-        if (tree->error_fn)
-            tree->error_fn(tree, error);
-    }
-
-}
-
-
-
-/*
- * Node misc functions
- */
-
-void mpack_node_flag_error(mpack_node_t node, mpack_error_t error) {
-    mpack_tree_flag_error(node.tree, error);
-}
-
-mpack_tag_t mpack_node_tag(mpack_node_t node) {
-    if (mpack_node_error(node) != mpack_ok)
-        return mpack_tag_nil();
-
-    mpack_tag_t tag = MPACK_TAG_ZERO;
-
-    tag.type = node.data->type;
-    switch (node.data->type) {
-        case mpack_type_missing:
-            // If a node is missing, I don't know if it makes sense to ask for
-            // a tag for it. We'll return a missing tag to match the missing
-            // node I guess, but attempting to use the tag for anything (like
-            // writing it for example) will flag mpack_error_bug.
-            break;
-        case mpack_type_nil:                                            break;
-        case mpack_type_bool:    tag.v.b = node.data->value.b;          break;
-        case mpack_type_float:   tag.v.f = node.data->value.f;          break;
-        case mpack_type_double:  tag.v.d = node.data->value.d;          break;
-        case mpack_type_int:     tag.v.i = node.data->value.i;          break;
-        case mpack_type_uint:    tag.v.u = node.data->value.u;          break;
-
-        case mpack_type_str:     tag.v.l = node.data->len;     break;
-        case mpack_type_bin:     tag.v.l = node.data->len;     break;
-
-        #if MPACK_EXTENSIONS
-        case mpack_type_ext:
-            tag.v.l = node.data->len;
-            tag.exttype = mpack_node_exttype_unchecked(node);
-            break;
-        #endif
-
-        case mpack_type_array:   tag.v.n = node.data->len;  break;
-        case mpack_type_map:     tag.v.n = node.data->len;  break;
-
-        default:
-            mpack_assert(0, "unrecognized type %i", (int)node.data->type);
-            break;
-    }
-    return tag;
-}
-
-#if MPACK_DEBUG && MPACK_STDIO
-static void mpack_node_print_element(mpack_node_t node, mpack_print_t* print, size_t depth) {
-    mpack_node_data_t* data = node.data;
-    size_t i,j;
-    switch (data->type) {
-        case mpack_type_str:
-            {
-                mpack_print_append_cstr(print, "\"");
-                const char* bytes = mpack_node_data_unchecked(node);
-                for (i = 0; i < data->len; ++i) {
-                    char c = bytes[i];
-                    switch (c) {
-                        case '\n': mpack_print_append_cstr(print, "\\n"); break;
-                        case '\\': mpack_print_append_cstr(print, "\\\\"); break;
-                        case '"': mpack_print_append_cstr(print, "\\\""); break;
-                        default: mpack_print_append(print, &c, 1); break;
-                    }
-                }
-                mpack_print_append_cstr(print, "\"");
-            }
-            break;
-
-        case mpack_type_array:
-            mpack_print_append_cstr(print, "[\n");
-            for (i = 0; i < data->len; ++i) {
-                for (j = 0; j < depth + 1; ++j)
-                    mpack_print_append_cstr(print, "    ");
-                mpack_node_print_element(mpack_node_array_at(node, i), print, depth + 1);
-                if (i != data->len - 1)
-                    mpack_print_append_cstr(print, ",");
-                mpack_print_append_cstr(print, "\n");
-            }
-            for (i = 0; i < depth; ++i)
-                mpack_print_append_cstr(print, "    ");
-            mpack_print_append_cstr(print, "]");
-            break;
-
-        case mpack_type_map:
-            mpack_print_append_cstr(print, "{\n");
-            for (i = 0; i < data->len; ++i) {
-                for (j = 0; j < depth + 1; ++j)
-                    mpack_print_append_cstr(print, "    ");
-                mpack_node_print_element(mpack_node_map_key_at(node, i), print, depth + 1);
-                mpack_print_append_cstr(print, ": ");
-                mpack_node_print_element(mpack_node_map_value_at(node, i), print, depth + 1);
-                if (i != data->len - 1)
-                    mpack_print_append_cstr(print, ",");
-                mpack_print_append_cstr(print, "\n");
-            }
-            for (i = 0; i < depth; ++i)
-                mpack_print_append_cstr(print, "    ");
-            mpack_print_append_cstr(print, "}");
-            break;
-
-        default:
-            {
-                const char* prefix = NULL;
-                size_t prefix_length = 0;
-                if (mpack_node_type(node) == mpack_type_bin
-                        #if MPACK_EXTENSIONS
-                        || mpack_node_type(node) == mpack_type_ext
-                        #endif
-                ) {
-                    prefix = mpack_node_data(node);
-                    prefix_length = mpack_node_data_len(node);
-                }
-
-                char buf[256];
-                mpack_tag_t tag = mpack_node_tag(node);
-                mpack_tag_debug_pseudo_json(tag, buf, sizeof(buf), prefix, prefix_length);
-                mpack_print_append_cstr(print, buf);
-            }
-            break;
-    }
-}
-
-void mpack_node_print_to_buffer(mpack_node_t node, char* buffer, size_t buffer_size) {
-    if (buffer_size == 0) {
-        mpack_assert(false, "buffer size is zero!");
-        return;
-    }
-
-    mpack_print_t print;
-    mpack_memset(&print, 0, sizeof(print));
-    print.buffer = buffer;
-    print.size = buffer_size;
-    mpack_node_print_element(node, &print, 0);
-    mpack_print_append(&print, "",  1); // null-terminator
-    mpack_print_flush(&print);
-
-    // we always make sure there's a null-terminator at the end of the buffer
-    // in case we ran out of space.
-    print.buffer[print.size - 1] = '\0';
-}
-
-void mpack_node_print_to_callback(mpack_node_t node, mpack_print_callback_t callback, void* context) {
-    char buffer[1024];
-    mpack_print_t print;
-    mpack_memset(&print, 0, sizeof(print));
-    print.buffer = buffer;
-    print.size = sizeof(buffer);
-    print.callback = callback;
-    print.context = context;
-    mpack_node_print_element(node, &print, 0);
-    mpack_print_flush(&print);
-}
-
-void mpack_node_print_to_file(mpack_node_t node, FILE* file) {
-    mpack_assert(file != NULL, "file is NULL");
-
-    char buffer[1024];
-    mpack_print_t print;
-    mpack_memset(&print, 0, sizeof(print));
-    print.buffer = buffer;
-    print.size = sizeof(buffer);
-    print.callback = &mpack_print_file_callback;
-    print.context = file;
-
-    size_t depth = 2;
-    size_t i;
-    for (i = 0; i < depth; ++i)
-        mpack_print_append_cstr(&print, "    ");
-    mpack_node_print_element(node, &print, depth);
-    mpack_print_append_cstr(&print, "\n");
-    mpack_print_flush(&print);
-}
-#endif
-
-
-
-/*
- * Node Value Functions
- */
-
-#if MPACK_EXTENSIONS
-mpack_timestamp_t mpack_node_timestamp(mpack_node_t node) {
-    mpack_timestamp_t timestamp = {0, 0};
-
-    // we'll let mpack_node_exttype() do most checks
-    if (mpack_node_exttype(node) != MPACK_EXTTYPE_TIMESTAMP) {
-        mpack_log("exttype %i\n", mpack_node_exttype(node));
-        mpack_node_flag_error(node, mpack_error_type);
-        return timestamp;
-    }
-
-    const char* p = mpack_node_data_unchecked(node);
-
-    switch (node.data->len) {
-        case 4:
-            timestamp.nanoseconds = 0;
-            timestamp.seconds = mpack_load_u32(p);
-            break;
-
-        case 8: {
-            uint64_t value = mpack_load_u64(p);
-            timestamp.nanoseconds = (uint32_t)(value >> 34);
-            timestamp.seconds = value & ((MPACK_UINT64_C(1) << 34) - 1);
-            break;
-        }
-
-        case 12:
-            timestamp.nanoseconds = mpack_load_u32(p);
-            timestamp.seconds = mpack_load_i64(p + 4);
-            break;
-
-        default:
-            mpack_tree_flag_error(node.tree, mpack_error_invalid);
-            return timestamp;
-    }
-
-    if (timestamp.nanoseconds > MPACK_TIMESTAMP_NANOSECONDS_MAX) {
-        mpack_tree_flag_error(node.tree, mpack_error_invalid);
-        mpack_timestamp_t zero = {0, 0};
-        return zero;
-    }
-
-    return timestamp;
-}
-
-int64_t mpack_node_timestamp_seconds(mpack_node_t node) {
-    return mpack_node_timestamp(node).seconds;
-}
-
-uint32_t mpack_node_timestamp_nanoseconds(mpack_node_t node) {
-    return mpack_node_timestamp(node).nanoseconds;
-}
-#endif
-
-
-
-/*
- * Node Data Functions
- */
-
-void mpack_node_check_utf8(mpack_node_t node) {
-    if (mpack_node_error(node) != mpack_ok)
-        return;
-    mpack_node_data_t* data = node.data;
-    if (data->type != mpack_type_str || !mpack_utf8_check(mpack_node_data_unchecked(node), data->len))
-        mpack_node_flag_error(node, mpack_error_type);
-}
-
-void mpack_node_check_utf8_cstr(mpack_node_t node) {
-    if (mpack_node_error(node) != mpack_ok)
-        return;
-    mpack_node_data_t* data = node.data;
-    if (data->type != mpack_type_str || !mpack_utf8_check_no_null(mpack_node_data_unchecked(node), data->len))
-        mpack_node_flag_error(node, mpack_error_type);
-}
-
-size_t mpack_node_copy_data(mpack_node_t node, char* buffer, size_t bufsize) {
-    if (mpack_node_error(node) != mpack_ok)
-        return 0;
-
-    mpack_assert(bufsize == 0 || buffer != NULL, "buffer is NULL for maximum of %i bytes", (int)bufsize);
-
-    mpack_type_t type = node.data->type;
-    if (type != mpack_type_str && type != mpack_type_bin
-            #if MPACK_EXTENSIONS
-            && type != mpack_type_ext
-            #endif
-    ) {
-        mpack_node_flag_error(node, mpack_error_type);
-        return 0;
-    }
-
-    if (node.data->len > bufsize) {
-        mpack_node_flag_error(node, mpack_error_too_big);
-        return 0;
-    }
-
-    mpack_memcpy(buffer, mpack_node_data_unchecked(node), node.data->len);
-    return (size_t)node.data->len;
-}
-
-size_t mpack_node_copy_utf8(mpack_node_t node, char* buffer, size_t bufsize) {
-    if (mpack_node_error(node) != mpack_ok)
-        return 0;
-
-    mpack_assert(bufsize == 0 || buffer != NULL, "buffer is NULL for maximum of %i bytes", (int)bufsize);
-
-    mpack_type_t type = node.data->type;
-    if (type != mpack_type_str) {
-        mpack_node_flag_error(node, mpack_error_type);
-        return 0;
-    }
-
-    if (node.data->len > bufsize) {
-        mpack_node_flag_error(node, mpack_error_too_big);
-        return 0;
-    }
-
-    if (!mpack_utf8_check(mpack_node_data_unchecked(node), node.data->len)) {
-        mpack_node_flag_error(node, mpack_error_type);
-        return 0;
-    }
-
-    mpack_memcpy(buffer, mpack_node_data_unchecked(node), node.data->len);
-    return (size_t)node.data->len;
-}
-
-void mpack_node_copy_cstr(mpack_node_t node, char* buffer, size_t bufsize) {
-
-    // we can't break here because the error isn't recoverable; we
-    // have to add a null-terminator.
-    mpack_assert(buffer != NULL, "buffer is NULL");
-    mpack_assert(bufsize >= 1, "buffer size is zero; you must have room for at least a null-terminator");
-
-    if (mpack_node_error(node) != mpack_ok) {
-        buffer[0] = '\0';
-        return;
-    }
-
-    if (node.data->type != mpack_type_str) {
-        buffer[0] = '\0';
-        mpack_node_flag_error(node, mpack_error_type);
-        return;
-    }
-
-    if (node.data->len > bufsize - 1) {
-        buffer[0] = '\0';
-        mpack_node_flag_error(node, mpack_error_too_big);
-        return;
-    }
-
-    if (!mpack_str_check_no_null(mpack_node_data_unchecked(node), node.data->len)) {
-        buffer[0] = '\0';
-        mpack_node_flag_error(node, mpack_error_type);
-        return;
-    }
-
-    mpack_memcpy(buffer, mpack_node_data_unchecked(node), node.data->len);
-    buffer[node.data->len] = '\0';
-}
-
-void mpack_node_copy_utf8_cstr(mpack_node_t node, char* buffer, size_t bufsize) {
-
-    // we can't break here because the error isn't recoverable; we
-    // have to add a null-terminator.
-    mpack_assert(buffer != NULL, "buffer is NULL");
-    mpack_assert(bufsize >= 1, "buffer size is zero; you must have room for at least a null-terminator");
-
-    if (mpack_node_error(node) != mpack_ok) {
-        buffer[0] = '\0';
-        return;
-    }
-
-    if (node.data->type != mpack_type_str) {
-        buffer[0] = '\0';
-        mpack_node_flag_error(node, mpack_error_type);
-        return;
-    }
-
-    if (node.data->len > bufsize - 1) {
-        buffer[0] = '\0';
-        mpack_node_flag_error(node, mpack_error_too_big);
-        return;
-    }
-
-    if (!mpack_utf8_check_no_null(mpack_node_data_unchecked(node), node.data->len)) {
-        buffer[0] = '\0';
-        mpack_node_flag_error(node, mpack_error_type);
-        return;
-    }
-
-    mpack_memcpy(buffer, mpack_node_data_unchecked(node), node.data->len);
-    buffer[node.data->len] = '\0';
-}
-
-#ifdef MPACK_MALLOC
-char* mpack_node_data_alloc(mpack_node_t node, size_t maxlen) {
-    if (mpack_node_error(node) != mpack_ok)
-        return NULL;
-
-    // make sure this is a valid data type
-    mpack_type_t type = node.data->type;
-    if (type != mpack_type_str && type != mpack_type_bin
-            #if MPACK_EXTENSIONS
-            && type != mpack_type_ext
-            #endif
-    ) {
-        mpack_node_flag_error(node, mpack_error_type);
-        return NULL;
-    }
-
-    if (node.data->len > maxlen) {
-        mpack_node_flag_error(node, mpack_error_too_big);
-        return NULL;
-    }
-
-    char* ret = (char*) MPACK_MALLOC((size_t)node.data->len);
-    if (ret == NULL) {
-        mpack_node_flag_error(node, mpack_error_memory);
-        return NULL;
-    }
-
-    mpack_memcpy(ret, mpack_node_data_unchecked(node), node.data->len);
-    return ret;
-}
-
-char* mpack_node_cstr_alloc(mpack_node_t node, size_t maxlen) {
-    if (mpack_node_error(node) != mpack_ok)
-        return NULL;
-
-    // make sure maxlen makes sense
-    if (maxlen < 1) {
-        mpack_break("maxlen is zero; you must have room for at least a null-terminator");
-        mpack_node_flag_error(node, mpack_error_bug);
-        return NULL;
-    }
-
-    if (node.data->type != mpack_type_str) {
-        mpack_node_flag_error(node, mpack_error_type);
-        return NULL;
-    }
-
-    if (node.data->len > maxlen - 1) {
-        mpack_node_flag_error(node, mpack_error_too_big);
-        return NULL;
-    }
-
-    if (!mpack_str_check_no_null(mpack_node_data_unchecked(node), node.data->len)) {
-        mpack_node_flag_error(node, mpack_error_type);
-        return NULL;
-    }
-
-    char* ret = (char*) MPACK_MALLOC((size_t)(node.data->len + 1));
-    if (ret == NULL) {
-        mpack_node_flag_error(node, mpack_error_memory);
-        return NULL;
-    }
-
-    mpack_memcpy(ret, mpack_node_data_unchecked(node), node.data->len);
-    ret[node.data->len] = '\0';
-    return ret;
-}
-
-char* mpack_node_utf8_cstr_alloc(mpack_node_t node, size_t maxlen) {
-    if (mpack_node_error(node) != mpack_ok)
-        return NULL;
-
-    // make sure maxlen makes sense
-    if (maxlen < 1) {
-        mpack_break("maxlen is zero; you must have room for at least a null-terminator");
-        mpack_node_flag_error(node, mpack_error_bug);
-        return NULL;
-    }
-
-    if (node.data->type != mpack_type_str) {
-        mpack_node_flag_error(node, mpack_error_type);
-        return NULL;
-    }
-
-    if (node.data->len > maxlen - 1) {
-        mpack_node_flag_error(node, mpack_error_too_big);
-        return NULL;
-    }
-
-    if (!mpack_utf8_check_no_null(mpack_node_data_unchecked(node), node.data->len)) {
-        mpack_node_flag_error(node, mpack_error_type);
-        return NULL;
-    }
-
-    char* ret = (char*) MPACK_MALLOC((size_t)(node.data->len + 1));
-    if (ret == NULL) {
-        mpack_node_flag_error(node, mpack_error_memory);
-        return NULL;
-    }
-
-    mpack_memcpy(ret, mpack_node_data_unchecked(node), node.data->len);
-    ret[node.data->len] = '\0';
-    return ret;
-}
-#endif
-
-
-/*
- * Compound Node Functions
- */
-
-static mpack_node_data_t* mpack_node_map_int_impl(mpack_node_t node, int64_t num) {
-    if (mpack_node_error(node) != mpack_ok)
-        return NULL;
-
-    if (node.data->type != mpack_type_map) {
-        mpack_node_flag_error(node, mpack_error_type);
-        return NULL;
-    }
-
-    mpack_node_data_t* found = NULL;
-
-    size_t i;
-    for (i = 0; i < node.data->len; ++i) {
-        mpack_node_data_t* key = mpack_node_child(node, i * 2);
-
-        if ((key->type == mpack_type_int && key->value.i == num) ||
-            (key->type == mpack_type_uint && num >= 0 && key->value.u == (uint64_t)num))
-        {
-            if (found) {
-                mpack_node_flag_error(node, mpack_error_data);
-                return NULL;
-            }
-            found = mpack_node_child(node, i * 2 + 1);
-        }
-    }
-
-    if (found)
-        return found;
-
-    return NULL;
-}
-
-static mpack_node_data_t* mpack_node_map_uint_impl(mpack_node_t node, uint64_t num) {
-    if (mpack_node_error(node) != mpack_ok)
-        return NULL;
-
-    if (node.data->type != mpack_type_map) {
-        mpack_node_flag_error(node, mpack_error_type);
-        return NULL;
-    }
-
-    mpack_node_data_t* found = NULL;
-
-    size_t i;
-    for (i = 0; i < node.data->len; ++i) {
-        mpack_node_data_t* key = mpack_node_child(node, i * 2);
-
-        if ((key->type == mpack_type_uint && key->value.u == num) ||
-            (key->type == mpack_type_int && key->value.i >= 0 && (uint64_t)key->value.i == num))
-        {
-            if (found) {
-                mpack_node_flag_error(node, mpack_error_data);
-                return NULL;
-            }
-            found = mpack_node_child(node, i * 2 + 1);
-        }
-    }
-
-    if (found)
-        return found;
-
-    return NULL;
-}
-
-static mpack_node_data_t* mpack_node_map_str_impl(mpack_node_t node, const char* str, size_t length) {
-    if (mpack_node_error(node) != mpack_ok)
-        return NULL;
-
-    mpack_assert(length == 0 || str != NULL, "str of length %i is NULL", (int)length);
-
-    if (node.data->type != mpack_type_map) {
-        mpack_node_flag_error(node, mpack_error_type);
-        return NULL;
-    }
-
-    mpack_tree_t* tree = node.tree;
-    mpack_node_data_t* found = NULL;
-
-    size_t i;
-    for (i = 0; i < node.data->len; ++i) {
-        mpack_node_data_t* key = mpack_node_child(node, i * 2);
-
-        if (key->type == mpack_type_str && key->len == length &&
-                mpack_memcmp(str, mpack_node_data_unchecked(mpack_node(tree, key)), length) == 0) {
-            if (found) {
-                mpack_node_flag_error(node, mpack_error_data);
-                return NULL;
-            }
-            found = mpack_node_child(node, i * 2 + 1);
-        }
-    }
-
-    if (found)
-        return found;
-
-    return NULL;
-}
-
-static mpack_node_t mpack_node_wrap_lookup(mpack_tree_t* tree, mpack_node_data_t* data) {
-    if (!data) {
-        if (tree->error == mpack_ok)
-            mpack_tree_flag_error(tree, mpack_error_data);
-        return mpack_tree_nil_node(tree);
-    }
-    return mpack_node(tree, data);
-}
-
-static mpack_node_t mpack_node_wrap_lookup_optional(mpack_tree_t* tree, mpack_node_data_t* data) {
-    if (!data) {
-        if (tree->error == mpack_ok)
-            return mpack_tree_missing_node(tree);
-        return mpack_tree_nil_node(tree);
-    }
-    return mpack_node(tree, data);
-}
-
-mpack_node_t mpack_node_map_int(mpack_node_t node, int64_t num) {
-    return mpack_node_wrap_lookup(node.tree, mpack_node_map_int_impl(node, num));
-}
-
-mpack_node_t mpack_node_map_int_optional(mpack_node_t node, int64_t num) {
-    return mpack_node_wrap_lookup_optional(node.tree, mpack_node_map_int_impl(node, num));
-}
-
-mpack_node_t mpack_node_map_uint(mpack_node_t node, uint64_t num) {
-    return mpack_node_wrap_lookup(node.tree, mpack_node_map_uint_impl(node, num));
-}
-
-mpack_node_t mpack_node_map_uint_optional(mpack_node_t node, uint64_t num) {
-    return mpack_node_wrap_lookup_optional(node.tree, mpack_node_map_uint_impl(node, num));
-}
-
-mpack_node_t mpack_node_map_str(mpack_node_t node, const char* str, size_t length) {
-    return mpack_node_wrap_lookup(node.tree, mpack_node_map_str_impl(node, str, length));
-}
-
-mpack_node_t mpack_node_map_str_optional(mpack_node_t node, const char* str, size_t length) {
-    return mpack_node_wrap_lookup_optional(node.tree, mpack_node_map_str_impl(node, str, length));
-}
-
-mpack_node_t mpack_node_map_cstr(mpack_node_t node, const char* cstr) {
-    mpack_assert(cstr != NULL, "cstr is NULL");
-    return mpack_node_map_str(node, cstr, mpack_strlen(cstr));
-}
-
-mpack_node_t mpack_node_map_cstr_optional(mpack_node_t node, const char* cstr) {
-    mpack_assert(cstr != NULL, "cstr is NULL");
-    return mpack_node_map_str_optional(node, cstr, mpack_strlen(cstr));
-}
-
-bool mpack_node_map_contains_int(mpack_node_t node, int64_t num) {
-    return mpack_node_map_int_impl(node, num) != NULL;
-}
-
-bool mpack_node_map_contains_uint(mpack_node_t node, uint64_t num) {
-    return mpack_node_map_uint_impl(node, num) != NULL;
-}
-
-bool mpack_node_map_contains_str(mpack_node_t node, const char* str, size_t length) {
-    return mpack_node_map_str_impl(node, str, length) != NULL;
-}
-
-bool mpack_node_map_contains_cstr(mpack_node_t node, const char* cstr) {
-    mpack_assert(cstr != NULL, "cstr is NULL");
-    return mpack_node_map_contains_str(node, cstr, mpack_strlen(cstr));
-}
-
-size_t mpack_node_enum_optional(mpack_node_t node, const char* strings[], size_t count) {
-    if (mpack_node_error(node) != mpack_ok)
-        return count;
-
-    // the value is only recognized if it is a string
-    if (mpack_node_type(node) != mpack_type_str)
-        return count;
-
-    // fetch the string
-    const char* key = mpack_node_str(node);
-    size_t keylen = mpack_node_strlen(node);
-    mpack_assert(mpack_node_error(node) == mpack_ok, "these should not fail");
-
-    // find what key it matches
-    size_t i;
-    for (i = 0; i < count; ++i) {
-        const char* other = strings[i];
-        size_t otherlen = mpack_strlen(other);
-        if (keylen == otherlen && mpack_memcmp(key, other, keylen) == 0)
-            return i;
-    }
-
-    // no matches
-    return count;
-}
-
-size_t mpack_node_enum(mpack_node_t node, const char* strings[], size_t count) {
-    size_t value = mpack_node_enum_optional(node, strings, count);
-    if (value == count)
-        mpack_node_flag_error(node, mpack_error_type);
-    return value;
-}
-
-mpack_type_t mpack_node_type(mpack_node_t node) {
-    if (mpack_node_error(node) != mpack_ok)
-        return mpack_type_nil;
-    return node.data->type;
-}
-
-bool mpack_node_is_nil(mpack_node_t node) {
-    if (mpack_node_error(node) != mpack_ok) {
-        // All nodes are treated as nil nodes when we are in error.
-        return true;
-    }
-    return node.data->type == mpack_type_nil;
-}
-
-bool mpack_node_is_missing(mpack_node_t node) {
-    if (mpack_node_error(node) != mpack_ok) {
-        // errors still return nil nodes, not missing nodes.
-        return false;
-    }
-    return node.data->type == mpack_type_missing;
-}
-
-void mpack_node_nil(mpack_node_t node) {
-    if (mpack_node_error(node) != mpack_ok)
-        return;
-    if (node.data->type != mpack_type_nil)
-        mpack_node_flag_error(node, mpack_error_type);
-}
-
-void mpack_node_missing(mpack_node_t node) {
-    if (mpack_node_error(node) != mpack_ok)
-        return;
-    if (node.data->type != mpack_type_missing)
-        mpack_node_flag_error(node, mpack_error_type);
-}
-
-bool mpack_node_bool(mpack_node_t node) {
-    if (mpack_node_error(node) != mpack_ok)
-        return false;
-
-    if (node.data->type == mpack_type_bool)
-        return node.data->value.b;
-
-    mpack_node_flag_error(node, mpack_error_type);
-    return false;
-}
-
-void mpack_node_true(mpack_node_t node) {
-    if (mpack_node_bool(node) != true)
-        mpack_node_flag_error(node, mpack_error_type);
-}
-
-void mpack_node_false(mpack_node_t node) {
-    if (mpack_node_bool(node) != false)
-        mpack_node_flag_error(node, mpack_error_type);
-}
-
-uint8_t mpack_node_u8(mpack_node_t node) {
-    if (mpack_node_error(node) != mpack_ok)
-        return 0;
-
-    if (node.data->type == mpack_type_uint) {
-        if (node.data->value.u <= MPACK_UINT8_MAX)
-            return (uint8_t)node.data->value.u;
-    } else if (node.data->type == mpack_type_int) {
-        if (node.data->value.i >= 0 && node.data->value.i <= MPACK_UINT8_MAX)
-            return (uint8_t)node.data->value.i;
-    }
-
-    mpack_node_flag_error(node, mpack_error_type);
-    return 0;
-}
-
-int8_t mpack_node_i8(mpack_node_t node) {
-    if (mpack_node_error(node) != mpack_ok)
-        return 0;
-
-    if (node.data->type == mpack_type_uint) {
-        if (node.data->value.u <= MPACK_INT8_MAX)
-            return (int8_t)node.data->value.u;
-    } else if (node.data->type == mpack_type_int) {
-        if (node.data->value.i >= MPACK_INT8_MIN && node.data->value.i <= MPACK_INT8_MAX)
-            return (int8_t)node.data->value.i;
-    }
-
-    mpack_node_flag_error(node, mpack_error_type);
-    return 0;
-}
-
-uint16_t mpack_node_u16(mpack_node_t node) {
-    if (mpack_node_error(node) != mpack_ok)
-        return 0;
-
-    if (node.data->type == mpack_type_uint) {
-        if (node.data->value.u <= MPACK_UINT16_MAX)
-            return (uint16_t)node.data->value.u;
-    } else if (node.data->type == mpack_type_int) {
-        if (node.data->value.i >= 0 && node.data->value.i <= MPACK_UINT16_MAX)
-            return (uint16_t)node.data->value.i;
-    }
-
-    mpack_node_flag_error(node, mpack_error_type);
-    return 0;
-}
-
-int16_t mpack_node_i16(mpack_node_t node) {
-    if (mpack_node_error(node) != mpack_ok)
-        return 0;
-
-    if (node.data->type == mpack_type_uint) {
-        if (node.data->value.u <= MPACK_INT16_MAX)
-            return (int16_t)node.data->value.u;
-    } else if (node.data->type == mpack_type_int) {
-        if (node.data->value.i >= MPACK_INT16_MIN && node.data->value.i <= MPACK_INT16_MAX)
-            return (int16_t)node.data->value.i;
-    }
-
-    mpack_node_flag_error(node, mpack_error_type);
-    return 0;
-}
-
-uint32_t mpack_node_u32(mpack_node_t node) {
-    if (mpack_node_error(node) != mpack_ok)
-        return 0;
-
-    if (node.data->type == mpack_type_uint) {
-        if (node.data->value.u <= MPACK_UINT32_MAX)
-            return (uint32_t)node.data->value.u;
-    } else if (node.data->type == mpack_type_int) {
-        if (node.data->value.i >= 0 && node.data->value.i <= MPACK_UINT32_MAX)
-            return (uint32_t)node.data->value.i;
-    }
-
-    mpack_node_flag_error(node, mpack_error_type);
-    return 0;
-}
-
-int32_t mpack_node_i32(mpack_node_t node) {
-    if (mpack_node_error(node) != mpack_ok)
-        return 0;
-
-    if (node.data->type == mpack_type_uint) {
-        if (node.data->value.u <= MPACK_INT32_MAX)
-            return (int32_t)node.data->value.u;
-    } else if (node.data->type == mpack_type_int) {
-        if (node.data->value.i >= MPACK_INT32_MIN && node.data->value.i <= MPACK_INT32_MAX)
-            return (int32_t)node.data->value.i;
-    }
-
-    mpack_node_flag_error(node, mpack_error_type);
-    return 0;
-}
-
-uint64_t mpack_node_u64(mpack_node_t node) {
-    if (mpack_node_error(node) != mpack_ok)
-        return 0;
-
-    if (node.data->type == mpack_type_uint) {
-        return node.data->value.u;
-    } else if (node.data->type == mpack_type_int) {
-        if (node.data->value.i >= 0)
-            return (uint64_t)node.data->value.i;
-    }
-
-    mpack_node_flag_error(node, mpack_error_type);
-    return 0;
-}
-
-int64_t mpack_node_i64(mpack_node_t node) {
-    if (mpack_node_error(node) != mpack_ok)
-        return 0;
-
-    if (node.data->type == mpack_type_uint) {
-        if (node.data->value.u <= (uint64_t)MPACK_INT64_MAX)
-            return (int64_t)node.data->value.u;
-    } else if (node.data->type == mpack_type_int) {
-        return node.data->value.i;
-    }
-
-    mpack_node_flag_error(node, mpack_error_type);
-    return 0;
-}
-
-unsigned int mpack_node_uint(mpack_node_t node) {
-
-    // This should be true at compile-time, so this just wraps the 32-bit function.
-    if (sizeof(unsigned int) == 4)
-        return (unsigned int)mpack_node_u32(node);
-
-    // Otherwise we use u64 and check the range.
-    uint64_t val = mpack_node_u64(node);
-    if (val <= MPACK_UINT_MAX)
-        return (unsigned int)val;
-
-    mpack_node_flag_error(node, mpack_error_type);
-    return 0;
-}
-
-int mpack_node_int(mpack_node_t node) {
-
-    // This should be true at compile-time, so this just wraps the 32-bit function.
-    if (sizeof(int) == 4)
-        return (int)mpack_node_i32(node);
-
-    // Otherwise we use i64 and check the range.
-    int64_t val = mpack_node_i64(node);
-    if (val >= MPACK_INT_MIN && val <= MPACK_INT_MAX)
-        return (int)val;
-
-    mpack_node_flag_error(node, mpack_error_type);
-    return 0;
-}
-
-#if MPACK_FLOAT
-float mpack_node_float(mpack_node_t node) {
-    if (mpack_node_error(node) != mpack_ok)
-        return 0.0f;
-
-    if (node.data->type == mpack_type_uint)
-        return (float)node.data->value.u;
-    if (node.data->type == mpack_type_int)
-        return (float)node.data->value.i;
-    if (node.data->type == mpack_type_float)
-        return node.data->value.f;
-
-    if (node.data->type == mpack_type_double) {
-        #if MPACK_DOUBLE
-        return (float)node.data->value.d;
-        #else
-        return mpack_shorten_raw_double_to_float(node.data->value.d);
-        #endif
-    }
-
-    mpack_node_flag_error(node, mpack_error_type);
-    return 0.0f;
-}
-#endif
-
-#if MPACK_DOUBLE
-double mpack_node_double(mpack_node_t node) {
-    if (mpack_node_error(node) != mpack_ok)
-        return 0.0;
-
-    if (node.data->type == mpack_type_uint)
-        return (double)node.data->value.u;
-    else if (node.data->type == mpack_type_int)
-        return (double)node.data->value.i;
-    else if (node.data->type == mpack_type_float)
-        return (double)node.data->value.f;
-    else if (node.data->type == mpack_type_double)
-        return node.data->value.d;
-
-    mpack_node_flag_error(node, mpack_error_type);
-    return 0.0;
-}
-#endif
-
-#if MPACK_FLOAT
-float mpack_node_float_strict(mpack_node_t node) {
-    if (mpack_node_error(node) != mpack_ok)
-        return 0.0f;
-
-    if (node.data->type == mpack_type_float)
-        return node.data->value.f;
-
-    mpack_node_flag_error(node, mpack_error_type);
-    return 0.0f;
-}
-#endif
-
-#if MPACK_DOUBLE
-double mpack_node_double_strict(mpack_node_t node) {
-    if (mpack_node_error(node) != mpack_ok)
-        return 0.0;
-
-    if (node.data->type == mpack_type_float)
-        return (double)node.data->value.f;
-    else if (node.data->type == mpack_type_double)
-        return node.data->value.d;
-
-    mpack_node_flag_error(node, mpack_error_type);
-    return 0.0;
-}
-#endif
-
-#if !MPACK_FLOAT
-uint32_t mpack_node_raw_float(mpack_node_t node) {
-    if (mpack_node_error(node) != mpack_ok)
-        return 0;
-
-    if (node.data->type == mpack_type_float)
-        return node.data->value.f;
-
-    mpack_node_flag_error(node, mpack_error_type);
-    return 0;
-}
-#endif
-
-#if !MPACK_DOUBLE
-uint64_t mpack_node_raw_double(mpack_node_t node) {
-    if (mpack_node_error(node) != mpack_ok)
-        return 0;
-
-    if (node.data->type == mpack_type_double)
-        return node.data->value.d;
-
-    mpack_node_flag_error(node, mpack_error_type);
-    return 0;
-}
-#endif
-
-#if MPACK_EXTENSIONS
-int8_t mpack_node_exttype(mpack_node_t node) {
-    if (mpack_node_error(node) != mpack_ok)
-        return 0;
-
-    if (node.data->type == mpack_type_ext)
-        return mpack_node_exttype_unchecked(node);
-
-    mpack_node_flag_error(node, mpack_error_type);
-    return 0;
-}
-#endif
-
-uint32_t mpack_node_data_len(mpack_node_t node) {
-    if (mpack_node_error(node) != mpack_ok)
-        return 0;
-
-    mpack_type_t type = node.data->type;
-    if (type == mpack_type_str || type == mpack_type_bin
-            #if MPACK_EXTENSIONS
-            || type == mpack_type_ext
-            #endif
-            )
-        return (uint32_t)node.data->len;
-
-    mpack_node_flag_error(node, mpack_error_type);
-    return 0;
-}
-
-size_t mpack_node_strlen(mpack_node_t node) {
-    if (mpack_node_error(node) != mpack_ok)
-        return 0;
-
-    if (node.data->type == mpack_type_str)
-        return (size_t)node.data->len;
-
-    mpack_node_flag_error(node, mpack_error_type);
-    return 0;
-}
-
-const char* mpack_node_str(mpack_node_t node) {
-    if (mpack_node_error(node) != mpack_ok)
-        return NULL;
-
-    mpack_type_t type = node.data->type;
-    if (type == mpack_type_str)
-        return mpack_node_data_unchecked(node);
-
-    mpack_node_flag_error(node, mpack_error_type);
-    return NULL;
-}
-
-const char* mpack_node_data(mpack_node_t node) {
-    if (mpack_node_error(node) != mpack_ok)
-        return NULL;
-
-    mpack_type_t type = node.data->type;
-    if (type == mpack_type_str || type == mpack_type_bin
-            #if MPACK_EXTENSIONS
-            || type == mpack_type_ext
-            #endif
-            )
-        return mpack_node_data_unchecked(node);
-
-    mpack_node_flag_error(node, mpack_error_type);
-    return NULL;
-}
-
-const char* mpack_node_bin_data(mpack_node_t node) {
-    if (mpack_node_error(node) != mpack_ok)
-        return NULL;
-
-    if (node.data->type == mpack_type_bin)
-        return mpack_node_data_unchecked(node);
-
-    mpack_node_flag_error(node, mpack_error_type);
-    return NULL;
-}
-
-size_t mpack_node_bin_size(mpack_node_t node) {
-    if (mpack_node_error(node) != mpack_ok)
-        return 0;
-
-    if (node.data->type == mpack_type_bin)
-        return (size_t)node.data->len;
-
-    mpack_node_flag_error(node, mpack_error_type);
-    return 0;
-}
-
-size_t mpack_node_array_length(mpack_node_t node) {
-    if (mpack_node_error(node) != mpack_ok)
-        return 0;
-
-    if (node.data->type != mpack_type_array) {
-        mpack_node_flag_error(node, mpack_error_type);
-        return 0;
-    }
-
-    return (size_t)node.data->len;
-}
-
-mpack_node_t mpack_node_array_at(mpack_node_t node, size_t index) {
-    if (mpack_node_error(node) != mpack_ok)
-        return mpack_tree_nil_node(node.tree);
-
-    if (node.data->type != mpack_type_array) {
-        mpack_node_flag_error(node, mpack_error_type);
-        return mpack_tree_nil_node(node.tree);
-    }
-
-    if (index >= node.data->len) {
-        mpack_node_flag_error(node, mpack_error_data);
-        return mpack_tree_nil_node(node.tree);
-    }
-
-    return mpack_node(node.tree, mpack_node_child(node, index));
-}
-
-size_t mpack_node_map_count(mpack_node_t node) {
-    if (mpack_node_error(node) != mpack_ok)
-        return 0;
-
-    if (node.data->type != mpack_type_map) {
-        mpack_node_flag_error(node, mpack_error_type);
-        return 0;
-    }
-
-    return node.data->len;
-}
-
-// internal node map lookup
-static mpack_node_t mpack_node_map_at(mpack_node_t node, size_t index, size_t offset) {
-    if (mpack_node_error(node) != mpack_ok)
-        return mpack_tree_nil_node(node.tree);
-
-    if (node.data->type != mpack_type_map) {
-        mpack_node_flag_error(node, mpack_error_type);
-        return mpack_tree_nil_node(node.tree);
-    }
-
-    if (index >= node.data->len) {
-        mpack_node_flag_error(node, mpack_error_data);
-        return mpack_tree_nil_node(node.tree);
-    }
-
-    return mpack_node(node.tree, mpack_node_child(node, index * 2 + offset));
-}
-
-mpack_node_t mpack_node_map_key_at(mpack_node_t node, size_t index) {
-    return mpack_node_map_at(node, index, 0);
-}
-
-mpack_node_t mpack_node_map_value_at(mpack_node_t node, size_t index) {
-    return mpack_node_map_at(node, index, 1);
-}
-
-#endif
-
-}  // namespace wpi
-MPACK_SILENCE_WARNINGS_END
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/raw_socket_istream.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/raw_socket_istream.cpp
deleted file mode 100644
index c6b759e..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/raw_socket_istream.cpp
+++ /dev/null
@@ -1,33 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/raw_socket_istream.h"
-
-#include "wpi/NetworkStream.h"
-
-using namespace wpi;
-
-void raw_socket_istream::read_impl(void* data, size_t len) {
-  char* cdata = static_cast<char*>(data);
-  size_t pos = 0;
-
-  while (pos < len) {
-    NetworkStream::Error err;
-    size_t count = m_stream.receive(&cdata[pos], len - pos, &err, m_timeout);
-    if (count == 0) {
-      error_detected();
-      break;
-    }
-    pos += count;
-  }
-  set_read_count(pos);
-}
-
-void raw_socket_istream::close() {
-  m_stream.close();
-}
-
-size_t raw_socket_istream::in_avail() const {
-  return 0;
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/raw_socket_ostream.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/raw_socket_ostream.cpp
deleted file mode 100644
index af01c84..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/raw_socket_ostream.cpp
+++ /dev/null
@@ -1,42 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/raw_socket_ostream.h"
-
-#include "wpi/NetworkStream.h"
-
-using namespace wpi;
-
-raw_socket_ostream::~raw_socket_ostream() {
-  flush();
-  if (m_shouldClose) {
-    close();
-  }
-}
-
-void raw_socket_ostream::write_impl(const char* data, size_t len) {
-  size_t pos = 0;
-
-  while (pos < len) {
-    NetworkStream::Error err;
-    size_t count = m_stream.send(&data[pos], len - pos, &err);
-    if (count == 0) {
-      error_detected();
-      return;
-    }
-    pos += count;
-  }
-}
-
-uint64_t raw_socket_ostream::current_pos() const {
-  return 0;
-}
-
-void raw_socket_ostream::close() {
-  if (!m_shouldClose) {
-    return;
-  }
-  flush();
-  m_stream.close();
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/raw_uv_ostream.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/raw_uv_ostream.cpp
deleted file mode 100644
index f055a2a..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/raw_uv_ostream.cpp
+++ /dev/null
@@ -1,39 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/raw_uv_ostream.h"
-
-#include <cstring>
-
-using namespace wpi;
-
-void raw_uv_ostream::write_impl(const char* data, size_t len) {
-  while (len > 0) {
-    // allocate additional buffers as required
-    if (m_left == 0) {
-      m_bufs.emplace_back(m_alloc());
-      // we want bufs() to always be valid, so set len=0 and keep track of the
-      // amount of space remaining separately
-      m_left = m_bufs.back().len;
-      m_bufs.back().len = 0;
-      assert(m_left != 0);
-    }
-
-    size_t amt = (std::min)(m_left, len);
-    auto& buf = m_bufs.back();
-    std::memcpy(buf.base + buf.len, data, amt);
-    data += amt;
-    len -= amt;
-    buf.len += amt;
-    m_left -= amt;
-  }
-}
-
-uint64_t raw_uv_ostream::current_pos() const {
-  uint64_t size = 0;
-  for (auto&& buf : m_bufs) {
-    size += buf.len;
-  }
-  return size;
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/sha1.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/sha1.cpp
index 8ec7cb1..98dc543 100644
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/sha1.cpp
+++ b/third_party/allwpilib/wpiutil/src/main/native/cpp/sha1.cpp
@@ -217,7 +217,7 @@
 }
 
 void SHA1::Update(std::string_view s) {
-  raw_mem_istream is(span<const char>(s.data(), s.size()));
+  raw_mem_istream is(std::span<const char>(s.data(), s.size()));
   Update(is);
 }
 
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Async.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Async.cpp
deleted file mode 100644
index c9d698e..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Async.cpp
+++ /dev/null
@@ -1,33 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/uv/Async.h"
-
-#include "wpi/uv/Loop.h"
-
-namespace wpi::uv {
-
-Async<>::~Async() noexcept {
-  if (auto loop = m_loop.lock()) {
-    Close();
-  } else {
-    ForceClosed();
-  }
-}
-
-std::shared_ptr<Async<>> Async<>::Create(const std::shared_ptr<Loop>& loop) {
-  auto h = std::make_shared<Async>(loop, private_init{});
-  int err = uv_async_init(loop->GetRaw(), h->GetRaw(), [](uv_async_t* handle) {
-    Async& h = *static_cast<Async*>(handle->data);
-    h.wakeup();
-  });
-  if (err < 0) {
-    loop->ReportError(err);
-    return nullptr;
-  }
-  h->Keep();
-  return h;
-}
-
-}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Check.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Check.cpp
deleted file mode 100644
index 97265d4..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Check.cpp
+++ /dev/null
@@ -1,29 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/uv/Check.h"
-
-#include "wpi/uv/Loop.h"
-
-namespace wpi::uv {
-
-std::shared_ptr<Check> Check::Create(Loop& loop) {
-  auto h = std::make_shared<Check>(private_init{});
-  int err = uv_check_init(loop.GetRaw(), h->GetRaw());
-  if (err < 0) {
-    loop.ReportError(err);
-    return nullptr;
-  }
-  h->Keep();
-  return h;
-}
-
-void Check::Start() {
-  Invoke(&uv_check_start, GetRaw(), [](uv_check_t* handle) {
-    Check& h = *static_cast<Check*>(handle->data);
-    h.check();
-  });
-}
-
-}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/FsEvent.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/FsEvent.cpp
deleted file mode 100644
index 3c83d1d..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/FsEvent.cpp
+++ /dev/null
@@ -1,63 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/uv/FsEvent.h"
-
-#include <cstdlib>
-
-#include "wpi/SmallString.h"
-#include "wpi/uv/Loop.h"
-
-namespace wpi::uv {
-
-std::shared_ptr<FsEvent> FsEvent::Create(Loop& loop) {
-  auto h = std::make_shared<FsEvent>(private_init{});
-  int err = uv_fs_event_init(loop.GetRaw(), h->GetRaw());
-  if (err < 0) {
-    loop.ReportError(err);
-    return nullptr;
-  }
-  h->Keep();
-  return h;
-}
-
-void FsEvent::Start(std::string_view path, unsigned int flags) {
-  SmallString<128> pathBuf{path};
-  Invoke(
-      &uv_fs_event_start, GetRaw(),
-      [](uv_fs_event_t* handle, const char* filename, int events, int status) {
-        FsEvent& h = *static_cast<FsEvent*>(handle->data);
-        if (status < 0) {
-          h.ReportError(status);
-        } else {
-          h.fsEvent(filename, events);
-        }
-      },
-      pathBuf.c_str(), flags);
-}
-
-std::string FsEvent::GetPath() {
-  // Per the libuv docs, GetPath() always gives us a null-terminated string.
-  // common case should be small
-  char buf[128];
-  size_t size = 128;
-  int r = uv_fs_event_getpath(GetRaw(), buf, &size);
-  if (r == 0) {
-    return buf;
-  } else if (r == UV_ENOBUFS) {
-    // need to allocate a big enough buffer
-    char* buf2 = static_cast<char*>(std::malloc(size));
-    r = uv_fs_event_getpath(GetRaw(), buf2, &size);
-    if (r == 0) {
-      std::string out{buf2};
-      std::free(buf2);
-      return out;
-    }
-    std::free(buf2);
-  }
-  ReportError(r);
-  return std::string{};
-}
-
-}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/GetAddrInfo.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/GetAddrInfo.cpp
deleted file mode 100644
index 2e6e38f..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/GetAddrInfo.cpp
+++ /dev/null
@@ -1,51 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/uv/GetAddrInfo.h"
-
-#include "wpi/SmallString.h"
-#include "wpi/uv/Loop.h"
-#include "wpi/uv/util.h"
-
-namespace wpi::uv {
-
-GetAddrInfoReq::GetAddrInfoReq() {
-  error = [this](Error err) { GetLoop().error(err); };
-}
-
-void GetAddrInfo(Loop& loop, const std::shared_ptr<GetAddrInfoReq>& req,
-                 std::string_view node, std::string_view service,
-                 const addrinfo* hints) {
-  SmallString<128> nodeStr{node};
-  SmallString<128> serviceStr{service};
-  int err = uv_getaddrinfo(
-      loop.GetRaw(), req->GetRaw(),
-      [](uv_getaddrinfo_t* req, int status, addrinfo* res) {
-        auto& h = *static_cast<GetAddrInfoReq*>(req->data);
-        if (status < 0) {
-          h.ReportError(status);
-        } else {
-          h.resolved(*res);
-        }
-        uv_freeaddrinfo(res);
-        h.Release();  // this is always a one-shot
-      },
-      node.empty() ? nullptr : nodeStr.c_str(),
-      service.empty() ? nullptr : serviceStr.c_str(), hints);
-  if (err < 0) {
-    loop.ReportError(err);
-  } else {
-    req->Keep();
-  }
-}
-
-void GetAddrInfo(Loop& loop, std::function<void(const addrinfo&)> callback,
-                 std::string_view node, std::string_view service,
-                 const addrinfo* hints) {
-  auto req = std::make_shared<GetAddrInfoReq>();
-  req->resolved.connect(std::move(callback));
-  GetAddrInfo(loop, req, node, service, hints);
-}
-
-}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/GetNameInfo.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/GetNameInfo.cpp
deleted file mode 100644
index 4e662f3..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/GetNameInfo.cpp
+++ /dev/null
@@ -1,94 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/uv/GetNameInfo.h"
-
-#include "wpi/uv/Loop.h"
-#include "wpi/uv/util.h"
-
-namespace wpi::uv {
-
-GetNameInfoReq::GetNameInfoReq() {
-  error = [this](Error err) { GetLoop().error(err); };
-}
-
-void GetNameInfo(Loop& loop, const std::shared_ptr<GetNameInfoReq>& req,
-                 const sockaddr& addr, int flags) {
-  int err = uv_getnameinfo(
-      loop.GetRaw(), req->GetRaw(),
-      [](uv_getnameinfo_t* req, int status, const char* hostname,
-         const char* service) {
-        auto& h = *static_cast<GetNameInfoReq*>(req->data);
-        if (status < 0) {
-          h.ReportError(status);
-        } else {
-          h.resolved(hostname, service);
-        }
-        h.Release();  // this is always a one-shot
-      },
-      &addr, flags);
-  if (err < 0) {
-    loop.ReportError(err);
-  } else {
-    req->Keep();
-  }
-}
-
-void GetNameInfo(Loop& loop,
-                 std::function<void(const char*, const char*)> callback,
-                 const sockaddr& addr, int flags) {
-  auto req = std::make_shared<GetNameInfoReq>();
-  req->resolved.connect(std::move(callback));
-  GetNameInfo(loop, req, addr, flags);
-}
-
-void GetNameInfo4(Loop& loop, const std::shared_ptr<GetNameInfoReq>& req,
-                  std::string_view ip, unsigned int port, int flags) {
-  sockaddr_in addr;
-  int err = NameToAddr(ip, port, &addr);
-  if (err < 0) {
-    loop.ReportError(err);
-  } else {
-    GetNameInfo(loop, req, reinterpret_cast<const sockaddr&>(addr), flags);
-  }
-}
-
-void GetNameInfo4(Loop& loop,
-                  std::function<void(const char*, const char*)> callback,
-                  std::string_view ip, unsigned int port, int flags) {
-  sockaddr_in addr;
-  int err = NameToAddr(ip, port, &addr);
-  if (err < 0) {
-    loop.ReportError(err);
-  } else {
-    GetNameInfo(loop, std::move(callback),
-                reinterpret_cast<const sockaddr&>(addr), flags);
-  }
-}
-
-void GetNameInfo6(Loop& loop, const std::shared_ptr<GetNameInfoReq>& req,
-                  std::string_view ip, unsigned int port, int flags) {
-  sockaddr_in6 addr;
-  int err = NameToAddr(ip, port, &addr);
-  if (err < 0) {
-    loop.ReportError(err);
-  } else {
-    GetNameInfo(loop, req, reinterpret_cast<const sockaddr&>(addr), flags);
-  }
-}
-
-void GetNameInfo6(Loop& loop,
-                  std::function<void(const char*, const char*)> callback,
-                  std::string_view ip, unsigned int port, int flags) {
-  sockaddr_in6 addr;
-  int err = NameToAddr(ip, port, &addr);
-  if (err < 0) {
-    loop.ReportError(err);
-  } else {
-    GetNameInfo(loop, std::move(callback),
-                reinterpret_cast<const sockaddr&>(addr), flags);
-  }
-}
-
-}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Handle.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Handle.cpp
deleted file mode 100644
index 74c4c60..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Handle.cpp
+++ /dev/null
@@ -1,35 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/uv/Handle.h"
-
-using namespace wpi::uv;
-
-Handle::~Handle() noexcept {
-  if (!m_closed && m_uv_handle->type != UV_UNKNOWN_HANDLE) {
-    uv_close(m_uv_handle, [](uv_handle_t* uv_handle) { std::free(uv_handle); });
-  } else {
-    std::free(m_uv_handle);
-  }
-}
-
-void Handle::Close() noexcept {
-  if (!IsClosing()) {
-    uv_close(m_uv_handle, [](uv_handle_t* handle) {
-      Handle& h = *static_cast<Handle*>(handle->data);
-      h.closed();
-      h.Release();  // free ourselves
-    });
-    m_closed = true;
-  }
-}
-
-void Handle::AllocBuf(uv_handle_t* handle, size_t size, uv_buf_t* buf) {
-  auto& h = *static_cast<Handle*>(handle->data);
-  *buf = h.m_allocBuf(size);
-}
-
-void Handle::DefaultFreeBuf(Buffer& buf) {
-  buf.Deallocate();
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Idle.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Idle.cpp
deleted file mode 100644
index 6bf8602..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Idle.cpp
+++ /dev/null
@@ -1,29 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/uv/Idle.h"
-
-#include "wpi/uv/Loop.h"
-
-namespace wpi::uv {
-
-std::shared_ptr<Idle> Idle::Create(Loop& loop) {
-  auto h = std::make_shared<Idle>(private_init{});
-  int err = uv_idle_init(loop.GetRaw(), h->GetRaw());
-  if (err < 0) {
-    loop.ReportError(err);
-    return nullptr;
-  }
-  h->Keep();
-  return h;
-}
-
-void Idle::Start() {
-  Invoke(&uv_idle_start, GetRaw(), [](uv_idle_t* handle) {
-    Idle& h = *static_cast<Idle*>(handle->data);
-    h.idle();
-  });
-}
-
-}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Loop.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Loop.cpp
deleted file mode 100644
index c5b7163..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Loop.cpp
+++ /dev/null
@@ -1,70 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/uv/Loop.h"
-
-using namespace wpi::uv;
-
-Loop::Loop(const private_init&) noexcept {
-#ifndef _WIN32
-  // Ignore SIGPIPE (see https://github.com/joyent/libuv/issues/1254)
-  static bool once = []() {
-    signal(SIGPIPE, SIG_IGN);
-    return true;
-  }();
-  (void)once;
-#endif
-}
-
-Loop::~Loop() noexcept {
-  if (m_loop) {
-    m_loop->data = nullptr;
-    Close();
-  }
-}
-
-std::shared_ptr<Loop> Loop::Create() {
-  auto loop = std::make_shared<Loop>(private_init{});
-  if (uv_loop_init(&loop->m_loopStruct) < 0) {
-    return nullptr;
-  }
-  loop->m_loop = &loop->m_loopStruct;
-  loop->m_loop->data = loop.get();
-  return loop;
-}
-
-std::shared_ptr<Loop> Loop::GetDefault() {
-  static std::shared_ptr<Loop> loop = std::make_shared<Loop>(private_init{});
-  loop->m_loop = uv_default_loop();
-  if (!loop->m_loop) {
-    return nullptr;
-  }
-  loop->m_loop->data = loop.get();
-  return loop;
-}
-
-void Loop::Close() {
-  int err = uv_loop_close(m_loop);
-  if (err < 0) {
-    ReportError(err);
-  }
-}
-
-void Loop::Walk(function_ref<void(Handle&)> callback) {
-  uv_walk(
-      m_loop,
-      [](uv_handle_t* handle, void* func) {
-        auto& h = *static_cast<Handle*>(handle->data);
-        auto& f = *static_cast<function_ref<void(Handle&)>*>(func);
-        f(h);
-      },
-      &callback);
-}
-
-void Loop::Fork() {
-  int err = uv_loop_fork(m_loop);
-  if (err < 0) {
-    ReportError(err);
-  }
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/NameToAddr.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/NameToAddr.cpp
deleted file mode 100644
index 23ec6da..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/NameToAddr.cpp
+++ /dev/null
@@ -1,59 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/uv/util.h"  // NOLINT(build/include_order)
-
-#include <cstring>
-
-#include "wpi/SmallString.h"
-
-namespace wpi::uv {
-
-int NameToAddr(std::string_view ip, unsigned int port, sockaddr_in* addr) {
-  if (ip.empty()) {
-    std::memset(addr, 0, sizeof(sockaddr_in));
-    addr->sin_family = PF_INET;
-    addr->sin_addr.s_addr = INADDR_ANY;
-    addr->sin_port = htons(port);
-    return 0;
-  } else {
-    SmallString<128> ipBuf{ip};
-    return uv_ip4_addr(ipBuf.c_str(), port, addr);
-  }
-}
-
-int NameToAddr(std::string_view ip, unsigned int port, sockaddr_in6* addr) {
-  if (ip.empty()) {
-    std::memset(addr, 0, sizeof(sockaddr_in6));
-    addr->sin6_family = PF_INET6;
-    addr->sin6_addr = in6addr_any;
-    addr->sin6_port = htons(port);
-    return 0;
-  } else {
-    SmallString<128> ipBuf{ip};
-    return uv_ip6_addr(ipBuf.c_str(), port, addr);
-  }
-}
-
-int NameToAddr(std::string_view ip, in_addr* addr) {
-  if (ip.empty()) {
-    addr->s_addr = INADDR_ANY;
-    return 0;
-  } else {
-    SmallString<128> ipBuf{ip};
-    return uv_inet_pton(AF_INET, ipBuf.c_str(), addr);
-  }
-}
-
-int NameToAddr(std::string_view ip, in6_addr* addr) {
-  if (ip.empty()) {
-    *addr = in6addr_any;
-    return 0;
-  } else {
-    SmallString<128> ipBuf{ip};
-    return uv_inet_pton(AF_INET6, ipBuf.c_str(), addr);
-  }
-}
-
-}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/NetworkStream.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/NetworkStream.cpp
deleted file mode 100644
index 0bc3337..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/NetworkStream.cpp
+++ /dev/null
@@ -1,30 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/uv/NetworkStream.h"
-
-namespace wpi::uv {
-
-ConnectReq::ConnectReq() {
-  error = [this](Error err) { GetStream().error(err); };
-}
-
-void NetworkStream::Listen(int backlog) {
-  Invoke(&uv_listen, GetRawStream(), backlog,
-         [](uv_stream_t* handle, int status) {
-           auto& h = *static_cast<NetworkStream*>(handle->data);
-           if (status < 0) {
-             h.ReportError(status);
-           } else {
-             h.connection();
-           }
-         });
-}
-
-void NetworkStream::Listen(std::function<void()> callback, int backlog) {
-  connection.connect(std::move(callback));
-  Listen(backlog);
-}
-
-}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Pipe.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Pipe.cpp
deleted file mode 100644
index b5ca673..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Pipe.cpp
+++ /dev/null
@@ -1,138 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/uv/Pipe.h"
-
-#include <cstdlib>
-
-#include "wpi/SmallString.h"
-
-namespace wpi::uv {
-
-std::shared_ptr<Pipe> Pipe::Create(Loop& loop, bool ipc) {
-  auto h = std::make_shared<Pipe>(private_init{});
-  int err = uv_pipe_init(loop.GetRaw(), h->GetRaw(), ipc ? 1 : 0);
-  if (err < 0) {
-    loop.ReportError(err);
-    return nullptr;
-  }
-  h->Keep();
-  return h;
-}
-
-void Pipe::Reuse(std::function<void()> callback, bool ipc) {
-  if (IsClosing()) {
-    return;
-  }
-  if (!m_reuseData) {
-    m_reuseData = std::make_unique<ReuseData>();
-  }
-  m_reuseData->callback = std::move(callback);
-  m_reuseData->ipc = ipc;
-  uv_close(GetRawHandle(), [](uv_handle_t* handle) {
-    Pipe& h = *static_cast<Pipe*>(handle->data);
-    if (!h.m_reuseData) {
-      return;
-    }
-    auto data = std::move(h.m_reuseData);
-    auto err =
-        uv_pipe_init(h.GetLoopRef().GetRaw(), h.GetRaw(), data->ipc ? 1 : 0);
-    if (err < 0) {
-      h.ReportError(err);
-      return;
-    }
-    data->callback();
-  });
-}
-
-std::shared_ptr<Pipe> Pipe::Accept() {
-  auto client = Create(GetLoopRef(), GetRaw()->ipc);
-  if (!client) {
-    return nullptr;
-  }
-  if (!Accept(client)) {
-    client->Release();
-    return nullptr;
-  }
-  return client;
-}
-
-Pipe* Pipe::DoAccept() {
-  return Accept().get();
-}
-
-void Pipe::Bind(std::string_view name) {
-  SmallString<128> nameBuf{name};
-  Invoke(&uv_pipe_bind, GetRaw(), nameBuf.c_str());
-}
-
-void Pipe::Connect(std::string_view name,
-                   const std::shared_ptr<PipeConnectReq>& req) {
-  SmallString<128> nameBuf{name};
-  uv_pipe_connect(req->GetRaw(), GetRaw(), nameBuf.c_str(),
-                  [](uv_connect_t* req, int status) {
-                    auto& h = *static_cast<PipeConnectReq*>(req->data);
-                    if (status < 0) {
-                      h.ReportError(status);
-                    } else {
-                      h.connected();
-                    }
-                    h.Release();  // this is always a one-shot
-                  });
-  req->Keep();
-}
-
-void Pipe::Connect(std::string_view name, std::function<void()> callback) {
-  auto req = std::make_shared<PipeConnectReq>();
-  req->connected.connect(std::move(callback));
-  Connect(name, req);
-}
-
-std::string Pipe::GetSock() {
-  // Per libuv docs, the returned buffer is NOT null terminated.
-  // common case should be small
-  char buf[128];
-  size_t size = 128;
-  int r = uv_pipe_getsockname(GetRaw(), buf, &size);
-  if (r == 0) {
-    return std::string{buf, size};
-  } else if (r == UV_ENOBUFS) {
-    // need to allocate a big enough buffer
-    char* buf2 = static_cast<char*>(std::malloc(size));
-    r = uv_pipe_getsockname(GetRaw(), buf2, &size);
-    if (r == 0) {
-      std::string out{buf2, size};
-      std::free(buf2);
-      return out;
-    }
-    std::free(buf2);
-  }
-  ReportError(r);
-  return std::string{};
-}
-
-std::string Pipe::GetPeer() {
-  // Per libuv docs, the returned buffer is NOT null terminated.
-  // common case should be small
-  char buf[128];
-  size_t size = 128;
-  int r = uv_pipe_getpeername(GetRaw(), buf, &size);
-  if (r == 0) {
-    return std::string{buf, size};
-  } else if (r == UV_ENOBUFS) {
-    // need to allocate a big enough buffer
-    char* buf2 = static_cast<char*>(std::malloc(size));
-    r = uv_pipe_getpeername(GetRaw(), buf2, &size);
-    if (r == 0) {
-      std::string out{buf2, size};
-      std::free(buf2);
-      return out;
-    }
-    std::free(buf2);
-  }
-  ReportError(r);
-  return std::string{};
-}
-
-}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Poll.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Poll.cpp
deleted file mode 100644
index 090a40b..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Poll.cpp
+++ /dev/null
@@ -1,95 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/uv/Poll.h"
-
-#include "wpi/uv/Loop.h"
-
-namespace wpi::uv {
-
-std::shared_ptr<Poll> Poll::Create(Loop& loop, int fd) {
-  auto h = std::make_shared<Poll>(private_init{});
-  int err = uv_poll_init(loop.GetRaw(), h->GetRaw(), fd);
-  if (err < 0) {
-    loop.ReportError(err);
-    return nullptr;
-  }
-  h->Keep();
-  return h;
-}
-
-std::shared_ptr<Poll> Poll::CreateSocket(Loop& loop, uv_os_sock_t sock) {
-  auto h = std::make_shared<Poll>(private_init{});
-  int err = uv_poll_init_socket(loop.GetRaw(), h->GetRaw(), sock);
-  if (err < 0) {
-    loop.ReportError(err);
-    return nullptr;
-  }
-  h->Keep();
-  return h;
-}
-
-void Poll::Reuse(int fd, std::function<void()> callback) {
-  if (IsClosing()) {
-    return;
-  }
-  if (!m_reuseData) {
-    m_reuseData = std::make_unique<ReuseData>();
-  }
-  m_reuseData->callback = std::move(callback);
-  m_reuseData->isSocket = false;
-  m_reuseData->fd = fd;
-  uv_close(GetRawHandle(), [](uv_handle_t* handle) {
-    Poll& h = *static_cast<Poll*>(handle->data);
-    if (!h.m_reuseData || h.m_reuseData->isSocket) {
-      return;  // just in case
-    }
-    auto data = std::move(h.m_reuseData);
-    int err = uv_poll_init(h.GetLoopRef().GetRaw(), h.GetRaw(), data->fd);
-    if (err < 0) {
-      h.ReportError(err);
-      return;
-    }
-    data->callback();
-  });
-}
-
-void Poll::ReuseSocket(uv_os_sock_t sock, std::function<void()> callback) {
-  if (IsClosing()) {
-    return;
-  }
-  if (!m_reuseData) {
-    m_reuseData = std::make_unique<ReuseData>();
-  }
-  m_reuseData->callback = std::move(callback);
-  m_reuseData->isSocket = true;
-  m_reuseData->sock = sock;
-  uv_close(GetRawHandle(), [](uv_handle_t* handle) {
-    Poll& h = *static_cast<Poll*>(handle->data);
-    if (!h.m_reuseData || !h.m_reuseData->isSocket) {
-      return;  // just in case
-    }
-    auto data = std::move(h.m_reuseData);
-    int err = uv_poll_init(h.GetLoopRef().GetRaw(), h.GetRaw(), data->sock);
-    if (err < 0) {
-      h.ReportError(err);
-      return;
-    }
-    data->callback();
-  });
-}
-
-void Poll::Start(int events) {
-  Invoke(&uv_poll_start, GetRaw(), events,
-         [](uv_poll_t* handle, int status, int events) {
-           Poll& h = *static_cast<Poll*>(handle->data);
-           if (status < 0) {
-             h.ReportError(status);
-           } else {
-             h.pollEvent(events);
-           }
-         });
-}
-
-}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Prepare.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Prepare.cpp
deleted file mode 100644
index 048fd08..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Prepare.cpp
+++ /dev/null
@@ -1,29 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/uv/Prepare.h"
-
-#include "wpi/uv/Loop.h"
-
-namespace wpi::uv {
-
-std::shared_ptr<Prepare> Prepare::Create(Loop& loop) {
-  auto h = std::make_shared<Prepare>(private_init{});
-  int err = uv_prepare_init(loop.GetRaw(), h->GetRaw());
-  if (err < 0) {
-    loop.ReportError(err);
-    return nullptr;
-  }
-  h->Keep();
-  return h;
-}
-
-void Prepare::Start() {
-  Invoke(&uv_prepare_start, GetRaw(), [](uv_prepare_t* handle) {
-    Prepare& h = *static_cast<Prepare*>(handle->data);
-    h.prepare();
-  });
-}
-
-}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Process.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Process.cpp
deleted file mode 100644
index c8d5229..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Process.cpp
+++ /dev/null
@@ -1,133 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/uv/Process.h"
-
-#include "wpi/SmallString.h"
-#include "wpi/uv/Loop.h"
-#include "wpi/uv/Pipe.h"
-
-namespace wpi::uv {
-
-std::shared_ptr<Process> Process::SpawnArray(Loop& loop, std::string_view file,
-                                             span<const Option> options) {
-  // convert Option array to libuv structure
-  uv_process_options_t coptions;
-
-  coptions.exit_cb = [](uv_process_t* handle, int64_t status, int signal) {
-    auto& h = *static_cast<Process*>(handle->data);
-    h.exited(status, signal);
-  };
-
-  SmallString<128> fileBuf{file};
-  coptions.file = fileBuf.c_str();
-  coptions.cwd = nullptr;
-  coptions.flags = 0;
-  coptions.uid = 0;
-  coptions.gid = 0;
-
-  SmallVector<char*, 4> argsBuf;
-  SmallVector<char*, 4> envBuf;
-  struct StdioContainer : public uv_stdio_container_t {
-    StdioContainer() {
-      flags = UV_IGNORE;
-      data.fd = 0;
-    }
-  };
-  SmallVector<StdioContainer, 4> stdioBuf;
-
-  for (auto&& o : options) {
-    switch (o.m_type) {
-      case Option::kArg:
-        argsBuf.push_back(const_cast<char*>(o.m_data.str));
-        break;
-      case Option::kEnv:
-        envBuf.push_back(const_cast<char*>(o.m_data.str));
-        break;
-      case Option::kCwd:
-        coptions.cwd = o.m_data.str[0] == '\0' ? nullptr : o.m_data.str;
-        break;
-      case Option::kUid:
-        coptions.uid = o.m_data.uid;
-        coptions.flags |= UV_PROCESS_SETUID;
-        break;
-      case Option::kGid:
-        coptions.gid = o.m_data.gid;
-        coptions.flags |= UV_PROCESS_SETGID;
-        break;
-      case Option::kSetFlags:
-        coptions.flags |= o.m_data.flags;
-        break;
-      case Option::kClearFlags:
-        coptions.flags &= ~o.m_data.flags;
-        break;
-      case Option::kStdioIgnore: {
-        size_t index = o.m_data.stdio.index;
-        if (index >= stdioBuf.size()) {
-          stdioBuf.resize(index + 1);
-        }
-        stdioBuf[index].flags = UV_IGNORE;
-        stdioBuf[index].data.fd = 0;
-        break;
-      }
-      case Option::kStdioInheritFd: {
-        size_t index = o.m_data.stdio.index;
-        if (index >= stdioBuf.size()) {
-          stdioBuf.resize(index + 1);
-        }
-        stdioBuf[index].flags = UV_INHERIT_FD;
-        stdioBuf[index].data.fd = o.m_data.stdio.fd;
-        break;
-      }
-      case Option::kStdioInheritPipe: {
-        size_t index = o.m_data.stdio.index;
-        if (index >= stdioBuf.size()) {
-          stdioBuf.resize(index + 1);
-        }
-        stdioBuf[index].flags = UV_INHERIT_STREAM;
-        stdioBuf[index].data.stream = o.m_data.stdio.pipe->GetRawStream();
-        break;
-      }
-      case Option::kStdioCreatePipe: {
-        size_t index = o.m_data.stdio.index;
-        if (index >= stdioBuf.size()) {
-          stdioBuf.resize(index + 1);
-        }
-        stdioBuf[index].flags =
-            static_cast<uv_stdio_flags>(UV_CREATE_PIPE | o.m_data.stdio.flags);
-        stdioBuf[index].data.stream = o.m_data.stdio.pipe->GetRawStream();
-        break;
-      }
-      default:
-        break;
-    }
-  }
-
-  if (argsBuf.empty()) {
-    argsBuf.push_back(const_cast<char*>(coptions.file));
-  }
-  argsBuf.push_back(nullptr);
-  coptions.args = argsBuf.data();
-
-  if (envBuf.empty()) {
-    coptions.env = nullptr;
-  } else {
-    envBuf.push_back(nullptr);
-    coptions.env = envBuf.data();
-  }
-
-  coptions.stdio_count = stdioBuf.size();
-  coptions.stdio = static_cast<uv_stdio_container_t*>(stdioBuf.data());
-
-  auto h = std::make_shared<Process>(private_init{});
-  int err = uv_spawn(loop.GetRaw(), h->GetRaw(), &coptions);
-  if (err < 0) {
-    loop.ReportError(err);
-    return nullptr;
-  }
-  h->Keep();
-  return h;
-}
-
-}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Signal.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Signal.cpp
deleted file mode 100644
index 81d7c3e..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Signal.cpp
+++ /dev/null
@@ -1,32 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/uv/Signal.h"
-
-#include "wpi/uv/Loop.h"
-
-namespace wpi::uv {
-
-std::shared_ptr<Signal> Signal::Create(Loop& loop) {
-  auto h = std::make_shared<Signal>(private_init{});
-  int err = uv_signal_init(loop.GetRaw(), h->GetRaw());
-  if (err < 0) {
-    loop.ReportError(err);
-    return nullptr;
-  }
-  h->Keep();
-  return h;
-}
-
-void Signal::Start(int signum) {
-  Invoke(
-      &uv_signal_start, GetRaw(),
-      [](uv_signal_t* handle, int signum) {
-        Signal& h = *static_cast<Signal*>(handle->data);
-        h.signal(signum);
-      },
-      signum);
-}
-
-}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Stream.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Stream.cpp
deleted file mode 100644
index a37750b..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Stream.cpp
+++ /dev/null
@@ -1,109 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/uv/Stream.h"
-
-#include "wpi/SmallVector.h"
-
-using namespace wpi;
-using namespace wpi::uv;
-
-namespace {
-class CallbackWriteReq : public WriteReq {
- public:
-  CallbackWriteReq(span<const Buffer> bufs,
-                   std::function<void(span<Buffer>, Error)> callback)
-      : m_bufs{bufs.begin(), bufs.end()} {
-    finish.connect(
-        [this, f = std::move(callback)](Error err) { f(m_bufs, err); });
-  }
-
- private:
-  SmallVector<Buffer, 4> m_bufs;
-};
-}  // namespace
-
-namespace wpi::uv {
-
-ShutdownReq::ShutdownReq() {
-  error = [this](Error err) { GetStream().error(err); };
-}
-
-WriteReq::WriteReq() {
-  error = [this](Error err) { GetStream().error(err); };
-}
-
-void Stream::Shutdown(const std::shared_ptr<ShutdownReq>& req) {
-  if (Invoke(&uv_shutdown, req->GetRaw(), GetRawStream(),
-             [](uv_shutdown_t* req, int status) {
-               auto& h = *static_cast<ShutdownReq*>(req->data);
-               if (status < 0) {
-                 h.ReportError(status);
-               } else {
-                 h.complete();
-               }
-               h.Release();  // this is always a one-shot
-             })) {
-    req->Keep();
-  }
-}
-
-void Stream::Shutdown(std::function<void()> callback) {
-  auto req = std::make_shared<ShutdownReq>();
-  if (callback) {
-    req->complete.connect(std::move(callback));
-  }
-  Shutdown(req);
-}
-
-void Stream::StartRead() {
-  Invoke(&uv_read_start, GetRawStream(), &Handle::AllocBuf,
-         [](uv_stream_t* stream, ssize_t nread, const uv_buf_t* buf) {
-           auto& h = *static_cast<Stream*>(stream->data);
-           Buffer data = *buf;
-
-           // nread=0 is simply ignored
-           if (nread == UV_EOF) {
-             h.end();
-           } else if (nread > 0) {
-             h.data(data, static_cast<size_t>(nread));
-           } else if (nread < 0) {
-             h.ReportError(nread);
-           }
-
-           // free the buffer
-           h.FreeBuf(data);
-         });
-}
-
-void Stream::Write(span<const Buffer> bufs,
-                   const std::shared_ptr<WriteReq>& req) {
-  if (Invoke(&uv_write, req->GetRaw(), GetRawStream(), bufs.data(), bufs.size(),
-             [](uv_write_t* r, int status) {
-               auto& h = *static_cast<WriteReq*>(r->data);
-               if (status < 0) {
-                 h.ReportError(status);
-               }
-               h.finish(Error(status));
-               h.Release();  // this is always a one-shot
-             })) {
-    req->Keep();
-  }
-}
-
-void Stream::Write(span<const Buffer> bufs,
-                   std::function<void(span<Buffer>, Error)> callback) {
-  Write(bufs, std::make_shared<CallbackWriteReq>(bufs, std::move(callback)));
-}
-
-int Stream::TryWrite(span<const Buffer> bufs) {
-  int val = uv_try_write(GetRawStream(), bufs.data(), bufs.size());
-  if (val < 0) {
-    this->ReportError(val);
-    return 0;
-  }
-  return val;
-}
-
-}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Tcp.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Tcp.cpp
deleted file mode 100644
index 6f92557..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Tcp.cpp
+++ /dev/null
@@ -1,170 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/uv/Tcp.h"
-
-#include <cstring>
-
-#include "wpi/uv/util.h"
-
-namespace wpi::uv {
-
-std::shared_ptr<Tcp> Tcp::Create(Loop& loop, unsigned int flags) {
-  auto h = std::make_shared<Tcp>(private_init{});
-  int err = uv_tcp_init_ex(loop.GetRaw(), h->GetRaw(), flags);
-  if (err < 0) {
-    loop.ReportError(err);
-    return nullptr;
-  }
-  h->Keep();
-  return h;
-}
-
-void Tcp::Reuse(std::function<void()> callback, unsigned int flags) {
-  if (IsClosing()) {
-    return;
-  }
-  if (!m_reuseData) {
-    m_reuseData = std::make_unique<ReuseData>();
-  }
-  m_reuseData->callback = std::move(callback);
-  m_reuseData->flags = flags;
-  uv_close(GetRawHandle(), [](uv_handle_t* handle) {
-    Tcp& h = *static_cast<Tcp*>(handle->data);
-    if (!h.m_reuseData) {
-      return;  // just in case
-    }
-    auto data = std::move(h.m_reuseData);
-    int err = uv_tcp_init_ex(h.GetLoopRef().GetRaw(), h.GetRaw(), data->flags);
-    if (err < 0) {
-      h.ReportError(err);
-      return;
-    }
-    data->callback();
-  });
-}
-
-std::shared_ptr<Tcp> Tcp::Accept() {
-  auto client = Create(GetLoopRef());
-  if (!client) {
-    return nullptr;
-  }
-  if (!Accept(client)) {
-    client->Release();
-    return nullptr;
-  }
-  return client;
-}
-
-Tcp* Tcp::DoAccept() {
-  return Accept().get();
-}
-
-void Tcp::Bind(std::string_view ip, unsigned int port, unsigned int flags) {
-  sockaddr_in addr;
-  int err = NameToAddr(ip, port, &addr);
-  if (err < 0) {
-    ReportError(err);
-  } else {
-    Bind(reinterpret_cast<const sockaddr&>(addr), flags);
-  }
-}
-
-void Tcp::Bind6(std::string_view ip, unsigned int port, unsigned int flags) {
-  sockaddr_in6 addr;
-  int err = NameToAddr(ip, port, &addr);
-  if (err < 0) {
-    ReportError(err);
-  } else {
-    Bind(reinterpret_cast<const sockaddr&>(addr), flags);
-  }
-}
-
-sockaddr_storage Tcp::GetSock() {
-  sockaddr_storage name;
-  int len = sizeof(name);
-  if (!Invoke(&uv_tcp_getsockname, GetRaw(), reinterpret_cast<sockaddr*>(&name),
-              &len)) {
-    std::memset(&name, 0, sizeof(name));
-  }
-  return name;
-}
-
-sockaddr_storage Tcp::GetPeer() {
-  sockaddr_storage name;
-  int len = sizeof(name);
-  if (!Invoke(&uv_tcp_getpeername, GetRaw(), reinterpret_cast<sockaddr*>(&name),
-              &len)) {
-    std::memset(&name, 0, sizeof(name));
-  }
-  return name;
-}
-
-void Tcp::Connect(const sockaddr& addr,
-                  const std::shared_ptr<TcpConnectReq>& req) {
-  if (Invoke(&uv_tcp_connect, req->GetRaw(), GetRaw(), &addr,
-             [](uv_connect_t* req, int status) {
-               auto& h = *static_cast<TcpConnectReq*>(req->data);
-               if (status < 0) {
-                 h.ReportError(status);
-               } else {
-                 h.connected();
-               }
-               h.Release();  // this is always a one-shot
-             })) {
-    req->Keep();
-  }
-}
-
-void Tcp::Connect(const sockaddr& addr, std::function<void()> callback) {
-  auto req = std::make_shared<TcpConnectReq>();
-  req->connected.connect(std::move(callback));
-  Connect(addr, req);
-}
-
-void Tcp::Connect(std::string_view ip, unsigned int port,
-                  const std::shared_ptr<TcpConnectReq>& req) {
-  sockaddr_in addr;
-  int err = NameToAddr(ip, port, &addr);
-  if (err < 0) {
-    ReportError(err);
-  } else {
-    Connect(reinterpret_cast<const sockaddr&>(addr), req);
-  }
-}
-
-void Tcp::Connect(std::string_view ip, unsigned int port,
-                  std::function<void()> callback) {
-  sockaddr_in addr;
-  int err = NameToAddr(ip, port, &addr);
-  if (err < 0) {
-    ReportError(err);
-  } else {
-    Connect(reinterpret_cast<const sockaddr&>(addr), std::move(callback));
-  }
-}
-
-void Tcp::Connect6(std::string_view ip, unsigned int port,
-                   const std::shared_ptr<TcpConnectReq>& req) {
-  sockaddr_in6 addr;
-  int err = NameToAddr(ip, port, &addr);
-  if (err < 0) {
-    ReportError(err);
-  } else {
-    Connect(reinterpret_cast<const sockaddr&>(addr), req);
-  }
-}
-
-void Tcp::Connect6(std::string_view ip, unsigned int port,
-                   std::function<void()> callback) {
-  sockaddr_in6 addr;
-  int err = NameToAddr(ip, port, &addr);
-  if (err < 0) {
-    ReportError(err);
-  } else {
-    Connect(reinterpret_cast<const sockaddr&>(addr), std::move(callback));
-  }
-}
-
-}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Timer.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Timer.cpp
deleted file mode 100644
index 33fd851..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Timer.cpp
+++ /dev/null
@@ -1,44 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/uv/Timer.h"
-
-#include "wpi/uv/Loop.h"
-
-namespace wpi::uv {
-
-std::shared_ptr<Timer> Timer::Create(Loop& loop) {
-  auto h = std::make_shared<Timer>(private_init{});
-  int err = uv_timer_init(loop.GetRaw(), h->GetRaw());
-  if (err < 0) {
-    loop.ReportError(err);
-    return nullptr;
-  }
-  h->Keep();
-  return h;
-}
-
-void Timer::SingleShot(Loop& loop, Time timeout, std::function<void()> func) {
-  auto h = Create(loop);
-  if (!h) {
-    return;
-  }
-  h->timeout.connect([theTimer = h.get(), f = std::move(func)]() {
-    f();
-    theTimer->Close();
-  });
-  h->Start(timeout);
-}
-
-void Timer::Start(Time timeout, Time repeat) {
-  Invoke(
-      &uv_timer_start, GetRaw(),
-      [](uv_timer_t* handle) {
-        Timer& h = *static_cast<Timer*>(handle->data);
-        h.timeout();
-      },
-      timeout.count(), repeat.count());
-}
-
-}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Tty.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Tty.cpp
deleted file mode 100644
index 4531ded..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Tty.cpp
+++ /dev/null
@@ -1,22 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/uv/Tty.h"
-
-#include "wpi/uv/Loop.h"
-
-namespace wpi::uv {
-
-std::shared_ptr<Tty> Tty::Create(Loop& loop, uv_file fd, bool readable) {
-  auto h = std::make_shared<Tty>(private_init{});
-  int err = uv_tty_init(loop.GetRaw(), h->GetRaw(), fd, readable ? 1 : 0);
-  if (err < 0) {
-    loop.ReportError(err);
-    return nullptr;
-  }
-  h->Keep();
-  return h;
-}
-
-}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Udp.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Udp.cpp
deleted file mode 100644
index bea2b57..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Udp.cpp
+++ /dev/null
@@ -1,184 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/uv/Udp.h"
-
-#include <cstring>
-
-#include "wpi/SmallString.h"
-#include "wpi/SmallVector.h"
-#include "wpi/uv/util.h"
-
-namespace {
-
-using namespace wpi;
-using namespace wpi::uv;
-
-class CallbackUdpSendReq : public UdpSendReq {
- public:
-  CallbackUdpSendReq(span<const Buffer> bufs,
-                     std::function<void(span<Buffer>, Error)> callback)
-      : m_bufs{bufs.begin(), bufs.end()} {
-    complete.connect(
-        [this, f = std::move(callback)](Error err) { f(m_bufs, err); });
-  }
-
- private:
-  SmallVector<Buffer, 4> m_bufs;
-};
-
-}  // namespace
-
-namespace wpi::uv {
-
-UdpSendReq::UdpSendReq() {
-  error = [this](Error err) { GetUdp().error(err); };
-}
-
-std::shared_ptr<Udp> Udp::Create(Loop& loop, unsigned int flags) {
-  auto h = std::make_shared<Udp>(private_init{});
-  int err = uv_udp_init_ex(loop.GetRaw(), h->GetRaw(), flags);
-  if (err < 0) {
-    loop.ReportError(err);
-    return nullptr;
-  }
-  h->Keep();
-  return h;
-}
-
-void Udp::Bind(std::string_view ip, unsigned int port, unsigned int flags) {
-  sockaddr_in addr;
-  int err = NameToAddr(ip, port, &addr);
-  if (err < 0) {
-    ReportError(err);
-  } else {
-    Bind(reinterpret_cast<const sockaddr&>(addr), flags);
-  }
-}
-
-void Udp::Bind6(std::string_view ip, unsigned int port, unsigned int flags) {
-  sockaddr_in6 addr;
-  int err = NameToAddr(ip, port, &addr);
-  if (err < 0) {
-    ReportError(err);
-  } else {
-    Bind(reinterpret_cast<const sockaddr&>(addr), flags);
-  }
-}
-
-void Udp::Connect(std::string_view ip, unsigned int port) {
-  sockaddr_in addr;
-  int err = NameToAddr(ip, port, &addr);
-  if (err < 0) {
-    ReportError(err);
-  } else {
-    Connect(reinterpret_cast<const sockaddr&>(addr));
-  }
-}
-
-void Udp::Connect6(std::string_view ip, unsigned int port) {
-  sockaddr_in6 addr;
-  int err = NameToAddr(ip, port, &addr);
-  if (err < 0) {
-    ReportError(err);
-  } else {
-    Connect(reinterpret_cast<const sockaddr&>(addr));
-  }
-}
-
-sockaddr_storage Udp::GetPeer() {
-  sockaddr_storage name;
-  int len = sizeof(name);
-  if (!Invoke(&uv_udp_getpeername, GetRaw(), reinterpret_cast<sockaddr*>(&name),
-              &len)) {
-    std::memset(&name, 0, sizeof(name));
-  }
-  return name;
-}
-
-sockaddr_storage Udp::GetSock() {
-  sockaddr_storage name;
-  int len = sizeof(name);
-  if (!Invoke(&uv_udp_getsockname, GetRaw(), reinterpret_cast<sockaddr*>(&name),
-              &len)) {
-    std::memset(&name, 0, sizeof(name));
-  }
-  return name;
-}
-
-void Udp::SetMembership(std::string_view multicastAddr,
-                        std::string_view interfaceAddr,
-                        uv_membership membership) {
-  SmallString<128> multicastAddrBuf{multicastAddr};
-  SmallString<128> interfaceAddrBuf{interfaceAddr};
-  Invoke(&uv_udp_set_membership, GetRaw(), multicastAddrBuf.c_str(),
-         interfaceAddrBuf.c_str(), membership);
-}
-
-void Udp::SetMulticastInterface(std::string_view interfaceAddr) {
-  SmallString<128> interfaceAddrBuf{interfaceAddr};
-  Invoke(&uv_udp_set_multicast_interface, GetRaw(), interfaceAddrBuf.c_str());
-}
-
-void Udp::Send(const sockaddr& addr, span<const Buffer> bufs,
-               const std::shared_ptr<UdpSendReq>& req) {
-  if (Invoke(&uv_udp_send, req->GetRaw(), GetRaw(), bufs.data(), bufs.size(),
-             &addr, [](uv_udp_send_t* r, int status) {
-               auto& h = *static_cast<UdpSendReq*>(r->data);
-               if (status < 0) {
-                 h.ReportError(status);
-               }
-               h.complete(Error(status));
-               h.Release();  // this is always a one-shot
-             })) {
-    req->Keep();
-  }
-}
-
-void Udp::Send(const sockaddr& addr, span<const Buffer> bufs,
-               std::function<void(span<Buffer>, Error)> callback) {
-  Send(addr, bufs,
-       std::make_shared<CallbackUdpSendReq>(bufs, std::move(callback)));
-}
-
-void Udp::Send(span<const Buffer> bufs,
-               const std::shared_ptr<UdpSendReq>& req) {
-  if (Invoke(&uv_udp_send, req->GetRaw(), GetRaw(), bufs.data(), bufs.size(),
-             nullptr, [](uv_udp_send_t* r, int status) {
-               auto& h = *static_cast<UdpSendReq*>(r->data);
-               if (status < 0) {
-                 h.ReportError(status);
-               }
-               h.complete(Error(status));
-               h.Release();  // this is always a one-shot
-             })) {
-    req->Keep();
-  }
-}
-
-void Udp::Send(span<const Buffer> bufs,
-               std::function<void(span<Buffer>, Error)> callback) {
-  Send(bufs, std::make_shared<CallbackUdpSendReq>(bufs, std::move(callback)));
-}
-
-void Udp::StartRecv() {
-  Invoke(&uv_udp_recv_start, GetRaw(), &AllocBuf,
-         [](uv_udp_t* handle, ssize_t nread, const uv_buf_t* buf,
-            const sockaddr* addr, unsigned flags) {
-           auto& h = *static_cast<Udp*>(handle->data);
-           Buffer data = *buf;
-
-           // nread=0 is simply ignored
-           if (nread > 0) {
-             h.received(data, static_cast<size_t>(nread), *addr, flags);
-           } else if (nread < 0) {
-             h.ReportError(nread);
-           }
-
-           // free the buffer
-           h.FreeBuf(data);
-         });
-}
-
-}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Work.cpp b/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Work.cpp
deleted file mode 100644
index 0fc254e..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/cpp/uv/Work.cpp
+++ /dev/null
@@ -1,50 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/uv/Work.h"
-
-#include "wpi/uv/Loop.h"
-
-namespace wpi::uv {
-
-WorkReq::WorkReq() {
-  error = [this](Error err) { GetLoop().error(err); };
-}
-
-void QueueWork(Loop& loop, const std::shared_ptr<WorkReq>& req) {
-  int err = uv_queue_work(
-      loop.GetRaw(), req->GetRaw(),
-      [](uv_work_t* req) {
-        auto& h = *static_cast<WorkReq*>(req->data);
-        h.work();
-      },
-      [](uv_work_t* req, int status) {
-        auto& h = *static_cast<WorkReq*>(req->data);
-        if (status < 0) {
-          h.ReportError(status);
-        } else {
-          h.afterWork();
-        }
-        h.Release();  // this is always a one-shot
-      });
-  if (err < 0) {
-    loop.ReportError(err);
-  } else {
-    req->Keep();
-  }
-}
-
-void QueueWork(Loop& loop, std::function<void()> work,
-               std::function<void()> afterWork) {
-  auto req = std::make_shared<WorkReq>();
-  if (work) {
-    req->work.connect(std::move(work));
-  }
-  if (afterWork) {
-    req->afterWork.connect(std::move(afterWork));
-  }
-  QueueWork(loop, req);
-}
-
-}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/args.h b/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/args.h
deleted file mode 100644
index 9a8e4ed..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/args.h
+++ /dev/null
@@ -1,234 +0,0 @@
-// Formatting library for C++ - dynamic format arguments
-//
-// Copyright (c) 2012 - present, Victor Zverovich
-// All rights reserved.
-//
-// For the license information refer to format.h.
-
-#ifndef FMT_ARGS_H_
-#define FMT_ARGS_H_
-
-#include <functional>  // std::reference_wrapper
-#include <memory>      // std::unique_ptr
-#include <vector>
-
-#include "core.h"
-
-FMT_BEGIN_NAMESPACE
-
-namespace detail {
-
-template <typename T> struct is_reference_wrapper : std::false_type {};
-template <typename T>
-struct is_reference_wrapper<std::reference_wrapper<T>> : std::true_type {};
-
-template <typename T> const T& unwrap(const T& v) { return v; }
-template <typename T> const T& unwrap(const std::reference_wrapper<T>& v) {
-  return static_cast<const T&>(v);
-}
-
-class dynamic_arg_list {
-  // Workaround for clang's -Wweak-vtables. Unlike for regular classes, for
-  // templates it doesn't complain about inability to deduce single translation
-  // unit for placing vtable. So storage_node_base is made a fake template.
-  template <typename = void> struct node {
-    virtual ~node() = default;
-    std::unique_ptr<node<>> next;
-  };
-
-  template <typename T> struct typed_node : node<> {
-    T value;
-
-    template <typename Arg>
-    FMT_CONSTEXPR typed_node(const Arg& arg) : value(arg) {}
-
-    template <typename Char>
-    FMT_CONSTEXPR typed_node(const basic_string_view<Char>& arg)
-        : value(arg.data(), arg.size()) {}
-  };
-
-  std::unique_ptr<node<>> head_;
-
- public:
-  template <typename T, typename Arg> const T& push(const Arg& arg) {
-    auto new_node = std::unique_ptr<typed_node<T>>(new typed_node<T>(arg));
-    auto& value = new_node->value;
-    new_node->next = std::move(head_);
-    head_ = std::move(new_node);
-    return value;
-  }
-};
-}  // namespace detail
-
-/**
-  \rst
-  A dynamic version of `fmt::format_arg_store`.
-  It's equipped with a storage to potentially temporary objects which lifetimes
-  could be shorter than the format arguments object.
-
-  It can be implicitly converted into `~fmt::basic_format_args` for passing
-  into type-erased formatting functions such as `~fmt::vformat`.
-  \endrst
- */
-template <typename Context>
-class dynamic_format_arg_store
-#if FMT_GCC_VERSION && FMT_GCC_VERSION < 409
-    // Workaround a GCC template argument substitution bug.
-    : public basic_format_args<Context>
-#endif
-{
- private:
-  using char_type = typename Context::char_type;
-
-  template <typename T> struct need_copy {
-    static constexpr detail::type mapped_type =
-        detail::mapped_type_constant<T, Context>::value;
-
-    enum {
-      value = !(detail::is_reference_wrapper<T>::value ||
-                std::is_same<T, basic_string_view<char_type>>::value ||
-                std::is_same<T, detail::std_string_view<char_type>>::value ||
-                (mapped_type != detail::type::cstring_type &&
-                 mapped_type != detail::type::string_type &&
-                 mapped_type != detail::type::custom_type))
-    };
-  };
-
-  template <typename T>
-  using stored_type = conditional_t<detail::is_string<T>::value &&
-                                        !has_formatter<T, Context>::value &&
-                                        !detail::is_reference_wrapper<T>::value,
-                                    std::basic_string<char_type>, T>;
-
-  // Storage of basic_format_arg must be contiguous.
-  std::vector<basic_format_arg<Context>> data_;
-  std::vector<detail::named_arg_info<char_type>> named_info_;
-
-  // Storage of arguments not fitting into basic_format_arg must grow
-  // without relocation because items in data_ refer to it.
-  detail::dynamic_arg_list dynamic_args_;
-
-  friend class basic_format_args<Context>;
-
-  unsigned long long get_types() const {
-    return detail::is_unpacked_bit | data_.size() |
-           (named_info_.empty()
-                ? 0ULL
-                : static_cast<unsigned long long>(detail::has_named_args_bit));
-  }
-
-  const basic_format_arg<Context>* data() const {
-    return named_info_.empty() ? data_.data() : data_.data() + 1;
-  }
-
-  template <typename T> void emplace_arg(const T& arg) {
-    data_.emplace_back(detail::make_arg<Context>(arg));
-  }
-
-  template <typename T>
-  void emplace_arg(const detail::named_arg<char_type, T>& arg) {
-    if (named_info_.empty()) {
-      constexpr const detail::named_arg_info<char_type>* zero_ptr{nullptr};
-      data_.insert(data_.begin(), {zero_ptr, 0});
-    }
-    data_.emplace_back(detail::make_arg<Context>(detail::unwrap(arg.value)));
-    auto pop_one = [](std::vector<basic_format_arg<Context>>* data) {
-      data->pop_back();
-    };
-    std::unique_ptr<std::vector<basic_format_arg<Context>>, decltype(pop_one)>
-        guard{&data_, pop_one};
-    named_info_.push_back({arg.name, static_cast<int>(data_.size() - 2u)});
-    data_[0].value_.named_args = {named_info_.data(), named_info_.size()};
-    guard.release();
-  }
-
- public:
-  constexpr dynamic_format_arg_store() = default;
-
-  /**
-    \rst
-    Adds an argument into the dynamic store for later passing to a formatting
-    function.
-
-    Note that custom types and string types (but not string views) are copied
-    into the store dynamically allocating memory if necessary.
-
-    **Example**::
-
-      fmt::dynamic_format_arg_store<fmt::format_context> store;
-      store.push_back(42);
-      store.push_back("abc");
-      store.push_back(1.5f);
-      std::string result = fmt::vformat("{} and {} and {}", store);
-    \endrst
-  */
-  template <typename T> void push_back(const T& arg) {
-    if (detail::const_check(need_copy<T>::value))
-      emplace_arg(dynamic_args_.push<stored_type<T>>(arg));
-    else
-      emplace_arg(detail::unwrap(arg));
-  }
-
-  /**
-    \rst
-    Adds a reference to the argument into the dynamic store for later passing to
-    a formatting function.
-
-    **Example**::
-
-      fmt::dynamic_format_arg_store<fmt::format_context> store;
-      char band[] = "Rolling Stones";
-      store.push_back(std::cref(band));
-      band[9] = 'c'; // Changing str affects the output.
-      std::string result = fmt::vformat("{}", store);
-      // result == "Rolling Scones"
-    \endrst
-  */
-  template <typename T> void push_back(std::reference_wrapper<T> arg) {
-    static_assert(
-        need_copy<T>::value,
-        "objects of built-in types and string views are always copied");
-    emplace_arg(arg.get());
-  }
-
-  /**
-    Adds named argument into the dynamic store for later passing to a formatting
-    function. ``std::reference_wrapper`` is supported to avoid copying of the
-    argument. The name is always copied into the store.
-  */
-  template <typename T>
-  void push_back(const detail::named_arg<char_type, T>& arg) {
-    const char_type* arg_name =
-        dynamic_args_.push<std::basic_string<char_type>>(arg.name).c_str();
-    if (detail::const_check(need_copy<T>::value)) {
-      emplace_arg(
-          fmt::arg(arg_name, dynamic_args_.push<stored_type<T>>(arg.value)));
-    } else {
-      emplace_arg(fmt::arg(arg_name, arg.value));
-    }
-  }
-
-  /** Erase all elements from the store */
-  void clear() {
-    data_.clear();
-    named_info_.clear();
-    dynamic_args_ = detail::dynamic_arg_list();
-  }
-
-  /**
-    \rst
-    Reserves space to store at least *new_cap* arguments including
-    *new_cap_named* named arguments.
-    \endrst
-  */
-  void reserve(size_t new_cap, size_t new_cap_named) {
-    FMT_ASSERT(new_cap >= new_cap_named,
-               "Set of arguments includes set of named arguments");
-    data_.reserve(new_cap);
-    named_info_.reserve(new_cap_named);
-  }
-};
-
-FMT_END_NAMESPACE
-
-#endif  // FMT_ARGS_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/chrono.h b/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/chrono.h
deleted file mode 100644
index 682efd8..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/chrono.h
+++ /dev/null
@@ -1,2067 +0,0 @@
-// Formatting library for C++ - chrono support
-//
-// Copyright (c) 2012 - present, Victor Zverovich
-// All rights reserved.
-//
-// For the license information refer to format.h.
-
-#ifndef FMT_CHRONO_H_
-#define FMT_CHRONO_H_
-
-#include <algorithm>
-#include <chrono>
-#include <ctime>
-#include <iterator>
-#include <locale>
-#include <ostream>
-#include <type_traits>
-
-#include "format.h"
-
-FMT_BEGIN_NAMESPACE
-
-// Enable tzset.
-#ifndef FMT_USE_TZSET
-// UWP doesn't provide _tzset.
-#  if FMT_HAS_INCLUDE("winapifamily.h")
-#    include <winapifamily.h>
-#  endif
-#  if defined(_WIN32) && (!defined(WINAPI_FAMILY) || \
-                          (WINAPI_FAMILY == WINAPI_FAMILY_DESKTOP_APP))
-#    define FMT_USE_TZSET 1
-#  else
-#    define FMT_USE_TZSET 0
-#  endif
-#endif
-
-// Enable safe chrono durations, unless explicitly disabled.
-#ifndef FMT_SAFE_DURATION_CAST
-#  define FMT_SAFE_DURATION_CAST 1
-#endif
-#if FMT_SAFE_DURATION_CAST
-
-// For conversion between std::chrono::durations without undefined
-// behaviour or erroneous results.
-// This is a stripped down version of duration_cast, for inclusion in fmt.
-// See https://github.com/pauldreik/safe_duration_cast
-//
-// Copyright Paul Dreik 2019
-namespace safe_duration_cast {
-
-template <typename To, typename From,
-          FMT_ENABLE_IF(!std::is_same<From, To>::value &&
-                        std::numeric_limits<From>::is_signed ==
-                            std::numeric_limits<To>::is_signed)>
-FMT_CONSTEXPR To lossless_integral_conversion(const From from, int& ec) {
-  ec = 0;
-  using F = std::numeric_limits<From>;
-  using T = std::numeric_limits<To>;
-  static_assert(F::is_integer, "From must be integral");
-  static_assert(T::is_integer, "To must be integral");
-
-  // A and B are both signed, or both unsigned.
-  if (detail::const_check(F::digits <= T::digits)) {
-    // From fits in To without any problem.
-  } else {
-    // From does not always fit in To, resort to a dynamic check.
-    if (from < (T::min)() || from > (T::max)()) {
-      // outside range.
-      ec = 1;
-      return {};
-    }
-  }
-  return static_cast<To>(from);
-}
-
-/**
- * converts From to To, without loss. If the dynamic value of from
- * can't be converted to To without loss, ec is set.
- */
-template <typename To, typename From,
-          FMT_ENABLE_IF(!std::is_same<From, To>::value &&
-                        std::numeric_limits<From>::is_signed !=
-                            std::numeric_limits<To>::is_signed)>
-FMT_CONSTEXPR To lossless_integral_conversion(const From from, int& ec) {
-  ec = 0;
-  using F = std::numeric_limits<From>;
-  using T = std::numeric_limits<To>;
-  static_assert(F::is_integer, "From must be integral");
-  static_assert(T::is_integer, "To must be integral");
-
-  if (detail::const_check(F::is_signed && !T::is_signed)) {
-    // From may be negative, not allowed!
-    if (fmt::detail::is_negative(from)) {
-      ec = 1;
-      return {};
-    }
-    // From is positive. Can it always fit in To?
-    if (detail::const_check(F::digits > T::digits) &&
-        from > static_cast<From>(detail::max_value<To>())) {
-      ec = 1;
-      return {};
-    }
-  }
-
-  if (detail::const_check(!F::is_signed && T::is_signed &&
-                          F::digits >= T::digits) &&
-      from > static_cast<From>(detail::max_value<To>())) {
-    ec = 1;
-    return {};
-  }
-  return static_cast<To>(from);  // Lossless conversion.
-}
-
-template <typename To, typename From,
-          FMT_ENABLE_IF(std::is_same<From, To>::value)>
-FMT_CONSTEXPR To lossless_integral_conversion(const From from, int& ec) {
-  ec = 0;
-  return from;
-}  // function
-
-// clang-format off
-/**
- * converts From to To if possible, otherwise ec is set.
- *
- * input                            |    output
- * ---------------------------------|---------------
- * NaN                              | NaN
- * Inf                              | Inf
- * normal, fits in output           | converted (possibly lossy)
- * normal, does not fit in output   | ec is set
- * subnormal                        | best effort
- * -Inf                             | -Inf
- */
-// clang-format on
-template <typename To, typename From,
-          FMT_ENABLE_IF(!std::is_same<From, To>::value)>
-FMT_CONSTEXPR To safe_float_conversion(const From from, int& ec) {
-  ec = 0;
-  using T = std::numeric_limits<To>;
-  static_assert(std::is_floating_point<From>::value, "From must be floating");
-  static_assert(std::is_floating_point<To>::value, "To must be floating");
-
-  // catch the only happy case
-  if (std::isfinite(from)) {
-    if (from >= T::lowest() && from <= (T::max)()) {
-      return static_cast<To>(from);
-    }
-    // not within range.
-    ec = 1;
-    return {};
-  }
-
-  // nan and inf will be preserved
-  return static_cast<To>(from);
-}  // function
-
-template <typename To, typename From,
-          FMT_ENABLE_IF(std::is_same<From, To>::value)>
-FMT_CONSTEXPR To safe_float_conversion(const From from, int& ec) {
-  ec = 0;
-  static_assert(std::is_floating_point<From>::value, "From must be floating");
-  return from;
-}
-
-/**
- * safe duration cast between integral durations
- */
-template <typename To, typename FromRep, typename FromPeriod,
-          FMT_ENABLE_IF(std::is_integral<FromRep>::value),
-          FMT_ENABLE_IF(std::is_integral<typename To::rep>::value)>
-To safe_duration_cast(std::chrono::duration<FromRep, FromPeriod> from,
-                      int& ec) {
-  using From = std::chrono::duration<FromRep, FromPeriod>;
-  ec = 0;
-  // the basic idea is that we need to convert from count() in the from type
-  // to count() in the To type, by multiplying it with this:
-  struct Factor
-      : std::ratio_divide<typename From::period, typename To::period> {};
-
-  static_assert(Factor::num > 0, "num must be positive");
-  static_assert(Factor::den > 0, "den must be positive");
-
-  // the conversion is like this: multiply from.count() with Factor::num
-  // /Factor::den and convert it to To::rep, all this without
-  // overflow/underflow. let's start by finding a suitable type that can hold
-  // both To, From and Factor::num
-  using IntermediateRep =
-      typename std::common_type<typename From::rep, typename To::rep,
-                                decltype(Factor::num)>::type;
-
-  // safe conversion to IntermediateRep
-  IntermediateRep count =
-      lossless_integral_conversion<IntermediateRep>(from.count(), ec);
-  if (ec) return {};
-  // multiply with Factor::num without overflow or underflow
-  if (detail::const_check(Factor::num != 1)) {
-    const auto max1 = detail::max_value<IntermediateRep>() / Factor::num;
-    if (count > max1) {
-      ec = 1;
-      return {};
-    }
-    const auto min1 =
-        (std::numeric_limits<IntermediateRep>::min)() / Factor::num;
-    if (count < min1) {
-      ec = 1;
-      return {};
-    }
-    count *= Factor::num;
-  }
-
-  if (detail::const_check(Factor::den != 1)) count /= Factor::den;
-  auto tocount = lossless_integral_conversion<typename To::rep>(count, ec);
-  return ec ? To() : To(tocount);
-}
-
-/**
- * safe duration_cast between floating point durations
- */
-template <typename To, typename FromRep, typename FromPeriod,
-          FMT_ENABLE_IF(std::is_floating_point<FromRep>::value),
-          FMT_ENABLE_IF(std::is_floating_point<typename To::rep>::value)>
-To safe_duration_cast(std::chrono::duration<FromRep, FromPeriod> from,
-                      int& ec) {
-  using From = std::chrono::duration<FromRep, FromPeriod>;
-  ec = 0;
-  if (std::isnan(from.count())) {
-    // nan in, gives nan out. easy.
-    return To{std::numeric_limits<typename To::rep>::quiet_NaN()};
-  }
-  // maybe we should also check if from is denormal, and decide what to do about
-  // it.
-
-  // +-inf should be preserved.
-  if (std::isinf(from.count())) {
-    return To{from.count()};
-  }
-
-  // the basic idea is that we need to convert from count() in the from type
-  // to count() in the To type, by multiplying it with this:
-  struct Factor
-      : std::ratio_divide<typename From::period, typename To::period> {};
-
-  static_assert(Factor::num > 0, "num must be positive");
-  static_assert(Factor::den > 0, "den must be positive");
-
-  // the conversion is like this: multiply from.count() with Factor::num
-  // /Factor::den and convert it to To::rep, all this without
-  // overflow/underflow. let's start by finding a suitable type that can hold
-  // both To, From and Factor::num
-  using IntermediateRep =
-      typename std::common_type<typename From::rep, typename To::rep,
-                                decltype(Factor::num)>::type;
-
-  // force conversion of From::rep -> IntermediateRep to be safe,
-  // even if it will never happen be narrowing in this context.
-  IntermediateRep count =
-      safe_float_conversion<IntermediateRep>(from.count(), ec);
-  if (ec) {
-    return {};
-  }
-
-  // multiply with Factor::num without overflow or underflow
-  if (detail::const_check(Factor::num != 1)) {
-    constexpr auto max1 = detail::max_value<IntermediateRep>() /
-                          static_cast<IntermediateRep>(Factor::num);
-    if (count > max1) {
-      ec = 1;
-      return {};
-    }
-    constexpr auto min1 = std::numeric_limits<IntermediateRep>::lowest() /
-                          static_cast<IntermediateRep>(Factor::num);
-    if (count < min1) {
-      ec = 1;
-      return {};
-    }
-    count *= static_cast<IntermediateRep>(Factor::num);
-  }
-
-  // this can't go wrong, right? den>0 is checked earlier.
-  if (detail::const_check(Factor::den != 1)) {
-    using common_t = typename std::common_type<IntermediateRep, intmax_t>::type;
-    count /= static_cast<common_t>(Factor::den);
-  }
-
-  // convert to the to type, safely
-  using ToRep = typename To::rep;
-
-  const ToRep tocount = safe_float_conversion<ToRep>(count, ec);
-  if (ec) {
-    return {};
-  }
-  return To{tocount};
-}
-}  // namespace safe_duration_cast
-#endif
-
-// Prevents expansion of a preceding token as a function-style macro.
-// Usage: f FMT_NOMACRO()
-#define FMT_NOMACRO
-
-namespace detail {
-template <typename T = void> struct null {};
-inline null<> localtime_r FMT_NOMACRO(...) { return null<>(); }
-inline null<> localtime_s(...) { return null<>(); }
-inline null<> gmtime_r(...) { return null<>(); }
-inline null<> gmtime_s(...) { return null<>(); }
-
-inline const std::locale& get_classic_locale() {
-  static const auto& locale = std::locale::classic();
-  return locale;
-}
-
-template <typename CodeUnit> struct codecvt_result {
-  static constexpr const size_t max_size = 32;
-  CodeUnit buf[max_size];
-  CodeUnit* end;
-};
-template <typename CodeUnit>
-constexpr const size_t codecvt_result<CodeUnit>::max_size;
-
-template <typename CodeUnit>
-void write_codecvt(codecvt_result<CodeUnit>& out, string_view in_buf,
-                   const std::locale& loc) {
-  using codecvt = std::codecvt<CodeUnit, char, std::mbstate_t>;
-#if FMT_CLANG_VERSION
-#  pragma clang diagnostic push
-#  pragma clang diagnostic ignored "-Wdeprecated"
-  auto& f = std::use_facet<codecvt>(loc);
-#  pragma clang diagnostic pop
-#else
-  auto& f = std::use_facet<codecvt>(loc);
-#endif
-  auto mb = std::mbstate_t();
-  const char* from_next = nullptr;
-  auto result = f.in(mb, in_buf.begin(), in_buf.end(), from_next,
-                     std::begin(out.buf), std::end(out.buf), out.end);
-  if (result != std::codecvt_base::ok)
-    FMT_THROW(format_error("failed to format time"));
-}
-
-template <typename OutputIt>
-auto write_encoded_tm_str(OutputIt out, string_view in, const std::locale& loc)
-    -> OutputIt {
-  if (detail::is_utf8() && loc != get_classic_locale()) {
-    // char16_t and char32_t codecvts are broken in MSVC (linkage errors) and
-    // gcc-4.
-#if FMT_MSC_VER != 0 || \
-    (defined(__GLIBCXX__) && !defined(_GLIBCXX_USE_DUAL_ABI))
-    // The _GLIBCXX_USE_DUAL_ABI macro is always defined in libstdc++ from gcc-5
-    // and newer.
-    using code_unit = wchar_t;
-#else
-    using code_unit = char32_t;
-#endif
-
-    using unit_t = codecvt_result<code_unit>;
-    unit_t unit;
-    write_codecvt(unit, in, loc);
-    // In UTF-8 is used one to four one-byte code units.
-    auto&& buf = basic_memory_buffer<char, unit_t::max_size * 4>();
-    for (code_unit* p = unit.buf; p != unit.end; ++p) {
-      uint32_t c = static_cast<uint32_t>(*p);
-      if (sizeof(code_unit) == 2 && c >= 0xd800 && c <= 0xdfff) {
-        // surrogate pair
-        ++p;
-        if (p == unit.end || (c & 0xfc00) != 0xd800 ||
-            (*p & 0xfc00) != 0xdc00) {
-          FMT_THROW(format_error("failed to format time"));
-        }
-        c = (c << 10) + static_cast<uint32_t>(*p) - 0x35fdc00;
-      }
-      if (c < 0x80) {
-        buf.push_back(static_cast<char>(c));
-      } else if (c < 0x800) {
-        buf.push_back(static_cast<char>(0xc0 | (c >> 6)));
-        buf.push_back(static_cast<char>(0x80 | (c & 0x3f)));
-      } else if ((c >= 0x800 && c <= 0xd7ff) || (c >= 0xe000 && c <= 0xffff)) {
-        buf.push_back(static_cast<char>(0xe0 | (c >> 12)));
-        buf.push_back(static_cast<char>(0x80 | ((c & 0xfff) >> 6)));
-        buf.push_back(static_cast<char>(0x80 | (c & 0x3f)));
-      } else if (c >= 0x10000 && c <= 0x10ffff) {
-        buf.push_back(static_cast<char>(0xf0 | (c >> 18)));
-        buf.push_back(static_cast<char>(0x80 | ((c & 0x3ffff) >> 12)));
-        buf.push_back(static_cast<char>(0x80 | ((c & 0xfff) >> 6)));
-        buf.push_back(static_cast<char>(0x80 | (c & 0x3f)));
-      } else {
-        FMT_THROW(format_error("failed to format time"));
-      }
-    }
-    return copy_str<char>(buf.data(), buf.data() + buf.size(), out);
-  }
-  return copy_str<char>(in.data(), in.data() + in.size(), out);
-}
-
-template <typename Char, typename OutputIt,
-          FMT_ENABLE_IF(!std::is_same<Char, char>::value)>
-auto write_tm_str(OutputIt out, string_view sv, const std::locale& loc)
-    -> OutputIt {
-  codecvt_result<Char> unit;
-  write_codecvt(unit, sv, loc);
-  return copy_str<Char>(unit.buf, unit.end, out);
-}
-
-template <typename Char, typename OutputIt,
-          FMT_ENABLE_IF(std::is_same<Char, char>::value)>
-auto write_tm_str(OutputIt out, string_view sv, const std::locale& loc)
-    -> OutputIt {
-  return write_encoded_tm_str(out, sv, loc);
-}
-
-template <typename Char>
-inline void do_write(buffer<Char>& buf, const std::tm& time,
-                     const std::locale& loc, char format, char modifier) {
-  auto&& format_buf = formatbuf<std::basic_streambuf<Char>>(buf);
-  auto&& os = std::basic_ostream<Char>(&format_buf);
-  os.imbue(loc);
-  using iterator = std::ostreambuf_iterator<Char>;
-  const auto& facet = std::use_facet<std::time_put<Char, iterator>>(loc);
-  auto end = facet.put(os, os, Char(' '), &time, format, modifier);
-  if (end.failed()) FMT_THROW(format_error("failed to format time"));
-}
-
-template <typename Char, typename OutputIt,
-          FMT_ENABLE_IF(!std::is_same<Char, char>::value)>
-auto write(OutputIt out, const std::tm& time, const std::locale& loc,
-           char format, char modifier = 0) -> OutputIt {
-  auto&& buf = get_buffer<Char>(out);
-  do_write<Char>(buf, time, loc, format, modifier);
-  return buf.out();
-}
-
-template <typename Char, typename OutputIt,
-          FMT_ENABLE_IF(std::is_same<Char, char>::value)>
-auto write(OutputIt out, const std::tm& time, const std::locale& loc,
-           char format, char modifier = 0) -> OutputIt {
-  auto&& buf = basic_memory_buffer<Char>();
-  do_write<char>(buf, time, loc, format, modifier);
-  return write_encoded_tm_str(out, string_view(buf.data(), buf.size()), loc);
-}
-
-}  // namespace detail
-
-FMT_MODULE_EXPORT_BEGIN
-
-/**
-  Converts given time since epoch as ``std::time_t`` value into calendar time,
-  expressed in local time. Unlike ``std::localtime``, this function is
-  thread-safe on most platforms.
- */
-inline std::tm localtime(std::time_t time) {
-  struct dispatcher {
-    std::time_t time_;
-    std::tm tm_;
-
-    dispatcher(std::time_t t) : time_(t) {}
-
-    bool run() {
-      using namespace fmt::detail;
-      return handle(localtime_r(&time_, &tm_));
-    }
-
-    bool handle(std::tm* tm) { return tm != nullptr; }
-
-    bool handle(detail::null<>) {
-      using namespace fmt::detail;
-      return fallback(localtime_s(&tm_, &time_));
-    }
-
-    bool fallback(int res) { return res == 0; }
-
-#if !FMT_MSC_VER
-    bool fallback(detail::null<>) {
-      using namespace fmt::detail;
-      std::tm* tm = std::localtime(&time_);
-      if (tm) tm_ = *tm;
-      return tm != nullptr;
-    }
-#endif
-  };
-  dispatcher lt(time);
-  // Too big time values may be unsupported.
-  if (!lt.run()) FMT_THROW(format_error("time_t value out of range"));
-  return lt.tm_;
-}
-
-inline std::tm localtime(
-    std::chrono::time_point<std::chrono::system_clock> time_point) {
-  return localtime(std::chrono::system_clock::to_time_t(time_point));
-}
-
-/**
-  Converts given time since epoch as ``std::time_t`` value into calendar time,
-  expressed in Coordinated Universal Time (UTC). Unlike ``std::gmtime``, this
-  function is thread-safe on most platforms.
- */
-inline std::tm gmtime(std::time_t time) {
-  struct dispatcher {
-    std::time_t time_;
-    std::tm tm_;
-
-    dispatcher(std::time_t t) : time_(t) {}
-
-    bool run() {
-      using namespace fmt::detail;
-      return handle(gmtime_r(&time_, &tm_));
-    }
-
-    bool handle(std::tm* tm) { return tm != nullptr; }
-
-    bool handle(detail::null<>) {
-      using namespace fmt::detail;
-      return fallback(gmtime_s(&tm_, &time_));
-    }
-
-    bool fallback(int res) { return res == 0; }
-
-#if !FMT_MSC_VER
-    bool fallback(detail::null<>) {
-      std::tm* tm = std::gmtime(&time_);
-      if (tm) tm_ = *tm;
-      return tm != nullptr;
-    }
-#endif
-  };
-  dispatcher gt(time);
-  // Too big time values may be unsupported.
-  if (!gt.run()) FMT_THROW(format_error("time_t value out of range"));
-  return gt.tm_;
-}
-
-inline std::tm gmtime(
-    std::chrono::time_point<std::chrono::system_clock> time_point) {
-  return gmtime(std::chrono::system_clock::to_time_t(time_point));
-}
-
-FMT_BEGIN_DETAIL_NAMESPACE
-
-// Writes two-digit numbers a, b and c separated by sep to buf.
-// The method by Pavel Novikov based on
-// https://johnnylee-sde.github.io/Fast-unsigned-integer-to-time-string/.
-inline void write_digit2_separated(char* buf, unsigned a, unsigned b,
-                                   unsigned c, char sep) {
-  unsigned long long digits =
-      a | (b << 24) | (static_cast<unsigned long long>(c) << 48);
-  // Convert each value to BCD.
-  // We have x = a * 10 + b and we want to convert it to BCD y = a * 16 + b.
-  // The difference is
-  //   y - x = a * 6
-  // a can be found from x:
-  //   a = floor(x / 10)
-  // then
-  //   y = x + a * 6 = x + floor(x / 10) * 6
-  // floor(x / 10) is (x * 205) >> 11 (needs 16 bits).
-  digits += (((digits * 205) >> 11) & 0x000f00000f00000f) * 6;
-  // Put low nibbles to high bytes and high nibbles to low bytes.
-  digits = ((digits & 0x00f00000f00000f0) >> 4) |
-           ((digits & 0x000f00000f00000f) << 8);
-  auto usep = static_cast<unsigned long long>(sep);
-  // Add ASCII '0' to each digit byte and insert separators.
-  digits |= 0x3030003030003030 | (usep << 16) | (usep << 40);
-
-  constexpr const size_t len = 8;
-  if (const_check(is_big_endian())) {
-    char tmp[len];
-    memcpy(tmp, &digits, len);
-    std::reverse_copy(tmp, tmp + len, buf);
-  } else {
-    memcpy(buf, &digits, len);
-  }
-}
-
-template <typename Period> FMT_CONSTEXPR inline const char* get_units() {
-  if (std::is_same<Period, std::atto>::value) return "as";
-  if (std::is_same<Period, std::femto>::value) return "fs";
-  if (std::is_same<Period, std::pico>::value) return "ps";
-  if (std::is_same<Period, std::nano>::value) return "ns";
-  if (std::is_same<Period, std::micro>::value) return "µs";
-  if (std::is_same<Period, std::milli>::value) return "ms";
-  if (std::is_same<Period, std::centi>::value) return "cs";
-  if (std::is_same<Period, std::deci>::value) return "ds";
-  if (std::is_same<Period, std::ratio<1>>::value) return "s";
-  if (std::is_same<Period, std::deca>::value) return "das";
-  if (std::is_same<Period, std::hecto>::value) return "hs";
-  if (std::is_same<Period, std::kilo>::value) return "ks";
-  if (std::is_same<Period, std::mega>::value) return "Ms";
-  if (std::is_same<Period, std::giga>::value) return "Gs";
-  if (std::is_same<Period, std::tera>::value) return "Ts";
-  if (std::is_same<Period, std::peta>::value) return "Ps";
-  if (std::is_same<Period, std::exa>::value) return "Es";
-  if (std::is_same<Period, std::ratio<60>>::value) return "m";
-  if (std::is_same<Period, std::ratio<3600>>::value) return "h";
-  return nullptr;
-}
-
-enum class numeric_system {
-  standard,
-  // Alternative numeric system, e.g. 十二 instead of 12 in ja_JP locale.
-  alternative
-};
-
-// Parses a put_time-like format string and invokes handler actions.
-template <typename Char, typename Handler>
-FMT_CONSTEXPR const Char* parse_chrono_format(const Char* begin,
-                                              const Char* end,
-                                              Handler&& handler) {
-  auto ptr = begin;
-  while (ptr != end) {
-    auto c = *ptr;
-    if (c == '}') break;
-    if (c != '%') {
-      ++ptr;
-      continue;
-    }
-    if (begin != ptr) handler.on_text(begin, ptr);
-    ++ptr;  // consume '%'
-    if (ptr == end) FMT_THROW(format_error("invalid format"));
-    c = *ptr++;
-    switch (c) {
-    case '%':
-      handler.on_text(ptr - 1, ptr);
-      break;
-    case 'n': {
-      const Char newline[] = {'\n'};
-      handler.on_text(newline, newline + 1);
-      break;
-    }
-    case 't': {
-      const Char tab[] = {'\t'};
-      handler.on_text(tab, tab + 1);
-      break;
-    }
-    // Year:
-    case 'Y':
-      handler.on_year(numeric_system::standard);
-      break;
-    case 'y':
-      handler.on_short_year(numeric_system::standard);
-      break;
-    case 'C':
-      handler.on_century(numeric_system::standard);
-      break;
-    case 'G':
-      handler.on_iso_week_based_year();
-      break;
-    case 'g':
-      handler.on_iso_week_based_short_year();
-      break;
-    // Day of the week:
-    case 'a':
-      handler.on_abbr_weekday();
-      break;
-    case 'A':
-      handler.on_full_weekday();
-      break;
-    case 'w':
-      handler.on_dec0_weekday(numeric_system::standard);
-      break;
-    case 'u':
-      handler.on_dec1_weekday(numeric_system::standard);
-      break;
-    // Month:
-    case 'b':
-    case 'h':
-      handler.on_abbr_month();
-      break;
-    case 'B':
-      handler.on_full_month();
-      break;
-    case 'm':
-      handler.on_dec_month(numeric_system::standard);
-      break;
-    // Day of the year/month:
-    case 'U':
-      handler.on_dec0_week_of_year(numeric_system::standard);
-      break;
-    case 'W':
-      handler.on_dec1_week_of_year(numeric_system::standard);
-      break;
-    case 'V':
-      handler.on_iso_week_of_year(numeric_system::standard);
-      break;
-    case 'j':
-      handler.on_day_of_year();
-      break;
-    case 'd':
-      handler.on_day_of_month(numeric_system::standard);
-      break;
-    case 'e':
-      handler.on_day_of_month_space(numeric_system::standard);
-      break;
-    // Hour, minute, second:
-    case 'H':
-      handler.on_24_hour(numeric_system::standard);
-      break;
-    case 'I':
-      handler.on_12_hour(numeric_system::standard);
-      break;
-    case 'M':
-      handler.on_minute(numeric_system::standard);
-      break;
-    case 'S':
-      handler.on_second(numeric_system::standard);
-      break;
-    // Other:
-    case 'c':
-      handler.on_datetime(numeric_system::standard);
-      break;
-    case 'x':
-      handler.on_loc_date(numeric_system::standard);
-      break;
-    case 'X':
-      handler.on_loc_time(numeric_system::standard);
-      break;
-    case 'D':
-      handler.on_us_date();
-      break;
-    case 'F':
-      handler.on_iso_date();
-      break;
-    case 'r':
-      handler.on_12_hour_time();
-      break;
-    case 'R':
-      handler.on_24_hour_time();
-      break;
-    case 'T':
-      handler.on_iso_time();
-      break;
-    case 'p':
-      handler.on_am_pm();
-      break;
-    case 'Q':
-      handler.on_duration_value();
-      break;
-    case 'q':
-      handler.on_duration_unit();
-      break;
-    case 'z':
-      handler.on_utc_offset();
-      break;
-    case 'Z':
-      handler.on_tz_name();
-      break;
-    // Alternative representation:
-    case 'E': {
-      if (ptr == end) FMT_THROW(format_error("invalid format"));
-      c = *ptr++;
-      switch (c) {
-      case 'Y':
-        handler.on_year(numeric_system::alternative);
-        break;
-      case 'y':
-        handler.on_offset_year();
-        break;
-      case 'C':
-        handler.on_century(numeric_system::alternative);
-        break;
-      case 'c':
-        handler.on_datetime(numeric_system::alternative);
-        break;
-      case 'x':
-        handler.on_loc_date(numeric_system::alternative);
-        break;
-      case 'X':
-        handler.on_loc_time(numeric_system::alternative);
-        break;
-      default:
-        FMT_THROW(format_error("invalid format"));
-      }
-      break;
-    }
-    case 'O':
-      if (ptr == end) FMT_THROW(format_error("invalid format"));
-      c = *ptr++;
-      switch (c) {
-      case 'y':
-        handler.on_short_year(numeric_system::alternative);
-        break;
-      case 'm':
-        handler.on_dec_month(numeric_system::alternative);
-        break;
-      case 'U':
-        handler.on_dec0_week_of_year(numeric_system::alternative);
-        break;
-      case 'W':
-        handler.on_dec1_week_of_year(numeric_system::alternative);
-        break;
-      case 'V':
-        handler.on_iso_week_of_year(numeric_system::alternative);
-        break;
-      case 'd':
-        handler.on_day_of_month(numeric_system::alternative);
-        break;
-      case 'e':
-        handler.on_day_of_month_space(numeric_system::alternative);
-        break;
-      case 'w':
-        handler.on_dec0_weekday(numeric_system::alternative);
-        break;
-      case 'u':
-        handler.on_dec1_weekday(numeric_system::alternative);
-        break;
-      case 'H':
-        handler.on_24_hour(numeric_system::alternative);
-        break;
-      case 'I':
-        handler.on_12_hour(numeric_system::alternative);
-        break;
-      case 'M':
-        handler.on_minute(numeric_system::alternative);
-        break;
-      case 'S':
-        handler.on_second(numeric_system::alternative);
-        break;
-      default:
-        FMT_THROW(format_error("invalid format"));
-      }
-      break;
-    default:
-      FMT_THROW(format_error("invalid format"));
-    }
-    begin = ptr;
-  }
-  if (begin != ptr) handler.on_text(begin, ptr);
-  return ptr;
-}
-
-template <typename Derived> struct null_chrono_spec_handler {
-  FMT_CONSTEXPR void unsupported() {
-    static_cast<Derived*>(this)->unsupported();
-  }
-  FMT_CONSTEXPR void on_year(numeric_system) { unsupported(); }
-  FMT_CONSTEXPR void on_short_year(numeric_system) { unsupported(); }
-  FMT_CONSTEXPR void on_offset_year() { unsupported(); }
-  FMT_CONSTEXPR void on_century(numeric_system) { unsupported(); }
-  FMT_CONSTEXPR void on_iso_week_based_year() { unsupported(); }
-  FMT_CONSTEXPR void on_iso_week_based_short_year() { unsupported(); }
-  FMT_CONSTEXPR void on_abbr_weekday() { unsupported(); }
-  FMT_CONSTEXPR void on_full_weekday() { unsupported(); }
-  FMT_CONSTEXPR void on_dec0_weekday(numeric_system) { unsupported(); }
-  FMT_CONSTEXPR void on_dec1_weekday(numeric_system) { unsupported(); }
-  FMT_CONSTEXPR void on_abbr_month() { unsupported(); }
-  FMT_CONSTEXPR void on_full_month() { unsupported(); }
-  FMT_CONSTEXPR void on_dec_month(numeric_system) { unsupported(); }
-  FMT_CONSTEXPR void on_dec0_week_of_year(numeric_system) { unsupported(); }
-  FMT_CONSTEXPR void on_dec1_week_of_year(numeric_system) { unsupported(); }
-  FMT_CONSTEXPR void on_iso_week_of_year(numeric_system) { unsupported(); }
-  FMT_CONSTEXPR void on_day_of_year() { unsupported(); }
-  FMT_CONSTEXPR void on_day_of_month(numeric_system) { unsupported(); }
-  FMT_CONSTEXPR void on_day_of_month_space(numeric_system) { unsupported(); }
-  FMT_CONSTEXPR void on_24_hour(numeric_system) { unsupported(); }
-  FMT_CONSTEXPR void on_12_hour(numeric_system) { unsupported(); }
-  FMT_CONSTEXPR void on_minute(numeric_system) { unsupported(); }
-  FMT_CONSTEXPR void on_second(numeric_system) { unsupported(); }
-  FMT_CONSTEXPR void on_datetime(numeric_system) { unsupported(); }
-  FMT_CONSTEXPR void on_loc_date(numeric_system) { unsupported(); }
-  FMT_CONSTEXPR void on_loc_time(numeric_system) { unsupported(); }
-  FMT_CONSTEXPR void on_us_date() { unsupported(); }
-  FMT_CONSTEXPR void on_iso_date() { unsupported(); }
-  FMT_CONSTEXPR void on_12_hour_time() { unsupported(); }
-  FMT_CONSTEXPR void on_24_hour_time() { unsupported(); }
-  FMT_CONSTEXPR void on_iso_time() { unsupported(); }
-  FMT_CONSTEXPR void on_am_pm() { unsupported(); }
-  FMT_CONSTEXPR void on_duration_value() { unsupported(); }
-  FMT_CONSTEXPR void on_duration_unit() { unsupported(); }
-  FMT_CONSTEXPR void on_utc_offset() { unsupported(); }
-  FMT_CONSTEXPR void on_tz_name() { unsupported(); }
-};
-
-struct tm_format_checker : null_chrono_spec_handler<tm_format_checker> {
-  FMT_NORETURN void unsupported() { FMT_THROW(format_error("no format")); }
-
-  template <typename Char>
-  FMT_CONSTEXPR void on_text(const Char*, const Char*) {}
-  FMT_CONSTEXPR void on_year(numeric_system) {}
-  FMT_CONSTEXPR void on_short_year(numeric_system) {}
-  FMT_CONSTEXPR void on_offset_year() {}
-  FMT_CONSTEXPR void on_century(numeric_system) {}
-  FMT_CONSTEXPR void on_iso_week_based_year() {}
-  FMT_CONSTEXPR void on_iso_week_based_short_year() {}
-  FMT_CONSTEXPR void on_abbr_weekday() {}
-  FMT_CONSTEXPR void on_full_weekday() {}
-  FMT_CONSTEXPR void on_dec0_weekday(numeric_system) {}
-  FMT_CONSTEXPR void on_dec1_weekday(numeric_system) {}
-  FMT_CONSTEXPR void on_abbr_month() {}
-  FMT_CONSTEXPR void on_full_month() {}
-  FMT_CONSTEXPR void on_dec_month(numeric_system) {}
-  FMT_CONSTEXPR void on_dec0_week_of_year(numeric_system) {}
-  FMT_CONSTEXPR void on_dec1_week_of_year(numeric_system) {}
-  FMT_CONSTEXPR void on_iso_week_of_year(numeric_system) {}
-  FMT_CONSTEXPR void on_day_of_year() {}
-  FMT_CONSTEXPR void on_day_of_month(numeric_system) {}
-  FMT_CONSTEXPR void on_day_of_month_space(numeric_system) {}
-  FMT_CONSTEXPR void on_24_hour(numeric_system) {}
-  FMT_CONSTEXPR void on_12_hour(numeric_system) {}
-  FMT_CONSTEXPR void on_minute(numeric_system) {}
-  FMT_CONSTEXPR void on_second(numeric_system) {}
-  FMT_CONSTEXPR void on_datetime(numeric_system) {}
-  FMT_CONSTEXPR void on_loc_date(numeric_system) {}
-  FMT_CONSTEXPR void on_loc_time(numeric_system) {}
-  FMT_CONSTEXPR void on_us_date() {}
-  FMT_CONSTEXPR void on_iso_date() {}
-  FMT_CONSTEXPR void on_12_hour_time() {}
-  FMT_CONSTEXPR void on_24_hour_time() {}
-  FMT_CONSTEXPR void on_iso_time() {}
-  FMT_CONSTEXPR void on_am_pm() {}
-  FMT_CONSTEXPR void on_utc_offset() {}
-  FMT_CONSTEXPR void on_tz_name() {}
-};
-
-inline const char* tm_wday_full_name(int wday) {
-  static constexpr const char* full_name_list[] = {
-      "Sunday",   "Monday", "Tuesday", "Wednesday",
-      "Thursday", "Friday", "Saturday"};
-  return wday >= 0 && wday <= 6 ? full_name_list[wday] : "?";
-}
-inline const char* tm_wday_short_name(int wday) {
-  static constexpr const char* short_name_list[] = {"Sun", "Mon", "Tue", "Wed",
-                                                    "Thu", "Fri", "Sat"};
-  return wday >= 0 && wday <= 6 ? short_name_list[wday] : "???";
-}
-
-inline const char* tm_mon_full_name(int mon) {
-  static constexpr const char* full_name_list[] = {
-      "January", "February", "March",     "April",   "May",      "June",
-      "July",    "August",   "September", "October", "November", "December"};
-  return mon >= 0 && mon <= 11 ? full_name_list[mon] : "?";
-}
-inline const char* tm_mon_short_name(int mon) {
-  static constexpr const char* short_name_list[] = {
-      "Jan", "Feb", "Mar", "Apr", "May", "Jun",
-      "Jul", "Aug", "Sep", "Oct", "Nov", "Dec",
-  };
-  return mon >= 0 && mon <= 11 ? short_name_list[mon] : "???";
-}
-
-template <typename T, typename = void>
-struct has_member_data_tm_gmtoff : std::false_type {};
-template <typename T>
-struct has_member_data_tm_gmtoff<T, void_t<decltype(T::tm_gmtoff)>>
-    : std::true_type {};
-
-template <typename T, typename = void>
-struct has_member_data_tm_zone : std::false_type {};
-template <typename T>
-struct has_member_data_tm_zone<T, void_t<decltype(T::tm_zone)>>
-    : std::true_type {};
-
-#if FMT_USE_TZSET
-inline void tzset_once() {
-  static bool init = []() -> bool {
-    _tzset();
-    return true;
-  }();
-  ignore_unused(init);
-}
-#endif
-
-template <typename OutputIt, typename Char> class tm_writer {
- private:
-  static constexpr int days_per_week = 7;
-
-  const std::locale& loc_;
-  const bool is_classic_;
-  OutputIt out_;
-  const std::tm& tm_;
-
-  auto tm_sec() const noexcept -> int {
-    FMT_ASSERT(tm_.tm_sec >= 0 && tm_.tm_sec <= 61, "");
-    return tm_.tm_sec;
-  }
-  auto tm_min() const noexcept -> int {
-    FMT_ASSERT(tm_.tm_min >= 0 && tm_.tm_min <= 59, "");
-    return tm_.tm_min;
-  }
-  auto tm_hour() const noexcept -> int {
-    FMT_ASSERT(tm_.tm_hour >= 0 && tm_.tm_hour <= 23, "");
-    return tm_.tm_hour;
-  }
-  auto tm_mday() const noexcept -> int {
-    FMT_ASSERT(tm_.tm_mday >= 1 && tm_.tm_mday <= 31, "");
-    return tm_.tm_mday;
-  }
-  auto tm_mon() const noexcept -> int {
-    FMT_ASSERT(tm_.tm_mon >= 0 && tm_.tm_mon <= 11, "");
-    return tm_.tm_mon;
-  }
-  auto tm_year() const noexcept -> long long { return 1900ll + tm_.tm_year; }
-  auto tm_wday() const noexcept -> int {
-    FMT_ASSERT(tm_.tm_wday >= 0 && tm_.tm_wday <= 6, "");
-    return tm_.tm_wday;
-  }
-  auto tm_yday() const noexcept -> int {
-    FMT_ASSERT(tm_.tm_yday >= 0 && tm_.tm_yday <= 365, "");
-    return tm_.tm_yday;
-  }
-
-  auto tm_hour12() const noexcept -> int {
-    const auto h = tm_hour();
-    const auto z = h < 12 ? h : h - 12;
-    return z == 0 ? 12 : z;
-  }
-
-  // POSIX and the C Standard are unclear or inconsistent about what %C and %y
-  // do if the year is negative or exceeds 9999. Use the convention that %C
-  // concatenated with %y yields the same output as %Y, and that %Y contains at
-  // least 4 characters, with more only if necessary.
-  auto split_year_lower(long long year) const noexcept -> int {
-    auto l = year % 100;
-    if (l < 0) l = -l;  // l in [0, 99]
-    return static_cast<int>(l);
-  }
-
-  // Algorithm:
-  // https://en.wikipedia.org/wiki/ISO_week_date#Calculating_the_week_number_from_a_month_and_day_of_the_month_or_ordinal_date
-  auto iso_year_weeks(long long curr_year) const noexcept -> int {
-    const auto prev_year = curr_year - 1;
-    const auto curr_p =
-        (curr_year + curr_year / 4 - curr_year / 100 + curr_year / 400) %
-        days_per_week;
-    const auto prev_p =
-        (prev_year + prev_year / 4 - prev_year / 100 + prev_year / 400) %
-        days_per_week;
-    return 52 + ((curr_p == 4 || prev_p == 3) ? 1 : 0);
-  }
-  auto iso_week_num(int tm_yday, int tm_wday) const noexcept -> int {
-    return (tm_yday + 11 - (tm_wday == 0 ? days_per_week : tm_wday)) /
-           days_per_week;
-  }
-  auto tm_iso_week_year() const noexcept -> long long {
-    const auto year = tm_year();
-    const auto w = iso_week_num(tm_yday(), tm_wday());
-    if (w < 1) return year - 1;
-    if (w > iso_year_weeks(year)) return year + 1;
-    return year;
-  }
-  auto tm_iso_week_of_year() const noexcept -> int {
-    const auto year = tm_year();
-    const auto w = iso_week_num(tm_yday(), tm_wday());
-    if (w < 1) return iso_year_weeks(year - 1);
-    if (w > iso_year_weeks(year)) return 1;
-    return w;
-  }
-
-  void write1(int value) {
-    *out_++ = static_cast<char>('0' + to_unsigned(value) % 10);
-  }
-  void write2(int value) {
-    const char* d = digits2(to_unsigned(value) % 100);
-    *out_++ = *d++;
-    *out_++ = *d;
-  }
-
-  void write_year_extended(long long year) {
-    // At least 4 characters.
-    int width = 4;
-    if (year < 0) {
-      *out_++ = '-';
-      year = 0 - year;
-      --width;
-    }
-    uint32_or_64_or_128_t<long long> n = to_unsigned(year);
-    const int num_digits = count_digits(n);
-    if (width > num_digits) out_ = std::fill_n(out_, width - num_digits, '0');
-    out_ = format_decimal<Char>(out_, n, num_digits).end;
-  }
-  void write_year(long long year) {
-    if (year >= 0 && year < 10000) {
-      write2(static_cast<int>(year / 100));
-      write2(static_cast<int>(year % 100));
-    } else {
-      write_year_extended(year);
-    }
-  }
-
-  void write_utc_offset(long offset) {
-    if (offset < 0) {
-      *out_++ = '-';
-      offset = -offset;
-    } else {
-      *out_++ = '+';
-    }
-    offset /= 60;
-    write2(static_cast<int>(offset / 60));
-    write2(static_cast<int>(offset % 60));
-  }
-  template <typename T, FMT_ENABLE_IF(has_member_data_tm_gmtoff<T>::value)>
-  void format_utc_offset_impl(const T& tm) {
-    write_utc_offset(tm.tm_gmtoff);
-  }
-  template <typename T, FMT_ENABLE_IF(!has_member_data_tm_gmtoff<T>::value)>
-  void format_utc_offset_impl(const T& tm) {
-#if defined(_WIN32) && defined(_UCRT)
-#  if FMT_USE_TZSET
-    tzset_once();
-#  endif
-    long offset = 0;
-    _get_timezone(&offset);
-    if (tm.tm_isdst) {
-      long dstbias = 0;
-      _get_dstbias(&dstbias);
-      offset += dstbias;
-    }
-    write_utc_offset(-offset);
-#else
-    ignore_unused(tm);
-    format_localized('z');
-#endif
-  }
-
-  template <typename T, FMT_ENABLE_IF(has_member_data_tm_zone<T>::value)>
-  void format_tz_name_impl(const T& tm) {
-    if (is_classic_)
-      out_ = write_tm_str<Char>(out_, tm.tm_zone, loc_);
-    else
-      format_localized('Z');
-  }
-  template <typename T, FMT_ENABLE_IF(!has_member_data_tm_zone<T>::value)>
-  void format_tz_name_impl(const T&) {
-    format_localized('Z');
-  }
-
-  void format_localized(char format, char modifier = 0) {
-    out_ = write<Char>(out_, tm_, loc_, format, modifier);
-  }
-
- public:
-  tm_writer(const std::locale& loc, OutputIt out, const std::tm& tm)
-      : loc_(loc),
-        is_classic_(loc_ == get_classic_locale()),
-        out_(out),
-        tm_(tm) {}
-
-  OutputIt out() const { return out_; }
-
-  FMT_CONSTEXPR void on_text(const Char* begin, const Char* end) {
-    out_ = copy_str<Char>(begin, end, out_);
-  }
-
-  void on_abbr_weekday() {
-    if (is_classic_)
-      out_ = write(out_, tm_wday_short_name(tm_wday()));
-    else
-      format_localized('a');
-  }
-  void on_full_weekday() {
-    if (is_classic_)
-      out_ = write(out_, tm_wday_full_name(tm_wday()));
-    else
-      format_localized('A');
-  }
-  void on_dec0_weekday(numeric_system ns) {
-    if (is_classic_ || ns == numeric_system::standard) return write1(tm_wday());
-    format_localized('w', 'O');
-  }
-  void on_dec1_weekday(numeric_system ns) {
-    if (is_classic_ || ns == numeric_system::standard) {
-      auto wday = tm_wday();
-      write1(wday == 0 ? days_per_week : wday);
-    } else {
-      format_localized('u', 'O');
-    }
-  }
-
-  void on_abbr_month() {
-    if (is_classic_)
-      out_ = write(out_, tm_mon_short_name(tm_mon()));
-    else
-      format_localized('b');
-  }
-  void on_full_month() {
-    if (is_classic_)
-      out_ = write(out_, tm_mon_full_name(tm_mon()));
-    else
-      format_localized('B');
-  }
-
-  void on_datetime(numeric_system ns) {
-    if (is_classic_) {
-      on_abbr_weekday();
-      *out_++ = ' ';
-      on_abbr_month();
-      *out_++ = ' ';
-      on_day_of_month_space(numeric_system::standard);
-      *out_++ = ' ';
-      on_iso_time();
-      *out_++ = ' ';
-      on_year(numeric_system::standard);
-    } else {
-      format_localized('c', ns == numeric_system::standard ? '\0' : 'E');
-    }
-  }
-  void on_loc_date(numeric_system ns) {
-    if (is_classic_)
-      on_us_date();
-    else
-      format_localized('x', ns == numeric_system::standard ? '\0' : 'E');
-  }
-  void on_loc_time(numeric_system ns) {
-    if (is_classic_)
-      on_iso_time();
-    else
-      format_localized('X', ns == numeric_system::standard ? '\0' : 'E');
-  }
-  void on_us_date() {
-    char buf[8];
-    write_digit2_separated(buf, to_unsigned(tm_mon() + 1),
-                           to_unsigned(tm_mday()),
-                           to_unsigned(split_year_lower(tm_year())), '/');
-    out_ = copy_str<Char>(std::begin(buf), std::end(buf), out_);
-  }
-  void on_iso_date() {
-    auto year = tm_year();
-    char buf[10];
-    size_t offset = 0;
-    if (year >= 0 && year < 10000) {
-      copy2(buf, digits2(to_unsigned(year / 100)));
-    } else {
-      offset = 4;
-      write_year_extended(year);
-      year = 0;
-    }
-    write_digit2_separated(buf + 2, static_cast<unsigned>(year % 100),
-                           to_unsigned(tm_mon() + 1), to_unsigned(tm_mday()),
-                           '-');
-    out_ = copy_str<Char>(std::begin(buf) + offset, std::end(buf), out_);
-  }
-
-  void on_utc_offset() { format_utc_offset_impl(tm_); }
-  void on_tz_name() { format_tz_name_impl(tm_); }
-
-  void on_year(numeric_system ns) {
-    if (is_classic_ || ns == numeric_system::standard)
-      return write_year(tm_year());
-    format_localized('Y', 'E');
-  }
-  void on_short_year(numeric_system ns) {
-    if (is_classic_ || ns == numeric_system::standard)
-      return write2(split_year_lower(tm_year()));
-    format_localized('y', 'O');
-  }
-  void on_offset_year() {
-    if (is_classic_) return write2(split_year_lower(tm_year()));
-    format_localized('y', 'E');
-  }
-
-  void on_century(numeric_system ns) {
-    if (is_classic_ || ns == numeric_system::standard) {
-      auto year = tm_year();
-      auto upper = year / 100;
-      if (year >= -99 && year < 0) {
-        // Zero upper on negative year.
-        *out_++ = '-';
-        *out_++ = '0';
-      } else if (upper >= 0 && upper < 100) {
-        write2(static_cast<int>(upper));
-      } else {
-        out_ = write<Char>(out_, upper);
-      }
-    } else {
-      format_localized('C', 'E');
-    }
-  }
-
-  void on_dec_month(numeric_system ns) {
-    if (is_classic_ || ns == numeric_system::standard)
-      return write2(tm_mon() + 1);
-    format_localized('m', 'O');
-  }
-
-  void on_dec0_week_of_year(numeric_system ns) {
-    if (is_classic_ || ns == numeric_system::standard)
-      return write2((tm_yday() + days_per_week - tm_wday()) / days_per_week);
-    format_localized('U', 'O');
-  }
-  void on_dec1_week_of_year(numeric_system ns) {
-    if (is_classic_ || ns == numeric_system::standard) {
-      auto wday = tm_wday();
-      write2((tm_yday() + days_per_week -
-              (wday == 0 ? (days_per_week - 1) : (wday - 1))) /
-             days_per_week);
-    } else {
-      format_localized('W', 'O');
-    }
-  }
-  void on_iso_week_of_year(numeric_system ns) {
-    if (is_classic_ || ns == numeric_system::standard)
-      return write2(tm_iso_week_of_year());
-    format_localized('V', 'O');
-  }
-
-  void on_iso_week_based_year() { write_year(tm_iso_week_year()); }
-  void on_iso_week_based_short_year() {
-    write2(split_year_lower(tm_iso_week_year()));
-  }
-
-  void on_day_of_year() {
-    auto yday = tm_yday() + 1;
-    write1(yday / 100);
-    write2(yday % 100);
-  }
-  void on_day_of_month(numeric_system ns) {
-    if (is_classic_ || ns == numeric_system::standard) return write2(tm_mday());
-    format_localized('d', 'O');
-  }
-  void on_day_of_month_space(numeric_system ns) {
-    if (is_classic_ || ns == numeric_system::standard) {
-      auto mday = to_unsigned(tm_mday()) % 100;
-      const char* d2 = digits2(mday);
-      *out_++ = mday < 10 ? ' ' : d2[0];
-      *out_++ = d2[1];
-    } else {
-      format_localized('e', 'O');
-    }
-  }
-
-  void on_24_hour(numeric_system ns) {
-    if (is_classic_ || ns == numeric_system::standard) return write2(tm_hour());
-    format_localized('H', 'O');
-  }
-  void on_12_hour(numeric_system ns) {
-    if (is_classic_ || ns == numeric_system::standard)
-      return write2(tm_hour12());
-    format_localized('I', 'O');
-  }
-  void on_minute(numeric_system ns) {
-    if (is_classic_ || ns == numeric_system::standard) return write2(tm_min());
-    format_localized('M', 'O');
-  }
-  void on_second(numeric_system ns) {
-    if (is_classic_ || ns == numeric_system::standard) return write2(tm_sec());
-    format_localized('S', 'O');
-  }
-
-  void on_12_hour_time() {
-    if (is_classic_) {
-      char buf[8];
-      write_digit2_separated(buf, to_unsigned(tm_hour12()),
-                             to_unsigned(tm_min()), to_unsigned(tm_sec()), ':');
-      out_ = copy_str<Char>(std::begin(buf), std::end(buf), out_);
-      *out_++ = ' ';
-      on_am_pm();
-    } else {
-      format_localized('r');
-    }
-  }
-  void on_24_hour_time() {
-    write2(tm_hour());
-    *out_++ = ':';
-    write2(tm_min());
-  }
-  void on_iso_time() {
-    char buf[8];
-    write_digit2_separated(buf, to_unsigned(tm_hour()), to_unsigned(tm_min()),
-                           to_unsigned(tm_sec()), ':');
-    out_ = copy_str<Char>(std::begin(buf), std::end(buf), out_);
-  }
-
-  void on_am_pm() {
-    if (is_classic_) {
-      *out_++ = tm_hour() < 12 ? 'A' : 'P';
-      *out_++ = 'M';
-    } else {
-      format_localized('p');
-    }
-  }
-
-  // These apply to chrono durations but not tm.
-  void on_duration_value() {}
-  void on_duration_unit() {}
-};
-
-struct chrono_format_checker : null_chrono_spec_handler<chrono_format_checker> {
-  FMT_NORETURN void unsupported() { FMT_THROW(format_error("no date")); }
-
-  template <typename Char>
-  FMT_CONSTEXPR void on_text(const Char*, const Char*) {}
-  FMT_CONSTEXPR void on_24_hour(numeric_system) {}
-  FMT_CONSTEXPR void on_12_hour(numeric_system) {}
-  FMT_CONSTEXPR void on_minute(numeric_system) {}
-  FMT_CONSTEXPR void on_second(numeric_system) {}
-  FMT_CONSTEXPR void on_12_hour_time() {}
-  FMT_CONSTEXPR void on_24_hour_time() {}
-  FMT_CONSTEXPR void on_iso_time() {}
-  FMT_CONSTEXPR void on_am_pm() {}
-  FMT_CONSTEXPR void on_duration_value() {}
-  FMT_CONSTEXPR void on_duration_unit() {}
-};
-
-template <typename T, FMT_ENABLE_IF(std::is_integral<T>::value)>
-inline bool isnan(T) {
-  return false;
-}
-template <typename T, FMT_ENABLE_IF(std::is_floating_point<T>::value)>
-inline bool isnan(T value) {
-  return std::isnan(value);
-}
-
-template <typename T, FMT_ENABLE_IF(std::is_integral<T>::value)>
-inline bool isfinite(T) {
-  return true;
-}
-
-// Converts value to Int and checks that it's in the range [0, upper).
-template <typename T, typename Int, FMT_ENABLE_IF(std::is_integral<T>::value)>
-inline Int to_nonnegative_int(T value, Int upper) {
-  FMT_ASSERT(value >= 0 && to_unsigned(value) <= to_unsigned(upper),
-             "invalid value");
-  (void)upper;
-  return static_cast<Int>(value);
-}
-template <typename T, typename Int, FMT_ENABLE_IF(!std::is_integral<T>::value)>
-inline Int to_nonnegative_int(T value, Int upper) {
-  if (value < 0 || value > static_cast<T>(upper))
-    FMT_THROW(format_error("invalid value"));
-  return static_cast<Int>(value);
-}
-
-template <typename T, FMT_ENABLE_IF(std::is_integral<T>::value)>
-inline T mod(T x, int y) {
-  return x % static_cast<T>(y);
-}
-template <typename T, FMT_ENABLE_IF(std::is_floating_point<T>::value)>
-inline T mod(T x, int y) {
-  return std::fmod(x, static_cast<T>(y));
-}
-
-// If T is an integral type, maps T to its unsigned counterpart, otherwise
-// leaves it unchanged (unlike std::make_unsigned).
-template <typename T, bool INTEGRAL = std::is_integral<T>::value>
-struct make_unsigned_or_unchanged {
-  using type = T;
-};
-
-template <typename T> struct make_unsigned_or_unchanged<T, true> {
-  using type = typename std::make_unsigned<T>::type;
-};
-
-#if FMT_SAFE_DURATION_CAST
-// throwing version of safe_duration_cast
-template <typename To, typename FromRep, typename FromPeriod>
-To fmt_safe_duration_cast(std::chrono::duration<FromRep, FromPeriod> from) {
-  int ec;
-  To to = safe_duration_cast::safe_duration_cast<To>(from, ec);
-  if (ec) FMT_THROW(format_error("cannot format duration"));
-  return to;
-}
-#endif
-
-template <typename Rep, typename Period,
-          FMT_ENABLE_IF(std::is_integral<Rep>::value)>
-inline std::chrono::duration<Rep, std::milli> get_milliseconds(
-    std::chrono::duration<Rep, Period> d) {
-  // this may overflow and/or the result may not fit in the
-  // target type.
-#if FMT_SAFE_DURATION_CAST
-  using CommonSecondsType =
-      typename std::common_type<decltype(d), std::chrono::seconds>::type;
-  const auto d_as_common = fmt_safe_duration_cast<CommonSecondsType>(d);
-  const auto d_as_whole_seconds =
-      fmt_safe_duration_cast<std::chrono::seconds>(d_as_common);
-  // this conversion should be nonproblematic
-  const auto diff = d_as_common - d_as_whole_seconds;
-  const auto ms =
-      fmt_safe_duration_cast<std::chrono::duration<Rep, std::milli>>(diff);
-  return ms;
-#else
-  auto s = std::chrono::duration_cast<std::chrono::seconds>(d);
-  return std::chrono::duration_cast<std::chrono::milliseconds>(d - s);
-#endif
-}
-
-// Returns the number of fractional digits in the range [0, 18] according to the
-// C++20 spec. If more than 18 fractional digits are required then returns 6 for
-// microseconds precision.
-constexpr int count_fractional_digits(long long num, long long den, int n = 0) {
-  return num % den == 0
-             ? n
-             : (n > 18 ? 6 : count_fractional_digits(num * 10, den, n + 1));
-}
-
-constexpr long long pow10(std::uint32_t n) {
-  return n == 0 ? 1 : 10 * pow10(n - 1);
-}
-
-template <class Rep, class Period,
-          FMT_ENABLE_IF(std::numeric_limits<Rep>::is_signed)>
-constexpr std::chrono::duration<Rep, Period> abs(
-    std::chrono::duration<Rep, Period> d) {
-  // We need to compare the duration using the count() method directly
-  // due to a compiler bug in clang-11 regarding the spaceship operator,
-  // when -Wzero-as-null-pointer-constant is enabled.
-  // In clang-12 the bug has been fixed. See
-  // https://bugs.llvm.org/show_bug.cgi?id=46235 and the reproducible example:
-  // https://www.godbolt.org/z/Knbb5joYx.
-  return d.count() >= d.zero().count() ? d : -d;
-}
-
-template <class Rep, class Period,
-          FMT_ENABLE_IF(!std::numeric_limits<Rep>::is_signed)>
-constexpr std::chrono::duration<Rep, Period> abs(
-    std::chrono::duration<Rep, Period> d) {
-  return d;
-}
-
-template <typename Char, typename Rep, typename OutputIt,
-          FMT_ENABLE_IF(std::is_integral<Rep>::value)>
-OutputIt format_duration_value(OutputIt out, Rep val, int) {
-  return write<Char>(out, val);
-}
-
-template <typename Char, typename Rep, typename OutputIt,
-          FMT_ENABLE_IF(std::is_floating_point<Rep>::value)>
-OutputIt format_duration_value(OutputIt out, Rep val, int precision) {
-  auto specs = basic_format_specs<Char>();
-  specs.precision = precision;
-  specs.type = precision >= 0 ? presentation_type::fixed_lower
-                              : presentation_type::general_lower;
-  return write<Char>(out, val, specs);
-}
-
-template <typename Char, typename OutputIt>
-OutputIt copy_unit(string_view unit, OutputIt out, Char) {
-  return std::copy(unit.begin(), unit.end(), out);
-}
-
-template <typename OutputIt>
-OutputIt copy_unit(string_view unit, OutputIt out, wchar_t) {
-  // This works when wchar_t is UTF-32 because units only contain characters
-  // that have the same representation in UTF-16 and UTF-32.
-  utf8_to_utf16 u(unit);
-  return std::copy(u.c_str(), u.c_str() + u.size(), out);
-}
-
-template <typename Char, typename Period, typename OutputIt>
-OutputIt format_duration_unit(OutputIt out) {
-  if (const char* unit = get_units<Period>())
-    return copy_unit(string_view(unit), out, Char());
-  *out++ = '[';
-  out = write<Char>(out, Period::num);
-  if (const_check(Period::den != 1)) {
-    *out++ = '/';
-    out = write<Char>(out, Period::den);
-  }
-  *out++ = ']';
-  *out++ = 's';
-  return out;
-}
-
-class get_locale {
- private:
-  union {
-    std::locale locale_;
-  };
-  bool has_locale_ = false;
-
- public:
-  get_locale(bool localized, locale_ref loc) : has_locale_(localized) {
-    if (localized)
-      ::new (&locale_) std::locale(loc.template get<std::locale>());
-  }
-  ~get_locale() {
-    if (has_locale_) locale_.~locale();
-  }
-  operator const std::locale&() const {
-    return has_locale_ ? locale_ : get_classic_locale();
-  }
-};
-
-template <typename FormatContext, typename OutputIt, typename Rep,
-          typename Period>
-struct chrono_formatter {
-  FormatContext& context;
-  OutputIt out;
-  int precision;
-  bool localized = false;
-  // rep is unsigned to avoid overflow.
-  using rep =
-      conditional_t<std::is_integral<Rep>::value && sizeof(Rep) < sizeof(int),
-                    unsigned, typename make_unsigned_or_unchanged<Rep>::type>;
-  rep val;
-  using seconds = std::chrono::duration<rep>;
-  seconds s;
-  using milliseconds = std::chrono::duration<rep, std::milli>;
-  bool negative;
-
-  using char_type = typename FormatContext::char_type;
-  using tm_writer_type = tm_writer<OutputIt, char_type>;
-
-  chrono_formatter(FormatContext& ctx, OutputIt o,
-                   std::chrono::duration<Rep, Period> d)
-      : context(ctx),
-        out(o),
-        val(static_cast<rep>(d.count())),
-        negative(false) {
-    if (d.count() < 0) {
-      val = 0 - val;
-      negative = true;
-    }
-
-    // this may overflow and/or the result may not fit in the
-    // target type.
-#if FMT_SAFE_DURATION_CAST
-    // might need checked conversion (rep!=Rep)
-    auto tmpval = std::chrono::duration<rep, Period>(val);
-    s = fmt_safe_duration_cast<seconds>(tmpval);
-#else
-    s = std::chrono::duration_cast<seconds>(
-        std::chrono::duration<rep, Period>(val));
-#endif
-  }
-
-  // returns true if nan or inf, writes to out.
-  bool handle_nan_inf() {
-    if (isfinite(val)) {
-      return false;
-    }
-    if (isnan(val)) {
-      write_nan();
-      return true;
-    }
-    // must be +-inf
-    if (val > 0) {
-      write_pinf();
-    } else {
-      write_ninf();
-    }
-    return true;
-  }
-
-  Rep hour() const { return static_cast<Rep>(mod((s.count() / 3600), 24)); }
-
-  Rep hour12() const {
-    Rep hour = static_cast<Rep>(mod((s.count() / 3600), 12));
-    return hour <= 0 ? 12 : hour;
-  }
-
-  Rep minute() const { return static_cast<Rep>(mod((s.count() / 60), 60)); }
-  Rep second() const { return static_cast<Rep>(mod(s.count(), 60)); }
-
-  std::tm time() const {
-    auto time = std::tm();
-    time.tm_hour = to_nonnegative_int(hour(), 24);
-    time.tm_min = to_nonnegative_int(minute(), 60);
-    time.tm_sec = to_nonnegative_int(second(), 60);
-    return time;
-  }
-
-  void write_sign() {
-    if (negative) {
-      *out++ = '-';
-      negative = false;
-    }
-  }
-
-  void write(Rep value, int width) {
-    write_sign();
-    if (isnan(value)) return write_nan();
-    uint32_or_64_or_128_t<int> n =
-        to_unsigned(to_nonnegative_int(value, max_value<int>()));
-    int num_digits = detail::count_digits(n);
-    if (width > num_digits) out = std::fill_n(out, width - num_digits, '0');
-    out = format_decimal<char_type>(out, n, num_digits).end;
-  }
-
-  template <class Duration> void write_fractional_seconds(Duration d) {
-    constexpr auto num_fractional_digits =
-        count_fractional_digits(Duration::period::num, Duration::period::den);
-
-    using subsecond_precision = std::chrono::duration<
-        typename std::common_type<typename Duration::rep,
-                                  std::chrono::seconds::rep>::type,
-        std::ratio<1, detail::pow10(num_fractional_digits)>>;
-    if (std::ratio_less<typename subsecond_precision::period,
-                        std::chrono::seconds::period>::value) {
-      *out++ = '.';
-      // Don't convert long double to integer seconds to avoid overflow.
-      using sec = conditional_t<
-          std::is_same<typename Duration::rep, long double>::value,
-          std::chrono::duration<long double>, std::chrono::seconds>;
-      auto fractional = detail::abs(d) - std::chrono::duration_cast<sec>(d);
-      const auto subseconds =
-          std::chrono::treat_as_floating_point<
-              typename subsecond_precision::rep>::value
-              ? fractional.count()
-              : std::chrono::duration_cast<subsecond_precision>(fractional)
-                    .count();
-      uint32_or_64_or_128_t<long long> n =
-          to_unsigned(to_nonnegative_int(subseconds, max_value<long long>()));
-      int num_digits = detail::count_digits(n);
-      if (num_fractional_digits > num_digits)
-        out = std::fill_n(out, num_fractional_digits - num_digits, '0');
-      out = format_decimal<char_type>(out, n, num_digits).end;
-    }
-  }
-
-  void write_nan() { std::copy_n("nan", 3, out); }
-  void write_pinf() { std::copy_n("inf", 3, out); }
-  void write_ninf() { std::copy_n("-inf", 4, out); }
-
-  template <typename Callback, typename... Args>
-  void format_tm(const tm& time, Callback cb, Args... args) {
-    if (isnan(val)) return write_nan();
-    get_locale loc(localized, context.locale());
-    auto w = tm_writer_type(loc, out, time);
-    (w.*cb)(args...);
-    out = w.out();
-  }
-
-  void on_text(const char_type* begin, const char_type* end) {
-    std::copy(begin, end, out);
-  }
-
-  // These are not implemented because durations don't have date information.
-  void on_abbr_weekday() {}
-  void on_full_weekday() {}
-  void on_dec0_weekday(numeric_system) {}
-  void on_dec1_weekday(numeric_system) {}
-  void on_abbr_month() {}
-  void on_full_month() {}
-  void on_datetime(numeric_system) {}
-  void on_loc_date(numeric_system) {}
-  void on_loc_time(numeric_system) {}
-  void on_us_date() {}
-  void on_iso_date() {}
-  void on_utc_offset() {}
-  void on_tz_name() {}
-  void on_year(numeric_system) {}
-  void on_short_year(numeric_system) {}
-  void on_offset_year() {}
-  void on_century(numeric_system) {}
-  void on_iso_week_based_year() {}
-  void on_iso_week_based_short_year() {}
-  void on_dec_month(numeric_system) {}
-  void on_dec0_week_of_year(numeric_system) {}
-  void on_dec1_week_of_year(numeric_system) {}
-  void on_iso_week_of_year(numeric_system) {}
-  void on_day_of_year() {}
-  void on_day_of_month(numeric_system) {}
-  void on_day_of_month_space(numeric_system) {}
-
-  void on_24_hour(numeric_system ns) {
-    if (handle_nan_inf()) return;
-
-    if (ns == numeric_system::standard) return write(hour(), 2);
-    auto time = tm();
-    time.tm_hour = to_nonnegative_int(hour(), 24);
-    format_tm(time, &tm_writer_type::on_24_hour, ns);
-  }
-
-  void on_12_hour(numeric_system ns) {
-    if (handle_nan_inf()) return;
-
-    if (ns == numeric_system::standard) return write(hour12(), 2);
-    auto time = tm();
-    time.tm_hour = to_nonnegative_int(hour12(), 12);
-    format_tm(time, &tm_writer_type::on_12_hour, ns);
-  }
-
-  void on_minute(numeric_system ns) {
-    if (handle_nan_inf()) return;
-
-    if (ns == numeric_system::standard) return write(minute(), 2);
-    auto time = tm();
-    time.tm_min = to_nonnegative_int(minute(), 60);
-    format_tm(time, &tm_writer_type::on_minute, ns);
-  }
-
-  void on_second(numeric_system ns) {
-    if (handle_nan_inf()) return;
-
-    if (ns == numeric_system::standard) {
-      write(second(), 2);
-      write_fractional_seconds(std::chrono::duration<rep, Period>{val});
-      return;
-    }
-    auto time = tm();
-    time.tm_sec = to_nonnegative_int(second(), 60);
-    format_tm(time, &tm_writer_type::on_second, ns);
-  }
-
-  void on_12_hour_time() {
-    if (handle_nan_inf()) return;
-    format_tm(time(), &tm_writer_type::on_12_hour_time);
-  }
-
-  void on_24_hour_time() {
-    if (handle_nan_inf()) {
-      *out++ = ':';
-      handle_nan_inf();
-      return;
-    }
-
-    write(hour(), 2);
-    *out++ = ':';
-    write(minute(), 2);
-  }
-
-  void on_iso_time() {
-    on_24_hour_time();
-    *out++ = ':';
-    if (handle_nan_inf()) return;
-    on_second(numeric_system::standard);
-  }
-
-  void on_am_pm() {
-    if (handle_nan_inf()) return;
-    format_tm(time(), &tm_writer_type::on_am_pm);
-  }
-
-  void on_duration_value() {
-    if (handle_nan_inf()) return;
-    write_sign();
-    out = format_duration_value<char_type>(out, val, precision);
-  }
-
-  void on_duration_unit() {
-    out = format_duration_unit<char_type, Period>(out);
-  }
-};
-
-FMT_END_DETAIL_NAMESPACE
-
-#if defined(__cpp_lib_chrono) && __cpp_lib_chrono >= 201907
-using weekday = std::chrono::weekday;
-#else
-// A fallback version of weekday.
-class weekday {
- private:
-  unsigned char value;
-
- public:
-  weekday() = default;
-  explicit constexpr weekday(unsigned wd) noexcept
-      : value(static_cast<unsigned char>(wd != 7 ? wd : 0)) {}
-  constexpr unsigned c_encoding() const noexcept { return value; }
-};
-
-class year_month_day {};
-#endif
-
-// A rudimentary weekday formatter.
-template <typename Char> struct formatter<weekday, Char> {
- private:
-  bool localized = false;
-
- public:
-  FMT_CONSTEXPR auto parse(basic_format_parse_context<Char>& ctx)
-      -> decltype(ctx.begin()) {
-    auto begin = ctx.begin(), end = ctx.end();
-    if (begin != end && *begin == 'L') {
-      ++begin;
-      localized = true;
-    }
-    return begin;
-  }
-
-  template <typename FormatContext>
-  auto format(weekday wd, FormatContext& ctx) const -> decltype(ctx.out()) {
-    auto time = std::tm();
-    time.tm_wday = static_cast<int>(wd.c_encoding());
-    detail::get_locale loc(localized, ctx.locale());
-    auto w = detail::tm_writer<decltype(ctx.out()), Char>(loc, ctx.out(), time);
-    w.on_abbr_weekday();
-    return w.out();
-  }
-};
-
-template <typename Rep, typename Period, typename Char>
-struct formatter<std::chrono::duration<Rep, Period>, Char> {
- private:
-  basic_format_specs<Char> specs;
-  int precision = -1;
-  using arg_ref_type = detail::arg_ref<Char>;
-  arg_ref_type width_ref;
-  arg_ref_type precision_ref;
-  bool localized = false;
-  basic_string_view<Char> format_str;
-  using duration = std::chrono::duration<Rep, Period>;
-
-  struct spec_handler {
-    formatter& f;
-    basic_format_parse_context<Char>& context;
-    basic_string_view<Char> format_str;
-
-    template <typename Id> FMT_CONSTEXPR arg_ref_type make_arg_ref(Id arg_id) {
-      context.check_arg_id(arg_id);
-      return arg_ref_type(arg_id);
-    }
-
-    FMT_CONSTEXPR arg_ref_type make_arg_ref(basic_string_view<Char> arg_id) {
-      context.check_arg_id(arg_id);
-      return arg_ref_type(arg_id);
-    }
-
-    FMT_CONSTEXPR arg_ref_type make_arg_ref(detail::auto_id) {
-      return arg_ref_type(context.next_arg_id());
-    }
-
-    void on_error(const char* msg) { FMT_THROW(format_error(msg)); }
-    FMT_CONSTEXPR void on_fill(basic_string_view<Char> fill) {
-      f.specs.fill = fill;
-    }
-    FMT_CONSTEXPR void on_align(align_t align) { f.specs.align = align; }
-    FMT_CONSTEXPR void on_width(int width) { f.specs.width = width; }
-    FMT_CONSTEXPR void on_precision(int _precision) {
-      f.precision = _precision;
-    }
-    FMT_CONSTEXPR void end_precision() {}
-
-    template <typename Id> FMT_CONSTEXPR void on_dynamic_width(Id arg_id) {
-      f.width_ref = make_arg_ref(arg_id);
-    }
-
-    template <typename Id> FMT_CONSTEXPR void on_dynamic_precision(Id arg_id) {
-      f.precision_ref = make_arg_ref(arg_id);
-    }
-  };
-
-  using iterator = typename basic_format_parse_context<Char>::iterator;
-  struct parse_range {
-    iterator begin;
-    iterator end;
-  };
-
-  FMT_CONSTEXPR parse_range do_parse(basic_format_parse_context<Char>& ctx) {
-    auto begin = ctx.begin(), end = ctx.end();
-    if (begin == end || *begin == '}') return {begin, begin};
-    spec_handler handler{*this, ctx, format_str};
-    begin = detail::parse_align(begin, end, handler);
-    if (begin == end) return {begin, begin};
-    begin = detail::parse_width(begin, end, handler);
-    if (begin == end) return {begin, begin};
-    if (*begin == '.') {
-      if (std::is_floating_point<Rep>::value)
-        begin = detail::parse_precision(begin, end, handler);
-      else
-        handler.on_error("precision not allowed for this argument type");
-    }
-    if (begin != end && *begin == 'L') {
-      ++begin;
-      localized = true;
-    }
-    end = detail::parse_chrono_format(begin, end,
-                                      detail::chrono_format_checker());
-    return {begin, end};
-  }
-
- public:
-  FMT_CONSTEXPR auto parse(basic_format_parse_context<Char>& ctx)
-      -> decltype(ctx.begin()) {
-    auto range = do_parse(ctx);
-    format_str = basic_string_view<Char>(
-        &*range.begin, detail::to_unsigned(range.end - range.begin));
-    return range.end;
-  }
-
-  template <typename FormatContext>
-  auto format(const duration& d, FormatContext& ctx) const
-      -> decltype(ctx.out()) {
-    auto specs_copy = specs;
-    auto precision_copy = precision;
-    auto begin = format_str.begin(), end = format_str.end();
-    // As a possible future optimization, we could avoid extra copying if width
-    // is not specified.
-    basic_memory_buffer<Char> buf;
-    auto out = std::back_inserter(buf);
-    detail::handle_dynamic_spec<detail::width_checker>(specs_copy.width,
-                                                       width_ref, ctx);
-    detail::handle_dynamic_spec<detail::precision_checker>(precision_copy,
-                                                           precision_ref, ctx);
-    if (begin == end || *begin == '}') {
-      out = detail::format_duration_value<Char>(out, d.count(), precision_copy);
-      detail::format_duration_unit<Char, Period>(out);
-    } else {
-      detail::chrono_formatter<FormatContext, decltype(out), Rep, Period> f(
-          ctx, out, d);
-      f.precision = precision_copy;
-      f.localized = localized;
-      detail::parse_chrono_format(begin, end, f);
-    }
-    return detail::write(
-        ctx.out(), basic_string_view<Char>(buf.data(), buf.size()), specs_copy);
-  }
-};
-
-template <typename Char, typename Duration>
-struct formatter<std::chrono::time_point<std::chrono::system_clock, Duration>,
-                 Char> : formatter<std::tm, Char> {
-  FMT_CONSTEXPR formatter() {
-    this->do_parse(default_specs,
-                   default_specs + sizeof(default_specs) / sizeof(Char));
-  }
-
-  template <typename ParseContext>
-  FMT_CONSTEXPR auto parse(ParseContext& ctx) -> decltype(ctx.begin()) {
-    return this->do_parse(ctx.begin(), ctx.end(), true);
-  }
-
-  template <typename FormatContext>
-  auto format(std::chrono::time_point<std::chrono::system_clock> val,
-              FormatContext& ctx) const -> decltype(ctx.out()) {
-    return formatter<std::tm, Char>::format(localtime(val), ctx);
-  }
-
-  static constexpr const Char default_specs[] = {'%', 'F', ' ', '%', 'T'};
-};
-
-template <typename Char, typename Duration>
-constexpr const Char
-    formatter<std::chrono::time_point<std::chrono::system_clock, Duration>,
-              Char>::default_specs[];
-
-template <typename Char> struct formatter<std::tm, Char> {
- private:
-  enum class spec {
-    unknown,
-    year_month_day,
-    hh_mm_ss,
-  };
-  spec spec_ = spec::unknown;
-  basic_string_view<Char> specs;
-
- protected:
-  template <typename It>
-  FMT_CONSTEXPR auto do_parse(It begin, It end, bool with_default = false)
-      -> It {
-    if (begin != end && *begin == ':') ++begin;
-    end = detail::parse_chrono_format(begin, end, detail::tm_format_checker());
-    if (!with_default || end != begin)
-      specs = {begin, detail::to_unsigned(end - begin)};
-    // basic_string_view<>::compare isn't constexpr before C++17.
-    if (specs.size() == 2 && specs[0] == Char('%')) {
-      if (specs[1] == Char('F'))
-        spec_ = spec::year_month_day;
-      else if (specs[1] == Char('T'))
-        spec_ = spec::hh_mm_ss;
-    }
-    return end;
-  }
-
- public:
-  template <typename ParseContext>
-  FMT_CONSTEXPR auto parse(ParseContext& ctx) -> decltype(ctx.begin()) {
-    return this->do_parse(ctx.begin(), ctx.end());
-  }
-
-  template <typename FormatContext>
-  auto format(const std::tm& tm, FormatContext& ctx) const
-      -> decltype(ctx.out()) {
-    const auto loc_ref = ctx.locale();
-    detail::get_locale loc(static_cast<bool>(loc_ref), loc_ref);
-    auto w = detail::tm_writer<decltype(ctx.out()), Char>(loc, ctx.out(), tm);
-    if (spec_ == spec::year_month_day)
-      w.on_iso_date();
-    else if (spec_ == spec::hh_mm_ss)
-      w.on_iso_time();
-    else
-      detail::parse_chrono_format(specs.begin(), specs.end(), w);
-    return w.out();
-  }
-};
-
-FMT_MODULE_EXPORT_END
-FMT_END_NAMESPACE
-
-#endif  // FMT_CHRONO_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/color.h b/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/color.h
deleted file mode 100644
index dfbe482..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/color.h
+++ /dev/null
@@ -1,638 +0,0 @@
-// Formatting library for C++ - color support
-//
-// Copyright (c) 2018 - present, Victor Zverovich and fmt contributors
-// All rights reserved.
-//
-// For the license information refer to format.h.
-
-#ifndef FMT_COLOR_H_
-#define FMT_COLOR_H_
-
-#include "format.h"
-
-// __declspec(deprecated) is broken in some MSVC versions.
-#if FMT_MSC_VER
-#  define FMT_DEPRECATED_NONMSVC
-#else
-#  define FMT_DEPRECATED_NONMSVC FMT_DEPRECATED
-#endif
-
-FMT_BEGIN_NAMESPACE
-FMT_MODULE_EXPORT_BEGIN
-
-enum class color : uint32_t {
-  alice_blue = 0xF0F8FF,               // rgb(240,248,255)
-  antique_white = 0xFAEBD7,            // rgb(250,235,215)
-  aqua = 0x00FFFF,                     // rgb(0,255,255)
-  aquamarine = 0x7FFFD4,               // rgb(127,255,212)
-  azure = 0xF0FFFF,                    // rgb(240,255,255)
-  beige = 0xF5F5DC,                    // rgb(245,245,220)
-  bisque = 0xFFE4C4,                   // rgb(255,228,196)
-  black = 0x000000,                    // rgb(0,0,0)
-  blanched_almond = 0xFFEBCD,          // rgb(255,235,205)
-  blue = 0x0000FF,                     // rgb(0,0,255)
-  blue_violet = 0x8A2BE2,              // rgb(138,43,226)
-  brown = 0xA52A2A,                    // rgb(165,42,42)
-  burly_wood = 0xDEB887,               // rgb(222,184,135)
-  cadet_blue = 0x5F9EA0,               // rgb(95,158,160)
-  chartreuse = 0x7FFF00,               // rgb(127,255,0)
-  chocolate = 0xD2691E,                // rgb(210,105,30)
-  coral = 0xFF7F50,                    // rgb(255,127,80)
-  cornflower_blue = 0x6495ED,          // rgb(100,149,237)
-  cornsilk = 0xFFF8DC,                 // rgb(255,248,220)
-  crimson = 0xDC143C,                  // rgb(220,20,60)
-  cyan = 0x00FFFF,                     // rgb(0,255,255)
-  dark_blue = 0x00008B,                // rgb(0,0,139)
-  dark_cyan = 0x008B8B,                // rgb(0,139,139)
-  dark_golden_rod = 0xB8860B,          // rgb(184,134,11)
-  dark_gray = 0xA9A9A9,                // rgb(169,169,169)
-  dark_green = 0x006400,               // rgb(0,100,0)
-  dark_khaki = 0xBDB76B,               // rgb(189,183,107)
-  dark_magenta = 0x8B008B,             // rgb(139,0,139)
-  dark_olive_green = 0x556B2F,         // rgb(85,107,47)
-  dark_orange = 0xFF8C00,              // rgb(255,140,0)
-  dark_orchid = 0x9932CC,              // rgb(153,50,204)
-  dark_red = 0x8B0000,                 // rgb(139,0,0)
-  dark_salmon = 0xE9967A,              // rgb(233,150,122)
-  dark_sea_green = 0x8FBC8F,           // rgb(143,188,143)
-  dark_slate_blue = 0x483D8B,          // rgb(72,61,139)
-  dark_slate_gray = 0x2F4F4F,          // rgb(47,79,79)
-  dark_turquoise = 0x00CED1,           // rgb(0,206,209)
-  dark_violet = 0x9400D3,              // rgb(148,0,211)
-  deep_pink = 0xFF1493,                // rgb(255,20,147)
-  deep_sky_blue = 0x00BFFF,            // rgb(0,191,255)
-  dim_gray = 0x696969,                 // rgb(105,105,105)
-  dodger_blue = 0x1E90FF,              // rgb(30,144,255)
-  fire_brick = 0xB22222,               // rgb(178,34,34)
-  floral_white = 0xFFFAF0,             // rgb(255,250,240)
-  forest_green = 0x228B22,             // rgb(34,139,34)
-  fuchsia = 0xFF00FF,                  // rgb(255,0,255)
-  gainsboro = 0xDCDCDC,                // rgb(220,220,220)
-  ghost_white = 0xF8F8FF,              // rgb(248,248,255)
-  gold = 0xFFD700,                     // rgb(255,215,0)
-  golden_rod = 0xDAA520,               // rgb(218,165,32)
-  gray = 0x808080,                     // rgb(128,128,128)
-  green = 0x008000,                    // rgb(0,128,0)
-  green_yellow = 0xADFF2F,             // rgb(173,255,47)
-  honey_dew = 0xF0FFF0,                // rgb(240,255,240)
-  hot_pink = 0xFF69B4,                 // rgb(255,105,180)
-  indian_red = 0xCD5C5C,               // rgb(205,92,92)
-  indigo = 0x4B0082,                   // rgb(75,0,130)
-  ivory = 0xFFFFF0,                    // rgb(255,255,240)
-  khaki = 0xF0E68C,                    // rgb(240,230,140)
-  lavender = 0xE6E6FA,                 // rgb(230,230,250)
-  lavender_blush = 0xFFF0F5,           // rgb(255,240,245)
-  lawn_green = 0x7CFC00,               // rgb(124,252,0)
-  lemon_chiffon = 0xFFFACD,            // rgb(255,250,205)
-  light_blue = 0xADD8E6,               // rgb(173,216,230)
-  light_coral = 0xF08080,              // rgb(240,128,128)
-  light_cyan = 0xE0FFFF,               // rgb(224,255,255)
-  light_golden_rod_yellow = 0xFAFAD2,  // rgb(250,250,210)
-  light_gray = 0xD3D3D3,               // rgb(211,211,211)
-  light_green = 0x90EE90,              // rgb(144,238,144)
-  light_pink = 0xFFB6C1,               // rgb(255,182,193)
-  light_salmon = 0xFFA07A,             // rgb(255,160,122)
-  light_sea_green = 0x20B2AA,          // rgb(32,178,170)
-  light_sky_blue = 0x87CEFA,           // rgb(135,206,250)
-  light_slate_gray = 0x778899,         // rgb(119,136,153)
-  light_steel_blue = 0xB0C4DE,         // rgb(176,196,222)
-  light_yellow = 0xFFFFE0,             // rgb(255,255,224)
-  lime = 0x00FF00,                     // rgb(0,255,0)
-  lime_green = 0x32CD32,               // rgb(50,205,50)
-  linen = 0xFAF0E6,                    // rgb(250,240,230)
-  magenta = 0xFF00FF,                  // rgb(255,0,255)
-  maroon = 0x800000,                   // rgb(128,0,0)
-  medium_aquamarine = 0x66CDAA,        // rgb(102,205,170)
-  medium_blue = 0x0000CD,              // rgb(0,0,205)
-  medium_orchid = 0xBA55D3,            // rgb(186,85,211)
-  medium_purple = 0x9370DB,            // rgb(147,112,219)
-  medium_sea_green = 0x3CB371,         // rgb(60,179,113)
-  medium_slate_blue = 0x7B68EE,        // rgb(123,104,238)
-  medium_spring_green = 0x00FA9A,      // rgb(0,250,154)
-  medium_turquoise = 0x48D1CC,         // rgb(72,209,204)
-  medium_violet_red = 0xC71585,        // rgb(199,21,133)
-  midnight_blue = 0x191970,            // rgb(25,25,112)
-  mint_cream = 0xF5FFFA,               // rgb(245,255,250)
-  misty_rose = 0xFFE4E1,               // rgb(255,228,225)
-  moccasin = 0xFFE4B5,                 // rgb(255,228,181)
-  navajo_white = 0xFFDEAD,             // rgb(255,222,173)
-  navy = 0x000080,                     // rgb(0,0,128)
-  old_lace = 0xFDF5E6,                 // rgb(253,245,230)
-  olive = 0x808000,                    // rgb(128,128,0)
-  olive_drab = 0x6B8E23,               // rgb(107,142,35)
-  orange = 0xFFA500,                   // rgb(255,165,0)
-  orange_red = 0xFF4500,               // rgb(255,69,0)
-  orchid = 0xDA70D6,                   // rgb(218,112,214)
-  pale_golden_rod = 0xEEE8AA,          // rgb(238,232,170)
-  pale_green = 0x98FB98,               // rgb(152,251,152)
-  pale_turquoise = 0xAFEEEE,           // rgb(175,238,238)
-  pale_violet_red = 0xDB7093,          // rgb(219,112,147)
-  papaya_whip = 0xFFEFD5,              // rgb(255,239,213)
-  peach_puff = 0xFFDAB9,               // rgb(255,218,185)
-  peru = 0xCD853F,                     // rgb(205,133,63)
-  pink = 0xFFC0CB,                     // rgb(255,192,203)
-  plum = 0xDDA0DD,                     // rgb(221,160,221)
-  powder_blue = 0xB0E0E6,              // rgb(176,224,230)
-  purple = 0x800080,                   // rgb(128,0,128)
-  rebecca_purple = 0x663399,           // rgb(102,51,153)
-  red = 0xFF0000,                      // rgb(255,0,0)
-  rosy_brown = 0xBC8F8F,               // rgb(188,143,143)
-  royal_blue = 0x4169E1,               // rgb(65,105,225)
-  saddle_brown = 0x8B4513,             // rgb(139,69,19)
-  salmon = 0xFA8072,                   // rgb(250,128,114)
-  sandy_brown = 0xF4A460,              // rgb(244,164,96)
-  sea_green = 0x2E8B57,                // rgb(46,139,87)
-  sea_shell = 0xFFF5EE,                // rgb(255,245,238)
-  sienna = 0xA0522D,                   // rgb(160,82,45)
-  silver = 0xC0C0C0,                   // rgb(192,192,192)
-  sky_blue = 0x87CEEB,                 // rgb(135,206,235)
-  slate_blue = 0x6A5ACD,               // rgb(106,90,205)
-  slate_gray = 0x708090,               // rgb(112,128,144)
-  snow = 0xFFFAFA,                     // rgb(255,250,250)
-  spring_green = 0x00FF7F,             // rgb(0,255,127)
-  steel_blue = 0x4682B4,               // rgb(70,130,180)
-  tan = 0xD2B48C,                      // rgb(210,180,140)
-  teal = 0x008080,                     // rgb(0,128,128)
-  thistle = 0xD8BFD8,                  // rgb(216,191,216)
-  tomato = 0xFF6347,                   // rgb(255,99,71)
-  turquoise = 0x40E0D0,                // rgb(64,224,208)
-  violet = 0xEE82EE,                   // rgb(238,130,238)
-  wheat = 0xF5DEB3,                    // rgb(245,222,179)
-  white = 0xFFFFFF,                    // rgb(255,255,255)
-  white_smoke = 0xF5F5F5,              // rgb(245,245,245)
-  yellow = 0xFFFF00,                   // rgb(255,255,0)
-  yellow_green = 0x9ACD32              // rgb(154,205,50)
-};                                     // enum class color
-
-enum class terminal_color : uint8_t {
-  black = 30,
-  red,
-  green,
-  yellow,
-  blue,
-  magenta,
-  cyan,
-  white,
-  bright_black = 90,
-  bright_red,
-  bright_green,
-  bright_yellow,
-  bright_blue,
-  bright_magenta,
-  bright_cyan,
-  bright_white
-};
-
-enum class emphasis : uint8_t {
-  bold = 1,
-  faint = 1 << 1,
-  italic = 1 << 2,
-  underline = 1 << 3,
-  blink = 1 << 4,
-  reverse = 1 << 5,
-  conceal = 1 << 6,
-  strikethrough = 1 << 7,
-};
-
-// rgb is a struct for red, green and blue colors.
-// Using the name "rgb" makes some editors show the color in a tooltip.
-struct rgb {
-  FMT_CONSTEXPR rgb() : r(0), g(0), b(0) {}
-  FMT_CONSTEXPR rgb(uint8_t r_, uint8_t g_, uint8_t b_) : r(r_), g(g_), b(b_) {}
-  FMT_CONSTEXPR rgb(uint32_t hex)
-      : r((hex >> 16) & 0xFF), g((hex >> 8) & 0xFF), b(hex & 0xFF) {}
-  FMT_CONSTEXPR rgb(color hex)
-      : r((uint32_t(hex) >> 16) & 0xFF),
-        g((uint32_t(hex) >> 8) & 0xFF),
-        b(uint32_t(hex) & 0xFF) {}
-  uint8_t r;
-  uint8_t g;
-  uint8_t b;
-};
-
-FMT_BEGIN_DETAIL_NAMESPACE
-
-// color is a struct of either a rgb color or a terminal color.
-struct color_type {
-  FMT_CONSTEXPR color_type() FMT_NOEXCEPT : is_rgb(), value{} {}
-  FMT_CONSTEXPR color_type(color rgb_color) FMT_NOEXCEPT : is_rgb(true),
-                                                           value{} {
-    value.rgb_color = static_cast<uint32_t>(rgb_color);
-  }
-  FMT_CONSTEXPR color_type(rgb rgb_color) FMT_NOEXCEPT : is_rgb(true), value{} {
-    value.rgb_color = (static_cast<uint32_t>(rgb_color.r) << 16) |
-                      (static_cast<uint32_t>(rgb_color.g) << 8) | rgb_color.b;
-  }
-  FMT_CONSTEXPR color_type(terminal_color term_color) FMT_NOEXCEPT : is_rgb(),
-                                                                     value{} {
-    value.term_color = static_cast<uint8_t>(term_color);
-  }
-  bool is_rgb;
-  union color_union {
-    uint8_t term_color;
-    uint32_t rgb_color;
-  } value;
-};
-
-FMT_END_DETAIL_NAMESPACE
-
-/** A text style consisting of foreground and background colors and emphasis. */
-class text_style {
- public:
-  FMT_CONSTEXPR text_style(emphasis em = emphasis()) FMT_NOEXCEPT
-      : set_foreground_color(),
-        set_background_color(),
-        ems(em) {}
-
-  FMT_CONSTEXPR text_style& operator|=(const text_style& rhs) {
-    if (!set_foreground_color) {
-      set_foreground_color = rhs.set_foreground_color;
-      foreground_color = rhs.foreground_color;
-    } else if (rhs.set_foreground_color) {
-      if (!foreground_color.is_rgb || !rhs.foreground_color.is_rgb)
-        FMT_THROW(format_error("can't OR a terminal color"));
-      foreground_color.value.rgb_color |= rhs.foreground_color.value.rgb_color;
-    }
-
-    if (!set_background_color) {
-      set_background_color = rhs.set_background_color;
-      background_color = rhs.background_color;
-    } else if (rhs.set_background_color) {
-      if (!background_color.is_rgb || !rhs.background_color.is_rgb)
-        FMT_THROW(format_error("can't OR a terminal color"));
-      background_color.value.rgb_color |= rhs.background_color.value.rgb_color;
-    }
-
-    ems = static_cast<emphasis>(static_cast<uint8_t>(ems) |
-                                static_cast<uint8_t>(rhs.ems));
-    return *this;
-  }
-
-  friend FMT_CONSTEXPR text_style operator|(text_style lhs,
-                                            const text_style& rhs) {
-    return lhs |= rhs;
-  }
-
-  FMT_DEPRECATED_NONMSVC FMT_CONSTEXPR text_style& operator&=(
-      const text_style& rhs) {
-    return and_assign(rhs);
-  }
-
-  FMT_DEPRECATED_NONMSVC friend FMT_CONSTEXPR text_style
-  operator&(text_style lhs, const text_style& rhs) {
-    return lhs.and_assign(rhs);
-  }
-
-  FMT_CONSTEXPR bool has_foreground() const FMT_NOEXCEPT {
-    return set_foreground_color;
-  }
-  FMT_CONSTEXPR bool has_background() const FMT_NOEXCEPT {
-    return set_background_color;
-  }
-  FMT_CONSTEXPR bool has_emphasis() const FMT_NOEXCEPT {
-    return static_cast<uint8_t>(ems) != 0;
-  }
-  FMT_CONSTEXPR detail::color_type get_foreground() const FMT_NOEXCEPT {
-    FMT_ASSERT(has_foreground(), "no foreground specified for this style");
-    return foreground_color;
-  }
-  FMT_CONSTEXPR detail::color_type get_background() const FMT_NOEXCEPT {
-    FMT_ASSERT(has_background(), "no background specified for this style");
-    return background_color;
-  }
-  FMT_CONSTEXPR emphasis get_emphasis() const FMT_NOEXCEPT {
-    FMT_ASSERT(has_emphasis(), "no emphasis specified for this style");
-    return ems;
-  }
-
- private:
-  FMT_CONSTEXPR text_style(bool is_foreground,
-                           detail::color_type text_color) FMT_NOEXCEPT
-      : set_foreground_color(),
-        set_background_color(),
-        ems() {
-    if (is_foreground) {
-      foreground_color = text_color;
-      set_foreground_color = true;
-    } else {
-      background_color = text_color;
-      set_background_color = true;
-    }
-  }
-
-  // DEPRECATED!
-  FMT_CONSTEXPR text_style& and_assign(const text_style& rhs) {
-    if (!set_foreground_color) {
-      set_foreground_color = rhs.set_foreground_color;
-      foreground_color = rhs.foreground_color;
-    } else if (rhs.set_foreground_color) {
-      if (!foreground_color.is_rgb || !rhs.foreground_color.is_rgb)
-        FMT_THROW(format_error("can't AND a terminal color"));
-      foreground_color.value.rgb_color &= rhs.foreground_color.value.rgb_color;
-    }
-
-    if (!set_background_color) {
-      set_background_color = rhs.set_background_color;
-      background_color = rhs.background_color;
-    } else if (rhs.set_background_color) {
-      if (!background_color.is_rgb || !rhs.background_color.is_rgb)
-        FMT_THROW(format_error("can't AND a terminal color"));
-      background_color.value.rgb_color &= rhs.background_color.value.rgb_color;
-    }
-
-    ems = static_cast<emphasis>(static_cast<uint8_t>(ems) &
-                                static_cast<uint8_t>(rhs.ems));
-    return *this;
-  }
-
-  friend FMT_CONSTEXPR_DECL text_style fg(detail::color_type foreground)
-      FMT_NOEXCEPT;
-
-  friend FMT_CONSTEXPR_DECL text_style bg(detail::color_type background)
-      FMT_NOEXCEPT;
-
-  detail::color_type foreground_color;
-  detail::color_type background_color;
-  bool set_foreground_color;
-  bool set_background_color;
-  emphasis ems;
-};
-
-/** Creates a text style from the foreground (text) color. */
-FMT_CONSTEXPR inline text_style fg(detail::color_type foreground) FMT_NOEXCEPT {
-  return text_style(true, foreground);
-}
-
-/** Creates a text style from the background color. */
-FMT_CONSTEXPR inline text_style bg(detail::color_type background) FMT_NOEXCEPT {
-  return text_style(false, background);
-}
-
-FMT_CONSTEXPR inline text_style operator|(emphasis lhs,
-                                          emphasis rhs) FMT_NOEXCEPT {
-  return text_style(lhs) | rhs;
-}
-
-FMT_BEGIN_DETAIL_NAMESPACE
-
-template <typename Char> struct ansi_color_escape {
-  FMT_CONSTEXPR ansi_color_escape(detail::color_type text_color,
-                                  const char* esc) FMT_NOEXCEPT {
-    // If we have a terminal color, we need to output another escape code
-    // sequence.
-    if (!text_color.is_rgb) {
-      bool is_background = esc == string_view("\x1b[48;2;");
-      uint32_t value = text_color.value.term_color;
-      // Background ASCII codes are the same as the foreground ones but with
-      // 10 more.
-      if (is_background) value += 10u;
-
-      size_t index = 0;
-      buffer[index++] = static_cast<Char>('\x1b');
-      buffer[index++] = static_cast<Char>('[');
-
-      if (value >= 100u) {
-        buffer[index++] = static_cast<Char>('1');
-        value %= 100u;
-      }
-      buffer[index++] = static_cast<Char>('0' + value / 10u);
-      buffer[index++] = static_cast<Char>('0' + value % 10u);
-
-      buffer[index++] = static_cast<Char>('m');
-      buffer[index++] = static_cast<Char>('\0');
-      return;
-    }
-
-    for (int i = 0; i < 7; i++) {
-      buffer[i] = static_cast<Char>(esc[i]);
-    }
-    rgb color(text_color.value.rgb_color);
-    to_esc(color.r, buffer + 7, ';');
-    to_esc(color.g, buffer + 11, ';');
-    to_esc(color.b, buffer + 15, 'm');
-    buffer[19] = static_cast<Char>(0);
-  }
-  FMT_CONSTEXPR ansi_color_escape(emphasis em) FMT_NOEXCEPT {
-    uint8_t em_codes[num_emphases] = {};
-    if (has_emphasis(em, emphasis::bold)) em_codes[0] = 1;
-    if (has_emphasis(em, emphasis::faint)) em_codes[1] = 2;
-    if (has_emphasis(em, emphasis::italic)) em_codes[2] = 3;
-    if (has_emphasis(em, emphasis::underline)) em_codes[3] = 4;
-    if (has_emphasis(em, emphasis::blink)) em_codes[4] = 5;
-    if (has_emphasis(em, emphasis::reverse)) em_codes[5] = 7;
-    if (has_emphasis(em, emphasis::conceal)) em_codes[6] = 8;
-    if (has_emphasis(em, emphasis::strikethrough)) em_codes[7] = 9;
-
-    size_t index = 0;
-    for (size_t i = 0; i < num_emphases; ++i) {
-      if (!em_codes[i]) continue;
-      buffer[index++] = static_cast<Char>('\x1b');
-      buffer[index++] = static_cast<Char>('[');
-      buffer[index++] = static_cast<Char>('0' + em_codes[i]);
-      buffer[index++] = static_cast<Char>('m');
-    }
-    buffer[index++] = static_cast<Char>(0);
-  }
-  FMT_CONSTEXPR operator const Char*() const FMT_NOEXCEPT { return buffer; }
-
-  FMT_CONSTEXPR const Char* begin() const FMT_NOEXCEPT { return buffer; }
-  FMT_CONSTEXPR_CHAR_TRAITS const Char* end() const FMT_NOEXCEPT {
-    return buffer + std::char_traits<Char>::length(buffer);
-  }
-
- private:
-  static constexpr size_t num_emphases = 8;
-  Char buffer[7u + 3u * num_emphases + 1u];
-
-  static FMT_CONSTEXPR void to_esc(uint8_t c, Char* out,
-                                   char delimiter) FMT_NOEXCEPT {
-    out[0] = static_cast<Char>('0' + c / 100);
-    out[1] = static_cast<Char>('0' + c / 10 % 10);
-    out[2] = static_cast<Char>('0' + c % 10);
-    out[3] = static_cast<Char>(delimiter);
-  }
-  static FMT_CONSTEXPR bool has_emphasis(emphasis em,
-                                         emphasis mask) FMT_NOEXCEPT {
-    return static_cast<uint8_t>(em) & static_cast<uint8_t>(mask);
-  }
-};
-
-template <typename Char>
-FMT_CONSTEXPR ansi_color_escape<Char> make_foreground_color(
-    detail::color_type foreground) FMT_NOEXCEPT {
-  return ansi_color_escape<Char>(foreground, "\x1b[38;2;");
-}
-
-template <typename Char>
-FMT_CONSTEXPR ansi_color_escape<Char> make_background_color(
-    detail::color_type background) FMT_NOEXCEPT {
-  return ansi_color_escape<Char>(background, "\x1b[48;2;");
-}
-
-template <typename Char>
-FMT_CONSTEXPR ansi_color_escape<Char> make_emphasis(emphasis em) FMT_NOEXCEPT {
-  return ansi_color_escape<Char>(em);
-}
-
-template <typename Char>
-inline void fputs(const Char* chars, FILE* stream) FMT_NOEXCEPT {
-  std::fputs(chars, stream);
-}
-
-template <>
-inline void fputs<wchar_t>(const wchar_t* chars, FILE* stream) FMT_NOEXCEPT {
-  std::fputws(chars, stream);
-}
-
-template <typename Char> inline void reset_color(FILE* stream) FMT_NOEXCEPT {
-  fputs("\x1b[0m", stream);
-}
-
-template <> inline void reset_color<wchar_t>(FILE* stream) FMT_NOEXCEPT {
-  fputs(L"\x1b[0m", stream);
-}
-
-template <typename Char>
-inline void reset_color(buffer<Char>& buffer) FMT_NOEXCEPT {
-  auto reset_color = string_view("\x1b[0m");
-  buffer.append(reset_color.begin(), reset_color.end());
-}
-
-template <typename Char>
-void vformat_to(buffer<Char>& buf, const text_style& ts,
-                basic_string_view<Char> format_str,
-                basic_format_args<buffer_context<type_identity_t<Char>>> args) {
-  bool has_style = false;
-  if (ts.has_emphasis()) {
-    has_style = true;
-    auto emphasis = detail::make_emphasis<Char>(ts.get_emphasis());
-    buf.append(emphasis.begin(), emphasis.end());
-  }
-  if (ts.has_foreground()) {
-    has_style = true;
-    auto foreground = detail::make_foreground_color<Char>(ts.get_foreground());
-    buf.append(foreground.begin(), foreground.end());
-  }
-  if (ts.has_background()) {
-    has_style = true;
-    auto background = detail::make_background_color<Char>(ts.get_background());
-    buf.append(background.begin(), background.end());
-  }
-  detail::vformat_to(buf, format_str, args, {});
-  if (has_style) detail::reset_color<Char>(buf);
-}
-
-FMT_END_DETAIL_NAMESPACE
-
-template <typename S, typename Char = char_t<S>>
-void vprint(std::FILE* f, const text_style& ts, const S& format,
-            basic_format_args<buffer_context<type_identity_t<Char>>> args) {
-  basic_memory_buffer<Char> buf;
-  detail::vformat_to(buf, ts, to_string_view(format), args);
-  buf.push_back(Char(0));
-  detail::fputs(buf.data(), f);
-}
-
-/**
-  \rst
-  Formats a string and prints it to the specified file stream using ANSI
-  escape sequences to specify text formatting.
-
-  **Example**::
-
-    fmt::print(fmt::emphasis::bold | fg(fmt::color::red),
-               "Elapsed time: {0:.2f} seconds", 1.23);
-  \endrst
- */
-template <typename S, typename... Args,
-          FMT_ENABLE_IF(detail::is_string<S>::value)>
-void print(std::FILE* f, const text_style& ts, const S& format_str,
-           const Args&... args) {
-  vprint(f, ts, format_str,
-         fmt::make_args_checked<Args...>(format_str, args...));
-}
-
-/**
-  \rst
-  Formats a string and prints it to stdout using ANSI escape sequences to
-  specify text formatting.
-
-  **Example**::
-
-    fmt::print(fmt::emphasis::bold | fg(fmt::color::red),
-               "Elapsed time: {0:.2f} seconds", 1.23);
-  \endrst
- */
-template <typename S, typename... Args,
-          FMT_ENABLE_IF(detail::is_string<S>::value)>
-void print(const text_style& ts, const S& format_str, const Args&... args) {
-  return print(stdout, ts, format_str, args...);
-}
-
-template <typename S, typename Char = char_t<S>>
-inline std::basic_string<Char> vformat(
-    const text_style& ts, const S& format_str,
-    basic_format_args<buffer_context<type_identity_t<Char>>> args) {
-  basic_memory_buffer<Char> buf;
-  detail::vformat_to(buf, ts, to_string_view(format_str), args);
-  return fmt::to_string(buf);
-}
-
-/**
-  \rst
-  Formats arguments and returns the result as a string using ANSI
-  escape sequences to specify text formatting.
-
-  **Example**::
-
-    #include <fmt/color.h>
-    std::string message = fmt::format(fmt::emphasis::bold | fg(fmt::color::red),
-                                      "The answer is {}", 42);
-  \endrst
-*/
-template <typename S, typename... Args, typename Char = char_t<S>>
-inline std::basic_string<Char> format(const text_style& ts, const S& format_str,
-                                      const Args&... args) {
-  return fmt::vformat(ts, to_string_view(format_str),
-                      fmt::make_args_checked<Args...>(format_str, args...));
-}
-
-/**
-  Formats a string with the given text_style and writes the output to ``out``.
- */
-template <typename OutputIt, typename Char,
-          FMT_ENABLE_IF(detail::is_output_iterator<OutputIt, Char>::value)>
-OutputIt vformat_to(
-    OutputIt out, const text_style& ts, basic_string_view<Char> format_str,
-    basic_format_args<buffer_context<type_identity_t<Char>>> args) {
-  auto&& buf = detail::get_buffer<Char>(out);
-  detail::vformat_to(buf, ts, format_str, args);
-  return detail::get_iterator(buf);
-}
-
-/**
-  \rst
-  Formats arguments with the given text_style, writes the result to the output
-  iterator ``out`` and returns the iterator past the end of the output range.
-
-  **Example**::
-
-    std::vector<char> out;
-    fmt::format_to(std::back_inserter(out),
-                   fmt::emphasis::bold | fg(fmt::color::red), "{}", 42);
-  \endrst
-*/
-template <typename OutputIt, typename S, typename... Args,
-          bool enable = detail::is_output_iterator<OutputIt, char_t<S>>::value&&
-              detail::is_string<S>::value>
-inline auto format_to(OutputIt out, const text_style& ts, const S& format_str,
-                      Args&&... args) ->
-    typename std::enable_if<enable, OutputIt>::type {
-  return vformat_to(out, ts, to_string_view(format_str),
-                    fmt::make_args_checked<Args...>(format_str, args...));
-}
-
-FMT_MODULE_EXPORT_END
-FMT_END_NAMESPACE
-
-#endif  // FMT_COLOR_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/compile.h b/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/compile.h
deleted file mode 100644
index 1dba3dd..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/compile.h
+++ /dev/null
@@ -1,642 +0,0 @@
-// Formatting library for C++ - experimental format string compilation
-//
-// Copyright (c) 2012 - present, Victor Zverovich and fmt contributors
-// All rights reserved.
-//
-// For the license information refer to format.h.
-
-#ifndef FMT_COMPILE_H_
-#define FMT_COMPILE_H_
-
-#include "format.h"
-
-FMT_BEGIN_NAMESPACE
-namespace detail {
-
-// An output iterator that counts the number of objects written to it and
-// discards them.
-class counting_iterator {
- private:
-  size_t count_;
-
- public:
-  using iterator_category = std::output_iterator_tag;
-  using difference_type = std::ptrdiff_t;
-  using pointer = void;
-  using reference = void;
-  using _Unchecked_type = counting_iterator;  // Mark iterator as checked.
-
-  struct value_type {
-    template <typename T> void operator=(const T&) {}
-  };
-
-  counting_iterator() : count_(0) {}
-
-  size_t count() const { return count_; }
-
-  counting_iterator& operator++() {
-    ++count_;
-    return *this;
-  }
-  counting_iterator operator++(int) {
-    auto it = *this;
-    ++*this;
-    return it;
-  }
-
-  friend counting_iterator operator+(counting_iterator it, difference_type n) {
-    it.count_ += static_cast<size_t>(n);
-    return it;
-  }
-
-  value_type operator*() const { return {}; }
-};
-
-template <typename Char, typename InputIt>
-inline counting_iterator copy_str(InputIt begin, InputIt end,
-                                  counting_iterator it) {
-  return it + (end - begin);
-}
-
-template <typename OutputIt> class truncating_iterator_base {
- protected:
-  OutputIt out_;
-  size_t limit_;
-  size_t count_ = 0;
-
-  truncating_iterator_base() : out_(), limit_(0) {}
-
-  truncating_iterator_base(OutputIt out, size_t limit)
-      : out_(out), limit_(limit) {}
-
- public:
-  using iterator_category = std::output_iterator_tag;
-  using value_type = typename std::iterator_traits<OutputIt>::value_type;
-  using difference_type = std::ptrdiff_t;
-  using pointer = void;
-  using reference = void;
-  using _Unchecked_type =
-      truncating_iterator_base;  // Mark iterator as checked.
-
-  OutputIt base() const { return out_; }
-  size_t count() const { return count_; }
-};
-
-// An output iterator that truncates the output and counts the number of objects
-// written to it.
-template <typename OutputIt,
-          typename Enable = typename std::is_void<
-              typename std::iterator_traits<OutputIt>::value_type>::type>
-class truncating_iterator;
-
-template <typename OutputIt>
-class truncating_iterator<OutputIt, std::false_type>
-    : public truncating_iterator_base<OutputIt> {
-  mutable typename truncating_iterator_base<OutputIt>::value_type blackhole_;
-
- public:
-  using value_type = typename truncating_iterator_base<OutputIt>::value_type;
-
-  truncating_iterator() = default;
-
-  truncating_iterator(OutputIt out, size_t limit)
-      : truncating_iterator_base<OutputIt>(out, limit) {}
-
-  truncating_iterator& operator++() {
-    if (this->count_++ < this->limit_) ++this->out_;
-    return *this;
-  }
-
-  truncating_iterator operator++(int) {
-    auto it = *this;
-    ++*this;
-    return it;
-  }
-
-  value_type& operator*() const {
-    return this->count_ < this->limit_ ? *this->out_ : blackhole_;
-  }
-};
-
-template <typename OutputIt>
-class truncating_iterator<OutputIt, std::true_type>
-    : public truncating_iterator_base<OutputIt> {
- public:
-  truncating_iterator() = default;
-
-  truncating_iterator(OutputIt out, size_t limit)
-      : truncating_iterator_base<OutputIt>(out, limit) {}
-
-  template <typename T> truncating_iterator& operator=(T val) {
-    if (this->count_++ < this->limit_) *this->out_++ = val;
-    return *this;
-  }
-
-  truncating_iterator& operator++() { return *this; }
-  truncating_iterator& operator++(int) { return *this; }
-  truncating_iterator& operator*() { return *this; }
-};
-
-// A compile-time string which is compiled into fast formatting code.
-class compiled_string {};
-
-template <typename S>
-struct is_compiled_string : std::is_base_of<compiled_string, S> {};
-
-/**
-  \rst
-  Converts a string literal *s* into a format string that will be parsed at
-  compile time and converted into efficient formatting code. Requires C++17
-  ``constexpr if`` compiler support.
-
-  **Example**::
-
-    // Converts 42 into std::string using the most efficient method and no
-    // runtime format string processing.
-    std::string s = fmt::format(FMT_COMPILE("{}"), 42);
-  \endrst
- */
-#if defined(__cpp_if_constexpr) && defined(__cpp_return_type_deduction)
-#  define FMT_COMPILE(s) \
-    FMT_STRING_IMPL(s, fmt::detail::compiled_string, explicit)
-#else
-#  define FMT_COMPILE(s) FMT_STRING(s)
-#endif
-
-#if FMT_USE_NONTYPE_TEMPLATE_PARAMETERS
-template <typename Char, size_t N,
-          fmt::detail_exported::fixed_string<Char, N> Str>
-struct udl_compiled_string : compiled_string {
-  using char_type = Char;
-  constexpr operator basic_string_view<char_type>() const {
-    return {Str.data, N - 1};
-  }
-};
-#endif
-
-template <typename T, typename... Tail>
-const T& first(const T& value, const Tail&...) {
-  return value;
-}
-
-#if defined(__cpp_if_constexpr) && defined(__cpp_return_type_deduction)
-template <typename... Args> struct type_list {};
-
-// Returns a reference to the argument at index N from [first, rest...].
-template <int N, typename T, typename... Args>
-constexpr const auto& get([[maybe_unused]] const T& first,
-                          [[maybe_unused]] const Args&... rest) {
-  static_assert(N < 1 + sizeof...(Args), "index is out of bounds");
-  if constexpr (N == 0)
-    return first;
-  else
-    return detail::get<N - 1>(rest...);
-}
-
-template <typename Char, typename... Args>
-constexpr int get_arg_index_by_name(basic_string_view<Char> name,
-                                    type_list<Args...>) {
-  return get_arg_index_by_name<Args...>(name);
-}
-
-template <int N, typename> struct get_type_impl;
-
-template <int N, typename... Args> struct get_type_impl<N, type_list<Args...>> {
-  using type =
-      remove_cvref_t<decltype(detail::get<N>(std::declval<Args>()...))>;
-};
-
-template <int N, typename T>
-using get_type = typename get_type_impl<N, T>::type;
-
-template <typename T> struct is_compiled_format : std::false_type {};
-
-template <typename Char> struct text {
-  basic_string_view<Char> data;
-  using char_type = Char;
-
-  template <typename OutputIt, typename... Args>
-  constexpr OutputIt format(OutputIt out, const Args&...) const {
-    return write<Char>(out, data);
-  }
-};
-
-template <typename Char>
-struct is_compiled_format<text<Char>> : std::true_type {};
-
-template <typename Char>
-constexpr text<Char> make_text(basic_string_view<Char> s, size_t pos,
-                               size_t size) {
-  return {{&s[pos], size}};
-}
-
-template <typename Char> struct code_unit {
-  Char value;
-  using char_type = Char;
-
-  template <typename OutputIt, typename... Args>
-  constexpr OutputIt format(OutputIt out, const Args&...) const {
-    return write<Char>(out, value);
-  }
-};
-
-// This ensures that the argument type is convertible to `const T&`.
-template <typename T, int N, typename... Args>
-constexpr const T& get_arg_checked(const Args&... args) {
-  const auto& arg = detail::get<N>(args...);
-  if constexpr (detail::is_named_arg<remove_cvref_t<decltype(arg)>>()) {
-    return arg.value;
-  } else {
-    return arg;
-  }
-}
-
-template <typename Char>
-struct is_compiled_format<code_unit<Char>> : std::true_type {};
-
-// A replacement field that refers to argument N.
-template <typename Char, typename T, int N> struct field {
-  using char_type = Char;
-
-  template <typename OutputIt, typename... Args>
-  constexpr OutputIt format(OutputIt out, const Args&... args) const {
-    return write<Char>(out, get_arg_checked<T, N>(args...));
-  }
-};
-
-template <typename Char, typename T, int N>
-struct is_compiled_format<field<Char, T, N>> : std::true_type {};
-
-// A replacement field that refers to argument with name.
-template <typename Char> struct runtime_named_field {
-  using char_type = Char;
-  basic_string_view<Char> name;
-
-  template <typename OutputIt, typename T>
-  constexpr static bool try_format_argument(
-      OutputIt& out,
-      // [[maybe_unused]] due to unused-but-set-parameter warning in GCC 7,8,9
-      [[maybe_unused]] basic_string_view<Char> arg_name, const T& arg) {
-    if constexpr (is_named_arg<typename std::remove_cv<T>::type>::value) {
-      if (arg_name == arg.name) {
-        out = write<Char>(out, arg.value);
-        return true;
-      }
-    }
-    return false;
-  }
-
-  template <typename OutputIt, typename... Args>
-  constexpr OutputIt format(OutputIt out, const Args&... args) const {
-    bool found = (try_format_argument(out, name, args) || ...);
-    if (!found) {
-      FMT_THROW(format_error("argument with specified name is not found"));
-    }
-    return out;
-  }
-};
-
-template <typename Char>
-struct is_compiled_format<runtime_named_field<Char>> : std::true_type {};
-
-// A replacement field that refers to argument N and has format specifiers.
-template <typename Char, typename T, int N> struct spec_field {
-  using char_type = Char;
-  formatter<T, Char> fmt;
-
-  template <typename OutputIt, typename... Args>
-  constexpr FMT_INLINE OutputIt format(OutputIt out,
-                                       const Args&... args) const {
-    const auto& vargs =
-        fmt::make_format_args<basic_format_context<OutputIt, Char>>(args...);
-    basic_format_context<OutputIt, Char> ctx(out, vargs);
-    return fmt.format(get_arg_checked<T, N>(args...), ctx);
-  }
-};
-
-template <typename Char, typename T, int N>
-struct is_compiled_format<spec_field<Char, T, N>> : std::true_type {};
-
-template <typename L, typename R> struct concat {
-  L lhs;
-  R rhs;
-  using char_type = typename L::char_type;
-
-  template <typename OutputIt, typename... Args>
-  constexpr OutputIt format(OutputIt out, const Args&... args) const {
-    out = lhs.format(out, args...);
-    return rhs.format(out, args...);
-  }
-};
-
-template <typename L, typename R>
-struct is_compiled_format<concat<L, R>> : std::true_type {};
-
-template <typename L, typename R>
-constexpr concat<L, R> make_concat(L lhs, R rhs) {
-  return {lhs, rhs};
-}
-
-struct unknown_format {};
-
-template <typename Char>
-constexpr size_t parse_text(basic_string_view<Char> str, size_t pos) {
-  for (size_t size = str.size(); pos != size; ++pos) {
-    if (str[pos] == '{' || str[pos] == '}') break;
-  }
-  return pos;
-}
-
-template <typename Args, size_t POS, int ID, typename S>
-constexpr auto compile_format_string(S format_str);
-
-template <typename Args, size_t POS, int ID, typename T, typename S>
-constexpr auto parse_tail(T head, S format_str) {
-  if constexpr (POS !=
-                basic_string_view<typename S::char_type>(format_str).size()) {
-    constexpr auto tail = compile_format_string<Args, POS, ID>(format_str);
-    if constexpr (std::is_same<remove_cvref_t<decltype(tail)>,
-                               unknown_format>())
-      return tail;
-    else
-      return make_concat(head, tail);
-  } else {
-    return head;
-  }
-}
-
-template <typename T, typename Char> struct parse_specs_result {
-  formatter<T, Char> fmt;
-  size_t end;
-  int next_arg_id;
-};
-
-constexpr int manual_indexing_id = -1;
-
-template <typename T, typename Char>
-constexpr parse_specs_result<T, Char> parse_specs(basic_string_view<Char> str,
-                                                  size_t pos, int next_arg_id) {
-  str.remove_prefix(pos);
-  auto ctx = basic_format_parse_context<Char>(str, {}, next_arg_id);
-  auto f = formatter<T, Char>();
-  auto end = f.parse(ctx);
-  return {f, pos + fmt::detail::to_unsigned(end - str.data()) + 1,
-          next_arg_id == 0 ? manual_indexing_id : ctx.next_arg_id()};
-}
-
-template <typename Char> struct arg_id_handler {
-  arg_ref<Char> arg_id;
-
-  constexpr int operator()() {
-    FMT_ASSERT(false, "handler cannot be used with automatic indexing");
-    return 0;
-  }
-  constexpr int operator()(int id) {
-    arg_id = arg_ref<Char>(id);
-    return 0;
-  }
-  constexpr int operator()(basic_string_view<Char> id) {
-    arg_id = arg_ref<Char>(id);
-    return 0;
-  }
-
-  constexpr void on_error(const char* message) {
-    FMT_THROW(format_error(message));
-  }
-};
-
-template <typename Char> struct parse_arg_id_result {
-  arg_ref<Char> arg_id;
-  const Char* arg_id_end;
-};
-
-template <int ID, typename Char>
-constexpr auto parse_arg_id(const Char* begin, const Char* end) {
-  auto handler = arg_id_handler<Char>{arg_ref<Char>{}};
-  auto arg_id_end = parse_arg_id(begin, end, handler);
-  return parse_arg_id_result<Char>{handler.arg_id, arg_id_end};
-}
-
-template <typename T, typename Enable = void> struct field_type {
-  using type = remove_cvref_t<T>;
-};
-
-template <typename T>
-struct field_type<T, enable_if_t<detail::is_named_arg<T>::value>> {
-  using type = remove_cvref_t<decltype(T::value)>;
-};
-
-template <typename T, typename Args, size_t END_POS, int ARG_INDEX, int NEXT_ID,
-          typename S>
-constexpr auto parse_replacement_field_then_tail(S format_str) {
-  using char_type = typename S::char_type;
-  constexpr auto str = basic_string_view<char_type>(format_str);
-  constexpr char_type c = END_POS != str.size() ? str[END_POS] : char_type();
-  if constexpr (c == '}') {
-    return parse_tail<Args, END_POS + 1, NEXT_ID>(
-        field<char_type, typename field_type<T>::type, ARG_INDEX>(),
-        format_str);
-  } else if constexpr (c == ':') {
-    constexpr auto result = parse_specs<typename field_type<T>::type>(
-        str, END_POS + 1, NEXT_ID == manual_indexing_id ? 0 : NEXT_ID);
-    return parse_tail<Args, result.end, result.next_arg_id>(
-        spec_field<char_type, typename field_type<T>::type, ARG_INDEX>{
-            result.fmt},
-        format_str);
-  }
-}
-
-// Compiles a non-empty format string and returns the compiled representation
-// or unknown_format() on unrecognized input.
-template <typename Args, size_t POS, int ID, typename S>
-constexpr auto compile_format_string(S format_str) {
-  using char_type = typename S::char_type;
-  constexpr auto str = basic_string_view<char_type>(format_str);
-  if constexpr (str[POS] == '{') {
-    if constexpr (POS + 1 == str.size())
-      FMT_THROW(format_error("unmatched '{' in format string"));
-    if constexpr (str[POS + 1] == '{') {
-      return parse_tail<Args, POS + 2, ID>(make_text(str, POS, 1), format_str);
-    } else if constexpr (str[POS + 1] == '}' || str[POS + 1] == ':') {
-      static_assert(ID != manual_indexing_id,
-                    "cannot switch from manual to automatic argument indexing");
-      constexpr auto next_id =
-          ID != manual_indexing_id ? ID + 1 : manual_indexing_id;
-      return parse_replacement_field_then_tail<get_type<ID, Args>, Args,
-                                               POS + 1, ID, next_id>(
-          format_str);
-    } else {
-      constexpr auto arg_id_result =
-          parse_arg_id<ID>(str.data() + POS + 1, str.data() + str.size());
-      constexpr auto arg_id_end_pos = arg_id_result.arg_id_end - str.data();
-      constexpr char_type c =
-          arg_id_end_pos != str.size() ? str[arg_id_end_pos] : char_type();
-      static_assert(c == '}' || c == ':', "missing '}' in format string");
-      if constexpr (arg_id_result.arg_id.kind == arg_id_kind::index) {
-        static_assert(
-            ID == manual_indexing_id || ID == 0,
-            "cannot switch from automatic to manual argument indexing");
-        constexpr auto arg_index = arg_id_result.arg_id.val.index;
-        return parse_replacement_field_then_tail<get_type<arg_index, Args>,
-                                                 Args, arg_id_end_pos,
-                                                 arg_index, manual_indexing_id>(
-            format_str);
-      } else if constexpr (arg_id_result.arg_id.kind == arg_id_kind::name) {
-        constexpr auto arg_index =
-            get_arg_index_by_name(arg_id_result.arg_id.val.name, Args{});
-        if constexpr (arg_index != invalid_arg_index) {
-          constexpr auto next_id =
-              ID != manual_indexing_id ? ID + 1 : manual_indexing_id;
-          return parse_replacement_field_then_tail<
-              decltype(get_type<arg_index, Args>::value), Args, arg_id_end_pos,
-              arg_index, next_id>(format_str);
-        } else {
-          if constexpr (c == '}') {
-            return parse_tail<Args, arg_id_end_pos + 1, ID>(
-                runtime_named_field<char_type>{arg_id_result.arg_id.val.name},
-                format_str);
-          } else if constexpr (c == ':') {
-            return unknown_format();  // no type info for specs parsing
-          }
-        }
-      }
-    }
-  } else if constexpr (str[POS] == '}') {
-    if constexpr (POS + 1 == str.size())
-      FMT_THROW(format_error("unmatched '}' in format string"));
-    return parse_tail<Args, POS + 2, ID>(make_text(str, POS, 1), format_str);
-  } else {
-    constexpr auto end = parse_text(str, POS + 1);
-    if constexpr (end - POS > 1) {
-      return parse_tail<Args, end, ID>(make_text(str, POS, end - POS),
-                                       format_str);
-    } else {
-      return parse_tail<Args, end, ID>(code_unit<char_type>{str[POS]},
-                                       format_str);
-    }
-  }
-}
-
-template <typename... Args, typename S,
-          FMT_ENABLE_IF(detail::is_compiled_string<S>::value)>
-constexpr auto compile(S format_str) {
-  constexpr auto str = basic_string_view<typename S::char_type>(format_str);
-  if constexpr (str.size() == 0) {
-    return detail::make_text(str, 0, 0);
-  } else {
-    constexpr auto result =
-        detail::compile_format_string<detail::type_list<Args...>, 0, 0>(
-            format_str);
-    return result;
-  }
-}
-#endif  // defined(__cpp_if_constexpr) && defined(__cpp_return_type_deduction)
-}  // namespace detail
-
-FMT_MODULE_EXPORT_BEGIN
-
-#if defined(__cpp_if_constexpr) && defined(__cpp_return_type_deduction)
-
-template <typename CompiledFormat, typename... Args,
-          typename Char = typename CompiledFormat::char_type,
-          FMT_ENABLE_IF(detail::is_compiled_format<CompiledFormat>::value)>
-FMT_INLINE std::basic_string<Char> format(const CompiledFormat& cf,
-                                          const Args&... args) {
-  auto s = std::basic_string<Char>();
-  cf.format(std::back_inserter(s), args...);
-  return s;
-}
-
-template <typename OutputIt, typename CompiledFormat, typename... Args,
-          FMT_ENABLE_IF(detail::is_compiled_format<CompiledFormat>::value)>
-constexpr FMT_INLINE OutputIt format_to(OutputIt out, const CompiledFormat& cf,
-                                        const Args&... args) {
-  return cf.format(out, args...);
-}
-
-template <typename S, typename... Args,
-          FMT_ENABLE_IF(detail::is_compiled_string<S>::value)>
-FMT_INLINE std::basic_string<typename S::char_type> format(const S&,
-                                                           Args&&... args) {
-  if constexpr (std::is_same<typename S::char_type, char>::value) {
-    constexpr auto str = basic_string_view<typename S::char_type>(S());
-    if constexpr (str.size() == 2 && str[0] == '{' && str[1] == '}') {
-      const auto& first = detail::first(args...);
-      if constexpr (detail::is_named_arg<
-                        remove_cvref_t<decltype(first)>>::value) {
-        return fmt::to_string(first.value);
-      } else {
-        return fmt::to_string(first);
-      }
-    }
-  }
-  constexpr auto compiled = detail::compile<Args...>(S());
-  if constexpr (std::is_same<remove_cvref_t<decltype(compiled)>,
-                             detail::unknown_format>()) {
-    return format(static_cast<basic_string_view<typename S::char_type>>(S()),
-                  std::forward<Args>(args)...);
-  } else {
-    return format(compiled, std::forward<Args>(args)...);
-  }
-}
-
-template <typename OutputIt, typename S, typename... Args,
-          FMT_ENABLE_IF(detail::is_compiled_string<S>::value)>
-FMT_CONSTEXPR OutputIt format_to(OutputIt out, const S&, Args&&... args) {
-  constexpr auto compiled = detail::compile<Args...>(S());
-  if constexpr (std::is_same<remove_cvref_t<decltype(compiled)>,
-                             detail::unknown_format>()) {
-    return format_to(out,
-                     static_cast<basic_string_view<typename S::char_type>>(S()),
-                     std::forward<Args>(args)...);
-  } else {
-    return format_to(out, compiled, std::forward<Args>(args)...);
-  }
-}
-#endif
-
-template <typename OutputIt, typename S, typename... Args,
-          FMT_ENABLE_IF(detail::is_compiled_string<S>::value)>
-format_to_n_result<OutputIt> format_to_n(OutputIt out, size_t n,
-                                         const S& format_str, Args&&... args) {
-  auto it = format_to(detail::truncating_iterator<OutputIt>(out, n), format_str,
-                      std::forward<Args>(args)...);
-  return {it.base(), it.count()};
-}
-
-template <typename S, typename... Args,
-          FMT_ENABLE_IF(detail::is_compiled_string<S>::value)>
-size_t formatted_size(const S& format_str, const Args&... args) {
-  return format_to(detail::counting_iterator(), format_str, args...).count();
-}
-
-template <typename S, typename... Args,
-          FMT_ENABLE_IF(detail::is_compiled_string<S>::value)>
-void print(std::FILE* f, const S& format_str, const Args&... args) {
-  memory_buffer buffer;
-  format_to(std::back_inserter(buffer), format_str, args...);
-  detail::print(f, {buffer.data(), buffer.size()});
-}
-
-template <typename S, typename... Args,
-          FMT_ENABLE_IF(detail::is_compiled_string<S>::value)>
-void print(const S& format_str, const Args&... args) {
-  print(stdout, format_str, args...);
-}
-
-#if FMT_USE_NONTYPE_TEMPLATE_PARAMETERS
-inline namespace literals {
-template <detail_exported::fixed_string Str>
-constexpr detail::udl_compiled_string<
-    remove_cvref_t<decltype(Str.data[0])>,
-    sizeof(Str.data) / sizeof(decltype(Str.data[0])), Str>
-operator""_cf() {
-  return {};
-}
-}  // namespace literals
-#endif
-
-FMT_MODULE_EXPORT_END
-FMT_END_NAMESPACE
-
-#endif  // FMT_COMPILE_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/core.h b/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/core.h
deleted file mode 100644
index 92a7aa1..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/core.h
+++ /dev/null
@@ -1,3236 +0,0 @@
-// Formatting library for C++ - the core API for char/UTF-8
-//
-// Copyright (c) 2012 - present, Victor Zverovich
-// All rights reserved.
-//
-// For the license information refer to format.h.
-
-#ifndef FMT_CORE_H_
-#define FMT_CORE_H_
-
-#include <cstddef>  // std::byte
-#include <cstdio>   // std::FILE
-#include <cstring>
-#include <iterator>
-#include <limits>
-#include <string>
-#include <type_traits>
-
-// The fmt library version in the form major * 10000 + minor * 100 + patch.
-#define FMT_VERSION 80101
-
-#if defined(__clang__) && !defined(__ibmxl__)
-#  define FMT_CLANG_VERSION (__clang_major__ * 100 + __clang_minor__)
-#else
-#  define FMT_CLANG_VERSION 0
-#endif
-
-#if defined(__GNUC__) && !defined(__clang__) && !defined(__INTEL_COMPILER) && \
-    !defined(__NVCOMPILER)
-#  define FMT_GCC_VERSION (__GNUC__ * 100 + __GNUC_MINOR__)
-#else
-#  define FMT_GCC_VERSION 0
-#endif
-
-#ifndef FMT_GCC_PRAGMA
-// Workaround _Pragma bug https://gcc.gnu.org/bugzilla/show_bug.cgi?id=59884.
-#  if FMT_GCC_VERSION >= 504
-#    define FMT_GCC_PRAGMA(arg) _Pragma(arg)
-#  else
-#    define FMT_GCC_PRAGMA(arg)
-#  endif
-#endif
-
-#ifdef __ICL
-#  define FMT_ICC_VERSION __ICL
-#elif defined(__INTEL_COMPILER)
-#  define FMT_ICC_VERSION __INTEL_COMPILER
-#else
-#  define FMT_ICC_VERSION 0
-#endif
-
-#ifdef __NVCC__
-#  define FMT_NVCC __NVCC__
-#else
-#  define FMT_NVCC 0
-#endif
-
-#ifdef _MSC_VER
-#  define FMT_MSC_VER _MSC_VER
-#  define FMT_MSC_WARNING(...) __pragma(warning(__VA_ARGS__))
-#else
-#  define FMT_MSC_VER 0
-#  define FMT_MSC_WARNING(...)
-#endif
-
-#ifdef __has_feature
-#  define FMT_HAS_FEATURE(x) __has_feature(x)
-#else
-#  define FMT_HAS_FEATURE(x) 0
-#endif
-
-#if defined(__has_include) &&                             \
-    (!defined(__INTELLISENSE__) || FMT_MSC_VER > 1900) && \
-    (!FMT_ICC_VERSION || FMT_ICC_VERSION >= 1600)
-#  define FMT_HAS_INCLUDE(x) __has_include(x)
-#else
-#  define FMT_HAS_INCLUDE(x) 0
-#endif
-
-#ifdef __has_cpp_attribute
-#  define FMT_HAS_CPP_ATTRIBUTE(x) __has_cpp_attribute(x)
-#else
-#  define FMT_HAS_CPP_ATTRIBUTE(x) 0
-#endif
-
-#ifdef _MSVC_LANG
-#  define FMT_CPLUSPLUS _MSVC_LANG
-#else
-#  define FMT_CPLUSPLUS __cplusplus
-#endif
-
-#define FMT_HAS_CPP14_ATTRIBUTE(attribute) \
-  (FMT_CPLUSPLUS >= 201402L && FMT_HAS_CPP_ATTRIBUTE(attribute))
-
-#define FMT_HAS_CPP17_ATTRIBUTE(attribute) \
-  (FMT_CPLUSPLUS >= 201703L && FMT_HAS_CPP_ATTRIBUTE(attribute))
-
-// Check if relaxed C++14 constexpr is supported.
-// GCC doesn't allow throw in constexpr until version 6 (bug 67371).
-#ifndef FMT_USE_CONSTEXPR
-#  define FMT_USE_CONSTEXPR                                           \
-    (FMT_HAS_FEATURE(cxx_relaxed_constexpr) || FMT_MSC_VER >= 1912 || \
-     (FMT_GCC_VERSION >= 600 && __cplusplus >= 201402L)) &&           \
-        !FMT_NVCC && !FMT_ICC_VERSION
-#endif
-#if FMT_USE_CONSTEXPR
-#  define FMT_CONSTEXPR constexpr
-#  define FMT_CONSTEXPR_DECL constexpr
-#else
-#  define FMT_CONSTEXPR
-#  define FMT_CONSTEXPR_DECL
-#endif
-
-#if ((__cplusplus >= 202002L) &&                              \
-     (!defined(_GLIBCXX_RELEASE) || _GLIBCXX_RELEASE > 9)) || \
-    (__cplusplus >= 201709L && FMT_GCC_VERSION >= 1002)
-#  define FMT_CONSTEXPR20 constexpr
-#else
-#  define FMT_CONSTEXPR20
-#endif
-
-// Check if constexpr std::char_traits<>::compare,length is supported.
-#if defined(__GLIBCXX__)
-#  if __cplusplus >= 201703L && defined(_GLIBCXX_RELEASE) && \
-      _GLIBCXX_RELEASE >= 7  // GCC 7+ libstdc++ has _GLIBCXX_RELEASE.
-#    define FMT_CONSTEXPR_CHAR_TRAITS constexpr
-#  endif
-#elif defined(_LIBCPP_VERSION) && __cplusplus >= 201703L && \
-    _LIBCPP_VERSION >= 4000
-#  define FMT_CONSTEXPR_CHAR_TRAITS constexpr
-#elif FMT_MSC_VER >= 1914 && _MSVC_LANG >= 201703L
-#  define FMT_CONSTEXPR_CHAR_TRAITS constexpr
-#endif
-#ifndef FMT_CONSTEXPR_CHAR_TRAITS
-#  define FMT_CONSTEXPR_CHAR_TRAITS
-#endif
-
-// Check if exceptions are disabled.
-#ifndef FMT_EXCEPTIONS
-#  if (defined(__GNUC__) && !defined(__EXCEPTIONS)) || \
-      FMT_MSC_VER && !_HAS_EXCEPTIONS
-#    define FMT_EXCEPTIONS 0
-#  else
-#    define FMT_EXCEPTIONS 1
-#  endif
-#endif
-
-// Define FMT_USE_NOEXCEPT to make fmt use noexcept (C++11 feature).
-#ifndef FMT_USE_NOEXCEPT
-#  define FMT_USE_NOEXCEPT 0
-#endif
-
-#if FMT_USE_NOEXCEPT || FMT_HAS_FEATURE(cxx_noexcept) || \
-    FMT_GCC_VERSION >= 408 || FMT_MSC_VER >= 1900
-#  define FMT_DETECTED_NOEXCEPT noexcept
-#  define FMT_HAS_CXX11_NOEXCEPT 1
-#else
-#  define FMT_DETECTED_NOEXCEPT throw()
-#  define FMT_HAS_CXX11_NOEXCEPT 0
-#endif
-
-#ifndef FMT_NOEXCEPT
-#  if FMT_EXCEPTIONS || FMT_HAS_CXX11_NOEXCEPT
-#    define FMT_NOEXCEPT FMT_DETECTED_NOEXCEPT
-#  else
-#    define FMT_NOEXCEPT
-#  endif
-#endif
-
-// [[noreturn]] is disabled on MSVC and NVCC because of bogus unreachable code
-// warnings.
-#if FMT_EXCEPTIONS && FMT_HAS_CPP_ATTRIBUTE(noreturn) && !FMT_MSC_VER && \
-    !FMT_NVCC
-#  define FMT_NORETURN [[noreturn]]
-#else
-#  define FMT_NORETURN
-#endif
-
-#if __cplusplus == 201103L || __cplusplus == 201402L
-#  if defined(__INTEL_COMPILER) || defined(__PGI)
-#    define FMT_FALLTHROUGH
-#  elif defined(__clang__)
-#    define FMT_FALLTHROUGH [[clang::fallthrough]]
-#  elif FMT_GCC_VERSION >= 700 && \
-      (!defined(__EDG_VERSION__) || __EDG_VERSION__ >= 520)
-#    define FMT_FALLTHROUGH [[gnu::fallthrough]]
-#  else
-#    define FMT_FALLTHROUGH
-#  endif
-#elif FMT_HAS_CPP17_ATTRIBUTE(fallthrough)
-#  define FMT_FALLTHROUGH [[fallthrough]]
-#else
-#  define FMT_FALLTHROUGH
-#endif
-
-#ifndef FMT_NODISCARD
-#  if FMT_HAS_CPP17_ATTRIBUTE(nodiscard)
-#    define FMT_NODISCARD [[nodiscard]]
-#  else
-#    define FMT_NODISCARD
-#  endif
-#endif
-
-#ifndef FMT_USE_FLOAT
-#  define FMT_USE_FLOAT 1
-#endif
-#ifndef FMT_USE_DOUBLE
-#  define FMT_USE_DOUBLE 1
-#endif
-#ifndef FMT_USE_LONG_DOUBLE
-#  define FMT_USE_LONG_DOUBLE 1
-#endif
-
-#ifndef FMT_INLINE
-#  if FMT_GCC_VERSION || FMT_CLANG_VERSION
-#    define FMT_INLINE inline __attribute__((always_inline))
-#  else
-#    define FMT_INLINE inline
-#  endif
-#endif
-
-#ifndef FMT_DEPRECATED
-#  if FMT_HAS_CPP14_ATTRIBUTE(deprecated) || FMT_MSC_VER >= 1900
-#    define FMT_DEPRECATED [[deprecated]]
-#  else
-#    if (defined(__GNUC__) && !defined(__LCC__)) || defined(__clang__)
-#      define FMT_DEPRECATED __attribute__((deprecated))
-#    elif FMT_MSC_VER
-#      define FMT_DEPRECATED __declspec(deprecated)
-#    else
-#      define FMT_DEPRECATED /* deprecated */
-#    endif
-#  endif
-#endif
-
-#ifndef FMT_BEGIN_NAMESPACE
-#  define FMT_BEGIN_NAMESPACE \
-    namespace fmt {           \
-    inline namespace v8 {
-#  define FMT_END_NAMESPACE \
-    }                       \
-    }
-#endif
-
-#ifndef FMT_MODULE_EXPORT
-#  define FMT_MODULE_EXPORT
-#  define FMT_MODULE_EXPORT_BEGIN
-#  define FMT_MODULE_EXPORT_END
-#  define FMT_BEGIN_DETAIL_NAMESPACE namespace detail {
-#  define FMT_END_DETAIL_NAMESPACE }
-#endif
-
-#if !defined(FMT_HEADER_ONLY) && defined(_WIN32)
-#  define FMT_CLASS_API FMT_MSC_WARNING(suppress : 4275)
-#  ifdef FMT_EXPORT
-#    define FMT_API __declspec(dllexport)
-#  elif defined(FMT_SHARED)
-#    define FMT_API __declspec(dllimport)
-#  endif
-#else
-#  define FMT_CLASS_API
-#  if defined(FMT_EXPORT) || defined(FMT_SHARED)
-#    if defined(__GNUC__) || defined(__clang__)
-#      define FMT_API __attribute__((visibility("default")))
-#    endif
-#  endif
-#endif
-#ifndef FMT_API
-#  define FMT_API
-#endif
-
-// libc++ supports string_view in pre-c++17.
-#if (FMT_HAS_INCLUDE(<string_view>) &&                       \
-     (__cplusplus > 201402L || defined(_LIBCPP_VERSION))) || \
-    (defined(_MSVC_LANG) && _MSVC_LANG > 201402L && _MSC_VER >= 1910)
-#  include <string_view>
-#  define FMT_USE_STRING_VIEW
-#elif FMT_HAS_INCLUDE("experimental/string_view") && __cplusplus >= 201402L
-#  include <experimental/string_view>
-#  define FMT_USE_EXPERIMENTAL_STRING_VIEW
-#endif
-
-#ifndef FMT_UNICODE
-#  define FMT_UNICODE !FMT_MSC_VER
-#endif
-
-#ifndef FMT_CONSTEVAL
-#  if ((FMT_GCC_VERSION >= 1000 || FMT_CLANG_VERSION >= 1101) &&      \
-       __cplusplus > 201703L && !defined(__apple_build_version__)) || \
-      (defined(__cpp_consteval) &&                                    \
-       (!FMT_MSC_VER || _MSC_FULL_VER >= 193030704))
-// consteval is broken in MSVC before VS2022 and Apple clang 13.
-#    define FMT_CONSTEVAL consteval
-#    define FMT_HAS_CONSTEVAL
-#  else
-#    define FMT_CONSTEVAL
-#  endif
-#endif
-
-#ifndef FMT_USE_NONTYPE_TEMPLATE_PARAMETERS
-#  if defined(__cpp_nontype_template_args) &&                \
-      ((FMT_GCC_VERSION >= 903 && __cplusplus >= 201709L) || \
-       __cpp_nontype_template_args >= 201911L)
-#    define FMT_USE_NONTYPE_TEMPLATE_PARAMETERS 1
-#  else
-#    define FMT_USE_NONTYPE_TEMPLATE_PARAMETERS 0
-#  endif
-#endif
-
-// Enable minimal optimizations for more compact code in debug mode.
-FMT_GCC_PRAGMA("GCC push_options")
-#ifndef __OPTIMIZE__
-FMT_GCC_PRAGMA("GCC optimize(\"Og\")")
-#endif
-
-FMT_BEGIN_NAMESPACE
-FMT_MODULE_EXPORT_BEGIN
-
-// Implementations of enable_if_t and other metafunctions for older systems.
-template <bool B, typename T = void>
-using enable_if_t = typename std::enable_if<B, T>::type;
-template <bool B, typename T, typename F>
-using conditional_t = typename std::conditional<B, T, F>::type;
-template <bool B> using bool_constant = std::integral_constant<bool, B>;
-template <typename T>
-using remove_reference_t = typename std::remove_reference<T>::type;
-template <typename T>
-using remove_const_t = typename std::remove_const<T>::type;
-template <typename T>
-using remove_cvref_t = typename std::remove_cv<remove_reference_t<T>>::type;
-template <typename T> struct type_identity { using type = T; };
-template <typename T> using type_identity_t = typename type_identity<T>::type;
-
-struct monostate {
-  constexpr monostate() {}
-};
-
-// An enable_if helper to be used in template parameters which results in much
-// shorter symbols: https://godbolt.org/z/sWw4vP. Extra parentheses are needed
-// to workaround a bug in MSVC 2019 (see #1140 and #1186).
-#ifdef FMT_DOC
-#  define FMT_ENABLE_IF(...)
-#else
-#  define FMT_ENABLE_IF(...) enable_if_t<(__VA_ARGS__), int> = 0
-#endif
-
-FMT_BEGIN_DETAIL_NAMESPACE
-
-// Suppress "unused variable" warnings with the method described in
-// https://herbsutter.com/2009/10/18/mailbag-shutting-up-compiler-warnings/.
-// (void)var does not work on many Intel compilers.
-template <typename... T> FMT_CONSTEXPR void ignore_unused(const T&...) {}
-
-constexpr FMT_INLINE auto is_constant_evaluated(bool default_value = false)
-    FMT_NOEXCEPT -> bool {
-#ifdef __cpp_lib_is_constant_evaluated
-  ignore_unused(default_value);
-  return std::is_constant_evaluated();
-#else
-  return default_value;
-#endif
-}
-
-// A function to suppress "conditional expression is constant" warnings.
-template <typename T> constexpr FMT_INLINE auto const_check(T value) -> T {
-  return value;
-}
-
-FMT_NORETURN FMT_API void assert_fail(const char* file, int line,
-                                      const char* message);
-
-#ifndef FMT_ASSERT
-#  ifdef NDEBUG
-// FMT_ASSERT is not empty to avoid -Werror=empty-body.
-#    define FMT_ASSERT(condition, message) \
-      ::fmt::detail::ignore_unused((condition), (message))
-#  else
-#    define FMT_ASSERT(condition, message)                                    \
-      ((condition) /* void() fails with -Winvalid-constexpr on clang 4.0.1 */ \
-           ? (void)0                                                          \
-           : ::fmt::detail::assert_fail(__FILE__, __LINE__, (message)))
-#  endif
-#endif
-
-#ifdef __cpp_lib_byte
-using byte = std::byte;
-#else
-enum class byte : unsigned char {};
-#endif
-
-#if defined(FMT_USE_STRING_VIEW)
-template <typename Char> using std_string_view = std::basic_string_view<Char>;
-#elif defined(FMT_USE_EXPERIMENTAL_STRING_VIEW)
-template <typename Char>
-using std_string_view = std::experimental::basic_string_view<Char>;
-#else
-template <typename T> struct std_string_view {};
-#endif
-
-#ifdef FMT_USE_INT128
-// Do nothing.
-#elif defined(__SIZEOF_INT128__) && !FMT_NVCC && \
-    !(FMT_CLANG_VERSION && FMT_MSC_VER)
-#  define FMT_USE_INT128 1
-using int128_t = __int128_t;
-using uint128_t = __uint128_t;
-template <typename T> inline auto convert_for_visit(T value) -> T {
-  return value;
-}
-#else
-#  define FMT_USE_INT128 0
-#endif
-#if !FMT_USE_INT128
-enum class int128_t {};
-enum class uint128_t {};
-// Reduce template instantiations.
-template <typename T> inline auto convert_for_visit(T) -> monostate {
-  return {};
-}
-#endif
-
-// Casts a nonnegative integer to unsigned.
-template <typename Int>
-FMT_CONSTEXPR auto to_unsigned(Int value) ->
-    typename std::make_unsigned<Int>::type {
-  FMT_ASSERT(value >= 0, "negative value");
-  return static_cast<typename std::make_unsigned<Int>::type>(value);
-}
-
-FMT_MSC_WARNING(suppress : 4566) constexpr unsigned char micro[] = "\u00B5";
-
-constexpr auto is_utf8() -> bool {
-  // Avoid buggy sign extensions in MSVC's constant evaluation mode.
-  // https://developercommunity.visualstudio.com/t/C-difference-in-behavior-for-unsigned/1233612
-  using uchar = unsigned char;
-  return FMT_UNICODE || (sizeof(micro) == 3 && uchar(micro[0]) == 0xC2 &&
-                         uchar(micro[1]) == 0xB5);
-}
-FMT_END_DETAIL_NAMESPACE
-
-/**
-  An implementation of ``std::basic_string_view`` for pre-C++17. It provides a
-  subset of the API. ``fmt::basic_string_view`` is used for format strings even
-  if ``std::string_view`` is available to prevent issues when a library is
-  compiled with a different ``-std`` option than the client code (which is not
-  recommended).
- */
-template <typename Char> class basic_string_view {
- private:
-  const Char* data_;
-  size_t size_;
-
- public:
-  using value_type = Char;
-  using iterator = const Char*;
-
-  constexpr basic_string_view() FMT_NOEXCEPT : data_(nullptr), size_(0) {}
-
-  /** Constructs a string reference object from a C string and a size. */
-  constexpr basic_string_view(const Char* s, size_t count) FMT_NOEXCEPT
-      : data_(s),
-        size_(count) {}
-
-  /**
-    \rst
-    Constructs a string reference object from a C string computing
-    the size with ``std::char_traits<Char>::length``.
-    \endrst
-   */
-  FMT_CONSTEXPR_CHAR_TRAITS
-  FMT_INLINE
-  basic_string_view(const Char* s)
-      : data_(s),
-        size_(detail::const_check(std::is_same<Char, char>::value &&
-                                  !detail::is_constant_evaluated(true))
-                  ? std::strlen(reinterpret_cast<const char*>(s))
-                  : std::char_traits<Char>::length(s)) {}
-
-  /** Constructs a string reference from a ``std::basic_string`` object. */
-  template <typename Traits, typename Alloc>
-  FMT_CONSTEXPR basic_string_view(
-      const std::basic_string<Char, Traits, Alloc>& s) FMT_NOEXCEPT
-      : data_(s.data()),
-        size_(s.size()) {}
-
-  template <typename S, FMT_ENABLE_IF(std::is_same<
-                                      S, detail::std_string_view<Char>>::value)>
-  FMT_CONSTEXPR basic_string_view(S s) FMT_NOEXCEPT : data_(s.data()),
-                                                      size_(s.size()) {}
-
-  /** Returns a pointer to the string data. */
-  constexpr auto data() const FMT_NOEXCEPT -> const Char* { return data_; }
-
-  /** Returns the string size. */
-  constexpr auto size() const FMT_NOEXCEPT -> size_t { return size_; }
-
-  constexpr auto begin() const FMT_NOEXCEPT -> iterator { return data_; }
-  constexpr auto end() const FMT_NOEXCEPT -> iterator { return data_ + size_; }
-
-  constexpr auto operator[](size_t pos) const FMT_NOEXCEPT -> const Char& {
-    return data_[pos];
-  }
-
-  FMT_CONSTEXPR void remove_prefix(size_t n) FMT_NOEXCEPT {
-    data_ += n;
-    size_ -= n;
-  }
-
-  // Lexicographically compare this string reference to other.
-  FMT_CONSTEXPR_CHAR_TRAITS auto compare(basic_string_view other) const -> int {
-    size_t str_size = size_ < other.size_ ? size_ : other.size_;
-    int result = std::char_traits<Char>::compare(data_, other.data_, str_size);
-    if (result == 0)
-      result = size_ == other.size_ ? 0 : (size_ < other.size_ ? -1 : 1);
-    return result;
-  }
-
-  FMT_CONSTEXPR_CHAR_TRAITS friend auto operator==(basic_string_view lhs,
-                                                   basic_string_view rhs)
-      -> bool {
-    return lhs.compare(rhs) == 0;
-  }
-  friend auto operator!=(basic_string_view lhs, basic_string_view rhs) -> bool {
-    return lhs.compare(rhs) != 0;
-  }
-  friend auto operator<(basic_string_view lhs, basic_string_view rhs) -> bool {
-    return lhs.compare(rhs) < 0;
-  }
-  friend auto operator<=(basic_string_view lhs, basic_string_view rhs) -> bool {
-    return lhs.compare(rhs) <= 0;
-  }
-  friend auto operator>(basic_string_view lhs, basic_string_view rhs) -> bool {
-    return lhs.compare(rhs) > 0;
-  }
-  friend auto operator>=(basic_string_view lhs, basic_string_view rhs) -> bool {
-    return lhs.compare(rhs) >= 0;
-  }
-};
-
-using string_view = basic_string_view<char>;
-
-/** Specifies if ``T`` is a character type. Can be specialized by users. */
-template <typename T> struct is_char : std::false_type {};
-template <> struct is_char<char> : std::true_type {};
-
-// Returns a string view of `s`.
-template <typename Char, FMT_ENABLE_IF(is_char<Char>::value)>
-FMT_INLINE auto to_string_view(const Char* s) -> basic_string_view<Char> {
-  return s;
-}
-template <typename Char, typename Traits, typename Alloc>
-inline auto to_string_view(const std::basic_string<Char, Traits, Alloc>& s)
-    -> basic_string_view<Char> {
-  return s;
-}
-template <typename Char>
-constexpr auto to_string_view(basic_string_view<Char> s)
-    -> basic_string_view<Char> {
-  return s;
-}
-template <typename Char,
-          FMT_ENABLE_IF(!std::is_empty<detail::std_string_view<Char>>::value)>
-inline auto to_string_view(detail::std_string_view<Char> s)
-    -> basic_string_view<Char> {
-  return s;
-}
-
-// A base class for compile-time strings. It is defined in the fmt namespace to
-// make formatting functions visible via ADL, e.g. format(FMT_STRING("{}"), 42).
-struct compile_string {};
-
-template <typename S>
-struct is_compile_string : std::is_base_of<compile_string, S> {};
-
-template <typename S, FMT_ENABLE_IF(is_compile_string<S>::value)>
-constexpr auto to_string_view(const S& s)
-    -> basic_string_view<typename S::char_type> {
-  return basic_string_view<typename S::char_type>(s);
-}
-
-FMT_BEGIN_DETAIL_NAMESPACE
-
-void to_string_view(...);
-using fmt::to_string_view;
-
-// Specifies whether S is a string type convertible to fmt::basic_string_view.
-// It should be a constexpr function but MSVC 2017 fails to compile it in
-// enable_if and MSVC 2015 fails to compile it as an alias template.
-template <typename S>
-struct is_string : std::is_class<decltype(to_string_view(std::declval<S>()))> {
-};
-
-template <typename S, typename = void> struct char_t_impl {};
-template <typename S> struct char_t_impl<S, enable_if_t<is_string<S>::value>> {
-  using result = decltype(to_string_view(std::declval<S>()));
-  using type = typename result::value_type;
-};
-
-// Reports a compile-time error if S is not a valid format string.
-template <typename..., typename S, FMT_ENABLE_IF(!is_compile_string<S>::value)>
-FMT_INLINE void check_format_string(const S&) {
-#ifdef FMT_ENFORCE_COMPILE_STRING
-  static_assert(is_compile_string<S>::value,
-                "FMT_ENFORCE_COMPILE_STRING requires all format strings to use "
-                "FMT_STRING.");
-#endif
-}
-template <typename..., typename S, FMT_ENABLE_IF(is_compile_string<S>::value)>
-void check_format_string(S);
-
-FMT_NORETURN FMT_API void throw_format_error(const char* message);
-
-struct error_handler {
-  constexpr error_handler() = default;
-  constexpr error_handler(const error_handler&) = default;
-
-  // This function is intentionally not constexpr to give a compile-time error.
-  FMT_NORETURN FMT_API void on_error(const char* message);
-};
-FMT_END_DETAIL_NAMESPACE
-
-/** String's character type. */
-template <typename S> using char_t = typename detail::char_t_impl<S>::type;
-
-/**
-  \rst
-  Parsing context consisting of a format string range being parsed and an
-  argument counter for automatic indexing.
-  You can use the ``format_parse_context`` type alias for ``char`` instead.
-  \endrst
- */
-template <typename Char, typename ErrorHandler = detail::error_handler>
-class basic_format_parse_context : private ErrorHandler {
- private:
-  basic_string_view<Char> format_str_;
-  int next_arg_id_;
-
- public:
-  using char_type = Char;
-  using iterator = typename basic_string_view<Char>::iterator;
-
-  explicit constexpr basic_format_parse_context(
-      basic_string_view<Char> format_str, ErrorHandler eh = {},
-      int next_arg_id = 0)
-      : ErrorHandler(eh), format_str_(format_str), next_arg_id_(next_arg_id) {}
-
-  /**
-    Returns an iterator to the beginning of the format string range being
-    parsed.
-   */
-  constexpr auto begin() const FMT_NOEXCEPT -> iterator {
-    return format_str_.begin();
-  }
-
-  /**
-    Returns an iterator past the end of the format string range being parsed.
-   */
-  constexpr auto end() const FMT_NOEXCEPT -> iterator {
-    return format_str_.end();
-  }
-
-  /** Advances the begin iterator to ``it``. */
-  FMT_CONSTEXPR void advance_to(iterator it) {
-    format_str_.remove_prefix(detail::to_unsigned(it - begin()));
-  }
-
-  /**
-    Reports an error if using the manual argument indexing; otherwise returns
-    the next argument index and switches to the automatic indexing.
-   */
-  FMT_CONSTEXPR auto next_arg_id() -> int {
-    // Don't check if the argument id is valid to avoid overhead and because it
-    // will be checked during formatting anyway.
-    if (next_arg_id_ >= 0) return next_arg_id_++;
-    on_error("cannot switch from manual to automatic argument indexing");
-    return 0;
-  }
-
-  /**
-    Reports an error if using the automatic argument indexing; otherwise
-    switches to the manual indexing.
-   */
-  FMT_CONSTEXPR void check_arg_id(int) {
-    if (next_arg_id_ > 0)
-      on_error("cannot switch from automatic to manual argument indexing");
-    else
-      next_arg_id_ = -1;
-  }
-
-  FMT_CONSTEXPR void check_arg_id(basic_string_view<Char>) {}
-
-  FMT_CONSTEXPR void on_error(const char* message) {
-    ErrorHandler::on_error(message);
-  }
-
-  constexpr auto error_handler() const -> ErrorHandler { return *this; }
-};
-
-using format_parse_context = basic_format_parse_context<char>;
-
-template <typename Context> class basic_format_arg;
-template <typename Context> class basic_format_args;
-template <typename Context> class dynamic_format_arg_store;
-
-// A formatter for objects of type T.
-template <typename T, typename Char = char, typename Enable = void>
-struct formatter {
-  // A deleted default constructor indicates a disabled formatter.
-  formatter() = delete;
-};
-
-// Specifies if T has an enabled formatter specialization. A type can be
-// formattable even if it doesn't have a formatter e.g. via a conversion.
-template <typename T, typename Context>
-using has_formatter =
-    std::is_constructible<typename Context::template formatter_type<T>>;
-
-// Checks whether T is a container with contiguous storage.
-template <typename T> struct is_contiguous : std::false_type {};
-template <typename Char>
-struct is_contiguous<std::basic_string<Char>> : std::true_type {};
-
-class appender;
-
-FMT_BEGIN_DETAIL_NAMESPACE
-
-template <typename Context, typename T>
-constexpr auto has_const_formatter_impl(T*)
-    -> decltype(typename Context::template formatter_type<T>().format(
-                    std::declval<const T&>(), std::declval<Context&>()),
-                true) {
-  return true;
-}
-template <typename Context>
-constexpr auto has_const_formatter_impl(...) -> bool {
-  return false;
-}
-template <typename T, typename Context>
-constexpr auto has_const_formatter() -> bool {
-  return has_const_formatter_impl<Context>(static_cast<T*>(nullptr));
-}
-
-// Extracts a reference to the container from back_insert_iterator.
-template <typename Container>
-inline auto get_container(std::back_insert_iterator<Container> it)
-    -> Container& {
-  using bi_iterator = std::back_insert_iterator<Container>;
-  struct accessor : bi_iterator {
-    accessor(bi_iterator iter) : bi_iterator(iter) {}
-    using bi_iterator::container;
-  };
-  return *accessor(it).container;
-}
-
-template <typename Char, typename InputIt, typename OutputIt>
-FMT_CONSTEXPR auto copy_str(InputIt begin, InputIt end, OutputIt out)
-    -> OutputIt {
-  while (begin != end) *out++ = static_cast<Char>(*begin++);
-  return out;
-}
-
-template <typename Char, typename T, typename U,
-          FMT_ENABLE_IF(
-              std::is_same<remove_const_t<T>, U>::value&& is_char<U>::value)>
-FMT_CONSTEXPR auto copy_str(T* begin, T* end, U* out) -> U* {
-  if (is_constant_evaluated()) return copy_str<Char, T*, U*>(begin, end, out);
-  auto size = to_unsigned(end - begin);
-  memcpy(out, begin, size * sizeof(U));
-  return out + size;
-}
-
-/**
-  \rst
-  A contiguous memory buffer with an optional growing ability. It is an internal
-  class and shouldn't be used directly, only via `~fmt::basic_memory_buffer`.
-  \endrst
- */
-template <typename T> class buffer {
- private:
-  T* ptr_;
-  size_t size_;
-  size_t capacity_;
-
- protected:
-  // Don't initialize ptr_ since it is not accessed to save a few cycles.
-  FMT_MSC_WARNING(suppress : 26495)
-  buffer(size_t sz) FMT_NOEXCEPT : size_(sz), capacity_(sz) {}
-
-  FMT_CONSTEXPR20 buffer(T* p = nullptr, size_t sz = 0,
-                         size_t cap = 0) FMT_NOEXCEPT : ptr_(p),
-                                                        size_(sz),
-                                                        capacity_(cap) {}
-
-  FMT_CONSTEXPR20 ~buffer() = default;
-  buffer(buffer&&) = default;
-
-  /** Sets the buffer data and capacity. */
-  FMT_CONSTEXPR void set(T* buf_data, size_t buf_capacity) FMT_NOEXCEPT {
-    ptr_ = buf_data;
-    capacity_ = buf_capacity;
-  }
-
-  /** Increases the buffer capacity to hold at least *capacity* elements. */
-  virtual FMT_CONSTEXPR20 void grow(size_t capacity) = 0;
-
- public:
-  using value_type = T;
-  using const_reference = const T&;
-
-  buffer(const buffer&) = delete;
-  void operator=(const buffer&) = delete;
-
-  auto begin() FMT_NOEXCEPT -> T* { return ptr_; }
-  auto end() FMT_NOEXCEPT -> T* { return ptr_ + size_; }
-
-  auto begin() const FMT_NOEXCEPT -> const T* { return ptr_; }
-  auto end() const FMT_NOEXCEPT -> const T* { return ptr_ + size_; }
-
-  /** Returns the size of this buffer. */
-  constexpr auto size() const FMT_NOEXCEPT -> size_t { return size_; }
-
-  /** Returns the capacity of this buffer. */
-  constexpr auto capacity() const FMT_NOEXCEPT -> size_t { return capacity_; }
-
-  /** Returns a pointer to the buffer data. */
-  FMT_CONSTEXPR auto data() FMT_NOEXCEPT -> T* { return ptr_; }
-
-  /** Returns a pointer to the buffer data. */
-  FMT_CONSTEXPR auto data() const FMT_NOEXCEPT -> const T* { return ptr_; }
-
-  /** Clears this buffer. */
-  void clear() { size_ = 0; }
-
-  // Tries resizing the buffer to contain *count* elements. If T is a POD type
-  // the new elements may not be initialized.
-  FMT_CONSTEXPR20 void try_resize(size_t count) {
-    try_reserve(count);
-    size_ = count <= capacity_ ? count : capacity_;
-  }
-
-  // Tries increasing the buffer capacity to *new_capacity*. It can increase the
-  // capacity by a smaller amount than requested but guarantees there is space
-  // for at least one additional element either by increasing the capacity or by
-  // flushing the buffer if it is full.
-  FMT_CONSTEXPR20 void try_reserve(size_t new_capacity) {
-    if (new_capacity > capacity_) grow(new_capacity);
-  }
-
-  FMT_CONSTEXPR20 void push_back(const T& value) {
-    try_reserve(size_ + 1);
-    ptr_[size_++] = value;
-  }
-
-  /** Appends data to the end of the buffer. */
-  template <typename U> void append(const U* begin, const U* end);
-
-  template <typename I> FMT_CONSTEXPR auto operator[](I index) -> T& {
-    return ptr_[index];
-  }
-  template <typename I>
-  FMT_CONSTEXPR auto operator[](I index) const -> const T& {
-    return ptr_[index];
-  }
-};
-
-struct buffer_traits {
-  explicit buffer_traits(size_t) {}
-  auto count() const -> size_t { return 0; }
-  auto limit(size_t size) -> size_t { return size; }
-};
-
-class fixed_buffer_traits {
- private:
-  size_t count_ = 0;
-  size_t limit_;
-
- public:
-  explicit fixed_buffer_traits(size_t limit) : limit_(limit) {}
-  auto count() const -> size_t { return count_; }
-  auto limit(size_t size) -> size_t {
-    size_t n = limit_ > count_ ? limit_ - count_ : 0;
-    count_ += size;
-    return size < n ? size : n;
-  }
-};
-
-// A buffer that writes to an output iterator when flushed.
-template <typename OutputIt, typename T, typename Traits = buffer_traits>
-class iterator_buffer final : public Traits, public buffer<T> {
- private:
-  OutputIt out_;
-  enum { buffer_size = 256 };
-  T data_[buffer_size];
-
- protected:
-  FMT_CONSTEXPR20 void grow(size_t) override {
-    if (this->size() == buffer_size) flush();
-  }
-
-  void flush() {
-    auto size = this->size();
-    this->clear();
-    out_ = copy_str<T>(data_, data_ + this->limit(size), out_);
-  }
-
- public:
-  explicit iterator_buffer(OutputIt out, size_t n = buffer_size)
-      : Traits(n), buffer<T>(data_, 0, buffer_size), out_(out) {}
-  iterator_buffer(iterator_buffer&& other)
-      : Traits(other), buffer<T>(data_, 0, buffer_size), out_(other.out_) {}
-  ~iterator_buffer() { flush(); }
-
-  auto out() -> OutputIt {
-    flush();
-    return out_;
-  }
-  auto count() const -> size_t { return Traits::count() + this->size(); }
-};
-
-template <typename T>
-class iterator_buffer<T*, T, fixed_buffer_traits> final
-    : public fixed_buffer_traits,
-      public buffer<T> {
- private:
-  T* out_;
-  enum { buffer_size = 256 };
-  T data_[buffer_size];
-
- protected:
-  FMT_CONSTEXPR20 void grow(size_t) override {
-    if (this->size() == this->capacity()) flush();
-  }
-
-  void flush() {
-    size_t n = this->limit(this->size());
-    if (this->data() == out_) {
-      out_ += n;
-      this->set(data_, buffer_size);
-    }
-    this->clear();
-  }
-
- public:
-  explicit iterator_buffer(T* out, size_t n = buffer_size)
-      : fixed_buffer_traits(n), buffer<T>(out, 0, n), out_(out) {}
-  iterator_buffer(iterator_buffer&& other)
-      : fixed_buffer_traits(other),
-        buffer<T>(std::move(other)),
-        out_(other.out_) {
-    if (this->data() != out_) {
-      this->set(data_, buffer_size);
-      this->clear();
-    }
-  }
-  ~iterator_buffer() { flush(); }
-
-  auto out() -> T* {
-    flush();
-    return out_;
-  }
-  auto count() const -> size_t {
-    return fixed_buffer_traits::count() + this->size();
-  }
-};
-
-template <typename T> class iterator_buffer<T*, T> final : public buffer<T> {
- protected:
-  FMT_CONSTEXPR20 void grow(size_t) override {}
-
- public:
-  explicit iterator_buffer(T* out, size_t = 0) : buffer<T>(out, 0, ~size_t()) {}
-
-  auto out() -> T* { return &*this->end(); }
-};
-
-// A buffer that writes to a container with the contiguous storage.
-template <typename Container>
-class iterator_buffer<std::back_insert_iterator<Container>,
-                      enable_if_t<is_contiguous<Container>::value,
-                                  typename Container::value_type>>
-    final : public buffer<typename Container::value_type> {
- private:
-  Container& container_;
-
- protected:
-  FMT_CONSTEXPR20 void grow(size_t capacity) override {
-    container_.resize(capacity);
-    this->set(&container_[0], capacity);
-  }
-
- public:
-  explicit iterator_buffer(Container& c)
-      : buffer<typename Container::value_type>(c.size()), container_(c) {}
-  explicit iterator_buffer(std::back_insert_iterator<Container> out, size_t = 0)
-      : iterator_buffer(get_container(out)) {}
-  auto out() -> std::back_insert_iterator<Container> {
-    return std::back_inserter(container_);
-  }
-};
-
-// A buffer that counts the number of code units written discarding the output.
-template <typename T = char> class counting_buffer final : public buffer<T> {
- private:
-  enum { buffer_size = 256 };
-  T data_[buffer_size];
-  size_t count_ = 0;
-
- protected:
-  FMT_CONSTEXPR20 void grow(size_t) override {
-    if (this->size() != buffer_size) return;
-    count_ += this->size();
-    this->clear();
-  }
-
- public:
-  counting_buffer() : buffer<T>(data_, 0, buffer_size) {}
-
-  auto count() -> size_t { return count_ + this->size(); }
-};
-
-template <typename T>
-using buffer_appender = conditional_t<std::is_same<T, char>::value, appender,
-                                      std::back_insert_iterator<buffer<T>>>;
-
-// Maps an output iterator to a buffer.
-template <typename T, typename OutputIt>
-auto get_buffer(OutputIt out) -> iterator_buffer<OutputIt, T> {
-  return iterator_buffer<OutputIt, T>(out);
-}
-
-template <typename Buffer>
-auto get_iterator(Buffer& buf) -> decltype(buf.out()) {
-  return buf.out();
-}
-template <typename T> auto get_iterator(buffer<T>& buf) -> buffer_appender<T> {
-  return buffer_appender<T>(buf);
-}
-
-template <typename T, typename Char = char, typename Enable = void>
-struct fallback_formatter {
-  fallback_formatter() = delete;
-};
-
-// Specifies if T has an enabled fallback_formatter specialization.
-template <typename T, typename Char>
-using has_fallback_formatter =
-    std::is_constructible<fallback_formatter<T, Char>>;
-
-struct view {};
-
-template <typename Char, typename T> struct named_arg : view {
-  const Char* name;
-  const T& value;
-  named_arg(const Char* n, const T& v) : name(n), value(v) {}
-};
-
-template <typename Char> struct named_arg_info {
-  const Char* name;
-  int id;
-};
-
-template <typename T, typename Char, size_t NUM_ARGS, size_t NUM_NAMED_ARGS>
-struct arg_data {
-  // args_[0].named_args points to named_args_ to avoid bloating format_args.
-  // +1 to workaround a bug in gcc 7.5 that causes duplicated-branches warning.
-  T args_[1 + (NUM_ARGS != 0 ? NUM_ARGS : +1)];
-  named_arg_info<Char> named_args_[NUM_NAMED_ARGS];
-
-  template <typename... U>
-  arg_data(const U&... init) : args_{T(named_args_, NUM_NAMED_ARGS), init...} {}
-  arg_data(const arg_data& other) = delete;
-  auto args() const -> const T* { return args_ + 1; }
-  auto named_args() -> named_arg_info<Char>* { return named_args_; }
-};
-
-template <typename T, typename Char, size_t NUM_ARGS>
-struct arg_data<T, Char, NUM_ARGS, 0> {
-  // +1 to workaround a bug in gcc 7.5 that causes duplicated-branches warning.
-  T args_[NUM_ARGS != 0 ? NUM_ARGS : +1];
-
-  template <typename... U>
-  FMT_CONSTEXPR FMT_INLINE arg_data(const U&... init) : args_{init...} {}
-  FMT_CONSTEXPR FMT_INLINE auto args() const -> const T* { return args_; }
-  FMT_CONSTEXPR FMT_INLINE auto named_args() -> std::nullptr_t {
-    return nullptr;
-  }
-};
-
-template <typename Char>
-inline void init_named_args(named_arg_info<Char>*, int, int) {}
-
-template <typename T> struct is_named_arg : std::false_type {};
-template <typename T> struct is_statically_named_arg : std::false_type {};
-
-template <typename T, typename Char>
-struct is_named_arg<named_arg<Char, T>> : std::true_type {};
-
-template <typename Char, typename T, typename... Tail,
-          FMT_ENABLE_IF(!is_named_arg<T>::value)>
-void init_named_args(named_arg_info<Char>* named_args, int arg_count,
-                     int named_arg_count, const T&, const Tail&... args) {
-  init_named_args(named_args, arg_count + 1, named_arg_count, args...);
-}
-
-template <typename Char, typename T, typename... Tail,
-          FMT_ENABLE_IF(is_named_arg<T>::value)>
-void init_named_args(named_arg_info<Char>* named_args, int arg_count,
-                     int named_arg_count, const T& arg, const Tail&... args) {
-  named_args[named_arg_count++] = {arg.name, arg_count};
-  init_named_args(named_args, arg_count + 1, named_arg_count, args...);
-}
-
-template <typename... Args>
-FMT_CONSTEXPR FMT_INLINE void init_named_args(std::nullptr_t, int, int,
-                                              const Args&...) {}
-
-template <bool B = false> constexpr auto count() -> size_t { return B ? 1 : 0; }
-template <bool B1, bool B2, bool... Tail> constexpr auto count() -> size_t {
-  return (B1 ? 1 : 0) + count<B2, Tail...>();
-}
-
-template <typename... Args> constexpr auto count_named_args() -> size_t {
-  return count<is_named_arg<Args>::value...>();
-}
-
-template <typename... Args>
-constexpr auto count_statically_named_args() -> size_t {
-  return count<is_statically_named_arg<Args>::value...>();
-}
-
-enum class type {
-  none_type,
-  // Integer types should go first,
-  int_type,
-  uint_type,
-  long_long_type,
-  ulong_long_type,
-  int128_type,
-  uint128_type,
-  bool_type,
-  char_type,
-  last_integer_type = char_type,
-  // followed by floating-point types.
-  float_type,
-  double_type,
-  long_double_type,
-  last_numeric_type = long_double_type,
-  cstring_type,
-  string_type,
-  pointer_type,
-  custom_type
-};
-
-// Maps core type T to the corresponding type enum constant.
-template <typename T, typename Char>
-struct type_constant : std::integral_constant<type, type::custom_type> {};
-
-#define FMT_TYPE_CONSTANT(Type, constant) \
-  template <typename Char>                \
-  struct type_constant<Type, Char>        \
-      : std::integral_constant<type, type::constant> {}
-
-FMT_TYPE_CONSTANT(int, int_type);
-FMT_TYPE_CONSTANT(unsigned, uint_type);
-FMT_TYPE_CONSTANT(long long, long_long_type);
-FMT_TYPE_CONSTANT(unsigned long long, ulong_long_type);
-FMT_TYPE_CONSTANT(int128_t, int128_type);
-FMT_TYPE_CONSTANT(uint128_t, uint128_type);
-FMT_TYPE_CONSTANT(bool, bool_type);
-FMT_TYPE_CONSTANT(Char, char_type);
-FMT_TYPE_CONSTANT(float, float_type);
-FMT_TYPE_CONSTANT(double, double_type);
-FMT_TYPE_CONSTANT(long double, long_double_type);
-FMT_TYPE_CONSTANT(const Char*, cstring_type);
-FMT_TYPE_CONSTANT(basic_string_view<Char>, string_type);
-FMT_TYPE_CONSTANT(const void*, pointer_type);
-
-constexpr bool is_integral_type(type t) {
-  return t > type::none_type && t <= type::last_integer_type;
-}
-
-constexpr bool is_arithmetic_type(type t) {
-  return t > type::none_type && t <= type::last_numeric_type;
-}
-
-struct unformattable {};
-struct unformattable_char : unformattable {};
-struct unformattable_const : unformattable {};
-struct unformattable_pointer : unformattable {};
-
-template <typename Char> struct string_value {
-  const Char* data;
-  size_t size;
-};
-
-template <typename Char> struct named_arg_value {
-  const named_arg_info<Char>* data;
-  size_t size;
-};
-
-template <typename Context> struct custom_value {
-  using parse_context = typename Context::parse_context_type;
-  void* value;
-  void (*format)(void* arg, parse_context& parse_ctx, Context& ctx);
-};
-
-// A formatting argument value.
-template <typename Context> class value {
- public:
-  using char_type = typename Context::char_type;
-
-  union {
-    monostate no_value;
-    int int_value;
-    unsigned uint_value;
-    long long long_long_value;
-    unsigned long long ulong_long_value;
-    int128_t int128_value;
-    uint128_t uint128_value;
-    bool bool_value;
-    char_type char_value;
-    float float_value;
-    double double_value;
-    long double long_double_value;
-    const void* pointer;
-    string_value<char_type> string;
-    custom_value<Context> custom;
-    named_arg_value<char_type> named_args;
-  };
-
-  constexpr FMT_INLINE value() : no_value() {}
-  constexpr FMT_INLINE value(int val) : int_value(val) {}
-  constexpr FMT_INLINE value(unsigned val) : uint_value(val) {}
-  constexpr FMT_INLINE value(long long val) : long_long_value(val) {}
-  constexpr FMT_INLINE value(unsigned long long val) : ulong_long_value(val) {}
-  FMT_INLINE value(int128_t val) : int128_value(val) {}
-  FMT_INLINE value(uint128_t val) : uint128_value(val) {}
-  constexpr FMT_INLINE value(float val) : float_value(val) {}
-  constexpr FMT_INLINE value(double val) : double_value(val) {}
-  FMT_INLINE value(long double val) : long_double_value(val) {}
-  constexpr FMT_INLINE value(bool val) : bool_value(val) {}
-  constexpr FMT_INLINE value(char_type val) : char_value(val) {}
-  FMT_CONSTEXPR FMT_INLINE value(const char_type* val) {
-    string.data = val;
-    if (is_constant_evaluated()) string.size = {};
-  }
-  FMT_CONSTEXPR FMT_INLINE value(basic_string_view<char_type> val) {
-    string.data = val.data();
-    string.size = val.size();
-  }
-  FMT_INLINE value(const void* val) : pointer(val) {}
-  FMT_INLINE value(const named_arg_info<char_type>* args, size_t size)
-      : named_args{args, size} {}
-
-  template <typename T> FMT_CONSTEXPR FMT_INLINE value(T& val) {
-    using value_type = remove_cvref_t<T>;
-    custom.value = const_cast<value_type*>(&val);
-    // Get the formatter type through the context to allow different contexts
-    // have different extension points, e.g. `formatter<T>` for `format` and
-    // `printf_formatter<T>` for `printf`.
-    custom.format = format_custom_arg<
-        value_type,
-        conditional_t<has_formatter<value_type, Context>::value,
-                      typename Context::template formatter_type<value_type>,
-                      fallback_formatter<value_type, char_type>>>;
-  }
-  value(unformattable);
-  value(unformattable_char);
-  value(unformattable_const);
-  value(unformattable_pointer);
-
- private:
-  // Formats an argument of a custom type, such as a user-defined class.
-  template <typename T, typename Formatter>
-  static void format_custom_arg(void* arg,
-                                typename Context::parse_context_type& parse_ctx,
-                                Context& ctx) {
-    auto f = Formatter();
-    parse_ctx.advance_to(f.parse(parse_ctx));
-    using qualified_type =
-        conditional_t<has_const_formatter<T, Context>(), const T, T>;
-    ctx.advance_to(f.format(*static_cast<qualified_type*>(arg), ctx));
-  }
-};
-
-template <typename Context, typename T>
-FMT_CONSTEXPR auto make_arg(const T& value) -> basic_format_arg<Context>;
-
-// To minimize the number of types we need to deal with, long is translated
-// either to int or to long long depending on its size.
-enum { long_short = sizeof(long) == sizeof(int) };
-using long_type = conditional_t<long_short, int, long long>;
-using ulong_type = conditional_t<long_short, unsigned, unsigned long long>;
-
-// Maps formatting arguments to core types.
-// arg_mapper reports errors by returning unformattable instead of using
-// static_assert because it's used in the is_formattable trait.
-template <typename Context> struct arg_mapper {
-  using char_type = typename Context::char_type;
-
-  FMT_CONSTEXPR FMT_INLINE auto map(signed char val) -> int { return val; }
-  FMT_CONSTEXPR FMT_INLINE auto map(unsigned char val) -> unsigned {
-    return val;
-  }
-  FMT_CONSTEXPR FMT_INLINE auto map(short val) -> int { return val; }
-  FMT_CONSTEXPR FMT_INLINE auto map(unsigned short val) -> unsigned {
-    return val;
-  }
-  FMT_CONSTEXPR FMT_INLINE auto map(int val) -> int { return val; }
-  FMT_CONSTEXPR FMT_INLINE auto map(unsigned val) -> unsigned { return val; }
-  FMT_CONSTEXPR FMT_INLINE auto map(long val) -> long_type { return val; }
-  FMT_CONSTEXPR FMT_INLINE auto map(unsigned long val) -> ulong_type {
-    return val;
-  }
-  FMT_CONSTEXPR FMT_INLINE auto map(long long val) -> long long { return val; }
-  FMT_CONSTEXPR FMT_INLINE auto map(unsigned long long val)
-      -> unsigned long long {
-    return val;
-  }
-  FMT_CONSTEXPR FMT_INLINE auto map(int128_t val) -> int128_t { return val; }
-  FMT_CONSTEXPR FMT_INLINE auto map(uint128_t val) -> uint128_t { return val; }
-  FMT_CONSTEXPR FMT_INLINE auto map(bool val) -> bool { return val; }
-
-  template <typename T, FMT_ENABLE_IF(std::is_same<T, char>::value ||
-                                      std::is_same<T, char_type>::value)>
-  FMT_CONSTEXPR FMT_INLINE auto map(T val) -> char_type {
-    return val;
-  }
-  template <typename T, enable_if_t<(std::is_same<T, wchar_t>::value ||
-#ifdef __cpp_char8_t
-                                     std::is_same<T, char8_t>::value ||
-#endif
-                                     std::is_same<T, char16_t>::value ||
-                                     std::is_same<T, char32_t>::value) &&
-                                        !std::is_same<T, char_type>::value,
-                                    int> = 0>
-  FMT_CONSTEXPR FMT_INLINE auto map(T) -> unformattable_char {
-    return {};
-  }
-
-  FMT_CONSTEXPR FMT_INLINE auto map(float val) -> float { return val; }
-  FMT_CONSTEXPR FMT_INLINE auto map(double val) -> double { return val; }
-  FMT_CONSTEXPR FMT_INLINE auto map(long double val) -> long double {
-    return val;
-  }
-
-  FMT_CONSTEXPR FMT_INLINE auto map(char_type* val) -> const char_type* {
-    return val;
-  }
-  FMT_CONSTEXPR FMT_INLINE auto map(const char_type* val) -> const char_type* {
-    return val;
-  }
-  template <typename T,
-            FMT_ENABLE_IF(is_string<T>::value && !std::is_pointer<T>::value &&
-                          std::is_same<char_type, char_t<T>>::value)>
-  FMT_CONSTEXPR FMT_INLINE auto map(const T& val)
-      -> basic_string_view<char_type> {
-    return to_string_view(val);
-  }
-  template <typename T,
-            FMT_ENABLE_IF(is_string<T>::value && !std::is_pointer<T>::value &&
-                          !std::is_same<char_type, char_t<T>>::value)>
-  FMT_CONSTEXPR FMT_INLINE auto map(const T&) -> unformattable_char {
-    return {};
-  }
-  template <typename T,
-            FMT_ENABLE_IF(
-                std::is_constructible<basic_string_view<char_type>, T>::value &&
-                !is_string<T>::value && !has_formatter<T, Context>::value &&
-                !has_fallback_formatter<T, char_type>::value)>
-  FMT_CONSTEXPR FMT_INLINE auto map(const T& val)
-      -> basic_string_view<char_type> {
-    return basic_string_view<char_type>(val);
-  }
-  template <
-      typename T,
-      FMT_ENABLE_IF(
-          std::is_constructible<std_string_view<char_type>, T>::value &&
-          !std::is_constructible<basic_string_view<char_type>, T>::value &&
-          !is_string<T>::value && !has_formatter<T, Context>::value &&
-          !has_fallback_formatter<T, char_type>::value)>
-  FMT_CONSTEXPR FMT_INLINE auto map(const T& val)
-      -> basic_string_view<char_type> {
-    return std_string_view<char_type>(val);
-  }
-
-  using cstring_result = conditional_t<std::is_same<char_type, char>::value,
-                                       const char*, unformattable_pointer>;
-
-  FMT_DEPRECATED FMT_CONSTEXPR FMT_INLINE auto map(const signed char* val)
-      -> cstring_result {
-    return map(reinterpret_cast<const char*>(val));
-  }
-  FMT_DEPRECATED FMT_CONSTEXPR FMT_INLINE auto map(const unsigned char* val)
-      -> cstring_result {
-    return map(reinterpret_cast<const char*>(val));
-  }
-  FMT_DEPRECATED FMT_CONSTEXPR FMT_INLINE auto map(signed char* val)
-      -> cstring_result {
-    return map(reinterpret_cast<const char*>(val));
-  }
-  FMT_DEPRECATED FMT_CONSTEXPR FMT_INLINE auto map(unsigned char* val)
-      -> cstring_result {
-    return map(reinterpret_cast<const char*>(val));
-  }
-
-  FMT_CONSTEXPR FMT_INLINE auto map(void* val) -> const void* { return val; }
-  FMT_CONSTEXPR FMT_INLINE auto map(const void* val) -> const void* {
-    return val;
-  }
-  FMT_CONSTEXPR FMT_INLINE auto map(std::nullptr_t val) -> const void* {
-    return val;
-  }
-
-  // We use SFINAE instead of a const T* parameter to avoid conflicting with
-  // the C array overload.
-  template <
-      typename T,
-      FMT_ENABLE_IF(
-          std::is_member_pointer<T>::value ||
-          std::is_function<typename std::remove_pointer<T>::type>::value ||
-          (std::is_convertible<const T&, const void*>::value &&
-           !std::is_convertible<const T&, const char_type*>::value))>
-  FMT_CONSTEXPR auto map(const T&) -> unformattable_pointer {
-    return {};
-  }
-
-  template <typename T, std::size_t N,
-            FMT_ENABLE_IF(!std::is_same<T, wchar_t>::value)>
-  FMT_CONSTEXPR FMT_INLINE auto map(const T (&values)[N]) -> const T (&)[N] {
-    return values;
-  }
-
-  template <typename T,
-            FMT_ENABLE_IF(
-                std::is_enum<T>::value&& std::is_convertible<T, int>::value &&
-                !has_formatter<T, Context>::value &&
-                !has_fallback_formatter<T, char_type>::value)>
-  FMT_CONSTEXPR FMT_INLINE auto map(const T& val)
-      -> decltype(std::declval<arg_mapper>().map(
-          static_cast<typename std::underlying_type<T>::type>(val))) {
-    return map(static_cast<typename std::underlying_type<T>::type>(val));
-  }
-
-  FMT_CONSTEXPR FMT_INLINE auto map(detail::byte val) -> unsigned {
-    return map(static_cast<unsigned char>(val));
-  }
-
-  template <typename T, typename U = remove_cvref_t<T>>
-  struct formattable
-      : bool_constant<has_const_formatter<U, Context>() ||
-                      !std::is_const<remove_reference_t<T>>::value ||
-                      has_fallback_formatter<U, char_type>::value> {};
-
-#if FMT_MSC_VER != 0 && FMT_MSC_VER < 1910
-  // Workaround a bug in MSVC.
-  template <typename T> FMT_CONSTEXPR FMT_INLINE auto do_map(T&& val) -> T& {
-    return val;
-  }
-#else
-  template <typename T, FMT_ENABLE_IF(formattable<T>::value)>
-  FMT_CONSTEXPR FMT_INLINE auto do_map(T&& val) -> T& {
-    return val;
-  }
-  template <typename T, FMT_ENABLE_IF(!formattable<T>::value)>
-  FMT_CONSTEXPR FMT_INLINE auto do_map(T&&) -> unformattable_const {
-    return {};
-  }
-#endif
-
-  template <typename T, typename U = remove_cvref_t<T>,
-            FMT_ENABLE_IF(!is_string<U>::value && !is_char<U>::value &&
-                          !std::is_array<U>::value &&
-                          (has_formatter<U, Context>::value ||
-                           has_fallback_formatter<U, char_type>::value))>
-  FMT_CONSTEXPR FMT_INLINE auto map(T&& val)
-      -> decltype(this->do_map(std::forward<T>(val))) {
-    return do_map(std::forward<T>(val));
-  }
-
-  template <typename T, FMT_ENABLE_IF(is_named_arg<T>::value)>
-  FMT_CONSTEXPR FMT_INLINE auto map(const T& named_arg)
-      -> decltype(std::declval<arg_mapper>().map(named_arg.value)) {
-    return map(named_arg.value);
-  }
-
-  auto map(...) -> unformattable { return {}; }
-};
-
-// A type constant after applying arg_mapper<Context>.
-template <typename T, typename Context>
-using mapped_type_constant =
-    type_constant<decltype(arg_mapper<Context>().map(std::declval<const T&>())),
-                  typename Context::char_type>;
-
-enum { packed_arg_bits = 4 };
-// Maximum number of arguments with packed types.
-enum { max_packed_args = 62 / packed_arg_bits };
-enum : unsigned long long { is_unpacked_bit = 1ULL << 63 };
-enum : unsigned long long { has_named_args_bit = 1ULL << 62 };
-
-FMT_END_DETAIL_NAMESPACE
-
-// An output iterator that appends to a buffer.
-// It is used to reduce symbol sizes for the common case.
-class appender : public std::back_insert_iterator<detail::buffer<char>> {
-  using base = std::back_insert_iterator<detail::buffer<char>>;
-
-  template <typename T>
-  friend auto get_buffer(appender out) -> detail::buffer<char>& {
-    return detail::get_container(out);
-  }
-
- public:
-  using std::back_insert_iterator<detail::buffer<char>>::back_insert_iterator;
-  appender(base it) FMT_NOEXCEPT : base(it) {}
-  using _Unchecked_type = appender;  // Mark iterator as checked.
-
-  auto operator++() FMT_NOEXCEPT -> appender& { return *this; }
-
-  auto operator++(int) FMT_NOEXCEPT -> appender { return *this; }
-};
-
-// A formatting argument. It is a trivially copyable/constructible type to
-// allow storage in basic_memory_buffer.
-template <typename Context> class basic_format_arg {
- private:
-  detail::value<Context> value_;
-  detail::type type_;
-
-  template <typename ContextType, typename T>
-  friend FMT_CONSTEXPR auto detail::make_arg(const T& value)
-      -> basic_format_arg<ContextType>;
-
-  template <typename Visitor, typename Ctx>
-  friend FMT_CONSTEXPR auto visit_format_arg(Visitor&& vis,
-                                             const basic_format_arg<Ctx>& arg)
-      -> decltype(vis(0));
-
-  friend class basic_format_args<Context>;
-  friend class dynamic_format_arg_store<Context>;
-
-  using char_type = typename Context::char_type;
-
-  template <typename T, typename Char, size_t NUM_ARGS, size_t NUM_NAMED_ARGS>
-  friend struct detail::arg_data;
-
-  basic_format_arg(const detail::named_arg_info<char_type>* args, size_t size)
-      : value_(args, size) {}
-
- public:
-  class handle {
-   public:
-    explicit handle(detail::custom_value<Context> custom) : custom_(custom) {}
-
-    void format(typename Context::parse_context_type& parse_ctx,
-                Context& ctx) const {
-      custom_.format(custom_.value, parse_ctx, ctx);
-    }
-
-   private:
-    detail::custom_value<Context> custom_;
-  };
-
-  constexpr basic_format_arg() : type_(detail::type::none_type) {}
-
-  constexpr explicit operator bool() const FMT_NOEXCEPT {
-    return type_ != detail::type::none_type;
-  }
-
-  auto type() const -> detail::type { return type_; }
-
-  auto is_integral() const -> bool { return detail::is_integral_type(type_); }
-  auto is_arithmetic() const -> bool {
-    return detail::is_arithmetic_type(type_);
-  }
-};
-
-/**
-  \rst
-  Visits an argument dispatching to the appropriate visit method based on
-  the argument type. For example, if the argument type is ``double`` then
-  ``vis(value)`` will be called with the value of type ``double``.
-  \endrst
- */
-template <typename Visitor, typename Context>
-FMT_CONSTEXPR FMT_INLINE auto visit_format_arg(
-    Visitor&& vis, const basic_format_arg<Context>& arg) -> decltype(vis(0)) {
-  switch (arg.type_) {
-  case detail::type::none_type:
-    break;
-  case detail::type::int_type:
-    return vis(arg.value_.int_value);
-  case detail::type::uint_type:
-    return vis(arg.value_.uint_value);
-  case detail::type::long_long_type:
-    return vis(arg.value_.long_long_value);
-  case detail::type::ulong_long_type:
-    return vis(arg.value_.ulong_long_value);
-  case detail::type::int128_type:
-    return vis(detail::convert_for_visit(arg.value_.int128_value));
-  case detail::type::uint128_type:
-    return vis(detail::convert_for_visit(arg.value_.uint128_value));
-  case detail::type::bool_type:
-    return vis(arg.value_.bool_value);
-  case detail::type::char_type:
-    return vis(arg.value_.char_value);
-  case detail::type::float_type:
-    return vis(arg.value_.float_value);
-  case detail::type::double_type:
-    return vis(arg.value_.double_value);
-  case detail::type::long_double_type:
-    return vis(arg.value_.long_double_value);
-  case detail::type::cstring_type:
-    return vis(arg.value_.string.data);
-  case detail::type::string_type:
-    using sv = basic_string_view<typename Context::char_type>;
-    return vis(sv(arg.value_.string.data, arg.value_.string.size));
-  case detail::type::pointer_type:
-    return vis(arg.value_.pointer);
-  case detail::type::custom_type:
-    return vis(typename basic_format_arg<Context>::handle(arg.value_.custom));
-  }
-  return vis(monostate());
-}
-
-FMT_BEGIN_DETAIL_NAMESPACE
-
-template <typename Char, typename InputIt>
-auto copy_str(InputIt begin, InputIt end, appender out) -> appender {
-  get_container(out).append(begin, end);
-  return out;
-}
-
-#if FMT_GCC_VERSION && FMT_GCC_VERSION < 500
-// A workaround for gcc 4.8 to make void_t work in a SFINAE context.
-template <typename... Ts> struct void_t_impl { using type = void; };
-template <typename... Ts>
-using void_t = typename detail::void_t_impl<Ts...>::type;
-#else
-template <typename...> using void_t = void;
-#endif
-
-template <typename It, typename T, typename Enable = void>
-struct is_output_iterator : std::false_type {};
-
-template <typename It, typename T>
-struct is_output_iterator<
-    It, T,
-    void_t<typename std::iterator_traits<It>::iterator_category,
-           decltype(*std::declval<It>() = std::declval<T>())>>
-    : std::true_type {};
-
-template <typename OutputIt>
-struct is_back_insert_iterator : std::false_type {};
-template <typename Container>
-struct is_back_insert_iterator<std::back_insert_iterator<Container>>
-    : std::true_type {};
-
-template <typename OutputIt>
-struct is_contiguous_back_insert_iterator : std::false_type {};
-template <typename Container>
-struct is_contiguous_back_insert_iterator<std::back_insert_iterator<Container>>
-    : is_contiguous<Container> {};
-template <>
-struct is_contiguous_back_insert_iterator<appender> : std::true_type {};
-
-// A type-erased reference to an std::locale to avoid heavy <locale> include.
-class locale_ref {
- private:
-  const void* locale_;  // A type-erased pointer to std::locale.
-
- public:
-  constexpr locale_ref() : locale_(nullptr) {}
-  template <typename Locale> explicit locale_ref(const Locale& loc);
-
-  explicit operator bool() const FMT_NOEXCEPT { return locale_ != nullptr; }
-
-  template <typename Locale> auto get() const -> Locale;
-};
-
-template <typename> constexpr auto encode_types() -> unsigned long long {
-  return 0;
-}
-
-template <typename Context, typename Arg, typename... Args>
-constexpr auto encode_types() -> unsigned long long {
-  return static_cast<unsigned>(mapped_type_constant<Arg, Context>::value) |
-         (encode_types<Context, Args...>() << packed_arg_bits);
-}
-
-template <typename Context, typename T>
-FMT_CONSTEXPR auto make_arg(const T& value) -> basic_format_arg<Context> {
-  basic_format_arg<Context> arg;
-  arg.type_ = mapped_type_constant<T, Context>::value;
-  arg.value_ = arg_mapper<Context>().map(value);
-  return arg;
-}
-
-// The type template parameter is there to avoid an ODR violation when using
-// a fallback formatter in one translation unit and an implicit conversion in
-// another (not recommended).
-template <bool IS_PACKED, typename Context, type, typename T,
-          FMT_ENABLE_IF(IS_PACKED)>
-FMT_CONSTEXPR FMT_INLINE auto make_arg(T&& val) -> value<Context> {
-  const auto& arg = arg_mapper<Context>().map(std::forward<T>(val));
-
-  constexpr bool formattable_char =
-      !std::is_same<decltype(arg), const unformattable_char&>::value;
-  static_assert(formattable_char, "Mixing character types is disallowed.");
-
-  constexpr bool formattable_const =
-      !std::is_same<decltype(arg), const unformattable_const&>::value;
-  static_assert(formattable_const, "Cannot format a const argument.");
-
-  // Formatting of arbitrary pointers is disallowed. If you want to output
-  // a pointer cast it to "void *" or "const void *". In particular, this
-  // forbids formatting of "[const] volatile char *" which is printed as bool
-  // by iostreams.
-  constexpr bool formattable_pointer =
-      !std::is_same<decltype(arg), const unformattable_pointer&>::value;
-  static_assert(formattable_pointer,
-                "Formatting of non-void pointers is disallowed.");
-
-  constexpr bool formattable =
-      !std::is_same<decltype(arg), const unformattable&>::value;
-  static_assert(
-      formattable,
-      "Cannot format an argument. To make type T formattable provide a "
-      "formatter<T> specialization: https://fmt.dev/latest/api.html#udt");
-  return {arg};
-}
-
-template <bool IS_PACKED, typename Context, type, typename T,
-          FMT_ENABLE_IF(!IS_PACKED)>
-inline auto make_arg(const T& value) -> basic_format_arg<Context> {
-  return make_arg<Context>(value);
-}
-FMT_END_DETAIL_NAMESPACE
-
-// Formatting context.
-template <typename OutputIt, typename Char> class basic_format_context {
- public:
-  /** The character type for the output. */
-  using char_type = Char;
-
- private:
-  OutputIt out_;
-  basic_format_args<basic_format_context> args_;
-  detail::locale_ref loc_;
-
- public:
-  using iterator = OutputIt;
-  using format_arg = basic_format_arg<basic_format_context>;
-  using parse_context_type = basic_format_parse_context<Char>;
-  template <typename T> using formatter_type = formatter<T, char_type>;
-
-  basic_format_context(basic_format_context&&) = default;
-  basic_format_context(const basic_format_context&) = delete;
-  void operator=(const basic_format_context&) = delete;
-  /**
-   Constructs a ``basic_format_context`` object. References to the arguments are
-   stored in the object so make sure they have appropriate lifetimes.
-   */
-  constexpr basic_format_context(
-      OutputIt out, basic_format_args<basic_format_context> ctx_args,
-      detail::locale_ref loc = detail::locale_ref())
-      : out_(out), args_(ctx_args), loc_(loc) {}
-
-  constexpr auto arg(int id) const -> format_arg { return args_.get(id); }
-  FMT_CONSTEXPR auto arg(basic_string_view<char_type> name) -> format_arg {
-    return args_.get(name);
-  }
-  FMT_CONSTEXPR auto arg_id(basic_string_view<char_type> name) -> int {
-    return args_.get_id(name);
-  }
-  auto args() const -> const basic_format_args<basic_format_context>& {
-    return args_;
-  }
-
-  FMT_CONSTEXPR auto error_handler() -> detail::error_handler { return {}; }
-  void on_error(const char* message) { error_handler().on_error(message); }
-
-  // Returns an iterator to the beginning of the output range.
-  FMT_CONSTEXPR auto out() -> iterator { return out_; }
-
-  // Advances the begin iterator to ``it``.
-  void advance_to(iterator it) {
-    if (!detail::is_back_insert_iterator<iterator>()) out_ = it;
-  }
-
-  FMT_CONSTEXPR auto locale() -> detail::locale_ref { return loc_; }
-};
-
-template <typename Char>
-using buffer_context =
-    basic_format_context<detail::buffer_appender<Char>, Char>;
-using format_context = buffer_context<char>;
-
-// Workaround an alias issue: https://stackoverflow.com/q/62767544/471164.
-#define FMT_BUFFER_CONTEXT(Char) \
-  basic_format_context<detail::buffer_appender<Char>, Char>
-
-template <typename T, typename Char = char>
-using is_formattable = bool_constant<
-    !std::is_base_of<detail::unformattable,
-                     decltype(detail::arg_mapper<buffer_context<Char>>().map(
-                         std::declval<T>()))>::value &&
-    !detail::has_fallback_formatter<T, Char>::value>;
-
-/**
-  \rst
-  An array of references to arguments. It can be implicitly converted into
-  `~fmt::basic_format_args` for passing into type-erased formatting functions
-  such as `~fmt::vformat`.
-  \endrst
- */
-template <typename Context, typename... Args>
-class format_arg_store
-#if FMT_GCC_VERSION && FMT_GCC_VERSION < 409
-    // Workaround a GCC template argument substitution bug.
-    : public basic_format_args<Context>
-#endif
-{
- private:
-  static const size_t num_args = sizeof...(Args);
-  static const size_t num_named_args = detail::count_named_args<Args...>();
-  static const bool is_packed = num_args <= detail::max_packed_args;
-
-  using value_type = conditional_t<is_packed, detail::value<Context>,
-                                   basic_format_arg<Context>>;
-
-  detail::arg_data<value_type, typename Context::char_type, num_args,
-                   num_named_args>
-      data_;
-
-  friend class basic_format_args<Context>;
-
-  static constexpr unsigned long long desc =
-      (is_packed ? detail::encode_types<Context, Args...>()
-                 : detail::is_unpacked_bit | num_args) |
-      (num_named_args != 0
-           ? static_cast<unsigned long long>(detail::has_named_args_bit)
-           : 0);
-
- public:
-  template <typename... T>
-  FMT_CONSTEXPR FMT_INLINE format_arg_store(T&&... args)
-      :
-#if FMT_GCC_VERSION && FMT_GCC_VERSION < 409
-        basic_format_args<Context>(*this),
-#endif
-        data_{detail::make_arg<
-            is_packed, Context,
-            detail::mapped_type_constant<remove_cvref_t<T>, Context>::value>(
-            std::forward<T>(args))...} {
-    detail::init_named_args(data_.named_args(), 0, 0, args...);
-  }
-};
-
-/**
-  \rst
-  Constructs a `~fmt::format_arg_store` object that contains references to
-  arguments and can be implicitly converted to `~fmt::format_args`. `Context`
-  can be omitted in which case it defaults to `~fmt::context`.
-  See `~fmt::arg` for lifetime considerations.
-  \endrst
- */
-template <typename Context = format_context, typename... Args>
-constexpr auto make_format_args(Args&&... args)
-    -> format_arg_store<Context, remove_cvref_t<Args>...> {
-  return {std::forward<Args>(args)...};
-}
-
-/**
-  \rst
-  Returns a named argument to be used in a formatting function.
-  It should only be used in a call to a formatting function or
-  `dynamic_format_arg_store::push_back`.
-
-  **Example**::
-
-    fmt::print("Elapsed time: {s:.2f} seconds", fmt::arg("s", 1.23));
-  \endrst
- */
-template <typename Char, typename T>
-inline auto arg(const Char* name, const T& arg) -> detail::named_arg<Char, T> {
-  static_assert(!detail::is_named_arg<T>(), "nested named arguments");
-  return {name, arg};
-}
-
-/**
-  \rst
-  A view of a collection of formatting arguments. To avoid lifetime issues it
-  should only be used as a parameter type in type-erased functions such as
-  ``vformat``::
-
-    void vlog(string_view format_str, format_args args);  // OK
-    format_args args = make_format_args(42);  // Error: dangling reference
-  \endrst
- */
-template <typename Context> class basic_format_args {
- public:
-  using size_type = int;
-  using format_arg = basic_format_arg<Context>;
-
- private:
-  // A descriptor that contains information about formatting arguments.
-  // If the number of arguments is less or equal to max_packed_args then
-  // argument types are passed in the descriptor. This reduces binary code size
-  // per formatting function call.
-  unsigned long long desc_;
-  union {
-    // If is_packed() returns true then argument values are stored in values_;
-    // otherwise they are stored in args_. This is done to improve cache
-    // locality and reduce compiled code size since storing larger objects
-    // may require more code (at least on x86-64) even if the same amount of
-    // data is actually copied to stack. It saves ~10% on the bloat test.
-    const detail::value<Context>* values_;
-    const format_arg* args_;
-  };
-
-  constexpr auto is_packed() const -> bool {
-    return (desc_ & detail::is_unpacked_bit) == 0;
-  }
-  auto has_named_args() const -> bool {
-    return (desc_ & detail::has_named_args_bit) != 0;
-  }
-
-  FMT_CONSTEXPR auto type(int index) const -> detail::type {
-    int shift = index * detail::packed_arg_bits;
-    unsigned int mask = (1 << detail::packed_arg_bits) - 1;
-    return static_cast<detail::type>((desc_ >> shift) & mask);
-  }
-
-  constexpr FMT_INLINE basic_format_args(unsigned long long desc,
-                                         const detail::value<Context>* values)
-      : desc_(desc), values_(values) {}
-  constexpr basic_format_args(unsigned long long desc, const format_arg* args)
-      : desc_(desc), args_(args) {}
-
- public:
-  constexpr basic_format_args() : desc_(0), args_(nullptr) {}
-
-  /**
-   \rst
-   Constructs a `basic_format_args` object from `~fmt::format_arg_store`.
-   \endrst
-   */
-  template <typename... Args>
-  constexpr FMT_INLINE basic_format_args(
-      const format_arg_store<Context, Args...>& store)
-      : basic_format_args(format_arg_store<Context, Args...>::desc,
-                          store.data_.args()) {}
-
-  /**
-   \rst
-   Constructs a `basic_format_args` object from
-   `~fmt::dynamic_format_arg_store`.
-   \endrst
-   */
-  constexpr FMT_INLINE basic_format_args(
-      const dynamic_format_arg_store<Context>& store)
-      : basic_format_args(store.get_types(), store.data()) {}
-
-  /**
-   \rst
-   Constructs a `basic_format_args` object from a dynamic set of arguments.
-   \endrst
-   */
-  constexpr basic_format_args(const format_arg* args, int count)
-      : basic_format_args(detail::is_unpacked_bit | detail::to_unsigned(count),
-                          args) {}
-
-  /** Returns the argument with the specified id. */
-  FMT_CONSTEXPR auto get(int id) const -> format_arg {
-    format_arg arg;
-    if (!is_packed()) {
-      if (id < max_size()) arg = args_[id];
-      return arg;
-    }
-    if (id >= detail::max_packed_args) return arg;
-    arg.type_ = type(id);
-    if (arg.type_ == detail::type::none_type) return arg;
-    arg.value_ = values_[id];
-    return arg;
-  }
-
-  template <typename Char>
-  auto get(basic_string_view<Char> name) const -> format_arg {
-    int id = get_id(name);
-    return id >= 0 ? get(id) : format_arg();
-  }
-
-  template <typename Char>
-  auto get_id(basic_string_view<Char> name) const -> int {
-    if (!has_named_args()) return -1;
-    const auto& named_args =
-        (is_packed() ? values_[-1] : args_[-1].value_).named_args;
-    for (size_t i = 0; i < named_args.size; ++i) {
-      if (named_args.data[i].name == name) return named_args.data[i].id;
-    }
-    return -1;
-  }
-
-  auto max_size() const -> int {
-    unsigned long long max_packed = detail::max_packed_args;
-    return static_cast<int>(is_packed() ? max_packed
-                                        : desc_ & ~detail::is_unpacked_bit);
-  }
-};
-
-/** An alias to ``basic_format_args<format_context>``. */
-// A separate type would result in shorter symbols but break ABI compatibility
-// between clang and gcc on ARM (#1919).
-using format_args = basic_format_args<format_context>;
-
-// We cannot use enum classes as bit fields because of a gcc bug
-// https://gcc.gnu.org/bugzilla/show_bug.cgi?id=61414.
-namespace align {
-enum type { none, left, right, center, numeric };
-}
-using align_t = align::type;
-namespace sign {
-enum type { none, minus, plus, space };
-}
-using sign_t = sign::type;
-
-FMT_BEGIN_DETAIL_NAMESPACE
-
-// Workaround an array initialization issue in gcc 4.8.
-template <typename Char> struct fill_t {
- private:
-  enum { max_size = 4 };
-  Char data_[max_size] = {Char(' '), Char(0), Char(0), Char(0)};
-  unsigned char size_ = 1;
-
- public:
-  FMT_CONSTEXPR void operator=(basic_string_view<Char> s) {
-    auto size = s.size();
-    if (size > max_size) return throw_format_error("invalid fill");
-    for (size_t i = 0; i < size; ++i) data_[i] = s[i];
-    size_ = static_cast<unsigned char>(size);
-  }
-
-  constexpr auto size() const -> size_t { return size_; }
-  constexpr auto data() const -> const Char* { return data_; }
-
-  FMT_CONSTEXPR auto operator[](size_t index) -> Char& { return data_[index]; }
-  FMT_CONSTEXPR auto operator[](size_t index) const -> const Char& {
-    return data_[index];
-  }
-};
-FMT_END_DETAIL_NAMESPACE
-
-enum class presentation_type : unsigned char {
-  none,
-  // Integer types should go first,
-  dec,             // 'd'
-  oct,             // 'o'
-  hex_lower,       // 'x'
-  hex_upper,       // 'X'
-  bin_lower,       // 'b'
-  bin_upper,       // 'B'
-  hexfloat_lower,  // 'a'
-  hexfloat_upper,  // 'A'
-  exp_lower,       // 'e'
-  exp_upper,       // 'E'
-  fixed_lower,     // 'f'
-  fixed_upper,     // 'F'
-  general_lower,   // 'g'
-  general_upper,   // 'G'
-  chr,             // 'c'
-  string,          // 's'
-  pointer          // 'p'
-};
-
-// Format specifiers for built-in and string types.
-template <typename Char> struct basic_format_specs {
-  int width;
-  int precision;
-  presentation_type type;
-  align_t align : 4;
-  sign_t sign : 3;
-  bool alt : 1;  // Alternate form ('#').
-  bool localized : 1;
-  detail::fill_t<Char> fill;
-
-  constexpr basic_format_specs()
-      : width(0),
-        precision(-1),
-        type(presentation_type::none),
-        align(align::none),
-        sign(sign::none),
-        alt(false),
-        localized(false) {}
-};
-
-using format_specs = basic_format_specs<char>;
-
-FMT_BEGIN_DETAIL_NAMESPACE
-
-enum class arg_id_kind { none, index, name };
-
-// An argument reference.
-template <typename Char> struct arg_ref {
-  FMT_CONSTEXPR arg_ref() : kind(arg_id_kind::none), val() {}
-
-  FMT_CONSTEXPR explicit arg_ref(int index)
-      : kind(arg_id_kind::index), val(index) {}
-  FMT_CONSTEXPR explicit arg_ref(basic_string_view<Char> name)
-      : kind(arg_id_kind::name), val(name) {}
-
-  FMT_CONSTEXPR auto operator=(int idx) -> arg_ref& {
-    kind = arg_id_kind::index;
-    val.index = idx;
-    return *this;
-  }
-
-  arg_id_kind kind;
-  union value {
-    FMT_CONSTEXPR value(int id = 0) : index{id} {}
-    FMT_CONSTEXPR value(basic_string_view<Char> n) : name(n) {}
-
-    int index;
-    basic_string_view<Char> name;
-  } val;
-};
-
-// Format specifiers with width and precision resolved at formatting rather
-// than parsing time to allow re-using the same parsed specifiers with
-// different sets of arguments (precompilation of format strings).
-template <typename Char>
-struct dynamic_format_specs : basic_format_specs<Char> {
-  arg_ref<Char> width_ref;
-  arg_ref<Char> precision_ref;
-};
-
-struct auto_id {};
-
-// A format specifier handler that sets fields in basic_format_specs.
-template <typename Char> class specs_setter {
- protected:
-  basic_format_specs<Char>& specs_;
-
- public:
-  explicit FMT_CONSTEXPR specs_setter(basic_format_specs<Char>& specs)
-      : specs_(specs) {}
-
-  FMT_CONSTEXPR specs_setter(const specs_setter& other)
-      : specs_(other.specs_) {}
-
-  FMT_CONSTEXPR void on_align(align_t align) { specs_.align = align; }
-  FMT_CONSTEXPR void on_fill(basic_string_view<Char> fill) {
-    specs_.fill = fill;
-  }
-  FMT_CONSTEXPR void on_sign(sign_t s) { specs_.sign = s; }
-  FMT_CONSTEXPR void on_hash() { specs_.alt = true; }
-  FMT_CONSTEXPR void on_localized() { specs_.localized = true; }
-
-  FMT_CONSTEXPR void on_zero() {
-    if (specs_.align == align::none) specs_.align = align::numeric;
-    specs_.fill[0] = Char('0');
-  }
-
-  FMT_CONSTEXPR void on_width(int width) { specs_.width = width; }
-  FMT_CONSTEXPR void on_precision(int precision) {
-    specs_.precision = precision;
-  }
-  FMT_CONSTEXPR void end_precision() {}
-
-  FMT_CONSTEXPR void on_type(presentation_type type) { specs_.type = type; }
-};
-
-// Format spec handler that saves references to arguments representing dynamic
-// width and precision to be resolved at formatting time.
-template <typename ParseContext>
-class dynamic_specs_handler
-    : public specs_setter<typename ParseContext::char_type> {
- public:
-  using char_type = typename ParseContext::char_type;
-
-  FMT_CONSTEXPR dynamic_specs_handler(dynamic_format_specs<char_type>& specs,
-                                      ParseContext& ctx)
-      : specs_setter<char_type>(specs), specs_(specs), context_(ctx) {}
-
-  FMT_CONSTEXPR dynamic_specs_handler(const dynamic_specs_handler& other)
-      : specs_setter<char_type>(other),
-        specs_(other.specs_),
-        context_(other.context_) {}
-
-  template <typename Id> FMT_CONSTEXPR void on_dynamic_width(Id arg_id) {
-    specs_.width_ref = make_arg_ref(arg_id);
-  }
-
-  template <typename Id> FMT_CONSTEXPR void on_dynamic_precision(Id arg_id) {
-    specs_.precision_ref = make_arg_ref(arg_id);
-  }
-
-  FMT_CONSTEXPR void on_error(const char* message) {
-    context_.on_error(message);
-  }
-
- private:
-  dynamic_format_specs<char_type>& specs_;
-  ParseContext& context_;
-
-  using arg_ref_type = arg_ref<char_type>;
-
-  FMT_CONSTEXPR auto make_arg_ref(int arg_id) -> arg_ref_type {
-    context_.check_arg_id(arg_id);
-    return arg_ref_type(arg_id);
-  }
-
-  FMT_CONSTEXPR auto make_arg_ref(auto_id) -> arg_ref_type {
-    return arg_ref_type(context_.next_arg_id());
-  }
-
-  FMT_CONSTEXPR auto make_arg_ref(basic_string_view<char_type> arg_id)
-      -> arg_ref_type {
-    context_.check_arg_id(arg_id);
-    basic_string_view<char_type> format_str(
-        context_.begin(), to_unsigned(context_.end() - context_.begin()));
-    return arg_ref_type(arg_id);
-  }
-};
-
-template <typename Char> constexpr bool is_ascii_letter(Char c) {
-  return (c >= 'a' && c <= 'z') || (c >= 'A' && c <= 'Z');
-}
-
-// Converts a character to ASCII. Returns a number > 127 on conversion failure.
-template <typename Char, FMT_ENABLE_IF(std::is_integral<Char>::value)>
-constexpr auto to_ascii(Char value) -> Char {
-  return value;
-}
-template <typename Char, FMT_ENABLE_IF(std::is_enum<Char>::value)>
-constexpr auto to_ascii(Char value) ->
-    typename std::underlying_type<Char>::type {
-  return value;
-}
-
-template <typename Char>
-FMT_CONSTEXPR auto code_point_length(const Char* begin) -> int {
-  if (const_check(sizeof(Char) != 1)) return 1;
-  auto lengths =
-      "\1\1\1\1\1\1\1\1\1\1\1\1\1\1\1\1\0\0\0\0\0\0\0\0\2\2\2\2\3\3\4";
-  int len = lengths[static_cast<unsigned char>(*begin) >> 3];
-
-  // Compute the pointer to the next character early so that the next
-  // iteration can start working on the next character. Neither Clang
-  // nor GCC figure out this reordering on their own.
-  return len + !len;
-}
-
-// Return the result via the out param to workaround gcc bug 77539.
-template <bool IS_CONSTEXPR, typename T, typename Ptr = const T*>
-FMT_CONSTEXPR auto find(Ptr first, Ptr last, T value, Ptr& out) -> bool {
-  for (out = first; out != last; ++out) {
-    if (*out == value) return true;
-  }
-  return false;
-}
-
-template <>
-inline auto find<false, char>(const char* first, const char* last, char value,
-                              const char*& out) -> bool {
-  out = static_cast<const char*>(
-      std::memchr(first, value, to_unsigned(last - first)));
-  return out != nullptr;
-}
-
-// Parses the range [begin, end) as an unsigned integer. This function assumes
-// that the range is non-empty and the first character is a digit.
-template <typename Char>
-FMT_CONSTEXPR auto parse_nonnegative_int(const Char*& begin, const Char* end,
-                                         int error_value) noexcept -> int {
-  FMT_ASSERT(begin != end && '0' <= *begin && *begin <= '9', "");
-  unsigned value = 0, prev = 0;
-  auto p = begin;
-  do {
-    prev = value;
-    value = value * 10 + unsigned(*p - '0');
-    ++p;
-  } while (p != end && '0' <= *p && *p <= '9');
-  auto num_digits = p - begin;
-  begin = p;
-  if (num_digits <= std::numeric_limits<int>::digits10)
-    return static_cast<int>(value);
-  // Check for overflow.
-  const unsigned max = to_unsigned((std::numeric_limits<int>::max)());
-  return num_digits == std::numeric_limits<int>::digits10 + 1 &&
-                 prev * 10ull + unsigned(p[-1] - '0') <= max
-             ? static_cast<int>(value)
-             : error_value;
-}
-
-// Parses fill and alignment.
-template <typename Char, typename Handler>
-FMT_CONSTEXPR auto parse_align(const Char* begin, const Char* end,
-                               Handler&& handler) -> const Char* {
-  FMT_ASSERT(begin != end, "");
-  auto align = align::none;
-  auto p = begin + code_point_length(begin);
-  if (p >= end) p = begin;
-  for (;;) {
-    switch (to_ascii(*p)) {
-    case '<':
-      align = align::left;
-      break;
-    case '>':
-      align = align::right;
-      break;
-    case '^':
-      align = align::center;
-      break;
-    default:
-      break;
-    }
-    if (align != align::none) {
-      if (p != begin) {
-        auto c = *begin;
-        if (c == '{')
-          return handler.on_error("invalid fill character '{'"), begin;
-        handler.on_fill(basic_string_view<Char>(begin, to_unsigned(p - begin)));
-        begin = p + 1;
-      } else
-        ++begin;
-      handler.on_align(align);
-      break;
-    } else if (p == begin) {
-      break;
-    }
-    p = begin;
-  }
-  return begin;
-}
-
-template <typename Char> FMT_CONSTEXPR bool is_name_start(Char c) {
-  return ('a' <= c && c <= 'z') || ('A' <= c && c <= 'Z') || '_' == c;
-}
-
-template <typename Char, typename IDHandler>
-FMT_CONSTEXPR auto do_parse_arg_id(const Char* begin, const Char* end,
-                                   IDHandler&& handler) -> const Char* {
-  FMT_ASSERT(begin != end, "");
-  Char c = *begin;
-  if (c >= '0' && c <= '9') {
-    int index = 0;
-    if (c != '0')
-      index =
-          parse_nonnegative_int(begin, end, (std::numeric_limits<int>::max)());
-    else
-      ++begin;
-    if (begin == end || (*begin != '}' && *begin != ':'))
-      handler.on_error("invalid format string");
-    else
-      handler(index);
-    return begin;
-  }
-  if (!is_name_start(c)) {
-    handler.on_error("invalid format string");
-    return begin;
-  }
-  auto it = begin;
-  do {
-    ++it;
-  } while (it != end && (is_name_start(c = *it) || ('0' <= c && c <= '9')));
-  handler(basic_string_view<Char>(begin, to_unsigned(it - begin)));
-  return it;
-}
-
-template <typename Char, typename IDHandler>
-FMT_CONSTEXPR FMT_INLINE auto parse_arg_id(const Char* begin, const Char* end,
-                                           IDHandler&& handler) -> const Char* {
-  Char c = *begin;
-  if (c != '}' && c != ':') return do_parse_arg_id(begin, end, handler);
-  handler();
-  return begin;
-}
-
-template <typename Char, typename Handler>
-FMT_CONSTEXPR auto parse_width(const Char* begin, const Char* end,
-                               Handler&& handler) -> const Char* {
-  using detail::auto_id;
-  struct width_adapter {
-    Handler& handler;
-
-    FMT_CONSTEXPR void operator()() { handler.on_dynamic_width(auto_id()); }
-    FMT_CONSTEXPR void operator()(int id) { handler.on_dynamic_width(id); }
-    FMT_CONSTEXPR void operator()(basic_string_view<Char> id) {
-      handler.on_dynamic_width(id);
-    }
-    FMT_CONSTEXPR void on_error(const char* message) {
-      if (message) handler.on_error(message);
-    }
-  };
-
-  FMT_ASSERT(begin != end, "");
-  if ('0' <= *begin && *begin <= '9') {
-    int width = parse_nonnegative_int(begin, end, -1);
-    if (width != -1)
-      handler.on_width(width);
-    else
-      handler.on_error("number is too big");
-  } else if (*begin == '{') {
-    ++begin;
-    if (begin != end) begin = parse_arg_id(begin, end, width_adapter{handler});
-    if (begin == end || *begin != '}')
-      return handler.on_error("invalid format string"), begin;
-    ++begin;
-  }
-  return begin;
-}
-
-template <typename Char, typename Handler>
-FMT_CONSTEXPR auto parse_precision(const Char* begin, const Char* end,
-                                   Handler&& handler) -> const Char* {
-  using detail::auto_id;
-  struct precision_adapter {
-    Handler& handler;
-
-    FMT_CONSTEXPR void operator()() { handler.on_dynamic_precision(auto_id()); }
-    FMT_CONSTEXPR void operator()(int id) { handler.on_dynamic_precision(id); }
-    FMT_CONSTEXPR void operator()(basic_string_view<Char> id) {
-      handler.on_dynamic_precision(id);
-    }
-    FMT_CONSTEXPR void on_error(const char* message) {
-      if (message) handler.on_error(message);
-    }
-  };
-
-  ++begin;
-  auto c = begin != end ? *begin : Char();
-  if ('0' <= c && c <= '9') {
-    auto precision = parse_nonnegative_int(begin, end, -1);
-    if (precision != -1)
-      handler.on_precision(precision);
-    else
-      handler.on_error("number is too big");
-  } else if (c == '{') {
-    ++begin;
-    if (begin != end)
-      begin = parse_arg_id(begin, end, precision_adapter{handler});
-    if (begin == end || *begin++ != '}')
-      return handler.on_error("invalid format string"), begin;
-  } else {
-    return handler.on_error("missing precision specifier"), begin;
-  }
-  handler.end_precision();
-  return begin;
-}
-
-template <typename Char>
-FMT_CONSTEXPR auto parse_presentation_type(Char type) -> presentation_type {
-  switch (to_ascii(type)) {
-  case 'd':
-    return presentation_type::dec;
-  case 'o':
-    return presentation_type::oct;
-  case 'x':
-    return presentation_type::hex_lower;
-  case 'X':
-    return presentation_type::hex_upper;
-  case 'b':
-    return presentation_type::bin_lower;
-  case 'B':
-    return presentation_type::bin_upper;
-  case 'a':
-    return presentation_type::hexfloat_lower;
-  case 'A':
-    return presentation_type::hexfloat_upper;
-  case 'e':
-    return presentation_type::exp_lower;
-  case 'E':
-    return presentation_type::exp_upper;
-  case 'f':
-    return presentation_type::fixed_lower;
-  case 'F':
-    return presentation_type::fixed_upper;
-  case 'g':
-    return presentation_type::general_lower;
-  case 'G':
-    return presentation_type::general_upper;
-  case 'c':
-    return presentation_type::chr;
-  case 's':
-    return presentation_type::string;
-  case 'p':
-    return presentation_type::pointer;
-  default:
-    return presentation_type::none;
-  }
-}
-
-// Parses standard format specifiers and sends notifications about parsed
-// components to handler.
-template <typename Char, typename SpecHandler>
-FMT_CONSTEXPR FMT_INLINE auto parse_format_specs(const Char* begin,
-                                                 const Char* end,
-                                                 SpecHandler&& handler)
-    -> const Char* {
-  if (1 < end - begin && begin[1] == '}' && is_ascii_letter(*begin) &&
-      *begin != 'L') {
-    presentation_type type = parse_presentation_type(*begin++);
-    if (type == presentation_type::none)
-      handler.on_error("invalid type specifier");
-    handler.on_type(type);
-    return begin;
-  }
-
-  if (begin == end) return begin;
-
-  begin = parse_align(begin, end, handler);
-  if (begin == end) return begin;
-
-  // Parse sign.
-  switch (to_ascii(*begin)) {
-  case '+':
-    handler.on_sign(sign::plus);
-    ++begin;
-    break;
-  case '-':
-    handler.on_sign(sign::minus);
-    ++begin;
-    break;
-  case ' ':
-    handler.on_sign(sign::space);
-    ++begin;
-    break;
-  default:
-    break;
-  }
-  if (begin == end) return begin;
-
-  if (*begin == '#') {
-    handler.on_hash();
-    if (++begin == end) return begin;
-  }
-
-  // Parse zero flag.
-  if (*begin == '0') {
-    handler.on_zero();
-    if (++begin == end) return begin;
-  }
-
-  begin = parse_width(begin, end, handler);
-  if (begin == end) return begin;
-
-  // Parse precision.
-  if (*begin == '.') {
-    begin = parse_precision(begin, end, handler);
-    if (begin == end) return begin;
-  }
-
-  if (*begin == 'L') {
-    handler.on_localized();
-    ++begin;
-  }
-
-  // Parse type.
-  if (begin != end && *begin != '}') {
-    presentation_type type = parse_presentation_type(*begin++);
-    if (type == presentation_type::none)
-      handler.on_error("invalid type specifier");
-    handler.on_type(type);
-  }
-  return begin;
-}
-
-template <typename Char, typename Handler>
-FMT_CONSTEXPR auto parse_replacement_field(const Char* begin, const Char* end,
-                                           Handler&& handler) -> const Char* {
-  struct id_adapter {
-    Handler& handler;
-    int arg_id;
-
-    FMT_CONSTEXPR void operator()() { arg_id = handler.on_arg_id(); }
-    FMT_CONSTEXPR void operator()(int id) { arg_id = handler.on_arg_id(id); }
-    FMT_CONSTEXPR void operator()(basic_string_view<Char> id) {
-      arg_id = handler.on_arg_id(id);
-    }
-    FMT_CONSTEXPR void on_error(const char* message) {
-      if (message) handler.on_error(message);
-    }
-  };
-
-  ++begin;
-  if (begin == end) return handler.on_error("invalid format string"), end;
-  if (*begin == '}') {
-    handler.on_replacement_field(handler.on_arg_id(), begin);
-  } else if (*begin == '{') {
-    handler.on_text(begin, begin + 1);
-  } else {
-    auto adapter = id_adapter{handler, 0};
-    begin = parse_arg_id(begin, end, adapter);
-    Char c = begin != end ? *begin : Char();
-    if (c == '}') {
-      handler.on_replacement_field(adapter.arg_id, begin);
-    } else if (c == ':') {
-      begin = handler.on_format_specs(adapter.arg_id, begin + 1, end);
-      if (begin == end || *begin != '}')
-        return handler.on_error("unknown format specifier"), end;
-    } else {
-      return handler.on_error("missing '}' in format string"), end;
-    }
-  }
-  return begin + 1;
-}
-
-template <bool IS_CONSTEXPR, typename Char, typename Handler>
-FMT_CONSTEXPR FMT_INLINE void parse_format_string(
-    basic_string_view<Char> format_str, Handler&& handler) {
-  // Workaround a name-lookup bug in MSVC's modules implementation.
-  using detail::find;
-
-  auto begin = format_str.data();
-  auto end = begin + format_str.size();
-  if (end - begin < 32) {
-    // Use a simple loop instead of memchr for small strings.
-    const Char* p = begin;
-    while (p != end) {
-      auto c = *p++;
-      if (c == '{') {
-        handler.on_text(begin, p - 1);
-        begin = p = parse_replacement_field(p - 1, end, handler);
-      } else if (c == '}') {
-        if (p == end || *p != '}')
-          return handler.on_error("unmatched '}' in format string");
-        handler.on_text(begin, p);
-        begin = ++p;
-      }
-    }
-    handler.on_text(begin, end);
-    return;
-  }
-  struct writer {
-    FMT_CONSTEXPR void operator()(const Char* pbegin, const Char* pend) {
-      if (pbegin == pend) return;
-      for (;;) {
-        const Char* p = nullptr;
-        if (!find<IS_CONSTEXPR>(pbegin, pend, Char('}'), p))
-          return handler_.on_text(pbegin, pend);
-        ++p;
-        if (p == pend || *p != '}')
-          return handler_.on_error("unmatched '}' in format string");
-        handler_.on_text(pbegin, p);
-        pbegin = p + 1;
-      }
-    }
-    Handler& handler_;
-  } write{handler};
-  while (begin != end) {
-    // Doing two passes with memchr (one for '{' and another for '}') is up to
-    // 2.5x faster than the naive one-pass implementation on big format strings.
-    const Char* p = begin;
-    if (*begin != '{' && !find<IS_CONSTEXPR>(begin + 1, end, Char('{'), p))
-      return write(begin, end);
-    write(begin, p);
-    begin = parse_replacement_field(p, end, handler);
-  }
-}
-
-template <typename T, typename ParseContext>
-FMT_CONSTEXPR auto parse_format_specs(ParseContext& ctx)
-    -> decltype(ctx.begin()) {
-  using char_type = typename ParseContext::char_type;
-  using context = buffer_context<char_type>;
-  using mapped_type = conditional_t<
-      mapped_type_constant<T, context>::value != type::custom_type,
-      decltype(arg_mapper<context>().map(std::declval<const T&>())), T>;
-  auto f = conditional_t<has_formatter<mapped_type, context>::value,
-                         formatter<mapped_type, char_type>,
-                         fallback_formatter<T, char_type>>();
-  return f.parse(ctx);
-}
-
-// A parse context with extra argument id checks. It is only used at compile
-// time because adding checks at runtime would introduce substantial overhead
-// and would be redundant since argument ids are checked when arguments are
-// retrieved anyway.
-template <typename Char, typename ErrorHandler = error_handler>
-class compile_parse_context
-    : public basic_format_parse_context<Char, ErrorHandler> {
- private:
-  int num_args_;
-  using base = basic_format_parse_context<Char, ErrorHandler>;
-
- public:
-  explicit FMT_CONSTEXPR compile_parse_context(
-      basic_string_view<Char> format_str,
-      int num_args = (std::numeric_limits<int>::max)(), ErrorHandler eh = {})
-      : base(format_str, eh), num_args_(num_args) {}
-
-  FMT_CONSTEXPR auto next_arg_id() -> int {
-    int id = base::next_arg_id();
-    if (id >= num_args_) this->on_error("argument not found");
-    return id;
-  }
-
-  FMT_CONSTEXPR void check_arg_id(int id) {
-    base::check_arg_id(id);
-    if (id >= num_args_) this->on_error("argument not found");
-  }
-  using base::check_arg_id;
-};
-
-template <typename ErrorHandler>
-FMT_CONSTEXPR void check_int_type_spec(presentation_type type,
-                                       ErrorHandler&& eh) {
-  if (type > presentation_type::bin_upper && type != presentation_type::chr)
-    eh.on_error("invalid type specifier");
-}
-
-// Checks char specs and returns true if the type spec is char (and not int).
-template <typename Char, typename ErrorHandler = error_handler>
-FMT_CONSTEXPR auto check_char_specs(const basic_format_specs<Char>& specs,
-                                    ErrorHandler&& eh = {}) -> bool {
-  if (specs.type != presentation_type::none &&
-      specs.type != presentation_type::chr) {
-    check_int_type_spec(specs.type, eh);
-    return false;
-  }
-  if (specs.align == align::numeric || specs.sign != sign::none || specs.alt)
-    eh.on_error("invalid format specifier for char");
-  return true;
-}
-
-// A floating-point presentation format.
-enum class float_format : unsigned char {
-  general,  // General: exponent notation or fixed point based on magnitude.
-  exp,      // Exponent notation with the default precision of 6, e.g. 1.2e-3.
-  fixed,    // Fixed point with the default precision of 6, e.g. 0.0012.
-  hex
-};
-
-struct float_specs {
-  int precision;
-  float_format format : 8;
-  sign_t sign : 8;
-  bool upper : 1;
-  bool locale : 1;
-  bool binary32 : 1;
-  bool fallback : 1;
-  bool showpoint : 1;
-};
-
-template <typename ErrorHandler = error_handler, typename Char>
-FMT_CONSTEXPR auto parse_float_type_spec(const basic_format_specs<Char>& specs,
-                                         ErrorHandler&& eh = {})
-    -> float_specs {
-  auto result = float_specs();
-  result.showpoint = specs.alt;
-  result.locale = specs.localized;
-  switch (specs.type) {
-  case presentation_type::none:
-    result.format = float_format::general;
-    break;
-  case presentation_type::general_upper:
-    result.upper = true;
-    FMT_FALLTHROUGH;
-  case presentation_type::general_lower:
-    result.format = float_format::general;
-    break;
-  case presentation_type::exp_upper:
-    result.upper = true;
-    FMT_FALLTHROUGH;
-  case presentation_type::exp_lower:
-    result.format = float_format::exp;
-    result.showpoint |= specs.precision != 0;
-    break;
-  case presentation_type::fixed_upper:
-    result.upper = true;
-    FMT_FALLTHROUGH;
-  case presentation_type::fixed_lower:
-    result.format = float_format::fixed;
-    result.showpoint |= specs.precision != 0;
-    break;
-  case presentation_type::hexfloat_upper:
-    result.upper = true;
-    FMT_FALLTHROUGH;
-  case presentation_type::hexfloat_lower:
-    result.format = float_format::hex;
-    break;
-  default:
-    eh.on_error("invalid type specifier");
-    break;
-  }
-  return result;
-}
-
-template <typename ErrorHandler = error_handler>
-FMT_CONSTEXPR auto check_cstring_type_spec(presentation_type type,
-                                           ErrorHandler&& eh = {}) -> bool {
-  if (type == presentation_type::none || type == presentation_type::string)
-    return true;
-  if (type != presentation_type::pointer) eh.on_error("invalid type specifier");
-  return false;
-}
-
-template <typename ErrorHandler = error_handler>
-FMT_CONSTEXPR void check_string_type_spec(presentation_type type,
-                                          ErrorHandler&& eh = {}) {
-  if (type != presentation_type::none && type != presentation_type::string)
-    eh.on_error("invalid type specifier");
-}
-
-template <typename ErrorHandler>
-FMT_CONSTEXPR void check_pointer_type_spec(presentation_type type,
-                                           ErrorHandler&& eh) {
-  if (type != presentation_type::none && type != presentation_type::pointer)
-    eh.on_error("invalid type specifier");
-}
-
-// A parse_format_specs handler that checks if specifiers are consistent with
-// the argument type.
-template <typename Handler> class specs_checker : public Handler {
- private:
-  detail::type arg_type_;
-
-  FMT_CONSTEXPR void require_numeric_argument() {
-    if (!is_arithmetic_type(arg_type_))
-      this->on_error("format specifier requires numeric argument");
-  }
-
- public:
-  FMT_CONSTEXPR specs_checker(const Handler& handler, detail::type arg_type)
-      : Handler(handler), arg_type_(arg_type) {}
-
-  FMT_CONSTEXPR void on_align(align_t align) {
-    if (align == align::numeric) require_numeric_argument();
-    Handler::on_align(align);
-  }
-
-  FMT_CONSTEXPR void on_sign(sign_t s) {
-    require_numeric_argument();
-    if (is_integral_type(arg_type_) && arg_type_ != type::int_type &&
-        arg_type_ != type::long_long_type && arg_type_ != type::char_type) {
-      this->on_error("format specifier requires signed argument");
-    }
-    Handler::on_sign(s);
-  }
-
-  FMT_CONSTEXPR void on_hash() {
-    require_numeric_argument();
-    Handler::on_hash();
-  }
-
-  FMT_CONSTEXPR void on_localized() {
-    require_numeric_argument();
-    Handler::on_localized();
-  }
-
-  FMT_CONSTEXPR void on_zero() {
-    require_numeric_argument();
-    Handler::on_zero();
-  }
-
-  FMT_CONSTEXPR void end_precision() {
-    if (is_integral_type(arg_type_) || arg_type_ == type::pointer_type)
-      this->on_error("precision not allowed for this argument type");
-  }
-};
-
-constexpr int invalid_arg_index = -1;
-
-#if FMT_USE_NONTYPE_TEMPLATE_PARAMETERS
-template <int N, typename T, typename... Args, typename Char>
-constexpr auto get_arg_index_by_name(basic_string_view<Char> name) -> int {
-  if constexpr (detail::is_statically_named_arg<T>()) {
-    if (name == T::name) return N;
-  }
-  if constexpr (sizeof...(Args) > 0)
-    return get_arg_index_by_name<N + 1, Args...>(name);
-  (void)name;  // Workaround an MSVC bug about "unused" parameter.
-  return invalid_arg_index;
-}
-#endif
-
-template <typename... Args, typename Char>
-FMT_CONSTEXPR auto get_arg_index_by_name(basic_string_view<Char> name) -> int {
-#if FMT_USE_NONTYPE_TEMPLATE_PARAMETERS
-  if constexpr (sizeof...(Args) > 0)
-    return get_arg_index_by_name<0, Args...>(name);
-#endif
-  (void)name;
-  return invalid_arg_index;
-}
-
-template <typename Char, typename ErrorHandler, typename... Args>
-class format_string_checker {
- private:
-  using parse_context_type = compile_parse_context<Char, ErrorHandler>;
-  enum { num_args = sizeof...(Args) };
-
-  // Format specifier parsing function.
-  using parse_func = const Char* (*)(parse_context_type&);
-
-  parse_context_type context_;
-  parse_func parse_funcs_[num_args > 0 ? num_args : 1];
-
- public:
-  explicit FMT_CONSTEXPR format_string_checker(
-      basic_string_view<Char> format_str, ErrorHandler eh)
-      : context_(format_str, num_args, eh),
-        parse_funcs_{&parse_format_specs<Args, parse_context_type>...} {}
-
-  FMT_CONSTEXPR void on_text(const Char*, const Char*) {}
-
-  FMT_CONSTEXPR auto on_arg_id() -> int { return context_.next_arg_id(); }
-  FMT_CONSTEXPR auto on_arg_id(int id) -> int {
-    return context_.check_arg_id(id), id;
-  }
-  FMT_CONSTEXPR auto on_arg_id(basic_string_view<Char> id) -> int {
-#if FMT_USE_NONTYPE_TEMPLATE_PARAMETERS
-    auto index = get_arg_index_by_name<Args...>(id);
-    if (index == invalid_arg_index) on_error("named argument is not found");
-    return context_.check_arg_id(index), index;
-#else
-    (void)id;
-    on_error("compile-time checks for named arguments require C++20 support");
-    return 0;
-#endif
-  }
-
-  FMT_CONSTEXPR void on_replacement_field(int, const Char*) {}
-
-  FMT_CONSTEXPR auto on_format_specs(int id, const Char* begin, const Char*)
-      -> const Char* {
-    context_.advance_to(context_.begin() + (begin - &*context_.begin()));
-    // id >= 0 check is a workaround for gcc 10 bug (#2065).
-    return id >= 0 && id < num_args ? parse_funcs_[id](context_) : begin;
-  }
-
-  FMT_CONSTEXPR void on_error(const char* message) {
-    context_.on_error(message);
-  }
-};
-
-template <typename... Args, typename S,
-          enable_if_t<(is_compile_string<S>::value), int>>
-void check_format_string(S format_str) {
-  FMT_CONSTEXPR auto s = to_string_view(format_str);
-  using checker = format_string_checker<typename S::char_type, error_handler,
-                                        remove_cvref_t<Args>...>;
-  FMT_CONSTEXPR bool invalid_format =
-      (parse_format_string<true>(s, checker(s, {})), true);
-  ignore_unused(invalid_format);
-}
-
-template <typename Char>
-void vformat_to(
-    buffer<Char>& buf, basic_string_view<Char> fmt,
-    basic_format_args<FMT_BUFFER_CONTEXT(type_identity_t<Char>)> args,
-    locale_ref loc = {});
-
-FMT_API void vprint_mojibake(std::FILE*, string_view, format_args);
-#ifndef _WIN32
-inline void vprint_mojibake(std::FILE*, string_view, format_args) {}
-#endif
-FMT_END_DETAIL_NAMESPACE
-
-// A formatter specialization for the core types corresponding to detail::type
-// constants.
-template <typename T, typename Char>
-struct formatter<T, Char,
-                 enable_if_t<detail::type_constant<T, Char>::value !=
-                             detail::type::custom_type>> {
- private:
-  detail::dynamic_format_specs<Char> specs_;
-
- public:
-  // Parses format specifiers stopping either at the end of the range or at the
-  // terminating '}'.
-  template <typename ParseContext>
-  FMT_CONSTEXPR auto parse(ParseContext& ctx) -> decltype(ctx.begin()) {
-    auto begin = ctx.begin(), end = ctx.end();
-    if (begin == end) return begin;
-    using handler_type = detail::dynamic_specs_handler<ParseContext>;
-    auto type = detail::type_constant<T, Char>::value;
-    auto checker =
-        detail::specs_checker<handler_type>(handler_type(specs_, ctx), type);
-    auto it = detail::parse_format_specs(begin, end, checker);
-    auto eh = ctx.error_handler();
-    switch (type) {
-    case detail::type::none_type:
-      FMT_ASSERT(false, "invalid argument type");
-      break;
-    case detail::type::bool_type:
-      if (specs_.type == presentation_type::none ||
-          specs_.type == presentation_type::string) {
-        break;
-      }
-      FMT_FALLTHROUGH;
-    case detail::type::int_type:
-    case detail::type::uint_type:
-    case detail::type::long_long_type:
-    case detail::type::ulong_long_type:
-    case detail::type::int128_type:
-    case detail::type::uint128_type:
-      detail::check_int_type_spec(specs_.type, eh);
-      break;
-    case detail::type::char_type:
-      detail::check_char_specs(specs_, eh);
-      break;
-    case detail::type::float_type:
-      if (detail::const_check(FMT_USE_FLOAT))
-        detail::parse_float_type_spec(specs_, eh);
-      else
-        FMT_ASSERT(false, "float support disabled");
-      break;
-    case detail::type::double_type:
-      if (detail::const_check(FMT_USE_DOUBLE))
-        detail::parse_float_type_spec(specs_, eh);
-      else
-        FMT_ASSERT(false, "double support disabled");
-      break;
-    case detail::type::long_double_type:
-      if (detail::const_check(FMT_USE_LONG_DOUBLE))
-        detail::parse_float_type_spec(specs_, eh);
-      else
-        FMT_ASSERT(false, "long double support disabled");
-      break;
-    case detail::type::cstring_type:
-      detail::check_cstring_type_spec(specs_.type, eh);
-      break;
-    case detail::type::string_type:
-      detail::check_string_type_spec(specs_.type, eh);
-      break;
-    case detail::type::pointer_type:
-      detail::check_pointer_type_spec(specs_.type, eh);
-      break;
-    case detail::type::custom_type:
-      // Custom format specifiers are checked in parse functions of
-      // formatter specializations.
-      break;
-    }
-    return it;
-  }
-
-  template <typename FormatContext>
-  FMT_CONSTEXPR auto format(const T& val, FormatContext& ctx) const
-      -> decltype(ctx.out());
-};
-
-template <typename Char> struct basic_runtime { basic_string_view<Char> str; };
-
-/** A compile-time format string. */
-template <typename Char, typename... Args> class basic_format_string {
- private:
-  basic_string_view<Char> str_;
-
- public:
-  template <typename S,
-            FMT_ENABLE_IF(
-                std::is_convertible<const S&, basic_string_view<Char>>::value)>
-  FMT_CONSTEVAL FMT_INLINE basic_format_string(const S& s) : str_(s) {
-    static_assert(
-        detail::count<
-            (std::is_base_of<detail::view, remove_reference_t<Args>>::value &&
-             std::is_reference<Args>::value)...>() == 0,
-        "passing views as lvalues is disallowed");
-#ifdef FMT_HAS_CONSTEVAL
-    if constexpr (detail::count_named_args<Args...>() ==
-                  detail::count_statically_named_args<Args...>()) {
-      using checker = detail::format_string_checker<Char, detail::error_handler,
-                                                    remove_cvref_t<Args>...>;
-      detail::parse_format_string<true>(str_, checker(s, {}));
-    }
-#else
-    detail::check_format_string<Args...>(s);
-#endif
-  }
-  basic_format_string(basic_runtime<Char> r) : str_(r.str) {}
-
-  FMT_INLINE operator basic_string_view<Char>() const { return str_; }
-};
-
-#if FMT_GCC_VERSION && FMT_GCC_VERSION < 409
-// Workaround broken conversion on older gcc.
-template <typename... Args> using format_string = string_view;
-template <typename S> auto runtime(const S& s) -> basic_string_view<char_t<S>> {
-  return s;
-}
-#else
-template <typename... Args>
-using format_string = basic_format_string<char, type_identity_t<Args>...>;
-/**
-  \rst
-  Creates a runtime format string.
-
-  **Example**::
-
-    // Check format string at runtime instead of compile-time.
-    fmt::print(fmt::runtime("{:d}"), "I am not a number");
-  \endrst
- */
-template <typename S> auto runtime(const S& s) -> basic_runtime<char_t<S>> {
-  return {{s}};
-}
-#endif
-
-FMT_API auto vformat(string_view fmt, format_args args) -> std::string;
-
-/**
-  \rst
-  Formats ``args`` according to specifications in ``fmt`` and returns the result
-  as a string.
-
-  **Example**::
-
-    #include <fmt/core.h>
-    std::string message = fmt::format("The answer is {}.", 42);
-  \endrst
-*/
-template <typename... T>
-FMT_NODISCARD FMT_INLINE auto format(format_string<T...> fmt, T&&... args)
-    -> std::string {
-  return vformat(fmt, fmt::make_format_args(args...));
-}
-
-/** Formats a string and writes the output to ``out``. */
-template <typename OutputIt,
-          FMT_ENABLE_IF(detail::is_output_iterator<OutputIt, char>::value)>
-auto vformat_to(OutputIt out, string_view fmt, format_args args) -> OutputIt {
-  using detail::get_buffer;
-  auto&& buf = get_buffer<char>(out);
-  detail::vformat_to(buf, fmt, args, {});
-  return detail::get_iterator(buf);
-}
-
-/**
- \rst
- Formats ``args`` according to specifications in ``fmt``, writes the result to
- the output iterator ``out`` and returns the iterator past the end of the output
- range. `format_to` does not append a terminating null character.
-
- **Example**::
-
-   auto out = std::vector<char>();
-   fmt::format_to(std::back_inserter(out), "{}", 42);
- \endrst
- */
-template <typename OutputIt, typename... T,
-          FMT_ENABLE_IF(detail::is_output_iterator<OutputIt, char>::value)>
-FMT_INLINE auto format_to(OutputIt out, format_string<T...> fmt, T&&... args)
-    -> OutputIt {
-  return vformat_to(out, fmt, fmt::make_format_args(args...));
-}
-
-template <typename OutputIt> struct format_to_n_result {
-  /** Iterator past the end of the output range. */
-  OutputIt out;
-  /** Total (not truncated) output size. */
-  size_t size;
-};
-
-template <typename OutputIt, typename... T,
-          FMT_ENABLE_IF(detail::is_output_iterator<OutputIt, char>::value)>
-auto vformat_to_n(OutputIt out, size_t n, string_view fmt, format_args args)
-    -> format_to_n_result<OutputIt> {
-  using traits = detail::fixed_buffer_traits;
-  auto buf = detail::iterator_buffer<OutputIt, char, traits>(out, n);
-  detail::vformat_to(buf, fmt, args, {});
-  return {buf.out(), buf.count()};
-}
-
-/**
-  \rst
-  Formats ``args`` according to specifications in ``fmt``, writes up to ``n``
-  characters of the result to the output iterator ``out`` and returns the total
-  (not truncated) output size and the iterator past the end of the output range.
-  `format_to_n` does not append a terminating null character.
-  \endrst
- */
-template <typename OutputIt, typename... T,
-          FMT_ENABLE_IF(detail::is_output_iterator<OutputIt, char>::value)>
-FMT_INLINE auto format_to_n(OutputIt out, size_t n, format_string<T...> fmt,
-                            T&&... args) -> format_to_n_result<OutputIt> {
-  return vformat_to_n(out, n, fmt, fmt::make_format_args(args...));
-}
-
-/** Returns the number of chars in the output of ``format(fmt, args...)``. */
-template <typename... T>
-FMT_NODISCARD FMT_INLINE auto formatted_size(format_string<T...> fmt,
-                                             T&&... args) -> size_t {
-  auto buf = detail::counting_buffer<>();
-  detail::vformat_to(buf, string_view(fmt), fmt::make_format_args(args...), {});
-  return buf.count();
-}
-
-FMT_API void vprint(string_view fmt, format_args args);
-FMT_API void vprint(std::FILE* f, string_view fmt, format_args args);
-
-/**
-  \rst
-  Formats ``args`` according to specifications in ``fmt`` and writes the output
-  to ``stdout``.
-
-  **Example**::
-
-    fmt::print("Elapsed time: {0:.2f} seconds", 1.23);
-  \endrst
- */
-template <typename... T>
-FMT_INLINE void print(format_string<T...> fmt, T&&... args) {
-  const auto& vargs = fmt::make_format_args(args...);
-  return detail::is_utf8() ? vprint(fmt, vargs)
-                           : detail::vprint_mojibake(stdout, fmt, vargs);
-}
-
-/**
-  \rst
-  Formats ``args`` according to specifications in ``fmt`` and writes the
-  output to the file ``f``.
-
-  **Example**::
-
-    fmt::print(stderr, "Don't {}!", "panic");
-  \endrst
- */
-template <typename... T>
-FMT_INLINE void print(std::FILE* f, format_string<T...> fmt, T&&... args) {
-  const auto& vargs = fmt::make_format_args(args...);
-  return detail::is_utf8() ? vprint(f, fmt, vargs)
-                           : detail::vprint_mojibake(f, fmt, vargs);
-}
-
-FMT_MODULE_EXPORT_END
-FMT_GCC_PRAGMA("GCC pop_options")
-FMT_END_NAMESPACE
-
-#ifdef FMT_HEADER_ONLY
-#  include "format.h"
-#endif
-#endif  // FMT_CORE_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/format-inl.h b/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/format-inl.h
deleted file mode 100644
index cc89abd..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/format-inl.h
+++ /dev/null
@@ -1,2642 +0,0 @@
-// Formatting library for C++ - implementation
-//
-// Copyright (c) 2012 - 2016, Victor Zverovich
-// All rights reserved.
-//
-// For the license information refer to format.h.
-
-#ifndef FMT_FORMAT_INL_H_
-#define FMT_FORMAT_INL_H_
-
-#include <algorithm>
-#include <cctype>
-#include <cerrno>  // errno
-#include <climits>
-#include <cmath>
-#include <cstdarg>
-#include <cstring>  // std::memmove
-#include <cwchar>
-#include <exception>
-
-#ifndef FMT_STATIC_THOUSANDS_SEPARATOR
-#  include <locale>
-#endif
-
-#ifdef _WIN32
-#  include <io.h>  // _isatty
-#endif
-
-#include "format.h"
-
-FMT_BEGIN_NAMESPACE
-namespace detail {
-
-FMT_FUNC void assert_fail(const char* file, int line, const char* message) {
-  // Use unchecked std::fprintf to avoid triggering another assertion when
-  // writing to stderr fails
-  std::fprintf(stderr, "%s:%d: assertion failed: %s", file, line, message);
-  // Chosen instead of std::abort to satisfy Clang in CUDA mode during device
-  // code pass.
-  std::terminate();
-}
-
-FMT_FUNC void throw_format_error(const char* message) {
-  FMT_THROW(format_error(message));
-}
-
-#ifndef _MSC_VER
-#  define FMT_SNPRINTF snprintf
-#else  // _MSC_VER
-inline int fmt_snprintf(char* buffer, size_t size, const char* format, ...) {
-  va_list args;
-  va_start(args, format);
-  int result = vsnprintf_s(buffer, size, _TRUNCATE, format, args);
-  va_end(args);
-  return result;
-}
-#  define FMT_SNPRINTF fmt_snprintf
-#endif  // _MSC_VER
-
-FMT_FUNC void format_error_code(detail::buffer<char>& out, int error_code,
-                                string_view message) FMT_NOEXCEPT {
-  // Report error code making sure that the output fits into
-  // inline_buffer_size to avoid dynamic memory allocation and potential
-  // bad_alloc.
-  out.try_resize(0);
-  static const char SEP[] = ": ";
-  static const char ERROR_STR[] = "error ";
-  // Subtract 2 to account for terminating null characters in SEP and ERROR_STR.
-  size_t error_code_size = sizeof(SEP) + sizeof(ERROR_STR) - 2;
-  auto abs_value = static_cast<uint32_or_64_or_128_t<int>>(error_code);
-  if (detail::is_negative(error_code)) {
-    abs_value = 0 - abs_value;
-    ++error_code_size;
-  }
-  error_code_size += detail::to_unsigned(detail::count_digits(abs_value));
-  auto it = buffer_appender<char>(out);
-  if (message.size() <= inline_buffer_size - error_code_size)
-    format_to(it, FMT_STRING("{}{}"), message, SEP);
-  format_to(it, FMT_STRING("{}{}"), ERROR_STR, error_code);
-  FMT_ASSERT(out.size() <= inline_buffer_size, "");
-}
-
-FMT_FUNC void report_error(format_func func, int error_code,
-                           const char* message) FMT_NOEXCEPT {
-  memory_buffer full_message;
-  func(full_message, error_code, message);
-  // Don't use fwrite_fully because the latter may throw.
-  if (std::fwrite(full_message.data(), full_message.size(), 1, stderr) > 0)
-    std::fputc('\n', stderr);
-}
-
-// A wrapper around fwrite that throws on error.
-inline void fwrite_fully(const void* ptr, size_t size, size_t count,
-                         FILE* stream) {
-  std::fwrite(ptr, size, count, stream);
-}
-
-#ifndef FMT_STATIC_THOUSANDS_SEPARATOR
-template <typename Locale>
-locale_ref::locale_ref(const Locale& loc) : locale_(&loc) {
-  static_assert(std::is_same<Locale, std::locale>::value, "");
-}
-
-template <typename Locale> Locale locale_ref::get() const {
-  static_assert(std::is_same<Locale, std::locale>::value, "");
-  return locale_ ? *static_cast<const std::locale*>(locale_) : std::locale();
-}
-
-template <typename Char>
-FMT_FUNC auto thousands_sep_impl(locale_ref loc) -> thousands_sep_result<Char> {
-  auto& facet = std::use_facet<std::numpunct<Char>>(loc.get<std::locale>());
-  auto grouping = facet.grouping();
-  auto thousands_sep = grouping.empty() ? Char() : facet.thousands_sep();
-  return {std::move(grouping), thousands_sep};
-}
-template <typename Char> FMT_FUNC Char decimal_point_impl(locale_ref loc) {
-  return std::use_facet<std::numpunct<Char>>(loc.get<std::locale>())
-      .decimal_point();
-}
-#else
-template <typename Char>
-FMT_FUNC auto thousands_sep_impl(locale_ref) -> thousands_sep_result<Char> {
-  return {"\03", FMT_STATIC_THOUSANDS_SEPARATOR};
-}
-template <typename Char> FMT_FUNC Char decimal_point_impl(locale_ref) {
-  return '.';
-}
-#endif
-}  // namespace detail
-
-#if !FMT_MSC_VER
-FMT_API FMT_FUNC format_error::~format_error() FMT_NOEXCEPT = default;
-#endif
-
-FMT_FUNC std::system_error vsystem_error(int error_code, string_view format_str,
-                                         format_args args) {
-  auto ec = std::error_code(error_code, std::generic_category());
-  return std::system_error(ec, vformat(format_str, args));
-}
-
-namespace detail {
-
-template <> FMT_FUNC int count_digits<4>(detail::fallback_uintptr n) {
-  // fallback_uintptr is always stored in little endian.
-  int i = static_cast<int>(sizeof(void*)) - 1;
-  while (i > 0 && n.value[i] == 0) --i;
-  auto char_digits = std::numeric_limits<unsigned char>::digits / 4;
-  return i >= 0 ? i * char_digits + count_digits<4, unsigned>(n.value[i]) : 1;
-}
-
-// log10(2) = 0x0.4d104d427de7fbcc...
-static constexpr uint64_t log10_2_significand = 0x4d104d427de7fbcc;
-
-template <typename T = void> struct basic_impl_data {
-  // Normalized 64-bit significands of pow(10, k), for k = -348, -340, ..., 340.
-  // These are generated by support/compute-powers.py.
-  static constexpr uint64_t pow10_significands[87] = {
-      0xfa8fd5a0081c0288, 0xbaaee17fa23ebf76, 0x8b16fb203055ac76,
-      0xcf42894a5dce35ea, 0x9a6bb0aa55653b2d, 0xe61acf033d1a45df,
-      0xab70fe17c79ac6ca, 0xff77b1fcbebcdc4f, 0xbe5691ef416bd60c,
-      0x8dd01fad907ffc3c, 0xd3515c2831559a83, 0x9d71ac8fada6c9b5,
-      0xea9c227723ee8bcb, 0xaecc49914078536d, 0x823c12795db6ce57,
-      0xc21094364dfb5637, 0x9096ea6f3848984f, 0xd77485cb25823ac7,
-      0xa086cfcd97bf97f4, 0xef340a98172aace5, 0xb23867fb2a35b28e,
-      0x84c8d4dfd2c63f3b, 0xc5dd44271ad3cdba, 0x936b9fcebb25c996,
-      0xdbac6c247d62a584, 0xa3ab66580d5fdaf6, 0xf3e2f893dec3f126,
-      0xb5b5ada8aaff80b8, 0x87625f056c7c4a8b, 0xc9bcff6034c13053,
-      0x964e858c91ba2655, 0xdff9772470297ebd, 0xa6dfbd9fb8e5b88f,
-      0xf8a95fcf88747d94, 0xb94470938fa89bcf, 0x8a08f0f8bf0f156b,
-      0xcdb02555653131b6, 0x993fe2c6d07b7fac, 0xe45c10c42a2b3b06,
-      0xaa242499697392d3, 0xfd87b5f28300ca0e, 0xbce5086492111aeb,
-      0x8cbccc096f5088cc, 0xd1b71758e219652c, 0x9c40000000000000,
-      0xe8d4a51000000000, 0xad78ebc5ac620000, 0x813f3978f8940984,
-      0xc097ce7bc90715b3, 0x8f7e32ce7bea5c70, 0xd5d238a4abe98068,
-      0x9f4f2726179a2245, 0xed63a231d4c4fb27, 0xb0de65388cc8ada8,
-      0x83c7088e1aab65db, 0xc45d1df942711d9a, 0x924d692ca61be758,
-      0xda01ee641a708dea, 0xa26da3999aef774a, 0xf209787bb47d6b85,
-      0xb454e4a179dd1877, 0x865b86925b9bc5c2, 0xc83553c5c8965d3d,
-      0x952ab45cfa97a0b3, 0xde469fbd99a05fe3, 0xa59bc234db398c25,
-      0xf6c69a72a3989f5c, 0xb7dcbf5354e9bece, 0x88fcf317f22241e2,
-      0xcc20ce9bd35c78a5, 0x98165af37b2153df, 0xe2a0b5dc971f303a,
-      0xa8d9d1535ce3b396, 0xfb9b7cd9a4a7443c, 0xbb764c4ca7a44410,
-      0x8bab8eefb6409c1a, 0xd01fef10a657842c, 0x9b10a4e5e9913129,
-      0xe7109bfba19c0c9d, 0xac2820d9623bf429, 0x80444b5e7aa7cf85,
-      0xbf21e44003acdd2d, 0x8e679c2f5e44ff8f, 0xd433179d9c8cb841,
-      0x9e19db92b4e31ba9, 0xeb96bf6ebadf77d9, 0xaf87023b9bf0ee6b,
-  };
-
-#if FMT_GCC_VERSION && FMT_GCC_VERSION < 409
-#  pragma GCC diagnostic push
-#  pragma GCC diagnostic ignored "-Wnarrowing"
-#endif
-  // Binary exponents of pow(10, k), for k = -348, -340, ..., 340, corresponding
-  // to significands above.
-  static constexpr int16_t pow10_exponents[87] = {
-      -1220, -1193, -1166, -1140, -1113, -1087, -1060, -1034, -1007, -980, -954,
-      -927,  -901,  -874,  -847,  -821,  -794,  -768,  -741,  -715,  -688, -661,
-      -635,  -608,  -582,  -555,  -529,  -502,  -475,  -449,  -422,  -396, -369,
-      -343,  -316,  -289,  -263,  -236,  -210,  -183,  -157,  -130,  -103, -77,
-      -50,   -24,   3,     30,    56,    83,    109,   136,   162,   189,  216,
-      242,   269,   295,   322,   348,   375,   402,   428,   455,   481,  508,
-      534,   561,   588,   614,   641,   667,   694,   720,   747,   774,  800,
-      827,   853,   880,   907,   933,   960,   986,   1013,  1039,  1066};
-#if FMT_GCC_VERSION && FMT_GCC_VERSION < 409
-#  pragma GCC diagnostic pop
-#endif
-
-  static constexpr uint64_t power_of_10_64[20] = {
-      1, FMT_POWERS_OF_10(1ULL), FMT_POWERS_OF_10(1000000000ULL),
-      10000000000000000000ULL};
-};
-
-// This is a struct rather than an alias to avoid shadowing warnings in gcc.
-struct impl_data : basic_impl_data<> {};
-
-#if __cplusplus < 201703L
-template <typename T>
-constexpr uint64_t basic_impl_data<T>::pow10_significands[];
-template <typename T> constexpr int16_t basic_impl_data<T>::pow10_exponents[];
-template <typename T> constexpr uint64_t basic_impl_data<T>::power_of_10_64[];
-#endif
-
-template <typename T> struct bits {
-  static FMT_CONSTEXPR_DECL const int value =
-      static_cast<int>(sizeof(T) * std::numeric_limits<unsigned char>::digits);
-};
-
-// Returns the number of significand bits in Float excluding the implicit bit.
-template <typename Float> constexpr int num_significand_bits() {
-  // Subtract 1 to account for an implicit most significant bit in the
-  // normalized form.
-  return std::numeric_limits<Float>::digits - 1;
-}
-
-// A floating-point number f * pow(2, e).
-struct fp {
-  uint64_t f;
-  int e;
-
-  static constexpr const int num_significand_bits = bits<decltype(f)>::value;
-
-  constexpr fp() : f(0), e(0) {}
-  constexpr fp(uint64_t f_val, int e_val) : f(f_val), e(e_val) {}
-
-  // Constructs fp from an IEEE754 floating-point number. It is a template to
-  // prevent compile errors on systems where n is not IEEE754.
-  template <typename Float> explicit FMT_CONSTEXPR fp(Float n) { assign(n); }
-
-  template <typename Float>
-  using is_supported = bool_constant<sizeof(Float) == sizeof(uint64_t) ||
-                                     sizeof(Float) == sizeof(uint32_t)>;
-
-  // Assigns d to this and return true iff predecessor is closer than successor.
-  template <typename Float, FMT_ENABLE_IF(is_supported<Float>::value)>
-  FMT_CONSTEXPR bool assign(Float n) {
-    // Assume float is in the format [sign][exponent][significand].
-    const int num_float_significand_bits =
-        detail::num_significand_bits<Float>();
-    const uint64_t implicit_bit = 1ULL << num_float_significand_bits;
-    const uint64_t significand_mask = implicit_bit - 1;
-    constexpr bool is_double = sizeof(Float) == sizeof(uint64_t);
-    auto u = bit_cast<conditional_t<is_double, uint64_t, uint32_t>>(n);
-    f = u & significand_mask;
-    const uint64_t exponent_mask = (~0ULL >> 1) & ~significand_mask;
-    int biased_e =
-        static_cast<int>((u & exponent_mask) >> num_float_significand_bits);
-    // The predecessor is closer if n is a normalized power of 2 (f == 0) other
-    // than the smallest normalized number (biased_e > 1).
-    bool is_predecessor_closer = f == 0 && biased_e > 1;
-    if (biased_e != 0)
-      f += implicit_bit;
-    else
-      biased_e = 1;  // Subnormals use biased exponent 1 (min exponent).
-    const int exponent_bias = std::numeric_limits<Float>::max_exponent - 1;
-    e = biased_e - exponent_bias - num_float_significand_bits;
-    return is_predecessor_closer;
-  }
-
-  template <typename Float, FMT_ENABLE_IF(!is_supported<Float>::value)>
-  bool assign(Float) {
-    FMT_ASSERT(false, "");
-    return false;
-  }
-};
-
-// Normalizes the value converted from double and multiplied by (1 << SHIFT).
-template <int SHIFT = 0> FMT_CONSTEXPR fp normalize(fp value) {
-  // Handle subnormals.
-  const uint64_t implicit_bit = 1ULL << num_significand_bits<double>();
-  const auto shifted_implicit_bit = implicit_bit << SHIFT;
-  while ((value.f & shifted_implicit_bit) == 0) {
-    value.f <<= 1;
-    --value.e;
-  }
-  // Subtract 1 to account for hidden bit.
-  const auto offset =
-      fp::num_significand_bits - num_significand_bits<double>() - SHIFT - 1;
-  value.f <<= offset;
-  value.e -= offset;
-  return value;
-}
-
-inline bool operator==(fp x, fp y) { return x.f == y.f && x.e == y.e; }
-
-// Computes lhs * rhs / pow(2, 64) rounded to nearest with half-up tie breaking.
-FMT_CONSTEXPR inline uint64_t multiply(uint64_t lhs, uint64_t rhs) {
-#if FMT_USE_INT128
-  auto product = static_cast<__uint128_t>(lhs) * rhs;
-  auto f = static_cast<uint64_t>(product >> 64);
-  return (static_cast<uint64_t>(product) & (1ULL << 63)) != 0 ? f + 1 : f;
-#else
-  // Multiply 32-bit parts of significands.
-  uint64_t mask = (1ULL << 32) - 1;
-  uint64_t a = lhs >> 32, b = lhs & mask;
-  uint64_t c = rhs >> 32, d = rhs & mask;
-  uint64_t ac = a * c, bc = b * c, ad = a * d, bd = b * d;
-  // Compute mid 64-bit of result and round.
-  uint64_t mid = (bd >> 32) + (ad & mask) + (bc & mask) + (1U << 31);
-  return ac + (ad >> 32) + (bc >> 32) + (mid >> 32);
-#endif
-}
-
-FMT_CONSTEXPR inline fp operator*(fp x, fp y) {
-  return {multiply(x.f, y.f), x.e + y.e + 64};
-}
-
-// Returns a cached power of 10 `c_k = c_k.f * pow(2, c_k.e)` such that its
-// (binary) exponent satisfies `min_exponent <= c_k.e <= min_exponent + 28`.
-FMT_CONSTEXPR inline fp get_cached_power(int min_exponent,
-                                         int& pow10_exponent) {
-  const int shift = 32;
-  const auto significand = static_cast<int64_t>(log10_2_significand);
-  int index = static_cast<int>(
-      ((min_exponent + fp::num_significand_bits - 1) * (significand >> shift) +
-       ((int64_t(1) << shift) - 1))  // ceil
-      >> 32                          // arithmetic shift
-  );
-  // Decimal exponent of the first (smallest) cached power of 10.
-  const int first_dec_exp = -348;
-  // Difference between 2 consecutive decimal exponents in cached powers of 10.
-  const int dec_exp_step = 8;
-  index = (index - first_dec_exp - 1) / dec_exp_step + 1;
-  pow10_exponent = first_dec_exp + index * dec_exp_step;
-  return {impl_data::pow10_significands[index],
-          impl_data::pow10_exponents[index]};
-}
-
-// A simple accumulator to hold the sums of terms in bigint::square if uint128_t
-// is not available.
-struct accumulator {
-  uint64_t lower;
-  uint64_t upper;
-
-  constexpr accumulator() : lower(0), upper(0) {}
-  constexpr explicit operator uint32_t() const {
-    return static_cast<uint32_t>(lower);
-  }
-
-  FMT_CONSTEXPR void operator+=(uint64_t n) {
-    lower += n;
-    if (lower < n) ++upper;
-  }
-  FMT_CONSTEXPR void operator>>=(int shift) {
-    FMT_ASSERT(shift == 32, "");
-    (void)shift;
-    lower = (upper << 32) | (lower >> 32);
-    upper >>= 32;
-  }
-};
-
-class bigint {
- private:
-  // A bigint is stored as an array of bigits (big digits), with bigit at index
-  // 0 being the least significant one.
-  using bigit = uint32_t;
-  using double_bigit = uint64_t;
-  enum { bigits_capacity = 32 };
-  basic_memory_buffer<bigit, bigits_capacity> bigits_;
-  int exp_;
-
-  FMT_CONSTEXPR20 bigit operator[](int index) const {
-    return bigits_[to_unsigned(index)];
-  }
-  FMT_CONSTEXPR20 bigit& operator[](int index) {
-    return bigits_[to_unsigned(index)];
-  }
-
-  static FMT_CONSTEXPR_DECL const int bigit_bits = bits<bigit>::value;
-
-  friend struct formatter<bigint>;
-
-  FMT_CONSTEXPR20 void subtract_bigits(int index, bigit other, bigit& borrow) {
-    auto result = static_cast<double_bigit>((*this)[index]) - other - borrow;
-    (*this)[index] = static_cast<bigit>(result);
-    borrow = static_cast<bigit>(result >> (bigit_bits * 2 - 1));
-  }
-
-  FMT_CONSTEXPR20 void remove_leading_zeros() {
-    int num_bigits = static_cast<int>(bigits_.size()) - 1;
-    while (num_bigits > 0 && (*this)[num_bigits] == 0) --num_bigits;
-    bigits_.resize(to_unsigned(num_bigits + 1));
-  }
-
-  // Computes *this -= other assuming aligned bigints and *this >= other.
-  FMT_CONSTEXPR20 void subtract_aligned(const bigint& other) {
-    FMT_ASSERT(other.exp_ >= exp_, "unaligned bigints");
-    FMT_ASSERT(compare(*this, other) >= 0, "");
-    bigit borrow = 0;
-    int i = other.exp_ - exp_;
-    for (size_t j = 0, n = other.bigits_.size(); j != n; ++i, ++j)
-      subtract_bigits(i, other.bigits_[j], borrow);
-    while (borrow > 0) subtract_bigits(i, 0, borrow);
-    remove_leading_zeros();
-  }
-
-  FMT_CONSTEXPR20 void multiply(uint32_t value) {
-    const double_bigit wide_value = value;
-    bigit carry = 0;
-    for (size_t i = 0, n = bigits_.size(); i < n; ++i) {
-      double_bigit result = bigits_[i] * wide_value + carry;
-      bigits_[i] = static_cast<bigit>(result);
-      carry = static_cast<bigit>(result >> bigit_bits);
-    }
-    if (carry != 0) bigits_.push_back(carry);
-  }
-
-  FMT_CONSTEXPR20 void multiply(uint64_t value) {
-    const bigit mask = ~bigit(0);
-    const double_bigit lower = value & mask;
-    const double_bigit upper = value >> bigit_bits;
-    double_bigit carry = 0;
-    for (size_t i = 0, n = bigits_.size(); i < n; ++i) {
-      double_bigit result = bigits_[i] * lower + (carry & mask);
-      carry =
-          bigits_[i] * upper + (result >> bigit_bits) + (carry >> bigit_bits);
-      bigits_[i] = static_cast<bigit>(result);
-    }
-    while (carry != 0) {
-      bigits_.push_back(carry & mask);
-      carry >>= bigit_bits;
-    }
-  }
-
- public:
-  FMT_CONSTEXPR20 bigint() : exp_(0) {}
-  explicit bigint(uint64_t n) { assign(n); }
-  FMT_CONSTEXPR20 ~bigint() {
-    FMT_ASSERT(bigits_.capacity() <= bigits_capacity, "");
-  }
-
-  bigint(const bigint&) = delete;
-  void operator=(const bigint&) = delete;
-
-  FMT_CONSTEXPR20 void assign(const bigint& other) {
-    auto size = other.bigits_.size();
-    bigits_.resize(size);
-    auto data = other.bigits_.data();
-    std::copy(data, data + size, make_checked(bigits_.data(), size));
-    exp_ = other.exp_;
-  }
-
-  FMT_CONSTEXPR20 void assign(uint64_t n) {
-    size_t num_bigits = 0;
-    do {
-      bigits_[num_bigits++] = n & ~bigit(0);
-      n >>= bigit_bits;
-    } while (n != 0);
-    bigits_.resize(num_bigits);
-    exp_ = 0;
-  }
-
-  FMT_CONSTEXPR20 int num_bigits() const {
-    return static_cast<int>(bigits_.size()) + exp_;
-  }
-
-  FMT_NOINLINE FMT_CONSTEXPR20 bigint& operator<<=(int shift) {
-    FMT_ASSERT(shift >= 0, "");
-    exp_ += shift / bigit_bits;
-    shift %= bigit_bits;
-    if (shift == 0) return *this;
-    bigit carry = 0;
-    for (size_t i = 0, n = bigits_.size(); i < n; ++i) {
-      bigit c = bigits_[i] >> (bigit_bits - shift);
-      bigits_[i] = (bigits_[i] << shift) + carry;
-      carry = c;
-    }
-    if (carry != 0) bigits_.push_back(carry);
-    return *this;
-  }
-
-  template <typename Int> FMT_CONSTEXPR20 bigint& operator*=(Int value) {
-    FMT_ASSERT(value > 0, "");
-    multiply(uint32_or_64_or_128_t<Int>(value));
-    return *this;
-  }
-
-  friend FMT_CONSTEXPR20 int compare(const bigint& lhs, const bigint& rhs) {
-    int num_lhs_bigits = lhs.num_bigits(), num_rhs_bigits = rhs.num_bigits();
-    if (num_lhs_bigits != num_rhs_bigits)
-      return num_lhs_bigits > num_rhs_bigits ? 1 : -1;
-    int i = static_cast<int>(lhs.bigits_.size()) - 1;
-    int j = static_cast<int>(rhs.bigits_.size()) - 1;
-    int end = i - j;
-    if (end < 0) end = 0;
-    for (; i >= end; --i, --j) {
-      bigit lhs_bigit = lhs[i], rhs_bigit = rhs[j];
-      if (lhs_bigit != rhs_bigit) return lhs_bigit > rhs_bigit ? 1 : -1;
-    }
-    if (i != j) return i > j ? 1 : -1;
-    return 0;
-  }
-
-  // Returns compare(lhs1 + lhs2, rhs).
-  friend FMT_CONSTEXPR20 int add_compare(const bigint& lhs1, const bigint& lhs2,
-                                         const bigint& rhs) {
-    int max_lhs_bigits = (std::max)(lhs1.num_bigits(), lhs2.num_bigits());
-    int num_rhs_bigits = rhs.num_bigits();
-    if (max_lhs_bigits + 1 < num_rhs_bigits) return -1;
-    if (max_lhs_bigits > num_rhs_bigits) return 1;
-    auto get_bigit = [](const bigint& n, int i) -> bigit {
-      return i >= n.exp_ && i < n.num_bigits() ? n[i - n.exp_] : 0;
-    };
-    double_bigit borrow = 0;
-    int min_exp = (std::min)((std::min)(lhs1.exp_, lhs2.exp_), rhs.exp_);
-    for (int i = num_rhs_bigits - 1; i >= min_exp; --i) {
-      double_bigit sum =
-          static_cast<double_bigit>(get_bigit(lhs1, i)) + get_bigit(lhs2, i);
-      bigit rhs_bigit = get_bigit(rhs, i);
-      if (sum > rhs_bigit + borrow) return 1;
-      borrow = rhs_bigit + borrow - sum;
-      if (borrow > 1) return -1;
-      borrow <<= bigit_bits;
-    }
-    return borrow != 0 ? -1 : 0;
-  }
-
-  // Assigns pow(10, exp) to this bigint.
-  FMT_CONSTEXPR20 void assign_pow10(int exp) {
-    FMT_ASSERT(exp >= 0, "");
-    if (exp == 0) return assign(1);
-    // Find the top bit.
-    int bitmask = 1;
-    while (exp >= bitmask) bitmask <<= 1;
-    bitmask >>= 1;
-    // pow(10, exp) = pow(5, exp) * pow(2, exp). First compute pow(5, exp) by
-    // repeated squaring and multiplication.
-    assign(5);
-    bitmask >>= 1;
-    while (bitmask != 0) {
-      square();
-      if ((exp & bitmask) != 0) *this *= 5;
-      bitmask >>= 1;
-    }
-    *this <<= exp;  // Multiply by pow(2, exp) by shifting.
-  }
-
-  FMT_CONSTEXPR20 void square() {
-    int num_bigits = static_cast<int>(bigits_.size());
-    int num_result_bigits = 2 * num_bigits;
-    basic_memory_buffer<bigit, bigits_capacity> n(std::move(bigits_));
-    bigits_.resize(to_unsigned(num_result_bigits));
-    using accumulator_t = conditional_t<FMT_USE_INT128, uint128_t, accumulator>;
-    auto sum = accumulator_t();
-    for (int bigit_index = 0; bigit_index < num_bigits; ++bigit_index) {
-      // Compute bigit at position bigit_index of the result by adding
-      // cross-product terms n[i] * n[j] such that i + j == bigit_index.
-      for (int i = 0, j = bigit_index; j >= 0; ++i, --j) {
-        // Most terms are multiplied twice which can be optimized in the future.
-        sum += static_cast<double_bigit>(n[i]) * n[j];
-      }
-      (*this)[bigit_index] = static_cast<bigit>(sum);
-      sum >>= bits<bigit>::value;  // Compute the carry.
-    }
-    // Do the same for the top half.
-    for (int bigit_index = num_bigits; bigit_index < num_result_bigits;
-         ++bigit_index) {
-      for (int j = num_bigits - 1, i = bigit_index - j; i < num_bigits;)
-        sum += static_cast<double_bigit>(n[i++]) * n[j--];
-      (*this)[bigit_index] = static_cast<bigit>(sum);
-      sum >>= bits<bigit>::value;
-    }
-    remove_leading_zeros();
-    exp_ *= 2;
-  }
-
-  // If this bigint has a bigger exponent than other, adds trailing zero to make
-  // exponents equal. This simplifies some operations such as subtraction.
-  FMT_CONSTEXPR20 void align(const bigint& other) {
-    int exp_difference = exp_ - other.exp_;
-    if (exp_difference <= 0) return;
-    int num_bigits = static_cast<int>(bigits_.size());
-    bigits_.resize(to_unsigned(num_bigits + exp_difference));
-    for (int i = num_bigits - 1, j = i + exp_difference; i >= 0; --i, --j)
-      bigits_[j] = bigits_[i];
-    std::uninitialized_fill_n(bigits_.data(), exp_difference, 0);
-    exp_ -= exp_difference;
-  }
-
-  // Divides this bignum by divisor, assigning the remainder to this and
-  // returning the quotient.
-  FMT_CONSTEXPR20 int divmod_assign(const bigint& divisor) {
-    FMT_ASSERT(this != &divisor, "");
-    if (compare(*this, divisor) < 0) return 0;
-    FMT_ASSERT(divisor.bigits_[divisor.bigits_.size() - 1u] != 0, "");
-    align(divisor);
-    int quotient = 0;
-    do {
-      subtract_aligned(divisor);
-      ++quotient;
-    } while (compare(*this, divisor) >= 0);
-    return quotient;
-  }
-};
-
-enum class round_direction { unknown, up, down };
-
-// Given the divisor (normally a power of 10), the remainder = v % divisor for
-// some number v and the error, returns whether v should be rounded up, down, or
-// whether the rounding direction can't be determined due to error.
-// error should be less than divisor / 2.
-FMT_CONSTEXPR inline round_direction get_round_direction(uint64_t divisor,
-                                                         uint64_t remainder,
-                                                         uint64_t error) {
-  FMT_ASSERT(remainder < divisor, "");  // divisor - remainder won't overflow.
-  FMT_ASSERT(error < divisor, "");      // divisor - error won't overflow.
-  FMT_ASSERT(error < divisor - error, "");  // error * 2 won't overflow.
-  // Round down if (remainder + error) * 2 <= divisor.
-  if (remainder <= divisor - remainder && error * 2 <= divisor - remainder * 2)
-    return round_direction::down;
-  // Round up if (remainder - error) * 2 >= divisor.
-  if (remainder >= error &&
-      remainder - error >= divisor - (remainder - error)) {
-    return round_direction::up;
-  }
-  return round_direction::unknown;
-}
-
-namespace digits {
-enum result {
-  more,  // Generate more digits.
-  done,  // Done generating digits.
-  error  // Digit generation cancelled due to an error.
-};
-}
-
-struct gen_digits_handler {
-  char* buf;
-  int size;
-  int precision;
-  int exp10;
-  bool fixed;
-
-  FMT_CONSTEXPR digits::result on_digit(char digit, uint64_t divisor,
-                                        uint64_t remainder, uint64_t error,
-                                        bool integral) {
-    FMT_ASSERT(remainder < divisor, "");
-    buf[size++] = digit;
-    if (!integral && error >= remainder) return digits::error;
-    if (size < precision) return digits::more;
-    if (!integral) {
-      // Check if error * 2 < divisor with overflow prevention.
-      // The check is not needed for the integral part because error = 1
-      // and divisor > (1 << 32) there.
-      if (error >= divisor || error >= divisor - error) return digits::error;
-    } else {
-      FMT_ASSERT(error == 1 && divisor > 2, "");
-    }
-    auto dir = get_round_direction(divisor, remainder, error);
-    if (dir != round_direction::up)
-      return dir == round_direction::down ? digits::done : digits::error;
-    ++buf[size - 1];
-    for (int i = size - 1; i > 0 && buf[i] > '9'; --i) {
-      buf[i] = '0';
-      ++buf[i - 1];
-    }
-    if (buf[0] > '9') {
-      buf[0] = '1';
-      if (fixed)
-        buf[size++] = '0';
-      else
-        ++exp10;
-    }
-    return digits::done;
-  }
-};
-
-// Generates output using the Grisu digit-gen algorithm.
-// error: the size of the region (lower, upper) outside of which numbers
-// definitely do not round to value (Delta in Grisu3).
-FMT_INLINE FMT_CONSTEXPR20 digits::result grisu_gen_digits(
-    fp value, uint64_t error, int& exp, gen_digits_handler& handler) {
-  const fp one(1ULL << -value.e, value.e);
-  // The integral part of scaled value (p1 in Grisu) = value / one. It cannot be
-  // zero because it contains a product of two 64-bit numbers with MSB set (due
-  // to normalization) - 1, shifted right by at most 60 bits.
-  auto integral = static_cast<uint32_t>(value.f >> -one.e);
-  FMT_ASSERT(integral != 0, "");
-  FMT_ASSERT(integral == value.f >> -one.e, "");
-  // The fractional part of scaled value (p2 in Grisu) c = value % one.
-  uint64_t fractional = value.f & (one.f - 1);
-  exp = count_digits(integral);  // kappa in Grisu.
-  // Non-fixed formats require at least one digit and no precision adjustment.
-  if (handler.fixed) {
-    // Adjust fixed precision by exponent because it is relative to decimal
-    // point.
-    int precision_offset = exp + handler.exp10;
-    if (precision_offset > 0 &&
-        handler.precision > max_value<int>() - precision_offset) {
-      FMT_THROW(format_error("number is too big"));
-    }
-    handler.precision += precision_offset;
-    // Check if precision is satisfied just by leading zeros, e.g.
-    // format("{:.2f}", 0.001) gives "0.00" without generating any digits.
-    if (handler.precision <= 0) {
-      if (handler.precision < 0) return digits::done;
-      // Divide by 10 to prevent overflow.
-      uint64_t divisor = impl_data::power_of_10_64[exp - 1] << -one.e;
-      auto dir = get_round_direction(divisor, value.f / 10, error * 10);
-      if (dir == round_direction::unknown) return digits::error;
-      handler.buf[handler.size++] = dir == round_direction::up ? '1' : '0';
-      return digits::done;
-    }
-  }
-  // Generate digits for the integral part. This can produce up to 10 digits.
-  do {
-    uint32_t digit = 0;
-    auto divmod_integral = [&](uint32_t divisor) {
-      digit = integral / divisor;
-      integral %= divisor;
-    };
-    // This optimization by Milo Yip reduces the number of integer divisions by
-    // one per iteration.
-    switch (exp) {
-    case 10:
-      divmod_integral(1000000000);
-      break;
-    case 9:
-      divmod_integral(100000000);
-      break;
-    case 8:
-      divmod_integral(10000000);
-      break;
-    case 7:
-      divmod_integral(1000000);
-      break;
-    case 6:
-      divmod_integral(100000);
-      break;
-    case 5:
-      divmod_integral(10000);
-      break;
-    case 4:
-      divmod_integral(1000);
-      break;
-    case 3:
-      divmod_integral(100);
-      break;
-    case 2:
-      divmod_integral(10);
-      break;
-    case 1:
-      digit = integral;
-      integral = 0;
-      break;
-    default:
-      FMT_ASSERT(false, "invalid number of digits");
-    }
-    --exp;
-    auto remainder = (static_cast<uint64_t>(integral) << -one.e) + fractional;
-    auto result = handler.on_digit(static_cast<char>('0' + digit),
-                                   impl_data::power_of_10_64[exp] << -one.e,
-                                   remainder, error, true);
-    if (result != digits::more) return result;
-  } while (exp > 0);
-  // Generate digits for the fractional part.
-  for (;;) {
-    fractional *= 10;
-    error *= 10;
-    char digit = static_cast<char>('0' + (fractional >> -one.e));
-    fractional &= one.f - 1;
-    --exp;
-    auto result = handler.on_digit(digit, one.f, fractional, error, false);
-    if (result != digits::more) return result;
-  }
-}
-
-// A 128-bit integer type used internally,
-struct uint128_wrapper {
-  uint128_wrapper() = default;
-
-#if FMT_USE_INT128
-  uint128_t internal_;
-
-  constexpr uint128_wrapper(uint64_t high, uint64_t low) FMT_NOEXCEPT
-      : internal_{static_cast<uint128_t>(low) |
-                  (static_cast<uint128_t>(high) << 64)} {}
-
-  constexpr uint128_wrapper(uint128_t u) : internal_{u} {}
-
-  constexpr uint64_t high() const FMT_NOEXCEPT {
-    return uint64_t(internal_ >> 64);
-  }
-  constexpr uint64_t low() const FMT_NOEXCEPT { return uint64_t(internal_); }
-
-  uint128_wrapper& operator+=(uint64_t n) FMT_NOEXCEPT {
-    internal_ += n;
-    return *this;
-  }
-#else
-  uint64_t high_;
-  uint64_t low_;
-
-  constexpr uint128_wrapper(uint64_t high, uint64_t low) FMT_NOEXCEPT
-      : high_{high},
-        low_{low} {}
-
-  constexpr uint64_t high() const FMT_NOEXCEPT { return high_; }
-  constexpr uint64_t low() const FMT_NOEXCEPT { return low_; }
-
-  uint128_wrapper& operator+=(uint64_t n) FMT_NOEXCEPT {
-#  if defined(_MSC_VER) && defined(_M_X64)
-    unsigned char carry = _addcarry_u64(0, low_, n, &low_);
-    _addcarry_u64(carry, high_, 0, &high_);
-    return *this;
-#  else
-    uint64_t sum = low_ + n;
-    high_ += (sum < low_ ? 1 : 0);
-    low_ = sum;
-    return *this;
-#  endif
-  }
-#endif
-};
-
-// Implementation of Dragonbox algorithm: https://github.com/jk-jeon/dragonbox.
-namespace dragonbox {
-// Computes 128-bit result of multiplication of two 64-bit unsigned integers.
-inline uint128_wrapper umul128(uint64_t x, uint64_t y) FMT_NOEXCEPT {
-#if FMT_USE_INT128
-  return static_cast<uint128_t>(x) * static_cast<uint128_t>(y);
-#elif defined(_MSC_VER) && defined(_M_X64)
-  uint128_wrapper result;
-  result.low_ = _umul128(x, y, &result.high_);
-  return result;
-#else
-  const uint64_t mask = (uint64_t(1) << 32) - uint64_t(1);
-
-  uint64_t a = x >> 32;
-  uint64_t b = x & mask;
-  uint64_t c = y >> 32;
-  uint64_t d = y & mask;
-
-  uint64_t ac = a * c;
-  uint64_t bc = b * c;
-  uint64_t ad = a * d;
-  uint64_t bd = b * d;
-
-  uint64_t intermediate = (bd >> 32) + (ad & mask) + (bc & mask);
-
-  return {ac + (intermediate >> 32) + (ad >> 32) + (bc >> 32),
-          (intermediate << 32) + (bd & mask)};
-#endif
-}
-
-// Computes upper 64 bits of multiplication of two 64-bit unsigned integers.
-inline uint64_t umul128_upper64(uint64_t x, uint64_t y) FMT_NOEXCEPT {
-#if FMT_USE_INT128
-  auto p = static_cast<uint128_t>(x) * static_cast<uint128_t>(y);
-  return static_cast<uint64_t>(p >> 64);
-#elif defined(_MSC_VER) && defined(_M_X64)
-  return __umulh(x, y);
-#else
-  return umul128(x, y).high();
-#endif
-}
-
-// Computes upper 64 bits of multiplication of a 64-bit unsigned integer and a
-// 128-bit unsigned integer.
-inline uint64_t umul192_upper64(uint64_t x, uint128_wrapper y) FMT_NOEXCEPT {
-  uint128_wrapper g0 = umul128(x, y.high());
-  g0 += umul128_upper64(x, y.low());
-  return g0.high();
-}
-
-// Computes upper 32 bits of multiplication of a 32-bit unsigned integer and a
-// 64-bit unsigned integer.
-inline uint32_t umul96_upper32(uint32_t x, uint64_t y) FMT_NOEXCEPT {
-  return static_cast<uint32_t>(umul128_upper64(x, y));
-}
-
-// Computes middle 64 bits of multiplication of a 64-bit unsigned integer and a
-// 128-bit unsigned integer.
-inline uint64_t umul192_middle64(uint64_t x, uint128_wrapper y) FMT_NOEXCEPT {
-  uint64_t g01 = x * y.high();
-  uint64_t g10 = umul128_upper64(x, y.low());
-  return g01 + g10;
-}
-
-// Computes lower 64 bits of multiplication of a 32-bit unsigned integer and a
-// 64-bit unsigned integer.
-inline uint64_t umul96_lower64(uint32_t x, uint64_t y) FMT_NOEXCEPT {
-  return x * y;
-}
-
-// Computes floor(log10(pow(2, e))) for e in [-1700, 1700] using the method from
-// https://fmt.dev/papers/Grisu-Exact.pdf#page=5, section 3.4.
-inline int floor_log10_pow2(int e) FMT_NOEXCEPT {
-  FMT_ASSERT(e <= 1700 && e >= -1700, "too large exponent");
-  const int shift = 22;
-  return (e * static_cast<int>(log10_2_significand >> (64 - shift))) >> shift;
-}
-
-// Various fast log computations.
-inline int floor_log2_pow10(int e) FMT_NOEXCEPT {
-  FMT_ASSERT(e <= 1233 && e >= -1233, "too large exponent");
-  const uint64_t log2_10_integer_part = 3;
-  const uint64_t log2_10_fractional_digits = 0x5269e12f346e2bf9;
-  const int shift_amount = 19;
-  return (e * static_cast<int>(
-                  (log2_10_integer_part << shift_amount) |
-                  (log2_10_fractional_digits >> (64 - shift_amount)))) >>
-         shift_amount;
-}
-inline int floor_log10_pow2_minus_log10_4_over_3(int e) FMT_NOEXCEPT {
-  FMT_ASSERT(e <= 1700 && e >= -1700, "too large exponent");
-  const uint64_t log10_4_over_3_fractional_digits = 0x1ffbfc2bbc780375;
-  const int shift_amount = 22;
-  return (e * static_cast<int>(log10_2_significand >> (64 - shift_amount)) -
-          static_cast<int>(log10_4_over_3_fractional_digits >>
-                           (64 - shift_amount))) >>
-         shift_amount;
-}
-
-// Returns true iff x is divisible by pow(2, exp).
-inline bool divisible_by_power_of_2(uint32_t x, int exp) FMT_NOEXCEPT {
-  FMT_ASSERT(exp >= 1, "");
-  FMT_ASSERT(x != 0, "");
-#ifdef FMT_BUILTIN_CTZ
-  return FMT_BUILTIN_CTZ(x) >= exp;
-#else
-  return exp < num_bits<uint32_t>() && x == ((x >> exp) << exp);
-#endif
-}
-inline bool divisible_by_power_of_2(uint64_t x, int exp) FMT_NOEXCEPT {
-  FMT_ASSERT(exp >= 1, "");
-  FMT_ASSERT(x != 0, "");
-#ifdef FMT_BUILTIN_CTZLL
-  return FMT_BUILTIN_CTZLL(x) >= exp;
-#else
-  return exp < num_bits<uint64_t>() && x == ((x >> exp) << exp);
-#endif
-}
-
-// Table entry type for divisibility test.
-template <typename T> struct divtest_table_entry {
-  T mod_inv;
-  T max_quotient;
-};
-
-// Returns true iff x is divisible by pow(5, exp).
-inline bool divisible_by_power_of_5(uint32_t x, int exp) FMT_NOEXCEPT {
-  FMT_ASSERT(exp <= 10, "too large exponent");
-  static constexpr const divtest_table_entry<uint32_t> divtest_table[] = {
-      {0x00000001, 0xffffffff}, {0xcccccccd, 0x33333333},
-      {0xc28f5c29, 0x0a3d70a3}, {0x26e978d5, 0x020c49ba},
-      {0x3afb7e91, 0x0068db8b}, {0x0bcbe61d, 0x0014f8b5},
-      {0x68c26139, 0x000431bd}, {0xae8d46a5, 0x0000d6bf},
-      {0x22e90e21, 0x00002af3}, {0x3a2e9c6d, 0x00000897},
-      {0x3ed61f49, 0x000001b7}};
-  return x * divtest_table[exp].mod_inv <= divtest_table[exp].max_quotient;
-}
-inline bool divisible_by_power_of_5(uint64_t x, int exp) FMT_NOEXCEPT {
-  FMT_ASSERT(exp <= 23, "too large exponent");
-  static constexpr const divtest_table_entry<uint64_t> divtest_table[] = {
-      {0x0000000000000001, 0xffffffffffffffff},
-      {0xcccccccccccccccd, 0x3333333333333333},
-      {0x8f5c28f5c28f5c29, 0x0a3d70a3d70a3d70},
-      {0x1cac083126e978d5, 0x020c49ba5e353f7c},
-      {0xd288ce703afb7e91, 0x0068db8bac710cb2},
-      {0x5d4e8fb00bcbe61d, 0x0014f8b588e368f0},
-      {0x790fb65668c26139, 0x000431bde82d7b63},
-      {0xe5032477ae8d46a5, 0x0000d6bf94d5e57a},
-      {0xc767074b22e90e21, 0x00002af31dc46118},
-      {0x8e47ce423a2e9c6d, 0x0000089705f4136b},
-      {0x4fa7f60d3ed61f49, 0x000001b7cdfd9d7b},
-      {0x0fee64690c913975, 0x00000057f5ff85e5},
-      {0x3662e0e1cf503eb1, 0x000000119799812d},
-      {0xa47a2cf9f6433fbd, 0x0000000384b84d09},
-      {0x54186f653140a659, 0x00000000b424dc35},
-      {0x7738164770402145, 0x0000000024075f3d},
-      {0xe4a4d1417cd9a041, 0x000000000734aca5},
-      {0xc75429d9e5c5200d, 0x000000000170ef54},
-      {0xc1773b91fac10669, 0x000000000049c977},
-      {0x26b172506559ce15, 0x00000000000ec1e4},
-      {0xd489e3a9addec2d1, 0x000000000002f394},
-      {0x90e860bb892c8d5d, 0x000000000000971d},
-      {0x502e79bf1b6f4f79, 0x0000000000001e39},
-      {0xdcd618596be30fe5, 0x000000000000060b}};
-  return x * divtest_table[exp].mod_inv <= divtest_table[exp].max_quotient;
-}
-
-// Replaces n by floor(n / pow(5, N)) returning true if and only if n is
-// divisible by pow(5, N).
-// Precondition: n <= 2 * pow(5, N + 1).
-template <int N>
-bool check_divisibility_and_divide_by_pow5(uint32_t& n) FMT_NOEXCEPT {
-  static constexpr struct {
-    uint32_t magic_number;
-    int bits_for_comparison;
-    uint32_t threshold;
-    int shift_amount;
-  } infos[] = {{0xcccd, 16, 0x3333, 18}, {0xa429, 8, 0x0a, 20}};
-  constexpr auto info = infos[N - 1];
-  n *= info.magic_number;
-  const uint32_t comparison_mask = (1u << info.bits_for_comparison) - 1;
-  bool result = (n & comparison_mask) <= info.threshold;
-  n >>= info.shift_amount;
-  return result;
-}
-
-// Computes floor(n / pow(10, N)) for small n and N.
-// Precondition: n <= pow(10, N + 1).
-template <int N> uint32_t small_division_by_pow10(uint32_t n) FMT_NOEXCEPT {
-  static constexpr struct {
-    uint32_t magic_number;
-    int shift_amount;
-    uint32_t divisor_times_10;
-  } infos[] = {{0xcccd, 19, 100}, {0xa3d8, 22, 1000}};
-  constexpr auto info = infos[N - 1];
-  FMT_ASSERT(n <= info.divisor_times_10, "n is too large");
-  return n * info.magic_number >> info.shift_amount;
-}
-
-// Computes floor(n / 10^(kappa + 1)) (float)
-inline uint32_t divide_by_10_to_kappa_plus_1(uint32_t n) FMT_NOEXCEPT {
-  return n / float_info<float>::big_divisor;
-}
-// Computes floor(n / 10^(kappa + 1)) (double)
-inline uint64_t divide_by_10_to_kappa_plus_1(uint64_t n) FMT_NOEXCEPT {
-  return umul128_upper64(n, 0x83126e978d4fdf3c) >> 9;
-}
-
-// Various subroutines using pow10 cache
-template <class T> struct cache_accessor;
-
-template <> struct cache_accessor<float> {
-  using carrier_uint = float_info<float>::carrier_uint;
-  using cache_entry_type = uint64_t;
-
-  static uint64_t get_cached_power(int k) FMT_NOEXCEPT {
-    FMT_ASSERT(k >= float_info<float>::min_k && k <= float_info<float>::max_k,
-               "k is out of range");
-    static constexpr const uint64_t pow10_significands[] = {
-        0x81ceb32c4b43fcf5, 0xa2425ff75e14fc32, 0xcad2f7f5359a3b3f,
-        0xfd87b5f28300ca0e, 0x9e74d1b791e07e49, 0xc612062576589ddb,
-        0xf79687aed3eec552, 0x9abe14cd44753b53, 0xc16d9a0095928a28,
-        0xf1c90080baf72cb2, 0x971da05074da7bef, 0xbce5086492111aeb,
-        0xec1e4a7db69561a6, 0x9392ee8e921d5d08, 0xb877aa3236a4b44a,
-        0xe69594bec44de15c, 0x901d7cf73ab0acda, 0xb424dc35095cd810,
-        0xe12e13424bb40e14, 0x8cbccc096f5088cc, 0xafebff0bcb24aaff,
-        0xdbe6fecebdedd5bf, 0x89705f4136b4a598, 0xabcc77118461cefd,
-        0xd6bf94d5e57a42bd, 0x8637bd05af6c69b6, 0xa7c5ac471b478424,
-        0xd1b71758e219652c, 0x83126e978d4fdf3c, 0xa3d70a3d70a3d70b,
-        0xcccccccccccccccd, 0x8000000000000000, 0xa000000000000000,
-        0xc800000000000000, 0xfa00000000000000, 0x9c40000000000000,
-        0xc350000000000000, 0xf424000000000000, 0x9896800000000000,
-        0xbebc200000000000, 0xee6b280000000000, 0x9502f90000000000,
-        0xba43b74000000000, 0xe8d4a51000000000, 0x9184e72a00000000,
-        0xb5e620f480000000, 0xe35fa931a0000000, 0x8e1bc9bf04000000,
-        0xb1a2bc2ec5000000, 0xde0b6b3a76400000, 0x8ac7230489e80000,
-        0xad78ebc5ac620000, 0xd8d726b7177a8000, 0x878678326eac9000,
-        0xa968163f0a57b400, 0xd3c21bcecceda100, 0x84595161401484a0,
-        0xa56fa5b99019a5c8, 0xcecb8f27f4200f3a, 0x813f3978f8940984,
-        0xa18f07d736b90be5, 0xc9f2c9cd04674ede, 0xfc6f7c4045812296,
-        0x9dc5ada82b70b59d, 0xc5371912364ce305, 0xf684df56c3e01bc6,
-        0x9a130b963a6c115c, 0xc097ce7bc90715b3, 0xf0bdc21abb48db20,
-        0x96769950b50d88f4, 0xbc143fa4e250eb31, 0xeb194f8e1ae525fd,
-        0x92efd1b8d0cf37be, 0xb7abc627050305ad, 0xe596b7b0c643c719,
-        0x8f7e32ce7bea5c6f, 0xb35dbf821ae4f38b, 0xe0352f62a19e306e};
-    return pow10_significands[k - float_info<float>::min_k];
-  }
-
-  static carrier_uint compute_mul(carrier_uint u,
-                                  const cache_entry_type& cache) FMT_NOEXCEPT {
-    return umul96_upper32(u, cache);
-  }
-
-  static uint32_t compute_delta(const cache_entry_type& cache,
-                                int beta_minus_1) FMT_NOEXCEPT {
-    return static_cast<uint32_t>(cache >> (64 - 1 - beta_minus_1));
-  }
-
-  static bool compute_mul_parity(carrier_uint two_f,
-                                 const cache_entry_type& cache,
-                                 int beta_minus_1) FMT_NOEXCEPT {
-    FMT_ASSERT(beta_minus_1 >= 1, "");
-    FMT_ASSERT(beta_minus_1 < 64, "");
-
-    return ((umul96_lower64(two_f, cache) >> (64 - beta_minus_1)) & 1) != 0;
-  }
-
-  static carrier_uint compute_left_endpoint_for_shorter_interval_case(
-      const cache_entry_type& cache, int beta_minus_1) FMT_NOEXCEPT {
-    return static_cast<carrier_uint>(
-        (cache - (cache >> (float_info<float>::significand_bits + 2))) >>
-        (64 - float_info<float>::significand_bits - 1 - beta_minus_1));
-  }
-
-  static carrier_uint compute_right_endpoint_for_shorter_interval_case(
-      const cache_entry_type& cache, int beta_minus_1) FMT_NOEXCEPT {
-    return static_cast<carrier_uint>(
-        (cache + (cache >> (float_info<float>::significand_bits + 1))) >>
-        (64 - float_info<float>::significand_bits - 1 - beta_minus_1));
-  }
-
-  static carrier_uint compute_round_up_for_shorter_interval_case(
-      const cache_entry_type& cache, int beta_minus_1) FMT_NOEXCEPT {
-    return (static_cast<carrier_uint>(
-                cache >>
-                (64 - float_info<float>::significand_bits - 2 - beta_minus_1)) +
-            1) /
-           2;
-  }
-};
-
-template <> struct cache_accessor<double> {
-  using carrier_uint = float_info<double>::carrier_uint;
-  using cache_entry_type = uint128_wrapper;
-
-  static uint128_wrapper get_cached_power(int k) FMT_NOEXCEPT {
-    FMT_ASSERT(k >= float_info<double>::min_k && k <= float_info<double>::max_k,
-               "k is out of range");
-
-    static constexpr const uint128_wrapper pow10_significands[] = {
-#if FMT_USE_FULL_CACHE_DRAGONBOX
-      {0xff77b1fcbebcdc4f, 0x25e8e89c13bb0f7b},
-      {0x9faacf3df73609b1, 0x77b191618c54e9ad},
-      {0xc795830d75038c1d, 0xd59df5b9ef6a2418},
-      {0xf97ae3d0d2446f25, 0x4b0573286b44ad1e},
-      {0x9becce62836ac577, 0x4ee367f9430aec33},
-      {0xc2e801fb244576d5, 0x229c41f793cda740},
-      {0xf3a20279ed56d48a, 0x6b43527578c11110},
-      {0x9845418c345644d6, 0x830a13896b78aaaa},
-      {0xbe5691ef416bd60c, 0x23cc986bc656d554},
-      {0xedec366b11c6cb8f, 0x2cbfbe86b7ec8aa9},
-      {0x94b3a202eb1c3f39, 0x7bf7d71432f3d6aa},
-      {0xb9e08a83a5e34f07, 0xdaf5ccd93fb0cc54},
-      {0xe858ad248f5c22c9, 0xd1b3400f8f9cff69},
-      {0x91376c36d99995be, 0x23100809b9c21fa2},
-      {0xb58547448ffffb2d, 0xabd40a0c2832a78b},
-      {0xe2e69915b3fff9f9, 0x16c90c8f323f516d},
-      {0x8dd01fad907ffc3b, 0xae3da7d97f6792e4},
-      {0xb1442798f49ffb4a, 0x99cd11cfdf41779d},
-      {0xdd95317f31c7fa1d, 0x40405643d711d584},
-      {0x8a7d3eef7f1cfc52, 0x482835ea666b2573},
-      {0xad1c8eab5ee43b66, 0xda3243650005eed0},
-      {0xd863b256369d4a40, 0x90bed43e40076a83},
-      {0x873e4f75e2224e68, 0x5a7744a6e804a292},
-      {0xa90de3535aaae202, 0x711515d0a205cb37},
-      {0xd3515c2831559a83, 0x0d5a5b44ca873e04},
-      {0x8412d9991ed58091, 0xe858790afe9486c3},
-      {0xa5178fff668ae0b6, 0x626e974dbe39a873},
-      {0xce5d73ff402d98e3, 0xfb0a3d212dc81290},
-      {0x80fa687f881c7f8e, 0x7ce66634bc9d0b9a},
-      {0xa139029f6a239f72, 0x1c1fffc1ebc44e81},
-      {0xc987434744ac874e, 0xa327ffb266b56221},
-      {0xfbe9141915d7a922, 0x4bf1ff9f0062baa9},
-      {0x9d71ac8fada6c9b5, 0x6f773fc3603db4aa},
-      {0xc4ce17b399107c22, 0xcb550fb4384d21d4},
-      {0xf6019da07f549b2b, 0x7e2a53a146606a49},
-      {0x99c102844f94e0fb, 0x2eda7444cbfc426e},
-      {0xc0314325637a1939, 0xfa911155fefb5309},
-      {0xf03d93eebc589f88, 0x793555ab7eba27cb},
-      {0x96267c7535b763b5, 0x4bc1558b2f3458df},
-      {0xbbb01b9283253ca2, 0x9eb1aaedfb016f17},
-      {0xea9c227723ee8bcb, 0x465e15a979c1cadd},
-      {0x92a1958a7675175f, 0x0bfacd89ec191eca},
-      {0xb749faed14125d36, 0xcef980ec671f667c},
-      {0xe51c79a85916f484, 0x82b7e12780e7401b},
-      {0x8f31cc0937ae58d2, 0xd1b2ecb8b0908811},
-      {0xb2fe3f0b8599ef07, 0x861fa7e6dcb4aa16},
-      {0xdfbdcece67006ac9, 0x67a791e093e1d49b},
-      {0x8bd6a141006042bd, 0xe0c8bb2c5c6d24e1},
-      {0xaecc49914078536d, 0x58fae9f773886e19},
-      {0xda7f5bf590966848, 0xaf39a475506a899f},
-      {0x888f99797a5e012d, 0x6d8406c952429604},
-      {0xaab37fd7d8f58178, 0xc8e5087ba6d33b84},
-      {0xd5605fcdcf32e1d6, 0xfb1e4a9a90880a65},
-      {0x855c3be0a17fcd26, 0x5cf2eea09a550680},
-      {0xa6b34ad8c9dfc06f, 0xf42faa48c0ea481f},
-      {0xd0601d8efc57b08b, 0xf13b94daf124da27},
-      {0x823c12795db6ce57, 0x76c53d08d6b70859},
-      {0xa2cb1717b52481ed, 0x54768c4b0c64ca6f},
-      {0xcb7ddcdda26da268, 0xa9942f5dcf7dfd0a},
-      {0xfe5d54150b090b02, 0xd3f93b35435d7c4d},
-      {0x9efa548d26e5a6e1, 0xc47bc5014a1a6db0},
-      {0xc6b8e9b0709f109a, 0x359ab6419ca1091c},
-      {0xf867241c8cc6d4c0, 0xc30163d203c94b63},
-      {0x9b407691d7fc44f8, 0x79e0de63425dcf1e},
-      {0xc21094364dfb5636, 0x985915fc12f542e5},
-      {0xf294b943e17a2bc4, 0x3e6f5b7b17b2939e},
-      {0x979cf3ca6cec5b5a, 0xa705992ceecf9c43},
-      {0xbd8430bd08277231, 0x50c6ff782a838354},
-      {0xece53cec4a314ebd, 0xa4f8bf5635246429},
-      {0x940f4613ae5ed136, 0x871b7795e136be9a},
-      {0xb913179899f68584, 0x28e2557b59846e40},
-      {0xe757dd7ec07426e5, 0x331aeada2fe589d0},
-      {0x9096ea6f3848984f, 0x3ff0d2c85def7622},
-      {0xb4bca50b065abe63, 0x0fed077a756b53aa},
-      {0xe1ebce4dc7f16dfb, 0xd3e8495912c62895},
-      {0x8d3360f09cf6e4bd, 0x64712dd7abbbd95d},
-      {0xb080392cc4349dec, 0xbd8d794d96aacfb4},
-      {0xdca04777f541c567, 0xecf0d7a0fc5583a1},
-      {0x89e42caaf9491b60, 0xf41686c49db57245},
-      {0xac5d37d5b79b6239, 0x311c2875c522ced6},
-      {0xd77485cb25823ac7, 0x7d633293366b828c},
-      {0x86a8d39ef77164bc, 0xae5dff9c02033198},
-      {0xa8530886b54dbdeb, 0xd9f57f830283fdfd},
-      {0xd267caa862a12d66, 0xd072df63c324fd7c},
-      {0x8380dea93da4bc60, 0x4247cb9e59f71e6e},
-      {0xa46116538d0deb78, 0x52d9be85f074e609},
-      {0xcd795be870516656, 0x67902e276c921f8c},
-      {0x806bd9714632dff6, 0x00ba1cd8a3db53b7},
-      {0xa086cfcd97bf97f3, 0x80e8a40eccd228a5},
-      {0xc8a883c0fdaf7df0, 0x6122cd128006b2ce},
-      {0xfad2a4b13d1b5d6c, 0x796b805720085f82},
-      {0x9cc3a6eec6311a63, 0xcbe3303674053bb1},
-      {0xc3f490aa77bd60fc, 0xbedbfc4411068a9d},
-      {0xf4f1b4d515acb93b, 0xee92fb5515482d45},
-      {0x991711052d8bf3c5, 0x751bdd152d4d1c4b},
-      {0xbf5cd54678eef0b6, 0xd262d45a78a0635e},
-      {0xef340a98172aace4, 0x86fb897116c87c35},
-      {0x9580869f0e7aac0e, 0xd45d35e6ae3d4da1},
-      {0xbae0a846d2195712, 0x8974836059cca10a},
-      {0xe998d258869facd7, 0x2bd1a438703fc94c},
-      {0x91ff83775423cc06, 0x7b6306a34627ddd0},
-      {0xb67f6455292cbf08, 0x1a3bc84c17b1d543},
-      {0xe41f3d6a7377eeca, 0x20caba5f1d9e4a94},
-      {0x8e938662882af53e, 0x547eb47b7282ee9d},
-      {0xb23867fb2a35b28d, 0xe99e619a4f23aa44},
-      {0xdec681f9f4c31f31, 0x6405fa00e2ec94d5},
-      {0x8b3c113c38f9f37e, 0xde83bc408dd3dd05},
-      {0xae0b158b4738705e, 0x9624ab50b148d446},
-      {0xd98ddaee19068c76, 0x3badd624dd9b0958},
-      {0x87f8a8d4cfa417c9, 0xe54ca5d70a80e5d7},
-      {0xa9f6d30a038d1dbc, 0x5e9fcf4ccd211f4d},
-      {0xd47487cc8470652b, 0x7647c32000696720},
-      {0x84c8d4dfd2c63f3b, 0x29ecd9f40041e074},
-      {0xa5fb0a17c777cf09, 0xf468107100525891},
-      {0xcf79cc9db955c2cc, 0x7182148d4066eeb5},
-      {0x81ac1fe293d599bf, 0xc6f14cd848405531},
-      {0xa21727db38cb002f, 0xb8ada00e5a506a7d},
-      {0xca9cf1d206fdc03b, 0xa6d90811f0e4851d},
-      {0xfd442e4688bd304a, 0x908f4a166d1da664},
-      {0x9e4a9cec15763e2e, 0x9a598e4e043287ff},
-      {0xc5dd44271ad3cdba, 0x40eff1e1853f29fe},
-      {0xf7549530e188c128, 0xd12bee59e68ef47d},
-      {0x9a94dd3e8cf578b9, 0x82bb74f8301958cf},
-      {0xc13a148e3032d6e7, 0xe36a52363c1faf02},
-      {0xf18899b1bc3f8ca1, 0xdc44e6c3cb279ac2},
-      {0x96f5600f15a7b7e5, 0x29ab103a5ef8c0ba},
-      {0xbcb2b812db11a5de, 0x7415d448f6b6f0e8},
-      {0xebdf661791d60f56, 0x111b495b3464ad22},
-      {0x936b9fcebb25c995, 0xcab10dd900beec35},
-      {0xb84687c269ef3bfb, 0x3d5d514f40eea743},
-      {0xe65829b3046b0afa, 0x0cb4a5a3112a5113},
-      {0x8ff71a0fe2c2e6dc, 0x47f0e785eaba72ac},
-      {0xb3f4e093db73a093, 0x59ed216765690f57},
-      {0xe0f218b8d25088b8, 0x306869c13ec3532d},
-      {0x8c974f7383725573, 0x1e414218c73a13fc},
-      {0xafbd2350644eeacf, 0xe5d1929ef90898fb},
-      {0xdbac6c247d62a583, 0xdf45f746b74abf3a},
-      {0x894bc396ce5da772, 0x6b8bba8c328eb784},
-      {0xab9eb47c81f5114f, 0x066ea92f3f326565},
-      {0xd686619ba27255a2, 0xc80a537b0efefebe},
-      {0x8613fd0145877585, 0xbd06742ce95f5f37},
-      {0xa798fc4196e952e7, 0x2c48113823b73705},
-      {0xd17f3b51fca3a7a0, 0xf75a15862ca504c6},
-      {0x82ef85133de648c4, 0x9a984d73dbe722fc},
-      {0xa3ab66580d5fdaf5, 0xc13e60d0d2e0ebbb},
-      {0xcc963fee10b7d1b3, 0x318df905079926a9},
-      {0xffbbcfe994e5c61f, 0xfdf17746497f7053},
-      {0x9fd561f1fd0f9bd3, 0xfeb6ea8bedefa634},
-      {0xc7caba6e7c5382c8, 0xfe64a52ee96b8fc1},
-      {0xf9bd690a1b68637b, 0x3dfdce7aa3c673b1},
-      {0x9c1661a651213e2d, 0x06bea10ca65c084f},
-      {0xc31bfa0fe5698db8, 0x486e494fcff30a63},
-      {0xf3e2f893dec3f126, 0x5a89dba3c3efccfb},
-      {0x986ddb5c6b3a76b7, 0xf89629465a75e01d},
-      {0xbe89523386091465, 0xf6bbb397f1135824},
-      {0xee2ba6c0678b597f, 0x746aa07ded582e2d},
-      {0x94db483840b717ef, 0xa8c2a44eb4571cdd},
-      {0xba121a4650e4ddeb, 0x92f34d62616ce414},
-      {0xe896a0d7e51e1566, 0x77b020baf9c81d18},
-      {0x915e2486ef32cd60, 0x0ace1474dc1d122f},
-      {0xb5b5ada8aaff80b8, 0x0d819992132456bb},
-      {0xe3231912d5bf60e6, 0x10e1fff697ed6c6a},
-      {0x8df5efabc5979c8f, 0xca8d3ffa1ef463c2},
-      {0xb1736b96b6fd83b3, 0xbd308ff8a6b17cb3},
-      {0xddd0467c64bce4a0, 0xac7cb3f6d05ddbdf},
-      {0x8aa22c0dbef60ee4, 0x6bcdf07a423aa96c},
-      {0xad4ab7112eb3929d, 0x86c16c98d2c953c7},
-      {0xd89d64d57a607744, 0xe871c7bf077ba8b8},
-      {0x87625f056c7c4a8b, 0x11471cd764ad4973},
-      {0xa93af6c6c79b5d2d, 0xd598e40d3dd89bd0},
-      {0xd389b47879823479, 0x4aff1d108d4ec2c4},
-      {0x843610cb4bf160cb, 0xcedf722a585139bb},
-      {0xa54394fe1eedb8fe, 0xc2974eb4ee658829},
-      {0xce947a3da6a9273e, 0x733d226229feea33},
-      {0x811ccc668829b887, 0x0806357d5a3f5260},
-      {0xa163ff802a3426a8, 0xca07c2dcb0cf26f8},
-      {0xc9bcff6034c13052, 0xfc89b393dd02f0b6},
-      {0xfc2c3f3841f17c67, 0xbbac2078d443ace3},
-      {0x9d9ba7832936edc0, 0xd54b944b84aa4c0e},
-      {0xc5029163f384a931, 0x0a9e795e65d4df12},
-      {0xf64335bcf065d37d, 0x4d4617b5ff4a16d6},
-      {0x99ea0196163fa42e, 0x504bced1bf8e4e46},
-      {0xc06481fb9bcf8d39, 0xe45ec2862f71e1d7},
-      {0xf07da27a82c37088, 0x5d767327bb4e5a4d},
-      {0x964e858c91ba2655, 0x3a6a07f8d510f870},
-      {0xbbe226efb628afea, 0x890489f70a55368c},
-      {0xeadab0aba3b2dbe5, 0x2b45ac74ccea842f},
-      {0x92c8ae6b464fc96f, 0x3b0b8bc90012929e},
-      {0xb77ada0617e3bbcb, 0x09ce6ebb40173745},
-      {0xe55990879ddcaabd, 0xcc420a6a101d0516},
-      {0x8f57fa54c2a9eab6, 0x9fa946824a12232e},
-      {0xb32df8e9f3546564, 0x47939822dc96abfa},
-      {0xdff9772470297ebd, 0x59787e2b93bc56f8},
-      {0x8bfbea76c619ef36, 0x57eb4edb3c55b65b},
-      {0xaefae51477a06b03, 0xede622920b6b23f2},
-      {0xdab99e59958885c4, 0xe95fab368e45ecee},
-      {0x88b402f7fd75539b, 0x11dbcb0218ebb415},
-      {0xaae103b5fcd2a881, 0xd652bdc29f26a11a},
-      {0xd59944a37c0752a2, 0x4be76d3346f04960},
-      {0x857fcae62d8493a5, 0x6f70a4400c562ddc},
-      {0xa6dfbd9fb8e5b88e, 0xcb4ccd500f6bb953},
-      {0xd097ad07a71f26b2, 0x7e2000a41346a7a8},
-      {0x825ecc24c873782f, 0x8ed400668c0c28c9},
-      {0xa2f67f2dfa90563b, 0x728900802f0f32fb},
-      {0xcbb41ef979346bca, 0x4f2b40a03ad2ffba},
-      {0xfea126b7d78186bc, 0xe2f610c84987bfa9},
-      {0x9f24b832e6b0f436, 0x0dd9ca7d2df4d7ca},
-      {0xc6ede63fa05d3143, 0x91503d1c79720dbc},
-      {0xf8a95fcf88747d94, 0x75a44c6397ce912b},
-      {0x9b69dbe1b548ce7c, 0xc986afbe3ee11abb},
-      {0xc24452da229b021b, 0xfbe85badce996169},
-      {0xf2d56790ab41c2a2, 0xfae27299423fb9c4},
-      {0x97c560ba6b0919a5, 0xdccd879fc967d41b},
-      {0xbdb6b8e905cb600f, 0x5400e987bbc1c921},
-      {0xed246723473e3813, 0x290123e9aab23b69},
-      {0x9436c0760c86e30b, 0xf9a0b6720aaf6522},
-      {0xb94470938fa89bce, 0xf808e40e8d5b3e6a},
-      {0xe7958cb87392c2c2, 0xb60b1d1230b20e05},
-      {0x90bd77f3483bb9b9, 0xb1c6f22b5e6f48c3},
-      {0xb4ecd5f01a4aa828, 0x1e38aeb6360b1af4},
-      {0xe2280b6c20dd5232, 0x25c6da63c38de1b1},
-      {0x8d590723948a535f, 0x579c487e5a38ad0f},
-      {0xb0af48ec79ace837, 0x2d835a9df0c6d852},
-      {0xdcdb1b2798182244, 0xf8e431456cf88e66},
-      {0x8a08f0f8bf0f156b, 0x1b8e9ecb641b5900},
-      {0xac8b2d36eed2dac5, 0xe272467e3d222f40},
-      {0xd7adf884aa879177, 0x5b0ed81dcc6abb10},
-      {0x86ccbb52ea94baea, 0x98e947129fc2b4ea},
-      {0xa87fea27a539e9a5, 0x3f2398d747b36225},
-      {0xd29fe4b18e88640e, 0x8eec7f0d19a03aae},
-      {0x83a3eeeef9153e89, 0x1953cf68300424ad},
-      {0xa48ceaaab75a8e2b, 0x5fa8c3423c052dd8},
-      {0xcdb02555653131b6, 0x3792f412cb06794e},
-      {0x808e17555f3ebf11, 0xe2bbd88bbee40bd1},
-      {0xa0b19d2ab70e6ed6, 0x5b6aceaeae9d0ec5},
-      {0xc8de047564d20a8b, 0xf245825a5a445276},
-      {0xfb158592be068d2e, 0xeed6e2f0f0d56713},
-      {0x9ced737bb6c4183d, 0x55464dd69685606c},
-      {0xc428d05aa4751e4c, 0xaa97e14c3c26b887},
-      {0xf53304714d9265df, 0xd53dd99f4b3066a9},
-      {0x993fe2c6d07b7fab, 0xe546a8038efe402a},
-      {0xbf8fdb78849a5f96, 0xde98520472bdd034},
-      {0xef73d256a5c0f77c, 0x963e66858f6d4441},
-      {0x95a8637627989aad, 0xdde7001379a44aa9},
-      {0xbb127c53b17ec159, 0x5560c018580d5d53},
-      {0xe9d71b689dde71af, 0xaab8f01e6e10b4a7},
-      {0x9226712162ab070d, 0xcab3961304ca70e9},
-      {0xb6b00d69bb55c8d1, 0x3d607b97c5fd0d23},
-      {0xe45c10c42a2b3b05, 0x8cb89a7db77c506b},
-      {0x8eb98a7a9a5b04e3, 0x77f3608e92adb243},
-      {0xb267ed1940f1c61c, 0x55f038b237591ed4},
-      {0xdf01e85f912e37a3, 0x6b6c46dec52f6689},
-      {0x8b61313bbabce2c6, 0x2323ac4b3b3da016},
-      {0xae397d8aa96c1b77, 0xabec975e0a0d081b},
-      {0xd9c7dced53c72255, 0x96e7bd358c904a22},
-      {0x881cea14545c7575, 0x7e50d64177da2e55},
-      {0xaa242499697392d2, 0xdde50bd1d5d0b9ea},
-      {0xd4ad2dbfc3d07787, 0x955e4ec64b44e865},
-      {0x84ec3c97da624ab4, 0xbd5af13bef0b113f},
-      {0xa6274bbdd0fadd61, 0xecb1ad8aeacdd58f},
-      {0xcfb11ead453994ba, 0x67de18eda5814af3},
-      {0x81ceb32c4b43fcf4, 0x80eacf948770ced8},
-      {0xa2425ff75e14fc31, 0xa1258379a94d028e},
-      {0xcad2f7f5359a3b3e, 0x096ee45813a04331},
-      {0xfd87b5f28300ca0d, 0x8bca9d6e188853fd},
-      {0x9e74d1b791e07e48, 0x775ea264cf55347e},
-      {0xc612062576589dda, 0x95364afe032a819e},
-      {0xf79687aed3eec551, 0x3a83ddbd83f52205},
-      {0x9abe14cd44753b52, 0xc4926a9672793543},
-      {0xc16d9a0095928a27, 0x75b7053c0f178294},
-      {0xf1c90080baf72cb1, 0x5324c68b12dd6339},
-      {0x971da05074da7bee, 0xd3f6fc16ebca5e04},
-      {0xbce5086492111aea, 0x88f4bb1ca6bcf585},
-      {0xec1e4a7db69561a5, 0x2b31e9e3d06c32e6},
-      {0x9392ee8e921d5d07, 0x3aff322e62439fd0},
-      {0xb877aa3236a4b449, 0x09befeb9fad487c3},
-      {0xe69594bec44de15b, 0x4c2ebe687989a9b4},
-      {0x901d7cf73ab0acd9, 0x0f9d37014bf60a11},
-      {0xb424dc35095cd80f, 0x538484c19ef38c95},
-      {0xe12e13424bb40e13, 0x2865a5f206b06fba},
-      {0x8cbccc096f5088cb, 0xf93f87b7442e45d4},
-      {0xafebff0bcb24aafe, 0xf78f69a51539d749},
-      {0xdbe6fecebdedd5be, 0xb573440e5a884d1c},
-      {0x89705f4136b4a597, 0x31680a88f8953031},
-      {0xabcc77118461cefc, 0xfdc20d2b36ba7c3e},
-      {0xd6bf94d5e57a42bc, 0x3d32907604691b4d},
-      {0x8637bd05af6c69b5, 0xa63f9a49c2c1b110},
-      {0xa7c5ac471b478423, 0x0fcf80dc33721d54},
-      {0xd1b71758e219652b, 0xd3c36113404ea4a9},
-      {0x83126e978d4fdf3b, 0x645a1cac083126ea},
-      {0xa3d70a3d70a3d70a, 0x3d70a3d70a3d70a4},
-      {0xcccccccccccccccc, 0xcccccccccccccccd},
-      {0x8000000000000000, 0x0000000000000000},
-      {0xa000000000000000, 0x0000000000000000},
-      {0xc800000000000000, 0x0000000000000000},
-      {0xfa00000000000000, 0x0000000000000000},
-      {0x9c40000000000000, 0x0000000000000000},
-      {0xc350000000000000, 0x0000000000000000},
-      {0xf424000000000000, 0x0000000000000000},
-      {0x9896800000000000, 0x0000000000000000},
-      {0xbebc200000000000, 0x0000000000000000},
-      {0xee6b280000000000, 0x0000000000000000},
-      {0x9502f90000000000, 0x0000000000000000},
-      {0xba43b74000000000, 0x0000000000000000},
-      {0xe8d4a51000000000, 0x0000000000000000},
-      {0x9184e72a00000000, 0x0000000000000000},
-      {0xb5e620f480000000, 0x0000000000000000},
-      {0xe35fa931a0000000, 0x0000000000000000},
-      {0x8e1bc9bf04000000, 0x0000000000000000},
-      {0xb1a2bc2ec5000000, 0x0000000000000000},
-      {0xde0b6b3a76400000, 0x0000000000000000},
-      {0x8ac7230489e80000, 0x0000000000000000},
-      {0xad78ebc5ac620000, 0x0000000000000000},
-      {0xd8d726b7177a8000, 0x0000000000000000},
-      {0x878678326eac9000, 0x0000000000000000},
-      {0xa968163f0a57b400, 0x0000000000000000},
-      {0xd3c21bcecceda100, 0x0000000000000000},
-      {0x84595161401484a0, 0x0000000000000000},
-      {0xa56fa5b99019a5c8, 0x0000000000000000},
-      {0xcecb8f27f4200f3a, 0x0000000000000000},
-      {0x813f3978f8940984, 0x4000000000000000},
-      {0xa18f07d736b90be5, 0x5000000000000000},
-      {0xc9f2c9cd04674ede, 0xa400000000000000},
-      {0xfc6f7c4045812296, 0x4d00000000000000},
-      {0x9dc5ada82b70b59d, 0xf020000000000000},
-      {0xc5371912364ce305, 0x6c28000000000000},
-      {0xf684df56c3e01bc6, 0xc732000000000000},
-      {0x9a130b963a6c115c, 0x3c7f400000000000},
-      {0xc097ce7bc90715b3, 0x4b9f100000000000},
-      {0xf0bdc21abb48db20, 0x1e86d40000000000},
-      {0x96769950b50d88f4, 0x1314448000000000},
-      {0xbc143fa4e250eb31, 0x17d955a000000000},
-      {0xeb194f8e1ae525fd, 0x5dcfab0800000000},
-      {0x92efd1b8d0cf37be, 0x5aa1cae500000000},
-      {0xb7abc627050305ad, 0xf14a3d9e40000000},
-      {0xe596b7b0c643c719, 0x6d9ccd05d0000000},
-      {0x8f7e32ce7bea5c6f, 0xe4820023a2000000},
-      {0xb35dbf821ae4f38b, 0xdda2802c8a800000},
-      {0xe0352f62a19e306e, 0xd50b2037ad200000},
-      {0x8c213d9da502de45, 0x4526f422cc340000},
-      {0xaf298d050e4395d6, 0x9670b12b7f410000},
-      {0xdaf3f04651d47b4c, 0x3c0cdd765f114000},
-      {0x88d8762bf324cd0f, 0xa5880a69fb6ac800},
-      {0xab0e93b6efee0053, 0x8eea0d047a457a00},
-      {0xd5d238a4abe98068, 0x72a4904598d6d880},
-      {0x85a36366eb71f041, 0x47a6da2b7f864750},
-      {0xa70c3c40a64e6c51, 0x999090b65f67d924},
-      {0xd0cf4b50cfe20765, 0xfff4b4e3f741cf6d},
-      {0x82818f1281ed449f, 0xbff8f10e7a8921a4},
-      {0xa321f2d7226895c7, 0xaff72d52192b6a0d},
-      {0xcbea6f8ceb02bb39, 0x9bf4f8a69f764490},
-      {0xfee50b7025c36a08, 0x02f236d04753d5b4},
-      {0x9f4f2726179a2245, 0x01d762422c946590},
-      {0xc722f0ef9d80aad6, 0x424d3ad2b7b97ef5},
-      {0xf8ebad2b84e0d58b, 0xd2e0898765a7deb2},
-      {0x9b934c3b330c8577, 0x63cc55f49f88eb2f},
-      {0xc2781f49ffcfa6d5, 0x3cbf6b71c76b25fb},
-      {0xf316271c7fc3908a, 0x8bef464e3945ef7a},
-      {0x97edd871cfda3a56, 0x97758bf0e3cbb5ac},
-      {0xbde94e8e43d0c8ec, 0x3d52eeed1cbea317},
-      {0xed63a231d4c4fb27, 0x4ca7aaa863ee4bdd},
-      {0x945e455f24fb1cf8, 0x8fe8caa93e74ef6a},
-      {0xb975d6b6ee39e436, 0xb3e2fd538e122b44},
-      {0xe7d34c64a9c85d44, 0x60dbbca87196b616},
-      {0x90e40fbeea1d3a4a, 0xbc8955e946fe31cd},
-      {0xb51d13aea4a488dd, 0x6babab6398bdbe41},
-      {0xe264589a4dcdab14, 0xc696963c7eed2dd1},
-      {0x8d7eb76070a08aec, 0xfc1e1de5cf543ca2},
-      {0xb0de65388cc8ada8, 0x3b25a55f43294bcb},
-      {0xdd15fe86affad912, 0x49ef0eb713f39ebe},
-      {0x8a2dbf142dfcc7ab, 0x6e3569326c784337},
-      {0xacb92ed9397bf996, 0x49c2c37f07965404},
-      {0xd7e77a8f87daf7fb, 0xdc33745ec97be906},
-      {0x86f0ac99b4e8dafd, 0x69a028bb3ded71a3},
-      {0xa8acd7c0222311bc, 0xc40832ea0d68ce0c},
-      {0xd2d80db02aabd62b, 0xf50a3fa490c30190},
-      {0x83c7088e1aab65db, 0x792667c6da79e0fa},
-      {0xa4b8cab1a1563f52, 0x577001b891185938},
-      {0xcde6fd5e09abcf26, 0xed4c0226b55e6f86},
-      {0x80b05e5ac60b6178, 0x544f8158315b05b4},
-      {0xa0dc75f1778e39d6, 0x696361ae3db1c721},
-      {0xc913936dd571c84c, 0x03bc3a19cd1e38e9},
-      {0xfb5878494ace3a5f, 0x04ab48a04065c723},
-      {0x9d174b2dcec0e47b, 0x62eb0d64283f9c76},
-      {0xc45d1df942711d9a, 0x3ba5d0bd324f8394},
-      {0xf5746577930d6500, 0xca8f44ec7ee36479},
-      {0x9968bf6abbe85f20, 0x7e998b13cf4e1ecb},
-      {0xbfc2ef456ae276e8, 0x9e3fedd8c321a67e},
-      {0xefb3ab16c59b14a2, 0xc5cfe94ef3ea101e},
-      {0x95d04aee3b80ece5, 0xbba1f1d158724a12},
-      {0xbb445da9ca61281f, 0x2a8a6e45ae8edc97},
-      {0xea1575143cf97226, 0xf52d09d71a3293bd},
-      {0x924d692ca61be758, 0x593c2626705f9c56},
-      {0xb6e0c377cfa2e12e, 0x6f8b2fb00c77836c},
-      {0xe498f455c38b997a, 0x0b6dfb9c0f956447},
-      {0x8edf98b59a373fec, 0x4724bd4189bd5eac},
-      {0xb2977ee300c50fe7, 0x58edec91ec2cb657},
-      {0xdf3d5e9bc0f653e1, 0x2f2967b66737e3ed},
-      {0x8b865b215899f46c, 0xbd79e0d20082ee74},
-      {0xae67f1e9aec07187, 0xecd8590680a3aa11},
-      {0xda01ee641a708de9, 0xe80e6f4820cc9495},
-      {0x884134fe908658b2, 0x3109058d147fdcdd},
-      {0xaa51823e34a7eede, 0xbd4b46f0599fd415},
-      {0xd4e5e2cdc1d1ea96, 0x6c9e18ac7007c91a},
-      {0x850fadc09923329e, 0x03e2cf6bc604ddb0},
-      {0xa6539930bf6bff45, 0x84db8346b786151c},
-      {0xcfe87f7cef46ff16, 0xe612641865679a63},
-      {0x81f14fae158c5f6e, 0x4fcb7e8f3f60c07e},
-      {0xa26da3999aef7749, 0xe3be5e330f38f09d},
-      {0xcb090c8001ab551c, 0x5cadf5bfd3072cc5},
-      {0xfdcb4fa002162a63, 0x73d9732fc7c8f7f6},
-      {0x9e9f11c4014dda7e, 0x2867e7fddcdd9afa},
-      {0xc646d63501a1511d, 0xb281e1fd541501b8},
-      {0xf7d88bc24209a565, 0x1f225a7ca91a4226},
-      {0x9ae757596946075f, 0x3375788de9b06958},
-      {0xc1a12d2fc3978937, 0x0052d6b1641c83ae},
-      {0xf209787bb47d6b84, 0xc0678c5dbd23a49a},
-      {0x9745eb4d50ce6332, 0xf840b7ba963646e0},
-      {0xbd176620a501fbff, 0xb650e5a93bc3d898},
-      {0xec5d3fa8ce427aff, 0xa3e51f138ab4cebe},
-      {0x93ba47c980e98cdf, 0xc66f336c36b10137},
-      {0xb8a8d9bbe123f017, 0xb80b0047445d4184},
-      {0xe6d3102ad96cec1d, 0xa60dc059157491e5},
-      {0x9043ea1ac7e41392, 0x87c89837ad68db2f},
-      {0xb454e4a179dd1877, 0x29babe4598c311fb},
-      {0xe16a1dc9d8545e94, 0xf4296dd6fef3d67a},
-      {0x8ce2529e2734bb1d, 0x1899e4a65f58660c},
-      {0xb01ae745b101e9e4, 0x5ec05dcff72e7f8f},
-      {0xdc21a1171d42645d, 0x76707543f4fa1f73},
-      {0x899504ae72497eba, 0x6a06494a791c53a8},
-      {0xabfa45da0edbde69, 0x0487db9d17636892},
-      {0xd6f8d7509292d603, 0x45a9d2845d3c42b6},
-      {0x865b86925b9bc5c2, 0x0b8a2392ba45a9b2},
-      {0xa7f26836f282b732, 0x8e6cac7768d7141e},
-      {0xd1ef0244af2364ff, 0x3207d795430cd926},
-      {0x8335616aed761f1f, 0x7f44e6bd49e807b8},
-      {0xa402b9c5a8d3a6e7, 0x5f16206c9c6209a6},
-      {0xcd036837130890a1, 0x36dba887c37a8c0f},
-      {0x802221226be55a64, 0xc2494954da2c9789},
-      {0xa02aa96b06deb0fd, 0xf2db9baa10b7bd6c},
-      {0xc83553c5c8965d3d, 0x6f92829494e5acc7},
-      {0xfa42a8b73abbf48c, 0xcb772339ba1f17f9},
-      {0x9c69a97284b578d7, 0xff2a760414536efb},
-      {0xc38413cf25e2d70d, 0xfef5138519684aba},
-      {0xf46518c2ef5b8cd1, 0x7eb258665fc25d69},
-      {0x98bf2f79d5993802, 0xef2f773ffbd97a61},
-      {0xbeeefb584aff8603, 0xaafb550ffacfd8fa},
-      {0xeeaaba2e5dbf6784, 0x95ba2a53f983cf38},
-      {0x952ab45cfa97a0b2, 0xdd945a747bf26183},
-      {0xba756174393d88df, 0x94f971119aeef9e4},
-      {0xe912b9d1478ceb17, 0x7a37cd5601aab85d},
-      {0x91abb422ccb812ee, 0xac62e055c10ab33a},
-      {0xb616a12b7fe617aa, 0x577b986b314d6009},
-      {0xe39c49765fdf9d94, 0xed5a7e85fda0b80b},
-      {0x8e41ade9fbebc27d, 0x14588f13be847307},
-      {0xb1d219647ae6b31c, 0x596eb2d8ae258fc8},
-      {0xde469fbd99a05fe3, 0x6fca5f8ed9aef3bb},
-      {0x8aec23d680043bee, 0x25de7bb9480d5854},
-      {0xada72ccc20054ae9, 0xaf561aa79a10ae6a},
-      {0xd910f7ff28069da4, 0x1b2ba1518094da04},
-      {0x87aa9aff79042286, 0x90fb44d2f05d0842},
-      {0xa99541bf57452b28, 0x353a1607ac744a53},
-      {0xd3fa922f2d1675f2, 0x42889b8997915ce8},
-      {0x847c9b5d7c2e09b7, 0x69956135febada11},
-      {0xa59bc234db398c25, 0x43fab9837e699095},
-      {0xcf02b2c21207ef2e, 0x94f967e45e03f4bb},
-      {0x8161afb94b44f57d, 0x1d1be0eebac278f5},
-      {0xa1ba1ba79e1632dc, 0x6462d92a69731732},
-      {0xca28a291859bbf93, 0x7d7b8f7503cfdcfe},
-      {0xfcb2cb35e702af78, 0x5cda735244c3d43e},
-      {0x9defbf01b061adab, 0x3a0888136afa64a7},
-      {0xc56baec21c7a1916, 0x088aaa1845b8fdd0},
-      {0xf6c69a72a3989f5b, 0x8aad549e57273d45},
-      {0x9a3c2087a63f6399, 0x36ac54e2f678864b},
-      {0xc0cb28a98fcf3c7f, 0x84576a1bb416a7dd},
-      {0xf0fdf2d3f3c30b9f, 0x656d44a2a11c51d5},
-      {0x969eb7c47859e743, 0x9f644ae5a4b1b325},
-      {0xbc4665b596706114, 0x873d5d9f0dde1fee},
-      {0xeb57ff22fc0c7959, 0xa90cb506d155a7ea},
-      {0x9316ff75dd87cbd8, 0x09a7f12442d588f2},
-      {0xb7dcbf5354e9bece, 0x0c11ed6d538aeb2f},
-      {0xe5d3ef282a242e81, 0x8f1668c8a86da5fa},
-      {0x8fa475791a569d10, 0xf96e017d694487bc},
-      {0xb38d92d760ec4455, 0x37c981dcc395a9ac},
-      {0xe070f78d3927556a, 0x85bbe253f47b1417},
-      {0x8c469ab843b89562, 0x93956d7478ccec8e},
-      {0xaf58416654a6babb, 0x387ac8d1970027b2},
-      {0xdb2e51bfe9d0696a, 0x06997b05fcc0319e},
-      {0x88fcf317f22241e2, 0x441fece3bdf81f03},
-      {0xab3c2fddeeaad25a, 0xd527e81cad7626c3},
-      {0xd60b3bd56a5586f1, 0x8a71e223d8d3b074},
-      {0x85c7056562757456, 0xf6872d5667844e49},
-      {0xa738c6bebb12d16c, 0xb428f8ac016561db},
-      {0xd106f86e69d785c7, 0xe13336d701beba52},
-      {0x82a45b450226b39c, 0xecc0024661173473},
-      {0xa34d721642b06084, 0x27f002d7f95d0190},
-      {0xcc20ce9bd35c78a5, 0x31ec038df7b441f4},
-      {0xff290242c83396ce, 0x7e67047175a15271},
-      {0x9f79a169bd203e41, 0x0f0062c6e984d386},
-      {0xc75809c42c684dd1, 0x52c07b78a3e60868},
-      {0xf92e0c3537826145, 0xa7709a56ccdf8a82},
-      {0x9bbcc7a142b17ccb, 0x88a66076400bb691},
-      {0xc2abf989935ddbfe, 0x6acff893d00ea435},
-      {0xf356f7ebf83552fe, 0x0583f6b8c4124d43},
-      {0x98165af37b2153de, 0xc3727a337a8b704a},
-      {0xbe1bf1b059e9a8d6, 0x744f18c0592e4c5c},
-      {0xeda2ee1c7064130c, 0x1162def06f79df73},
-      {0x9485d4d1c63e8be7, 0x8addcb5645ac2ba8},
-      {0xb9a74a0637ce2ee1, 0x6d953e2bd7173692},
-      {0xe8111c87c5c1ba99, 0xc8fa8db6ccdd0437},
-      {0x910ab1d4db9914a0, 0x1d9c9892400a22a2},
-      {0xb54d5e4a127f59c8, 0x2503beb6d00cab4b},
-      {0xe2a0b5dc971f303a, 0x2e44ae64840fd61d},
-      {0x8da471a9de737e24, 0x5ceaecfed289e5d2},
-      {0xb10d8e1456105dad, 0x7425a83e872c5f47},
-      {0xdd50f1996b947518, 0xd12f124e28f77719},
-      {0x8a5296ffe33cc92f, 0x82bd6b70d99aaa6f},
-      {0xace73cbfdc0bfb7b, 0x636cc64d1001550b},
-      {0xd8210befd30efa5a, 0x3c47f7e05401aa4e},
-      {0x8714a775e3e95c78, 0x65acfaec34810a71},
-      {0xa8d9d1535ce3b396, 0x7f1839a741a14d0d},
-      {0xd31045a8341ca07c, 0x1ede48111209a050},
-      {0x83ea2b892091e44d, 0x934aed0aab460432},
-      {0xa4e4b66b68b65d60, 0xf81da84d5617853f},
-      {0xce1de40642e3f4b9, 0x36251260ab9d668e},
-      {0x80d2ae83e9ce78f3, 0xc1d72b7c6b426019},
-      {0xa1075a24e4421730, 0xb24cf65b8612f81f},
-      {0xc94930ae1d529cfc, 0xdee033f26797b627},
-      {0xfb9b7cd9a4a7443c, 0x169840ef017da3b1},
-      {0x9d412e0806e88aa5, 0x8e1f289560ee864e},
-      {0xc491798a08a2ad4e, 0xf1a6f2bab92a27e2},
-      {0xf5b5d7ec8acb58a2, 0xae10af696774b1db},
-      {0x9991a6f3d6bf1765, 0xacca6da1e0a8ef29},
-      {0xbff610b0cc6edd3f, 0x17fd090a58d32af3},
-      {0xeff394dcff8a948e, 0xddfc4b4cef07f5b0},
-      {0x95f83d0a1fb69cd9, 0x4abdaf101564f98e},
-      {0xbb764c4ca7a4440f, 0x9d6d1ad41abe37f1},
-      {0xea53df5fd18d5513, 0x84c86189216dc5ed},
-      {0x92746b9be2f8552c, 0x32fd3cf5b4e49bb4},
-      {0xb7118682dbb66a77, 0x3fbc8c33221dc2a1},
-      {0xe4d5e82392a40515, 0x0fabaf3feaa5334a},
-      {0x8f05b1163ba6832d, 0x29cb4d87f2a7400e},
-      {0xb2c71d5bca9023f8, 0x743e20e9ef511012},
-      {0xdf78e4b2bd342cf6, 0x914da9246b255416},
-      {0x8bab8eefb6409c1a, 0x1ad089b6c2f7548e},
-      {0xae9672aba3d0c320, 0xa184ac2473b529b1},
-      {0xda3c0f568cc4f3e8, 0xc9e5d72d90a2741e},
-      {0x8865899617fb1871, 0x7e2fa67c7a658892},
-      {0xaa7eebfb9df9de8d, 0xddbb901b98feeab7},
-      {0xd51ea6fa85785631, 0x552a74227f3ea565},
-      {0x8533285c936b35de, 0xd53a88958f87275f},
-      {0xa67ff273b8460356, 0x8a892abaf368f137},
-      {0xd01fef10a657842c, 0x2d2b7569b0432d85},
-      {0x8213f56a67f6b29b, 0x9c3b29620e29fc73},
-      {0xa298f2c501f45f42, 0x8349f3ba91b47b8f},
-      {0xcb3f2f7642717713, 0x241c70a936219a73},
-      {0xfe0efb53d30dd4d7, 0xed238cd383aa0110},
-      {0x9ec95d1463e8a506, 0xf4363804324a40aa},
-      {0xc67bb4597ce2ce48, 0xb143c6053edcd0d5},
-      {0xf81aa16fdc1b81da, 0xdd94b7868e94050a},
-      {0x9b10a4e5e9913128, 0xca7cf2b4191c8326},
-      {0xc1d4ce1f63f57d72, 0xfd1c2f611f63a3f0},
-      {0xf24a01a73cf2dccf, 0xbc633b39673c8cec},
-      {0x976e41088617ca01, 0xd5be0503e085d813},
-      {0xbd49d14aa79dbc82, 0x4b2d8644d8a74e18},
-      {0xec9c459d51852ba2, 0xddf8e7d60ed1219e},
-      {0x93e1ab8252f33b45, 0xcabb90e5c942b503},
-      {0xb8da1662e7b00a17, 0x3d6a751f3b936243},
-      {0xe7109bfba19c0c9d, 0x0cc512670a783ad4},
-      {0x906a617d450187e2, 0x27fb2b80668b24c5},
-      {0xb484f9dc9641e9da, 0xb1f9f660802dedf6},
-      {0xe1a63853bbd26451, 0x5e7873f8a0396973},
-      {0x8d07e33455637eb2, 0xdb0b487b6423e1e8},
-      {0xb049dc016abc5e5f, 0x91ce1a9a3d2cda62},
-      {0xdc5c5301c56b75f7, 0x7641a140cc7810fb},
-      {0x89b9b3e11b6329ba, 0xa9e904c87fcb0a9d},
-      {0xac2820d9623bf429, 0x546345fa9fbdcd44},
-      {0xd732290fbacaf133, 0xa97c177947ad4095},
-      {0x867f59a9d4bed6c0, 0x49ed8eabcccc485d},
-      {0xa81f301449ee8c70, 0x5c68f256bfff5a74},
-      {0xd226fc195c6a2f8c, 0x73832eec6fff3111},
-      {0x83585d8fd9c25db7, 0xc831fd53c5ff7eab},
-      {0xa42e74f3d032f525, 0xba3e7ca8b77f5e55},
-      {0xcd3a1230c43fb26f, 0x28ce1bd2e55f35eb},
-      {0x80444b5e7aa7cf85, 0x7980d163cf5b81b3},
-      {0xa0555e361951c366, 0xd7e105bcc332621f},
-      {0xc86ab5c39fa63440, 0x8dd9472bf3fefaa7},
-      {0xfa856334878fc150, 0xb14f98f6f0feb951},
-      {0x9c935e00d4b9d8d2, 0x6ed1bf9a569f33d3},
-      {0xc3b8358109e84f07, 0x0a862f80ec4700c8},
-      {0xf4a642e14c6262c8, 0xcd27bb612758c0fa},
-      {0x98e7e9cccfbd7dbd, 0x8038d51cb897789c},
-      {0xbf21e44003acdd2c, 0xe0470a63e6bd56c3},
-      {0xeeea5d5004981478, 0x1858ccfce06cac74},
-      {0x95527a5202df0ccb, 0x0f37801e0c43ebc8},
-      {0xbaa718e68396cffd, 0xd30560258f54e6ba},
-      {0xe950df20247c83fd, 0x47c6b82ef32a2069},
-      {0x91d28b7416cdd27e, 0x4cdc331d57fa5441},
-      {0xb6472e511c81471d, 0xe0133fe4adf8e952},
-      {0xe3d8f9e563a198e5, 0x58180fddd97723a6},
-      {0x8e679c2f5e44ff8f, 0x570f09eaa7ea7648},
-      {0xb201833b35d63f73, 0x2cd2cc6551e513da},
-      {0xde81e40a034bcf4f, 0xf8077f7ea65e58d1},
-      {0x8b112e86420f6191, 0xfb04afaf27faf782},
-      {0xadd57a27d29339f6, 0x79c5db9af1f9b563},
-      {0xd94ad8b1c7380874, 0x18375281ae7822bc},
-      {0x87cec76f1c830548, 0x8f2293910d0b15b5},
-      {0xa9c2794ae3a3c69a, 0xb2eb3875504ddb22},
-      {0xd433179d9c8cb841, 0x5fa60692a46151eb},
-      {0x849feec281d7f328, 0xdbc7c41ba6bcd333},
-      {0xa5c7ea73224deff3, 0x12b9b522906c0800},
-      {0xcf39e50feae16bef, 0xd768226b34870a00},
-      {0x81842f29f2cce375, 0xe6a1158300d46640},
-      {0xa1e53af46f801c53, 0x60495ae3c1097fd0},
-      {0xca5e89b18b602368, 0x385bb19cb14bdfc4},
-      {0xfcf62c1dee382c42, 0x46729e03dd9ed7b5},
-      {0x9e19db92b4e31ba9, 0x6c07a2c26a8346d1},
-      {0xc5a05277621be293, 0xc7098b7305241885},
-      { 0xf70867153aa2db38,
-        0xb8cbee4fc66d1ea7 }
-#else
-      {0xff77b1fcbebcdc4f, 0x25e8e89c13bb0f7b},
-      {0xce5d73ff402d98e3, 0xfb0a3d212dc81290},
-      {0xa6b34ad8c9dfc06f, 0xf42faa48c0ea481f},
-      {0x86a8d39ef77164bc, 0xae5dff9c02033198},
-      {0xd98ddaee19068c76, 0x3badd624dd9b0958},
-      {0xafbd2350644eeacf, 0xe5d1929ef90898fb},
-      {0x8df5efabc5979c8f, 0xca8d3ffa1ef463c2},
-      {0xe55990879ddcaabd, 0xcc420a6a101d0516},
-      {0xb94470938fa89bce, 0xf808e40e8d5b3e6a},
-      {0x95a8637627989aad, 0xdde7001379a44aa9},
-      {0xf1c90080baf72cb1, 0x5324c68b12dd6339},
-      {0xc350000000000000, 0x0000000000000000},
-      {0x9dc5ada82b70b59d, 0xf020000000000000},
-      {0xfee50b7025c36a08, 0x02f236d04753d5b4},
-      {0xcde6fd5e09abcf26, 0xed4c0226b55e6f86},
-      {0xa6539930bf6bff45, 0x84db8346b786151c},
-      {0x865b86925b9bc5c2, 0x0b8a2392ba45a9b2},
-      {0xd910f7ff28069da4, 0x1b2ba1518094da04},
-      {0xaf58416654a6babb, 0x387ac8d1970027b2},
-      {0x8da471a9de737e24, 0x5ceaecfed289e5d2},
-      {0xe4d5e82392a40515, 0x0fabaf3feaa5334a},
-      {0xb8da1662e7b00a17, 0x3d6a751f3b936243},
-      { 0x95527a5202df0ccb,
-        0x0f37801e0c43ebc8 }
-#endif
-    };
-
-#if FMT_USE_FULL_CACHE_DRAGONBOX
-    return pow10_significands[k - float_info<double>::min_k];
-#else
-    static constexpr const uint64_t powers_of_5_64[] = {
-        0x0000000000000001, 0x0000000000000005, 0x0000000000000019,
-        0x000000000000007d, 0x0000000000000271, 0x0000000000000c35,
-        0x0000000000003d09, 0x000000000001312d, 0x000000000005f5e1,
-        0x00000000001dcd65, 0x00000000009502f9, 0x0000000002e90edd,
-        0x000000000e8d4a51, 0x0000000048c27395, 0x000000016bcc41e9,
-        0x000000071afd498d, 0x0000002386f26fc1, 0x000000b1a2bc2ec5,
-        0x000003782dace9d9, 0x00001158e460913d, 0x000056bc75e2d631,
-        0x0001b1ae4d6e2ef5, 0x000878678326eac9, 0x002a5a058fc295ed,
-        0x00d3c21bcecceda1, 0x0422ca8b0a00a425, 0x14adf4b7320334b9};
-
-    static constexpr const uint32_t pow10_recovery_errors[] = {
-        0x50001400, 0x54044100, 0x54014555, 0x55954415, 0x54115555, 0x00000001,
-        0x50000000, 0x00104000, 0x54010004, 0x05004001, 0x55555544, 0x41545555,
-        0x54040551, 0x15445545, 0x51555514, 0x10000015, 0x00101100, 0x01100015,
-        0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x04450514, 0x45414110,
-        0x55555145, 0x50544050, 0x15040155, 0x11054140, 0x50111514, 0x11451454,
-        0x00400541, 0x00000000, 0x55555450, 0x10056551, 0x10054011, 0x55551014,
-        0x69514555, 0x05151109, 0x00155555};
-
-    static const int compression_ratio = 27;
-
-    // Compute base index.
-    int cache_index = (k - float_info<double>::min_k) / compression_ratio;
-    int kb = cache_index * compression_ratio + float_info<double>::min_k;
-    int offset = k - kb;
-
-    // Get base cache.
-    uint128_wrapper base_cache = pow10_significands[cache_index];
-    if (offset == 0) return base_cache;
-
-    // Compute the required amount of bit-shift.
-    int alpha = floor_log2_pow10(kb + offset) - floor_log2_pow10(kb) - offset;
-    FMT_ASSERT(alpha > 0 && alpha < 64, "shifting error detected");
-
-    // Try to recover the real cache.
-    uint64_t pow5 = powers_of_5_64[offset];
-    uint128_wrapper recovered_cache = umul128(base_cache.high(), pow5);
-    uint128_wrapper middle_low =
-        umul128(base_cache.low() - (kb < 0 ? 1u : 0u), pow5);
-
-    recovered_cache += middle_low.high();
-
-    uint64_t high_to_middle = recovered_cache.high() << (64 - alpha);
-    uint64_t middle_to_low = recovered_cache.low() << (64 - alpha);
-
-    recovered_cache =
-        uint128_wrapper{(recovered_cache.low() >> alpha) | high_to_middle,
-                        ((middle_low.low() >> alpha) | middle_to_low)};
-
-    if (kb < 0) recovered_cache += 1;
-
-    // Get error.
-    int error_idx = (k - float_info<double>::min_k) / 16;
-    uint32_t error = (pow10_recovery_errors[error_idx] >>
-                      ((k - float_info<double>::min_k) % 16) * 2) &
-                     0x3;
-
-    // Add the error back.
-    FMT_ASSERT(recovered_cache.low() + error >= recovered_cache.low(), "");
-    return {recovered_cache.high(), recovered_cache.low() + error};
-#endif
-  }
-
-  static carrier_uint compute_mul(carrier_uint u,
-                                  const cache_entry_type& cache) FMT_NOEXCEPT {
-    return umul192_upper64(u, cache);
-  }
-
-  static uint32_t compute_delta(cache_entry_type const& cache,
-                                int beta_minus_1) FMT_NOEXCEPT {
-    return static_cast<uint32_t>(cache.high() >> (64 - 1 - beta_minus_1));
-  }
-
-  static bool compute_mul_parity(carrier_uint two_f,
-                                 const cache_entry_type& cache,
-                                 int beta_minus_1) FMT_NOEXCEPT {
-    FMT_ASSERT(beta_minus_1 >= 1, "");
-    FMT_ASSERT(beta_minus_1 < 64, "");
-
-    return ((umul192_middle64(two_f, cache) >> (64 - beta_minus_1)) & 1) != 0;
-  }
-
-  static carrier_uint compute_left_endpoint_for_shorter_interval_case(
-      const cache_entry_type& cache, int beta_minus_1) FMT_NOEXCEPT {
-    return (cache.high() -
-            (cache.high() >> (float_info<double>::significand_bits + 2))) >>
-           (64 - float_info<double>::significand_bits - 1 - beta_minus_1);
-  }
-
-  static carrier_uint compute_right_endpoint_for_shorter_interval_case(
-      const cache_entry_type& cache, int beta_minus_1) FMT_NOEXCEPT {
-    return (cache.high() +
-            (cache.high() >> (float_info<double>::significand_bits + 1))) >>
-           (64 - float_info<double>::significand_bits - 1 - beta_minus_1);
-  }
-
-  static carrier_uint compute_round_up_for_shorter_interval_case(
-      const cache_entry_type& cache, int beta_minus_1) FMT_NOEXCEPT {
-    return ((cache.high() >>
-             (64 - float_info<double>::significand_bits - 2 - beta_minus_1)) +
-            1) /
-           2;
-  }
-};
-
-// Various integer checks
-template <class T>
-bool is_left_endpoint_integer_shorter_interval(int exponent) FMT_NOEXCEPT {
-  return exponent >=
-             float_info<
-                 T>::case_shorter_interval_left_endpoint_lower_threshold &&
-         exponent <=
-             float_info<T>::case_shorter_interval_left_endpoint_upper_threshold;
-}
-template <class T>
-bool is_endpoint_integer(typename float_info<T>::carrier_uint two_f,
-                         int exponent, int minus_k) FMT_NOEXCEPT {
-  if (exponent < float_info<T>::case_fc_pm_half_lower_threshold) return false;
-  // For k >= 0.
-  if (exponent <= float_info<T>::case_fc_pm_half_upper_threshold) return true;
-  // For k < 0.
-  if (exponent > float_info<T>::divisibility_check_by_5_threshold) return false;
-  return divisible_by_power_of_5(two_f, minus_k);
-}
-
-template <class T>
-bool is_center_integer(typename float_info<T>::carrier_uint two_f, int exponent,
-                       int minus_k) FMT_NOEXCEPT {
-  // Exponent for 5 is negative.
-  if (exponent > float_info<T>::divisibility_check_by_5_threshold) return false;
-  if (exponent > float_info<T>::case_fc_upper_threshold)
-    return divisible_by_power_of_5(two_f, minus_k);
-  // Both exponents are nonnegative.
-  if (exponent >= float_info<T>::case_fc_lower_threshold) return true;
-  // Exponent for 2 is negative.
-  return divisible_by_power_of_2(two_f, minus_k - exponent + 1);
-}
-
-// Remove trailing zeros from n and return the number of zeros removed (float)
-FMT_INLINE int remove_trailing_zeros(uint32_t& n) FMT_NOEXCEPT {
-#ifdef FMT_BUILTIN_CTZ
-  int t = FMT_BUILTIN_CTZ(n);
-#else
-  int t = ctz(n);
-#endif
-  if (t > float_info<float>::max_trailing_zeros)
-    t = float_info<float>::max_trailing_zeros;
-
-  const uint32_t mod_inv1 = 0xcccccccd;
-  const uint32_t max_quotient1 = 0x33333333;
-  const uint32_t mod_inv2 = 0xc28f5c29;
-  const uint32_t max_quotient2 = 0x0a3d70a3;
-
-  int s = 0;
-  for (; s < t - 1; s += 2) {
-    if (n * mod_inv2 > max_quotient2) break;
-    n *= mod_inv2;
-  }
-  if (s < t && n * mod_inv1 <= max_quotient1) {
-    n *= mod_inv1;
-    ++s;
-  }
-  n >>= s;
-  return s;
-}
-
-// Removes trailing zeros and returns the number of zeros removed (double)
-FMT_INLINE int remove_trailing_zeros(uint64_t& n) FMT_NOEXCEPT {
-#ifdef FMT_BUILTIN_CTZLL
-  int t = FMT_BUILTIN_CTZLL(n);
-#else
-  int t = ctzll(n);
-#endif
-  if (t > float_info<double>::max_trailing_zeros)
-    t = float_info<double>::max_trailing_zeros;
-  // Divide by 10^8 and reduce to 32-bits
-  // Since ret_value.significand <= (2^64 - 1) / 1000 < 10^17,
-  // both of the quotient and the r should fit in 32-bits
-
-  const uint32_t mod_inv1 = 0xcccccccd;
-  const uint32_t max_quotient1 = 0x33333333;
-  const uint64_t mod_inv8 = 0xc767074b22e90e21;
-  const uint64_t max_quotient8 = 0x00002af31dc46118;
-
-  // If the number is divisible by 1'0000'0000, work with the quotient
-  if (t >= 8) {
-    auto quotient_candidate = n * mod_inv8;
-
-    if (quotient_candidate <= max_quotient8) {
-      auto quotient = static_cast<uint32_t>(quotient_candidate >> 8);
-
-      int s = 8;
-      for (; s < t; ++s) {
-        if (quotient * mod_inv1 > max_quotient1) break;
-        quotient *= mod_inv1;
-      }
-      quotient >>= (s - 8);
-      n = quotient;
-      return s;
-    }
-  }
-
-  // Otherwise, work with the remainder
-  auto quotient = static_cast<uint32_t>(n / 100000000);
-  auto remainder = static_cast<uint32_t>(n - 100000000 * quotient);
-
-  if (t == 0 || remainder * mod_inv1 > max_quotient1) {
-    return 0;
-  }
-  remainder *= mod_inv1;
-
-  if (t == 1 || remainder * mod_inv1 > max_quotient1) {
-    n = (remainder >> 1) + quotient * 10000000ull;
-    return 1;
-  }
-  remainder *= mod_inv1;
-
-  if (t == 2 || remainder * mod_inv1 > max_quotient1) {
-    n = (remainder >> 2) + quotient * 1000000ull;
-    return 2;
-  }
-  remainder *= mod_inv1;
-
-  if (t == 3 || remainder * mod_inv1 > max_quotient1) {
-    n = (remainder >> 3) + quotient * 100000ull;
-    return 3;
-  }
-  remainder *= mod_inv1;
-
-  if (t == 4 || remainder * mod_inv1 > max_quotient1) {
-    n = (remainder >> 4) + quotient * 10000ull;
-    return 4;
-  }
-  remainder *= mod_inv1;
-
-  if (t == 5 || remainder * mod_inv1 > max_quotient1) {
-    n = (remainder >> 5) + quotient * 1000ull;
-    return 5;
-  }
-  remainder *= mod_inv1;
-
-  if (t == 6 || remainder * mod_inv1 > max_quotient1) {
-    n = (remainder >> 6) + quotient * 100ull;
-    return 6;
-  }
-  remainder *= mod_inv1;
-
-  n = (remainder >> 7) + quotient * 10ull;
-  return 7;
-}
-
-// The main algorithm for shorter interval case
-template <class T>
-FMT_INLINE decimal_fp<T> shorter_interval_case(int exponent) FMT_NOEXCEPT {
-  decimal_fp<T> ret_value;
-  // Compute k and beta
-  const int minus_k = floor_log10_pow2_minus_log10_4_over_3(exponent);
-  const int beta_minus_1 = exponent + floor_log2_pow10(-minus_k);
-
-  // Compute xi and zi
-  using cache_entry_type = typename cache_accessor<T>::cache_entry_type;
-  const cache_entry_type cache = cache_accessor<T>::get_cached_power(-minus_k);
-
-  auto xi = cache_accessor<T>::compute_left_endpoint_for_shorter_interval_case(
-      cache, beta_minus_1);
-  auto zi = cache_accessor<T>::compute_right_endpoint_for_shorter_interval_case(
-      cache, beta_minus_1);
-
-  // If the left endpoint is not an integer, increase it
-  if (!is_left_endpoint_integer_shorter_interval<T>(exponent)) ++xi;
-
-  // Try bigger divisor
-  ret_value.significand = zi / 10;
-
-  // If succeed, remove trailing zeros if necessary and return
-  if (ret_value.significand * 10 >= xi) {
-    ret_value.exponent = minus_k + 1;
-    ret_value.exponent += remove_trailing_zeros(ret_value.significand);
-    return ret_value;
-  }
-
-  // Otherwise, compute the round-up of y
-  ret_value.significand =
-      cache_accessor<T>::compute_round_up_for_shorter_interval_case(
-          cache, beta_minus_1);
-  ret_value.exponent = minus_k;
-
-  // When tie occurs, choose one of them according to the rule
-  if (exponent >= float_info<T>::shorter_interval_tie_lower_threshold &&
-      exponent <= float_info<T>::shorter_interval_tie_upper_threshold) {
-    ret_value.significand = ret_value.significand % 2 == 0
-                                ? ret_value.significand
-                                : ret_value.significand - 1;
-  } else if (ret_value.significand < xi) {
-    ++ret_value.significand;
-  }
-  return ret_value;
-}
-
-template <typename T> decimal_fp<T> to_decimal(T x) FMT_NOEXCEPT {
-  // Step 1: integer promotion & Schubfach multiplier calculation.
-
-  using carrier_uint = typename float_info<T>::carrier_uint;
-  using cache_entry_type = typename cache_accessor<T>::cache_entry_type;
-  auto br = bit_cast<carrier_uint>(x);
-
-  // Extract significand bits and exponent bits.
-  const carrier_uint significand_mask =
-      (static_cast<carrier_uint>(1) << float_info<T>::significand_bits) - 1;
-  carrier_uint significand = (br & significand_mask);
-  int exponent = static_cast<int>((br & exponent_mask<T>()) >>
-                                  float_info<T>::significand_bits);
-
-  if (exponent != 0) {  // Check if normal.
-    exponent += float_info<T>::exponent_bias - float_info<T>::significand_bits;
-
-    // Shorter interval case; proceed like Schubfach.
-    if (significand == 0) return shorter_interval_case<T>(exponent);
-
-    significand |=
-        (static_cast<carrier_uint>(1) << float_info<T>::significand_bits);
-  } else {
-    // Subnormal case; the interval is always regular.
-    if (significand == 0) return {0, 0};
-    exponent = float_info<T>::min_exponent - float_info<T>::significand_bits;
-  }
-
-  const bool include_left_endpoint = (significand % 2 == 0);
-  const bool include_right_endpoint = include_left_endpoint;
-
-  // Compute k and beta.
-  const int minus_k = floor_log10_pow2(exponent) - float_info<T>::kappa;
-  const cache_entry_type cache = cache_accessor<T>::get_cached_power(-minus_k);
-  const int beta_minus_1 = exponent + floor_log2_pow10(-minus_k);
-
-  // Compute zi and deltai
-  // 10^kappa <= deltai < 10^(kappa + 1)
-  const uint32_t deltai = cache_accessor<T>::compute_delta(cache, beta_minus_1);
-  const carrier_uint two_fc = significand << 1;
-  const carrier_uint two_fr = two_fc | 1;
-  const carrier_uint zi =
-      cache_accessor<T>::compute_mul(two_fr << beta_minus_1, cache);
-
-  // Step 2: Try larger divisor; remove trailing zeros if necessary
-
-  // Using an upper bound on zi, we might be able to optimize the division
-  // better than the compiler; we are computing zi / big_divisor here
-  decimal_fp<T> ret_value;
-  ret_value.significand = divide_by_10_to_kappa_plus_1(zi);
-  uint32_t r = static_cast<uint32_t>(zi - float_info<T>::big_divisor *
-                                              ret_value.significand);
-
-  if (r > deltai) {
-    goto small_divisor_case_label;
-  } else if (r < deltai) {
-    // Exclude the right endpoint if necessary
-    if (r == 0 && !include_right_endpoint &&
-        is_endpoint_integer<T>(two_fr, exponent, minus_k)) {
-      --ret_value.significand;
-      r = float_info<T>::big_divisor;
-      goto small_divisor_case_label;
-    }
-  } else {
-    // r == deltai; compare fractional parts
-    // Check conditions in the order different from the paper
-    // to take advantage of short-circuiting
-    const carrier_uint two_fl = two_fc - 1;
-    if ((!include_left_endpoint ||
-         !is_endpoint_integer<T>(two_fl, exponent, minus_k)) &&
-        !cache_accessor<T>::compute_mul_parity(two_fl, cache, beta_minus_1)) {
-      goto small_divisor_case_label;
-    }
-  }
-  ret_value.exponent = minus_k + float_info<T>::kappa + 1;
-
-  // We may need to remove trailing zeros
-  ret_value.exponent += remove_trailing_zeros(ret_value.significand);
-  return ret_value;
-
-  // Step 3: Find the significand with the smaller divisor
-
-small_divisor_case_label:
-  ret_value.significand *= 10;
-  ret_value.exponent = minus_k + float_info<T>::kappa;
-
-  const uint32_t mask = (1u << float_info<T>::kappa) - 1;
-  auto dist = r - (deltai / 2) + (float_info<T>::small_divisor / 2);
-
-  // Is dist divisible by 2^kappa?
-  if ((dist & mask) == 0) {
-    const bool approx_y_parity =
-        ((dist ^ (float_info<T>::small_divisor / 2)) & 1) != 0;
-    dist >>= float_info<T>::kappa;
-
-    // Is dist divisible by 5^kappa?
-    if (check_divisibility_and_divide_by_pow5<float_info<T>::kappa>(dist)) {
-      ret_value.significand += dist;
-
-      // Check z^(f) >= epsilon^(f)
-      // We have either yi == zi - epsiloni or yi == (zi - epsiloni) - 1,
-      // where yi == zi - epsiloni if and only if z^(f) >= epsilon^(f)
-      // Since there are only 2 possibilities, we only need to care about the
-      // parity. Also, zi and r should have the same parity since the divisor
-      // is an even number
-      if (cache_accessor<T>::compute_mul_parity(two_fc, cache, beta_minus_1) !=
-          approx_y_parity) {
-        --ret_value.significand;
-      } else {
-        // If z^(f) >= epsilon^(f), we might have a tie
-        // when z^(f) == epsilon^(f), or equivalently, when y is an integer
-        if (is_center_integer<T>(two_fc, exponent, minus_k)) {
-          ret_value.significand = ret_value.significand % 2 == 0
-                                      ? ret_value.significand
-                                      : ret_value.significand - 1;
-        }
-      }
-    }
-    // Is dist not divisible by 5^kappa?
-    else {
-      ret_value.significand += dist;
-    }
-  }
-  // Is dist not divisible by 2^kappa?
-  else {
-    // Since we know dist is small, we might be able to optimize the division
-    // better than the compiler; we are computing dist / small_divisor here
-    ret_value.significand +=
-        small_division_by_pow10<float_info<T>::kappa>(dist);
-  }
-  return ret_value;
-}
-}  // namespace dragonbox
-
-// Formats a floating-point number using a variation of the Fixed-Precision
-// Positive Floating-Point Printout ((FPP)^2) algorithm by Steele & White:
-// https://fmt.dev/papers/p372-steele.pdf.
-FMT_CONSTEXPR20 inline void format_dragon(fp value, bool is_predecessor_closer,
-                                          int num_digits, buffer<char>& buf,
-                                          int& exp10) {
-  bigint numerator;    // 2 * R in (FPP)^2.
-  bigint denominator;  // 2 * S in (FPP)^2.
-  // lower and upper are differences between value and corresponding boundaries.
-  bigint lower;             // (M^- in (FPP)^2).
-  bigint upper_store;       // upper's value if different from lower.
-  bigint* upper = nullptr;  // (M^+ in (FPP)^2).
-  // Shift numerator and denominator by an extra bit or two (if lower boundary
-  // is closer) to make lower and upper integers. This eliminates multiplication
-  // by 2 during later computations.
-  int shift = is_predecessor_closer ? 2 : 1;
-  uint64_t significand = value.f << shift;
-  if (value.e >= 0) {
-    numerator.assign(significand);
-    numerator <<= value.e;
-    lower.assign(1);
-    lower <<= value.e;
-    if (shift != 1) {
-      upper_store.assign(1);
-      upper_store <<= value.e + 1;
-      upper = &upper_store;
-    }
-    denominator.assign_pow10(exp10);
-    denominator <<= shift;
-  } else if (exp10 < 0) {
-    numerator.assign_pow10(-exp10);
-    lower.assign(numerator);
-    if (shift != 1) {
-      upper_store.assign(numerator);
-      upper_store <<= 1;
-      upper = &upper_store;
-    }
-    numerator *= significand;
-    denominator.assign(1);
-    denominator <<= shift - value.e;
-  } else {
-    numerator.assign(significand);
-    denominator.assign_pow10(exp10);
-    denominator <<= shift - value.e;
-    lower.assign(1);
-    if (shift != 1) {
-      upper_store.assign(1ULL << 1);
-      upper = &upper_store;
-    }
-  }
-  // Invariant: value == (numerator / denominator) * pow(10, exp10).
-  if (num_digits < 0) {
-    // Generate the shortest representation.
-    if (!upper) upper = &lower;
-    bool even = (value.f & 1) == 0;
-    num_digits = 0;
-    char* data = buf.data();
-    for (;;) {
-      int digit = numerator.divmod_assign(denominator);
-      bool low = compare(numerator, lower) - even < 0;  // numerator <[=] lower.
-      // numerator + upper >[=] pow10:
-      bool high = add_compare(numerator, *upper, denominator) + even > 0;
-      data[num_digits++] = static_cast<char>('0' + digit);
-      if (low || high) {
-        if (!low) {
-          ++data[num_digits - 1];
-        } else if (high) {
-          int result = add_compare(numerator, numerator, denominator);
-          // Round half to even.
-          if (result > 0 || (result == 0 && (digit % 2) != 0))
-            ++data[num_digits - 1];
-        }
-        buf.try_resize(to_unsigned(num_digits));
-        exp10 -= num_digits - 1;
-        return;
-      }
-      numerator *= 10;
-      lower *= 10;
-      if (upper != &lower) *upper *= 10;
-    }
-  }
-  // Generate the given number of digits.
-  exp10 -= num_digits - 1;
-  if (num_digits == 0) {
-    denominator *= 10;
-    auto digit = add_compare(numerator, numerator, denominator) > 0 ? '1' : '0';
-    buf.push_back(digit);
-    return;
-  }
-  buf.try_resize(to_unsigned(num_digits));
-  for (int i = 0; i < num_digits - 1; ++i) {
-    int digit = numerator.divmod_assign(denominator);
-    buf[i] = static_cast<char>('0' + digit);
-    numerator *= 10;
-  }
-  int digit = numerator.divmod_assign(denominator);
-  auto result = add_compare(numerator, numerator, denominator);
-  if (result > 0 || (result == 0 && (digit % 2) != 0)) {
-    if (digit == 9) {
-      const auto overflow = '0' + 10;
-      buf[num_digits - 1] = overflow;
-      // Propagate the carry.
-      for (int i = num_digits - 1; i > 0 && buf[i] == overflow; --i) {
-        buf[i] = '0';
-        ++buf[i - 1];
-      }
-      if (buf[0] == overflow) {
-        buf[0] = '1';
-        ++exp10;
-      }
-      return;
-    }
-    ++digit;
-  }
-  buf[num_digits - 1] = static_cast<char>('0' + digit);
-}
-
-template <typename Float>
-FMT_HEADER_ONLY_CONSTEXPR20 int format_float(Float value, int precision,
-                                             float_specs specs,
-                                             buffer<char>& buf) {
-  // float is passed as double to reduce the number of instantiations.
-  static_assert(!std::is_same<Float, float>::value, "");
-  FMT_ASSERT(value >= 0, "value is negative");
-
-  const bool fixed = specs.format == float_format::fixed;
-  if (value <= 0) {  // <= instead of == to silence a warning.
-    if (precision <= 0 || !fixed) {
-      buf.push_back('0');
-      return 0;
-    }
-    buf.try_resize(to_unsigned(precision));
-    fill_n(buf.data(), precision, '0');
-    return -precision;
-  }
-
-  if (specs.fallback) return snprintf_float(value, precision, specs, buf);
-
-  if (!is_constant_evaluated() && precision < 0) {
-    // Use Dragonbox for the shortest format.
-    if (specs.binary32) {
-      auto dec = dragonbox::to_decimal(static_cast<float>(value));
-      write<char>(buffer_appender<char>(buf), dec.significand);
-      return dec.exponent;
-    }
-    auto dec = dragonbox::to_decimal(static_cast<double>(value));
-    write<char>(buffer_appender<char>(buf), dec.significand);
-    return dec.exponent;
-  }
-
-  int exp = 0;
-  bool use_dragon = true;
-  if (is_fast_float<Float>()) {
-    // Use Grisu + Dragon4 for the given precision:
-    // https://www.cs.tufts.edu/~nr/cs257/archive/florian-loitsch/printf.pdf.
-    const int min_exp = -60;  // alpha in Grisu.
-    int cached_exp10 = 0;     // K in Grisu.
-    fp normalized = normalize(fp(value));
-    const auto cached_pow = get_cached_power(
-        min_exp - (normalized.e + fp::num_significand_bits), cached_exp10);
-    normalized = normalized * cached_pow;
-    gen_digits_handler handler{buf.data(), 0, precision, -cached_exp10, fixed};
-    if (grisu_gen_digits(normalized, 1, exp, handler) != digits::error &&
-        !is_constant_evaluated()) {
-      exp += handler.exp10;
-      buf.try_resize(to_unsigned(handler.size));
-      use_dragon = false;
-    } else {
-      exp += handler.size - cached_exp10 - 1;
-      precision = handler.precision;
-    }
-  }
-  if (use_dragon) {
-    auto f = fp();
-    bool is_predecessor_closer =
-        specs.binary32 ? f.assign(static_cast<float>(value)) : f.assign(value);
-    // Limit precision to the maximum possible number of significant digits in
-    // an IEEE754 double because we don't need to generate zeros.
-    const int max_double_digits = 767;
-    if (precision > max_double_digits) precision = max_double_digits;
-    format_dragon(f, is_predecessor_closer, precision, buf, exp);
-  }
-  if (!fixed && !specs.showpoint) {
-    // Remove trailing zeros.
-    auto num_digits = buf.size();
-    while (num_digits > 0 && buf[num_digits - 1] == '0') {
-      --num_digits;
-      ++exp;
-    }
-    buf.try_resize(num_digits);
-  }
-  return exp;
-}
-
-template <typename T>
-int snprintf_float(T value, int precision, float_specs specs,
-                   buffer<char>& buf) {
-  // Buffer capacity must be non-zero, otherwise MSVC's vsnprintf_s will fail.
-  FMT_ASSERT(buf.capacity() > buf.size(), "empty buffer");
-  static_assert(!std::is_same<T, float>::value, "");
-
-  // Subtract 1 to account for the difference in precision since we use %e for
-  // both general and exponent format.
-  if (specs.format == float_format::general ||
-      specs.format == float_format::exp)
-    precision = (precision >= 0 ? precision : 6) - 1;
-
-  // Build the format string.
-  enum { max_format_size = 7 };  // The longest format is "%#.*Le".
-  char format[max_format_size];
-  char* format_ptr = format;
-  *format_ptr++ = '%';
-  if (specs.showpoint && specs.format == float_format::hex) *format_ptr++ = '#';
-  if (precision >= 0) {
-    *format_ptr++ = '.';
-    *format_ptr++ = '*';
-  }
-  if (std::is_same<T, long double>()) *format_ptr++ = 'L';
-  *format_ptr++ = specs.format != float_format::hex
-                      ? (specs.format == float_format::fixed ? 'f' : 'e')
-                      : (specs.upper ? 'A' : 'a');
-  *format_ptr = '\0';
-
-  // Format using snprintf.
-  auto offset = buf.size();
-  for (;;) {
-    auto begin = buf.data() + offset;
-    auto capacity = buf.capacity() - offset;
-#ifdef FMT_FUZZ
-    if (precision > 100000)
-      throw std::runtime_error(
-          "fuzz mode - avoid large allocation inside snprintf");
-#endif
-    // Suppress the warning about a nonliteral format string.
-    // Cannot use auto because of a bug in MinGW (#1532).
-    int (*snprintf_ptr)(char*, size_t, const char*, ...) = FMT_SNPRINTF;
-    int result = precision >= 0
-                     ? snprintf_ptr(begin, capacity, format, precision, value)
-                     : snprintf_ptr(begin, capacity, format, value);
-    if (result < 0) {
-      // The buffer will grow exponentially.
-      buf.try_reserve(buf.capacity() + 1);
-      continue;
-    }
-    auto size = to_unsigned(result);
-    // Size equal to capacity means that the last character was truncated.
-    if (size >= capacity) {
-      buf.try_reserve(size + offset + 1);  // Add 1 for the terminating '\0'.
-      continue;
-    }
-    auto is_digit = [](char c) { return c >= '0' && c <= '9'; };
-    if (specs.format == float_format::fixed) {
-      if (precision == 0) {
-        buf.try_resize(size);
-        return 0;
-      }
-      // Find and remove the decimal point.
-      auto end = begin + size, p = end;
-      do {
-        --p;
-      } while (is_digit(*p));
-      int fraction_size = static_cast<int>(end - p - 1);
-      std::memmove(p, p + 1, to_unsigned(fraction_size));
-      buf.try_resize(size - 1);
-      return -fraction_size;
-    }
-    if (specs.format == float_format::hex) {
-      buf.try_resize(size + offset);
-      return 0;
-    }
-    // Find and parse the exponent.
-    auto end = begin + size, exp_pos = end;
-    do {
-      --exp_pos;
-    } while (*exp_pos != 'e');
-    char sign = exp_pos[1];
-    FMT_ASSERT(sign == '+' || sign == '-', "");
-    int exp = 0;
-    auto p = exp_pos + 2;  // Skip 'e' and sign.
-    do {
-      FMT_ASSERT(is_digit(*p), "");
-      exp = exp * 10 + (*p++ - '0');
-    } while (p != end);
-    if (sign == '-') exp = -exp;
-    int fraction_size = 0;
-    if (exp_pos != begin + 1) {
-      // Remove trailing zeros.
-      auto fraction_end = exp_pos - 1;
-      while (*fraction_end == '0') --fraction_end;
-      // Move the fractional part left to get rid of the decimal point.
-      fraction_size = static_cast<int>(fraction_end - begin - 1);
-      std::memmove(begin + 1, begin + 2, to_unsigned(fraction_size));
-    }
-    buf.try_resize(to_unsigned(fraction_size) + offset + 1);
-    return exp - fraction_size;
-  }
-}
-}  // namespace detail
-
-template <> struct formatter<detail::bigint> {
-  FMT_CONSTEXPR format_parse_context::iterator parse(
-      format_parse_context& ctx) {
-    return ctx.begin();
-  }
-
-  format_context::iterator format(const detail::bigint& n,
-                                  format_context& ctx) {
-    auto out = ctx.out();
-    bool first = true;
-    for (auto i = n.bigits_.size(); i > 0; --i) {
-      auto value = n.bigits_[i - 1u];
-      if (first) {
-        out = format_to(out, FMT_STRING("{:x}"), value);
-        first = false;
-        continue;
-      }
-      out = format_to(out, FMT_STRING("{:08x}"), value);
-    }
-    if (n.exp_ > 0)
-      out = format_to(out, FMT_STRING("p{}"),
-                      n.exp_ * detail::bigint::bigit_bits);
-    return out;
-  }
-};
-
-FMT_FUNC detail::utf8_to_utf16::utf8_to_utf16(string_view s) {
-  for_each_codepoint(s, [this](uint32_t cp, string_view) {
-    if (cp == invalid_code_point) FMT_THROW(std::runtime_error("invalid utf8"));
-    if (cp <= 0xFFFF) {
-      buffer_.push_back(static_cast<wchar_t>(cp));
-    } else {
-      cp -= 0x10000;
-      buffer_.push_back(static_cast<wchar_t>(0xD800 + (cp >> 10)));
-      buffer_.push_back(static_cast<wchar_t>(0xDC00 + (cp & 0x3FF)));
-    }
-    return true;
-  });
-  buffer_.push_back(0);
-}
-
-FMT_FUNC void format_system_error(detail::buffer<char>& out, int error_code,
-                                  const char* message) FMT_NOEXCEPT {
-  FMT_TRY {
-    auto ec = std::error_code(error_code, std::generic_category());
-    write(std::back_inserter(out), std::system_error(ec, message).what());
-    return;
-  }
-  FMT_CATCH(...) {}
-  format_error_code(out, error_code, message);
-}
-
-FMT_FUNC void report_system_error(int error_code,
-                                  const char* message) FMT_NOEXCEPT {
-  report_error(format_system_error, error_code, message);
-}
-
-// DEPRECATED!
-// This function is defined here and not inline for ABI compatiblity.
-FMT_FUNC void detail::error_handler::on_error(const char* message) {
-  throw_format_error(message);
-}
-
-FMT_FUNC std::string vformat(string_view fmt, format_args args) {
-  // Don't optimize the "{}" case to keep the binary size small and because it
-  // can be better optimized in fmt::format anyway.
-  auto buffer = memory_buffer();
-  detail::vformat_to(buffer, fmt, args);
-  return to_string(buffer);
-}
-
-#ifdef _WIN32
-namespace detail {
-using dword = conditional_t<sizeof(long) == 4, unsigned long, unsigned>;
-extern "C" __declspec(dllimport) int __stdcall WriteConsoleW(  //
-    void*, const void*, dword, dword*, void*);
-}  // namespace detail
-#endif
-
-namespace detail {
-FMT_FUNC void print(std::FILE* f, string_view text) {
-#ifdef _WIN32
-  auto fd = _fileno(f);
-  if (_isatty(fd)) {
-    detail::utf8_to_utf16 u16(string_view(text.data(), text.size()));
-    auto written = detail::dword();
-    if (detail::WriteConsoleW(reinterpret_cast<void*>(_get_osfhandle(fd)),
-                              u16.c_str(), static_cast<uint32_t>(u16.size()),
-                              &written, nullptr)) {
-      return;
-    }
-    // Fallback to fwrite on failure. It can happen if the output has been
-    // redirected to NUL.
-  }
-#endif
-  detail::fwrite_fully(text.data(), 1, text.size(), f);
-}
-}  // namespace detail
-
-FMT_FUNC void vprint(std::FILE* f, string_view format_str, format_args args) {
-  memory_buffer buffer;
-  detail::vformat_to(buffer, format_str, args);
-  detail::print(f, {buffer.data(), buffer.size()});
-}
-
-#ifdef _WIN32
-// Print assuming legacy (non-Unicode) encoding.
-FMT_FUNC void detail::vprint_mojibake(std::FILE* f, string_view format_str,
-                                      format_args args) {
-  memory_buffer buffer;
-  detail::vformat_to(buffer, format_str,
-                     basic_format_args<buffer_context<char>>(args));
-  fwrite_fully(buffer.data(), 1, buffer.size(), f);
-}
-#endif
-
-FMT_FUNC void vprint(string_view format_str, format_args args) {
-  vprint(stdout, format_str, args);
-}
-
-FMT_END_NAMESPACE
-
-#endif  // FMT_FORMAT_INL_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/format.h b/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/format.h
deleted file mode 100644
index ee69651..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/format.h
+++ /dev/null
@@ -1,3104 +0,0 @@
-/*
- Formatting library for C++
-
- Copyright (c) 2012 - present, Victor Zverovich
-
- Permission is hereby granted, free of charge, to any person obtaining
- a copy of this software and associated documentation files (the
- "Software"), to deal in the Software without restriction, including
- without limitation the rights to use, copy, modify, merge, publish,
- distribute, sublicense, and/or sell copies of the Software, and to
- permit persons to whom the Software is furnished to do so, subject to
- the following conditions:
-
- The above copyright notice and this permission notice shall be
- included in all copies or substantial portions of the Software.
-
- THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
- EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
- MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
- NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE
- LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION
- OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION
- WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
-
- --- Optional exception to the license ---
-
- As an exception, if, as a result of your compiling your source code, portions
- of this Software are embedded into a machine-executable object form of such
- source code, you may redistribute such embedded portions in such object form
- without including the above copyright and permission notices.
- */
-
-#ifndef FMT_FORMAT_H_
-#define FMT_FORMAT_H_
-
-#include <cmath>         // std::signbit
-#include <cstdint>       // uint32_t
-#include <limits>        // std::numeric_limits
-#include <memory>        // std::uninitialized_copy
-#include <stdexcept>     // std::runtime_error
-#include <system_error>  // std::system_error
-#include <utility>       // std::swap
-
-#ifdef __cpp_lib_bit_cast
-#  include <bit>  // std::bitcast
-#endif
-
-#include "core.h"
-
-#if FMT_GCC_VERSION
-#  define FMT_GCC_VISIBILITY_HIDDEN __attribute__((visibility("hidden")))
-#else
-#  define FMT_GCC_VISIBILITY_HIDDEN
-#endif
-
-#ifdef __NVCC__
-#  define FMT_CUDA_VERSION (__CUDACC_VER_MAJOR__ * 100 + __CUDACC_VER_MINOR__)
-#else
-#  define FMT_CUDA_VERSION 0
-#endif
-
-#ifdef __has_builtin
-#  define FMT_HAS_BUILTIN(x) __has_builtin(x)
-#else
-#  define FMT_HAS_BUILTIN(x) 0
-#endif
-
-#if FMT_GCC_VERSION || FMT_CLANG_VERSION
-#  define FMT_NOINLINE __attribute__((noinline))
-#else
-#  define FMT_NOINLINE
-#endif
-
-#if FMT_MSC_VER
-#  define FMT_MSC_DEFAULT = default
-#else
-#  define FMT_MSC_DEFAULT
-#endif
-
-#ifndef FMT_THROW
-#  if FMT_EXCEPTIONS
-#    if FMT_MSC_VER || FMT_NVCC
-FMT_BEGIN_NAMESPACE
-namespace detail {
-template <typename Exception> inline void do_throw(const Exception& x) {
-  // Silence unreachable code warnings in MSVC and NVCC because these
-  // are nearly impossible to fix in a generic code.
-  volatile bool b = true;
-  if (b) throw x;
-}
-}  // namespace detail
-FMT_END_NAMESPACE
-#      define FMT_THROW(x) detail::do_throw(x)
-#    else
-#      define FMT_THROW(x) throw x
-#    endif
-#  else
-#    define FMT_THROW(x)               \
-      do {                             \
-        FMT_ASSERT(false, (x).what()); \
-      } while (false)
-#  endif
-#endif
-
-#if FMT_EXCEPTIONS
-#  define FMT_TRY try
-#  define FMT_CATCH(x) catch (x)
-#else
-#  define FMT_TRY if (true)
-#  define FMT_CATCH(x) if (false)
-#endif
-
-#ifndef FMT_MAYBE_UNUSED
-#  if FMT_HAS_CPP17_ATTRIBUTE(maybe_unused)
-#    define FMT_MAYBE_UNUSED [[maybe_unused]]
-#  else
-#    define FMT_MAYBE_UNUSED
-#  endif
-#endif
-
-// Workaround broken [[deprecated]] in the Intel, PGI and NVCC compilers.
-#if FMT_ICC_VERSION || defined(__PGI) || FMT_NVCC
-#  define FMT_DEPRECATED_ALIAS
-#else
-#  define FMT_DEPRECATED_ALIAS FMT_DEPRECATED
-#endif
-
-#ifndef FMT_USE_USER_DEFINED_LITERALS
-// EDG based compilers (Intel, NVIDIA, Elbrus, etc), GCC and MSVC support UDLs.
-#  if (FMT_HAS_FEATURE(cxx_user_literals) || FMT_GCC_VERSION >= 407 || \
-       FMT_MSC_VER >= 1900) &&                                         \
-      (!defined(__EDG_VERSION__) || __EDG_VERSION__ >= /* UDL feature */ 480)
-#    define FMT_USE_USER_DEFINED_LITERALS 1
-#  else
-#    define FMT_USE_USER_DEFINED_LITERALS 0
-#  endif
-#endif
-
-// Defining FMT_REDUCE_INT_INSTANTIATIONS to 1, will reduce the number of
-// integer formatter template instantiations to just one by only using the
-// largest integer type. This results in a reduction in binary size but will
-// cause a decrease in integer formatting performance.
-#if !defined(FMT_REDUCE_INT_INSTANTIATIONS)
-#  define FMT_REDUCE_INT_INSTANTIATIONS 0
-#endif
-
-// __builtin_clz is broken in clang with Microsoft CodeGen:
-// https://github.com/fmtlib/fmt/issues/519.
-#if !FMT_MSC_VER
-#  if FMT_HAS_BUILTIN(__builtin_clz) || FMT_GCC_VERSION || FMT_ICC_VERSION
-#    define FMT_BUILTIN_CLZ(n) __builtin_clz(n)
-#  endif
-#  if FMT_HAS_BUILTIN(__builtin_clzll) || FMT_GCC_VERSION || FMT_ICC_VERSION
-#    define FMT_BUILTIN_CLZLL(n) __builtin_clzll(n)
-#  endif
-#endif
-
-// __builtin_ctz is broken in Intel Compiler Classic on Windows:
-// https://github.com/fmtlib/fmt/issues/2510.
-#ifndef __ICL
-#  if FMT_HAS_BUILTIN(__builtin_ctz) || FMT_GCC_VERSION || FMT_ICC_VERSION
-#    define FMT_BUILTIN_CTZ(n) __builtin_ctz(n)
-#  endif
-#  if FMT_HAS_BUILTIN(__builtin_ctzll) || FMT_GCC_VERSION || FMT_ICC_VERSION
-#    define FMT_BUILTIN_CTZLL(n) __builtin_ctzll(n)
-#  endif
-#endif
-
-#if FMT_MSC_VER
-#  include <intrin.h>  // _BitScanReverse[64], _BitScanForward[64], _umul128
-#endif
-
-// Some compilers masquerade as both MSVC and GCC-likes or otherwise support
-// __builtin_clz and __builtin_clzll, so only define FMT_BUILTIN_CLZ using the
-// MSVC intrinsics if the clz and clzll builtins are not available.
-#if FMT_MSC_VER && !defined(FMT_BUILTIN_CLZLL) && !defined(FMT_BUILTIN_CTZLL)
-FMT_BEGIN_NAMESPACE
-namespace detail {
-// Avoid Clang with Microsoft CodeGen's -Wunknown-pragmas warning.
-#  if !defined(__clang__)
-#    pragma intrinsic(_BitScanForward)
-#    pragma intrinsic(_BitScanReverse)
-#    if defined(_WIN64)
-#      pragma intrinsic(_BitScanForward64)
-#      pragma intrinsic(_BitScanReverse64)
-#    endif
-#  endif
-
-inline auto clz(uint32_t x) -> int {
-  unsigned long r = 0;
-  _BitScanReverse(&r, x);
-  FMT_ASSERT(x != 0, "");
-  // Static analysis complains about using uninitialized data
-  // "r", but the only way that can happen is if "x" is 0,
-  // which the callers guarantee to not happen.
-  FMT_MSC_WARNING(suppress : 6102)
-  return 31 ^ static_cast<int>(r);
-}
-#  define FMT_BUILTIN_CLZ(n) detail::clz(n)
-
-inline auto clzll(uint64_t x) -> int {
-  unsigned long r = 0;
-#  ifdef _WIN64
-  _BitScanReverse64(&r, x);
-#  else
-  // Scan the high 32 bits.
-  if (_BitScanReverse(&r, static_cast<uint32_t>(x >> 32))) return 63 ^ (r + 32);
-  // Scan the low 32 bits.
-  _BitScanReverse(&r, static_cast<uint32_t>(x));
-#  endif
-  FMT_ASSERT(x != 0, "");
-  FMT_MSC_WARNING(suppress : 6102)  // Suppress a bogus static analysis warning.
-  return 63 ^ static_cast<int>(r);
-}
-#  define FMT_BUILTIN_CLZLL(n) detail::clzll(n)
-
-inline auto ctz(uint32_t x) -> int {
-  unsigned long r = 0;
-  _BitScanForward(&r, x);
-  FMT_ASSERT(x != 0, "");
-  FMT_MSC_WARNING(suppress : 6102)  // Suppress a bogus static analysis warning.
-  return static_cast<int>(r);
-}
-#  define FMT_BUILTIN_CTZ(n) detail::ctz(n)
-
-inline auto ctzll(uint64_t x) -> int {
-  unsigned long r = 0;
-  FMT_ASSERT(x != 0, "");
-  FMT_MSC_WARNING(suppress : 6102)  // Suppress a bogus static analysis warning.
-#  ifdef _WIN64
-  _BitScanForward64(&r, x);
-#  else
-  // Scan the low 32 bits.
-  if (_BitScanForward(&r, static_cast<uint32_t>(x))) return static_cast<int>(r);
-  // Scan the high 32 bits.
-  _BitScanForward(&r, static_cast<uint32_t>(x >> 32));
-  r += 32;
-#  endif
-  return static_cast<int>(r);
-}
-#  define FMT_BUILTIN_CTZLL(n) detail::ctzll(n)
-}  // namespace detail
-FMT_END_NAMESPACE
-#endif
-
-#ifdef FMT_HEADER_ONLY
-#  define FMT_HEADER_ONLY_CONSTEXPR20 FMT_CONSTEXPR20
-#else
-#  define FMT_HEADER_ONLY_CONSTEXPR20
-#endif
-
-FMT_BEGIN_NAMESPACE
-namespace detail {
-
-template <typename Streambuf> class formatbuf : public Streambuf {
- private:
-  using char_type = typename Streambuf::char_type;
-  using streamsize = decltype(std::declval<Streambuf>().sputn(nullptr, 0));
-  using int_type = typename Streambuf::int_type;
-  using traits_type = typename Streambuf::traits_type;
-
-  buffer<char_type>& buffer_;
-
- public:
-  explicit formatbuf(buffer<char_type>& buf) : buffer_(buf) {}
-
- protected:
-  // The put area is always empty. This makes the implementation simpler and has
-  // the advantage that the streambuf and the buffer are always in sync and
-  // sputc never writes into uninitialized memory. A disadvantage is that each
-  // call to sputc always results in a (virtual) call to overflow. There is no
-  // disadvantage here for sputn since this always results in a call to xsputn.
-
-  auto overflow(int_type ch) -> int_type override {
-    if (!traits_type::eq_int_type(ch, traits_type::eof()))
-      buffer_.push_back(static_cast<char_type>(ch));
-    return ch;
-  }
-
-  auto xsputn(const char_type* s, streamsize count) -> streamsize override {
-    buffer_.append(s, s + count);
-    return count;
-  }
-};
-
-// Implementation of std::bit_cast for pre-C++20.
-template <typename To, typename From>
-FMT_CONSTEXPR20 auto bit_cast(const From& from) -> To {
-  static_assert(sizeof(To) == sizeof(From), "size mismatch");
-#ifdef __cpp_lib_bit_cast
-  if (is_constant_evaluated()) return std::bit_cast<To>(from);
-#endif
-  auto to = To();
-  std::memcpy(&to, &from, sizeof(to));
-  return to;
-}
-
-inline auto is_big_endian() -> bool {
-#ifdef _WIN32
-  return false;
-#elif defined(__BIG_ENDIAN__)
-  return true;
-#elif defined(__BYTE_ORDER__) && defined(__ORDER_BIG_ENDIAN__)
-  return __BYTE_ORDER__ == __ORDER_BIG_ENDIAN__;
-#else
-  struct bytes {
-    char data[sizeof(int)];
-  };
-  return bit_cast<bytes>(1).data[0] == 0;
-#endif
-}
-
-// A fallback implementation of uintptr_t for systems that lack it.
-struct fallback_uintptr {
-  unsigned char value[sizeof(void*)];
-
-  fallback_uintptr() = default;
-  explicit fallback_uintptr(const void* p) {
-    *this = bit_cast<fallback_uintptr>(p);
-    if (const_check(is_big_endian())) {
-      for (size_t i = 0, j = sizeof(void*) - 1; i < j; ++i, --j)
-        std::swap(value[i], value[j]);
-    }
-  }
-};
-#ifdef UINTPTR_MAX
-using uintptr_t = ::uintptr_t;
-inline auto to_uintptr(const void* p) -> uintptr_t {
-  return bit_cast<uintptr_t>(p);
-}
-#else
-using uintptr_t = fallback_uintptr;
-inline auto to_uintptr(const void* p) -> fallback_uintptr {
-  return fallback_uintptr(p);
-}
-#endif
-
-// Returns the largest possible value for type T. Same as
-// std::numeric_limits<T>::max() but shorter and not affected by the max macro.
-template <typename T> constexpr auto max_value() -> T {
-  return (std::numeric_limits<T>::max)();
-}
-template <typename T> constexpr auto num_bits() -> int {
-  return std::numeric_limits<T>::digits;
-}
-// std::numeric_limits<T>::digits may return 0 for 128-bit ints.
-template <> constexpr auto num_bits<int128_t>() -> int { return 128; }
-template <> constexpr auto num_bits<uint128_t>() -> int { return 128; }
-template <> constexpr auto num_bits<fallback_uintptr>() -> int {
-  return static_cast<int>(sizeof(void*) *
-                          std::numeric_limits<unsigned char>::digits);
-}
-
-FMT_INLINE void assume(bool condition) {
-  (void)condition;
-#if FMT_HAS_BUILTIN(__builtin_assume)
-  __builtin_assume(condition);
-#endif
-}
-
-// An approximation of iterator_t for pre-C++20 systems.
-template <typename T>
-using iterator_t = decltype(std::begin(std::declval<T&>()));
-template <typename T> using sentinel_t = decltype(std::end(std::declval<T&>()));
-
-// A workaround for std::string not having mutable data() until C++17.
-template <typename Char>
-inline auto get_data(std::basic_string<Char>& s) -> Char* {
-  return &s[0];
-}
-template <typename Container>
-inline auto get_data(Container& c) -> typename Container::value_type* {
-  return c.data();
-}
-
-#if defined(_SECURE_SCL) && _SECURE_SCL
-// Make a checked iterator to avoid MSVC warnings.
-template <typename T> using checked_ptr = stdext::checked_array_iterator<T*>;
-template <typename T>
-constexpr auto make_checked(T* p, size_t size) -> checked_ptr<T> {
-  return {p, size};
-}
-#else
-template <typename T> using checked_ptr = T*;
-template <typename T> constexpr auto make_checked(T* p, size_t) -> T* {
-  return p;
-}
-#endif
-
-// Attempts to reserve space for n extra characters in the output range.
-// Returns a pointer to the reserved range or a reference to it.
-template <typename Container, FMT_ENABLE_IF(is_contiguous<Container>::value)>
-#if FMT_CLANG_VERSION >= 307 && !FMT_ICC_VERSION
-__attribute__((no_sanitize("undefined")))
-#endif
-inline auto
-reserve(std::back_insert_iterator<Container> it, size_t n)
-    -> checked_ptr<typename Container::value_type> {
-  Container& c = get_container(it);
-  size_t size = c.size();
-  c.resize(size + n);
-  return make_checked(get_data(c) + size, n);
-}
-
-template <typename T>
-inline auto reserve(buffer_appender<T> it, size_t n) -> buffer_appender<T> {
-  buffer<T>& buf = get_container(it);
-  buf.try_reserve(buf.size() + n);
-  return it;
-}
-
-template <typename Iterator>
-constexpr auto reserve(Iterator& it, size_t) -> Iterator& {
-  return it;
-}
-
-template <typename OutputIt>
-using reserve_iterator =
-    remove_reference_t<decltype(reserve(std::declval<OutputIt&>(), 0))>;
-
-template <typename T, typename OutputIt>
-constexpr auto to_pointer(OutputIt, size_t) -> T* {
-  return nullptr;
-}
-template <typename T> auto to_pointer(buffer_appender<T> it, size_t n) -> T* {
-  buffer<T>& buf = get_container(it);
-  auto size = buf.size();
-  if (buf.capacity() < size + n) return nullptr;
-  buf.try_resize(size + n);
-  return buf.data() + size;
-}
-
-template <typename Container, FMT_ENABLE_IF(is_contiguous<Container>::value)>
-inline auto base_iterator(std::back_insert_iterator<Container>& it,
-                          checked_ptr<typename Container::value_type>)
-    -> std::back_insert_iterator<Container> {
-  return it;
-}
-
-template <typename Iterator>
-constexpr auto base_iterator(Iterator, Iterator it) -> Iterator {
-  return it;
-}
-
-// <algorithm> is spectacularly slow to compile in C++20 so use a simple fill_n
-// instead (#1998).
-template <typename OutputIt, typename Size, typename T>
-FMT_CONSTEXPR auto fill_n(OutputIt out, Size count, const T& value)
-    -> OutputIt {
-  for (Size i = 0; i < count; ++i) *out++ = value;
-  return out;
-}
-template <typename T, typename Size>
-FMT_CONSTEXPR20 auto fill_n(T* out, Size count, char value) -> T* {
-  if (is_constant_evaluated()) {
-    return fill_n<T*, Size, T>(out, count, value);
-  }
-  std::memset(out, value, to_unsigned(count));
-  return out + count;
-}
-
-#ifdef __cpp_char8_t
-using char8_type = char8_t;
-#else
-enum char8_type : unsigned char {};
-#endif
-
-template <typename OutChar, typename InputIt, typename OutputIt>
-FMT_CONSTEXPR FMT_NOINLINE auto copy_str_noinline(InputIt begin, InputIt end,
-                                                  OutputIt out) -> OutputIt {
-  return copy_str<OutChar>(begin, end, out);
-}
-
-// A public domain branchless UTF-8 decoder by Christopher Wellons:
-// https://github.com/skeeto/branchless-utf8
-/* Decode the next character, c, from s, reporting errors in e.
- *
- * Since this is a branchless decoder, four bytes will be read from the
- * buffer regardless of the actual length of the next character. This
- * means the buffer _must_ have at least three bytes of zero padding
- * following the end of the data stream.
- *
- * Errors are reported in e, which will be non-zero if the parsed
- * character was somehow invalid: invalid byte sequence, non-canonical
- * encoding, or a surrogate half.
- *
- * The function returns a pointer to the next character. When an error
- * occurs, this pointer will be a guess that depends on the particular
- * error, but it will always advance at least one byte.
- */
-FMT_CONSTEXPR inline auto utf8_decode(const char* s, uint32_t* c, int* e)
-    -> const char* {
-  constexpr const int masks[] = {0x00, 0x7f, 0x1f, 0x0f, 0x07};
-  constexpr const uint32_t mins[] = {4194304, 0, 128, 2048, 65536};
-  constexpr const int shiftc[] = {0, 18, 12, 6, 0};
-  constexpr const int shifte[] = {0, 6, 4, 2, 0};
-
-  int len = code_point_length(s);
-  const char* next = s + len;
-
-  // Assume a four-byte character and load four bytes. Unused bits are
-  // shifted out.
-  *c = uint32_t(s[0] & masks[len]) << 18;
-  *c |= uint32_t(s[1] & 0x3f) << 12;
-  *c |= uint32_t(s[2] & 0x3f) << 6;
-  *c |= uint32_t(s[3] & 0x3f) << 0;
-  *c >>= shiftc[len];
-
-  // Accumulate the various error conditions.
-  using uchar = unsigned char;
-  *e = (*c < mins[len]) << 6;       // non-canonical encoding
-  *e |= ((*c >> 11) == 0x1b) << 7;  // surrogate half?
-  *e |= (*c > 0x10FFFF) << 8;       // out of range?
-  *e |= (uchar(s[1]) & 0xc0) >> 2;
-  *e |= (uchar(s[2]) & 0xc0) >> 4;
-  *e |= uchar(s[3]) >> 6;
-  *e ^= 0x2a;  // top two bits of each tail byte correct?
-  *e >>= shifte[len];
-
-  return next;
-}
-
-constexpr uint32_t invalid_code_point = ~uint32_t();
-
-// Invokes f(cp, sv) for every code point cp in s with sv being the string view
-// corresponding to the code point. cp is invalid_code_point on error.
-template <typename F>
-FMT_CONSTEXPR void for_each_codepoint(string_view s, F f) {
-  auto decode = [f](const char* buf_ptr, const char* ptr) {
-    auto cp = uint32_t();
-    auto error = 0;
-    auto end = utf8_decode(buf_ptr, &cp, &error);
-    bool result = f(error ? invalid_code_point : cp,
-                    string_view(ptr, to_unsigned(end - buf_ptr)));
-    return result ? end : nullptr;
-  };
-  auto p = s.data();
-  const size_t block_size = 4;  // utf8_decode always reads blocks of 4 chars.
-  if (s.size() >= block_size) {
-    for (auto end = p + s.size() - block_size + 1; p < end;) {
-      p = decode(p, p);
-      if (!p) return;
-    }
-  }
-  if (auto num_chars_left = s.data() + s.size() - p) {
-    char buf[2 * block_size - 1] = {};
-    copy_str<char>(p, p + num_chars_left, buf);
-    const char* buf_ptr = buf;
-    do {
-      auto end = decode(buf_ptr, p);
-      if (!end) return;
-      p += end - buf_ptr;
-      buf_ptr = end;
-    } while (buf_ptr - buf < num_chars_left);
-  }
-}
-
-template <typename Char>
-inline auto compute_width(basic_string_view<Char> s) -> size_t {
-  return s.size();
-}
-
-// Computes approximate display width of a UTF-8 string.
-FMT_CONSTEXPR inline size_t compute_width(string_view s) {
-  size_t num_code_points = 0;
-  // It is not a lambda for compatibility with C++14.
-  struct count_code_points {
-    size_t* count;
-    FMT_CONSTEXPR auto operator()(uint32_t cp, string_view) const -> bool {
-      *count += detail::to_unsigned(
-          1 +
-          (cp >= 0x1100 &&
-           (cp <= 0x115f ||  // Hangul Jamo init. consonants
-            cp == 0x2329 ||  // LEFT-POINTING ANGLE BRACKET
-            cp == 0x232a ||  // RIGHT-POINTING ANGLE BRACKET
-            // CJK ... Yi except IDEOGRAPHIC HALF FILL SPACE:
-            (cp >= 0x2e80 && cp <= 0xa4cf && cp != 0x303f) ||
-            (cp >= 0xac00 && cp <= 0xd7a3) ||    // Hangul Syllables
-            (cp >= 0xf900 && cp <= 0xfaff) ||    // CJK Compatibility Ideographs
-            (cp >= 0xfe10 && cp <= 0xfe19) ||    // Vertical Forms
-            (cp >= 0xfe30 && cp <= 0xfe6f) ||    // CJK Compatibility Forms
-            (cp >= 0xff00 && cp <= 0xff60) ||    // Fullwidth Forms
-            (cp >= 0xffe0 && cp <= 0xffe6) ||    // Fullwidth Forms
-            (cp >= 0x20000 && cp <= 0x2fffd) ||  // CJK
-            (cp >= 0x30000 && cp <= 0x3fffd) ||
-            // Miscellaneous Symbols and Pictographs + Emoticons:
-            (cp >= 0x1f300 && cp <= 0x1f64f) ||
-            // Supplemental Symbols and Pictographs:
-            (cp >= 0x1f900 && cp <= 0x1f9ff))));
-      return true;
-    }
-  };
-  for_each_codepoint(s, count_code_points{&num_code_points});
-  return num_code_points;
-}
-
-inline auto compute_width(basic_string_view<char8_type> s) -> size_t {
-  return compute_width(basic_string_view<char>(
-      reinterpret_cast<const char*>(s.data()), s.size()));
-}
-
-template <typename Char>
-inline auto code_point_index(basic_string_view<Char> s, size_t n) -> size_t {
-  size_t size = s.size();
-  return n < size ? n : size;
-}
-
-// Calculates the index of the nth code point in a UTF-8 string.
-inline auto code_point_index(basic_string_view<char8_type> s, size_t n)
-    -> size_t {
-  const char8_type* data = s.data();
-  size_t num_code_points = 0;
-  for (size_t i = 0, size = s.size(); i != size; ++i) {
-    if ((data[i] & 0xc0) != 0x80 && ++num_code_points > n) return i;
-  }
-  return s.size();
-}
-
-template <typename T, bool = std::is_floating_point<T>::value>
-struct is_fast_float : bool_constant<std::numeric_limits<T>::is_iec559 &&
-                                     sizeof(T) <= sizeof(double)> {};
-template <typename T> struct is_fast_float<T, false> : std::false_type {};
-
-#ifndef FMT_USE_FULL_CACHE_DRAGONBOX
-#  define FMT_USE_FULL_CACHE_DRAGONBOX 0
-#endif
-
-template <typename T>
-template <typename U>
-void buffer<T>::append(const U* begin, const U* end) {
-  while (begin != end) {
-    auto count = to_unsigned(end - begin);
-    try_reserve(size_ + count);
-    auto free_cap = capacity_ - size_;
-    if (free_cap < count) count = free_cap;
-    std::uninitialized_copy_n(begin, count, make_checked(ptr_ + size_, count));
-    size_ += count;
-    begin += count;
-  }
-}
-
-template <typename T, typename Enable = void>
-struct is_locale : std::false_type {};
-template <typename T>
-struct is_locale<T, void_t<decltype(T::classic())>> : std::true_type {};
-}  // namespace detail
-
-FMT_MODULE_EXPORT_BEGIN
-
-// The number of characters to store in the basic_memory_buffer object itself
-// to avoid dynamic memory allocation.
-enum { inline_buffer_size = 500 };
-
-/**
-  \rst
-  A dynamically growing memory buffer for trivially copyable/constructible types
-  with the first ``SIZE`` elements stored in the object itself.
-
-  You can use the ``memory_buffer`` type alias for ``char`` instead.
-
-  **Example**::
-
-     auto out = fmt::memory_buffer();
-     format_to(std::back_inserter(out), "The answer is {}.", 42);
-
-  This will append the following output to the ``out`` object:
-
-  .. code-block:: none
-
-     The answer is 42.
-
-  The output can be converted to an ``std::string`` with ``to_string(out)``.
-  \endrst
- */
-template <typename T, size_t SIZE = inline_buffer_size,
-          typename Allocator = std::allocator<T>>
-class basic_memory_buffer final : public detail::buffer<T> {
- private:
-  T store_[SIZE];
-
-  // Don't inherit from Allocator avoid generating type_info for it.
-  Allocator alloc_;
-
-  // Deallocate memory allocated by the buffer.
-  FMT_CONSTEXPR20 void deallocate() {
-    T* data = this->data();
-    if (data != store_) alloc_.deallocate(data, this->capacity());
-  }
-
- protected:
-  FMT_CONSTEXPR20 void grow(size_t size) override;
-
- public:
-  using value_type = T;
-  using const_reference = const T&;
-
-  FMT_CONSTEXPR20 explicit basic_memory_buffer(
-      const Allocator& alloc = Allocator())
-      : alloc_(alloc) {
-    this->set(store_, SIZE);
-    if (detail::is_constant_evaluated()) {
-      detail::fill_n(store_, SIZE, T{});
-    }
-  }
-  FMT_CONSTEXPR20 ~basic_memory_buffer() { deallocate(); }
-
- private:
-  // Move data from other to this buffer.
-  FMT_CONSTEXPR20 void move(basic_memory_buffer& other) {
-    alloc_ = std::move(other.alloc_);
-    T* data = other.data();
-    size_t size = other.size(), capacity = other.capacity();
-    if (data == other.store_) {
-      this->set(store_, capacity);
-      if (detail::is_constant_evaluated()) {
-        detail::copy_str<T>(other.store_, other.store_ + size,
-                            detail::make_checked(store_, capacity));
-      } else {
-        std::uninitialized_copy(other.store_, other.store_ + size,
-                                detail::make_checked(store_, capacity));
-      }
-    } else {
-      this->set(data, capacity);
-      // Set pointer to the inline array so that delete is not called
-      // when deallocating.
-      other.set(other.store_, 0);
-    }
-    this->resize(size);
-  }
-
- public:
-  /**
-    \rst
-    Constructs a :class:`fmt::basic_memory_buffer` object moving the content
-    of the other object to it.
-    \endrst
-   */
-  FMT_CONSTEXPR20 basic_memory_buffer(basic_memory_buffer&& other)
-      FMT_NOEXCEPT {
-    move(other);
-  }
-
-  /**
-    \rst
-    Moves the content of the other ``basic_memory_buffer`` object to this one.
-    \endrst
-   */
-  auto operator=(basic_memory_buffer&& other) FMT_NOEXCEPT
-      -> basic_memory_buffer& {
-    FMT_ASSERT(this != &other, "");
-    deallocate();
-    move(other);
-    return *this;
-  }
-
-  // Returns a copy of the allocator associated with this buffer.
-  auto get_allocator() const -> Allocator { return alloc_; }
-
-  /**
-    Resizes the buffer to contain *count* elements. If T is a POD type new
-    elements may not be initialized.
-   */
-  FMT_CONSTEXPR20 void resize(size_t count) { this->try_resize(count); }
-
-  /** Increases the buffer capacity to *new_capacity*. */
-  void reserve(size_t new_capacity) { this->try_reserve(new_capacity); }
-
-  // Directly append data into the buffer
-  using detail::buffer<T>::append;
-  template <typename ContiguousRange>
-  void append(const ContiguousRange& range) {
-    append(range.data(), range.data() + range.size());
-  }
-};
-
-template <typename T, size_t SIZE, typename Allocator>
-FMT_CONSTEXPR20 void basic_memory_buffer<T, SIZE, Allocator>::grow(
-    size_t size) {
-#ifdef FMT_FUZZ
-  if (size > 5000) throw std::runtime_error("fuzz mode - won't grow that much");
-#endif
-  const size_t max_size = std::allocator_traits<Allocator>::max_size(alloc_);
-  size_t old_capacity = this->capacity();
-  size_t new_capacity = old_capacity + old_capacity / 2;
-  if (size > new_capacity)
-    new_capacity = size;
-  else if (new_capacity > max_size)
-    new_capacity = size > max_size ? size : max_size;
-  T* old_data = this->data();
-  T* new_data =
-      std::allocator_traits<Allocator>::allocate(alloc_, new_capacity);
-  // The following code doesn't throw, so the raw pointer above doesn't leak.
-  std::uninitialized_copy(old_data, old_data + this->size(),
-                          detail::make_checked(new_data, new_capacity));
-  this->set(new_data, new_capacity);
-  // deallocate must not throw according to the standard, but even if it does,
-  // the buffer already uses the new storage and will deallocate it in
-  // destructor.
-  if (old_data != store_) alloc_.deallocate(old_data, old_capacity);
-}
-
-using memory_buffer = basic_memory_buffer<char>;
-
-template <typename T, size_t SIZE, typename Allocator>
-struct is_contiguous<basic_memory_buffer<T, SIZE, Allocator>> : std::true_type {
-};
-
-namespace detail {
-FMT_API void print(std::FILE*, string_view);
-}
-
-/** A formatting error such as invalid format string. */
-FMT_CLASS_API
-class FMT_API format_error : public std::runtime_error {
- public:
-  explicit format_error(const char* message) : std::runtime_error(message) {}
-  explicit format_error(const std::string& message)
-      : std::runtime_error(message) {}
-  format_error(const format_error&) = default;
-  format_error& operator=(const format_error&) = default;
-  format_error(format_error&&) = default;
-  format_error& operator=(format_error&&) = default;
-  ~format_error() FMT_NOEXCEPT override FMT_MSC_DEFAULT;
-};
-
-/**
-  \rst
-  Constructs a `~fmt::format_arg_store` object that contains references
-  to arguments and can be implicitly converted to `~fmt::format_args`.
-  If ``fmt`` is a compile-time string then `make_args_checked` checks
-  its validity at compile time.
-  \endrst
- */
-template <typename... Args, typename S, typename Char = char_t<S>>
-FMT_INLINE auto make_args_checked(const S& fmt,
-                                  const remove_reference_t<Args>&... args)
-    -> format_arg_store<buffer_context<Char>, remove_reference_t<Args>...> {
-  static_assert(
-      detail::count<(
-              std::is_base_of<detail::view, remove_reference_t<Args>>::value &&
-              std::is_reference<Args>::value)...>() == 0,
-      "passing views as lvalues is disallowed");
-  detail::check_format_string<Args...>(fmt);
-  return {args...};
-}
-
-// compile-time support
-namespace detail_exported {
-#if FMT_USE_NONTYPE_TEMPLATE_PARAMETERS
-template <typename Char, size_t N> struct fixed_string {
-  constexpr fixed_string(const Char (&str)[N]) {
-    detail::copy_str<Char, const Char*, Char*>(static_cast<const Char*>(str),
-                                               str + N, data);
-  }
-  Char data[N]{};
-};
-#endif
-
-// Converts a compile-time string to basic_string_view.
-template <typename Char, size_t N>
-constexpr auto compile_string_to_view(const Char (&s)[N])
-    -> basic_string_view<Char> {
-  // Remove trailing NUL character if needed. Won't be present if this is used
-  // with a raw character array (i.e. not defined as a string).
-  return {s, N - (std::char_traits<Char>::to_int_type(s[N - 1]) == 0 ? 1 : 0)};
-}
-template <typename Char>
-constexpr auto compile_string_to_view(detail::std_string_view<Char> s)
-    -> basic_string_view<Char> {
-  return {s.data(), s.size()};
-}
-}  // namespace detail_exported
-
-FMT_BEGIN_DETAIL_NAMESPACE
-
-template <typename T> struct is_integral : std::is_integral<T> {};
-template <> struct is_integral<int128_t> : std::true_type {};
-template <> struct is_integral<uint128_t> : std::true_type {};
-
-template <typename T>
-using is_signed =
-    std::integral_constant<bool, std::numeric_limits<T>::is_signed ||
-                                     std::is_same<T, int128_t>::value>;
-
-// Returns true if value is negative, false otherwise.
-// Same as `value < 0` but doesn't produce warnings if T is an unsigned type.
-template <typename T, FMT_ENABLE_IF(is_signed<T>::value)>
-FMT_CONSTEXPR auto is_negative(T value) -> bool {
-  return value < 0;
-}
-template <typename T, FMT_ENABLE_IF(!is_signed<T>::value)>
-FMT_CONSTEXPR auto is_negative(T) -> bool {
-  return false;
-}
-
-template <typename T, FMT_ENABLE_IF(std::is_floating_point<T>::value)>
-FMT_CONSTEXPR auto is_supported_floating_point(T) -> uint16_t {
-  return (std::is_same<T, float>::value && FMT_USE_FLOAT) ||
-         (std::is_same<T, double>::value && FMT_USE_DOUBLE) ||
-         (std::is_same<T, long double>::value && FMT_USE_LONG_DOUBLE);
-}
-
-// Smallest of uint32_t, uint64_t, uint128_t that is large enough to
-// represent all values of an integral type T.
-template <typename T>
-using uint32_or_64_or_128_t =
-    conditional_t<num_bits<T>() <= 32 && !FMT_REDUCE_INT_INSTANTIATIONS,
-                  uint32_t,
-                  conditional_t<num_bits<T>() <= 64, uint64_t, uint128_t>>;
-template <typename T>
-using uint64_or_128_t = conditional_t<num_bits<T>() <= 64, uint64_t, uint128_t>;
-
-#define FMT_POWERS_OF_10(factor)                                             \
-  factor * 10, (factor)*100, (factor)*1000, (factor)*10000, (factor)*100000, \
-      (factor)*1000000, (factor)*10000000, (factor)*100000000,               \
-      (factor)*1000000000
-
-// Converts value in the range [0, 100) to a string.
-constexpr const char* digits2(size_t value) {
-  // GCC generates slightly better code when value is pointer-size.
-  return &"0001020304050607080910111213141516171819"
-         "2021222324252627282930313233343536373839"
-         "4041424344454647484950515253545556575859"
-         "6061626364656667686970717273747576777879"
-         "8081828384858687888990919293949596979899"[value * 2];
-}
-
-// Sign is a template parameter to workaround a bug in gcc 4.8.
-template <typename Char, typename Sign> constexpr Char sign(Sign s) {
-#if !FMT_GCC_VERSION || FMT_GCC_VERSION >= 604
-  static_assert(std::is_same<Sign, sign_t>::value, "");
-#endif
-  return static_cast<Char>("\0-+ "[s]);
-}
-
-template <typename T> FMT_CONSTEXPR auto count_digits_fallback(T n) -> int {
-  int count = 1;
-  for (;;) {
-    // Integer division is slow so do it for a group of four digits instead
-    // of for every digit. The idea comes from the talk by Alexandrescu
-    // "Three Optimization Tips for C++". See speed-test for a comparison.
-    if (n < 10) return count;
-    if (n < 100) return count + 1;
-    if (n < 1000) return count + 2;
-    if (n < 10000) return count + 3;
-    n /= 10000u;
-    count += 4;
-  }
-}
-#if FMT_USE_INT128
-FMT_CONSTEXPR inline auto count_digits(uint128_t n) -> int {
-  return count_digits_fallback(n);
-}
-#endif
-
-#ifdef FMT_BUILTIN_CLZLL
-// It is a separate function rather than a part of count_digits to workaround
-// the lack of static constexpr in constexpr functions.
-inline auto do_count_digits(uint64_t n) -> int {
-  // This has comparable performance to the version by Kendall Willets
-  // (https://github.com/fmtlib/format-benchmark/blob/master/digits10)
-  // but uses smaller tables.
-  // Maps bsr(n) to ceil(log10(pow(2, bsr(n) + 1) - 1)).
-  static constexpr uint8_t bsr2log10[] = {
-      1,  1,  1,  2,  2,  2,  3,  3,  3,  4,  4,  4,  4,  5,  5,  5,
-      6,  6,  6,  7,  7,  7,  7,  8,  8,  8,  9,  9,  9,  10, 10, 10,
-      10, 11, 11, 11, 12, 12, 12, 13, 13, 13, 13, 14, 14, 14, 15, 15,
-      15, 16, 16, 16, 16, 17, 17, 17, 18, 18, 18, 19, 19, 19, 19, 20};
-  auto t = bsr2log10[FMT_BUILTIN_CLZLL(n | 1) ^ 63];
-  static constexpr const uint64_t zero_or_powers_of_10[] = {
-      0, 0, FMT_POWERS_OF_10(1U), FMT_POWERS_OF_10(1000000000ULL),
-      10000000000000000000ULL};
-  return t - (n < zero_or_powers_of_10[t]);
-}
-#endif
-
-// Returns the number of decimal digits in n. Leading zeros are not counted
-// except for n == 0 in which case count_digits returns 1.
-FMT_CONSTEXPR20 inline auto count_digits(uint64_t n) -> int {
-#ifdef FMT_BUILTIN_CLZLL
-  if (!is_constant_evaluated()) {
-    return do_count_digits(n);
-  }
-#endif
-  return count_digits_fallback(n);
-}
-
-// Counts the number of digits in n. BITS = log2(radix).
-template <int BITS, typename UInt>
-FMT_CONSTEXPR auto count_digits(UInt n) -> int {
-#ifdef FMT_BUILTIN_CLZ
-  if (num_bits<UInt>() == 32)
-    return (FMT_BUILTIN_CLZ(static_cast<uint32_t>(n) | 1) ^ 31) / BITS + 1;
-#endif
-  // Lambda avoids unreachable code warnings from NVHPC.
-  return [](UInt m) {
-    int num_digits = 0;
-    do {
-      ++num_digits;
-    } while ((m >>= BITS) != 0);
-    return num_digits;
-  }(n);
-}
-
-template <> auto count_digits<4>(detail::fallback_uintptr n) -> int;
-
-#ifdef FMT_BUILTIN_CLZ
-// It is a separate function rather than a part of count_digits to workaround
-// the lack of static constexpr in constexpr functions.
-FMT_INLINE auto do_count_digits(uint32_t n) -> int {
-// An optimization by Kendall Willets from https://bit.ly/3uOIQrB.
-// This increments the upper 32 bits (log10(T) - 1) when >= T is added.
-#  define FMT_INC(T) (((sizeof(#  T) - 1ull) << 32) - T)
-  static constexpr uint64_t table[] = {
-      FMT_INC(0),          FMT_INC(0),          FMT_INC(0),           // 8
-      FMT_INC(10),         FMT_INC(10),         FMT_INC(10),          // 64
-      FMT_INC(100),        FMT_INC(100),        FMT_INC(100),         // 512
-      FMT_INC(1000),       FMT_INC(1000),       FMT_INC(1000),        // 4096
-      FMT_INC(10000),      FMT_INC(10000),      FMT_INC(10000),       // 32k
-      FMT_INC(100000),     FMT_INC(100000),     FMT_INC(100000),      // 256k
-      FMT_INC(1000000),    FMT_INC(1000000),    FMT_INC(1000000),     // 2048k
-      FMT_INC(10000000),   FMT_INC(10000000),   FMT_INC(10000000),    // 16M
-      FMT_INC(100000000),  FMT_INC(100000000),  FMT_INC(100000000),   // 128M
-      FMT_INC(1000000000), FMT_INC(1000000000), FMT_INC(1000000000),  // 1024M
-      FMT_INC(1000000000), FMT_INC(1000000000)                        // 4B
-  };
-  auto inc = table[FMT_BUILTIN_CLZ(n | 1) ^ 31];
-  return static_cast<int>((n + inc) >> 32);
-}
-#endif
-
-// Optional version of count_digits for better performance on 32-bit platforms.
-FMT_CONSTEXPR20 inline auto count_digits(uint32_t n) -> int {
-#ifdef FMT_BUILTIN_CLZ
-  if (!is_constant_evaluated()) {
-    return do_count_digits(n);
-  }
-#endif
-  return count_digits_fallback(n);
-}
-
-template <typename Int> constexpr auto digits10() FMT_NOEXCEPT -> int {
-  return std::numeric_limits<Int>::digits10;
-}
-template <> constexpr auto digits10<int128_t>() FMT_NOEXCEPT -> int {
-  return 38;
-}
-template <> constexpr auto digits10<uint128_t>() FMT_NOEXCEPT -> int {
-  return 38;
-}
-
-template <typename Char> struct thousands_sep_result {
-  std::string grouping;
-  Char thousands_sep;
-};
-
-template <typename Char>
-FMT_API auto thousands_sep_impl(locale_ref loc) -> thousands_sep_result<Char>;
-template <typename Char>
-inline auto thousands_sep(locale_ref loc) -> thousands_sep_result<Char> {
-  auto result = thousands_sep_impl<char>(loc);
-  return {result.grouping, Char(result.thousands_sep)};
-}
-template <>
-inline auto thousands_sep(locale_ref loc) -> thousands_sep_result<wchar_t> {
-  return thousands_sep_impl<wchar_t>(loc);
-}
-
-template <typename Char>
-FMT_API auto decimal_point_impl(locale_ref loc) -> Char;
-template <typename Char> inline auto decimal_point(locale_ref loc) -> Char {
-  return Char(decimal_point_impl<char>(loc));
-}
-template <> inline auto decimal_point(locale_ref loc) -> wchar_t {
-  return decimal_point_impl<wchar_t>(loc);
-}
-
-// Compares two characters for equality.
-template <typename Char> auto equal2(const Char* lhs, const char* rhs) -> bool {
-  return lhs[0] == Char(rhs[0]) && lhs[1] == Char(rhs[1]);
-}
-inline auto equal2(const char* lhs, const char* rhs) -> bool {
-  return memcmp(lhs, rhs, 2) == 0;
-}
-
-// Copies two characters from src to dst.
-template <typename Char>
-FMT_CONSTEXPR20 FMT_INLINE void copy2(Char* dst, const char* src) {
-  if (!is_constant_evaluated() && sizeof(Char) == sizeof(char)) {
-    memcpy(dst, src, 2);
-    return;
-  }
-  *dst++ = static_cast<Char>(*src++);
-  *dst = static_cast<Char>(*src);
-}
-
-template <typename Iterator> struct format_decimal_result {
-  Iterator begin;
-  Iterator end;
-};
-
-// Formats a decimal unsigned integer value writing into out pointing to a
-// buffer of specified size. The caller must ensure that the buffer is large
-// enough.
-template <typename Char, typename UInt>
-FMT_CONSTEXPR20 auto format_decimal(Char* out, UInt value, int size)
-    -> format_decimal_result<Char*> {
-  FMT_ASSERT(size >= count_digits(value), "invalid digit count");
-  out += size;
-  Char* end = out;
-  while (value >= 100) {
-    // Integer division is slow so do it for a group of two digits instead
-    // of for every digit. The idea comes from the talk by Alexandrescu
-    // "Three Optimization Tips for C++". See speed-test for a comparison.
-    out -= 2;
-    copy2(out, digits2(static_cast<size_t>(value % 100)));
-    value /= 100;
-  }
-  if (value < 10) {
-    *--out = static_cast<Char>('0' + value);
-    return {out, end};
-  }
-  out -= 2;
-  copy2(out, digits2(static_cast<size_t>(value)));
-  return {out, end};
-}
-
-template <typename Char, typename UInt, typename Iterator,
-          FMT_ENABLE_IF(!std::is_pointer<remove_cvref_t<Iterator>>::value)>
-inline auto format_decimal(Iterator out, UInt value, int size)
-    -> format_decimal_result<Iterator> {
-  // Buffer is large enough to hold all digits (digits10 + 1).
-  Char buffer[digits10<UInt>() + 1];
-  auto end = format_decimal(buffer, value, size).end;
-  return {out, detail::copy_str_noinline<Char>(buffer, end, out)};
-}
-
-template <unsigned BASE_BITS, typename Char, typename UInt>
-FMT_CONSTEXPR auto format_uint(Char* buffer, UInt value, int num_digits,
-                               bool upper = false) -> Char* {
-  buffer += num_digits;
-  Char* end = buffer;
-  do {
-    const char* digits = upper ? "0123456789ABCDEF" : "0123456789abcdef";
-    unsigned digit = (value & ((1 << BASE_BITS) - 1));
-    *--buffer = static_cast<Char>(BASE_BITS < 4 ? static_cast<char>('0' + digit)
-                                                : digits[digit]);
-  } while ((value >>= BASE_BITS) != 0);
-  return end;
-}
-
-template <unsigned BASE_BITS, typename Char>
-auto format_uint(Char* buffer, detail::fallback_uintptr n, int num_digits,
-                 bool = false) -> Char* {
-  auto char_digits = std::numeric_limits<unsigned char>::digits / 4;
-  int start = (num_digits + char_digits - 1) / char_digits - 1;
-  if (int start_digits = num_digits % char_digits) {
-    unsigned value = n.value[start--];
-    buffer = format_uint<BASE_BITS>(buffer, value, start_digits);
-  }
-  for (; start >= 0; --start) {
-    unsigned value = n.value[start];
-    buffer += char_digits;
-    auto p = buffer;
-    for (int i = 0; i < char_digits; ++i) {
-      unsigned digit = (value & ((1 << BASE_BITS) - 1));
-      *--p = static_cast<Char>("0123456789abcdef"[digit]);
-      value >>= BASE_BITS;
-    }
-  }
-  return buffer;
-}
-
-template <unsigned BASE_BITS, typename Char, typename It, typename UInt>
-inline auto format_uint(It out, UInt value, int num_digits, bool upper = false)
-    -> It {
-  if (auto ptr = to_pointer<Char>(out, to_unsigned(num_digits))) {
-    format_uint<BASE_BITS>(ptr, value, num_digits, upper);
-    return out;
-  }
-  // Buffer should be large enough to hold all digits (digits / BASE_BITS + 1).
-  char buffer[num_bits<UInt>() / BASE_BITS + 1];
-  format_uint<BASE_BITS>(buffer, value, num_digits, upper);
-  return detail::copy_str_noinline<Char>(buffer, buffer + num_digits, out);
-}
-
-// A converter from UTF-8 to UTF-16.
-class utf8_to_utf16 {
- private:
-  basic_memory_buffer<wchar_t> buffer_;
-
- public:
-  FMT_API explicit utf8_to_utf16(string_view s);
-  operator basic_string_view<wchar_t>() const { return {&buffer_[0], size()}; }
-  auto size() const -> size_t { return buffer_.size() - 1; }
-  auto c_str() const -> const wchar_t* { return &buffer_[0]; }
-  auto str() const -> std::wstring { return {&buffer_[0], size()}; }
-};
-
-namespace dragonbox {
-
-// Type-specific information that Dragonbox uses.
-template <class T> struct float_info;
-
-template <> struct float_info<float> {
-  using carrier_uint = uint32_t;
-  static const int significand_bits = 23;
-  static const int exponent_bits = 8;
-  static const int min_exponent = -126;
-  static const int max_exponent = 127;
-  static const int exponent_bias = -127;
-  static const int decimal_digits = 9;
-  static const int kappa = 1;
-  static const int big_divisor = 100;
-  static const int small_divisor = 10;
-  static const int min_k = -31;
-  static const int max_k = 46;
-  static const int cache_bits = 64;
-  static const int divisibility_check_by_5_threshold = 39;
-  static const int case_fc_pm_half_lower_threshold = -1;
-  static const int case_fc_pm_half_upper_threshold = 6;
-  static const int case_fc_lower_threshold = -2;
-  static const int case_fc_upper_threshold = 6;
-  static const int case_shorter_interval_left_endpoint_lower_threshold = 2;
-  static const int case_shorter_interval_left_endpoint_upper_threshold = 3;
-  static const int shorter_interval_tie_lower_threshold = -35;
-  static const int shorter_interval_tie_upper_threshold = -35;
-  static const int max_trailing_zeros = 7;
-};
-
-template <> struct float_info<double> {
-  using carrier_uint = uint64_t;
-  static const int significand_bits = 52;
-  static const int exponent_bits = 11;
-  static const int min_exponent = -1022;
-  static const int max_exponent = 1023;
-  static const int exponent_bias = -1023;
-  static const int decimal_digits = 17;
-  static const int kappa = 2;
-  static const int big_divisor = 1000;
-  static const int small_divisor = 100;
-  static const int min_k = -292;
-  static const int max_k = 326;
-  static const int cache_bits = 128;
-  static const int divisibility_check_by_5_threshold = 86;
-  static const int case_fc_pm_half_lower_threshold = -2;
-  static const int case_fc_pm_half_upper_threshold = 9;
-  static const int case_fc_lower_threshold = -4;
-  static const int case_fc_upper_threshold = 9;
-  static const int case_shorter_interval_left_endpoint_lower_threshold = 2;
-  static const int case_shorter_interval_left_endpoint_upper_threshold = 3;
-  static const int shorter_interval_tie_lower_threshold = -77;
-  static const int shorter_interval_tie_upper_threshold = -77;
-  static const int max_trailing_zeros = 16;
-};
-
-template <typename T> struct decimal_fp {
-  using significand_type = typename float_info<T>::carrier_uint;
-  significand_type significand;
-  int exponent;
-};
-
-template <typename T>
-FMT_API auto to_decimal(T x) FMT_NOEXCEPT -> decimal_fp<T>;
-}  // namespace dragonbox
-
-template <typename T>
-constexpr auto exponent_mask() ->
-    typename dragonbox::float_info<T>::carrier_uint {
-  using uint = typename dragonbox::float_info<T>::carrier_uint;
-  return ((uint(1) << dragonbox::float_info<T>::exponent_bits) - 1)
-         << dragonbox::float_info<T>::significand_bits;
-}
-
-// Writes the exponent exp in the form "[+-]d{2,3}" to buffer.
-template <typename Char, typename It>
-FMT_CONSTEXPR auto write_exponent(int exp, It it) -> It {
-  FMT_ASSERT(-10000 < exp && exp < 10000, "exponent out of range");
-  if (exp < 0) {
-    *it++ = static_cast<Char>('-');
-    exp = -exp;
-  } else {
-    *it++ = static_cast<Char>('+');
-  }
-  if (exp >= 100) {
-    const char* top = digits2(to_unsigned(exp / 100));
-    if (exp >= 1000) *it++ = static_cast<Char>(top[0]);
-    *it++ = static_cast<Char>(top[1]);
-    exp %= 100;
-  }
-  const char* d = digits2(to_unsigned(exp));
-  *it++ = static_cast<Char>(d[0]);
-  *it++ = static_cast<Char>(d[1]);
-  return it;
-}
-
-template <typename T>
-FMT_HEADER_ONLY_CONSTEXPR20 auto format_float(T value, int precision,
-                                              float_specs specs,
-                                              buffer<char>& buf) -> int;
-
-// Formats a floating-point number with snprintf.
-template <typename T>
-auto snprintf_float(T value, int precision, float_specs specs,
-                    buffer<char>& buf) -> int;
-
-template <typename T> constexpr auto promote_float(T value) -> T {
-  return value;
-}
-constexpr auto promote_float(float value) -> double {
-  return static_cast<double>(value);
-}
-
-template <typename OutputIt, typename Char>
-FMT_NOINLINE FMT_CONSTEXPR auto fill(OutputIt it, size_t n,
-                                     const fill_t<Char>& fill) -> OutputIt {
-  auto fill_size = fill.size();
-  if (fill_size == 1) return detail::fill_n(it, n, fill[0]);
-  auto data = fill.data();
-  for (size_t i = 0; i < n; ++i)
-    it = copy_str<Char>(data, data + fill_size, it);
-  return it;
-}
-
-// Writes the output of f, padded according to format specifications in specs.
-// size: output size in code units.
-// width: output display width in (terminal) column positions.
-template <align::type align = align::left, typename OutputIt, typename Char,
-          typename F>
-FMT_CONSTEXPR auto write_padded(OutputIt out,
-                                const basic_format_specs<Char>& specs,
-                                size_t size, size_t width, F&& f) -> OutputIt {
-  static_assert(align == align::left || align == align::right, "");
-  unsigned spec_width = to_unsigned(specs.width);
-  size_t padding = spec_width > width ? spec_width - width : 0;
-  // Shifts are encoded as string literals because static constexpr is not
-  // supported in constexpr functions.
-  auto* shifts = align == align::left ? "\x1f\x1f\x00\x01" : "\x00\x1f\x00\x01";
-  size_t left_padding = padding >> shifts[specs.align];
-  size_t right_padding = padding - left_padding;
-  auto it = reserve(out, size + padding * specs.fill.size());
-  if (left_padding != 0) it = fill(it, left_padding, specs.fill);
-  it = f(it);
-  if (right_padding != 0) it = fill(it, right_padding, specs.fill);
-  return base_iterator(out, it);
-}
-
-template <align::type align = align::left, typename OutputIt, typename Char,
-          typename F>
-constexpr auto write_padded(OutputIt out, const basic_format_specs<Char>& specs,
-                            size_t size, F&& f) -> OutputIt {
-  return write_padded<align>(out, specs, size, size, f);
-}
-
-template <align::type align = align::left, typename Char, typename OutputIt>
-FMT_CONSTEXPR auto write_bytes(OutputIt out, string_view bytes,
-                               const basic_format_specs<Char>& specs)
-    -> OutputIt {
-  return write_padded<align>(
-      out, specs, bytes.size(), [bytes](reserve_iterator<OutputIt> it) {
-        const char* data = bytes.data();
-        return copy_str<Char>(data, data + bytes.size(), it);
-      });
-}
-
-template <typename Char, typename OutputIt, typename UIntPtr>
-auto write_ptr(OutputIt out, UIntPtr value,
-               const basic_format_specs<Char>* specs) -> OutputIt {
-  int num_digits = count_digits<4>(value);
-  auto size = to_unsigned(num_digits) + size_t(2);
-  auto write = [=](reserve_iterator<OutputIt> it) {
-    *it++ = static_cast<Char>('0');
-    *it++ = static_cast<Char>('x');
-    return format_uint<4, Char>(it, value, num_digits);
-  };
-  return specs ? write_padded<align::right>(out, *specs, size, write)
-               : base_iterator(out, write(reserve(out, size)));
-}
-
-template <typename Char, typename OutputIt>
-FMT_CONSTEXPR auto write_char(OutputIt out, Char value,
-                              const basic_format_specs<Char>& specs)
-    -> OutputIt {
-  return write_padded(out, specs, 1, [=](reserve_iterator<OutputIt> it) {
-    *it++ = value;
-    return it;
-  });
-}
-template <typename Char, typename OutputIt>
-FMT_CONSTEXPR auto write(OutputIt out, Char value,
-                         const basic_format_specs<Char>& specs,
-                         locale_ref loc = {}) -> OutputIt {
-  return check_char_specs(specs)
-             ? write_char(out, value, specs)
-             : write(out, static_cast<int>(value), specs, loc);
-}
-
-// Data for write_int that doesn't depend on output iterator type. It is used to
-// avoid template code bloat.
-template <typename Char> struct write_int_data {
-  size_t size;
-  size_t padding;
-
-  FMT_CONSTEXPR write_int_data(int num_digits, unsigned prefix,
-                               const basic_format_specs<Char>& specs)
-      : size((prefix >> 24) + to_unsigned(num_digits)), padding(0) {
-    if (specs.align == align::numeric) {
-      auto width = to_unsigned(specs.width);
-      if (width > size) {
-        padding = width - size;
-        size = width;
-      }
-    } else if (specs.precision > num_digits) {
-      size = (prefix >> 24) + to_unsigned(specs.precision);
-      padding = to_unsigned(specs.precision - num_digits);
-    }
-  }
-};
-
-// Writes an integer in the format
-//   <left-padding><prefix><numeric-padding><digits><right-padding>
-// where <digits> are written by write_digits(it).
-// prefix contains chars in three lower bytes and the size in the fourth byte.
-template <typename OutputIt, typename Char, typename W>
-FMT_CONSTEXPR FMT_INLINE auto write_int(OutputIt out, int num_digits,
-                                        unsigned prefix,
-                                        const basic_format_specs<Char>& specs,
-                                        W write_digits) -> OutputIt {
-  // Slightly faster check for specs.width == 0 && specs.precision == -1.
-  if ((specs.width | (specs.precision + 1)) == 0) {
-    auto it = reserve(out, to_unsigned(num_digits) + (prefix >> 24));
-    if (prefix != 0) {
-      for (unsigned p = prefix & 0xffffff; p != 0; p >>= 8)
-        *it++ = static_cast<Char>(p & 0xff);
-    }
-    return base_iterator(out, write_digits(it));
-  }
-  auto data = write_int_data<Char>(num_digits, prefix, specs);
-  return write_padded<align::right>(
-      out, specs, data.size, [=](reserve_iterator<OutputIt> it) {
-        for (unsigned p = prefix & 0xffffff; p != 0; p >>= 8)
-          *it++ = static_cast<Char>(p & 0xff);
-        it = detail::fill_n(it, data.padding, static_cast<Char>('0'));
-        return write_digits(it);
-      });
-}
-
-template <typename Char> class digit_grouping {
- private:
-  thousands_sep_result<Char> sep_;
-
-  struct next_state {
-    std::string::const_iterator group;
-    int pos;
-  };
-  next_state initial_state() const { return {sep_.grouping.begin(), 0}; }
-
-  // Returns the next digit group separator position.
-  int next(next_state& state) const {
-    if (!sep_.thousands_sep) return max_value<int>();
-    if (state.group == sep_.grouping.end())
-      return state.pos += sep_.grouping.back();
-    if (*state.group <= 0 || *state.group == max_value<char>())
-      return max_value<int>();
-    state.pos += *state.group++;
-    return state.pos;
-  }
-
- public:
-  explicit digit_grouping(locale_ref loc, bool localized = true) {
-    if (localized)
-      sep_ = thousands_sep<Char>(loc);
-    else
-      sep_.thousands_sep = Char();
-  }
-  explicit digit_grouping(thousands_sep_result<Char> sep) : sep_(sep) {}
-
-  Char separator() const { return sep_.thousands_sep; }
-
-  int count_separators(int num_digits) const {
-    int count = 0;
-    auto state = initial_state();
-    while (num_digits > next(state)) ++count;
-    return count;
-  }
-
-  // Applies grouping to digits and write the output to out.
-  template <typename Out, typename C>
-  Out apply(Out out, basic_string_view<C> digits) const {
-    auto num_digits = static_cast<int>(digits.size());
-    auto separators = basic_memory_buffer<int>();
-    separators.push_back(0);
-    auto state = initial_state();
-    while (int i = next(state)) {
-      if (i >= num_digits) break;
-      separators.push_back(i);
-    }
-    for (int i = 0, sep_index = static_cast<int>(separators.size() - 1);
-         i < num_digits; ++i) {
-      if (num_digits - i == separators[sep_index]) {
-        *out++ = separator();
-        --sep_index;
-      }
-      *out++ = static_cast<Char>(digits[to_unsigned(i)]);
-    }
-    return out;
-  }
-};
-
-template <typename OutputIt, typename UInt, typename Char>
-auto write_int_localized(OutputIt out, UInt value, unsigned prefix,
-                         const basic_format_specs<Char>& specs,
-                         const digit_grouping<Char>& grouping) -> OutputIt {
-  static_assert(std::is_same<uint64_or_128_t<UInt>, UInt>::value, "");
-  int num_digits = count_digits(value);
-  char digits[40];
-  format_decimal(digits, value, num_digits);
-  unsigned size = to_unsigned((prefix != 0 ? 1 : 0) + num_digits +
-                              grouping.count_separators(num_digits));
-  return write_padded<align::right>(
-      out, specs, size, size, [&](reserve_iterator<OutputIt> it) {
-        if (prefix != 0) *it++ = static_cast<Char>(prefix);
-        return grouping.apply(it, string_view(digits, to_unsigned(num_digits)));
-      });
-}
-
-template <typename OutputIt, typename UInt, typename Char>
-auto write_int_localized(OutputIt& out, UInt value, unsigned prefix,
-                         const basic_format_specs<Char>& specs, locale_ref loc)
-    -> bool {
-  auto grouping = digit_grouping<Char>(loc);
-  out = write_int_localized(out, value, prefix, specs, grouping);
-  return true;
-}
-
-FMT_CONSTEXPR inline void prefix_append(unsigned& prefix, unsigned value) {
-  prefix |= prefix != 0 ? value << 8 : value;
-  prefix += (1u + (value > 0xff ? 1 : 0)) << 24;
-}
-
-template <typename UInt> struct write_int_arg {
-  UInt abs_value;
-  unsigned prefix;
-};
-
-template <typename T>
-FMT_CONSTEXPR auto make_write_int_arg(T value, sign_t sign)
-    -> write_int_arg<uint32_or_64_or_128_t<T>> {
-  auto prefix = 0u;
-  auto abs_value = static_cast<uint32_or_64_or_128_t<T>>(value);
-  if (is_negative(value)) {
-    prefix = 0x01000000 | '-';
-    abs_value = 0 - abs_value;
-  } else {
-    constexpr const unsigned prefixes[4] = {0, 0, 0x1000000u | '+',
-                                            0x1000000u | ' '};
-    prefix = prefixes[sign];
-  }
-  return {abs_value, prefix};
-}
-
-template <typename Char, typename OutputIt, typename T>
-FMT_CONSTEXPR FMT_INLINE auto write_int(OutputIt out, write_int_arg<T> arg,
-                                        const basic_format_specs<Char>& specs,
-                                        locale_ref loc) -> OutputIt {
-  static_assert(std::is_same<T, uint32_or_64_or_128_t<T>>::value, "");
-  auto abs_value = arg.abs_value;
-  auto prefix = arg.prefix;
-  switch (specs.type) {
-  case presentation_type::none:
-  case presentation_type::dec: {
-    if (specs.localized &&
-        write_int_localized(out, static_cast<uint64_or_128_t<T>>(abs_value),
-                            prefix, specs, loc)) {
-      return out;
-    }
-    auto num_digits = count_digits(abs_value);
-    return write_int(
-        out, num_digits, prefix, specs, [=](reserve_iterator<OutputIt> it) {
-          return format_decimal<Char>(it, abs_value, num_digits).end;
-        });
-  }
-  case presentation_type::hex_lower:
-  case presentation_type::hex_upper: {
-    bool upper = specs.type == presentation_type::hex_upper;
-    if (specs.alt)
-      prefix_append(prefix, unsigned(upper ? 'X' : 'x') << 8 | '0');
-    int num_digits = count_digits<4>(abs_value);
-    return write_int(
-        out, num_digits, prefix, specs, [=](reserve_iterator<OutputIt> it) {
-          return format_uint<4, Char>(it, abs_value, num_digits, upper);
-        });
-  }
-  case presentation_type::bin_lower:
-  case presentation_type::bin_upper: {
-    bool upper = specs.type == presentation_type::bin_upper;
-    if (specs.alt)
-      prefix_append(prefix, unsigned(upper ? 'B' : 'b') << 8 | '0');
-    int num_digits = count_digits<1>(abs_value);
-    return write_int(out, num_digits, prefix, specs,
-                     [=](reserve_iterator<OutputIt> it) {
-                       return format_uint<1, Char>(it, abs_value, num_digits);
-                     });
-  }
-  case presentation_type::oct: {
-    int num_digits = count_digits<3>(abs_value);
-    // Octal prefix '0' is counted as a digit, so only add it if precision
-    // is not greater than the number of digits.
-    if (specs.alt && specs.precision <= num_digits && abs_value != 0)
-      prefix_append(prefix, '0');
-    return write_int(out, num_digits, prefix, specs,
-                     [=](reserve_iterator<OutputIt> it) {
-                       return format_uint<3, Char>(it, abs_value, num_digits);
-                     });
-  }
-  case presentation_type::chr:
-    return write_char(out, static_cast<Char>(abs_value), specs);
-  default:
-    throw_format_error("invalid type specifier");
-  }
-  return out;
-}
-template <typename Char, typename OutputIt, typename T>
-FMT_CONSTEXPR FMT_NOINLINE auto write_int_noinline(
-    OutputIt out, write_int_arg<T> arg, const basic_format_specs<Char>& specs,
-    locale_ref loc) -> OutputIt {
-  return write_int(out, arg, specs, loc);
-}
-template <typename Char, typename OutputIt, typename T,
-          FMT_ENABLE_IF(is_integral<T>::value &&
-                        !std::is_same<T, bool>::value &&
-                        std::is_same<OutputIt, buffer_appender<Char>>::value)>
-FMT_CONSTEXPR FMT_INLINE auto write(OutputIt out, T value,
-                                    const basic_format_specs<Char>& specs,
-                                    locale_ref loc) -> OutputIt {
-  return write_int_noinline(out, make_write_int_arg(value, specs.sign), specs,
-                            loc);
-}
-// An inlined version of write used in format string compilation.
-template <typename Char, typename OutputIt, typename T,
-          FMT_ENABLE_IF(is_integral<T>::value &&
-                        !std::is_same<T, bool>::value &&
-                        !std::is_same<OutputIt, buffer_appender<Char>>::value)>
-FMT_CONSTEXPR FMT_INLINE auto write(OutputIt out, T value,
-                                    const basic_format_specs<Char>& specs,
-                                    locale_ref loc) -> OutputIt {
-  return write_int(out, make_write_int_arg(value, specs.sign), specs, loc);
-}
-
-template <typename Char, typename OutputIt>
-FMT_CONSTEXPR auto write(OutputIt out, basic_string_view<Char> s,
-                         const basic_format_specs<Char>& specs) -> OutputIt {
-  auto data = s.data();
-  auto size = s.size();
-  if (specs.precision >= 0 && to_unsigned(specs.precision) < size)
-    size = code_point_index(s, to_unsigned(specs.precision));
-  auto width =
-      specs.width != 0 ? compute_width(basic_string_view<Char>(data, size)) : 0;
-  return write_padded(out, specs, size, width,
-                      [=](reserve_iterator<OutputIt> it) {
-                        return copy_str<Char>(data, data + size, it);
-                      });
-}
-template <typename Char, typename OutputIt>
-FMT_CONSTEXPR auto write(OutputIt out,
-                         basic_string_view<type_identity_t<Char>> s,
-                         const basic_format_specs<Char>& specs, locale_ref)
-    -> OutputIt {
-  check_string_type_spec(specs.type);
-  return write(out, s, specs);
-}
-template <typename Char, typename OutputIt>
-FMT_CONSTEXPR auto write(OutputIt out, const Char* s,
-                         const basic_format_specs<Char>& specs, locale_ref)
-    -> OutputIt {
-  return check_cstring_type_spec(specs.type)
-             ? write(out, basic_string_view<Char>(s), specs, {})
-             : write_ptr<Char>(out, to_uintptr(s), &specs);
-}
-
-template <typename Char, typename OutputIt>
-FMT_CONSTEXPR20 auto write_nonfinite(OutputIt out, bool isinf,
-                                     basic_format_specs<Char> specs,
-                                     const float_specs& fspecs) -> OutputIt {
-  auto str =
-      isinf ? (fspecs.upper ? "INF" : "inf") : (fspecs.upper ? "NAN" : "nan");
-  constexpr size_t str_size = 3;
-  auto sign = fspecs.sign;
-  auto size = str_size + (sign ? 1 : 0);
-  // Replace '0'-padding with space for non-finite values.
-  const bool is_zero_fill =
-      specs.fill.size() == 1 && *specs.fill.data() == static_cast<Char>('0');
-  if (is_zero_fill) specs.fill[0] = static_cast<Char>(' ');
-  return write_padded(out, specs, size, [=](reserve_iterator<OutputIt> it) {
-    if (sign) *it++ = detail::sign<Char>(sign);
-    return copy_str<Char>(str, str + str_size, it);
-  });
-}
-
-// A decimal floating-point number significand * pow(10, exp).
-struct big_decimal_fp {
-  const char* significand;
-  int significand_size;
-  int exponent;
-};
-
-constexpr auto get_significand_size(const big_decimal_fp& fp) -> int {
-  return fp.significand_size;
-}
-template <typename T>
-inline auto get_significand_size(const dragonbox::decimal_fp<T>& fp) -> int {
-  return count_digits(fp.significand);
-}
-
-template <typename Char, typename OutputIt>
-constexpr auto write_significand(OutputIt out, const char* significand,
-                                 int significand_size) -> OutputIt {
-  return copy_str<Char>(significand, significand + significand_size, out);
-}
-template <typename Char, typename OutputIt, typename UInt>
-inline auto write_significand(OutputIt out, UInt significand,
-                              int significand_size) -> OutputIt {
-  return format_decimal<Char>(out, significand, significand_size).end;
-}
-template <typename Char, typename OutputIt, typename T, typename Grouping>
-FMT_CONSTEXPR20 auto write_significand(OutputIt out, T significand,
-                                       int significand_size, int exponent,
-                                       const Grouping& grouping) -> OutputIt {
-  if (!grouping.separator()) {
-    out = write_significand<Char>(out, significand, significand_size);
-    return detail::fill_n(out, exponent, static_cast<Char>('0'));
-  }
-  auto buffer = memory_buffer();
-  write_significand<char>(appender(buffer), significand, significand_size);
-  detail::fill_n(appender(buffer), exponent, '0');
-  return grouping.apply(out, string_view(buffer.data(), buffer.size()));
-}
-
-template <typename Char, typename UInt,
-          FMT_ENABLE_IF(std::is_integral<UInt>::value)>
-inline auto write_significand(Char* out, UInt significand, int significand_size,
-                              int integral_size, Char decimal_point) -> Char* {
-  if (!decimal_point)
-    return format_decimal(out, significand, significand_size).end;
-  out += significand_size + 1;
-  Char* end = out;
-  int floating_size = significand_size - integral_size;
-  for (int i = floating_size / 2; i > 0; --i) {
-    out -= 2;
-    copy2(out, digits2(significand % 100));
-    significand /= 100;
-  }
-  if (floating_size % 2 != 0) {
-    *--out = static_cast<Char>('0' + significand % 10);
-    significand /= 10;
-  }
-  *--out = decimal_point;
-  format_decimal(out - integral_size, significand, integral_size);
-  return end;
-}
-
-template <typename OutputIt, typename UInt, typename Char,
-          FMT_ENABLE_IF(!std::is_pointer<remove_cvref_t<OutputIt>>::value)>
-inline auto write_significand(OutputIt out, UInt significand,
-                              int significand_size, int integral_size,
-                              Char decimal_point) -> OutputIt {
-  // Buffer is large enough to hold digits (digits10 + 1) and a decimal point.
-  Char buffer[digits10<UInt>() + 2];
-  auto end = write_significand(buffer, significand, significand_size,
-                               integral_size, decimal_point);
-  return detail::copy_str_noinline<Char>(buffer, end, out);
-}
-
-template <typename OutputIt, typename Char>
-FMT_CONSTEXPR auto write_significand(OutputIt out, const char* significand,
-                                     int significand_size, int integral_size,
-                                     Char decimal_point) -> OutputIt {
-  out = detail::copy_str_noinline<Char>(significand,
-                                        significand + integral_size, out);
-  if (!decimal_point) return out;
-  *out++ = decimal_point;
-  return detail::copy_str_noinline<Char>(significand + integral_size,
-                                         significand + significand_size, out);
-}
-
-template <typename OutputIt, typename Char, typename T, typename Grouping>
-FMT_CONSTEXPR20 auto write_significand(OutputIt out, T significand,
-                                       int significand_size, int integral_size,
-                                       Char decimal_point,
-                                       const Grouping& grouping) -> OutputIt {
-  if (!grouping.separator()) {
-    return write_significand(out, significand, significand_size, integral_size,
-                             decimal_point);
-  }
-  auto buffer = basic_memory_buffer<Char>();
-  write_significand(buffer_appender<Char>(buffer), significand,
-                    significand_size, integral_size, decimal_point);
-  grouping.apply(
-      out, basic_string_view<Char>(buffer.data(), to_unsigned(integral_size)));
-  return detail::copy_str_noinline<Char>(buffer.data() + integral_size,
-                                         buffer.end(), out);
-}
-
-template <typename OutputIt, typename DecimalFP, typename Char,
-          typename Grouping = digit_grouping<Char>>
-FMT_CONSTEXPR20 auto do_write_float(OutputIt out, const DecimalFP& fp,
-                                    const basic_format_specs<Char>& specs,
-                                    float_specs fspecs, locale_ref loc)
-    -> OutputIt {
-  auto significand = fp.significand;
-  int significand_size = get_significand_size(fp);
-  constexpr Char zero = static_cast<Char>('0');
-  auto sign = fspecs.sign;
-  size_t size = to_unsigned(significand_size) + (sign ? 1 : 0);
-  using iterator = reserve_iterator<OutputIt>;
-
-  Char decimal_point =
-      fspecs.locale ? detail::decimal_point<Char>(loc) : static_cast<Char>('.');
-
-  int output_exp = fp.exponent + significand_size - 1;
-  auto use_exp_format = [=]() {
-    if (fspecs.format == float_format::exp) return true;
-    if (fspecs.format != float_format::general) return false;
-    // Use the fixed notation if the exponent is in [exp_lower, exp_upper),
-    // e.g. 0.0001 instead of 1e-04. Otherwise use the exponent notation.
-    const int exp_lower = -4, exp_upper = 16;
-    return output_exp < exp_lower ||
-           output_exp >= (fspecs.precision > 0 ? fspecs.precision : exp_upper);
-  };
-  if (use_exp_format()) {
-    int num_zeros = 0;
-    if (fspecs.showpoint) {
-      num_zeros = fspecs.precision - significand_size;
-      if (num_zeros < 0) num_zeros = 0;
-      size += to_unsigned(num_zeros);
-    } else if (significand_size == 1) {
-      decimal_point = Char();
-    }
-    auto abs_output_exp = output_exp >= 0 ? output_exp : -output_exp;
-    int exp_digits = 2;
-    if (abs_output_exp >= 100) exp_digits = abs_output_exp >= 1000 ? 4 : 3;
-
-    size += to_unsigned((decimal_point ? 1 : 0) + 2 + exp_digits);
-    char exp_char = fspecs.upper ? 'E' : 'e';
-    auto write = [=](iterator it) {
-      if (sign) *it++ = detail::sign<Char>(sign);
-      // Insert a decimal point after the first digit and add an exponent.
-      it = write_significand(it, significand, significand_size, 1,
-                             decimal_point);
-      if (num_zeros > 0) it = detail::fill_n(it, num_zeros, zero);
-      *it++ = static_cast<Char>(exp_char);
-      return write_exponent<Char>(output_exp, it);
-    };
-    return specs.width > 0 ? write_padded<align::right>(out, specs, size, write)
-                           : base_iterator(out, write(reserve(out, size)));
-  }
-
-  int exp = fp.exponent + significand_size;
-  if (fp.exponent >= 0) {
-    // 1234e5 -> 123400000[.0+]
-    size += to_unsigned(fp.exponent);
-    int num_zeros = fspecs.precision - exp;
-#ifdef FMT_FUZZ
-    if (num_zeros > 5000)
-      throw std::runtime_error("fuzz mode - avoiding excessive cpu use");
-#endif
-    if (fspecs.showpoint) {
-      if (num_zeros <= 0 && fspecs.format != float_format::fixed) num_zeros = 1;
-      if (num_zeros > 0) size += to_unsigned(num_zeros) + 1;
-    }
-    auto grouping = Grouping(loc, fspecs.locale);
-    size += to_unsigned(grouping.count_separators(significand_size));
-    return write_padded<align::right>(out, specs, size, [&](iterator it) {
-      if (sign) *it++ = detail::sign<Char>(sign);
-      it = write_significand<Char>(it, significand, significand_size,
-                                   fp.exponent, grouping);
-      if (!fspecs.showpoint) return it;
-      *it++ = decimal_point;
-      return num_zeros > 0 ? detail::fill_n(it, num_zeros, zero) : it;
-    });
-  } else if (exp > 0) {
-    // 1234e-2 -> 12.34[0+]
-    int num_zeros = fspecs.showpoint ? fspecs.precision - significand_size : 0;
-    size += 1 + to_unsigned(num_zeros > 0 ? num_zeros : 0);
-    auto grouping = Grouping(loc, fspecs.locale);
-    size += to_unsigned(grouping.count_separators(significand_size));
-    return write_padded<align::right>(out, specs, size, [&](iterator it) {
-      if (sign) *it++ = detail::sign<Char>(sign);
-      it = write_significand(it, significand, significand_size, exp,
-                             decimal_point, grouping);
-      return num_zeros > 0 ? detail::fill_n(it, num_zeros, zero) : it;
-    });
-  }
-  // 1234e-6 -> 0.001234
-  int num_zeros = -exp;
-  if (significand_size == 0 && fspecs.precision >= 0 &&
-      fspecs.precision < num_zeros) {
-    num_zeros = fspecs.precision;
-  }
-  bool pointy = num_zeros != 0 || significand_size != 0 || fspecs.showpoint;
-  size += 1 + (pointy ? 1 : 0) + to_unsigned(num_zeros);
-  return write_padded<align::right>(out, specs, size, [&](iterator it) {
-    if (sign) *it++ = detail::sign<Char>(sign);
-    *it++ = zero;
-    if (!pointy) return it;
-    *it++ = decimal_point;
-    it = detail::fill_n(it, num_zeros, zero);
-    return write_significand<Char>(it, significand, significand_size);
-  });
-}
-
-template <typename Char> class fallback_digit_grouping {
- public:
-  constexpr fallback_digit_grouping(locale_ref, bool) {}
-
-  constexpr Char separator() const { return Char(); }
-
-  constexpr int count_separators(int) const { return 0; }
-
-  template <typename Out, typename C>
-  constexpr Out apply(Out out, basic_string_view<C>) const {
-    return out;
-  }
-};
-
-template <typename OutputIt, typename DecimalFP, typename Char>
-FMT_CONSTEXPR20 auto write_float(OutputIt out, const DecimalFP& fp,
-                                 const basic_format_specs<Char>& specs,
-                                 float_specs fspecs, locale_ref loc)
-    -> OutputIt {
-  if (is_constant_evaluated()) {
-    return do_write_float<OutputIt, DecimalFP, Char,
-                          fallback_digit_grouping<Char>>(out, fp, specs, fspecs,
-                                                         loc);
-  } else {
-    return do_write_float(out, fp, specs, fspecs, loc);
-  }
-}
-
-template <typename T, FMT_ENABLE_IF(std::is_floating_point<T>::value)>
-FMT_CONSTEXPR20 bool isinf(T value) {
-  if (is_constant_evaluated()) {
-#if defined(__cpp_if_constexpr)
-    if constexpr (std::numeric_limits<double>::is_iec559) {
-      auto bits = detail::bit_cast<uint64_t>(static_cast<double>(value));
-      constexpr auto significand_bits =
-          dragonbox::float_info<double>::significand_bits;
-      return (bits & exponent_mask<double>()) &&
-             !(bits & ((uint64_t(1) << significand_bits) - 1));
-    }
-#endif
-  }
-  return std::isinf(value);
-}
-
-template <typename T, FMT_ENABLE_IF(std::is_floating_point<T>::value)>
-FMT_CONSTEXPR20 bool isfinite(T value) {
-  if (is_constant_evaluated()) {
-#if defined(__cpp_if_constexpr)
-    if constexpr (std::numeric_limits<double>::is_iec559) {
-      auto bits = detail::bit_cast<uint64_t>(static_cast<double>(value));
-      return (bits & exponent_mask<double>()) != exponent_mask<double>();
-    }
-#endif
-  }
-  return std::isfinite(value);
-}
-
-template <typename T, FMT_ENABLE_IF(std::is_floating_point<T>::value)>
-FMT_INLINE FMT_CONSTEXPR bool signbit(T value) {
-  if (is_constant_evaluated()) {
-#ifdef __cpp_if_constexpr
-    if constexpr (std::numeric_limits<double>::is_iec559) {
-      auto bits = detail::bit_cast<uint64_t>(static_cast<double>(value));
-      return (bits & (uint64_t(1) << (num_bits<uint64_t>() - 1))) != 0;
-    }
-#endif
-  }
-  return std::signbit(value);
-}
-
-template <typename Char, typename OutputIt, typename T,
-          FMT_ENABLE_IF(std::is_floating_point<T>::value)>
-FMT_CONSTEXPR20 auto write(OutputIt out, T value,
-                           basic_format_specs<Char> specs, locale_ref loc = {})
-    -> OutputIt {
-  if (const_check(!is_supported_floating_point(value))) return out;
-  float_specs fspecs = parse_float_type_spec(specs);
-  fspecs.sign = specs.sign;
-  if (detail::signbit(value)) {  // value < 0 is false for NaN so use signbit.
-    fspecs.sign = sign::minus;
-    value = -value;
-  } else if (fspecs.sign == sign::minus) {
-    fspecs.sign = sign::none;
-  }
-
-  if (!detail::isfinite(value))
-    return write_nonfinite(out, detail::isinf(value), specs, fspecs);
-
-  if (specs.align == align::numeric && fspecs.sign) {
-    auto it = reserve(out, 1);
-    *it++ = detail::sign<Char>(fspecs.sign);
-    out = base_iterator(out, it);
-    fspecs.sign = sign::none;
-    if (specs.width != 0) --specs.width;
-  }
-
-  memory_buffer buffer;
-  if (fspecs.format == float_format::hex) {
-    if (fspecs.sign) buffer.push_back(detail::sign<char>(fspecs.sign));
-    snprintf_float(promote_float(value), specs.precision, fspecs, buffer);
-    return write_bytes<align::right>(out, {buffer.data(), buffer.size()},
-                                     specs);
-  }
-  int precision = specs.precision >= 0 || specs.type == presentation_type::none
-                      ? specs.precision
-                      : 6;
-  if (fspecs.format == float_format::exp) {
-    if (precision == max_value<int>())
-      throw_format_error("number is too big");
-    else
-      ++precision;
-  }
-  if (const_check(std::is_same<T, float>())) fspecs.binary32 = true;
-  if (!is_fast_float<T>()) fspecs.fallback = true;
-  int exp = format_float(promote_float(value), precision, fspecs, buffer);
-  fspecs.precision = precision;
-  auto fp = big_decimal_fp{buffer.data(), static_cast<int>(buffer.size()), exp};
-  return write_float(out, fp, specs, fspecs, loc);
-}
-
-template <typename Char, typename OutputIt, typename T,
-          FMT_ENABLE_IF(is_fast_float<T>::value)>
-FMT_CONSTEXPR20 auto write(OutputIt out, T value) -> OutputIt {
-  if (is_constant_evaluated()) {
-    return write(out, value, basic_format_specs<Char>());
-  }
-
-  if (const_check(!is_supported_floating_point(value))) return out;
-
-  using floaty = conditional_t<std::is_same<T, long double>::value, double, T>;
-  using uint = typename dragonbox::float_info<floaty>::carrier_uint;
-  auto bits = bit_cast<uint>(value);
-
-  auto fspecs = float_specs();
-  if (detail::signbit(value)) {
-    fspecs.sign = sign::minus;
-    value = -value;
-  }
-
-  constexpr auto specs = basic_format_specs<Char>();
-  uint mask = exponent_mask<floaty>();
-  if ((bits & mask) == mask)
-    return write_nonfinite(out, std::isinf(value), specs, fspecs);
-
-  auto dec = dragonbox::to_decimal(static_cast<floaty>(value));
-  return write_float(out, dec, specs, fspecs, {});
-}
-
-template <typename Char, typename OutputIt, typename T,
-          FMT_ENABLE_IF(std::is_floating_point<T>::value &&
-                        !is_fast_float<T>::value)>
-inline auto write(OutputIt out, T value) -> OutputIt {
-  return write(out, value, basic_format_specs<Char>());
-}
-
-template <typename Char, typename OutputIt>
-auto write(OutputIt out, monostate, basic_format_specs<Char> = {},
-           locale_ref = {}) -> OutputIt {
-  FMT_ASSERT(false, "");
-  return out;
-}
-
-template <typename Char, typename OutputIt>
-FMT_CONSTEXPR auto write(OutputIt out, basic_string_view<Char> value)
-    -> OutputIt {
-  auto it = reserve(out, value.size());
-  it = copy_str_noinline<Char>(value.begin(), value.end(), it);
-  return base_iterator(out, it);
-}
-
-template <typename Char, typename OutputIt, typename T,
-          FMT_ENABLE_IF(is_string<T>::value)>
-constexpr auto write(OutputIt out, const T& value) -> OutputIt {
-  return write<Char>(out, to_string_view(value));
-}
-
-template <typename Char, typename OutputIt, typename T,
-          FMT_ENABLE_IF(is_integral<T>::value &&
-                        !std::is_same<T, bool>::value &&
-                        !std::is_same<T, Char>::value)>
-FMT_CONSTEXPR auto write(OutputIt out, T value) -> OutputIt {
-  auto abs_value = static_cast<uint32_or_64_or_128_t<T>>(value);
-  bool negative = is_negative(value);
-  // Don't do -abs_value since it trips unsigned-integer-overflow sanitizer.
-  if (negative) abs_value = ~abs_value + 1;
-  int num_digits = count_digits(abs_value);
-  auto size = (negative ? 1 : 0) + static_cast<size_t>(num_digits);
-  auto it = reserve(out, size);
-  if (auto ptr = to_pointer<Char>(it, size)) {
-    if (negative) *ptr++ = static_cast<Char>('-');
-    format_decimal<Char>(ptr, abs_value, num_digits);
-    return out;
-  }
-  if (negative) *it++ = static_cast<Char>('-');
-  it = format_decimal<Char>(it, abs_value, num_digits).end;
-  return base_iterator(out, it);
-}
-
-// FMT_ENABLE_IF() condition separated to workaround an MSVC bug.
-template <
-    typename Char, typename OutputIt, typename T,
-    bool check =
-        std::is_enum<T>::value && !std::is_same<T, Char>::value &&
-        mapped_type_constant<T, basic_format_context<OutputIt, Char>>::value !=
-            type::custom_type,
-    FMT_ENABLE_IF(check)>
-FMT_CONSTEXPR auto write(OutputIt out, T value) -> OutputIt {
-  return write<Char>(
-      out, static_cast<typename std::underlying_type<T>::type>(value));
-}
-
-template <typename Char, typename OutputIt, typename T,
-          FMT_ENABLE_IF(std::is_same<T, bool>::value)>
-FMT_CONSTEXPR auto write(OutputIt out, T value,
-                         const basic_format_specs<Char>& specs = {},
-                         locale_ref = {}) -> OutputIt {
-  return specs.type != presentation_type::none &&
-                 specs.type != presentation_type::string
-             ? write(out, value ? 1 : 0, specs, {})
-             : write_bytes(out, value ? "true" : "false", specs);
-}
-
-template <typename Char, typename OutputIt>
-FMT_CONSTEXPR auto write(OutputIt out, Char value) -> OutputIt {
-  auto it = reserve(out, 1);
-  *it++ = value;
-  return base_iterator(out, it);
-}
-
-template <typename Char, typename OutputIt>
-FMT_CONSTEXPR_CHAR_TRAITS auto write(OutputIt out, const Char* value)
-    -> OutputIt {
-  if (!value) {
-    throw_format_error("string pointer is null");
-  } else {
-    out = write(out, basic_string_view<Char>(value));
-  }
-  return out;
-}
-
-template <typename Char, typename OutputIt, typename T,
-          FMT_ENABLE_IF(std::is_same<T, void>::value)>
-auto write(OutputIt out, const T* value,
-           const basic_format_specs<Char>& specs = {}, locale_ref = {})
-    -> OutputIt {
-  check_pointer_type_spec(specs.type, error_handler());
-  return write_ptr<Char>(out, to_uintptr(value), &specs);
-}
-
-// A write overload that handles implicit conversions.
-template <typename Char, typename OutputIt, typename T,
-          typename Context = basic_format_context<OutputIt, Char>>
-FMT_CONSTEXPR auto write(OutputIt out, const T& value) -> enable_if_t<
-    std::is_class<T>::value && !is_string<T>::value &&
-        !std::is_same<T, Char>::value &&
-        !std::is_same<const T&,
-                      decltype(arg_mapper<Context>().map(value))>::value,
-    OutputIt> {
-  return write<Char>(out, arg_mapper<Context>().map(value));
-}
-
-template <typename Char, typename OutputIt, typename T,
-          typename Context = basic_format_context<OutputIt, Char>>
-FMT_CONSTEXPR auto write(OutputIt out, const T& value)
-    -> enable_if_t<mapped_type_constant<T, Context>::value == type::custom_type,
-                   OutputIt> {
-  using formatter_type =
-      conditional_t<has_formatter<T, Context>::value,
-                    typename Context::template formatter_type<T>,
-                    fallback_formatter<T, Char>>;
-  auto ctx = Context(out, {}, {});
-  return formatter_type().format(value, ctx);
-}
-
-// An argument visitor that formats the argument and writes it via the output
-// iterator. It's a class and not a generic lambda for compatibility with C++11.
-template <typename Char> struct default_arg_formatter {
-  using iterator = buffer_appender<Char>;
-  using context = buffer_context<Char>;
-
-  iterator out;
-  basic_format_args<context> args;
-  locale_ref loc;
-
-  template <typename T> auto operator()(T value) -> iterator {
-    return write<Char>(out, value);
-  }
-  auto operator()(typename basic_format_arg<context>::handle h) -> iterator {
-    basic_format_parse_context<Char> parse_ctx({});
-    context format_ctx(out, args, loc);
-    h.format(parse_ctx, format_ctx);
-    return format_ctx.out();
-  }
-};
-
-template <typename Char> struct arg_formatter {
-  using iterator = buffer_appender<Char>;
-  using context = buffer_context<Char>;
-
-  iterator out;
-  const basic_format_specs<Char>& specs;
-  locale_ref locale;
-
-  template <typename T>
-  FMT_CONSTEXPR FMT_INLINE auto operator()(T value) -> iterator {
-    return detail::write(out, value, specs, locale);
-  }
-  auto operator()(typename basic_format_arg<context>::handle) -> iterator {
-    // User-defined types are handled separately because they require access
-    // to the parse context.
-    return out;
-  }
-};
-
-template <typename Char> struct custom_formatter {
-  basic_format_parse_context<Char>& parse_ctx;
-  buffer_context<Char>& ctx;
-
-  void operator()(
-      typename basic_format_arg<buffer_context<Char>>::handle h) const {
-    h.format(parse_ctx, ctx);
-  }
-  template <typename T> void operator()(T) const {}
-};
-
-template <typename T>
-using is_integer =
-    bool_constant<is_integral<T>::value && !std::is_same<T, bool>::value &&
-                  !std::is_same<T, char>::value &&
-                  !std::is_same<T, wchar_t>::value>;
-
-template <typename ErrorHandler> class width_checker {
- public:
-  explicit FMT_CONSTEXPR width_checker(ErrorHandler& eh) : handler_(eh) {}
-
-  template <typename T, FMT_ENABLE_IF(is_integer<T>::value)>
-  FMT_CONSTEXPR auto operator()(T value) -> unsigned long long {
-    if (is_negative(value)) handler_.on_error("negative width");
-    return static_cast<unsigned long long>(value);
-  }
-
-  template <typename T, FMT_ENABLE_IF(!is_integer<T>::value)>
-  FMT_CONSTEXPR auto operator()(T) -> unsigned long long {
-    handler_.on_error("width is not integer");
-    return 0;
-  }
-
- private:
-  ErrorHandler& handler_;
-};
-
-template <typename ErrorHandler> class precision_checker {
- public:
-  explicit FMT_CONSTEXPR precision_checker(ErrorHandler& eh) : handler_(eh) {}
-
-  template <typename T, FMT_ENABLE_IF(is_integer<T>::value)>
-  FMT_CONSTEXPR auto operator()(T value) -> unsigned long long {
-    if (is_negative(value)) handler_.on_error("negative precision");
-    return static_cast<unsigned long long>(value);
-  }
-
-  template <typename T, FMT_ENABLE_IF(!is_integer<T>::value)>
-  FMT_CONSTEXPR auto operator()(T) -> unsigned long long {
-    handler_.on_error("precision is not integer");
-    return 0;
-  }
-
- private:
-  ErrorHandler& handler_;
-};
-
-template <template <typename> class Handler, typename FormatArg,
-          typename ErrorHandler>
-FMT_CONSTEXPR auto get_dynamic_spec(FormatArg arg, ErrorHandler eh) -> int {
-  unsigned long long value = visit_format_arg(Handler<ErrorHandler>(eh), arg);
-  if (value > to_unsigned(max_value<int>())) eh.on_error("number is too big");
-  return static_cast<int>(value);
-}
-
-template <typename Context, typename ID>
-FMT_CONSTEXPR auto get_arg(Context& ctx, ID id) ->
-    typename Context::format_arg {
-  auto arg = ctx.arg(id);
-  if (!arg) ctx.on_error("argument not found");
-  return arg;
-}
-
-// The standard format specifier handler with checking.
-template <typename Char> class specs_handler : public specs_setter<Char> {
- private:
-  basic_format_parse_context<Char>& parse_context_;
-  buffer_context<Char>& context_;
-
-  // This is only needed for compatibility with gcc 4.4.
-  using format_arg = basic_format_arg<buffer_context<Char>>;
-
-  FMT_CONSTEXPR auto get_arg(auto_id) -> format_arg {
-    return detail::get_arg(context_, parse_context_.next_arg_id());
-  }
-
-  FMT_CONSTEXPR auto get_arg(int arg_id) -> format_arg {
-    parse_context_.check_arg_id(arg_id);
-    return detail::get_arg(context_, arg_id);
-  }
-
-  FMT_CONSTEXPR auto get_arg(basic_string_view<Char> arg_id) -> format_arg {
-    parse_context_.check_arg_id(arg_id);
-    return detail::get_arg(context_, arg_id);
-  }
-
- public:
-  FMT_CONSTEXPR specs_handler(basic_format_specs<Char>& specs,
-                              basic_format_parse_context<Char>& parse_ctx,
-                              buffer_context<Char>& ctx)
-      : specs_setter<Char>(specs), parse_context_(parse_ctx), context_(ctx) {}
-
-  template <typename Id> FMT_CONSTEXPR void on_dynamic_width(Id arg_id) {
-    this->specs_.width = get_dynamic_spec<width_checker>(
-        get_arg(arg_id), context_.error_handler());
-  }
-
-  template <typename Id> FMT_CONSTEXPR void on_dynamic_precision(Id arg_id) {
-    this->specs_.precision = get_dynamic_spec<precision_checker>(
-        get_arg(arg_id), context_.error_handler());
-  }
-
-  void on_error(const char* message) { context_.on_error(message); }
-};
-
-template <template <typename> class Handler, typename Context>
-FMT_CONSTEXPR void handle_dynamic_spec(int& value,
-                                       arg_ref<typename Context::char_type> ref,
-                                       Context& ctx) {
-  switch (ref.kind) {
-  case arg_id_kind::none:
-    break;
-  case arg_id_kind::index:
-    value = detail::get_dynamic_spec<Handler>(ctx.arg(ref.val.index),
-                                              ctx.error_handler());
-    break;
-  case arg_id_kind::name:
-    value = detail::get_dynamic_spec<Handler>(ctx.arg(ref.val.name),
-                                              ctx.error_handler());
-    break;
-  }
-}
-
-#define FMT_STRING_IMPL(s, base, explicit)                                 \
-  [] {                                                                     \
-    /* Use the hidden visibility as a workaround for a GCC bug (#1973). */ \
-    /* Use a macro-like name to avoid shadowing warnings. */               \
-    struct FMT_GCC_VISIBILITY_HIDDEN FMT_COMPILE_STRING : base {           \
-      using char_type = fmt::remove_cvref_t<decltype(s[0])>;               \
-      FMT_MAYBE_UNUSED FMT_CONSTEXPR explicit                              \
-      operator fmt::basic_string_view<char_type>() const {                 \
-        return fmt::detail_exported::compile_string_to_view<char_type>(s); \
-      }                                                                    \
-    };                                                                     \
-    return FMT_COMPILE_STRING();                                           \
-  }()
-
-/**
-  \rst
-  Constructs a compile-time format string from a string literal *s*.
-
-  **Example**::
-
-    // A compile-time error because 'd' is an invalid specifier for strings.
-    std::string s = fmt::format(FMT_STRING("{:d}"), "foo");
-  \endrst
- */
-#define FMT_STRING(s) FMT_STRING_IMPL(s, fmt::compile_string, )
-
-#if FMT_USE_USER_DEFINED_LITERALS
-template <typename Char> struct udl_formatter {
-  basic_string_view<Char> str;
-
-  template <typename... T>
-  auto operator()(T&&... args) const -> std::basic_string<Char> {
-    return vformat(str, fmt::make_args_checked<T...>(str, args...));
-  }
-};
-
-#  if FMT_USE_NONTYPE_TEMPLATE_PARAMETERS
-template <typename T, typename Char, size_t N,
-          fmt::detail_exported::fixed_string<Char, N> Str>
-struct statically_named_arg : view {
-  static constexpr auto name = Str.data;
-
-  const T& value;
-  statically_named_arg(const T& v) : value(v) {}
-};
-
-template <typename T, typename Char, size_t N,
-          fmt::detail_exported::fixed_string<Char, N> Str>
-struct is_named_arg<statically_named_arg<T, Char, N, Str>> : std::true_type {};
-
-template <typename T, typename Char, size_t N,
-          fmt::detail_exported::fixed_string<Char, N> Str>
-struct is_statically_named_arg<statically_named_arg<T, Char, N, Str>>
-    : std::true_type {};
-
-template <typename Char, size_t N,
-          fmt::detail_exported::fixed_string<Char, N> Str>
-struct udl_arg {
-  template <typename T> auto operator=(T&& value) const {
-    return statically_named_arg<T, Char, N, Str>(std::forward<T>(value));
-  }
-};
-#  else
-template <typename Char> struct udl_arg {
-  const Char* str;
-
-  template <typename T> auto operator=(T&& value) const -> named_arg<Char, T> {
-    return {str, std::forward<T>(value)};
-  }
-};
-#  endif
-#endif  // FMT_USE_USER_DEFINED_LITERALS
-
-template <typename Locale, typename Char>
-auto vformat(const Locale& loc, basic_string_view<Char> format_str,
-             basic_format_args<buffer_context<type_identity_t<Char>>> args)
-    -> std::basic_string<Char> {
-  basic_memory_buffer<Char> buffer;
-  detail::vformat_to(buffer, format_str, args, detail::locale_ref(loc));
-  return {buffer.data(), buffer.size()};
-}
-
-using format_func = void (*)(detail::buffer<char>&, int, const char*);
-
-FMT_API void format_error_code(buffer<char>& out, int error_code,
-                               string_view message) FMT_NOEXCEPT;
-
-FMT_API void report_error(format_func func, int error_code,
-                          const char* message) FMT_NOEXCEPT;
-FMT_END_DETAIL_NAMESPACE
-
-FMT_API auto vsystem_error(int error_code, string_view format_str,
-                           format_args args) -> std::system_error;
-
-/**
- \rst
- Constructs :class:`std::system_error` with a message formatted with
- ``fmt::format(fmt, args...)``.
-  *error_code* is a system error code as given by ``errno``.
-
- **Example**::
-
-   // This throws std::system_error with the description
-   //   cannot open file 'madeup': No such file or directory
-   // or similar (system message may vary).
-   const char* filename = "madeup";
-   std::FILE* file = std::fopen(filename, "r");
-   if (!file)
-     throw fmt::system_error(errno, "cannot open file '{}'", filename);
- \endrst
-*/
-template <typename... T>
-auto system_error(int error_code, format_string<T...> fmt, T&&... args)
-    -> std::system_error {
-  return vsystem_error(error_code, fmt, fmt::make_format_args(args...));
-}
-
-/**
-  \rst
-  Formats an error message for an error returned by an operating system or a
-  language runtime, for example a file opening error, and writes it to *out*.
-  The format is the same as the one used by ``std::system_error(ec, message)``
-  where ``ec`` is ``std::error_code(error_code, std::generic_category()})``.
-  It is implementation-defined but normally looks like:
-
-  .. parsed-literal::
-     *<message>*: *<system-message>*
-
-  where *<message>* is the passed message and *<system-message>* is the system
-  message corresponding to the error code.
-  *error_code* is a system error code as given by ``errno``.
-  \endrst
- */
-FMT_API void format_system_error(detail::buffer<char>& out, int error_code,
-                                 const char* message) FMT_NOEXCEPT;
-
-// Reports a system error without throwing an exception.
-// Can be used to report errors from destructors.
-FMT_API void report_system_error(int error_code,
-                                 const char* message) FMT_NOEXCEPT;
-
-/** Fast integer formatter. */
-class format_int {
- private:
-  // Buffer should be large enough to hold all digits (digits10 + 1),
-  // a sign and a null character.
-  enum { buffer_size = std::numeric_limits<unsigned long long>::digits10 + 3 };
-  mutable char buffer_[buffer_size];
-  char* str_;
-
-  template <typename UInt> auto format_unsigned(UInt value) -> char* {
-    auto n = static_cast<detail::uint32_or_64_or_128_t<UInt>>(value);
-    return detail::format_decimal(buffer_, n, buffer_size - 1).begin;
-  }
-
-  template <typename Int> auto format_signed(Int value) -> char* {
-    auto abs_value = static_cast<detail::uint32_or_64_or_128_t<Int>>(value);
-    bool negative = value < 0;
-    if (negative) abs_value = 0 - abs_value;
-    auto begin = format_unsigned(abs_value);
-    if (negative) *--begin = '-';
-    return begin;
-  }
-
- public:
-  explicit format_int(int value) : str_(format_signed(value)) {}
-  explicit format_int(long value) : str_(format_signed(value)) {}
-  explicit format_int(long long value) : str_(format_signed(value)) {}
-  explicit format_int(unsigned value) : str_(format_unsigned(value)) {}
-  explicit format_int(unsigned long value) : str_(format_unsigned(value)) {}
-  explicit format_int(unsigned long long value)
-      : str_(format_unsigned(value)) {}
-
-  /** Returns the number of characters written to the output buffer. */
-  auto size() const -> size_t {
-    return detail::to_unsigned(buffer_ - str_ + buffer_size - 1);
-  }
-
-  /**
-    Returns a pointer to the output buffer content. No terminating null
-    character is appended.
-   */
-  auto data() const -> const char* { return str_; }
-
-  /**
-    Returns a pointer to the output buffer content with terminating null
-    character appended.
-   */
-  auto c_str() const -> const char* {
-    buffer_[buffer_size - 1] = '\0';
-    return str_;
-  }
-
-  /**
-    \rst
-    Returns the content of the output buffer as an ``std::string``.
-    \endrst
-   */
-  auto str() const -> std::string { return std::string(str_, size()); }
-};
-
-template <typename T, typename Char>
-template <typename FormatContext>
-FMT_CONSTEXPR FMT_INLINE auto
-formatter<T, Char,
-          enable_if_t<detail::type_constant<T, Char>::value !=
-                      detail::type::custom_type>>::format(const T& val,
-                                                          FormatContext& ctx)
-    const -> decltype(ctx.out()) {
-  if (specs_.width_ref.kind != detail::arg_id_kind::none ||
-      specs_.precision_ref.kind != detail::arg_id_kind::none) {
-    auto specs = specs_;
-    detail::handle_dynamic_spec<detail::width_checker>(specs.width,
-                                                       specs.width_ref, ctx);
-    detail::handle_dynamic_spec<detail::precision_checker>(
-        specs.precision, specs.precision_ref, ctx);
-    return detail::write<Char>(ctx.out(), val, specs, ctx.locale());
-  }
-  return detail::write<Char>(ctx.out(), val, specs_, ctx.locale());
-}
-
-#define FMT_FORMAT_AS(Type, Base)                                        \
-  template <typename Char>                                               \
-  struct formatter<Type, Char> : formatter<Base, Char> {                 \
-    template <typename FormatContext>                                    \
-    auto format(Type const& val, FormatContext& ctx) const               \
-        -> decltype(ctx.out()) {                                         \
-      return formatter<Base, Char>::format(static_cast<Base>(val), ctx); \
-    }                                                                    \
-  }
-
-FMT_FORMAT_AS(signed char, int);
-FMT_FORMAT_AS(unsigned char, unsigned);
-FMT_FORMAT_AS(short, int);
-FMT_FORMAT_AS(unsigned short, unsigned);
-FMT_FORMAT_AS(long, long long);
-FMT_FORMAT_AS(unsigned long, unsigned long long);
-FMT_FORMAT_AS(Char*, const Char*);
-FMT_FORMAT_AS(std::basic_string<Char>, basic_string_view<Char>);
-FMT_FORMAT_AS(std::nullptr_t, const void*);
-FMT_FORMAT_AS(detail::byte, unsigned char);
-FMT_FORMAT_AS(detail::std_string_view<Char>, basic_string_view<Char>);
-
-template <typename Char>
-struct formatter<void*, Char> : formatter<const void*, Char> {
-  template <typename FormatContext>
-  auto format(void* val, FormatContext& ctx) const -> decltype(ctx.out()) {
-    return formatter<const void*, Char>::format(val, ctx);
-  }
-};
-
-template <typename Char, size_t N>
-struct formatter<Char[N], Char> : formatter<basic_string_view<Char>, Char> {
-  template <typename FormatContext>
-  FMT_CONSTEXPR auto format(const Char* val, FormatContext& ctx) const
-      -> decltype(ctx.out()) {
-    return formatter<basic_string_view<Char>, Char>::format(val, ctx);
-  }
-};
-
-// A formatter for types known only at run time such as variant alternatives.
-//
-// Usage:
-//   using variant = std::variant<int, std::string>;
-//   template <>
-//   struct formatter<variant>: dynamic_formatter<> {
-//     auto format(const variant& v, format_context& ctx) {
-//       return visit([&](const auto& val) {
-//           return dynamic_formatter<>::format(val, ctx);
-//       }, v);
-//     }
-//   };
-template <typename Char = char> class dynamic_formatter {
- private:
-  detail::dynamic_format_specs<Char> specs_;
-  const Char* format_str_;
-
-  struct null_handler : detail::error_handler {
-    void on_align(align_t) {}
-    void on_sign(sign_t) {}
-    void on_hash() {}
-  };
-
-  template <typename Context> void handle_specs(Context& ctx) {
-    detail::handle_dynamic_spec<detail::width_checker>(specs_.width,
-                                                       specs_.width_ref, ctx);
-    detail::handle_dynamic_spec<detail::precision_checker>(
-        specs_.precision, specs_.precision_ref, ctx);
-  }
-
- public:
-  template <typename ParseContext>
-  FMT_CONSTEXPR auto parse(ParseContext& ctx) -> decltype(ctx.begin()) {
-    format_str_ = ctx.begin();
-    // Checks are deferred to formatting time when the argument type is known.
-    detail::dynamic_specs_handler<ParseContext> handler(specs_, ctx);
-    return detail::parse_format_specs(ctx.begin(), ctx.end(), handler);
-  }
-
-  template <typename T, typename FormatContext>
-  auto format(const T& val, FormatContext& ctx) -> decltype(ctx.out()) {
-    handle_specs(ctx);
-    detail::specs_checker<null_handler> checker(
-        null_handler(), detail::mapped_type_constant<T, FormatContext>::value);
-    checker.on_align(specs_.align);
-    if (specs_.sign != sign::none) checker.on_sign(specs_.sign);
-    if (specs_.alt) checker.on_hash();
-    if (specs_.precision >= 0) checker.end_precision();
-    return detail::write<Char>(ctx.out(), val, specs_, ctx.locale());
-  }
-};
-
-/**
-  \rst
-  Converts ``p`` to ``const void*`` for pointer formatting.
-
-  **Example**::
-
-    auto s = fmt::format("{}", fmt::ptr(p));
-  \endrst
- */
-template <typename T> auto ptr(T p) -> const void* {
-  static_assert(std::is_pointer<T>::value, "");
-  return detail::bit_cast<const void*>(p);
-}
-template <typename T> auto ptr(const std::unique_ptr<T>& p) -> const void* {
-  return p.get();
-}
-template <typename T> auto ptr(const std::shared_ptr<T>& p) -> const void* {
-  return p.get();
-}
-
-class bytes {
- private:
-  string_view data_;
-  friend struct formatter<bytes>;
-
- public:
-  explicit bytes(string_view data) : data_(data) {}
-};
-
-template <> struct formatter<bytes> {
- private:
-  detail::dynamic_format_specs<char> specs_;
-
- public:
-  template <typename ParseContext>
-  FMT_CONSTEXPR auto parse(ParseContext& ctx) -> decltype(ctx.begin()) {
-    using handler_type = detail::dynamic_specs_handler<ParseContext>;
-    detail::specs_checker<handler_type> handler(handler_type(specs_, ctx),
-                                                detail::type::string_type);
-    auto it = parse_format_specs(ctx.begin(), ctx.end(), handler);
-    detail::check_string_type_spec(specs_.type, ctx.error_handler());
-    return it;
-  }
-
-  template <typename FormatContext>
-  auto format(bytes b, FormatContext& ctx) -> decltype(ctx.out()) {
-    detail::handle_dynamic_spec<detail::width_checker>(specs_.width,
-                                                       specs_.width_ref, ctx);
-    detail::handle_dynamic_spec<detail::precision_checker>(
-        specs_.precision, specs_.precision_ref, ctx);
-    return detail::write_bytes(ctx.out(), b.data_, specs_);
-  }
-};
-
-// group_digits_view is not derived from view because it copies the argument.
-template <typename T> struct group_digits_view { T value; };
-
-/**
-  \rst
-  Returns a view that formats an integer value using ',' as a locale-independent
-  thousands separator.
-
-  **Example**::
-
-    fmt::print("{}", fmt::group_digits(12345));
-    // Output: "12,345"
-  \endrst
- */
-template <typename T> auto group_digits(T value) -> group_digits_view<T> {
-  return {value};
-}
-
-template <typename T> struct formatter<group_digits_view<T>> : formatter<T> {
- private:
-  detail::dynamic_format_specs<char> specs_;
-
- public:
-  template <typename ParseContext>
-  FMT_CONSTEXPR auto parse(ParseContext& ctx) -> decltype(ctx.begin()) {
-    using handler_type = detail::dynamic_specs_handler<ParseContext>;
-    detail::specs_checker<handler_type> handler(handler_type(specs_, ctx),
-                                                detail::type::int_type);
-    auto it = parse_format_specs(ctx.begin(), ctx.end(), handler);
-    detail::check_string_type_spec(specs_.type, ctx.error_handler());
-    return it;
-  }
-
-  template <typename FormatContext>
-  auto format(group_digits_view<T> t, FormatContext& ctx)
-      -> decltype(ctx.out()) {
-    detail::handle_dynamic_spec<detail::width_checker>(specs_.width,
-                                                       specs_.width_ref, ctx);
-    detail::handle_dynamic_spec<detail::precision_checker>(
-        specs_.precision, specs_.precision_ref, ctx);
-    return detail::write_int_localized(
-        ctx.out(), static_cast<detail::uint64_or_128_t<T>>(t.value), 0, specs_,
-        detail::digit_grouping<char>({"\3", ','}));
-  }
-};
-
-template <typename It, typename Sentinel, typename Char = char>
-struct join_view : detail::view {
-  It begin;
-  Sentinel end;
-  basic_string_view<Char> sep;
-
-  join_view(It b, Sentinel e, basic_string_view<Char> s)
-      : begin(b), end(e), sep(s) {}
-};
-
-template <typename It, typename Sentinel, typename Char>
-using arg_join FMT_DEPRECATED_ALIAS = join_view<It, Sentinel, Char>;
-
-template <typename It, typename Sentinel, typename Char>
-struct formatter<join_view<It, Sentinel, Char>, Char> {
- private:
-  using value_type =
-#ifdef __cpp_lib_ranges
-      std::iter_value_t<It>;
-#else
-      typename std::iterator_traits<It>::value_type;
-#endif
-  using context = buffer_context<Char>;
-  using mapper = detail::arg_mapper<context>;
-
-  template <typename T, FMT_ENABLE_IF(has_formatter<T, context>::value)>
-  static auto map(const T& value) -> const T& {
-    return value;
-  }
-  template <typename T, FMT_ENABLE_IF(!has_formatter<T, context>::value)>
-  static auto map(const T& value) -> decltype(mapper().map(value)) {
-    return mapper().map(value);
-  }
-
-  using formatter_type =
-      conditional_t<is_formattable<value_type, Char>::value,
-                    formatter<remove_cvref_t<decltype(map(
-                                  std::declval<const value_type&>()))>,
-                              Char>,
-                    detail::fallback_formatter<value_type, Char>>;
-
-  formatter_type value_formatter_;
-
- public:
-  template <typename ParseContext>
-  FMT_CONSTEXPR auto parse(ParseContext& ctx) -> decltype(ctx.begin()) {
-    return value_formatter_.parse(ctx);
-  }
-
-  template <typename FormatContext>
-  auto format(const join_view<It, Sentinel, Char>& value, FormatContext& ctx)
-      -> decltype(ctx.out()) {
-    auto it = value.begin;
-    auto out = ctx.out();
-    if (it != value.end) {
-      out = value_formatter_.format(map(*it), ctx);
-      ++it;
-      while (it != value.end) {
-        out = detail::copy_str<Char>(value.sep.begin(), value.sep.end(), out);
-        ctx.advance_to(out);
-        out = value_formatter_.format(map(*it), ctx);
-        ++it;
-      }
-    }
-    return out;
-  }
-};
-
-/**
-  Returns a view that formats the iterator range `[begin, end)` with elements
-  separated by `sep`.
- */
-template <typename It, typename Sentinel>
-auto join(It begin, Sentinel end, string_view sep) -> join_view<It, Sentinel> {
-  return {begin, end, sep};
-}
-
-/**
-  \rst
-  Returns a view that formats `range` with elements separated by `sep`.
-
-  **Example**::
-
-    std::vector<int> v = {1, 2, 3};
-    fmt::print("{}", fmt::join(v, ", "));
-    // Output: "1, 2, 3"
-
-  ``fmt::join`` applies passed format specifiers to the range elements::
-
-    fmt::print("{:02}", fmt::join(v, ", "));
-    // Output: "01, 02, 03"
-  \endrst
- */
-template <typename Range>
-auto join(Range&& range, string_view sep)
-    -> join_view<detail::iterator_t<Range>, detail::sentinel_t<Range>> {
-  return join(std::begin(range), std::end(range), sep);
-}
-
-/**
-  \rst
-  Converts *value* to ``std::string`` using the default format for type *T*.
-
-  **Example**::
-
-    #include <fmt/format.h>
-
-    std::string answer = fmt::to_string(42);
-  \endrst
- */
-template <typename T, FMT_ENABLE_IF(!std::is_integral<T>::value)>
-inline auto to_string(const T& value) -> std::string {
-  auto result = std::string();
-  detail::write<char>(std::back_inserter(result), value);
-  return result;
-}
-
-template <typename T, FMT_ENABLE_IF(std::is_integral<T>::value)>
-FMT_NODISCARD inline auto to_string(T value) -> std::string {
-  // The buffer should be large enough to store the number including the sign
-  // or "false" for bool.
-  constexpr int max_size = detail::digits10<T>() + 2;
-  char buffer[max_size > 5 ? static_cast<unsigned>(max_size) : 5];
-  char* begin = buffer;
-  return std::string(begin, detail::write<char>(begin, value));
-}
-
-template <typename Char, size_t SIZE>
-FMT_NODISCARD auto to_string(const basic_memory_buffer<Char, SIZE>& buf)
-    -> std::basic_string<Char> {
-  auto size = buf.size();
-  detail::assume(size < std::basic_string<Char>().max_size());
-  return std::basic_string<Char>(buf.data(), size);
-}
-
-FMT_BEGIN_DETAIL_NAMESPACE
-
-template <typename Char>
-void vformat_to(
-    buffer<Char>& buf, basic_string_view<Char> fmt,
-    basic_format_args<FMT_BUFFER_CONTEXT(type_identity_t<Char>)> args,
-    locale_ref loc) {
-  // workaround for msvc bug regarding name-lookup in module
-  // link names into function scope
-  using detail::arg_formatter;
-  using detail::buffer_appender;
-  using detail::custom_formatter;
-  using detail::default_arg_formatter;
-  using detail::get_arg;
-  using detail::locale_ref;
-  using detail::parse_format_specs;
-  using detail::specs_checker;
-  using detail::specs_handler;
-  using detail::to_unsigned;
-  using detail::type;
-  using detail::write;
-  auto out = buffer_appender<Char>(buf);
-  if (fmt.size() == 2 && equal2(fmt.data(), "{}")) {
-    auto arg = args.get(0);
-    if (!arg) error_handler().on_error("argument not found");
-    visit_format_arg(default_arg_formatter<Char>{out, args, loc}, arg);
-    return;
-  }
-
-  struct format_handler : error_handler {
-    basic_format_parse_context<Char> parse_context;
-    buffer_context<Char> context;
-
-    format_handler(buffer_appender<Char> out, basic_string_view<Char> str,
-                   basic_format_args<buffer_context<Char>> args, locale_ref loc)
-        : parse_context(str), context(out, args, loc) {}
-
-    void on_text(const Char* begin, const Char* end) {
-      auto text = basic_string_view<Char>(begin, to_unsigned(end - begin));
-      context.advance_to(write<Char>(context.out(), text));
-    }
-
-    FMT_CONSTEXPR auto on_arg_id() -> int {
-      return parse_context.next_arg_id();
-    }
-    FMT_CONSTEXPR auto on_arg_id(int id) -> int {
-      return parse_context.check_arg_id(id), id;
-    }
-    FMT_CONSTEXPR auto on_arg_id(basic_string_view<Char> id) -> int {
-      int arg_id = context.arg_id(id);
-      if (arg_id < 0) on_error("argument not found");
-      return arg_id;
-    }
-
-    FMT_INLINE void on_replacement_field(int id, const Char*) {
-      auto arg = get_arg(context, id);
-      context.advance_to(visit_format_arg(
-          default_arg_formatter<Char>{context.out(), context.args(),
-                                      context.locale()},
-          arg));
-    }
-
-    auto on_format_specs(int id, const Char* begin, const Char* end)
-        -> const Char* {
-      auto arg = get_arg(context, id);
-      if (arg.type() == type::custom_type) {
-        parse_context.advance_to(parse_context.begin() +
-                                 (begin - &*parse_context.begin()));
-        visit_format_arg(custom_formatter<Char>{parse_context, context}, arg);
-        return parse_context.begin();
-      }
-      auto specs = basic_format_specs<Char>();
-      specs_checker<specs_handler<Char>> handler(
-          specs_handler<Char>(specs, parse_context, context), arg.type());
-      begin = parse_format_specs(begin, end, handler);
-      if (begin == end || *begin != '}')
-        on_error("missing '}' in format string");
-      auto f = arg_formatter<Char>{context.out(), specs, context.locale()};
-      context.advance_to(visit_format_arg(f, arg));
-      return begin;
-    }
-  };
-  detail::parse_format_string<false>(fmt, format_handler(out, fmt, args, loc));
-}
-
-#ifndef FMT_HEADER_ONLY
-extern template FMT_API auto thousands_sep_impl<char>(locale_ref)
-    -> thousands_sep_result<char>;
-extern template FMT_API auto thousands_sep_impl<wchar_t>(locale_ref)
-    -> thousands_sep_result<wchar_t>;
-extern template FMT_API auto decimal_point_impl(locale_ref) -> char;
-extern template FMT_API auto decimal_point_impl(locale_ref) -> wchar_t;
-extern template auto format_float<double>(double value, int precision,
-                                          float_specs specs, buffer<char>& buf)
-    -> int;
-extern template auto format_float<long double>(long double value, int precision,
-                                               float_specs specs,
-                                               buffer<char>& buf) -> int;
-void snprintf_float(float, int, float_specs, buffer<char>&) = delete;
-extern template auto snprintf_float<double>(double value, int precision,
-                                            float_specs specs,
-                                            buffer<char>& buf) -> int;
-extern template auto snprintf_float<long double>(long double value,
-                                                 int precision,
-                                                 float_specs specs,
-                                                 buffer<char>& buf) -> int;
-#endif  // FMT_HEADER_ONLY
-
-FMT_END_DETAIL_NAMESPACE
-
-#if FMT_USE_USER_DEFINED_LITERALS
-inline namespace literals {
-/**
-  \rst
-  User-defined literal equivalent of :func:`fmt::arg`.
-
-  **Example**::
-
-    using namespace fmt::literals;
-    fmt::print("Elapsed time: {s:.2f} seconds", "s"_a=1.23);
-  \endrst
- */
-#  if FMT_USE_NONTYPE_TEMPLATE_PARAMETERS
-template <detail_exported::fixed_string Str>
-constexpr auto operator""_a()
-    -> detail::udl_arg<remove_cvref_t<decltype(Str.data[0])>,
-                       sizeof(Str.data) / sizeof(decltype(Str.data[0])), Str> {
-  return {};
-}
-#  else
-constexpr auto operator"" _a(const char* s, size_t) -> detail::udl_arg<char> {
-  return {s};
-}
-#  endif
-
-// DEPRECATED!
-// User-defined literal equivalent of fmt::format.
-FMT_DEPRECATED constexpr auto operator"" _format(const char* s, size_t n)
-    -> detail::udl_formatter<char> {
-  return {{s, n}};
-}
-}  // namespace literals
-#endif  // FMT_USE_USER_DEFINED_LITERALS
-
-template <typename Locale, FMT_ENABLE_IF(detail::is_locale<Locale>::value)>
-inline auto vformat(const Locale& loc, string_view fmt, format_args args)
-    -> std::string {
-  return detail::vformat(loc, fmt, args);
-}
-
-template <typename Locale, typename... T,
-          FMT_ENABLE_IF(detail::is_locale<Locale>::value)>
-inline auto format(const Locale& loc, format_string<T...> fmt, T&&... args)
-    -> std::string {
-  return vformat(loc, string_view(fmt), fmt::make_format_args(args...));
-}
-
-template <typename... T, size_t SIZE, typename Allocator>
-FMT_DEPRECATED auto format_to(basic_memory_buffer<char, SIZE, Allocator>& buf,
-                              format_string<T...> fmt, T&&... args)
-    -> appender {
-  detail::vformat_to(buf, string_view(fmt), fmt::make_format_args(args...));
-  return appender(buf);
-}
-
-template <typename OutputIt, typename Locale,
-          FMT_ENABLE_IF(detail::is_output_iterator<OutputIt, char>::value&&
-                            detail::is_locale<Locale>::value)>
-auto vformat_to(OutputIt out, const Locale& loc, string_view fmt,
-                format_args args) -> OutputIt {
-  using detail::get_buffer;
-  auto&& buf = get_buffer<char>(out);
-  detail::vformat_to(buf, fmt, args, detail::locale_ref(loc));
-  return detail::get_iterator(buf);
-}
-
-template <typename OutputIt, typename Locale, typename... T,
-          FMT_ENABLE_IF(detail::is_output_iterator<OutputIt, char>::value&&
-                            detail::is_locale<Locale>::value)>
-FMT_INLINE auto format_to(OutputIt out, const Locale& loc,
-                          format_string<T...> fmt, T&&... args) -> OutputIt {
-  return vformat_to(out, loc, fmt, fmt::make_format_args(args...));
-}
-
-FMT_MODULE_EXPORT_END
-FMT_END_NAMESPACE
-
-#ifdef FMT_DEPRECATED_INCLUDE_XCHAR
-#  include "xchar.h"
-#endif
-
-#ifdef FMT_HEADER_ONLY
-#  define FMT_FUNC inline
-#  include "format-inl.h"
-#else
-#  define FMT_FUNC
-#endif
-
-#endif  // FMT_FORMAT_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/locale.h b/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/locale.h
deleted file mode 100644
index 7571b52..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/locale.h
+++ /dev/null
@@ -1,2 +0,0 @@
-#include "xchar.h"
-#warning fmt/locale.h is deprecated, include fmt/format.h or fmt/xchar.h instead
diff --git a/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/os.h b/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/os.h
deleted file mode 100644
index b64f8bb..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/os.h
+++ /dev/null
@@ -1,527 +0,0 @@
-// Formatting library for C++ - optional OS-specific functionality
-//
-// Copyright (c) 2012 - present, Victor Zverovich
-// All rights reserved.
-//
-// For the license information refer to format.h.
-
-#ifndef FMT_OS_H_
-#define FMT_OS_H_
-
-#include <cerrno>
-#include <clocale>  // locale_t
-#include <cstddef>
-#include <cstdio>
-#include <cstdlib>       // strtod_l
-#include <system_error>  // std::system_error
-
-#if defined __APPLE__ || defined(__FreeBSD__)
-#  include <xlocale.h>  // for LC_NUMERIC_MASK on OS X
-#endif
-
-#include "format.h"
-
-#ifndef FMT_USE_FCNTL
-// UWP doesn't provide _pipe.
-#  if FMT_HAS_INCLUDE("winapifamily.h")
-#    include <winapifamily.h>
-#  endif
-#  if (FMT_HAS_INCLUDE(<fcntl.h>) || defined(__APPLE__) || \
-       defined(__linux__)) &&                              \
-      (!defined(WINAPI_FAMILY) ||                          \
-       (WINAPI_FAMILY == WINAPI_FAMILY_DESKTOP_APP))
-#    include <fcntl.h>  // for O_RDONLY
-#    define FMT_USE_FCNTL 1
-#  else
-#    define FMT_USE_FCNTL 0
-#  endif
-#endif
-
-#ifndef FMT_POSIX
-#  if defined(_WIN32) && !defined(__MINGW32__)
-// Fix warnings about deprecated symbols.
-#    define FMT_POSIX(call) _##call
-#  else
-#    define FMT_POSIX(call) call
-#  endif
-#endif
-
-// Calls to system functions are wrapped in FMT_SYSTEM for testability.
-#ifdef FMT_SYSTEM
-#  define FMT_POSIX_CALL(call) FMT_SYSTEM(call)
-#else
-#  define FMT_SYSTEM(call) ::call
-#  ifdef _WIN32
-// Fix warnings about deprecated symbols.
-#    define FMT_POSIX_CALL(call) ::_##call
-#  else
-#    define FMT_POSIX_CALL(call) ::call
-#  endif
-#endif
-
-// Retries the expression while it evaluates to error_result and errno
-// equals to EINTR.
-#ifndef _WIN32
-#  define FMT_RETRY_VAL(result, expression, error_result) \
-    do {                                                  \
-      (result) = (expression);                            \
-    } while ((result) == (error_result) && errno == EINTR)
-#else
-#  define FMT_RETRY_VAL(result, expression, error_result) result = (expression)
-#endif
-
-#define FMT_RETRY(result, expression) FMT_RETRY_VAL(result, expression, -1)
-
-FMT_BEGIN_NAMESPACE
-FMT_MODULE_EXPORT_BEGIN
-
-/**
-  \rst
-  A reference to a null-terminated string. It can be constructed from a C
-  string or ``std::string``.
-
-  You can use one of the following type aliases for common character types:
-
-  +---------------+-----------------------------+
-  | Type          | Definition                  |
-  +===============+=============================+
-  | cstring_view  | basic_cstring_view<char>    |
-  +---------------+-----------------------------+
-  | wcstring_view | basic_cstring_view<wchar_t> |
-  +---------------+-----------------------------+
-
-  This class is most useful as a parameter type to allow passing
-  different types of strings to a function, for example::
-
-    template <typename... Args>
-    std::string format(cstring_view format_str, const Args & ... args);
-
-    format("{}", 42);
-    format(std::string("{}"), 42);
-  \endrst
- */
-template <typename Char> class basic_cstring_view {
- private:
-  const Char* data_;
-
- public:
-  /** Constructs a string reference object from a C string. */
-  basic_cstring_view(const Char* s) : data_(s) {}
-
-  /**
-    \rst
-    Constructs a string reference from an ``std::string`` object.
-    \endrst
-   */
-  basic_cstring_view(const std::basic_string<Char>& s) : data_(s.c_str()) {}
-
-  /** Returns the pointer to a C string. */
-  const Char* c_str() const { return data_; }
-};
-
-using cstring_view = basic_cstring_view<char>;
-using wcstring_view = basic_cstring_view<wchar_t>;
-
-template <typename Char> struct formatter<std::error_code, Char> {
-  template <typename ParseContext>
-  FMT_CONSTEXPR auto parse(ParseContext& ctx) -> decltype(ctx.begin()) {
-    return ctx.begin();
-  }
-
-  template <typename FormatContext>
-  FMT_CONSTEXPR auto format(const std::error_code& ec, FormatContext& ctx) const
-      -> decltype(ctx.out()) {
-    auto out = ctx.out();
-    out = detail::write_bytes(out, ec.category().name(),
-                              basic_format_specs<Char>());
-    out = detail::write<Char>(out, Char(':'));
-    out = detail::write<Char>(out, ec.value());
-    return out;
-  }
-};
-
-#ifdef _WIN32
-FMT_API const std::error_category& system_category() FMT_NOEXCEPT;
-
-FMT_BEGIN_DETAIL_NAMESPACE
-// A converter from UTF-16 to UTF-8.
-// It is only provided for Windows since other systems support UTF-8 natively.
-class utf16_to_utf8 {
- private:
-  memory_buffer buffer_;
-
- public:
-  utf16_to_utf8() {}
-  FMT_API explicit utf16_to_utf8(basic_string_view<wchar_t> s);
-  operator string_view() const { return string_view(&buffer_[0], size()); }
-  size_t size() const { return buffer_.size() - 1; }
-  const char* c_str() const { return &buffer_[0]; }
-  std::string str() const { return std::string(&buffer_[0], size()); }
-
-  // Performs conversion returning a system error code instead of
-  // throwing exception on conversion error. This method may still throw
-  // in case of memory allocation error.
-  FMT_API int convert(basic_string_view<wchar_t> s);
-};
-
-FMT_API void format_windows_error(buffer<char>& out, int error_code,
-                                  const char* message) FMT_NOEXCEPT;
-FMT_END_DETAIL_NAMESPACE
-
-FMT_API std::system_error vwindows_error(int error_code, string_view format_str,
-                                         format_args args);
-
-/**
- \rst
- Constructs a :class:`std::system_error` object with the description
- of the form
-
- .. parsed-literal::
-   *<message>*: *<system-message>*
-
- where *<message>* is the formatted message and *<system-message>* is the
- system message corresponding to the error code.
- *error_code* is a Windows error code as given by ``GetLastError``.
- If *error_code* is not a valid error code such as -1, the system message
- will look like "error -1".
-
- **Example**::
-
-   // This throws a system_error with the description
-   //   cannot open file 'madeup': The system cannot find the file specified.
-   // or similar (system message may vary).
-   const char *filename = "madeup";
-   LPOFSTRUCT of = LPOFSTRUCT();
-   HFILE file = OpenFile(filename, &of, OF_READ);
-   if (file == HFILE_ERROR) {
-     throw fmt::windows_error(GetLastError(),
-                              "cannot open file '{}'", filename);
-   }
- \endrst
-*/
-template <typename... Args>
-std::system_error windows_error(int error_code, string_view message,
-                                const Args&... args) {
-  return vwindows_error(error_code, message, fmt::make_format_args(args...));
-}
-
-// Reports a Windows error without throwing an exception.
-// Can be used to report errors from destructors.
-FMT_API void report_windows_error(int error_code,
-                                  const char* message) FMT_NOEXCEPT;
-#else
-inline const std::error_category& system_category() FMT_NOEXCEPT {
-  return std::system_category();
-}
-#endif  // _WIN32
-
-// std::system is not available on some platforms such as iOS (#2248).
-#ifdef __OSX__
-template <typename S, typename... Args, typename Char = char_t<S>>
-void say(const S& format_str, Args&&... args) {
-  std::system(format("say \"{}\"", format(format_str, args...)).c_str());
-}
-#endif
-
-// A buffered file.
-class buffered_file {
- private:
-  FILE* file_;
-
-  friend class file;
-
-  explicit buffered_file(FILE* f) : file_(f) {}
-
- public:
-  buffered_file(const buffered_file&) = delete;
-  void operator=(const buffered_file&) = delete;
-
-  // Constructs a buffered_file object which doesn't represent any file.
-  buffered_file() FMT_NOEXCEPT : file_(nullptr) {}
-
-  // Destroys the object closing the file it represents if any.
-  FMT_API ~buffered_file() FMT_NOEXCEPT;
-
- public:
-  buffered_file(buffered_file&& other) FMT_NOEXCEPT : file_(other.file_) {
-    other.file_ = nullptr;
-  }
-
-  buffered_file& operator=(buffered_file&& other) {
-    close();
-    file_ = other.file_;
-    other.file_ = nullptr;
-    return *this;
-  }
-
-  // Opens a file.
-  FMT_API buffered_file(cstring_view filename, cstring_view mode);
-
-  // Closes the file.
-  FMT_API void close();
-
-  // Returns the pointer to a FILE object representing this file.
-  FILE* get() const FMT_NOEXCEPT { return file_; }
-
-  // We place parentheses around fileno to workaround a bug in some versions
-  // of MinGW that define fileno as a macro.
-  FMT_API int(fileno)() const;
-
-  void vprint(string_view format_str, format_args args) {
-    fmt::vprint(file_, format_str, args);
-  }
-
-  template <typename... Args>
-  inline void print(string_view format_str, const Args&... args) {
-    vprint(format_str, fmt::make_format_args(args...));
-  }
-};
-
-#if FMT_USE_FCNTL
-// A file. Closed file is represented by a file object with descriptor -1.
-// Methods that are not declared with FMT_NOEXCEPT may throw
-// fmt::system_error in case of failure. Note that some errors such as
-// closing the file multiple times will cause a crash on Windows rather
-// than an exception. You can get standard behavior by overriding the
-// invalid parameter handler with _set_invalid_parameter_handler.
-class file {
- private:
-  int fd_;  // File descriptor.
-
-  // Constructs a file object with a given descriptor.
-  explicit file(int fd) : fd_(fd) {}
-
- public:
-  // Possible values for the oflag argument to the constructor.
-  enum {
-    RDONLY = FMT_POSIX(O_RDONLY),  // Open for reading only.
-    WRONLY = FMT_POSIX(O_WRONLY),  // Open for writing only.
-    RDWR = FMT_POSIX(O_RDWR),      // Open for reading and writing.
-    CREATE = FMT_POSIX(O_CREAT),   // Create if the file doesn't exist.
-    APPEND = FMT_POSIX(O_APPEND),  // Open in append mode.
-    TRUNC = FMT_POSIX(O_TRUNC)     // Truncate the content of the file.
-  };
-
-  // Constructs a file object which doesn't represent any file.
-  file() FMT_NOEXCEPT : fd_(-1) {}
-
-  // Opens a file and constructs a file object representing this file.
-  FMT_API file(cstring_view path, int oflag);
-
- public:
-  file(const file&) = delete;
-  void operator=(const file&) = delete;
-
-  file(file&& other) FMT_NOEXCEPT : fd_(other.fd_) { other.fd_ = -1; }
-
-  // Move assignment is not noexcept because close may throw.
-  file& operator=(file&& other) {
-    close();
-    fd_ = other.fd_;
-    other.fd_ = -1;
-    return *this;
-  }
-
-  // Destroys the object closing the file it represents if any.
-  FMT_API ~file() FMT_NOEXCEPT;
-
-  // Returns the file descriptor.
-  int descriptor() const FMT_NOEXCEPT { return fd_; }
-
-  // Closes the file.
-  FMT_API void close();
-
-  // Returns the file size. The size has signed type for consistency with
-  // stat::st_size.
-  FMT_API long long size() const;
-
-  // Attempts to read count bytes from the file into the specified buffer.
-  FMT_API size_t read(void* buffer, size_t count);
-
-  // Attempts to write count bytes from the specified buffer to the file.
-  FMT_API size_t write(const void* buffer, size_t count);
-
-  // Duplicates a file descriptor with the dup function and returns
-  // the duplicate as a file object.
-  FMT_API static file dup(int fd);
-
-  // Makes fd be the copy of this file descriptor, closing fd first if
-  // necessary.
-  FMT_API void dup2(int fd);
-
-  // Makes fd be the copy of this file descriptor, closing fd first if
-  // necessary.
-  FMT_API void dup2(int fd, std::error_code& ec) FMT_NOEXCEPT;
-
-  // Creates a pipe setting up read_end and write_end file objects for reading
-  // and writing respectively.
-  FMT_API static void pipe(file& read_end, file& write_end);
-
-  // Creates a buffered_file object associated with this file and detaches
-  // this file object from the file.
-  FMT_API buffered_file fdopen(const char* mode);
-};
-
-// Returns the memory page size.
-long getpagesize();
-
-FMT_BEGIN_DETAIL_NAMESPACE
-
-struct buffer_size {
-  buffer_size() = default;
-  size_t value = 0;
-  buffer_size operator=(size_t val) const {
-    auto bs = buffer_size();
-    bs.value = val;
-    return bs;
-  }
-};
-
-struct ostream_params {
-  int oflag = file::WRONLY | file::CREATE | file::TRUNC;
-  size_t buffer_size = BUFSIZ > 32768 ? BUFSIZ : 32768;
-
-  ostream_params() {}
-
-  template <typename... T>
-  ostream_params(T... params, int new_oflag) : ostream_params(params...) {
-    oflag = new_oflag;
-  }
-
-  template <typename... T>
-  ostream_params(T... params, detail::buffer_size bs)
-      : ostream_params(params...) {
-    this->buffer_size = bs.value;
-  }
-
-// Intel has a bug that results in failure to deduce a constructor
-// for empty parameter packs.
-#  if defined(__INTEL_COMPILER) && __INTEL_COMPILER < 2000
-  ostream_params(int new_oflag) : oflag(new_oflag) {}
-  ostream_params(detail::buffer_size bs) : buffer_size(bs.value) {}
-#  endif
-};
-
-FMT_END_DETAIL_NAMESPACE
-
-// Added {} below to work around default constructor error known to
-// occur in Xcode versions 7.2.1 and 8.2.1.
-constexpr detail::buffer_size buffer_size{};
-
-/** A fast output stream which is not thread-safe. */
-class FMT_API ostream final : private detail::buffer<char> {
- private:
-  file file_;
-
-  void grow(size_t) override;
-
-  ostream(cstring_view path, const detail::ostream_params& params)
-      : file_(path, params.oflag) {
-    set(new char[params.buffer_size], params.buffer_size);
-  }
-
- public:
-  ostream(ostream&& other)
-      : detail::buffer<char>(other.data(), other.size(), other.capacity()),
-        file_(std::move(other.file_)) {
-    other.clear();
-    other.set(nullptr, 0);
-  }
-  ~ostream() {
-    flush();
-    delete[] data();
-  }
-
-  void flush() {
-    if (size() == 0) return;
-    file_.write(data(), size());
-    clear();
-  }
-
-  template <typename... T>
-  friend ostream output_file(cstring_view path, T... params);
-
-  void close() {
-    flush();
-    file_.close();
-  }
-
-  /**
-    Formats ``args`` according to specifications in ``fmt`` and writes the
-    output to the file.
-   */
-  template <typename... T> void print(format_string<T...> fmt, T&&... args) {
-    vformat_to(detail::buffer_appender<char>(*this), fmt,
-               fmt::make_format_args(args...));
-  }
-};
-
-/**
-  \rst
-  Opens a file for writing. Supported parameters passed in *params*:
-
-  * ``<integer>``: Flags passed to `open
-    <https://pubs.opengroup.org/onlinepubs/007904875/functions/open.html>`_
-    (``file::WRONLY | file::CREATE`` by default)
-  * ``buffer_size=<integer>``: Output buffer size
-
-  **Example**::
-
-    auto out = fmt::output_file("guide.txt");
-    out.print("Don't {}", "Panic");
-  \endrst
- */
-template <typename... T>
-inline ostream output_file(cstring_view path, T... params) {
-  return {path, detail::ostream_params(params...)};
-}
-#endif  // FMT_USE_FCNTL
-
-#ifdef FMT_LOCALE
-// A "C" numeric locale.
-class locale {
- private:
-#  ifdef _WIN32
-  using locale_t = _locale_t;
-
-  static void freelocale(locale_t loc) { _free_locale(loc); }
-
-  static double strtod_l(const char* nptr, char** endptr, _locale_t loc) {
-    return _strtod_l(nptr, endptr, loc);
-  }
-#  endif
-
-  locale_t locale_;
-
- public:
-  using type = locale_t;
-  locale(const locale&) = delete;
-  void operator=(const locale&) = delete;
-
-  locale() {
-#  ifndef _WIN32
-    locale_ = FMT_SYSTEM(newlocale(LC_NUMERIC_MASK, "C", nullptr));
-#  else
-    locale_ = _create_locale(LC_NUMERIC, "C");
-#  endif
-    if (!locale_) FMT_THROW(system_error(errno, "cannot create locale"));
-  }
-  ~locale() { freelocale(locale_); }
-
-  type get() const { return locale_; }
-
-  // Converts string to floating-point number and advances str past the end
-  // of the parsed input.
-  FMT_DEPRECATED double strtod(const char*& str) const {
-    char* end = nullptr;
-    double result = strtod_l(str, &end, locale_);
-    str = end;
-    return result;
-  }
-};
-using Locale FMT_DEPRECATED_ALIAS = locale;
-#endif  // FMT_LOCALE
-FMT_MODULE_EXPORT_END
-FMT_END_NAMESPACE
-
-#endif  // FMT_OS_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/ostream.h b/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/ostream.h
deleted file mode 100644
index 3d716ec..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/ostream.h
+++ /dev/null
@@ -1,135 +0,0 @@
-// Formatting library for C++ - std::ostream support
-//
-// Copyright (c) 2012 - present, Victor Zverovich
-// All rights reserved.
-//
-// For the license information refer to format.h.
-
-#ifndef FMT_OSTREAM_H_
-#define FMT_OSTREAM_H_
-
-#include <ostream>
-
-#include "format.h"
-
-FMT_BEGIN_NAMESPACE
-
-template <typename OutputIt, typename Char> class basic_printf_context;
-
-namespace detail {
-
-// Checks if T has a user-defined operator<<.
-template <typename T, typename Char, typename Enable = void>
-class is_streamable {
- private:
-  template <typename U>
-  static auto test(int)
-      -> bool_constant<sizeof(std::declval<std::basic_ostream<Char>&>()
-                              << std::declval<U>()) != 0>;
-
-  template <typename> static auto test(...) -> std::false_type;
-
-  using result = decltype(test<T>(0));
-
- public:
-  is_streamable() = default;
-
-  static const bool value = result::value;
-};
-
-// Formatting of built-in types and arrays is intentionally disabled because
-// it's handled by standard (non-ostream) formatters.
-template <typename T, typename Char>
-struct is_streamable<
-    T, Char,
-    enable_if_t<
-        std::is_arithmetic<T>::value || std::is_array<T>::value ||
-        std::is_pointer<T>::value || std::is_same<T, char8_type>::value ||
-        std::is_same<T, std::basic_string<Char>>::value ||
-        std::is_same<T, std_string_view<Char>>::value ||
-        (std::is_convertible<T, int>::value && !std::is_enum<T>::value)>>
-    : std::false_type {};
-
-// Write the content of buf to os.
-// It is a separate function rather than a part of vprint to simplify testing.
-template <typename Char>
-void write_buffer(std::basic_ostream<Char>& os, buffer<Char>& buf) {
-  const Char* buf_data = buf.data();
-  using unsigned_streamsize = std::make_unsigned<std::streamsize>::type;
-  unsigned_streamsize size = buf.size();
-  unsigned_streamsize max_size = to_unsigned(max_value<std::streamsize>());
-  do {
-    unsigned_streamsize n = size <= max_size ? size : max_size;
-    os.write(buf_data, static_cast<std::streamsize>(n));
-    buf_data += n;
-    size -= n;
-  } while (size != 0);
-}
-
-template <typename Char, typename T>
-void format_value(buffer<Char>& buf, const T& value,
-                  locale_ref loc = locale_ref()) {
-  auto&& format_buf = formatbuf<std::basic_streambuf<Char>>(buf);
-  auto&& output = std::basic_ostream<Char>(&format_buf);
-#if !defined(FMT_STATIC_THOUSANDS_SEPARATOR)
-  if (loc) output.imbue(loc.get<std::locale>());
-#endif
-  output << value;
-  output.exceptions(std::ios_base::failbit | std::ios_base::badbit);
-  buf.try_resize(buf.size());
-}
-
-// Formats an object of type T that has an overloaded ostream operator<<.
-template <typename T, typename Char>
-struct fallback_formatter<T, Char, enable_if_t<is_streamable<T, Char>::value>>
-    : private formatter<basic_string_view<Char>, Char> {
-  using formatter<basic_string_view<Char>, Char>::parse;
-
-  template <typename OutputIt>
-  auto format(const T& value, basic_format_context<OutputIt, Char>& ctx)
-      -> OutputIt {
-    auto buffer = basic_memory_buffer<Char>();
-    format_value(buffer, value, ctx.locale());
-    return formatter<basic_string_view<Char>, Char>::format(
-        {buffer.data(), buffer.size()}, ctx);
-  }
-
-  // DEPRECATED!
-  template <typename OutputIt>
-  auto format(const T& value, basic_printf_context<OutputIt, Char>& ctx)
-      -> OutputIt {
-    auto buffer = basic_memory_buffer<Char>();
-    format_value(buffer, value, ctx.locale());
-    return std::copy(buffer.begin(), buffer.end(), ctx.out());
-  }
-};
-}  // namespace detail
-
-FMT_MODULE_EXPORT
-template <typename Char>
-void vprint(std::basic_ostream<Char>& os, basic_string_view<Char> format_str,
-            basic_format_args<buffer_context<type_identity_t<Char>>> args) {
-  auto buffer = basic_memory_buffer<Char>();
-  detail::vformat_to(buffer, format_str, args);
-  detail::write_buffer(os, buffer);
-}
-
-/**
-  \rst
-  Prints formatted data to the stream *os*.
-
-  **Example**::
-
-    fmt::print(cerr, "Don't {}!", "panic");
-  \endrst
- */
-FMT_MODULE_EXPORT
-template <typename S, typename... Args,
-          typename Char = enable_if_t<detail::is_string<S>::value, char_t<S>>>
-void print(std::basic_ostream<Char>& os, const S& format_str, Args&&... args) {
-  vprint(os, to_string_view(format_str),
-         fmt::make_args_checked<Args...>(format_str, args...));
-}
-FMT_END_NAMESPACE
-
-#endif  // FMT_OSTREAM_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/printf.h b/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/printf.h
deleted file mode 100644
index 19d550f..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/printf.h
+++ /dev/null
@@ -1,657 +0,0 @@
-// Formatting library for C++ - legacy printf implementation
-//
-// Copyright (c) 2012 - 2016, Victor Zverovich
-// All rights reserved.
-//
-// For the license information refer to format.h.
-
-#ifndef FMT_PRINTF_H_
-#define FMT_PRINTF_H_
-
-#include <algorithm>  // std::max
-#include <limits>     // std::numeric_limits
-#include <ostream>
-
-#include "format.h"
-
-FMT_BEGIN_NAMESPACE
-FMT_MODULE_EXPORT_BEGIN
-
-template <typename T> struct printf_formatter { printf_formatter() = delete; };
-
-template <typename Char>
-class basic_printf_parse_context : public basic_format_parse_context<Char> {
-  using basic_format_parse_context<Char>::basic_format_parse_context;
-};
-
-template <typename OutputIt, typename Char> class basic_printf_context {
- private:
-  OutputIt out_;
-  basic_format_args<basic_printf_context> args_;
-
- public:
-  using char_type = Char;
-  using format_arg = basic_format_arg<basic_printf_context>;
-  using parse_context_type = basic_printf_parse_context<Char>;
-  template <typename T> using formatter_type = printf_formatter<T>;
-
-  /**
-    \rst
-    Constructs a ``printf_context`` object. References to the arguments are
-    stored in the context object so make sure they have appropriate lifetimes.
-    \endrst
-   */
-  basic_printf_context(OutputIt out,
-                       basic_format_args<basic_printf_context> args)
-      : out_(out), args_(args) {}
-
-  OutputIt out() { return out_; }
-  void advance_to(OutputIt it) { out_ = it; }
-
-  detail::locale_ref locale() { return {}; }
-
-  format_arg arg(int id) const { return args_.get(id); }
-
-  FMT_CONSTEXPR void on_error(const char* message) {
-    detail::error_handler().on_error(message);
-  }
-};
-
-FMT_BEGIN_DETAIL_NAMESPACE
-
-// Checks if a value fits in int - used to avoid warnings about comparing
-// signed and unsigned integers.
-template <bool IsSigned> struct int_checker {
-  template <typename T> static bool fits_in_int(T value) {
-    unsigned max = max_value<int>();
-    return value <= max;
-  }
-  static bool fits_in_int(bool) { return true; }
-};
-
-template <> struct int_checker<true> {
-  template <typename T> static bool fits_in_int(T value) {
-    return value >= (std::numeric_limits<int>::min)() &&
-           value <= max_value<int>();
-  }
-  static bool fits_in_int(int) { return true; }
-};
-
-class printf_precision_handler {
- public:
-  template <typename T, FMT_ENABLE_IF(std::is_integral<T>::value)>
-  int operator()(T value) {
-    if (!int_checker<std::numeric_limits<T>::is_signed>::fits_in_int(value))
-      FMT_THROW(format_error("number is too big"));
-    return (std::max)(static_cast<int>(value), 0);
-  }
-
-  template <typename T, FMT_ENABLE_IF(!std::is_integral<T>::value)>
-  int operator()(T) {
-    FMT_THROW(format_error("precision is not integer"));
-    return 0;
-  }
-};
-
-// An argument visitor that returns true iff arg is a zero integer.
-class is_zero_int {
- public:
-  template <typename T, FMT_ENABLE_IF(std::is_integral<T>::value)>
-  bool operator()(T value) {
-    return value == 0;
-  }
-
-  template <typename T, FMT_ENABLE_IF(!std::is_integral<T>::value)>
-  bool operator()(T) {
-    return false;
-  }
-};
-
-template <typename T> struct make_unsigned_or_bool : std::make_unsigned<T> {};
-
-template <> struct make_unsigned_or_bool<bool> { using type = bool; };
-
-template <typename T, typename Context> class arg_converter {
- private:
-  using char_type = typename Context::char_type;
-
-  basic_format_arg<Context>& arg_;
-  char_type type_;
-
- public:
-  arg_converter(basic_format_arg<Context>& arg, char_type type)
-      : arg_(arg), type_(type) {}
-
-  void operator()(bool value) {
-    if (type_ != 's') operator()<bool>(value);
-  }
-
-  template <typename U, FMT_ENABLE_IF(std::is_integral<U>::value)>
-  void operator()(U value) {
-    bool is_signed = type_ == 'd' || type_ == 'i';
-    using target_type = conditional_t<std::is_same<T, void>::value, U, T>;
-    if (const_check(sizeof(target_type) <= sizeof(int))) {
-      // Extra casts are used to silence warnings.
-      if (is_signed) {
-        arg_ = detail::make_arg<Context>(
-            static_cast<int>(static_cast<target_type>(value)));
-      } else {
-        using unsigned_type = typename make_unsigned_or_bool<target_type>::type;
-        arg_ = detail::make_arg<Context>(
-            static_cast<unsigned>(static_cast<unsigned_type>(value)));
-      }
-    } else {
-      if (is_signed) {
-        // glibc's printf doesn't sign extend arguments of smaller types:
-        //   std::printf("%lld", -42);  // prints "4294967254"
-        // but we don't have to do the same because it's a UB.
-        arg_ = detail::make_arg<Context>(static_cast<long long>(value));
-      } else {
-        arg_ = detail::make_arg<Context>(
-            static_cast<typename make_unsigned_or_bool<U>::type>(value));
-      }
-    }
-  }
-
-  template <typename U, FMT_ENABLE_IF(!std::is_integral<U>::value)>
-  void operator()(U) {}  // No conversion needed for non-integral types.
-};
-
-// Converts an integer argument to T for printf, if T is an integral type.
-// If T is void, the argument is converted to corresponding signed or unsigned
-// type depending on the type specifier: 'd' and 'i' - signed, other -
-// unsigned).
-template <typename T, typename Context, typename Char>
-void convert_arg(basic_format_arg<Context>& arg, Char type) {
-  visit_format_arg(arg_converter<T, Context>(arg, type), arg);
-}
-
-// Converts an integer argument to char for printf.
-template <typename Context> class char_converter {
- private:
-  basic_format_arg<Context>& arg_;
-
- public:
-  explicit char_converter(basic_format_arg<Context>& arg) : arg_(arg) {}
-
-  template <typename T, FMT_ENABLE_IF(std::is_integral<T>::value)>
-  void operator()(T value) {
-    arg_ = detail::make_arg<Context>(
-        static_cast<typename Context::char_type>(value));
-  }
-
-  template <typename T, FMT_ENABLE_IF(!std::is_integral<T>::value)>
-  void operator()(T) {}  // No conversion needed for non-integral types.
-};
-
-// An argument visitor that return a pointer to a C string if argument is a
-// string or null otherwise.
-template <typename Char> struct get_cstring {
-  template <typename T> const Char* operator()(T) { return nullptr; }
-  const Char* operator()(const Char* s) { return s; }
-};
-
-// Checks if an argument is a valid printf width specifier and sets
-// left alignment if it is negative.
-template <typename Char> class printf_width_handler {
- private:
-  using format_specs = basic_format_specs<Char>;
-
-  format_specs& specs_;
-
- public:
-  explicit printf_width_handler(format_specs& specs) : specs_(specs) {}
-
-  template <typename T, FMT_ENABLE_IF(std::is_integral<T>::value)>
-  unsigned operator()(T value) {
-    auto width = static_cast<uint32_or_64_or_128_t<T>>(value);
-    if (detail::is_negative(value)) {
-      specs_.align = align::left;
-      width = 0 - width;
-    }
-    unsigned int_max = max_value<int>();
-    if (width > int_max) FMT_THROW(format_error("number is too big"));
-    return static_cast<unsigned>(width);
-  }
-
-  template <typename T, FMT_ENABLE_IF(!std::is_integral<T>::value)>
-  unsigned operator()(T) {
-    FMT_THROW(format_error("width is not integer"));
-    return 0;
-  }
-};
-
-// The ``printf`` argument formatter.
-template <typename OutputIt, typename Char>
-class printf_arg_formatter : public arg_formatter<Char> {
- private:
-  using base = arg_formatter<Char>;
-  using context_type = basic_printf_context<OutputIt, Char>;
-  using format_specs = basic_format_specs<Char>;
-
-  context_type& context_;
-
-  OutputIt write_null_pointer(bool is_string = false) {
-    auto s = this->specs;
-    s.type = presentation_type::none;
-    return write_bytes(this->out, is_string ? "(null)" : "(nil)", s);
-  }
-
- public:
-  printf_arg_formatter(OutputIt iter, format_specs& s, context_type& ctx)
-      : base{iter, s, locale_ref()}, context_(ctx) {}
-
-  OutputIt operator()(monostate value) { return base::operator()(value); }
-
-  template <typename T, FMT_ENABLE_IF(detail::is_integral<T>::value)>
-  OutputIt operator()(T value) {
-    // MSVC2013 fails to compile separate overloads for bool and Char so use
-    // std::is_same instead.
-    if (std::is_same<T, Char>::value) {
-      format_specs fmt_specs = this->specs;
-      if (fmt_specs.type != presentation_type::none &&
-          fmt_specs.type != presentation_type::chr) {
-        return (*this)(static_cast<int>(value));
-      }
-      fmt_specs.sign = sign::none;
-      fmt_specs.alt = false;
-      fmt_specs.fill[0] = ' ';  // Ignore '0' flag for char types.
-      // align::numeric needs to be overwritten here since the '0' flag is
-      // ignored for non-numeric types
-      if (fmt_specs.align == align::none || fmt_specs.align == align::numeric)
-        fmt_specs.align = align::right;
-      return write<Char>(this->out, static_cast<Char>(value), fmt_specs);
-    }
-    return base::operator()(value);
-  }
-
-  template <typename T, FMT_ENABLE_IF(std::is_floating_point<T>::value)>
-  OutputIt operator()(T value) {
-    return base::operator()(value);
-  }
-
-  /** Formats a null-terminated C string. */
-  OutputIt operator()(const char* value) {
-    if (value) return base::operator()(value);
-    return write_null_pointer(this->specs.type != presentation_type::pointer);
-  }
-
-  /** Formats a null-terminated wide C string. */
-  OutputIt operator()(const wchar_t* value) {
-    if (value) return base::operator()(value);
-    return write_null_pointer(this->specs.type != presentation_type::pointer);
-  }
-
-  OutputIt operator()(basic_string_view<Char> value) {
-    return base::operator()(value);
-  }
-
-  /** Formats a pointer. */
-  OutputIt operator()(const void* value) {
-    return value ? base::operator()(value) : write_null_pointer();
-  }
-
-  /** Formats an argument of a custom (user-defined) type. */
-  OutputIt operator()(typename basic_format_arg<context_type>::handle handle) {
-    auto parse_ctx =
-        basic_printf_parse_context<Char>(basic_string_view<Char>());
-    handle.format(parse_ctx, context_);
-    return this->out;
-  }
-};
-
-template <typename Char>
-void parse_flags(basic_format_specs<Char>& specs, const Char*& it,
-                 const Char* end) {
-  for (; it != end; ++it) {
-    switch (*it) {
-    case '-':
-      specs.align = align::left;
-      break;
-    case '+':
-      specs.sign = sign::plus;
-      break;
-    case '0':
-      specs.fill[0] = '0';
-      break;
-    case ' ':
-      if (specs.sign != sign::plus) {
-        specs.sign = sign::space;
-      }
-      break;
-    case '#':
-      specs.alt = true;
-      break;
-    default:
-      return;
-    }
-  }
-}
-
-template <typename Char, typename GetArg>
-int parse_header(const Char*& it, const Char* end,
-                 basic_format_specs<Char>& specs, GetArg get_arg) {
-  int arg_index = -1;
-  Char c = *it;
-  if (c >= '0' && c <= '9') {
-    // Parse an argument index (if followed by '$') or a width possibly
-    // preceded with '0' flag(s).
-    int value = parse_nonnegative_int(it, end, -1);
-    if (it != end && *it == '$') {  // value is an argument index
-      ++it;
-      arg_index = value != -1 ? value : max_value<int>();
-    } else {
-      if (c == '0') specs.fill[0] = '0';
-      if (value != 0) {
-        // Nonzero value means that we parsed width and don't need to
-        // parse it or flags again, so return now.
-        if (value == -1) FMT_THROW(format_error("number is too big"));
-        specs.width = value;
-        return arg_index;
-      }
-    }
-  }
-  parse_flags(specs, it, end);
-  // Parse width.
-  if (it != end) {
-    if (*it >= '0' && *it <= '9') {
-      specs.width = parse_nonnegative_int(it, end, -1);
-      if (specs.width == -1) FMT_THROW(format_error("number is too big"));
-    } else if (*it == '*') {
-      ++it;
-      specs.width = static_cast<int>(visit_format_arg(
-          detail::printf_width_handler<Char>(specs), get_arg(-1)));
-    }
-  }
-  return arg_index;
-}
-
-template <typename Char, typename Context>
-void vprintf(buffer<Char>& buf, basic_string_view<Char> format,
-             basic_format_args<Context> args) {
-  using OutputIt = buffer_appender<Char>;
-  auto out = OutputIt(buf);
-  auto context = basic_printf_context<OutputIt, Char>(out, args);
-  auto parse_ctx = basic_printf_parse_context<Char>(format);
-
-  // Returns the argument with specified index or, if arg_index is -1, the next
-  // argument.
-  auto get_arg = [&](int arg_index) {
-    if (arg_index < 0)
-      arg_index = parse_ctx.next_arg_id();
-    else
-      parse_ctx.check_arg_id(--arg_index);
-    return detail::get_arg(context, arg_index);
-  };
-
-  const Char* start = parse_ctx.begin();
-  const Char* end = parse_ctx.end();
-  auto it = start;
-  while (it != end) {
-    if (!detail::find<false, Char>(it, end, '%', it)) {
-      it = end;  // detail::find leaves it == nullptr if it doesn't find '%'
-      break;
-    }
-    Char c = *it++;
-    if (it != end && *it == c) {
-      out = detail::write(
-          out, basic_string_view<Char>(start, detail::to_unsigned(it - start)));
-      start = ++it;
-      continue;
-    }
-    out = detail::write(out, basic_string_view<Char>(
-                                 start, detail::to_unsigned(it - 1 - start)));
-
-    basic_format_specs<Char> specs;
-    specs.align = align::right;
-
-    // Parse argument index, flags and width.
-    int arg_index = parse_header(it, end, specs, get_arg);
-    if (arg_index == 0) parse_ctx.on_error("argument not found");
-
-    // Parse precision.
-    if (it != end && *it == '.') {
-      ++it;
-      c = it != end ? *it : 0;
-      if ('0' <= c && c <= '9') {
-        specs.precision = parse_nonnegative_int(it, end, 0);
-      } else if (c == '*') {
-        ++it;
-        specs.precision = static_cast<int>(
-            visit_format_arg(detail::printf_precision_handler(), get_arg(-1)));
-      } else {
-        specs.precision = 0;
-      }
-    }
-
-    auto arg = get_arg(arg_index);
-    // For d, i, o, u, x, and X conversion specifiers, if a precision is
-    // specified, the '0' flag is ignored
-    if (specs.precision >= 0 && arg.is_integral())
-      specs.fill[0] =
-          ' ';  // Ignore '0' flag for non-numeric types or if '-' present.
-    if (specs.precision >= 0 && arg.type() == detail::type::cstring_type) {
-      auto str = visit_format_arg(detail::get_cstring<Char>(), arg);
-      auto str_end = str + specs.precision;
-      auto nul = std::find(str, str_end, Char());
-      arg = detail::make_arg<basic_printf_context<OutputIt, Char>>(
-          basic_string_view<Char>(
-              str, detail::to_unsigned(nul != str_end ? nul - str
-                                                      : specs.precision)));
-    }
-    if (specs.alt && visit_format_arg(detail::is_zero_int(), arg))
-      specs.alt = false;
-    if (specs.fill[0] == '0') {
-      if (arg.is_arithmetic() && specs.align != align::left)
-        specs.align = align::numeric;
-      else
-        specs.fill[0] = ' ';  // Ignore '0' flag for non-numeric types or if '-'
-                              // flag is also present.
-    }
-
-    // Parse length and convert the argument to the required type.
-    c = it != end ? *it++ : 0;
-    Char t = it != end ? *it : 0;
-    using detail::convert_arg;
-    switch (c) {
-    case 'h':
-      if (t == 'h') {
-        ++it;
-        t = it != end ? *it : 0;
-        convert_arg<signed char>(arg, t);
-      } else {
-        convert_arg<short>(arg, t);
-      }
-      break;
-    case 'l':
-      if (t == 'l') {
-        ++it;
-        t = it != end ? *it : 0;
-        convert_arg<long long>(arg, t);
-      } else {
-        convert_arg<long>(arg, t);
-      }
-      break;
-    case 'j':
-      convert_arg<intmax_t>(arg, t);
-      break;
-    case 'z':
-      convert_arg<size_t>(arg, t);
-      break;
-    case 't':
-      convert_arg<std::ptrdiff_t>(arg, t);
-      break;
-    case 'L':
-      // printf produces garbage when 'L' is omitted for long double, no
-      // need to do the same.
-      break;
-    default:
-      --it;
-      convert_arg<void>(arg, c);
-    }
-
-    // Parse type.
-    if (it == end) FMT_THROW(format_error("invalid format string"));
-    char type = static_cast<char>(*it++);
-    if (arg.is_integral()) {
-      // Normalize type.
-      switch (type) {
-      case 'i':
-      case 'u':
-        type = 'd';
-        break;
-      case 'c':
-        visit_format_arg(
-            detail::char_converter<basic_printf_context<OutputIt, Char>>(arg),
-            arg);
-        break;
-      }
-    }
-    specs.type = parse_presentation_type(type);
-    if (specs.type == presentation_type::none)
-      parse_ctx.on_error("invalid type specifier");
-
-    start = it;
-
-    // Format argument.
-    out = visit_format_arg(
-        detail::printf_arg_formatter<OutputIt, Char>(out, specs, context), arg);
-  }
-  detail::write(out, basic_string_view<Char>(start, to_unsigned(it - start)));
-}
-FMT_END_DETAIL_NAMESPACE
-
-template <typename Char>
-using basic_printf_context_t =
-    basic_printf_context<detail::buffer_appender<Char>, Char>;
-
-using printf_context = basic_printf_context_t<char>;
-using wprintf_context = basic_printf_context_t<wchar_t>;
-
-using printf_args = basic_format_args<printf_context>;
-using wprintf_args = basic_format_args<wprintf_context>;
-
-/**
-  \rst
-  Constructs an `~fmt::format_arg_store` object that contains references to
-  arguments and can be implicitly converted to `~fmt::printf_args`.
-  \endrst
- */
-template <typename... T>
-inline auto make_printf_args(const T&... args)
-    -> format_arg_store<printf_context, T...> {
-  return {args...};
-}
-
-/**
-  \rst
-  Constructs an `~fmt::format_arg_store` object that contains references to
-  arguments and can be implicitly converted to `~fmt::wprintf_args`.
-  \endrst
- */
-template <typename... T>
-inline auto make_wprintf_args(const T&... args)
-    -> format_arg_store<wprintf_context, T...> {
-  return {args...};
-}
-
-template <typename S, typename Char = char_t<S>>
-inline auto vsprintf(
-    const S& fmt,
-    basic_format_args<basic_printf_context_t<type_identity_t<Char>>> args)
-    -> std::basic_string<Char> {
-  basic_memory_buffer<Char> buffer;
-  vprintf(buffer, to_string_view(fmt), args);
-  return to_string(buffer);
-}
-
-/**
-  \rst
-  Formats arguments and returns the result as a string.
-
-  **Example**::
-
-    std::string message = fmt::sprintf("The answer is %d", 42);
-  \endrst
-*/
-template <typename S, typename... T,
-          typename Char = enable_if_t<detail::is_string<S>::value, char_t<S>>>
-inline auto sprintf(const S& fmt, const T&... args) -> std::basic_string<Char> {
-  using context = basic_printf_context_t<Char>;
-  return vsprintf(to_string_view(fmt), fmt::make_format_args<context>(args...));
-}
-
-template <typename S, typename Char = char_t<S>>
-inline auto vfprintf(
-    std::FILE* f, const S& fmt,
-    basic_format_args<basic_printf_context_t<type_identity_t<Char>>> args)
-    -> int {
-  basic_memory_buffer<Char> buffer;
-  vprintf(buffer, to_string_view(fmt), args);
-  size_t size = buffer.size();
-  return std::fwrite(buffer.data(), sizeof(Char), size, f) < size
-             ? -1
-             : static_cast<int>(size);
-}
-
-/**
-  \rst
-  Prints formatted data to the file *f*.
-
-  **Example**::
-
-    fmt::fprintf(stderr, "Don't %s!", "panic");
-  \endrst
- */
-template <typename S, typename... T, typename Char = char_t<S>>
-inline auto fprintf(std::FILE* f, const S& fmt, const T&... args) -> int {
-  using context = basic_printf_context_t<Char>;
-  return vfprintf(f, to_string_view(fmt),
-                  fmt::make_format_args<context>(args...));
-}
-
-template <typename S, typename Char = char_t<S>>
-inline auto vprintf(
-    const S& fmt,
-    basic_format_args<basic_printf_context_t<type_identity_t<Char>>> args)
-    -> int {
-  return vfprintf(stdout, to_string_view(fmt), args);
-}
-
-/**
-  \rst
-  Prints formatted data to ``stdout``.
-
-  **Example**::
-
-    fmt::printf("Elapsed time: %.2f seconds", 1.23);
-  \endrst
- */
-template <typename S, typename... T, FMT_ENABLE_IF(detail::is_string<S>::value)>
-inline auto printf(const S& fmt, const T&... args) -> int {
-  return vprintf(
-      to_string_view(fmt),
-      fmt::make_format_args<basic_printf_context_t<char_t<S>>>(args...));
-}
-
-template <typename S, typename Char = char_t<S>>
-FMT_DEPRECATED auto vfprintf(
-    std::basic_ostream<Char>& os, const S& fmt,
-    basic_format_args<basic_printf_context_t<type_identity_t<Char>>> args)
-    -> int {
-  basic_memory_buffer<Char> buffer;
-  vprintf(buffer, to_string_view(fmt), args);
-  os.write(buffer.data(), static_cast<std::streamsize>(buffer.size()));
-  return static_cast<int>(buffer.size());
-}
-template <typename S, typename... T, typename Char = char_t<S>>
-FMT_DEPRECATED auto fprintf(std::basic_ostream<Char>& os, const S& fmt,
-                            const T&... args) -> int {
-  return vfprintf(os, to_string_view(fmt),
-                  fmt::make_format_args<basic_printf_context_t<Char>>(args...));
-}
-
-FMT_MODULE_EXPORT_END
-FMT_END_NAMESPACE
-
-#endif  // FMT_PRINTF_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/ranges.h b/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/ranges.h
deleted file mode 100644
index eb9fb8a..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/ranges.h
+++ /dev/null
@@ -1,793 +0,0 @@
-// Formatting library for C++ - experimental range support
-//
-// Copyright (c) 2012 - present, Victor Zverovich
-// All rights reserved.
-//
-// For the license information refer to format.h.
-//
-// Copyright (c) 2018 - present, Remotion (Igor Schulz)
-// All Rights Reserved
-// {fmt} support for ranges, containers and types tuple interface.
-
-#ifndef FMT_RANGES_H_
-#define FMT_RANGES_H_
-
-#include <initializer_list>
-#include <tuple>
-#include <type_traits>
-
-#include "format.h"
-
-FMT_BEGIN_NAMESPACE
-
-namespace detail {
-
-template <typename RangeT, typename OutputIterator>
-OutputIterator copy(const RangeT& range, OutputIterator out) {
-  for (auto it = range.begin(), end = range.end(); it != end; ++it)
-    *out++ = *it;
-  return out;
-}
-
-template <typename OutputIterator>
-OutputIterator copy(const char* str, OutputIterator out) {
-  while (*str) *out++ = *str++;
-  return out;
-}
-
-template <typename OutputIterator>
-OutputIterator copy(char ch, OutputIterator out) {
-  *out++ = ch;
-  return out;
-}
-
-template <typename OutputIterator>
-OutputIterator copy(wchar_t ch, OutputIterator out) {
-  *out++ = ch;
-  return out;
-}
-
-// Returns true if T has a std::string-like interface, like std::string_view.
-template <typename T> class is_std_string_like {
-  template <typename U>
-  static auto check(U* p)
-      -> decltype((void)p->find('a'), p->length(), (void)p->data(), int());
-  template <typename> static void check(...);
-
- public:
-  static FMT_CONSTEXPR_DECL const bool value =
-      is_string<T>::value ||
-      std::is_convertible<T, std_string_view<char>>::value ||
-      !std::is_void<decltype(check<T>(nullptr))>::value;
-};
-
-template <typename Char>
-struct is_std_string_like<fmt::basic_string_view<Char>> : std::true_type {};
-
-template <typename T> class is_map {
-  template <typename U> static auto check(U*) -> typename U::mapped_type;
-  template <typename> static void check(...);
-
- public:
-#ifdef FMT_FORMAT_MAP_AS_LIST
-  static FMT_CONSTEXPR_DECL const bool value = false;
-#else
-  static FMT_CONSTEXPR_DECL const bool value =
-      !std::is_void<decltype(check<T>(nullptr))>::value;
-#endif
-};
-
-template <typename T> class is_set {
-  template <typename U> static auto check(U*) -> typename U::key_type;
-  template <typename> static void check(...);
-
- public:
-#ifdef FMT_FORMAT_SET_AS_LIST
-  static FMT_CONSTEXPR_DECL const bool value = false;
-#else
-  static FMT_CONSTEXPR_DECL const bool value =
-      !std::is_void<decltype(check<T>(nullptr))>::value && !is_map<T>::value;
-#endif
-};
-
-template <typename... Ts> struct conditional_helper {};
-
-template <typename T, typename _ = void> struct is_range_ : std::false_type {};
-
-#if !FMT_MSC_VER || FMT_MSC_VER > 1800
-
-#  define FMT_DECLTYPE_RETURN(val)  \
-    ->decltype(val) { return val; } \
-    static_assert(                  \
-        true, "")  // This makes it so that a semicolon is required after the
-                   // macro, which helps clang-format handle the formatting.
-
-// C array overload
-template <typename T, std::size_t N>
-auto range_begin(const T (&arr)[N]) -> const T* {
-  return arr;
-}
-template <typename T, std::size_t N>
-auto range_end(const T (&arr)[N]) -> const T* {
-  return arr + N;
-}
-
-template <typename T, typename Enable = void>
-struct has_member_fn_begin_end_t : std::false_type {};
-
-template <typename T>
-struct has_member_fn_begin_end_t<T, void_t<decltype(std::declval<T>().begin()),
-                                           decltype(std::declval<T>().end())>>
-    : std::true_type {};
-
-// Member function overload
-template <typename T>
-auto range_begin(T&& rng) FMT_DECLTYPE_RETURN(static_cast<T&&>(rng).begin());
-template <typename T>
-auto range_end(T&& rng) FMT_DECLTYPE_RETURN(static_cast<T&&>(rng).end());
-
-// ADL overload. Only participates in overload resolution if member functions
-// are not found.
-template <typename T>
-auto range_begin(T&& rng)
-    -> enable_if_t<!has_member_fn_begin_end_t<T&&>::value,
-                   decltype(begin(static_cast<T&&>(rng)))> {
-  return begin(static_cast<T&&>(rng));
-}
-template <typename T>
-auto range_end(T&& rng) -> enable_if_t<!has_member_fn_begin_end_t<T&&>::value,
-                                       decltype(end(static_cast<T&&>(rng)))> {
-  return end(static_cast<T&&>(rng));
-}
-
-template <typename T, typename Enable = void>
-struct has_const_begin_end : std::false_type {};
-template <typename T, typename Enable = void>
-struct has_mutable_begin_end : std::false_type {};
-
-template <typename T>
-struct has_const_begin_end<
-    T,
-    void_t<
-        decltype(detail::range_begin(std::declval<const remove_cvref_t<T>&>())),
-        decltype(detail::range_end(std::declval<const remove_cvref_t<T>&>()))>>
-    : std::true_type {};
-
-template <typename T>
-struct has_mutable_begin_end<
-    T, void_t<decltype(detail::range_begin(std::declval<T>())),
-              decltype(detail::range_end(std::declval<T>())),
-              enable_if_t<std::is_copy_constructible<T>::value>>>
-    : std::true_type {};
-
-template <typename T>
-struct is_range_<T, void>
-    : std::integral_constant<bool, (has_const_begin_end<T>::value ||
-                                    has_mutable_begin_end<T>::value)> {};
-#  undef FMT_DECLTYPE_RETURN
-#endif
-
-// tuple_size and tuple_element check.
-template <typename T> class is_tuple_like_ {
-  template <typename U>
-  static auto check(U* p) -> decltype(std::tuple_size<U>::value, int());
-  template <typename> static void check(...);
-
- public:
-  static FMT_CONSTEXPR_DECL const bool value =
-      !std::is_void<decltype(check<T>(nullptr))>::value;
-};
-
-// Check for integer_sequence
-#if defined(__cpp_lib_integer_sequence) || FMT_MSC_VER >= 1900
-template <typename T, T... N>
-using integer_sequence = std::integer_sequence<T, N...>;
-template <size_t... N> using index_sequence = std::index_sequence<N...>;
-template <size_t N> using make_index_sequence = std::make_index_sequence<N>;
-#else
-template <typename T, T... N> struct integer_sequence {
-  using value_type = T;
-
-  static FMT_CONSTEXPR size_t size() { return sizeof...(N); }
-};
-
-template <size_t... N> using index_sequence = integer_sequence<size_t, N...>;
-
-template <typename T, size_t N, T... Ns>
-struct make_integer_sequence : make_integer_sequence<T, N - 1, N - 1, Ns...> {};
-template <typename T, T... Ns>
-struct make_integer_sequence<T, 0, Ns...> : integer_sequence<T, Ns...> {};
-
-template <size_t N>
-using make_index_sequence = make_integer_sequence<size_t, N>;
-#endif
-
-template <class Tuple, class F, size_t... Is>
-void for_each(index_sequence<Is...>, Tuple&& tup, F&& f) FMT_NOEXCEPT {
-  using std::get;
-  // using free function get<I>(T) now.
-  const int _[] = {0, ((void)f(get<Is>(tup)), 0)...};
-  (void)_;  // blocks warnings
-}
-
-template <class T>
-FMT_CONSTEXPR make_index_sequence<std::tuple_size<T>::value> get_indexes(
-    T const&) {
-  return {};
-}
-
-template <class Tuple, class F> void for_each(Tuple&& tup, F&& f) {
-  const auto indexes = get_indexes(tup);
-  for_each(indexes, std::forward<Tuple>(tup), std::forward<F>(f));
-}
-
-template <typename Range>
-using value_type =
-    remove_cvref_t<decltype(*detail::range_begin(std::declval<Range>()))>;
-
-template <typename OutputIt> OutputIt write_delimiter(OutputIt out) {
-  *out++ = ',';
-  *out++ = ' ';
-  return out;
-}
-
-struct singleton {
-  unsigned char upper;
-  unsigned char lower_count;
-};
-
-inline auto is_printable(uint16_t x, const singleton* singletons,
-                         size_t singletons_size,
-                         const unsigned char* singleton_lowers,
-                         const unsigned char* normal, size_t normal_size)
-    -> bool {
-  auto upper = x >> 8;
-  auto lower_start = 0;
-  for (size_t i = 0; i < singletons_size; ++i) {
-    auto s = singletons[i];
-    auto lower_end = lower_start + s.lower_count;
-    if (upper < s.upper) break;
-    if (upper == s.upper) {
-      for (auto j = lower_start; j < lower_end; ++j) {
-        if (singleton_lowers[j] == (x & 0xff)) return false;
-      }
-    }
-    lower_start = lower_end;
-  }
-
-  auto xsigned = static_cast<int>(x);
-  auto current = true;
-  for (size_t i = 0; i < normal_size; ++i) {
-    auto v = static_cast<int>(normal[i]);
-    auto len = (v & 0x80) != 0 ? (v & 0x7f) << 8 | normal[++i] : v;
-    xsigned -= len;
-    if (xsigned < 0) break;
-    current = !current;
-  }
-  return current;
-}
-
-// Returns true iff the code point cp is printable.
-// This code is generated by support/printable.py.
-inline auto is_printable(uint32_t cp) -> bool {
-  static constexpr singleton singletons0[] = {
-      {0x00, 1},  {0x03, 5},  {0x05, 6},  {0x06, 3},  {0x07, 6},  {0x08, 8},
-      {0x09, 17}, {0x0a, 28}, {0x0b, 25}, {0x0c, 20}, {0x0d, 16}, {0x0e, 13},
-      {0x0f, 4},  {0x10, 3},  {0x12, 18}, {0x13, 9},  {0x16, 1},  {0x17, 5},
-      {0x18, 2},  {0x19, 3},  {0x1a, 7},  {0x1c, 2},  {0x1d, 1},  {0x1f, 22},
-      {0x20, 3},  {0x2b, 3},  {0x2c, 2},  {0x2d, 11}, {0x2e, 1},  {0x30, 3},
-      {0x31, 2},  {0x32, 1},  {0xa7, 2},  {0xa9, 2},  {0xaa, 4},  {0xab, 8},
-      {0xfa, 2},  {0xfb, 5},  {0xfd, 4},  {0xfe, 3},  {0xff, 9},
-  };
-  static constexpr unsigned char singletons0_lower[] = {
-      0xad, 0x78, 0x79, 0x8b, 0x8d, 0xa2, 0x30, 0x57, 0x58, 0x8b, 0x8c, 0x90,
-      0x1c, 0x1d, 0xdd, 0x0e, 0x0f, 0x4b, 0x4c, 0xfb, 0xfc, 0x2e, 0x2f, 0x3f,
-      0x5c, 0x5d, 0x5f, 0xb5, 0xe2, 0x84, 0x8d, 0x8e, 0x91, 0x92, 0xa9, 0xb1,
-      0xba, 0xbb, 0xc5, 0xc6, 0xc9, 0xca, 0xde, 0xe4, 0xe5, 0xff, 0x00, 0x04,
-      0x11, 0x12, 0x29, 0x31, 0x34, 0x37, 0x3a, 0x3b, 0x3d, 0x49, 0x4a, 0x5d,
-      0x84, 0x8e, 0x92, 0xa9, 0xb1, 0xb4, 0xba, 0xbb, 0xc6, 0xca, 0xce, 0xcf,
-      0xe4, 0xe5, 0x00, 0x04, 0x0d, 0x0e, 0x11, 0x12, 0x29, 0x31, 0x34, 0x3a,
-      0x3b, 0x45, 0x46, 0x49, 0x4a, 0x5e, 0x64, 0x65, 0x84, 0x91, 0x9b, 0x9d,
-      0xc9, 0xce, 0xcf, 0x0d, 0x11, 0x29, 0x45, 0x49, 0x57, 0x64, 0x65, 0x8d,
-      0x91, 0xa9, 0xb4, 0xba, 0xbb, 0xc5, 0xc9, 0xdf, 0xe4, 0xe5, 0xf0, 0x0d,
-      0x11, 0x45, 0x49, 0x64, 0x65, 0x80, 0x84, 0xb2, 0xbc, 0xbe, 0xbf, 0xd5,
-      0xd7, 0xf0, 0xf1, 0x83, 0x85, 0x8b, 0xa4, 0xa6, 0xbe, 0xbf, 0xc5, 0xc7,
-      0xce, 0xcf, 0xda, 0xdb, 0x48, 0x98, 0xbd, 0xcd, 0xc6, 0xce, 0xcf, 0x49,
-      0x4e, 0x4f, 0x57, 0x59, 0x5e, 0x5f, 0x89, 0x8e, 0x8f, 0xb1, 0xb6, 0xb7,
-      0xbf, 0xc1, 0xc6, 0xc7, 0xd7, 0x11, 0x16, 0x17, 0x5b, 0x5c, 0xf6, 0xf7,
-      0xfe, 0xff, 0x80, 0x0d, 0x6d, 0x71, 0xde, 0xdf, 0x0e, 0x0f, 0x1f, 0x6e,
-      0x6f, 0x1c, 0x1d, 0x5f, 0x7d, 0x7e, 0xae, 0xaf, 0xbb, 0xbc, 0xfa, 0x16,
-      0x17, 0x1e, 0x1f, 0x46, 0x47, 0x4e, 0x4f, 0x58, 0x5a, 0x5c, 0x5e, 0x7e,
-      0x7f, 0xb5, 0xc5, 0xd4, 0xd5, 0xdc, 0xf0, 0xf1, 0xf5, 0x72, 0x73, 0x8f,
-      0x74, 0x75, 0x96, 0x2f, 0x5f, 0x26, 0x2e, 0x2f, 0xa7, 0xaf, 0xb7, 0xbf,
-      0xc7, 0xcf, 0xd7, 0xdf, 0x9a, 0x40, 0x97, 0x98, 0x30, 0x8f, 0x1f, 0xc0,
-      0xc1, 0xce, 0xff, 0x4e, 0x4f, 0x5a, 0x5b, 0x07, 0x08, 0x0f, 0x10, 0x27,
-      0x2f, 0xee, 0xef, 0x6e, 0x6f, 0x37, 0x3d, 0x3f, 0x42, 0x45, 0x90, 0x91,
-      0xfe, 0xff, 0x53, 0x67, 0x75, 0xc8, 0xc9, 0xd0, 0xd1, 0xd8, 0xd9, 0xe7,
-      0xfe, 0xff,
-  };
-  static constexpr singleton singletons1[] = {
-      {0x00, 6},  {0x01, 1}, {0x03, 1},  {0x04, 2}, {0x08, 8},  {0x09, 2},
-      {0x0a, 5},  {0x0b, 2}, {0x0e, 4},  {0x10, 1}, {0x11, 2},  {0x12, 5},
-      {0x13, 17}, {0x14, 1}, {0x15, 2},  {0x17, 2}, {0x19, 13}, {0x1c, 5},
-      {0x1d, 8},  {0x24, 1}, {0x6a, 3},  {0x6b, 2}, {0xbc, 2},  {0xd1, 2},
-      {0xd4, 12}, {0xd5, 9}, {0xd6, 2},  {0xd7, 2}, {0xda, 1},  {0xe0, 5},
-      {0xe1, 2},  {0xe8, 2}, {0xee, 32}, {0xf0, 4}, {0xf8, 2},  {0xf9, 2},
-      {0xfa, 2},  {0xfb, 1},
-  };
-  static constexpr unsigned char singletons1_lower[] = {
-      0x0c, 0x27, 0x3b, 0x3e, 0x4e, 0x4f, 0x8f, 0x9e, 0x9e, 0x9f, 0x06, 0x07,
-      0x09, 0x36, 0x3d, 0x3e, 0x56, 0xf3, 0xd0, 0xd1, 0x04, 0x14, 0x18, 0x36,
-      0x37, 0x56, 0x57, 0x7f, 0xaa, 0xae, 0xaf, 0xbd, 0x35, 0xe0, 0x12, 0x87,
-      0x89, 0x8e, 0x9e, 0x04, 0x0d, 0x0e, 0x11, 0x12, 0x29, 0x31, 0x34, 0x3a,
-      0x45, 0x46, 0x49, 0x4a, 0x4e, 0x4f, 0x64, 0x65, 0x5c, 0xb6, 0xb7, 0x1b,
-      0x1c, 0x07, 0x08, 0x0a, 0x0b, 0x14, 0x17, 0x36, 0x39, 0x3a, 0xa8, 0xa9,
-      0xd8, 0xd9, 0x09, 0x37, 0x90, 0x91, 0xa8, 0x07, 0x0a, 0x3b, 0x3e, 0x66,
-      0x69, 0x8f, 0x92, 0x6f, 0x5f, 0xee, 0xef, 0x5a, 0x62, 0x9a, 0x9b, 0x27,
-      0x28, 0x55, 0x9d, 0xa0, 0xa1, 0xa3, 0xa4, 0xa7, 0xa8, 0xad, 0xba, 0xbc,
-      0xc4, 0x06, 0x0b, 0x0c, 0x15, 0x1d, 0x3a, 0x3f, 0x45, 0x51, 0xa6, 0xa7,
-      0xcc, 0xcd, 0xa0, 0x07, 0x19, 0x1a, 0x22, 0x25, 0x3e, 0x3f, 0xc5, 0xc6,
-      0x04, 0x20, 0x23, 0x25, 0x26, 0x28, 0x33, 0x38, 0x3a, 0x48, 0x4a, 0x4c,
-      0x50, 0x53, 0x55, 0x56, 0x58, 0x5a, 0x5c, 0x5e, 0x60, 0x63, 0x65, 0x66,
-      0x6b, 0x73, 0x78, 0x7d, 0x7f, 0x8a, 0xa4, 0xaa, 0xaf, 0xb0, 0xc0, 0xd0,
-      0xae, 0xaf, 0x79, 0xcc, 0x6e, 0x6f, 0x93,
-  };
-  static constexpr unsigned char normal0[] = {
-      0x00, 0x20, 0x5f, 0x22, 0x82, 0xdf, 0x04, 0x82, 0x44, 0x08, 0x1b, 0x04,
-      0x06, 0x11, 0x81, 0xac, 0x0e, 0x80, 0xab, 0x35, 0x28, 0x0b, 0x80, 0xe0,
-      0x03, 0x19, 0x08, 0x01, 0x04, 0x2f, 0x04, 0x34, 0x04, 0x07, 0x03, 0x01,
-      0x07, 0x06, 0x07, 0x11, 0x0a, 0x50, 0x0f, 0x12, 0x07, 0x55, 0x07, 0x03,
-      0x04, 0x1c, 0x0a, 0x09, 0x03, 0x08, 0x03, 0x07, 0x03, 0x02, 0x03, 0x03,
-      0x03, 0x0c, 0x04, 0x05, 0x03, 0x0b, 0x06, 0x01, 0x0e, 0x15, 0x05, 0x3a,
-      0x03, 0x11, 0x07, 0x06, 0x05, 0x10, 0x07, 0x57, 0x07, 0x02, 0x07, 0x15,
-      0x0d, 0x50, 0x04, 0x43, 0x03, 0x2d, 0x03, 0x01, 0x04, 0x11, 0x06, 0x0f,
-      0x0c, 0x3a, 0x04, 0x1d, 0x25, 0x5f, 0x20, 0x6d, 0x04, 0x6a, 0x25, 0x80,
-      0xc8, 0x05, 0x82, 0xb0, 0x03, 0x1a, 0x06, 0x82, 0xfd, 0x03, 0x59, 0x07,
-      0x15, 0x0b, 0x17, 0x09, 0x14, 0x0c, 0x14, 0x0c, 0x6a, 0x06, 0x0a, 0x06,
-      0x1a, 0x06, 0x59, 0x07, 0x2b, 0x05, 0x46, 0x0a, 0x2c, 0x04, 0x0c, 0x04,
-      0x01, 0x03, 0x31, 0x0b, 0x2c, 0x04, 0x1a, 0x06, 0x0b, 0x03, 0x80, 0xac,
-      0x06, 0x0a, 0x06, 0x21, 0x3f, 0x4c, 0x04, 0x2d, 0x03, 0x74, 0x08, 0x3c,
-      0x03, 0x0f, 0x03, 0x3c, 0x07, 0x38, 0x08, 0x2b, 0x05, 0x82, 0xff, 0x11,
-      0x18, 0x08, 0x2f, 0x11, 0x2d, 0x03, 0x20, 0x10, 0x21, 0x0f, 0x80, 0x8c,
-      0x04, 0x82, 0x97, 0x19, 0x0b, 0x15, 0x88, 0x94, 0x05, 0x2f, 0x05, 0x3b,
-      0x07, 0x02, 0x0e, 0x18, 0x09, 0x80, 0xb3, 0x2d, 0x74, 0x0c, 0x80, 0xd6,
-      0x1a, 0x0c, 0x05, 0x80, 0xff, 0x05, 0x80, 0xdf, 0x0c, 0xee, 0x0d, 0x03,
-      0x84, 0x8d, 0x03, 0x37, 0x09, 0x81, 0x5c, 0x14, 0x80, 0xb8, 0x08, 0x80,
-      0xcb, 0x2a, 0x38, 0x03, 0x0a, 0x06, 0x38, 0x08, 0x46, 0x08, 0x0c, 0x06,
-      0x74, 0x0b, 0x1e, 0x03, 0x5a, 0x04, 0x59, 0x09, 0x80, 0x83, 0x18, 0x1c,
-      0x0a, 0x16, 0x09, 0x4c, 0x04, 0x80, 0x8a, 0x06, 0xab, 0xa4, 0x0c, 0x17,
-      0x04, 0x31, 0xa1, 0x04, 0x81, 0xda, 0x26, 0x07, 0x0c, 0x05, 0x05, 0x80,
-      0xa5, 0x11, 0x81, 0x6d, 0x10, 0x78, 0x28, 0x2a, 0x06, 0x4c, 0x04, 0x80,
-      0x8d, 0x04, 0x80, 0xbe, 0x03, 0x1b, 0x03, 0x0f, 0x0d,
-  };
-  static constexpr unsigned char normal1[] = {
-      0x5e, 0x22, 0x7b, 0x05, 0x03, 0x04, 0x2d, 0x03, 0x66, 0x03, 0x01, 0x2f,
-      0x2e, 0x80, 0x82, 0x1d, 0x03, 0x31, 0x0f, 0x1c, 0x04, 0x24, 0x09, 0x1e,
-      0x05, 0x2b, 0x05, 0x44, 0x04, 0x0e, 0x2a, 0x80, 0xaa, 0x06, 0x24, 0x04,
-      0x24, 0x04, 0x28, 0x08, 0x34, 0x0b, 0x01, 0x80, 0x90, 0x81, 0x37, 0x09,
-      0x16, 0x0a, 0x08, 0x80, 0x98, 0x39, 0x03, 0x63, 0x08, 0x09, 0x30, 0x16,
-      0x05, 0x21, 0x03, 0x1b, 0x05, 0x01, 0x40, 0x38, 0x04, 0x4b, 0x05, 0x2f,
-      0x04, 0x0a, 0x07, 0x09, 0x07, 0x40, 0x20, 0x27, 0x04, 0x0c, 0x09, 0x36,
-      0x03, 0x3a, 0x05, 0x1a, 0x07, 0x04, 0x0c, 0x07, 0x50, 0x49, 0x37, 0x33,
-      0x0d, 0x33, 0x07, 0x2e, 0x08, 0x0a, 0x81, 0x26, 0x52, 0x4e, 0x28, 0x08,
-      0x2a, 0x56, 0x1c, 0x14, 0x17, 0x09, 0x4e, 0x04, 0x1e, 0x0f, 0x43, 0x0e,
-      0x19, 0x07, 0x0a, 0x06, 0x48, 0x08, 0x27, 0x09, 0x75, 0x0b, 0x3f, 0x41,
-      0x2a, 0x06, 0x3b, 0x05, 0x0a, 0x06, 0x51, 0x06, 0x01, 0x05, 0x10, 0x03,
-      0x05, 0x80, 0x8b, 0x62, 0x1e, 0x48, 0x08, 0x0a, 0x80, 0xa6, 0x5e, 0x22,
-      0x45, 0x0b, 0x0a, 0x06, 0x0d, 0x13, 0x39, 0x07, 0x0a, 0x36, 0x2c, 0x04,
-      0x10, 0x80, 0xc0, 0x3c, 0x64, 0x53, 0x0c, 0x48, 0x09, 0x0a, 0x46, 0x45,
-      0x1b, 0x48, 0x08, 0x53, 0x1d, 0x39, 0x81, 0x07, 0x46, 0x0a, 0x1d, 0x03,
-      0x47, 0x49, 0x37, 0x03, 0x0e, 0x08, 0x0a, 0x06, 0x39, 0x07, 0x0a, 0x81,
-      0x36, 0x19, 0x80, 0xb7, 0x01, 0x0f, 0x32, 0x0d, 0x83, 0x9b, 0x66, 0x75,
-      0x0b, 0x80, 0xc4, 0x8a, 0xbc, 0x84, 0x2f, 0x8f, 0xd1, 0x82, 0x47, 0xa1,
-      0xb9, 0x82, 0x39, 0x07, 0x2a, 0x04, 0x02, 0x60, 0x26, 0x0a, 0x46, 0x0a,
-      0x28, 0x05, 0x13, 0x82, 0xb0, 0x5b, 0x65, 0x4b, 0x04, 0x39, 0x07, 0x11,
-      0x40, 0x05, 0x0b, 0x02, 0x0e, 0x97, 0xf8, 0x08, 0x84, 0xd6, 0x2a, 0x09,
-      0xa2, 0xf7, 0x81, 0x1f, 0x31, 0x03, 0x11, 0x04, 0x08, 0x81, 0x8c, 0x89,
-      0x04, 0x6b, 0x05, 0x0d, 0x03, 0x09, 0x07, 0x10, 0x93, 0x60, 0x80, 0xf6,
-      0x0a, 0x73, 0x08, 0x6e, 0x17, 0x46, 0x80, 0x9a, 0x14, 0x0c, 0x57, 0x09,
-      0x19, 0x80, 0x87, 0x81, 0x47, 0x03, 0x85, 0x42, 0x0f, 0x15, 0x85, 0x50,
-      0x2b, 0x80, 0xd5, 0x2d, 0x03, 0x1a, 0x04, 0x02, 0x81, 0x70, 0x3a, 0x05,
-      0x01, 0x85, 0x00, 0x80, 0xd7, 0x29, 0x4c, 0x04, 0x0a, 0x04, 0x02, 0x83,
-      0x11, 0x44, 0x4c, 0x3d, 0x80, 0xc2, 0x3c, 0x06, 0x01, 0x04, 0x55, 0x05,
-      0x1b, 0x34, 0x02, 0x81, 0x0e, 0x2c, 0x04, 0x64, 0x0c, 0x56, 0x0a, 0x80,
-      0xae, 0x38, 0x1d, 0x0d, 0x2c, 0x04, 0x09, 0x07, 0x02, 0x0e, 0x06, 0x80,
-      0x9a, 0x83, 0xd8, 0x08, 0x0d, 0x03, 0x0d, 0x03, 0x74, 0x0c, 0x59, 0x07,
-      0x0c, 0x14, 0x0c, 0x04, 0x38, 0x08, 0x0a, 0x06, 0x28, 0x08, 0x22, 0x4e,
-      0x81, 0x54, 0x0c, 0x15, 0x03, 0x03, 0x05, 0x07, 0x09, 0x19, 0x07, 0x07,
-      0x09, 0x03, 0x0d, 0x07, 0x29, 0x80, 0xcb, 0x25, 0x0a, 0x84, 0x06,
-  };
-  auto lower = static_cast<uint16_t>(cp);
-  if (cp < 0x10000) {
-    return is_printable(lower, singletons0,
-                        sizeof(singletons0) / sizeof(*singletons0),
-                        singletons0_lower, normal0, sizeof(normal0));
-  }
-  if (cp < 0x20000) {
-    return is_printable(lower, singletons1,
-                        sizeof(singletons1) / sizeof(*singletons1),
-                        singletons1_lower, normal1, sizeof(normal1));
-  }
-  if (0x2a6de <= cp && cp < 0x2a700) return false;
-  if (0x2b735 <= cp && cp < 0x2b740) return false;
-  if (0x2b81e <= cp && cp < 0x2b820) return false;
-  if (0x2cea2 <= cp && cp < 0x2ceb0) return false;
-  if (0x2ebe1 <= cp && cp < 0x2f800) return false;
-  if (0x2fa1e <= cp && cp < 0x30000) return false;
-  if (0x3134b <= cp && cp < 0xe0100) return false;
-  if (0xe01f0 <= cp && cp < 0x110000) return false;
-  return cp < 0x110000;
-}
-
-inline auto needs_escape(uint32_t cp) -> bool {
-  return cp < 0x20 || cp == 0x7f || cp == '"' || cp == '\\' ||
-         !is_printable(cp);
-}
-
-template <typename Char> struct find_escape_result {
-  const Char* begin;
-  const Char* end;
-  uint32_t cp;
-};
-
-template <typename Char>
-auto find_escape(const Char* begin, const Char* end)
-    -> find_escape_result<Char> {
-  for (; begin != end; ++begin) {
-    auto cp = static_cast<typename std::make_unsigned<Char>::type>(*begin);
-    if (sizeof(Char) == 1 && cp >= 0x80) continue;
-    if (needs_escape(cp)) return {begin, begin + 1, cp};
-  }
-  return {begin, nullptr, 0};
-}
-
-inline auto find_escape(const char* begin, const char* end)
-    -> find_escape_result<char> {
-  if (!is_utf8()) return find_escape<char>(begin, end);
-  auto result = find_escape_result<char>{end, nullptr, 0};
-  for_each_codepoint(string_view(begin, to_unsigned(end - begin)),
-                     [&](uint32_t cp, string_view sv) {
-                       if (needs_escape(cp)) {
-                         result = {sv.begin(), sv.end(), cp};
-                         return false;
-                       }
-                       return true;
-                     });
-  return result;
-}
-
-template <typename Char, typename OutputIt>
-auto write_range_entry(OutputIt out, basic_string_view<Char> str) -> OutputIt {
-  *out++ = '"';
-  auto begin = str.begin(), end = str.end();
-  do {
-    auto escape = find_escape(begin, end);
-    out = copy_str<Char>(begin, escape.begin, out);
-    begin = escape.end;
-    if (!begin) break;
-    auto c = static_cast<Char>(escape.cp);
-    switch (escape.cp) {
-    case '\n':
-      *out++ = '\\';
-      c = 'n';
-      break;
-    case '\r':
-      *out++ = '\\';
-      c = 'r';
-      break;
-    case '\t':
-      *out++ = '\\';
-      c = 't';
-      break;
-    case '"':
-      FMT_FALLTHROUGH;
-    case '\\':
-      *out++ = '\\';
-      break;
-    default:
-      if (is_utf8()) {
-        if (escape.cp < 0x100) {
-          out = format_to(out, "\\x{:02x}", escape.cp);
-          continue;
-        }
-        if (escape.cp < 0x10000) {
-          out = format_to(out, "\\u{:04x}", escape.cp);
-          continue;
-        }
-        if (escape.cp < 0x110000) {
-          out = format_to(out, "\\U{:08x}", escape.cp);
-          continue;
-        }
-      }
-      for (Char escape_char : basic_string_view<Char>(
-               escape.begin, to_unsigned(escape.end - escape.begin))) {
-        out = format_to(
-            out, "\\x{:02x}",
-            static_cast<typename std::make_unsigned<Char>::type>(escape_char));
-      }
-      continue;
-    }
-    *out++ = c;
-  } while (begin != end);
-  *out++ = '"';
-  return out;
-}
-
-template <typename Char, typename OutputIt, typename T,
-          FMT_ENABLE_IF(std::is_convertible<T, std_string_view<char>>::value)>
-inline auto write_range_entry(OutputIt out, const T& str) -> OutputIt {
-  auto sv = std_string_view<Char>(str);
-  return write_range_entry<Char>(out, basic_string_view<Char>(sv));
-}
-
-template <typename Char, typename OutputIt, typename Arg,
-          FMT_ENABLE_IF(std::is_same<Arg, Char>::value)>
-OutputIt write_range_entry(OutputIt out, const Arg v) {
-  *out++ = '\'';
-  *out++ = v;
-  *out++ = '\'';
-  return out;
-}
-
-template <
-    typename Char, typename OutputIt, typename Arg,
-    FMT_ENABLE_IF(!is_std_string_like<typename std::decay<Arg>::type>::value &&
-                  !std::is_same<Arg, Char>::value)>
-OutputIt write_range_entry(OutputIt out, const Arg& v) {
-  return write<Char>(out, v);
-}
-
-}  // namespace detail
-
-template <typename T> struct is_tuple_like {
-  static FMT_CONSTEXPR_DECL const bool value =
-      detail::is_tuple_like_<T>::value && !detail::is_range_<T>::value;
-};
-
-template <typename TupleT, typename Char>
-struct formatter<TupleT, Char, enable_if_t<fmt::is_tuple_like<TupleT>::value>> {
- private:
-  // C++11 generic lambda for format().
-  template <typename FormatContext> struct format_each {
-    template <typename T> void operator()(const T& v) {
-      if (i > 0) out = detail::write_delimiter(out);
-      out = detail::write_range_entry<Char>(out, v);
-      ++i;
-    }
-    int i;
-    typename FormatContext::iterator& out;
-  };
-
- public:
-  template <typename ParseContext>
-  FMT_CONSTEXPR auto parse(ParseContext& ctx) -> decltype(ctx.begin()) {
-    return ctx.begin();
-  }
-
-  template <typename FormatContext = format_context>
-  auto format(const TupleT& values, FormatContext& ctx) -> decltype(ctx.out()) {
-    auto out = ctx.out();
-    *out++ = '(';
-    detail::for_each(values, format_each<FormatContext>{0, out});
-    *out++ = ')';
-    return out;
-  }
-};
-
-template <typename T, typename Char> struct is_range {
-  static FMT_CONSTEXPR_DECL const bool value =
-      detail::is_range_<T>::value && !detail::is_std_string_like<T>::value &&
-      !detail::is_map<T>::value &&
-      !std::is_convertible<T, std::basic_string<Char>>::value &&
-      !std::is_constructible<detail::std_string_view<Char>, T>::value;
-};
-
-template <typename T, typename Char>
-struct formatter<
-    T, Char,
-    enable_if_t<
-        fmt::is_range<T, Char>::value
-// Workaround a bug in MSVC 2019 and earlier.
-#if !FMT_MSC_VER
-        && (is_formattable<detail::value_type<T>, Char>::value ||
-            detail::has_fallback_formatter<detail::value_type<T>, Char>::value)
-#endif
-        >> {
-  template <typename ParseContext>
-  FMT_CONSTEXPR auto parse(ParseContext& ctx) -> decltype(ctx.begin()) {
-    return ctx.begin();
-  }
-
-  template <
-      typename FormatContext, typename U,
-      FMT_ENABLE_IF(
-          std::is_same<U, conditional_t<detail::has_const_begin_end<T>::value,
-                                        const T, T>>::value)>
-  auto format(U& range, FormatContext& ctx) -> decltype(ctx.out()) {
-#ifdef FMT_DEPRECATED_BRACED_RANGES
-    Char prefix = '{';
-    Char postfix = '}';
-#else
-    Char prefix = detail::is_set<T>::value ? '{' : '[';
-    Char postfix = detail::is_set<T>::value ? '}' : ']';
-#endif
-    auto out = ctx.out();
-    *out++ = prefix;
-    int i = 0;
-    auto it = std::begin(range);
-    auto end = std::end(range);
-    for (; it != end; ++it) {
-      if (i > 0) out = detail::write_delimiter(out);
-      out = detail::write_range_entry<Char>(out, *it);
-      ++i;
-    }
-    *out++ = postfix;
-    return out;
-  }
-};
-
-template <typename T, typename Char>
-struct formatter<
-    T, Char,
-    enable_if_t<
-        detail::is_map<T>::value
-// Workaround a bug in MSVC 2019 and earlier.
-#if !FMT_MSC_VER
-        && (is_formattable<detail::value_type<T>, Char>::value ||
-            detail::has_fallback_formatter<detail::value_type<T>, Char>::value)
-#endif
-        >> {
-  template <typename ParseContext>
-  FMT_CONSTEXPR auto parse(ParseContext& ctx) -> decltype(ctx.begin()) {
-    return ctx.begin();
-  }
-
-  template <
-      typename FormatContext, typename U,
-      FMT_ENABLE_IF(
-          std::is_same<U, conditional_t<detail::has_const_begin_end<T>::value,
-                                        const T, T>>::value)>
-  auto format(U& map, FormatContext& ctx) -> decltype(ctx.out()) {
-    auto out = ctx.out();
-    *out++ = '{';
-    int i = 0;
-    for (const auto& item : map) {
-      if (i > 0) out = detail::write_delimiter(out);
-      out = detail::write_range_entry<Char>(out, item.first);
-      *out++ = ':';
-      *out++ = ' ';
-      out = detail::write_range_entry<Char>(out, item.second);
-      ++i;
-    }
-    *out++ = '}';
-    return out;
-  }
-};
-
-template <typename Char, typename... T> struct tuple_join_view : detail::view {
-  const std::tuple<T...>& tuple;
-  basic_string_view<Char> sep;
-
-  tuple_join_view(const std::tuple<T...>& t, basic_string_view<Char> s)
-      : tuple(t), sep{s} {}
-};
-
-template <typename Char, typename... T>
-using tuple_arg_join = tuple_join_view<Char, T...>;
-
-// Define FMT_TUPLE_JOIN_SPECIFIERS to enable experimental format specifiers
-// support in tuple_join. It is disabled by default because of issues with
-// the dynamic width and precision.
-#ifndef FMT_TUPLE_JOIN_SPECIFIERS
-#  define FMT_TUPLE_JOIN_SPECIFIERS 0
-#endif
-
-template <typename Char, typename... T>
-struct formatter<tuple_join_view<Char, T...>, Char> {
-  template <typename ParseContext>
-  FMT_CONSTEXPR auto parse(ParseContext& ctx) -> decltype(ctx.begin()) {
-    return do_parse(ctx, std::integral_constant<size_t, sizeof...(T)>());
-  }
-
-  template <typename FormatContext>
-  auto format(const tuple_join_view<Char, T...>& value,
-              FormatContext& ctx) const -> typename FormatContext::iterator {
-    return do_format(value, ctx,
-                     std::integral_constant<size_t, sizeof...(T)>());
-  }
-
- private:
-  std::tuple<formatter<typename std::decay<T>::type, Char>...> formatters_;
-
-  template <typename ParseContext>
-  FMT_CONSTEXPR auto do_parse(ParseContext& ctx,
-                              std::integral_constant<size_t, 0>)
-      -> decltype(ctx.begin()) {
-    return ctx.begin();
-  }
-
-  template <typename ParseContext, size_t N>
-  FMT_CONSTEXPR auto do_parse(ParseContext& ctx,
-                              std::integral_constant<size_t, N>)
-      -> decltype(ctx.begin()) {
-    auto end = ctx.begin();
-#if FMT_TUPLE_JOIN_SPECIFIERS
-    end = std::get<sizeof...(T) - N>(formatters_).parse(ctx);
-    if (N > 1) {
-      auto end1 = do_parse(ctx, std::integral_constant<size_t, N - 1>());
-      if (end != end1)
-        FMT_THROW(format_error("incompatible format specs for tuple elements"));
-    }
-#endif
-    return end;
-  }
-
-  template <typename FormatContext>
-  auto do_format(const tuple_join_view<Char, T...>&, FormatContext& ctx,
-                 std::integral_constant<size_t, 0>) const ->
-      typename FormatContext::iterator {
-    return ctx.out();
-  }
-
-  template <typename FormatContext, size_t N>
-  auto do_format(const tuple_join_view<Char, T...>& value, FormatContext& ctx,
-                 std::integral_constant<size_t, N>) const ->
-      typename FormatContext::iterator {
-    auto out = std::get<sizeof...(T) - N>(formatters_)
-                   .format(std::get<sizeof...(T) - N>(value.tuple), ctx);
-    if (N > 1) {
-      out = std::copy(value.sep.begin(), value.sep.end(), out);
-      ctx.advance_to(out);
-      return do_format(value, ctx, std::integral_constant<size_t, N - 1>());
-    }
-    return out;
-  }
-};
-
-FMT_MODULE_EXPORT_BEGIN
-
-/**
-  \rst
-  Returns an object that formats `tuple` with elements separated by `sep`.
-
-  **Example**::
-
-    std::tuple<int, char> t = {1, 'a'};
-    fmt::print("{}", fmt::join(t, ", "));
-    // Output: "1, a"
-  \endrst
- */
-template <typename... T>
-FMT_CONSTEXPR auto join(const std::tuple<T...>& tuple, string_view sep)
-    -> tuple_join_view<char, T...> {
-  return {tuple, sep};
-}
-
-template <typename... T>
-FMT_CONSTEXPR auto join(const std::tuple<T...>& tuple,
-                        basic_string_view<wchar_t> sep)
-    -> tuple_join_view<wchar_t, T...> {
-  return {tuple, sep};
-}
-
-/**
-  \rst
-  Returns an object that formats `initializer_list` with elements separated by
-  `sep`.
-
-  **Example**::
-
-    fmt::print("{}", fmt::join({1, 2, 3}, ", "));
-    // Output: "1, 2, 3"
-  \endrst
- */
-template <typename T>
-auto join(std::initializer_list<T> list, string_view sep)
-    -> join_view<const T*, const T*> {
-  return join(std::begin(list), std::end(list), sep);
-}
-
-FMT_MODULE_EXPORT_END
-FMT_END_NAMESPACE
-
-#endif  // FMT_RANGES_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/xchar.h b/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/xchar.h
deleted file mode 100644
index 9acb893..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/fmtlib/include/fmt/xchar.h
+++ /dev/null
@@ -1,235 +0,0 @@
-// Formatting library for C++ - optional wchar_t and exotic character support
-//
-// Copyright (c) 2012 - present, Victor Zverovich
-// All rights reserved.
-//
-// For the license information refer to format.h.
-
-#ifndef FMT_XCHAR_H_
-#define FMT_XCHAR_H_
-
-#include <cwchar>
-#include <tuple>
-
-#include "format.h"
-
-FMT_BEGIN_NAMESPACE
-namespace detail {
-template <typename T>
-using is_exotic_char = bool_constant<!std::is_same<T, char>::value>;
-}
-
-FMT_MODULE_EXPORT_BEGIN
-
-using wstring_view = basic_string_view<wchar_t>;
-using wformat_parse_context = basic_format_parse_context<wchar_t>;
-using wformat_context = buffer_context<wchar_t>;
-using wformat_args = basic_format_args<wformat_context>;
-using wmemory_buffer = basic_memory_buffer<wchar_t>;
-
-#if FMT_GCC_VERSION && FMT_GCC_VERSION < 409
-// Workaround broken conversion on older gcc.
-template <typename... Args> using wformat_string = wstring_view;
-#else
-template <typename... Args>
-using wformat_string = basic_format_string<wchar_t, type_identity_t<Args>...>;
-#endif
-
-template <> struct is_char<wchar_t> : std::true_type {};
-template <> struct is_char<detail::char8_type> : std::true_type {};
-template <> struct is_char<char16_t> : std::true_type {};
-template <> struct is_char<char32_t> : std::true_type {};
-
-template <typename... Args>
-constexpr format_arg_store<wformat_context, Args...> make_wformat_args(
-    const Args&... args) {
-  return {args...};
-}
-
-inline namespace literals {
-constexpr auto operator"" _format(const wchar_t* s, size_t n)
-    -> detail::udl_formatter<wchar_t> {
-  return {{s, n}};
-}
-
-#if FMT_USE_USER_DEFINED_LITERALS && !FMT_USE_NONTYPE_TEMPLATE_PARAMETERS
-constexpr detail::udl_arg<wchar_t> operator"" _a(const wchar_t* s, size_t) {
-  return {s};
-}
-#endif
-}  // namespace literals
-
-template <typename It, typename Sentinel>
-auto join(It begin, Sentinel end, wstring_view sep)
-    -> join_view<It, Sentinel, wchar_t> {
-  return {begin, end, sep};
-}
-
-template <typename Range>
-auto join(Range&& range, wstring_view sep)
-    -> join_view<detail::iterator_t<Range>, detail::sentinel_t<Range>,
-                 wchar_t> {
-  return join(std::begin(range), std::end(range), sep);
-}
-
-template <typename T>
-auto join(std::initializer_list<T> list, wstring_view sep)
-    -> join_view<const T*, const T*, wchar_t> {
-  return join(std::begin(list), std::end(list), sep);
-}
-
-template <typename Char, FMT_ENABLE_IF(!std::is_same<Char, char>::value)>
-auto vformat(basic_string_view<Char> format_str,
-             basic_format_args<buffer_context<type_identity_t<Char>>> args)
-    -> std::basic_string<Char> {
-  basic_memory_buffer<Char> buffer;
-  detail::vformat_to(buffer, format_str, args);
-  return to_string(buffer);
-}
-
-// Pass char_t as a default template parameter instead of using
-// std::basic_string<char_t<S>> to reduce the symbol size.
-template <typename S, typename... Args, typename Char = char_t<S>,
-          FMT_ENABLE_IF(!std::is_same<Char, char>::value)>
-auto format(const S& format_str, Args&&... args) -> std::basic_string<Char> {
-  const auto& vargs = fmt::make_args_checked<Args...>(format_str, args...);
-  return vformat(to_string_view(format_str), vargs);
-}
-
-template <typename Locale, typename S, typename Char = char_t<S>,
-          FMT_ENABLE_IF(detail::is_locale<Locale>::value&&
-                            detail::is_exotic_char<Char>::value)>
-inline auto vformat(
-    const Locale& loc, const S& format_str,
-    basic_format_args<buffer_context<type_identity_t<Char>>> args)
-    -> std::basic_string<Char> {
-  return detail::vformat(loc, to_string_view(format_str), args);
-}
-
-template <typename Locale, typename S, typename... Args,
-          typename Char = char_t<S>,
-          FMT_ENABLE_IF(detail::is_locale<Locale>::value&&
-                            detail::is_exotic_char<Char>::value)>
-inline auto format(const Locale& loc, const S& format_str, Args&&... args)
-    -> std::basic_string<Char> {
-  return detail::vformat(loc, to_string_view(format_str),
-                         fmt::make_args_checked<Args...>(format_str, args...));
-}
-
-template <typename OutputIt, typename S, typename Char = char_t<S>,
-          FMT_ENABLE_IF(detail::is_output_iterator<OutputIt, Char>::value&&
-                            detail::is_exotic_char<Char>::value)>
-auto vformat_to(OutputIt out, const S& format_str,
-                basic_format_args<buffer_context<type_identity_t<Char>>> args)
-    -> OutputIt {
-  auto&& buf = detail::get_buffer<Char>(out);
-  detail::vformat_to(buf, to_string_view(format_str), args);
-  return detail::get_iterator(buf);
-}
-
-template <typename OutputIt, typename S, typename... Args,
-          typename Char = char_t<S>,
-          FMT_ENABLE_IF(detail::is_output_iterator<OutputIt, Char>::value&&
-                            detail::is_exotic_char<Char>::value)>
-inline auto format_to(OutputIt out, const S& fmt, Args&&... args) -> OutputIt {
-  const auto& vargs = fmt::make_args_checked<Args...>(fmt, args...);
-  return vformat_to(out, to_string_view(fmt), vargs);
-}
-
-template <typename S, typename... Args, typename Char, size_t SIZE,
-          typename Allocator, FMT_ENABLE_IF(detail::is_string<S>::value)>
-FMT_DEPRECATED auto format_to(basic_memory_buffer<Char, SIZE, Allocator>& buf,
-                              const S& format_str, Args&&... args) ->
-    typename buffer_context<Char>::iterator {
-  const auto& vargs = fmt::make_args_checked<Args...>(format_str, args...);
-  detail::vformat_to(buf, to_string_view(format_str), vargs, {});
-  return detail::buffer_appender<Char>(buf);
-}
-
-template <typename Locale, typename S, typename OutputIt, typename... Args,
-          typename Char = char_t<S>,
-          FMT_ENABLE_IF(detail::is_output_iterator<OutputIt, Char>::value&&
-                            detail::is_locale<Locale>::value&&
-                                detail::is_exotic_char<Char>::value)>
-inline auto vformat_to(
-    OutputIt out, const Locale& loc, const S& format_str,
-    basic_format_args<buffer_context<type_identity_t<Char>>> args) -> OutputIt {
-  auto&& buf = detail::get_buffer<Char>(out);
-  vformat_to(buf, to_string_view(format_str), args, detail::locale_ref(loc));
-  return detail::get_iterator(buf);
-}
-
-template <
-    typename OutputIt, typename Locale, typename S, typename... Args,
-    typename Char = char_t<S>,
-    bool enable = detail::is_output_iterator<OutputIt, Char>::value&&
-        detail::is_locale<Locale>::value&& detail::is_exotic_char<Char>::value>
-inline auto format_to(OutputIt out, const Locale& loc, const S& format_str,
-                      Args&&... args) ->
-    typename std::enable_if<enable, OutputIt>::type {
-  const auto& vargs = fmt::make_args_checked<Args...>(format_str, args...);
-  return vformat_to(out, loc, to_string_view(format_str), vargs);
-}
-
-template <typename OutputIt, typename Char, typename... Args,
-          FMT_ENABLE_IF(detail::is_output_iterator<OutputIt, Char>::value&&
-                            detail::is_exotic_char<Char>::value)>
-inline auto vformat_to_n(
-    OutputIt out, size_t n, basic_string_view<Char> format_str,
-    basic_format_args<buffer_context<type_identity_t<Char>>> args)
-    -> format_to_n_result<OutputIt> {
-  detail::iterator_buffer<OutputIt, Char, detail::fixed_buffer_traits> buf(out,
-                                                                           n);
-  detail::vformat_to(buf, format_str, args);
-  return {buf.out(), buf.count()};
-}
-
-template <typename OutputIt, typename S, typename... Args,
-          typename Char = char_t<S>,
-          FMT_ENABLE_IF(detail::is_output_iterator<OutputIt, Char>::value&&
-                            detail::is_exotic_char<Char>::value)>
-inline auto format_to_n(OutputIt out, size_t n, const S& fmt,
-                        const Args&... args) -> format_to_n_result<OutputIt> {
-  const auto& vargs = fmt::make_args_checked<Args...>(fmt, args...);
-  return vformat_to_n(out, n, to_string_view(fmt), vargs);
-}
-
-template <typename S, typename... Args, typename Char = char_t<S>,
-          FMT_ENABLE_IF(detail::is_exotic_char<Char>::value)>
-inline auto formatted_size(const S& fmt, Args&&... args) -> size_t {
-  detail::counting_buffer<Char> buf;
-  const auto& vargs = fmt::make_args_checked<Args...>(fmt, args...);
-  detail::vformat_to(buf, to_string_view(fmt), vargs);
-  return buf.count();
-}
-
-inline void vprint(std::FILE* f, wstring_view fmt, wformat_args args) {
-  wmemory_buffer buffer;
-  detail::vformat_to(buffer, fmt, args);
-  buffer.push_back(L'\0');
-  std::fputws(buffer.data(), f);
-}
-
-inline void vprint(wstring_view fmt, wformat_args args) {
-  vprint(stdout, fmt, args);
-}
-
-template <typename... T>
-void print(std::FILE* f, wformat_string<T...> fmt, T&&... args) {
-  return vprint(f, wstring_view(fmt), fmt::make_wformat_args(args...));
-}
-
-template <typename... T> void print(wformat_string<T...> fmt, T&&... args) {
-  return vprint(wstring_view(fmt), fmt::make_wformat_args(args...));
-}
-
-/**
-  Converts *value* to ``std::wstring`` using the default format for type *T*.
- */
-template <typename T> inline auto to_wstring(const T& value) -> std::wstring {
-  return format(FMT_STRING(L"{}"), value);
-}
-FMT_MODULE_EXPORT_END
-FMT_END_NAMESPACE
-
-#endif  // FMT_XCHAR_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/fmtlib/src/format.cpp b/third_party/allwpilib/wpiutil/src/main/native/fmtlib/src/format.cpp
deleted file mode 100644
index ecb8cc7..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/fmtlib/src/format.cpp
+++ /dev/null
@@ -1,124 +0,0 @@
-// Formatting library for C++
-//
-// Copyright (c) 2012 - 2016, Victor Zverovich
-// All rights reserved.
-//
-// For the license information refer to format.h.
-
-#include "fmt/format-inl.h"
-
-FMT_BEGIN_NAMESPACE
-namespace detail {
-
-// DEPRECATED!
-template <typename T = void> struct basic_data {
-  FMT_API static constexpr const char digits[100][2] = {
-      {'0', '0'}, {'0', '1'}, {'0', '2'}, {'0', '3'}, {'0', '4'}, {'0', '5'},
-      {'0', '6'}, {'0', '7'}, {'0', '8'}, {'0', '9'}, {'1', '0'}, {'1', '1'},
-      {'1', '2'}, {'1', '3'}, {'1', '4'}, {'1', '5'}, {'1', '6'}, {'1', '7'},
-      {'1', '8'}, {'1', '9'}, {'2', '0'}, {'2', '1'}, {'2', '2'}, {'2', '3'},
-      {'2', '4'}, {'2', '5'}, {'2', '6'}, {'2', '7'}, {'2', '8'}, {'2', '9'},
-      {'3', '0'}, {'3', '1'}, {'3', '2'}, {'3', '3'}, {'3', '4'}, {'3', '5'},
-      {'3', '6'}, {'3', '7'}, {'3', '8'}, {'3', '9'}, {'4', '0'}, {'4', '1'},
-      {'4', '2'}, {'4', '3'}, {'4', '4'}, {'4', '5'}, {'4', '6'}, {'4', '7'},
-      {'4', '8'}, {'4', '9'}, {'5', '0'}, {'5', '1'}, {'5', '2'}, {'5', '3'},
-      {'5', '4'}, {'5', '5'}, {'5', '6'}, {'5', '7'}, {'5', '8'}, {'5', '9'},
-      {'6', '0'}, {'6', '1'}, {'6', '2'}, {'6', '3'}, {'6', '4'}, {'6', '5'},
-      {'6', '6'}, {'6', '7'}, {'6', '8'}, {'6', '9'}, {'7', '0'}, {'7', '1'},
-      {'7', '2'}, {'7', '3'}, {'7', '4'}, {'7', '5'}, {'7', '6'}, {'7', '7'},
-      {'7', '8'}, {'7', '9'}, {'8', '0'}, {'8', '1'}, {'8', '2'}, {'8', '3'},
-      {'8', '4'}, {'8', '5'}, {'8', '6'}, {'8', '7'}, {'8', '8'}, {'8', '9'},
-      {'9', '0'}, {'9', '1'}, {'9', '2'}, {'9', '3'}, {'9', '4'}, {'9', '5'},
-      {'9', '6'}, {'9', '7'}, {'9', '8'}, {'9', '9'}};
-  FMT_API static constexpr const char hex_digits[] = "0123456789abcdef";
-  FMT_API static constexpr const char signs[4] = {0, '-', '+', ' '};
-  FMT_API static constexpr const char left_padding_shifts[5] = {31, 31, 0, 1,
-                                                                0};
-  FMT_API static constexpr const char right_padding_shifts[5] = {0, 31, 0, 1,
-                                                                 0};
-  FMT_API static constexpr const unsigned prefixes[4] = {0, 0, 0x1000000u | '+',
-                                                         0x1000000u | ' '};
-};
-
-#ifdef FMT_SHARED
-// Required for -flto, -fivisibility=hidden and -shared to work
-extern template struct basic_data<void>;
-#endif
-
-#if __cplusplus < 201703L
-// DEPRECATED! These are here only for ABI compatiblity.
-template <typename T> constexpr const char basic_data<T>::digits[][2];
-template <typename T> constexpr const char basic_data<T>::hex_digits[];
-template <typename T> constexpr const char basic_data<T>::signs[];
-template <typename T> constexpr const char basic_data<T>::left_padding_shifts[];
-template <typename T>
-constexpr const char basic_data<T>::right_padding_shifts[];
-template <typename T> constexpr const unsigned basic_data<T>::prefixes[];
-#endif
-
-template <typename T>
-int format_float(char* buf, std::size_t size, const char* format, int precision,
-                 T value) {
-#ifdef FMT_FUZZ
-  if (precision > 100000)
-    throw std::runtime_error(
-        "fuzz mode - avoid large allocation inside snprintf");
-#endif
-  // Suppress the warning about nonliteral format string.
-  int (*snprintf_ptr)(char*, size_t, const char*, ...) = FMT_SNPRINTF;
-  return precision < 0 ? snprintf_ptr(buf, size, format, value)
-                       : snprintf_ptr(buf, size, format, precision, value);
-}
-
-template FMT_API dragonbox::decimal_fp<float> dragonbox::to_decimal(float x)
-    FMT_NOEXCEPT;
-template FMT_API dragonbox::decimal_fp<double> dragonbox::to_decimal(double x)
-    FMT_NOEXCEPT;
-}  // namespace detail
-
-// Workaround a bug in MSVC2013 that prevents instantiation of format_float.
-int (*instantiate_format_float)(double, int, detail::float_specs,
-                                detail::buffer<char>&) = detail::format_float;
-
-#ifndef FMT_STATIC_THOUSANDS_SEPARATOR
-template FMT_API detail::locale_ref::locale_ref(const std::locale& loc);
-template FMT_API std::locale detail::locale_ref::get<std::locale>() const;
-#endif
-
-// Explicit instantiations for char.
-
-template FMT_API auto detail::thousands_sep_impl(locale_ref)
-    -> thousands_sep_result<char>;
-template FMT_API char detail::decimal_point_impl(locale_ref);
-
-template FMT_API void detail::buffer<char>::append(const char*, const char*);
-
-// DEPRECATED!
-// There is no correspondent extern template in format.h because of
-// incompatibility between clang and gcc (#2377).
-template FMT_API void detail::vformat_to(
-    detail::buffer<char>&, string_view,
-    basic_format_args<FMT_BUFFER_CONTEXT(char)>, detail::locale_ref);
-
-template FMT_API int detail::snprintf_float(double, int, detail::float_specs,
-                                            detail::buffer<char>&);
-template FMT_API int detail::snprintf_float(long double, int,
-                                            detail::float_specs,
-                                            detail::buffer<char>&);
-template FMT_API int detail::format_float(double, int, detail::float_specs,
-                                          detail::buffer<char>&);
-template FMT_API int detail::format_float(long double, int, detail::float_specs,
-                                          detail::buffer<char>&);
-
-// Explicit instantiations for wchar_t.
-
-template FMT_API auto detail::thousands_sep_impl(locale_ref)
-    -> thousands_sep_result<wchar_t>;
-template FMT_API wchar_t detail::decimal_point_impl(locale_ref);
-
-template FMT_API void detail::buffer<wchar_t>::append(const wchar_t*,
-                                                      const wchar_t*);
-
-template struct detail::basic_data<void>;
-
-FMT_END_NAMESPACE
diff --git a/third_party/allwpilib/wpiutil/src/main/native/fmtlib/src/os.cpp b/third_party/allwpilib/wpiutil/src/main/native/fmtlib/src/os.cpp
deleted file mode 100644
index 4eb3e1f..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/fmtlib/src/os.cpp
+++ /dev/null
@@ -1,360 +0,0 @@
-// Formatting library for C++ - optional OS-specific functionality
-//
-// Copyright (c) 2012 - 2016, Victor Zverovich
-// All rights reserved.
-//
-// For the license information refer to format.h.
-
-// Disable bogus MSVC warnings.
-#if !defined(_CRT_SECURE_NO_WARNINGS) && defined(_MSC_VER)
-#  define _CRT_SECURE_NO_WARNINGS
-#endif
-
-#include "fmt/os.h"
-
-#include <climits>
-
-#if FMT_USE_FCNTL
-#  include <sys/stat.h>
-#  include <sys/types.h>
-
-#  ifndef _WIN32
-#    include <unistd.h>
-#  else
-#    ifndef WIN32_LEAN_AND_MEAN
-#      define WIN32_LEAN_AND_MEAN
-#    endif
-#    include <io.h>
-
-#    ifndef S_IRUSR
-#      define S_IRUSR _S_IREAD
-#    endif
-#    ifndef S_IWUSR
-#      define S_IWUSR _S_IWRITE
-#    endif
-#    ifndef S_IRGRP
-#      define S_IRGRP 0
-#    endif
-#    ifndef S_IROTH
-#      define S_IROTH 0
-#    endif
-#  endif  // _WIN32
-#endif    // FMT_USE_FCNTL
-
-#ifdef _WIN32
-#  include <windows.h>
-#endif
-
-#ifdef fileno
-#  undef fileno
-#endif
-
-namespace {
-#ifdef _WIN32
-// Return type of read and write functions.
-using rwresult = int;
-
-// On Windows the count argument to read and write is unsigned, so convert
-// it from size_t preventing integer overflow.
-inline unsigned convert_rwcount(std::size_t count) {
-  return count <= UINT_MAX ? static_cast<unsigned>(count) : UINT_MAX;
-}
-#elif FMT_USE_FCNTL
-// Return type of read and write functions.
-using rwresult = ssize_t;
-
-inline std::size_t convert_rwcount(std::size_t count) { return count; }
-#endif
-}  // namespace
-
-FMT_BEGIN_NAMESPACE
-
-#ifdef _WIN32
-detail::utf16_to_utf8::utf16_to_utf8(basic_string_view<wchar_t> s) {
-  if (int error_code = convert(s)) {
-    FMT_THROW(windows_error(error_code,
-                            "cannot convert string from UTF-16 to UTF-8"));
-  }
-}
-
-int detail::utf16_to_utf8::convert(basic_string_view<wchar_t> s) {
-  if (s.size() > INT_MAX) return ERROR_INVALID_PARAMETER;
-  int s_size = static_cast<int>(s.size());
-  if (s_size == 0) {
-    // WideCharToMultiByte does not support zero length, handle separately.
-    buffer_.resize(1);
-    buffer_[0] = 0;
-    return 0;
-  }
-
-  int length = WideCharToMultiByte(CP_UTF8, 0, s.data(), s_size, nullptr, 0,
-                                   nullptr, nullptr);
-  if (length == 0) return GetLastError();
-  buffer_.resize(length + 1);
-  length = WideCharToMultiByte(CP_UTF8, 0, s.data(), s_size, &buffer_[0],
-                               length, nullptr, nullptr);
-  if (length == 0) return GetLastError();
-  buffer_[length] = 0;
-  return 0;
-}
-
-namespace detail {
-
-class system_message {
-  system_message(const system_message&) = delete;
-  void operator=(const system_message&) = delete;
-
-  unsigned long result_;
-  wchar_t* message_;
-
-  static bool is_whitespace(wchar_t c) FMT_NOEXCEPT {
-    return c == L' ' || c == L'\n' || c == L'\r' || c == L'\t' || c == L'\0';
-  }
-
- public:
-  explicit system_message(unsigned long error_code)
-      : result_(0), message_(nullptr) {
-    result_ = FormatMessageW(
-        FORMAT_MESSAGE_ALLOCATE_BUFFER | FORMAT_MESSAGE_FROM_SYSTEM |
-            FORMAT_MESSAGE_IGNORE_INSERTS,
-        nullptr, error_code, MAKELANGID(LANG_NEUTRAL, SUBLANG_DEFAULT),
-        reinterpret_cast<wchar_t*>(&message_), 0, nullptr);
-    if (result_ != 0) {
-      while (result_ != 0 && is_whitespace(message_[result_ - 1])) {
-        --result_;
-      }
-    }
-  }
-  ~system_message() { LocalFree(message_); }
-  explicit operator bool() const FMT_NOEXCEPT { return result_ != 0; }
-  operator basic_string_view<wchar_t>() const FMT_NOEXCEPT {
-    return basic_string_view<wchar_t>(message_, result_);
-  }
-};
-
-class utf8_system_category final : public std::error_category {
- public:
-  const char* name() const FMT_NOEXCEPT override { return "system"; }
-  std::string message(int error_code) const override {
-    system_message msg(error_code);
-    if (msg) {
-      utf16_to_utf8 utf8_message;
-      if (utf8_message.convert(msg) == ERROR_SUCCESS) {
-        return utf8_message.str();
-      }
-    }
-    return "unknown error";
-  }
-};
-
-}  // namespace detail
-
-FMT_API const std::error_category& system_category() FMT_NOEXCEPT {
-  static const detail::utf8_system_category category;
-  return category;
-}
-
-std::system_error vwindows_error(int err_code, string_view format_str,
-                                 format_args args) {
-  auto ec = std::error_code(err_code, system_category());
-  return std::system_error(ec, vformat(format_str, args));
-}
-
-void detail::format_windows_error(detail::buffer<char>& out, int error_code,
-                                  const char* message) FMT_NOEXCEPT {
-  FMT_TRY {
-    system_message msg(error_code);
-    if (msg) {
-      utf16_to_utf8 utf8_message;
-      if (utf8_message.convert(msg) == ERROR_SUCCESS) {
-        format_to(buffer_appender<char>(out), "{}: {}", message, utf8_message);
-        return;
-      }
-    }
-  }
-  FMT_CATCH(...) {}
-  format_error_code(out, error_code, message);
-}
-
-void report_windows_error(int error_code, const char* message) FMT_NOEXCEPT {
-  report_error(detail::format_windows_error, error_code, message);
-}
-#endif  // _WIN32
-
-buffered_file::~buffered_file() FMT_NOEXCEPT {
-  if (file_ && FMT_SYSTEM(fclose(file_)) != 0)
-    report_system_error(errno, "cannot close file");
-}
-
-buffered_file::buffered_file(cstring_view filename, cstring_view mode) {
-  FMT_RETRY_VAL(file_, FMT_SYSTEM(fopen(filename.c_str(), mode.c_str())),
-                nullptr);
-  if (!file_)
-    FMT_THROW(system_error(errno, "cannot open file {}", filename.c_str()));
-}
-
-void buffered_file::close() {
-  if (!file_) return;
-  int result = FMT_SYSTEM(fclose(file_));
-  file_ = nullptr;
-  if (result != 0) FMT_THROW(system_error(errno, "cannot close file"));
-}
-
-// A macro used to prevent expansion of fileno on broken versions of MinGW.
-#define FMT_ARGS
-
-int buffered_file::fileno() const {
-  int fd = FMT_POSIX_CALL(fileno FMT_ARGS(file_));
-  if (fd == -1) FMT_THROW(system_error(errno, "cannot get file descriptor"));
-  return fd;
-}
-
-#if FMT_USE_FCNTL
-file::file(cstring_view path, int oflag) {
-#  ifdef _WIN32
-  using mode_t = int;
-#  endif
-  mode_t mode = S_IRUSR | S_IWUSR | S_IRGRP | S_IROTH;
-#  if defined(_WIN32) && !defined(__MINGW32__)
-  fd_ = -1;
-  FMT_POSIX_CALL(sopen_s(&fd_, path.c_str(), oflag, _SH_DENYNO, mode));
-#  else
-  FMT_RETRY(fd_, FMT_POSIX_CALL(open(path.c_str(), oflag, mode)));
-#  endif
-  if (fd_ == -1)
-    FMT_THROW(system_error(errno, "cannot open file {}", path.c_str()));
-}
-
-file::~file() FMT_NOEXCEPT {
-  // Don't retry close in case of EINTR!
-  // See http://linux.derkeiler.com/Mailing-Lists/Kernel/2005-09/3000.html
-  if (fd_ != -1 && FMT_POSIX_CALL(close(fd_)) != 0)
-    report_system_error(errno, "cannot close file");
-}
-
-void file::close() {
-  if (fd_ == -1) return;
-  // Don't retry close in case of EINTR!
-  // See http://linux.derkeiler.com/Mailing-Lists/Kernel/2005-09/3000.html
-  int result = FMT_POSIX_CALL(close(fd_));
-  fd_ = -1;
-  if (result != 0) FMT_THROW(system_error(errno, "cannot close file"));
-}
-
-long long file::size() const {
-#  ifdef _WIN32
-  // Use GetFileSize instead of GetFileSizeEx for the case when _WIN32_WINNT
-  // is less than 0x0500 as is the case with some default MinGW builds.
-  // Both functions support large file sizes.
-  DWORD size_upper = 0;
-  HANDLE handle = reinterpret_cast<HANDLE>(_get_osfhandle(fd_));
-  DWORD size_lower = FMT_SYSTEM(GetFileSize(handle, &size_upper));
-  if (size_lower == INVALID_FILE_SIZE) {
-    DWORD error = GetLastError();
-    if (error != NO_ERROR)
-      FMT_THROW(windows_error(GetLastError(), "cannot get file size"));
-  }
-  unsigned long long long_size = size_upper;
-  return (long_size << sizeof(DWORD) * CHAR_BIT) | size_lower;
-#  else
-  using Stat = struct stat;
-  Stat file_stat = Stat();
-  if (FMT_POSIX_CALL(fstat(fd_, &file_stat)) == -1)
-    FMT_THROW(system_error(errno, "cannot get file attributes"));
-  static_assert(sizeof(long long) >= sizeof(file_stat.st_size),
-                "return type of file::size is not large enough");
-  return file_stat.st_size;
-#  endif
-}
-
-std::size_t file::read(void* buffer, std::size_t count) {
-  rwresult result = 0;
-  FMT_RETRY(result, FMT_POSIX_CALL(read(fd_, buffer, convert_rwcount(count))));
-  if (result < 0) FMT_THROW(system_error(errno, "cannot read from file"));
-  return detail::to_unsigned(result);
-}
-
-std::size_t file::write(const void* buffer, std::size_t count) {
-  rwresult result = 0;
-  FMT_RETRY(result, FMT_POSIX_CALL(write(fd_, buffer, convert_rwcount(count))));
-  return count;
-}
-
-file file::dup(int fd) {
-  // Don't retry as dup doesn't return EINTR.
-  // http://pubs.opengroup.org/onlinepubs/009695399/functions/dup.html
-  int new_fd = FMT_POSIX_CALL(dup(fd));
-  if (new_fd == -1)
-    FMT_THROW(system_error(errno, "cannot duplicate file descriptor {}", fd));
-  return file(new_fd);
-}
-
-void file::dup2(int fd) {
-  int result = 0;
-  FMT_RETRY(result, FMT_POSIX_CALL(dup2(fd_, fd)));
-  if (result == -1) {
-    FMT_THROW(system_error(errno, "cannot duplicate file descriptor {} to {}",
-                           fd_, fd));
-  }
-}
-
-void file::dup2(int fd, std::error_code& ec) FMT_NOEXCEPT {
-  int result = 0;
-  FMT_RETRY(result, FMT_POSIX_CALL(dup2(fd_, fd)));
-  if (result == -1) ec = std::error_code(errno, std::generic_category());
-}
-
-void file::pipe(file& read_end, file& write_end) {
-  // Close the descriptors first to make sure that assignments don't throw
-  // and there are no leaks.
-  read_end.close();
-  write_end.close();
-  int fds[2] = {};
-#  ifdef _WIN32
-  // Make the default pipe capacity same as on Linux 2.6.11+.
-  enum { DEFAULT_CAPACITY = 65536 };
-  int result = FMT_POSIX_CALL(pipe(fds, DEFAULT_CAPACITY, _O_BINARY));
-#  else
-  // Don't retry as the pipe function doesn't return EINTR.
-  // http://pubs.opengroup.org/onlinepubs/009696799/functions/pipe.html
-  int result = FMT_POSIX_CALL(pipe(fds));
-#  endif
-  if (result != 0) FMT_THROW(system_error(errno, "cannot create pipe"));
-  // The following assignments don't throw because read_fd and write_fd
-  // are closed.
-  read_end = file(fds[0]);
-  write_end = file(fds[1]);
-}
-
-buffered_file file::fdopen(const char* mode) {
-// Don't retry as fdopen doesn't return EINTR.
-#  if defined(__MINGW32__) && defined(_POSIX_)
-  FILE* f = ::fdopen(fd_, mode);
-#  else
-  FILE* f = FMT_POSIX_CALL(fdopen(fd_, mode));
-#  endif
-  if (!f)
-    FMT_THROW(
-        system_error(errno, "cannot associate stream with file descriptor"));
-  buffered_file bf(f);
-  fd_ = -1;
-  return bf;
-}
-
-long getpagesize() {
-#  ifdef _WIN32
-  SYSTEM_INFO si;
-  GetSystemInfo(&si);
-  return si.dwPageSize;
-#  else
-  long size = FMT_POSIX_CALL(sysconf(_SC_PAGESIZE));
-  if (size < 0) FMT_THROW(system_error(errno, "cannot get memory page size"));
-  return size;
-#  endif
-}
-
-FMT_API void ostream::grow(size_t) {
-  if (this->size() == this->capacity()) flush();
-}
-#endif  // FMT_USE_FCNTL
-FMT_END_NAMESPACE
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/Algorithm.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/Algorithm.h
index d0744dc..1fd2502 100644
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/Algorithm.h
+++ b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/Algorithm.h
@@ -9,7 +9,7 @@
 
 namespace wpi {
 
-// Binary insortion into vector; std::log(n) efficiency.
+// Binary insertion into vector; std::log(n) efficiency.
 template <typename T>
 typename std::vector<T>::iterator insert_sorted(std::vector<T>& vec,
                                                 T const& item) {
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/AlignOf.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/AlignOf.h
deleted file mode 100644
index adddd13..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/AlignOf.h
+++ /dev/null
@@ -1,146 +0,0 @@
-//===--- AlignOf.h - Portable calculation of type alignment -----*- C++ -*-===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-//
-// This file defines the AlignedCharArray and AlignedCharArrayUnion classes.
-//
-//===----------------------------------------------------------------------===//
-
-#ifndef WPIUTIL_WPI_ALIGNOF_H
-#define WPIUTIL_WPI_ALIGNOF_H
-
-#include "wpi/Compiler.h"
-#include <cstddef>
-
-namespace wpi {
-
-/// \struct AlignedCharArray
-/// Helper for building an aligned character array type.
-///
-/// This template is used to explicitly build up a collection of aligned
-/// character array types. We have to build these up using a macro and explicit
-/// specialization to cope with MSVC (at least till 2015) where only an
-/// integer literal can be used to specify an alignment constraint. Once built
-/// up here, we can then begin to indirect between these using normal C++
-/// template parameters.
-
-// MSVC requires special handling here.
-#ifndef _MSC_VER
-
-template<std::size_t Alignment, std::size_t Size>
-struct AlignedCharArray {
-  alignas(Alignment) char buffer[Size];
-};
-
-#else // _MSC_VER
-
-/// Create a type with an aligned char buffer.
-template<std::size_t Alignment, std::size_t Size>
-struct AlignedCharArray;
-
-// We provide special variations of this template for the most common
-// alignments because __declspec(align(...)) doesn't actually work when it is
-// a member of a by-value function argument in MSVC, even if the alignment
-// request is something reasonably like 8-byte or 16-byte. Note that we can't
-// even include the declspec with the union that forces the alignment because
-// MSVC warns on the existence of the declspec despite the union member forcing
-// proper alignment.
-
-template<std::size_t Size>
-struct AlignedCharArray<1, Size> {
-  union {
-    char aligned;
-    char buffer[Size];
-  };
-};
-
-template<std::size_t Size>
-struct AlignedCharArray<2, Size> {
-  union {
-    short aligned;
-    char buffer[Size];
-  };
-};
-
-template<std::size_t Size>
-struct AlignedCharArray<4, Size> {
-  union {
-    int aligned;
-    char buffer[Size];
-  };
-};
-
-template<std::size_t Size>
-struct AlignedCharArray<8, Size> {
-  union {
-    double aligned;
-    char buffer[Size];
-  };
-};
-
-
-// The rest of these are provided with a __declspec(align(...)) and we simply
-// can't pass them by-value as function arguments on MSVC.
-
-#define LLVM_ALIGNEDCHARARRAY_TEMPLATE_ALIGNMENT(x) \
-  template<std::size_t Size> \
-  struct AlignedCharArray<x, Size> { \
-    __declspec(align(x)) char buffer[Size]; \
-  };
-
-LLVM_ALIGNEDCHARARRAY_TEMPLATE_ALIGNMENT(16)
-LLVM_ALIGNEDCHARARRAY_TEMPLATE_ALIGNMENT(32)
-LLVM_ALIGNEDCHARARRAY_TEMPLATE_ALIGNMENT(64)
-LLVM_ALIGNEDCHARARRAY_TEMPLATE_ALIGNMENT(128)
-
-#undef LLVM_ALIGNEDCHARARRAY_TEMPLATE_ALIGNMENT
-
-#endif // _MSC_VER
-
-namespace detail {
-template <typename T1,
-          typename T2 = char, typename T3 = char, typename T4 = char,
-          typename T5 = char, typename T6 = char, typename T7 = char,
-          typename T8 = char, typename T9 = char, typename T10 = char>
-class AlignerImpl {
-  T1 t1; T2 t2; T3 t3; T4 t4; T5 t5; T6 t6; T7 t7; T8 t8; T9 t9; T10 t10;
-
-  AlignerImpl() = delete;
-};
-
-template <typename T1,
-          typename T2 = char, typename T3 = char, typename T4 = char,
-          typename T5 = char, typename T6 = char, typename T7 = char,
-          typename T8 = char, typename T9 = char, typename T10 = char>
-union SizerImpl {
-  char arr1[sizeof(T1)], arr2[sizeof(T2)], arr3[sizeof(T3)], arr4[sizeof(T4)],
-       arr5[sizeof(T5)], arr6[sizeof(T6)], arr7[sizeof(T7)], arr8[sizeof(T8)],
-       arr9[sizeof(T9)], arr10[sizeof(T10)];
-};
-} // end namespace detail
-
-/// This union template exposes a suitably aligned and sized character
-/// array member which can hold elements of any of up to ten types.
-///
-/// These types may be arrays, structs, or any other types. The goal is to
-/// expose a char array buffer member which can be used as suitable storage for
-/// a placement new of any of these types. Support for more than ten types can
-/// be added at the cost of more boilerplate.
-template <typename T1,
-          typename T2 = char, typename T3 = char, typename T4 = char,
-          typename T5 = char, typename T6 = char, typename T7 = char,
-          typename T8 = char, typename T9 = char, typename T10 = char>
-struct AlignedCharArrayUnion : wpi::AlignedCharArray<
-    alignof(wpi::detail::AlignerImpl<T1, T2, T3, T4, T5,
-                                      T6, T7, T8, T9, T10>),
-    sizeof(::wpi::detail::SizerImpl<T1, T2, T3, T4, T5,
-                                     T6, T7, T8, T9, T10>)> {
-};
-} // end namespace wpi
-
-#endif // LLVM_SUPPORT_ALIGNOF_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/Base64.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/Base64.h
index 41b0062..c410bd0 100644
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/Base64.h
+++ b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/Base64.h
@@ -6,12 +6,11 @@
 #define WPIUTIL_WPI_BASE64_H_
 
 #include <cstddef>
+#include <span>
 #include <string>
 #include <string_view>
 #include <vector>
 
-#include "wpi/span.h"
-
 namespace wpi {
 template <typename T>
 class SmallVectorImpl;
@@ -26,8 +25,8 @@
 
 size_t Base64Decode(std::string_view encoded, std::vector<uint8_t>* plain);
 
-span<uint8_t> Base64Decode(std::string_view encoded, size_t* num_read,
-                           SmallVectorImpl<uint8_t>& buf);
+std::span<uint8_t> Base64Decode(std::string_view encoded, size_t* num_read,
+                                SmallVectorImpl<uint8_t>& buf);
 
 void Base64Encode(raw_ostream& os, std::string_view plain);
 
@@ -36,11 +35,11 @@
 std::string_view Base64Encode(std::string_view plain,
                               SmallVectorImpl<char>& buf);
 
-void Base64Encode(raw_ostream& os, span<const uint8_t> plain);
+void Base64Encode(raw_ostream& os, std::span<const uint8_t> plain);
 
-void Base64Encode(span<const uint8_t> plain, std::string* encoded);
+void Base64Encode(std::span<const uint8_t> plain, std::string* encoded);
 
-std::string_view Base64Encode(span<const uint8_t> plain,
+std::string_view Base64Encode(std::span<const uint8_t> plain,
                               SmallVectorImpl<char>& buf);
 
 }  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/Chrono.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/Chrono.h
deleted file mode 100644
index 33341c6..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/Chrono.h
+++ /dev/null
@@ -1,63 +0,0 @@
-//===- llvm/Support/Chrono.h - Utilities for Timing Manipulation-*- C++ -*-===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-
-#ifndef WPIUTIL_WPI_CHRONO_H
-#define WPIUTIL_WPI_CHRONO_H
-
-#include "wpi/Compiler.h"
-
-#include <chrono>
-#include <ctime>
-
-namespace wpi {
-
-class raw_ostream;
-
-namespace sys {
-
-/// A time point on the system clock. This is provided for two reasons:
-/// - to insulate us against subtle differences in behavior to differences in
-///   system clock precision (which is implementation-defined and differs between
-///   platforms).
-/// - to shorten the type name
-/// The default precision is nanoseconds. If need a specific precision specify
-/// it explicitly. If unsure, use the default. If you need a time point on a
-/// clock other than the system_clock, use std::chrono directly.
-template <typename D = std::chrono::nanoseconds>
-using TimePoint = std::chrono::time_point<std::chrono::system_clock, D>;
-
-/// Convert a TimePoint to std::time_t
-LLVM_ATTRIBUTE_ALWAYS_INLINE std::time_t toTimeT(TimePoint<> TP) {
-  using namespace std::chrono;
-  return system_clock::to_time_t(
-      time_point_cast<system_clock::time_point::duration>(TP));
-}
-
-/// Convert a std::time_t to a TimePoint
-LLVM_ATTRIBUTE_ALWAYS_INLINE TimePoint<std::chrono::seconds>
-toTimePoint(std::time_t T) {
-  using namespace std::chrono;
-  return time_point_cast<seconds>(system_clock::from_time_t(T));
-}
-
-/// Convert a std::time_t + nanoseconds to a TimePoint
-LLVM_ATTRIBUTE_ALWAYS_INLINE TimePoint<>
-toTimePoint(std::time_t T, uint32_t nsec) {
-  using namespace std::chrono;
-  return time_point_cast<nanoseconds>(system_clock::from_time_t(T))
-    + nanoseconds(nsec);
-}
-
-} // namespace sys
-
-raw_ostream &operator<<(raw_ostream &OS, sys::TimePoint<> TP);
-
-} // namespace wpi
-
-#endif // WPIUTIL_WPI_CHRONO_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/Compiler.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/Compiler.h
deleted file mode 100644
index 5ceb605..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/Compiler.h
+++ /dev/null
@@ -1,516 +0,0 @@
-//===-- llvm/Support/Compiler.h - Compiler abstraction support --*- C++ -*-===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-//
-// This file defines several macros, based on the current compiler.  This allows
-// use of compiler-specific features in a way that remains portable.
-//
-//===----------------------------------------------------------------------===//
-
-#ifndef WPIUTIL_WPI_COMPILER_H
-#define WPIUTIL_WPI_COMPILER_H
-
-#include <new>
-#include <stddef.h>
-
-#if defined(_MSC_VER)
-#include <sal.h>
-#endif
-
-#ifndef __has_feature
-# define __has_feature(x) 0
-#endif
-
-#ifndef __has_extension
-# define __has_extension(x) 0
-#endif
-
-#ifndef __has_attribute
-# define __has_attribute(x) 0
-#endif
-
-#ifndef __has_cpp_attribute
-# define __has_cpp_attribute(x) 0
-#endif
-
-#ifndef __has_builtin
-# define __has_builtin(x) 0
-#endif
-
-/// \macro LLVM_GNUC_PREREQ
-/// Extend the default __GNUC_PREREQ even if glibc's features.h isn't
-/// available.
-#ifndef LLVM_GNUC_PREREQ
-# if defined(__GNUC__) && defined(__GNUC_MINOR__) && defined(__GNUC_PATCHLEVEL__)
-#  define LLVM_GNUC_PREREQ(maj, min, patch) \
-    ((__GNUC__ << 20) + (__GNUC_MINOR__ << 10) + __GNUC_PATCHLEVEL__ >= \
-     ((maj) << 20) + ((min) << 10) + (patch))
-# elif defined(__GNUC__) && defined(__GNUC_MINOR__)
-#  define LLVM_GNUC_PREREQ(maj, min, patch) \
-    ((__GNUC__ << 20) + (__GNUC_MINOR__ << 10) >= ((maj) << 20) + ((min) << 10))
-# else
-#  define LLVM_GNUC_PREREQ(maj, min, patch) 0
-# endif
-#endif
-
-/// \macro LLVM_MSC_PREREQ
-/// Is the compiler MSVC of at least the specified version?
-/// The common \param version values to check for are:
-///  * 1900: Microsoft Visual Studio 2015 / 14.0
-#ifndef LLVM_MSC_PREREQ
-#ifdef _MSC_VER
-#define LLVM_MSC_PREREQ(version) (_MSC_VER >= (version))
-
-// We require at least MSVC 2015.
-#if !LLVM_MSC_PREREQ(1900)
-#error wpiutil requires at least MSVC 2015.
-#endif
-
-#else
-#define LLVM_MSC_PREREQ(version) 0
-#endif
-#endif
-
-/// Does the compiler support ref-qualifiers for *this?
-///
-/// Sadly, this is separate from just rvalue reference support because GCC
-/// and MSVC implemented this later than everything else.
-#ifndef LLVM_HAS_RVALUE_REFERENCE_THIS
-#if __has_feature(cxx_rvalue_references) || LLVM_GNUC_PREREQ(4, 8, 1)
-#define LLVM_HAS_RVALUE_REFERENCE_THIS 1
-#else
-#define LLVM_HAS_RVALUE_REFERENCE_THIS 0
-#endif
-#endif
-
-/// Expands to '&' if ref-qualifiers for *this are supported.
-///
-/// This can be used to provide lvalue/rvalue overrides of member functions.
-/// The rvalue override should be guarded by LLVM_HAS_RVALUE_REFERENCE_THIS
-#ifndef LLVM_LVALUE_FUNCTION
-#if LLVM_HAS_RVALUE_REFERENCE_THIS
-#define LLVM_LVALUE_FUNCTION &
-#else
-#define LLVM_LVALUE_FUNCTION
-#endif
-#endif
-
-#ifndef LLVM_PREFETCH
-#if defined(__GNUC__)
-#define LLVM_PREFETCH(addr, rw, locality) __builtin_prefetch(addr, rw, locality)
-#else
-#define LLVM_PREFETCH(addr, rw, locality)
-#endif
-#endif
-
-#ifndef LLVM_ATTRIBUTE_USED
-#if __has_attribute(used) || LLVM_GNUC_PREREQ(3, 1, 0)
-#define LLVM_ATTRIBUTE_USED __attribute__((__used__))
-#else
-#define LLVM_ATTRIBUTE_USED
-#endif
-#endif
-
-/// LLVM_NODISCARD - Warn if a type or return value is discarded.
-#ifndef LLVM_NODISCARD
-#if __cplusplus > 201402L && __has_cpp_attribute(nodiscard)
-#define LLVM_NODISCARD [[nodiscard]]
-// Detect MSVC directly, since __cplusplus still defaults to old version
-#elif _MSVC_LANG >= 201703L
-#define LLVM_NODISCARD [[nodiscard]]
-#elif _MSC_VER
-#define LLVM_NODISCARD
-#elif !__cplusplus
-// Workaround for llvm.org/PR23435, since clang 3.6 and below emit a spurious
-// error when __has_cpp_attribute is given a scoped attribute in C mode.
-#define LLVM_NODISCARD
-#elif __has_cpp_attribute(clang::warn_unused_result)
-#define LLVM_NODISCARD [[clang::warn_unused_result]]
-#else
-#define LLVM_NODISCARD
-#endif
-#endif
-
-// Some compilers warn about unused functions. When a function is sometimes
-// used or not depending on build settings (e.g. a function only called from
-// within "assert"), this attribute can be used to suppress such warnings.
-//
-// However, it shouldn't be used for unused *variables*, as those have a much
-// more portable solution:
-//   (void)unused_var_name;
-// Prefer cast-to-void wherever it is sufficient.
-#ifndef LLVM_ATTRIBUTE_UNUSED
-#if __has_attribute(unused) || LLVM_GNUC_PREREQ(3, 1, 0)
-#define LLVM_ATTRIBUTE_UNUSED __attribute__((__unused__))
-#else
-#define LLVM_ATTRIBUTE_UNUSED
-#endif
-#endif
-
-#ifndef LLVM_READNONE
-// Prior to clang 3.2, clang did not accept any spelling of
-// __has_attribute(const), so assume it is supported.
-#if defined(__clang__) || defined(__GNUC__)
-// aka 'CONST' but following LLVM Conventions.
-#define LLVM_READNONE __attribute__((__const__))
-#else
-#define LLVM_READNONE
-#endif
-#endif
-
-#ifndef LLVM_READONLY
-#if __has_attribute(pure) || defined(__GNUC__)
-// aka 'PURE' but following LLVM Conventions.
-#define LLVM_READONLY __attribute__((__pure__))
-#else
-#define LLVM_READONLY
-#endif
-#endif
-
-#ifndef LLVM_LIKELY
-#if __has_builtin(__builtin_expect) || LLVM_GNUC_PREREQ(4, 0, 0)
-#define LLVM_LIKELY(EXPR) __builtin_expect((bool)(EXPR), true)
-#define LLVM_UNLIKELY(EXPR) __builtin_expect((bool)(EXPR), false)
-#else
-#define LLVM_LIKELY(EXPR) (EXPR)
-#define LLVM_UNLIKELY(EXPR) (EXPR)
-#endif
-#endif
-
-/// LLVM_ATTRIBUTE_NOINLINE - On compilers where we have a directive to do so,
-/// mark a method "not for inlining".
-#ifndef LLVM_ATTRIBUTE_NOINLINE
-#if __has_attribute(noinline) || LLVM_GNUC_PREREQ(3, 4, 0)
-#define LLVM_ATTRIBUTE_NOINLINE __attribute__((noinline))
-#elif defined(_MSC_VER)
-#define LLVM_ATTRIBUTE_NOINLINE __declspec(noinline)
-#else
-#define LLVM_ATTRIBUTE_NOINLINE
-#endif
-#endif
-
-/// LLVM_ATTRIBUTE_ALWAYS_INLINE - On compilers where we have a directive to do
-/// so, mark a method "always inline" because it is performance sensitive. GCC
-/// 3.4 supported this but is buggy in various cases and produces unimplemented
-/// errors, just use it in GCC 4.0 and later.
-#ifndef LLVM_ATTRIBUTE_ALWAYS_INLINE
-#if __has_attribute(always_inline) || LLVM_GNUC_PREREQ(4, 0, 0)
-#define LLVM_ATTRIBUTE_ALWAYS_INLINE __attribute__((always_inline)) inline
-#elif defined(_MSC_VER)
-#define LLVM_ATTRIBUTE_ALWAYS_INLINE __forceinline
-#else
-#define LLVM_ATTRIBUTE_ALWAYS_INLINE inline
-#endif
-#endif
-
-#ifndef LLVM_ATTRIBUTE_NORETURN
-#ifdef __GNUC__
-#define LLVM_ATTRIBUTE_NORETURN __attribute__((noreturn))
-#elif defined(_MSC_VER)
-#define LLVM_ATTRIBUTE_NORETURN __declspec(noreturn)
-#else
-#define LLVM_ATTRIBUTE_NORETURN
-#endif
-#endif
-
-#ifndef LLVM_ATTRIBUTE_RETURNS_NONNULL
-#if __has_attribute(returns_nonnull) || LLVM_GNUC_PREREQ(4, 9, 0)
-#define LLVM_ATTRIBUTE_RETURNS_NONNULL __attribute__((returns_nonnull))
-#elif defined(_MSC_VER)
-#define LLVM_ATTRIBUTE_RETURNS_NONNULL _Ret_notnull_
-#else
-#define LLVM_ATTRIBUTE_RETURNS_NONNULL
-#endif
-#endif
-
-/// \macro LLVM_ATTRIBUTE_RETURNS_NOALIAS Used to mark a function as returning a
-/// pointer that does not alias any other valid pointer.
-#ifndef LLVM_ATTRIBUTE_RETURNS_NOALIAS
-#ifdef __GNUC__
-#define LLVM_ATTRIBUTE_RETURNS_NOALIAS __attribute__((__malloc__))
-#elif defined(_MSC_VER)
-#define LLVM_ATTRIBUTE_RETURNS_NOALIAS __declspec(restrict)
-#else
-#define LLVM_ATTRIBUTE_RETURNS_NOALIAS
-#endif
-#endif
-
-/// LLVM_FALLTHROUGH - Mark fallthrough cases in switch statements.
-#ifndef LLVM_FALLTHROUGH
-#if __cplusplus > 201402L && __has_cpp_attribute(fallthrough)
-#define LLVM_FALLTHROUGH [[fallthrough]]
-// Detect MSVC directly, since __cplusplus still defaults to old version
-#elif _MSVC_LANG >= 201703L
-#define LLVM_FALLTHROUGH [[fallthrough]]
-#elif _MSC_VER
-#define LLVM_FALLTHROUGH
-#elif __has_cpp_attribute(gnu::fallthrough)
-#define LLVM_FALLTHROUGH [[gnu::fallthrough]]
-#elif !__cplusplus
-// Workaround for llvm.org/PR23435, since clang 3.6 and below emit a spurious
-// error when __has_cpp_attribute is given a scoped attribute in C mode.
-#define LLVM_FALLTHROUGH
-#elif __has_cpp_attribute(clang::fallthrough)
-#define LLVM_FALLTHROUGH [[clang::fallthrough]]
-#else
-#define LLVM_FALLTHROUGH
-#endif
-#endif
-
-/// LLVM_EXTENSION - Support compilers where we have a keyword to suppress
-/// pedantic diagnostics.
-#ifndef LLVM_EXTENSION
-#ifdef __GNUC__
-#define LLVM_EXTENSION __extension__
-#else
-#define LLVM_EXTENSION
-#endif
-#endif
-
-// LLVM_ATTRIBUTE_DEPRECATED(decl, "message")
-#ifndef LLVM_ATTRIBUTE_DEPRECATED
-#if __has_feature(attribute_deprecated_with_message)
-# define LLVM_ATTRIBUTE_DEPRECATED(decl, message) \
-  decl __attribute__((deprecated(message)))
-#elif defined(__GNUC__)
-# define LLVM_ATTRIBUTE_DEPRECATED(decl, message) \
-  decl __attribute__((deprecated))
-#elif defined(_MSC_VER)
-# define LLVM_ATTRIBUTE_DEPRECATED(decl, message) \
-  __declspec(deprecated(message)) decl
-#else
-# define LLVM_ATTRIBUTE_DEPRECATED(decl, message) \
-  decl
-#endif
-#endif
-
-/// LLVM_BUILTIN_UNREACHABLE - On compilers which support it, expands
-/// to an expression which states that it is undefined behavior for the
-/// compiler to reach this point.  Otherwise is not defined.
-#ifndef LLVM_BUILTIN_UNREACHABLE
-#if __has_builtin(__builtin_unreachable) || LLVM_GNUC_PREREQ(4, 5, 0)
-# define LLVM_BUILTIN_UNREACHABLE __builtin_unreachable()
-#elif defined(_MSC_VER)
-# define LLVM_BUILTIN_UNREACHABLE __assume(false)
-#endif
-#endif
-
-/// LLVM_BUILTIN_TRAP - On compilers which support it, expands to an expression
-/// which causes the program to exit abnormally.
-#ifndef LLVM_BUILTIN_TRAP
-#if __has_builtin(__builtin_trap) || LLVM_GNUC_PREREQ(4, 3, 0)
-# define LLVM_BUILTIN_TRAP __builtin_trap()
-#elif defined(_MSC_VER)
-// The __debugbreak intrinsic is supported by MSVC, does not require forward
-// declarations involving platform-specific typedefs (unlike RaiseException),
-// results in a call to vectored exception handlers, and encodes to a short
-// instruction that still causes the trapping behavior we want.
-# define LLVM_BUILTIN_TRAP __debugbreak()
-#else
-# define LLVM_BUILTIN_TRAP *(volatile int*)0x11 = 0
-#endif
-#endif
-
-/// LLVM_BUILTIN_DEBUGTRAP - On compilers which support it, expands to
-/// an expression which causes the program to break while running
-/// under a debugger.
-#ifndef LLVM_BUILTIN_DEBUGTRAP
-#if __has_builtin(__builtin_debugtrap)
-# define LLVM_BUILTIN_DEBUGTRAP __builtin_debugtrap()
-#elif defined(_MSC_VER)
-// The __debugbreak intrinsic is supported by MSVC and breaks while
-// running under the debugger, and also supports invoking a debugger
-// when the OS is configured appropriately.
-# define LLVM_BUILTIN_DEBUGTRAP __debugbreak()
-#else
-// Just continue execution when built with compilers that have no
-// support. This is a debugging aid and not intended to force the
-// program to abort if encountered.
-# define LLVM_BUILTIN_DEBUGTRAP
-#endif
-#endif
-
-/// \macro LLVM_ASSUME_ALIGNED
-/// Returns a pointer with an assumed alignment.
-#ifndef LLVM_ASSUME_ALIGNED
-#if __has_builtin(__builtin_assume_aligned) || LLVM_GNUC_PREREQ(4, 7, 0)
-# define LLVM_ASSUME_ALIGNED(p, a) __builtin_assume_aligned(p, a)
-#elif defined(LLVM_BUILTIN_UNREACHABLE)
-// As of today, clang does not support __builtin_assume_aligned.
-# define LLVM_ASSUME_ALIGNED(p, a) \
-           (((uintptr_t(p) % (a)) == 0) ? (p) : (LLVM_BUILTIN_UNREACHABLE, (p)))
-#else
-# define LLVM_ASSUME_ALIGNED(p, a) (p)
-#endif
-#endif
-
-/// \macro LLVM_ALIGNAS
-/// Used to specify a minimum alignment for a structure or variable.
-#ifndef LLVM_ALIGNAS
-#if __GNUC__ && !__has_feature(cxx_alignas) && !LLVM_GNUC_PREREQ(4, 8, 1)
-# define LLVM_ALIGNAS(x) __attribute__((aligned(x)))
-#else
-# define LLVM_ALIGNAS(x) alignas(x)
-#endif
-#endif
-
-/// \macro LLVM_PACKED
-/// Used to specify a packed structure.
-/// LLVM_PACKED(
-///    struct A {
-///      int i;
-///      int j;
-///      int k;
-///      long long l;
-///   });
-///
-/// LLVM_PACKED_START
-/// struct B {
-///   int i;
-///   int j;
-///   int k;
-///   long long l;
-/// };
-/// LLVM_PACKED_END
-#ifndef LLVM_PACKED
-#ifdef _MSC_VER
-# define LLVM_PACKED(d) __pragma(pack(push, 1)) d __pragma(pack(pop))
-# define LLVM_PACKED_START __pragma(pack(push, 1))
-# define LLVM_PACKED_END   __pragma(pack(pop))
-#else
-# define LLVM_PACKED(d) d __attribute__((packed))
-# define LLVM_PACKED_START _Pragma("pack(push, 1)")
-# define LLVM_PACKED_END   _Pragma("pack(pop)")
-#endif
-#endif
-
-/// \macro LLVM_PTR_SIZE
-/// A constant integer equivalent to the value of sizeof(void*).
-/// Generally used in combination with LLVM_ALIGNAS or when doing computation in
-/// the preprocessor.
-#ifndef LLVM_PTR_SIZE
-#ifdef __SIZEOF_POINTER__
-# define LLVM_PTR_SIZE __SIZEOF_POINTER__
-#elif defined(_WIN64)
-# define LLVM_PTR_SIZE 8
-#elif defined(_WIN32)
-# define LLVM_PTR_SIZE 4
-#elif defined(_MSC_VER)
-# error "could not determine LLVM_PTR_SIZE as a constant int for MSVC"
-#else
-# define LLVM_PTR_SIZE sizeof(void *)
-#endif
-#endif
-
-/// \macro LLVM_NO_SANITIZE
-/// Disable a particular sanitizer for a function.
-#ifndef LLVM_NO_SANITIZE
-#if __has_attribute(no_sanitize)
-#define LLVM_NO_SANITIZE(KIND) __attribute__((no_sanitize(KIND)))
-#else
-#define LLVM_NO_SANITIZE(KIND)
-#endif
-#endif
-
-/// Mark debug helper function definitions like dump() that should not be
-/// stripped from debug builds.
-/// Note that you should also surround dump() functions with
-/// `#if !defined(NDEBUG) || defined(LLVM_ENABLE_DUMP)` so they do always
-/// get stripped in release builds.
-// FIXME: Move this to a private config.h as it's not usable in public headers.
-#ifndef LLVM_DUMP_METHOD
-#if !defined(NDEBUG) || defined(LLVM_ENABLE_DUMP)
-#define LLVM_DUMP_METHOD LLVM_ATTRIBUTE_NOINLINE LLVM_ATTRIBUTE_USED
-#else
-#define LLVM_DUMP_METHOD LLVM_ATTRIBUTE_NOINLINE
-#endif
-#endif
-
-/// \macro LLVM_PRETTY_FUNCTION
-/// Gets a user-friendly looking function signature for the current scope
-/// using the best available method on each platform.  The exact format of the
-/// resulting string is implementation specific and non-portable, so this should
-/// only be used, for example, for logging or diagnostics.
-#ifndef LLVM_PRETTY_FUNCTION
-#if defined(_MSC_VER)
-#define LLVM_PRETTY_FUNCTION __FUNCSIG__
-#elif defined(__GNUC__) || defined(__clang__)
-#define LLVM_PRETTY_FUNCTION __PRETTY_FUNCTION__
-#else
-#define LLVM_PRETTY_FUNCTION __func__
-#endif
-#endif
-
-/// \macro LLVM_THREAD_LOCAL
-/// A thread-local storage specifier which can be used with globals,
-/// extern globals, and static globals.
-///
-/// This is essentially an extremely restricted analog to C++11's thread_local
-/// support, and uses that when available. However, it falls back on
-/// platform-specific or vendor-provided extensions when necessary. These
-/// extensions don't support many of the C++11 thread_local's features. You
-/// should only use this for PODs that you can statically initialize to
-/// some constant value. In almost all circumstances this is most appropriate
-/// for use with a pointer, integer, or small aggregation of pointers and
-/// integers.
-#ifndef LLVM_THREAD_LOCAL
-#if __has_feature(cxx_thread_local)
-#define LLVM_THREAD_LOCAL thread_local
-#elif defined(_MSC_VER)
-// MSVC supports this with a __declspec.
-#define LLVM_THREAD_LOCAL __declspec(thread)
-#else
-// Clang, GCC, and other compatible compilers used __thread prior to C++11 and
-// we only need the restricted functionality that provides.
-#define LLVM_THREAD_LOCAL __thread
-#endif
-#endif
-
-namespace wpi {
-
-/// Allocate a buffer of memory with the given size and alignment.
-///
-/// When the compiler supports aligned operator new, this will use it to to
-/// handle even over-aligned allocations.
-///
-/// However, this doesn't make any attempt to leverage the fancier techniques
-/// like posix_memalign due to portability. It is mostly intended to allow
-/// compatibility with platforms that, after aligned allocation was added, use
-/// reduced default alignment.
-inline void *allocate_buffer(size_t Size, size_t Alignment) {
-  return ::operator new(Size
-#ifdef __cpp_aligned_new
-                        ,
-                        std::align_val_t(Alignment)
-#endif
-  );
-}
-
-/// Deallocate a buffer of memory with the given size and alignment.
-///
-/// If supported, this will used the sized delete operator. Also if supported,
-/// this will pass the alignment to the delete operator.
-///
-/// The pointer must have been allocated with the corresponding new operator,
-/// most likely using the above helper.
-inline void deallocate_buffer(void *Ptr, size_t Size, size_t Alignment) {
-  ::operator delete(Ptr
-#ifdef __cpp_sized_deallocation
-                    ,
-                    Size
-#endif
-#ifdef __cpp_aligned_new
-                    ,
-                    std::align_val_t(Alignment)
-#endif
-  );
-}
-
-} // End namespace wpi
-
-#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/ConvertUTF.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/ConvertUTF.h
deleted file mode 100644
index aa113b1..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/ConvertUTF.h
+++ /dev/null
@@ -1,269 +0,0 @@
-/*===--- ConvertUTF.h - Universal Character Names conversions ---------------===
- *
- *                     The LLVM Compiler Infrastructure
- *
- * This file is distributed under the University of Illinois Open Source
- * License. See LICENSE.TXT for details.
- *
- *==------------------------------------------------------------------------==*/
-/*
- * Copyright 2001-2004 Unicode, Inc.
- *
- * Disclaimer
- *
- * This source code is provided as is by Unicode, Inc. No claims are
- * made as to fitness for any particular purpose. No warranties of any
- * kind are expressed or implied. The recipient agrees to determine
- * applicability of information provided. If this file has been
- * purchased on magnetic or optical media from Unicode, Inc., the
- * sole remedy for any claim will be exchange of defective media
- * within 90 days of receipt.
- *
- * Limitations on Rights to Redistribute This Code
- *
- * Unicode, Inc. hereby grants the right to freely use the information
- * supplied in this file in the creation of products supporting the
- * Unicode Standard, and to make copies of this file in any form
- * for internal or external distribution as long as this notice
- * remains attached.
- */
-
-/* ---------------------------------------------------------------------
-
-    Conversions between UTF32, UTF-16, and UTF-8.  Header file.
-
-    Several funtions are included here, forming a complete set of
-    conversions between the three formats.  UTF-7 is not included
-    here, but is handled in a separate source file.
-
-    Each of these routines takes pointers to input buffers and output
-    buffers.  The input buffers are const.
-
-    Each routine converts the text between *sourceStart and sourceEnd,
-    putting the result into the buffer between *targetStart and
-    targetEnd. Note: the end pointers are *after* the last item: e.g.
-    *(sourceEnd - 1) is the last item.
-
-    The return result indicates whether the conversion was successful,
-    and if not, whether the problem was in the source or target buffers.
-    (Only the first encountered problem is indicated.)
-
-    After the conversion, *sourceStart and *targetStart are both
-    updated to point to the end of last text successfully converted in
-    the respective buffers.
-
-    Input parameters:
-        sourceStart - pointer to a pointer to the source buffer.
-                The contents of this are modified on return so that
-                it points at the next thing to be converted.
-        targetStart - similarly, pointer to pointer to the target buffer.
-        sourceEnd, targetEnd - respectively pointers to the ends of the
-                two buffers, for overflow checking only.
-
-    These conversion functions take a ConversionFlags argument. When this
-    flag is set to strict, both irregular sequences and isolated surrogates
-    will cause an error.  When the flag is set to lenient, both irregular
-    sequences and isolated surrogates are converted.
-
-    Whether the flag is strict or lenient, all illegal sequences will cause
-    an error return. This includes sequences such as: <F4 90 80 80>, <C0 80>,
-    or <A0> in UTF-8, and values above 0x10FFFF in UTF-32. Conformant code
-    must check for illegal sequences.
-
-    When the flag is set to lenient, characters over 0x10FFFF are converted
-    to the replacement character; otherwise (when the flag is set to strict)
-    they constitute an error.
-
-    Output parameters:
-        The value "sourceIllegal" is returned from some routines if the input
-        sequence is malformed.  When "sourceIllegal" is returned, the source
-        value will point to the illegal value that caused the problem. E.g.,
-        in UTF-8 when a sequence is malformed, it points to the start of the
-        malformed sequence.
-
-    Author: Mark E. Davis, 1994.
-    Rev History: Rick McGowan, fixes & updates May 2001.
-         Fixes & updates, Sept 2001.
-
------------------------------------------------------------------------- */
-
-#ifndef LLVM_SUPPORT_CONVERTUTF_H
-#define LLVM_SUPPORT_CONVERTUTF_H
-
-#include "wpi/span.h"
-
-#include <cstddef>
-#include <string>
-#include <string_view>
-#include <system_error>
-
-// Wrap everything in namespace wpi so that programs can link with wpiutil and
-// their own version of the unicode libraries.
-
-namespace wpi {
-
-template <typename T>
-class SmallVectorImpl;
-
-/* ---------------------------------------------------------------------
-    The following 4 definitions are compiler-specific.
-    The C standard does not guarantee that wchar_t has at least
-    16 bits, so wchar_t is no less portable than unsigned short!
-    All should be unsigned values to avoid sign extension during
-    bit mask & shift operations.
------------------------------------------------------------------------- */
-
-typedef unsigned int    UTF32;  /* at least 32 bits */
-typedef unsigned short  UTF16;  /* at least 16 bits */
-typedef unsigned char   UTF8;   /* typically 8 bits */
-typedef bool   Boolean; /* 0 or 1 */
-
-/* Some fundamental constants */
-#define UNI_REPLACEMENT_CHAR (UTF32)0x0000FFFD
-#define UNI_MAX_BMP (UTF32)0x0000FFFF
-#define UNI_MAX_UTF16 (UTF32)0x0010FFFF
-#define UNI_MAX_UTF32 (UTF32)0x7FFFFFFF
-#define UNI_MAX_LEGAL_UTF32 (UTF32)0x0010FFFF
-
-#define UNI_MAX_UTF8_BYTES_PER_CODE_POINT 4
-
-#define UNI_UTF16_BYTE_ORDER_MARK_NATIVE  0xFEFF
-#define UNI_UTF16_BYTE_ORDER_MARK_SWAPPED 0xFFFE
-
-typedef enum {
-  conversionOK,           /* conversion successful */
-  sourceExhausted,        /* partial character in source, but hit end */
-  targetExhausted,        /* insuff. room in target for conversion */
-  sourceIllegal           /* source sequence is illegal/malformed */
-} ConversionResult;
-
-typedef enum {
-  strictConversion = 0,
-  lenientConversion
-} ConversionFlags;
-
-ConversionResult ConvertUTF8toUTF16 (
-  const UTF8** sourceStart, const UTF8* sourceEnd,
-  UTF16** targetStart, UTF16* targetEnd, ConversionFlags flags);
-
-/**
- * Convert a partial UTF8 sequence to UTF32.  If the sequence ends in an
- * incomplete code unit sequence, returns \c sourceExhausted.
- */
-ConversionResult ConvertUTF8toUTF32Partial(
-  const UTF8** sourceStart, const UTF8* sourceEnd,
-  UTF32** targetStart, UTF32* targetEnd, ConversionFlags flags);
-
-/**
- * Convert a partial UTF8 sequence to UTF32.  If the sequence ends in an
- * incomplete code unit sequence, returns \c sourceIllegal.
- */
-ConversionResult ConvertUTF8toUTF32(
-  const UTF8** sourceStart, const UTF8* sourceEnd,
-  UTF32** targetStart, UTF32* targetEnd, ConversionFlags flags);
-
-ConversionResult ConvertUTF16toUTF8 (
-  const UTF16** sourceStart, const UTF16* sourceEnd,
-  UTF8** targetStart, UTF8* targetEnd, ConversionFlags flags);
-
-ConversionResult ConvertUTF32toUTF8 (
-  const UTF32** sourceStart, const UTF32* sourceEnd,
-  UTF8** targetStart, UTF8* targetEnd, ConversionFlags flags);
-
-ConversionResult ConvertUTF16toUTF32 (
-  const UTF16** sourceStart, const UTF16* sourceEnd,
-  UTF32** targetStart, UTF32* targetEnd, ConversionFlags flags);
-
-ConversionResult ConvertUTF32toUTF16 (
-  const UTF32** sourceStart, const UTF32* sourceEnd,
-  UTF16** targetStart, UTF16* targetEnd, ConversionFlags flags);
-
-Boolean isLegalUTF8Sequence(const UTF8 *source, const UTF8 *sourceEnd);
-
-Boolean isLegalUTF8String(const UTF8 **source, const UTF8 *sourceEnd);
-
-unsigned getNumBytesForUTF8(UTF8 firstByte);
-
-/*************************************************************************/
-/* Below are LLVM-specific wrappers of the functions above. */
-
-
-/**
- * Convert an Unicode code point to UTF8 sequence.
- *
- * \param Source a Unicode code point.
- * \param [in,out] ResultPtr pointer to the output buffer, needs to be at least
- * \c UNI_MAX_UTF8_BYTES_PER_CODE_POINT bytes.  On success \c ResultPtr is
- * updated one past end of the converted sequence.
- *
- * \returns true on success.
- */
-bool ConvertCodePointToUTF8(unsigned Source, char *&ResultPtr);
-
-/**
- * Convert the first UTF8 sequence in the given source buffer to a UTF32
- * code point.
- *
- * \param [in,out] source A pointer to the source buffer. If the conversion
- * succeeds, this pointer will be updated to point to the byte just past the
- * end of the converted sequence.
- * \param sourceEnd A pointer just past the end of the source buffer.
- * \param [out] target The converted code
- * \param flags Whether the conversion is strict or lenient.
- *
- * \returns conversionOK on success
- *
- * \sa ConvertUTF8toUTF32
- */
-static inline ConversionResult convertUTF8Sequence(const UTF8 **source,
-                                                   const UTF8 *sourceEnd,
-                                                   UTF32 *target,
-                                                   ConversionFlags flags) {
-  if (*source == sourceEnd)
-    return sourceExhausted;
-  unsigned size = getNumBytesForUTF8(**source);
-  if ((ptrdiff_t)size > sourceEnd - *source)
-    return sourceExhausted;
-  return ConvertUTF8toUTF32(source, *source + size, &target, target + 1, flags);
-}
-
-/**
- * Returns true if a blob of text starts with a UTF-16 big or little endian byte
- * order mark.
- */
-bool hasUTF16ByteOrderMark(span<const char> SrcBytes);
-
-/**
- * Converts a UTF-16 string into a UTF-8 string.
- *
- * \returns true on success
- */
-bool convertUTF16ToUTF8String(span<const UTF16> SrcUTF16,
-                              SmallVectorImpl<char> &DstUTF8);
-
-/**
- * Converts a UTF-8 string into a UTF-16 string with native endianness.
- *
- * \returns true on success
- */
-bool convertUTF8ToUTF16String(std::string_view SrcUTF8,
-                              SmallVectorImpl<UTF16> &DstUTF16);
-
-#if defined(_WIN32)
-namespace sys {
-namespace windows {
-std::error_code UTF8ToUTF16(std::string_view utf8, SmallVectorImpl<wchar_t> &utf16);
-/// Convert to UTF16 from the current code page used in the system
-std::error_code CurCPToUTF16(std::string_view utf8, SmallVectorImpl<wchar_t> &utf16);
-std::error_code UTF16ToUTF8(const wchar_t *utf16, size_t utf16_len,
-                            SmallVectorImpl<char> &utf8);
-/// Convert from UTF16 to the current code page used in the system
-std::error_code UTF16ToCurCP(const wchar_t *utf16, size_t utf16_len,
-                             SmallVectorImpl<char> &utf8);
-} // namespace windows
-} // namespace sys
-#endif
-
-} /* end namespace wpi */
-
-#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/DataLog.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/DataLog.h
new file mode 100644
index 0000000..cac273c
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/DataLog.h
@@ -0,0 +1,696 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <stdint.h>
+
+#include <functional>
+#include <initializer_list>
+#include <memory>
+#include <span>
+#include <string>
+#include <string_view>
+#include <thread>
+#include <vector>
+
+#include "wpi/DenseMap.h"
+#include "wpi/StringMap.h"
+#include "wpi/condition_variable.h"
+#include "wpi/mutex.h"
+
+namespace wpi {
+class Logger;
+}  // namespace wpi
+
+namespace wpi::log {
+
+namespace impl {
+
+enum ControlRecordType {
+  kControlStart = 0,
+  kControlFinish,
+  kControlSetMetadata
+};
+
+}  // namespace impl
+
+/**
+ * A data log. The log file is created immediately upon construction with a
+ * temporary filename.  The file may be renamed at any time using the
+ * SetFilename() function.
+ *
+ * The lifetime of the data log object must be longer than any data log entry
+ * objects that refer to it.
+ *
+ * The data log is periodically flushed to disk.  It can also be explicitly
+ * flushed to disk by using the Flush() function.
+ *
+ * Finish() is needed only to indicate in the log that a particular entry is
+ * no longer being used (it releases the name to ID mapping).  Finish() is not
+ * required to be called for data to be flushed to disk; entries in the log
+ * are written as Append() calls are being made.  In fact, Finish() does not
+ * need to be called at all; this is helpful to avoid shutdown races where the
+ * DataLog object might be destroyed before other objects.  It's often not a
+ * good idea to call Finish() from destructors for this reason.
+ *
+ * DataLog calls are thread safe.  DataLog uses a typical multiple-supplier,
+ * single-consumer setup.  Writes to the log are atomic, but there is no
+ * guaranteed order in the log when multiple threads are writing to it;
+ * whichever thread grabs the write mutex first will get written first.
+ * For this reason (as well as the fact that timestamps can be set to
+ * arbitrary values), records in the log are not guaranteed to be sorted by
+ * timestamp.
+ */
+class DataLog final {
+ public:
+  /**
+   * Construct a new Data Log.  The log will be initially created with a
+   * temporary filename.
+   *
+   * @param dir directory to store the log
+   * @param filename filename to use; if none provided, a random filename is
+   *                 generated of the form "wpilog_{}.wpilog"
+   * @param period time between automatic flushes to disk, in seconds;
+   *               this is a time/storage tradeoff
+   * @param extraHeader extra header data
+   */
+  explicit DataLog(std::string_view dir = "", std::string_view filename = "",
+                   double period = 0.25, std::string_view extraHeader = "");
+
+  /**
+   * Construct a new Data Log.  The log will be initially created with a
+   * temporary filename.
+   *
+   * @param msglog message logger (will be called from separate thread)
+   * @param dir directory to store the log
+   * @param filename filename to use; if none provided, a random filename is
+   *                 generated of the form "wpilog_{}.wpilog"
+   * @param period time between automatic flushes to disk, in seconds;
+   *               this is a time/storage tradeoff
+   * @param extraHeader extra header data
+   */
+  explicit DataLog(wpi::Logger& msglog, std::string_view dir = "",
+                   std::string_view filename = "", double period = 0.25,
+                   std::string_view extraHeader = "");
+
+  /**
+   * Construct a new Data Log that passes its output to the provided function
+   * rather than a file.  The write function will be called on a separate
+   * background thread and may block.  The write function is called with an
+   * empty data array when the thread is terminating.
+   *
+   * @param write write function
+   * @param period time between automatic calls to write, in seconds;
+   *               this is a time/storage tradeoff
+   * @param extraHeader extra header data
+   */
+  explicit DataLog(std::function<void(std::span<const uint8_t> data)> write,
+                   double period = 0.25, std::string_view extraHeader = "");
+
+  /**
+   * Construct a new Data Log that passes its output to the provided function
+   * rather than a file.  The write function will be called on a separate
+   * background thread and may block.  The write function is called with an
+   * empty data array when the thread is terminating.
+   *
+   * @param msglog message logger (will be called from separate thread)
+   * @param write write function
+   * @param period time between automatic calls to write, in seconds;
+   *               this is a time/storage tradeoff
+   * @param extraHeader extra header data
+   */
+  explicit DataLog(wpi::Logger& msglog,
+                   std::function<void(std::span<const uint8_t> data)> write,
+                   double period = 0.25, std::string_view extraHeader = "");
+
+  ~DataLog();
+  DataLog(const DataLog&) = delete;
+  DataLog& operator=(const DataLog&) = delete;
+  DataLog(DataLog&&) = delete;
+  DataLog& operator=(const DataLog&&) = delete;
+
+  /**
+   * Change log filename.
+   *
+   * @param filename filename
+   */
+  void SetFilename(std::string_view filename);
+
+  /**
+   * Explicitly flushes the log data to disk.
+   */
+  void Flush();
+
+  /**
+   * Pauses appending of data records to the log.  While paused, no data records
+   * are saved (e.g. AppendX is a no-op).  Has no effect on entry starts /
+   * finishes / metadata changes.
+   */
+  void Pause();
+
+  /**
+   * Resumes appending of data records to the log.
+   */
+  void Resume();
+
+  /**
+   * Start an entry.  Duplicate names are allowed (with the same type), and
+   * result in the same index being returned (Start/Finish are reference
+   * counted).  A duplicate name with a different type will result in an error
+   * message being printed to the console and 0 being returned (which will be
+   * ignored by the Append functions).
+   *
+   * @param name Name
+   * @param type Data type
+   * @param metadata Initial metadata (e.g. data properties)
+   * @param timestamp Time stamp (may be 0 to indicate now)
+   *
+   * @return Entry index
+   */
+  int Start(std::string_view name, std::string_view type,
+            std::string_view metadata = {}, int64_t timestamp = 0);
+
+  /**
+   * Finish an entry.
+   *
+   * @param entry Entry index
+   * @param timestamp Time stamp (may be 0 to indicate now)
+   */
+  void Finish(int entry, int64_t timestamp = 0);
+
+  /**
+   * Updates the metadata for an entry.
+   *
+   * @param entry Entry index
+   * @param metadata New metadata for the entry
+   * @param timestamp Time stamp (may be 0 to indicate now)
+   */
+  void SetMetadata(int entry, std::string_view metadata, int64_t timestamp = 0);
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param entry Entry index, as returned by Start()
+   * @param data Data to record
+   * @param timestamp Time stamp (may be 0 to indicate now)
+   */
+  void AppendRaw(int entry, std::span<const uint8_t> data, int64_t timestamp);
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param entry Entry index, as returned by Start()
+   * @param data Data to record
+   * @param timestamp Time stamp (may be 0 to indicate now)
+   */
+  void AppendRaw2(int entry, std::span<const std::span<const uint8_t>> data,
+                  int64_t timestamp);
+
+  void AppendBoolean(int entry, bool value, int64_t timestamp);
+  void AppendInteger(int entry, int64_t value, int64_t timestamp);
+  void AppendFloat(int entry, float value, int64_t timestamp);
+  void AppendDouble(int entry, double value, int64_t timestamp);
+  void AppendString(int entry, std::string_view value, int64_t timestamp);
+  void AppendBooleanArray(int entry, std::span<const bool> arr,
+                          int64_t timestamp);
+  void AppendBooleanArray(int entry, std::span<const int> arr,
+                          int64_t timestamp);
+  void AppendBooleanArray(int entry, std::span<const uint8_t> arr,
+                          int64_t timestamp);
+  void AppendIntegerArray(int entry, std::span<const int64_t> arr,
+                          int64_t timestamp);
+  void AppendFloatArray(int entry, std::span<const float> arr,
+                        int64_t timestamp);
+  void AppendDoubleArray(int entry, std::span<const double> arr,
+                         int64_t timestamp);
+  void AppendStringArray(int entry, std::span<const std::string> arr,
+                         int64_t timestamp);
+  void AppendStringArray(int entry, std::span<const std::string_view> arr,
+                         int64_t timestamp);
+
+ private:
+  void WriterThreadMain(std::string_view dir);
+  void WriterThreadMain(
+      std::function<void(std::span<const uint8_t> data)> write);
+
+  // must be called with m_mutex held
+  uint8_t* StartRecord(uint32_t entry, uint64_t timestamp, uint32_t payloadSize,
+                       size_t reserveSize);
+  uint8_t* Reserve(size_t size);
+  void AppendImpl(std::span<const uint8_t> data);
+  void AppendStringImpl(std::string_view str);
+
+  wpi::Logger& m_msglog;
+  mutable wpi::mutex m_mutex;
+  wpi::condition_variable m_cond;
+  bool m_active{true};
+  bool m_doFlush{false};
+  bool m_paused{false};
+  double m_period;
+  std::string m_extraHeader;
+  std::string m_newFilename;
+  class Buffer;
+  std::vector<Buffer> m_free;
+  std::vector<Buffer> m_outgoing;
+  struct EntryInfo {
+    std::string type;
+    int id{0};
+  };
+  wpi::StringMap<EntryInfo> m_entries;
+  wpi::DenseMap<int, unsigned int> m_entryCounts;
+  int m_lastId = 0;
+  std::thread m_thread;
+};
+
+/**
+ * Log entry base class.
+ */
+class DataLogEntry {
+ protected:
+  DataLogEntry() = default;
+  DataLogEntry(DataLog& log, std::string_view name, std::string_view type,
+               std::string_view metadata = {}, int64_t timestamp = 0)
+      : m_log{&log}, m_entry{log.Start(name, type, metadata, timestamp)} {}
+
+ public:
+  DataLogEntry(const DataLogEntry&) = delete;
+  DataLogEntry& operator=(const DataLogEntry&) = delete;
+
+  DataLogEntry(DataLogEntry&& rhs) : m_log{rhs.m_log}, m_entry{rhs.m_entry} {
+    rhs.m_log = nullptr;
+  }
+  DataLogEntry& operator=(DataLogEntry&& rhs) {
+    if (m_log) {
+      m_log->Finish(m_entry);
+    }
+    m_log = rhs.m_log;
+    rhs.m_log = nullptr;
+    m_entry = rhs.m_entry;
+    return *this;
+  }
+
+  explicit operator bool() const { return m_log != nullptr; }
+
+  /**
+   * Updates the metadata for the entry.
+   *
+   * @param metadata New metadata for the entry
+   * @param timestamp Time stamp (may be 0 to indicate now)
+   */
+  void SetMetadata(std::string_view metadata, int64_t timestamp = 0) {
+    m_log->SetMetadata(m_entry, metadata, timestamp);
+  }
+
+  /**
+   * Finishes the entry.
+   *
+   * @param timestamp Time stamp (may be 0 to indicate now)
+   */
+  void Finish(int64_t timestamp = 0) { m_log->Finish(m_entry, timestamp); }
+
+ protected:
+  DataLog* m_log = nullptr;
+  int m_entry = 0;
+};
+
+/**
+ * Log arbitrary byte data.
+ */
+class RawLogEntry : public DataLogEntry {
+ public:
+  static constexpr std::string_view kDataType = "raw";
+
+  RawLogEntry() = default;
+  RawLogEntry(DataLog& log, std::string_view name, int64_t timestamp = 0)
+      : RawLogEntry{log, name, {}, kDataType, timestamp} {}
+  RawLogEntry(DataLog& log, std::string_view name, std::string_view metadata,
+              int64_t timestamp = 0)
+      : RawLogEntry{log, name, metadata, kDataType, timestamp} {}
+  RawLogEntry(DataLog& log, std::string_view name, std::string_view metadata,
+              std::string_view type, int64_t timestamp = 0)
+      : DataLogEntry{log, name, type, metadata, timestamp} {}
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param data Data to record
+   * @param timestamp Time stamp (may be 0 to indicate now)
+   */
+  void Append(std::span<const uint8_t> data, int64_t timestamp = 0) {
+    m_log->AppendRaw(m_entry, data, timestamp);
+  }
+};
+
+/**
+ * Log boolean values.
+ */
+class BooleanLogEntry : public DataLogEntry {
+ public:
+  static constexpr std::string_view kDataType = "boolean";
+
+  BooleanLogEntry() = default;
+  BooleanLogEntry(DataLog& log, std::string_view name, int64_t timestamp = 0)
+      : BooleanLogEntry{log, name, {}, timestamp} {}
+  BooleanLogEntry(DataLog& log, std::string_view name,
+                  std::string_view metadata, int64_t timestamp = 0)
+      : DataLogEntry{log, name, kDataType, metadata, timestamp} {}
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param value Value to record
+   * @param timestamp Time stamp (may be 0 to indicate now)
+   */
+  void Append(bool value, int64_t timestamp = 0) {
+    m_log->AppendBoolean(m_entry, value, timestamp);
+  }
+};
+
+/**
+ * Log integer values.
+ */
+class IntegerLogEntry : public DataLogEntry {
+ public:
+  static constexpr std::string_view kDataType = "int64";
+
+  IntegerLogEntry() = default;
+  IntegerLogEntry(DataLog& log, std::string_view name, int64_t timestamp = 0)
+      : IntegerLogEntry{log, name, {}, timestamp} {}
+  IntegerLogEntry(DataLog& log, std::string_view name,
+                  std::string_view metadata, int64_t timestamp = 0)
+      : DataLogEntry{log, name, kDataType, metadata, timestamp} {}
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param value Value to record
+   * @param timestamp Time stamp (may be 0 to indicate now)
+   */
+  void Append(int64_t value, int64_t timestamp = 0) {
+    m_log->AppendInteger(m_entry, value, timestamp);
+  }
+};
+
+/**
+ * Log float values.
+ */
+class FloatLogEntry : public DataLogEntry {
+ public:
+  static constexpr std::string_view kDataType = "float";
+
+  FloatLogEntry() = default;
+  FloatLogEntry(DataLog& log, std::string_view name, int64_t timestamp = 0)
+      : FloatLogEntry{log, name, {}, timestamp} {}
+  FloatLogEntry(DataLog& log, std::string_view name, std::string_view metadata,
+                int64_t timestamp = 0)
+      : DataLogEntry{log, name, kDataType, metadata, timestamp} {}
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param value Value to record
+   * @param timestamp Time stamp (may be 0 to indicate now)
+   */
+  void Append(float value, int64_t timestamp = 0) {
+    m_log->AppendFloat(m_entry, value, timestamp);
+  }
+};
+
+/**
+ * Log double values.
+ */
+class DoubleLogEntry : public DataLogEntry {
+ public:
+  static constexpr std::string_view kDataType = "double";
+
+  DoubleLogEntry() = default;
+  DoubleLogEntry(DataLog& log, std::string_view name, int64_t timestamp = 0)
+      : DoubleLogEntry{log, name, {}, timestamp} {}
+  DoubleLogEntry(DataLog& log, std::string_view name, std::string_view metadata,
+                 int64_t timestamp = 0)
+      : DataLogEntry{log, name, kDataType, metadata, timestamp} {}
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param value Value to record
+   * @param timestamp Time stamp (may be 0 to indicate now)
+   */
+  void Append(double value, int64_t timestamp = 0) {
+    m_log->AppendDouble(m_entry, value, timestamp);
+  }
+};
+
+/**
+ * Log string values.
+ */
+class StringLogEntry : public DataLogEntry {
+ public:
+  static constexpr const char* kDataType = "string";
+
+  StringLogEntry() = default;
+  StringLogEntry(DataLog& log, std::string_view name, int64_t timestamp = 0)
+      : StringLogEntry{log, name, {}, kDataType, timestamp} {}
+  StringLogEntry(DataLog& log, std::string_view name, std::string_view metadata,
+                 int64_t timestamp = 0)
+      : StringLogEntry{log, name, metadata, kDataType, timestamp} {}
+  StringLogEntry(DataLog& log, std::string_view name, std::string_view metadata,
+                 std::string_view type, int64_t timestamp = 0)
+      : DataLogEntry{log, name, type, metadata, timestamp} {}
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param value Value to record
+   * @param timestamp Time stamp (may be 0 to indicate now)
+   */
+  void Append(std::string_view value, int64_t timestamp = 0) {
+    m_log->AppendString(m_entry, value, timestamp);
+  }
+};
+
+/**
+ * Log array of boolean values.
+ */
+class BooleanArrayLogEntry : public DataLogEntry {
+ public:
+  static constexpr const char* kDataType = "boolean[]";
+
+  BooleanArrayLogEntry() = default;
+  BooleanArrayLogEntry(DataLog& log, std::string_view name,
+                       int64_t timestamp = 0)
+      : BooleanArrayLogEntry{log, name, {}, timestamp} {}
+  BooleanArrayLogEntry(DataLog& log, std::string_view name,
+                       std::string_view metadata, int64_t timestamp = 0)
+      : DataLogEntry{log, name, kDataType, metadata, timestamp} {}
+
+  /**
+   * Appends a record to the log.  For find functions to work, timestamp
+   * must be monotonically increasing.
+   *
+   * @param arr Values to record
+   * @param timestamp Time stamp (may be 0 to indicate now)
+   */
+  void Append(std::span<const bool> arr, int64_t timestamp = 0) {
+    m_log->AppendBooleanArray(m_entry, arr, timestamp);
+  }
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param arr Values to record
+   * @param timestamp Time stamp (may be 0 to indicate now)
+   */
+  void Append(std::initializer_list<bool> arr, int64_t timestamp = 0) {
+    Append(std::span{arr.begin(), arr.end()}, timestamp);
+  }
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param arr Values to record
+   * @param timestamp Time stamp (may be 0 to indicate now)
+   */
+  void Append(std::span<const int> arr, int64_t timestamp = 0) {
+    m_log->AppendBooleanArray(m_entry, arr, timestamp);
+  }
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param arr Values to record
+   * @param timestamp Time stamp (may be 0 to indicate now)
+   */
+  void Append(std::initializer_list<int> arr, int64_t timestamp = 0) {
+    Append(std::span{arr.begin(), arr.end()}, timestamp);
+  }
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param arr Values to record
+   * @param timestamp Time stamp (may be 0 to indicate now)
+   */
+  void Append(std::span<const uint8_t> arr, int64_t timestamp = 0) {
+    m_log->AppendBooleanArray(m_entry, arr, timestamp);
+  }
+};
+
+/**
+ * Log array of integer values.
+ */
+class IntegerArrayLogEntry : public DataLogEntry {
+ public:
+  static constexpr const char* kDataType = "int64[]";
+
+  IntegerArrayLogEntry() = default;
+  IntegerArrayLogEntry(DataLog& log, std::string_view name,
+                       int64_t timestamp = 0)
+      : IntegerArrayLogEntry{log, name, {}, timestamp} {}
+  IntegerArrayLogEntry(DataLog& log, std::string_view name,
+                       std::string_view metadata, int64_t timestamp = 0)
+      : DataLogEntry{log, name, kDataType, metadata, timestamp} {}
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param arr Values to record
+   * @param timestamp Time stamp (may be 0 to indicate now)
+   */
+  void Append(std::span<const int64_t> arr, int64_t timestamp = 0) {
+    m_log->AppendIntegerArray(m_entry, arr, timestamp);
+  }
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param arr Values to record
+   * @param timestamp Time stamp (may be 0 to indicate now)
+   */
+  void Append(std::initializer_list<int64_t> arr, int64_t timestamp = 0) {
+    Append({arr.begin(), arr.end()}, timestamp);
+  }
+};
+
+/**
+ * Log array of float values.
+ */
+class FloatArrayLogEntry : public DataLogEntry {
+ public:
+  static constexpr const char* kDataType = "float[]";
+
+  FloatArrayLogEntry() = default;
+  FloatArrayLogEntry(DataLog& log, std::string_view name, int64_t timestamp = 0)
+      : FloatArrayLogEntry{log, name, {}, timestamp} {}
+  FloatArrayLogEntry(DataLog& log, std::string_view name,
+                     std::string_view metadata, int64_t timestamp = 0)
+      : DataLogEntry{log, name, kDataType, metadata, timestamp} {}
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param arr Values to record
+   * @param timestamp Time stamp (may be 0 to indicate now)
+   */
+  void Append(std::span<const float> arr, int64_t timestamp = 0) {
+    m_log->AppendFloatArray(m_entry, arr, timestamp);
+  }
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param arr Values to record
+   * @param timestamp Time stamp (may be 0 to indicate now)
+   */
+  void Append(std::initializer_list<float> arr, int64_t timestamp = 0) {
+    Append({arr.begin(), arr.end()}, timestamp);
+  }
+};
+
+/**
+ * Log array of double values.
+ */
+class DoubleArrayLogEntry : public DataLogEntry {
+ public:
+  static constexpr const char* kDataType = "double[]";
+
+  DoubleArrayLogEntry() = default;
+  DoubleArrayLogEntry(DataLog& log, std::string_view name,
+                      int64_t timestamp = 0)
+      : DoubleArrayLogEntry{log, name, {}, timestamp} {}
+  DoubleArrayLogEntry(DataLog& log, std::string_view name,
+                      std::string_view metadata, int64_t timestamp = 0)
+      : DataLogEntry{log, name, kDataType, metadata, timestamp} {}
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param arr Values to record
+   * @param timestamp Time stamp (may be 0 to indicate now)
+   */
+  void Append(std::span<const double> arr, int64_t timestamp = 0) {
+    m_log->AppendDoubleArray(m_entry, arr, timestamp);
+  }
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param arr Values to record
+   * @param timestamp Time stamp (may be 0 to indicate now)
+   */
+  void Append(std::initializer_list<double> arr, int64_t timestamp = 0) {
+    Append({arr.begin(), arr.end()}, timestamp);
+  }
+};
+
+/**
+ * Log array of string values.
+ */
+class StringArrayLogEntry : public DataLogEntry {
+ public:
+  static constexpr const char* kDataType = "string[]";
+
+  StringArrayLogEntry() = default;
+  StringArrayLogEntry(DataLog& log, std::string_view name,
+                      int64_t timestamp = 0)
+      : StringArrayLogEntry{log, name, {}, timestamp} {}
+  StringArrayLogEntry(DataLog& log, std::string_view name,
+                      std::string_view metadata, int64_t timestamp = 0)
+      : DataLogEntry{log, name, kDataType, metadata, timestamp} {}
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param arr Values to record
+   * @param timestamp Time stamp (may be 0 to indicate now)
+   */
+  void Append(std::span<const std::string> arr, int64_t timestamp = 0) {
+    m_log->AppendStringArray(m_entry, arr, timestamp);
+  }
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param arr Values to record
+   * @param timestamp Time stamp (may be 0 to indicate now)
+   */
+  void Append(std::span<const std::string_view> arr, int64_t timestamp = 0) {
+    m_log->AppendStringArray(m_entry, arr, timestamp);
+  }
+
+  /**
+   * Appends a record to the log.
+   *
+   * @param arr Values to record
+   * @param timestamp Time stamp (may be 0 to indicate now)
+   */
+  void Append(std::initializer_list<std::string_view> arr,
+              int64_t timestamp = 0) {
+    Append(std::span<const std::string_view>{arr.begin(), arr.end()},
+           timestamp);
+  }
+};
+
+}  // namespace wpi::log
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/DataLogReader.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/DataLogReader.h
new file mode 100644
index 0000000..b1153e4
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/DataLogReader.h
@@ -0,0 +1,369 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <stdint.h>
+
+#include <iterator>
+#include <memory>
+#include <span>
+#include <utility>
+#include <vector>
+
+#include "wpi/MemoryBuffer.h"
+
+namespace wpi::log {
+
+/**
+ * Data contained in a start control record as created by DataLog::Start() when
+ * writing the log. This can be read by calling DataLogRecord::GetStartData().
+ */
+struct StartRecordData {
+  /** Entry ID; this will be used for this entry in future records. */
+  int entry;
+
+  /** Entry name. */
+  std::string_view name;
+
+  /** Type of the stored data for this entry, as a string, e.g. "double". */
+  std::string_view type;
+
+  /** Initial metadata. */
+  std::string_view metadata;
+};
+
+/**
+ * Data contained in a set metadata control record as created by
+ * DataLog::SetMetadata(). This can be read by calling
+ * DataLogRecord::GetSetMetadataData().
+ */
+struct MetadataRecordData {
+  /** Entry ID. */
+  int entry;
+
+  /** New metadata for the entry. */
+  std::string_view metadata;
+};
+
+/**
+ * A record in the data log. May represent either a control record (entry == 0)
+ * or a data record. Used only for reading (e.g. with DataLogReader).
+ */
+class DataLogRecord {
+ public:
+  DataLogRecord() = default;
+  DataLogRecord(int entry, int64_t timestamp, std::span<const uint8_t> data)
+      : m_timestamp{timestamp}, m_data{data}, m_entry{entry} {}
+
+  /**
+   * Gets the entry ID.
+   *
+   * @return entry ID
+   */
+  int GetEntry() const { return m_entry; }
+
+  /**
+   * Gets the record timestamp.
+   *
+   * @return Timestamp, in integer microseconds
+   */
+  int64_t GetTimestamp() const { return m_timestamp; }
+
+  /**
+   * Gets the size of the raw data.
+   *
+   * @return size
+   */
+  size_t GetSize() const { return m_data.size(); }
+
+  /**
+   * Gets the raw data. Use the GetX functions to decode based on the data type
+   * in the entry's start record.
+   */
+  std::span<const uint8_t> GetRaw() const { return m_data; }
+
+  /**
+   * Returns true if the record is a control record.
+   *
+   * @return True if control record, false if normal data record.
+   */
+  bool IsControl() const { return m_entry == 0; }
+
+  /**
+   * Returns true if the record is a start control record. Use GetStartData()
+   * to decode the contents.
+   *
+   * @return True if start control record, false otherwise.
+   */
+  bool IsStart() const;
+
+  /**
+   * Returns true if the record is a finish control record. Use GetFinishEntry()
+   * to decode the contents.
+   *
+   * @return True if finish control record, false otherwise.
+   */
+  bool IsFinish() const;
+
+  /**
+   * Returns true if the record is a set metadata control record. Use
+   * GetSetMetadataData() to decode the contents.
+   *
+   * @return True if set metadata control record, false otherwise.
+   */
+  bool IsSetMetadata() const;
+
+  /**
+   * Decodes a start control record.
+   *
+   * @param[out] out start record decoded data (if successful)
+   * @return True on success, false on error
+   */
+  bool GetStartData(StartRecordData* out) const;
+
+  /**
+   * Decodes a finish control record.
+   *
+   * @param[out] out finish record entry ID (if successful)
+   * @return True on success, false on error
+   */
+  bool GetFinishEntry(int* out) const;
+
+  /**
+   * Decodes a set metadata control record.
+   *
+   * @param[out] out set metadata record decoded data (if successful)
+   * @return True on success, false on error
+   */
+  bool GetSetMetadataData(MetadataRecordData* out) const;
+
+  /**
+   * Decodes a data record as a boolean. Note if the data type (as indicated in
+   * the corresponding start control record for this entry) is not "boolean",
+   * invalid results may be returned.
+   *
+   * @param[out] value boolean value (if successful)
+   * @return True on success, false on error
+   */
+  bool GetBoolean(bool* value) const;
+
+  /**
+   * Decodes a data record as an integer. Note if the data type (as indicated in
+   * the corresponding start control record for this entry) is not "int64",
+   * invalid results may be returned.
+   *
+   * @param[out] value integer value (if successful)
+   * @return True on success, false on error
+   */
+  bool GetInteger(int64_t* value) const;
+
+  /**
+   * Decodes a data record as a float. Note if the data type (as indicated in
+   * the corresponding start control record for this entry) is not "float",
+   * invalid results may be returned.
+   *
+   * @param[out] value float value (if successful)
+   * @return True on success, false on error
+   */
+  bool GetFloat(float* value) const;
+
+  /**
+   * Decodes a data record as a double. Note if the data type (as indicated in
+   * the corresponding start control record for this entry) is not "double",
+   * invalid results may be returned.
+   *
+   * @param[out] value double value (if successful)
+   * @return True on success, false on error
+   */
+  bool GetDouble(double* value) const;
+
+  /**
+   * Decodes a data record as a string. Note if the data type (as indicated in
+   * the corresponding start control record for this entry) is not "string",
+   * invalid results may be returned.
+   *
+   * @param[out] value string value
+   * @return True (never fails)
+   */
+  bool GetString(std::string_view* value) const;
+
+  /**
+   * Decodes a data record as a boolean array. Note if the data type (as
+   * indicated in the corresponding start control record for this entry) is not
+   * "boolean[]", invalid results may be returned.
+   *
+   * @param[out] arr boolean array
+   * @return True (never fails)
+   */
+  bool GetBooleanArray(std::vector<int>* arr) const;
+
+  /**
+   * Decodes a data record as an integer array. Note if the data type (as
+   * indicated in the corresponding start control record for this entry) is not
+   * "int64[]", invalid results may be returned.
+   *
+   * @param[out] arr integer array (if successful)
+   * @return True on success, false on error
+   */
+  bool GetIntegerArray(std::vector<int64_t>* arr) const;
+
+  /**
+   * Decodes a data record as a float array. Note if the data type (as
+   * indicated in the corresponding start control record for this entry) is not
+   * "float[]", invalid results may be returned.
+   *
+   * @param[out] arr float array (if successful)
+   * @return True on success, false on error
+   */
+  bool GetFloatArray(std::vector<float>* arr) const;
+
+  /**
+   * Decodes a data record as a double array. Note if the data type (as
+   * indicated in the corresponding start control record for this entry) is not
+   * "double[]", invalid results may be returned.
+   *
+   * @param[out] arr double array (if successful)
+   * @return True on success, false on error
+   */
+  bool GetDoubleArray(std::vector<double>* arr) const;
+
+  /**
+   * Decodes a data record as a string array. Note if the data type (as
+   * indicated in the corresponding start control record for this entry) is not
+   * "string[]", invalid results may be returned.
+   *
+   * @param[out] arr string array (if successful)
+   * @return True on success, false on error
+   */
+  bool GetStringArray(std::vector<std::string_view>* arr) const;
+
+ private:
+  int64_t m_timestamp{0};
+  std::span<const uint8_t> m_data;
+  int m_entry{-1};
+};
+
+class DataLogReader;
+
+/** DataLogReader iterator. */
+class DataLogIterator {
+ public:
+  using iterator_category = std::forward_iterator_tag;
+  using value_type = DataLogRecord;
+  using pointer = const value_type*;
+  using reference = const value_type&;
+
+  DataLogIterator(const DataLogReader* reader, size_t pos)
+      : m_reader{reader}, m_pos{pos} {}
+
+  bool operator==(const DataLogIterator& oth) const {
+    return m_reader == oth.m_reader && m_pos == oth.m_pos;
+  }
+  bool operator!=(const DataLogIterator& oth) const {
+    return !this->operator==(oth);
+  }
+
+  bool operator<(const DataLogIterator& oth) const { return m_pos < oth.m_pos; }
+  bool operator>(const DataLogIterator& oth) const {
+    return !this->operator<(oth) && !this->operator==(oth);
+  }
+  bool operator<=(const DataLogIterator& oth) const {
+    return !this->operator>(oth);
+  }
+  bool operator>=(const DataLogIterator& oth) const {
+    return !this->operator<(oth);
+  }
+
+  DataLogIterator& operator++();
+
+  DataLogIterator operator++(int) {
+    DataLogIterator tmp = *this;
+    ++*this;
+    return tmp;
+  }
+
+  reference operator*() const;
+
+  pointer operator->() const { return &this->operator*(); }
+
+ private:
+  const DataLogReader* m_reader;
+  size_t m_pos;
+  mutable bool m_valid = false;
+  mutable DataLogRecord m_value;
+};
+
+/** Data log reader (reads logs written by the DataLog class). */
+class DataLogReader {
+  friend class DataLogIterator;
+
+ public:
+  using iterator = DataLogIterator;
+
+  /** Constructs from a memory buffer. */
+  explicit DataLogReader(std::unique_ptr<MemoryBuffer> buffer);
+
+  /** Returns true if the data log is valid (e.g. has a valid header). */
+  explicit operator bool() const { return IsValid(); }
+
+  /** Returns true if the data log is valid (e.g. has a valid header). */
+  bool IsValid() const;
+
+  /**
+   * Gets the data log version. Returns 0 if data log is invalid.
+   *
+   * @return Version number; most significant byte is major, least significant
+   *         is minor (so version 1.0 will be 0x0100)
+   */
+  uint16_t GetVersion() const;
+
+  /**
+   * Gets the extra header data.
+   *
+   * @return Extra header data
+   */
+  std::string_view GetExtraHeader() const;
+
+  /**
+   * Gets the buffer identifier, typically the filename.
+   *
+   * @return Identifier string
+   */
+  std::string_view GetBufferIdentifier() const {
+    return m_buf ? m_buf->GetBufferIdentifier() : "Invalid";
+  }
+
+  /** Returns iterator to first record. */
+  iterator begin() const;
+
+  /** Returns end iterator. */
+  iterator end() const { return DataLogIterator{this, SIZE_MAX}; }
+
+ private:
+  std::unique_ptr<MemoryBuffer> m_buf;
+
+  bool GetRecord(size_t* pos, DataLogRecord* out) const;
+  bool GetNextRecord(size_t* pos) const;
+};
+
+inline DataLogIterator& DataLogIterator::operator++() {
+  if (!m_reader->GetNextRecord(&m_pos)) {
+    m_pos = SIZE_MAX;
+  }
+  m_valid = false;
+  return *this;
+}
+
+inline DataLogIterator::reference DataLogIterator::operator*() const {
+  if (!m_valid) {
+    size_t pos = m_pos;
+    if (m_reader->GetRecord(&pos, &m_value)) {
+      m_valid = true;
+    }
+  }
+  return m_value;
+}
+
+}  // namespace wpi::log
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/DenseMap.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/DenseMap.h
deleted file mode 100644
index 12bb712..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/DenseMap.h
+++ /dev/null
@@ -1,1239 +0,0 @@
-//===- llvm/ADT/DenseMap.h - Dense probed hash table ------------*- C++ -*-===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-//
-// This file defines the DenseMap class.
-//
-//===----------------------------------------------------------------------===//
-
-#ifndef WPIUTIL_WPI_DENSEMAP_H
-#define WPIUTIL_WPI_DENSEMAP_H
-
-#include "wpi/DenseMapInfo.h"
-#include "wpi/EpochTracker.h"
-#include "wpi/AlignOf.h"
-#include "wpi/Compiler.h"
-#include "wpi/MathExtras.h"
-#include "wpi/PointerLikeTypeTraits.h"
-#include "wpi/type_traits.h"
-#include <algorithm>
-#include <cassert>
-#include <cstddef>
-#include <cstring>
-#include <iterator>
-#include <new>
-#include <type_traits>
-#include <utility>
-
-namespace wpi {
-
-namespace detail {
-
-// We extend a pair to allow users to override the bucket type with their own
-// implementation without requiring two members.
-template <typename KeyT, typename ValueT>
-struct DenseMapPair : public std::pair<KeyT, ValueT> {
-  KeyT &getFirst() { return std::pair<KeyT, ValueT>::first; }
-  const KeyT &getFirst() const { return std::pair<KeyT, ValueT>::first; }
-  ValueT &getSecond() { return std::pair<KeyT, ValueT>::second; }
-  const ValueT &getSecond() const { return std::pair<KeyT, ValueT>::second; }
-};
-
-} // end namespace detail
-
-template <typename KeyT, typename ValueT,
-          typename KeyInfoT = DenseMapInfo<KeyT>,
-          typename Bucket = wpi::detail::DenseMapPair<KeyT, ValueT>,
-          bool IsConst = false>
-class DenseMapIterator;
-
-template <typename DerivedT, typename KeyT, typename ValueT, typename KeyInfoT,
-          typename BucketT>
-class DenseMapBase : public DebugEpochBase {
-  template <typename T>
-  using const_arg_type_t = typename const_pointer_or_const_ref<T>::type;
-
-public:
-  using size_type = unsigned;
-  using key_type = KeyT;
-  using mapped_type = ValueT;
-  using value_type = BucketT;
-
-  using iterator = DenseMapIterator<KeyT, ValueT, KeyInfoT, BucketT>;
-  using const_iterator =
-      DenseMapIterator<KeyT, ValueT, KeyInfoT, BucketT, true>;
-
-  inline iterator begin() {
-    // When the map is empty, avoid the overhead of advancing/retreating past
-    // empty buckets.
-    if (empty())
-      return end();
-    return makeIterator(getBuckets(), getBucketsEnd(), *this);
-  }
-  inline iterator end() {
-    return makeIterator(getBucketsEnd(), getBucketsEnd(), *this, true);
-  }
-  inline const_iterator begin() const {
-    if (empty())
-      return end();
-    return makeConstIterator(getBuckets(), getBucketsEnd(), *this);
-  }
-  inline const_iterator end() const {
-    return makeConstIterator(getBucketsEnd(), getBucketsEnd(), *this, true);
-  }
-
-  LLVM_NODISCARD bool empty() const {
-    return getNumEntries() == 0;
-  }
-  unsigned size() const { return getNumEntries(); }
-
-  /// Grow the densemap so that it can contain at least \p NumEntries items
-  /// before resizing again.
-  void reserve(size_type NumEntries) {
-    auto NumBuckets = getMinBucketToReserveForEntries(NumEntries);
-    incrementEpoch();
-    if (NumBuckets > getNumBuckets())
-      grow(NumBuckets);
-  }
-
-  void clear() {
-    incrementEpoch();
-    if (getNumEntries() == 0 && getNumTombstones() == 0) return;
-
-    // If the capacity of the array is huge, and the # elements used is small,
-    // shrink the array.
-    if (getNumEntries() * 4 < getNumBuckets() && getNumBuckets() > 64) {
-      shrink_and_clear();
-      return;
-    }
-
-    const KeyT EmptyKey = getEmptyKey(), TombstoneKey = getTombstoneKey();
-    if (isPodLike<KeyT>::value && isPodLike<ValueT>::value) {
-      // Use a simpler loop when these are trivial types.
-      for (BucketT *P = getBuckets(), *E = getBucketsEnd(); P != E; ++P)
-        P->getFirst() = EmptyKey;
-    } else {
-      unsigned NumEntries = getNumEntries();
-      for (BucketT *P = getBuckets(), *E = getBucketsEnd(); P != E; ++P) {
-        if (!KeyInfoT::isEqual(P->getFirst(), EmptyKey)) {
-          if (!KeyInfoT::isEqual(P->getFirst(), TombstoneKey)) {
-            P->getSecond().~ValueT();
-            --NumEntries;
-          }
-          P->getFirst() = EmptyKey;
-        }
-      }
-      assert(NumEntries == 0 && "Node count imbalance!");
-    }
-    setNumEntries(0);
-    setNumTombstones(0);
-  }
-
-  /// Return 1 if the specified key is in the map, 0 otherwise.
-  size_type count(const_arg_type_t<KeyT> Val) const {
-    const BucketT *TheBucket;
-    return LookupBucketFor(Val, TheBucket) ? 1 : 0;
-  }
-
-  iterator find(const_arg_type_t<KeyT> Val) {
-    BucketT *TheBucket;
-    if (LookupBucketFor(Val, TheBucket))
-      return makeIterator(TheBucket, getBucketsEnd(), *this, true);
-    return end();
-  }
-  const_iterator find(const_arg_type_t<KeyT> Val) const {
-    const BucketT *TheBucket;
-    if (LookupBucketFor(Val, TheBucket))
-      return makeConstIterator(TheBucket, getBucketsEnd(), *this, true);
-    return end();
-  }
-
-  /// Alternate version of find() which allows a different, and possibly
-  /// less expensive, key type.
-  /// The DenseMapInfo is responsible for supplying methods
-  /// getHashValue(LookupKeyT) and isEqual(LookupKeyT, KeyT) for each key
-  /// type used.
-  template<class LookupKeyT>
-  iterator find_as(const LookupKeyT &Val) {
-    BucketT *TheBucket;
-    if (LookupBucketFor(Val, TheBucket))
-      return makeIterator(TheBucket, getBucketsEnd(), *this, true);
-    return end();
-  }
-  template<class LookupKeyT>
-  const_iterator find_as(const LookupKeyT &Val) const {
-    const BucketT *TheBucket;
-    if (LookupBucketFor(Val, TheBucket))
-      return makeConstIterator(TheBucket, getBucketsEnd(), *this, true);
-    return end();
-  }
-
-  /// lookup - Return the entry for the specified key, or a default
-  /// constructed value if no such entry exists.
-  ValueT lookup(const_arg_type_t<KeyT> Val) const {
-    const BucketT *TheBucket;
-    if (LookupBucketFor(Val, TheBucket))
-      return TheBucket->getSecond();
-    return ValueT();
-  }
-
-  // Inserts key,value pair into the map if the key isn't already in the map.
-  // If the key is already in the map, it returns false and doesn't update the
-  // value.
-  std::pair<iterator, bool> insert(const std::pair<KeyT, ValueT> &KV) {
-    return try_emplace(KV.first, KV.second);
-  }
-
-  // Inserts key,value pair into the map if the key isn't already in the map.
-  // If the key is already in the map, it returns false and doesn't update the
-  // value.
-  std::pair<iterator, bool> insert(std::pair<KeyT, ValueT> &&KV) {
-    return try_emplace(std::move(KV.first), std::move(KV.second));
-  }
-
-  // Inserts key,value pair into the map if the key isn't already in the map.
-  // The value is constructed in-place if the key is not in the map, otherwise
-  // it is not moved.
-  template <typename... Ts>
-  std::pair<iterator, bool> try_emplace(KeyT &&Key, Ts &&... Args) {
-    BucketT *TheBucket;
-    if (LookupBucketFor(Key, TheBucket))
-      return std::make_pair(
-               makeIterator(TheBucket, getBucketsEnd(), *this, true),
-               false); // Already in map.
-
-    // Otherwise, insert the new element.
-    TheBucket =
-        InsertIntoBucket(TheBucket, std::move(Key), std::forward<Ts>(Args)...);
-    return std::make_pair(
-             makeIterator(TheBucket, getBucketsEnd(), *this, true),
-             true);
-  }
-
-  // Inserts key,value pair into the map if the key isn't already in the map.
-  // The value is constructed in-place if the key is not in the map, otherwise
-  // it is not moved.
-  template <typename... Ts>
-  std::pair<iterator, bool> try_emplace(const KeyT &Key, Ts &&... Args) {
-    BucketT *TheBucket;
-    if (LookupBucketFor(Key, TheBucket))
-      return std::make_pair(
-               makeIterator(TheBucket, getBucketsEnd(), *this, true),
-               false); // Already in map.
-
-    // Otherwise, insert the new element.
-    TheBucket = InsertIntoBucket(TheBucket, Key, std::forward<Ts>(Args)...);
-    return std::make_pair(
-             makeIterator(TheBucket, getBucketsEnd(), *this, true),
-             true);
-  }
-
-  /// Alternate version of insert() which allows a different, and possibly
-  /// less expensive, key type.
-  /// The DenseMapInfo is responsible for supplying methods
-  /// getHashValue(LookupKeyT) and isEqual(LookupKeyT, KeyT) for each key
-  /// type used.
-  template <typename LookupKeyT>
-  std::pair<iterator, bool> insert_as(std::pair<KeyT, ValueT> &&KV,
-                                      const LookupKeyT &Val) {
-    BucketT *TheBucket;
-    if (LookupBucketFor(Val, TheBucket))
-      return std::make_pair(
-               makeIterator(TheBucket, getBucketsEnd(), *this, true),
-               false); // Already in map.
-
-    // Otherwise, insert the new element.
-    TheBucket = InsertIntoBucketWithLookup(TheBucket, std::move(KV.first),
-                                           std::move(KV.second), Val);
-    return std::make_pair(
-             makeIterator(TheBucket, getBucketsEnd(), *this, true),
-             true);
-  }
-
-  /// insert - Range insertion of pairs.
-  template<typename InputIt>
-  void insert(InputIt I, InputIt E) {
-    for (; I != E; ++I)
-      insert(*I);
-  }
-
-  bool erase(const KeyT &Val) {
-    BucketT *TheBucket;
-    if (!LookupBucketFor(Val, TheBucket))
-      return false; // not in map.
-
-    TheBucket->getSecond().~ValueT();
-    TheBucket->getFirst() = getTombstoneKey();
-    decrementNumEntries();
-    incrementNumTombstones();
-    return true;
-  }
-  void erase(iterator I) {
-    BucketT *TheBucket = &*I;
-    TheBucket->getSecond().~ValueT();
-    TheBucket->getFirst() = getTombstoneKey();
-    decrementNumEntries();
-    incrementNumTombstones();
-  }
-
-  value_type& FindAndConstruct(const KeyT &Key) {
-    BucketT *TheBucket;
-    if (LookupBucketFor(Key, TheBucket))
-      return *TheBucket;
-
-    return *InsertIntoBucket(TheBucket, Key);
-  }
-
-  ValueT &operator[](const KeyT &Key) {
-    return FindAndConstruct(Key).second;
-  }
-
-  value_type& FindAndConstruct(KeyT &&Key) {
-    BucketT *TheBucket;
-    if (LookupBucketFor(Key, TheBucket))
-      return *TheBucket;
-
-    return *InsertIntoBucket(TheBucket, std::move(Key));
-  }
-
-  ValueT &operator[](KeyT &&Key) {
-    return FindAndConstruct(std::move(Key)).second;
-  }
-
-  /// isPointerIntoBucketsArray - Return true if the specified pointer points
-  /// somewhere into the DenseMap's array of buckets (i.e. either to a key or
-  /// value in the DenseMap).
-  bool isPointerIntoBucketsArray(const void *Ptr) const {
-    return Ptr >= getBuckets() && Ptr < getBucketsEnd();
-  }
-
-  /// getPointerIntoBucketsArray() - Return an opaque pointer into the buckets
-  /// array.  In conjunction with the previous method, this can be used to
-  /// determine whether an insertion caused the DenseMap to reallocate.
-  const void *getPointerIntoBucketsArray() const { return getBuckets(); }
-
-protected:
-  DenseMapBase() = default;
-
-  void destroyAll() {
-    if (getNumBuckets() == 0) // Nothing to do.
-      return;
-
-    const KeyT EmptyKey = getEmptyKey(), TombstoneKey = getTombstoneKey();
-    for (BucketT *P = getBuckets(), *E = getBucketsEnd(); P != E; ++P) {
-      if (!KeyInfoT::isEqual(P->getFirst(), EmptyKey) &&
-          !KeyInfoT::isEqual(P->getFirst(), TombstoneKey))
-        P->getSecond().~ValueT();
-      P->getFirst().~KeyT();
-    }
-  }
-
-  void initEmpty() {
-    setNumEntries(0);
-    setNumTombstones(0);
-
-    assert((getNumBuckets() & (getNumBuckets()-1)) == 0 &&
-           "# initial buckets must be a power of two!");
-    const KeyT EmptyKey = getEmptyKey();
-    for (BucketT *B = getBuckets(), *E = getBucketsEnd(); B != E; ++B)
-      ::new (&B->getFirst()) KeyT(EmptyKey);
-  }
-
-  /// Returns the number of buckets to allocate to ensure that the DenseMap can
-  /// accommodate \p NumEntries without need to grow().
-  unsigned getMinBucketToReserveForEntries(unsigned NumEntries) {
-    // Ensure that "NumEntries * 4 < NumBuckets * 3"
-    if (NumEntries == 0)
-      return 0;
-    // +1 is required because of the strict equality.
-    // For example if NumEntries is 48, we need to return 401.
-    return static_cast<unsigned>(NextPowerOf2(NumEntries * 4 / 3 + 1));
-  }
-
-  void moveFromOldBuckets(BucketT *OldBucketsBegin, BucketT *OldBucketsEnd) {
-    initEmpty();
-
-    // Insert all the old elements.
-    const KeyT EmptyKey = getEmptyKey();
-    const KeyT TombstoneKey = getTombstoneKey();
-    for (BucketT *B = OldBucketsBegin, *E = OldBucketsEnd; B != E; ++B) {
-      if (!KeyInfoT::isEqual(B->getFirst(), EmptyKey) &&
-          !KeyInfoT::isEqual(B->getFirst(), TombstoneKey)) {
-        // Insert the key/value into the new table.
-        BucketT *DestBucket;
-        bool FoundVal = LookupBucketFor(B->getFirst(), DestBucket);
-        (void)FoundVal; // silence warning.
-        assert(!FoundVal && "Key already in new map?");
-        DestBucket->getFirst() = std::move(B->getFirst());
-        ::new (&DestBucket->getSecond()) ValueT(std::move(B->getSecond()));
-        incrementNumEntries();
-
-        // Free the value.
-        B->getSecond().~ValueT();
-      }
-      B->getFirst().~KeyT();
-    }
-  }
-
-  template <typename OtherBaseT>
-  void copyFrom(
-      const DenseMapBase<OtherBaseT, KeyT, ValueT, KeyInfoT, BucketT> &other) {
-    assert(&other != this);
-    assert(getNumBuckets() == other.getNumBuckets());
-
-    setNumEntries(other.getNumEntries());
-    setNumTombstones(other.getNumTombstones());
-
-    if (isPodLike<KeyT>::value && isPodLike<ValueT>::value)
-      memcpy(reinterpret_cast<void *>(getBuckets()), other.getBuckets(),
-             getNumBuckets() * sizeof(BucketT));
-    else
-      for (size_t i = 0; i < getNumBuckets(); ++i) {
-        ::new (&getBuckets()[i].getFirst())
-            KeyT(other.getBuckets()[i].getFirst());
-        if (!KeyInfoT::isEqual(getBuckets()[i].getFirst(), getEmptyKey()) &&
-            !KeyInfoT::isEqual(getBuckets()[i].getFirst(), getTombstoneKey()))
-          ::new (&getBuckets()[i].getSecond())
-              ValueT(other.getBuckets()[i].getSecond());
-      }
-  }
-
-  static unsigned getHashValue(const KeyT &Val) {
-    return KeyInfoT::getHashValue(Val);
-  }
-
-  template<typename LookupKeyT>
-  static unsigned getHashValue(const LookupKeyT &Val) {
-    return KeyInfoT::getHashValue(Val);
-  }
-
-  static const KeyT getEmptyKey() {
-    static_assert(std::is_base_of<DenseMapBase, DerivedT>::value,
-                  "Must pass the derived type to this template!");
-    return KeyInfoT::getEmptyKey();
-  }
-
-  static const KeyT getTombstoneKey() {
-    return KeyInfoT::getTombstoneKey();
-  }
-
-private:
-  iterator makeIterator(BucketT *P, BucketT *E,
-                        DebugEpochBase &Epoch,
-                        bool NoAdvance=false) {
-    return iterator(P, E, Epoch, NoAdvance);
-  }
-
-  const_iterator makeConstIterator(const BucketT *P, const BucketT *E,
-                                   const DebugEpochBase &Epoch,
-                                   const bool NoAdvance=false) const {
-    return const_iterator(P, E, Epoch, NoAdvance);
-  }
-
-  unsigned getNumEntries() const {
-    return static_cast<const DerivedT *>(this)->getNumEntries();
-  }
-
-  void setNumEntries(unsigned Num) {
-    static_cast<DerivedT *>(this)->setNumEntries(Num);
-  }
-
-  void incrementNumEntries() {
-    setNumEntries(getNumEntries() + 1);
-  }
-
-  void decrementNumEntries() {
-    setNumEntries(getNumEntries() - 1);
-  }
-
-  unsigned getNumTombstones() const {
-    return static_cast<const DerivedT *>(this)->getNumTombstones();
-  }
-
-  void setNumTombstones(unsigned Num) {
-    static_cast<DerivedT *>(this)->setNumTombstones(Num);
-  }
-
-  void incrementNumTombstones() {
-    setNumTombstones(getNumTombstones() + 1);
-  }
-
-  void decrementNumTombstones() {
-    setNumTombstones(getNumTombstones() - 1);
-  }
-
-  const BucketT *getBuckets() const {
-    return static_cast<const DerivedT *>(this)->getBuckets();
-  }
-
-  BucketT *getBuckets() {
-    return static_cast<DerivedT *>(this)->getBuckets();
-  }
-
-  unsigned getNumBuckets() const {
-    return static_cast<const DerivedT *>(this)->getNumBuckets();
-  }
-
-  BucketT *getBucketsEnd() {
-    return getBuckets() + getNumBuckets();
-  }
-
-  const BucketT *getBucketsEnd() const {
-    return getBuckets() + getNumBuckets();
-  }
-
-  void grow(unsigned AtLeast) {
-    static_cast<DerivedT *>(this)->grow(AtLeast);
-  }
-
-  void shrink_and_clear() {
-    static_cast<DerivedT *>(this)->shrink_and_clear();
-  }
-
-  template <typename KeyArg, typename... ValueArgs>
-  BucketT *InsertIntoBucket(BucketT *TheBucket, KeyArg &&Key,
-                            ValueArgs &&... Values) {
-    TheBucket = InsertIntoBucketImpl(Key, Key, TheBucket);
-
-    TheBucket->getFirst() = std::forward<KeyArg>(Key);
-    ::new (&TheBucket->getSecond()) ValueT(std::forward<ValueArgs>(Values)...);
-    return TheBucket;
-  }
-
-  template <typename LookupKeyT>
-  BucketT *InsertIntoBucketWithLookup(BucketT *TheBucket, KeyT &&Key,
-                                      ValueT &&Value, LookupKeyT &Lookup) {
-    TheBucket = InsertIntoBucketImpl(Key, Lookup, TheBucket);
-
-    TheBucket->getFirst() = std::move(Key);
-    ::new (&TheBucket->getSecond()) ValueT(std::move(Value));
-    return TheBucket;
-  }
-
-  template <typename LookupKeyT>
-  BucketT *InsertIntoBucketImpl(const KeyT &Key, const LookupKeyT &Lookup,
-                                BucketT *TheBucket) {
-    incrementEpoch();
-
-    // If the load of the hash table is more than 3/4, or if fewer than 1/8 of
-    // the buckets are empty (meaning that many are filled with tombstones),
-    // grow the table.
-    //
-    // The later case is tricky.  For example, if we had one empty bucket with
-    // tons of tombstones, failing lookups (e.g. for insertion) would have to
-    // probe almost the entire table until it found the empty bucket.  If the
-    // table completely filled with tombstones, no lookup would ever succeed,
-    // causing infinite loops in lookup.
-    unsigned NewNumEntries = getNumEntries() + 1;
-    unsigned NumBuckets = getNumBuckets();
-    if (LLVM_UNLIKELY(NewNumEntries * 4 >= NumBuckets * 3)) {
-      this->grow(NumBuckets * 2);
-      LookupBucketFor(Lookup, TheBucket);
-      NumBuckets = getNumBuckets();
-    } else if (LLVM_UNLIKELY(NumBuckets-(NewNumEntries+getNumTombstones()) <=
-                             NumBuckets/8)) {
-      this->grow(NumBuckets);
-      LookupBucketFor(Lookup, TheBucket);
-    }
-    assert(TheBucket);
-
-    // Only update the state after we've grown our bucket space appropriately
-    // so that when growing buckets we have self-consistent entry count.
-    incrementNumEntries();
-
-    // If we are writing over a tombstone, remember this.
-    const KeyT EmptyKey = getEmptyKey();
-    if (!KeyInfoT::isEqual(TheBucket->getFirst(), EmptyKey))
-      decrementNumTombstones();
-
-    return TheBucket;
-  }
-
-  /// LookupBucketFor - Lookup the appropriate bucket for Val, returning it in
-  /// FoundBucket.  If the bucket contains the key and a value, this returns
-  /// true, otherwise it returns a bucket with an empty marker or tombstone and
-  /// returns false.
-  template<typename LookupKeyT>
-  bool LookupBucketFor(const LookupKeyT &Val,
-                       const BucketT *&FoundBucket) const {
-    const BucketT *BucketsPtr = getBuckets();
-    const unsigned NumBuckets = getNumBuckets();
-
-    if (NumBuckets == 0) {
-      FoundBucket = nullptr;
-      return false;
-    }
-
-    // FoundTombstone - Keep track of whether we find a tombstone while probing.
-    const BucketT *FoundTombstone = nullptr;
-    const KeyT EmptyKey = getEmptyKey();
-    const KeyT TombstoneKey = getTombstoneKey();
-    assert(!KeyInfoT::isEqual(Val, EmptyKey) &&
-           !KeyInfoT::isEqual(Val, TombstoneKey) &&
-           "Empty/Tombstone value shouldn't be inserted into map!");
-
-    unsigned BucketNo = getHashValue(Val) & (NumBuckets-1);
-    unsigned ProbeAmt = 1;
-    while (true) {
-      const BucketT *ThisBucket = BucketsPtr + BucketNo;
-      // Found Val's bucket?  If so, return it.
-      if (LLVM_LIKELY(KeyInfoT::isEqual(Val, ThisBucket->getFirst()))) {
-        FoundBucket = ThisBucket;
-        return true;
-      }
-
-      // If we found an empty bucket, the key doesn't exist in the set.
-      // Insert it and return the default value.
-      if (LLVM_LIKELY(KeyInfoT::isEqual(ThisBucket->getFirst(), EmptyKey))) {
-        // If we've already seen a tombstone while probing, fill it in instead
-        // of the empty bucket we eventually probed to.
-        FoundBucket = FoundTombstone ? FoundTombstone : ThisBucket;
-        return false;
-      }
-
-      // If this is a tombstone, remember it.  If Val ends up not in the map, we
-      // prefer to return it than something that would require more probing.
-      if (KeyInfoT::isEqual(ThisBucket->getFirst(), TombstoneKey) &&
-          !FoundTombstone)
-        FoundTombstone = ThisBucket;  // Remember the first tombstone found.
-
-      // Otherwise, it's a hash collision or a tombstone, continue quadratic
-      // probing.
-      BucketNo += ProbeAmt++;
-      BucketNo &= (NumBuckets-1);
-    }
-  }
-
-  template <typename LookupKeyT>
-  bool LookupBucketFor(const LookupKeyT &Val, BucketT *&FoundBucket) {
-    const BucketT *ConstFoundBucket;
-    bool Result = const_cast<const DenseMapBase *>(this)
-      ->LookupBucketFor(Val, ConstFoundBucket);
-    FoundBucket = const_cast<BucketT *>(ConstFoundBucket);
-    return Result;
-  }
-
-public:
-  /// Return the approximate size (in bytes) of the actual map.
-  /// This is just the raw memory used by DenseMap.
-  /// If entries are pointers to objects, the size of the referenced objects
-  /// are not included.
-  size_t getMemorySize() const {
-    return getNumBuckets() * sizeof(BucketT);
-  }
-};
-
-/// Equality comparison for DenseMap.
-///
-/// Iterates over elements of LHS confirming that each (key, value) pair in LHS
-/// is also in RHS, and that no additional pairs are in RHS.
-/// Equivalent to N calls to RHS.find and N value comparisons. Amortized
-/// complexity is linear, worst case is O(N^2) (if every hash collides).
-template <typename DerivedT, typename KeyT, typename ValueT, typename KeyInfoT,
-          typename BucketT>
-bool operator==(
-    const DenseMapBase<DerivedT, KeyT, ValueT, KeyInfoT, BucketT> &LHS,
-    const DenseMapBase<DerivedT, KeyT, ValueT, KeyInfoT, BucketT> &RHS) {
-  if (LHS.size() != RHS.size())
-    return false;
-
-  for (auto &KV : LHS) {
-    auto I = RHS.find(KV.first);
-    if (I == RHS.end() || I->second != KV.second)
-      return false;
-  }
-
-  return true;
-}
-
-/// Inequality comparison for DenseMap.
-///
-/// Equivalent to !(LHS == RHS). See operator== for performance notes.
-template <typename DerivedT, typename KeyT, typename ValueT, typename KeyInfoT,
-          typename BucketT>
-bool operator!=(
-    const DenseMapBase<DerivedT, KeyT, ValueT, KeyInfoT, BucketT> &LHS,
-    const DenseMapBase<DerivedT, KeyT, ValueT, KeyInfoT, BucketT> &RHS) {
-  return !(LHS == RHS);
-}
-
-template <typename KeyT, typename ValueT,
-          typename KeyInfoT = DenseMapInfo<KeyT>,
-          typename BucketT = wpi::detail::DenseMapPair<KeyT, ValueT>>
-class DenseMap : public DenseMapBase<DenseMap<KeyT, ValueT, KeyInfoT, BucketT>,
-                                     KeyT, ValueT, KeyInfoT, BucketT> {
-  friend class DenseMapBase<DenseMap, KeyT, ValueT, KeyInfoT, BucketT>;
-
-  // Lift some types from the dependent base class into this class for
-  // simplicity of referring to them.
-  using BaseT = DenseMapBase<DenseMap, KeyT, ValueT, KeyInfoT, BucketT>;
-
-  BucketT *Buckets;
-  unsigned NumEntries;
-  unsigned NumTombstones;
-  unsigned NumBuckets;
-
-public:
-  /// Create a DenseMap wth an optional \p InitialReserve that guarantee that
-  /// this number of elements can be inserted in the map without grow()
-  explicit DenseMap(unsigned InitialReserve = 0) { init(InitialReserve); }
-
-  DenseMap(const DenseMap &other) : BaseT() {
-    init(0);
-    copyFrom(other);
-  }
-
-  DenseMap(DenseMap &&other) : BaseT() {
-    init(0);
-    swap(other);
-  }
-
-  template<typename InputIt>
-  DenseMap(const InputIt &I, const InputIt &E) {
-    init(std::distance(I, E));
-    this->insert(I, E);
-  }
-
-  DenseMap(std::initializer_list<typename BaseT::value_type> Vals) {
-    init(Vals.size());
-    this->insert(Vals.begin(), Vals.end());
-  }
-
-  ~DenseMap() {
-    this->destroyAll();
-    operator delete(Buckets);
-  }
-
-  void swap(DenseMap& RHS) {
-    this->incrementEpoch();
-    RHS.incrementEpoch();
-    std::swap(Buckets, RHS.Buckets);
-    std::swap(NumEntries, RHS.NumEntries);
-    std::swap(NumTombstones, RHS.NumTombstones);
-    std::swap(NumBuckets, RHS.NumBuckets);
-  }
-
-  DenseMap& operator=(const DenseMap& other) {
-    if (&other != this)
-      copyFrom(other);
-    return *this;
-  }
-
-  DenseMap& operator=(DenseMap &&other) {
-    this->destroyAll();
-    operator delete(Buckets);
-    init(0);
-    swap(other);
-    return *this;
-  }
-
-  void copyFrom(const DenseMap& other) {
-    this->destroyAll();
-    operator delete(Buckets);
-    if (allocateBuckets(other.NumBuckets)) {
-      this->BaseT::copyFrom(other);
-    } else {
-      NumEntries = 0;
-      NumTombstones = 0;
-    }
-  }
-
-  void init(unsigned InitNumEntries) {
-    auto InitBuckets = BaseT::getMinBucketToReserveForEntries(InitNumEntries);
-    if (allocateBuckets(InitBuckets)) {
-      this->BaseT::initEmpty();
-    } else {
-      NumEntries = 0;
-      NumTombstones = 0;
-    }
-  }
-
-  void grow(unsigned AtLeast) {
-    unsigned OldNumBuckets = NumBuckets;
-    BucketT *OldBuckets = Buckets;
-
-    allocateBuckets(std::max<unsigned>(64, static_cast<unsigned>(NextPowerOf2(AtLeast-1))));
-    assert(Buckets);
-    if (!OldBuckets) {
-      this->BaseT::initEmpty();
-      return;
-    }
-
-    this->moveFromOldBuckets(OldBuckets, OldBuckets+OldNumBuckets);
-
-    // Free the old table.
-    operator delete(OldBuckets);
-  }
-
-  void shrink_and_clear() {
-    unsigned OldNumEntries = NumEntries;
-    this->destroyAll();
-
-    // Reduce the number of buckets.
-    unsigned NewNumBuckets = 0;
-    if (OldNumEntries)
-      NewNumBuckets = (std::max)(64, 1 << (Log2_32_Ceil(OldNumEntries) + 1));
-    if (NewNumBuckets == NumBuckets) {
-      this->BaseT::initEmpty();
-      return;
-    }
-
-    operator delete(Buckets);
-    init(NewNumBuckets);
-  }
-
-private:
-  unsigned getNumEntries() const {
-    return NumEntries;
-  }
-
-  void setNumEntries(unsigned Num) {
-    NumEntries = Num;
-  }
-
-  unsigned getNumTombstones() const {
-    return NumTombstones;
-  }
-
-  void setNumTombstones(unsigned Num) {
-    NumTombstones = Num;
-  }
-
-  BucketT *getBuckets() const {
-    return Buckets;
-  }
-
-  unsigned getNumBuckets() const {
-    return NumBuckets;
-  }
-
-  bool allocateBuckets(unsigned Num) {
-    NumBuckets = Num;
-    if (NumBuckets == 0) {
-      Buckets = nullptr;
-      return false;
-    }
-
-    Buckets = static_cast<BucketT*>(operator new(sizeof(BucketT) * NumBuckets));
-    return true;
-  }
-};
-
-template <typename KeyT, typename ValueT, unsigned InlineBuckets = 4,
-          typename KeyInfoT = DenseMapInfo<KeyT>,
-          typename BucketT = wpi::detail::DenseMapPair<KeyT, ValueT>>
-class SmallDenseMap
-    : public DenseMapBase<
-          SmallDenseMap<KeyT, ValueT, InlineBuckets, KeyInfoT, BucketT>, KeyT,
-          ValueT, KeyInfoT, BucketT> {
-  friend class DenseMapBase<SmallDenseMap, KeyT, ValueT, KeyInfoT, BucketT>;
-
-  // Lift some types from the dependent base class into this class for
-  // simplicity of referring to them.
-  using BaseT = DenseMapBase<SmallDenseMap, KeyT, ValueT, KeyInfoT, BucketT>;
-
-  static_assert(isPowerOf2_64(InlineBuckets),
-                "InlineBuckets must be a power of 2.");
-
-  unsigned Small : 1;
-  unsigned NumEntries : 31;
-  unsigned NumTombstones;
-
-  struct LargeRep {
-    BucketT *Buckets;
-    unsigned NumBuckets;
-  };
-
-  /// A "union" of an inline bucket array and the struct representing
-  /// a large bucket. This union will be discriminated by the 'Small' bit.
-  AlignedCharArrayUnion<BucketT[InlineBuckets], LargeRep> storage;
-
-public:
-  explicit SmallDenseMap(unsigned NumInitBuckets = 0) {
-    init(NumInitBuckets);
-  }
-
-  SmallDenseMap(const SmallDenseMap &other) : BaseT() {
-    init(0);
-    copyFrom(other);
-  }
-
-  SmallDenseMap(SmallDenseMap &&other) : BaseT() {
-    init(0);
-    swap(other);
-  }
-
-  template<typename InputIt>
-  SmallDenseMap(const InputIt &I, const InputIt &E) {
-    init(NextPowerOf2(std::distance(I, E)));
-    this->insert(I, E);
-  }
-
-  ~SmallDenseMap() {
-    this->destroyAll();
-    deallocateBuckets();
-  }
-
-  void swap(SmallDenseMap& RHS) {
-    unsigned TmpNumEntries = RHS.NumEntries;
-    RHS.NumEntries = NumEntries;
-    NumEntries = TmpNumEntries;
-    std::swap(NumTombstones, RHS.NumTombstones);
-
-    const KeyT EmptyKey = this->getEmptyKey();
-    const KeyT TombstoneKey = this->getTombstoneKey();
-    if (Small && RHS.Small) {
-      // If we're swapping inline bucket arrays, we have to cope with some of
-      // the tricky bits of DenseMap's storage system: the buckets are not
-      // fully initialized. Thus we swap every key, but we may have
-      // a one-directional move of the value.
-      for (unsigned i = 0, e = InlineBuckets; i != e; ++i) {
-        BucketT *LHSB = &getInlineBuckets()[i],
-                *RHSB = &RHS.getInlineBuckets()[i];
-        bool hasLHSValue = (!KeyInfoT::isEqual(LHSB->getFirst(), EmptyKey) &&
-                            !KeyInfoT::isEqual(LHSB->getFirst(), TombstoneKey));
-        bool hasRHSValue = (!KeyInfoT::isEqual(RHSB->getFirst(), EmptyKey) &&
-                            !KeyInfoT::isEqual(RHSB->getFirst(), TombstoneKey));
-        if (hasLHSValue && hasRHSValue) {
-          // Swap together if we can...
-          std::swap(*LHSB, *RHSB);
-          continue;
-        }
-        // Swap separately and handle any assymetry.
-        std::swap(LHSB->getFirst(), RHSB->getFirst());
-        if (hasLHSValue) {
-          ::new (&RHSB->getSecond()) ValueT(std::move(LHSB->getSecond()));
-          LHSB->getSecond().~ValueT();
-        } else if (hasRHSValue) {
-          ::new (&LHSB->getSecond()) ValueT(std::move(RHSB->getSecond()));
-          RHSB->getSecond().~ValueT();
-        }
-      }
-      return;
-    }
-    if (!Small && !RHS.Small) {
-      std::swap(getLargeRep()->Buckets, RHS.getLargeRep()->Buckets);
-      std::swap(getLargeRep()->NumBuckets, RHS.getLargeRep()->NumBuckets);
-      return;
-    }
-
-    SmallDenseMap &SmallSide = Small ? *this : RHS;
-    SmallDenseMap &LargeSide = Small ? RHS : *this;
-
-    // First stash the large side's rep and move the small side across.
-    LargeRep TmpRep = std::move(*LargeSide.getLargeRep());
-    LargeSide.getLargeRep()->~LargeRep();
-    LargeSide.Small = true;
-    // This is similar to the standard move-from-old-buckets, but the bucket
-    // count hasn't actually rotated in this case. So we have to carefully
-    // move construct the keys and values into their new locations, but there
-    // is no need to re-hash things.
-    for (unsigned i = 0, e = InlineBuckets; i != e; ++i) {
-      BucketT *NewB = &LargeSide.getInlineBuckets()[i],
-              *OldB = &SmallSide.getInlineBuckets()[i];
-      ::new (&NewB->getFirst()) KeyT(std::move(OldB->getFirst()));
-      OldB->getFirst().~KeyT();
-      if (!KeyInfoT::isEqual(NewB->getFirst(), EmptyKey) &&
-          !KeyInfoT::isEqual(NewB->getFirst(), TombstoneKey)) {
-        ::new (&NewB->getSecond()) ValueT(std::move(OldB->getSecond()));
-        OldB->getSecond().~ValueT();
-      }
-    }
-
-    // The hard part of moving the small buckets across is done, just move
-    // the TmpRep into its new home.
-    SmallSide.Small = false;
-    new (SmallSide.getLargeRep()) LargeRep(std::move(TmpRep));
-  }
-
-  SmallDenseMap& operator=(const SmallDenseMap& other) {
-    if (&other != this)
-      copyFrom(other);
-    return *this;
-  }
-
-  SmallDenseMap& operator=(SmallDenseMap &&other) {
-    this->destroyAll();
-    deallocateBuckets();
-    init(0);
-    swap(other);
-    return *this;
-  }
-
-  void copyFrom(const SmallDenseMap& other) {
-    this->destroyAll();
-    deallocateBuckets();
-    Small = true;
-    if (other.getNumBuckets() > InlineBuckets) {
-      Small = false;
-      new (getLargeRep()) LargeRep(allocateBuckets(other.getNumBuckets()));
-    }
-    this->BaseT::copyFrom(other);
-  }
-
-  void init(unsigned InitBuckets) {
-    Small = true;
-    if (InitBuckets > InlineBuckets) {
-      Small = false;
-      new (getLargeRep()) LargeRep(allocateBuckets(InitBuckets));
-    }
-    this->BaseT::initEmpty();
-  }
-
-  void grow(unsigned AtLeast) {
-    if (AtLeast >= InlineBuckets)
-      AtLeast = std::max<unsigned>(64, NextPowerOf2(AtLeast-1));
-
-    if (Small) {
-      if (AtLeast < InlineBuckets)
-        return; // Nothing to do.
-
-      // First move the inline buckets into a temporary storage.
-      AlignedCharArrayUnion<BucketT[InlineBuckets]> TmpStorage;
-      BucketT *TmpBegin = reinterpret_cast<BucketT *>(TmpStorage.buffer);
-      BucketT *TmpEnd = TmpBegin;
-
-      // Loop over the buckets, moving non-empty, non-tombstones into the
-      // temporary storage. Have the loop move the TmpEnd forward as it goes.
-      const KeyT EmptyKey = this->getEmptyKey();
-      const KeyT TombstoneKey = this->getTombstoneKey();
-      for (BucketT *P = getBuckets(), *E = P + InlineBuckets; P != E; ++P) {
-        if (!KeyInfoT::isEqual(P->getFirst(), EmptyKey) &&
-            !KeyInfoT::isEqual(P->getFirst(), TombstoneKey)) {
-          assert(size_t(TmpEnd - TmpBegin) < InlineBuckets &&
-                 "Too many inline buckets!");
-          ::new (&TmpEnd->getFirst()) KeyT(std::move(P->getFirst()));
-          ::new (&TmpEnd->getSecond()) ValueT(std::move(P->getSecond()));
-          ++TmpEnd;
-          P->getSecond().~ValueT();
-        }
-        P->getFirst().~KeyT();
-      }
-
-      // Now make this map use the large rep, and move all the entries back
-      // into it.
-      Small = false;
-      new (getLargeRep()) LargeRep(allocateBuckets(AtLeast));
-      this->moveFromOldBuckets(TmpBegin, TmpEnd);
-      return;
-    }
-
-    LargeRep OldRep = std::move(*getLargeRep());
-    getLargeRep()->~LargeRep();
-    if (AtLeast <= InlineBuckets) {
-      Small = true;
-    } else {
-      new (getLargeRep()) LargeRep(allocateBuckets(AtLeast));
-    }
-
-    this->moveFromOldBuckets(OldRep.Buckets, OldRep.Buckets+OldRep.NumBuckets);
-
-    // Free the old table.
-    operator delete(OldRep.Buckets);
-  }
-
-  void shrink_and_clear() {
-    unsigned OldSize = this->size();
-    this->destroyAll();
-
-    // Reduce the number of buckets.
-    unsigned NewNumBuckets = 0;
-    if (OldSize) {
-      NewNumBuckets = 1 << (Log2_32_Ceil(OldSize) + 1);
-      if (NewNumBuckets > InlineBuckets && NewNumBuckets < 64u)
-        NewNumBuckets = 64;
-    }
-    if ((Small && NewNumBuckets <= InlineBuckets) ||
-        (!Small && NewNumBuckets == getLargeRep()->NumBuckets)) {
-      this->BaseT::initEmpty();
-      return;
-    }
-
-    deallocateBuckets();
-    init(NewNumBuckets);
-  }
-
-private:
-  unsigned getNumEntries() const {
-    return NumEntries;
-  }
-
-  void setNumEntries(unsigned Num) {
-    // NumEntries is hardcoded to be 31 bits wide.
-    assert(Num < (1U << 31) && "Cannot support more than 1<<31 entries");
-    NumEntries = Num;
-  }
-
-  unsigned getNumTombstones() const {
-    return NumTombstones;
-  }
-
-  void setNumTombstones(unsigned Num) {
-    NumTombstones = Num;
-  }
-
-  const BucketT *getInlineBuckets() const {
-    assert(Small);
-    // Note that this cast does not violate aliasing rules as we assert that
-    // the memory's dynamic type is the small, inline bucket buffer, and the
-    // 'storage.buffer' static type is 'char *'.
-    return reinterpret_cast<const BucketT *>(storage.buffer);
-  }
-
-  BucketT *getInlineBuckets() {
-    return const_cast<BucketT *>(
-      const_cast<const SmallDenseMap *>(this)->getInlineBuckets());
-  }
-
-  const LargeRep *getLargeRep() const {
-    assert(!Small);
-    // Note, same rule about aliasing as with getInlineBuckets.
-    return reinterpret_cast<const LargeRep *>(storage.buffer);
-  }
-
-  LargeRep *getLargeRep() {
-    return const_cast<LargeRep *>(
-      const_cast<const SmallDenseMap *>(this)->getLargeRep());
-  }
-
-  const BucketT *getBuckets() const {
-    return Small ? getInlineBuckets() : getLargeRep()->Buckets;
-  }
-
-  BucketT *getBuckets() {
-    return const_cast<BucketT *>(
-      const_cast<const SmallDenseMap *>(this)->getBuckets());
-  }
-
-  unsigned getNumBuckets() const {
-    return Small ? InlineBuckets : getLargeRep()->NumBuckets;
-  }
-
-  void deallocateBuckets() {
-    if (Small)
-      return;
-
-    operator delete(getLargeRep()->Buckets);
-    getLargeRep()->~LargeRep();
-  }
-
-  LargeRep allocateBuckets(unsigned Num) {
-    assert(Num > InlineBuckets && "Must allocate more buckets than are inline");
-    LargeRep Rep = {
-      static_cast<BucketT*>(operator new(sizeof(BucketT) * Num)), Num
-    };
-    return Rep;
-  }
-};
-
-template <typename KeyT, typename ValueT, typename KeyInfoT, typename Bucket,
-          bool IsConst>
-class DenseMapIterator : DebugEpochBase::HandleBase {
-  friend class DenseMapIterator<KeyT, ValueT, KeyInfoT, Bucket, true>;
-  friend class DenseMapIterator<KeyT, ValueT, KeyInfoT, Bucket, false>;
-
-  using ConstIterator = DenseMapIterator<KeyT, ValueT, KeyInfoT, Bucket, true>;
-
-public:
-  using difference_type = ptrdiff_t;
-  using value_type =
-      typename std::conditional<IsConst, const Bucket, Bucket>::type;
-  using pointer = value_type *;
-  using reference = value_type &;
-  using iterator_category = std::forward_iterator_tag;
-
-private:
-  pointer Ptr = nullptr;
-  pointer End = nullptr;
-
-public:
-  DenseMapIterator() = default;
-
-  DenseMapIterator(pointer Pos, pointer E, const DebugEpochBase &Epoch,
-                   bool NoAdvance = false)
-      : DebugEpochBase::HandleBase(&Epoch), Ptr(Pos), End(E) {
-    assert(isHandleInSync() && "invalid construction!");
-
-    if (NoAdvance) return;
-    AdvancePastEmptyBuckets();
-  }
-
-  // Converting ctor from non-const iterators to const iterators. SFINAE'd out
-  // for const iterator destinations so it doesn't end up as a user defined copy
-  // constructor.
-  template <bool IsConstSrc,
-            typename = typename std::enable_if<!IsConstSrc && IsConst>::type>
-  DenseMapIterator(
-      const DenseMapIterator<KeyT, ValueT, KeyInfoT, Bucket, IsConstSrc> &I)
-      : DebugEpochBase::HandleBase(I), Ptr(I.Ptr), End(I.End) {}
-
-  reference operator*() const {
-    assert(isHandleInSync() && "invalid iterator access!");
-    return *Ptr;
-  }
-  pointer operator->() const {
-    assert(isHandleInSync() && "invalid iterator access!");
-    return Ptr;
-  }
-
-  bool operator==(const ConstIterator &RHS) const {
-    assert((!Ptr || isHandleInSync()) && "handle not in sync!");
-    assert((!RHS.Ptr || RHS.isHandleInSync()) && "handle not in sync!");
-    assert(getEpochAddress() == RHS.getEpochAddress() &&
-           "comparing incomparable iterators!");
-    return Ptr == RHS.Ptr;
-  }
-  bool operator!=(const ConstIterator &RHS) const {
-    assert((!Ptr || isHandleInSync()) && "handle not in sync!");
-    assert((!RHS.Ptr || RHS.isHandleInSync()) && "handle not in sync!");
-    assert(getEpochAddress() == RHS.getEpochAddress() &&
-           "comparing incomparable iterators!");
-    return Ptr != RHS.Ptr;
-  }
-
-  inline DenseMapIterator& operator++() {  // Preincrement
-    assert(isHandleInSync() && "invalid iterator access!");
-    ++Ptr;
-    AdvancePastEmptyBuckets();
-    return *this;
-  }
-  DenseMapIterator operator++(int) {  // Postincrement
-    assert(isHandleInSync() && "invalid iterator access!");
-    DenseMapIterator tmp = *this; ++*this; return tmp;
-  }
-
-private:
-  void AdvancePastEmptyBuckets() {
-    assert(Ptr <= End);
-    const KeyT Empty = KeyInfoT::getEmptyKey();
-    const KeyT Tombstone = KeyInfoT::getTombstoneKey();
-
-    while (Ptr != End && (KeyInfoT::isEqual(Ptr->getFirst(), Empty) ||
-                          KeyInfoT::isEqual(Ptr->getFirst(), Tombstone)))
-      ++Ptr;
-  }
-
-  void RetreatPastEmptyBuckets() {
-    assert(Ptr >= End);
-    const KeyT Empty = KeyInfoT::getEmptyKey();
-    const KeyT Tombstone = KeyInfoT::getTombstoneKey();
-
-    while (Ptr != End && (KeyInfoT::isEqual(Ptr[-1].getFirst(), Empty) ||
-                          KeyInfoT::isEqual(Ptr[-1].getFirst(), Tombstone)))
-      --Ptr;
-  }
-};
-
-template <typename KeyT, typename ValueT, typename KeyInfoT>
-inline size_t capacity_in_bytes(const DenseMap<KeyT, ValueT, KeyInfoT> &X) {
-  return X.getMemorySize();
-}
-
-} // end namespace wpi
-
-#endif // LLVM_ADT_DENSEMAP_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/DenseMapInfo.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/DenseMapInfo.h
deleted file mode 100644
index b6525a3..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/DenseMapInfo.h
+++ /dev/null
@@ -1,274 +0,0 @@
-//===- llvm/ADT/DenseMapInfo.h - Type traits for DenseMap -------*- C++ -*-===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-//
-// This file defines DenseMapInfo traits for DenseMap.
-//
-//===----------------------------------------------------------------------===//
-
-#ifndef WPIUTIL_WPI_DENSEMAPINFO_H
-#define WPIUTIL_WPI_DENSEMAPINFO_H
-
-#include "wpi/Hashing.h"
-#include "wpi/PointerLikeTypeTraits.h"
-#include "wpi/span.h"
-#include <cassert>
-#include <cstddef>
-#include <cstdint>
-#include <string_view>
-#include <utility>
-
-namespace wpi {
-
-template<typename T>
-struct DenseMapInfo {
-  //static inline T getEmptyKey();
-  //static inline T getTombstoneKey();
-  //static unsigned getHashValue(const T &Val);
-  //static bool isEqual(const T &LHS, const T &RHS);
-};
-
-// Provide DenseMapInfo for all pointers.
-template<typename T>
-struct DenseMapInfo<T*> {
-  static inline T* getEmptyKey() {
-    uintptr_t Val = static_cast<uintptr_t>(-1);
-    Val <<= PointerLikeTypeTraits<T*>::NumLowBitsAvailable;
-    return reinterpret_cast<T*>(Val);
-  }
-
-  static inline T* getTombstoneKey() {
-    uintptr_t Val = static_cast<uintptr_t>(-2);
-    Val <<= PointerLikeTypeTraits<T*>::NumLowBitsAvailable;
-    return reinterpret_cast<T*>(Val);
-  }
-
-  static unsigned getHashValue(const T *PtrVal) {
-    return (unsigned((uintptr_t)PtrVal) >> 4) ^
-           (unsigned((uintptr_t)PtrVal) >> 9);
-  }
-
-  static bool isEqual(const T *LHS, const T *RHS) { return LHS == RHS; }
-};
-
-// Provide DenseMapInfo for chars.
-template<> struct DenseMapInfo<char> {
-  static inline char getEmptyKey() { return ~0; }
-  static inline char getTombstoneKey() { return ~0 - 1; }
-  static unsigned getHashValue(const char& Val) { return Val * 37U; }
-
-  static bool isEqual(const char &LHS, const char &RHS) {
-    return LHS == RHS;
-  }
-};
-
-// Provide DenseMapInfo for unsigned shorts.
-template <> struct DenseMapInfo<unsigned short> {
-  static inline unsigned short getEmptyKey() { return 0xFFFF; }
-  static inline unsigned short getTombstoneKey() { return 0xFFFF - 1; }
-  static unsigned getHashValue(const unsigned short &Val) { return Val * 37U; }
-
-  static bool isEqual(const unsigned short &LHS, const unsigned short &RHS) {
-    return LHS == RHS;
-  }
-};
-
-// Provide DenseMapInfo for unsigned ints.
-template<> struct DenseMapInfo<unsigned> {
-  static inline unsigned getEmptyKey() { return ~0U; }
-  static inline unsigned getTombstoneKey() { return ~0U - 1; }
-  static unsigned getHashValue(const unsigned& Val) { return Val * 37U; }
-
-  static bool isEqual(const unsigned& LHS, const unsigned& RHS) {
-    return LHS == RHS;
-  }
-};
-
-// Provide DenseMapInfo for unsigned longs.
-template<> struct DenseMapInfo<unsigned long> {
-  static inline unsigned long getEmptyKey() { return ~0UL; }
-  static inline unsigned long getTombstoneKey() { return ~0UL - 1L; }
-
-  static unsigned getHashValue(const unsigned long& Val) {
-    return (unsigned)(Val * 37UL);
-  }
-
-  static bool isEqual(const unsigned long& LHS, const unsigned long& RHS) {
-    return LHS == RHS;
-  }
-};
-
-// Provide DenseMapInfo for unsigned long longs.
-template<> struct DenseMapInfo<unsigned long long> {
-  static inline unsigned long long getEmptyKey() { return ~0ULL; }
-  static inline unsigned long long getTombstoneKey() { return ~0ULL - 1ULL; }
-
-  static unsigned getHashValue(const unsigned long long& Val) {
-    return (unsigned)(Val * 37ULL);
-  }
-
-  static bool isEqual(const unsigned long long& LHS,
-                      const unsigned long long& RHS) {
-    return LHS == RHS;
-  }
-};
-
-// Provide DenseMapInfo for shorts.
-template <> struct DenseMapInfo<short> {
-  static inline short getEmptyKey() { return 0x7FFF; }
-  static inline short getTombstoneKey() { return -0x7FFF - 1; }
-  static unsigned getHashValue(const short &Val) { return Val * 37U; }
-  static bool isEqual(const short &LHS, const short &RHS) { return LHS == RHS; }
-};
-
-// Provide DenseMapInfo for ints.
-template<> struct DenseMapInfo<int> {
-  static inline int getEmptyKey() { return 0x7fffffff; }
-  static inline int getTombstoneKey() { return -0x7fffffff - 1; }
-  static unsigned getHashValue(const int& Val) { return (unsigned)(Val * 37U); }
-
-  static bool isEqual(const int& LHS, const int& RHS) {
-    return LHS == RHS;
-  }
-};
-
-// Provide DenseMapInfo for longs.
-template<> struct DenseMapInfo<long> {
-  static inline long getEmptyKey() {
-    return (1UL << (sizeof(long) * 8 - 1)) - 1UL;
-  }
-
-  static inline long getTombstoneKey() { return getEmptyKey() - 1L; }
-
-  static unsigned getHashValue(const long& Val) {
-    return (unsigned)(Val * 37UL);
-  }
-
-  static bool isEqual(const long& LHS, const long& RHS) {
-    return LHS == RHS;
-  }
-};
-
-// Provide DenseMapInfo for long longs.
-template<> struct DenseMapInfo<long long> {
-  static inline long long getEmptyKey() { return 0x7fffffffffffffffLL; }
-  static inline long long getTombstoneKey() { return -0x7fffffffffffffffLL-1; }
-
-  static unsigned getHashValue(const long long& Val) {
-    return (unsigned)(Val * 37ULL);
-  }
-
-  static bool isEqual(const long long& LHS,
-                      const long long& RHS) {
-    return LHS == RHS;
-  }
-};
-
-// Provide DenseMapInfo for all pairs whose members have info.
-template<typename T, typename U>
-struct DenseMapInfo<std::pair<T, U>> {
-  using Pair = std::pair<T, U>;
-  using FirstInfo = DenseMapInfo<T>;
-  using SecondInfo = DenseMapInfo<U>;
-
-  static inline Pair getEmptyKey() {
-    return std::make_pair(FirstInfo::getEmptyKey(),
-                          SecondInfo::getEmptyKey());
-  }
-
-  static inline Pair getTombstoneKey() {
-    return std::make_pair(FirstInfo::getTombstoneKey(),
-                          SecondInfo::getTombstoneKey());
-  }
-
-  static unsigned getHashValue(const Pair& PairVal) {
-    uint64_t key = (uint64_t)FirstInfo::getHashValue(PairVal.first) << 32
-          | (uint64_t)SecondInfo::getHashValue(PairVal.second);
-    key += ~(key << 32);
-    key ^= (key >> 22);
-    key += ~(key << 13);
-    key ^= (key >> 8);
-    key += (key << 3);
-    key ^= (key >> 15);
-    key += ~(key << 27);
-    key ^= (key >> 31);
-    return (unsigned)key;
-  }
-
-  static bool isEqual(const Pair &LHS, const Pair &RHS) {
-    return FirstInfo::isEqual(LHS.first, RHS.first) &&
-           SecondInfo::isEqual(LHS.second, RHS.second);
-  }
-};
-
-// Provide DenseMapInfo for std::string_view.
-template <> struct DenseMapInfo<std::string_view> {
-  static inline std::string_view getEmptyKey() {
-    return std::string_view(reinterpret_cast<const char *>(~static_cast<uintptr_t>(0)),
-                     0);
-  }
-
-  static inline std::string_view getTombstoneKey() {
-    return std::string_view(reinterpret_cast<const char *>(~static_cast<uintptr_t>(1)),
-                     0);
-  }
-
-  static unsigned getHashValue(std::string_view Val) {
-    assert(Val.data() != getEmptyKey().data() && "Cannot hash the empty key!");
-    assert(Val.data() != getTombstoneKey().data() &&
-           "Cannot hash the tombstone key!");
-    return (unsigned)(hash_value(Val));
-  }
-
-  static bool isEqual(std::string_view LHS, std::string_view RHS) {
-    if (RHS.data() == getEmptyKey().data())
-      return LHS.data() == getEmptyKey().data();
-    if (RHS.data() == getTombstoneKey().data())
-      return LHS.data() == getTombstoneKey().data();
-    return LHS == RHS;
-  }
-};
-
-// Provide DenseMapInfo for spans.
-template <typename T> struct DenseMapInfo<span<T>> {
-  static inline span<T> getEmptyKey() {
-    return span<T>(reinterpret_cast<const T *>(~static_cast<uintptr_t>(0)),
-                   size_t(0));
-  }
-
-  static inline span<T> getTombstoneKey() {
-    return span<T>(reinterpret_cast<const T *>(~static_cast<uintptr_t>(1)),
-                   size_t(0));
-  }
-
-  static unsigned getHashValue(span<T> Val) {
-    assert(Val.data() != getEmptyKey().data() && "Cannot hash the empty key!");
-    assert(Val.data() != getTombstoneKey().data() &&
-           "Cannot hash the tombstone key!");
-    return (unsigned)(hash_value(Val));
-  }
-
-  static bool isEqual(span<T> LHS, span<T> RHS) {
-    if (RHS.data() == getEmptyKey().data())
-      return LHS.data() == getEmptyKey().data();
-    if (RHS.data() == getTombstoneKey().data())
-      return LHS.data() == getTombstoneKey().data();
-    return LHS == RHS;
-  }
-};
-
-template <> struct DenseMapInfo<hash_code> {
-  static inline hash_code getEmptyKey() { return hash_code(-1); }
-  static inline hash_code getTombstoneKey() { return hash_code(-2); }
-  static unsigned getHashValue(hash_code val) { return static_cast<unsigned>(val); }
-  static bool isEqual(hash_code LHS, hash_code RHS) { return LHS == RHS; }
-};
-
-} // end namespace wpi
-
-#endif // LLVM_ADT_DENSEMAPINFO_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/DsClient.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/DsClient.h
deleted file mode 100644
index c24ba3b..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/DsClient.h
+++ /dev/null
@@ -1,55 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <memory>
-#include <string>
-#include <string_view>
-
-#include "wpi/Signal.h"
-
-namespace wpi {
-
-class Logger;
-
-namespace uv {
-class Loop;
-class Tcp;
-class Timer;
-}  // namespace uv
-
-class DsClient : public std::enable_shared_from_this<DsClient> {
-  struct private_init {};
-
- public:
-  static std::shared_ptr<DsClient> Create(wpi::uv::Loop& loop,
-                                          wpi::Logger& logger) {
-    return std::make_shared<DsClient>(loop, logger, private_init{});
-  }
-
-  DsClient(wpi::uv::Loop& loop, wpi::Logger& logger, const private_init&);
-  ~DsClient();
-  DsClient(const DsClient&) = delete;
-  DsClient& operator=(const DsClient&) = delete;
-
-  void Close();
-
-  sig::Signal<std::string_view> setIp;
-  sig::Signal<> clearIp;
-
- private:
-  void Connect();
-  void HandleIncoming(std::string_view in);
-  void ParseJson();
-
-  wpi::Logger& m_logger;
-
-  std::shared_ptr<wpi::uv::Tcp> m_tcp;
-  std::shared_ptr<wpi::uv::Timer> m_timer;
-
-  std::string m_json;
-};
-
-}  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/Endian.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/Endian.h
deleted file mode 100644
index b31cb2d..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/Endian.h
+++ /dev/null
@@ -1,435 +0,0 @@
-//===- Endian.h - Utilities for IO with endian specific data ----*- C++ -*-===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-//
-// This file declares generic functions to read and write endian specific data.
-//
-//===----------------------------------------------------------------------===//
-
-#ifndef WPIUTIL_WPI_ENDIAN_H
-#define WPIUTIL_WPI_ENDIAN_H
-
-#include "wpi/AlignOf.h"
-#include "wpi/Compiler.h"
-#include "wpi/SwapByteOrder.h"
-
-#if defined(__linux__) || defined(__GNU__)
-#include <endian.h>
-#endif
-
-#include <cassert>
-#include <cstddef>
-#include <cstdint>
-#include <cstring>
-#include <type_traits>
-
-namespace wpi {
-namespace support {
-
-enum endianness {big, little, native};
-
-// These are named values for common alignments.
-enum {aligned = 0, unaligned = 1};
-
-namespace detail {
-
-// value is either alignment, or alignof(T) if alignment is 0.
-template<class T, int alignment>
-struct PickAlignment {
- enum { value = alignment == 0 ? alignof(T) : alignment };
-};
-
-} // end namespace detail
-
-namespace endian {
-
-constexpr endianness system_endianness() {
-#ifdef _WIN32
-  return little;
-#elif defined(__BYTE_ORDER) && defined(__BIG_ENDIAN) && __BYTE_ORDER == __BIG_ENDIAN
-  return big;
-#else
-  return little;
-#endif
-}
-
-template <typename value_type>
-inline value_type byte_swap(value_type value, endianness endian) {
-  if ((endian != native) && (endian != system_endianness()))
-    sys::swapByteOrder(value);
-  return value;
-}
-
-/// Swap the bytes of value to match the given endianness.
-template<typename value_type, endianness endian>
-inline value_type byte_swap(value_type value) {
-  if constexpr ((endian != native) && (endian != system_endianness()))
-    sys::swapByteOrder(value);
-  return value;
-}
-
-/// Read a value of a particular endianness from memory.
-template <typename value_type, std::size_t alignment>
-inline value_type read(const void *memory, endianness endian) {
-  value_type ret;
-
-  memcpy(&ret,
-         LLVM_ASSUME_ALIGNED(
-             memory, (detail::PickAlignment<value_type, alignment>::value)),
-         sizeof(value_type));
-  return byte_swap<value_type>(ret, endian);
-}
-
-template<typename value_type,
-         endianness endian,
-         std::size_t alignment>
-inline value_type read(const void *memory) {
-  value_type ret;
-
-  memcpy(&ret,
-         LLVM_ASSUME_ALIGNED(
-             memory, (detail::PickAlignment<value_type, alignment>::value)),
-         sizeof(value_type));
-  return byte_swap<value_type, endian>(ret);
-}
-
-/// Read a value of a particular endianness from a buffer, and increment the
-/// buffer past that value.
-template <typename value_type, std::size_t alignment, typename CharT>
-inline value_type readNext(const CharT *&memory, endianness endian) {
-  value_type ret = read<value_type, alignment>(memory, endian);
-  memory += sizeof(value_type);
-  return ret;
-}
-
-template<typename value_type, endianness endian, std::size_t alignment,
-         typename CharT>
-inline value_type readNext(const CharT *&memory) {
-  value_type ret = read<value_type, endian, alignment>(memory);
-  memory += sizeof(value_type);
-  return ret;
-}
-
-/// Write a value to memory with a particular endianness.
-template <typename value_type, std::size_t alignment>
-inline void write(void *memory, value_type value, endianness endian) {
-  value = byte_swap<value_type>(value, endian);
-  memcpy(LLVM_ASSUME_ALIGNED(
-             memory, (detail::PickAlignment<value_type, alignment>::value)),
-         &value, sizeof(value_type));
-}
-
-template<typename value_type,
-         endianness endian,
-         std::size_t alignment>
-inline void write(void *memory, value_type value) {
-  value = byte_swap<value_type, endian>(value);
-  memcpy(LLVM_ASSUME_ALIGNED(
-             memory, (detail::PickAlignment<value_type, alignment>::value)),
-         &value, sizeof(value_type));
-}
-
-/// Read a value of a particular endianness from memory, for a location
-/// that starts at the given bit offset within the first byte.
-template <typename value_type, endianness endian, std::size_t alignment>
-inline value_type readAtBitAlignment(const void *memory, uint64_t startBit) {
-  assert(startBit < 8);
-  if (startBit == 0)
-    return read<value_type, endian, alignment>(memory);
-  else {
-    // Read two values and compose the result from them.
-    value_type val[2];
-    memcpy(&val[0],
-           LLVM_ASSUME_ALIGNED(
-               memory, (detail::PickAlignment<value_type, alignment>::value)),
-           sizeof(value_type) * 2);
-    val[0] = byte_swap<value_type, endian>(val[0]);
-    val[1] = byte_swap<value_type, endian>(val[1]);
-
-    // Shift bits from the lower value into place.
-    std::make_unsigned_t<value_type> lowerVal = val[0] >> startBit;
-    // Mask off upper bits after right shift in case of signed type.
-    std::make_unsigned_t<value_type> numBitsFirstVal =
-        (sizeof(value_type) * 8) - startBit;
-    lowerVal &= ((std::make_unsigned_t<value_type>)1 << numBitsFirstVal) - 1;
-
-    // Get the bits from the upper value.
-    std::make_unsigned_t<value_type> upperVal =
-        val[1] & (((std::make_unsigned_t<value_type>)1 << startBit) - 1);
-    // Shift them in to place.
-    upperVal <<= numBitsFirstVal;
-
-    return lowerVal | upperVal;
-  }
-}
-
-/// Write a value to memory with a particular endianness, for a location
-/// that starts at the given bit offset within the first byte.
-template <typename value_type, endianness endian, std::size_t alignment>
-inline void writeAtBitAlignment(void *memory, value_type value,
-                                uint64_t startBit) {
-  assert(startBit < 8);
-  if (startBit == 0)
-    write<value_type, endian, alignment>(memory, value);
-  else {
-    // Read two values and shift the result into them.
-    value_type val[2];
-    memcpy(&val[0],
-           LLVM_ASSUME_ALIGNED(
-               memory, (detail::PickAlignment<value_type, alignment>::value)),
-           sizeof(value_type) * 2);
-    val[0] = byte_swap<value_type, endian>(val[0]);
-    val[1] = byte_swap<value_type, endian>(val[1]);
-
-    // Mask off any existing bits in the upper part of the lower value that
-    // we want to replace.
-    val[0] &= ((std::make_unsigned_t<value_type>)1 << startBit) - 1;
-    std::make_unsigned_t<value_type> numBitsFirstVal =
-        (sizeof(value_type) * 8) - startBit;
-    std::make_unsigned_t<value_type> lowerVal = value;
-    if (startBit > 0) {
-      // Mask off the upper bits in the new value that are not going to go into
-      // the lower value. This avoids a left shift of a negative value, which
-      // is undefined behavior.
-      lowerVal &= (((std::make_unsigned_t<value_type>)1 << numBitsFirstVal) - 1);
-      // Now shift the new bits into place
-      lowerVal <<= startBit;
-    }
-    val[0] |= lowerVal;
-
-    // Mask off any existing bits in the lower part of the upper value that
-    // we want to replace.
-    val[1] &= ~(((std::make_unsigned_t<value_type>)1 << startBit) - 1);
-    // Next shift the bits that go into the upper value into position.
-    std::make_unsigned_t<value_type> upperVal = value >> numBitsFirstVal;
-    // Mask off upper bits after right shift in case of signed type.
-    upperVal &= ((std::make_unsigned_t<value_type>)1 << startBit) - 1;
-    val[1] |= upperVal;
-
-    // Finally, rewrite values.
-    val[0] = byte_swap<value_type, endian>(val[0]);
-    val[1] = byte_swap<value_type, endian>(val[1]);
-    memcpy(LLVM_ASSUME_ALIGNED(
-               memory, (detail::PickAlignment<value_type, alignment>::value)),
-           &val[0], sizeof(value_type) * 2);
-  }
-}
-
-} // end namespace endian
-
-namespace detail {
-
-template<typename value_type,
-         endianness endian,
-         std::size_t alignment>
-struct packed_endian_specific_integral {
-  packed_endian_specific_integral() = default;
-
-  explicit packed_endian_specific_integral(value_type val) { *this = val; }
-
-  operator value_type() const {
-    return endian::read<value_type, endian, alignment>(
-      (const void*)Value.buffer);
-  }
-
-  void operator=(value_type newValue) {
-    endian::write<value_type, endian, alignment>(
-      (void*)Value.buffer, newValue);
-  }
-
-  packed_endian_specific_integral &operator+=(value_type newValue) {
-    *this = *this + newValue;
-    return *this;
-  }
-
-  packed_endian_specific_integral &operator-=(value_type newValue) {
-    *this = *this - newValue;
-    return *this;
-  }
-
-  packed_endian_specific_integral &operator|=(value_type newValue) {
-    *this = *this | newValue;
-    return *this;
-  }
-
-  packed_endian_specific_integral &operator&=(value_type newValue) {
-    *this = *this & newValue;
-    return *this;
-  }
-
-private:
-  AlignedCharArray<PickAlignment<value_type, alignment>::value,
-                   sizeof(value_type)> Value;
-
-public:
-  struct ref {
-    explicit ref(void *Ptr) : Ptr(Ptr) {}
-
-    operator value_type() const {
-      return endian::read<value_type, endian, alignment>(Ptr);
-    }
-
-    void operator=(value_type NewValue) {
-      endian::write<value_type, endian, alignment>(Ptr, NewValue);
-    }
-
-  private:
-    void *Ptr;
-  };
-};
-
-} // end namespace detail
-
-using ulittle16_t =
-    detail::packed_endian_specific_integral<uint16_t, little, unaligned>;
-using ulittle32_t =
-    detail::packed_endian_specific_integral<uint32_t, little, unaligned>;
-using ulittle64_t =
-    detail::packed_endian_specific_integral<uint64_t, little, unaligned>;
-
-using little16_t =
-    detail::packed_endian_specific_integral<int16_t, little, unaligned>;
-using little32_t =
-    detail::packed_endian_specific_integral<int32_t, little, unaligned>;
-using little64_t =
-    detail::packed_endian_specific_integral<int64_t, little, unaligned>;
-
-using aligned_ulittle16_t =
-    detail::packed_endian_specific_integral<uint16_t, little, aligned>;
-using aligned_ulittle32_t =
-    detail::packed_endian_specific_integral<uint32_t, little, aligned>;
-using aligned_ulittle64_t =
-    detail::packed_endian_specific_integral<uint64_t, little, aligned>;
-
-using aligned_little16_t =
-    detail::packed_endian_specific_integral<int16_t, little, aligned>;
-using aligned_little32_t =
-    detail::packed_endian_specific_integral<int32_t, little, aligned>;
-using aligned_little64_t =
-    detail::packed_endian_specific_integral<int64_t, little, aligned>;
-
-using ubig16_t =
-    detail::packed_endian_specific_integral<uint16_t, big, unaligned>;
-using ubig32_t =
-    detail::packed_endian_specific_integral<uint32_t, big, unaligned>;
-using ubig64_t =
-    detail::packed_endian_specific_integral<uint64_t, big, unaligned>;
-
-using big16_t =
-    detail::packed_endian_specific_integral<int16_t, big, unaligned>;
-using big32_t =
-    detail::packed_endian_specific_integral<int32_t, big, unaligned>;
-using big64_t =
-    detail::packed_endian_specific_integral<int64_t, big, unaligned>;
-
-using aligned_ubig16_t =
-    detail::packed_endian_specific_integral<uint16_t, big, aligned>;
-using aligned_ubig32_t =
-    detail::packed_endian_specific_integral<uint32_t, big, aligned>;
-using aligned_ubig64_t =
-    detail::packed_endian_specific_integral<uint64_t, big, aligned>;
-
-using aligned_big16_t =
-    detail::packed_endian_specific_integral<int16_t, big, aligned>;
-using aligned_big32_t =
-    detail::packed_endian_specific_integral<int32_t, big, aligned>;
-using aligned_big64_t =
-    detail::packed_endian_specific_integral<int64_t, big, aligned>;
-
-using unaligned_uint16_t =
-    detail::packed_endian_specific_integral<uint16_t, native, unaligned>;
-using unaligned_uint32_t =
-    detail::packed_endian_specific_integral<uint32_t, native, unaligned>;
-using unaligned_uint64_t =
-    detail::packed_endian_specific_integral<uint64_t, native, unaligned>;
-
-using unaligned_int16_t =
-    detail::packed_endian_specific_integral<int16_t, native, unaligned>;
-using unaligned_int32_t =
-    detail::packed_endian_specific_integral<int32_t, native, unaligned>;
-using unaligned_int64_t =
-    detail::packed_endian_specific_integral<int64_t, native, unaligned>;
-
-namespace endian {
-
-template <typename T> inline T read(const void *P, endianness E) {
-  return read<T, unaligned>(P, E);
-}
-
-template <typename T, endianness E> inline T read(const void *P) {
-  return *(const detail::packed_endian_specific_integral<T, E, unaligned> *)P;
-}
-
-inline uint16_t read16(const void *P, endianness E) {
-  return read<uint16_t>(P, E);
-}
-inline uint32_t read32(const void *P, endianness E) {
-  return read<uint32_t>(P, E);
-}
-inline uint64_t read64(const void *P, endianness E) {
-  return read<uint64_t>(P, E);
-}
-
-template <endianness E> inline uint16_t read16(const void *P) {
-  return read<uint16_t, E>(P);
-}
-template <endianness E> inline uint32_t read32(const void *P) {
-  return read<uint32_t, E>(P);
-}
-template <endianness E> inline uint64_t read64(const void *P) {
-  return read<uint64_t, E>(P);
-}
-
-inline uint16_t read16le(const void *P) { return read16<little>(P); }
-inline uint32_t read32le(const void *P) { return read32<little>(P); }
-inline uint64_t read64le(const void *P) { return read64<little>(P); }
-inline uint16_t read16be(const void *P) { return read16<big>(P); }
-inline uint32_t read32be(const void *P) { return read32<big>(P); }
-inline uint64_t read64be(const void *P) { return read64<big>(P); }
-
-template <typename T> inline void write(void *P, T V, endianness E) {
-  write<T, unaligned>(P, V, E);
-}
-
-template <typename T, endianness E> inline void write(void *P, T V) {
-  *(detail::packed_endian_specific_integral<T, E, unaligned> *)P = V;
-}
-
-inline void write16(void *P, uint16_t V, endianness E) {
-  write<uint16_t>(P, V, E);
-}
-inline void write32(void *P, uint32_t V, endianness E) {
-  write<uint32_t>(P, V, E);
-}
-inline void write64(void *P, uint64_t V, endianness E) {
-  write<uint64_t>(P, V, E);
-}
-
-template <endianness E> inline void write16(void *P, uint16_t V) {
-  write<uint16_t, E>(P, V);
-}
-template <endianness E> inline void write32(void *P, uint32_t V) {
-  write<uint32_t, E>(P, V);
-}
-template <endianness E> inline void write64(void *P, uint64_t V) {
-  write<uint64_t, E>(P, V);
-}
-
-inline void write16le(void *P, uint16_t V) { write16<little>(P, V); }
-inline void write32le(void *P, uint32_t V) { write32<little>(P, V); }
-inline void write64le(void *P, uint64_t V) { write64<little>(P, V); }
-inline void write16be(void *P, uint16_t V) { write16<big>(P, V); }
-inline void write32be(void *P, uint32_t V) { write32<big>(P, V); }
-inline void write64be(void *P, uint64_t V) { write64<big>(P, V); }
-
-} // end namespace endian
-
-} // end namespace support
-} // end namespace wpi
-
-#endif // WPIUTIL_WPI_ENDIAN_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/EpochTracker.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/EpochTracker.h
deleted file mode 100644
index b26800b..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/EpochTracker.h
+++ /dev/null
@@ -1,97 +0,0 @@
-//===- llvm/ADT/EpochTracker.h - ADT epoch tracking --------------*- C++ -*-==//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-//
-// This file defines the DebugEpochBase and DebugEpochBase::HandleBase classes.
-// These can be used to write iterators that are fail-fast when LLVM is built
-// with asserts enabled.
-//
-//===----------------------------------------------------------------------===//
-
-#ifndef WPIUTIL_WPI_EPOCH_TRACKER_H
-#define WPIUTIL_WPI_EPOCH_TRACKER_H
-
-#include <cstdint>
-
-namespace wpi {
-
-#ifdef NDEBUG //ifndef LLVM_ENABLE_ABI_BREAKING_CHECKS
-
-class DebugEpochBase {
-public:
-  void incrementEpoch() {}
-
-  class HandleBase {
-  public:
-    HandleBase() = default;
-    explicit HandleBase(const DebugEpochBase *) {}
-    bool isHandleInSync() const { return true; }
-    const void *getEpochAddress() const { return nullptr; }
-  };
-};
-
-#else
-
-/// A base class for data structure classes wishing to make iterators
-/// ("handles") pointing into themselves fail-fast.  When building without
-/// asserts, this class is empty and does nothing.
-///
-/// DebugEpochBase does not by itself track handles pointing into itself.  The
-/// expectation is that routines touching the handles will poll on
-/// isHandleInSync at appropriate points to assert that the handle they're using
-/// is still valid.
-///
-class DebugEpochBase {
-  uint64_t Epoch;
-
-public:
-  DebugEpochBase() : Epoch(0) {}
-
-  /// Calling incrementEpoch invalidates all handles pointing into the
-  /// calling instance.
-  void incrementEpoch() { ++Epoch; }
-
-  /// The destructor calls incrementEpoch to make use-after-free bugs
-  /// more likely to crash deterministically.
-  ~DebugEpochBase() { incrementEpoch(); }
-
-  /// A base class for iterator classes ("handles") that wish to poll for
-  /// iterator invalidating modifications in the underlying data structure.
-  /// When LLVM is built without asserts, this class is empty and does nothing.
-  ///
-  /// HandleBase does not track the parent data structure by itself.  It expects
-  /// the routines modifying the data structure to call incrementEpoch when they
-  /// make an iterator-invalidating modification.
-  ///
-  class HandleBase {
-    const uint64_t *EpochAddress;
-    uint64_t EpochAtCreation;
-
-  public:
-    HandleBase() : EpochAddress(nullptr), EpochAtCreation(UINT64_MAX) {}
-
-    explicit HandleBase(const DebugEpochBase *Parent)
-        : EpochAddress(&Parent->Epoch), EpochAtCreation(Parent->Epoch) {}
-
-    /// Returns true if the DebugEpochBase this Handle is linked to has
-    /// not called incrementEpoch on itself since the creation of this
-    /// HandleBase instance.
-    bool isHandleInSync() const { return *EpochAddress == EpochAtCreation; }
-
-    /// Returns a pointer to the epoch word stored in the data structure
-    /// this handle points into.  Can be used to check if two iterators point
-    /// into the same data structure.
-    const void *getEpochAddress() const { return EpochAddress; }
-  };
-};
-
-#endif // LLVM_ENABLE_ABI_BREAKING_CHECKS
-
-} // namespace wpi
-
-#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/Errc.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/Errc.h
deleted file mode 100644
index ebce58a..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/Errc.h
+++ /dev/null
@@ -1,87 +0,0 @@
-//===- llvm/Support/Errc.h - Defines the llvm::errc enum --------*- C++ -*-===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-//
-// While std::error_code works OK on all platforms we use, there are some
-// some problems with std::errc that can be avoided by using our own
-// enumeration:
-//
-// * std::errc is a namespace in some implementations. That meas that ADL
-//   doesn't work and it is sometimes necessary to write std::make_error_code
-//   or in templates:
-//   using std::make_error_code;
-//   make_error_code(...);
-//
-//   with this enum it is safe to always just use make_error_code.
-//
-// * Some implementations define fewer names than others. This header has
-//   the intersection of all the ones we support.
-//
-// * std::errc is just marked with is_error_condition_enum. This means that
-//   common patters like AnErrorCode == errc::no_such_file_or_directory take
-//   4 virtual calls instead of two comparisons.
-//===----------------------------------------------------------------------===//
-
-#ifndef WPIUTIL_WPI_ERRC_H
-#define WPIUTIL_WPI_ERRC_H
-
-#include <system_error>
-
-namespace wpi {
-enum class errc {
-  argument_list_too_long = int(std::errc::argument_list_too_long),
-  argument_out_of_domain = int(std::errc::argument_out_of_domain),
-  bad_address = int(std::errc::bad_address),
-  bad_file_descriptor = int(std::errc::bad_file_descriptor),
-  broken_pipe = int(std::errc::broken_pipe),
-  device_or_resource_busy = int(std::errc::device_or_resource_busy),
-  directory_not_empty = int(std::errc::directory_not_empty),
-  executable_format_error = int(std::errc::executable_format_error),
-  file_exists = int(std::errc::file_exists),
-  file_too_large = int(std::errc::file_too_large),
-  filename_too_long = int(std::errc::filename_too_long),
-  function_not_supported = int(std::errc::function_not_supported),
-  illegal_byte_sequence = int(std::errc::illegal_byte_sequence),
-  inappropriate_io_control_operation =
-      int(std::errc::inappropriate_io_control_operation),
-  interrupted = int(std::errc::interrupted),
-  invalid_argument = int(std::errc::invalid_argument),
-  invalid_seek = int(std::errc::invalid_seek),
-  io_error = int(std::errc::io_error),
-  is_a_directory = int(std::errc::is_a_directory),
-  no_child_process = int(std::errc::no_child_process),
-  no_lock_available = int(std::errc::no_lock_available),
-  no_space_on_device = int(std::errc::no_space_on_device),
-  no_such_device_or_address = int(std::errc::no_such_device_or_address),
-  no_such_device = int(std::errc::no_such_device),
-  no_such_file_or_directory = int(std::errc::no_such_file_or_directory),
-  no_such_process = int(std::errc::no_such_process),
-  not_a_directory = int(std::errc::not_a_directory),
-  not_enough_memory = int(std::errc::not_enough_memory),
-  not_supported = int(std::errc::not_supported),
-  operation_not_permitted = int(std::errc::operation_not_permitted),
-  permission_denied = int(std::errc::permission_denied),
-  read_only_file_system = int(std::errc::read_only_file_system),
-  resource_deadlock_would_occur = int(std::errc::resource_deadlock_would_occur),
-  resource_unavailable_try_again =
-      int(std::errc::resource_unavailable_try_again),
-  result_out_of_range = int(std::errc::result_out_of_range),
-  too_many_files_open_in_system = int(std::errc::too_many_files_open_in_system),
-  too_many_files_open = int(std::errc::too_many_files_open),
-  too_many_links = int(std::errc::too_many_links)
-};
-
-inline std::error_code make_error_code(errc E) {
-  return std::error_code(static_cast<int>(E), std::generic_category());
-}
-}
-
-namespace std {
-template <> struct is_error_code_enum<wpi::errc> : std::true_type {};
-}
-#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/Errno.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/Errno.h
deleted file mode 100644
index 042d432..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/Errno.h
+++ /dev/null
@@ -1,38 +0,0 @@
-//===- llvm/Support/Errno.h - Portable+convenient errno handling -*- C++ -*-===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-//
-// This file declares some portable and convenient functions to deal with errno.
-//
-//===----------------------------------------------------------------------===//
-
-#ifndef WPIUTIL_WPI_ERRNO_H
-#define WPIUTIL_WPI_ERRNO_H
-
-#include <cerrno>
-#include <string>
-#include <type_traits>
-
-namespace wpi {
-namespace sys {
-
-template <typename FailT, typename Fun, typename... Args>
-inline auto RetryAfterSignal(const FailT &Fail, const Fun &F,
-                             const Args &... As) -> decltype(F(As...)) {
-  decltype(F(As...)) Res;
-  do {
-    errno = 0;
-    Res = F(As...);
-  } while (Res == Fail && errno == EINTR);
-  return Res;
-}
-
-}  // namespace sys
-}  // namespace wpi
-
-#endif  // WPIUTIL_WPI_ERRNO_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/ErrorHandling.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/ErrorHandling.h
deleted file mode 100644
index da9af4b..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/ErrorHandling.h
+++ /dev/null
@@ -1,140 +0,0 @@
-//===- llvm/Support/ErrorHandling.h - Fatal error handling ------*- C++ -*-===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-//
-// This file defines an API used to indicate fatal error conditions.  Non-fatal
-// errors (most of them) should be handled through LLVMContext.
-//
-//===----------------------------------------------------------------------===//
-
-#ifndef WPIUTIL_WPI_ERRORHANDLING_H
-#define WPIUTIL_WPI_ERRORHANDLING_H
-
-#include "wpi/Compiler.h"
-#include <string>
-#include <string_view>
-
-namespace wpi {
-  /// An error handler callback.
-  typedef void (*fatal_error_handler_t)(void *user_data,
-                                        const std::string& reason,
-                                        bool gen_crash_diag);
-
-  /// install_fatal_error_handler - Installs a new error handler to be used
-  /// whenever a serious (non-recoverable) error is encountered by LLVM.
-  ///
-  /// If no error handler is installed the default is to print the error message
-  /// to stderr, and call exit(1).  If an error handler is installed then it is
-  /// the handler's responsibility to log the message, it will no longer be
-  /// printed to stderr.  If the error handler returns, then exit(1) will be
-  /// called.
-  ///
-  /// It is dangerous to naively use an error handler which throws an exception.
-  /// Even though some applications desire to gracefully recover from arbitrary
-  /// faults, blindly throwing exceptions through unfamiliar code isn't a way to
-  /// achieve this.
-  ///
-  /// \param user_data - An argument which will be passed to the install error
-  /// handler.
-  void install_fatal_error_handler(fatal_error_handler_t handler,
-                                   void *user_data = nullptr);
-
-  /// Restores default error handling behavior.
-  void remove_fatal_error_handler();
-
-  /// ScopedFatalErrorHandler - This is a simple helper class which just
-  /// calls install_fatal_error_handler in its constructor and
-  /// remove_fatal_error_handler in its destructor.
-  struct ScopedFatalErrorHandler {
-    explicit ScopedFatalErrorHandler(fatal_error_handler_t handler,
-                                     void *user_data = nullptr) {
-      install_fatal_error_handler(handler, user_data);
-    }
-
-    ~ScopedFatalErrorHandler() { remove_fatal_error_handler(); }
-  };
-
-/// Reports a serious error, calling any installed error handler. These
-/// functions are intended to be used for error conditions which are outside
-/// the control of the compiler (I/O errors, invalid user input, etc.)
-///
-/// If no error handler is installed the default is to print the message to
-/// standard error, followed by a newline.
-/// After the error handler is called this function will call exit(1), it
-/// does not return.
-LLVM_ATTRIBUTE_NORETURN void report_fatal_error(const char *reason,
-                                                bool gen_crash_diag = true);
-LLVM_ATTRIBUTE_NORETURN void report_fatal_error(const std::string &reason,
-                                                bool gen_crash_diag = true);
-LLVM_ATTRIBUTE_NORETURN void report_fatal_error(std::string_view reason,
-                                                bool gen_crash_diag = true);
-
-/// Installs a new bad alloc error handler that should be used whenever a
-/// bad alloc error, e.g. failing malloc/calloc, is encountered by LLVM.
-///
-/// The user can install a bad alloc handler, in order to define the behavior
-/// in case of failing allocations, e.g. throwing an exception. Note that this
-/// handler must not trigger any additional allocations itself.
-///
-/// If no error handler is installed the default is to print the error message
-/// to stderr, and call exit(1).  If an error handler is installed then it is
-/// the handler's responsibility to log the message, it will no longer be
-/// printed to stderr.  If the error handler returns, then exit(1) will be
-/// called.
-///
-///
-/// \param user_data - An argument which will be passed to the installed error
-/// handler.
-void install_bad_alloc_error_handler(fatal_error_handler_t handler,
-                                     void *user_data = nullptr);
-
-/// Restores default bad alloc error handling behavior.
-void remove_bad_alloc_error_handler();
-
-void install_out_of_memory_new_handler();
-
-/// Reports a bad alloc error, calling any user defined bad alloc
-/// error handler. In contrast to the generic 'report_fatal_error'
-/// functions, this function is expected to return, e.g. the user
-/// defined error handler throws an exception.
-///
-/// Note: When throwing an exception in the bad alloc handler, make sure that
-/// the following unwind succeeds, e.g. do not trigger additional allocations
-/// in the unwind chain.
-///
-/// If no error handler is installed (default), then a bad_alloc exception
-/// is thrown, if LLVM is compiled with exception support, otherwise an
-/// assertion is called.
-void report_bad_alloc_error(const char *Reason, bool GenCrashDiag = true);
-
-/// This function calls abort(), and prints the optional message to stderr.
-/// Use the wpi_unreachable macro (that adds location info), instead of
-/// calling this function directly.
-LLVM_ATTRIBUTE_NORETURN void
-wpi_unreachable_internal(const char *msg = nullptr, const char *file = nullptr,
-                         unsigned line = 0);
-}
-
-/// Marks that the current location is not supposed to be reachable.
-/// In !NDEBUG builds, prints the message and location info to stderr.
-/// In NDEBUG builds, becomes an optimizer hint that the current location
-/// is not supposed to be reachable.  On compilers that don't support
-/// such hints, prints a reduced message instead.
-///
-/// Use this instead of assert(0).  It conveys intent more clearly and
-/// allows compilers to omit some unnecessary code.
-#ifndef NDEBUG
-#define wpi_unreachable(msg) \
-  ::wpi::wpi_unreachable_internal(msg, __FILE__, __LINE__)
-#elif defined(LLVM_BUILTIN_UNREACHABLE)
-#define wpi_unreachable(msg) LLVM_BUILTIN_UNREACHABLE
-#else
-#define wpi_unreachable(msg) ::wpi::wpi_unreachable_internal()
-#endif
-
-#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/EventLoopRunner.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/EventLoopRunner.h
deleted file mode 100644
index 5d35d40..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/EventLoopRunner.h
+++ /dev/null
@@ -1,62 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_EVENTLOOPRUNNER_H_
-#define WPIUTIL_WPI_EVENTLOOPRUNNER_H_
-
-#include <functional>
-#include <memory>
-
-#include "wpi/SafeThread.h"
-#include "wpi/uv/Loop.h"
-
-namespace wpi {
-
-/**
- * Executes an event loop on a separate thread.
- */
-class EventLoopRunner {
- public:
-  using LoopFunc = std::function<void(uv::Loop&)>;
-
-  EventLoopRunner();
-  virtual ~EventLoopRunner();
-
-  /**
-   * Stop the loop.  Once the loop is stopped it cannot be restarted.
-   * This function does not return until the loop has exited.
-   */
-  void Stop();
-
-  /**
-   * Run a function asynchronously (once) on the loop.
-   * This is safe to call from any thread, but is NOT safe to call from the
-   * provided function (it will deadlock).
-   * @param func function to execute on the loop
-   */
-  void ExecAsync(LoopFunc func);
-
-  /**
-   * Run a function synchronously (once) on the loop.
-   * This is safe to call from any thread, but is NOT safe to call from the
-   * provided function (it will deadlock).
-   * This does not return until the function finishes executing.
-   * @param func function to execute on the loop
-   */
-  void ExecSync(LoopFunc func);
-
-  /**
-   * Get the loop.  If the loop thread is not running, returns nullptr.
-   * @return The loop
-   */
-  std::shared_ptr<uv::Loop> GetLoop();
-
- private:
-  class Thread;
-  SafeThreadOwner<Thread> m_owner;
-};
-
-}  // namespace wpi
-
-#endif  // WPIUTIL_WPI_EVENTLOOPRUNNER_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/EventVector.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/EventVector.h
new file mode 100644
index 0000000..fc54df7
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/EventVector.h
@@ -0,0 +1,51 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include "wpi/SmallVector.h"
+#include "wpi/Synchronization.h"
+#include "wpi/mutex.h"
+
+namespace wpi {
+struct EventVector {
+  wpi::mutex mutex;
+  wpi::SmallVector<WPI_EventHandle, 4> events;
+
+  /**
+   * Adds an event to the event vector.
+   *
+   * @param handle the event to add
+   */
+  void Add(WPI_EventHandle handle) {
+    std::scoped_lock lock{mutex};
+    events.emplace_back(handle);
+  }
+
+  /**
+   * Removes an event from the event vector.
+   *
+   * @param handle The event to remove
+   */
+  void Remove(WPI_EventHandle handle) {
+    std::scoped_lock lock{mutex};
+    auto it = std::find_if(
+        events.begin(), events.end(),
+        [=](const WPI_EventHandle fromHandle) { return fromHandle == handle; });
+    if (it != events.end()) {
+      events.erase(it);
+    }
+  }
+
+  /**
+   * Wakes up all events in the event vector.
+   */
+  void Wakeup() {
+    std::scoped_lock lock{mutex};
+    for (auto&& handle : events) {
+      wpi::SetEvent(handle);
+    }
+  }
+};
+}  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/FunctionExtras.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/FunctionExtras.h
deleted file mode 100644
index 57bc8dc..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/FunctionExtras.h
+++ /dev/null
@@ -1,308 +0,0 @@
-//===- FunctionExtras.h - Function type erasure utilities -------*- C++ -*-===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-/// \file
-/// This file provides a collection of function (or more generally, callable)
-/// type erasure utilities supplementing those provided by the standard library
-/// in `<function>`.
-///
-/// It provides `unique_function`, which works like `std::function` but supports
-/// move-only callable objects.
-///
-/// Future plans:
-/// - Add a `function` that provides const, volatile, and ref-qualified support,
-///   which doesn't work with `std::function`.
-/// - Provide support for specifying multiple signatures to type erase callable
-///   objects with an overload set, such as those produced by generic lambdas.
-/// - Expand to include a copyable utility that directly replaces std::function
-///   but brings the above improvements.
-///
-/// Note that LLVM's utilities are greatly simplified by not supporting
-/// allocators.
-///
-/// If the standard library ever begins to provide comparable facilities we can
-/// consider switching to those.
-///
-//===----------------------------------------------------------------------===//
-
-#ifndef WPIUTIL_WPI_FUNCTION_EXTRAS_H
-#define WPIUTIL_WPI_FUNCTION_EXTRAS_H
-
-#include "wpi/Compiler.h"
-#include "wpi/PointerIntPair.h"
-#include "wpi/PointerUnion.h"
-#include <memory>
-#include <type_traits>
-
-namespace wpi {
-
-template <typename FunctionT> class unique_function;
-
-// GCC warns on OutOfLineStorage
-#if defined(__GNUC__) && !defined(__clang__)
-#pragma GCC diagnostic push
-#pragma GCC diagnostic ignored "-Wmaybe-uninitialized"
-#endif
-
-template <typename ReturnT, typename... ParamTs>
-class unique_function<ReturnT(ParamTs...)> {
-  static constexpr size_t InlineStorageSize = sizeof(void *) * 4;
-
-  // MSVC has a bug and ICEs if we give it a particular dependent value
-  // expression as part of the `std::conditional` below. To work around this,
-  // we build that into a template struct's constexpr bool.
-  template <typename T> struct IsSizeLessThanThresholdT {
-    static constexpr bool value = sizeof(T) <= (2 * sizeof(void *));
-  };
-
-  // Provide a type function to map parameters that won't observe extra copies
-  // or moves and which are small enough to likely pass in register to values
-  // and all other types to l-value reference types. We use this to compute the
-  // types used in our erased call utility to minimize copies and moves unless
-  // doing so would force things unnecessarily into memory.
-  //
-  // The heuristic used is related to common ABI register passing conventions.
-  // It doesn't have to be exact though, and in one way it is more strict
-  // because we want to still be able to observe either moves *or* copies.
-  template <typename T>
-  using AdjustedParamT = typename std::conditional<
-      !std::is_reference<T>::value &&
-          std::is_trivially_copy_constructible<T>::value &&
-          std::is_trivially_move_constructible<T>::value &&
-          IsSizeLessThanThresholdT<T>::value,
-      T, T &>::type;
-
-  // The type of the erased function pointer we use as a callback to dispatch to
-  // the stored callable when it is trivial to move and destroy.
-  using CallPtrT = ReturnT (*)(void *CallableAddr,
-                               AdjustedParamT<ParamTs>... Params);
-  using MovePtrT = void (*)(void *LHSCallableAddr, void *RHSCallableAddr);
-  using DestroyPtrT = void (*)(void *CallableAddr);
-
-  /// A struct to hold a single trivial callback with sufficient alignment for
-  /// our bitpacking.
-  struct alignas(8) TrivialCallback {
-    CallPtrT CallPtr;
-  };
-
-  /// A struct we use to aggregate three callbacks when we need full set of
-  /// operations.
-  struct alignas(8) NonTrivialCallbacks {
-    CallPtrT CallPtr;
-    MovePtrT MovePtr;
-    DestroyPtrT DestroyPtr;
-  };
-
-  // Create a pointer union between either a pointer to a static trivial call
-  // pointer in a struct or a pointer to a static struct of the call, move, and
-  // destroy pointers.
-  using CallbackPointerUnionT =
-      PointerUnion<TrivialCallback *, NonTrivialCallbacks *>;
-
-  // The main storage buffer. This will either have a pointer to out-of-line
-  // storage or an inline buffer storing the callable.
-  union StorageUnionT {
-    // For out-of-line storage we keep a pointer to the underlying storage and
-    // the size. This is enough to deallocate the memory.
-    struct OutOfLineStorageT {
-      void *StoragePtr;
-      size_t Size;
-      size_t Alignment;
-    } OutOfLineStorage;
-    static_assert(
-        sizeof(OutOfLineStorageT) <= InlineStorageSize,
-        "Should always use all of the out-of-line storage for inline storage!");
-
-    // For in-line storage, we just provide an aligned character buffer. We
-    // provide four pointers worth of storage here.
-    typename std::aligned_storage<InlineStorageSize, alignof(void *)>::type
-        InlineStorage;
-  } StorageUnion;
-
-  // A compressed pointer to either our dispatching callback or our table of
-  // dispatching callbacks and the flag for whether the callable itself is
-  // stored inline or not.
-  PointerIntPair<CallbackPointerUnionT, 1, bool> CallbackAndInlineFlag;
-
-  bool isInlineStorage() const { return CallbackAndInlineFlag.getInt(); }
-
-  bool isTrivialCallback() const {
-    return CallbackAndInlineFlag.getPointer().template is<TrivialCallback *>();
-  }
-
-  CallPtrT getTrivialCallback() const {
-    return CallbackAndInlineFlag.getPointer().template get<TrivialCallback *>()->CallPtr;
-  }
-
-  NonTrivialCallbacks *getNonTrivialCallbacks() const {
-    return CallbackAndInlineFlag.getPointer()
-        .template get<NonTrivialCallbacks *>();
-  }
-
-  void *getInlineStorage() { return &StorageUnion.InlineStorage; }
-
-  void *getOutOfLineStorage() {
-    return StorageUnion.OutOfLineStorage.StoragePtr;
-  }
-  size_t getOutOfLineStorageSize() const {
-    return StorageUnion.OutOfLineStorage.Size;
-  }
-  size_t getOutOfLineStorageAlignment() const {
-    return StorageUnion.OutOfLineStorage.Alignment;
-  }
-
-  void setOutOfLineStorage(void *Ptr, size_t Size, size_t Alignment) {
-    StorageUnion.OutOfLineStorage = {Ptr, Size, Alignment};
-  }
-
-  template <typename CallableT>
-  static ReturnT CallImpl(void *CallableAddr, AdjustedParamT<ParamTs>... Params) {
-    return (*reinterpret_cast<CallableT *>(CallableAddr))(
-        std::forward<ParamTs>(Params)...);
-  }
-
-  template <typename CallableT>
-  static void MoveImpl(void *LHSCallableAddr, void *RHSCallableAddr) noexcept {
-    new (LHSCallableAddr)
-        CallableT(std::move(*reinterpret_cast<CallableT *>(RHSCallableAddr)));
-  }
-
-  template <typename CallableT>
-  static void DestroyImpl(void *CallableAddr) noexcept {
-    reinterpret_cast<CallableT *>(CallableAddr)->~CallableT();
-  }
-
-public:
-  unique_function() = default;
-  unique_function(std::nullptr_t /*null_callable*/) {}
-
-  ~unique_function() {
-    if (!CallbackAndInlineFlag.getPointer())
-      return;
-
-    // Cache this value so we don't re-check it after type-erased operations.
-    bool IsInlineStorage = isInlineStorage();
-
-    if (!isTrivialCallback())
-      getNonTrivialCallbacks()->DestroyPtr(
-          IsInlineStorage ? getInlineStorage() : getOutOfLineStorage());
-
-    if (!IsInlineStorage)
-      deallocate_buffer(getOutOfLineStorage(), getOutOfLineStorageSize(),
-                        getOutOfLineStorageAlignment());
-  }
-
-  unique_function(unique_function &&RHS) noexcept {
-    // Copy the callback and inline flag.
-    CallbackAndInlineFlag = RHS.CallbackAndInlineFlag;
-
-    // If the RHS is empty, just copying the above is sufficient.
-    if (!RHS)
-      return;
-
-    if (!isInlineStorage()) {
-      // The out-of-line case is easiest to move.
-      StorageUnion.OutOfLineStorage = RHS.StorageUnion.OutOfLineStorage;
-    } else if (isTrivialCallback()) {
-      // Move is trivial, just memcpy the bytes across.
-      memcpy(getInlineStorage(), RHS.getInlineStorage(), InlineStorageSize);
-    } else {
-      // Non-trivial move, so dispatch to a type-erased implementation.
-      getNonTrivialCallbacks()->MovePtr(getInlineStorage(),
-                                        RHS.getInlineStorage());
-    }
-
-    // Clear the old callback and inline flag to get back to as-if-null.
-    RHS.CallbackAndInlineFlag = {};
-
-#ifndef NDEBUG
-    // In debug builds, we also scribble across the rest of the storage.
-    memset(RHS.getInlineStorage(), 0xAD, InlineStorageSize);
-#endif
-  }
-
-  unique_function &operator=(unique_function &&RHS) noexcept {
-    if (this == &RHS)
-      return *this;
-
-    // Because we don't try to provide any exception safety guarantees we can
-    // implement move assignment very simply by first destroying the current
-    // object and then move-constructing over top of it.
-    this->~unique_function();
-    new (this) unique_function(std::move(RHS));
-    return *this;
-  }
-
-  template <typename CallableT>
-  unique_function(CallableT Callable,
-                  std::enable_if_t<
-                    std::is_invocable_r_v<
-                      ReturnT, CallableT, ParamTs...>>* = nullptr) {
-    bool IsInlineStorage = true;
-    void *CallableAddr = getInlineStorage();
-    if (sizeof(CallableT) > InlineStorageSize ||
-        alignof(CallableT) > alignof(decltype(StorageUnion.InlineStorage))) {
-      IsInlineStorage = false;
-      // Allocate out-of-line storage. FIXME: Use an explicit alignment
-      // parameter in C++17 mode.
-      auto Size = sizeof(CallableT);
-      auto Alignment = alignof(CallableT);
-      CallableAddr = allocate_buffer(Size, Alignment);
-      setOutOfLineStorage(CallableAddr, Size, Alignment);
-    }
-
-    // Now move into the storage.
-    new (CallableAddr) CallableT(std::move(Callable));
-
-    // See if we can create a trivial callback. We need the callable to be
-    // trivially moved and trivially destroyed so that we don't have to store
-    // type erased callbacks for those operations.
-    //
-    // FIXME: We should use constexpr if here and below to avoid instantiating
-    // the non-trivial static objects when unnecessary. While the linker should
-    // remove them, it is still wasteful.
-    if (std::is_trivially_move_constructible<CallableT>::value &&
-        std::is_trivially_destructible<CallableT>::value) {
-      // We need to create a nicely aligned object. We use a static variable
-      // for this because it is a trivial struct.
-      static TrivialCallback Callback = { &CallImpl<CallableT> };
-
-      CallbackAndInlineFlag = {&Callback, IsInlineStorage};
-      return;
-    }
-
-    // Otherwise, we need to point at an object that contains all the different
-    // type erased behaviors needed. Create a static instance of the struct type
-    // here and then use a pointer to that.
-    static NonTrivialCallbacks Callbacks = {
-        &CallImpl<CallableT>, &MoveImpl<CallableT>, &DestroyImpl<CallableT>};
-
-    CallbackAndInlineFlag = {&Callbacks, IsInlineStorage};
-  }
-
-  ReturnT operator()(ParamTs... Params) {
-    void *CallableAddr =
-        isInlineStorage() ? getInlineStorage() : getOutOfLineStorage();
-
-    return (isTrivialCallback()
-                ? getTrivialCallback()
-                : getNonTrivialCallbacks()->CallPtr)(CallableAddr, Params...);
-  }
-
-  explicit operator bool() const {
-    return (bool)CallbackAndInlineFlag.getPointer();
-  }
-};
-
-#if defined(__GNUC__) && !defined(__clang__)
-#pragma GCC diagnostic pop
-#endif
-
-} // end namespace wpi
-
-#endif // WPIUTIL_WPI_FUNCTION_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/Hashing.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/Hashing.h
deleted file mode 100644
index e58bfdd..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/Hashing.h
+++ /dev/null
@@ -1,675 +0,0 @@
-//===-- llvm/ADT/Hashing.h - Utilities for hashing --------------*- C++ -*-===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-//
-// This file implements the newly proposed standard C++ interfaces for hashing
-// arbitrary data and building hash functions for user-defined types. This
-// interface was originally proposed in N3333[1] and is currently under review
-// for inclusion in a future TR and/or standard.
-//
-// The primary interfaces provide are comprised of one type and three functions:
-//
-//  -- 'hash_code' class is an opaque type representing the hash code for some
-//     data. It is the intended product of hashing, and can be used to implement
-//     hash tables, checksumming, and other common uses of hashes. It is not an
-//     integer type (although it can be converted to one) because it is risky
-//     to assume much about the internals of a hash_code. In particular, each
-//     execution of the program has a high probability of producing a different
-//     hash_code for a given input. Thus their values are not stable to save or
-//     persist, and should only be used during the execution for the
-//     construction of hashing datastructures.
-//
-//  -- 'hash_value' is a function designed to be overloaded for each
-//     user-defined type which wishes to be used within a hashing context. It
-//     should be overloaded within the user-defined type's namespace and found
-//     via ADL. Overloads for primitive types are provided by this library.
-//
-//  -- 'hash_combine' and 'hash_combine_range' are functions designed to aid
-//      programmers in easily and intuitively combining a set of data into
-//      a single hash_code for their object. They should only logically be used
-//      within the implementation of a 'hash_value' routine or similar context.
-//
-// Note that 'hash_combine_range' contains very special logic for hashing
-// a contiguous array of integers or pointers. This logic is *extremely* fast,
-// on a modern Intel "Gainestown" Xeon (Nehalem uarch) @2.2 GHz, these were
-// benchmarked at over 6.5 GiB/s for large keys, and <20 cycles/hash for keys
-// under 32-bytes.
-//
-//===----------------------------------------------------------------------===//
-
-#ifndef WPIUTIL_WPI_HASHING_H
-#define WPIUTIL_WPI_HASHING_H
-
-#include "wpi/Endian.h"
-#include "wpi/SwapByteOrder.h"
-#include "wpi/type_traits.h"
-#include <stdint.h>
-#include <algorithm>
-#include <cassert>
-#include <cstring>
-#include <string>
-#include <string_view>
-#include <utility>
-
-#ifdef _WIN32
-#pragma warning(push)
-#pragma warning(disable : 26495)
-#endif
-
-namespace wpi {
-
-/// An opaque object representing a hash code.
-///
-/// This object represents the result of hashing some entity. It is intended to
-/// be used to implement hashtables or other hashing-based data structures.
-/// While it wraps and exposes a numeric value, this value should not be
-/// trusted to be stable or predictable across processes or executions.
-///
-/// In order to obtain the hash_code for an object 'x':
-/// \code
-///   using wpi::hash_value;
-///   wpi::hash_code code = hash_value(x);
-/// \endcode
-class hash_code {
-  size_t value;
-
-public:
-  /// Default construct a hash_code.
-  /// Note that this leaves the value uninitialized.
-  hash_code() = default;
-
-  /// Form a hash code directly from a numerical value.
-  hash_code(size_t value) : value(value) {}
-
-  /// Convert the hash code to its numerical value for use.
-  /*explicit*/ operator size_t() const { return value; }
-
-  friend bool operator==(const hash_code &lhs, const hash_code &rhs) {
-    return lhs.value == rhs.value;
-  }
-  friend bool operator!=(const hash_code &lhs, const hash_code &rhs) {
-    return lhs.value != rhs.value;
-  }
-
-  /// Allow a hash_code to be directly run through hash_value.
-  friend size_t hash_value(const hash_code &code) { return code.value; }
-};
-
-/// Compute a hash_code for any integer value.
-///
-/// Note that this function is intended to compute the same hash_code for
-/// a particular value without regard to the pre-promotion type. This is in
-/// contrast to hash_combine which may produce different hash_codes for
-/// differing argument types even if they would implicit promote to a common
-/// type without changing the value.
-template <typename T>
-typename std::enable_if<is_integral_or_enum<T>::value, hash_code>::type
-hash_value(T value);
-
-/// Compute a hash_code for a pointer's address.
-///
-/// N.B.: This hashes the *address*. Not the value and not the type.
-template <typename T> hash_code hash_value(const T *ptr);
-
-/// Compute a hash_code for a pair of objects.
-template <typename T, typename U>
-hash_code hash_value(const std::pair<T, U> &arg);
-
-/// Compute a hash_code for a standard string.
-template <typename T>
-hash_code hash_value(const std::basic_string<T> &arg);
-
-
-/// Override the execution seed with a fixed value.
-///
-/// This hashing library uses a per-execution seed designed to change on each
-/// run with high probability in order to ensure that the hash codes are not
-/// attackable and to ensure that output which is intended to be stable does
-/// not rely on the particulars of the hash codes produced.
-///
-/// That said, there are use cases where it is important to be able to
-/// reproduce *exactly* a specific behavior. To that end, we provide a function
-/// which will forcibly set the seed to a fixed value. This must be done at the
-/// start of the program, before any hashes are computed. Also, it cannot be
-/// undone. This makes it thread-hostile and very hard to use outside of
-/// immediately on start of a simple program designed for reproducible
-/// behavior.
-void set_fixed_execution_hash_seed(uint64_t fixed_value);
-
-
-// All of the implementation details of actually computing the various hash
-// code values are held within this namespace. These routines are included in
-// the header file mainly to allow inlining and constant propagation.
-namespace hashing {
-namespace detail {
-
-inline uint64_t fetch64(const char *p) {
-  uint64_t result;
-  memcpy(&result, p, sizeof(result));
-  if (support::endian::system_endianness() == support::big)
-    sys::swapByteOrder(result);
-  return result;
-}
-
-inline uint32_t fetch32(const char *p) {
-  uint32_t result;
-  memcpy(&result, p, sizeof(result));
-  if (support::endian::system_endianness() == support::big)
-    sys::swapByteOrder(result);
-  return result;
-}
-
-/// Some primes between 2^63 and 2^64 for various uses.
-static const uint64_t k0 = 0xc3a5c85c97cb3127ULL;
-static const uint64_t k1 = 0xb492b66fbe98f273ULL;
-static const uint64_t k2 = 0x9ae16a3b2f90404fULL;
-static const uint64_t k3 = 0xc949d7c7509e6557ULL;
-
-/// Bitwise right rotate.
-/// Normally this will compile to a single instruction, especially if the
-/// shift is a manifest constant.
-inline uint64_t rotate(uint64_t val, size_t shift) {
-  // Avoid shifting by 64: doing so yields an undefined result.
-  return shift == 0 ? val : ((val >> shift) | (val << (64 - shift)));
-}
-
-inline uint64_t shift_mix(uint64_t val) {
-  return val ^ (val >> 47);
-}
-
-inline uint64_t hash_16_bytes(uint64_t low, uint64_t high) {
-  // Murmur-inspired hashing.
-  const uint64_t kMul = 0x9ddfea08eb382d69ULL;
-  uint64_t a = (low ^ high) * kMul;
-  a ^= (a >> 47);
-  uint64_t b = (high ^ a) * kMul;
-  b ^= (b >> 47);
-  b *= kMul;
-  return b;
-}
-
-inline uint64_t hash_1to3_bytes(const char *s, size_t len, uint64_t seed) {
-  uint8_t a = s[0];
-  uint8_t b = s[len >> 1];
-  uint8_t c = s[len - 1];
-  uint32_t y = static_cast<uint32_t>(a) + (static_cast<uint32_t>(b) << 8);
-  uint32_t z = static_cast<uint32_t>(len + (static_cast<uint64_t>(c) << 2));
-  return shift_mix(y * k2 ^ z * k3 ^ seed) * k2;
-}
-
-inline uint64_t hash_4to8_bytes(const char *s, size_t len, uint64_t seed) {
-  uint64_t a = fetch32(s);
-  return hash_16_bytes(len + (a << 3), seed ^ fetch32(s + len - 4));
-}
-
-inline uint64_t hash_9to16_bytes(const char *s, size_t len, uint64_t seed) {
-  uint64_t a = fetch64(s);
-  uint64_t b = fetch64(s + len - 8);
-  return hash_16_bytes(seed ^ a, rotate(b + len, len)) ^ b;
-}
-
-inline uint64_t hash_17to32_bytes(const char *s, size_t len, uint64_t seed) {
-  uint64_t a = fetch64(s) * k1;
-  uint64_t b = fetch64(s + 8);
-  uint64_t c = fetch64(s + len - 8) * k2;
-  uint64_t d = fetch64(s + len - 16) * k0;
-  return hash_16_bytes(rotate(a - b, 43) + rotate(c ^ seed, 30) + d,
-                       a + rotate(b ^ k3, 20) - c + len + seed);
-}
-
-inline uint64_t hash_33to64_bytes(const char *s, size_t len, uint64_t seed) {
-  uint64_t z = fetch64(s + 24);
-  uint64_t a = fetch64(s) + (len + fetch64(s + len - 16)) * k0;
-  uint64_t b = rotate(a + z, 52);
-  uint64_t c = rotate(a, 37);
-  a += fetch64(s + 8);
-  c += rotate(a, 7);
-  a += fetch64(s + 16);
-  uint64_t vf = a + z;
-  uint64_t vs = b + rotate(a, 31) + c;
-  a = fetch64(s + 16) + fetch64(s + len - 32);
-  z = fetch64(s + len - 8);
-  b = rotate(a + z, 52);
-  c = rotate(a, 37);
-  a += fetch64(s + len - 24);
-  c += rotate(a, 7);
-  a += fetch64(s + len - 16);
-  uint64_t wf = a + z;
-  uint64_t ws = b + rotate(a, 31) + c;
-  uint64_t r = shift_mix((vf + ws) * k2 + (wf + vs) * k0);
-  return shift_mix((seed ^ (r * k0)) + vs) * k2;
-}
-
-inline uint64_t hash_short(const char *s, size_t length, uint64_t seed) {
-  if (length >= 4 && length <= 8)
-    return hash_4to8_bytes(s, length, seed);
-  if (length > 8 && length <= 16)
-    return hash_9to16_bytes(s, length, seed);
-  if (length > 16 && length <= 32)
-    return hash_17to32_bytes(s, length, seed);
-  if (length > 32)
-    return hash_33to64_bytes(s, length, seed);
-  if (length != 0)
-    return hash_1to3_bytes(s, length, seed);
-
-  return k2 ^ seed;
-}
-
-/// The intermediate state used during hashing.
-/// Currently, the algorithm for computing hash codes is based on CityHash and
-/// keeps 56 bytes of arbitrary state.
-struct hash_state {
-  uint64_t h0, h1, h2, h3, h4, h5, h6;
-
-  /// Create a new hash_state structure and initialize it based on the
-  /// seed and the first 64-byte chunk.
-  /// This effectively performs the initial mix.
-  static hash_state create(const char *s, uint64_t seed) {
-    hash_state state = {
-      0, seed, hash_16_bytes(seed, k1), rotate(seed ^ k1, 49),
-      seed * k1, shift_mix(seed), 0 };
-    state.h6 = hash_16_bytes(state.h4, state.h5);
-    state.mix(s);
-    return state;
-  }
-
-  /// Mix 32-bytes from the input sequence into the 16-bytes of 'a'
-  /// and 'b', including whatever is already in 'a' and 'b'.
-  static void mix_32_bytes(const char *s, uint64_t &a, uint64_t &b) {
-    a += fetch64(s);
-    uint64_t c = fetch64(s + 24);
-    b = rotate(b + a + c, 21);
-    uint64_t d = a;
-    a += fetch64(s + 8) + fetch64(s + 16);
-    b += rotate(a, 44) + d;
-    a += c;
-  }
-
-  /// Mix in a 64-byte buffer of data.
-  /// We mix all 64 bytes even when the chunk length is smaller, but we
-  /// record the actual length.
-  void mix(const char *s) {
-    h0 = rotate(h0 + h1 + h3 + fetch64(s + 8), 37) * k1;
-    h1 = rotate(h1 + h4 + fetch64(s + 48), 42) * k1;
-    h0 ^= h6;
-    h1 += h3 + fetch64(s + 40);
-    h2 = rotate(h2 + h5, 33) * k1;
-    h3 = h4 * k1;
-    h4 = h0 + h5;
-    mix_32_bytes(s, h3, h4);
-    h5 = h2 + h6;
-    h6 = h1 + fetch64(s + 16);
-    mix_32_bytes(s + 32, h5, h6);
-    std::swap(h2, h0);
-  }
-
-  /// Compute the final 64-bit hash code value based on the current
-  /// state and the length of bytes hashed.
-  uint64_t finalize(size_t length) {
-    return hash_16_bytes(hash_16_bytes(h3, h5) + shift_mix(h1) * k1 + h2,
-                         hash_16_bytes(h4, h6) + shift_mix(length) * k1 + h0);
-  }
-};
-
-
-/// A global, fixed seed-override variable.
-///
-/// This variable can be set using the \see wpi::set_fixed_execution_seed
-/// function. See that function for details. Do not, under any circumstances,
-/// set or read this variable.
-extern uint64_t fixed_seed_override;
-
-inline uint64_t get_execution_seed() {
-  // FIXME: This needs to be a per-execution seed. This is just a placeholder
-  // implementation. Switching to a per-execution seed is likely to flush out
-  // instability bugs and so will happen as its own commit.
-  //
-  // However, if there is a fixed seed override set the first time this is
-  // called, return that instead of the per-execution seed.
-  const uint64_t seed_prime = 0xff51afd7ed558ccdULL;
-  static uint64_t seed = fixed_seed_override ? fixed_seed_override : seed_prime;
-  return seed;
-}
-
-
-/// Trait to indicate whether a type's bits can be hashed directly.
-///
-/// A type trait which is true if we want to combine values for hashing by
-/// reading the underlying data. It is false if values of this type must
-/// first be passed to hash_value, and the resulting hash_codes combined.
-//
-// FIXME: We want to replace is_integral_or_enum and is_pointer here with
-// a predicate which asserts that comparing the underlying storage of two
-// values of the type for equality is equivalent to comparing the two values
-// for equality. For all the platforms we care about, this holds for integers
-// and pointers, but there are platforms where it doesn't and we would like to
-// support user-defined types which happen to satisfy this property.
-template <typename T> struct is_hashable_data
-  : std::integral_constant<bool, ((is_integral_or_enum<T>::value ||
-                                   std::is_pointer<T>::value) &&
-                                  64 % sizeof(T) == 0)> {};
-
-// Special case std::pair to detect when both types are viable and when there
-// is no alignment-derived padding in the pair. This is a bit of a lie because
-// std::pair isn't truly POD, but it's close enough in all reasonable
-// implementations for our use case of hashing the underlying data.
-template <typename T, typename U> struct is_hashable_data<std::pair<T, U> >
-  : std::integral_constant<bool, (is_hashable_data<T>::value &&
-                                  is_hashable_data<U>::value &&
-                                  (sizeof(T) + sizeof(U)) ==
-                                   sizeof(std::pair<T, U>))> {};
-
-/// Helper to get the hashable data representation for a type.
-/// This variant is enabled when the type itself can be used.
-template <typename T>
-typename std::enable_if<is_hashable_data<T>::value, T>::type
-get_hashable_data(const T &value) {
-  return value;
-}
-/// Helper to get the hashable data representation for a type.
-/// This variant is enabled when we must first call hash_value and use the
-/// result as our data.
-template <typename T>
-typename std::enable_if<!is_hashable_data<T>::value, size_t>::type
-get_hashable_data(const T &value) {
-  using ::wpi::hash_value;
-  return hash_value(value);
-}
-
-/// Helper to store data from a value into a buffer and advance the
-/// pointer into that buffer.
-///
-/// This routine first checks whether there is enough space in the provided
-/// buffer, and if not immediately returns false. If there is space, it
-/// copies the underlying bytes of value into the buffer, advances the
-/// buffer_ptr past the copied bytes, and returns true.
-template <typename T>
-bool store_and_advance(char *&buffer_ptr, char *buffer_end, const T& value,
-                       size_t offset = 0) {
-  size_t store_size = sizeof(value) - offset;
-  if (buffer_ptr + store_size > buffer_end)
-    return false;
-  const char *value_data = reinterpret_cast<const char *>(&value);
-  memcpy(buffer_ptr, value_data + offset, store_size);
-  buffer_ptr += store_size;
-  return true;
-}
-
-/// Implement the combining of integral values into a hash_code.
-///
-/// This overload is selected when the value type of the iterator is
-/// integral. Rather than computing a hash_code for each object and then
-/// combining them, this (as an optimization) directly combines the integers.
-template <typename InputIteratorT>
-hash_code hash_combine_range_impl(InputIteratorT first, InputIteratorT last) {
-  const uint64_t seed = get_execution_seed();
-  char buffer[64], *buffer_ptr = buffer;
-  char *const buffer_end = std::end(buffer);
-  while (first != last && store_and_advance(buffer_ptr, buffer_end,
-                                            get_hashable_data(*first)))
-    ++first;
-  if (first == last)
-    return hash_short(buffer, buffer_ptr - buffer, seed);
-  assert(buffer_ptr == buffer_end);
-
-  hash_state state = state.create(buffer, seed);
-  size_t length = 64;
-  while (first != last) {
-    // Fill up the buffer. We don't clear it, which re-mixes the last round
-    // when only a partial 64-byte chunk is left.
-    buffer_ptr = buffer;
-    while (first != last && store_and_advance(buffer_ptr, buffer_end,
-                                              get_hashable_data(*first)))
-      ++first;
-
-    // Rotate the buffer if we did a partial fill in order to simulate doing
-    // a mix of the last 64-bytes. That is how the algorithm works when we
-    // have a contiguous byte sequence, and we want to emulate that here.
-    std::rotate(buffer, buffer_ptr, buffer_end);
-
-    // Mix this chunk into the current state.
-    state.mix(buffer);
-    length += buffer_ptr - buffer;
-  };
-
-  return state.finalize(length);
-}
-
-/// Implement the combining of integral values into a hash_code.
-///
-/// This overload is selected when the value type of the iterator is integral
-/// and when the input iterator is actually a pointer. Rather than computing
-/// a hash_code for each object and then combining them, this (as an
-/// optimization) directly combines the integers. Also, because the integers
-/// are stored in contiguous memory, this routine avoids copying each value
-/// and directly reads from the underlying memory.
-template <typename ValueT>
-typename std::enable_if<is_hashable_data<ValueT>::value, hash_code>::type
-hash_combine_range_impl(ValueT *first, ValueT *last) {
-  const uint64_t seed = get_execution_seed();
-  const char *s_begin = reinterpret_cast<const char *>(first);
-  const char *s_end = reinterpret_cast<const char *>(last);
-  const size_t length = std::distance(s_begin, s_end);
-  if (length <= 64)
-    return hash_short(s_begin, length, seed);
-
-  const char *s_aligned_end = s_begin + (length & ~63);
-  hash_state state = state.create(s_begin, seed);
-  s_begin += 64;
-  while (s_begin != s_aligned_end) {
-    state.mix(s_begin);
-    s_begin += 64;
-  }
-  if (length & 63)
-    state.mix(s_end - 64);
-
-  return state.finalize(length);
-}
-
-} // namespace detail
-} // namespace hashing
-
-
-/// Compute a hash_code for a sequence of values.
-///
-/// This hashes a sequence of values. It produces the same hash_code as
-/// 'hash_combine(a, b, c, ...)', but can run over arbitrary sized sequences
-/// and is significantly faster given pointers and types which can be hashed as
-/// a sequence of bytes.
-template <typename InputIteratorT>
-hash_code hash_combine_range(InputIteratorT first, InputIteratorT last) {
-  return ::wpi::hashing::detail::hash_combine_range_impl(first, last);
-}
-
-
-// Implementation details for hash_combine.
-namespace hashing {
-namespace detail {
-
-/// Helper class to manage the recursive combining of hash_combine
-/// arguments.
-///
-/// This class exists to manage the state and various calls involved in the
-/// recursive combining of arguments used in hash_combine. It is particularly
-/// useful at minimizing the code in the recursive calls to ease the pain
-/// caused by a lack of variadic functions.
-struct hash_combine_recursive_helper {
-  char buffer[64];
-  hash_state state;
-  const uint64_t seed;
-
-public:
-  /// Construct a recursive hash combining helper.
-  ///
-  /// This sets up the state for a recursive hash combine, including getting
-  /// the seed and buffer setup.
-  hash_combine_recursive_helper()
-    : seed(get_execution_seed()) {}
-
-  /// Combine one chunk of data into the current in-flight hash.
-  ///
-  /// This merges one chunk of data into the hash. First it tries to buffer
-  /// the data. If the buffer is full, it hashes the buffer into its
-  /// hash_state, empties it, and then merges the new chunk in. This also
-  /// handles cases where the data straddles the end of the buffer.
-  template <typename T>
-  char *combine_data(size_t &length, char *buffer_ptr, char *buffer_end, T data) {
-    if (!store_and_advance(buffer_ptr, buffer_end, data)) {
-      // Check for skew which prevents the buffer from being packed, and do
-      // a partial store into the buffer to fill it. This is only a concern
-      // with the variadic combine because that formation can have varying
-      // argument types.
-      size_t partial_store_size = buffer_end - buffer_ptr;
-      memcpy(buffer_ptr, &data, partial_store_size);
-
-      // If the store fails, our buffer is full and ready to hash. We have to
-      // either initialize the hash state (on the first full buffer) or mix
-      // this buffer into the existing hash state. Length tracks the *hashed*
-      // length, not the buffered length.
-      if (length == 0) {
-        state = state.create(buffer, seed);
-        length = 64;
-      } else {
-        // Mix this chunk into the current state and bump length up by 64.
-        state.mix(buffer);
-        length += 64;
-      }
-      // Reset the buffer_ptr to the head of the buffer for the next chunk of
-      // data.
-      buffer_ptr = buffer;
-
-      // Try again to store into the buffer -- this cannot fail as we only
-      // store types smaller than the buffer.
-      if (!store_and_advance(buffer_ptr, buffer_end, data,
-                             partial_store_size))
-        abort();
-    }
-    return buffer_ptr;
-  }
-
-  /// Recursive, variadic combining method.
-  ///
-  /// This function recurses through each argument, combining that argument
-  /// into a single hash.
-  template <typename T, typename ...Ts>
-  hash_code combine(size_t length, char *buffer_ptr, char *buffer_end,
-                    const T &arg, const Ts &...args) {
-    buffer_ptr = combine_data(length, buffer_ptr, buffer_end, get_hashable_data(arg));
-
-    // Recurse to the next argument.
-    return combine(length, buffer_ptr, buffer_end, args...);
-  }
-
-  /// Base case for recursive, variadic combining.
-  ///
-  /// The base case when combining arguments recursively is reached when all
-  /// arguments have been handled. It flushes the remaining buffer and
-  /// constructs a hash_code.
-  hash_code combine(size_t length, char *buffer_ptr, char *buffer_end) {
-    // Check whether the entire set of values fit in the buffer. If so, we'll
-    // use the optimized short hashing routine and skip state entirely.
-    if (length == 0)
-      return static_cast<size_t>(hash_short(buffer, buffer_ptr - buffer, seed));
-
-    // Mix the final buffer, rotating it if we did a partial fill in order to
-    // simulate doing a mix of the last 64-bytes. That is how the algorithm
-    // works when we have a contiguous byte sequence, and we want to emulate
-    // that here.
-    std::rotate(buffer, buffer_ptr, buffer_end);
-
-    // Mix this chunk into the current state.
-    state.mix(buffer);
-    length += buffer_ptr - buffer;
-
-    return static_cast<size_t>(state.finalize(length));
-  }
-};
-
-} // namespace detail
-} // namespace hashing
-
-/// Combine values into a single hash_code.
-///
-/// This routine accepts a varying number of arguments of any type. It will
-/// attempt to combine them into a single hash_code. For user-defined types it
-/// attempts to call a \see hash_value overload (via ADL) for the type. For
-/// integer and pointer types it directly combines their data into the
-/// resulting hash_code.
-///
-/// The result is suitable for returning from a user's hash_value
-/// *implementation* for their user-defined type. Consumers of a type should
-/// *not* call this routine, they should instead call 'hash_value'.
-template <typename ...Ts> hash_code hash_combine(const Ts &...args) {
-  // Recursively hash each argument using a helper class.
-  ::wpi::hashing::detail::hash_combine_recursive_helper helper;
-  return helper.combine(0, helper.buffer, helper.buffer + 64, args...);
-}
-
-// Implementation details for implementations of hash_value overloads provided
-// here.
-namespace hashing {
-namespace detail {
-
-/// Helper to hash the value of a single integer.
-///
-/// Overloads for smaller integer types are not provided to ensure consistent
-/// behavior in the presence of integral promotions. Essentially,
-/// "hash_value('4')" and "hash_value('0' + 4)" should be the same.
-inline hash_code hash_integer_value(uint64_t value) {
-  // Similar to hash_4to8_bytes but using a seed instead of length.
-  const uint64_t seed = get_execution_seed();
-  const char *s = reinterpret_cast<const char *>(&value);
-  const uint64_t a = fetch32(s);
-  return static_cast<size_t>(hash_16_bytes(seed + (a << 3), fetch32(s + 4)));
-}
-
-} // namespace detail
-} // namespace hashing
-
-// Declared and documented above, but defined here so that any of the hashing
-// infrastructure is available.
-template <typename T>
-typename std::enable_if<is_integral_or_enum<T>::value, hash_code>::type
-hash_value(T value) {
-  return ::wpi::hashing::detail::hash_integer_value(
-      static_cast<uint64_t>(value));
-}
-
-// Declared and documented above, but defined here so that any of the hashing
-// infrastructure is available.
-template <typename T> hash_code hash_value(const T *ptr) {
-  return ::wpi::hashing::detail::hash_integer_value(
-    reinterpret_cast<uintptr_t>(ptr));
-}
-
-// Declared and documented above, but defined here so that any of the hashing
-// infrastructure is available.
-template <typename T, typename U>
-hash_code hash_value(const std::pair<T, U> &arg) {
-  return hash_combine(arg.first, arg.second);
-}
-
-// Declared and documented above, but defined here so that any of the hashing
-// infrastructure is available.
-template <typename T>
-hash_code hash_value(const std::basic_string<T> &arg) {
-  return hash_combine_range(arg.begin(), arg.end());
-}
-
-template <typename T>
-hash_code hash_value(const std::basic_string_view<T> &arg) {
-  return hash_combine_range(arg.begin(), arg.end());
-}
-
-} // namespace wpi
-
-#ifdef _WIN32
-#pragma warning(pop)
-#endif
-
-#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/HttpParser.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/HttpParser.h
deleted file mode 100644
index 72e5dad..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/HttpParser.h
+++ /dev/null
@@ -1,227 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_HTTPPARSER_H_
-#define WPIUTIL_WPI_HTTPPARSER_H_
-
-#include <stdint.h>
-
-#include <string_view>
-
-#include "wpi/Signal.h"
-#include "wpi/SmallString.h"
-#include "wpi/http_parser.h"
-
-namespace wpi {
-
-/**
- * HTTP protocol parser.  Performs incremental parsing with callbacks for each
- * part of the HTTP protocol.  As this is incremental, it's suitable for use
- * with event based frameworks that provide arbitrary chunks of data.
- */
-class HttpParser {
- public:
-  enum Type {
-    kRequest = HTTP_REQUEST,
-    kResponse = HTTP_RESPONSE,
-    kBoth = HTTP_BOTH
-  };
-
-  /**
-   * Returns the library version. Bits 16-23 contain the major version number,
-   * bits 8-15 the minor version number and bits 0-7 the patch level.
-   */
-  static uint32_t GetParserVersion();
-
-  /**
-   * Constructor.
-   * @param type Type of parser (request or response or both)
-   */
-  explicit HttpParser(Type type);
-
-  /**
-   * Reset the parser to initial state.
-   * This allows reusing the same parser object from request to request.
-   * @param type Type of parser (request or response or both)
-   */
-  void Reset(Type type);
-
-  /**
-   * Set the maximum accepted length for URLs, field names, and field values.
-   * The default is 1024.
-   * @param len maximum length
-   */
-  void SetMaxLength(size_t len) { m_maxLength = len; }
-
-  /**
-   * Executes the parser.  An empty input is treated as EOF.
-   * @param in input data
-   * @return Trailing input data after the parse.
-   */
-  std::string_view Execute(std::string_view in) {
-    in.remove_prefix(
-        http_parser_execute(&m_parser, &m_settings, in.data(), in.size()));
-    return in;
-  }
-
-  /**
-   * Get HTTP major version.
-   */
-  unsigned int GetMajor() const { return m_parser.http_major; }
-
-  /**
-   * Get HTTP minor version.
-   */
-  unsigned int GetMinor() const { return m_parser.http_minor; }
-
-  /**
-   * Get HTTP status code.  Valid only on responses.  Valid in and after
-   * the OnStatus() callback has been called.
-   */
-  unsigned int GetStatusCode() const { return m_parser.status_code; }
-
-  /**
-   * Get HTTP method.  Valid only on requests.
-   */
-  http_method GetMethod() const {
-    return static_cast<http_method>(m_parser.method);
-  }
-
-  /**
-   * Determine if an error occurred.
-   * @return False if no error.
-   */
-  bool HasError() const { return m_parser.http_errno != HPE_OK; }
-
-  /**
-   * Get error number.
-   */
-  http_errno GetError() const {
-    return static_cast<http_errno>(m_parser.http_errno);
-  }
-
-  /**
-   * Abort the parse.  Call this from a callback handler to indicate an error.
-   * This will result in GetError() returning one of the callback-related
-   * errors (e.g. HPE_CB_message_begin).
-   */
-  void Abort() { m_aborted = true; }
-
-  /**
-   * Determine if an upgrade header was present and the parser has exited
-   * because of that.  Should be checked when Execute() returns in addition to
-   * checking GetError().
-   * @return True if upgrade header, false otherwise.
-   */
-  bool IsUpgrade() const { return m_parser.upgrade; }
-
-  /**
-   * If this returns false in the headersComplete or messageComplete
-   * callback, then this should be the last message on the connection.
-   * If you are the server, respond with the "Connection: close" header.
-   * If you are the client, close the connection.
-   */
-  bool ShouldKeepAlive() const { return http_should_keep_alive(&m_parser); }
-
-  /**
-   * Pause the parser.
-   * @param paused True to pause, false to unpause.
-   */
-  void Pause(bool paused) { http_parser_pause(&m_parser, paused); }
-
-  /**
-   * Checks if this is the final chunk of the body.
-   */
-  bool IsBodyFinal() const { return http_body_is_final(&m_parser); }
-
-  /**
-   * Get URL.  Valid in and after the url callback has been called.
-   */
-  std::string_view GetUrl() const { return m_urlBuf.str(); }
-
-  /**
-   * Message begin callback.
-   */
-  sig::Signal<> messageBegin;
-
-  /**
-   * URL callback.
-   *
-   * The parameter to the callback is the complete URL string.
-   */
-  sig::Signal<std::string_view> url;
-
-  /**
-   * Status callback.
-   *
-   * The parameter to the callback is the complete status string.
-   * GetStatusCode() can be used to get the numeric status code.
-   */
-  sig::Signal<std::string_view> status;
-
-  /**
-   * Header field callback.
-   *
-   * The parameters to the callback are the field name and field value.
-   */
-  sig::Signal<std::string_view, std::string_view> header;
-
-  /**
-   * Headers complete callback.
-   *
-   * The parameter to the callback is whether the connection should be kept
-   * alive.  If this is false, then this should be the last message on the
-   * connection.  If you are the server, respond with the "Connection: close"
-   * header.  If you are the client, close the connection.
-   */
-  sig::Signal<bool> headersComplete;
-
-  /**
-   * Body data callback.
-   *
-   * The parameters to the callback is the data chunk and whether this is the
-   * final chunk of data in the message.  Note this callback will be called
-   * multiple times arbitrarily (e.g. it's possible that it may be called with
-   * just a few characters at a time).
-   */
-  sig::Signal<std::string_view, bool> body;
-
-  /**
-   * Headers complete callback.
-   *
-   * The parameter to the callback is whether the connection should be kept
-   * alive.  If this is false, then this should be the last message on the
-   * connection.  If you are the server, respond with the "Connection: close"
-   * header.  If you are the client, close the connection.
-   */
-  sig::Signal<bool> messageComplete;
-
-  /**
-   * Chunk header callback.
-   *
-   * The parameter to the callback is the chunk size.
-   */
-  sig::Signal<uint64_t> chunkHeader;
-
-  /**
-   * Chunk complete callback.
-   */
-  sig::Signal<> chunkComplete;
-
- private:
-  http_parser m_parser;
-  http_parser_settings m_settings;
-
-  size_t m_maxLength = 1024;
-  enum { kStart, kUrl, kStatus, kField, kValue } m_state = kStart;
-  SmallString<128> m_urlBuf;
-  SmallString<32> m_fieldBuf;
-  SmallString<128> m_valueBuf;
-
-  bool m_aborted = false;
-};
-
-}  // namespace wpi
-
-#endif  // WPIUTIL_WPI_HTTPPARSER_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/HttpServerConnection.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/HttpServerConnection.h
deleted file mode 100644
index a4d4cf8..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/HttpServerConnection.h
+++ /dev/null
@@ -1,152 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_HTTPSERVERCONNECTION_H_
-#define WPIUTIL_WPI_HTTPSERVERCONNECTION_H_
-
-#include <memory>
-#include <string_view>
-
-#include "wpi/HttpParser.h"
-#include "wpi/span.h"
-#include "wpi/uv/Stream.h"
-
-namespace wpi {
-
-class raw_ostream;
-
-class HttpServerConnection {
- public:
-  explicit HttpServerConnection(std::shared_ptr<uv::Stream> stream);
-  virtual ~HttpServerConnection() = default;
-
- protected:
-  /**
-   * Process an incoming HTTP request.  This is called after the incoming
-   * message completes (e.g. from the HttpParser::messageComplete callback).
-   *
-   * The implementation should read request details from m_request and call the
-   * appropriate Send() functions to send a response back to the client.
-   */
-  virtual void ProcessRequest() = 0;
-
-  /**
-   * Build common response headers.
-   *
-   * Called by SendHeader() to send headers common to every response.
-   * Each line must be terminated with "\r\n".
-   *
-   * The default implementation sends the following:
-   * "Server: WebServer/1.0\r\n"
-   * "Cache-Control: no-store, no-cache, must-revalidate, pre-check=0, "
-   * "post-check=0, max-age=0\r\n"
-   * "Pragma: no-cache\r\n"
-   * "Expires: Mon, 3 Jan 2000 12:34:56 GMT\r\n"
-   *
-   * These parameters should ensure the browser does not cache the response.
-   * A browser should connect for each file and not serve files from its cache.
-   *
-   * @param os response stream
-   */
-  virtual void BuildCommonHeaders(raw_ostream& os);
-
-  /**
-   * Build HTTP response header, along with other header information like
-   * mimetype.  Calls BuildCommonHeaders().
-   *
-   * @param os response stream
-   * @param code HTTP response code (e.g. 200)
-   * @param codeText HTTP response code text (e.g. "OK")
-   * @param contentType MIME content type (e.g. "text/plain")
-   * @param contentLength Length of content.  If 0 is provided, m_keepAlive will
-   *                      be set to false.
-   * @param extra Extra HTTP headers to send, including final "\r\n"
-   */
-  virtual void BuildHeader(raw_ostream& os, int code, std::string_view codeText,
-                           std::string_view contentType, uint64_t contentLength,
-                           std::string_view extra = {});
-
-  /**
-   * Send data to client.
-   *
-   * This is a convenience wrapper around m_stream.Write() to provide
-   * auto-close functionality.
-   *
-   * @param bufs Buffers to write.  Deallocate() will be called on each
-   *             buffer after the write completes.  If different behavior
-   *             is desired, call m_stream.Write() directly instead.
-   * @param closeAfter close the connection after the write completes
-   */
-  void SendData(span<const uv::Buffer> bufs, bool closeAfter = false);
-
-  /**
-   * Send HTTP response, along with other header information like mimetype.
-   * Calls BuildHeader().
-   *
-   * @param code HTTP response code (e.g. 200)
-   * @param codeText HTTP response code text (e.g. "OK")
-   * @param contentType MIME content type (e.g. "text/plain")
-   * @param content Response message content
-   * @param extraHeader Extra HTTP headers to send, including final "\r\n"
-   */
-  virtual void SendResponse(int code, std::string_view codeText,
-                            std::string_view contentType,
-                            std::string_view content,
-                            std::string_view extraHeader = {});
-
-  /**
-   * Send HTTP response from static data, along with other header information
-   * like mimetype.  Calls BuildHeader().  Supports gzip pre-compressed data
-   * (it will decompress if the client does not accept gzip encoded data).
-   * Unlike SendResponse(), content is not copied and its contents must remain
-   * valid for an unspecified lifetime.
-   *
-   * @param code HTTP response code (e.g. 200)
-   * @param codeText HTTP response code text (e.g. "OK")
-   * @param contentType MIME content type (e.g. "text/plain")
-   * @param content Response message content
-   * @param gzipped True if content is gzip compressed
-   * @param extraHeader Extra HTTP headers to send, including final "\r\n"
-   */
-  virtual void SendStaticResponse(int code, std::string_view codeText,
-                                  std::string_view contentType,
-                                  std::string_view content, bool gzipped,
-                                  std::string_view extraHeader = {});
-
-  /**
-   * Send error header and message.
-   * This provides standard code responses for 400, 401, 403, 404, 500, and 503.
-   * Other codes will be reported as 501.  For arbitrary code handling, use
-   * SendResponse() instead.
-   *
-   * @param code HTTP error code (e.g. 404)
-   * @param message Additional message text
-   */
-  virtual void SendError(int code, std::string_view message = {});
-
-  /** The HTTP request. */
-  HttpParser m_request{HttpParser::kRequest};
-
-  /** Whether the connection should be kept alive. */
-  bool m_keepAlive = false;
-
-  /** If gzip is an acceptable encoding for responses. */
-  bool m_acceptGzip = false;
-
-  /** The underlying stream for the connection. */
-  uv::Stream& m_stream;
-
-  /** The header reader connection. */
-  sig::ScopedConnection m_dataConn;
-
-  /** The end stream connection. */
-  sig::ScopedConnection m_endConn;
-
-  /** The message complete connection. */
-  sig::Connection m_messageCompleteConn;
-};
-
-}  // namespace wpi
-
-#endif  // WPIUTIL_WPI_HTTPSERVERCONNECTION_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/HttpUtil.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/HttpUtil.h
deleted file mode 100644
index b10d127..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/HttpUtil.h
+++ /dev/null
@@ -1,422 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_HTTPUTIL_H_
-#define WPIUTIL_WPI_HTTPUTIL_H_
-
-#include <initializer_list>
-#include <memory>
-#include <optional>
-#include <string>
-#include <string_view>
-#include <utility>
-#include <vector>
-
-#include "wpi/NetworkStream.h"
-#include "wpi/SmallString.h"
-#include "wpi/SmallVector.h"
-#include "wpi/StringMap.h"
-#include "wpi/raw_istream.h"
-#include "wpi/raw_socket_istream.h"
-#include "wpi/raw_socket_ostream.h"
-#include "wpi/span.h"
-
-namespace wpi {
-
-// Unescape a %xx-encoded URI.
-// @param buf Buffer for output
-// @param error Set to true if an error occurred
-// @return Escaped string
-std::string_view UnescapeURI(std::string_view str, SmallVectorImpl<char>& buf,
-                             bool* error);
-
-// Escape a string with %xx-encoding.
-// @param buf Buffer for output
-// @param spacePlus If true, encodes spaces to '+' rather than "%20"
-// @return Escaped string
-std::string_view EscapeURI(std::string_view str, SmallVectorImpl<char>& buf,
-                           bool spacePlus = true);
-
-// Parse a set of HTTP headers.  Saves just the Content-Type and Content-Length
-// fields.
-// @param is Input stream
-// @param contentType If not null, Content-Type contents are saved here.
-// @param contentLength If not null, Content-Length contents are saved here.
-// @return False if error occurred in input stream
-bool ParseHttpHeaders(raw_istream& is, SmallVectorImpl<char>* contentType,
-                      SmallVectorImpl<char>* contentLength);
-
-// Look for a MIME multi-part boundary.  On return, the input stream will
-// be located at the character following the boundary (usually "\r\n").
-// @param is Input stream
-// @param boundary Boundary string to scan for (not including "--" prefix)
-// @param saveBuf If not null, all scanned characters up to but not including
-//     the boundary are saved to this string
-// @return False if error occurred on input stream, true if boundary found.
-bool FindMultipartBoundary(wpi::raw_istream& is, std::string_view boundary,
-                           std::string* saveBuf);
-
-/**
- * Map for looking up elements of the query portion of a URI.  Does not
- * handle multiple elements with the same name.  This is a reference type;
- * it does not make a copy of the query string, so it is important that the
- * query string has a lifetime at least as long as this object.
- */
-class HttpQueryMap {
- public:
-  /**
-   * Constructs an empty map (with no entries).
-   */
-  HttpQueryMap() = default;
-
-  /**
-   * Constructs from an escaped query string.  Note: does not make a copy of
-   * the query string, so it must not be a temporary.
-   *
-   * @param query query string
-   */
-  explicit HttpQueryMap(std::string_view query);
-
-  /**
-   * Gets an element of the query string.  Both the name and the returned
-   * value are unescaped strings.
-   *
-   * @param name name (unescaped)
-   * @param buf result buffer for value
-   * @return Optional unescaped value.  Returns an empty optional if the
-   *         name is not present in the query map.
-   */
-  std::optional<std::string_view> Get(std::string_view name,
-                                      SmallVectorImpl<char>& buf) const;
-
- private:
-  StringMap<std::string_view> m_elems;
-};
-
-class HttpPathRef;
-
-/**
- * Class for HTTP path matching.  A root path is represented as a single
- * empty element, otherwise the path consists of each non-empty element
- * between the '/' characters:
- *  - "" -> []
- *  - "/" -> [""]
- *  - "/foo" -> ["foo"]
- *  - "/foo/bar" -> ["foo", "bar"]
- *  - "/foo//bar/" -> ["foo", "bar"]
- *
- * All path elements are unescaped.
- */
-class HttpPath {
- public:
-  /**
-   * Constructs an empty HTTP path.
-   */
-  HttpPath() = default;
-
-  /**
-   * Constructs a HTTP path from an escaped path string.  Makes a copy of the
-   * path, so it's safe to be a temporary.
-   */
-  explicit HttpPath(std::string_view path);
-
-  /**
-   * Evaluates to true if the path is not empty.
-   */
-  explicit operator bool() const { return !empty(); }
-
-  /**
-   * Returns true if the path has no elements.
-   */
-  bool empty() const { return m_pathEnds.empty(); }
-
-  /**
-   * Returns number of elements in the path.
-   */
-  size_t size() const { return m_pathEnds.size(); }
-
-  /**
-   * Returns true if the path exactly matches the provided match list.
-   *
-   * @param match match list
-   * @return True if path equals match list
-   */
-  bool equals(std::initializer_list<std::string_view> match) const {
-    return equals(0, {match.begin(), match.end()});
-  }
-  bool equals(span<const std::string_view> match) const {
-    return equals(0, match);
-  }
-  bool equals(std::string_view match) const { return equals(0, {match}); }
-
-  /**
-   * Returns true if the elements of the path starting at the "start" element
-   * match the provided match list, and there are no additional elements.
-   *
-   * @param start element to start matching at
-   * @param match match list
-   * @return True if match
-   */
-  bool equals(size_t start,
-              std::initializer_list<std::string_view> match) const {
-    return equals(start, {match.begin(), match.end()});
-  }
-  bool equals(size_t start, span<const std::string_view> match) const {
-    if (m_pathEnds.size() != (start + match.size())) {
-      return false;
-    }
-    return startswith(start, match);
-  }
-  bool equals(size_t start, std::string_view match) const {
-    return equals(start, {match});
-  }
-
-  /**
-   * Returns true if the first elements of the path match the provided match
-   * list.  The path may have additional elements.
-   *
-   * @param match match list
-   * @return True if path starts with match list
-   */
-  bool startswith(std::initializer_list<std::string_view> match) const {
-    return startswith(0, {match.begin(), match.end()});
-  }
-  bool startswith(span<const std::string_view> match) const {
-    return startswith(0, match);
-  }
-  bool startswith(std::string_view match) const {
-    return startswith(0, {match});
-  }
-
-  /**
-   * Returns true if the elements of the path starting at the "start" element
-   * match the provided match list.  The path may have additional elements.
-   *
-   * @param start element to start matching at
-   * @param match match list
-   * @return True if path starting at the start element matches the match list
-   */
-  bool startswith(size_t start,
-                  std::initializer_list<std::string_view> match) const {
-    return startswith(start, {match.begin(), match.end()});
-  }
-
-  bool startswith(size_t start, span<const std::string_view> match) const;
-
-  bool startswith(size_t start, std::string_view match) const {
-    return startswith(start, {match});
-  }
-
-  /**
-   * Gets a single element of the path.
-   */
-  std::string_view operator[](size_t n) const;
-
-  /**
-   * Returns a path reference with the first N elements of the path removed.
-   */
-  HttpPathRef drop_front(size_t n) const;
-
- private:
-  SmallString<128> m_pathBuf;
-  SmallVector<size_t, 16> m_pathEnds;
-};
-
-/**
- * Proxy reference object for a portion of a HttpPath.
- */
-class HttpPathRef {
- public:
-  HttpPathRef() = default;
-  /*implicit*/ HttpPathRef(const HttpPath& path,  // NOLINT
-                           size_t start = 0)
-      : m_path(&path), m_start(start) {}
-
-  explicit operator bool() const { return !empty(); }
-  bool empty() const { return m_path && m_path->size() == m_start; }
-  size_t size() const { return m_path ? m_path->size() - m_start : 0; }
-
-  bool equals(std::initializer_list<std::string_view> match) const {
-    return equals(0, {match.begin(), match.end()});
-  }
-  bool equals(span<const std::string_view> match) const {
-    return equals(0, match);
-  }
-  bool equals(std::string_view match) const { return equals(0, {match}); }
-
-  bool equals(size_t start,
-              std::initializer_list<std::string_view> match) const {
-    return equals(start, {match.begin(), match.end()});
-  }
-  bool equals(size_t start, span<const std::string_view> match) const {
-    return m_path ? m_path->equals(m_start + start, match) : false;
-  }
-  bool equals(size_t start, std::string_view match) const {
-    return equals(start, {match});
-  }
-
-  bool startswith(std::initializer_list<std::string_view> match) const {
-    return startswith(0, {match.begin(), match.end()});
-  }
-  bool startswith(span<const std::string_view> match) const {
-    return startswith(0, match);
-  }
-  bool startswith(std::string_view match) const {
-    return startswith(0, {match});
-  }
-
-  bool startswith(size_t start,
-                  std::initializer_list<std::string_view> match) const {
-    return startswith(start, {match.begin(), match.end()});
-  }
-  bool startswith(size_t start, span<const std::string_view> match) const {
-    return m_path ? m_path->startswith(m_start + start, match) : false;
-  }
-  bool startswith(size_t start, std::string_view match) const {
-    return startswith(start, {match});
-  }
-
-  std::string_view operator[](size_t n) const {
-    return m_path ? m_path->operator[](m_start + n) : std::string_view{};
-  }
-  HttpPathRef drop_front(size_t n) const {
-    return m_path ? m_path->drop_front(m_start + n) : HttpPathRef{};
-  }
-
- private:
-  const HttpPath* m_path = nullptr;
-  size_t m_start = 0;
-};
-
-class HttpLocation {
- public:
-  HttpLocation() = default;
-  HttpLocation(std::string_view url_, bool* error, std::string* errorMsg);
-
-  std::string url;       // retain copy
-  std::string user;      // unescaped
-  std::string password;  // unescaped
-  std::string host;
-  int port;
-  std::string path;  // escaped, not including leading '/'
-  std::vector<std::pair<std::string, std::string>> params;  // unescaped
-  std::string fragment;
-};
-
-class HttpRequest {
- public:
-  HttpRequest() = default;
-
-  explicit HttpRequest(const HttpLocation& loc)
-      : host{loc.host}, port{loc.port} {
-    SetPath(loc.path, loc.params);
-    SetAuth(loc);
-  }
-
-  template <typename T>
-  HttpRequest(const HttpLocation& loc, const T& extraParams);
-
-  HttpRequest(const HttpLocation& loc, std::string_view path_)
-      : host{loc.host}, port{loc.port}, path{path_} {
-    SetAuth(loc);
-  }
-
-  template <typename T>
-  HttpRequest(const HttpLocation& loc, std::string_view path_, const T& params)
-      : host{loc.host}, port{loc.port} {
-    SetPath(path_, params);
-    SetAuth(loc);
-  }
-
-  SmallString<128> host;
-  int port;
-  std::string auth;
-  SmallString<128> path;
-
- private:
-  void SetAuth(const HttpLocation& loc);
-  template <typename T>
-  void SetPath(std::string_view path_, const T& params);
-
-  template <typename T>
-  static std::string_view GetFirst(const T& elem) {
-    return elem.first;
-  }
-  template <typename T>
-  static std::string_view GetFirst(const StringMapEntry<T>& elem) {
-    return elem.getKey();
-  }
-  template <typename T>
-  static std::string_view GetSecond(const T& elem) {
-    return elem.second;
-  }
-};
-
-class HttpConnection {
- public:
-  HttpConnection(std::unique_ptr<wpi::NetworkStream> stream_, int timeout)
-      : stream{std::move(stream_)}, is{*stream, timeout}, os{*stream, true} {}
-
-  bool Handshake(const HttpRequest& request, std::string* warnMsg);
-
-  std::unique_ptr<wpi::NetworkStream> stream;
-  wpi::raw_socket_istream is;
-  wpi::raw_socket_ostream os;
-
-  // Valid after Handshake() is successful
-  SmallString<64> contentType;
-  SmallString<64> contentLength;
-
-  explicit operator bool() const { return stream && !is.has_error(); }
-};
-
-class HttpMultipartScanner {
- public:
-  explicit HttpMultipartScanner(std::string_view boundary,
-                                bool saveSkipped = false) {
-    Reset(saveSkipped);
-    SetBoundary(boundary);
-  }
-
-  // Change the boundary.  This is only safe to do when IsDone() is true (or
-  // immediately after construction).
-  void SetBoundary(std::string_view boundary);
-
-  // Reset the scanner.  This allows reuse of internal buffers.
-  void Reset(bool saveSkipped = false);
-
-  // Execute the scanner.  Will automatically call Reset() on entry if IsDone()
-  // is true.
-  // @param in input data
-  // @return the input not consumed; empty if all input consumed
-  std::string_view Execute(std::string_view in);
-
-  // Returns true when the boundary has been found.
-  bool IsDone() const { return m_state == kDone; }
-
-  // Get the skipped data.  Will be empty if saveSkipped was false.
-  std::string_view GetSkipped() const {
-    return m_saveSkipped ? std::string_view{m_buf} : std::string_view{};
-  }
-
- private:
-  SmallString<64> m_boundaryWith, m_boundaryWithout;
-
-  // Internal state
-  enum State { kBoundary, kPadding, kDone };
-  State m_state;
-  size_t m_posWith, m_posWithout;
-  enum Dashes { kUnknown, kWith, kWithout };
-  Dashes m_dashes;
-
-  // Buffer
-  bool m_saveSkipped;
-  std::string m_buf;
-};
-
-}  // namespace wpi
-
-#include "HttpUtil.inc"
-
-#endif  // WPIUTIL_WPI_HTTPUTIL_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/HttpUtil.inc b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/HttpUtil.inc
deleted file mode 100644
index 726cdfb..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/HttpUtil.inc
+++ /dev/null
@@ -1,55 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_HTTPUTIL_INC_
-#define WPIUTIL_WPI_HTTPUTIL_INC_
-
-#include <utility>
-
-#include "wpi/HttpUtil.h"
-
-namespace wpi {
-
-inline HttpPathRef HttpPath::drop_front(size_t n) const {
-  return HttpPathRef(*this, n);
-}
-
-template <typename T>
-HttpRequest::HttpRequest(const HttpLocation& loc, const T& extraParams)
-    : host{loc.host}, port{loc.port} {
-  StringMap<std::string_view> params;
-  for (const auto& p : loc.params) {
-    params.insert(std::make_pair(GetFirst(p), GetSecond(p)));
-  }
-  for (const auto& p : extraParams) {
-    params.insert(std::make_pair(GetFirst(p), GetSecond(p)));
-  }
-  SetPath(loc.path, params);
-  SetAuth(loc);
-}
-
-template <typename T>
-void HttpRequest::SetPath(std::string_view path_, const T& params) {
-  // Build location including query string
-  raw_svector_ostream pathOs{path};
-  pathOs << path_;
-  bool first = true;
-  for (const auto& param : params) {
-    if (first) {
-      pathOs << '?';
-      first = false;
-    } else {
-      pathOs << '&';
-    }
-    SmallString<64> escapeBuf;
-    pathOs << EscapeURI(GetFirst(param), escapeBuf, false);
-    if (!GetSecond(param).empty()) {
-      pathOs << '=' << EscapeURI(GetSecond(param), escapeBuf, false);
-    }
-  }
-}
-
-}  // namespace wpi
-
-#endif  // WPIUTIL_WPI_HTTPUTIL_INC_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/HttpWebSocketServerConnection.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/HttpWebSocketServerConnection.h
deleted file mode 100644
index d89b61f..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/HttpWebSocketServerConnection.h
+++ /dev/null
@@ -1,92 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_HTTPWEBSOCKETSERVERCONNECTION_H_
-#define WPIUTIL_WPI_HTTPWEBSOCKETSERVERCONNECTION_H_
-
-#include <initializer_list>
-#include <memory>
-#include <string>
-#include <string_view>
-
-#include "wpi/HttpServerConnection.h"
-#include "wpi/SmallVector.h"
-#include "wpi/WebSocket.h"
-#include "wpi/WebSocketServer.h"
-#include "wpi/span.h"
-#include "wpi/uv/Stream.h"
-
-namespace wpi {
-
-/**
- * A server-side HTTP connection that also accepts WebSocket upgrades.
- *
- * @tparam Derived derived class for std::enable_shared_from_this.
- */
-template <typename Derived>
-class HttpWebSocketServerConnection
-    : public HttpServerConnection,
-      public std::enable_shared_from_this<Derived> {
- public:
-  /**
-   * Constructor.
-   *
-   * @param stream network stream
-   * @param protocols Acceptable subprotocols
-   */
-  HttpWebSocketServerConnection(std::shared_ptr<uv::Stream> stream,
-                                span<const std::string_view> protocols);
-
-  /**
-   * Constructor.
-   *
-   * @param stream network stream
-   * @param protocols Acceptable subprotocols
-   */
-  HttpWebSocketServerConnection(
-      std::shared_ptr<uv::Stream> stream,
-      std::initializer_list<std::string_view> protocols)
-      : HttpWebSocketServerConnection(stream,
-                                      {protocols.begin(), protocols.end()}) {}
-
- protected:
-  /**
-   * Check that an incoming WebSocket upgrade is okay.  This is called prior
-   * to accepting the upgrade (so prior to ProcessWsUpgrade()).
-   *
-   * The implementation should check other headers and return true if the
-   * WebSocket connection should be accepted.
-   *
-   * @param protocol negotiated subprotocol
-   */
-  virtual bool IsValidWsUpgrade(std::string_view protocol) { return true; }
-
-  /**
-   * Process an incoming WebSocket upgrade.  This is called after the header
-   * reader has been disconnected and the websocket has been accepted.
-   *
-   * The implementation should set up appropriate callbacks on the websocket
-   * object to continue communication.
-   *
-   * @note When a WebSocket upgrade occurs, the stream user data is replaced
-   *       with the websocket, and the websocket user data points to "this".
-   *       Replace the websocket user data with caution!
-   */
-  virtual void ProcessWsUpgrade() = 0;
-
-  /**
-   * WebSocket connection; not valid until ProcessWsUpgrade is called.
-   */
-  WebSocket* m_websocket = nullptr;
-
- private:
-  WebSocketServerHelper m_helper;
-  SmallVector<std::string, 2> m_protocols;
-};
-
-}  // namespace wpi
-
-#include "HttpWebSocketServerConnection.inc"
-
-#endif  // WPIUTIL_WPI_HTTPWEBSOCKETSERVERCONNECTION_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/HttpWebSocketServerConnection.inc b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/HttpWebSocketServerConnection.inc
deleted file mode 100644
index 68b9f2d..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/HttpWebSocketServerConnection.inc
+++ /dev/null
@@ -1,56 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_HTTPWEBSOCKETSERVERCONNECTION_INC_
-#define WPIUTIL_WPI_HTTPWEBSOCKETSERVERCONNECTION_INC_
-
-#include <memory>
-
-#include "wpi/HttpWebSocketServerConnection.h"
-
-namespace wpi {
-
-template <typename Derived>
-HttpWebSocketServerConnection<Derived>::HttpWebSocketServerConnection(
-    std::shared_ptr<uv::Stream> stream, span<const std::string_view> protocols)
-    : HttpServerConnection{stream},
-      m_helper{m_request},
-      m_protocols{protocols.begin(), protocols.end()} {
-  // Handle upgrade event
-  m_helper.upgrade.connect([this] {
-    // Negotiate sub-protocol
-    SmallVector<std::string_view, 2> protocols{m_protocols.begin(),
-                                               m_protocols.end()};
-    std::string_view protocol = m_helper.MatchProtocol(protocols).second;
-
-    // Check that the upgrade is valid
-    if (!IsValidWsUpgrade(protocol)) {
-      return;
-    }
-
-    // Disconnect HttpServerConnection header reader
-    m_dataConn.disconnect();
-    m_messageCompleteConn.disconnect();
-
-    // Accepting the stream may destroy this (as it replaces the stream user
-    // data), so grab a shared pointer first.
-    auto self = this->shared_from_this();
-
-    // Accept the upgrade
-    auto ws = m_helper.Accept(m_stream, protocol);
-
-    // Set this as the websocket user data to keep it around
-    ws->SetData(self);
-
-    // Store in member
-    m_websocket = ws.get();
-
-    // Call derived class function
-    ProcessWsUpgrade();
-  });
-}
-
-}  // namespace wpi
-
-#endif  // WPIUTIL_WPI_HTTPWEBSOCKETSERVERCONNECTION_INC_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/Logger.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/Logger.h
index 807e472..883336f 100644
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/Logger.h
+++ b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/Logger.h
@@ -45,12 +45,11 @@
   void LogV(unsigned int level, const char* file, unsigned int line,
             fmt::string_view format, fmt::format_args args);
 
-  template <typename S, typename... Args>
+  template <typename... Args>
   void Log(unsigned int level, const char* file, unsigned int line,
-           const S& format, Args&&... args) {
+           fmt::string_view format, Args&&... args) {
     if (m_func && level >= m_min_level) {
-      LogV(level, file, line, format,
-           fmt::make_args_checked<Args...>(format, args...));
+      LogV(level, file, line, format, fmt::make_format_args(args...));
     }
   }
 
@@ -61,15 +60,25 @@
   unsigned int m_min_level = 20;
 };
 
-#define WPI_LOG(logger_inst, level, format, ...) \
-  logger_inst.Log(level, __FILE__, __LINE__, FMT_STRING(format), __VA_ARGS__)
+// C++20 relaxed the number of arguments to variadics, but Apple Clang's
+// warnings haven't caught up yet: https://stackoverflow.com/a/67996331
+#ifdef __clang__
+#pragma clang diagnostic ignored "-Wgnu-zero-variadic-macro-arguments"
+#endif
+
+#define WPI_LOG(logger_inst, level, format, ...)                         \
+  if ((logger_inst).HasLogger() && level >= (logger_inst).min_level()) { \
+    (logger_inst)                                                        \
+        .Log(level, __FILE__, __LINE__,                                  \
+             FMT_STRING(format) __VA_OPT__(, ) __VA_ARGS__);             \
+  }
 
 #define WPI_ERROR(inst, format, ...) \
-  WPI_LOG(inst, ::wpi::WPI_LOG_ERROR, format, __VA_ARGS__)
+  WPI_LOG(inst, ::wpi::WPI_LOG_ERROR, format __VA_OPT__(, ) __VA_ARGS__)
 #define WPI_WARNING(inst, format, ...) \
-  WPI_LOG(inst, ::wpi::WPI_LOG_WARNING, format, __VA_ARGS__)
+  WPI_LOG(inst, ::wpi::WPI_LOG_WARNING, format __VA_OPT__(, ) __VA_ARGS__)
 #define WPI_INFO(inst, format, ...) \
-  WPI_LOG(inst, ::wpi::WPI_LOG_INFO, format, __VA_ARGS__)
+  WPI_LOG(inst, ::wpi::WPI_LOG_INFO, format __VA_OPT__(, ) __VA_ARGS__)
 
 #ifdef NDEBUG
 #define WPI_DEBUG(inst, format, ...) \
@@ -89,15 +98,15 @@
   } while (0)
 #else
 #define WPI_DEBUG(inst, format, ...) \
-  WPI_LOG(inst, ::wpi::WPI_LOG_DEBUG, format, __VA_ARGS__)
+  WPI_LOG(inst, ::wpi::WPI_LOG_DEBUG, format __VA_OPT__(, ) __VA_ARGS__)
 #define WPI_DEBUG1(inst, format, ...) \
-  WPI_LOG(inst, ::wpi::WPI_LOG_DEBUG1, format, __VA_ARGS__)
+  WPI_LOG(inst, ::wpi::WPI_LOG_DEBUG1, format __VA_OPT__(, ) __VA_ARGS__)
 #define WPI_DEBUG2(inst, format, ...) \
-  WPI_LOG(inst, ::wpi::WPI_LOG_DEBUG2, format, __VA_ARGS__)
+  WPI_LOG(inst, ::wpi::WPI_LOG_DEBUG2, format __VA_OPT__(, ) __VA_ARGS__)
 #define WPI_DEBUG3(inst, format, ...) \
-  WPI_LOG(inst, ::wpi::WPI_LOG_DEBUG3, format, __VA_ARGS__)
+  WPI_LOG(inst, ::wpi::WPI_LOG_DEBUG3, format __VA_OPT__(, ) __VA_ARGS__)
 #define WPI_DEBUG4(inst, format, ...) \
-  WPI_LOG(inst, ::wpi::WPI_LOG_DEBUG4, format, __VA_ARGS__)
+  WPI_LOG(inst, ::wpi::WPI_LOG_DEBUG4, format __VA_OPT__(, ) __VA_ARGS__)
 #endif
 
 }  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/ManagedStatic.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/ManagedStatic.h
deleted file mode 100644
index 28c11fa..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/ManagedStatic.h
+++ /dev/null
@@ -1,104 +0,0 @@
-//===-- llvm/Support/ManagedStatic.h - Static Global wrapper ----*- C++ -*-===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-//
-// This file defines the ManagedStatic class and the wpi_shutdown() function.
-//
-//===----------------------------------------------------------------------===//
-
-#ifndef WPIUTIL_WPI_MANAGEDSTATIC_H
-#define WPIUTIL_WPI_MANAGEDSTATIC_H
-
-#include <atomic>
-#include <cstddef>
-
-namespace wpi {
-
-/// object_creator - Helper method for ManagedStatic.
-template <class C> struct object_creator {
-  static void *call() { return new C(); }
-};
-
-/// object_deleter - Helper method for ManagedStatic.
-///
-template <typename T> struct object_deleter {
-  static void call(void *Ptr) { delete (T *)Ptr; }
-};
-template <typename T, size_t N> struct object_deleter<T[N]> {
-  static void call(void *Ptr) { delete[](T *)Ptr; }
-};
-
-/// ManagedStaticBase - Common base class for ManagedStatic instances.
-class ManagedStaticBase {
-protected:
-  // This should only be used as a static variable, which guarantees that this
-  // will be zero initialized.
-  mutable std::atomic<void *> Ptr;
-  mutable void (*DeleterFn)(void*);
-  mutable const ManagedStaticBase *Next;
-
-  void RegisterManagedStatic(void *(*creator)(), void (*deleter)(void*)) const;
-  void RegisterManagedStatic(void *created, void (*deleter)(void*)) const;
-
-public:
-  /// isConstructed - Return true if this object has not been created yet.
-  bool isConstructed() const { return Ptr != nullptr; }
-
-  void destroy() const;
-};
-
-/// ManagedStatic - This transparently changes the behavior of global statics to
-/// be lazily constructed on demand (good for reducing startup times of dynamic
-/// libraries that link in LLVM components) and for making destruction be
-/// explicit through the wpi_shutdown() function call.
-///
-template <class C, class Creator = object_creator<C>,
-          class Deleter = object_deleter<C>>
-class ManagedStatic : public ManagedStaticBase {
-public:
-  ManagedStatic() = default;
-
-  ManagedStatic(C* created, void(*deleter)(void*)) {
-    RegisterManagedStatic(created, deleter);
-  }
-
-  // Accessors.
-  C &operator*() {
-    void *Tmp = Ptr.load(std::memory_order_acquire);
-    if (!Tmp)
-      RegisterManagedStatic(Creator::call, Deleter::call);
-
-    return *static_cast<C *>(Ptr.load(std::memory_order_relaxed));
-  }
-
-  C *operator->() { return &**this; }
-
-  const C &operator*() const {
-    void *Tmp = Ptr.load(std::memory_order_acquire);
-    if (!Tmp)
-      RegisterManagedStatic(Creator::call, Deleter::call);
-
-    return *static_cast<C *>(Ptr.load(std::memory_order_relaxed));
-  }
-
-  const C *operator->() const { return &**this; }
-};
-
-/// wpi_shutdown - Deallocate and destroy all ManagedStatic variables.
-void wpi_shutdown();
-
-/// wpi_shutdown_obj - This is a simple helper class that calls
-/// wpi_shutdown() when it is destroyed.
-struct wpi_shutdown_obj {
-  wpi_shutdown_obj() = default;
-  ~wpi_shutdown_obj() { wpi_shutdown(); }
-};
-
-} // end namespace wpi
-
-#endif // WPIUTIL_WPI_MANAGEDSTATIC_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/MapVector.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/MapVector.h
deleted file mode 100644
index 34e0267..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/MapVector.h
+++ /dev/null
@@ -1,240 +0,0 @@
-//===- llvm/ADT/MapVector.h - Map w/ deterministic value order --*- C++ -*-===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-//
-// This file implements a map that provides insertion order iteration. The
-// interface is purposefully minimal. The key is assumed to be cheap to copy
-// and 2 copies are kept, one for indexing in a DenseMap, one for iteration in
-// a std::vector.
-//
-//===----------------------------------------------------------------------===//
-
-#ifndef WPIUTIL_WPI_MAPVECTOR_H
-#define WPIUTIL_WPI_MAPVECTOR_H
-
-#include "wpi/DenseMap.h"
-#include "wpi/SmallVector.h"
-#include <algorithm>
-#include <cassert>
-#include <cstddef>
-#include <iterator>
-#include <type_traits>
-#include <utility>
-#include <vector>
-
-namespace wpi {
-
-/// This class implements a map that also provides access to all stored values
-/// in a deterministic order. The values are kept in a std::vector and the
-/// mapping is done with DenseMap from Keys to indexes in that vector.
-template<typename KeyT, typename ValueT,
-         typename MapType = DenseMap<KeyT, unsigned>,
-         typename VectorType = std::vector<std::pair<KeyT, ValueT>>>
-class MapVector {
-  MapType Map;
-  VectorType Vector;
-
-  static_assert(
-      std::is_integral<typename MapType::mapped_type>::value,
-      "The mapped_type of the specified Map must be an integral type");
-
-public:
-  using value_type = typename VectorType::value_type;
-  using size_type = typename VectorType::size_type;
-
-  using iterator = typename VectorType::iterator;
-  using const_iterator = typename VectorType::const_iterator;
-  using reverse_iterator = typename VectorType::reverse_iterator;
-  using const_reverse_iterator = typename VectorType::const_reverse_iterator;
-
-  /// Clear the MapVector and return the underlying vector.
-  VectorType takeVector() {
-    Map.clear();
-    return std::move(Vector);
-  }
-
-  size_type size() const { return Vector.size(); }
-
-  /// Grow the MapVector so that it can contain at least \p NumEntries items
-  /// before resizing again.
-  void reserve(size_type NumEntries) {
-    Map.reserve(NumEntries);
-    Vector.reserve(NumEntries);
-  }
-
-  iterator begin() { return Vector.begin(); }
-  const_iterator begin() const { return Vector.begin(); }
-  iterator end() { return Vector.end(); }
-  const_iterator end() const { return Vector.end(); }
-
-  reverse_iterator rbegin() { return Vector.rbegin(); }
-  const_reverse_iterator rbegin() const { return Vector.rbegin(); }
-  reverse_iterator rend() { return Vector.rend(); }
-  const_reverse_iterator rend() const { return Vector.rend(); }
-
-  bool empty() const {
-    return Vector.empty();
-  }
-
-  std::pair<KeyT, ValueT>       &front()       { return Vector.front(); }
-  const std::pair<KeyT, ValueT> &front() const { return Vector.front(); }
-  std::pair<KeyT, ValueT>       &back()        { return Vector.back(); }
-  const std::pair<KeyT, ValueT> &back()  const { return Vector.back(); }
-
-  void clear() {
-    Map.clear();
-    Vector.clear();
-  }
-
-  void swap(MapVector &RHS) {
-    std::swap(Map, RHS.Map);
-    std::swap(Vector, RHS.Vector);
-  }
-
-  ValueT &operator[](const KeyT &Key) {
-    std::pair<KeyT, typename MapType::mapped_type> Pair = std::make_pair(Key, 0);
-    std::pair<typename MapType::iterator, bool> Result = Map.insert(Pair);
-    auto &I = Result.first->second;
-    if (Result.second) {
-      Vector.push_back(std::make_pair(Key, ValueT()));
-      I = Vector.size() - 1;
-    }
-    return Vector[I].second;
-  }
-
-  // Returns a copy of the value.  Only allowed if ValueT is copyable.
-  ValueT lookup(const KeyT &Key) const {
-    static_assert(std::is_copy_constructible<ValueT>::value,
-                  "Cannot call lookup() if ValueT is not copyable.");
-    typename MapType::const_iterator Pos = Map.find(Key);
-    return Pos == Map.end()? ValueT() : Vector[Pos->second].second;
-  }
-
-  std::pair<iterator, bool> insert(const std::pair<KeyT, ValueT> &KV) {
-    std::pair<KeyT, typename MapType::mapped_type> Pair = std::make_pair(KV.first, 0);
-    std::pair<typename MapType::iterator, bool> Result = Map.insert(Pair);
-    auto &I = Result.first->second;
-    if (Result.second) {
-      Vector.push_back(std::make_pair(KV.first, KV.second));
-      I = Vector.size() - 1;
-      return std::make_pair(std::prev(end()), true);
-    }
-    return std::make_pair(begin() + I, false);
-  }
-
-  std::pair<iterator, bool> insert(std::pair<KeyT, ValueT> &&KV) {
-    // Copy KV.first into the map, then move it into the vector.
-    std::pair<KeyT, typename MapType::mapped_type> Pair = std::make_pair(KV.first, 0);
-    std::pair<typename MapType::iterator, bool> Result = Map.insert(Pair);
-    auto &I = Result.first->second;
-    if (Result.second) {
-      Vector.push_back(std::move(KV));
-      I = Vector.size() - 1;
-      return std::make_pair(std::prev(end()), true);
-    }
-    return std::make_pair(begin() + I, false);
-  }
-
-  size_type count(const KeyT &Key) const {
-    typename MapType::const_iterator Pos = Map.find(Key);
-    return Pos == Map.end()? 0 : 1;
-  }
-
-  iterator find(const KeyT &Key) {
-    typename MapType::const_iterator Pos = Map.find(Key);
-    return Pos == Map.end()? Vector.end() :
-                            (Vector.begin() + Pos->second);
-  }
-
-  const_iterator find(const KeyT &Key) const {
-    typename MapType::const_iterator Pos = Map.find(Key);
-    return Pos == Map.end()? Vector.end() :
-                            (Vector.begin() + Pos->second);
-  }
-
-  /// Remove the last element from the vector.
-  void pop_back() {
-    typename MapType::iterator Pos = Map.find(Vector.back().first);
-    Map.erase(Pos);
-    Vector.pop_back();
-  }
-
-  /// Remove the element given by Iterator.
-  ///
-  /// Returns an iterator to the element following the one which was removed,
-  /// which may be end().
-  ///
-  /// \note This is a deceivingly expensive operation (linear time).  It's
-  /// usually better to use \a remove_if() if possible.
-  typename VectorType::iterator erase(typename VectorType::iterator Iterator) {
-    Map.erase(Iterator->first);
-    auto Next = Vector.erase(Iterator);
-    if (Next == Vector.end())
-      return Next;
-
-    // Update indices in the map.
-    size_t Index = Next - Vector.begin();
-    for (auto &I : Map) {
-      assert(I.second != Index && "Index was already erased!");
-      if (I.second > Index)
-        --I.second;
-    }
-    return Next;
-  }
-
-  /// Remove all elements with the key value Key.
-  ///
-  /// Returns the number of elements removed.
-  size_type erase(const KeyT &Key) {
-    auto Iterator = find(Key);
-    if (Iterator == end())
-      return 0;
-    erase(Iterator);
-    return 1;
-  }
-
-  /// Remove the elements that match the predicate.
-  ///
-  /// Erase all elements that match \c Pred in a single pass.  Takes linear
-  /// time.
-  template <class Predicate> void remove_if(Predicate Pred);
-};
-
-template <typename KeyT, typename ValueT, typename MapType, typename VectorType>
-template <class Function>
-void MapVector<KeyT, ValueT, MapType, VectorType>::remove_if(Function Pred) {
-  auto O = Vector.begin();
-  for (auto I = O, E = Vector.end(); I != E; ++I) {
-    if (Pred(*I)) {
-      // Erase from the map.
-      Map.erase(I->first);
-      continue;
-    }
-
-    if (I != O) {
-      // Move the value and update the index in the map.
-      *O = std::move(*I);
-      Map[O->first] = O - Vector.begin();
-    }
-    ++O;
-  }
-  // Erase trailing entries in the vector.
-  Vector.erase(O, Vector.end());
-}
-
-/// A MapVector that performs no allocations if smaller than a certain
-/// size.
-template <typename KeyT, typename ValueT, unsigned N>
-struct SmallMapVector
-    : MapVector<KeyT, ValueT, SmallDenseMap<KeyT, unsigned, N>,
-                SmallVector<std::pair<KeyT, ValueT>, N>> {
-};
-
-} // end namespace wpi
-
-#endif // LLVM_ADT_MAPVECTOR_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/MappedFileRegion.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/MappedFileRegion.h
new file mode 100644
index 0000000..05e487e
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/MappedFileRegion.h
@@ -0,0 +1,92 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <stdint.h>
+
+#include <system_error>
+
+// Duplicated from fs.h to avoid a dependency
+namespace fs {
+#if defined(_WIN32)
+// A Win32 HANDLE is a typedef of void*
+using file_t = void*;
+#else
+using file_t = int;
+#endif
+}  // namespace fs
+
+namespace wpi {
+
+class MappedFileRegion {
+ public:
+  enum MapMode {
+    kReadOnly,   ///< May only access map via const_data as read only.
+    kReadWrite,  ///< May access map via data and modify it. Written to path.
+    kPriv        ///< May modify via data, but changes are lost on destruction.
+  };
+
+  MappedFileRegion() = default;
+  MappedFileRegion(fs::file_t f, uint64_t length, uint64_t offset,
+                   MapMode mapMode, std::error_code& ec);
+  ~MappedFileRegion() { Unmap(); }
+
+  MappedFileRegion(const MappedFileRegion&) = delete;
+  MappedFileRegion& operator=(const MappedFileRegion&) = delete;
+
+  MappedFileRegion(MappedFileRegion&& rhs)
+      : m_size(rhs.m_size), m_mapping(rhs.m_mapping) {
+    rhs.m_mapping = nullptr;
+#ifdef _WIN32
+    m_fileHandle = rhs.m_fileHandle;
+    rhs.m_fileHandle = nullptr;
+#endif
+  }
+
+  MappedFileRegion& operator=(MappedFileRegion&& rhs) {
+    if (m_mapping) {
+      Unmap();
+    }
+    m_size = rhs.m_size;
+    m_mapping = rhs.m_mapping;
+    rhs.m_mapping = nullptr;
+#ifdef _WIN32
+    m_fileHandle = rhs.m_fileHandle;
+    rhs.m_fileHandle = nullptr;
+#endif
+    return *this;
+  }
+
+  explicit operator bool() const {
+    return m_mapping != nullptr;
+  }
+
+  void Flush();
+  void Unmap();
+
+  uint64_t size() const {
+    return m_size;
+  }
+  uint8_t* data() const {
+    return static_cast<uint8_t*>(m_mapping);
+  }
+  const uint8_t* const_data() const {
+    return static_cast<const uint8_t*>(m_mapping);
+  }
+
+  /**
+   * Returns required alignment.
+   */
+  static size_t GetAlignment();
+
+ private:
+  uint64_t m_size = 0;
+  void* m_mapping = nullptr;
+#ifdef _WIN32
+  fs::file_t m_fileHandle = nullptr;
+#endif
+};
+
+}  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/MathExtras.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/MathExtras.h
deleted file mode 100644
index ac88cb9..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/MathExtras.h
+++ /dev/null
@@ -1,864 +0,0 @@
-//===-- llvm/Support/MathExtras.h - Useful math functions -------*- C++ -*-===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-//
-// This file contains some functions that are useful for math stuff.
-//
-//===----------------------------------------------------------------------===//
-
-#ifndef WPIUTIL_WPI_MATHEXTRAS_H
-#define WPIUTIL_WPI_MATHEXTRAS_H
-
-#include "wpi/Compiler.h"
-#include <cstdint>
-#include <algorithm>
-#include <cassert>
-#include <climits>
-#include <cmath>
-#include <cstring>
-#include <limits>
-#include <type_traits>
-
-#ifdef _MSC_VER
-// Declare these intrinsics manually rather including intrin.h. It's very
-// expensive, and MathExtras.h is popular.
-// #include <intrin.h>
-extern "C" {
-unsigned char _BitScanForward(unsigned long *_Index, unsigned long _Mask);
-unsigned char _BitScanForward64(unsigned long *_Index, unsigned __int64 _Mask);
-unsigned char _BitScanReverse(unsigned long *_Index, unsigned long _Mask);
-unsigned char _BitScanReverse64(unsigned long *_Index, unsigned __int64 _Mask);
-}
-#endif
-
-namespace wpi {
-/// The behavior an operation has on an input of 0.
-enum ZeroBehavior {
-  /// The returned value is undefined.
-  ZB_Undefined,
-  /// The returned value is numeric_limits<T>::max()
-  ZB_Max,
-  /// The returned value is numeric_limits<T>::digits
-  ZB_Width
-};
-
-namespace detail {
-template <typename T, std::size_t SizeOfT> struct TrailingZerosCounter {
-  static std::size_t count(T Val, ZeroBehavior) {
-    if (!Val)
-      return std::numeric_limits<T>::digits;
-    if (Val & 0x1)
-      return 0;
-
-    // Bisection method.
-    std::size_t ZeroBits = 0;
-    T Shift = std::numeric_limits<T>::digits >> 1;
-    T Mask = (std::numeric_limits<T>::max)() >> Shift;
-    while (Shift) {
-      if ((Val & Mask) == 0) {
-        Val >>= Shift;
-        ZeroBits |= Shift;
-      }
-      Shift >>= 1;
-      Mask >>= Shift;
-    }
-    return ZeroBits;
-  }
-};
-
-#if __GNUC__ >= 4 || defined(_MSC_VER)
-template <typename T> struct TrailingZerosCounter<T, 4> {
-  static std::size_t count(T Val, ZeroBehavior ZB) {
-    if (ZB != ZB_Undefined && Val == 0)
-      return 32;
-
-#if __has_builtin(__builtin_ctz) || LLVM_GNUC_PREREQ(4, 0, 0)
-    return __builtin_ctz(Val);
-#elif defined(_MSC_VER)
-    unsigned long Index;
-    _BitScanForward(&Index, Val);
-    return Index;
-#endif
-  }
-};
-
-#if !defined(_MSC_VER) || defined(_M_X64)
-template <typename T> struct TrailingZerosCounter<T, 8> {
-  static std::size_t count(T Val, ZeroBehavior ZB) {
-    if (ZB != ZB_Undefined && Val == 0)
-      return 64;
-
-#if __has_builtin(__builtin_ctzll) || LLVM_GNUC_PREREQ(4, 0, 0)
-    return __builtin_ctzll(Val);
-#elif defined(_MSC_VER)
-    unsigned long Index;
-    _BitScanForward64(&Index, Val);
-    return Index;
-#endif
-  }
-};
-#endif
-#endif
-} // namespace detail
-
-/// Count number of 0's from the least significant bit to the most
-///   stopping at the first 1.
-///
-/// Only unsigned integral types are allowed.
-///
-/// \param ZB the behavior on an input of 0. Only ZB_Width and ZB_Undefined are
-///   valid arguments.
-template <typename T>
-std::size_t countTrailingZeros(T Val, ZeroBehavior ZB = ZB_Width) {
-  static_assert(std::numeric_limits<T>::is_integer &&
-                    !std::numeric_limits<T>::is_signed,
-                "Only unsigned integral types are allowed.");
-  return wpi::detail::TrailingZerosCounter<T, sizeof(T)>::count(Val, ZB);
-}
-
-namespace detail {
-template <typename T, std::size_t SizeOfT> struct LeadingZerosCounter {
-  static std::size_t count(T Val, ZeroBehavior) {
-    if (!Val)
-      return std::numeric_limits<T>::digits;
-
-    // Bisection method.
-    std::size_t ZeroBits = 0;
-    for (T Shift = std::numeric_limits<T>::digits >> 1; Shift; Shift >>= 1) {
-      T Tmp = Val >> Shift;
-      if (Tmp)
-        Val = Tmp;
-      else
-        ZeroBits |= Shift;
-    }
-    return ZeroBits;
-  }
-};
-
-#if __GNUC__ >= 4 || defined(_MSC_VER)
-template <typename T> struct LeadingZerosCounter<T, 4> {
-  static std::size_t count(T Val, ZeroBehavior ZB) {
-    if (ZB != ZB_Undefined && Val == 0)
-      return 32;
-
-#if __has_builtin(__builtin_clz) || LLVM_GNUC_PREREQ(4, 0, 0)
-    return __builtin_clz(Val);
-#elif defined(_MSC_VER)
-    unsigned long Index;
-    _BitScanReverse(&Index, Val);
-    return Index ^ 31;
-#endif
-  }
-};
-
-#if !defined(_MSC_VER) || defined(_M_X64)
-template <typename T> struct LeadingZerosCounter<T, 8> {
-  static std::size_t count(T Val, ZeroBehavior ZB) {
-    if (ZB != ZB_Undefined && Val == 0)
-      return 64;
-
-#if __has_builtin(__builtin_clzll) || LLVM_GNUC_PREREQ(4, 0, 0)
-    return __builtin_clzll(Val);
-#elif defined(_MSC_VER)
-    unsigned long Index;
-    _BitScanReverse64(&Index, Val);
-    return Index ^ 63;
-#endif
-  }
-};
-#endif
-#endif
-} // namespace detail
-
-/// Count number of 0's from the most significant bit to the least
-///   stopping at the first 1.
-///
-/// Only unsigned integral types are allowed.
-///
-/// \param ZB the behavior on an input of 0. Only ZB_Width and ZB_Undefined are
-///   valid arguments.
-template <typename T>
-std::size_t countLeadingZeros(T Val, ZeroBehavior ZB = ZB_Width) {
-  static_assert(std::numeric_limits<T>::is_integer &&
-                    !std::numeric_limits<T>::is_signed,
-                "Only unsigned integral types are allowed.");
-  return wpi::detail::LeadingZerosCounter<T, sizeof(T)>::count(Val, ZB);
-}
-
-/// Get the index of the first set bit starting from the least
-///   significant bit.
-///
-/// Only unsigned integral types are allowed.
-///
-/// \param ZB the behavior on an input of 0. Only ZB_Max and ZB_Undefined are
-///   valid arguments.
-template <typename T> T findFirstSet(T Val, ZeroBehavior ZB = ZB_Max) {
-  if (ZB == ZB_Max && Val == 0)
-    return (std::numeric_limits<T>::max)();
-
-  return countTrailingZeros(Val, ZB_Undefined);
-}
-
-/// Create a bitmask with the N right-most bits set to 1, and all other
-/// bits set to 0.  Only unsigned types are allowed.
-template <typename T> T maskTrailingOnes(unsigned N) {
-  static_assert(std::is_unsigned<T>::value, "Invalid type!");
-  const unsigned Bits = CHAR_BIT * sizeof(T);
-  assert(N <= Bits && "Invalid bit index");
-  return N == 0 ? 0 : (T(-1) >> (Bits - N));
-}
-
-/// Create a bitmask with the N left-most bits set to 1, and all other
-/// bits set to 0.  Only unsigned types are allowed.
-template <typename T> T maskLeadingOnes(unsigned N) {
-  return ~maskTrailingOnes<T>(CHAR_BIT * sizeof(T) - N);
-}
-
-/// Create a bitmask with the N right-most bits set to 0, and all other
-/// bits set to 1.  Only unsigned types are allowed.
-template <typename T> T maskTrailingZeros(unsigned N) {
-  return maskLeadingOnes<T>(CHAR_BIT * sizeof(T) - N);
-}
-
-/// Create a bitmask with the N left-most bits set to 0, and all other
-/// bits set to 1.  Only unsigned types are allowed.
-template <typename T> T maskLeadingZeros(unsigned N) {
-  return maskTrailingOnes<T>(CHAR_BIT * sizeof(T) - N);
-}
-
-/// Get the index of the last set bit starting from the least
-///   significant bit.
-///
-/// Only unsigned integral types are allowed.
-///
-/// \param ZB the behavior on an input of 0. Only ZB_Max and ZB_Undefined are
-///   valid arguments.
-template <typename T> T findLastSet(T Val, ZeroBehavior ZB = ZB_Max) {
-  if (ZB == ZB_Max && Val == 0)
-    return (std::numeric_limits<T>::max)();
-
-  // Use ^ instead of - because both gcc and llvm can remove the associated ^
-  // in the __builtin_clz intrinsic on x86.
-  return countLeadingZeros(Val, ZB_Undefined) ^
-         (std::numeric_limits<T>::digits - 1);
-}
-
-/// Macro compressed bit reversal table for 256 bits.
-///
-/// http://graphics.stanford.edu/~seander/bithacks.html#BitReverseTable
-static const unsigned char BitReverseTable256[256] = {
-#define R2(n) n, n + 2 * 64, n + 1 * 64, n + 3 * 64
-#define R4(n) R2(n), R2(n + 2 * 16), R2(n + 1 * 16), R2(n + 3 * 16)
-#define R6(n) R4(n), R4(n + 2 * 4), R4(n + 1 * 4), R4(n + 3 * 4)
-  R6(0), R6(2), R6(1), R6(3)
-#undef R2
-#undef R4
-#undef R6
-};
-
-/// Reverse the bits in \p Val.
-template <typename T>
-T reverseBits(T Val) {
-  unsigned char in[sizeof(Val)];
-  unsigned char out[sizeof(Val)];
-  std::memcpy(in, &Val, sizeof(Val));
-  for (unsigned i = 0; i < sizeof(Val); ++i)
-    out[(sizeof(Val) - i) - 1] = BitReverseTable256[in[i]];
-  std::memcpy(&Val, out, sizeof(Val));
-  return Val;
-}
-
-// NOTE: The following support functions use the _32/_64 extensions instead of
-// type overloading so that signed and unsigned integers can be used without
-// ambiguity.
-
-/// Return the high 32 bits of a 64 bit value.
-constexpr inline uint32_t Hi_32(uint64_t Value) {
-  return static_cast<uint32_t>(Value >> 32);
-}
-
-/// Return the low 32 bits of a 64 bit value.
-constexpr inline uint32_t Lo_32(uint64_t Value) {
-  return static_cast<uint32_t>(Value);
-}
-
-/// Make a 64-bit integer from a high / low pair of 32-bit integers.
-constexpr inline uint64_t Make_64(uint32_t High, uint32_t Low) {
-  return ((uint64_t)High << 32) | (uint64_t)Low;
-}
-
-/// Checks if an integer fits into the given bit width.
-template <unsigned N> constexpr inline bool isInt(int64_t x) {
-  return N >= 64 || (-(INT64_C(1)<<(N-1)) <= x && x < (INT64_C(1)<<(N-1)));
-}
-// Template specializations to get better code for common cases.
-template <> constexpr inline bool isInt<8>(int64_t x) {
-  return static_cast<int8_t>(x) == x;
-}
-template <> constexpr inline bool isInt<16>(int64_t x) {
-  return static_cast<int16_t>(x) == x;
-}
-template <> constexpr inline bool isInt<32>(int64_t x) {
-  return static_cast<int32_t>(x) == x;
-}
-
-/// Checks if a signed integer is an N bit number shifted left by S.
-template <unsigned N, unsigned S>
-constexpr inline bool isShiftedInt(int64_t x) {
-  static_assert(
-      N > 0, "isShiftedInt<0> doesn't make sense (refers to a 0-bit number.");
-  static_assert(N + S <= 64, "isShiftedInt<N, S> with N + S > 64 is too wide.");
-  return isInt<N + S>(x) && (x % (UINT64_C(1) << S) == 0);
-}
-
-/// Checks if an unsigned integer fits into the given bit width.
-///
-/// This is written as two functions rather than as simply
-///
-///   return N >= 64 || X < (UINT64_C(1) << N);
-///
-/// to keep MSVC from (incorrectly) warning on isUInt<64> that we're shifting
-/// left too many places.
-template <unsigned N>
-constexpr inline typename std::enable_if<(N < 64), bool>::type
-isUInt(uint64_t X) {
-  static_assert(N > 0, "isUInt<0> doesn't make sense");
-  return X < (UINT64_C(1) << (N));
-}
-template <unsigned N>
-constexpr inline typename std::enable_if<N >= 64, bool>::type
-isUInt(uint64_t X) {
-  return true;
-}
-
-// Template specializations to get better code for common cases.
-template <> constexpr inline bool isUInt<8>(uint64_t x) {
-  return static_cast<uint8_t>(x) == x;
-}
-template <> constexpr inline bool isUInt<16>(uint64_t x) {
-  return static_cast<uint16_t>(x) == x;
-}
-template <> constexpr inline bool isUInt<32>(uint64_t x) {
-  return static_cast<uint32_t>(x) == x;
-}
-
-/// Checks if a unsigned integer is an N bit number shifted left by S.
-template <unsigned N, unsigned S>
-constexpr inline bool isShiftedUInt(uint64_t x) {
-  static_assert(
-      N > 0, "isShiftedUInt<0> doesn't make sense (refers to a 0-bit number)");
-  static_assert(N + S <= 64,
-                "isShiftedUInt<N, S> with N + S > 64 is too wide.");
-  // Per the two static_asserts above, S must be strictly less than 64.  So
-  // 1 << S is not undefined behavior.
-  return isUInt<N + S>(x) && (x % (UINT64_C(1) << S) == 0);
-}
-
-/// Gets the maximum value for a N-bit unsigned integer.
-inline uint64_t maxUIntN(uint64_t N) {
-  assert(N > 0 && N <= 64 && "integer width out of range");
-
-  // uint64_t(1) << 64 is undefined behavior, so we can't do
-  //   (uint64_t(1) << N) - 1
-  // without checking first that N != 64.  But this works and doesn't have a
-  // branch.
-  return UINT64_MAX >> (64 - N);
-}
-
-#ifdef _WIN32
-#pragma warning(push)
-#pragma warning(disable : 4146)
-#endif
-
-/// Gets the minimum value for a N-bit signed integer.
-inline int64_t minIntN(int64_t N) {
-  assert(N > 0 && N <= 64 && "integer width out of range");
-
-  return -(UINT64_C(1)<<(N-1));
-}
-
-#ifdef _WIN32
-#pragma warning(pop)
-#endif
-
-/// Gets the maximum value for a N-bit signed integer.
-inline int64_t maxIntN(int64_t N) {
-  assert(N > 0 && N <= 64 && "integer width out of range");
-
-  // This relies on two's complement wraparound when N == 64, so we convert to
-  // int64_t only at the very end to avoid UB.
-  return (UINT64_C(1) << (N - 1)) - 1;
-}
-
-/// Checks if an unsigned integer fits into the given (dynamic) bit width.
-inline bool isUIntN(unsigned N, uint64_t x) {
-  return N >= 64 || x <= maxUIntN(N);
-}
-
-/// Checks if an signed integer fits into the given (dynamic) bit width.
-inline bool isIntN(unsigned N, int64_t x) {
-  return N >= 64 || (minIntN(N) <= x && x <= maxIntN(N));
-}
-
-/// Return true if the argument is a non-empty sequence of ones starting at the
-/// least significant bit with the remainder zero (32 bit version).
-/// Ex. isMask_32(0x0000FFFFU) == true.
-constexpr inline bool isMask_32(uint32_t Value) {
-  return Value && ((Value + 1) & Value) == 0;
-}
-
-/// Return true if the argument is a non-empty sequence of ones starting at the
-/// least significant bit with the remainder zero (64 bit version).
-constexpr inline bool isMask_64(uint64_t Value) {
-  return Value && ((Value + 1) & Value) == 0;
-}
-
-/// Return true if the argument contains a non-empty sequence of ones with the
-/// remainder zero (32 bit version.) Ex. isShiftedMask_32(0x0000FF00U) == true.
-constexpr inline bool isShiftedMask_32(uint32_t Value) {
-  return Value && isMask_32((Value - 1) | Value);
-}
-
-/// Return true if the argument contains a non-empty sequence of ones with the
-/// remainder zero (64 bit version.)
-constexpr inline bool isShiftedMask_64(uint64_t Value) {
-  return Value && isMask_64((Value - 1) | Value);
-}
-
-/// Return true if the argument is a power of two > 0.
-/// Ex. isPowerOf2_32(0x00100000U) == true (32 bit edition.)
-constexpr inline bool isPowerOf2_32(uint32_t Value) {
-  return Value && !(Value & (Value - 1));
-}
-
-/// Return true if the argument is a power of two > 0 (64 bit edition.)
-constexpr inline bool isPowerOf2_64(uint64_t Value) {
-  return Value && !(Value & (Value - 1));
-}
-
-/// Count the number of ones from the most significant bit to the first
-/// zero bit.
-///
-/// Ex. countLeadingOnes(0xFF0FFF00) == 8.
-/// Only unsigned integral types are allowed.
-///
-/// \param ZB the behavior on an input of all ones. Only ZB_Width and
-/// ZB_Undefined are valid arguments.
-template <typename T>
-std::size_t countLeadingOnes(T Value, ZeroBehavior ZB = ZB_Width) {
-  static_assert(std::numeric_limits<T>::is_integer &&
-                    !std::numeric_limits<T>::is_signed,
-                "Only unsigned integral types are allowed.");
-  return countLeadingZeros<T>(~Value, ZB);
-}
-
-/// Count the number of ones from the least significant bit to the first
-/// zero bit.
-///
-/// Ex. countTrailingOnes(0x00FF00FF) == 8.
-/// Only unsigned integral types are allowed.
-///
-/// \param ZB the behavior on an input of all ones. Only ZB_Width and
-/// ZB_Undefined are valid arguments.
-template <typename T>
-std::size_t countTrailingOnes(T Value, ZeroBehavior ZB = ZB_Width) {
-  static_assert(std::numeric_limits<T>::is_integer &&
-                    !std::numeric_limits<T>::is_signed,
-                "Only unsigned integral types are allowed.");
-  return countTrailingZeros<T>(~Value, ZB);
-}
-
-namespace detail {
-template <typename T, std::size_t SizeOfT> struct PopulationCounter {
-  static unsigned count(T Value) {
-    // Generic version, forward to 32 bits.
-    static_assert(SizeOfT <= 4, "Not implemented!");
-#if __GNUC__ >= 4
-    return __builtin_popcount(Value);
-#else
-    uint32_t v = Value;
-    v = v - ((v >> 1) & 0x55555555);
-    v = (v & 0x33333333) + ((v >> 2) & 0x33333333);
-    return ((v + (v >> 4) & 0xF0F0F0F) * 0x1010101) >> 24;
-#endif
-  }
-};
-
-template <typename T> struct PopulationCounter<T, 8> {
-  static unsigned count(T Value) {
-#if __GNUC__ >= 4
-    return __builtin_popcountll(Value);
-#else
-    uint64_t v = Value;
-    v = v - ((v >> 1) & 0x5555555555555555ULL);
-    v = (v & 0x3333333333333333ULL) + ((v >> 2) & 0x3333333333333333ULL);
-    v = (v + (v >> 4)) & 0x0F0F0F0F0F0F0F0FULL;
-    return unsigned((uint64_t)(v * 0x0101010101010101ULL) >> 56);
-#endif
-  }
-};
-} // namespace detail
-
-/// Count the number of set bits in a value.
-/// Ex. countPopulation(0xF000F000) = 8
-/// Returns 0 if the word is zero.
-template <typename T>
-inline unsigned countPopulation(T Value) {
-  static_assert(std::numeric_limits<T>::is_integer &&
-                    !std::numeric_limits<T>::is_signed,
-                "Only unsigned integral types are allowed.");
-  return detail::PopulationCounter<T, sizeof(T)>::count(Value);
-}
-
-/// Return the log base 2 of the specified value.
-inline double Log2(double Value) {
-#if defined(__ANDROID_API__) && __ANDROID_API__ < 18
-  return __builtin_log(Value) / __builtin_log(2.0);
-#else
-  return std::log2(Value);
-#endif
-}
-
-/// Return the floor log base 2 of the specified value, -1 if the value is zero.
-/// (32 bit edition.)
-/// Ex. Log2_32(32) == 5, Log2_32(1) == 0, Log2_32(0) == -1, Log2_32(6) == 2
-inline unsigned Log2_32(uint32_t Value) {
-  return static_cast<unsigned>(31 - countLeadingZeros(Value));
-}
-
-/// Return the floor log base 2 of the specified value, -1 if the value is zero.
-/// (64 bit edition.)
-inline unsigned Log2_64(uint64_t Value) {
-  return static_cast<unsigned>(63 - countLeadingZeros(Value));
-}
-
-/// Return the ceil log base 2 of the specified value, 32 if the value is zero.
-/// (32 bit edition).
-/// Ex. Log2_32_Ceil(32) == 5, Log2_32_Ceil(1) == 0, Log2_32_Ceil(6) == 3
-inline unsigned Log2_32_Ceil(uint32_t Value) {
-  return static_cast<unsigned>(32 - countLeadingZeros(Value - 1));
-}
-
-/// Return the ceil log base 2 of the specified value, 64 if the value is zero.
-/// (64 bit edition.)
-inline unsigned Log2_64_Ceil(uint64_t Value) {
-  return static_cast<unsigned>(64 - countLeadingZeros(Value - 1));
-}
-
-/// Return the greatest common divisor of the values using Euclid's algorithm.
-inline uint64_t GreatestCommonDivisor64(uint64_t A, uint64_t B) {
-  while (B) {
-    uint64_t T = B;
-    B = A % B;
-    A = T;
-  }
-  return A;
-}
-
-/// This function takes a 64-bit integer and returns the bit equivalent double.
-inline double BitsToDouble(uint64_t Bits) {
-  double D;
-  static_assert(sizeof(uint64_t) == sizeof(double), "Unexpected type sizes");
-  memcpy(&D, &Bits, sizeof(Bits));
-  return D;
-}
-
-/// This function takes a 32-bit integer and returns the bit equivalent float.
-inline float BitsToFloat(uint32_t Bits) {
-  float F;
-  static_assert(sizeof(uint32_t) == sizeof(float), "Unexpected type sizes");
-  memcpy(&F, &Bits, sizeof(Bits));
-  return F;
-}
-
-/// This function takes a double and returns the bit equivalent 64-bit integer.
-/// Note that copying doubles around changes the bits of NaNs on some hosts,
-/// notably x86, so this routine cannot be used if these bits are needed.
-inline uint64_t DoubleToBits(double Double) {
-  uint64_t Bits;
-  static_assert(sizeof(uint64_t) == sizeof(double), "Unexpected type sizes");
-  memcpy(&Bits, &Double, sizeof(Double));
-  return Bits;
-}
-
-/// This function takes a float and returns the bit equivalent 32-bit integer.
-/// Note that copying floats around changes the bits of NaNs on some hosts,
-/// notably x86, so this routine cannot be used if these bits are needed.
-inline uint32_t FloatToBits(float Float) {
-  uint32_t Bits;
-  static_assert(sizeof(uint32_t) == sizeof(float), "Unexpected type sizes");
-  memcpy(&Bits, &Float, sizeof(Float));
-  return Bits;
-}
-
-/// A and B are either alignments or offsets. Return the minimum alignment that
-/// may be assumed after adding the two together.
-constexpr inline uint64_t MinAlign(uint64_t A, uint64_t B) {
-  // The largest power of 2 that divides both A and B.
-  //
-  // Replace "-Value" by "1+~Value" in the following commented code to avoid
-  // MSVC warning C4146
-  //    return (A | B) & -(A | B);
-  return (A | B) & (1 + ~(A | B));
-}
-
-/// Aligns \c Addr to \c Alignment bytes, rounding up.
-///
-/// Alignment should be a power of two.  This method rounds up, so
-/// alignAddr(7, 4) == 8 and alignAddr(8, 4) == 8.
-inline uintptr_t alignAddr(const void *Addr, size_t Alignment) {
-  assert(Alignment && isPowerOf2_64((uint64_t)Alignment) &&
-         "Alignment is not a power of two!");
-
-  assert((uintptr_t)Addr + Alignment - 1 >= (uintptr_t)Addr);
-
-  return (((uintptr_t)Addr + Alignment - 1) & ~(uintptr_t)(Alignment - 1));
-}
-
-/// Returns the necessary adjustment for aligning \c Ptr to \c Alignment
-/// bytes, rounding up.
-inline size_t alignmentAdjustment(const void *Ptr, size_t Alignment) {
-  return alignAddr(Ptr, Alignment) - (uintptr_t)Ptr;
-}
-
-/// Returns the next power of two (in 64-bits) that is strictly greater than A.
-/// Returns zero on overflow.
-inline uint64_t NextPowerOf2(uint64_t A) {
-  A |= (A >> 1);
-  A |= (A >> 2);
-  A |= (A >> 4);
-  A |= (A >> 8);
-  A |= (A >> 16);
-  A |= (A >> 32);
-  return A + 1;
-}
-
-/// Returns the power of two which is less than or equal to the given value.
-/// Essentially, it is a floor operation across the domain of powers of two.
-inline uint64_t PowerOf2Floor(uint64_t A) {
-  if (!A) return 0;
-  return 1ull << (63 - countLeadingZeros(A, ZB_Undefined));
-}
-
-/// Returns the power of two which is greater than or equal to the given value.
-/// Essentially, it is a ceil operation across the domain of powers of two.
-inline uint64_t PowerOf2Ceil(uint64_t A) {
-  if (!A)
-    return 0;
-  return NextPowerOf2(A - 1);
-}
-
-/// Returns the next integer (mod 2**64) that is greater than or equal to
-/// \p Value and is a multiple of \p Align. \p Align must be non-zero.
-///
-/// If non-zero \p Skew is specified, the return value will be a minimal
-/// integer that is greater than or equal to \p Value and equal to
-/// \p Align * N + \p Skew for some integer N. If \p Skew is larger than
-/// \p Align, its value is adjusted to '\p Skew mod \p Align'.
-///
-/// Examples:
-/// \code
-///   alignTo(5, 8) = 8
-///   alignTo(17, 8) = 24
-///   alignTo(~0LL, 8) = 0
-///   alignTo(321, 255) = 510
-///
-///   alignTo(5, 8, 7) = 7
-///   alignTo(17, 8, 1) = 17
-///   alignTo(~0LL, 8, 3) = 3
-///   alignTo(321, 255, 42) = 552
-/// \endcode
-inline uint64_t alignTo(uint64_t Value, uint64_t Align, uint64_t Skew = 0) {
-  assert(Align != 0u && "Align can't be 0.");
-  Skew %= Align;
-  return (Value + Align - 1 - Skew) / Align * Align + Skew;
-}
-
-/// Returns the next integer (mod 2**64) that is greater than or equal to
-/// \p Value and is a multiple of \c Align. \c Align must be non-zero.
-template <uint64_t Align> constexpr inline uint64_t alignTo(uint64_t Value) {
-  static_assert(Align != 0u, "Align must be non-zero");
-  return (Value + Align - 1) / Align * Align;
-}
-
-/// Returns the integer ceil(Numerator / Denominator).
-inline uint64_t divideCeil(uint64_t Numerator, uint64_t Denominator) {
-  return alignTo(Numerator, Denominator) / Denominator;
-}
-
-/// \c alignTo for contexts where a constant expression is required.
-/// \sa alignTo
-///
-/// \todo FIXME: remove when \c constexpr becomes really \c constexpr
-template <uint64_t Align>
-struct AlignTo {
-  static_assert(Align != 0u, "Align must be non-zero");
-  template <uint64_t Value>
-  struct from_value {
-    static const uint64_t value = (Value + Align - 1) / Align * Align;
-  };
-};
-
-/// Returns the largest uint64_t less than or equal to \p Value and is
-/// \p Skew mod \p Align. \p Align must be non-zero
-inline uint64_t alignDown(uint64_t Value, uint64_t Align, uint64_t Skew = 0) {
-  assert(Align != 0u && "Align can't be 0.");
-  Skew %= Align;
-  return (Value - Skew) / Align * Align + Skew;
-}
-
-/// Returns the offset to the next integer (mod 2**64) that is greater than
-/// or equal to \p Value and is a multiple of \p Align. \p Align must be
-/// non-zero.
-inline uint64_t OffsetToAlignment(uint64_t Value, uint64_t Align) {
-  return alignTo(Value, Align) - Value;
-}
-
-/// Sign-extend the number in the bottom B bits of X to a 32-bit integer.
-/// Requires 0 < B <= 32.
-template <unsigned B> constexpr inline int32_t SignExtend32(uint32_t X) {
-  static_assert(B > 0, "Bit width can't be 0.");
-  static_assert(B <= 32, "Bit width out of range.");
-  return int32_t(X << (32 - B)) >> (32 - B);
-}
-
-/// Sign-extend the number in the bottom B bits of X to a 32-bit integer.
-/// Requires 0 < B < 32.
-inline int32_t SignExtend32(uint32_t X, unsigned B) {
-  assert(B > 0 && "Bit width can't be 0.");
-  assert(B <= 32 && "Bit width out of range.");
-  return int32_t(X << (32 - B)) >> (32 - B);
-}
-
-/// Sign-extend the number in the bottom B bits of X to a 64-bit integer.
-/// Requires 0 < B < 64.
-template <unsigned B> constexpr inline int64_t SignExtend64(uint64_t x) {
-  static_assert(B > 0, "Bit width can't be 0.");
-  static_assert(B <= 64, "Bit width out of range.");
-  return int64_t(x << (64 - B)) >> (64 - B);
-}
-
-/// Sign-extend the number in the bottom B bits of X to a 64-bit integer.
-/// Requires 0 < B < 64.
-inline int64_t SignExtend64(uint64_t X, unsigned B) {
-  assert(B > 0 && "Bit width can't be 0.");
-  assert(B <= 64 && "Bit width out of range.");
-  return int64_t(X << (64 - B)) >> (64 - B);
-}
-
-/// Subtract two unsigned integers, X and Y, of type T and return the absolute
-/// value of the result.
-template <typename T>
-typename std::enable_if<std::is_unsigned<T>::value, T>::type
-AbsoluteDifference(T X, T Y) {
-  return (std::max)(X, Y) - (std::min)(X, Y);
-}
-
-/// Add two unsigned integers, X and Y, of type T.  Clamp the result to the
-/// maximum representable value of T on overflow.  ResultOverflowed indicates if
-/// the result is larger than the maximum representable value of type T.
-template <typename T>
-typename std::enable_if<std::is_unsigned<T>::value, T>::type
-SaturatingAdd(T X, T Y, bool *ResultOverflowed = nullptr) {
-  bool Dummy;
-  bool &Overflowed = ResultOverflowed ? *ResultOverflowed : Dummy;
-  // Hacker's Delight, p. 29
-  T Z = X + Y;
-  Overflowed = (Z < X || Z < Y);
-  if (Overflowed)
-    return (std::numeric_limits<T>::max)();
-  else
-    return Z;
-}
-
-/// Multiply two unsigned integers, X and Y, of type T.  Clamp the result to the
-/// maximum representable value of T on overflow.  ResultOverflowed indicates if
-/// the result is larger than the maximum representable value of type T.
-template <typename T>
-typename std::enable_if<std::is_unsigned<T>::value, T>::type
-SaturatingMultiply(T X, T Y, bool *ResultOverflowed = nullptr) {
-  bool Dummy;
-  bool &Overflowed = ResultOverflowed ? *ResultOverflowed : Dummy;
-
-  // Hacker's Delight, p. 30 has a different algorithm, but we don't use that
-  // because it fails for uint16_t (where multiplication can have undefined
-  // behavior due to promotion to int), and requires a division in addition
-  // to the multiplication.
-
-  Overflowed = false;
-
-  // Log2(Z) would be either Log2Z or Log2Z + 1.
-  // Special case: if X or Y is 0, Log2_64 gives -1, and Log2Z
-  // will necessarily be less than Log2Max as desired.
-  int Log2Z = Log2_64(X) + Log2_64(Y);
-  const T Max = (std::numeric_limits<T>::max)();
-  int Log2Max = Log2_64(Max);
-  if (Log2Z < Log2Max) {
-    return X * Y;
-  }
-  if (Log2Z > Log2Max) {
-    Overflowed = true;
-    return Max;
-  }
-
-  // We're going to use the top bit, and maybe overflow one
-  // bit past it. Multiply all but the bottom bit then add
-  // that on at the end.
-  T Z = (X >> 1) * Y;
-  if (Z & ~(Max >> 1)) {
-    Overflowed = true;
-    return Max;
-  }
-  Z <<= 1;
-  if (X & 1)
-    return SaturatingAdd(Z, Y, ResultOverflowed);
-
-  return Z;
-}
-
-/// Multiply two unsigned integers, X and Y, and add the unsigned integer, A to
-/// the product. Clamp the result to the maximum representable value of T on
-/// overflow. ResultOverflowed indicates if the result is larger than the
-/// maximum representable value of type T.
-template <typename T>
-typename std::enable_if<std::is_unsigned<T>::value, T>::type
-SaturatingMultiplyAdd(T X, T Y, T A, bool *ResultOverflowed = nullptr) {
-  bool Dummy;
-  bool &Overflowed = ResultOverflowed ? *ResultOverflowed : Dummy;
-
-  T Product = SaturatingMultiply(X, Y, &Overflowed);
-  if (Overflowed)
-    return Product;
-
-  return SaturatingAdd(A, Product, &Overflowed);
-}
-
-// Typesafe implementation of the signum function.
-// Returns -1 if negative, 1 if positive, 0 if 0.
-template <typename T>
-constexpr int sgn(T val) {
-  return (T(0) < val) - (val < T(0));
-}
-
-/**
- * Linearly interpolates between two values.
- *
- * @param startValue The start value.
- * @param endValue The end value.
- * @param t The fraction for interpolation.
- *
- * @return The interpolated value.
- */
-template <typename T>
-constexpr T Lerp(const T& startValue, const T& endValue, double t) {
-  return startValue + (endValue - startValue) * t;
-}
-
-} // namespace wpi
-
-#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/MemAlloc.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/MemAlloc.h
deleted file mode 100644
index addccb5..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/MemAlloc.h
+++ /dev/null
@@ -1,61 +0,0 @@
-//===- MemAlloc.h - Memory allocation functions -----------------*- C++ -*-===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-/// \file
-///
-/// This file defines counterparts of C library allocation functions defined in
-/// the namespace 'std'. The new allocation functions crash on allocation
-/// failure instead of returning null pointer.
-///
-//===----------------------------------------------------------------------===//
-
-#ifndef WPIUTIL_WPI_MEMALLOC_H
-#define WPIUTIL_WPI_MEMALLOC_H
-
-#include "wpi/Compiler.h"
-#include "wpi/ErrorHandling.h"
-#include <cstdlib>
-
-namespace wpi {
-
-#ifdef _WIN32
-#pragma warning(push)
-// Warning on NONNULL, report is not known to abort
-#pragma warning(disable : 6387)
-#pragma warning(disable : 28196)
-#pragma warning(disable : 28183)
-#endif
-
-LLVM_ATTRIBUTE_RETURNS_NONNULL inline void *safe_malloc(size_t Sz) {
-  void *Result = std::malloc(Sz);
-  if (Result == nullptr)
-    report_bad_alloc_error("Allocation failed");
-  return Result;
-}
-
-LLVM_ATTRIBUTE_RETURNS_NONNULL inline void *safe_calloc(size_t Count,
-                                                        size_t Sz) {
-  void *Result = std::calloc(Count, Sz);
-  if (Result == nullptr)
-    report_bad_alloc_error("Allocation failed");
-  return Result;
-}
-
-LLVM_ATTRIBUTE_RETURNS_NONNULL inline void *safe_realloc(void *Ptr, size_t Sz) {
-  void *Result = std::realloc(Ptr, Sz);
-  if (Result == nullptr)
-    report_bad_alloc_error("Allocation failed");
-  return Result;
-}
-
-#ifdef _WIN32
-#pragma warning(pop)
-#endif
-
-}
-#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/MessagePack.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/MessagePack.h
new file mode 100644
index 0000000..e1f54e5
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/MessagePack.h
@@ -0,0 +1,39 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <stdint.h>
+
+#include <span>
+#include <string>
+#include <string_view>
+
+#include "wpi/mpack.h"
+
+namespace mpack {
+
+inline void mpack_write_str(mpack_writer_t* writer, std::string_view str) {
+  mpack_write_str(writer, str.data(), str.size());
+}
+
+inline void mpack_write_bytes(mpack_writer_t* writer,
+                              std::span<const uint8_t> data) {
+  mpack_write_bytes(writer, reinterpret_cast<const char*>(data.data()),
+                    data.size());
+}
+
+inline void mpack_reader_init_data(mpack_reader_t* reader,
+                                   std::span<const uint8_t> data) {
+  mpack_reader_init_data(reader, reinterpret_cast<const char*>(data.data()),
+                         data.size());
+}
+
+mpack_error_t mpack_expect_str(mpack_reader_t* reader, std::string* out,
+                               uint32_t maxLen = 1024);
+
+mpack_error_t mpack_read_str(mpack_reader_t* reader, mpack_tag_t* tag,
+                             std::string* out, uint32_t maxLen = 1024);
+
+}  // namespace mpack
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/MimeTypes.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/MimeTypes.h
deleted file mode 100644
index ce36ea2..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/MimeTypes.h
+++ /dev/null
@@ -1,16 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_MIMETYPES_H_
-#define WPIUTIL_WPI_MIMETYPES_H_
-
-#include <string_view>
-
-namespace wpi {
-
-std::string_view MimeTypeFromPath(std::string_view path);
-
-}  // namespace wpi
-
-#endif  // WPIUTIL_WPI_MIMETYPES_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/MulticastServiceAnnouncer.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/MulticastServiceAnnouncer.h
deleted file mode 100644
index 5d2048d..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/MulticastServiceAnnouncer.h
+++ /dev/null
@@ -1,61 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <stdint.h>
-
-#ifdef __cplusplus
-#include <memory>
-#include <string>
-#include <string_view>
-#include <utility>
-
-#include "wpi/span.h"
-namespace wpi {
-class MulticastServiceAnnouncer {
- public:
-  MulticastServiceAnnouncer(
-      std::string_view serviceName, std::string_view serviceType, int port,
-      wpi::span<const std::pair<std::string, std::string>> txt);
-  MulticastServiceAnnouncer(
-      std::string_view serviceName, std::string_view serviceType, int port,
-      wpi::span<const std::pair<std::string_view, std::string_view>> txt);
-  ~MulticastServiceAnnouncer() noexcept;
-  void Start();
-  void Stop();
-  bool HasImplementation() const;
-  struct Impl;
-
- private:
-  std::unique_ptr<Impl> pImpl;
-};
-}  // namespace wpi
-#endif
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-typedef unsigned int WPI_MulticastServiceAnnouncerHandle;  // NOLINT
-
-WPI_MulticastServiceAnnouncerHandle WPI_CreateMulticastServiceAnnouncer(
-    const char* serviceName, const char* serviceType, int32_t port,
-    int32_t txtCount, const char** keys, const char** values);
-
-void WPI_FreeMulticastServiceAnnouncer(
-    WPI_MulticastServiceAnnouncerHandle handle);
-
-void WPI_StartMulticastServiceAnnouncer(
-    WPI_MulticastServiceAnnouncerHandle handle);
-
-void WPI_StopMulticastServiceAnnouncer(
-    WPI_MulticastServiceAnnouncerHandle handle);
-
-int32_t WPI_GetMulticastServiceAnnouncerHasImplementation(
-    WPI_MulticastServiceAnnouncerHandle handle);
-
-#ifdef __cplusplus
-}  // extern "C"
-#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/MulticastServiceResolver.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/MulticastServiceResolver.h
deleted file mode 100644
index 0b63c2f..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/MulticastServiceResolver.h
+++ /dev/null
@@ -1,102 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include "wpi/Synchronization.h"
-
-#ifdef __cplusplus
-#include <functional>
-#include <memory>
-#include <string>
-#include <string_view>
-#include <utility>
-#include <vector>
-
-#include "wpi/mutex.h"
-#include "wpi/span.h"
-namespace wpi {
-class MulticastServiceResolver {
- public:
-  explicit MulticastServiceResolver(std::string_view serviceType);
-  ~MulticastServiceResolver() noexcept;
-  struct ServiceData {
-    unsigned int ipv4Address;
-    int port;
-    std::string serviceName;
-    std::string hostName;
-    std::vector<std::pair<std::string, std::string>> txt;
-  };
-  void Start();
-  void Stop();
-  WPI_EventHandle GetEventHandle() const { return event.GetHandle(); }
-  std::vector<ServiceData> GetData() {
-    std::scoped_lock lock{mutex};
-    event.Reset();
-    if (queue.empty()) {
-      return {};
-    }
-    std::vector<ServiceData> ret;
-    queue.swap(ret);
-    return ret;
-  }
-  bool HasImplementation() const;
-  struct Impl;
-
- private:
-  void PushData(ServiceData&& data) {
-    std::scoped_lock lock{mutex};
-    queue.emplace_back(std::forward<ServiceData>(data));
-    event.Set();
-  }
-  wpi::Event event{true};
-  std::vector<ServiceData> queue;
-  wpi::mutex mutex;
-  std::unique_ptr<Impl> pImpl;
-};
-}  // namespace wpi
-#endif
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-typedef unsigned int WPI_MulticastServiceResolverHandle;  // NOLINT
-
-WPI_MulticastServiceResolverHandle WPI_CreateMulticastServiceResolver(
-    const char* serviceType);
-
-void WPI_FreeMulticastServiceResolver(
-    WPI_MulticastServiceResolverHandle handle);
-
-void WPI_StartMulticastServiceResolver(
-    WPI_MulticastServiceResolverHandle handle);
-
-void WPI_StopMulticastServiceResolver(
-    WPI_MulticastServiceResolverHandle handle);
-
-int32_t WPI_GetMulticastServiceResolverHasImplementation(
-    WPI_MulticastServiceResolverHandle handle);
-
-WPI_EventHandle WPI_GetMulticastServiceResolverEventHandle(
-    WPI_MulticastServiceResolverHandle handle);
-
-typedef struct WPI_ServiceData {  // NOLINT
-  uint32_t ipv4Address;
-  int32_t port;
-  const char* serviceName;
-  const char* hostName;
-  int32_t txtCount;
-  const char** txtKeys;
-  const char** txtValues;
-} WPI_ServiceData;
-
-WPI_ServiceData* WPI_GetMulticastServiceResolverData(
-    WPI_MulticastServiceResolverHandle handle, int32_t* dataCount);
-
-void WPI_FreeServiceData(WPI_ServiceData* serviceData, int32_t length);
-
-#ifdef __cplusplus
-}  // extern "C"
-#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/NetworkAcceptor.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/NetworkAcceptor.h
deleted file mode 100644
index 9982360..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/NetworkAcceptor.h
+++ /dev/null
@@ -1,29 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_NETWORKACCEPTOR_H_
-#define WPIUTIL_WPI_NETWORKACCEPTOR_H_
-
-#include <memory>
-
-#include "wpi/NetworkStream.h"
-
-namespace wpi {
-
-class NetworkAcceptor {
- public:
-  NetworkAcceptor() = default;
-  virtual ~NetworkAcceptor() = default;
-
-  virtual int start() = 0;
-  virtual void shutdown() = 0;
-  virtual std::unique_ptr<NetworkStream> accept() = 0;
-
-  NetworkAcceptor(const NetworkAcceptor&) = delete;
-  NetworkAcceptor& operator=(const NetworkAcceptor&) = delete;
-};
-
-}  // namespace wpi
-
-#endif  // WPIUTIL_WPI_NETWORKACCEPTOR_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/NetworkStream.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/NetworkStream.h
deleted file mode 100644
index b842ecd..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/NetworkStream.h
+++ /dev/null
@@ -1,44 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_NETWORKSTREAM_H_
-#define WPIUTIL_WPI_NETWORKSTREAM_H_
-
-#include <cstddef>
-#include <string_view>
-
-namespace wpi {
-
-class NetworkStream {
- public:
-  NetworkStream() = default;
-  virtual ~NetworkStream() = default;
-
-  enum Error {
-    kConnectionClosed = 0,
-    kConnectionReset = -1,
-    kConnectionTimedOut = -2,
-    kWouldBlock = -3
-  };
-
-  virtual size_t send(const char* buffer, size_t len, Error* err) = 0;
-  virtual size_t receive(char* buffer, size_t len, Error* err,
-                         int timeout = 0) = 0;
-  virtual void close() = 0;
-
-  virtual std::string_view getPeerIP() const = 0;
-  virtual int getPeerPort() const = 0;
-  virtual void setNoDelay() = 0;
-
-  // returns false on failure
-  virtual bool setBlocking(bool enabled) = 0;
-  virtual int getNativeHandle() const = 0;
-
-  NetworkStream(const NetworkStream&) = delete;
-  NetworkStream& operator=(const NetworkStream&) = delete;
-};
-
-}  // namespace wpi
-
-#endif  // WPIUTIL_WPI_NETWORKSTREAM_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/ParallelTcpConnector.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/ParallelTcpConnector.h
deleted file mode 100644
index 47c29d0..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/ParallelTcpConnector.h
+++ /dev/null
@@ -1,119 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <stdint.h>
-
-#include <functional>
-#include <memory>
-#include <string>
-#include <utility>
-#include <vector>
-
-#include "wpi/span.h"
-#include "wpi/uv/Timer.h"
-
-namespace wpi {
-
-class Logger;
-
-namespace uv {
-class GetAddrInfoReq;
-class Loop;
-class Tcp;
-class Timer;
-}  // namespace uv
-
-/**
- * Parallel TCP connector.  Attempts parallel resolution and connection to
- * multiple servers with automatic retry if none connect.
- *
- * Each successful TCP connection results in a call to the connected callback.
- * For correct operation, the consuming code (either the connected callback or
- * e.g. task it starts) must call Succeeded() to indicate if the connection has
- * succeeded prior to the reconnect rate timeout.  A successful connection
- * results in the connector terminating all other connection attempts.
- *
- * After the reconnect rate times out, all remaining active connection attempts
- * are canceled and new ones started.
- */
-class ParallelTcpConnector
-    : public std::enable_shared_from_this<ParallelTcpConnector> {
-  struct private_init {};
-
- public:
-  /**
-   * Create.
-   *
-   * @param loop loop
-   * @param reconnectRate how long to wait after starting connection attempts
-   *                      to cancel and attempt connecting again
-   * @param logger logger
-   * @param connected callback function when a connection succeeds; may be
-   *                  called multiple times if it does not call Succeeded()
-   *                  before returning
-   * @return Parallel connector
-   */
-  static std::shared_ptr<ParallelTcpConnector> Create(
-      wpi::uv::Loop& loop, wpi::uv::Timer::Time reconnectRate,
-      wpi::Logger& logger, std::function<void(wpi::uv::Tcp& tcp)> connected) {
-    return std::make_shared<ParallelTcpConnector>(
-        loop, reconnectRate, logger, std::move(connected), private_init{});
-  }
-
-  ParallelTcpConnector(wpi::uv::Loop& loop, wpi::uv::Timer::Time reconnectRate,
-                       wpi::Logger& logger,
-                       std::function<void(wpi::uv::Tcp& tcp)> connected,
-                       const private_init&);
-  ~ParallelTcpConnector();
-
-  ParallelTcpConnector(const ParallelTcpConnector&) = delete;
-  ParallelTcpConnector& operator=(const ParallelTcpConnector&) = delete;
-
-  /**
-   * Closes resources, canceling all pending action attempts.
-   */
-  void Close();
-
-  /**
-   * Changes the servers/ports to connect to.  Starts connection attempts if not
-   * already connected.
-   *
-   * @param servers array of server/port pairs
-   */
-  void SetServers(
-      wpi::span<const std::pair<std::string, unsigned int>> servers);
-
-  /**
-   * Tells the parallel connector that the current connection has terminated and
-   * it is necessary to start reconnection attempts.
-   */
-  void Disconnected();
-
-  /**
-   * Tells the parallel connector that a particular connection has succeeded and
-   * it should stop trying to connect.
-   *
-   * @param tcp connection passed to connected callback
-   */
-  void Succeeded(wpi::uv::Tcp& tcp);
-
- private:
-  bool IsConnected() const { return m_isConnected || m_servers.empty(); }
-  void Connect();
-  void CancelAll(wpi::uv::Tcp* except = nullptr);
-
-  wpi::uv::Loop& m_loop;
-  wpi::Logger& m_logger;
-  wpi::uv::Timer::Time m_reconnectRate;
-  std::function<void(wpi::uv::Tcp& tcp)> m_connected;
-  std::shared_ptr<wpi::uv::Timer> m_reconnectTimer;
-  std::vector<std::pair<std::string, unsigned int>> m_servers;
-  std::vector<std::weak_ptr<wpi::uv::GetAddrInfoReq>> m_resolvers;
-  std::vector<std::weak_ptr<wpi::uv::Tcp>> m_attempts;
-  bool m_isConnected{false};
-};
-
-}  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/PointerIntPair.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/PointerIntPair.h
deleted file mode 100644
index e6a1212..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/PointerIntPair.h
+++ /dev/null
@@ -1,235 +0,0 @@
-//===- llvm/ADT/PointerIntPair.h - Pair for pointer and int -----*- C++ -*-===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-//
-// This file defines the PointerIntPair class.
-//
-//===----------------------------------------------------------------------===//
-
-#ifndef WPIUTIL_WPI_POINTERINTPAIR_H
-#define WPIUTIL_WPI_POINTERINTPAIR_H
-
-#include "wpi/PointerLikeTypeTraits.h"
-#include <cassert>
-#include <cstdint>
-#include <limits>
-
-namespace wpi {
-
-template <typename T> struct DenseMapInfo;
-template <typename PointerT, unsigned IntBits, typename PtrTraits>
-struct PointerIntPairInfo;
-
-/// PointerIntPair - This class implements a pair of a pointer and small
-/// integer.  It is designed to represent this in the space required by one
-/// pointer by bitmangling the integer into the low part of the pointer.  This
-/// can only be done for small integers: typically up to 3 bits, but it depends
-/// on the number of bits available according to PointerLikeTypeTraits for the
-/// type.
-///
-/// Note that PointerIntPair always puts the IntVal part in the highest bits
-/// possible.  For example, PointerIntPair<void*, 1, bool> will put the bit for
-/// the bool into bit #2, not bit #0, which allows the low two bits to be used
-/// for something else.  For example, this allows:
-///   PointerIntPair<PointerIntPair<void*, 1, bool>, 1, bool>
-/// ... and the two bools will land in different bits.
-template <typename PointerTy, unsigned IntBits, typename IntType = unsigned,
-          typename PtrTraits = PointerLikeTypeTraits<PointerTy>,
-          typename Info = PointerIntPairInfo<PointerTy, IntBits, PtrTraits>>
-class PointerIntPair {
-  // Used by MSVC visualizer and generally helpful for debugging/visualizing.
-  using InfoTy = Info;
-  intptr_t Value = 0;
-
-public:
-  constexpr PointerIntPair() = default;
-
-  PointerIntPair(PointerTy PtrVal, IntType IntVal) {
-    setPointerAndInt(PtrVal, IntVal);
-  }
-
-  explicit PointerIntPair(PointerTy PtrVal) { initWithPointer(PtrVal); }
-
-  PointerTy getPointer() const { return Info::getPointer(Value); }
-
-  IntType getInt() const { return (IntType)Info::getInt(Value); }
-
-  void setPointer(PointerTy PtrVal) {
-    Value = Info::updatePointer(Value, PtrVal);
-  }
-
-  void setInt(IntType IntVal) {
-    Value = Info::updateInt(Value, static_cast<intptr_t>(IntVal));
-  }
-
-  void initWithPointer(PointerTy PtrVal) {
-    Value = Info::updatePointer(0, PtrVal);
-  }
-
-  void setPointerAndInt(PointerTy PtrVal, IntType IntVal) {
-    Value = Info::updateInt(Info::updatePointer(0, PtrVal),
-                            static_cast<intptr_t>(IntVal));
-  }
-
-  PointerTy const *getAddrOfPointer() const {
-    return const_cast<PointerIntPair *>(this)->getAddrOfPointer();
-  }
-
-  PointerTy *getAddrOfPointer() {
-    assert(Value == reinterpret_cast<intptr_t>(getPointer()) &&
-           "Can only return the address if IntBits is cleared and "
-           "PtrTraits doesn't change the pointer");
-    return reinterpret_cast<PointerTy *>(&Value);
-  }
-
-  void *getOpaqueValue() const { return reinterpret_cast<void *>(Value); }
-
-  void setFromOpaqueValue(void *Val) {
-    Value = reinterpret_cast<intptr_t>(Val);
-  }
-
-  static PointerIntPair getFromOpaqueValue(void *V) {
-    PointerIntPair P;
-    P.setFromOpaqueValue(V);
-    return P;
-  }
-
-  // Allow PointerIntPairs to be created from const void * if and only if the
-  // pointer type could be created from a const void *.
-  static PointerIntPair getFromOpaqueValue(const void *V) {
-    (void)PtrTraits::getFromVoidPointer(V);
-    return getFromOpaqueValue(const_cast<void *>(V));
-  }
-
-  bool operator==(const PointerIntPair &RHS) const {
-    return Value == RHS.Value;
-  }
-
-  bool operator!=(const PointerIntPair &RHS) const {
-    return Value != RHS.Value;
-  }
-
-  bool operator<(const PointerIntPair &RHS) const { return Value < RHS.Value; }
-  bool operator>(const PointerIntPair &RHS) const { return Value > RHS.Value; }
-
-  bool operator<=(const PointerIntPair &RHS) const {
-    return Value <= RHS.Value;
-  }
-
-  bool operator>=(const PointerIntPair &RHS) const {
-    return Value >= RHS.Value;
-  }
-};
-
-template <typename PointerT, unsigned IntBits, typename PtrTraits>
-struct PointerIntPairInfo {
-  static_assert(PtrTraits::NumLowBitsAvailable <
-                    std::numeric_limits<uintptr_t>::digits,
-                "cannot use a pointer type that has all bits free");
-  static_assert(IntBits <= PtrTraits::NumLowBitsAvailable,
-                "PointerIntPair with integer size too large for pointer");
-  enum : uintptr_t {
-    /// PointerBitMask - The bits that come from the pointer.
-    PointerBitMask =
-        ~(uintptr_t)(((intptr_t)1 << PtrTraits::NumLowBitsAvailable) - 1),
-
-    /// IntShift - The number of low bits that we reserve for other uses, and
-    /// keep zero.
-    IntShift = (uintptr_t)PtrTraits::NumLowBitsAvailable - IntBits,
-
-    /// IntMask - This is the unshifted mask for valid bits of the int type.
-    IntMask = (uintptr_t)(((intptr_t)1 << IntBits) - 1),
-
-    // ShiftedIntMask - This is the bits for the integer shifted in place.
-    ShiftedIntMask = (uintptr_t)(IntMask << IntShift)
-  };
-
-  static PointerT getPointer(intptr_t Value) {
-    return PtrTraits::getFromVoidPointer(
-        reinterpret_cast<void *>(Value & PointerBitMask));
-  }
-
-  static intptr_t getInt(intptr_t Value) {
-    return (Value >> IntShift) & IntMask;
-  }
-
-  static intptr_t updatePointer(intptr_t OrigValue, PointerT Ptr) {
-    intptr_t PtrWord =
-        reinterpret_cast<intptr_t>(PtrTraits::getAsVoidPointer(Ptr));
-    assert((PtrWord & ~PointerBitMask) == 0 &&
-           "Pointer is not sufficiently aligned");
-    // Preserve all low bits, just update the pointer.
-    return PtrWord | (OrigValue & ~PointerBitMask);
-  }
-
-  static intptr_t updateInt(intptr_t OrigValue, intptr_t Int) {
-    intptr_t IntWord = static_cast<intptr_t>(Int);
-    assert((IntWord & ~IntMask) == 0 && "Integer too large for field");
-
-    // Preserve all bits other than the ones we are updating.
-    return (OrigValue & ~ShiftedIntMask) | IntWord << IntShift;
-  }
-};
-
-template <typename T> struct isPodLike;
-template <typename PointerTy, unsigned IntBits, typename IntType>
-struct isPodLike<PointerIntPair<PointerTy, IntBits, IntType>> {
-  static const bool value = true;
-};
-
-// Provide specialization of DenseMapInfo for PointerIntPair.
-template <typename PointerTy, unsigned IntBits, typename IntType>
-struct DenseMapInfo<PointerIntPair<PointerTy, IntBits, IntType>> {
-  using Ty = PointerIntPair<PointerTy, IntBits, IntType>;
-
-  static Ty getEmptyKey() {
-    uintptr_t Val = static_cast<uintptr_t>(-1);
-    Val <<= PointerLikeTypeTraits<Ty>::NumLowBitsAvailable;
-    return Ty::getFromOpaqueValue(reinterpret_cast<void *>(Val));
-  }
-
-  static Ty getTombstoneKey() {
-    uintptr_t Val = static_cast<uintptr_t>(-2);
-    Val <<= PointerLikeTypeTraits<PointerTy>::NumLowBitsAvailable;
-    return Ty::getFromOpaqueValue(reinterpret_cast<void *>(Val));
-  }
-
-  static unsigned getHashValue(Ty V) {
-    uintptr_t IV = reinterpret_cast<uintptr_t>(V.getOpaqueValue());
-    return unsigned(IV) ^ unsigned(IV >> 9);
-  }
-
-  static bool isEqual(const Ty &LHS, const Ty &RHS) { return LHS == RHS; }
-};
-
-// Teach SmallPtrSet that PointerIntPair is "basically a pointer".
-template <typename PointerTy, unsigned IntBits, typename IntType,
-          typename PtrTraits>
-struct PointerLikeTypeTraits<
-    PointerIntPair<PointerTy, IntBits, IntType, PtrTraits>> {
-  static inline void *
-  getAsVoidPointer(const PointerIntPair<PointerTy, IntBits, IntType> &P) {
-    return P.getOpaqueValue();
-  }
-
-  static inline PointerIntPair<PointerTy, IntBits, IntType>
-  getFromVoidPointer(void *P) {
-    return PointerIntPair<PointerTy, IntBits, IntType>::getFromOpaqueValue(P);
-  }
-
-  static inline PointerIntPair<PointerTy, IntBits, IntType>
-  getFromVoidPointer(const void *P) {
-    return PointerIntPair<PointerTy, IntBits, IntType>::getFromOpaqueValue(P);
-  }
-
-  enum { NumLowBitsAvailable = PtrTraits::NumLowBitsAvailable - IntBits };
-};
-
-} // end namespace wpi
-
-#endif // WPIUTIL_WPI_POINTERINTPAIR_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/PointerLikeTypeTraits.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/PointerLikeTypeTraits.h
deleted file mode 100644
index fa136e0..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/PointerLikeTypeTraits.h
+++ /dev/null
@@ -1,150 +0,0 @@
-//===- llvm/Support/PointerLikeTypeTraits.h - Pointer Traits ----*- C++ -*-===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-//
-// This file defines the PointerLikeTypeTraits class.  This allows data
-// structures to reason about pointers and other things that are pointer sized.
-//
-//===----------------------------------------------------------------------===//
-
-#ifndef WPIUTIL_WPI_POINTERLIKETYPETRAITS_H
-#define WPIUTIL_WPI_POINTERLIKETYPETRAITS_H
-
-#include <cstdint>
-#include <cstdlib>
-#include <type_traits>
-
-namespace wpi {
-
-/// A traits type that is used to handle pointer types and things that are just
-/// wrappers for pointers as a uniform entity.
-template <typename T> struct PointerLikeTypeTraits;
-
-namespace detail {
-/// A tiny meta function to compute the log2 of a compile time constant.
-template <size_t N>
-struct ConstantLog2
-    : std::integral_constant<size_t, ConstantLog2<N / 2>::value + 1> {};
-template <> struct ConstantLog2<1> : std::integral_constant<size_t, 0> {};
-
-// Provide a trait to check if T is pointer-like.
-template <typename T, typename U = void> struct HasPointerLikeTypeTraits {
-  static const bool value = false;
-};
-
-// sizeof(T) is valid only for a complete T.
-template <typename T> struct HasPointerLikeTypeTraits<
-  T, decltype((sizeof(PointerLikeTypeTraits<T>) + sizeof(T)), void())> {
-  static const bool value = true;
-};
-
-template <typename T> struct IsPointerLike {
-  static const bool value = HasPointerLikeTypeTraits<T>::value;
-};
-
-template <typename T> struct IsPointerLike<T *> {
-  static const bool value = true;
-};
-} // namespace detail
-
-// Provide PointerLikeTypeTraits for non-cvr pointers.
-template <typename T> struct PointerLikeTypeTraits<T *> {
-  static inline void *getAsVoidPointer(T *P) { return P; }
-  static inline T *getFromVoidPointer(void *P) { return static_cast<T *>(P); }
-
-  enum { NumLowBitsAvailable = detail::ConstantLog2<alignof(T)>::value };
-};
-
-template <> struct PointerLikeTypeTraits<void *> {
-  static inline void *getAsVoidPointer(void *P) { return P; }
-  static inline void *getFromVoidPointer(void *P) { return P; }
-
-  /// Note, we assume here that void* is related to raw malloc'ed memory and
-  /// that malloc returns objects at least 4-byte aligned. However, this may be
-  /// wrong, or pointers may be from something other than malloc. In this case,
-  /// you should specify a real typed pointer or avoid this template.
-  ///
-  /// All clients should use assertions to do a run-time check to ensure that
-  /// this is actually true.
-  enum { NumLowBitsAvailable = 2 };
-};
-
-// Provide PointerLikeTypeTraits for const things.
-template <typename T> struct PointerLikeTypeTraits<const T> {
-  typedef PointerLikeTypeTraits<T> NonConst;
-
-  static inline const void *getAsVoidPointer(const T P) {
-    return NonConst::getAsVoidPointer(P);
-  }
-  static inline const T getFromVoidPointer(const void *P) {
-    return NonConst::getFromVoidPointer(const_cast<void *>(P));
-  }
-  enum { NumLowBitsAvailable = NonConst::NumLowBitsAvailable };
-};
-
-// Provide PointerLikeTypeTraits for const pointers.
-template <typename T> struct PointerLikeTypeTraits<const T *> {
-  typedef PointerLikeTypeTraits<T *> NonConst;
-
-  static inline const void *getAsVoidPointer(const T *P) {
-    return NonConst::getAsVoidPointer(const_cast<T *>(P));
-  }
-  static inline const T *getFromVoidPointer(const void *P) {
-    return NonConst::getFromVoidPointer(const_cast<void *>(P));
-  }
-  enum { NumLowBitsAvailable = NonConst::NumLowBitsAvailable };
-};
-
-// Provide PointerLikeTypeTraits for uintptr_t.
-template <> struct PointerLikeTypeTraits<uintptr_t> {
-  static inline void *getAsVoidPointer(uintptr_t P) {
-    return reinterpret_cast<void *>(P);
-  }
-  static inline uintptr_t getFromVoidPointer(void *P) {
-    return reinterpret_cast<uintptr_t>(P);
-  }
-  // No bits are available!
-  enum { NumLowBitsAvailable = 0 };
-};
-
-/// Provide suitable custom traits struct for function pointers.
-///
-/// Function pointers can't be directly given these traits as functions can't
-/// have their alignment computed with `alignof` and we need different casting.
-///
-/// To rely on higher alignment for a specialized use, you can provide a
-/// customized form of this template explicitly with higher alignment, and
-/// potentially use alignment attributes on functions to satisfy that.
-template <int Alignment, typename FunctionPointerT>
-struct FunctionPointerLikeTypeTraits {
-  enum { NumLowBitsAvailable = detail::ConstantLog2<Alignment>::value };
-  static inline void *getAsVoidPointer(FunctionPointerT P) {
-    assert((reinterpret_cast<uintptr_t>(P) &
-            ~((uintptr_t)-1 << NumLowBitsAvailable)) == 0 &&
-           "Alignment not satisfied for an actual function pointer!");
-    return reinterpret_cast<void *>(P);
-  }
-  static inline FunctionPointerT getFromVoidPointer(void *P) {
-    return reinterpret_cast<FunctionPointerT>(P);
-  }
-};
-
-/// Provide a default specialization for function pointers that assumes 4-byte
-/// alignment.
-///
-/// We assume here that functions used with this are always at least 4-byte
-/// aligned. This means that, for example, thumb functions won't work or systems
-/// with weird unaligned function pointers won't work. But all practical systems
-/// we support satisfy this requirement.
-template <typename ReturnT, typename... ParamTs>
-struct PointerLikeTypeTraits<ReturnT (*)(ParamTs...)>
-    : FunctionPointerLikeTypeTraits<4, ReturnT (*)(ParamTs...)> {};
-
-} // end namespace wpi
-
-#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/PointerUnion.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/PointerUnion.h
deleted file mode 100644
index 8d6e580..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/PointerUnion.h
+++ /dev/null
@@ -1,491 +0,0 @@
-//===- llvm/ADT/PointerUnion.h - Discriminated Union of 2 Ptrs --*- C++ -*-===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-//
-// This file defines the PointerUnion class, which is a discriminated union of
-// pointer types.
-//
-//===----------------------------------------------------------------------===//
-
-#ifndef WPIUTIL_WPI_POINTERUNION_H
-#define WPIUTIL_WPI_POINTERUNION_H
-
-#include "wpi/DenseMapInfo.h"
-#include "wpi/PointerIntPair.h"
-#include "wpi/PointerLikeTypeTraits.h"
-#include <cassert>
-#include <cstddef>
-#include <cstdint>
-
-namespace wpi {
-
-template <typename T> struct PointerUnionTypeSelectorReturn {
-  using Return = T;
-};
-
-/// Get a type based on whether two types are the same or not.
-///
-/// For:
-///
-/// \code
-///   using Ret = typename PointerUnionTypeSelector<T1, T2, EQ, NE>::Return;
-/// \endcode
-///
-/// Ret will be EQ type if T1 is same as T2 or NE type otherwise.
-template <typename T1, typename T2, typename RET_EQ, typename RET_NE>
-struct PointerUnionTypeSelector {
-  using Return = typename PointerUnionTypeSelectorReturn<RET_NE>::Return;
-};
-
-template <typename T, typename RET_EQ, typename RET_NE>
-struct PointerUnionTypeSelector<T, T, RET_EQ, RET_NE> {
-  using Return = typename PointerUnionTypeSelectorReturn<RET_EQ>::Return;
-};
-
-template <typename T1, typename T2, typename RET_EQ, typename RET_NE>
-struct PointerUnionTypeSelectorReturn<
-    PointerUnionTypeSelector<T1, T2, RET_EQ, RET_NE>> {
-  using Return =
-      typename PointerUnionTypeSelector<T1, T2, RET_EQ, RET_NE>::Return;
-};
-
-/// Provide PointerLikeTypeTraits for void* that is used by PointerUnion
-/// for the two template arguments.
-template <typename PT1, typename PT2> class PointerUnionUIntTraits {
-public:
-  static inline void *getAsVoidPointer(void *P) { return P; }
-  static inline void *getFromVoidPointer(void *P) { return P; }
-
-  enum {
-    PT1BitsAv = (int)(PointerLikeTypeTraits<PT1>::NumLowBitsAvailable),
-    PT2BitsAv = (int)(PointerLikeTypeTraits<PT2>::NumLowBitsAvailable),
-    NumLowBitsAvailable = PT1BitsAv < PT2BitsAv ? PT1BitsAv : PT2BitsAv
-  };
-};
-
-/// A discriminated union of two pointer types, with the discriminator in the
-/// low bit of the pointer.
-///
-/// This implementation is extremely efficient in space due to leveraging the
-/// low bits of the pointer, while exposing a natural and type-safe API.
-///
-/// Common use patterns would be something like this:
-///    PointerUnion<int*, float*> P;
-///    P = (int*)0;
-///    printf("%d %d", P.is<int*>(), P.is<float*>());  // prints "1 0"
-///    X = P.get<int*>();     // ok.
-///    Y = P.get<float*>();   // runtime assertion failure.
-///    Z = P.get<double*>();  // compile time failure.
-///    P = (float*)0;
-///    Y = P.get<float*>();   // ok.
-///    X = P.get<int*>();     // runtime assertion failure.
-template <typename PT1, typename PT2> class PointerUnion {
-public:
-  using ValTy =
-      PointerIntPair<void *, 1, bool, PointerUnionUIntTraits<PT1, PT2>>;
-
-private:
-  ValTy Val;
-
-  struct IsPT1 {
-    static const int Num = 0;
-  };
-  struct IsPT2 {
-    static const int Num = 1;
-  };
-  template <typename T> struct UNION_DOESNT_CONTAIN_TYPE {};
-
-public:
-  PointerUnion() = default;
-  PointerUnion(PT1 V)
-      : Val(const_cast<void *>(
-            PointerLikeTypeTraits<PT1>::getAsVoidPointer(V))) {}
-  PointerUnion(PT2 V)
-      : Val(const_cast<void *>(PointerLikeTypeTraits<PT2>::getAsVoidPointer(V)),
-            1) {}
-
-  /// Test if the pointer held in the union is null, regardless of
-  /// which type it is.
-  bool isNull() const {
-    // Convert from the void* to one of the pointer types, to make sure that
-    // we recursively strip off low bits if we have a nested PointerUnion.
-    return !PointerLikeTypeTraits<PT1>::getFromVoidPointer(Val.getPointer());
-  }
-
-  explicit operator bool() const { return !isNull(); }
-
-  /// Test if the Union currently holds the type matching T.
-  template <typename T> int is() const {
-    using Ty = typename ::wpi::PointerUnionTypeSelector<
-        PT1, T, IsPT1,
-        ::wpi::PointerUnionTypeSelector<PT2, T, IsPT2,
-                                        UNION_DOESNT_CONTAIN_TYPE<T>>>::Return;
-    int TyNo = Ty::Num;
-    return static_cast<int>(Val.getInt()) == TyNo;
-  }
-
-  /// Returns the value of the specified pointer type.
-  ///
-  /// If the specified pointer type is incorrect, assert.
-  template <typename T> T get() const {
-    assert(is<T>() && "Invalid accessor called");
-    return PointerLikeTypeTraits<T>::getFromVoidPointer(Val.getPointer());
-  }
-
-  /// Returns the current pointer if it is of the specified pointer type,
-  /// otherwises returns null.
-  template <typename T> T dyn_cast() const {
-    if (is<T>())
-      return get<T>();
-    return T();
-  }
-
-  /// If the union is set to the first pointer type get an address pointing to
-  /// it.
-  PT1 const *getAddrOfPtr1() const {
-    return const_cast<PointerUnion *>(this)->getAddrOfPtr1();
-  }
-
-  /// If the union is set to the first pointer type get an address pointing to
-  /// it.
-  PT1 *getAddrOfPtr1() {
-    assert(is<PT1>() && "Val is not the first pointer");
-    assert(
-        get<PT1>() == Val.getPointer() &&
-        "Can't get the address because PointerLikeTypeTraits changes the ptr");
-    return const_cast<PT1 *>(
-        reinterpret_cast<const PT1 *>(Val.getAddrOfPointer()));
-  }
-
-  /// Assignment from nullptr which just clears the union.
-  const PointerUnion &operator=(std::nullptr_t) {
-    Val.initWithPointer(nullptr);
-    return *this;
-  }
-
-  /// Assignment operators - Allow assigning into this union from either
-  /// pointer type, setting the discriminator to remember what it came from.
-  const PointerUnion &operator=(const PT1 &RHS) {
-    Val.initWithPointer(
-        const_cast<void *>(PointerLikeTypeTraits<PT1>::getAsVoidPointer(RHS)));
-    return *this;
-  }
-  const PointerUnion &operator=(const PT2 &RHS) {
-    Val.setPointerAndInt(
-        const_cast<void *>(PointerLikeTypeTraits<PT2>::getAsVoidPointer(RHS)),
-        1);
-    return *this;
-  }
-
-  void *getOpaqueValue() const { return Val.getOpaqueValue(); }
-  static inline PointerUnion getFromOpaqueValue(void *VP) {
-    PointerUnion V;
-    V.Val = ValTy::getFromOpaqueValue(VP);
-    return V;
-  }
-};
-
-template <typename PT1, typename PT2>
-bool operator==(PointerUnion<PT1, PT2> lhs, PointerUnion<PT1, PT2> rhs) {
-  return lhs.getOpaqueValue() == rhs.getOpaqueValue();
-}
-
-template <typename PT1, typename PT2>
-bool operator!=(PointerUnion<PT1, PT2> lhs, PointerUnion<PT1, PT2> rhs) {
-  return lhs.getOpaqueValue() != rhs.getOpaqueValue();
-}
-
-template <typename PT1, typename PT2>
-bool operator<(PointerUnion<PT1, PT2> lhs, PointerUnion<PT1, PT2> rhs) {
-  return lhs.getOpaqueValue() < rhs.getOpaqueValue();
-}
-
-// Teach SmallPtrSet that PointerUnion is "basically a pointer", that has
-// # low bits available = min(PT1bits,PT2bits)-1.
-template <typename PT1, typename PT2>
-struct PointerLikeTypeTraits<PointerUnion<PT1, PT2>> {
-  static inline void *getAsVoidPointer(const PointerUnion<PT1, PT2> &P) {
-    return P.getOpaqueValue();
-  }
-
-  static inline PointerUnion<PT1, PT2> getFromVoidPointer(void *P) {
-    return PointerUnion<PT1, PT2>::getFromOpaqueValue(P);
-  }
-
-  // The number of bits available are the min of the two pointer types.
-  enum {
-    NumLowBitsAvailable = PointerLikeTypeTraits<
-        typename PointerUnion<PT1, PT2>::ValTy>::NumLowBitsAvailable
-  };
-};
-
-/// A pointer union of three pointer types. See documentation for PointerUnion
-/// for usage.
-template <typename PT1, typename PT2, typename PT3> class PointerUnion3 {
-public:
-  using InnerUnion = PointerUnion<PT1, PT2>;
-  using ValTy = PointerUnion<InnerUnion, PT3>;
-
-private:
-  ValTy Val;
-
-  struct IsInnerUnion {
-    ValTy Val;
-
-    IsInnerUnion(ValTy val) : Val(val) {}
-
-    template <typename T> int is() const {
-      return Val.template is<InnerUnion>() &&
-             Val.template get<InnerUnion>().template is<T>();
-    }
-
-    template <typename T> T get() const {
-      return Val.template get<InnerUnion>().template get<T>();
-    }
-  };
-
-  struct IsPT3 {
-    ValTy Val;
-
-    IsPT3(ValTy val) : Val(val) {}
-
-    template <typename T> int is() const { return Val.template is<T>(); }
-    template <typename T> T get() const { return Val.template get<T>(); }
-  };
-
-public:
-  PointerUnion3() = default;
-  PointerUnion3(PT1 V) { Val = InnerUnion(V); }
-  PointerUnion3(PT2 V) { Val = InnerUnion(V); }
-  PointerUnion3(PT3 V) { Val = V; }
-
-  /// Test if the pointer held in the union is null, regardless of
-  /// which type it is.
-  bool isNull() const { return Val.isNull(); }
-  explicit operator bool() const { return !isNull(); }
-
-  /// Test if the Union currently holds the type matching T.
-  template <typename T> int is() const {
-    // If T is PT1/PT2 choose IsInnerUnion otherwise choose IsPT3.
-    using Ty = typename ::wpi::PointerUnionTypeSelector<
-        PT1, T, IsInnerUnion,
-        ::wpi::PointerUnionTypeSelector<PT2, T, IsInnerUnion, IsPT3>>::Return;
-    return Ty(Val).template is<T>();
-  }
-
-  /// Returns the value of the specified pointer type.
-  ///
-  /// If the specified pointer type is incorrect, assert.
-  template <typename T> T get() const {
-    assert(is<T>() && "Invalid accessor called");
-    // If T is PT1/PT2 choose IsInnerUnion otherwise choose IsPT3.
-    using Ty = typename ::wpi::PointerUnionTypeSelector<
-        PT1, T, IsInnerUnion,
-        ::wpi::PointerUnionTypeSelector<PT2, T, IsInnerUnion, IsPT3>>::Return;
-    return Ty(Val).template get<T>();
-  }
-
-  /// Returns the current pointer if it is of the specified pointer type,
-  /// otherwises returns null.
-  template <typename T> T dyn_cast() const {
-    if (is<T>())
-      return get<T>();
-    return T();
-  }
-
-  /// Assignment from nullptr which just clears the union.
-  const PointerUnion3 &operator=(std::nullptr_t) {
-    Val = nullptr;
-    return *this;
-  }
-
-  /// Assignment operators - Allow assigning into this union from either
-  /// pointer type, setting the discriminator to remember what it came from.
-  const PointerUnion3 &operator=(const PT1 &RHS) {
-    Val = InnerUnion(RHS);
-    return *this;
-  }
-  const PointerUnion3 &operator=(const PT2 &RHS) {
-    Val = InnerUnion(RHS);
-    return *this;
-  }
-  const PointerUnion3 &operator=(const PT3 &RHS) {
-    Val = RHS;
-    return *this;
-  }
-
-  void *getOpaqueValue() const { return Val.getOpaqueValue(); }
-  static inline PointerUnion3 getFromOpaqueValue(void *VP) {
-    PointerUnion3 V;
-    V.Val = ValTy::getFromOpaqueValue(VP);
-    return V;
-  }
-};
-
-// Teach SmallPtrSet that PointerUnion3 is "basically a pointer", that has
-// # low bits available = min(PT1bits,PT2bits,PT2bits)-2.
-template <typename PT1, typename PT2, typename PT3>
-struct PointerLikeTypeTraits<PointerUnion3<PT1, PT2, PT3>> {
-  static inline void *getAsVoidPointer(const PointerUnion3<PT1, PT2, PT3> &P) {
-    return P.getOpaqueValue();
-  }
-
-  static inline PointerUnion3<PT1, PT2, PT3> getFromVoidPointer(void *P) {
-    return PointerUnion3<PT1, PT2, PT3>::getFromOpaqueValue(P);
-  }
-
-  // The number of bits available are the min of the two pointer types.
-  enum {
-    NumLowBitsAvailable = PointerLikeTypeTraits<
-        typename PointerUnion3<PT1, PT2, PT3>::ValTy>::NumLowBitsAvailable
-  };
-};
-
-template <typename PT1, typename PT2, typename PT3>
-bool operator<(PointerUnion3<PT1, PT2, PT3> lhs,
-               PointerUnion3<PT1, PT2, PT3> rhs) {
-  return lhs.getOpaqueValue() < rhs.getOpaqueValue();
-}
-
-/// A pointer union of four pointer types. See documentation for PointerUnion
-/// for usage.
-template <typename PT1, typename PT2, typename PT3, typename PT4>
-class PointerUnion4 {
-public:
-  using InnerUnion1 = PointerUnion<PT1, PT2>;
-  using InnerUnion2 = PointerUnion<PT3, PT4>;
-  using ValTy = PointerUnion<InnerUnion1, InnerUnion2>;
-
-private:
-  ValTy Val;
-
-public:
-  PointerUnion4() = default;
-  PointerUnion4(PT1 V) { Val = InnerUnion1(V); }
-  PointerUnion4(PT2 V) { Val = InnerUnion1(V); }
-  PointerUnion4(PT3 V) { Val = InnerUnion2(V); }
-  PointerUnion4(PT4 V) { Val = InnerUnion2(V); }
-
-  /// Test if the pointer held in the union is null, regardless of
-  /// which type it is.
-  bool isNull() const { return Val.isNull(); }
-  explicit operator bool() const { return !isNull(); }
-
-  /// Test if the Union currently holds the type matching T.
-  template <typename T> int is() const {
-    // If T is PT1/PT2 choose InnerUnion1 otherwise choose InnerUnion2.
-    using Ty = typename ::wpi::PointerUnionTypeSelector<
-        PT1, T, InnerUnion1,
-        ::wpi::PointerUnionTypeSelector<PT2, T, InnerUnion1,
-                                        InnerUnion2>>::Return;
-    return Val.template is<Ty>() && Val.template get<Ty>().template is<T>();
-  }
-
-  /// Returns the value of the specified pointer type.
-  ///
-  /// If the specified pointer type is incorrect, assert.
-  template <typename T> T get() const {
-    assert(is<T>() && "Invalid accessor called");
-    // If T is PT1/PT2 choose InnerUnion1 otherwise choose InnerUnion2.
-    using Ty = typename ::wpi::PointerUnionTypeSelector<
-        PT1, T, InnerUnion1,
-        ::wpi::PointerUnionTypeSelector<PT2, T, InnerUnion1,
-                                        InnerUnion2>>::Return;
-    return Val.template get<Ty>().template get<T>();
-  }
-
-  /// Returns the current pointer if it is of the specified pointer type,
-  /// otherwises returns null.
-  template <typename T> T dyn_cast() const {
-    if (is<T>())
-      return get<T>();
-    return T();
-  }
-
-  /// Assignment from nullptr which just clears the union.
-  const PointerUnion4 &operator=(std::nullptr_t) {
-    Val = nullptr;
-    return *this;
-  }
-
-  /// Assignment operators - Allow assigning into this union from either
-  /// pointer type, setting the discriminator to remember what it came from.
-  const PointerUnion4 &operator=(const PT1 &RHS) {
-    Val = InnerUnion1(RHS);
-    return *this;
-  }
-  const PointerUnion4 &operator=(const PT2 &RHS) {
-    Val = InnerUnion1(RHS);
-    return *this;
-  }
-  const PointerUnion4 &operator=(const PT3 &RHS) {
-    Val = InnerUnion2(RHS);
-    return *this;
-  }
-  const PointerUnion4 &operator=(const PT4 &RHS) {
-    Val = InnerUnion2(RHS);
-    return *this;
-  }
-
-  void *getOpaqueValue() const { return Val.getOpaqueValue(); }
-  static inline PointerUnion4 getFromOpaqueValue(void *VP) {
-    PointerUnion4 V;
-    V.Val = ValTy::getFromOpaqueValue(VP);
-    return V;
-  }
-};
-
-// Teach SmallPtrSet that PointerUnion4 is "basically a pointer", that has
-// # low bits available = min(PT1bits,PT2bits,PT2bits)-2.
-template <typename PT1, typename PT2, typename PT3, typename PT4>
-struct PointerLikeTypeTraits<PointerUnion4<PT1, PT2, PT3, PT4>> {
-  static inline void *
-  getAsVoidPointer(const PointerUnion4<PT1, PT2, PT3, PT4> &P) {
-    return P.getOpaqueValue();
-  }
-
-  static inline PointerUnion4<PT1, PT2, PT3, PT4> getFromVoidPointer(void *P) {
-    return PointerUnion4<PT1, PT2, PT3, PT4>::getFromOpaqueValue(P);
-  }
-
-  // The number of bits available are the min of the two pointer types.
-  enum {
-    NumLowBitsAvailable = PointerLikeTypeTraits<
-        typename PointerUnion4<PT1, PT2, PT3, PT4>::ValTy>::NumLowBitsAvailable
-  };
-};
-
-// Teach DenseMap how to use PointerUnions as keys.
-template <typename T, typename U> struct DenseMapInfo<PointerUnion<T, U>> {
-  using Pair = PointerUnion<T, U>;
-  using FirstInfo = DenseMapInfo<T>;
-  using SecondInfo = DenseMapInfo<U>;
-
-  static inline Pair getEmptyKey() { return Pair(FirstInfo::getEmptyKey()); }
-
-  static inline Pair getTombstoneKey() {
-    return Pair(FirstInfo::getTombstoneKey());
-  }
-
-  static unsigned getHashValue(const Pair &PairVal) {
-    intptr_t key = (intptr_t)PairVal.getOpaqueValue();
-    return DenseMapInfo<intptr_t>::getHashValue(key);
-  }
-
-  static bool isEqual(const Pair &LHS, const Pair &RHS) {
-    return LHS.template is<T>() == RHS.template is<T>() &&
-           (LHS.template is<T>() ? FirstInfo::isEqual(LHS.template get<T>(),
-                                                      RHS.template get<T>())
-                                 : SecondInfo::isEqual(LHS.template get<U>(),
-                                                       RHS.template get<U>()));
-  }
-};
-
-} // end namespace wpi
-
-#endif // WPIUTIL_WPI_POINTERUNION_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/PortForwarder.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/PortForwarder.h
deleted file mode 100644
index 9e445a0..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/PortForwarder.h
+++ /dev/null
@@ -1,59 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_PORTFORWARDER_H_
-#define WPIUTIL_WPI_PORTFORWARDER_H_
-
-#pragma once
-
-#include <memory>
-#include <string_view>
-
-namespace wpi {
-
-/**
- * Forward ports to another host.  This is primarily useful for accessing
- * Ethernet-connected devices from a computer tethered to the RoboRIO USB port.
- */
-class PortForwarder {
- public:
-  PortForwarder(const PortForwarder&) = delete;
-  PortForwarder& operator=(const PortForwarder&) = delete;
-
-  /**
-   * Get an instance of the PortForwarder class.
-   *
-   * This is a singleton to guarantee that there is only a single instance
-   * regardless of how many times GetInstance is called.
-   */
-  static PortForwarder& GetInstance();
-
-  /**
-   * Forward a local TCP port to a remote host and port.
-   * Note that local ports less than 1024 won't work as a normal user.
-   *
-   * @param port       local port number
-   * @param remoteHost remote IP address / DNS name
-   * @param remotePort remote port number
-   */
-  void Add(unsigned int port, std::string_view remoteHost,
-           unsigned int remotePort);
-
-  /**
-   * Stop TCP forwarding on a port.
-   *
-   * @param port local port number
-   */
-  void Remove(unsigned int port);
-
- private:
-  PortForwarder();
-
-  struct Impl;
-  std::unique_ptr<Impl> m_impl;
-};
-
-}  // namespace wpi
-
-#endif  // WPIUTIL_WPI_PORTFORWARDER_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/SafeThread.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/SafeThread.h
index bf37732..753dc6c 100644
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/SafeThread.h
+++ b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/SafeThread.h
@@ -10,6 +10,7 @@
 #include <thread>
 #include <utility>
 
+#include "wpi/Synchronization.h"
 #include "wpi/condition_variable.h"
 #include "wpi/mutex.h"
 
@@ -18,17 +19,33 @@
 /**
  * Base class for SafeThreadOwner threads.
  */
-class SafeThread {
+class SafeThreadBase {
  public:
-  virtual ~SafeThread() = default;
+  virtual ~SafeThreadBase() = default;
   virtual void Main() = 0;
+  virtual void Stop() = 0;
 
   mutable wpi::mutex m_mutex;
   std::atomic_bool m_active{true};
-  wpi::condition_variable m_cond;
   std::thread::id m_threadId;
 };
 
+class SafeThread : public SafeThreadBase {
+ public:
+  void Stop() override;
+
+  wpi::condition_variable m_cond;
+};
+
+class SafeThreadEvent : public SafeThreadBase {
+ public:
+  SafeThreadEvent() : m_stopEvent{true} {}
+
+  void Stop() override;
+
+  Event m_stopEvent;
+};
+
 namespace detail {
 
 /**
@@ -36,12 +53,12 @@
  */
 class SafeThreadProxyBase {
  public:
-  explicit SafeThreadProxyBase(std::shared_ptr<SafeThread> thr);
+  explicit SafeThreadProxyBase(std::shared_ptr<SafeThreadBase> thr);
   explicit operator bool() const { return m_thread != nullptr; }
   std::unique_lock<wpi::mutex>& GetLock() { return m_lock; }
 
  protected:
-  std::shared_ptr<SafeThread> m_thread;
+  std::shared_ptr<SafeThreadBase> m_thread;
   std::unique_lock<wpi::mutex> m_lock;
 };
 
@@ -53,7 +70,7 @@
 template <typename T>
 class SafeThreadProxy : public SafeThreadProxyBase {
  public:
-  explicit SafeThreadProxy(std::shared_ptr<SafeThread> thr)
+  explicit SafeThreadProxy(std::shared_ptr<SafeThreadBase> thr)
       : SafeThreadProxyBase(std::move(thr)) {}
   T& operator*() const { return *static_cast<T*>(m_thread.get()); }
   T* operator->() const { return static_cast<T*>(m_thread.get()); }
@@ -89,13 +106,13 @@
   void SetJoinAtExit(bool joinAtExit) { m_joinAtExit = joinAtExit; }
 
  protected:
-  void Start(std::shared_ptr<SafeThread> thr);
-  std::shared_ptr<SafeThread> GetThreadSharedPtr() const;
+  void Start(std::shared_ptr<SafeThreadBase> thr);
+  std::shared_ptr<SafeThreadBase> GetThreadSharedPtr() const;
 
  private:
   mutable wpi::mutex m_mutex;
   std::thread m_stdThread;
-  std::weak_ptr<SafeThread> m_thread;
+  std::weak_ptr<SafeThreadBase> m_thread;
   std::atomic_bool m_joinAtExit{true};
 };
 
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/SmallPtrSet.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/SmallPtrSet.h
deleted file mode 100644
index 8669527..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/SmallPtrSet.h
+++ /dev/null
@@ -1,463 +0,0 @@
-//===- llvm/ADT/SmallPtrSet.h - 'Normally small' pointer set ----*- C++ -*-===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-//
-// This file defines the SmallPtrSet class.  See the doxygen comment for
-// SmallPtrSetImplBase for more details on the algorithm used.
-//
-//===----------------------------------------------------------------------===//
-
-#ifndef WPIUTIL_WPI_SMALLPTRSET_H
-#define WPIUTIL_WPI_SMALLPTRSET_H
-
-#include "wpi/Compiler.h"
-#include "wpi/PointerLikeTypeTraits.h"
-#include "wpi/type_traits.h"
-#include <cassert>
-#include <cstddef>
-#include <cstdint>
-#include <cstdlib>
-#include <cstring>
-#include <initializer_list>
-#include <iterator>
-#include <utility>
-
-namespace wpi {
-
-/// SmallPtrSetImplBase - This is the common code shared among all the
-/// SmallPtrSet<>'s, which is almost everything.  SmallPtrSet has two modes, one
-/// for small and one for large sets.
-///
-/// Small sets use an array of pointers allocated in the SmallPtrSet object,
-/// which is treated as a simple array of pointers.  When a pointer is added to
-/// the set, the array is scanned to see if the element already exists, if not
-/// the element is 'pushed back' onto the array.  If we run out of space in the
-/// array, we grow into the 'large set' case.  SmallSet should be used when the
-/// sets are often small.  In this case, no memory allocation is used, and only
-/// light-weight and cache-efficient scanning is used.
-///
-/// Large sets use a classic exponentially-probed hash table.  Empty buckets are
-/// represented with an illegal pointer value (-1) to allow null pointers to be
-/// inserted.  Tombstones are represented with another illegal pointer value
-/// (-2), to allow deletion.  The hash table is resized when the table is 3/4 or
-/// more.  When this happens, the table is doubled in size.
-///
-class SmallPtrSetImplBase {
-  friend class SmallPtrSetIteratorImpl;
-
-protected:
-  /// SmallArray - Points to a fixed size set of buckets, used in 'small mode'.
-  const void **SmallArray;
-  /// CurArray - This is the current set of buckets.  If equal to SmallArray,
-  /// then the set is in 'small mode'.
-  const void **CurArray;
-  /// CurArraySize - The allocated size of CurArray, always a power of two.
-  unsigned CurArraySize;
-
-  /// Number of elements in CurArray that contain a value or are a tombstone.
-  /// If small, all these elements are at the beginning of CurArray and the rest
-  /// is uninitialized.
-  unsigned NumNonEmpty;
-  /// Number of tombstones in CurArray.
-  unsigned NumTombstones;
-
-  // Helpers to copy and move construct a SmallPtrSet.
-  SmallPtrSetImplBase(const void **SmallStorage,
-                      const SmallPtrSetImplBase &that);
-  SmallPtrSetImplBase(const void **SmallStorage, unsigned SmallSize,
-                      SmallPtrSetImplBase &&that);
-
-  explicit SmallPtrSetImplBase(const void **SmallStorage, unsigned SmallSize)
-      : SmallArray(SmallStorage), CurArray(SmallStorage),
-        CurArraySize(SmallSize), NumNonEmpty(0), NumTombstones(0) {
-    assert(SmallSize && (SmallSize & (SmallSize-1)) == 0 &&
-           "Initial size must be a power of two!");
-  }
-
-  ~SmallPtrSetImplBase() {
-    if (!isSmall())
-      free(CurArray);
-  }
-
-public:
-  using size_type = unsigned;
-
-  SmallPtrSetImplBase &operator=(const SmallPtrSetImplBase &) = delete;
-
-  LLVM_NODISCARD bool empty() const { return size() == 0; }
-  size_type size() const { return NumNonEmpty - NumTombstones; }
-
-  void clear() {
-    // If the capacity of the array is huge, and the # elements used is small,
-    // shrink the array.
-    if (!isSmall()) {
-      if (size() * 4 < CurArraySize && CurArraySize > 32)
-        return shrink_and_clear();
-      // Fill the array with empty markers.
-      memset(CurArray, -1, CurArraySize * sizeof(void *));
-    }
-
-    NumNonEmpty = 0;
-    NumTombstones = 0;
-  }
-
-protected:
-  static void *getTombstoneMarker() { return reinterpret_cast<void*>(-2); }
-
-  static void *getEmptyMarker() {
-    // Note that -1 is chosen to make clear() efficiently implementable with
-    // memset and because it's not a valid pointer value.
-    return reinterpret_cast<void*>(-1);
-  }
-
-  const void **EndPointer() const {
-    return isSmall() ? CurArray + NumNonEmpty : CurArray + CurArraySize;
-  }
-
-  /// insert_imp - This returns true if the pointer was new to the set, false if
-  /// it was already in the set.  This is hidden from the client so that the
-  /// derived class can check that the right type of pointer is passed in.
-  std::pair<const void *const *, bool> insert_imp(const void *Ptr) {
-    if (isSmall()) {
-      // Check to see if it is already in the set.
-      const void **LastTombstone = nullptr;
-      for (const void **APtr = SmallArray, **E = SmallArray + NumNonEmpty;
-           APtr != E; ++APtr) {
-        const void *Value = *APtr;
-        if (Value == Ptr)
-          return std::make_pair(APtr, false);
-        if (Value == getTombstoneMarker())
-          LastTombstone = APtr;
-      }
-
-      // Did we find any tombstone marker?
-      if (LastTombstone != nullptr) {
-        *LastTombstone = Ptr;
-        --NumTombstones;
-        return std::make_pair(LastTombstone, true);
-      }
-
-      // Nope, there isn't.  If we stay small, just 'pushback' now.
-      if (NumNonEmpty < CurArraySize) {
-        SmallArray[NumNonEmpty++] = Ptr;
-        return std::make_pair(SmallArray + (NumNonEmpty - 1), true);
-      }
-      // Otherwise, hit the big set case, which will call grow.
-    }
-    return insert_imp_big(Ptr);
-  }
-
-  /// erase_imp - If the set contains the specified pointer, remove it and
-  /// return true, otherwise return false.  This is hidden from the client so
-  /// that the derived class can check that the right type of pointer is passed
-  /// in.
-  bool erase_imp(const void * Ptr) {
-    const void *const *P = find_imp(Ptr);
-    if (P == EndPointer())
-      return false;
-
-    const void **Loc = const_cast<const void **>(P);
-    assert(*Loc == Ptr && "broken find!");
-    *Loc = getTombstoneMarker();
-    NumTombstones++;
-    return true;
-  }
-
-  /// Returns the raw pointer needed to construct an iterator.  If element not
-  /// found, this will be EndPointer.  Otherwise, it will be a pointer to the
-  /// slot which stores Ptr;
-  const void *const * find_imp(const void * Ptr) const {
-    if (isSmall()) {
-      // Linear search for the item.
-      for (const void *const *APtr = SmallArray,
-                      *const *E = SmallArray + NumNonEmpty; APtr != E; ++APtr)
-        if (*APtr == Ptr)
-          return APtr;
-      return EndPointer();
-    }
-
-    // Big set case.
-    auto *Bucket = FindBucketFor(Ptr);
-    if (*Bucket == Ptr)
-      return Bucket;
-    return EndPointer();
-  }
-
-private:
-  bool isSmall() const { return CurArray == SmallArray; }
-
-  std::pair<const void *const *, bool> insert_imp_big(const void *Ptr);
-
-  const void * const *FindBucketFor(const void *Ptr) const;
-  void shrink_and_clear();
-
-  /// Grow - Allocate a larger backing store for the buckets and move it over.
-  void Grow(unsigned NewSize);
-
-protected:
-  /// swap - Swaps the elements of two sets.
-  /// Note: This method assumes that both sets have the same small size.
-  void swap(SmallPtrSetImplBase &RHS);
-
-  void CopyFrom(const SmallPtrSetImplBase &RHS);
-  void MoveFrom(unsigned SmallSize, SmallPtrSetImplBase &&RHS);
-
-private:
-  /// Code shared by MoveFrom() and move constructor.
-  void MoveHelper(unsigned SmallSize, SmallPtrSetImplBase &&RHS);
-  /// Code shared by CopyFrom() and copy constructor.
-  void CopyHelper(const SmallPtrSetImplBase &RHS);
-};
-
-/// SmallPtrSetIteratorImpl - This is the common base class shared between all
-/// instances of SmallPtrSetIterator.
-class SmallPtrSetIteratorImpl {
-protected:
-  const void *const *Bucket;
-  const void *const *End;
-
-public:
-  explicit SmallPtrSetIteratorImpl(const void *const *BP, const void*const *E)
-    : Bucket(BP), End(E) {
-    AdvanceIfNotValid();
-  }
-
-  bool operator==(const SmallPtrSetIteratorImpl &RHS) const {
-    return Bucket == RHS.Bucket;
-  }
-  bool operator!=(const SmallPtrSetIteratorImpl &RHS) const {
-    return Bucket != RHS.Bucket;
-  }
-
-protected:
-  /// AdvanceIfNotValid - If the current bucket isn't valid, advance to a bucket
-  /// that is.   This is guaranteed to stop because the end() bucket is marked
-  /// valid.
-  void AdvanceIfNotValid() {
-    assert(Bucket <= End);
-    while (Bucket != End &&
-           (*Bucket == SmallPtrSetImplBase::getEmptyMarker() ||
-            *Bucket == SmallPtrSetImplBase::getTombstoneMarker()))
-      ++Bucket;
-  }
-  void RetreatIfNotValid() {
-    assert(Bucket >= End);
-    while (Bucket != End &&
-           (Bucket[-1] == SmallPtrSetImplBase::getEmptyMarker() ||
-            Bucket[-1] == SmallPtrSetImplBase::getTombstoneMarker())) {
-      --Bucket;
-    }
-  }
-};
-
-/// SmallPtrSetIterator - This implements a const_iterator for SmallPtrSet.
-template <typename PtrTy>
-class SmallPtrSetIterator : public SmallPtrSetIteratorImpl {
-  using PtrTraits = PointerLikeTypeTraits<PtrTy>;
-
-public:
-  using value_type = PtrTy;
-  using reference = PtrTy;
-  using pointer = PtrTy;
-  using difference_type = std::ptrdiff_t;
-  using iterator_category = std::forward_iterator_tag;
-
-  explicit SmallPtrSetIterator(const void *const *BP, const void *const *E)
-      : SmallPtrSetIteratorImpl(BP, E) {}
-
-  // Most methods provided by baseclass.
-
-  const PtrTy operator*() const {
-    assert(Bucket < End);
-    return PtrTraits::getFromVoidPointer(const_cast<void*>(*Bucket));
-  }
-
-  inline SmallPtrSetIterator& operator++() {          // Preincrement
-    ++Bucket;
-    AdvanceIfNotValid();
-    return *this;
-  }
-
-  SmallPtrSetIterator operator++(int) {        // Postincrement
-    SmallPtrSetIterator tmp = *this;
-    ++*this;
-    return tmp;
-  }
-};
-
-/// RoundUpToPowerOfTwo - This is a helper template that rounds N up to the next
-/// power of two (which means N itself if N is already a power of two).
-template<unsigned N>
-struct RoundUpToPowerOfTwo;
-
-/// RoundUpToPowerOfTwoH - If N is not a power of two, increase it.  This is a
-/// helper template used to implement RoundUpToPowerOfTwo.
-template<unsigned N, bool isPowerTwo>
-struct RoundUpToPowerOfTwoH {
-  enum { Val = N };
-};
-template<unsigned N>
-struct RoundUpToPowerOfTwoH<N, false> {
-  enum {
-    // We could just use NextVal = N+1, but this converges faster.  N|(N-1) sets
-    // the right-most zero bits to one all at once, e.g. 0b0011000 -> 0b0011111.
-    Val = RoundUpToPowerOfTwo<(N|(N-1)) + 1>::Val
-  };
-};
-
-template<unsigned N>
-struct RoundUpToPowerOfTwo {
-  enum { Val = RoundUpToPowerOfTwoH<N, (N&(N-1)) == 0>::Val };
-};
-
-/// A templated base class for \c SmallPtrSet which provides the
-/// typesafe interface that is common across all small sizes.
-///
-/// This is particularly useful for passing around between interface boundaries
-/// to avoid encoding a particular small size in the interface boundary.
-template <typename PtrType>
-class SmallPtrSetImpl : public SmallPtrSetImplBase {
-  using ConstPtrType = typename add_const_past_pointer<PtrType>::type;
-  using PtrTraits = PointerLikeTypeTraits<PtrType>;
-  using ConstPtrTraits = PointerLikeTypeTraits<ConstPtrType>;
-
-protected:
-  // Constructors that forward to the base.
-  SmallPtrSetImpl(const void **SmallStorage, const SmallPtrSetImpl &that)
-      : SmallPtrSetImplBase(SmallStorage, that) {}
-  SmallPtrSetImpl(const void **SmallStorage, unsigned SmallSize,
-                  SmallPtrSetImpl &&that)
-      : SmallPtrSetImplBase(SmallStorage, SmallSize, std::move(that)) {}
-  explicit SmallPtrSetImpl(const void **SmallStorage, unsigned SmallSize)
-      : SmallPtrSetImplBase(SmallStorage, SmallSize) {}
-
-public:
-  using iterator = SmallPtrSetIterator<PtrType>;
-  using const_iterator = SmallPtrSetIterator<PtrType>;
-  using key_type = ConstPtrType;
-  using value_type = PtrType;
-
-  SmallPtrSetImpl(const SmallPtrSetImpl &) = delete;
-
-  /// Inserts Ptr if and only if there is no element in the container equal to
-  /// Ptr. The bool component of the returned pair is true if and only if the
-  /// insertion takes place, and the iterator component of the pair points to
-  /// the element equal to Ptr.
-  std::pair<iterator, bool> insert(PtrType Ptr) {
-    auto p = insert_imp(PtrTraits::getAsVoidPointer(Ptr));
-    return std::make_pair(makeIterator(p.first), p.second);
-  }
-
-  /// erase - If the set contains the specified pointer, remove it and return
-  /// true, otherwise return false.
-  bool erase(PtrType Ptr) {
-    return erase_imp(PtrTraits::getAsVoidPointer(Ptr));
-  }
-
-  /// count - Return 1 if the specified pointer is in the set, 0 otherwise.
-  size_type count(ConstPtrType Ptr) const { return find(Ptr) != end() ? 1 : 0; }
-  iterator find(ConstPtrType Ptr) const {
-    return makeIterator(find_imp(ConstPtrTraits::getAsVoidPointer(Ptr)));
-  }
-
-  template <typename IterT>
-  void insert(IterT I, IterT E) {
-    for (; I != E; ++I)
-      insert(*I);
-  }
-
-  void insert(std::initializer_list<PtrType> IL) {
-    insert(IL.begin(), IL.end());
-  }
-
-  iterator begin() const {
-    return makeIterator(CurArray);
-  }
-  iterator end() const { return makeIterator(EndPointer()); }
-
-private:
-  /// Create an iterator that dereferences to same place as the given pointer.
-  iterator makeIterator(const void *const *P) const {
-    return iterator(P, EndPointer());
-  }
-};
-
-/// SmallPtrSet - This class implements a set which is optimized for holding
-/// SmallSize or less elements.  This internally rounds up SmallSize to the next
-/// power of two if it is not already a power of two.  See the comments above
-/// SmallPtrSetImplBase for details of the algorithm.
-template<class PtrType, unsigned SmallSize>
-class SmallPtrSet : public SmallPtrSetImpl<PtrType> {
-  // In small mode SmallPtrSet uses linear search for the elements, so it is
-  // not a good idea to choose this value too high. You may consider using a
-  // DenseSet<> instead if you expect many elements in the set.
-  static_assert(SmallSize <= 32, "SmallSize should be small");
-
-  using BaseT = SmallPtrSetImpl<PtrType>;
-
-  // Make sure that SmallSize is a power of two, round up if not.
-  enum { SmallSizePowTwo = RoundUpToPowerOfTwo<SmallSize>::Val };
-  /// SmallStorage - Fixed size storage used in 'small mode'.
-  const void *SmallStorage[SmallSizePowTwo];
-
-public:
-  SmallPtrSet() : BaseT(SmallStorage, SmallSizePowTwo) {}
-  SmallPtrSet(const SmallPtrSet &that) : BaseT(SmallStorage, that) {}
-  SmallPtrSet(SmallPtrSet &&that)
-      : BaseT(SmallStorage, SmallSizePowTwo, std::move(that)) {}
-
-  template<typename It>
-  SmallPtrSet(It I, It E) : BaseT(SmallStorage, SmallSizePowTwo) {
-    this->insert(I, E);
-  }
-
-  SmallPtrSet(std::initializer_list<PtrType> IL)
-      : BaseT(SmallStorage, SmallSizePowTwo) {
-    this->insert(IL.begin(), IL.end());
-  }
-
-  SmallPtrSet<PtrType, SmallSize> &
-  operator=(const SmallPtrSet<PtrType, SmallSize> &RHS) {
-    if (&RHS != this)
-      this->CopyFrom(RHS);
-    return *this;
-  }
-
-  SmallPtrSet<PtrType, SmallSize> &
-  operator=(SmallPtrSet<PtrType, SmallSize> &&RHS) {
-    if (&RHS != this)
-      this->MoveFrom(SmallSizePowTwo, std::move(RHS));
-    return *this;
-  }
-
-  SmallPtrSet<PtrType, SmallSize> &
-  operator=(std::initializer_list<PtrType> IL) {
-    this->clear();
-    this->insert(IL.begin(), IL.end());
-    return *this;
-  }
-
-  /// swap - Swaps the elements of two sets.
-  void swap(SmallPtrSet<PtrType, SmallSize> &RHS) {
-    SmallPtrSetImplBase::swap(RHS);
-  }
-};
-
-} // end namespace wpi
-
-namespace std {
-
-  /// Implement std::swap in terms of SmallPtrSet swap.
-  template<class T, unsigned N>
-  inline void swap(wpi::SmallPtrSet<T, N> &LHS, wpi::SmallPtrSet<T, N> &RHS) {
-    LHS.swap(RHS);
-  }
-
-} // end namespace std
-
-#endif // LLVM_ADT_SMALLPTRSET_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/SmallSet.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/SmallSet.h
deleted file mode 100644
index dca204e..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/SmallSet.h
+++ /dev/null
@@ -1,254 +0,0 @@
-//===- llvm/ADT/SmallSet.h - 'Normally small' sets --------------*- C++ -*-===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-//
-// This file defines the SmallSet class.
-//
-//===----------------------------------------------------------------------===//
-
-#ifndef WPIUTIL_WPI_SMALLSET_H
-#define WPIUTIL_WPI_SMALLSET_H
-
-#include "wpi/SmallPtrSet.h"
-#include "wpi/SmallVector.h"
-#include "wpi/Compiler.h"
-#include "wpi/iterator.h"
-#include "wpi/type_traits.h"
-#include <cstddef>
-#include <functional>
-#include <optional>
-#include <set>
-#include <type_traits>
-#include <utility>
-
-namespace wpi {
-
-/// SmallSetIterator - This class implements a const_iterator for SmallSet by
-/// delegating to the underlying SmallVector or Set iterators.
-template <typename T, unsigned N, typename C>
-class SmallSetIterator
-    : public iterator_facade_base<SmallSetIterator<T, N, C>,
-                                  std::forward_iterator_tag, T> {
-private:
-  using SetIterTy = typename std::set<T, C>::const_iterator;
-  using VecIterTy = typename SmallVector<T, N>::const_iterator;
-  using SelfTy = SmallSetIterator<T, N, C>;
-
-  /// Iterators to the parts of the SmallSet containing the data. They are set
-  /// depending on isSmall.
-  union {
-    SetIterTy SetIter;
-    VecIterTy VecIter;
-  };
-
-  bool isSmall;
-
-public:
-  SmallSetIterator(SetIterTy SetIter) : SetIter(SetIter), isSmall(false) {}
-
-  SmallSetIterator(VecIterTy VecIter) : VecIter(VecIter), isSmall(true) {}
-
-  // Spell out destructor, copy/move constructor and assignment operators for
-  // MSVC STL, where set<T>::const_iterator is not trivially copy constructible.
-  ~SmallSetIterator() {
-    if (isSmall)
-      VecIter.~VecIterTy();
-    else
-      SetIter.~SetIterTy();
-  }
-
-  SmallSetIterator(const SmallSetIterator &Other) : isSmall(Other.isSmall) {
-    if (isSmall)
-      VecIter = Other.VecIter;
-    else
-      // Use placement new, to make sure SetIter is properly constructed, even
-      // if it is not trivially copy-able (e.g. in MSVC).
-      new (&SetIter) SetIterTy(Other.SetIter);
-  }
-
-  SmallSetIterator(SmallSetIterator &&Other) : isSmall(Other.isSmall) {
-    if (isSmall)
-      VecIter = std::move(Other.VecIter);
-    else
-      // Use placement new, to make sure SetIter is properly constructed, even
-      // if it is not trivially copy-able (e.g. in MSVC).
-      new (&SetIter) SetIterTy(std::move(Other.SetIter));
-  }
-
-  SmallSetIterator& operator=(const SmallSetIterator& Other) {
-    // Call destructor for SetIter, so it gets properly destroyed if it is
-    // not trivially destructible in case we are setting VecIter.
-    if (!isSmall)
-      SetIter.~SetIterTy();
-
-    isSmall = Other.isSmall;
-    if (isSmall)
-      VecIter = Other.VecIter;
-    else
-      new (&SetIter) SetIterTy(Other.SetIter);
-    return *this;
-  }
-
-  SmallSetIterator& operator=(SmallSetIterator&& Other) {
-    // Call destructor for SetIter, so it gets properly destroyed if it is
-    // not trivially destructible in case we are setting VecIter.
-    if (!isSmall)
-      SetIter.~SetIterTy();
-
-    isSmall = Other.isSmall;
-    if (isSmall)
-      VecIter = std::move(Other.VecIter);
-    else
-      new (&SetIter) SetIterTy(std::move(Other.SetIter));
-    return *this;
-  }
-
-  bool operator==(const SmallSetIterator &RHS) const {
-    if (isSmall != RHS.isSmall)
-      return false;
-    if (isSmall)
-      return VecIter == RHS.VecIter;
-    return SetIter == RHS.SetIter;
-  }
-
-  SmallSetIterator &operator++() { // Preincrement
-    if (isSmall)
-      VecIter++;
-    else
-      SetIter++;
-    return *this;
-  }
-
-  const T &operator*() const { return isSmall ? *VecIter : *SetIter; }
-};
-
-/// SmallSet - This maintains a set of unique values, optimizing for the case
-/// when the set is small (less than N).  In this case, the set can be
-/// maintained with no mallocs.  If the set gets large, we expand to using an
-/// std::set to maintain reasonable lookup times.
-template <typename T, unsigned N, typename C = std::less<T>>
-class SmallSet {
-  /// Use a SmallVector to hold the elements here (even though it will never
-  /// reach its 'large' stage) to avoid calling the default ctors of elements
-  /// we will never use.
-  SmallVector<T, N> Vector;
-  std::set<T, C> Set;
-
-  using VIterator = typename SmallVector<T, N>::const_iterator;
-  using mutable_iterator = typename SmallVector<T, N>::iterator;
-
-  // In small mode SmallPtrSet uses linear search for the elements, so it is
-  // not a good idea to choose this value too high. You may consider using a
-  // DenseSet<> instead if you expect many elements in the set.
-  static_assert(N <= 32, "N should be small");
-
-public:
-  using size_type = size_t;
-  using const_iterator = SmallSetIterator<T, N, C>;
-
-  SmallSet() = default;
-
-  LLVM_NODISCARD bool empty() const {
-    return Vector.empty() && Set.empty();
-  }
-
-  size_type size() const {
-    return isSmall() ? Vector.size() : Set.size();
-  }
-
-  /// count - Return 1 if the element is in the set, 0 otherwise.
-  size_type count(const T &V) const {
-    if (isSmall()) {
-      // Since the collection is small, just do a linear search.
-      return vfind(V) == Vector.end() ? 0 : 1;
-    } else {
-      return Set.count(V);
-    }
-  }
-
-  /// insert - Insert an element into the set if it isn't already there.
-  /// Returns true if the element is inserted (it was not in the set before).
-  /// The first value of the returned pair is unused and provided for
-  /// partial compatibility with the standard library self-associative container
-  /// concept.
-  // FIXME: Add iterators that abstract over the small and large form, and then
-  // return those here.
-  std::pair<std::nullopt_t, bool> insert(const T &V) {
-    if (!isSmall())
-      return std::make_pair(std::nullopt, Set.insert(V).second);
-
-    VIterator I = vfind(V);
-    if (I != Vector.end())    // Don't reinsert if it already exists.
-      return std::make_pair(std::nullopt, false);
-    if (Vector.size() < N) {
-      Vector.push_back(V);
-      return std::make_pair(std::nullopt, true);
-    }
-
-    // Otherwise, grow from vector to set.
-    while (!Vector.empty()) {
-      Set.insert(Vector.back());
-      Vector.pop_back();
-    }
-    Set.insert(V);
-    return std::make_pair(std::nullopt, true);
-  }
-
-  template <typename IterT>
-  void insert(IterT I, IterT E) {
-    for (; I != E; ++I)
-      insert(*I);
-  }
-
-  bool erase(const T &V) {
-    if (!isSmall())
-      return Set.erase(V);
-    for (mutable_iterator I = Vector.begin(), E = Vector.end(); I != E; ++I)
-      if (*I == V) {
-        Vector.erase(I);
-        return true;
-      }
-    return false;
-  }
-
-  void clear() {
-    Vector.clear();
-    Set.clear();
-  }
-
-  const_iterator begin() const {
-    if (isSmall())
-      return {Vector.begin()};
-    return {Set.begin()};
-  }
-
-  const_iterator end() const {
-    if (isSmall())
-      return {Vector.end()};
-    return {Set.end()};
-  }
-
-private:
-  bool isSmall() const { return Set.empty(); }
-
-  VIterator vfind(const T &V) const {
-    for (VIterator I = Vector.begin(), E = Vector.end(); I != E; ++I)
-      if (*I == V)
-        return I;
-    return Vector.end();
-  }
-};
-
-/// If this set is of pointer values, transparently switch over to using
-/// SmallPtrSet for performance.
-template <typename PointeeType, unsigned N>
-class SmallSet<PointeeType*, N> : public SmallPtrSet<PointeeType*, N> {};
-
-} // end namespace wpi
-
-#endif // LLVM_ADT_SMALLSET_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/SmallString.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/SmallString.h
deleted file mode 100644
index da4b2e4..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/SmallString.h
+++ /dev/null
@@ -1,224 +0,0 @@
-//===- llvm/ADT/SmallString.h - 'Normally small' strings --------*- C++ -*-===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-//
-// This file defines the SmallString class.
-//
-//===----------------------------------------------------------------------===//
-
-#ifndef WPIUTIL_WPI_SMALLSTRING_H
-#define WPIUTIL_WPI_SMALLSTRING_H
-
-#include "wpi/SmallVector.h"
-#include <cstddef>
-#include <string_view>
-
-namespace wpi {
-
-/// SmallString - A SmallString is just a SmallVector with methods and accessors
-/// that make it work better as a string (e.g. operator+ etc).
-template<unsigned InternalLen>
-class SmallString : public SmallVector<char, InternalLen> {
-public:
-  /// Default ctor - Initialize to empty.
-  SmallString() = default;
-
-  /// Initialize from a std::string_view.
-  SmallString(std::string_view S)
-    : SmallVector<char, InternalLen>(S.begin(), S.end()) {}
-
-  /// Initialize with a range.
-  template<typename ItTy>
-  SmallString(ItTy S, ItTy E) : SmallVector<char, InternalLen>(S, E) {}
-
-  // Note that in order to add new overloads for append & assign, we have to
-  // duplicate the inherited versions so as not to inadvertently hide them.
-
-  /// @}
-  /// @name String Assignment
-  /// @{
-
-  /// Assign from a repeated element.
-  void assign(size_t NumElts, char Elt) {
-    this->SmallVectorImpl<char>::assign(NumElts, Elt);
-  }
-
-  /// Assign from an iterator pair.
-  template<typename in_iter>
-  void assign(in_iter S, in_iter E) {
-    this->clear();
-    SmallVectorImpl<char>::append(S, E);
-  }
-
-  /// Assign from a std::string_view.
-  void assign(std::string_view RHS) {
-    this->clear();
-    SmallVectorImpl<char>::append(RHS.begin(), RHS.end());
-  }
-
-  /// Assign from a SmallVector.
-  void assign(const SmallVectorImpl<char> &RHS) {
-    this->clear();
-    SmallVectorImpl<char>::append(RHS.begin(), RHS.end());
-  }
-
-  /// @}
-  /// @name String Concatenation
-  /// @{
-
-  /// Append from an iterator pair.
-  template<typename in_iter>
-  void append(in_iter S, in_iter E) {
-    SmallVectorImpl<char>::append(S, E);
-  }
-
-  void append(size_t NumInputs, char Elt) {
-    SmallVectorImpl<char>::append(NumInputs, Elt);
-  }
-
-  /// Append from a std::string_view.
-  void append(std::string_view RHS) {
-    SmallVectorImpl<char>::append(RHS.begin(), RHS.end());
-  }
-
-  /// Append from a SmallVector.
-  void append(const SmallVectorImpl<char> &RHS) {
-    SmallVectorImpl<char>::append(RHS.begin(), RHS.end());
-  }
-
-  /// @}
-  /// @name String Comparison
-  /// @{
-
-  /// Compare two strings; the result is -1, 0, or 1 if this string is
-  /// lexicographically less than, equal to, or greater than the \p RHS.
-  int compare(std::string_view RHS) const {
-    return str().compare(RHS);
-  }
-
-  /// @}
-  /// @name String Searching
-  /// @{
-
-  /// find - Search for the first character \p C in the string.
-  ///
-  /// \return - The index of the first occurrence of \p C, or npos if not
-  /// found.
-  size_t find(char C, size_t From = 0) const {
-    return str().find(C, From);
-  }
-
-  /// Search for the first string \p Str in the string.
-  ///
-  /// \returns The index of the first occurrence of \p Str, or npos if not
-  /// found.
-  size_t find(std::string_view Str, size_t From = 0) const {
-    return str().find(Str, From);
-  }
-
-  /// Search for the last character \p C in the string.
-  ///
-  /// \returns The index of the last occurrence of \p C, or npos if not
-  /// found.
-  size_t rfind(char C, size_t From = std::string_view::npos) const {
-    return str().rfind(C, From);
-  }
-
-  /// Search for the last string \p Str in the string.
-  ///
-  /// \returns The index of the last occurrence of \p Str, or npos if not
-  /// found.
-  size_t rfind(std::string_view Str) const {
-    return str().rfind(Str);
-  }
-
-  /// Find the first character in the string that is \p C, or npos if not
-  /// found. Same as find.
-  size_t find_first_of(char C, size_t From = 0) const {
-    return str().find_first_of(C, From);
-  }
-
-  /// Find the first character in the string that is in \p Chars, or npos if
-  /// not found.
-  ///
-  /// Complexity: O(size() + Chars.size())
-  size_t find_first_of(std::string_view Chars, size_t From = 0) const {
-    return str().find_first_of(Chars, From);
-  }
-
-  /// Find the first character in the string that is not \p C or npos if not
-  /// found.
-  size_t find_first_not_of(char C, size_t From = 0) const {
-    return str().find_first_not_of(C, From);
-  }
-
-  /// Find the first character in the string that is not in the string
-  /// \p Chars, or npos if not found.
-  ///
-  /// Complexity: O(size() + Chars.size())
-  size_t find_first_not_of(std::string_view Chars, size_t From = 0) const {
-    return str().find_first_not_of(Chars, From);
-  }
-
-  /// Find the last character in the string that is \p C, or npos if not
-  /// found.
-  size_t find_last_of(char C, size_t From = std::string_view::npos) const {
-    return str().find_last_of(C, From);
-  }
-
-  /// Find the last character in the string that is in \p C, or npos if not
-  /// found.
-  ///
-  /// Complexity: O(size() + Chars.size())
-  size_t find_last_of(
-      std::string_view Chars, size_t From = std::string_view::npos) const {
-    return str().find_last_of(Chars, From);
-  }
-
-  /// @}
-
-  // Extra methods.
-
-  /// Explicit conversion to std::string_view.
-  std::string_view str() const { return {this->begin(), this->size()}; }
-
-  /// Explicit conversion to std::string.
-  std::string string() const { return {this->begin(), this->size()}; }
-
-  // TODO: Make this const, if it's safe...
-  const char* c_str() {
-    this->push_back(0);
-    this->pop_back();
-    return this->data();
-  }
-
-  /// Implicit conversion to std::string_view.
-  operator std::string_view() const { return str(); }
-
-  /// Implicit conversion to std::string.
-  operator std::string() const { return string(); }
-
-  // Extra operators.
-  const SmallString &operator=(std::string_view RHS) {
-    this->clear();
-    return *this += RHS;
-  }
-
-  SmallString &operator+=(std::string_view RHS) {
-    this->append(RHS.begin(), RHS.end());
-    return *this;
-  }
-  SmallString &operator+=(char C) {
-    this->push_back(C);
-    return *this;
-  }
-};
-
-} // end namespace wpi
-
-#endif // LLVM_ADT_SMALLSTRING_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/SmallVector.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/SmallVector.h
deleted file mode 100644
index 430f85a..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/SmallVector.h
+++ /dev/null
@@ -1,949 +0,0 @@
-//===- llvm/ADT/SmallVector.h - 'Normally small' vectors --------*- C++ -*-===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-//
-// This file defines the SmallVector class.
-//
-//===----------------------------------------------------------------------===//
-
-#ifndef WPIUTIL_WPI_SMALLVECTOR_H
-#define WPIUTIL_WPI_SMALLVECTOR_H
-
-// This file uses std::memcpy() to copy std::pair<unsigned int, unsigned int>.
-// That type is POD, but the standard doesn't guarantee that. GCC doesn't treat
-// the type as POD so it throws a warning. We want to consider this a warning
-// instead of an error.
-#if __GNUC__ >= 8
-#pragma GCC diagnostic warning "-Wclass-memaccess"
-#endif
-
-#include "wpi/iterator_range.h"
-#include "wpi/AlignOf.h"
-#include "wpi/Compiler.h"
-#include "wpi/MathExtras.h"
-#include "wpi/MemAlloc.h"
-#include "wpi/type_traits.h"
-#include <algorithm>
-#include <cassert>
-#include <cstddef>
-#include <cstdlib>
-#include <cstring>
-#include <initializer_list>
-#include <iterator>
-#include <memory>
-#include <new>
-#include <type_traits>
-#include <utility>
-
-namespace wpi {
-
-/// This is all the non-templated stuff common to all SmallVectors.
-class SmallVectorBase {
-protected:
-  void *BeginX;
-  unsigned Size = 0, Capacity;
-
-  SmallVectorBase() = delete;
-  SmallVectorBase(void *FirstEl, size_t Capacity)
-      : BeginX(FirstEl), Capacity(static_cast<unsigned>(Capacity)) {}
-
-  /// This is an implementation of the grow() method which only works
-  /// on POD-like data types and is out of line to reduce code duplication.
-  void grow_pod(void *FirstEl, size_t MinCapacity, size_t TSize);
-
-public:
-  LLVM_ATTRIBUTE_ALWAYS_INLINE
-  size_t size() const { return Size; }
-  LLVM_ATTRIBUTE_ALWAYS_INLINE
-  size_t capacity() const { return Capacity; }
-
-  LLVM_NODISCARD bool empty() const { return !Size; }
-
-  /// Set the array size to \p N, which the current array must have enough
-  /// capacity for.
-  ///
-  /// This does not construct or destroy any elements in the vector.
-  ///
-  /// Clients can use this in conjunction with capacity() to write past the end
-  /// of the buffer when they know that more elements are available, and only
-  /// update the size later. This avoids the cost of value initializing elements
-  /// which will only be overwritten.
-  void set_size(size_t Size) {
-    assert(Size <= capacity());
-    this->Size = static_cast<unsigned>(Size);
-  }
-};
-
-/// Figure out the offset of the first element.
-template <class T, typename = void> struct SmallVectorAlignmentAndSize {
-  AlignedCharArrayUnion<SmallVectorBase> Base;
-  AlignedCharArrayUnion<T> FirstEl;
-};
-
-/// This is the part of SmallVectorTemplateBase which does not depend on whether
-/// the type T is a POD. The extra dummy template argument is used by ArrayRef
-/// to avoid unnecessarily requiring T to be complete.
-template <typename T, typename = void>
-class SmallVectorTemplateCommon : public SmallVectorBase {
-  /// Find the address of the first element.  For this pointer math to be valid
-  /// with small-size of 0 for T with lots of alignment, it's important that
-  /// SmallVectorStorage is properly-aligned even for small-size of 0.
-  void *getFirstEl() const {
-    return const_cast<void *>(reinterpret_cast<const void *>(
-        reinterpret_cast<const char *>(this) +
-        offsetof(SmallVectorAlignmentAndSize<T>, FirstEl)));
-  }
-  // Space after 'FirstEl' is clobbered, do not add any instance vars after it.
-
-protected:
-  SmallVectorTemplateCommon(size_t Size)
-      : SmallVectorBase(getFirstEl(), Size) {}
-
-  void grow_pod(size_t MinCapacity, size_t TSize) {
-    SmallVectorBase::grow_pod(getFirstEl(), MinCapacity, TSize);
-  }
-
-  /// Return true if this is a smallvector which has not had dynamic
-  /// memory allocated for it.
-  bool isSmall() const { return BeginX == getFirstEl(); }
-
-  /// Put this vector in a state of being small.
-  void resetToSmall() {
-    BeginX = getFirstEl();
-    Size = Capacity = 0; // FIXME: Setting Capacity to 0 is suspect.
-  }
-
-public:
-  using size_type = size_t;
-  using difference_type = ptrdiff_t;
-  using value_type = T;
-  using iterator = T *;
-  using const_iterator = const T *;
-
-  using const_reverse_iterator = std::reverse_iterator<const_iterator>;
-  using reverse_iterator = std::reverse_iterator<iterator>;
-
-  using reference = T &;
-  using const_reference = const T &;
-  using pointer = T *;
-  using const_pointer = const T *;
-
-  // forward iterator creation methods.
-  LLVM_ATTRIBUTE_ALWAYS_INLINE
-  iterator begin() { return (iterator)this->BeginX; }
-  LLVM_ATTRIBUTE_ALWAYS_INLINE
-  const_iterator begin() const { return (const_iterator)this->BeginX; }
-  LLVM_ATTRIBUTE_ALWAYS_INLINE
-  iterator end() { return begin() + size(); }
-  LLVM_ATTRIBUTE_ALWAYS_INLINE
-  const_iterator end() const { return begin() + size(); }
-
-  // reverse iterator creation methods.
-  reverse_iterator rbegin()            { return reverse_iterator(end()); }
-  const_reverse_iterator rbegin() const{ return const_reverse_iterator(end()); }
-  reverse_iterator rend()              { return reverse_iterator(begin()); }
-  const_reverse_iterator rend() const { return const_reverse_iterator(begin());}
-
-  size_type size_in_bytes() const { return size() * sizeof(T); }
-  size_type max_size() const { return size_type(-1) / sizeof(T); }
-
-  size_t capacity_in_bytes() const { return capacity() * sizeof(T); }
-
-  /// Return a pointer to the vector's buffer, even if empty().
-  pointer data() { return pointer(begin()); }
-  /// Return a pointer to the vector's buffer, even if empty().
-  const_pointer data() const { return const_pointer(begin()); }
-
-  LLVM_ATTRIBUTE_ALWAYS_INLINE
-  reference operator[](size_type idx) {
-    assert(idx < size());
-    return begin()[idx];
-  }
-  LLVM_ATTRIBUTE_ALWAYS_INLINE
-  const_reference operator[](size_type idx) const {
-    assert(idx < size());
-    return begin()[idx];
-  }
-
-  reference front() {
-    assert(!empty());
-    return begin()[0];
-  }
-  const_reference front() const {
-    assert(!empty());
-    return begin()[0];
-  }
-
-  reference back() {
-    assert(!empty());
-    return end()[-1];
-  }
-  const_reference back() const {
-    assert(!empty());
-    return end()[-1];
-  }
-};
-
-/// SmallVectorTemplateBase<isPodLike = false> - This is where we put method
-/// implementations that are designed to work with non-POD-like T's.
-template <typename T, bool = isPodLike<T>::value>
-class SmallVectorTemplateBase : public SmallVectorTemplateCommon<T> {
-protected:
-  SmallVectorTemplateBase(size_t Size) : SmallVectorTemplateCommon<T>(Size) {}
-
-  static void destroy_range(T *S, T *E) {
-    while (S != E) {
-      --E;
-      E->~T();
-    }
-  }
-
-  /// Move the range [I, E) into the uninitialized memory starting with "Dest",
-  /// constructing elements as needed.
-  template<typename It1, typename It2>
-  static void uninitialized_move(It1 I, It1 E, It2 Dest) {
-    std::uninitialized_copy(std::make_move_iterator(I),
-                            std::make_move_iterator(E), Dest);
-  }
-
-  /// Copy the range [I, E) onto the uninitialized memory starting with "Dest",
-  /// constructing elements as needed.
-  template<typename It1, typename It2>
-  static void uninitialized_copy(It1 I, It1 E, It2 Dest) {
-    std::uninitialized_copy(I, E, Dest);
-  }
-
-  /// Grow the allocated memory (without initializing new elements), doubling
-  /// the size of the allocated memory. Guarantees space for at least one more
-  /// element, or MinSize more elements if specified.
-  void grow(size_t MinSize = 0);
-
-public:
-  void push_back(const T &Elt) {
-    if (LLVM_UNLIKELY(this->size() >= this->capacity()))
-      this->grow();
-    ::new ((void*) this->end()) T(Elt);
-    this->set_size(this->size() + 1);
-  }
-
-  void push_back(T &&Elt) {
-    if (LLVM_UNLIKELY(this->size() >= this->capacity()))
-      this->grow();
-    ::new ((void*) this->end()) T(::std::move(Elt));
-    this->set_size(this->size() + 1);
-  }
-
-  void pop_back() {
-    this->set_size(this->size() - 1);
-    this->end()->~T();
-  }
-};
-
-// Define this out-of-line to dissuade the C++ compiler from inlining it.
-template <typename T, bool isPodLike>
-void SmallVectorTemplateBase<T, isPodLike>::grow(size_t MinSize) {
-  if (MinSize > UINT32_MAX)
-    report_bad_alloc_error("SmallVector capacity overflow during allocation");
-
-  // Always grow, even from zero.
-  size_t NewCapacity = size_t(NextPowerOf2(this->capacity() + 2));
-  NewCapacity = (std::min)((std::max)(NewCapacity, MinSize), size_t(UINT32_MAX));
-  T *NewElts = static_cast<T*>(wpi::safe_malloc(NewCapacity*sizeof(T)));
-
-  // Move the elements over.
-  this->uninitialized_move(this->begin(), this->end(), NewElts);
-
-  // Destroy the original elements.
-  destroy_range(this->begin(), this->end());
-
-  // If this wasn't grown from the inline copy, deallocate the old space.
-  if (!this->isSmall())
-    free(this->begin());
-
-  this->BeginX = NewElts;
-  this->Capacity = static_cast<unsigned>(NewCapacity);
-}
-
-
-/// SmallVectorTemplateBase<isPodLike = true> - This is where we put method
-/// implementations that are designed to work with POD-like T's.
-template <typename T>
-class SmallVectorTemplateBase<T, true> : public SmallVectorTemplateCommon<T> {
-protected:
-  SmallVectorTemplateBase(size_t Size) : SmallVectorTemplateCommon<T>(Size) {}
-
-  // No need to do a destroy loop for POD's.
-  static void destroy_range(T *, T *) {}
-
-  /// Move the range [I, E) onto the uninitialized memory
-  /// starting with "Dest", constructing elements into it as needed.
-  template<typename It1, typename It2>
-  static void uninitialized_move(It1 I, It1 E, It2 Dest) {
-    // Just do a copy.
-    uninitialized_copy(I, E, Dest);
-  }
-
-  /// Copy the range [I, E) onto the uninitialized memory
-  /// starting with "Dest", constructing elements into it as needed.
-  template<typename It1, typename It2>
-  static void uninitialized_copy(It1 I, It1 E, It2 Dest) {
-    // Arbitrary iterator types; just use the basic implementation.
-    std::uninitialized_copy(I, E, Dest);
-  }
-
-  /// Copy the range [I, E) onto the uninitialized memory
-  /// starting with "Dest", constructing elements into it as needed.
-  template <typename T1, typename T2>
-  static void uninitialized_copy(
-      T1 *I, T1 *E, T2 *Dest,
-      typename std::enable_if<std::is_same<typename std::remove_const<T1>::type,
-                                           T2>::value>::type * = nullptr) {
-    // Use memcpy for PODs iterated by pointers (which includes SmallVector
-    // iterators): std::uninitialized_copy optimizes to memmove, but we can
-    // use memcpy here. Note that I and E are iterators and thus might be
-    // invalid for memcpy if they are equal.
-    if (I != E)
-      memcpy(reinterpret_cast<void *>(Dest), I, (E - I) * sizeof(T));
-  }
-
-  /// Double the size of the allocated memory, guaranteeing space for at
-  /// least one more element or MinSize if specified.
-  void grow(size_t MinSize = 0) { this->grow_pod(MinSize, sizeof(T)); }
-
-public:
-  void push_back(const T &Elt) {
-    if (LLVM_UNLIKELY(this->size() >= this->capacity()))
-      this->grow();
-    memcpy(reinterpret_cast<void *>(this->end()), &Elt, sizeof(T));
-    this->set_size(this->size() + 1);
-  }
-
-  void pop_back() { this->set_size(this->size() - 1); }
-};
-
-/// This class consists of common code factored out of the SmallVector class to
-/// reduce code duplication based on the SmallVector 'N' template parameter.
-template <typename T>
-class SmallVectorImpl : public SmallVectorTemplateBase<T> {
-  using SuperClass = SmallVectorTemplateBase<T>;
-
-public:
-  using iterator = typename SuperClass::iterator;
-  using const_iterator = typename SuperClass::const_iterator;
-  using size_type = typename SuperClass::size_type;
-
-protected:
-  // Default ctor - Initialize to empty.
-  explicit SmallVectorImpl(unsigned N)
-      : SmallVectorTemplateBase<T, isPodLike<T>::value>(N) {}
-
-public:
-  SmallVectorImpl(const SmallVectorImpl &) = delete;
-
-  ~SmallVectorImpl() {
-    // Subclass has already destructed this vector's elements.
-    // If this wasn't grown from the inline copy, deallocate the old space.
-    if (!this->isSmall())
-      free(this->begin());
-  }
-
-  void clear() {
-    this->destroy_range(this->begin(), this->end());
-    this->Size = 0;
-  }
-
-  void resize(size_type N) {
-    if (N < this->size()) {
-      this->destroy_range(this->begin()+N, this->end());
-      this->set_size(N);
-    } else if (N > this->size()) {
-      if (this->capacity() < N)
-        this->grow(N);
-      for (auto I = this->end(), E = this->begin() + N; I != E; ++I)
-        new (&*I) T();
-      this->set_size(N);
-    }
-  }
-
-  void resize(size_type N, const T &NV) {
-    if (N < this->size()) {
-      this->destroy_range(this->begin()+N, this->end());
-      this->set_size(N);
-    } else if (N > this->size()) {
-      if (this->capacity() < N)
-        this->grow(N);
-      std::uninitialized_fill(this->end(), this->begin()+N, NV);
-      this->set_size(N);
-    }
-  }
-
-  void reserve(size_type N) {
-    if (this->capacity() < N)
-      this->grow(N);
-  }
-
-  LLVM_NODISCARD T pop_back_val() {
-    T Result = ::std::move(this->back());
-    this->pop_back();
-    return Result;
-  }
-
-  void swap(SmallVectorImpl &RHS);
-
-  /// Add the specified range to the end of the SmallVector.
-  template <typename in_iter,
-            typename = typename std::enable_if<std::is_convertible<
-                typename std::iterator_traits<in_iter>::iterator_category,
-                std::input_iterator_tag>::value>::type>
-  void append(in_iter in_start, in_iter in_end) {
-    size_type NumInputs = std::distance(in_start, in_end);
-    // Grow allocated space if needed.
-    if (NumInputs > this->capacity() - this->size())
-      this->grow(this->size()+NumInputs);
-
-    // Copy the new elements over.
-    this->uninitialized_copy(in_start, in_end, this->end());
-    this->set_size(this->size() + NumInputs);
-  }
-
-  /// Add the specified range to the end of the SmallVector.
-  void append(size_type NumInputs, const T &Elt) {
-    // Grow allocated space if needed.
-    if (NumInputs > this->capacity() - this->size())
-      this->grow(this->size()+NumInputs);
-
-    // Copy the new elements over.
-    std::uninitialized_fill_n(this->end(), NumInputs, Elt);
-    this->set_size(this->size() + NumInputs);
-  }
-
-  void append(std::initializer_list<T> IL) {
-    append(IL.begin(), IL.end());
-  }
-
-  // FIXME: Consider assigning over existing elements, rather than clearing &
-  // re-initializing them - for all assign(...) variants.
-
-  void assign(size_type NumElts, const T &Elt) {
-    clear();
-    if (this->capacity() < NumElts)
-      this->grow(NumElts);
-    this->set_size(NumElts);
-    std::uninitialized_fill(this->begin(), this->end(), Elt);
-  }
-
-  template <typename in_iter,
-            typename = typename std::enable_if<std::is_convertible<
-                typename std::iterator_traits<in_iter>::iterator_category,
-                std::input_iterator_tag>::value>::type>
-  void assign(in_iter in_start, in_iter in_end) {
-    clear();
-    append(in_start, in_end);
-  }
-
-  void assign(std::initializer_list<T> IL) {
-    clear();
-    append(IL);
-  }
-
-  iterator erase(const_iterator CI) {
-    // Just cast away constness because this is a non-const member function.
-    iterator I = const_cast<iterator>(CI);
-
-    assert(I >= this->begin() && "Iterator to erase is out of bounds.");
-    assert(I < this->end() && "Erasing at past-the-end iterator.");
-
-    iterator N = I;
-    // Shift all elts down one.
-    std::move(I+1, this->end(), I);
-    // Drop the last elt.
-    this->pop_back();
-    return(N);
-  }
-
-  iterator erase(const_iterator CS, const_iterator CE) {
-    // Just cast away constness because this is a non-const member function.
-    iterator S = const_cast<iterator>(CS);
-    iterator E = const_cast<iterator>(CE);
-
-    assert(S >= this->begin() && "Range to erase is out of bounds.");
-    assert(S <= E && "Trying to erase invalid range.");
-    assert(E <= this->end() && "Trying to erase past the end.");
-
-    iterator N = S;
-    // Shift all elts down.
-    iterator I = std::move(E, this->end(), S);
-    // Drop the last elts.
-    this->destroy_range(I, this->end());
-    this->set_size(I - this->begin());
-    return(N);
-  }
-
-  iterator insert(iterator I, T &&Elt) {
-    if (I == this->end()) {  // Important special case for empty vector.
-      this->push_back(::std::move(Elt));
-      return this->end()-1;
-    }
-
-    assert(I >= this->begin() && "Insertion iterator is out of bounds.");
-    assert(I <= this->end() && "Inserting past the end of the vector.");
-
-    if (this->size() >= this->capacity()) {
-      size_t EltNo = I-this->begin();
-      this->grow();
-      I = this->begin()+EltNo;
-    }
-
-    ::new ((void*) this->end()) T(::std::move(this->back()));
-    // Push everything else over.
-    std::move_backward(I, this->end()-1, this->end());
-    this->set_size(this->size() + 1);
-
-    // If we just moved the element we're inserting, be sure to update
-    // the reference.
-    T *EltPtr = &Elt;
-    if (I <= EltPtr && EltPtr < this->end())
-      ++EltPtr;
-
-    *I = ::std::move(*EltPtr);
-    return I;
-  }
-
-  iterator insert(iterator I, const T &Elt) {
-    if (I == this->end()) {  // Important special case for empty vector.
-      this->push_back(Elt);
-      return this->end()-1;
-    }
-
-    assert(I >= this->begin() && "Insertion iterator is out of bounds.");
-    assert(I <= this->end() && "Inserting past the end of the vector.");
-
-    if (this->size() >= this->capacity()) {
-      size_t EltNo = I-this->begin();
-      this->grow();
-      I = this->begin()+EltNo;
-    }
-    ::new ((void*) this->end()) T(std::move(this->back()));
-    // Push everything else over.
-    std::move_backward(I, this->end()-1, this->end());
-    this->set_size(this->size() + 1);
-
-    // If we just moved the element we're inserting, be sure to update
-    // the reference.
-    const T *EltPtr = &Elt;
-    if (I <= EltPtr && EltPtr < this->end())
-      ++EltPtr;
-
-    *I = *EltPtr;
-    return I;
-  }
-
-  iterator insert(iterator I, size_type NumToInsert, const T &Elt) {
-    // Convert iterator to elt# to avoid invalidating iterator when we reserve()
-    size_t InsertElt = I - this->begin();
-
-    if (I == this->end()) {  // Important special case for empty vector.
-      append(NumToInsert, Elt);
-      return this->begin()+InsertElt;
-    }
-
-    assert(I >= this->begin() && "Insertion iterator is out of bounds.");
-    assert(I <= this->end() && "Inserting past the end of the vector.");
-
-    // Ensure there is enough space.
-    reserve(this->size() + NumToInsert);
-
-    // Uninvalidate the iterator.
-    I = this->begin()+InsertElt;
-
-    // If there are more elements between the insertion point and the end of the
-    // range than there are being inserted, we can use a simple approach to
-    // insertion.  Since we already reserved space, we know that this won't
-    // reallocate the vector.
-    if (size_t(this->end()-I) >= NumToInsert) {
-      T *OldEnd = this->end();
-      append(std::move_iterator<iterator>(this->end() - NumToInsert),
-             std::move_iterator<iterator>(this->end()));
-
-      // Copy the existing elements that get replaced.
-      std::move_backward(I, OldEnd-NumToInsert, OldEnd);
-
-      std::fill_n(I, NumToInsert, Elt);
-      return I;
-    }
-
-    // Otherwise, we're inserting more elements than exist already, and we're
-    // not inserting at the end.
-
-    // Move over the elements that we're about to overwrite.
-    T *OldEnd = this->end();
-    this->set_size(this->size() + NumToInsert);
-    size_t NumOverwritten = OldEnd-I;
-    this->uninitialized_move(I, OldEnd, this->end()-NumOverwritten);
-
-    // Replace the overwritten part.
-    std::fill_n(I, NumOverwritten, Elt);
-
-    // Insert the non-overwritten middle part.
-    std::uninitialized_fill_n(OldEnd, NumToInsert-NumOverwritten, Elt);
-    return I;
-  }
-
-  template <typename ItTy,
-            typename = typename std::enable_if<std::is_convertible<
-                typename std::iterator_traits<ItTy>::iterator_category,
-                std::input_iterator_tag>::value>::type>
-  iterator insert(iterator I, ItTy From, ItTy To) {
-    // Convert iterator to elt# to avoid invalidating iterator when we reserve()
-    size_t InsertElt = I - this->begin();
-
-    if (I == this->end()) {  // Important special case for empty vector.
-      append(From, To);
-      return this->begin()+InsertElt;
-    }
-
-    assert(I >= this->begin() && "Insertion iterator is out of bounds.");
-    assert(I <= this->end() && "Inserting past the end of the vector.");
-
-    size_t NumToInsert = std::distance(From, To);
-
-    // Ensure there is enough space.
-    reserve(this->size() + NumToInsert);
-
-    // Uninvalidate the iterator.
-    I = this->begin()+InsertElt;
-
-    // If there are more elements between the insertion point and the end of the
-    // range than there are being inserted, we can use a simple approach to
-    // insertion.  Since we already reserved space, we know that this won't
-    // reallocate the vector.
-    if (size_t(this->end()-I) >= NumToInsert) {
-      T *OldEnd = this->end();
-      append(std::move_iterator<iterator>(this->end() - NumToInsert),
-             std::move_iterator<iterator>(this->end()));
-
-      // Copy the existing elements that get replaced.
-      std::move_backward(I, OldEnd-NumToInsert, OldEnd);
-
-      std::copy(From, To, I);
-      return I;
-    }
-
-    // Otherwise, we're inserting more elements than exist already, and we're
-    // not inserting at the end.
-
-    // Move over the elements that we're about to overwrite.
-    T *OldEnd = this->end();
-    this->set_size(this->size() + NumToInsert);
-    size_t NumOverwritten = OldEnd-I;
-    this->uninitialized_move(I, OldEnd, this->end()-NumOverwritten);
-
-    // Replace the overwritten part.
-    for (T *J = I; NumOverwritten > 0; --NumOverwritten) {
-      *J = *From;
-      ++J; ++From;
-    }
-
-    // Insert the non-overwritten middle part.
-    this->uninitialized_copy(From, To, OldEnd);
-    return I;
-  }
-
-  void insert(iterator I, std::initializer_list<T> IL) {
-    insert(I, IL.begin(), IL.end());
-  }
-
-  template <typename... ArgTypes> void emplace_back(ArgTypes &&... Args) {
-    if (LLVM_UNLIKELY(this->size() >= this->capacity()))
-      this->grow();
-    ::new ((void *)this->end()) T(std::forward<ArgTypes>(Args)...);
-    this->set_size(this->size() + 1);
-  }
-
-  SmallVectorImpl &operator=(const SmallVectorImpl &RHS);
-
-  SmallVectorImpl &operator=(SmallVectorImpl &&RHS);
-
-  bool operator==(const SmallVectorImpl &RHS) const {
-    if (this->size() != RHS.size()) return false;
-    return std::equal(this->begin(), this->end(), RHS.begin());
-  }
-  bool operator!=(const SmallVectorImpl &RHS) const {
-    return !(*this == RHS);
-  }
-
-  bool operator<(const SmallVectorImpl &RHS) const {
-    return std::lexicographical_compare(this->begin(), this->end(),
-                                        RHS.begin(), RHS.end());
-  }
-};
-
-template <typename T>
-void SmallVectorImpl<T>::swap(SmallVectorImpl<T> &RHS) {
-  if (this == &RHS) return;
-
-  // We can only avoid copying elements if neither vector is small.
-  if (!this->isSmall() && !RHS.isSmall()) {
-    std::swap(this->BeginX, RHS.BeginX);
-    std::swap(this->Size, RHS.Size);
-    std::swap(this->Capacity, RHS.Capacity);
-    return;
-  }
-  if (RHS.size() > this->capacity())
-    this->grow(RHS.size());
-  if (this->size() > RHS.capacity())
-    RHS.grow(this->size());
-
-  // Swap the shared elements.
-  size_t NumShared = this->size();
-  if (NumShared > RHS.size()) NumShared = RHS.size();
-  for (size_type i = 0; i != NumShared; ++i)
-    std::swap((*this)[i], RHS[i]);
-
-  // Copy over the extra elts.
-  if (this->size() > RHS.size()) {
-    size_t EltDiff = this->size() - RHS.size();
-    this->uninitialized_copy(this->begin()+NumShared, this->end(), RHS.end());
-    RHS.set_size(RHS.size() + EltDiff);
-    this->destroy_range(this->begin()+NumShared, this->end());
-    this->set_size(NumShared);
-  } else if (RHS.size() > this->size()) {
-    size_t EltDiff = RHS.size() - this->size();
-    this->uninitialized_copy(RHS.begin()+NumShared, RHS.end(), this->end());
-    this->set_size(this->size() + EltDiff);
-    this->destroy_range(RHS.begin()+NumShared, RHS.end());
-    RHS.set_size(NumShared);
-  }
-}
-
-template <typename T>
-SmallVectorImpl<T> &SmallVectorImpl<T>::
-  operator=(const SmallVectorImpl<T> &RHS) {
-  // Avoid self-assignment.
-  if (this == &RHS) return *this;
-
-  // If we already have sufficient space, assign the common elements, then
-  // destroy any excess.
-  size_t RHSSize = RHS.size();
-  size_t CurSize = this->size();
-  if (CurSize >= RHSSize) {
-    // Assign common elements.
-    iterator NewEnd;
-    if (RHSSize)
-      NewEnd = std::copy(RHS.begin(), RHS.begin()+RHSSize, this->begin());
-    else
-      NewEnd = this->begin();
-
-    // Destroy excess elements.
-    this->destroy_range(NewEnd, this->end());
-
-    // Trim.
-    this->set_size(RHSSize);
-    return *this;
-  }
-
-  // If we have to grow to have enough elements, destroy the current elements.
-  // This allows us to avoid copying them during the grow.
-  // FIXME: don't do this if they're efficiently moveable.
-  if (this->capacity() < RHSSize) {
-    // Destroy current elements.
-    this->destroy_range(this->begin(), this->end());
-    this->set_size(0);
-    CurSize = 0;
-    this->grow(RHSSize);
-  } else if (CurSize) {
-    // Otherwise, use assignment for the already-constructed elements.
-    std::copy(RHS.begin(), RHS.begin()+CurSize, this->begin());
-  }
-
-  // Copy construct the new elements in place.
-  this->uninitialized_copy(RHS.begin()+CurSize, RHS.end(),
-                           this->begin()+CurSize);
-
-  // Set end.
-  this->set_size(RHSSize);
-  return *this;
-}
-
-template <typename T>
-SmallVectorImpl<T> &SmallVectorImpl<T>::operator=(SmallVectorImpl<T> &&RHS) {
-  // Avoid self-assignment.
-  if (this == &RHS) return *this;
-
-  // If the RHS isn't small, clear this vector and then steal its buffer.
-  if (!RHS.isSmall()) {
-    this->destroy_range(this->begin(), this->end());
-    if (!this->isSmall()) free(this->begin());
-    this->BeginX = RHS.BeginX;
-    this->Size = RHS.Size;
-    this->Capacity = RHS.Capacity;
-    RHS.resetToSmall();
-    return *this;
-  }
-
-  // If we already have sufficient space, assign the common elements, then
-  // destroy any excess.
-  size_t RHSSize = RHS.size();
-  size_t CurSize = this->size();
-  if (CurSize >= RHSSize) {
-    // Assign common elements.
-    iterator NewEnd = this->begin();
-    if (RHSSize)
-      NewEnd = std::move(RHS.begin(), RHS.end(), NewEnd);
-
-    // Destroy excess elements and trim the bounds.
-    this->destroy_range(NewEnd, this->end());
-    this->set_size(RHSSize);
-
-    // Clear the RHS.
-    RHS.clear();
-
-    return *this;
-  }
-
-  // If we have to grow to have enough elements, destroy the current elements.
-  // This allows us to avoid copying them during the grow.
-  // FIXME: this may not actually make any sense if we can efficiently move
-  // elements.
-  if (this->capacity() < RHSSize) {
-    // Destroy current elements.
-    this->destroy_range(this->begin(), this->end());
-    this->set_size(0);
-    CurSize = 0;
-    this->grow(RHSSize);
-  } else if (CurSize) {
-    // Otherwise, use assignment for the already-constructed elements.
-    std::move(RHS.begin(), RHS.begin()+CurSize, this->begin());
-  }
-
-  // Move-construct the new elements in place.
-  this->uninitialized_move(RHS.begin()+CurSize, RHS.end(),
-                           this->begin()+CurSize);
-
-  // Set end.
-  this->set_size(RHSSize);
-
-  RHS.clear();
-  return *this;
-}
-
-/// Storage for the SmallVector elements.  This is specialized for the N=0 case
-/// to avoid allocating unnecessary storage.
-template <typename T, unsigned N>
-struct SmallVectorStorage {
-  AlignedCharArrayUnion<T> InlineElts[N];
-};
-
-/// We need the storage to be properly aligned even for small-size of 0 so that
-/// the pointer math in \a SmallVectorTemplateCommon::getFirstEl() is
-/// well-defined.
-template <typename T> struct alignas(alignof(T)) SmallVectorStorage<T, 0> {};
-
-/// This is a 'vector' (really, a variable-sized array), optimized
-/// for the case when the array is small.  It contains some number of elements
-/// in-place, which allows it to avoid heap allocation when the actual number of
-/// elements is below that threshold.  This allows normal "small" cases to be
-/// fast without losing generality for large inputs.
-///
-/// Note that this does not attempt to be exception safe.
-///
-template <typename T, unsigned N>
-class SmallVector : public SmallVectorImpl<T>, SmallVectorStorage<T, N> {
-public:
-  SmallVector() : SmallVectorImpl<T>(N) {}
-
-  ~SmallVector() {
-    // Destroy the constructed elements in the vector.
-    this->destroy_range(this->begin(), this->end());
-  }
-
-  explicit SmallVector(size_t Size, const T &Value = T())
-    : SmallVectorImpl<T>(N) {
-    this->assign(Size, Value);
-  }
-
-  template <typename ItTy,
-            typename = typename std::enable_if<std::is_convertible<
-                typename std::iterator_traits<ItTy>::iterator_category,
-                std::input_iterator_tag>::value>::type>
-  SmallVector(ItTy S, ItTy E) : SmallVectorImpl<T>(N) {
-    this->append(S, E);
-  }
-
-  template <typename RangeTy>
-  explicit SmallVector(const iterator_range<RangeTy> &R)
-      : SmallVectorImpl<T>(N) {
-    this->append(R.begin(), R.end());
-  }
-
-  SmallVector(std::initializer_list<T> IL) : SmallVectorImpl<T>(N) {
-    this->assign(IL);
-  }
-
-  SmallVector(const SmallVector &RHS) : SmallVectorImpl<T>(N) {
-    if (!RHS.empty())
-      SmallVectorImpl<T>::operator=(RHS);
-  }
-
-  const SmallVector &operator=(const SmallVector &RHS) {
-    SmallVectorImpl<T>::operator=(RHS);
-    return *this;
-  }
-
-  SmallVector(SmallVector &&RHS) : SmallVectorImpl<T>(N) {
-    if (!RHS.empty())
-      SmallVectorImpl<T>::operator=(::std::move(RHS));
-  }
-
-  SmallVector(SmallVectorImpl<T> &&RHS) : SmallVectorImpl<T>(N) {
-    if (!RHS.empty())
-      SmallVectorImpl<T>::operator=(::std::move(RHS));
-  }
-
-  const SmallVector &operator=(SmallVector &&RHS) {
-    SmallVectorImpl<T>::operator=(::std::move(RHS));
-    return *this;
-  }
-
-  const SmallVector &operator=(SmallVectorImpl<T> &&RHS) {
-    SmallVectorImpl<T>::operator=(::std::move(RHS));
-    return *this;
-  }
-
-  const SmallVector &operator=(std::initializer_list<T> IL) {
-    this->assign(IL);
-    return *this;
-  }
-};
-
-template <typename T, unsigned N>
-inline size_t capacity_in_bytes(const SmallVector<T, N> &X) {
-  return X.capacity_in_bytes();
-}
-
-} // end namespace wpi
-
-namespace std {
-
-  /// Implement std::swap in terms of SmallVector swap.
-  template<typename T>
-  inline void
-  swap(wpi::SmallVectorImpl<T> &LHS, wpi::SmallVectorImpl<T> &RHS) {
-    LHS.swap(RHS);
-  }
-
-  /// Implement std::swap in terms of SmallVector swap.
-  template<typename T, unsigned N>
-  inline void
-  swap(wpi::SmallVector<T, N> &LHS, wpi::SmallVector<T, N> &RHS) {
-    LHS.swap(RHS);
-  }
-
-} // end namespace std
-
-#endif // LLVM_ADT_SMALLVECTOR_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/SocketError.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/SocketError.h
deleted file mode 100644
index b893ac6..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/SocketError.h
+++ /dev/null
@@ -1,22 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_SOCKETERROR_H_
-#define WPIUTIL_WPI_SOCKETERROR_H_
-
-#include <string>
-
-namespace wpi {
-
-int SocketErrno();
-
-std::string SocketStrerror(int code);
-
-inline std::string SocketStrerror() {
-  return SocketStrerror(SocketErrno());
-}
-
-}  // namespace wpi
-
-#endif  // WPIUTIL_WPI_SOCKETERROR_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/SpanExtras.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/SpanExtras.h
index 41e4014..aa7b9ab 100644
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/SpanExtras.h
+++ b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/SpanExtras.h
@@ -5,21 +5,22 @@
 #pragma once
 
 #include <cassert>
-
-#include "wpi/span.h"
+#include <span>
 
 namespace wpi {
 
 /// Drop the first \p N elements of the array.
 template <typename T>
-constexpr span<T> drop_front(span<T> in, typename span<T>::size_type n = 1) {
+constexpr std::span<T> drop_front(std::span<T> in,
+                                  typename std::span<T>::size_type n = 1) {
   assert(in.size() >= n && "Dropping more elements than exist");
   return in.subspan(n, in.size() - n);
 }
 
 /// Drop the last \p N elements of the array.
 template <typename T>
-constexpr span<T> drop_back(span<T> in, typename span<T>::size_type n = 1) {
+constexpr std::span<T> drop_back(std::span<T> in,
+                                 typename std::span<T>::size_type n = 1) {
   assert(in.size() >= n && "Dropping more elements than exist");
   return in.subspan(0, in.size() - n);
 }
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/StringExtras.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/StringExtras.h
deleted file mode 100644
index 9e70f52..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/StringExtras.h
+++ /dev/null
@@ -1,712 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-//===- llvm/ADT/StringExtras.h - Useful string functions --------*- C++ -*-===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-//
-// This file contains some functions that are useful when dealing with strings.
-//
-//===----------------------------------------------------------------------===//
-
-#pragma once
-
-#include <limits>
-#include <optional>
-#include <string>
-#include <string_view>
-#include <type_traits>
-#include <utility>
-
-namespace wpi {
-
-template <typename T>
-class SmallVectorImpl;
-
-/// hexdigit - Return the hexadecimal character for the
-/// given number \p X (which should be less than 16).
-constexpr char hexdigit(unsigned X, bool LowerCase = false) noexcept {
-  const char HexChar = LowerCase ? 'a' : 'A';
-  return X < 10 ? '0' + X : HexChar + X - 10;
-}
-
-/// Interpret the given character \p C as a hexadecimal digit and return its
-/// value.
-///
-/// If \p C is not a valid hex digit, -1U is returned.
-constexpr unsigned hexDigitValue(char C) noexcept {
-  if (C >= '0' && C <= '9') {
-    return C - '0';
-  }
-  if (C >= 'a' && C <= 'f') {
-    return C - 'a' + 10U;
-  }
-  if (C >= 'A' && C <= 'F') {
-    return C - 'A' + 10U;
-  }
-  return (std::numeric_limits<unsigned>::max)();
-}
-
-/// Checks if character \p C is one of the 10 decimal digits.
-constexpr bool isDigit(char C) noexcept {
-  return C >= '0' && C <= '9';
-}
-
-/// Checks if character \p C is a hexadecimal numeric character.
-constexpr bool isHexDigit(char C) noexcept {
-  return hexDigitValue(C) != (std::numeric_limits<unsigned>::max)();
-}
-
-/// Checks if character \p C is a valid letter as classified by "C" locale.
-constexpr bool isAlpha(char C) noexcept {
-  return ('a' <= C && C <= 'z') || ('A' <= C && C <= 'Z');
-}
-
-/// Checks whether character \p C is either a decimal digit or an uppercase or
-/// lowercase letter as classified by "C" locale.
-constexpr bool isAlnum(char C) noexcept {
-  return isAlpha(C) || isDigit(C);
-}
-
-/// Checks whether character \p C is valid ASCII (high bit is zero).
-constexpr bool isASCII(char C) noexcept {
-  return static_cast<unsigned char>(C) <= 127;
-}
-
-/// Checks whether character \p C is printable.
-///
-/// Locale-independent version of the C standard library isprint whose results
-/// may differ on different platforms.
-constexpr bool isPrint(char C) noexcept {
-  unsigned char UC = static_cast<unsigned char>(C);
-  return (0x20 <= UC) && (UC <= 0x7E);
-}
-
-/// Returns the corresponding lowercase character if \p x is uppercase.
-constexpr char toLower(char x) noexcept {
-  if (x >= 'A' && x <= 'Z') {
-    return x - 'A' + 'a';
-  }
-  return x;
-}
-
-/// Returns the corresponding uppercase character if \p x is lowercase.
-constexpr char toUpper(char x) noexcept {
-  if (x >= 'a' && x <= 'z') {
-    return x - 'a' + 'A';
-  }
-  return x;
-}
-
-inline std::string utohexstr(unsigned long long val,  // NOLINT(runtime/int)
-                             bool lowerCase = false) {
-  char buf[17];
-  char* bufptr = std::end(buf);
-
-  if (val == 0) {
-    *--bufptr = '0';
-  }
-
-  while (val) {
-    unsigned char mod = static_cast<unsigned char>(val) & 15;
-    *--bufptr = hexdigit(mod, lowerCase);
-    val >>= 4;
-  }
-
-  return std::string(bufptr, std::end(buf));
-}
-
-/**
- * equals - Check for string equality, this is more efficient than
- * compare() when the relative ordering of inequal strings isn't needed.
- */
-constexpr bool equals(std::string_view lhs, std::string_view rhs) noexcept {
-  auto length = lhs.size();
-  return length == rhs.size() && std::string_view::traits_type::compare(
-                                     lhs.data(), rhs.data(), length) == 0;
-}
-
-/**
- * compare_lower - Compare two strings, ignoring case.
- */
-int compare_lower(std::string_view lhs, std::string_view rhs) noexcept;
-
-/**
- * equals_lower - Check for string equality, ignoring case.
- */
-constexpr bool equals_lower(std::string_view lhs,
-                            std::string_view rhs) noexcept {
-  return lhs.size() == rhs.size() && compare_lower(lhs, rhs) == 0;
-}
-
-/**
- * Search for the first character @p ch in @p str, ignoring case.
- *
- * @returns The index of the first occurrence of @p ch, or npos if not
- * found.
- */
-std::string_view::size_type find_lower(
-    std::string_view str, char ch,
-    std::string_view::size_type from = 0) noexcept;
-
-/**
- * Search for the first string @p other in @p str, ignoring case.
- *
- * @returns The index of the first occurrence of @p other, or npos if not
- * found.
- */
-std::string_view::size_type find_lower(
-    std::string_view str, std::string_view other,
-    std::string_view::size_type from = 0) noexcept;
-
-/**
- * Search for the first string @p other in @p str, ignoring case.
- *
- * @returns The index of the first occurrence of @p other, or npos if not
- * found.
- */
-inline std::string_view::size_type find_lower(
-    std::string_view str, const char* other,
-    std::string_view::size_type from = 0) noexcept {
-  return find_lower(str, std::string_view{other}, from);
-}
-
-/**
- * Search for the last character @p ch in @p str, ignoring case.
- *
- * @returns The index of the last occurrence of @p ch, or npos if not
- * found.
- */
-std::string_view::size_type rfind_lower(
-    std::string_view str, char ch,
-    std::string_view::size_type from = std::string_view::npos) noexcept;
-
-/**
- * Search for the last string @p other in @p str, ignoring case.
- *
- * @returns The index of the last occurrence of @p other, or npos if not
- * found.
- */
-std::string_view::size_type rfind_lower(std::string_view str,
-                                        std::string_view other) noexcept;
-
-/**
- * Search for the last string @p other in @p str, ignoring case.
- *
- * @returns The index of the last occurrence of @p other, or npos if not
- * found.
- */
-inline std::string_view::size_type rfind_lower(std::string_view str,
-                                               const char* other) noexcept {
-  return rfind_lower(str, std::string_view{other});
-}
-
-/**
- * Returns the substring of @p str from [start, start + n).
- *
- * @param start The index of the starting character in the substring; if
- * the index is npos or greater than the length of the string then the
- * empty substring will be returned.
- *
- * @param n The number of characters to included in the substring. If n
- * exceeds the number of characters remaining in the string, the string
- * suffix (starting with @p start) will be returned.
- */
-constexpr std::string_view substr(
-    std::string_view str, std::string_view::size_type start,
-    std::string_view::size_type n = std::string_view::npos) noexcept {
-  auto length = str.size();
-  start = (std::min)(start, length);
-  return {str.data() + start, (std::min)(n, length - start)};
-}
-
-/**
- * Checks if @p str starts with the given @p prefix.
- */
-constexpr bool starts_with(std::string_view str,
-                           std::string_view prefix) noexcept {
-  return substr(str, 0, prefix.size()) == prefix;
-}
-
-/**
- * Checks if @p str starts with the given @p prefix.
- */
-constexpr bool starts_with(std::string_view str, char prefix) noexcept {
-  return !str.empty() && std::string_view::traits_type::eq(str.front(), prefix);
-}
-
-/**
- * Checks if @p str starts with the given @p prefix.
- */
-constexpr bool starts_with(std::string_view str, const char* prefix) noexcept {
-  return starts_with(str, std::string_view(prefix));
-}
-
-/**
- * Checks if @p str starts with the given @p prefix, ignoring case.
- */
-bool starts_with_lower(std::string_view str, std::string_view prefix) noexcept;
-
-/**
- * Checks if @p str starts with the given @p prefix, ignoring case.
- */
-constexpr bool starts_with_lower(std::string_view str, char prefix) noexcept {
-  return !str.empty() && toLower(str.front()) == toLower(prefix);
-}
-
-/**
- * Checks if @p str starts with the given @p prefix, ignoring case.
- */
-inline bool starts_with_lower(std::string_view str,
-                              const char* prefix) noexcept {
-  return starts_with_lower(str, std::string_view(prefix));
-}
-
-/**
- * Checks if @p str ends with the given @p suffix.
- */
-constexpr bool ends_with(std::string_view str,
-                         std::string_view suffix) noexcept {
-  return str.size() >= suffix.size() &&
-         str.compare(str.size() - suffix.size(), std::string_view::npos,
-                     suffix) == 0;
-}
-
-/**
- * Checks if @p str ends with the given @p suffix.
- */
-constexpr bool ends_with(std::string_view str, char suffix) noexcept {
-  return !str.empty() && std::string_view::traits_type::eq(str.back(), suffix);
-}
-
-/**
- * Checks if @p str ends with the given @p suffix.
- */
-constexpr bool ends_with(std::string_view str, const char* suffix) noexcept {
-  return ends_with(str, std::string_view(suffix));
-}
-
-/**
- * Checks if @p str ends with the given @p suffix, ignoring case.
- */
-bool ends_with_lower(std::string_view str, std::string_view suffix) noexcept;
-
-/**
- * Checks if @p str ends with the given @p suffix, ignoring case.
- */
-constexpr bool ends_with_lower(std::string_view str, char suffix) noexcept {
-  return !str.empty() && toLower(str.back()) == toLower(suffix);
-}
-
-/**
- * Checks if @p str ends with the given @p suffix, ignoring case.
- */
-inline bool ends_with_lower(std::string_view str, const char* suffix) noexcept {
-  return ends_with_lower(str, std::string_view(suffix));
-}
-
-/**
- * Checks if @p str contains the substring @p other.
- */
-constexpr bool contains(std::string_view str, std::string_view other) noexcept {
-  return str.find(other) != std::string_view::npos;
-}
-
-/**
- * Checks if @p str contains the substring @p other.
- */
-constexpr bool contains(std::string_view str, char ch) noexcept {
-  return str.find(ch) != std::string_view::npos;
-}
-
-/**
- * Checks if @p str contains the substring @p other.
- */
-constexpr bool contains(std::string_view str, const char* other) noexcept {
-  return str.find(other) != std::string_view::npos;
-}
-
-/**
- * Checks if @p str contains the substring @p other, ignoring case.
- */
-inline bool contains_lower(std::string_view str,
-                           std::string_view other) noexcept {
-  return find_lower(str, other) != std::string_view::npos;
-}
-
-/**
- * Checks if @p str contains the substring @p other, ignoring case.
- */
-inline bool contains_lower(std::string_view str, char ch) noexcept {
-  return find_lower(str, ch) != std::string_view::npos;
-}
-
-/**
- * Checks if @p str contains the substring @p other, ignoring case.
- */
-inline bool contains_lower(std::string_view str, const char* other) noexcept {
-  return find_lower(str, other) != std::string_view::npos;
-}
-
-/**
- * Return a string_view equal to @p str but with the first @p n elements
- * dropped.
- */
-constexpr std::string_view drop_front(
-    std::string_view str, std::string_view::size_type n = 1) noexcept {
-  str.remove_prefix(n);
-  return str;
-}
-
-/**
- * Return a string_view equal to @p str but with the last @p n elements dropped.
- */
-constexpr std::string_view drop_back(
-    std::string_view str, std::string_view::size_type n = 1) noexcept {
-  str.remove_suffix(n);
-  return str;
-}
-
-/**
- * Returns a view equal to @p str but with only the first @p n
- * elements remaining.  If @p n is greater than the length of the
- * string, the entire string is returned.
- */
-constexpr std::string_view take_front(
-    std::string_view str, std::string_view::size_type n = 1) noexcept {
-  auto length = str.size();
-  if (n >= length) {
-    return str;
-  }
-  return drop_back(str, length - n);
-}
-
-/**
- * Returns a view equal to @p str but with only the last @p n
- * elements remaining.  If @p n is greater than the length of the
- * string, the entire string is returned.
- */
-constexpr std::string_view take_back(
-    std::string_view str, std::string_view::size_type n = 1) noexcept {
-  auto length = str.size();
-  if (n >= length) {
-    return str;
-  }
-  return drop_front(str, length - n);
-}
-
-/**
- * Returns a reference to the substring of @p str from [start, end).
- *
- * @param start The index of the starting character in the substring; if
- * the index is npos or greater than the length of the string then the
- * empty substring will be returned.
- *
- * @param end The index following the last character to include in the
- * substring. If this is npos or exceeds the number of characters
- * remaining in the string, the string suffix (starting with @p start)
- * will be returned. If this is less than @p start, an empty string will
- * be returned.
- */
-constexpr std::string_view slice(std::string_view str,
-                                 std::string_view::size_type start,
-                                 std::string_view::size_type end) noexcept {
-  auto length = str.size();
-  start = (std::min)(start, length);
-  end = (std::min)((std::max)(start, end), length);
-  return {str.data() + start, end - start};
-}
-
-/**
- * Splits @p str into two substrings around the first occurrence of a separator
- * character.
- *
- * If @p separator is in the string, then the result is a pair (LHS, RHS)
- * such that (str == LHS + separator + RHS) is true and RHS is
- * maximal. If @p separator is not in the string, then the result is a
- * pair (LHS, RHS) where (str == LHS) and (RHS == "").
- *
- * @param separator The character to split on.
- * @returns The split substrings.
- */
-constexpr std::pair<std::string_view, std::string_view> split(
-    std::string_view str, char separator) noexcept {
-  auto idx = str.find(separator);
-  if (idx == std::string_view::npos) {
-    return {str, {}};
-  }
-  return {slice(str, 0, idx), slice(str, idx + 1, std::string_view::npos)};
-}
-
-/**
- * Splits @p str into two substrings around the first occurrence of a separator
- * string.
- *
- * If @p separator is in the string, then the result is a pair (LHS, RHS)
- * such that (str == LHS + separator + RHS) is true and RHS is
- * maximal. If @p separator is not in the string, then the result is a
- * pair (LHS, RHS) where (str == LHS) and (RHS == "").
- *
- * @param separator The string to split on.
- * @return The split substrings.
- */
-constexpr std::pair<std::string_view, std::string_view> split(
-    std::string_view str, std::string_view separator) noexcept {
-  auto idx = str.find(separator);
-  if (idx == std::string_view::npos) {
-    return {str, {}};
-  }
-  return {slice(str, 0, idx),
-          slice(str, idx + separator.size(), std::string_view::npos)};
-}
-
-/**
- * Splits @p str into two substrings around the last occurrence of a separator
- * character.
- *
- * If @p separator is in the string, then the result is a pair (LHS, RHS)
- * such that (str == LHS + separator + RHS) is true and RHS is
- * minimal. If @p separator is not in the string, then the result is a
- * pair (LHS, RHS) where (str == LHS) and (RHS == "").
- *
- * @param separator The string to split on.
- * @return The split substrings.
- */
-constexpr std::pair<std::string_view, std::string_view> rsplit(
-    std::string_view str, char separator) noexcept {
-  auto idx = str.rfind(separator);
-  if (idx == std::string_view::npos) {
-    return {str, {}};
-  }
-  return {slice(str, 0, idx), slice(str, idx + 1, std::string_view::npos)};
-}
-
-/**
- * Splits @p str into two substrings around the last occurrence of a separator
- * string.
- *
- * If @p separator is in the string, then the result is a pair (LHS, RHS)
- * such that (str == LHS + separator + RHS) is true and RHS is
- * minimal. If @p separator is not in the string, then the result is a
- * pair (LHS, RHS) where (str == LHS) and (RHS == "").
- *
- * @param separator The string to split on.
- * @return The split substrings.
- */
-constexpr std::pair<std::string_view, std::string_view> rsplit(
-    std::string_view str, std::string_view separator) noexcept {
-  auto idx = str.rfind(separator);
-  if (idx == std::string_view::npos) {
-    return {str, {}};
-  }
-  return {slice(str, 0, idx),
-          slice(str, idx + separator.size(), std::string_view::npos)};
-}
-
-/**
- * Splits @p str into substrings around the occurrences of a separator string.
- *
- * Each substring is stored in @p arr. If @p maxSplit is >= 0, at most
- * @p maxSplit splits are done and consequently <= @p maxSplit + 1
- * elements are added to arr.
- * If @p keepEmpty is false, empty strings are not added to @p arr. They
- * still count when considering @p maxSplit
- * An useful invariant is that
- * separator.join(arr) == str if maxSplit == -1 and keepEmpty == true
- *
- * @param arr Where to put the substrings.
- * @param separator The string to split on.
- * @param maxSplit The maximum number of times the string is split.
- * @param keepEmpty True if empty substring should be added.
- */
-void split(std::string_view str, SmallVectorImpl<std::string_view>& arr,
-           std::string_view separator, int maxSplit = -1,
-           bool keepEmpty = true) noexcept;
-
-/**
- * Splits @p str into substrings around the occurrences of a separator
- * character.
- *
- * Each substring is stored in @p arr. If @p maxSplit is >= 0, at most
- * @p maxSplit splits are done and consequently <= @p maxSplit + 1
- * elements are added to arr.
- * If @p keepEmpty is false, empty strings are not added to @p arr. They
- * still count when considering @p maxSplit
- * An useful invariant is that
- * separator.join(arr) == str if maxSplit == -1 and keepEmpty == true
- *
- * @param arr Where to put the substrings.
- * @param separator The character to split on.
- * @param maxSplit The maximum number of times the string is split.
- * @param keepEmpty True if empty substring should be added.
- */
-void split(std::string_view str, SmallVectorImpl<std::string_view>& arr,
-           char separator, int maxSplit = -1, bool keepEmpty = true) noexcept;
-
-/**
- * Returns @p str with consecutive @p ch characters starting from the
- * the left removed.
- */
-constexpr std::string_view ltrim(std::string_view str, char ch) noexcept {
-  return drop_front(str, (std::min)(str.size(), str.find_first_not_of(ch)));
-}
-
-/**
- * Returns @p str with consecutive characters in @p chars starting from
- * the left removed.
- */
-constexpr std::string_view ltrim(
-    std::string_view str, std::string_view chars = " \t\n\v\f\r") noexcept {
-  return drop_front(str, (std::min)(str.size(), str.find_first_not_of(chars)));
-}
-
-/**
- * Returns @p str with consecutive @p Char characters starting from the
- * right removed.
- */
-constexpr std::string_view rtrim(std::string_view str, char ch) noexcept {
-  return drop_back(
-      str, str.size() - (std::min)(str.size(), str.find_last_not_of(ch) + 1));
-}
-
-/**
- * Returns @p str with consecutive characters in @p chars starting from
- * the right removed.
- */
-constexpr std::string_view rtrim(
-    std::string_view str, std::string_view chars = " \t\n\v\f\r") noexcept {
-  return drop_back(
-      str,
-      str.size() - (std::min)(str.size(), str.find_last_not_of(chars) + 1));
-}
-
-/**
- * Returns @p str with consecutive @p ch characters starting from the
- * left and right removed.
- */
-constexpr std::string_view trim(std::string_view str, char ch) noexcept {
-  return rtrim(ltrim(str, ch), ch);
-}
-
-/**
- * Returns @p str with consecutive characters in @p chars starting from
- * the left and right removed.
- */
-constexpr std::string_view trim(
-    std::string_view str, std::string_view chars = " \t\n\v\f\r") noexcept {
-  return rtrim(ltrim(str, chars), chars);
-}
-
-namespace detail {
-bool GetAsUnsignedInteger(
-    std::string_view str, unsigned radix,
-    unsigned long long& result) noexcept;  // NOLINT(runtime/int)
-bool GetAsSignedInteger(std::string_view str, unsigned radix,
-                        long long& result) noexcept;  // NOLINT(runtime/int)
-
-bool ConsumeUnsignedInteger(
-    std::string_view& str, unsigned radix,
-    unsigned long long& result) noexcept;  // NOLINT(runtime/int)
-bool ConsumeSignedInteger(std::string_view& str, unsigned radix,
-                          long long& result) noexcept;  // NOLINT(runtime/int)
-}  // namespace detail
-
-/**
- * Parses the string @p str as an integer of the specified radix.  If
- * @p radix is specified as zero, this does radix autosensing using
- * extended C rules: 0 is octal, 0x is hex, 0b is binary.
- *
- * If the string is invalid or if only a subset of the string is valid,
- * this returns nullopt to signify the error.  The string is considered
- * erroneous if empty or if it overflows T.
- */
-template <typename T,
-          std::enable_if_t<std::numeric_limits<T>::is_signed, bool> = true>
-inline std::optional<T> parse_integer(std::string_view str,
-                                      unsigned radix) noexcept {
-  long long val;  // NOLINT(runtime/int)
-  if (detail::GetAsSignedInteger(str, radix, val) ||
-      static_cast<T>(val) != val) {
-    return std::nullopt;
-  }
-  return val;
-}
-
-template <typename T,
-          std::enable_if_t<!std::numeric_limits<T>::is_signed, bool> = true>
-inline std::optional<T> parse_integer(std::string_view str,
-                                      unsigned radix) noexcept {
-  using Int = unsigned long long;  // NOLINT(runtime/int)
-  Int val;
-  // The additional cast to unsigned long long is required to avoid the
-  // Visual C++ warning C4805: '!=' : unsafe mix of type 'bool' and type
-  // 'unsigned __int64' when instantiating getAsInteger with T = bool.
-  if (detail::GetAsUnsignedInteger(str, radix, val) ||
-      static_cast<Int>(static_cast<T>(val)) != val) {
-    return std::nullopt;
-  }
-  return val;
-}
-
-/**
- * Parses the string @p str as an integer of the specified radix.  If
- * @p radix is specified as zero, this does radix autosensing using
- * extended C rules: 0 is octal, 0x is hex, 0b is binary.
- *
- * If the string does not begin with a number of the specified radix,
- * this returns nullopt to signify the error. The string is considered
- * erroneous if empty or if it overflows T.
- * The portion of the string representing the discovered numeric value
- * is removed from the beginning of the string.
- */
-template <typename T,
-          std::enable_if_t<std::numeric_limits<T>::is_signed, bool> = true>
-inline std::optional<T> consume_integer(std::string_view* str,
-                                        unsigned radix) noexcept {
-  using Int = long long;  // NOLINT(runtime/int)
-  Int val;
-  if (detail::ConsumeSignedInteger(*str, radix, val) ||
-      static_cast<Int>(static_cast<T>(val)) != val) {
-    return std::nullopt;
-  }
-  return val;
-}
-
-template <typename T,
-          std::enable_if_t<!std::numeric_limits<T>::is_signed, bool> = true>
-inline std::optional<T> consume_integer(std::string_view* str,
-                                        unsigned radix) noexcept {
-  using Int = unsigned long long;  // NOLINT(runtime/int)
-  Int val;
-  if (detail::ConsumeUnsignedInteger(*str, radix, val) ||
-      static_cast<Int>(static_cast<T>(val)) != val) {
-    return std::nullopt;
-  }
-  return val;
-}
-
-/**
- * Parses the string @p str as a floating point value.
- *
- * If the string is invalid or if only a subset of the string is valid,
- * this returns nullopt to signify the error.  The string is considered
- * erroneous if empty or if it overflows T.
- */
-template <typename T>
-std::optional<T> parse_float(std::string_view str) noexcept;
-
-template <>
-std::optional<float> parse_float<float>(std::string_view str) noexcept;
-template <>
-std::optional<double> parse_float<double>(std::string_view str) noexcept;
-template <>
-std::optional<long double> parse_float<long double>(
-    std::string_view str) noexcept;
-
-}  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/StringMap.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/StringMap.h
deleted file mode 100644
index dac2f20..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/StringMap.h
+++ /dev/null
@@ -1,638 +0,0 @@
-//===- StringMap.h - String Hash table map interface ------------*- C++ -*-===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-//
-// This file defines the StringMap class.
-//
-//===----------------------------------------------------------------------===//
-
-#ifndef WPIUTIL_WPI_STRINGMAP_H
-#define WPIUTIL_WPI_STRINGMAP_H
-
-#include "wpi/SmallVector.h"
-#include "wpi/iterator.h"
-#include "wpi/iterator_range.h"
-#include "wpi/MemAlloc.h"
-#include "wpi/PointerLikeTypeTraits.h"
-#include "wpi/ErrorHandling.h"
-#include <algorithm>
-#include <cassert>
-#include <cstdint>
-#include <cstdlib>
-#include <cstring>
-#include <initializer_list>
-#include <iterator>
-#include <string_view>
-#include <utility>
-
-namespace wpi {
-
-template<typename ValueTy> class StringMapConstIterator;
-template<typename ValueTy> class StringMapIterator;
-template<typename ValueTy> class StringMapKeyIterator;
-template<typename ValueTy> class StringMapEntry;
-
-/// StringMapEntryBase - Shared base class of StringMapEntry instances.
-class StringMapEntryBase {
-  size_t StrLen;
-
-public:
-  explicit StringMapEntryBase(size_t Len) : StrLen(Len) {}
-
-  size_t getKeyLength() const { return StrLen; }
-};
-
-/// StringMapImpl - This is the base class of StringMap that is shared among
-/// all of its instantiations.
-class StringMapImpl {
-protected:
-  // Array of NumBuckets pointers to entries, null pointers are holes.
-  // TheTable[NumBuckets] contains a sentinel value for easy iteration. Followed
-  // by an array of the actual hash values as unsigned integers.
-  StringMapEntryBase **TheTable = nullptr;
-  unsigned NumBuckets = 0;
-  unsigned NumItems = 0;
-  unsigned NumTombstones = 0;
-  unsigned ItemSize;
-
-protected:
-  explicit StringMapImpl(unsigned itemSize)
-      : ItemSize(itemSize) {}
-  StringMapImpl(StringMapImpl &&RHS) noexcept
-      : TheTable(RHS.TheTable), NumBuckets(RHS.NumBuckets),
-        NumItems(RHS.NumItems), NumTombstones(RHS.NumTombstones),
-        ItemSize(RHS.ItemSize) {
-    RHS.TheTable = nullptr;
-    RHS.NumBuckets = 0;
-    RHS.NumItems = 0;
-    RHS.NumTombstones = 0;
-  }
-
-  StringMapImpl(unsigned InitSize, unsigned ItemSize);
-  unsigned RehashTable(unsigned BucketNo = 0);
-
-  /// LookupBucketFor - Look up the bucket that the specified string should end
-  /// up in.  If it already exists as a key in the map, the Item pointer for the
-  /// specified bucket will be non-null.  Otherwise, it will be null.  In either
-  /// case, the FullHashValue field of the bucket will be set to the hash value
-  /// of the string.
-  unsigned LookupBucketFor(std::string_view Key);
-
-  /// FindKey - Look up the bucket that contains the specified key. If it exists
-  /// in the map, return the bucket number of the key.  Otherwise return -1.
-  /// This does not modify the map.
-  int FindKey(std::string_view Key) const;
-
-  /// RemoveKey - Remove the specified StringMapEntry from the table, but do not
-  /// delete it.  This aborts if the value isn't in the table.
-  void RemoveKey(StringMapEntryBase *V);
-
-  /// RemoveKey - Remove the StringMapEntry for the specified key from the
-  /// table, returning it.  If the key is not in the table, this returns null.
-  StringMapEntryBase *RemoveKey(std::string_view Key);
-
-  /// Allocate the table with the specified number of buckets and otherwise
-  /// setup the map as empty.
-  void init(unsigned Size);
-
-public:
-  static StringMapEntryBase *getTombstoneVal() {
-    uintptr_t Val = static_cast<uintptr_t>(-1);
-    Val <<= PointerLikeTypeTraits<StringMapEntryBase *>::NumLowBitsAvailable;
-    return reinterpret_cast<StringMapEntryBase *>(Val);
-  }
-
-  unsigned getNumBuckets() const { return NumBuckets; }
-  unsigned getNumItems() const { return NumItems; }
-
-  bool empty() const { return NumItems == 0; }
-  unsigned size() const { return NumItems; }
-
-  void swap(StringMapImpl &Other) {
-    std::swap(TheTable, Other.TheTable);
-    std::swap(NumBuckets, Other.NumBuckets);
-    std::swap(NumItems, Other.NumItems);
-    std::swap(NumTombstones, Other.NumTombstones);
-  }
-};
-
-/// StringMapEntry - This is used to represent one value that is inserted into
-/// a StringMap.  It contains the Value itself and the key: the string length
-/// and data.
-template<typename ValueTy>
-class StringMapEntry : public StringMapEntryBase {
-public:
-  ValueTy second;
-
-  explicit StringMapEntry(size_t strLen)
-    : StringMapEntryBase(strLen), second() {}
-  template <typename... InitTy>
-  StringMapEntry(size_t strLen, InitTy &&... InitVals)
-      : StringMapEntryBase(strLen), second(std::forward<InitTy>(InitVals)...) {}
-  StringMapEntry(StringMapEntry &E) = delete;
-
-  std::string_view getKey() const {
-    return {getKeyData(), getKeyLength()};
-  }
-
-  const ValueTy &getValue() const { return second; }
-  ValueTy &getValue() { return second; }
-
-  void setValue(const ValueTy &V) { second = V; }
-
-  /// getKeyData - Return the start of the string data that is the key for this
-  /// value.  The string data is always stored immediately after the
-  /// StringMapEntry object.
-  const char *getKeyData() const {return reinterpret_cast<const char*>(this+1);}
-
-  std::string_view first() const { return {getKeyData(), getKeyLength()}; }
-
-  /// Create a StringMapEntry for the specified key construct the value using
-  /// \p InitiVals.
-  template <typename... InitTy>
-  static StringMapEntry *Create(std::string_view Key, InitTy &&... InitVals) {
-    size_t KeyLength = Key.size();
-
-    // Allocate a new item with space for the string at the end and a null
-    // terminator.
-    size_t AllocSize = sizeof(StringMapEntry) + KeyLength + 1;
-
-    StringMapEntry *NewItem =
-      static_cast<StringMapEntry*>(safe_malloc(AllocSize));
-
-    // Construct the value.
-    new (NewItem) StringMapEntry(KeyLength, std::forward<InitTy>(InitVals)...);
-
-    // Copy the string information.
-    char *StrBuffer = const_cast<char*>(NewItem->getKeyData());
-    if (KeyLength > 0)
-      memcpy(StrBuffer, Key.data(), KeyLength);
-    StrBuffer[KeyLength] = 0;  // Null terminate for convenience of clients.
-    return NewItem;
-  }
-
-  static StringMapEntry *Create(std::string_view Key) {
-    return Create(Key, ValueTy());
-  }
-
-  /// GetStringMapEntryFromKeyData - Given key data that is known to be embedded
-  /// into a StringMapEntry, return the StringMapEntry itself.
-  static StringMapEntry &GetStringMapEntryFromKeyData(const char *KeyData) {
-    char *Ptr = const_cast<char*>(KeyData) - sizeof(StringMapEntry<ValueTy>);
-    return *reinterpret_cast<StringMapEntry*>(Ptr);
-  }
-
-  /// Destroy - Destroy this StringMapEntry, releasing memory back to the
-  /// specified allocator.
-  void Destroy() {
-    // Free memory referenced by the item.
-    this->~StringMapEntry();
-    std::free(static_cast<void *>(this));
-  }
-};
-
-
-/// StringMap - This is an unconventional map that is specialized for handling
-/// keys that are "strings", which are basically ranges of bytes. This does some
-/// funky memory allocation and hashing things to make it extremely efficient,
-/// storing the string data *after* the value in the map.
-template<typename ValueTy>
-class StringMap : public StringMapImpl {
-public:
-  using MapEntryTy = StringMapEntry<ValueTy>;
-
-  StringMap() : StringMapImpl(static_cast<unsigned>(sizeof(MapEntryTy))) {}
-
-  explicit StringMap(unsigned InitialSize)
-    : StringMapImpl(InitialSize, static_cast<unsigned>(sizeof(MapEntryTy))) {}
-
-  StringMap(std::initializer_list<std::pair<std::string_view, ValueTy>> List)
-      : StringMapImpl(List.size(), static_cast<unsigned>(sizeof(MapEntryTy))) {
-    for (const auto &P : List) {
-      insert(P);
-    }
-  }
-
-  StringMap(StringMap &&RHS)
-      : StringMapImpl(std::move(RHS)) {}
-
-  StringMap(const StringMap &RHS) :
-    StringMapImpl(static_cast<unsigned>(sizeof(MapEntryTy))) {
-    if (RHS.empty())
-      return;
-
-    // Allocate TheTable of the same size as RHS's TheTable, and set the
-    // sentinel appropriately (and NumBuckets).
-    init(RHS.NumBuckets);
-    unsigned *HashTable = (unsigned *)(TheTable + NumBuckets + 1),
-             *RHSHashTable = (unsigned *)(RHS.TheTable + NumBuckets + 1);
-
-    NumItems = RHS.NumItems;
-    NumTombstones = RHS.NumTombstones;
-    for (unsigned I = 0, E = NumBuckets; I != E; ++I) {
-      StringMapEntryBase *Bucket = RHS.TheTable[I];
-      if (!Bucket || Bucket == getTombstoneVal()) {
-        TheTable[I] = Bucket;
-        continue;
-      }
-
-      TheTable[I] = MapEntryTy::Create(
-          static_cast<MapEntryTy *>(Bucket)->getKey(),
-          static_cast<MapEntryTy *>(Bucket)->getValue());
-      HashTable[I] = RHSHashTable[I];
-    }
-
-    // Note that here we've copied everything from the RHS into this object,
-    // tombstones included. We could, instead, have re-probed for each key to
-    // instantiate this new object without any tombstone buckets. The
-    // assumption here is that items are rarely deleted from most StringMaps,
-    // and so tombstones are rare, so the cost of re-probing for all inputs is
-    // not worthwhile.
-  }
-
-  StringMap &operator=(StringMap RHS) {
-    StringMapImpl::swap(RHS);
-    return *this;
-  }
-
-  ~StringMap() {
-    // Delete all the elements in the map, but don't reset the elements
-    // to default values.  This is a copy of clear(), but avoids unnecessary
-    // work not required in the destructor.
-    if (!empty()) {
-      for (unsigned I = 0, E = NumBuckets; I != E; ++I) {
-        StringMapEntryBase *Bucket = TheTable[I];
-        if (Bucket && Bucket != getTombstoneVal()) {
-          static_cast<MapEntryTy*>(Bucket)->Destroy();
-        }
-      }
-    }
-    free(TheTable);
-  }
-
-  using key_type = const char*;
-  using mapped_type = ValueTy;
-  using value_type = StringMapEntry<ValueTy>;
-  using size_type = size_t;
-
-  using const_iterator = StringMapConstIterator<ValueTy>;
-  using iterator = StringMapIterator<ValueTy>;
-
-  iterator begin() {
-    return iterator(TheTable, NumBuckets == 0);
-  }
-  iterator end() {
-    return iterator(TheTable+NumBuckets, true);
-  }
-  const_iterator begin() const {
-    return const_iterator(TheTable, NumBuckets == 0);
-  }
-  const_iterator end() const {
-    return const_iterator(TheTable+NumBuckets, true);
-  }
-
-  iterator_range<StringMapKeyIterator<ValueTy>> keys() const {
-    return make_range(StringMapKeyIterator<ValueTy>(begin()),
-                      StringMapKeyIterator<ValueTy>(end()));
-  }
-
-  iterator find(std::string_view Key) {
-    int Bucket = FindKey(Key);
-    if (Bucket == -1) return end();
-    return iterator(TheTable+Bucket, true);
-  }
-
-  const_iterator find(std::string_view Key) const {
-    int Bucket = FindKey(Key);
-    if (Bucket == -1) return end();
-    return const_iterator(TheTable+Bucket, true);
-  }
-
-  /// lookup - Return the entry for the specified key, or a default
-  /// constructed value if no such entry exists.
-  ValueTy lookup(std::string_view Key) const {
-    const_iterator it = find(Key);
-    if (it != end())
-      return it->second;
-    return ValueTy();
-  }
-
-  /// Lookup the ValueTy for the \p Key, or create a default constructed value
-  /// if the key is not in the map.
-  ValueTy &operator[](std::string_view Key) { return try_emplace(Key).first->second; }
-
-  /// count - Return 1 if the element is in the map, 0 otherwise.
-  size_type count(std::string_view Key) const {
-    return find(Key) == end() ? 0 : 1;
-  }
-
-  /// insert - Insert the specified key/value pair into the map.  If the key
-  /// already exists in the map, return false and ignore the request, otherwise
-  /// insert it and return true.
-  bool insert(MapEntryTy *KeyValue) {
-    unsigned BucketNo = LookupBucketFor(KeyValue->getKey());
-    StringMapEntryBase *&Bucket = TheTable[BucketNo];
-    if (Bucket && Bucket != getTombstoneVal())
-      return false;  // Already exists in map.
-
-    if (Bucket == getTombstoneVal())
-      --NumTombstones;
-    Bucket = KeyValue;
-    ++NumItems;
-    assert(NumItems + NumTombstones <= NumBuckets);
-
-    RehashTable();
-    return true;
-  }
-
-  /// insert - Inserts the specified key/value pair into the map if the key
-  /// isn't already in the map. The bool component of the returned pair is true
-  /// if and only if the insertion takes place, and the iterator component of
-  /// the pair points to the element with key equivalent to the key of the pair.
-  std::pair<iterator, bool> insert(std::pair<std::string_view, ValueTy> KV) {
-    return try_emplace(KV.first, std::move(KV.second));
-  }
-
-  /// Emplace a new element for the specified key into the map if the key isn't
-  /// already in the map. The bool component of the returned pair is true
-  /// if and only if the insertion takes place, and the iterator component of
-  /// the pair points to the element with key equivalent to the key of the pair.
-  template <typename... ArgsTy>
-  std::pair<iterator, bool> try_emplace(std::string_view Key, ArgsTy &&... Args) {
-    unsigned BucketNo = LookupBucketFor(Key);
-    StringMapEntryBase *&Bucket = TheTable[BucketNo];
-    if (Bucket && Bucket != getTombstoneVal())
-      return std::make_pair(iterator(TheTable + BucketNo, false),
-                            false); // Already exists in map.
-
-    if (Bucket == getTombstoneVal())
-      --NumTombstones;
-    Bucket = MapEntryTy::Create(Key, std::forward<ArgsTy>(Args)...);
-    ++NumItems;
-    assert(NumItems + NumTombstones <= NumBuckets);
-
-    BucketNo = RehashTable(BucketNo);
-    return std::make_pair(iterator(TheTable + BucketNo, false), true);
-  }
-
-  // clear - Empties out the StringMap
-  void clear() {
-    if (empty()) return;
-
-    // Zap all values, resetting the keys back to non-present (not tombstone),
-    // which is safe because we're removing all elements.
-    for (unsigned I = 0, E = NumBuckets; I != E; ++I) {
-      StringMapEntryBase *&Bucket = TheTable[I];
-      if (Bucket && Bucket != getTombstoneVal()) {
-        static_cast<MapEntryTy*>(Bucket)->Destroy();
-      }
-      Bucket = nullptr;
-    }
-
-    NumItems = 0;
-    NumTombstones = 0;
-  }
-
-  /// remove - Remove the specified key/value pair from the map, but do not
-  /// erase it.  This aborts if the key is not in the map.
-  void remove(MapEntryTy *KeyValue) {
-    RemoveKey(KeyValue);
-  }
-
-  void erase(iterator I) {
-    MapEntryTy &V = *I;
-    remove(&V);
-    V.Destroy();
-  }
-
-  bool erase(std::string_view Key) {
-    iterator I = find(Key);
-    if (I == end()) return false;
-    erase(I);
-    return true;
-  }
-};
-
-template <typename DerivedTy, typename ValueTy>
-class StringMapIterBase
-    : public iterator_facade_base<DerivedTy, std::forward_iterator_tag,
-                                  ValueTy> {
-protected:
-  StringMapEntryBase **Ptr = nullptr;
-
-public:
-  StringMapIterBase() = default;
-
-  explicit StringMapIterBase(StringMapEntryBase **Bucket,
-                             bool NoAdvance = false)
-      : Ptr(Bucket) {
-    if (!NoAdvance) AdvancePastEmptyBuckets();
-  }
-
-  DerivedTy &operator=(const DerivedTy &Other) {
-    Ptr = Other.Ptr;
-    return static_cast<DerivedTy &>(*this);
-  }
-
-#if __cplusplus < 202002L
-  bool operator==(const DerivedTy &RHS) const { return Ptr == RHS.Ptr; }
-#else
-  friend bool operator==(const DerivedTy &LHS, const DerivedTy &RHS) {
-    return LHS.Ptr == RHS.Ptr;
-  }
-#endif
-
-  DerivedTy &operator++() { // Preincrement
-    ++Ptr;
-    AdvancePastEmptyBuckets();
-    return static_cast<DerivedTy &>(*this);
-  }
-
-  DerivedTy operator++(int) { // Post-increment
-    DerivedTy Tmp(Ptr);
-    ++*this;
-    return Tmp;
-  }
-
-  DerivedTy &operator--() { // Predecrement
-    --Ptr;
-    ReversePastEmptyBuckets();
-    return static_cast<DerivedTy &>(*this);
-  }
-
-  DerivedTy operator--(int) { // Post-decrement
-    DerivedTy Tmp(Ptr);
-    --*this;
-    return Tmp;
-  }
-
-private:
-  void AdvancePastEmptyBuckets() {
-    while (*Ptr == nullptr || *Ptr == StringMapImpl::getTombstoneVal())
-      ++Ptr;
-  }
-  void ReversePastEmptyBuckets() {
-    while (*Ptr == nullptr || *Ptr == StringMapImpl::getTombstoneVal())
-      --Ptr;
-  }
-};
-
-template <typename ValueTy>
-class StringMapConstIterator
-    : public StringMapIterBase<StringMapConstIterator<ValueTy>,
-                               const StringMapEntry<ValueTy>> {
-  using base = StringMapIterBase<StringMapConstIterator<ValueTy>,
-                                 const StringMapEntry<ValueTy>>;
-
-public:
-  using value_type = const StringMapEntry<ValueTy>;
-
-  StringMapConstIterator() = default;
-  explicit StringMapConstIterator(StringMapEntryBase **Bucket,
-                                  bool NoAdvance = false)
-      : base(Bucket, NoAdvance) {}
-
-  value_type &operator*() const {
-    return *static_cast<value_type *>(*this->Ptr);
-  }
-};
-
-template <typename ValueTy>
-class StringMapIterator : public StringMapIterBase<StringMapIterator<ValueTy>,
-                                                   StringMapEntry<ValueTy>> {
-  using base =
-      StringMapIterBase<StringMapIterator<ValueTy>, StringMapEntry<ValueTy>>;
-
-public:
-  using value_type = StringMapEntry<ValueTy>;
-
-  StringMapIterator() = default;
-  explicit StringMapIterator(StringMapEntryBase **Bucket,
-                             bool NoAdvance = false)
-      : base(Bucket, NoAdvance) {}
-
-  value_type &operator*() const {
-    return *static_cast<value_type *>(*this->Ptr);
-  }
-
-  operator StringMapConstIterator<ValueTy>() const {
-    return StringMapConstIterator<ValueTy>(this->Ptr, true);
-  }
-};
-
-template <typename ValueTy>
-class StringMapKeyIterator
-    : public iterator_adaptor_base<StringMapKeyIterator<ValueTy>,
-                                   StringMapConstIterator<ValueTy>,
-                                   std::forward_iterator_tag, std::string_view> {
-  using base = iterator_adaptor_base<StringMapKeyIterator<ValueTy>,
-                                     StringMapConstIterator<ValueTy>,
-                                     std::forward_iterator_tag, std::string_view>;
-
-public:
-  StringMapKeyIterator() = default;
-  explicit StringMapKeyIterator(StringMapConstIterator<ValueTy> Iter)
-      : base(std::move(Iter)) {}
-
-  std::string_view &operator*() {
-    Key = this->wrapped()->getKey();
-    return Key;
-  }
-
-private:
-  std::string_view Key;
-};
-
-template <typename ValueTy>
-bool operator==(const StringMap<ValueTy>& lhs, const StringMap<ValueTy>& rhs) {
-  // same instance?
-  if (&lhs == &rhs) return true;
-
-  // first check that sizes are identical
-  if (lhs.size() != rhs.size()) return false;
-
-  // copy into vectors and sort by key
-  SmallVector<StringMapConstIterator<ValueTy>, 16> lhs_items;
-  lhs_items.reserve(lhs.size());
-  for (auto i = lhs.begin(), end = lhs.end(); i != end; ++i)
-    lhs_items.push_back(i);
-  std::sort(lhs_items.begin(), lhs_items.end(),
-            [](const StringMapConstIterator<ValueTy>& a,
-               const StringMapConstIterator<ValueTy>& b) {
-              return a->getKey() < b->getKey();
-            });
-
-  SmallVector<StringMapConstIterator<ValueTy>, 16> rhs_items;
-  rhs_items.reserve(rhs.size());
-  for (auto i = rhs.begin(), end = rhs.end(); i != end; ++i)
-    rhs_items.push_back(i);
-  std::sort(rhs_items.begin(), rhs_items.end(),
-            [](const StringMapConstIterator<ValueTy>& a,
-               const StringMapConstIterator<ValueTy>& b) {
-              return a->getKey() < b->getKey();
-            });
-
-  // compare vector keys and values
-  for (auto a = lhs_items.begin(), b = rhs_items.begin(),
-            aend = lhs_items.end(), bend = rhs_items.end();
-       a != aend && b != bend; ++a, ++b) {
-    if ((*a)->first() != (*b)->first() || (*a)->second != (*b)->second)
-      return false;
-  }
-  return true;
-}
-
-template <typename ValueTy>
-inline bool operator!=(const StringMap<ValueTy>& lhs,
-                       const StringMap<ValueTy>& rhs) {
-  return !(lhs == rhs);
-}
-
-template <typename ValueTy>
-bool operator<(const StringMap<ValueTy>& lhs, const StringMap<ValueTy>& rhs) {
-  // same instance?
-  if (&lhs == &rhs) return false;
-
-  // copy into vectors and sort by key
-  SmallVector<std::string_view, 16> lhs_keys;
-  lhs_keys.reserve(lhs.size());
-  for (auto i = lhs.begin(), end = lhs.end(); i != end; ++i)
-    lhs_keys.push_back(i->getKey());
-  std::sort(lhs_keys.begin(), lhs_keys.end());
-
-  SmallVector<std::string_view, 16> rhs_keys;
-  rhs_keys.reserve(rhs.size());
-  for (auto i = rhs.begin(), end = rhs.end(); i != end; ++i)
-    rhs_keys.push_back(i->getKey());
-  std::sort(rhs_keys.begin(), rhs_keys.end());
-
-  // use std::vector comparison
-  return lhs_keys < rhs_keys;
-}
-
-template <typename ValueTy>
-inline bool operator<=(const StringMap<ValueTy>& lhs,
-                       const StringMap<ValueTy>& rhs) {
-  return !(rhs < lhs);
-}
-
-template <typename ValueTy>
-inline bool operator>(const StringMap<ValueTy>& lhs,
-                      const StringMap<ValueTy>& rhs) {
-  return !(lhs <= rhs);
-}
-
-template <typename ValueTy>
-inline bool operator>=(const StringMap<ValueTy>& lhs,
-                       const StringMap<ValueTy>& rhs) {
-  return !(lhs < rhs);
-}
-
-} // end namespace wpi
-
-#endif // LLVM_ADT_STRINGMAP_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/SwapByteOrder.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/SwapByteOrder.h
deleted file mode 100644
index 50ad832..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/SwapByteOrder.h
+++ /dev/null
@@ -1,127 +0,0 @@
-//===- SwapByteOrder.h - Generic and optimized byte swaps -------*- C++ -*-===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-//
-// This file declares generic and optimized functions to swap the byte order of
-// an integral type.
-//
-//===----------------------------------------------------------------------===//
-
-#ifndef WPIUTIL_WPI_SWAPBYTEORDER_H
-#define WPIUTIL_WPI_SWAPBYTEORDER_H
-
-#include "wpi/Compiler.h"
-#include <cstddef>
-#include <stdint.h>
-#if defined(_MSC_VER) && !defined(_DEBUG)
-#include <stdlib.h>
-#endif
-
-namespace wpi {
-namespace sys {
-
-/// SwapByteOrder_16 - This function returns a byte-swapped representation of
-/// the 16-bit argument.
-inline uint16_t SwapByteOrder_16(uint16_t value) {
-#if defined(_MSC_VER) && !defined(_DEBUG)
-  // The DLL version of the runtime lacks these functions (bug!?), but in a
-  // release build they're replaced with BSWAP instructions anyway.
-  return _byteswap_ushort(value);
-#else
-  uint16_t Hi = value << 8;
-  uint16_t Lo = value >> 8;
-  return Hi | Lo;
-#endif
-}
-
-/// SwapByteOrder_32 - This function returns a byte-swapped representation of
-/// the 32-bit argument.
-inline uint32_t SwapByteOrder_32(uint32_t value) {
-#if defined(__llvm__) || (LLVM_GNUC_PREREQ(4, 3, 0) && !defined(__ICC))
-  return __builtin_bswap32(value);
-#elif defined(_MSC_VER) && !defined(_DEBUG)
-  return _byteswap_ulong(value);
-#else
-  uint32_t Byte0 = value & 0x000000FF;
-  uint32_t Byte1 = value & 0x0000FF00;
-  uint32_t Byte2 = value & 0x00FF0000;
-  uint32_t Byte3 = value & 0xFF000000;
-  return (Byte0 << 24) | (Byte1 << 8) | (Byte2 >> 8) | (Byte3 >> 24);
-#endif
-}
-
-/// SwapByteOrder_64 - This function returns a byte-swapped representation of
-/// the 64-bit argument.
-inline uint64_t SwapByteOrder_64(uint64_t value) {
-#if defined(__llvm__) || (LLVM_GNUC_PREREQ(4, 3, 0) && !defined(__ICC))
-  return __builtin_bswap64(value);
-#elif defined(_MSC_VER) && !defined(_DEBUG)
-  return _byteswap_uint64(value);
-#else
-  uint64_t Hi = SwapByteOrder_32(uint32_t(value));
-  uint32_t Lo = SwapByteOrder_32(uint32_t(value >> 32));
-  return (Hi << 32) | Lo;
-#endif
-}
-
-inline unsigned char  getSwappedBytes(unsigned char C) { return C; }
-inline   signed char  getSwappedBytes(signed char C) { return C; }
-inline          char  getSwappedBytes(char C) { return C; }
-
-inline unsigned short getSwappedBytes(unsigned short C) { return SwapByteOrder_16(C); }
-inline   signed short getSwappedBytes(  signed short C) { return SwapByteOrder_16(C); }
-
-inline unsigned int   getSwappedBytes(unsigned int   C) { return SwapByteOrder_32(C); }
-inline   signed int   getSwappedBytes(  signed int   C) { return SwapByteOrder_32(C); }
-
-#if __LONG_MAX__ == __INT_MAX__
-inline unsigned long  getSwappedBytes(unsigned long  C) { return SwapByteOrder_32(C); }
-inline   signed long  getSwappedBytes(  signed long  C) { return SwapByteOrder_32(C); }
-#elif __LONG_MAX__ == __LONG_LONG_MAX__
-inline unsigned long  getSwappedBytes(unsigned long  C) { return SwapByteOrder_64(C); }
-inline   signed long  getSwappedBytes(  signed long  C) { return SwapByteOrder_64(C); }
-#else
-#error "Unknown long size!"
-#endif
-
-inline unsigned long long getSwappedBytes(unsigned long long C) {
-  return SwapByteOrder_64(C);
-}
-inline signed long long getSwappedBytes(signed long long C) {
-  return SwapByteOrder_64(C);
-}
-
-inline float getSwappedBytes(float C) {
-  union {
-    uint32_t i;
-    float f;
-  } in, out;
-  in.f = C;
-  out.i = SwapByteOrder_32(in.i);
-  return out.f;
-}
-
-inline double getSwappedBytes(double C) {
-  union {
-    uint64_t i;
-    double d;
-  } in, out;
-  in.d = C;
-  out.i = SwapByteOrder_64(in.i);
-  return out.d;
-}
-
-template<typename T>
-inline void swapByteOrder(T &Value) {
-  Value = getSwappedBytes(Value);
-}
-
-} // end namespace sys
-} // end namespace wpi
-
-#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/SymbolExports.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/SymbolExports.h
index 4e84825..9ffc936 100644
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/SymbolExports.h
+++ b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/SymbolExports.h
@@ -14,10 +14,179 @@
 #define WPILIB_DLLEXPORT __declspec(dllexport)
 #endif
 
+#elif defined(WPILIB_IMPORTS)
+
+#ifdef __GNUC__
+#define WPILIB_DLLEXPORT __attribute__((dllimport))
+#else
+#define WPILIB_DLLEXPORT __declspec(dllimport)
+#endif
+
 #else
 #define WPILIB_DLLEXPORT
 #endif
 
-#else
+#else  // _WIN32
+
+#ifdef WPILIB_EXPORTS
 #define WPILIB_DLLEXPORT __attribute__((visibility("default")))
+#else
+#define WPILIB_DLLEXPORT
 #endif
+
+#endif  // _WIN32
+
+// Synopsis
+//
+// This header provides macros for using FOO_EXPORT macros with explicit
+// template instantiation declarations and definitions.
+// Generally, the FOO_EXPORT macros are used at declarations,
+// and GCC requires them to be used at explicit instantiation declarations,
+// but MSVC requires __declspec(dllexport) to be used at the explicit
+// instantiation definitions instead.
+
+// Usage
+//
+// In a header file, write:
+//
+//   extern template class EXPORT_TEMPLATE_DECLARE(FOO_EXPORT) foo<bar>;
+//
+// In a source file, write:
+//
+//   template class EXPORT_TEMPLATE_DEFINE(FOO_EXPORT) foo<bar>;
+
+// Implementation notes
+//
+// The implementation of this header uses some subtle macro semantics to
+// detect what the provided FOO_EXPORT value was defined as and then
+// to dispatch to appropriate macro definitions.  Unfortunately,
+// MSVC's C preprocessor is rather non-compliant and requires special
+// care to make it work.
+//
+// Issue 1.
+//
+//   #define F(x)
+//   F()
+//
+// MSVC emits warning C4003 ("not enough actual parameters for macro
+// 'F'), even though it's a valid macro invocation.  This affects the
+// macros below that take just an "export" parameter, because export
+// may be empty.
+//
+// As a workaround, we can add a dummy parameter and arguments:
+//
+//   #define F(x,_)
+//   F(,)
+//
+// Issue 2.
+//
+//   #define F(x) G##x
+//   #define Gj() ok
+//   F(j())
+//
+// The correct replacement for "F(j())" is "ok", but MSVC replaces it
+// with "Gj()".  As a workaround, we can pass the result to an
+// identity macro to force MSVC to look for replacements again.  (This
+// is why EXPORT_TEMPLATE_STYLE_3 exists.)
+
+#define EXPORT_TEMPLATE_DECLARE(export) \
+  EXPORT_TEMPLATE_INVOKE(DECLARE, EXPORT_TEMPLATE_STYLE(export, ), export)
+#define EXPORT_TEMPLATE_DEFINE(export) \
+  EXPORT_TEMPLATE_INVOKE(DEFINE, EXPORT_TEMPLATE_STYLE(export, ), export)
+
+// INVOKE is an internal helper macro to perform parameter replacements
+// and token pasting to chain invoke another macro.  E.g.,
+//     EXPORT_TEMPLATE_INVOKE(DECLARE, DEFAULT, FOO_EXPORT)
+// will export to call
+//     EXPORT_TEMPLATE_DECLARE_DEFAULT(FOO_EXPORT, )
+// (but with FOO_EXPORT expanded too).
+#define EXPORT_TEMPLATE_INVOKE(which, style, export) \
+  EXPORT_TEMPLATE_INVOKE_2(which, style, export)
+#define EXPORT_TEMPLATE_INVOKE_2(which, style, export) \
+  EXPORT_TEMPLATE_##which##_##style(export, )
+
+// Default style is to apply the FOO_EXPORT macro at declaration sites.
+#define EXPORT_TEMPLATE_DECLARE_DEFAULT(export, _) export
+#define EXPORT_TEMPLATE_DEFINE_DEFAULT(export, _)
+
+// The "MSVC hack" style is used when FOO_EXPORT is defined
+// as __declspec(dllexport), which MSVC requires to be used at
+// definition sites instead.
+#define EXPORT_TEMPLATE_DECLARE_MSVC_HACK(export, _)
+#define EXPORT_TEMPLATE_DEFINE_MSVC_HACK(export, _) export
+
+// EXPORT_TEMPLATE_STYLE is an internal helper macro that identifies which
+// export style needs to be used for the provided FOO_EXPORT macro definition.
+// "", "__attribute__(...)", and "__declspec(dllimport)" are mapped
+// to "DEFAULT"; while "__declspec(dllexport)" is mapped to "MSVC_HACK".
+//
+// It's implemented with token pasting to transform the __attribute__ and
+// __declspec annotations into macro invocations.  E.g., if FOO_EXPORT is
+// defined as "__declspec(dllimport)", it undergoes the following sequence of
+// macro substitutions:
+//     EXPORT_TEMPLATE_STYLE(FOO_EXPORT, )
+//     EXPORT_TEMPLATE_STYLE_2(__declspec(dllimport), )
+//     EXPORT_TEMPLATE_STYLE_3(EXPORT_TEMPLATE_STYLE_MATCH__declspec(dllimport))
+//     EXPORT_TEMPLATE_STYLE_MATCH__declspec(dllimport)
+//     EXPORT_TEMPLATE_STYLE_MATCH_DECLSPEC_dllimport
+//     DEFAULT
+#define EXPORT_TEMPLATE_STYLE(export, _) EXPORT_TEMPLATE_STYLE_2(export, )
+#define EXPORT_TEMPLATE_STYLE_2(export, _) \
+  EXPORT_TEMPLATE_STYLE_3(                 \
+      EXPORT_TEMPLATE_STYLE_MATCH_foj3FJo5StF0OvIzl7oMxA##export)
+#define EXPORT_TEMPLATE_STYLE_3(style) style
+
+// Internal helper macros for EXPORT_TEMPLATE_STYLE.
+//
+// XXX: C++ reserves all identifiers containing "__" for the implementation,
+// but "__attribute__" and "__declspec" already contain "__" and the token-paste
+// operator can only add characters; not remove them.  To minimize the risk of
+// conflict with implementations, we include "foj3FJo5StF0OvIzl7oMxA" (a random
+// 128-bit string, encoded in Base64) in the macro name.
+#define EXPORT_TEMPLATE_STYLE_MATCH_foj3FJo5StF0OvIzl7oMxA DEFAULT
+#define EXPORT_TEMPLATE_STYLE_MATCH_foj3FJo5StF0OvIzl7oMxA__attribute__(...) \
+  DEFAULT
+#define EXPORT_TEMPLATE_STYLE_MATCH_foj3FJo5StF0OvIzl7oMxA__declspec(arg) \
+  EXPORT_TEMPLATE_STYLE_MATCH_DECLSPEC_##arg
+
+// Internal helper macros for EXPORT_TEMPLATE_STYLE.
+#define EXPORT_TEMPLATE_STYLE_MATCH_DECLSPEC_dllexport MSVC_HACK
+#define EXPORT_TEMPLATE_STYLE_MATCH_DECLSPEC_dllimport DEFAULT
+
+// Sanity checks.
+//
+// EXPORT_TEMPLATE_TEST uses the same macro invocation pattern as
+// EXPORT_TEMPLATE_DECLARE and EXPORT_TEMPLATE_DEFINE do to check that they're
+// working correctly.  When they're working correctly, the sequence of macro
+// replacements should go something like:
+//
+//     EXPORT_TEMPLATE_TEST(DEFAULT, __declspec(dllimport));
+//
+//     static_assert(EXPORT_TEMPLATE_INVOKE(TEST_DEFAULT,
+//         EXPORT_TEMPLATE_STYLE(__declspec(dllimport), ),
+//         __declspec(dllimport)), "__declspec(dllimport)");
+//
+//     static_assert(EXPORT_TEMPLATE_INVOKE(TEST_DEFAULT,
+//         DEFAULT, __declspec(dllimport)), "__declspec(dllimport)");
+//
+//     static_assert(EXPORT_TEMPLATE_TEST_DEFAULT_DEFAULT(
+//         __declspec(dllimport)), "__declspec(dllimport)");
+//
+//     static_assert(true, "__declspec(dllimport)");
+//
+// When they're not working correctly, a syntax error should occur instead.
+#define EXPORT_TEMPLATE_TEST(want, export)                                 \
+  static_assert(EXPORT_TEMPLATE_INVOKE(                                    \
+                    TEST_##want, EXPORT_TEMPLATE_STYLE(export, ), export), \
+                #export)
+#define EXPORT_TEMPLATE_TEST_DEFAULT_DEFAULT(...) true
+#define EXPORT_TEMPLATE_TEST_MSVC_HACK_MSVC_HACK(...) true
+
+EXPORT_TEMPLATE_TEST(DEFAULT, );
+EXPORT_TEMPLATE_TEST(DEFAULT, __attribute__((visibility("default"))));
+EXPORT_TEMPLATE_TEST(MSVC_HACK, __declspec(dllexport));
+EXPORT_TEMPLATE_TEST(DEFAULT, __declspec(dllimport));
+
+#undef EXPORT_TEMPLATE_TEST
+#undef EXPORT_TEMPLATE_TEST_DEFAULT_DEFAULT
+#undef EXPORT_TEMPLATE_TEST_MSVC_HACK_MSVC_HACK
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/Synchronization.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/Synchronization.h
index 57fc4ee..4ac3c8c 100644
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/Synchronization.h
+++ b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/Synchronization.h
@@ -4,12 +4,11 @@
 
 #pragma once
 
+#ifdef __cplusplus
 #include <climits>  // NOLINT
 
-#ifdef __cplusplus
 #include <initializer_list>
-
-#include "wpi/span.h"
+#include <span>
 #endif
 
 /**
@@ -43,8 +42,8 @@
 constexpr int kHandleTypeSemaphore = 2;
 constexpr int kHandleTypeCSBase = 3;
 constexpr int kHandleTypeNTBase = 16;
-constexpr int kHandleTypeHALBase = 32;
-constexpr int kHandleTypeUserBase = 64;
+constexpr int kHandleTypeHALBase = 48;
+constexpr int kHandleTypeUserBase = 80;
 /** @} */
 
 /**
@@ -149,8 +148,8 @@
  *        least the size of the handles input array
  * @return array of signaled handles (points into signaled array)
  */
-wpi::span<WPI_Handle> WaitForObjects(wpi::span<const WPI_Handle> handles,
-                                     wpi::span<WPI_Handle> signaled);
+std::span<WPI_Handle> WaitForObjects(std::span<const WPI_Handle> handles,
+                                     std::span<WPI_Handle> signaled);
 
 /**
  * Waits for one or more handles to be signaled.
@@ -163,9 +162,9 @@
  *        least the size of the handles input array
  * @return array of signaled handles (points into signaled array)
  */
-inline wpi::span<WPI_Handle> WaitForObjects(
-    std::initializer_list<WPI_Handle> handles, wpi::span<WPI_Handle> signaled) {
-  return WaitForObjects(wpi::span{handles.begin(), handles.size()}, signaled);
+inline std::span<WPI_Handle> WaitForObjects(
+    std::initializer_list<WPI_Handle> handles, std::span<WPI_Handle> signaled) {
+  return WaitForObjects(std::span{handles.begin(), handles.size()}, signaled);
 }
 
 /**
@@ -182,8 +181,8 @@
  *        handle being signaled; set to false otherwise (output)
  * @return array of signaled handles (points into signaled array)
  */
-wpi::span<WPI_Handle> WaitForObjects(wpi::span<const WPI_Handle> handles,
-                                     wpi::span<WPI_Handle> signaled,
+std::span<WPI_Handle> WaitForObjects(std::span<const WPI_Handle> handles,
+                                     std::span<WPI_Handle> signaled,
                                      double timeout, bool* timedOut);
 /**
  * Waits for one or more handles to be signaled, with timeout.
@@ -199,10 +198,10 @@
  *        handle being signaled; set to false otherwise (output)
  * @return array of signaled handles (points into signaled array)
  */
-inline wpi::span<WPI_Handle> WaitForObjects(
-    std::initializer_list<WPI_Handle> handles, wpi::span<WPI_Handle> signaled,
+inline std::span<WPI_Handle> WaitForObjects(
+    std::initializer_list<WPI_Handle> handles, std::span<WPI_Handle> signaled,
     double timeout, bool* timedOut) {
-  return WaitForObjects(wpi::span{handles.begin(), handles.size()}, signaled,
+  return WaitForObjects(std::span{handles.begin(), handles.size()}, signaled,
                         timeout, timedOut);
 }
 
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/TCPAcceptor.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/TCPAcceptor.h
deleted file mode 100644
index 083897a..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/TCPAcceptor.h
+++ /dev/null
@@ -1,58 +0,0 @@
-/*
-   TCPAcceptor.h
-
-   TCPAcceptor class interface. TCPAcceptor provides methods to passively
-   establish TCP/IP connections with clients.
-
-   ------------------------------------------
-
-   Copyright (c) 2013 [Vic Hargrave - http://vichargrave.com]
-
-   Licensed under the Apache License, Version 2.0 (the "License");
-   you may not use this file except in compliance with the License.
-   You may obtain a copy of the License at
-
-       http://www.apache.org/licenses/LICENSE-2.0
-
-   Unless required by applicable law or agreed to in writing, software
-   distributed under the License is distributed on an "AS IS" BASIS,
-   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-   See the License for the specific language governing permissions and
-   limitations under the License.
-*/
-
-#ifndef WPIUTIL_WPI_TCPACCEPTOR_H_
-#define WPIUTIL_WPI_TCPACCEPTOR_H_
-
-#include <atomic>
-#include <memory>
-#include <string>
-#include <string_view>
-
-#include "wpi/NetworkAcceptor.h"
-#include "wpi/TCPStream.h"
-
-namespace wpi {
-
-class Logger;
-
-class TCPAcceptor : public NetworkAcceptor {
-  int m_lsd;
-  int m_port;
-  std::string m_address;
-  bool m_listening;
-  std::atomic_bool m_shutdown;
-  Logger& m_logger;
-
- public:
-  TCPAcceptor(int port, std::string_view address, Logger& logger);
-  ~TCPAcceptor() override;
-
-  int start() override;
-  void shutdown() final;
-  std::unique_ptr<NetworkStream> accept() override;
-};
-
-}  // namespace wpi
-
-#endif  // WPIUTIL_WPI_TCPACCEPTOR_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/TCPConnector.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/TCPConnector.h
deleted file mode 100644
index 63e8906..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/TCPConnector.h
+++ /dev/null
@@ -1,49 +0,0 @@
-/*
-   TCPConnector.h
-
-   TCPConnector class interface. TCPConnector provides methods to actively
-   establish TCP/IP connections with a server.
-
-   ------------------------------------------
-
-   Copyright (c) 2013 [Vic Hargrave - http://vichargrave.com]
-
-   Licensed under the Apache License, Version 2.0 (the "License");
-   you may not use this file except in compliance with the License.
-   You may obtain a copy of the License at
-
-       http://www.apache.org/licenses/LICENSE-2.0
-
-   Unless required by applicable law or agreed to in writing, software
-   distributed under the License is distributed on an "AS IS" BASIS,
-   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-   See the License for the specific language governing permissions and
-   limitations under the License
-*/
-
-#ifndef WPIUTIL_WPI_TCPCONNECTOR_H_
-#define WPIUTIL_WPI_TCPCONNECTOR_H_
-
-#include <memory>
-#include <utility>
-
-#include "wpi/NetworkStream.h"
-#include "wpi/span.h"
-
-namespace wpi {
-
-class Logger;
-
-class TCPConnector {
- public:
-  static std::unique_ptr<NetworkStream> connect(const char* server, int port,
-                                                Logger& logger,
-                                                int timeout = 0);
-  static std::unique_ptr<NetworkStream> connect_parallel(
-      span<const std::pair<const char*, int>> servers, Logger& logger,
-      int timeout = 0);
-};
-
-}  // namespace wpi
-
-#endif  // WPIUTIL_WPI_TCPCONNECTOR_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/TCPStream.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/TCPStream.h
deleted file mode 100644
index 2d54300..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/TCPStream.h
+++ /dev/null
@@ -1,72 +0,0 @@
-/*
-   TCPStream.h
-
-   TCPStream class interface. TCPStream provides methods to transfer
-   data between peers over a TCP/IP connection.
-
-   ------------------------------------------
-
-   Copyright (c) 2013 [Vic Hargrave - http://vichargrave.com]
-
-   Licensed under the Apache License, Version 2.0 (the "License");
-   you may not use this file except in compliance with the License.
-   You may obtain a copy of the License at
-
-       http://www.apache.org/licenses/LICENSE-2.0
-
-   Unless required by applicable law or agreed to in writing, software
-   distributed under the License is distributed on an "AS IS" BASIS,
-   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-   See the License for the specific language governing permissions and
-   limitations under the License.
-*/
-
-#ifndef WPIUTIL_WPI_TCPSTREAM_H_
-#define WPIUTIL_WPI_TCPSTREAM_H_
-
-#include <cstddef>
-#include <string>
-#include <string_view>
-
-#include "wpi/NetworkStream.h"
-
-struct sockaddr_in;
-
-namespace wpi {
-
-class TCPStream : public NetworkStream {
-  int m_sd;
-  std::string m_peerIP;
-  int m_peerPort;
-  bool m_blocking;
-
- public:
-  friend class TCPAcceptor;
-  friend class TCPConnector;
-
-  ~TCPStream() override;
-
-  size_t send(const char* buffer, size_t len, Error* err) override;
-  size_t receive(char* buffer, size_t len, Error* err,
-                 int timeout = 0) override;
-  void close() final;
-
-  std::string_view getPeerIP() const override;
-  int getPeerPort() const override;
-  void setNoDelay() override;
-  bool setBlocking(bool enabled) override;
-  int getNativeHandle() const override;
-
-  TCPStream(const TCPStream& stream) = delete;
-  TCPStream& operator=(const TCPStream&) = delete;
-
- private:
-  bool WaitForReadEvent(int timeout);
-
-  TCPStream(int sd, sockaddr_in* address);
-  TCPStream() = delete;
-};
-
-}  // namespace wpi
-
-#endif  // WPIUTIL_WPI_TCPSTREAM_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/UDPClient.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/UDPClient.h
deleted file mode 100644
index fd2e30b..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/UDPClient.h
+++ /dev/null
@@ -1,49 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_UDPCLIENT_H_
-#define WPIUTIL_WPI_UDPCLIENT_H_
-
-#include <string>
-#include <string_view>
-
-#include "wpi/SmallVector.h"
-#include "wpi/mutex.h"
-#include "wpi/span.h"
-
-namespace wpi {
-
-class Logger;
-
-class UDPClient {
-  int m_lsd;
-  int m_port;
-  std::string m_address;
-  Logger& m_logger;
-
- public:
-  explicit UDPClient(Logger& logger);
-  UDPClient(std::string_view address, Logger& logger);
-  UDPClient(const UDPClient& other) = delete;
-  UDPClient(UDPClient&& other);
-  ~UDPClient();
-
-  UDPClient& operator=(const UDPClient& other) = delete;
-  UDPClient& operator=(UDPClient&& other);
-
-  int start();
-  int start(int port);
-  void shutdown();
-  // The passed in address MUST be a resolved IP address.
-  int send(span<const uint8_t> data, std::string_view server, int port);
-  int send(std::string_view data, std::string_view server, int port);
-  int receive(uint8_t* data_received, int receive_len);
-  int receive(uint8_t* data_received, int receive_len,
-              SmallVectorImpl<char>* addr_received, int* port_received);
-  int set_timeout(double timeout);
-};
-
-}  // namespace wpi
-
-#endif  // WPIUTIL_WPI_UDPCLIENT_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/UrlParser.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/UrlParser.h
deleted file mode 100644
index 1932c3e..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/UrlParser.h
+++ /dev/null
@@ -1,95 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_URLPARSER_H_
-#define WPIUTIL_WPI_URLPARSER_H_
-
-#include <string_view>
-
-#include "wpi/StringExtras.h"
-#include "wpi/http_parser.h"
-
-namespace wpi {
-
-/**
- * Parses a URL into its constiuent components.
- * `schema://userinfo@host:port/the/path?query#fragment`
- */
-class UrlParser {
- public:
-  /**
-   * Parse a URL.
-   * @param in input
-   * @param isConnect
-   */
-  UrlParser(std::string_view in, bool isConnect) {
-    m_data = in;
-    http_parser_url_init(&m_url);
-    m_error = http_parser_parse_url(in.data(), in.size(), isConnect, &m_url);
-  }
-
-  /**
-   * Determine if the URL is valid (e.g. the parse was successful).
-   */
-  bool IsValid() const { return !m_error; }
-
-  bool HasSchema() const { return (m_url.field_set & (1 << UF_SCHEMA)) != 0; }
-
-  bool HasHost() const { return (m_url.field_set & (1 << UF_HOST)) != 0; }
-
-  bool HasPort() const { return (m_url.field_set & (1 << UF_PORT)) != 0; }
-
-  bool HasPath() const { return (m_url.field_set & (1 << UF_PATH)) != 0; }
-
-  bool HasQuery() const { return (m_url.field_set & (1 << UF_QUERY)) != 0; }
-
-  bool HasFragment() const {
-    return (m_url.field_set & (1 << UF_FRAGMENT)) != 0;
-  }
-
-  bool HasUserInfo() const {
-    return (m_url.field_set & (1 << UF_USERINFO)) != 0;
-  }
-
-  std::string_view GetSchema() const {
-    return wpi::substr(m_data, m_url.field_data[UF_SCHEMA].off,
-                       m_url.field_data[UF_SCHEMA].len);
-  }
-
-  std::string_view GetHost() const {
-    return wpi::substr(m_data, m_url.field_data[UF_HOST].off,
-                       m_url.field_data[UF_HOST].len);
-  }
-
-  unsigned int GetPort() const { return m_url.port; }
-
-  std::string_view GetPath() const {
-    return wpi::substr(m_data, m_url.field_data[UF_PATH].off,
-                       m_url.field_data[UF_PATH].len);
-  }
-
-  std::string_view GetQuery() const {
-    return wpi::substr(m_data, m_url.field_data[UF_QUERY].off,
-                       m_url.field_data[UF_QUERY].len);
-  }
-
-  std::string_view GetFragment() const {
-    return wpi::substr(m_data, m_url.field_data[UF_FRAGMENT].off,
-                       m_url.field_data[UF_FRAGMENT].len);
-  }
-
-  std::string_view GetUserInfo() const {
-    return wpi::substr(m_data, m_url.field_data[UF_USERINFO].off,
-                       m_url.field_data[UF_USERINFO].len);
-  }
-
- private:
-  bool m_error;
-  std::string_view m_data;
-  http_parser_url m_url;
-};
-
-}  // namespace wpi
-
-#endif  // WPIUTIL_WPI_URLPARSER_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/VersionTuple.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/VersionTuple.h
deleted file mode 100644
index 59df41c..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/VersionTuple.h
+++ /dev/null
@@ -1,140 +0,0 @@
-//===- VersionTuple.h - Version Number Handling -----------------*- C++ -*-===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-///
-/// \file
-/// Defines the llvm::VersionTuple class, which represents a version in
-/// the form major[.minor[.subminor]].
-///
-//===----------------------------------------------------------------------===//
-#ifndef WPIUTIL_WPI_VERSIONTUPLE_H
-#define WPIUTIL_WPI_VERSIONTUPLE_H
-
-#include <optional>
-#include <string>
-
-namespace wpi {
-
-/// Represents a version number in the form major[.minor[.subminor[.build]]].
-class VersionTuple {
-  unsigned Major : 32;
-
-  unsigned Minor : 31;
-  unsigned HasMinor : 1;
-
-  unsigned Subminor : 31;
-  unsigned HasSubminor : 1;
-
-  unsigned Build : 31;
-  unsigned HasBuild : 1;
-
-public:
-  VersionTuple()
-      : Major(0), Minor(0), HasMinor(false), Subminor(0), HasSubminor(false),
-        Build(0), HasBuild(false) {}
-
-  explicit VersionTuple(unsigned Major)
-      : Major(Major), Minor(0), HasMinor(false), Subminor(0),
-        HasSubminor(false), Build(0), HasBuild(false) {}
-
-  explicit VersionTuple(unsigned Major, unsigned Minor)
-      : Major(Major), Minor(Minor), HasMinor(true), Subminor(0),
-        HasSubminor(false), Build(0), HasBuild(false) {}
-
-  explicit VersionTuple(unsigned Major, unsigned Minor, unsigned Subminor)
-      : Major(Major), Minor(Minor), HasMinor(true), Subminor(Subminor),
-        HasSubminor(true), Build(0), HasBuild(false) {}
-
-  explicit VersionTuple(unsigned Major, unsigned Minor, unsigned Subminor,
-                        unsigned Build)
-      : Major(Major), Minor(Minor), HasMinor(true), Subminor(Subminor),
-        HasSubminor(true), Build(Build), HasBuild(true) {}
-
-  /// Determine whether this version information is empty
-  /// (e.g., all version components are zero).
-  bool empty() const {
-    return Major == 0 && Minor == 0 && Subminor == 0 && Build == 0;
-  }
-
-  /// Retrieve the major version number.
-  unsigned getMajor() const { return Major; }
-
-  /// Retrieve the minor version number, if provided.
-  std::optional<unsigned> getMinor() const {
-    if (!HasMinor)
-      return std::nullopt;
-    return Minor;
-  }
-
-  /// Retrieve the subminor version number, if provided.
-  std::optional<unsigned> getSubminor() const {
-    if (!HasSubminor)
-      return std::nullopt;
-    return Subminor;
-  }
-
-  /// Retrieve the build version number, if provided.
-  std::optional<unsigned> getBuild() const {
-    if (!HasBuild)
-      return std::nullopt;
-    return Build;
-  }
-
-  /// Determine if two version numbers are equivalent. If not
-  /// provided, minor and subminor version numbers are considered to be zero.
-  friend bool operator==(const VersionTuple &X, const VersionTuple &Y) {
-    return X.Major == Y.Major && X.Minor == Y.Minor &&
-           X.Subminor == Y.Subminor && X.Build == Y.Build;
-  }
-
-  /// Determine if two version numbers are not equivalent.
-  ///
-  /// If not provided, minor and subminor version numbers are considered to be
-  /// zero.
-  friend bool operator!=(const VersionTuple &X, const VersionTuple &Y) {
-    return !(X == Y);
-  }
-
-  /// Determine whether one version number precedes another.
-  ///
-  /// If not provided, minor and subminor version numbers are considered to be
-  /// zero.
-  friend bool operator<(const VersionTuple &X, const VersionTuple &Y) {
-    return std::tie(X.Major, X.Minor, X.Subminor, X.Build) <
-           std::tie(Y.Major, Y.Minor, Y.Subminor, Y.Build);
-  }
-
-  /// Determine whether one version number follows another.
-  ///
-  /// If not provided, minor and subminor version numbers are considered to be
-  /// zero.
-  friend bool operator>(const VersionTuple &X, const VersionTuple &Y) {
-    return Y < X;
-  }
-
-  /// Determine whether one version number precedes or is
-  /// equivalent to another.
-  ///
-  /// If not provided, minor and subminor version numbers are considered to be
-  /// zero.
-  friend bool operator<=(const VersionTuple &X, const VersionTuple &Y) {
-    return !(Y < X);
-  }
-
-  /// Determine whether one version number follows or is
-  /// equivalent to another.
-  ///
-  /// If not provided, minor and subminor version numbers are considered to be
-  /// zero.
-  friend bool operator>=(const VersionTuple &X, const VersionTuple &Y) {
-    return !(X < Y);
-  }
-};
-
-} // end namespace wpi
-#endif // WPIUTIL_WPI_VERSIONTUPLE_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/WebSocket.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/WebSocket.h
deleted file mode 100644
index fc2ae4a..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/WebSocket.h
+++ /dev/null
@@ -1,477 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_WEBSOCKET_H_
-#define WPIUTIL_WPI_WEBSOCKET_H_
-
-#include <stdint.h>
-
-#include <functional>
-#include <initializer_list>
-#include <memory>
-#include <string>
-#include <string_view>
-#include <utility>
-
-#include "wpi/Signal.h"
-#include "wpi/SmallVector.h"
-#include "wpi/span.h"
-#include "wpi/uv/Buffer.h"
-#include "wpi/uv/Error.h"
-#include "wpi/uv/Timer.h"
-
-namespace wpi {
-
-namespace uv {
-class Stream;
-}  // namespace uv
-
-/**
- * RFC 6455 compliant WebSocket client and server implementation.
- */
-class WebSocket : public std::enable_shared_from_this<WebSocket> {
-  struct private_init {};
-
-  static constexpr uint8_t kOpCont = 0x00;
-  static constexpr uint8_t kOpText = 0x01;
-  static constexpr uint8_t kOpBinary = 0x02;
-  static constexpr uint8_t kOpClose = 0x08;
-  static constexpr uint8_t kOpPing = 0x09;
-  static constexpr uint8_t kOpPong = 0x0A;
-  static constexpr uint8_t kOpMask = 0x0F;
-  static constexpr uint8_t kFlagFin = 0x80;
-  static constexpr uint8_t kFlagMasking = 0x80;
-  static constexpr uint8_t kLenMask = 0x7f;
-
- public:
-  WebSocket(uv::Stream& stream, bool server, const private_init&);
-  WebSocket(const WebSocket&) = delete;
-  WebSocket(WebSocket&&) = delete;
-  WebSocket& operator=(const WebSocket&) = delete;
-  WebSocket& operator=(WebSocket&&) = delete;
-  ~WebSocket();
-
-  /**
-   * Connection states.
-   */
-  enum State {
-    /** The connection is not yet open. */
-    CONNECTING = 0,
-    /** The connection is open and ready to communicate. */
-    OPEN,
-    /** The connection is in the process of closing. */
-    CLOSING,
-    /** The connection failed. */
-    FAILED,
-    /** The connection is closed. */
-    CLOSED
-  };
-
-  /**
-   * Client connection options.
-   */
-  struct ClientOptions {
-    ClientOptions() : handshakeTimeout{(uv::Timer::Time::max)()} {}
-
-    /** Timeout for the handshake request. */
-    uv::Timer::Time handshakeTimeout;  // NOLINT
-
-    /** Additional headers to include in handshake. */
-    span<const std::pair<std::string_view, std::string_view>> extraHeaders;
-  };
-
-  /**
-   * Starts a client connection by performing the initial client handshake.
-   * An open event is emitted when the handshake completes.
-   * This sets the stream user data to the websocket.
-   * @param stream Connection stream
-   * @param uri The Request-URI to send
-   * @param host The host or host:port to send
-   * @param protocols The list of subprotocols
-   * @param options Handshake options
-   */
-  static std::shared_ptr<WebSocket> CreateClient(
-      uv::Stream& stream, std::string_view uri, std::string_view host,
-      span<const std::string_view> protocols = {},
-      const ClientOptions& options = {});
-
-  /**
-   * Starts a client connection by performing the initial client handshake.
-   * An open event is emitted when the handshake completes.
-   * This sets the stream user data to the websocket.
-   * @param stream Connection stream
-   * @param uri The Request-URI to send
-   * @param host The host or host:port to send
-   * @param protocols The list of subprotocols
-   * @param options Handshake options
-   */
-  static std::shared_ptr<WebSocket> CreateClient(
-      uv::Stream& stream, std::string_view uri, std::string_view host,
-      std::initializer_list<std::string_view> protocols,
-      const ClientOptions& options = {}) {
-    return CreateClient(stream, uri, host, {protocols.begin(), protocols.end()},
-                        options);
-  }
-
-  /**
-   * Starts a server connection by performing the initial server side handshake.
-   * This should be called after the HTTP headers have been received.
-   * An open event is emitted when the handshake completes.
-   * This sets the stream user data to the websocket.
-   * @param stream Connection stream
-   * @param key The value of the Sec-WebSocket-Key header field in the client
-   *            request
-   * @param version The value of the Sec-WebSocket-Version header field in the
-   *                client request
-   * @param protocol The subprotocol to send to the client (in the
-   *                 Sec-WebSocket-Protocol header field).
-   */
-  static std::shared_ptr<WebSocket> CreateServer(
-      uv::Stream& stream, std::string_view key, std::string_view version,
-      std::string_view protocol = {});
-
-  /**
-   * Get connection state.
-   */
-  State GetState() const { return m_state; }
-
-  /**
-   * Return if the connection is open.  Messages can only be sent on open
-   * connections.
-   */
-  bool IsOpen() const { return m_state == OPEN; }
-
-  /**
-   * Get the underlying stream.
-   */
-  uv::Stream& GetStream() const { return m_stream; }
-
-  /**
-   * Get the selected sub-protocol.  Only valid in or after the open() event.
-   */
-  std::string_view GetProtocol() const { return m_protocol; }
-
-  /**
-   * Set the maximum message size.  Default is 128 KB.  If configured to combine
-   * fragments this maximum applies to the entire message (all combined
-   * fragments).
-   * @param size Maximum message size in bytes
-   */
-  void SetMaxMessageSize(size_t size) { m_maxMessageSize = size; }
-
-  /**
-   * Set whether or not fragmented frames should be combined.  Default is to
-   * combine.  If fragmented frames are combined, the text and binary callbacks
-   * will always have the second parameter (fin) set to true.
-   * @param combine True if fragmented frames should be combined.
-   */
-  void SetCombineFragments(bool combine) { m_combineFragments = combine; }
-
-  /**
-   * Initiate a closing handshake.
-   * @param code A numeric status code (defaults to 1005, no status code)
-   * @param reason A human-readable string explaining why the connection is
-   *               closing (optional).
-   */
-  void Close(uint16_t code = 1005, std::string_view reason = {});
-
-  /**
-   * Send a text message.
-   * @param data UTF-8 encoded data to send
-   * @param callback Callback which is invoked when the write completes.
-   */
-  void SendText(span<const uv::Buffer> data,
-                std::function<void(span<uv::Buffer>, uv::Error)> callback) {
-    Send(kFlagFin | kOpText, data, std::move(callback));
-  }
-
-  /**
-   * Send a text message.
-   * @param data UTF-8 encoded data to send
-   * @param callback Callback which is invoked when the write completes.
-   */
-  void SendText(std::initializer_list<uv::Buffer> data,
-                std::function<void(span<uv::Buffer>, uv::Error)> callback) {
-    SendText({data.begin(), data.end()}, std::move(callback));
-  }
-
-  /**
-   * Send a binary message.
-   * @param data Data to send
-   * @param callback Callback which is invoked when the write completes.
-   */
-  void SendBinary(span<const uv::Buffer> data,
-                  std::function<void(span<uv::Buffer>, uv::Error)> callback) {
-    Send(kFlagFin | kOpBinary, data, std::move(callback));
-  }
-
-  /**
-   * Send a binary message.
-   * @param data Data to send
-   * @param callback Callback which is invoked when the write completes.
-   */
-  void SendBinary(std::initializer_list<uv::Buffer> data,
-                  std::function<void(span<uv::Buffer>, uv::Error)> callback) {
-    SendBinary({data.begin(), data.end()}, std::move(callback));
-  }
-
-  /**
-   * Send a text message fragment.  This must be followed by one or more
-   * SendFragment() calls, where the last one has fin=True, to complete the
-   * message.
-   * @param data UTF-8 encoded data to send
-   * @param callback Callback which is invoked when the write completes.
-   */
-  void SendTextFragment(
-      span<const uv::Buffer> data,
-      std::function<void(span<uv::Buffer>, uv::Error)> callback) {
-    Send(kOpText, data, std::move(callback));
-  }
-
-  /**
-   * Send a text message fragment.  This must be followed by one or more
-   * SendFragment() calls, where the last one has fin=True, to complete the
-   * message.
-   * @param data UTF-8 encoded data to send
-   * @param callback Callback which is invoked when the write completes.
-   */
-  void SendTextFragment(
-      std::initializer_list<uv::Buffer> data,
-      std::function<void(span<uv::Buffer>, uv::Error)> callback) {
-    SendTextFragment({data.begin(), data.end()}, std::move(callback));
-  }
-
-  /**
-   * Send a text message fragment.  This must be followed by one or more
-   * SendFragment() calls, where the last one has fin=True, to complete the
-   * message.
-   * @param data Data to send
-   * @param callback Callback which is invoked when the write completes.
-   */
-  void SendBinaryFragment(
-      span<const uv::Buffer> data,
-      std::function<void(span<uv::Buffer>, uv::Error)> callback) {
-    Send(kOpBinary, data, std::move(callback));
-  }
-
-  /**
-   * Send a text message fragment.  This must be followed by one or more
-   * SendFragment() calls, where the last one has fin=True, to complete the
-   * message.
-   * @param data Data to send
-   * @param callback Callback which is invoked when the write completes.
-   */
-  void SendBinaryFragment(
-      std::initializer_list<uv::Buffer> data,
-      std::function<void(span<uv::Buffer>, uv::Error)> callback) {
-    SendBinaryFragment({data.begin(), data.end()}, std::move(callback));
-  }
-
-  /**
-   * Send a continuation frame.  This is used to send additional parts of a
-   * message started with SendTextFragment() or SendBinaryFragment().
-   * @param data Data to send
-   * @param fin Set to true if this is the final fragment of the message
-   * @param callback Callback which is invoked when the write completes.
-   */
-  void SendFragment(span<const uv::Buffer> data, bool fin,
-                    std::function<void(span<uv::Buffer>, uv::Error)> callback) {
-    Send(kOpCont | (fin ? kFlagFin : 0), data, std::move(callback));
-  }
-
-  /**
-   * Send a continuation frame.  This is used to send additional parts of a
-   * message started with SendTextFragment() or SendBinaryFragment().
-   * @param data Data to send
-   * @param fin Set to true if this is the final fragment of the message
-   * @param callback Callback which is invoked when the write completes.
-   */
-  void SendFragment(std::initializer_list<uv::Buffer> data, bool fin,
-                    std::function<void(span<uv::Buffer>, uv::Error)> callback) {
-    SendFragment({data.begin(), data.end()}, fin, std::move(callback));
-  }
-
-  /**
-   * Send a ping frame with no data.
-   * @param callback Optional callback which is invoked when the ping frame
-   *                 write completes.
-   */
-  void SendPing(std::function<void(uv::Error)> callback = nullptr) {
-    SendPing({}, [f = std::move(callback)](auto bufs, uv::Error err) {
-      if (f) {
-        f(err);
-      }
-    });
-  }
-
-  /**
-   * Send a ping frame.
-   * @param data Data to send in the ping frame
-   * @param callback Callback which is invoked when the ping frame
-   *                 write completes.
-   */
-  void SendPing(span<const uv::Buffer> data,
-                std::function<void(span<uv::Buffer>, uv::Error)> callback) {
-    Send(kFlagFin | kOpPing, data, std::move(callback));
-  }
-
-  /**
-   * Send a ping frame.
-   * @param data Data to send in the ping frame
-   * @param callback Callback which is invoked when the ping frame
-   *                 write completes.
-   */
-  void SendPing(std::initializer_list<uv::Buffer> data,
-                std::function<void(span<uv::Buffer>, uv::Error)> callback) {
-    SendPing({data.begin(), data.end()}, std::move(callback));
-  }
-
-  /**
-   * Send a pong frame with no data.
-   * @param callback Optional callback which is invoked when the pong frame
-   *                 write completes.
-   */
-  void SendPong(std::function<void(uv::Error)> callback = nullptr) {
-    SendPong({}, [f = std::move(callback)](auto bufs, uv::Error err) {
-      if (f) {
-        f(err);
-      }
-    });
-  }
-
-  /**
-   * Send a pong frame.
-   * @param data Data to send in the pong frame
-   * @param callback Callback which is invoked when the pong frame
-   *                 write completes.
-   */
-  void SendPong(span<const uv::Buffer> data,
-                std::function<void(span<uv::Buffer>, uv::Error)> callback) {
-    Send(kFlagFin | kOpPong, data, std::move(callback));
-  }
-
-  /**
-   * Send a pong frame.
-   * @param data Data to send in the pong frame
-   * @param callback Callback which is invoked when the pong frame
-   *                 write completes.
-   */
-  void SendPong(std::initializer_list<uv::Buffer> data,
-                std::function<void(span<uv::Buffer>, uv::Error)> callback) {
-    SendPong({data.begin(), data.end()}, std::move(callback));
-  }
-
-  /**
-   * Fail the connection.
-   */
-  void Fail(uint16_t code = 1002, std::string_view reason = "protocol error");
-
-  /**
-   * Forcibly close the connection.
-   */
-  void Terminate(uint16_t code = 1006, std::string_view reason = "terminated");
-
-  /**
-   * Gets user-defined data.
-   * @return User-defined data if any, nullptr otherwise.
-   */
-  template <typename T = void>
-  std::shared_ptr<T> GetData() const {
-    return std::static_pointer_cast<T>(m_data);
-  }
-
-  /**
-   * Sets user-defined data.
-   * @param data User-defined arbitrary data.
-   */
-  void SetData(std::shared_ptr<void> data) { m_data = std::move(data); }
-
-  /**
-   * Shuts down and closes the underlying stream.
-   */
-  void Shutdown();
-
-  /**
-   * Open event.  Emitted when the connection is open and ready to communicate.
-   * The parameter is the selected subprotocol.
-   */
-  sig::Signal<std::string_view> open;
-
-  /**
-   * Close event.  Emitted when the connection is closed.  The first parameter
-   * is a numeric value indicating the status code explaining why the connection
-   * has been closed.  The second parameter is a human-readable string
-   * explaining the reason why the connection has been closed.
-   */
-  sig::Signal<uint16_t, std::string_view> closed;
-
-  /**
-   * Text message event.  Emitted when a text message is received.
-   * The first parameter is the data, the second parameter is true if the
-   * data is the last fragment of the message.
-   */
-  sig::Signal<std::string_view, bool> text;
-
-  /**
-   * Binary message event.  Emitted when a binary message is received.
-   * The first parameter is the data, the second parameter is true if the
-   * data is the last fragment of the message.
-   */
-  sig::Signal<span<const uint8_t>, bool> binary;
-
-  /**
-   * Ping event.  Emitted when a ping message is received.
-   */
-  sig::Signal<span<const uint8_t>> ping;
-
-  /**
-   * Pong event.  Emitted when a pong message is received.
-   */
-  sig::Signal<span<const uint8_t>> pong;
-
- private:
-  // user data
-  std::shared_ptr<void> m_data;
-
-  // constructor parameters
-  uv::Stream& m_stream;
-  bool m_server;
-
-  // subprotocol, set via constructor (server) or handshake (client)
-  std::string m_protocol;
-
-  // user-settable configuration
-  size_t m_maxMessageSize = 128 * 1024;
-  bool m_combineFragments = true;
-
-  // operating state
-  State m_state = CONNECTING;
-
-  // incoming message buffers/state
-  SmallVector<uint8_t, 14> m_header;
-  size_t m_headerSize = 0;
-  SmallVector<uint8_t, 1024> m_payload;
-  size_t m_frameStart = 0;
-  uint64_t m_frameSize = UINT64_MAX;
-  uint8_t m_fragmentOpcode = 0;
-
-  // temporary data used only during client handshake
-  class ClientHandshakeData;
-  std::unique_ptr<ClientHandshakeData> m_clientHandshake;
-
-  void StartClient(std::string_view uri, std::string_view host,
-                   span<const std::string_view> protocols,
-                   const ClientOptions& options);
-  void StartServer(std::string_view key, std::string_view version,
-                   std::string_view protocol);
-  void SendClose(uint16_t code, std::string_view reason);
-  void SetClosed(uint16_t code, std::string_view reason, bool failed = false);
-  void HandleIncoming(uv::Buffer& buf, size_t size);
-  void Send(uint8_t opcode, span<const uv::Buffer> data,
-            std::function<void(span<uv::Buffer>, uv::Error)> callback);
-};
-
-}  // namespace wpi
-
-#endif  // WPIUTIL_WPI_WEBSOCKET_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/WebSocketServer.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/WebSocketServer.h
deleted file mode 100644
index 1f76d16..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/WebSocketServer.h
+++ /dev/null
@@ -1,177 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_WEBSOCKETSERVER_H_
-#define WPIUTIL_WPI_WEBSOCKETSERVER_H_
-
-#include <functional>
-#include <initializer_list>
-#include <memory>
-#include <string>
-#include <string_view>
-#include <utility>
-
-#include "wpi/HttpParser.h"
-#include "wpi/Signal.h"
-#include "wpi/SmallString.h"
-#include "wpi/SmallVector.h"
-#include "wpi/WebSocket.h"
-#include "wpi/span.h"
-
-namespace wpi {
-
-namespace uv {
-class Stream;
-}  // namespace uv
-
-/**
- * WebSocket HTTP server helper.  Handles websocket-specific headers.  User
- * must provide the HttpParser.
- */
-class WebSocketServerHelper {
- public:
-  /**
-   * Constructor.
-   * @param req HttpParser for request
-   */
-  explicit WebSocketServerHelper(HttpParser& req);
-
-  /**
-   * Get whether or not this was a websocket upgrade.
-   * Only valid during and after the upgrade event.
-   */
-  bool IsWebsocket() const { return m_websocket; }
-
-  /**
-   * Try to find a match to the list of sub-protocols provided by the client.
-   * The list is priority ordered, so the first match wins.
-   * Only valid during and after the upgrade event.
-   * @param protocols Acceptable protocols
-   * @return Pair; first item is true if a match was made, false if not.
-   *         Second item is the matched protocol if a match was made, otherwise
-   *         is empty.
-   */
-  std::pair<bool, std::string_view> MatchProtocol(
-      span<const std::string_view> protocols);
-
-  /**
-   * Try to find a match to the list of sub-protocols provided by the client.
-   * The list is priority ordered, so the first match wins.
-   * Only valid during and after the upgrade event.
-   * @param protocols Acceptable protocols
-   * @return Pair; first item is true if a match was made, false if not.
-   *         Second item is the matched protocol if a match was made, otherwise
-   *         is empty.
-   */
-  std::pair<bool, std::string_view> MatchProtocol(
-      std::initializer_list<std::string_view> protocols) {
-    return MatchProtocol({protocols.begin(), protocols.end()});
-  }
-
-  /**
-   * Accept the upgrade.  Disconnect other readers (such as the HttpParser
-   * reader) before calling this.  See also WebSocket::CreateServer().
-   * @param stream Connection stream
-   * @param protocol The subprotocol to send to the client
-   */
-  std::shared_ptr<WebSocket> Accept(uv::Stream& stream,
-                                    std::string_view protocol = {}) {
-    return WebSocket::CreateServer(stream, m_key, m_version, protocol);
-  }
-
-  bool IsUpgrade() const { return m_gotHost && m_websocket; }
-
-  /**
-   * Upgrade event.  Call Accept() to accept the upgrade.
-   */
-  sig::Signal<> upgrade;
-
- private:
-  bool m_gotHost = false;
-  bool m_websocket = false;
-  SmallVector<std::string, 2> m_protocols;
-  SmallString<64> m_key;
-  SmallString<16> m_version;
-};
-
-/**
- * Dedicated WebSocket server.
- */
-class WebSocketServer : public std::enable_shared_from_this<WebSocketServer> {
-  struct private_init {};
-
- public:
-  /**
-   * Server options.
-   */
-  struct ServerOptions {
-    /**
-     * Checker for URL.  Return true if URL should be accepted.  By default all
-     * URLs are accepted.
-     */
-    std::function<bool(std::string_view)> checkUrl;
-
-    /**
-     * Checker for Host header.  Return true if Host should be accepted.  By
-     * default all hosts are accepted.
-     */
-    std::function<bool(std::string_view)> checkHost;
-  };
-
-  /**
-   * Private constructor.
-   */
-  WebSocketServer(uv::Stream& stream, span<const std::string_view> protocols,
-                  ServerOptions options, const private_init&);
-
-  /**
-   * Starts a dedicated WebSocket server on the provided connection.  The
-   * connection should be an accepted client stream.
-   * This also sets the stream user data to the socket server.
-   * A connected event is emitted when the connection is opened.
-   * @param stream Connection stream
-   * @param protocols Acceptable subprotocols
-   * @param options Handshake options
-   */
-  static std::shared_ptr<WebSocketServer> Create(
-      uv::Stream& stream, span<const std::string_view> protocols = {},
-      const ServerOptions& options = {});
-
-  /**
-   * Starts a dedicated WebSocket server on the provided connection.  The
-   * connection should be an accepted client stream.
-   * This also sets the stream user data to the socket server.
-   * A connected event is emitted when the connection is opened.
-   * @param stream Connection stream
-   * @param protocols Acceptable subprotocols
-   * @param options Handshake options
-   */
-  static std::shared_ptr<WebSocketServer> Create(
-      uv::Stream& stream, std::initializer_list<std::string_view> protocols,
-      const ServerOptions& options = {}) {
-    return Create(stream, {protocols.begin(), protocols.end()}, options);
-  }
-
-  /**
-   * Connected event.  First parameter is the URL, second is the websocket.
-   */
-  sig::Signal<std::string_view, WebSocket&> connected;
-
- private:
-  uv::Stream& m_stream;
-  HttpParser m_req{HttpParser::kRequest};
-  WebSocketServerHelper m_helper;
-  SmallVector<std::string, 2> m_protocols;
-  ServerOptions m_options;
-  bool m_aborted = false;
-  sig::ScopedConnection m_dataConn;
-  sig::ScopedConnection m_errorConn;
-  sig::ScopedConnection m_endConn;
-
-  void Abort(uint16_t code, std::string_view reason);
-};
-
-}  // namespace wpi
-
-#endif  // WPIUTIL_WPI_WEBSOCKETSERVER_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/WindowsError.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/WindowsError.h
deleted file mode 100644
index 565e2b7..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/WindowsError.h
+++ /dev/null
@@ -1,19 +0,0 @@
-//===-- WindowsError.h - Support for mapping windows errors to posix-------===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-
-#ifndef WPIUTIL_WPI_WINDOWSERROR_H
-#define WPIUTIL_WPI_WINDOWSERROR_H
-
-#include <system_error>
-
-namespace wpi {
-std::error_code mapWindowsError(unsigned EV);
-}
-
-#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/WorkerThread.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/WorkerThread.h
deleted file mode 100644
index 6c8852e..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/WorkerThread.h
+++ /dev/null
@@ -1,285 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_WORKERTHREAD_H_
-#define WPIUTIL_WPI_WORKERTHREAD_H_
-
-#include <functional>
-#include <memory>
-#include <tuple>
-#include <utility>
-#include <vector>
-
-#include "wpi/SafeThread.h"
-#include "wpi/future.h"
-#include "wpi/uv/Async.h"
-
-namespace wpi {
-
-namespace detail {
-
-template <typename R>
-struct WorkerThreadAsync {
-  using AfterWorkFunction = std::function<void(R)>;
-
-  ~WorkerThreadAsync() { UnsetLoop(); }
-
-  void SetLoop(uv::Loop& loop) {
-    auto async = uv::Async<AfterWorkFunction, R>::Create(loop);
-    async->wakeup.connect(
-        [](AfterWorkFunction func, R result) { func(result); });
-    m_async = async;
-  }
-
-  void UnsetLoop() {
-    if (auto async = m_async.lock()) {
-      async->Close();
-      m_async.reset();
-    }
-  }
-
-  std::weak_ptr<uv::Async<AfterWorkFunction, R>> m_async;
-};
-
-template <>
-struct WorkerThreadAsync<void> {
-  using AfterWorkFunction = std::function<void()>;
-
-  ~WorkerThreadAsync() { RemoveLoop(); }
-
-  void SetLoop(uv::Loop& loop) {
-    auto async = uv::Async<AfterWorkFunction>::Create(loop);
-    async->wakeup.connect([](AfterWorkFunction func) { func(); });
-    m_async = async;
-  }
-
-  void RemoveLoop() {
-    if (auto async = m_async.lock()) {
-      async->Close();
-      m_async.reset();
-    }
-  }
-
-  std::weak_ptr<uv::Async<AfterWorkFunction>> m_async;
-};
-
-template <typename R, typename... T>
-struct WorkerThreadRequest {
-  using WorkFunction = std::function<R(T...)>;
-  using AfterWorkFunction = typename WorkerThreadAsync<R>::AfterWorkFunction;
-
-  WorkerThreadRequest() = default;
-  WorkerThreadRequest(uint64_t promiseId_, WorkFunction work_,
-                      std::tuple<T...> params_)
-      : promiseId(promiseId_),
-        work(std::move(work_)),
-        params(std::move(params_)) {}
-  WorkerThreadRequest(WorkFunction work_, AfterWorkFunction afterWork_,
-                      std::tuple<T...> params_)
-      : promiseId(0),
-        work(std::move(work_)),
-        afterWork(std::move(afterWork_)),
-        params(std::move(params_)) {}
-
-  uint64_t promiseId;
-  WorkFunction work;
-  AfterWorkFunction afterWork;
-  std::tuple<T...> params;
-};
-
-template <typename R, typename... T>
-class WorkerThreadThread : public SafeThread {
- public:
-  using Request = WorkerThreadRequest<R, T...>;
-
-  void Main() override;
-
-  std::vector<Request> m_requests;
-  PromiseFactory<R> m_promises;
-  detail::WorkerThreadAsync<R> m_async;
-};
-
-template <typename R, typename... T>
-void RunWorkerThreadRequest(WorkerThreadThread<R, T...>& thr,
-                            WorkerThreadRequest<R, T...>& req) {
-  R result = std::apply(req.work, std::move(req.params));
-  if (req.afterWork) {
-    if (auto async = thr.m_async.m_async.lock()) {
-      async->Send(std::move(req.afterWork), std::move(result));
-    }
-  } else {
-    thr.m_promises.SetValue(req.promiseId, std::move(result));
-  }
-}
-
-template <typename... T>
-void RunWorkerThreadRequest(WorkerThreadThread<void, T...>& thr,
-                            WorkerThreadRequest<void, T...>& req) {
-  std::apply(req.work, req.params);
-  if (req.afterWork) {
-    if (auto async = thr.m_async.m_async.lock()) {
-      async->Send(std::move(req.afterWork));
-    }
-  } else {
-    thr.m_promises.SetValue(req.promiseId);
-  }
-}
-
-template <typename R, typename... T>
-void WorkerThreadThread<R, T...>::Main() {
-  std::vector<Request> requests;
-  while (m_active) {
-    std::unique_lock lock(m_mutex);
-    m_cond.wait(lock, [&] { return !m_active || !m_requests.empty(); });
-    if (!m_active) {
-      break;
-    }
-
-    // don't want to hold the lock while executing the callbacks
-    requests.swap(m_requests);
-    lock.unlock();
-
-    for (auto&& req : requests) {
-      if (!m_active) {
-        break;  // requests may be long-running
-      }
-      RunWorkerThreadRequest(*this, req);
-    }
-    requests.clear();
-    m_promises.Notify();
-  }
-}
-
-}  // namespace detail
-
-template <typename T>
-class WorkerThread;
-
-template <typename R, typename... T>
-class WorkerThread<R(T...)> final {
-  using Thread = detail::WorkerThreadThread<R, T...>;
-
- public:
-  using WorkFunction = std::function<R(T...)>;
-  using AfterWorkFunction =
-      typename detail::WorkerThreadAsync<R>::AfterWorkFunction;
-
-  WorkerThread() { m_owner.Start(); }
-
-  /**
-   * Set the loop.  This must be called from the loop thread.
-   * Subsequent calls to QueueWorkThen will run afterWork on the provided
-   * loop (via an async handle).
-   *
-   * @param loop the loop to use for running afterWork routines
-   */
-  void SetLoop(uv::Loop& loop) {
-    if (auto thr = m_owner.GetThread()) {
-      thr->m_async.SetLoop(loop);
-    }
-  }
-
-  /**
-   * Set the loop.  This must be called from the loop thread.
-   * Subsequent calls to QueueWorkThen will run afterWork on the provided
-   * loop (via an async handle).
-   *
-   * @param loop the loop to use for running afterWork routines
-   */
-  void SetLoop(std::shared_ptr<uv::Loop> loop) { SetLoop(*loop); }
-
-  /**
-   * Unset the loop.  This must be called from the loop thread.
-   * Subsequent calls to QueueWorkThen will no longer run afterWork.
-   */
-  void UnsetLoop() {
-    if (auto thr = m_owner.GetThread()) {
-      thr->m_async.UnsetLoop();
-    }
-  }
-
-  /**
-   * Get the handle used by QueueWorkThen() to run afterWork.
-   * This handle is set by SetLoop().
-   * Calling Close() on this handle is the same as calling UnsetLoop().
-   *
-   * @return The handle (if nullptr, no handle is set)
-   */
-  std::shared_ptr<uv::Handle> GetHandle() const {
-    if (auto thr = m_owner.GetThread()) {
-      return thr->m_async.m_async.lock();
-    } else {
-      return nullptr;
-    }
-  }
-
-  /**
-   * Wakeup the worker thread, call the work function, and return a future for
-   * the result.
-   *
-   * It’s safe to call this function from any thread.
-   * The work function will be called on the worker thread.
-   *
-   * The future will return a default-constructed result if this class is
-   * destroyed while waiting for a result.
-   *
-   * @param work Work function (called on worker thread)
-   * @param u Arguments to work function
-   */
-  template <typename... U>
-  future<R> QueueWork(WorkFunction work, U&&... u) {
-    if (auto thr = m_owner.GetThread()) {
-      // create the future
-      uint64_t req = thr->m_promises.CreateRequest();
-
-      // add the parameters to the input queue
-      thr->m_requests.emplace_back(
-          req, std::move(work), std::forward_as_tuple(std::forward<U>(u)...));
-
-      // signal the thread
-      thr->m_cond.notify_one();
-
-      // return future
-      return thr->m_promises.CreateFuture(req);
-    }
-
-    // XXX: is this the right thing to do?
-    return future<R>();
-  }
-
-  /**
-   * Wakeup the worker thread, call the work function, and call the afterWork
-   * function with the result on the loop set by SetLoop().
-   *
-   * It’s safe to call this function from any thread.
-   * The work function will be called on the worker thread, and the afterWork
-   * function will be called on the loop thread.
-   *
-   * SetLoop() must be called prior to calling this function for afterWork to
-   * be called.
-   *
-   * @param work Work function (called on worker thread)
-   * @param afterWork After work function (called on loop thread)
-   * @param u Arguments to work function
-   */
-  template <typename... U>
-  void QueueWorkThen(WorkFunction work, AfterWorkFunction afterWork, U&&... u) {
-    if (auto thr = m_owner.GetThread()) {
-      // add the parameters to the input queue
-      thr->m_requests.emplace_back(
-          std::move(work), std::move(afterWork),
-          std::forward_as_tuple(std::forward<U>(u)...));
-
-      // signal the thread
-      thr->m_cond.notify_one();
-    }
-  }
-
- private:
-  SafeThreadOwner<Thread> m_owner;
-};
-
-}  // namespace wpi
-
-#endif  // WPIUTIL_WPI_WORKERTHREAD_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/array.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/array.h
index f2604ec..cfbb7b0 100644
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/array.h
+++ b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/array.h
@@ -24,33 +24,33 @@
 template <typename T, size_t N>
 class array : public std::array<T, N> {
  public:
-  explicit array(empty_array_t) {}
+  constexpr explicit array(empty_array_t) {}
 
   template <typename... Ts>
-  array(T arg, Ts&&... args)  // NOLINT
+  constexpr array(T arg, Ts&&... args)  // NOLINT
       : std::array<T, N>{std::forward<T>(arg), std::forward<Ts>(args)...} {
     static_assert(1 + sizeof...(args) == N, "Dimension mismatch");
   }
 
-  array(const array<T, N>&) = default;
-  array& operator=(const array<T, N>&) = default;
-  array(array<T, N>&&) = default;
-  array& operator=(array<T, N>&&) = default;
+  constexpr array(const array<T, N>&) = default;
+  constexpr array& operator=(const array<T, N>&) = default;
+  constexpr array(array<T, N>&&) = default;
+  constexpr array& operator=(array<T, N>&&) = default;
 
-  array(const std::array<T, N>& rhs) {  // NOLINT
+  constexpr array(const std::array<T, N>& rhs) {  // NOLINT
     *static_cast<std::array<T, N>*>(this) = rhs;
   }
 
-  array& operator=(const std::array<T, N>& rhs) {
+  constexpr array& operator=(const std::array<T, N>& rhs) {
     *static_cast<std::array<T, N>*>(this) = rhs;
     return *this;
   }
 
-  array(std::array<T, N>&& rhs) {  // NOLINT
+  constexpr array(std::array<T, N>&& rhs) {  // NOLINT
     *static_cast<std::array<T, N>*>(this) = rhs;
   }
 
-  array& operator=(std::array<T, N>&& rhs) {
+  constexpr array& operator=(std::array<T, N>&& rhs) {
     *static_cast<std::array<T, N>*>(this) = rhs;
     return *this;
   }
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/circular_buffer.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/circular_buffer.h
index 40913f9..c54e2f5 100644
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/circular_buffer.h
+++ b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/circular_buffer.h
@@ -43,10 +43,7 @@
       ++(*this);
       return retval;
     }
-    bool operator==(const iterator& other) const {
-      return m_buffer == other.m_buffer && m_index == other.m_index;
-    }
-    bool operator!=(const iterator& other) const { return !(*this == other); }
+    bool operator==(const iterator&) const = default;
     reference operator*() { return (*m_buffer)[m_index]; }
 
    private:
@@ -74,12 +71,7 @@
       ++(*this);
       return retval;
     }
-    bool operator==(const const_iterator& other) const {
-      return m_buffer == other.m_buffer && m_index == other.m_index;
-    }
-    bool operator!=(const const_iterator& other) const {
-      return !(*this == other);
-    }
+    bool operator==(const const_iterator&) const = default;
     const_reference operator*() const { return (*m_buffer)[m_index]; }
 
    private:
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/deprecated.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/deprecated.h
index 6e6a3bf..c5b4af2 100644
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/deprecated.h
+++ b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/deprecated.h
@@ -9,4 +9,23 @@
 #define WPI_DEPRECATED(msg) [[deprecated(msg)]]
 #endif
 
+#ifndef WPI_IGNORE_DEPRECATED
+#ifdef __GNUC__
+#define WPI_IGNORE_DEPRECATED    \
+  _Pragma("GCC diagnostic push") \
+      _Pragma("GCC diagnostic ignored \"-Wdeprecated-declarations\"")
+#elif defined(_WIN32)
+#define WPI_IGNORE_DEPRECATED _Pragma("warning(disable : 4996)")
+#endif
+
+#endif
+
+#ifndef WPI_UNIGNORE_DEPRECATED
+#ifdef __GNUC__
+#define WPI_UNIGNORE_DEPRECATED _Pragma("GCC diagnostic pop")
+#elif defined(_WIN32)
+#define WPI_UNIGNORE_DEPRECATED _Pragma("warning(default : 4996)")
+#endif
+#endif
+
 #endif  // WPIUTIL_WPI_DEPRECATED_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/fmt/raw_ostream.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/fmt/raw_ostream.h
index 8779bfc..024e04c 100644
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/fmt/raw_ostream.h
+++ b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/fmt/raw_ostream.h
@@ -22,7 +22,7 @@
  */
 template <typename S, typename... Args>
 void print(wpi::raw_ostream& os, const S& format_str, Args&&... args) {
-  vprint(os, format_str, fmt::make_args_checked<Args...>(format_str, args...));
+  vprint(os, format_str, fmt::make_format_args(args...));
 }
 
 FMT_END_NAMESPACE
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/fs.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/fs.h
index fca8069..587a23c 100644
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/fs.h
+++ b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/fs.h
@@ -40,7 +40,7 @@
 #ifndef GHC_USE_STD_FS
 // #define GHC_WIN_DISABLE_WSTRING_STORAGE_TYPE
 #define GHC_FILESYSTEM_FWD
-#include "ghc/filesystem.hpp"
+#include "wpi/ghc/filesystem.hpp"
 namespace fs {
 using namespace ghc::filesystem;
 using ifstream = ghc::filesystem::ifstream;
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/future.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/future.h
index 5cb4a8d..70dc60f 100644
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/future.h
+++ b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/future.h
@@ -334,7 +334,7 @@
     }
   }
 
-  template <typename F, typename R = typename std::result_of<F && (T &&)>::type>
+  template <typename F, typename R = typename std::invoke_result_t<F&&, T&&>>
   future<R> then(F&& func) {
     return then(PromiseFactory<R>::GetInstance(), std::forward<F>(func));
   }
@@ -457,7 +457,7 @@
     }
   }
 
-  template <typename F, typename R = typename std::result_of<F && ()>::type>
+  template <typename F, typename R = typename std::invoke_result_t<F&&>>
   future<R> then(F&& func) {
     return then(PromiseFactory<R>::GetInstance(), std::forward<F>(func));
   }
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/hostname.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/hostname.h
deleted file mode 100644
index bd93b4a..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/hostname.h
+++ /dev/null
@@ -1,19 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_HOSTNAME_H_
-#define WPIUTIL_WPI_HOSTNAME_H_
-
-#include <string>
-#include <string_view>
-
-namespace wpi {
-template <typename T>
-class SmallVectorImpl;
-
-std::string GetHostname();
-std::string_view GetHostname(SmallVectorImpl<char>& name);
-}  // namespace wpi
-
-#endif  // WPIUTIL_WPI_HOSTNAME_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/interpolating_map.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/interpolating_map.h
new file mode 100644
index 0000000..5eff514
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/interpolating_map.h
@@ -0,0 +1,87 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <map>
+#include <utility>
+
+namespace wpi {
+
+/**
+ * Implements a table of key-value pairs with linear interpolation between
+ * values.
+ *
+ * If there's no matching key, the value returned will be a linear interpolation
+ * between the keys before and after the provided one.
+ *
+ * @tparam Key   The key type.
+ * @tparam Value The value type.
+ */
+template <typename Key, typename Value>
+class interpolating_map {
+ public:
+  /**
+   * Inserts a key-value pair.
+   *
+   * @param key   The key.
+   * @param value The value.
+   */
+  void insert(const Key& key, const Value& value) {
+    m_container.insert(std::make_pair(key, value));
+  }
+
+  /**
+   * Inserts a key-value pair.
+   *
+   * @param key   The key.
+   * @param value The value.
+   */
+  void insert(Key&& key, Value&& value) {
+    m_container.insert(std::make_pair(key, value));
+  }
+
+  /**
+   * Returns the value associated with a given key.
+   *
+   * If there's no matching key, the value returned will be a linear
+   * interpolation between the keys before and after the provided one.
+   *
+   * @param key The key.
+   */
+  Value operator[](const Key& key) const {
+    using const_iterator = typename std::map<Key, Value>::const_iterator;
+
+    // Get iterator to upper bound key-value pair for the given key
+    const_iterator upper = m_container.upper_bound(key);
+
+    // If key > largest key in table, return value for largest table key
+    if (upper == m_container.end()) {
+      return (--upper)->second;
+    }
+
+    // If key <= smallest key in table, return value for smallest table key
+    if (upper == m_container.begin()) {
+      return upper->second;
+    }
+
+    // Get iterator to lower bound key-value pair
+    const_iterator lower = upper;
+    --lower;
+
+    // Perform linear interpolation between lower and upper bound
+    const double delta = (key - lower->first) / (upper->first - lower->first);
+    return delta * upper->second + (1.0 - delta) * lower->second;
+  }
+
+  /**
+   * Clears the contents.
+   */
+  void clear() { m_container.clear(); }
+
+ private:
+  std::map<Key, Value> m_container;
+};
+
+}  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/iterator.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/iterator.h
deleted file mode 100644
index 70bbdab..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/iterator.h
+++ /dev/null
@@ -1,339 +0,0 @@
-//===- iterator.h - Utilities for using and defining iterators --*- C++ -*-===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-
-#ifndef WPIUTIL_WPI_ITERATOR_H
-#define WPIUTIL_WPI_ITERATOR_H
-
-#include "wpi/iterator_range.h"
-#include <algorithm>
-#include <cstddef>
-#include <iterator>
-#include <type_traits>
-#include <utility>
-
-namespace wpi {
-
-/// CRTP base class which implements the entire standard iterator facade
-/// in terms of a minimal subset of the interface.
-///
-/// Use this when it is reasonable to implement most of the iterator
-/// functionality in terms of a core subset. If you need special behavior or
-/// there are performance implications for this, you may want to override the
-/// relevant members instead.
-///
-/// Note, one abstraction that this does *not* provide is implementing
-/// subtraction in terms of addition by negating the difference. Negation isn't
-/// always information preserving, and I can see very reasonable iterator
-/// designs where this doesn't work well. It doesn't really force much added
-/// boilerplate anyways.
-///
-/// Another abstraction that this doesn't provide is implementing increment in
-/// terms of addition of one. These aren't equivalent for all iterator
-/// categories, and respecting that adds a lot of complexity for little gain.
-///
-/// Classes wishing to use `iterator_facade_base` should implement the following
-/// methods:
-///
-/// Forward Iterators:
-///   (All of the following methods)
-///   - DerivedT &operator=(const DerivedT &R);
-///   - bool operator==(const DerivedT &R) const;
-///   - const T &operator*() const;
-///   - T &operator*();
-///   - DerivedT &operator++();
-///
-/// Bidirectional Iterators:
-///   (All methods of forward iterators, plus the following)
-///   - DerivedT &operator--();
-///
-/// Random-access Iterators:
-///   (All methods of bidirectional iterators excluding the following)
-///   - DerivedT &operator++();
-///   - DerivedT &operator--();
-///   (and plus the following)
-///   - bool operator<(const DerivedT &RHS) const;
-///   - DifferenceTypeT operator-(const DerivedT &R) const;
-///   - DerivedT &operator+=(DifferenceTypeT N);
-///   - DerivedT &operator-=(DifferenceTypeT N);
-///
-template <typename DerivedT, typename IteratorCategoryT, typename T,
-          typename DifferenceTypeT = std::ptrdiff_t, typename PointerT = T *,
-          typename ReferenceT = T &>
-class iterator_facade_base
-    : public std::iterator<IteratorCategoryT, T, DifferenceTypeT, PointerT,
-                           ReferenceT> {
-protected:
-  enum {
-    IsRandomAccess = std::is_base_of<std::random_access_iterator_tag,
-                                     IteratorCategoryT>::value,
-    IsBidirectional = std::is_base_of<std::bidirectional_iterator_tag,
-                                      IteratorCategoryT>::value,
-  };
-
-  /// A proxy object for computing a reference via indirecting a copy of an
-  /// iterator. This is used in APIs which need to produce a reference via
-  /// indirection but for which the iterator object might be a temporary. The
-  /// proxy preserves the iterator internally and exposes the indirected
-  /// reference via a conversion operator.
-  class ReferenceProxy {
-    friend iterator_facade_base;
-
-    DerivedT I;
-
-    ReferenceProxy(DerivedT I) : I(std::move(I)) {}
-
-  public:
-    operator ReferenceT() const { return *I; }
-  };
-
-public:
-  DerivedT operator+(DifferenceTypeT n) const {
-    static_assert(std::is_base_of<iterator_facade_base, DerivedT>::value,
-                  "Must pass the derived type to this template!");
-    static_assert(
-        IsRandomAccess,
-        "The '+' operator is only defined for random access iterators.");
-    DerivedT tmp = *static_cast<const DerivedT *>(this);
-    tmp += n;
-    return tmp;
-  }
-  friend DerivedT operator+(DifferenceTypeT n, const DerivedT &i) {
-    static_assert(
-        IsRandomAccess,
-        "The '+' operator is only defined for random access iterators.");
-    return i + n;
-  }
-  DerivedT operator-(DifferenceTypeT n) const {
-    static_assert(
-        IsRandomAccess,
-        "The '-' operator is only defined for random access iterators.");
-    DerivedT tmp = *static_cast<const DerivedT *>(this);
-    tmp -= n;
-    return tmp;
-  }
-
-  DerivedT &operator++() {
-    static_assert(std::is_base_of<iterator_facade_base, DerivedT>::value,
-                  "Must pass the derived type to this template!");
-    return static_cast<DerivedT *>(this)->operator+=(1);
-  }
-  DerivedT operator++(int) {
-    DerivedT tmp = *static_cast<DerivedT *>(this);
-    ++*static_cast<DerivedT *>(this);
-    return tmp;
-  }
-  DerivedT &operator--() {
-    static_assert(
-        IsBidirectional,
-        "The decrement operator is only defined for bidirectional iterators.");
-    return static_cast<DerivedT *>(this)->operator-=(1);
-  }
-  DerivedT operator--(int) {
-    static_assert(
-        IsBidirectional,
-        "The decrement operator is only defined for bidirectional iterators.");
-    DerivedT tmp = *static_cast<DerivedT *>(this);
-    --*static_cast<DerivedT *>(this);
-    return tmp;
-  }
-
-  bool operator!=(const DerivedT &RHS) const {
-    return !static_cast<const DerivedT *>(this)->operator==(RHS);
-  }
-
-  bool operator>(const DerivedT &RHS) const {
-    static_assert(
-        IsRandomAccess,
-        "Relational operators are only defined for random access iterators.");
-    return !static_cast<const DerivedT *>(this)->operator<(RHS) &&
-           !static_cast<const DerivedT *>(this)->operator==(RHS);
-  }
-  bool operator<=(const DerivedT &RHS) const {
-    static_assert(
-        IsRandomAccess,
-        "Relational operators are only defined for random access iterators.");
-    return !static_cast<const DerivedT *>(this)->operator>(RHS);
-  }
-  bool operator>=(const DerivedT &RHS) const {
-    static_assert(
-        IsRandomAccess,
-        "Relational operators are only defined for random access iterators.");
-    return !static_cast<const DerivedT *>(this)->operator<(RHS);
-  }
-
-  PointerT operator->() { return &static_cast<DerivedT *>(this)->operator*(); }
-  PointerT operator->() const {
-    return &static_cast<const DerivedT *>(this)->operator*();
-  }
-  ReferenceProxy operator[](DifferenceTypeT n) {
-    static_assert(IsRandomAccess,
-                  "Subscripting is only defined for random access iterators.");
-    return ReferenceProxy(static_cast<DerivedT *>(this)->operator+(n));
-  }
-  ReferenceProxy operator[](DifferenceTypeT n) const {
-    static_assert(IsRandomAccess,
-                  "Subscripting is only defined for random access iterators.");
-    return ReferenceProxy(static_cast<const DerivedT *>(this)->operator+(n));
-  }
-};
-
-/// CRTP base class for adapting an iterator to a different type.
-///
-/// This class can be used through CRTP to adapt one iterator into another.
-/// Typically this is done through providing in the derived class a custom \c
-/// operator* implementation. Other methods can be overridden as well.
-template <
-    typename DerivedT, typename WrappedIteratorT,
-    typename IteratorCategoryT =
-        typename std::iterator_traits<WrappedIteratorT>::iterator_category,
-    typename T = typename std::iterator_traits<WrappedIteratorT>::value_type,
-    typename DifferenceTypeT =
-        typename std::iterator_traits<WrappedIteratorT>::difference_type,
-    typename PointerT = typename std::conditional<
-        std::is_same<T, typename std::iterator_traits<
-                            WrappedIteratorT>::value_type>::value,
-        typename std::iterator_traits<WrappedIteratorT>::pointer, T *>::type,
-    typename ReferenceT = typename std::conditional<
-        std::is_same<T, typename std::iterator_traits<
-                            WrappedIteratorT>::value_type>::value,
-        typename std::iterator_traits<WrappedIteratorT>::reference, T &>::type>
-class iterator_adaptor_base
-    : public iterator_facade_base<DerivedT, IteratorCategoryT, T,
-                                  DifferenceTypeT, PointerT, ReferenceT> {
-  using BaseT = typename iterator_adaptor_base::iterator_facade_base;
-
-protected:
-  WrappedIteratorT I;
-
-  iterator_adaptor_base() = default;
-
-  explicit iterator_adaptor_base(WrappedIteratorT u) : I(std::move(u)) {
-    static_assert(std::is_base_of<iterator_adaptor_base, DerivedT>::value,
-                  "Must pass the derived type to this template!");
-  }
-
-  const WrappedIteratorT &wrapped() const { return I; }
-
-public:
-  using difference_type = DifferenceTypeT;
-
-  DerivedT &operator+=(difference_type n) {
-    static_assert(
-        BaseT::IsRandomAccess,
-        "The '+=' operator is only defined for random access iterators.");
-    I += n;
-    return *static_cast<DerivedT *>(this);
-  }
-  DerivedT &operator-=(difference_type n) {
-    static_assert(
-        BaseT::IsRandomAccess,
-        "The '-=' operator is only defined for random access iterators.");
-    I -= n;
-    return *static_cast<DerivedT *>(this);
-  }
-  using BaseT::operator-;
-  difference_type operator-(const DerivedT &RHS) const {
-    static_assert(
-        BaseT::IsRandomAccess,
-        "The '-' operator is only defined for random access iterators.");
-    return I - RHS.I;
-  }
-
-  // We have to explicitly provide ++ and -- rather than letting the facade
-  // forward to += because WrappedIteratorT might not support +=.
-  using BaseT::operator++;
-  DerivedT &operator++() {
-    ++I;
-    return *static_cast<DerivedT *>(this);
-  }
-  using BaseT::operator--;
-  DerivedT &operator--() {
-    static_assert(
-        BaseT::IsBidirectional,
-        "The decrement operator is only defined for bidirectional iterators.");
-    --I;
-    return *static_cast<DerivedT *>(this);
-  }
-
-  bool operator==(const DerivedT &RHS) const { return I == RHS.I; }
-  bool operator<(const DerivedT &RHS) const {
-    static_assert(
-        BaseT::IsRandomAccess,
-        "Relational operators are only defined for random access iterators.");
-    return I < RHS.I;
-  }
-
-  ReferenceT operator*() const { return *I; }
-};
-
-/// An iterator type that allows iterating over the pointees via some
-/// other iterator.
-///
-/// The typical usage of this is to expose a type that iterates over Ts, but
-/// which is implemented with some iterator over T*s:
-///
-/// \code
-///   using iterator = pointee_iterator<SmallVectorImpl<T *>::iterator>;
-/// \endcode
-template <typename WrappedIteratorT,
-          typename T = typename std::remove_reference<
-              decltype(**std::declval<WrappedIteratorT>())>::type>
-struct pointee_iterator
-    : iterator_adaptor_base<
-          pointee_iterator<WrappedIteratorT, T>, WrappedIteratorT,
-          typename std::iterator_traits<WrappedIteratorT>::iterator_category,
-          T> {
-  pointee_iterator() = default;
-  template <typename U>
-  pointee_iterator(U &&u)
-      : pointee_iterator::iterator_adaptor_base(std::forward<U &&>(u)) {}
-
-  T &operator*() const { return **this->I; }
-};
-
-template <typename RangeT, typename WrappedIteratorT =
-                               decltype(std::begin(std::declval<RangeT>()))>
-iterator_range<pointee_iterator<WrappedIteratorT>>
-make_pointee_range(RangeT &&Range) {
-  using PointeeIteratorT = pointee_iterator<WrappedIteratorT>;
-  return make_range(PointeeIteratorT(std::begin(std::forward<RangeT>(Range))),
-                    PointeeIteratorT(std::end(std::forward<RangeT>(Range))));
-}
-
-template <typename WrappedIteratorT,
-          typename T = decltype(&*std::declval<WrappedIteratorT>())>
-class pointer_iterator
-    : public iterator_adaptor_base<
-          pointer_iterator<WrappedIteratorT, T>, WrappedIteratorT,
-          typename std::iterator_traits<WrappedIteratorT>::iterator_category,
-          T> {
-  mutable T Ptr;
-
-public:
-  pointer_iterator() = default;
-
-  explicit pointer_iterator(WrappedIteratorT u)
-      : pointer_iterator::iterator_adaptor_base(std::move(u)) {}
-
-  T &operator*() { return Ptr = &*this->I; }
-  const T &operator*() const { return Ptr = &*this->I; }
-};
-
-template <typename RangeT, typename WrappedIteratorT =
-                               decltype(std::begin(std::declval<RangeT>()))>
-iterator_range<pointer_iterator<WrappedIteratorT>>
-make_pointer_range(RangeT &&Range) {
-  using PointerIteratorT = pointer_iterator<WrappedIteratorT>;
-  return make_range(PointerIteratorT(std::begin(std::forward<RangeT>(Range))),
-                    PointerIteratorT(std::end(std::forward<RangeT>(Range))));
-}
-
-} // end namespace wpi
-
-#endif // LLVM_ADT_ITERATOR_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/iterator_range.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/iterator_range.h
deleted file mode 100644
index 78a60c2..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/iterator_range.h
+++ /dev/null
@@ -1,69 +0,0 @@
-//===- iterator_range.h - A range adaptor for iterators ---------*- C++ -*-===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-/// \file
-/// This provides a very simple, boring adaptor for a begin and end iterator
-/// into a range type. This should be used to build range views that work well
-/// with range based for loops and range based constructors.
-///
-/// Note that code here follows more standards-based coding conventions as it
-/// is mirroring proposed interfaces for standardization.
-///
-//===----------------------------------------------------------------------===//
-
-#ifndef WPIUTIL_WPI_ITERATOR_RANGE_H
-#define WPIUTIL_WPI_ITERATOR_RANGE_H
-
-#include <iterator>
-#include <utility>
-
-namespace wpi {
-
-/// A range adaptor for a pair of iterators.
-///
-/// This just wraps two iterators into a range-compatible interface. Nothing
-/// fancy at all.
-template <typename IteratorT>
-class iterator_range {
-  IteratorT begin_iterator, end_iterator;
-
-public:
-  //TODO: Add SFINAE to test that the Container's iterators match the range's
-  //      iterators.
-  template <typename Container>
-  iterator_range(Container &&c)
-  //TODO: Consider ADL/non-member begin/end calls.
-      : begin_iterator(c.begin()), end_iterator(c.end()) {}
-  iterator_range(IteratorT begin_iterator, IteratorT end_iterator)
-      : begin_iterator(std::move(begin_iterator)),
-        end_iterator(std::move(end_iterator)) {}
-
-  IteratorT begin() const { return begin_iterator; }
-  IteratorT end() const { return end_iterator; }
-};
-
-/// Convenience function for iterating over sub-ranges.
-///
-/// This provides a bit of syntactic sugar to make using sub-ranges
-/// in for loops a bit easier. Analogous to std::make_pair().
-template <class T> iterator_range<T> make_range(T x, T y) {
-  return iterator_range<T>(std::move(x), std::move(y));
-}
-
-template <typename T> iterator_range<T> make_range(std::pair<T, T> p) {
-  return iterator_range<T>(std::move(p.first), std::move(p.second));
-}
-
-template <typename T>
-iterator_range<decltype(adl_begin(std::declval<T>()))> drop_begin(T &&t,
-                                                                  int n) {
-  return make_range(std::next(adl_begin(t), n), adl_end(t));
-}
-}
-
-#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/jni_util.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/jni_util.h
index 585c1c6..8d50fdd 100644
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/jni_util.h
+++ b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/jni_util.h
@@ -8,6 +8,7 @@
 #include <jni.h>
 
 #include <queue>
+#include <span>
 #include <string>
 #include <string_view>
 #include <type_traits>
@@ -21,7 +22,6 @@
 #include "wpi/StringExtras.h"
 #include "wpi/mutex.h"
 #include "wpi/raw_ostream.h"
-#include "wpi/span.h"
 
 /** Java Native Interface (JNI) utility functions */
 namespace wpi::java {
@@ -154,7 +154,7 @@
       jsize size = env->GetStringLength(str);
       const jchar* chars = env->GetStringCritical(str, nullptr);
       if (chars) {
-        convertUTF16ToUTF8String(wpi::span<const jchar>(chars, size), m_str);
+        convertUTF16ToUTF8String(std::span<const jchar>(chars, size), m_str);
         env->ReleaseStringCritical(str, chars);
       }
     } else {
@@ -179,10 +179,16 @@
 namespace detail {
 
 template <typename C, typename T>
-class JArrayRefInner {};
+class JArrayRefInner {
+ public:
+  operator std::span<const T>() const {  // NOLINT
+    return static_cast<const C*>(this)->array();
+  }
+};
 
 /**
- * Specialization of JArrayRefBase to provide std::string_view conversion.
+ * Specialization of JArrayRefBase to provide std::string_view conversion
+ * and span<const uint8_t> conversion.
  */
 template <typename C>
 class JArrayRefInner<C, jbyte> {
@@ -196,6 +202,33 @@
     }
     return {reinterpret_cast<const char*>(arr.data()), arr.size()};
   }
+
+  std::span<const uint8_t> uarray() const {
+    auto arr = static_cast<const C*>(this)->array();
+    if (arr.empty()) {
+      return {};
+    }
+    return {reinterpret_cast<const uint8_t*>(arr.data()), arr.size()};
+  }
+};
+
+/**
+ * Specialization of JArrayRefBase to handle both "long long" and "long" on
+ * 64-bit systems.
+ */
+template <typename C>
+class JArrayRefInner<C, jlong> {
+ public:
+  template <typename U,
+            typename = std::enable_if_t<sizeof(U) == sizeof(jlong) &&
+                                        std::is_integral_v<U>>>
+  operator std::span<const U>() const {  // NOLINT
+    auto arr = static_cast<const C*>(this)->array();
+    if (arr.empty()) {
+      return {};
+    }
+    return {reinterpret_cast<const U*>(arr.data()), arr.size()};
+  }
 };
 
 /**
@@ -206,9 +239,7 @@
  public:
   explicit operator bool() const { return this->m_elements != nullptr; }
 
-  operator span<const T>() const { return array(); }  // NOLINT
-
-  span<const T> array() const {
+  std::span<const T> array() const {
     if (!this->m_elements) {
       return {};
     }
@@ -375,7 +406,7 @@
 template <typename T,
           bool = (std::is_integral<T>::value && sizeof(jint) == sizeof(T))>
 struct ConvertIntArray {
-  static jintArray ToJava(JNIEnv* env, span<const T> arr) {
+  static jintArray ToJava(JNIEnv* env, std::span<const T> arr) {
     jintArray jarr = env->NewIntArray(arr.size());
     if (!jarr) {
       return nullptr;
@@ -398,7 +429,7 @@
  */
 template <typename T>
 struct ConvertIntArray<T, true> {
-  static jintArray ToJava(JNIEnv* env, span<const T> arr) {
+  static jintArray ToJava(JNIEnv* env, std::span<const T> arr) {
     jintArray jarr = env->NewIntArray(arr.size());
     if (!jarr) {
       return nullptr;
@@ -418,7 +449,7 @@
  * @param arr Span to convert.
  */
 template <typename T>
-inline jintArray MakeJIntArray(JNIEnv* env, span<const T> arr) {
+inline jintArray MakeJIntArray(JNIEnv* env, std::span<const T> arr) {
   return detail::ConvertIntArray<T>::ToJava(env, arr);
 }
 
@@ -429,7 +460,7 @@
  * @param arr Span to convert.
  */
 template <typename T>
-inline jintArray MakeJIntArray(JNIEnv* env, span<T> arr) {
+inline jintArray MakeJIntArray(JNIEnv* env, std::span<T> arr) {
   return detail::ConvertIntArray<T>::ToJava(env, arr);
 }
 
@@ -462,12 +493,12 @@
 }
 
 /**
- * Convert a std::string_view into a jbyteArray.
+ * Convert a span into a jbyteArray.
  *
  * @param env JRE environment.
- * @param str std::string_view to convert.
+ * @param str span to convert.
  */
-inline jbyteArray MakeJByteArray(JNIEnv* env, std::string_view str) {
+inline jbyteArray MakeJByteArray(JNIEnv* env, std::span<const uint8_t> str) {
   jbyteArray jarr = env->NewByteArray(str.size());
   if (!jarr) {
     return nullptr;
@@ -483,7 +514,7 @@
  * @param env JRE environment.
  * @param arr Array to convert.
  */
-inline jbooleanArray MakeJBooleanArray(JNIEnv* env, span<const int> arr) {
+inline jbooleanArray MakeJBooleanArray(JNIEnv* env, std::span<const int> arr) {
   jbooleanArray jarr = env->NewBooleanArray(arr.size());
   if (!jarr) {
     return nullptr;
@@ -506,7 +537,7 @@
  * @param env JRE environment.
  * @param arr Array to convert.
  */
-inline jbooleanArray MakeJBooleanArray(JNIEnv* env, span<const bool> arr) {
+inline jbooleanArray MakeJBooleanArray(JNIEnv* env, std::span<const bool> arr) {
   jbooleanArray jarr = env->NewBooleanArray(arr.size());
   if (!jarr) {
     return nullptr;
@@ -525,32 +556,45 @@
 
 // Other MakeJ*Array conversions.
 
-#define WPI_JNI_MAKEJARRAY(T, F)                                    \
-  inline T##Array MakeJ##F##Array(JNIEnv* env, span<const T> arr) { \
-    T##Array jarr = env->New##F##Array(arr.size());                 \
-    if (!jarr) {                                                    \
-      return nullptr;                                               \
-    }                                                               \
-    env->Set##F##ArrayRegion(jarr, 0, arr.size(), arr.data());      \
-    return jarr;                                                    \
+#define WPI_JNI_MAKEJARRAY(T, F)                                         \
+  inline T##Array MakeJ##F##Array(JNIEnv* env, std::span<const T> arr) { \
+    T##Array jarr = env->New##F##Array(arr.size());                      \
+    if (!jarr) {                                                         \
+      return nullptr;                                                    \
+    }                                                                    \
+    env->Set##F##ArrayRegion(jarr, 0, arr.size(), arr.data());           \
+    return jarr;                                                         \
   }
 
 WPI_JNI_MAKEJARRAY(jboolean, Boolean)
 WPI_JNI_MAKEJARRAY(jbyte, Byte)
 WPI_JNI_MAKEJARRAY(jshort, Short)
-WPI_JNI_MAKEJARRAY(jlong, Long)
 WPI_JNI_MAKEJARRAY(jfloat, Float)
 WPI_JNI_MAKEJARRAY(jdouble, Double)
 
 #undef WPI_JNI_MAKEJARRAY
 
+template <class T, typename = std::enable_if_t<
+                       sizeof(typename T::value_type) == sizeof(jlong) &&
+                       std::is_integral_v<typename T::value_type>>>
+inline jlongArray MakeJLongArray(JNIEnv* env, const T& arr) {
+  jlongArray jarr = env->NewLongArray(arr.size());
+  if (!jarr) {
+    return nullptr;
+  }
+  env->SetLongArrayRegion(jarr, 0, arr.size(),
+                          reinterpret_cast<const jlong*>(arr.data()));
+  return jarr;
+}
+
 /**
  * Convert an array of std::string into a jarray of jstring.
  *
  * @param env JRE environment.
  * @param arr Array to convert.
  */
-inline jobjectArray MakeJStringArray(JNIEnv* env, span<const std::string> arr) {
+inline jobjectArray MakeJStringArray(JNIEnv* env,
+                                     std::span<const std::string> arr) {
   static JClass stringCls{env, "java/lang/String"};
   if (!stringCls) {
     return nullptr;
@@ -572,7 +616,8 @@
  * @param env JRE environment.
  * @param arr Array to convert.
  */
-inline jobjectArray MakeJStringArray(JNIEnv* env, span<std::string_view> arr) {
+inline jobjectArray MakeJStringArray(JNIEnv* env,
+                                     std::span<std::string_view> arr) {
   static JClass stringCls{env, "java/lang/String"};
   if (!stringCls) {
     return nullptr;
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/json.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/json.h
deleted file mode 100644
index 1a4e410..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/json.h
+++ /dev/null
@@ -1,8120 +0,0 @@
-/*----------------------------------------------------------------------------*/
-/* Modifications Copyright (c) 2017-2019 FIRST. All Rights Reserved.          */
-/* Open Source Software - may be modified and shared by FRC teams. The code   */
-/* must be accompanied by the FIRST BSD license file in the root directory of */
-/* the project.                                                               */
-/*----------------------------------------------------------------------------*/
-/*
-    __ _____ _____ _____
- __|  |   __|     |   | |  JSON for Modern C++
-|  |  |__   |  |  | | | |  version 3.1.2
-|_____|_____|_____|_|___|  https://github.com/nlohmann/json
-
-Licensed under the MIT License <http://opensource.org/licenses/MIT>.
-Copyright (c) 2013-2018 Niels Lohmann <http://nlohmann.me>.
-
-Permission is hereby  granted, free of charge, to any  person obtaining a copy
-of this software and associated  documentation files (the "Software"), to deal
-in the Software  without restriction, including without  limitation the rights
-to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
-copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
-furnished to do so, subject to the following conditions:
-
-The above copyright notice and this permission notice shall be included in all
-copies or substantial portions of the Software.
-
-THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
-IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
-FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
-AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
-LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
-OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
-SOFTWARE.
-*/
-
-#ifndef WPIUTIL_JSON_H
-#define WPIUTIL_JSON_H
-
-#define NLOHMANN_JSON_VERSION_MAJOR 3
-#define NLOHMANN_JSON_VERSION_MINOR 1
-#define NLOHMANN_JSON_VERSION_PATCH 2
-
-
-#include <algorithm> // all_of, copy, find, for_each, generate_n, min, reverse, remove, fill, none_of, transform
-#include <array> // array
-#include <cassert> // assert
-#include <ciso646> // and, not, or
-#include <cstddef> // nullptr_t, ptrdiff_t, size_t
-#include <cstdint> // uint8_t, uint16_t, uint32_t, uint64_t
-#include <exception> // exception
-#include <functional> // function, hash, less
-#include <initializer_list> // initializer_list
-#include <iterator>
-#include <limits> // numeric_limits
-#include <memory> // allocator, shared_ptr, make_shared, addressof
-#include <stdexcept> // runtime_error
-#include <string> // string, char_traits, stoi, to_string
-#include <string_view>
-#include <tuple> // tuple, get, make_tuple
-#include <type_traits>
-#include <utility>
-#include <vector> // vector
-
-#include "wpi/StringMap.h"
-#include "wpi/span.h"
-
-namespace wpi
-{
-
-class raw_istream;
-class raw_ostream;
-
-class JsonTest;
-
-/*!
-@brief default JSONSerializer template argument
-
-This serializer ignores the template arguments and uses ADL
-([argument-dependent lookup](http://en.cppreference.com/w/cpp/language/adl))
-for serialization.
-*/
-template<typename = void, typename = void>
-struct adl_serializer;
-
-/*!
-@brief JSON Pointer
-
-A JSON pointer defines a string syntax for identifying a specific value
-within a JSON document. It can be used with functions `at` and
-`operator[]`. Furthermore, JSON pointers are the base for JSON patches.
-
-@sa [RFC 6901](https://tools.ietf.org/html/rfc6901)
-
-@since version 2.0.0
-*/
-class json_pointer;
-
-/*!
-@brief default JSON class
-
-This type is the default specialization of the @ref json class which
-uses the standard template types.
-
-@since version 1.0.0
-*/
-class json;
-}
-
-// exclude unsupported compilers
-#if defined(__clang__)
-    #if (__clang_major__ * 10000 + __clang_minor__ * 100 + __clang_patchlevel__) < 30400
-        #error "unsupported Clang version - see https://github.com/nlohmann/json#supported-compilers"
-    #endif
-#elif defined(__GNUC__) && !(defined(__ICC) || defined(__INTEL_COMPILER))
-    #if (__GNUC__ * 10000 + __GNUC_MINOR__ * 100 + __GNUC_PATCHLEVEL__) < 40900
-        #error "unsupported GCC version - see https://github.com/nlohmann/json#supported-compilers"
-    #endif
-#endif
-
-// disable float-equal warnings on GCC/clang
-#if defined(__clang__) || defined(__GNUC__) || defined(__GNUG__)
-    #pragma GCC diagnostic push
-    #pragma GCC diagnostic ignored "-Wfloat-equal"
-#endif
-
-// disable documentation warnings on clang
-#if defined(__clang__)
-    #pragma GCC diagnostic push
-    #pragma GCC diagnostic ignored "-Wdocumentation"
-#endif
-
-// allow to disable exceptions
-#if (defined(__cpp_exceptions) || defined(__EXCEPTIONS) || defined(_CPPUNWIND)) && !defined(JSON_NOEXCEPTION)
-    #define JSON_THROW(exception) throw exception
-    #define JSON_TRY try
-    #define JSON_CATCH(exception) catch(exception)
-#else
-    #define JSON_THROW(exception) std::abort()
-    #define JSON_TRY if(true)
-    #define JSON_CATCH(exception) if(false)
-#endif
-
-// override exception macros
-#if defined(JSON_THROW_USER)
-    #undef JSON_THROW
-    #define JSON_THROW JSON_THROW_USER
-#endif
-#if defined(JSON_TRY_USER)
-    #undef JSON_TRY
-    #define JSON_TRY JSON_TRY_USER
-#endif
-#if defined(JSON_CATCH_USER)
-    #undef JSON_CATCH
-    #define JSON_CATCH JSON_CATCH_USER
-#endif
-
-// manual branch prediction
-#if defined(__clang__) || defined(__GNUC__) || defined(__GNUG__)
-    #define JSON_LIKELY(x)      __builtin_expect(!!(x), 1)
-    #define JSON_UNLIKELY(x)    __builtin_expect(!!(x), 0)
-#else
-    #define JSON_LIKELY(x)      x
-    #define JSON_UNLIKELY(x)    x
-#endif
-
-/*!
-@brief Helper to determine whether there's a key_type for T.
-
-This helper is used to tell associative containers apart from other containers
-such as sequence containers. For instance, `std::map` passes the test as it
-contains a `mapped_type`, whereas `std::vector` fails the test.
-
-@sa http://stackoverflow.com/a/7728728/266378
-@since version 1.0.0, overworked in version 2.0.6
-*/
-#define NLOHMANN_JSON_HAS_HELPER(type)                                        \
-    template<typename T> struct has_##type {                                  \
-    private:                                                                  \
-        template<typename U, typename = typename U::type>                     \
-        static int detect(U &&);                                              \
-        static void detect(...);                                              \
-    public:                                                                   \
-        static constexpr bool value =                                         \
-                std::is_integral<decltype(detect(std::declval<T>()))>::value; \
-    }
-
-namespace wpi
-{
-/*!
-@brief detail namespace with internal helper functions
-
-This namespace collects functions that should not be exposed,
-implementations of some @ref json methods, and meta-programming helpers.
-
-@since version 2.1.0
-*/
-namespace detail
-{
-/////////////
-// helpers //
-/////////////
-
-template<typename> struct is_json : std::false_type {};
-
-template<> struct is_json<json> : std::true_type {};
-
-// alias templates to reduce boilerplate
-template<bool B, typename T = void>
-using enable_if_t = typename std::enable_if<B, T>::type;
-
-template<typename T>
-using uncvref_t = typename std::remove_cv<typename std::remove_reference<T>::type>::type;
-
-// dispatch utility (taken from ranges-v3)
-template<unsigned N> struct priority_tag : priority_tag < N - 1 > {};
-template<> struct priority_tag<0> {};
-
-////////////////////////
-// has_/is_ functions //
-////////////////////////
-
-// source: https://stackoverflow.com/a/37193089/4116453
-
-template <typename T, typename = void>
-struct is_complete_type : std::false_type {};
-
-template <typename T>
-struct is_complete_type<T, decltype(void(sizeof(T)))> : std::true_type {};
-
-NLOHMANN_JSON_HAS_HELPER(mapped_type);
-NLOHMANN_JSON_HAS_HELPER(key_type);
-NLOHMANN_JSON_HAS_HELPER(value_type);
-NLOHMANN_JSON_HAS_HELPER(iterator);
-
-template<bool B, class RealType, class CompatibleObjectType>
-struct is_compatible_object_type_impl : std::false_type {};
-
-template<class RealType, class CompatibleObjectType>
-struct is_compatible_object_type_impl<true, RealType, CompatibleObjectType>
-{
-    static constexpr auto value =
-        std::is_constructible<std::string_view, typename CompatibleObjectType::key_type>::value and
-        std::is_constructible<typename RealType::mapped_type, typename CompatibleObjectType::mapped_type>::value;
-};
-
-template<class BasicJsonType, class CompatibleObjectType>
-struct is_compatible_object_type
-{
-    static auto constexpr value = is_compatible_object_type_impl <
-                                  std::conjunction<std::negation<std::is_same<void, CompatibleObjectType>>,
-                                  has_mapped_type<CompatibleObjectType>,
-                                  has_key_type<CompatibleObjectType>>::value,
-                                  typename BasicJsonType::object_t, CompatibleObjectType >::value;
-};
-
-template<typename BasicJsonType, typename T>
-struct is_json_nested_type
-{
-    static auto constexpr value = std::is_same<T, typename BasicJsonType::iterator>::value or
-                                  std::is_same<T, typename BasicJsonType::const_iterator>::value or
-                                  std::is_same<T, typename BasicJsonType::reverse_iterator>::value or
-                                  std::is_same<T, typename BasicJsonType::const_reverse_iterator>::value;
-};
-
-template<class BasicJsonType, class CompatibleArrayType>
-struct is_compatible_array_type
-{
-    static auto constexpr value =
-        std::conjunction<std::negation<std::is_same<void, CompatibleArrayType>>,
-        std::negation<is_compatible_object_type<
-        BasicJsonType, CompatibleArrayType>>,
-        std::negation<std::is_constructible<std::string_view,
-        CompatibleArrayType>>,
-        std::negation<is_json_nested_type<BasicJsonType, CompatibleArrayType>>,
-        has_value_type<CompatibleArrayType>,
-        has_iterator<CompatibleArrayType>>::value;
-};
-
-template<bool, typename, typename>
-struct is_compatible_integer_type_impl : std::false_type {};
-
-template<typename RealIntegerType, typename CompatibleNumberIntegerType>
-struct is_compatible_integer_type_impl<true, RealIntegerType, CompatibleNumberIntegerType>
-{
-    // is there an assert somewhere on overflows?
-    using RealLimits = std::numeric_limits<RealIntegerType>;
-    using CompatibleLimits = std::numeric_limits<CompatibleNumberIntegerType>;
-
-    static constexpr auto value =
-        std::is_constructible<RealIntegerType, CompatibleNumberIntegerType>::value and
-        CompatibleLimits::is_integer and
-        RealLimits::is_signed == CompatibleLimits::is_signed;
-};
-
-template<typename RealIntegerType, typename CompatibleNumberIntegerType>
-struct is_compatible_integer_type
-{
-    static constexpr auto value =
-        is_compatible_integer_type_impl <
-        std::is_integral<CompatibleNumberIntegerType>::value and
-        not std::is_same<bool, CompatibleNumberIntegerType>::value,
-        RealIntegerType, CompatibleNumberIntegerType > ::value;
-};
-
-// trait checking if JSONSerializer<T>::from_json(json const&, udt&) exists
-template<typename BasicJsonType, typename T>
-struct has_from_json
-{
-  private:
-    // also check the return type of from_json
-    template<typename U, typename = enable_if_t<std::is_same<void, decltype(uncvref_t<U>::from_json(
-                 std::declval<BasicJsonType>(), std::declval<T&>()))>::value>>
-    static int detect(U&&);
-    static void detect(...);
-
-  public:
-    static constexpr bool value = std::is_integral<decltype(
-                                      detect(std::declval<typename BasicJsonType::template json_serializer<T, void>>()))>::value;
-};
-
-// This trait checks if JSONSerializer<T>::from_json(json const&) exists
-// this overload is used for non-default-constructible user-defined-types
-template<typename BasicJsonType, typename T>
-struct has_non_default_from_json
-{
-  private:
-    template <
-        typename U,
-        typename = enable_if_t<std::is_same<
-                                   T, decltype(uncvref_t<U>::from_json(std::declval<BasicJsonType>()))>::value >>
-    static int detect(U&&);
-    static void detect(...);
-
-  public:
-    static constexpr bool value = std::is_integral<decltype(detect(
-                                      std::declval<typename BasicJsonType::template json_serializer<T, void>>()))>::value;
-};
-
-// This trait checks if BasicJsonType::json_serializer<T>::to_json exists
-template<typename BasicJsonType, typename T>
-struct has_to_json
-{
-  private:
-    template<typename U, typename = decltype(uncvref_t<U>::to_json(
-                 std::declval<BasicJsonType&>(), std::declval<T>()))>
-    static int detect(U&&);
-    static void detect(...);
-
-  public:
-    static constexpr bool value = std::is_integral<decltype(detect(
-                                      std::declval<typename BasicJsonType::template json_serializer<T, void>>()))>::value;
-};
-
-template <typename BasicJsonType, typename CompatibleCompleteType>
-struct is_compatible_complete_type
-{
-    static constexpr bool value =
-        not std::is_base_of<std::istream, CompatibleCompleteType>::value and
-        not is_json<CompatibleCompleteType>::value and
-        not is_json_nested_type<BasicJsonType, CompatibleCompleteType>::value and
-        has_to_json<BasicJsonType, CompatibleCompleteType>::value;
-};
-
-template <typename BasicJsonType, typename CompatibleType>
-struct is_compatible_type
-    : std::conjunction<is_complete_type<CompatibleType>,
-      is_compatible_complete_type<BasicJsonType, CompatibleType>>
-{
-};
-
-// taken from ranges-v3
-template<typename T>
-struct static_const
-{
-    static constexpr T value{};
-};
-
-template<typename T>
-constexpr T static_const<T>::value;
-
-////////////////
-// exceptions //
-////////////////
-
-/*!
-@brief general exception of the @ref json class
-
-This class is an extension of `std::exception` objects with a member @a id for
-exception ids. It is used as the base class for all exceptions thrown by the
-@ref json class. This class can hence be used as "wildcard" to catch
-exceptions.
-
-Subclasses:
-- @ref parse_error for exceptions indicating a parse error
-- @ref invalid_iterator for exceptions indicating errors with iterators
-- @ref type_error for exceptions indicating executing a member function with
-                  a wrong type
-- @ref out_of_range for exceptions indicating access out of the defined range
-- @ref other_error for exceptions indicating other library errors
-
-@internal
-@note To have nothrow-copy-constructible exceptions, we internally use
-      `std::runtime_error` which can cope with arbitrary-length error messages.
-      Intermediate strings are built with static functions and then passed to
-      the actual constructor.
-@endinternal
-
-@liveexample{The following code shows how arbitrary library exceptions can be
-caught.,exception}
-
-@since version 3.0.0
-*/
-class exception : public std::exception
-{
-  public:
-    /// returns the explanatory string
-    const char* what() const noexcept override
-    {
-        return m.what();
-    }
-
-    /// the id of the exception
-    const int id;
-
-  protected:
-    exception(int id_, std::string_view what_arg);
-
-  private:
-    /// an exception object as storage for error messages
-    std::runtime_error m;
-};
-
-/*!
-@brief exception indicating a parse error
-
-This exception is thrown by the library when a parse error occurs. Parse errors
-can occur during the deserialization of JSON text, CBOR, MessagePack, as well
-as when using JSON Patch.
-
-Member @a byte holds the byte index of the last read character in the input
-file.
-
-Exceptions have ids 1xx.
-
-name / id                      | example message | description
------------------------------- | --------------- | -------------------------
-json.exception.parse_error.101 | parse error at 2: unexpected end of input; expected string literal | This error indicates a syntax error while deserializing a JSON text. The error message describes that an unexpected token (character) was encountered, and the member @a byte indicates the error position.
-json.exception.parse_error.102 | parse error at 14: missing or wrong low surrogate | JSON uses the `\uxxxx` format to describe Unicode characters. Code points above above 0xFFFF are split into two `\uxxxx` entries ("surrogate pairs"). This error indicates that the surrogate pair is incomplete or contains an invalid code point.
-json.exception.parse_error.103 | parse error: code points above 0x10FFFF are invalid | Unicode supports code points up to 0x10FFFF. Code points above 0x10FFFF are invalid.
-json.exception.parse_error.104 | parse error: JSON patch must be an array of objects | [RFC 6902](https://tools.ietf.org/html/rfc6902) requires a JSON Patch document to be a JSON document that represents an array of objects.
-json.exception.parse_error.105 | parse error: operation must have string member 'op' | An operation of a JSON Patch document must contain exactly one "op" member, whose value indicates the operation to perform. Its value must be one of "add", "remove", "replace", "move", "copy", or "test"; other values are errors.
-json.exception.parse_error.106 | parse error: array index '01' must not begin with '0' | An array index in a JSON Pointer ([RFC 6901](https://tools.ietf.org/html/rfc6901)) may be `0` or any number without a leading `0`.
-json.exception.parse_error.107 | parse error: JSON pointer must be empty or begin with '/' - was: 'foo' | A JSON Pointer must be a Unicode string containing a sequence of zero or more reference tokens, each prefixed by a `/` character.
-json.exception.parse_error.108 | parse error: escape character '~' must be followed with '0' or '1' | In a JSON Pointer, only `~0` and `~1` are valid escape sequences.
-json.exception.parse_error.109 | parse error: array index 'one' is not a number | A JSON Pointer array index must be a number.
-json.exception.parse_error.110 | parse error at 1: cannot read 2 bytes from vector | When parsing CBOR or MessagePack, the byte vector ends before the complete value has been read.
-json.exception.parse_error.112 | parse error at 1: error reading CBOR; last byte: 0xF8 | Not all types of CBOR or MessagePack are supported. This exception occurs if an unsupported byte was read.
-json.exception.parse_error.113 | parse error at 2: expected a CBOR string; last byte: 0x98 | While parsing a map key, a value that is not a string has been read.
-
-@note For an input with n bytes, 1 is the index of the first character and n+1
-      is the index of the terminating null byte or the end of file. This also
-      holds true when reading a byte vector (CBOR or MessagePack).
-
-@liveexample{The following code shows how a `parse_error` exception can be
-caught.,parse_error}
-
-@sa @ref exception for the base class of the library exceptions
-@sa @ref invalid_iterator for exceptions indicating errors with iterators
-@sa @ref type_error for exceptions indicating executing a member function with
-                    a wrong type
-@sa @ref out_of_range for exceptions indicating access out of the defined range
-@sa @ref other_error for exceptions indicating other library errors
-
-@since version 3.0.0
-*/
-class parse_error : public exception
-{
-  public:
-    /*!
-    @brief create a parse error exception
-    @param[in] id_       the id of the exception
-    @param[in] byte_     the byte index where the error occurred (or 0 if the
-                         position cannot be determined)
-    @param[in] what_arg  the explanatory string
-    @return parse_error object
-    */
-    static parse_error create(int id_, std::size_t byte_, std::string_view what_arg);
-
-    /*!
-    @brief byte index of the parse error
-
-    The byte index of the last read character in the input file.
-
-    @note For an input with n bytes, 1 is the index of the first character and
-          n+1 is the index of the terminating null byte or the end of file.
-          This also holds true when reading a byte vector (CBOR or MessagePack).
-    */
-    const std::size_t byte;
-
-  private:
-    parse_error(int id_, std::size_t byte_, std::string_view what_arg)
-        : exception(id_, what_arg), byte(byte_) {}
-};
-
-/*!
-@brief exception indicating errors with iterators
-
-This exception is thrown if iterators passed to a library function do not match
-the expected semantics.
-
-Exceptions have ids 2xx.
-
-name / id                           | example message | description
------------------------------------ | --------------- | -------------------------
-json.exception.invalid_iterator.201 | iterators are not compatible | The iterators passed to constructor @ref json(InputIT first, InputIT last) are not compatible, meaning they do not belong to the same container. Therefore, the range (@a first, @a last) is invalid.
-json.exception.invalid_iterator.202 | iterator does not fit current value | In an erase or insert function, the passed iterator @a pos does not belong to the JSON value for which the function was called. It hence does not define a valid position for the deletion/insertion.
-json.exception.invalid_iterator.203 | iterators do not fit current value | Either iterator passed to function @ref erase(IteratorType first, IteratorType last) does not belong to the JSON value from which values shall be erased. It hence does not define a valid range to delete values from.
-json.exception.invalid_iterator.204 | iterators out of range | When an iterator range for a primitive type (number, boolean, or string) is passed to a constructor or an erase function, this range has to be exactly (@ref begin(), @ref end()), because this is the only way the single stored value is expressed. All other ranges are invalid.
-json.exception.invalid_iterator.205 | iterator out of range | When an iterator for a primitive type (number, boolean, or string) is passed to an erase function, the iterator has to be the @ref begin() iterator, because it is the only way to address the stored value. All other iterators are invalid.
-json.exception.invalid_iterator.206 | cannot construct with iterators from null | The iterators passed to constructor @ref json(InputIT first, InputIT last) belong to a JSON null value and hence to not define a valid range.
-json.exception.invalid_iterator.207 | cannot use key() for non-object iterators | The key() member function can only be used on iterators belonging to a JSON object, because other types do not have a concept of a key.
-json.exception.invalid_iterator.208 | cannot use operator[] for object iterators | The operator[] to specify a concrete offset cannot be used on iterators belonging to a JSON object, because JSON objects are unordered.
-json.exception.invalid_iterator.209 | cannot use offsets with object iterators | The offset operators (+, -, +=, -=) cannot be used on iterators belonging to a JSON object, because JSON objects are unordered.
-json.exception.invalid_iterator.210 | iterators do not fit | The iterator range passed to the insert function are not compatible, meaning they do not belong to the same container. Therefore, the range (@a first, @a last) is invalid.
-json.exception.invalid_iterator.211 | passed iterators may not belong to container | The iterator range passed to the insert function must not be a subrange of the container to insert to.
-json.exception.invalid_iterator.212 | cannot compare iterators of different containers | When two iterators are compared, they must belong to the same container.
-json.exception.invalid_iterator.213 | cannot compare order of object iterators | The order of object iterators cannot be compared, because JSON objects are unordered.
-json.exception.invalid_iterator.214 | cannot get value | Cannot get value for iterator: Either the iterator belongs to a null value or it is an iterator to a primitive type (number, boolean, or string), but the iterator is different to @ref begin().
-
-@liveexample{The following code shows how an `invalid_iterator` exception can be
-caught.,invalid_iterator}
-
-@sa @ref exception for the base class of the library exceptions
-@sa @ref parse_error for exceptions indicating a parse error
-@sa @ref type_error for exceptions indicating executing a member function with
-                    a wrong type
-@sa @ref out_of_range for exceptions indicating access out of the defined range
-@sa @ref other_error for exceptions indicating other library errors
-
-@since version 3.0.0
-*/
-class invalid_iterator : public exception
-{
-  public:
-    static invalid_iterator create(int id_, std::string_view what_arg);
-    static invalid_iterator create(int id_, std::string_view what_arg, std::string_view type_info);
-
-  private:
-    invalid_iterator(int id_, std::string_view what_arg)
-        : exception(id_, what_arg) {}
-};
-
-/*!
-@brief exception indicating executing a member function with a wrong type
-
-This exception is thrown in case of a type error; that is, a library function is
-executed on a JSON value whose type does not match the expected semantics.
-
-Exceptions have ids 3xx.
-
-name / id                     | example message | description
------------------------------ | --------------- | -------------------------
-json.exception.type_error.301 | cannot create object from initializer list | To create an object from an initializer list, the initializer list must consist only of a list of pairs whose first element is a string. When this constraint is violated, an array is created instead.
-json.exception.type_error.302 | type must be object, but is array | During implicit or explicit value conversion, the JSON type must be compatible to the target type. For instance, a JSON string can only be converted into string types, but not into numbers or boolean types.
-json.exception.type_error.303 | incompatible ReferenceType for get_ref, actual type is object | To retrieve a reference to a value stored in a @ref json object with @ref get_ref, the type of the reference must match the value type. For instance, for a JSON array, the @a ReferenceType must be @ref array_t&.
-json.exception.type_error.304 | cannot use at() with string | The @ref at() member functions can only be executed for certain JSON types.
-json.exception.type_error.305 | cannot use operator[] with string | The @ref operator[] member functions can only be executed for certain JSON types.
-json.exception.type_error.306 | cannot use value() with string | The @ref value() member functions can only be executed for certain JSON types.
-json.exception.type_error.307 | cannot use erase() with string | The @ref erase() member functions can only be executed for certain JSON types.
-json.exception.type_error.308 | cannot use push_back() with string | The @ref push_back() and @ref operator+= member functions can only be executed for certain JSON types.
-json.exception.type_error.309 | cannot use insert() with | The @ref insert() member functions can only be executed for certain JSON types.
-json.exception.type_error.310 | cannot use swap() with number | The @ref swap() member functions can only be executed for certain JSON types.
-json.exception.type_error.311 | cannot use emplace_back() with string | The @ref emplace_back() member function can only be executed for certain JSON types.
-json.exception.type_error.312 | cannot use update() with string | The @ref update() member functions can only be executed for certain JSON types.
-json.exception.type_error.313 | invalid value to unflatten | The @ref unflatten function converts an object whose keys are JSON Pointers back into an arbitrary nested JSON value. The JSON Pointers must not overlap, because then the resulting value would not be well defined.
-json.exception.type_error.314 | only objects can be unflattened | The @ref unflatten function only works for an object whose keys are JSON Pointers.
-json.exception.type_error.315 | values in object must be primitive | The @ref unflatten function only works for an object whose keys are JSON Pointers and whose values are primitive.
-json.exception.type_error.316 | invalid UTF-8 byte at index 10: 0x7E | The @ref dump function only works with UTF-8 encoded strings; that is, if you assign a `std::string` to a JSON value, make sure it is UTF-8 encoded. |
-
-@liveexample{The following code shows how a `type_error` exception can be
-caught.,type_error}
-
-@sa @ref exception for the base class of the library exceptions
-@sa @ref parse_error for exceptions indicating a parse error
-@sa @ref invalid_iterator for exceptions indicating errors with iterators
-@sa @ref out_of_range for exceptions indicating access out of the defined range
-@sa @ref other_error for exceptions indicating other library errors
-
-@since version 3.0.0
-*/
-class type_error : public exception
-{
-  public:
-    static type_error create(int id_, std::string_view what_arg);
-    static type_error create(int id_, std::string_view what_arg, std::string_view type_info);
-
-  private:
-    type_error(int id_, std::string_view what_arg) : exception(id_, what_arg) {}
-};
-
-/*!
-@brief exception indicating access out of the defined range
-
-This exception is thrown in case a library function is called on an input
-parameter that exceeds the expected range, for instance in case of array
-indices or nonexisting object keys.
-
-Exceptions have ids 4xx.
-
-name / id                       | example message | description
-------------------------------- | --------------- | -------------------------
-json.exception.out_of_range.401 | array index 3 is out of range | The provided array index @a i is larger than @a size-1.
-json.exception.out_of_range.402 | array index '-' (3) is out of range | The special array index `-` in a JSON Pointer never describes a valid element of the array, but the index past the end. That is, it can only be used to add elements at this position, but not to read it.
-json.exception.out_of_range.403 | key 'foo' not found | The provided key was not found in the JSON object.
-json.exception.out_of_range.404 | unresolved reference token 'foo' | A reference token in a JSON Pointer could not be resolved.
-json.exception.out_of_range.405 | JSON pointer has no parent | The JSON Patch operations 'remove' and 'add' can not be applied to the root element of the JSON value.
-json.exception.out_of_range.406 | number overflow parsing '10E1000' | A parsed number could not be stored as without changing it to NaN or INF.
-json.exception.out_of_range.407 | number overflow serializing '9223372036854775808' | UBJSON only supports integers numbers up to 9223372036854775807. |
-json.exception.out_of_range.408 | excessive array size: 8658170730974374167 | The size (following `#`) of an UBJSON array or object exceeds the maximal capacity. |
-
-@liveexample{The following code shows how an `out_of_range` exception can be
-caught.,out_of_range}
-
-@sa @ref exception for the base class of the library exceptions
-@sa @ref parse_error for exceptions indicating a parse error
-@sa @ref invalid_iterator for exceptions indicating errors with iterators
-@sa @ref type_error for exceptions indicating executing a member function with
-                    a wrong type
-@sa @ref other_error for exceptions indicating other library errors
-
-@since version 3.0.0
-*/
-class out_of_range : public exception
-{
-  public:
-    static out_of_range create(int id_, std::string_view what_arg);
-
-  private:
-    out_of_range(int id_, std::string_view what_arg) : exception(id_, what_arg) {}
-};
-
-/*!
-@brief exception indicating other library errors
-
-This exception is thrown in case of errors that cannot be classified with the
-other exception types.
-
-Exceptions have ids 5xx.
-
-name / id                      | example message | description
------------------------------- | --------------- | -------------------------
-json.exception.other_error.501 | unsuccessful: {"op":"test","path":"/baz", "value":"bar"} | A JSON Patch operation 'test' failed. The unsuccessful operation is also printed.
-
-@sa @ref exception for the base class of the library exceptions
-@sa @ref parse_error for exceptions indicating a parse error
-@sa @ref invalid_iterator for exceptions indicating errors with iterators
-@sa @ref type_error for exceptions indicating executing a member function with
-                    a wrong type
-@sa @ref out_of_range for exceptions indicating access out of the defined range
-
-@liveexample{The following code shows how an `other_error` exception can be
-caught.,other_error}
-
-@since version 3.0.0
-*/
-class other_error : public exception
-{
-  public:
-    static other_error create(int id_, std::string_view what_arg);
-
-  private:
-    other_error(int id_, std::string_view what_arg) : exception(id_, what_arg) {}
-};
-
-///////////////////////////
-// JSON type enumeration //
-///////////////////////////
-
-/*!
-@brief the JSON type enumeration
-
-This enumeration collects the different JSON types. It is internally used to
-distinguish the stored values, and the functions @ref json::is_null(),
-@ref json::is_object(), @ref json::is_array(),
-@ref json::is_string(), @ref json::is_boolean(),
-@ref json::is_number() (with @ref json::is_number_integer(),
-@ref json::is_number_unsigned(), and @ref json::is_number_float()),
-@ref json::is_discarded(), @ref json::is_primitive(), and
-@ref json::is_structured() rely on it.
-
-@note There are three enumeration entries (number_integer, number_unsigned, and
-number_float), because the library distinguishes these three types for numbers:
-uint64_t is used for unsigned integers,
-int64_t is used for signed integers, and
-double is used for floating-point numbers or to
-approximate integers which do not fit in the limits of their respective type.
-
-@sa @ref json::json(const value_t value_type) -- create a JSON
-value with the default value for a given type
-
-@since version 1.0.0
-*/
-enum class value_t : std::uint8_t
-{
-    null,             ///< null value
-    object,           ///< object (unordered set of name/value pairs)
-    array,            ///< array (ordered collection of values)
-    string,           ///< string value
-    boolean,          ///< boolean value
-    number_integer,   ///< number value (signed integer)
-    number_unsigned,  ///< number value (unsigned integer)
-    number_float,     ///< number value (floating-point)
-    discarded         ///< discarded by the the parser callback function
-};
-
-/*!
-@brief comparison operator for JSON types
-
-Returns an ordering that is similar to Python:
-- order: null < boolean < number < object < array < string
-- furthermore, each type is not smaller than itself
-- discarded values are not comparable
-
-@since version 1.0.0
-*/
-inline bool operator<(const value_t lhs, const value_t rhs) noexcept
-{
-    static constexpr std::array<std::uint8_t, 8> order = {{
-            0 /* null */, 3 /* object */, 4 /* array */, 5 /* string */,
-            1 /* boolean */, 2 /* integer */, 2 /* unsigned */, 2 /* float */
-        }
-    };
-
-    const auto l_index = static_cast<std::size_t>(lhs);
-    const auto r_index = static_cast<std::size_t>(rhs);
-    return l_index < order.size() and r_index < order.size() and order[l_index] < order[r_index];
-}
-
-// overloads for json template parameters
-template<typename BasicJsonType, typename ArithmeticType,
-         enable_if_t<std::is_arithmetic<ArithmeticType>::value and
-                     not std::is_same<ArithmeticType, bool>::value,
-                     int> = 0>
-void get_arithmetic_value(const BasicJsonType& j, ArithmeticType& val)
-{
-    switch (static_cast<value_t>(j))
-    {
-        case value_t::number_unsigned:
-        {
-            val = static_cast<ArithmeticType>(*j.template get_ptr<const uint64_t*>());
-            break;
-        }
-        case value_t::number_integer:
-        {
-            val = static_cast<ArithmeticType>(*j.template get_ptr<const int64_t*>());
-            break;
-        }
-        case value_t::number_float:
-        {
-            val = static_cast<ArithmeticType>(*j.template get_ptr<const double*>());
-            break;
-        }
-
-        default:
-            JSON_THROW(type_error::create(302, "type must be number, but is", j.type_name()));
-    }
-}
-
-template<typename BasicJsonType>
-void from_json(const BasicJsonType& j, bool& b)
-{
-    if (JSON_UNLIKELY(not j.is_boolean()))
-    {
-        JSON_THROW(type_error::create(302, "type must be boolean, but is", j.type_name()));
-    }
-    b = *j.template get_ptr<const bool*>();
-}
-
-template<typename BasicJsonType>
-void from_json(const BasicJsonType& j, std::string& s)
-{
-    if (JSON_UNLIKELY(not j.is_string()))
-    {
-        JSON_THROW(type_error::create(302, "type must be string, but is", j.type_name()));
-    }
-    s = *j.template get_ptr<const std::string*>();
-}
-
-template<typename BasicJsonType>
-void from_json(const BasicJsonType& j, double& val)
-{
-    get_arithmetic_value(j, val);
-}
-
-template<typename BasicJsonType>
-void from_json(const BasicJsonType& j, uint64_t& val)
-{
-    get_arithmetic_value(j, val);
-}
-
-template<typename BasicJsonType>
-void from_json(const BasicJsonType& j, int64_t& val)
-{
-    get_arithmetic_value(j, val);
-}
-
-template<typename BasicJsonType, typename EnumType,
-         enable_if_t<std::is_enum<EnumType>::value, int> = 0>
-void from_json(const BasicJsonType& j, EnumType& e)
-{
-    typename std::underlying_type<EnumType>::type val;
-    get_arithmetic_value(j, val);
-    e = static_cast<EnumType>(val);
-}
-
-template<typename BasicJsonType>
-void from_json(const BasicJsonType& j, typename BasicJsonType::array_t& arr)
-{
-    if (JSON_UNLIKELY(not j.is_array()))
-    {
-        JSON_THROW(type_error::create(302, "type must be array, but is", j.type_name()));
-    }
-    arr = *j.template get_ptr<const typename BasicJsonType::array_t*>();
-}
-
-template<typename BasicJsonType, typename CompatibleArrayType>
-void from_json_array_impl(const BasicJsonType& j, CompatibleArrayType& arr, priority_tag<0> /*unused*/)
-{
-    using std::end;
-
-    std::transform(j.begin(), j.end(),
-                   std::inserter(arr, end(arr)), [](const BasicJsonType & i)
-    {
-        // get<BasicJsonType>() returns *this, this won't call a from_json
-        // method when value_type is BasicJsonType
-        return i.template get<typename CompatibleArrayType::value_type>();
-    });
-}
-
-template<typename BasicJsonType, typename CompatibleArrayType>
-auto from_json_array_impl(const BasicJsonType& j, CompatibleArrayType& arr, priority_tag<1> /*unused*/)
--> decltype(
-    arr.reserve(std::declval<typename CompatibleArrayType::size_type>()),
-    void())
-{
-    using std::end;
-
-    arr.reserve(j.size());
-    std::transform(j.begin(), j.end(),
-                   std::inserter(arr, end(arr)), [](const BasicJsonType & i)
-    {
-        // get<BasicJsonType>() returns *this, this won't call a from_json
-        // method when value_type is BasicJsonType
-        return i.template get<typename CompatibleArrayType::value_type>();
-    });
-}
-
-template<typename BasicJsonType, typename T, std::size_t N>
-void from_json_array_impl(const BasicJsonType& j, std::array<T, N>& arr, priority_tag<2> /*unused*/)
-{
-    for (std::size_t i = 0; i < N; ++i)
-    {
-        arr[i] = j.at(i).template get<T>();
-    }
-}
-
-template <
-    typename BasicJsonType, typename CompatibleArrayType,
-    enable_if_t <
-        is_compatible_array_type<BasicJsonType, CompatibleArrayType>::value and
-        not std::is_same<typename BasicJsonType::array_t,
-                         CompatibleArrayType>::value and
-        std::is_constructible <
-            BasicJsonType, typename CompatibleArrayType::value_type >::value,
-        int > = 0 >
-void from_json(const BasicJsonType& j, CompatibleArrayType& arr)
-{
-    if (JSON_UNLIKELY(not j.is_array()))
-    {
-        JSON_THROW(type_error::create(302, "type must be array, but is", j.type_name()));
-    }
-
-    from_json_array_impl(j, arr, priority_tag<2> {});
-}
-
-template<typename BasicJsonType>
-inline
-void from_json(const BasicJsonType& j, typename BasicJsonType::object_t& obj)
-{
-    if (!j.is_object())
-    {
-        JSON_THROW(type_error::create(302, "type must be object, but is", j.type_name()));
-    }
-
-    auto inner_object = j.template get_ptr<const typename BasicJsonType::object_t*>();
-    for (const auto& i : *inner_object) {
-        obj.try_emplace(i.first(), i.second);
-    }
-}
-
-template<typename BasicJsonType, typename CompatibleObjectType,
-         enable_if_t<is_compatible_object_type<BasicJsonType, CompatibleObjectType>::value and
-                     not std::is_same<typename BasicJsonType::object_t, CompatibleObjectType>::value, int> = 0>
-void from_json(const BasicJsonType& j, CompatibleObjectType& obj)
-{
-    if (JSON_UNLIKELY(not j.is_object()))
-    {
-        JSON_THROW(type_error::create(302, "type must be object, but is", j.type_name()));
-    }
-
-    auto inner_object = j.template get_ptr<const typename BasicJsonType::object_t*>();
-    using std::begin;
-    using std::end;
-    using value_type = typename CompatibleObjectType::value_type;
-    std::vector<value_type> v;
-    v.reserve(j.size());
-    for (const auto& p : *inner_object)
-    {
-        v.emplace_back(
-            p.first(),
-            p.second
-            .template get<typename CompatibleObjectType::mapped_type>());
-    }
-    // we could avoid the assignment, but this might require a for loop, which
-    // might be less efficient than the container constructor for some
-    // containers (would it?)
-    obj = CompatibleObjectType(std::make_move_iterator(begin(v)),
-                               std::make_move_iterator(end(v)));
-}
-
-// overload for arithmetic types, not chosen for json template arguments
-// (BooleanType, etc..); note: Is it really necessary to provide explicit
-// overloads for bool etc. in case of a custom BooleanType which is not
-// an arithmetic type?
-template<typename BasicJsonType, typename ArithmeticType,
-         enable_if_t <
-             std::is_arithmetic<ArithmeticType>::value and
-             not std::is_same<ArithmeticType, uint64_t>::value and
-             not std::is_same<ArithmeticType, int64_t>::value and
-             not std::is_same<ArithmeticType, double>::value and
-             not std::is_same<ArithmeticType, bool>::value,
-             int> = 0>
-void from_json(const BasicJsonType& j, ArithmeticType& val)
-{
-    switch (static_cast<value_t>(j))
-    {
-        case value_t::number_unsigned:
-        {
-            val = static_cast<ArithmeticType>(*j.template get_ptr<const uint64_t*>());
-            break;
-        }
-        case value_t::number_integer:
-        {
-            val = static_cast<ArithmeticType>(*j.template get_ptr<const int64_t*>());
-            break;
-        }
-        case value_t::number_float:
-        {
-            val = static_cast<ArithmeticType>(*j.template get_ptr<const double*>());
-            break;
-        }
-        case value_t::boolean:
-        {
-            val = static_cast<ArithmeticType>(*j.template get_ptr<const bool*>());
-            break;
-        }
-
-        default:
-            JSON_THROW(type_error::create(302, "type must be number, but is", j.type_name()));
-    }
-}
-
-template<typename BasicJsonType, typename A1, typename A2>
-void from_json(const BasicJsonType& j, std::pair<A1, A2>& p)
-{
-    p = {j.at(0).template get<A1>(), j.at(1).template get<A2>()};
-}
-
-template<typename BasicJsonType, typename Tuple, std::size_t... Idx>
-void from_json_tuple_impl(const BasicJsonType& j, Tuple& t, std::index_sequence<Idx...>)
-{
-    t = std::make_tuple(j.at(Idx).template get<typename std::tuple_element<Idx, Tuple>::type>()...);
-}
-
-template<typename BasicJsonType, typename... Args>
-void from_json(const BasicJsonType& j, std::tuple<Args...>& t)
-{
-    from_json_tuple_impl(j, t, std::index_sequence_for<Args...> {});
-}
-
-struct from_json_fn
-{
-  private:
-    template<typename BasicJsonType, typename T>
-    auto call(const BasicJsonType& j, T& val, priority_tag<1> /*unused*/) const
-    noexcept(noexcept(from_json(j, val)))
-    -> decltype(from_json(j, val), void())
-    {
-        return from_json(j, val);
-    }
-
-    template<typename BasicJsonType, typename T>
-    void call(const BasicJsonType& /*unused*/, T& /*unused*/, priority_tag<0> /*unused*/) const noexcept
-    {
-        static_assert(sizeof(BasicJsonType) == 0,
-                      "could not find from_json() method in T's namespace");
-#ifdef _MSC_VER
-        // MSVC does not show a stacktrace for the above assert
-        using decayed = uncvref_t<T>;
-        static_assert(sizeof(typename decayed::force_msvc_stacktrace) == 0,
-                      "forcing MSVC stacktrace to show which T we're talking about.");
-#endif
-    }
-
-  public:
-    template<typename BasicJsonType, typename T>
-    void operator()(const BasicJsonType& j, T& val) const
-    noexcept(noexcept(std::declval<from_json_fn>().call(j, val, priority_tag<1> {})))
-    {
-        return call(j, val, priority_tag<1> {});
-    }
-};
-}
-
-// namespace to hold default `from_json` function
-// to see why this is required:
-// http://www.open-std.org/jtc1/sc22/wg21/docs/papers/2015/n4381.html
-namespace
-{
-constexpr const auto& from_json = detail::static_const<detail::from_json_fn>::value;
-}
-
-namespace detail
-{
-//////////////////
-// constructors //
-//////////////////
-
-template<value_t> struct external_constructor;
-
-template<>
-struct external_constructor<value_t::boolean>
-{
-    template<typename BasicJsonType>
-    static void construct(BasicJsonType& j, bool b) noexcept
-    {
-        j.m_type = value_t::boolean;
-        j.m_value = b;
-        j.assert_invariant();
-    }
-};
-
-template<>
-struct external_constructor<value_t::string>
-{
-    template<typename BasicJsonType>
-    static void construct(BasicJsonType& j, std::string_view s)
-    {
-        j.m_type = value_t::string;
-        j.m_value = s;
-        j.assert_invariant();
-    }
-
-    template<typename BasicJsonType, typename T,
-             enable_if_t<std::is_same<std::string, T>::value, int> = 0>
-    static void construct(BasicJsonType& j, T&& s)
-    {
-        j.m_type = value_t::string;
-        j.m_value = std::move(s);
-        j.assert_invariant();
-    }
-};
-
-template<>
-struct external_constructor<value_t::number_float>
-{
-    template<typename BasicJsonType>
-    static void construct(BasicJsonType& j, double val) noexcept
-    {
-        j.m_type = value_t::number_float;
-        j.m_value = val;
-        j.assert_invariant();
-    }
-};
-
-template<>
-struct external_constructor<value_t::number_unsigned>
-{
-    template<typename BasicJsonType>
-    static void construct(BasicJsonType& j, uint64_t val) noexcept
-    {
-        j.m_type = value_t::number_unsigned;
-        j.m_value = val;
-        j.assert_invariant();
-    }
-};
-
-template<>
-struct external_constructor<value_t::number_integer>
-{
-    template<typename BasicJsonType>
-    static void construct(BasicJsonType& j, int64_t val) noexcept
-    {
-        j.m_type = value_t::number_integer;
-        j.m_value = val;
-        j.assert_invariant();
-    }
-};
-
-template<>
-struct external_constructor<value_t::array>
-{
-    template<typename BasicJsonType>
-    static void construct(BasicJsonType& j, const typename BasicJsonType::array_t& arr)
-    {
-        j.m_type = value_t::array;
-        j.m_value = arr;
-        j.assert_invariant();
-    }
-
-    template<typename BasicJsonType>
-    static void construct(BasicJsonType& j, typename BasicJsonType::array_t&& arr)
-    {
-        j.m_type = value_t::array;
-        j.m_value = std::move(arr);
-        j.assert_invariant();
-    }
-
-    template<typename BasicJsonType, typename T>
-    static void construct(BasicJsonType& j, span<T> arr)
-    {
-        using std::begin;
-        using std::end;
-        j.m_type = value_t::array;
-        j.m_value.array = j.template create<typename BasicJsonType::array_t>(begin(arr), end(arr));
-        j.assert_invariant();
-    }
-
-    template<typename BasicJsonType, typename CompatibleArrayType,
-             enable_if_t<not std::is_same<CompatibleArrayType, typename BasicJsonType::array_t>::value,
-                         int> = 0>
-    static void construct(BasicJsonType& j, const CompatibleArrayType& arr)
-    {
-        using std::begin;
-        using std::end;
-        j.m_type = value_t::array;
-        j.m_value.array = j.template create<typename BasicJsonType::array_t>(begin(arr), end(arr));
-        j.assert_invariant();
-    }
-
-    template<typename BasicJsonType>
-    static void construct(BasicJsonType& j, const std::vector<bool>& arr)
-    {
-        j.m_type = value_t::array;
-        j.m_value = value_t::array;
-        j.m_value.array->reserve(arr.size());
-        for (const bool x : arr)
-        {
-            j.m_value.array->push_back(x);
-        }
-        j.assert_invariant();
-    }
-};
-
-template<>
-struct external_constructor<value_t::object>
-{
-    template<typename BasicJsonType>
-    static void construct(BasicJsonType& j, const typename BasicJsonType::object_t& obj)
-    {
-        j.m_type = value_t::object;
-        j.m_value = obj;
-        j.assert_invariant();
-    }
-
-    template<typename BasicJsonType>
-    static void construct(BasicJsonType& j, typename BasicJsonType::object_t&& obj)
-    {
-        j.m_type = value_t::object;
-        j.m_value = std::move(obj);
-        j.assert_invariant();
-    }
-
-    template<typename BasicJsonType, typename CompatibleObjectType,
-             enable_if_t<not std::is_same<CompatibleObjectType, typename BasicJsonType::object_t>::value, int> = 0>
-    static void construct(BasicJsonType& j, const CompatibleObjectType& obj)
-    {
-        j.m_type = value_t::object;
-        j.m_value = value_t::object;
-        for (const auto& x : obj)
-        {
-            j.m_value.object->try_emplace(x.first, x.second);
-        }
-        j.assert_invariant();
-    }
-};
-
-/////////////
-// to_json //
-/////////////
-
-template<typename BasicJsonType, typename T,
-         enable_if_t<std::is_same<T, bool>::value, int> = 0>
-void to_json(BasicJsonType& j, T b) noexcept
-{
-    external_constructor<value_t::boolean>::construct(j, b);
-}
-
-template<typename BasicJsonType, typename CompatibleString,
-         enable_if_t<std::is_constructible<std::string_view, CompatibleString>::value, int> = 0>
-void to_json(BasicJsonType& j, const CompatibleString& s)
-{
-    external_constructor<value_t::string>::construct(j, s);
-}
-
-template<typename BasicJsonType, typename T,
-         enable_if_t<std::is_same<std::string, T>::value, int> = 0>
-void to_json(BasicJsonType& j, T&& s)
-{
-    external_constructor<value_t::string>::construct(j, std::move(s));
-}
-
-template<typename BasicJsonType, typename FloatType,
-         enable_if_t<std::is_floating_point<FloatType>::value, int> = 0>
-void to_json(BasicJsonType& j, FloatType val) noexcept
-{
-    external_constructor<value_t::number_float>::construct(j, static_cast<double>(val));
-}
-
-template<typename BasicJsonType, typename CompatibleNumberUnsignedType,
-         enable_if_t<is_compatible_integer_type<uint64_t, CompatibleNumberUnsignedType>::value, int> = 0>
-void to_json(BasicJsonType& j, CompatibleNumberUnsignedType val) noexcept
-{
-    external_constructor<value_t::number_unsigned>::construct(j, static_cast<uint64_t>(val));
-}
-
-template<typename BasicJsonType, typename CompatibleNumberIntegerType,
-         enable_if_t<is_compatible_integer_type<int64_t, CompatibleNumberIntegerType>::value, int> = 0>
-void to_json(BasicJsonType& j, CompatibleNumberIntegerType val) noexcept
-{
-    external_constructor<value_t::number_integer>::construct(j, static_cast<int64_t>(val));
-}
-
-template<typename BasicJsonType, typename EnumType,
-         enable_if_t<std::is_enum<EnumType>::value, int> = 0>
-void to_json(BasicJsonType& j, EnumType e) noexcept
-{
-    using underlying_type = typename std::underlying_type<EnumType>::type;
-    external_constructor<value_t::number_integer>::construct(j, static_cast<underlying_type>(e));
-}
-
-template<typename BasicJsonType>
-void to_json(BasicJsonType& j, const std::vector<bool>& e)
-{
-    external_constructor<value_t::array>::construct(j, e);
-}
-
-template<typename BasicJsonType, typename CompatibleArrayType,
-         enable_if_t<is_compatible_array_type<BasicJsonType, CompatibleArrayType>::value or
-                     std::is_same<typename BasicJsonType::array_t, CompatibleArrayType>::value,
-                     int> = 0>
-void to_json(BasicJsonType& j, const CompatibleArrayType& arr)
-{
-    external_constructor<value_t::array>::construct(j, arr);
-}
-
-template<typename BasicJsonType>
-void to_json(BasicJsonType& j, typename BasicJsonType::array_t&& arr)
-{
-    external_constructor<value_t::array>::construct(j, std::move(arr));
-}
-
-template<typename BasicJsonType, typename CompatibleObjectType,
-         enable_if_t<is_compatible_object_type<BasicJsonType, CompatibleObjectType>::value, int> = 0>
-void to_json(BasicJsonType& j, const CompatibleObjectType& obj)
-{
-    external_constructor<value_t::object>::construct(j, obj);
-}
-
-template<typename BasicJsonType>
-void to_json(BasicJsonType& j, typename BasicJsonType::object_t&& obj)
-{
-    external_constructor<value_t::object>::construct(j, std::move(obj));
-}
-
-template<typename BasicJsonType, typename T, std::size_t N,
-         enable_if_t<not std::is_constructible<std::string_view, T (&)[N]>::value, int> = 0>
-void to_json(BasicJsonType& j, T (&arr)[N])
-{
-    external_constructor<value_t::array>::construct(j, arr);
-}
-
-template<typename BasicJsonType, typename... Args>
-void to_json(BasicJsonType& j, const std::pair<Args...>& p)
-{
-    j = {p.first, p.second};
-}
-
-template<typename BasicJsonType, typename Tuple, std::size_t... Idx>
-void to_json_tuple_impl(BasicJsonType& j, const Tuple& t, std::index_sequence<Idx...>)
-{
-    j = {std::get<Idx>(t)...};
-}
-
-template<typename BasicJsonType, typename... Args>
-void to_json(BasicJsonType& j, const std::tuple<Args...>& t)
-{
-    to_json_tuple_impl(j, t, std::index_sequence_for<Args...> {});
-}
-
-struct to_json_fn
-{
-  private:
-    template<typename BasicJsonType, typename T>
-    auto call(BasicJsonType& j, T&& val, priority_tag<1> /*unused*/) const noexcept(noexcept(to_json(j, std::forward<T>(val))))
-    -> decltype(to_json(j, std::forward<T>(val)), void())
-    {
-        return to_json(j, std::forward<T>(val));
-    }
-
-    template<typename BasicJsonType, typename T>
-    void call(BasicJsonType& /*unused*/, T&& /*unused*/, priority_tag<0> /*unused*/) const noexcept
-    {
-        static_assert(sizeof(BasicJsonType) == 0,
-                      "could not find to_json() method in T's namespace");
-
-#ifdef _MSC_VER
-        // MSVC does not show a stacktrace for the above assert
-        using decayed = uncvref_t<T>;
-        static_assert(sizeof(typename decayed::force_msvc_stacktrace) == 0,
-                      "forcing MSVC stacktrace to show which T we're talking about.");
-#endif
-    }
-
-  public:
-    template<typename BasicJsonType, typename T>
-    void operator()(BasicJsonType& j, T&& val) const
-    noexcept(noexcept(std::declval<to_json_fn>().call(j, std::forward<T>(val), priority_tag<1> {})))
-    {
-        return call(j, std::forward<T>(val), priority_tag<1> {});
-    }
-};
-}
-
-// namespace to hold default `to_json` function
-namespace
-{
-constexpr const auto& to_json = detail::static_const<detail::to_json_fn>::value;
-}
-
-namespace detail
-{
-/*
-@brief an iterator for primitive JSON types
-
-This class models an iterator for primitive JSON types (boolean, number,
-string). It's only purpose is to allow the iterator/const_iterator classes
-to "iterate" over primitive values. Internally, the iterator is modeled by
-a `difference_type` variable. Value begin_value (`0`) models the begin,
-end_value (`1`) models past the end.
-*/
-class primitive_iterator_t
-{
-  private:
-    using difference_type = std::ptrdiff_t;
-    static constexpr difference_type begin_value = 0;
-    static constexpr difference_type end_value = begin_value + 1;
-
-    /// iterator as signed integer type
-    difference_type m_it = (std::numeric_limits<std::ptrdiff_t>::min)();
-
-  public:
-    constexpr difference_type get_value() const noexcept
-    {
-        return m_it;
-    }
-
-    /// set iterator to a defined beginning
-    void set_begin() noexcept
-    {
-        m_it = begin_value;
-    }
-
-    /// set iterator to a defined past the end
-    void set_end() noexcept
-    {
-        m_it = end_value;
-    }
-
-    /// return whether the iterator can be dereferenced
-    constexpr bool is_begin() const noexcept
-    {
-        return m_it == begin_value;
-    }
-
-    /// return whether the iterator is at end
-    constexpr bool is_end() const noexcept
-    {
-        return m_it == end_value;
-    }
-
-    friend constexpr bool operator==(primitive_iterator_t lhs, primitive_iterator_t rhs) noexcept
-    {
-        return lhs.m_it == rhs.m_it;
-    }
-
-    friend constexpr bool operator<(primitive_iterator_t lhs, primitive_iterator_t rhs) noexcept
-    {
-        return lhs.m_it < rhs.m_it;
-    }
-
-    primitive_iterator_t operator+(difference_type n) noexcept
-    {
-        auto result = *this;
-        result += n;
-        return result;
-    }
-
-    friend constexpr difference_type operator-(primitive_iterator_t lhs, primitive_iterator_t rhs) noexcept
-    {
-        return lhs.m_it - rhs.m_it;
-    }
-
-    primitive_iterator_t& operator++() noexcept
-    {
-        ++m_it;
-        return *this;
-    }
-
-    primitive_iterator_t const operator++(int) noexcept
-    {
-        auto result = *this;
-        m_it++;
-        return result;
-    }
-
-    primitive_iterator_t& operator--() noexcept
-    {
-        --m_it;
-        return *this;
-    }
-
-    primitive_iterator_t const operator--(int) noexcept
-    {
-        auto result = *this;
-        m_it--;
-        return result;
-    }
-
-    primitive_iterator_t& operator+=(difference_type n) noexcept
-    {
-        m_it += n;
-        return *this;
-    }
-
-    primitive_iterator_t& operator-=(difference_type n) noexcept
-    {
-        m_it -= n;
-        return *this;
-    }
-};
-
-/*!
-@brief an iterator value
-
-@note This structure could easily be a union, but MSVC currently does not allow
-unions members with complex constructors, see https://github.com/nlohmann/json/pull/105.
-*/
-template<typename BasicJsonType> struct internal_iterator
-{
-    /// iterator for JSON objects
-    typename BasicJsonType::object_t::iterator object_iterator {};
-    /// iterator for JSON arrays
-    typename BasicJsonType::array_t::iterator array_iterator {};
-    /// generic iterator for all other types
-    primitive_iterator_t primitive_iterator {};
-};
-
-// forward declare, to be able to friend it later on
-template<typename IteratorType> class iteration_proxy;
-
-/*!
-@brief a template for a bidirectional iterator for the @ref json class
-
-This class implements a both iterators (iterator and const_iterator) for the
-@ref json class.
-
-@note An iterator is called *initialized* when a pointer to a JSON value has
-      been set (e.g., by a constructor or a copy assignment). If the iterator is
-      default-constructed, it is *uninitialized* and most methods are undefined.
-      **The library uses assertions to detect calls on uninitialized iterators.**
-
-@requirement The class satisfies the following concept requirements:
--
-[BidirectionalIterator](http://en.cppreference.com/w/cpp/concept/BidirectionalIterator):
-  The iterator that can be moved can be moved in both directions (i.e.
-  incremented and decremented).
-
-@since version 1.0.0, simplified in version 2.0.9, change to bidirectional
-       iterators in version 3.0.0 (see https://github.com/nlohmann/json/issues/593)
-*/
-template<typename BasicJsonType>
-class iter_impl
-{
-    /// allow json to access private members
-    friend iter_impl<typename std::conditional<std::is_const<BasicJsonType>::value, typename std::remove_const<BasicJsonType>::type, const BasicJsonType>::type>;
-    friend BasicJsonType;
-    friend iteration_proxy<iter_impl>;
-    friend class ::wpi::JsonTest;
-
-    using object_t = typename BasicJsonType::object_t;
-    using array_t = typename BasicJsonType::array_t;
-    // make sure BasicJsonType is json or const json
-    static_assert(is_json<typename std::remove_const<BasicJsonType>::type>::value,
-                  "iter_impl only accepts (const) json");
-
-  public:
-
-    /// The std::iterator class template (used as a base class to provide typedefs) is deprecated in C++17.
-    /// The C++ Standard has never required user-defined iterators to derive from std::iterator.
-    /// A user-defined iterator should provide publicly accessible typedefs named
-    /// iterator_category, value_type, difference_type, pointer, and reference.
-    /// Note that value_type is required to be non-const, even for constant iterators.
-    using iterator_category = std::bidirectional_iterator_tag;
-
-    /// the type of the values when the iterator is dereferenced
-    using value_type = typename BasicJsonType::value_type;
-    /// a type to represent differences between iterators
-    using difference_type = typename BasicJsonType::difference_type;
-    /// defines a pointer to the type iterated over (value_type)
-    using pointer = typename std::conditional<std::is_const<BasicJsonType>::value,
-          typename BasicJsonType::const_pointer,
-          typename BasicJsonType::pointer>::type;
-    /// defines a reference to the type iterated over (value_type)
-    using reference =
-        typename std::conditional<std::is_const<BasicJsonType>::value,
-        typename BasicJsonType::const_reference,
-        typename BasicJsonType::reference>::type;
-
-    /// default constructor
-    iter_impl() = default;
-
-    /*!
-    @brief constructor for a given JSON instance
-    @param[in] object  pointer to a JSON object for this iterator
-    @pre object != nullptr
-    @post The iterator is initialized; i.e. `m_object != nullptr`.
-    */
-    explicit iter_impl(pointer object) noexcept : m_object(object)
-    {
-        assert(m_object != nullptr);
-
-        switch (m_object->m_type)
-        {
-            case value_t::object:
-            {
-                m_it.object_iterator = typename object_t::iterator();
-                break;
-            }
-
-            case value_t::array:
-            {
-                m_it.array_iterator = typename array_t::iterator();
-                break;
-            }
-
-            default:
-            {
-                m_it.primitive_iterator = primitive_iterator_t();
-                break;
-            }
-        }
-    }
-
-    /*!
-    @note The conventional copy constructor and copy assignment are implicitly
-          defined. Combined with the following converting constructor and
-          assignment, they support: (1) copy from iterator to iterator, (2)
-          copy from const iterator to const iterator, and (3) conversion from
-          iterator to const iterator. However conversion from const iterator
-          to iterator is not defined.
-    */
-
-    /*!
-    @brief converting constructor
-    @param[in] other  non-const iterator to copy from
-    @note It is not checked whether @a other is initialized.
-    */
-    iter_impl(const iter_impl<typename std::remove_const<BasicJsonType>::type>& other) noexcept
-        : m_object(other.m_object), m_it(other.m_it) {}
-
-    /*!
-    @brief converting assignment
-    @param[in,out] other  non-const iterator to copy from
-    @return const/non-const iterator
-    @note It is not checked whether @a other is initialized.
-    */
-    iter_impl& operator=(const iter_impl<typename std::remove_const<BasicJsonType>::type>& other) noexcept
-    {
-        m_object = other.m_object;
-        m_it = other.m_it;
-        return *this;
-    }
-
-  private:
-    /*!
-    @brief set the iterator to the first value
-    @pre The iterator is initialized; i.e. `m_object != nullptr`.
-    */
-    void set_begin() noexcept
-    {
-        assert(m_object != nullptr);
-
-        switch (m_object->m_type)
-        {
-            case value_t::object:
-            {
-                m_it.object_iterator = m_object->m_value.object->begin();
-                break;
-            }
-
-            case value_t::array:
-            {
-                m_it.array_iterator = m_object->m_value.array->begin();
-                break;
-            }
-
-            case value_t::null:
-            {
-                // set to end so begin()==end() is true: null is empty
-                m_it.primitive_iterator.set_end();
-                break;
-            }
-
-            default:
-            {
-                m_it.primitive_iterator.set_begin();
-                break;
-            }
-        }
-    }
-
-    /*!
-    @brief set the iterator past the last value
-    @pre The iterator is initialized; i.e. `m_object != nullptr`.
-    */
-    void set_end() noexcept
-    {
-        assert(m_object != nullptr);
-
-        switch (m_object->m_type)
-        {
-            case value_t::object:
-            {
-                m_it.object_iterator = m_object->m_value.object->end();
-                break;
-            }
-
-            case value_t::array:
-            {
-                m_it.array_iterator = m_object->m_value.array->end();
-                break;
-            }
-
-            default:
-            {
-                m_it.primitive_iterator.set_end();
-                break;
-            }
-        }
-    }
-
-  public:
-    /*!
-    @brief return a reference to the value pointed to by the iterator
-    @pre The iterator is initialized; i.e. `m_object != nullptr`.
-    */
-    reference operator*() const
-    {
-        assert(m_object != nullptr);
-
-        switch (m_object->m_type)
-        {
-            case value_t::object:
-            {
-                assert(m_it.object_iterator != m_object->m_value.object->end());
-                return m_it.object_iterator->second;
-            }
-
-            case value_t::array:
-            {
-                assert(m_it.array_iterator != m_object->m_value.array->end());
-                return *m_it.array_iterator;
-            }
-
-            case value_t::null:
-                JSON_THROW(invalid_iterator::create(214, "cannot get value"));
-
-            default:
-            {
-                if (JSON_LIKELY(m_it.primitive_iterator.is_begin()))
-                {
-                    return *m_object;
-                }
-
-                JSON_THROW(invalid_iterator::create(214, "cannot get value"));
-            }
-        }
-    }
-
-    /*!
-    @brief dereference the iterator
-    @pre The iterator is initialized; i.e. `m_object != nullptr`.
-    */
-    pointer operator->() const
-    {
-        assert(m_object != nullptr);
-
-        switch (m_object->m_type)
-        {
-            case value_t::object:
-            {
-                assert(m_it.object_iterator != m_object->m_value.object->end());
-                return &(m_it.object_iterator->second);
-            }
-
-            case value_t::array:
-            {
-                assert(m_it.array_iterator != m_object->m_value.array->end());
-                return &*m_it.array_iterator;
-            }
-
-            default:
-            {
-                if (JSON_LIKELY(m_it.primitive_iterator.is_begin()))
-                {
-                    return m_object;
-                }
-
-                JSON_THROW(invalid_iterator::create(214, "cannot get value"));
-            }
-        }
-    }
-
-    /*!
-    @brief post-increment (it++)
-    @pre The iterator is initialized; i.e. `m_object != nullptr`.
-    */
-    iter_impl const operator++(int)
-    {
-        auto result = *this;
-        ++(*this);
-        return result;
-    }
-
-    /*!
-    @brief pre-increment (++it)
-    @pre The iterator is initialized; i.e. `m_object != nullptr`.
-    */
-    iter_impl& operator++()
-    {
-        assert(m_object != nullptr);
-
-        switch (m_object->m_type)
-        {
-            case value_t::object:
-            {
-                ++m_it.object_iterator;
-                break;
-            }
-
-            case value_t::array:
-            {
-                std::advance(m_it.array_iterator, 1);
-                break;
-            }
-
-            default:
-            {
-                ++m_it.primitive_iterator;
-                break;
-            }
-        }
-
-        return *this;
-    }
-
-    /*!
-    @brief post-decrement (it--)
-    @pre The iterator is initialized; i.e. `m_object != nullptr`.
-    */
-    iter_impl const operator--(int)
-    {
-        auto result = *this;
-        --(*this);
-        return result;
-    }
-
-    /*!
-    @brief pre-decrement (--it)
-    @pre The iterator is initialized; i.e. `m_object != nullptr`.
-    */
-    iter_impl& operator--()
-    {
-        assert(m_object != nullptr);
-
-        switch (m_object->m_type)
-        {
-            case value_t::object:
-            {
-                --m_it.object_iterator;
-                break;
-            }
-
-            case value_t::array:
-            {
-                std::advance(m_it.array_iterator, -1);
-                break;
-            }
-
-            default:
-            {
-                --m_it.primitive_iterator;
-                break;
-            }
-        }
-
-        return *this;
-    }
-
-    /*!
-    @brief  comparison: equal
-    @pre The iterator is initialized; i.e. `m_object != nullptr`.
-    */
-    bool operator==(const iter_impl& other) const
-    {
-        // if objects are not the same, the comparison is undefined
-        if (JSON_UNLIKELY(m_object != other.m_object))
-        {
-            JSON_THROW(invalid_iterator::create(212, "cannot compare iterators of different containers"));
-        }
-
-        assert(m_object != nullptr);
-
-        switch (m_object->m_type)
-        {
-            case value_t::object:
-                return (m_it.object_iterator == other.m_it.object_iterator);
-
-            case value_t::array:
-                return (m_it.array_iterator == other.m_it.array_iterator);
-
-            default:
-                return (m_it.primitive_iterator == other.m_it.primitive_iterator);
-        }
-    }
-
-    /*!
-    @brief  comparison: not equal
-    @pre The iterator is initialized; i.e. `m_object != nullptr`.
-    */
-    bool operator!=(const iter_impl& other) const
-    {
-        return not operator==(other);
-    }
-
-    /*!
-    @brief  comparison: smaller
-    @pre The iterator is initialized; i.e. `m_object != nullptr`.
-    */
-    bool operator<(const iter_impl& other) const
-    {
-        // if objects are not the same, the comparison is undefined
-        if (JSON_UNLIKELY(m_object != other.m_object))
-        {
-            JSON_THROW(invalid_iterator::create(212, "cannot compare iterators of different containers"));
-        }
-
-        assert(m_object != nullptr);
-
-        switch (m_object->m_type)
-        {
-            case value_t::object:
-                JSON_THROW(invalid_iterator::create(213, "cannot compare order of object iterators"));
-
-            case value_t::array:
-                return (m_it.array_iterator < other.m_it.array_iterator);
-
-            default:
-                return (m_it.primitive_iterator < other.m_it.primitive_iterator);
-        }
-    }
-
-    /*!
-    @brief  comparison: less than or equal
-    @pre The iterator is initialized; i.e. `m_object != nullptr`.
-    */
-    bool operator<=(const iter_impl& other) const
-    {
-        return not other.operator < (*this);
-    }
-
-    /*!
-    @brief  comparison: greater than
-    @pre The iterator is initialized; i.e. `m_object != nullptr`.
-    */
-    bool operator>(const iter_impl& other) const
-    {
-        return not operator<=(other);
-    }
-
-    /*!
-    @brief  comparison: greater than or equal
-    @pre The iterator is initialized; i.e. `m_object != nullptr`.
-    */
-    bool operator>=(const iter_impl& other) const
-    {
-        return not operator<(other);
-    }
-
-    /*!
-    @brief  add to iterator
-    @pre The iterator is initialized; i.e. `m_object != nullptr`.
-    */
-    iter_impl& operator+=(difference_type i)
-    {
-        assert(m_object != nullptr);
-
-        switch (m_object->m_type)
-        {
-            case value_t::object:
-                JSON_THROW(invalid_iterator::create(209, "cannot use offsets with object iterators"));
-
-            case value_t::array:
-            {
-                std::advance(m_it.array_iterator, i);
-                break;
-            }
-
-            default:
-            {
-                m_it.primitive_iterator += i;
-                break;
-            }
-        }
-
-        return *this;
-    }
-
-    /*!
-    @brief  subtract from iterator
-    @pre The iterator is initialized; i.e. `m_object != nullptr`.
-    */
-    iter_impl& operator-=(difference_type i)
-    {
-        return operator+=(-i);
-    }
-
-    /*!
-    @brief  add to iterator
-    @pre The iterator is initialized; i.e. `m_object != nullptr`.
-    */
-    iter_impl operator+(difference_type i) const
-    {
-        auto result = *this;
-        result += i;
-        return result;
-    }
-
-    /*!
-    @brief  addition of distance and iterator
-    @pre The iterator is initialized; i.e. `m_object != nullptr`.
-    */
-    friend iter_impl operator+(difference_type i, const iter_impl& it)
-    {
-        auto result = it;
-        result += i;
-        return result;
-    }
-
-    /*!
-    @brief  subtract from iterator
-    @pre The iterator is initialized; i.e. `m_object != nullptr`.
-    */
-    iter_impl operator-(difference_type i) const
-    {
-        auto result = *this;
-        result -= i;
-        return result;
-    }
-
-    /*!
-    @brief  return difference
-    @pre The iterator is initialized; i.e. `m_object != nullptr`.
-    */
-    difference_type operator-(const iter_impl& other) const
-    {
-        assert(m_object != nullptr);
-
-        switch (m_object->m_type)
-        {
-            case value_t::object:
-                JSON_THROW(invalid_iterator::create(209, "cannot use offsets with object iterators"));
-
-            case value_t::array:
-                return m_it.array_iterator - other.m_it.array_iterator;
-
-            default:
-                return m_it.primitive_iterator - other.m_it.primitive_iterator;
-        }
-    }
-
-    /*!
-    @brief  access to successor
-    @pre The iterator is initialized; i.e. `m_object != nullptr`.
-    */
-    reference operator[](difference_type n) const
-    {
-        assert(m_object != nullptr);
-
-        switch (m_object->m_type)
-        {
-            case value_t::object:
-                JSON_THROW(invalid_iterator::create(208, "cannot use operator[] for object iterators"));
-
-            case value_t::array:
-                return *std::next(m_it.array_iterator, n);
-
-            case value_t::null:
-                JSON_THROW(invalid_iterator::create(214, "cannot get value"));
-
-            default:
-            {
-                if (JSON_LIKELY(m_it.primitive_iterator.get_value() == -n))
-                {
-                    return *m_object;
-                }
-
-                JSON_THROW(invalid_iterator::create(214, "cannot get value"));
-            }
-        }
-    }
-
-    /*!
-    @brief  return the key of an object iterator
-    @pre The iterator is initialized; i.e. `m_object != nullptr`.
-    */
-    std::string_view key() const
-    {
-        assert(m_object != nullptr);
-
-        if (JSON_LIKELY(m_object->is_object()))
-        {
-            return m_it.object_iterator->first();
-        }
-
-        JSON_THROW(invalid_iterator::create(207, "cannot use key() for non-object iterators"));
-    }
-
-    /*!
-    @brief  return the value of an iterator
-    @pre The iterator is initialized; i.e. `m_object != nullptr`.
-    */
-    reference value() const
-    {
-        return operator*();
-    }
-
-  private:
-    /// associated JSON instance
-    pointer m_object = nullptr;
-    /// the actual iterator of the associated instance
-    internal_iterator<typename std::remove_const<BasicJsonType>::type> m_it;
-};
-
-/// proxy class for the items() function
-template<typename IteratorType> class iteration_proxy
-{
-  private:
-    /// helper class for iteration
-    class iteration_proxy_internal
-    {
-      private:
-        /// the iterator
-        IteratorType anchor;
-        /// an index for arrays (used to create key names)
-        std::size_t array_index = 0;
-
-      public:
-        explicit iteration_proxy_internal(IteratorType it) noexcept : anchor(it) {}
-
-        /// dereference operator (needed for range-based for)
-        iteration_proxy_internal& operator*()
-        {
-            return *this;
-        }
-
-        /// increment operator (needed for range-based for)
-        iteration_proxy_internal& operator++()
-        {
-            ++anchor;
-            ++array_index;
-
-            return *this;
-        }
-
-        /// inequality operator (needed for range-based for)
-        bool operator!=(const iteration_proxy_internal& o) const noexcept
-        {
-            return anchor != o.anchor;
-        }
-
-        /// return key of the iterator
-        std::string key() const
-        {
-            assert(anchor.m_object != nullptr);
-
-            switch (anchor.m_object->type())
-            {
-                // use integer array index as key
-                case value_t::array:
-                    return std::to_string(array_index);
-
-                // use key from the object
-                case value_t::object:
-                    return std::string{anchor.key()};
-
-                // use an empty key for all primitive types
-                default:
-                    return "";
-            }
-        }
-
-        /// return value of the iterator
-        typename IteratorType::reference value() const
-        {
-            return anchor.value();
-        }
-    };
-
-    /// the container to iterate
-    typename IteratorType::reference container;
-
-  public:
-    /// construct iteration proxy from a container
-    explicit iteration_proxy(typename IteratorType::reference cont) noexcept
-        : container(cont) {}
-
-    /// return iterator begin (needed for range-based for)
-    iteration_proxy_internal begin() noexcept
-    {
-        return iteration_proxy_internal(container.begin());
-    }
-
-    /// return iterator end (needed for range-based for)
-    iteration_proxy_internal end() noexcept
-    {
-        return iteration_proxy_internal(container.end());
-    }
-};
-
-//////////////////////
-// reverse_iterator //
-//////////////////////
-
-/*!
-@brief a template for a reverse iterator class
-
-@tparam Base the base iterator type to reverse. Valid types are @ref
-iterator (to create @ref reverse_iterator) and @ref const_iterator (to
-create @ref const_reverse_iterator).
-
-@requirement The class satisfies the following concept requirements:
--
-[BidirectionalIterator](http://en.cppreference.com/w/cpp/concept/BidirectionalIterator):
-  The iterator that can be moved can be moved in both directions (i.e.
-  incremented and decremented).
-- [OutputIterator](http://en.cppreference.com/w/cpp/concept/OutputIterator):
-  It is possible to write to the pointed-to element (only if @a Base is
-  @ref iterator).
-
-@since version 1.0.0
-*/
-template<typename Base>
-class json_reverse_iterator : public std::reverse_iterator<Base>
-{
-  public:
-    using difference_type = std::ptrdiff_t;
-    /// shortcut to the reverse iterator adapter
-    using base_iterator = std::reverse_iterator<Base>;
-    /// the reference type for the pointed-to element
-    using reference = typename Base::reference;
-
-    /// create reverse iterator from iterator
-    json_reverse_iterator(const typename base_iterator::iterator_type& it) noexcept
-        : base_iterator(it) {}
-
-    /// create reverse iterator from base class
-    json_reverse_iterator(const base_iterator& it) noexcept : base_iterator(it) {}
-
-    /// post-increment (it++)
-    json_reverse_iterator const operator++(int)
-    {
-        return static_cast<json_reverse_iterator>(base_iterator::operator++(1));
-    }
-
-    /// pre-increment (++it)
-    json_reverse_iterator& operator++()
-    {
-        return static_cast<json_reverse_iterator&>(base_iterator::operator++());
-    }
-
-    /// post-decrement (it--)
-    json_reverse_iterator const operator--(int)
-    {
-        return static_cast<json_reverse_iterator>(base_iterator::operator--(1));
-    }
-
-    /// pre-decrement (--it)
-    json_reverse_iterator& operator--()
-    {
-        return static_cast<json_reverse_iterator&>(base_iterator::operator--());
-    }
-
-    /// add to iterator
-    json_reverse_iterator& operator+=(difference_type i)
-    {
-        return static_cast<json_reverse_iterator&>(base_iterator::operator+=(i));
-    }
-
-    /// add to iterator
-    json_reverse_iterator operator+(difference_type i) const
-    {
-        return static_cast<json_reverse_iterator>(base_iterator::operator+(i));
-    }
-
-    /// subtract from iterator
-    json_reverse_iterator operator-(difference_type i) const
-    {
-        return static_cast<json_reverse_iterator>(base_iterator::operator-(i));
-    }
-
-    /// return difference
-    difference_type operator-(const json_reverse_iterator& other) const
-    {
-        return base_iterator(*this) - base_iterator(other);
-    }
-
-    /// access to successor
-    reference operator[](difference_type n) const
-    {
-        return *(this->operator+(n));
-    }
-
-    /// return the key of an object iterator
-    auto key() const -> decltype(std::declval<Base>().key())
-    {
-        auto it = --this->base();
-        return it.key();
-    }
-
-    /// return the value of an iterator
-    reference value() const
-    {
-        auto it = --this->base();
-        return it.operator * ();
-    }
-};
-
-template<typename BasicJsonType>
-class json_ref
-{
-  public:
-    using value_type = BasicJsonType;
-
-    json_ref(value_type&& value)
-        : owned_value(std::move(value)), value_ref(&owned_value), is_rvalue(true)
-    {}
-
-    json_ref(const value_type& value)
-        : value_ref(const_cast<value_type*>(&value)), is_rvalue(false)
-    {}
-
-    json_ref(std::initializer_list<json_ref> init)
-        : owned_value(init), value_ref(&owned_value), is_rvalue(true)
-    {}
-
-    template<class... Args>
-    json_ref(Args&& ... args)
-        : owned_value(std::forward<Args>(args)...), value_ref(&owned_value), is_rvalue(true)
-    {}
-
-    // class should be movable only
-    json_ref(json_ref&&) = default;
-    json_ref(const json_ref&) = delete;
-    json_ref& operator=(const json_ref&) = delete;
-
-    value_type moved_or_copied() const
-    {
-        if (is_rvalue)
-        {
-            return std::move(*value_ref);
-        }
-        return *value_ref;
-    }
-
-    value_type const& operator*() const
-    {
-        return *static_cast<value_type const*>(value_ref);
-    }
-
-    value_type const* operator->() const
-    {
-        return static_cast<value_type const*>(value_ref);
-    }
-
-  private:
-    mutable value_type owned_value = nullptr;
-    value_type* value_ref = nullptr;
-    const bool is_rvalue;
-};
-}  // namespace detail
-
-class json_pointer
-{
-    // allow json to access private members
-    friend class json;
-    friend class JsonTest;
-
-  public:
-    /*!
-    @brief create JSON pointer
-
-    Create a JSON pointer according to the syntax described in
-    [Section 3 of RFC6901](https://tools.ietf.org/html/rfc6901#section-3).
-
-    @param[in] s  string representing the JSON pointer; if omitted, the empty
-                  string is assumed which references the whole JSON value
-
-    @throw parse_error.107 if the given JSON pointer @a s is nonempty and does
-                           not begin with a slash (`/`); see example below
-
-    @throw parse_error.108 if a tilde (`~`) in the given JSON pointer @a s is
-    not followed by `0` (representing `~`) or `1` (representing `/`); see
-    example below
-
-    @liveexample{The example shows the construction several valid JSON pointers
-    as well as the exceptional behavior.,json_pointer}
-
-    @since version 2.0.0
-    */
-    explicit json_pointer(std::string_view s = {})
-        : reference_tokens(split(s))
-    {}
-
-    /*!
-    @brief return a string representation of the JSON pointer
-
-    @invariant For each JSON pointer `ptr`, it holds:
-    @code {.cpp}
-    ptr == json_pointer(ptr.to_string());
-    @endcode
-
-    @return a string representation of the JSON pointer
-
-    @liveexample{The example shows the result of `to_string`.,
-    json_pointer__to_string}
-
-    @since version 2.0.0
-    */
-    std::string to_string() const noexcept;
-
-    /// @copydoc to_string()
-    operator std::string() const
-    {
-        return to_string();
-    }
-
-    /*!
-    @param[in] s  reference token to be converted into an array index
-
-    @return integer representation of @a s
-
-    @throw out_of_range.404 if string @a s could not be converted to an integer
-    */
-    static int array_index(std::string_view s);
-
-  private:
-    /*!
-    @brief remove and return last reference pointer
-    @throw out_of_range.405 if JSON pointer has no parent
-    */
-    std::string pop_back()
-    {
-        if (JSON_UNLIKELY(is_root()))
-        {
-            JSON_THROW(detail::out_of_range::create(405, "JSON pointer has no parent"));
-        }
-
-        auto last = reference_tokens.back();
-        reference_tokens.pop_back();
-        return last;
-    }
-
-    /// return whether pointer points to the root document
-    bool is_root() const
-    {
-        return reference_tokens.empty();
-    }
-
-    json_pointer top() const
-    {
-        if (JSON_UNLIKELY(is_root()))
-        {
-            JSON_THROW(detail::out_of_range::create(405, "JSON pointer has no parent"));
-        }
-
-        json_pointer result = *this;
-        result.reference_tokens = {reference_tokens[0]};
-        return result;
-    }
-
-    /*!
-    @brief create and return a reference to the pointed to value
-
-    @complexity Linear in the number of reference tokens.
-
-    @throw parse_error.109 if array index is not a number
-    @throw type_error.313 if value cannot be unflattened
-    */
-    json& get_and_create(json& j) const;
-
-    /*!
-    @brief return a reference to the pointed to value
-
-    @note This version does not throw if a value is not present, but tries to
-          create nested values instead. For instance, calling this function
-          with pointer `"/this/that"` on a null value is equivalent to calling
-          `operator[]("this").operator[]("that")` on that value, effectively
-          changing the null value to an object.
-
-    @param[in] ptr  a JSON value
-
-    @return reference to the JSON value pointed to by the JSON pointer
-
-    @complexity Linear in the length of the JSON pointer.
-
-    @throw parse_error.106   if an array index begins with '0'
-    @throw parse_error.109   if an array index was not a number
-    @throw out_of_range.404  if the JSON pointer can not be resolved
-    */
-    json& get_unchecked(json* ptr) const;
-
-    /*!
-    @throw parse_error.106   if an array index begins with '0'
-    @throw parse_error.109   if an array index was not a number
-    @throw out_of_range.402  if the array index '-' is used
-    @throw out_of_range.404  if the JSON pointer can not be resolved
-    */
-    json& get_checked(json* ptr) const;
-
-    /*!
-    @brief return a const reference to the pointed to value
-
-    @param[in] ptr  a JSON value
-
-    @return const reference to the JSON value pointed to by the JSON
-    pointer
-
-    @throw parse_error.106   if an array index begins with '0'
-    @throw parse_error.109   if an array index was not a number
-    @throw out_of_range.402  if the array index '-' is used
-    @throw out_of_range.404  if the JSON pointer can not be resolved
-    */
-    const json& get_unchecked(const json* ptr) const;
-
-    /*!
-    @throw parse_error.106   if an array index begins with '0'
-    @throw parse_error.109   if an array index was not a number
-    @throw out_of_range.402  if the array index '-' is used
-    @throw out_of_range.404  if the JSON pointer can not be resolved
-    */
-    const json& get_checked(const json* ptr) const;
-
-    /*!
-    @brief split the string input to reference tokens
-
-    @note This function is only called by the json_pointer constructor.
-          All exceptions below are documented there.
-
-    @throw parse_error.107  if the pointer is not empty or begins with '/'
-    @throw parse_error.108  if character '~' is not followed by '0' or '1'
-    */
-    static std::vector<std::string> split(std::string_view reference_string);
-
-    /*!
-    @brief replace all occurrences of a substring by another string
-
-    @param[in,out] s  the string to manipulate; changed so that all
-                   occurrences of @a f are replaced with @a t
-    @param[in]     f  the substring to replace with @a t
-    @param[in]     t  the string to replace @a f
-
-    @pre The search string @a f must not be empty. **This precondition is
-    enforced with an assertion.**
-
-    @since version 2.0.0
-    */
-    static void replace_substring(std::string& s, const std::string& f,
-                                  const std::string& t);
-
-    /// escape "~"" to "~0" and "/" to "~1"
-    static std::string escape(std::string s);
-
-    /// unescape "~1" to tilde and "~0" to slash (order is important!)
-    static void unescape(std::string& s);
-
-    /*!
-    @param[in] reference_string  the reference string to the current value
-    @param[in] value             the value to consider
-    @param[in,out] result        the result object to insert values to
-
-    @note Empty objects or arrays are flattened to `null`.
-    */
-    static void flatten(std::string_view reference_string,
-                        const json& value,
-                        json& result);
-
-    /*!
-    @param[in] value  flattened JSON
-
-    @return unflattened JSON
-
-    @throw parse_error.109 if array index is not a number
-    @throw type_error.314  if value is not an object
-    @throw type_error.315  if object values are not primitive
-    @throw type_error.313  if value cannot be unflattened
-    */
-    static json
-    unflatten(const json& value);
-
-    friend bool operator==(json_pointer const& lhs,
-                           json_pointer const& rhs) noexcept
-    {
-        return (lhs.reference_tokens == rhs.reference_tokens);
-    }
-
-    friend bool operator!=(json_pointer const& lhs,
-                           json_pointer const& rhs) noexcept
-    {
-        return not (lhs == rhs);
-    }
-
-    /// the reference tokens
-    std::vector<std::string> reference_tokens;
-};
-
-template<typename, typename>
-struct adl_serializer
-{
-    /*!
-    @brief convert a JSON value to any value type
-
-    This function is usually called by the `get()` function of the
-    @ref json class (either explicit or via conversion operators).
-
-    @param[in] j         JSON value to read from
-    @param[in,out] val  value to write to
-    */
-    template<typename BasicJsonType, typename ValueType>
-    static void from_json(BasicJsonType&& j, ValueType& val) noexcept(
-        noexcept(::wpi::from_json(std::forward<BasicJsonType>(j), val)))
-    {
-        ::wpi::from_json(std::forward<BasicJsonType>(j), val);
-    }
-
-    /*!
-    @brief convert any value type to a JSON value
-
-    This function is usually called by the constructors of the @ref json
-    class.
-
-    @param[in,out] j  JSON value to write to
-    @param[in] val     value to read from
-    */
-    template<typename BasicJsonType, typename ValueType>
-    static void to_json(BasicJsonType& j, ValueType&& val) noexcept(
-        noexcept(::wpi::to_json(j, std::forward<ValueType>(val))))
-    {
-        ::wpi::to_json(j, std::forward<ValueType>(val));
-    }
-};
-
-/*!
-@brief a class to store JSON values
-
-@requirement The class satisfies the following concept requirements:
-- Basic
- - [DefaultConstructible](http://en.cppreference.com/w/cpp/concept/DefaultConstructible):
-   JSON values can be default constructed. The result will be a JSON null
-   value.
- - [MoveConstructible](http://en.cppreference.com/w/cpp/concept/MoveConstructible):
-   A JSON value can be constructed from an rvalue argument.
- - [CopyConstructible](http://en.cppreference.com/w/cpp/concept/CopyConstructible):
-   A JSON value can be copy-constructed from an lvalue expression.
- - [MoveAssignable](http://en.cppreference.com/w/cpp/concept/MoveAssignable):
-   A JSON value van be assigned from an rvalue argument.
- - [CopyAssignable](http://en.cppreference.com/w/cpp/concept/CopyAssignable):
-   A JSON value can be copy-assigned from an lvalue expression.
- - [Destructible](http://en.cppreference.com/w/cpp/concept/Destructible):
-   JSON values can be destructed.
-- Layout
- - [StandardLayoutType](http://en.cppreference.com/w/cpp/concept/StandardLayoutType):
-   JSON values have
-   [standard layout](http://en.cppreference.com/w/cpp/language/data_members#Standard_layout):
-   All non-static data members are private and standard layout types, the
-   class has no virtual functions or (virtual) base classes.
-- Library-wide
- - [EqualityComparable](http://en.cppreference.com/w/cpp/concept/EqualityComparable):
-   JSON values can be compared with `==`, see @ref
-   operator==(const_reference,const_reference).
- - [LessThanComparable](http://en.cppreference.com/w/cpp/concept/LessThanComparable):
-   JSON values can be compared with `<`, see @ref
-   operator<(const_reference,const_reference).
- - [Swappable](http://en.cppreference.com/w/cpp/concept/Swappable):
-   Any JSON lvalue or rvalue of can be swapped with any lvalue or rvalue of
-   other compatible types, using unqualified function call @ref swap().
- - [NullablePointer](http://en.cppreference.com/w/cpp/concept/NullablePointer):
-   JSON values can be compared against `std::nullptr_t` objects which are used
-   to model the `null` value.
-- Container
- - [Container](http://en.cppreference.com/w/cpp/concept/Container):
-   JSON values can be used like STL containers and provide iterator access.
- - [ReversibleContainer](http://en.cppreference.com/w/cpp/concept/ReversibleContainer);
-   JSON values can be used like STL containers and provide reverse iterator
-   access.
-
-@invariant The member variables @a m_value and @a m_type have the following
-relationship:
-- If `m_type == value_t::object`, then `m_value.object != nullptr`.
-- If `m_type == value_t::array`, then `m_value.array != nullptr`.
-- If `m_type == value_t::string`, then `m_value.string != nullptr`.
-The invariants are checked by member function assert_invariant().
-
-@internal
-@note ObjectType trick from http://stackoverflow.com/a/9860911
-@endinternal
-
-@see [RFC 7159: The JavaScript Object Notation (JSON) Data Interchange
-Format](http://rfc7159.net/rfc7159)
-
-@since version 1.0.0
-
-@nosubgrouping
-*/
-class json
-{
-  private:
-    template<detail::value_t> friend struct detail::external_constructor;
-    friend ::wpi::json_pointer;
-    template<typename BasicJsonType>
-    friend class ::wpi::detail::iter_impl;
-    friend class JsonTest;
-
-    /// workaround type for MSVC
-    using json_t = json;
-
-    // convenience aliases for types residing in namespace detail;
-    using primitive_iterator_t = ::wpi::detail::primitive_iterator_t;
-    template<typename BasicJsonType>
-    using internal_iterator = ::wpi::detail::internal_iterator<BasicJsonType>;
-    template<typename BasicJsonType>
-    using iter_impl = ::wpi::detail::iter_impl<BasicJsonType>;
-    template<typename Iterator>
-    using iteration_proxy = ::wpi::detail::iteration_proxy<Iterator>;
-    template<typename Base> using json_reverse_iterator = ::wpi::detail::json_reverse_iterator<Base>;
-
-    class binary_reader;
-    class binary_writer;
-    class lexer;
-    class parser;
-
-  public:
-    class serializer;
-
-    using value_t = detail::value_t;
-    /// @copydoc wpi::json_pointer
-    using json_pointer = ::wpi::json_pointer;
-    template<typename T, typename SFINAE>
-    using json_serializer = adl_serializer<T, SFINAE>;
-    /// helper type for initializer lists of json values
-    using initializer_list_t = std::initializer_list<detail::json_ref<json>>;
-
-    ////////////////
-    // exceptions //
-    ////////////////
-
-    /// @name exceptions
-    /// Classes to implement user-defined exceptions.
-    /// @{
-
-    /// @copydoc detail::exception
-    using exception = detail::exception;
-    /// @copydoc detail::parse_error
-    using parse_error = detail::parse_error;
-    /// @copydoc detail::invalid_iterator
-    using invalid_iterator = detail::invalid_iterator;
-    /// @copydoc detail::type_error
-    using type_error = detail::type_error;
-    /// @copydoc detail::out_of_range
-    using out_of_range = detail::out_of_range;
-    /// @copydoc detail::other_error
-    using other_error = detail::other_error;
-
-    /// @}
-
-
-    /////////////////////
-    // container types //
-    /////////////////////
-
-    /// @name container types
-    /// The canonic container types to use @ref json like any other STL
-    /// container.
-    /// @{
-
-    /// the type of elements in a json container
-    using value_type = json;
-
-    /// the type of an element reference
-    using reference = value_type&;
-    /// the type of an element const reference
-    using const_reference = const value_type&;
-
-    /// a type to represent differences between iterators
-    using difference_type = std::ptrdiff_t;
-    /// a type to represent container sizes
-    using size_type = std::size_t;
-
-    /// the allocator type
-    using allocator_type = std::allocator<json>;
-
-    /// the type of an element pointer
-    using pointer = json*;
-    /// the type of an element const pointer
-    using const_pointer = const json*;
-
-    /// an iterator for a json container
-    using iterator = iter_impl<json>;
-    /// a const iterator for a json container
-    using const_iterator = iter_impl<const json>;
-    /// a reverse iterator for a json container
-    using reverse_iterator = json_reverse_iterator<typename json::iterator>;
-    /// a const reverse iterator for a json container
-    using const_reverse_iterator = json_reverse_iterator<typename json::const_iterator>;
-
-    /// @}
-
-
-    /*!
-    @brief returns the allocator associated with the container
-    */
-    static allocator_type get_allocator()
-    {
-        return allocator_type();
-    }
-
-    /*!
-    @brief returns version information on the library
-
-    This function returns a JSON object with information about the library,
-    including the version number and information on the platform and compiler.
-
-    @return JSON object holding version information
-    key         | description
-    ----------- | ---------------
-    `compiler`  | Information on the used compiler. It is an object with the following keys: `c++` (the used C++ standard), `family` (the compiler family; possible values are `clang`, `icc`, `gcc`, `ilecpp`, `msvc`, `pgcpp`, `sunpro`, and `unknown`), and `version` (the compiler version).
-    `copyright` | The copyright line for the library as string.
-    `name`      | The name of the library as string.
-    `platform`  | The used platform as string. Possible values are `win32`, `linux`, `apple`, `unix`, and `unknown`.
-    `url`       | The URL of the project as string.
-    `version`   | The version of the library. It is an object with the following keys: `major`, `minor`, and `patch` as defined by [Semantic Versioning](http://semver.org), and `string` (the version string).
-
-    @liveexample{The following code shows an example output of the `meta()`
-    function.,meta}
-
-    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
-    changes to any JSON value.
-
-    @complexity Constant.
-
-    @since 2.1.0
-    */
-    static json meta();
-
-
-    ///////////////////////////
-    // JSON value data types //
-    ///////////////////////////
-
-    /// @name JSON value data types
-    /// The data types to store a JSON value. These types are derived from
-    /// the template arguments passed to class @ref json.
-    /// @{
-
-    // Use transparent comparator if possible, combined with perfect forwarding
-    // on find() and count() calls prevents unnecessary string construction.
-    using object_comparator_t = std::less<>;
-
-    /*!
-    @brief a type for an object
-
-    [RFC 7159](http://rfc7159.net/rfc7159) describes JSON objects as follows:
-    > An object is an unordered collection of zero or more name/value pairs,
-    > where a name is a string and a value is a string, number, boolean, null,
-    > object, or array.
-
-    #### Behavior
-
-    The choice of @a object_t influences the behavior of the JSON class. With
-    the default type, objects have the following behavior:
-
-    - When all names are unique, objects will be interoperable in the sense
-      that all software implementations receiving that object will agree on
-      the name-value mappings.
-    - When the names within an object are not unique, it is unspecified which
-      one of the values for a given key will be chosen. For instance,
-      `{"key": 2, "key": 1}` could be equal to either `{"key": 1}` or
-      `{"key": 2}`.
-    - Internally, name/value pairs are stored in lexicographical order of the
-      names. Objects will also be serialized (see @ref dump) in this order.
-      For instance, `{"b": 1, "a": 2}` and `{"a": 2, "b": 1}` will be stored
-      and serialized as `{"a": 2, "b": 1}`.
-    - When comparing objects, the order of the name/value pairs is irrelevant.
-      This makes objects interoperable in the sense that they will not be
-      affected by these differences. For instance, `{"b": 1, "a": 2}` and
-      `{"a": 2, "b": 1}` will be treated as equal.
-
-    #### Limits
-
-    [RFC 7159](http://rfc7159.net/rfc7159) specifies:
-    > An implementation may set limits on the maximum depth of nesting.
-
-    In this class, the object's limit of nesting is not explicitly constrained.
-    However, a maximum depth of nesting may be introduced by the compiler or
-    runtime environment. A theoretical limit can be queried by calling the
-    @ref max_size function of a JSON object.
-
-    #### Storage
-
-    Objects are stored as pointers in a @ref json type. That is, for any
-    access to object values, a pointer of type `object_t*` must be
-    dereferenced.
-
-    @since version 1.0.0
-
-    @note The order name/value pairs are added to the object is *not*
-    preserved by the library. Therefore, iterating an object may return
-    name/value pairs in a different order than they were originally stored. In
-    fact, keys will be traversed in alphabetical order as `std::map` with
-    `std::less` is used by default. Please note this behavior conforms to [RFC
-    7159](http://rfc7159.net/rfc7159), because any order implements the
-    specified "unordered" nature of JSON objects.
-    */
-    using object_t = StringMap<json>;
-
-    /*!
-    @brief a type for an array
-
-    [RFC 7159](http://rfc7159.net/rfc7159) describes JSON arrays as follows:
-    > An array is an ordered sequence of zero or more values.
-
-    #### Limits
-
-    [RFC 7159](http://rfc7159.net/rfc7159) specifies:
-    > An implementation may set limits on the maximum depth of nesting.
-
-    In this class, the array's limit of nesting is not explicitly constrained.
-    However, a maximum depth of nesting may be introduced by the compiler or
-    runtime environment. A theoretical limit can be queried by calling the
-    @ref max_size function of a JSON array.
-
-    #### Storage
-
-    Arrays are stored as pointers in a @ref json type. That is, for any
-    access to array values, a pointer of type `array_t*` must be dereferenced.
-
-    @sa @ref object_t -- type for an object value
-
-    @since version 1.0.0
-    */
-    using array_t = std::vector<json>;
-
-    /// @}
-
-  private:
-
-    /// helper for exception-safe object creation
-    template<typename T, typename... Args>
-    static T* create(Args&& ... args)
-    {
-        std::allocator<T> alloc;
-
-		using AllocatorTraits = std::allocator_traits<std::allocator<T>>;
-
-		auto deleter = [&](T * object)
-		{
-			AllocatorTraits::deallocate(alloc, object, 1);
-		};
-		std::unique_ptr<T, decltype(deleter)> object(AllocatorTraits::allocate(alloc, 1), deleter);
-		AllocatorTraits::construct(alloc, object.get(), std::forward<Args>(args)...);
-        assert(object != nullptr);
-        return object.release();
-    }
-
-    ////////////////////////
-    // JSON value storage //
-    ////////////////////////
-
-    /*!
-    @brief a JSON value
-
-    The actual storage for a JSON value of the @ref json class. This
-    union combines the different storage types for the JSON value types
-    defined in @ref value_t.
-
-    JSON type | value_t type    | used type
-    --------- | --------------- | ------------------------
-    object    | object          | pointer to @ref object_t
-    array     | array           | pointer to @ref array_t
-    string    | string          | pointer to std::string
-    boolean   | boolean         | bool
-    number    | number_integer  | int64_t
-    number    | number_unsigned | uint64_t
-    number    | number_float    | double
-    null      | null            | *no value is stored*
-
-    @note Variable-length types (objects, arrays, and strings) are stored as
-    pointers. The size of the union should not exceed 64 bits if the default
-    value types are used.
-
-    @since version 1.0.0
-    */
-    union json_value
-    {
-        /// object (stored with pointer to save storage)
-        object_t* object;
-        /// array (stored with pointer to save storage)
-        array_t* array;
-        /// string (stored with pointer to save storage)
-        std::string* string;
-        /// boolean
-        bool boolean;
-        /// number (integer)
-        int64_t number_integer;
-        /// number (unsigned integer)
-        uint64_t number_unsigned;
-        /// number (floating-point)
-        double number_float;
-
-        /// default constructor (for null values)
-        json_value() = default;
-        /// constructor for booleans
-        json_value(bool v) noexcept : boolean(v) {}
-        /// constructor for numbers (integer)
-        json_value(int64_t v) noexcept : number_integer(v) {}
-        /// constructor for numbers (unsigned)
-        json_value(uint64_t v) noexcept : number_unsigned(v) {}
-        /// constructor for numbers (floating-point)
-        json_value(double v) noexcept : number_float(v) {}
-        /// constructor for empty values of a given type
-        json_value(value_t t);
-
-        /// constructor for strings
-        json_value(std::string_view value)
-        {
-            string = create<std::string>(value);
-        }
-
-        /// constructor for strings
-        json_value(const std::string& value)
-        {
-            string = create<std::string>(value);
-        }
-
-        /// constructor for rvalue strings
-        json_value(std::string&& value)
-        {
-            string = create<std::string>(std::move(value));
-        }
-
-        /// constructor for objects
-        json_value(const object_t& value)
-        {
-            object = create<object_t>(value);
-        }
-
-        /// constructor for rvalue objects
-        json_value(object_t&& value)
-        {
-            object = create<object_t>(std::move(value));
-        }
-
-        /// constructor for arrays
-        json_value(const array_t& value)
-        {
-            array = create<array_t>(value);
-        }
-
-        /// constructor for rvalue arrays
-        json_value(array_t&& value)
-        {
-            array = create<array_t>(std::move(value));
-        }
-
-        void destroy(value_t t) noexcept;
-    };
-
-    /*!
-    @brief checks the class invariants
-
-    This function asserts the class invariants. It needs to be called at the
-    end of every constructor to make sure that created objects respect the
-    invariant. Furthermore, it has to be called each time the type of a JSON
-    value is changed, because the invariant expresses a relationship between
-    @a m_type and @a m_value.
-    */
-    void assert_invariant() const noexcept
-    {
-        assert(m_type != value_t::object or m_value.object != nullptr);
-        assert(m_type != value_t::array or m_value.array != nullptr);
-        assert(m_type != value_t::string or m_value.string != nullptr);
-    }
-
-  public:
-    //////////////////////////
-    // JSON parser callback //
-    //////////////////////////
-
-    /*!
-    @brief parser event types
-
-    The parser callback distinguishes the following events:
-    - `object_start`: the parser read `{` and started to process a JSON object
-    - `key`: the parser read a key of a value in an object
-    - `object_end`: the parser read `}` and finished processing a JSON object
-    - `array_start`: the parser read `[` and started to process a JSON array
-    - `array_end`: the parser read `]` and finished processing a JSON array
-    - `value`: the parser finished reading a JSON value
-
-    @image html callback_events.png "Example when certain parse events are triggered"
-
-    @sa @ref parser_callback_t for more information and examples
-    */
-    enum class parse_event_t : uint8_t
-    {
-        /// the parser read `{` and started to process a JSON object
-        object_start,
-        /// the parser read `}` and finished processing a JSON object
-        object_end,
-        /// the parser read `[` and started to process a JSON array
-        array_start,
-        /// the parser read `]` and finished processing a JSON array
-        array_end,
-        /// the parser read a key of a value in an object
-        key,
-        /// the parser finished reading a JSON value
-        value
-    };
-
-    /*!
-    @brief per-element parser callback type
-
-    With a parser callback function, the result of parsing a JSON text can be
-    influenced. When passed to @ref parse, it is called on certain events
-    (passed as @ref parse_event_t via parameter @a event) with a set recursion
-    depth @a depth and context JSON value @a parsed. The return value of the
-    callback function is a boolean indicating whether the element that emitted
-    the callback shall be kept or not.
-
-    We distinguish six scenarios (determined by the event type) in which the
-    callback function can be called. The following table describes the values
-    of the parameters @a depth, @a event, and @a parsed.
-
-    parameter @a event | description | parameter @a depth | parameter @a parsed
-    ------------------ | ----------- | ------------------ | -------------------
-    parse_event_t::object_start | the parser read `{` and started to process a JSON object | depth of the parent of the JSON object | a JSON value with type discarded
-    parse_event_t::key | the parser read a key of a value in an object | depth of the currently parsed JSON object | a JSON string containing the key
-    parse_event_t::object_end | the parser read `}` and finished processing a JSON object | depth of the parent of the JSON object | the parsed JSON object
-    parse_event_t::array_start | the parser read `[` and started to process a JSON array | depth of the parent of the JSON array | a JSON value with type discarded
-    parse_event_t::array_end | the parser read `]` and finished processing a JSON array | depth of the parent of the JSON array | the parsed JSON array
-    parse_event_t::value | the parser finished reading a JSON value | depth of the value | the parsed JSON value
-
-    @image html callback_events.png "Example when certain parse events are triggered"
-
-    Discarding a value (i.e., returning `false`) has different effects
-    depending on the context in which function was called:
-
-    - Discarded values in structured types are skipped. That is, the parser
-      will behave as if the discarded value was never read.
-    - In case a value outside a structured type is skipped, it is replaced
-      with `null`. This case happens if the top-level element is skipped.
-
-    @param[in] depth  the depth of the recursion during parsing
-
-    @param[in] event  an event of type parse_event_t indicating the context in
-    the callback function has been called
-
-    @param[in,out] parsed  the current intermediate parse result; note that
-    writing to this value has no effect for parse_event_t::key events
-
-    @return Whether the JSON value which called the function during parsing
-    should be kept (`true`) or not (`false`). In the latter case, it is either
-    skipped completely or replaced by an empty discarded object.
-
-    @sa @ref parse for examples
-
-    @since version 1.0.0
-    */
-    using parser_callback_t =
-        std::function<bool(int depth, parse_event_t event, json& parsed)>;
-
-
-    //////////////////
-    // constructors //
-    //////////////////
-
-    /// @name constructors and destructors
-    /// Constructors of class @ref json, copy/move constructor, copy
-    /// assignment, static functions creating objects, and the destructor.
-    /// @{
-
-    /*!
-    @brief create an empty value with a given type
-
-    Create an empty JSON value with a given type. The value will be default
-    initialized with an empty value which depends on the type:
-
-    Value type  | initial value
-    ----------- | -------------
-    null        | `null`
-    boolean     | `false`
-    string      | `""`
-    number      | `0`
-    object      | `{}`
-    array       | `[]`
-
-    @param[in] v  the type of the value to create
-
-    @complexity Constant.
-
-    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
-    changes to any JSON value.
-
-    @liveexample{The following code shows the constructor for different @ref
-    value_t values,json__value_t}
-
-    @sa @ref clear() -- restores the postcondition of this constructor
-
-    @since version 1.0.0
-    */
-    json(const value_t v)
-        : m_type(v), m_value(v)
-    {
-        assert_invariant();
-    }
-
-    /*!
-    @brief create a null object
-
-    Create a `null` JSON value. It either takes a null pointer as parameter
-    (explicitly creating `null`) or no parameter (implicitly creating `null`).
-    The passed null pointer itself is not read -- it is only used to choose
-    the right constructor.
-
-    @complexity Constant.
-
-    @exceptionsafety No-throw guarantee: this constructor never throws
-    exceptions.
-
-    @liveexample{The following code shows the constructor with and without a
-    null pointer parameter.,json__nullptr_t}
-
-    @since version 1.0.0
-    */
-    json(std::nullptr_t = nullptr) noexcept
-        : json(value_t::null)
-    {
-        assert_invariant();
-    }
-
-    /*!
-    @brief create a JSON value
-
-    This is a "catch all" constructor for all compatible JSON types; that is,
-    types for which a `to_json()` method exists. The constructor forwards the
-    parameter @a val to that method (to `json_serializer<U>::to_json` method
-    with `U = uncvref_t<CompatibleType>`, to be exact).
-
-    Template type @a CompatibleType includes, but is not limited to, the
-    following types:
-    - **arrays**: @ref array_t and all kinds of compatible containers such as
-      `std::vector`, `std::deque`, `std::list`,
-      `std::array`, `std::set`, `std::unordered_set`,
-      `std::multiset`, and `std::unordered_multiset` with a `value_type` from
-      which a @ref json value can be constructed.
-    - **objects**: @ref object_t and all kinds of compatible associative
-      containers such as `std::map`, `std::unordered_map`, `std::multimap`,
-      and `std::unordered_multimap` with a `key_type` compatible to
-      `std::string` and a `value_type` from which a @ref json value can
-      be constructed.
-    - **strings**: `std::string`, string literals, and all compatible string
-      containers can be used.
-    - **numbers**: int64_t, uint64_t,
-      double, and all convertible number types such as `int`,
-      `size_t`, `int64_t`, `float` or `double` can be used.
-    - **boolean**: `bool` can be used.
-
-    See the examples below.
-
-    @tparam CompatibleType a type such that:
-    - @a CompatibleType is not derived from `std::istream`,
-    - @a CompatibleType is not @ref json (to avoid hijacking copy/move
-         constructors),
-    - @a CompatibleType is not a different @ref json type (i.e. with different template arguments)
-    - @a CompatibleType is not a @ref json nested type (e.g.,
-         @ref json_pointer, @ref iterator, etc ...)
-    - @ref @ref json_serializer<U> has a
-         `to_json(json_t&, CompatibleType&&)` method
-
-    @tparam U = `uncvref_t<CompatibleType>`
-
-    @param[in] val the value to be forwarded to the respective constructor
-
-    @complexity Usually linear in the size of the passed @a val, also
-                depending on the implementation of the called `to_json()`
-                method.
-
-    @exceptionsafety Depends on the called constructor. For types directly
-    supported by the library (i.e., all types for which no `to_json()` function
-    was provided), strong guarantee holds: if an exception is thrown, there are
-    no changes to any JSON value.
-
-    @liveexample{The following code shows the constructor with several
-    compatible types.,json__CompatibleType}
-
-    @since version 2.1.0
-    */
-    template <typename CompatibleType,
-              typename U = detail::uncvref_t<CompatibleType>,
-              detail::enable_if_t<
-                  detail::is_compatible_type<json_t, U>::value, int> = 0>
-    json(CompatibleType && val) noexcept(noexcept(
-                adl_serializer<U, void>::to_json(std::declval<json_t&>(),
-                                           std::forward<CompatibleType>(val))))
-    {
-        adl_serializer<U, void>::to_json(*this, std::forward<CompatibleType>(val));
-        assert_invariant();
-    }
-
-    /*!
-    @brief create a container (array or object) from an initializer list
-
-    Creates a JSON value of type array or object from the passed initializer
-    list @a init. In case @a type_deduction is `true` (default), the type of
-    the JSON value to be created is deducted from the initializer list @a init
-    according to the following rules:
-
-    1. If the list is empty, an empty JSON object value `{}` is created.
-    2. If the list consists of pairs whose first element is a string, a JSON
-       object value is created where the first elements of the pairs are
-       treated as keys and the second elements are as values.
-    3. In all other cases, an array is created.
-
-    The rules aim to create the best fit between a C++ initializer list and
-    JSON values. The rationale is as follows:
-
-    1. The empty initializer list is written as `{}` which is exactly an empty
-       JSON object.
-    2. C++ has no way of describing mapped types other than to list a list of
-       pairs. As JSON requires that keys must be of type string, rule 2 is the
-       weakest constraint one can pose on initializer lists to interpret them
-       as an object.
-    3. In all other cases, the initializer list could not be interpreted as
-       JSON object type, so interpreting it as JSON array type is safe.
-
-    With the rules described above, the following JSON values cannot be
-    expressed by an initializer list:
-
-    - the empty array (`[]`): use @ref array(initializer_list_t)
-      with an empty initializer list in this case
-    - arrays whose elements satisfy rule 2: use @ref
-      array(initializer_list_t) with the same initializer list
-      in this case
-
-    @note When used without parentheses around an empty initializer list, @ref
-    json() is called instead of this function, yielding the JSON null
-    value.
-
-    @param[in] init  initializer list with JSON values
-
-    @param[in] type_deduction internal parameter; when set to `true`, the type
-    of the JSON value is deducted from the initializer list @a init; when set
-    to `false`, the type provided via @a manual_type is forced. This mode is
-    used by the functions @ref array(initializer_list_t) and
-    @ref object(initializer_list_t).
-
-    @param[in] manual_type internal parameter; when @a type_deduction is set
-    to `false`, the created JSON value will use the provided type (only @ref
-    value_t::array and @ref value_t::object are valid); when @a type_deduction
-    is set to `true`, this parameter has no effect
-
-    @throw type_error.301 if @a type_deduction is `false`, @a manual_type is
-    `value_t::object`, but @a init contains an element which is not a pair
-    whose first element is a string. In this case, the constructor could not
-    create an object. If @a type_deduction would have be `true`, an array
-    would have been created. See @ref object(initializer_list_t)
-    for an example.
-
-    @complexity Linear in the size of the initializer list @a init.
-
-    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
-    changes to any JSON value.
-
-    @liveexample{The example below shows how JSON values are created from
-    initializer lists.,json__list_init_t}
-
-    @sa @ref array(initializer_list_t) -- create a JSON array
-    value from an initializer list
-    @sa @ref object(initializer_list_t) -- create a JSON object
-    value from an initializer list
-
-    @since version 1.0.0
-    */
-    json(initializer_list_t init,
-               bool type_deduction = true,
-               value_t manual_type = value_t::array);
-
-    /*!
-    @brief explicitly create an array from an initializer list
-
-    Creates a JSON array value from a given initializer list. That is, given a
-    list of values `a, b, c`, creates the JSON value `[a, b, c]`. If the
-    initializer list is empty, the empty array `[]` is created.
-
-    @note This function is only needed to express two edge cases that cannot
-    be realized with the initializer list constructor (@ref
-    json(initializer_list_t, bool, value_t)). These cases
-    are:
-    1. creating an array whose elements are all pairs whose first element is a
-    string -- in this case, the initializer list constructor would create an
-    object, taking the first elements as keys
-    2. creating an empty array -- passing the empty initializer list to the
-    initializer list constructor yields an empty object
-
-    @param[in] init  initializer list with JSON values to create an array from
-    (optional)
-
-    @return JSON array value
-
-    @complexity Linear in the size of @a init.
-
-    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
-    changes to any JSON value.
-
-    @liveexample{The following code shows an example for the `array`
-    function.,array}
-
-    @sa @ref json(initializer_list_t, bool, value_t) --
-    create a JSON value from an initializer list
-    @sa @ref object(initializer_list_t) -- create a JSON object
-    value from an initializer list
-
-    @since version 1.0.0
-    */
-    static json array(initializer_list_t init = {})
-    {
-        return json(init, false, value_t::array);
-    }
-
-    /*!
-    @brief explicitly create an object from an initializer list
-
-    Creates a JSON object value from a given initializer list. The initializer
-    lists elements must be pairs, and their first elements must be strings. If
-    the initializer list is empty, the empty object `{}` is created.
-
-    @note This function is only added for symmetry reasons. In contrast to the
-    related function @ref array(initializer_list_t), there are
-    no cases which can only be expressed by this function. That is, any
-    initializer list @a init can also be passed to the initializer list
-    constructor @ref json(initializer_list_t, bool, value_t).
-
-    @param[in] init  initializer list to create an object from (optional)
-
-    @return JSON object value
-
-    @throw type_error.301 if @a init is not a list of pairs whose first
-    elements are strings. In this case, no object can be created. When such a
-    value is passed to @ref json(initializer_list_t, bool, value_t),
-    an array would have been created from the passed initializer list @a init.
-    See example below.
-
-    @complexity Linear in the size of @a init.
-
-    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
-    changes to any JSON value.
-
-    @liveexample{The following code shows an example for the `object`
-    function.,object}
-
-    @sa @ref json(initializer_list_t, bool, value_t) --
-    create a JSON value from an initializer list
-    @sa @ref array(initializer_list_t) -- create a JSON array
-    value from an initializer list
-
-    @since version 1.0.0
-    */
-    static json object(initializer_list_t init = {})
-    {
-        return json(init, false, value_t::object);
-    }
-
-    /*!
-    @brief construct an array with count copies of given value
-
-    Constructs a JSON array value by creating @a cnt copies of a passed value.
-    In case @a cnt is `0`, an empty array is created.
-
-    @param[in] cnt  the number of JSON copies of @a val to create
-    @param[in] val  the JSON value to copy
-
-    @post `std::distance(begin(),end()) == cnt` holds.
-
-    @complexity Linear in @a cnt.
-
-    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
-    changes to any JSON value.
-
-    @liveexample{The following code shows examples for the @ref
-    json(size_type\, const json&)
-    constructor.,json__size_type_json}
-
-    @since version 1.0.0
-    */
-    json(size_type cnt, const json& val);
-
-    /*!
-    @brief construct a JSON container given an iterator range
-
-    Constructs the JSON value with the contents of the range `[first, last)`.
-    The semantics depends on the different types a JSON value can have:
-    - In case of a null type, invalid_iterator.206 is thrown.
-    - In case of other primitive types (number, boolean, or string), @a first
-      must be `begin()` and @a last must be `end()`. In this case, the value is
-      copied. Otherwise, invalid_iterator.204 is thrown.
-    - In case of structured types (array, object), the constructor behaves as
-      similar versions for `std::vector` or `std::map`; that is, a JSON array
-      or object is constructed from the values in the range.
-
-    @tparam InputIT an input iterator type (@ref iterator or @ref
-    const_iterator)
-
-    @param[in] first begin of the range to copy from (included)
-    @param[in] last end of the range to copy from (excluded)
-
-    @pre Iterators @a first and @a last must be initialized. **This
-         precondition is enforced with an assertion (see warning).** If
-         assertions are switched off, a violation of this precondition yields
-         undefined behavior.
-
-    @pre Range `[first, last)` is valid. Usually, this precondition cannot be
-         checked efficiently. Only certain edge cases are detected; see the
-         description of the exceptions below. A violation of this precondition
-         yields undefined behavior.
-
-    @warning A precondition is enforced with a runtime assertion that will
-             result in calling `std::abort` if this precondition is not met.
-             Assertions can be disabled by defining `NDEBUG` at compile time.
-             See http://en.cppreference.com/w/cpp/error/assert for more
-             information.
-
-    @throw invalid_iterator.201 if iterators @a first and @a last are not
-    compatible (i.e., do not belong to the same JSON value). In this case,
-    the range `[first, last)` is undefined.
-    @throw invalid_iterator.204 if iterators @a first and @a last belong to a
-    primitive type (number, boolean, or string), but @a first does not point
-    to the first element any more. In this case, the range `[first, last)` is
-    undefined. See example code below.
-    @throw invalid_iterator.206 if iterators @a first and @a last belong to a
-    null value. In this case, the range `[first, last)` is undefined.
-
-    @complexity Linear in distance between @a first and @a last.
-
-    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
-    changes to any JSON value.
-
-    @liveexample{The example below shows several ways to create JSON values by
-    specifying a subrange with iterators.,json__InputIt_InputIt}
-
-    @since version 1.0.0
-    */
-    template<class InputIT, typename std::enable_if<
-                 std::is_same<InputIT, typename json_t::iterator>::value or
-                 std::is_same<InputIT, typename json_t::const_iterator>::value, int>::type = 0>
-    json(InputIT first, InputIT last)
-    {
-        assert(first.m_object != nullptr);
-        assert(last.m_object != nullptr);
-
-        // make sure iterator fits the current value
-        if (JSON_UNLIKELY(first.m_object != last.m_object))
-        {
-            JSON_THROW(invalid_iterator::create(201, "iterators are not compatible"));
-        }
-
-        // copy type from first iterator
-        m_type = first.m_object->m_type;
-
-        // check if iterator range is complete for primitive values
-        switch (m_type)
-        {
-            case value_t::boolean:
-            case value_t::number_float:
-            case value_t::number_integer:
-            case value_t::number_unsigned:
-            case value_t::string:
-            {
-                if (JSON_UNLIKELY(not first.m_it.primitive_iterator.is_begin()
-                                  or not last.m_it.primitive_iterator.is_end()))
-                {
-                    JSON_THROW(invalid_iterator::create(204, "iterators out of range"));
-                }
-                break;
-            }
-
-            default:
-                break;
-        }
-
-        switch (m_type)
-        {
-            case value_t::number_integer:
-            {
-                m_value.number_integer = first.m_object->m_value.number_integer;
-                break;
-            }
-
-            case value_t::number_unsigned:
-            {
-                m_value.number_unsigned = first.m_object->m_value.number_unsigned;
-                break;
-            }
-
-            case value_t::number_float:
-            {
-                m_value.number_float = first.m_object->m_value.number_float;
-                break;
-            }
-
-            case value_t::boolean:
-            {
-                m_value.boolean = first.m_object->m_value.boolean;
-                break;
-            }
-
-            case value_t::string:
-            {
-                m_value = *first.m_object->m_value.string;
-                break;
-            }
-
-            case value_t::array:
-            {
-                m_value.array = create<array_t>(first.m_it.array_iterator,
-                                                last.m_it.array_iterator);
-                break;
-            }
-
-            default:
-                JSON_THROW(invalid_iterator::create(206, "cannot construct with iterators from", first.m_object->type_name()));
-        }
-
-        assert_invariant();
-    }
-
-
-    ///////////////////////////////////////
-    // other constructors and destructor //
-    ///////////////////////////////////////
-
-    /// @private
-    json(const detail::json_ref<json>& ref)
-        : json(ref.moved_or_copied())
-    {}
-
-    /*!
-    @brief copy constructor
-
-    Creates a copy of a given JSON value.
-
-    @param[in] other  the JSON value to copy
-
-    @post `*this == other`
-
-    @complexity Linear in the size of @a other.
-
-    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
-    changes to any JSON value.
-
-    @requirement This function helps `json` satisfying the
-    [Container](http://en.cppreference.com/w/cpp/concept/Container)
-    requirements:
-    - The complexity is linear.
-    - As postcondition, it holds: `other == json(other)`.
-
-    @liveexample{The following code shows an example for the copy
-    constructor.,json__json}
-
-    @since version 1.0.0
-    */
-    json(const json& other);
-
-    /*!
-    @brief move constructor
-
-    Move constructor. Constructs a JSON value with the contents of the given
-    value @a other using move semantics. It "steals" the resources from @a
-    other and leaves it as JSON null value.
-
-    @param[in,out] other  value to move to this object
-
-    @post `*this` has the same value as @a other before the call.
-    @post @a other is a JSON null value.
-
-    @complexity Constant.
-
-    @exceptionsafety No-throw guarantee: this constructor never throws
-    exceptions.
-
-    @requirement This function helps `json` satisfying the
-    [MoveConstructible](http://en.cppreference.com/w/cpp/concept/MoveConstructible)
-    requirements.
-
-    @liveexample{The code below shows the move constructor explicitly called
-    via std::move.,json__moveconstructor}
-
-    @since version 1.0.0
-    */
-    json(json&& other) noexcept
-        : m_type(std::move(other.m_type)),
-          m_value(std::move(other.m_value))
-    {
-        // check that passed value is valid
-        other.assert_invariant();
-
-        // invalidate payload
-        other.m_type = value_t::null;
-        other.m_value = {};
-
-        assert_invariant();
-    }
-
-    /*!
-    @brief copy assignment
-
-    Copy assignment operator. Copies a JSON value via the "copy and swap"
-    strategy: It is expressed in terms of the copy constructor, destructor,
-    and the `swap()` member function.
-
-    @param[in] other  value to copy from
-
-    @complexity Linear.
-
-    @requirement This function helps `json` satisfying the
-    [Container](http://en.cppreference.com/w/cpp/concept/Container)
-    requirements:
-    - The complexity is linear.
-
-    @liveexample{The code below shows and example for the copy assignment. It
-    creates a copy of value `a` which is then swapped with `b`. Finally\, the
-    copy of `a` (which is the null value after the swap) is
-    destroyed.,json__copyassignment}
-
-    @since version 1.0.0
-    */
-    reference& operator=(json other) noexcept (
-        std::is_nothrow_move_constructible<value_t>::value and
-        std::is_nothrow_move_assignable<value_t>::value and
-        std::is_nothrow_move_constructible<json_value>::value and
-        std::is_nothrow_move_assignable<json_value>::value
-    )
-    {
-        // check that passed value is valid
-        other.assert_invariant();
-
-        using std::swap;
-        swap(m_type, other.m_type);
-        swap(m_value, other.m_value);
-
-        assert_invariant();
-        return *this;
-    }
-
-    /*!
-    @brief destructor
-
-    Destroys the JSON value and frees all allocated memory.
-
-    @complexity Linear.
-
-    @requirement This function helps `json` satisfying the
-    [Container](http://en.cppreference.com/w/cpp/concept/Container)
-    requirements:
-    - The complexity is linear.
-    - All stored elements are destroyed and all memory is freed.
-
-    @since version 1.0.0
-    */
-    ~json() noexcept
-    {
-        assert_invariant();
-        m_value.destroy(m_type);
-    }
-
-    /// @}
-
-  public:
-    ///////////////////////
-    // object inspection //
-    ///////////////////////
-
-    /// @name object inspection
-    /// Functions to inspect the type of a JSON value.
-    /// @{
-
-    /*!
-    @brief serialization
-
-    Serialization function for JSON values. The function tries to mimic
-    Python's `json.dumps()` function, and currently supports its @a indent
-    and @a ensure_ascii parameters.
-
-    @param[in] indent If indent is nonnegative, then array elements and object
-    members will be pretty-printed with that indent level. An indent level of
-    `0` will only insert newlines. `-1` (the default) selects the most compact
-    representation.
-    @param[in] indent_char The character to use for indentation if @a indent is
-    greater than `0`. The default is ` ` (space).
-    @param[in] ensure_ascii If @a ensure_ascii is true, all non-ASCII characters
-    in the output are escaped with `\uXXXX` sequences, and the result consists
-    of ASCII characters only.
-
-    @return string containing the serialization of the JSON value
-
-    @throw type_error.316 if a string stored inside the JSON value is not
-                          UTF-8 encoded
-
-    @complexity Linear.
-
-    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
-    changes in the JSON value.
-
-    @liveexample{The following example shows the effect of different @a indent\,
-    @a indent_char\, and @a ensure_ascii parameters to the result of the
-    serialization.,dump}
-
-    @see https://docs.python.org/2/library/json.html#json.dump
-
-    @since version 1.0.0; indentation character @a indent_char, option
-           @a ensure_ascii and exceptions added in version 3.0.0
-    */
-    std::string dump(const int indent = -1, const char indent_char = ' ',
-                     const bool ensure_ascii = false) const;
-
-    void dump(raw_ostream& os, int indent = -1, const char indent_char = ' ',
-              const bool ensure_ascii = false) const;
-
-    /*!
-    @brief return the type of the JSON value (explicit)
-
-    Return the type of the JSON value as a value from the @ref value_t
-    enumeration.
-
-    @return the type of the JSON value
-            Value type                | return value
-            ------------------------- | -------------------------
-            null                      | value_t::null
-            boolean                   | value_t::boolean
-            string                    | value_t::string
-            number (integer)          | value_t::number_integer
-            number (unsigned integer) | value_t::number_unsigned
-            number (floating-point)   | value_t::number_float
-            object                    | value_t::object
-            array                     | value_t::array
-            discarded                 | value_t::discarded
-
-    @complexity Constant.
-
-    @exceptionsafety No-throw guarantee: this member function never throws
-    exceptions.
-
-    @liveexample{The following code exemplifies `type()` for all JSON
-    types.,type}
-
-    @sa @ref operator value_t() -- return the type of the JSON value (implicit)
-    @sa @ref type_name() -- return the type as string
-
-    @since version 1.0.0
-    */
-    value_t type() const noexcept
-    {
-        return m_type;
-    }
-
-    /*!
-    @brief return whether type is primitive
-
-    This function returns true if and only if the JSON type is primitive
-    (string, number, boolean, or null).
-
-    @return `true` if type is primitive (string, number, boolean, or null),
-    `false` otherwise.
-
-    @complexity Constant.
-
-    @exceptionsafety No-throw guarantee: this member function never throws
-    exceptions.
-
-    @liveexample{The following code exemplifies `is_primitive()` for all JSON
-    types.,is_primitive}
-
-    @sa @ref is_structured() -- returns whether JSON value is structured
-    @sa @ref is_null() -- returns whether JSON value is `null`
-    @sa @ref is_string() -- returns whether JSON value is a string
-    @sa @ref is_boolean() -- returns whether JSON value is a boolean
-    @sa @ref is_number() -- returns whether JSON value is a number
-
-    @since version 1.0.0
-    */
-    bool is_primitive() const noexcept
-    {
-        return is_null() or is_string() or is_boolean() or is_number();
-    }
-
-    /*!
-    @brief return whether type is structured
-
-    This function returns true if and only if the JSON type is structured
-    (array or object).
-
-    @return `true` if type is structured (array or object), `false` otherwise.
-
-    @complexity Constant.
-
-    @exceptionsafety No-throw guarantee: this member function never throws
-    exceptions.
-
-    @liveexample{The following code exemplifies `is_structured()` for all JSON
-    types.,is_structured}
-
-    @sa @ref is_primitive() -- returns whether value is primitive
-    @sa @ref is_array() -- returns whether value is an array
-    @sa @ref is_object() -- returns whether value is an object
-
-    @since version 1.0.0
-    */
-    bool is_structured() const noexcept
-    {
-        return is_array() or is_object();
-    }
-
-    /*!
-    @brief return whether value is null
-
-    This function returns true if and only if the JSON value is null.
-
-    @return `true` if type is null, `false` otherwise.
-
-    @complexity Constant.
-
-    @exceptionsafety No-throw guarantee: this member function never throws
-    exceptions.
-
-    @liveexample{The following code exemplifies `is_null()` for all JSON
-    types.,is_null}
-
-    @since version 1.0.0
-    */
-    bool is_null() const noexcept
-    {
-        return (m_type == value_t::null);
-    }
-
-    /*!
-    @brief return whether value is a boolean
-
-    This function returns true if and only if the JSON value is a boolean.
-
-    @return `true` if type is boolean, `false` otherwise.
-
-    @complexity Constant.
-
-    @exceptionsafety No-throw guarantee: this member function never throws
-    exceptions.
-
-    @liveexample{The following code exemplifies `is_boolean()` for all JSON
-    types.,is_boolean}
-
-    @since version 1.0.0
-    */
-    bool is_boolean() const noexcept
-    {
-        return (m_type == value_t::boolean);
-    }
-
-    /*!
-    @brief return whether value is a number
-
-    This function returns true if and only if the JSON value is a number. This
-    includes both integer (signed and unsigned) and floating-point values.
-
-    @return `true` if type is number (regardless whether integer, unsigned
-    integer or floating-type), `false` otherwise.
-
-    @complexity Constant.
-
-    @exceptionsafety No-throw guarantee: this member function never throws
-    exceptions.
-
-    @liveexample{The following code exemplifies `is_number()` for all JSON
-    types.,is_number}
-
-    @sa @ref is_number_integer() -- check if value is an integer or unsigned
-    integer number
-    @sa @ref is_number_unsigned() -- check if value is an unsigned integer
-    number
-    @sa @ref is_number_float() -- check if value is a floating-point number
-
-    @since version 1.0.0
-    */
-    bool is_number() const noexcept
-    {
-        return is_number_integer() or is_number_float();
-    }
-
-    /*!
-    @brief return whether value is an integer number
-
-    This function returns true if and only if the JSON value is a signed or
-    unsigned integer number. This excludes floating-point values.
-
-    @return `true` if type is an integer or unsigned integer number, `false`
-    otherwise.
-
-    @complexity Constant.
-
-    @exceptionsafety No-throw guarantee: this member function never throws
-    exceptions.
-
-    @liveexample{The following code exemplifies `is_number_integer()` for all
-    JSON types.,is_number_integer}
-
-    @sa @ref is_number() -- check if value is a number
-    @sa @ref is_number_unsigned() -- check if value is an unsigned integer
-    number
-    @sa @ref is_number_float() -- check if value is a floating-point number
-
-    @since version 1.0.0
-    */
-    bool is_number_integer() const noexcept
-    {
-        return (m_type == value_t::number_integer or m_type == value_t::number_unsigned);
-    }
-
-    /*!
-    @brief return whether value is an unsigned integer number
-
-    This function returns true if and only if the JSON value is an unsigned
-    integer number. This excludes floating-point and signed integer values.
-
-    @return `true` if type is an unsigned integer number, `false` otherwise.
-
-    @complexity Constant.
-
-    @exceptionsafety No-throw guarantee: this member function never throws
-    exceptions.
-
-    @liveexample{The following code exemplifies `is_number_unsigned()` for all
-    JSON types.,is_number_unsigned}
-
-    @sa @ref is_number() -- check if value is a number
-    @sa @ref is_number_integer() -- check if value is an integer or unsigned
-    integer number
-    @sa @ref is_number_float() -- check if value is a floating-point number
-
-    @since version 2.0.0
-    */
-    bool is_number_unsigned() const noexcept
-    {
-        return (m_type == value_t::number_unsigned);
-    }
-
-    /*!
-    @brief return whether value is a floating-point number
-
-    This function returns true if and only if the JSON value is a
-    floating-point number. This excludes signed and unsigned integer values.
-
-    @return `true` if type is a floating-point number, `false` otherwise.
-
-    @complexity Constant.
-
-    @exceptionsafety No-throw guarantee: this member function never throws
-    exceptions.
-
-    @liveexample{The following code exemplifies `is_number_float()` for all
-    JSON types.,is_number_float}
-
-    @sa @ref is_number() -- check if value is number
-    @sa @ref is_number_integer() -- check if value is an integer number
-    @sa @ref is_number_unsigned() -- check if value is an unsigned integer
-    number
-
-    @since version 1.0.0
-    */
-    bool is_number_float() const noexcept
-    {
-        return (m_type == value_t::number_float);
-    }
-
-    /*!
-    @brief return whether value is an object
-
-    This function returns true if and only if the JSON value is an object.
-
-    @return `true` if type is object, `false` otherwise.
-
-    @complexity Constant.
-
-    @exceptionsafety No-throw guarantee: this member function never throws
-    exceptions.
-
-    @liveexample{The following code exemplifies `is_object()` for all JSON
-    types.,is_object}
-
-    @since version 1.0.0
-    */
-    bool is_object() const noexcept
-    {
-        return (m_type == value_t::object);
-    }
-
-    /*!
-    @brief return whether value is an array
-
-    This function returns true if and only if the JSON value is an array.
-
-    @return `true` if type is array, `false` otherwise.
-
-    @complexity Constant.
-
-    @exceptionsafety No-throw guarantee: this member function never throws
-    exceptions.
-
-    @liveexample{The following code exemplifies `is_array()` for all JSON
-    types.,is_array}
-
-    @since version 1.0.0
-    */
-    bool is_array() const noexcept
-    {
-        return (m_type == value_t::array);
-    }
-
-    /*!
-    @brief return whether value is a string
-
-    This function returns true if and only if the JSON value is a string.
-
-    @return `true` if type is string, `false` otherwise.
-
-    @complexity Constant.
-
-    @exceptionsafety No-throw guarantee: this member function never throws
-    exceptions.
-
-    @liveexample{The following code exemplifies `is_string()` for all JSON
-    types.,is_string}
-
-    @since version 1.0.0
-    */
-    bool is_string() const noexcept
-    {
-        return (m_type == value_t::string);
-    }
-
-    /*!
-    @brief return whether value is discarded
-
-    This function returns true if and only if the JSON value was discarded
-    during parsing with a callback function (see @ref parser_callback_t).
-
-    @note This function will always be `false` for JSON values after parsing.
-    That is, discarded values can only occur during parsing, but will be
-    removed when inside a structured value or replaced by null in other cases.
-
-    @return `true` if type is discarded, `false` otherwise.
-
-    @complexity Constant.
-
-    @exceptionsafety No-throw guarantee: this member function never throws
-    exceptions.
-
-    @liveexample{The following code exemplifies `is_discarded()` for all JSON
-    types.,is_discarded}
-
-    @since version 1.0.0
-    */
-    bool is_discarded() const noexcept
-    {
-        return (m_type == value_t::discarded);
-    }
-
-    /*!
-    @brief return the type of the JSON value (implicit)
-
-    Implicitly return the type of the JSON value as a value from the @ref
-    value_t enumeration.
-
-    @return the type of the JSON value
-
-    @complexity Constant.
-
-    @exceptionsafety No-throw guarantee: this member function never throws
-    exceptions.
-
-    @liveexample{The following code exemplifies the @ref value_t operator for
-    all JSON types.,operator__value_t}
-
-    @sa @ref type() -- return the type of the JSON value (explicit)
-    @sa @ref type_name() -- return the type as string
-
-    @since version 1.0.0
-    */
-    operator value_t() const noexcept
-    {
-        return m_type;
-    }
-
-    /// @}
-
-  private:
-    //////////////////
-    // value access //
-    //////////////////
-
-    /// get a boolean (explicit)
-    bool get_impl(bool* /*unused*/) const
-    {
-        if (JSON_LIKELY(is_boolean()))
-        {
-            return m_value.boolean;
-        }
-
-        JSON_THROW(type_error::create(302, "type must be boolean, but is", type_name()));
-    }
-
-    /// get a pointer to the value (object)
-    object_t* get_impl_ptr(object_t* /*unused*/) noexcept
-    {
-        return is_object() ? m_value.object : nullptr;
-    }
-
-    /// get a pointer to the value (object)
-    const object_t* get_impl_ptr(const object_t* /*unused*/) const noexcept
-    {
-        return is_object() ? m_value.object : nullptr;
-    }
-
-    /// get a pointer to the value (array)
-    array_t* get_impl_ptr(array_t* /*unused*/) noexcept
-    {
-        return is_array() ? m_value.array : nullptr;
-    }
-
-    /// get a pointer to the value (array)
-    const array_t* get_impl_ptr(const array_t* /*unused*/) const noexcept
-    {
-        return is_array() ? m_value.array : nullptr;
-    }
-
-    /// get a pointer to the value (string)
-    std::string* get_impl_ptr(std::string* /*unused*/) noexcept
-    {
-        return is_string() ? m_value.string : nullptr;
-    }
-
-    /// get a pointer to the value (string)
-    const std::string* get_impl_ptr(const std::string* /*unused*/) const noexcept
-    {
-        return is_string() ? m_value.string : nullptr;
-    }
-
-    /// get a pointer to the value (boolean)
-    bool* get_impl_ptr(bool* /*unused*/) noexcept
-    {
-        return is_boolean() ? &m_value.boolean : nullptr;
-    }
-
-    /// get a pointer to the value (boolean)
-    const bool* get_impl_ptr(const bool* /*unused*/) const noexcept
-    {
-        return is_boolean() ? &m_value.boolean : nullptr;
-    }
-
-    /// get a pointer to the value (integer number)
-    int64_t* get_impl_ptr(int64_t* /*unused*/) noexcept
-    {
-        return is_number_integer() ? &m_value.number_integer : nullptr;
-    }
-
-    /// get a pointer to the value (integer number)
-    const int64_t* get_impl_ptr(const int64_t* /*unused*/) const noexcept
-    {
-        return is_number_integer() ? &m_value.number_integer : nullptr;
-    }
-
-    /// get a pointer to the value (unsigned number)
-    uint64_t* get_impl_ptr(uint64_t* /*unused*/) noexcept
-    {
-        return is_number_unsigned() ? &m_value.number_unsigned : nullptr;
-    }
-
-    /// get a pointer to the value (unsigned number)
-    const uint64_t* get_impl_ptr(const uint64_t* /*unused*/) const noexcept
-    {
-        return is_number_unsigned() ? &m_value.number_unsigned : nullptr;
-    }
-
-    /// get a pointer to the value (floating-point number)
-    double* get_impl_ptr(double* /*unused*/) noexcept
-    {
-        return is_number_float() ? &m_value.number_float : nullptr;
-    }
-
-    /// get a pointer to the value (floating-point number)
-    const double* get_impl_ptr(const double* /*unused*/) const noexcept
-    {
-        return is_number_float() ? &m_value.number_float : nullptr;
-    }
-
-    /*!
-    @brief helper function to implement get_ref()
-
-    This function helps to implement get_ref() without code duplication for
-    const and non-const overloads
-
-    @tparam ThisType will be deduced as `json` or `const json`
-
-    @throw type_error.303 if ReferenceType does not match underlying value
-    type of the current JSON
-    */
-    template<typename ReferenceType, typename ThisType>
-    static ReferenceType get_ref_impl(ThisType& obj)
-    {
-        // delegate the call to get_ptr<>()
-        auto ptr = obj.template get_ptr<typename std::add_pointer<ReferenceType>::type>();
-
-        if (JSON_LIKELY(ptr != nullptr))
-        {
-            return *ptr;
-        }
-
-        JSON_THROW(type_error::create(303, "incompatible ReferenceType for get_ref, actual type is", obj.type_name()));
-    }
-
-  public:
-    /// @name value access
-    /// Direct access to the stored value of a JSON value.
-    /// @{
-
-    /*!
-    @brief get special-case overload
-
-    This overloads avoids a lot of template boilerplate, it can be seen as the
-    identity method
-
-    @tparam BasicJsonType == @ref json
-
-    @return a copy of *this
-
-    @complexity Constant.
-
-    @since version 2.1.0
-    */
-    template<typename BasicJsonType, detail::enable_if_t<
-                 std::is_same<typename std::remove_const<BasicJsonType>::type, json_t>::value,
-                 int> = 0>
-    json get() const
-    {
-        return *this;
-    }
-
-    /*!
-    @brief get a value (explicit)
-
-    Explicit type conversion between the JSON value and a compatible value
-    which is [CopyConstructible](http://en.cppreference.com/w/cpp/concept/CopyConstructible)
-    and [DefaultConstructible](http://en.cppreference.com/w/cpp/concept/DefaultConstructible).
-    The value is converted by calling the @ref json_serializer<ValueType>
-    `from_json()` method.
-
-    The function is equivalent to executing
-    @code {.cpp}
-    ValueType ret;
-    adl_serializer<ValueType, void>::from_json(*this, ret);
-    return ret;
-    @endcode
-
-    This overloads is chosen if:
-    - @a ValueType is not @ref json,
-    - @ref json_serializer<ValueType> has a `from_json()` method of the form
-      `void from_json(const json&, ValueType&)`, and
-    - @ref json_serializer<ValueType> does not have a `from_json()` method of
-      the form `ValueType from_json(const json&)`
-
-    @tparam ValueTypeCV the provided value type
-    @tparam ValueType the returned value type
-
-    @return copy of the JSON value, converted to @a ValueType
-
-    @throw what @ref json_serializer<ValueType> `from_json()` method throws
-
-    @liveexample{The example below shows several conversions from JSON values
-    to other types. There a few things to note: (1) Floating-point numbers can
-    be converted to integers\, (2) A JSON array can be converted to a standard
-    `std::vector<short>`\, (3) A JSON object can be converted to C++
-    associative containers such as `std::unordered_map<std::string\,
-    json>`.,get__ValueType_const}
-
-    @since version 2.1.0
-    */
-    template<typename ValueTypeCV, typename ValueType = detail::uncvref_t<ValueTypeCV>,
-             detail::enable_if_t <
-                 not detail::is_json<ValueType>::value and
-                 detail::has_from_json<json_t, ValueType>::value and
-                 not detail::has_non_default_from_json<json_t, ValueType>::value,
-                 int> = 0>
-    ValueType get() const noexcept(noexcept(
-                                       adl_serializer<ValueType, void>::from_json(std::declval<const json_t&>(), std::declval<ValueType&>())))
-    {
-        // we cannot static_assert on ValueTypeCV being non-const, because
-        // there is support for get<const json_t>(), which is why we
-        // still need the uncvref
-        static_assert(not std::is_reference<ValueTypeCV>::value,
-                      "get() cannot be used with reference types, you might want to use get_ref()");
-        static_assert(std::is_default_constructible<ValueType>::value,
-                      "types must be DefaultConstructible when used with get()");
-
-        ValueType ret;
-        adl_serializer<ValueType, void>::from_json(*this, ret);
-        return ret;
-    }
-
-    /*!
-    @brief get a value (explicit); special case
-
-    Explicit type conversion between the JSON value and a compatible value
-    which is **not** [CopyConstructible](http://en.cppreference.com/w/cpp/concept/CopyConstructible)
-    and **not** [DefaultConstructible](http://en.cppreference.com/w/cpp/concept/DefaultConstructible).
-    The value is converted by calling the @ref json_serializer<ValueType>
-    `from_json()` method.
-
-    The function is equivalent to executing
-    @code {.cpp}
-    return adl_serializer<ValueTypeCV, void>::from_json(*this);
-    @endcode
-
-    This overloads is chosen if:
-    - @a ValueType is not @ref json and
-    - @ref json_serializer<ValueType> has a `from_json()` method of the form
-      `ValueType from_json(const json&)`
-
-    @note If @ref json_serializer<ValueType> has both overloads of
-    `from_json()`, this one is chosen.
-
-    @tparam ValueTypeCV the provided value type
-    @tparam ValueType the returned value type
-
-    @return copy of the JSON value, converted to @a ValueType
-
-    @throw what @ref json_serializer<ValueType> `from_json()` method throws
-
-    @since version 2.1.0
-    */
-    template<typename ValueTypeCV, typename ValueType = detail::uncvref_t<ValueTypeCV>,
-             detail::enable_if_t<not std::is_same<json_t, ValueType>::value and
-                                 detail::has_non_default_from_json<json_t, ValueType>::value,
-                                 int> = 0>
-    ValueType get() const noexcept(noexcept(
-                                       adl_serializer<ValueTypeCV, void>::from_json(std::declval<const json_t&>())))
-    {
-        static_assert(not std::is_reference<ValueTypeCV>::value,
-                      "get() cannot be used with reference types, you might want to use get_ref()");
-        return adl_serializer<ValueTypeCV, void>::from_json(*this);
-    }
-
-    /*!
-    @brief get a pointer value (explicit)
-
-    Explicit pointer access to the internally stored JSON value. No copies are
-    made.
-
-    @warning The pointer becomes invalid if the underlying JSON object
-    changes.
-
-    @tparam PointerType pointer type; must be a pointer to @ref array_t, @ref
-    object_t, `std::string`, bool, int64_t, uint64_t, or double.
-
-    @return pointer to the internally stored JSON value if the requested
-    pointer type @a PointerType fits to the JSON value; `nullptr` otherwise
-
-    @complexity Constant.
-
-    @liveexample{The example below shows how pointers to internal values of a
-    JSON value can be requested. Note that no type conversions are made and a
-    `nullptr` is returned if the value and the requested pointer type does not
-    match.,get__PointerType}
-
-    @sa @ref get_ptr() for explicit pointer-member access
-
-    @since version 1.0.0
-    */
-    template<typename PointerType, typename std::enable_if<
-                 std::is_pointer<PointerType>::value, int>::type = 0>
-    PointerType get() noexcept
-    {
-        // delegate the call to get_ptr
-        return get_ptr<PointerType>();
-    }
-
-    /*!
-    @brief get a pointer value (explicit)
-    @copydoc get()
-    */
-    template<typename PointerType, typename std::enable_if<
-                 std::is_pointer<PointerType>::value, int>::type = 0>
-    const PointerType get() const noexcept
-    {
-        // delegate the call to get_ptr
-        return get_ptr<PointerType>();
-    }
-
-    /*!
-    @brief get a pointer value (implicit)
-
-    Implicit pointer access to the internally stored JSON value. No copies are
-    made.
-
-    @warning Writing data to the pointee of the result yields an undefined
-    state.
-
-    @tparam PointerType pointer type; must be a pointer to @ref array_t, @ref
-    object_t, `std::string`, bool, int64_t,
-    uint64_t, or double. Enforced by a static assertion.
-
-    @return pointer to the internally stored JSON value if the requested
-    pointer type @a PointerType fits to the JSON value; `nullptr` otherwise
-
-    @complexity Constant.
-
-    @liveexample{The example below shows how pointers to internal values of a
-    JSON value can be requested. Note that no type conversions are made and a
-    `nullptr` is returned if the value and the requested pointer type does not
-    match.,get_ptr}
-
-    @since version 1.0.0
-    */
-    template<typename PointerType, typename std::enable_if<
-                 std::is_pointer<PointerType>::value, int>::type = 0>
-    PointerType get_ptr() noexcept
-    {
-        // get the type of the PointerType (remove pointer and const)
-        using pointee_t = typename std::remove_const<typename
-                          std::remove_pointer<typename
-                          std::remove_const<PointerType>::type>::type>::type;
-        // make sure the type matches the allowed types
-        static_assert(
-            std::is_same<object_t, pointee_t>::value
-            or std::is_same<array_t, pointee_t>::value
-            or std::is_same<std::string, pointee_t>::value
-            or std::is_same<bool, pointee_t>::value
-            or std::is_same<int64_t, pointee_t>::value
-            or std::is_same<uint64_t, pointee_t>::value
-            or std::is_same<double, pointee_t>::value
-            , "incompatible pointer type");
-
-        // delegate the call to get_impl_ptr<>()
-        return get_impl_ptr(static_cast<PointerType>(nullptr));
-    }
-
-    /*!
-    @brief get a pointer value (implicit)
-    @copydoc get_ptr()
-    */
-    template<typename PointerType, typename std::enable_if<
-                 std::is_pointer<PointerType>::value and
-                 std::is_const<typename std::remove_pointer<PointerType>::type>::value, int>::type = 0>
-    const PointerType get_ptr() const noexcept
-    {
-        // get the type of the PointerType (remove pointer and const)
-        using pointee_t = typename std::remove_const<typename
-                          std::remove_pointer<typename
-                          std::remove_const<PointerType>::type>::type>::type;
-        // make sure the type matches the allowed types
-        static_assert(
-            std::is_same<object_t, pointee_t>::value
-            or std::is_same<array_t, pointee_t>::value
-            or std::is_same<std::string, pointee_t>::value
-            or std::is_same<bool, pointee_t>::value
-            or std::is_same<int64_t, pointee_t>::value
-            or std::is_same<uint64_t, pointee_t>::value
-            or std::is_same<double, pointee_t>::value
-            , "incompatible pointer type");
-
-        // delegate the call to get_impl_ptr<>() const
-        return get_impl_ptr(static_cast<PointerType>(nullptr));
-    }
-
-    /*!
-    @brief get a reference value (implicit)
-
-    Implicit reference access to the internally stored JSON value. No copies
-    are made.
-
-    @warning Writing data to the referee of the result yields an undefined
-    state.
-
-    @tparam ReferenceType reference type; must be a reference to @ref array_t,
-    @ref object_t, std::string, bool, int64_t, or
-    double. Enforced by static assertion.
-
-    @return reference to the internally stored JSON value if the requested
-    reference type @a ReferenceType fits to the JSON value; throws
-    type_error.303 otherwise
-
-    @throw type_error.303 in case passed type @a ReferenceType is incompatible
-    with the stored JSON value; see example below
-
-    @complexity Constant.
-
-    @liveexample{The example shows several calls to `get_ref()`.,get_ref}
-
-    @since version 1.1.0
-    */
-    template<typename ReferenceType, typename std::enable_if<
-                 std::is_reference<ReferenceType>::value, int>::type = 0>
-    ReferenceType get_ref()
-    {
-        // delegate call to get_ref_impl
-        return get_ref_impl<ReferenceType>(*this);
-    }
-
-    /*!
-    @brief get a reference value (implicit)
-    @copydoc get_ref()
-    */
-    template<typename ReferenceType, typename std::enable_if<
-                 std::is_reference<ReferenceType>::value and
-                 std::is_const<typename std::remove_reference<ReferenceType>::type>::value, int>::type = 0>
-    ReferenceType get_ref() const
-    {
-        // delegate call to get_ref_impl
-        return get_ref_impl<ReferenceType>(*this);
-    }
-
-    /*!
-    @brief get a value (implicit)
-
-    Implicit type conversion between the JSON value and a compatible value.
-    The call is realized by calling @ref get() const.
-
-    @tparam ValueType non-pointer type compatible to the JSON value, for
-    instance `int` for JSON integer numbers, `bool` for JSON booleans, or
-    `std::vector` types for JSON arrays. The character type of `std::string`
-    as well as an initializer list of this type is excluded to avoid
-    ambiguities as these types implicitly convert to `std::string`.
-
-    @return copy of the JSON value, converted to type @a ValueType
-
-    @throw type_error.302 in case passed type @a ValueType is incompatible
-    to the JSON value type (e.g., the JSON value is of type boolean, but a
-    string is requested); see example below
-
-    @complexity Linear in the size of the JSON value.
-
-    @liveexample{The example below shows several conversions from JSON values
-    to other types. There a few things to note: (1) Floating-point numbers can
-    be converted to integers\, (2) A JSON array can be converted to a standard
-    `std::vector<short>`\, (3) A JSON object can be converted to C++
-    associative containers such as `std::unordered_map<std::string\,
-    json>`.,operator__ValueType}
-
-    @since version 1.0.0
-    */
-    template < typename ValueType, typename std::enable_if <
-                   not std::is_pointer<ValueType>::value and
-                   not std::is_same<ValueType, detail::json_ref<json>>::value and
-                   not std::is_same<ValueType, std::string::value_type>::value and
-                   not detail::is_json<ValueType>::value
-#ifndef _MSC_VER  // fix for issue #167 operator<< ambiguity under VS2015
-                   and not std::is_same<ValueType, std::initializer_list<std::string::value_type>>::value
-#endif
-                   and not std::is_same<ValueType, typename std::string_view>::value
-                   , int >::type = 0 >
-    operator ValueType() const
-    {
-        // delegate the call to get<>() const
-        return get<ValueType>();
-    }
-
-    /// @}
-
-
-    ////////////////////
-    // element access //
-    ////////////////////
-
-    /// @name element access
-    /// Access to the JSON value.
-    /// @{
-
-    /*!
-    @brief access specified array element with bounds checking
-
-    Returns a reference to the element at specified location @a idx, with
-    bounds checking.
-
-    @param[in] idx  index of the element to access
-
-    @return reference to the element at index @a idx
-
-    @throw type_error.304 if the JSON value is not an array; in this case,
-    calling `at` with an index makes no sense. See example below.
-    @throw out_of_range.401 if the index @a idx is out of range of the array;
-    that is, `idx >= size()`. See example below.
-
-    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
-    changes in the JSON value.
-
-    @complexity Constant.
-
-    @since version 1.0.0
-
-    @liveexample{The example below shows how array elements can be read and
-    written using `at()`. It also demonstrates the different exceptions that
-    can be thrown.,at__size_type}
-    */
-    reference at(size_type idx);
-
-    /*!
-    @brief access specified array element with bounds checking
-
-    Returns a const reference to the element at specified location @a idx,
-    with bounds checking.
-
-    @param[in] idx  index of the element to access
-
-    @return const reference to the element at index @a idx
-
-    @throw type_error.304 if the JSON value is not an array; in this case,
-    calling `at` with an index makes no sense. See example below.
-    @throw out_of_range.401 if the index @a idx is out of range of the array;
-    that is, `idx >= size()`. See example below.
-
-    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
-    changes in the JSON value.
-
-    @complexity Constant.
-
-    @since version 1.0.0
-
-    @liveexample{The example below shows how array elements can be read using
-    `at()`. It also demonstrates the different exceptions that can be thrown.,
-    at__size_type_const}
-    */
-    const_reference at(size_type idx) const;
-
-    /*!
-    @brief access specified object element with bounds checking
-
-    Returns a reference to the element at with specified key @a key, with
-    bounds checking.
-
-    @param[in] key  key of the element to access
-
-    @return reference to the element at key @a key
-
-    @throw type_error.304 if the JSON value is not an object; in this case,
-    calling `at` with a key makes no sense. See example below.
-    @throw out_of_range.403 if the key @a key is is not stored in the object;
-    that is, `find(key) == end()`. See example below.
-
-    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
-    changes in the JSON value.
-
-    @complexity Logarithmic in the size of the container.
-
-    @sa @ref operator[](const typename object_t::key_type&) for unchecked
-    access by reference
-    @sa @ref value() for access by value with a default value
-
-    @since version 1.0.0
-
-    @liveexample{The example below shows how object elements can be read and
-    written using `at()`. It also demonstrates the different exceptions that
-    can be thrown.,at__object_t_key_type}
-    */
-    reference at(std::string_view key);
-
-    /*!
-    @brief access specified object element with bounds checking
-
-    Returns a const reference to the element at with specified key @a key,
-    with bounds checking.
-
-    @param[in] key  key of the element to access
-
-    @return const reference to the element at key @a key
-
-    @throw type_error.304 if the JSON value is not an object; in this case,
-    calling `at` with a key makes no sense. See example below.
-    @throw out_of_range.403 if the key @a key is is not stored in the object;
-    that is, `find(key) == end()`. See example below.
-
-    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
-    changes in the JSON value.
-
-    @complexity Logarithmic in the size of the container.
-
-    @sa @ref operator[](const typename object_t::key_type&) for unchecked
-    access by reference
-    @sa @ref value() for access by value with a default value
-
-    @since version 1.0.0
-
-    @liveexample{The example below shows how object elements can be read using
-    `at()`. It also demonstrates the different exceptions that can be thrown.,
-    at__object_t_key_type_const}
-    */
-    const_reference at(std::string_view key) const;
-
-    /*!
-    @brief access specified array element
-
-    Returns a reference to the element at specified location @a idx.
-
-    @note If @a idx is beyond the range of the array (i.e., `idx >= size()`),
-    then the array is silently filled up with `null` values to make `idx` a
-    valid reference to the last stored element.
-
-    @param[in] idx  index of the element to access
-
-    @return reference to the element at index @a idx
-
-    @throw type_error.305 if the JSON value is not an array or null; in that
-    cases, using the [] operator with an index makes no sense.
-
-    @complexity Constant if @a idx is in the range of the array. Otherwise
-    linear in `idx - size()`.
-
-    @liveexample{The example below shows how array elements can be read and
-    written using `[]` operator. Note the addition of `null`
-    values.,operatorarray__size_type}
-
-    @since version 1.0.0
-    */
-    reference operator[](size_type idx);
-
-    /*!
-    @brief access specified array element
-
-    Returns a const reference to the element at specified location @a idx.
-
-    @param[in] idx  index of the element to access
-
-    @return const reference to the element at index @a idx
-
-    @throw type_error.305 if the JSON value is not an array; in that case,
-    using the [] operator with an index makes no sense.
-
-    @complexity Constant.
-
-    @liveexample{The example below shows how array elements can be read using
-    the `[]` operator.,operatorarray__size_type_const}
-
-    @since version 1.0.0
-    */
-    const_reference operator[](size_type idx) const;
-
-    /*!
-    @brief access specified object element
-
-    Returns a reference to the element at with specified key @a key.
-
-    @note If @a key is not found in the object, then it is silently added to
-    the object and filled with a `null` value to make `key` a valid reference.
-    In case the value was `null` before, it is converted to an object.
-
-    @param[in] key  key of the element to access
-
-    @return reference to the element at key @a key
-
-    @throw type_error.305 if the JSON value is not an object or null; in that
-    cases, using the [] operator with a key makes no sense.
-
-    @complexity Logarithmic in the size of the container.
-
-    @liveexample{The example below shows how object elements can be read and
-    written using the `[]` operator.,operatorarray__key_type}
-
-    @sa @ref at(const typename object_t::key_type&) for access by reference
-    with range checking
-    @sa @ref value() for access by value with a default value
-
-    @since version 1.0.0
-    */
-    reference operator[](std::string_view key);
-
-    /*!
-    @brief read-only access specified object element
-
-    Returns a const reference to the element at with specified key @a key. No
-    bounds checking is performed.
-
-    @warning If the element with key @a key does not exist, the behavior is
-    undefined.
-
-    @param[in] key  key of the element to access
-
-    @return const reference to the element at key @a key
-
-    @pre The element with key @a key must exist. **This precondition is
-         enforced with an assertion.**
-
-    @throw type_error.305 if the JSON value is not an object; in that case,
-    using the [] operator with a key makes no sense.
-
-    @complexity Logarithmic in the size of the container.
-
-    @liveexample{The example below shows how object elements can be read using
-    the `[]` operator.,operatorarray__key_type_const}
-
-    @sa @ref at(const typename object_t::key_type&) for access by reference
-    with range checking
-    @sa @ref value() for access by value with a default value
-
-    @since version 1.0.0
-    */
-    const_reference operator[](std::string_view key) const;
-
-    /*!
-    @brief access specified object element
-
-    Returns a reference to the element at with specified key @a key.
-
-    @note If @a key is not found in the object, then it is silently added to
-    the object and filled with a `null` value to make `key` a valid reference.
-    In case the value was `null` before, it is converted to an object.
-
-    @param[in] key  key of the element to access
-
-    @return reference to the element at key @a key
-
-    @throw type_error.305 if the JSON value is not an object or null; in that
-    cases, using the [] operator with a key makes no sense.
-
-    @complexity Logarithmic in the size of the container.
-
-    @liveexample{The example below shows how object elements can be read and
-    written using the `[]` operator.,operatorarray__key_type}
-
-    @sa @ref at(const typename object_t::key_type&) for access by reference
-    with range checking
-    @sa @ref value() for access by value with a default value
-
-    @since version 1.1.0
-    */
-    template<typename T>
-    reference operator[](T* key)
-    {
-        // implicitly convert null to object
-        if (is_null())
-        {
-            m_type = value_t::object;
-            m_value = value_t::object;
-            assert_invariant();
-        }
-
-        // at only works for objects
-        if (JSON_LIKELY(is_object()))
-        {
-            return m_value.object->operator[](key);
-        }
-
-        JSON_THROW(type_error::create(305, "cannot use operator[] with", type_name()));
-    }
-
-    /*!
-    @brief read-only access specified object element
-
-    Returns a const reference to the element at with specified key @a key. No
-    bounds checking is performed.
-
-    @warning If the element with key @a key does not exist, the behavior is
-    undefined.
-
-    @param[in] key  key of the element to access
-
-    @return const reference to the element at key @a key
-
-    @pre The element with key @a key must exist. **This precondition is
-         enforced with an assertion.**
-
-    @throw type_error.305 if the JSON value is not an object; in that case,
-    using the [] operator with a key makes no sense.
-
-    @complexity Logarithmic in the size of the container.
-
-    @liveexample{The example below shows how object elements can be read using
-    the `[]` operator.,operatorarray__key_type_const}
-
-    @sa @ref at(const typename object_t::key_type&) for access by reference
-    with range checking
-    @sa @ref value() for access by value with a default value
-
-    @since version 1.1.0
-    */
-    template<typename T>
-    const_reference operator[](T* key) const
-    {
-        // at only works for objects
-        if (JSON_LIKELY(is_object()))
-        {
-            assert(m_value.object->find(key) != m_value.object->end());
-            return m_value.object->find(key)->second;
-        }
-
-        JSON_THROW(type_error::create(305, "cannot use operator[] with", type_name()));
-    }
-
-    /*!
-    @brief access specified object element with default value
-
-    Returns either a copy of an object's element at the specified key @a key
-    or a given default value if no element with key @a key exists.
-
-    The function is basically equivalent to executing
-    @code {.cpp}
-    try {
-        return at(key);
-    } catch(out_of_range) {
-        return default_value;
-    }
-    @endcode
-
-    @note Unlike @ref at(const typename object_t::key_type&), this function
-    does not throw if the given key @a key was not found.
-
-    @note Unlike @ref operator[](const typename object_t::key_type& key), this
-    function does not implicitly add an element to the position defined by @a
-    key. This function is furthermore also applicable to const objects.
-
-    @param[in] key  key of the element to access
-    @param[in] default_value  the value to return if @a key is not found
-
-    @tparam ValueType type compatible to JSON values, for instance `int` for
-    JSON integer numbers, `bool` for JSON booleans, or `std::vector` types for
-    JSON arrays. Note the type of the expected value at @a key and the default
-    value @a default_value must be compatible.
-
-    @return copy of the element at key @a key or @a default_value if @a key
-    is not found
-
-    @throw type_error.306 if the JSON value is not an object; in that case,
-    using `value()` with a key makes no sense.
-
-    @complexity Logarithmic in the size of the container.
-
-    @liveexample{The example below shows how object elements can be queried
-    with a default value.,json__value}
-
-    @sa @ref at(const typename object_t::key_type&) for access by reference
-    with range checking
-    @sa @ref operator[](const typename object_t::key_type&) for unchecked
-    access by reference
-
-    @since version 1.0.0
-    */
-    template<class ValueType, typename std::enable_if<
-                 std::is_convertible<json_t, ValueType>::value, int>::type = 0>
-    ValueType value(std::string_view key, const ValueType& default_value) const
-    {
-        // at only works for objects
-        if (JSON_LIKELY(is_object()))
-        {
-            // if key is found, return value and given default value otherwise
-            const auto it = find(key);
-            if (it != end())
-            {
-                return *it;
-            }
-
-            return default_value;
-        }
-
-        JSON_THROW(type_error::create(306, "cannot use value() with", type_name()));
-    }
-
-    /*!
-    @brief overload for a default value of type const char*
-    @copydoc json::value(const typename object_t::key_type&, ValueType) const
-    */
-    std::string value(std::string_view key, const char* default_value) const
-    {
-        return value(key, std::string(default_value));
-    }
-
-    /*!
-    @brief access specified object element via JSON Pointer with default value
-
-    Returns either a copy of an object's element at the specified key @a key
-    or a given default value if no element with key @a key exists.
-
-    The function is basically equivalent to executing
-    @code {.cpp}
-    try {
-        return at(ptr);
-    } catch(out_of_range) {
-        return default_value;
-    }
-    @endcode
-
-    @note Unlike @ref at(const json_pointer&), this function does not throw
-    if the given key @a key was not found.
-
-    @param[in] ptr  a JSON pointer to the element to access
-    @param[in] default_value  the value to return if @a ptr found no value
-
-    @tparam ValueType type compatible to JSON values, for instance `int` for
-    JSON integer numbers, `bool` for JSON booleans, or `std::vector` types for
-    JSON arrays. Note the type of the expected value at @a key and the default
-    value @a default_value must be compatible.
-
-    @return copy of the element at key @a key or @a default_value if @a key
-    is not found
-
-    @throw type_error.306 if the JSON value is not an object; in that case,
-    using `value()` with a key makes no sense.
-
-    @complexity Logarithmic in the size of the container.
-
-    @liveexample{The example below shows how object elements can be queried
-    with a default value.,json__value_ptr}
-
-    @sa @ref operator[](const json_pointer&) for unchecked access by reference
-
-    @since version 2.0.2
-    */
-    template<class ValueType, typename std::enable_if<
-                 std::is_convertible<json_t, ValueType>::value, int>::type = 0>
-    ValueType value(const json_pointer& ptr, const ValueType& default_value) const
-    {
-        // at only works for objects
-        if (JSON_LIKELY(is_object()))
-        {
-            // if pointer resolves a value, return it or use default value
-            JSON_TRY
-            {
-                return ptr.get_checked(this);
-            }
-            JSON_CATCH (out_of_range&)
-            {
-                return default_value;
-            }
-        }
-
-        JSON_THROW(type_error::create(306, "cannot use value() with", type_name()));
-    }
-
-    /*!
-    @brief overload for a default value of type const char*
-    @copydoc json::value(const json_pointer&, ValueType) const
-    */
-    std::string value(const json_pointer& ptr, const char* default_value) const
-    {
-        return value(ptr, std::string(default_value));
-    }
-
-    /*!
-    @brief access the first element
-
-    Returns a reference to the first element in the container. For a JSON
-    container `c`, the expression `c.front()` is equivalent to `*c.begin()`.
-
-    @return In case of a structured type (array or object), a reference to the
-    first element is returned. In case of number, string, or boolean values, a
-    reference to the value is returned.
-
-    @complexity Constant.
-
-    @pre The JSON value must not be `null` (would throw `std::out_of_range`)
-    or an empty array or object (undefined behavior, **guarded by
-    assertions**).
-    @post The JSON value remains unchanged.
-
-    @throw invalid_iterator.214 when called on `null` value
-
-    @liveexample{The following code shows an example for `front()`.,front}
-
-    @sa @ref back() -- access the last element
-
-    @since version 1.0.0
-    */
-    reference front()
-    {
-        return *begin();
-    }
-
-    /*!
-    @copydoc json::front()
-    */
-    const_reference front() const
-    {
-        return *cbegin();
-    }
-
-    /*!
-    @brief access the last element
-
-    Returns a reference to the last element in the container. For a JSON
-    container `c`, the expression `c.back()` is equivalent to
-    @code {.cpp}
-    auto tmp = c.end();
-    --tmp;
-    return *tmp;
-    @endcode
-
-    @return In case of a structured type (array or object), a reference to the
-    last element is returned. In case of number, string, or boolean values, a
-    reference to the value is returned.
-
-    @complexity Constant.
-
-    @pre The JSON value must not be `null` (would throw `std::out_of_range`)
-    or an empty array or object (undefined behavior, **guarded by
-    assertions**).
-    @post The JSON value remains unchanged.
-
-    @throw invalid_iterator.214 when called on a `null` value. See example
-    below.
-
-    @liveexample{The following code shows an example for `back()`.,back}
-
-    @sa @ref front() -- access the first element
-
-    @since version 1.0.0
-    */
-    reference back()
-    {
-        auto tmp = end();
-        --tmp;
-        return *tmp;
-    }
-
-    /*!
-    @copydoc json::back()
-    */
-    const_reference back() const
-    {
-        auto tmp = cend();
-        --tmp;
-        return *tmp;
-    }
-
-    /*!
-    @brief remove element given an iterator
-
-    Removes the element specified by iterator @a pos. The iterator @a pos must
-    be valid and dereferenceable. Thus the `end()` iterator (which is valid,
-    but is not dereferenceable) cannot be used as a value for @a pos.
-
-    If called on a primitive type other than `null`, the resulting JSON value
-    will be `null`.
-
-    @param[in] pos iterator to the element to remove
-
-    @tparam IteratorType an @ref iterator or @ref const_iterator
-
-    @post Invalidates iterators and references at or after the point of the
-    erase, including the `end()` iterator.
-
-    @throw type_error.307 if called on a `null` value; example: `"cannot use
-    erase() with null"`
-    @throw invalid_iterator.202 if called on an iterator which does not belong
-    to the current JSON value; example: `"iterator does not fit current
-    value"`
-    @throw invalid_iterator.205 if called on a primitive type with invalid
-    iterator (i.e., any iterator which is not `begin()`); example: `"iterator
-    out of range"`
-
-    @complexity The complexity depends on the type:
-    - objects: amortized constant
-    - arrays: linear in distance between @a pos and the end of the container
-    - strings: linear in the length of the string
-    - other types: constant
-
-    @liveexample{The example shows the result of `erase()` for different JSON
-    types.,erase__IteratorType}
-
-    @sa @ref erase(IteratorType, IteratorType) -- removes the elements in
-    the given range
-    @sa @ref erase(std::string_view) -- removes the element
-    from an object at the given key
-    @sa @ref erase(const size_type) -- removes the element from an array at
-    the given index
-
-    @since version 1.0.0
-    */
-    template<class IteratorType, typename std::enable_if<
-                 std::is_same<IteratorType, typename json_t::iterator>::value or
-                 std::is_same<IteratorType, typename json_t::const_iterator>::value, int>::type
-             = 0>
-    void erase(IteratorType pos)
-    {
-        // make sure iterator fits the current value
-        if (JSON_UNLIKELY(this != pos.m_object))
-        {
-            JSON_THROW(invalid_iterator::create(202, "iterator does not fit current value"));
-        }
-
-        switch (m_type)
-        {
-            case value_t::boolean:
-            case value_t::number_float:
-            case value_t::number_integer:
-            case value_t::number_unsigned:
-            case value_t::string:
-            {
-                if (JSON_UNLIKELY(not pos.m_it.primitive_iterator.is_begin()))
-                {
-                    JSON_THROW(invalid_iterator::create(205, "iterator out of range"));
-                }
-
-                if (is_string())
-                {
-                    std::allocator<std::string> alloc;
-					std::allocator_traits<decltype(alloc)>::destroy(alloc, m_value.string);
-					std::allocator_traits<decltype(alloc)>::deallocate(alloc, m_value.string, 1);
-                    m_value.string = nullptr;
-                }
-
-                m_type = value_t::null;
-                assert_invariant();
-                break;
-            }
-
-            case value_t::object:
-            {
-                m_value.object->erase(pos.m_it.object_iterator);
-                break;
-            }
-
-            case value_t::array:
-            {
-                m_value.array->erase(pos.m_it.array_iterator);
-                break;
-            }
-
-            default:
-                JSON_THROW(type_error::create(307, "cannot use erase() with", type_name()));
-        }
-    }
-
-    /*!
-    @brief remove elements given an iterator range
-
-    Removes the element specified by the range `[first; last)`. The iterator
-    @a first does not need to be dereferenceable if `first == last`: erasing
-    an empty range is a no-op.
-
-    If called on a primitive type other than `null`, the resulting JSON value
-    will be `null`.
-
-    @param[in] first iterator to the beginning of the range to remove
-    @param[in] last iterator past the end of the range to remove
-    @return Iterator following the last removed element. If the iterator @a
-    second refers to the last element, the `end()` iterator is returned.
-
-    @tparam IteratorType an @ref iterator or @ref const_iterator
-
-    @post Invalidates iterators and references at or after the point of the
-    erase, including the `end()` iterator.
-
-    @throw type_error.307 if called on a `null` value; example: `"cannot use
-    erase() with null"`
-    @throw invalid_iterator.203 if called on iterators which does not belong
-    to the current JSON value; example: `"iterators do not fit current value"`
-    @throw invalid_iterator.204 if called on a primitive type with invalid
-    iterators (i.e., if `first != begin()` and `last != end()`); example:
-    `"iterators out of range"`
-
-    @complexity The complexity depends on the type:
-    - objects: `log(size()) + std::distance(first, last)`
-    - arrays: linear in the distance between @a first and @a last, plus linear
-      in the distance between @a last and end of the container
-    - strings: linear in the length of the string
-    - other types: constant
-
-    @liveexample{The example shows the result of `erase()` for different JSON
-    types.,erase__IteratorType_IteratorType}
-
-    @sa @ref erase(IteratorType) -- removes the element at a given position
-    @sa @ref erase(const typename object_t::key_type&) -- removes the element
-    from an object at the given key
-    @sa @ref erase(const size_type) -- removes the element from an array at
-    the given index
-
-    @since version 1.0.0
-    */
-    template<class IteratorType, typename std::enable_if<
-                 std::is_same<IteratorType, typename json_t::iterator>::value or
-                 std::is_same<IteratorType, typename json_t::const_iterator>::value, int>::type
-             = 0>
-    IteratorType erase(IteratorType first, IteratorType last)
-    {
-        // make sure iterator fits the current value
-        if (JSON_UNLIKELY(this != first.m_object or this != last.m_object))
-        {
-            JSON_THROW(invalid_iterator::create(203, "iterators do not fit current value"));
-        }
-
-        IteratorType result = end();
-
-        switch (m_type)
-        {
-            case value_t::boolean:
-            case value_t::number_float:
-            case value_t::number_integer:
-            case value_t::number_unsigned:
-            case value_t::string:
-            {
-                if (JSON_LIKELY(not first.m_it.primitive_iterator.is_begin()
-                                or not last.m_it.primitive_iterator.is_end()))
-                {
-                    JSON_THROW(invalid_iterator::create(204, "iterators out of range"));
-                }
-
-                if (is_string())
-                {
-                    std::allocator<std::string> alloc;
-					std::allocator_traits<decltype(alloc)>::destroy(alloc, m_value.string);
-					std::allocator_traits<decltype(alloc)>::deallocate(alloc, m_value.string, 1);
-                    m_value.string = nullptr;
-                }
-
-                m_type = value_t::null;
-                assert_invariant();
-                break;
-            }
-
-            case value_t::array:
-            {
-                result.m_it.array_iterator = m_value.array->erase(first.m_it.array_iterator,
-                                             last.m_it.array_iterator);
-                break;
-            }
-
-            default:
-                JSON_THROW(type_error::create(307, "cannot use erase() with", type_name()));
-        }
-
-        return result;
-    }
-
-    /*!
-    @brief remove element from a JSON object given a key
-
-    Removes elements from a JSON object with the key value @a key.
-
-    @param[in] key value of the elements to remove
-
-    @return Number of elements removed. If @a ObjectType is the default
-    `std::map` type, the return value will always be `0` (@a key was not
-    found) or `1` (@a key was found).
-
-    @post References and iterators to the erased elements are invalidated.
-    Other references and iterators are not affected.
-
-    @throw type_error.307 when called on a type other than JSON object;
-    example: `"cannot use erase() with null"`
-
-    @complexity `log(size()) + count(key)`
-
-    @liveexample{The example shows the effect of `erase()`.,erase__key_type}
-
-    @sa @ref erase(IteratorType) -- removes the element at a given position
-    @sa @ref erase(IteratorType, IteratorType) -- removes the elements in
-    the given range
-    @sa @ref erase(const size_type) -- removes the element from an array at
-    the given index
-
-    @since version 1.0.0
-    */
-    size_type erase(std::string_view key);
-
-    /*!
-    @brief remove element from a JSON array given an index
-
-    Removes element from a JSON array at the index @a idx.
-
-    @param[in] idx index of the element to remove
-
-    @throw type_error.307 when called on a type other than JSON object;
-    example: `"cannot use erase() with null"`
-    @throw out_of_range.401 when `idx >= size()`; example: `"array index 17
-    is out of range"`
-
-    @complexity Linear in distance between @a idx and the end of the container.
-
-    @liveexample{The example shows the effect of `erase()`.,erase__size_type}
-
-    @sa @ref erase(IteratorType) -- removes the element at a given position
-    @sa @ref erase(IteratorType, IteratorType) -- removes the elements in
-    the given range
-    @sa @ref erase(const typename object_t::key_type&) -- removes the element
-    from an object at the given key
-
-    @since version 1.0.0
-    */
-    void erase(const size_type idx);
-
-    /// @}
-
-
-    ////////////
-    // lookup //
-    ////////////
-
-    /// @name lookup
-    /// @{
-
-    /*!
-    @brief find an element in a JSON object
-
-    Finds an element in a JSON object with key equivalent to @a key. If the
-    element is not found or the JSON value is not an object, end() is
-    returned.
-
-    @note This method always returns @ref end() when executed on a JSON type
-          that is not an object.
-
-    @param[in] key key value of the element to search for.
-
-    @return Iterator to an element with key equivalent to @a key. If no such
-    element is found or the JSON value is not an object, past-the-end (see
-    @ref end()) iterator is returned.
-
-    @complexity Logarithmic in the size of the JSON object.
-
-    @liveexample{The example shows how `find()` is used.,find__key_type}
-
-    @since version 1.0.0
-    */
-    iterator find(std::string_view key);
-
-    /*!
-    @brief find an element in a JSON object
-    @copydoc find(KeyT&&)
-    */
-    const_iterator find(std::string_view key) const;
-
-    /*!
-    @brief returns the number of occurrences of a key in a JSON object
-
-    Returns the number of elements with key @a key. If ObjectType is the
-    default `std::map` type, the return value will always be `0` (@a key was
-    not found) or `1` (@a key was found).
-
-    @note This method always returns `0` when executed on a JSON type that is
-          not an object.
-
-    @param[in] key key value of the element to count
-
-    @return Number of elements with key @a key. If the JSON value is not an
-    object, the return value will be `0`.
-
-    @complexity Logarithmic in the size of the JSON object.
-
-    @liveexample{The example shows how `count()` is used.,count}
-
-    @since version 1.0.0
-    */
-    size_type count(std::string_view key) const;
-
-    /// @}
-
-
-    ///////////////
-    // iterators //
-    ///////////////
-
-    /// @name iterators
-    /// @{
-
-    /*!
-    @brief returns an iterator to the first element
-
-    Returns an iterator to the first element.
-
-    @image html range-begin-end.svg "Illustration from cppreference.com"
-
-    @return iterator to the first element
-
-    @complexity Constant.
-
-    @requirement This function helps `json` satisfying the
-    [Container](http://en.cppreference.com/w/cpp/concept/Container)
-    requirements:
-    - The complexity is constant.
-
-    @liveexample{The following code shows an example for `begin()`.,begin}
-
-    @sa @ref cbegin() -- returns a const iterator to the beginning
-    @sa @ref end() -- returns an iterator to the end
-    @sa @ref cend() -- returns a const iterator to the end
-
-    @since version 1.0.0
-    */
-    iterator begin() noexcept
-    {
-        iterator result(this);
-        result.set_begin();
-        return result;
-    }
-
-    /*!
-    @copydoc json::cbegin()
-    */
-    const_iterator begin() const noexcept
-    {
-        return cbegin();
-    }
-
-    /*!
-    @brief returns a const iterator to the first element
-
-    Returns a const iterator to the first element.
-
-    @image html range-begin-end.svg "Illustration from cppreference.com"
-
-    @return const iterator to the first element
-
-    @complexity Constant.
-
-    @requirement This function helps `json` satisfying the
-    [Container](http://en.cppreference.com/w/cpp/concept/Container)
-    requirements:
-    - The complexity is constant.
-    - Has the semantics of `const_cast<const json&>(*this).begin()`.
-
-    @liveexample{The following code shows an example for `cbegin()`.,cbegin}
-
-    @sa @ref begin() -- returns an iterator to the beginning
-    @sa @ref end() -- returns an iterator to the end
-    @sa @ref cend() -- returns a const iterator to the end
-
-    @since version 1.0.0
-    */
-    const_iterator cbegin() const noexcept
-    {
-        const_iterator result(this);
-        result.set_begin();
-        return result;
-    }
-
-    /*!
-    @brief returns an iterator to one past the last element
-
-    Returns an iterator to one past the last element.
-
-    @image html range-begin-end.svg "Illustration from cppreference.com"
-
-    @return iterator one past the last element
-
-    @complexity Constant.
-
-    @requirement This function helps `json` satisfying the
-    [Container](http://en.cppreference.com/w/cpp/concept/Container)
-    requirements:
-    - The complexity is constant.
-
-    @liveexample{The following code shows an example for `end()`.,end}
-
-    @sa @ref cend() -- returns a const iterator to the end
-    @sa @ref begin() -- returns an iterator to the beginning
-    @sa @ref cbegin() -- returns a const iterator to the beginning
-
-    @since version 1.0.0
-    */
-    iterator end() noexcept
-    {
-        iterator result(this);
-        result.set_end();
-        return result;
-    }
-
-    /*!
-    @copydoc json::cend()
-    */
-    const_iterator end() const noexcept
-    {
-        return cend();
-    }
-
-    /*!
-    @brief returns a const iterator to one past the last element
-
-    Returns a const iterator to one past the last element.
-
-    @image html range-begin-end.svg "Illustration from cppreference.com"
-
-    @return const iterator one past the last element
-
-    @complexity Constant.
-
-    @requirement This function helps `json` satisfying the
-    [Container](http://en.cppreference.com/w/cpp/concept/Container)
-    requirements:
-    - The complexity is constant.
-    - Has the semantics of `const_cast<const json&>(*this).end()`.
-
-    @liveexample{The following code shows an example for `cend()`.,cend}
-
-    @sa @ref end() -- returns an iterator to the end
-    @sa @ref begin() -- returns an iterator to the beginning
-    @sa @ref cbegin() -- returns a const iterator to the beginning
-
-    @since version 1.0.0
-    */
-    const_iterator cend() const noexcept
-    {
-        const_iterator result(this);
-        result.set_end();
-        return result;
-    }
-
-    /*!
-    @brief returns an iterator to the reverse-beginning
-
-    Returns an iterator to the reverse-beginning; that is, the last element.
-
-    @image html range-rbegin-rend.svg "Illustration from cppreference.com"
-
-    @complexity Constant.
-
-    @requirement This function helps `json` satisfying the
-    [ReversibleContainer](http://en.cppreference.com/w/cpp/concept/ReversibleContainer)
-    requirements:
-    - The complexity is constant.
-    - Has the semantics of `reverse_iterator(end())`.
-
-    @liveexample{The following code shows an example for `rbegin()`.,rbegin}
-
-    @sa @ref crbegin() -- returns a const reverse iterator to the beginning
-    @sa @ref rend() -- returns a reverse iterator to the end
-    @sa @ref crend() -- returns a const reverse iterator to the end
-
-    @since version 1.0.0
-    */
-    reverse_iterator rbegin() noexcept
-    {
-        return reverse_iterator(end());
-    }
-
-    /*!
-    @copydoc json::crbegin()
-    */
-    const_reverse_iterator rbegin() const noexcept
-    {
-        return crbegin();
-    }
-
-    /*!
-    @brief returns an iterator to the reverse-end
-
-    Returns an iterator to the reverse-end; that is, one before the first
-    element.
-
-    @image html range-rbegin-rend.svg "Illustration from cppreference.com"
-
-    @complexity Constant.
-
-    @requirement This function helps `json` satisfying the
-    [ReversibleContainer](http://en.cppreference.com/w/cpp/concept/ReversibleContainer)
-    requirements:
-    - The complexity is constant.
-    - Has the semantics of `reverse_iterator(begin())`.
-
-    @liveexample{The following code shows an example for `rend()`.,rend}
-
-    @sa @ref crend() -- returns a const reverse iterator to the end
-    @sa @ref rbegin() -- returns a reverse iterator to the beginning
-    @sa @ref crbegin() -- returns a const reverse iterator to the beginning
-
-    @since version 1.0.0
-    */
-    reverse_iterator rend() noexcept
-    {
-        return reverse_iterator(begin());
-    }
-
-    /*!
-    @copydoc json::crend()
-    */
-    const_reverse_iterator rend() const noexcept
-    {
-        return crend();
-    }
-
-    /*!
-    @brief returns a const reverse iterator to the last element
-
-    Returns a const iterator to the reverse-beginning; that is, the last
-    element.
-
-    @image html range-rbegin-rend.svg "Illustration from cppreference.com"
-
-    @complexity Constant.
-
-    @requirement This function helps `json` satisfying the
-    [ReversibleContainer](http://en.cppreference.com/w/cpp/concept/ReversibleContainer)
-    requirements:
-    - The complexity is constant.
-    - Has the semantics of `const_cast<const json&>(*this).rbegin()`.
-
-    @liveexample{The following code shows an example for `crbegin()`.,crbegin}
-
-    @sa @ref rbegin() -- returns a reverse iterator to the beginning
-    @sa @ref rend() -- returns a reverse iterator to the end
-    @sa @ref crend() -- returns a const reverse iterator to the end
-
-    @since version 1.0.0
-    */
-    const_reverse_iterator crbegin() const noexcept
-    {
-        return const_reverse_iterator(cend());
-    }
-
-    /*!
-    @brief returns a const reverse iterator to one before the first
-
-    Returns a const reverse iterator to the reverse-end; that is, one before
-    the first element.
-
-    @image html range-rbegin-rend.svg "Illustration from cppreference.com"
-
-    @complexity Constant.
-
-    @requirement This function helps `json` satisfying the
-    [ReversibleContainer](http://en.cppreference.com/w/cpp/concept/ReversibleContainer)
-    requirements:
-    - The complexity is constant.
-    - Has the semantics of `const_cast<const json&>(*this).rend()`.
-
-    @liveexample{The following code shows an example for `crend()`.,crend}
-
-    @sa @ref rend() -- returns a reverse iterator to the end
-    @sa @ref rbegin() -- returns a reverse iterator to the beginning
-    @sa @ref crbegin() -- returns a const reverse iterator to the beginning
-
-    @since version 1.0.0
-    */
-    const_reverse_iterator crend() const noexcept
-    {
-        return const_reverse_iterator(cbegin());
-    }
-
-  public:
-    /*!
-    @brief helper to access iterator member functions in range-based for
-
-    This function allows to access @ref iterator::key() and @ref
-    iterator::value() during range-based for loops. In these loops, a
-    reference to the JSON values is returned, so there is no access to the
-    underlying iterator.
-
-    For loop without `items()` function:
-
-    @code{cpp}
-    for (auto it = j_object.begin(); it != j_object.end(); ++it)
-    {
-        std::cout << "key: " << it.key() << ", value:" << it.value() << '\n';
-    }
-    @endcode
-
-    Range-based for loop without `items()` function:
-
-    @code{cpp}
-    for (auto it : j_object)
-    {
-        // "it" is of type json::reference and has no key() member
-        std::cout << "value: " << it << '\n';
-    }
-    @endcode
-
-    Range-based for loop with `items()` function:
-
-    @code{cpp}
-    for (auto it : j_object.items())
-    {
-        std::cout << "key: " << it.key() << ", value:" << it.value() << '\n';
-    }
-    @endcode
-
-    @note When iterating over an array, `key()` will return the index of the
-          element as string (see example). For primitive types (e.g., numbers),
-          `key()` returns an empty string.
-
-    @return iteration proxy object wrapping @a ref with an interface to use in
-            range-based for loops
-
-    @liveexample{The following code shows how the function is used.,items}
-
-    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
-    changes in the JSON value.
-
-    @complexity Constant.
-
-    @since version 3.x.x.
-    */
-    iteration_proxy<iterator> items() noexcept
-    {
-        return iteration_proxy<iterator>(*this);
-    }
-
-    /*!
-    @copydoc items()
-    */
-    iteration_proxy<const_iterator> items() const noexcept
-    {
-        return iteration_proxy<const_iterator>(*this);
-    }
-
-    /// @}
-
-
-    //////////////
-    // capacity //
-    //////////////
-
-    /// @name capacity
-    /// @{
-
-    /*!
-    @brief checks whether the container is empty.
-
-    Checks if a JSON value has no elements (i.e. whether its @ref size is `0`).
-
-    @return The return value depends on the different types and is
-            defined as follows:
-            Value type  | return value
-            ----------- | -------------
-            null        | `true`
-            boolean     | `false`
-            string      | `false`
-            number      | `false`
-            object      | result of function `object_t::empty()`
-            array       | result of function `array_t::empty()`
-
-    @liveexample{The following code uses `empty()` to check if a JSON
-    object contains any elements.,empty}
-
-    @complexity Constant, as long as @ref array_t and @ref object_t satisfy
-    the Container concept; that is, their `empty()` functions have constant
-    complexity.
-
-    @iterators No changes.
-
-    @exceptionsafety No-throw guarantee: this function never throws exceptions.
-
-    @note This function does not return whether a string stored as JSON value
-    is empty - it returns whether the JSON container itself is empty which is
-    false in the case of a string.
-
-    @requirement This function helps `json` satisfying the
-    [Container](http://en.cppreference.com/w/cpp/concept/Container)
-    requirements:
-    - The complexity is constant.
-    - Has the semantics of `begin() == end()`.
-
-    @sa @ref size() -- returns the number of elements
-
-    @since version 1.0.0
-    */
-    bool empty() const noexcept;
-
-    /*!
-    @brief returns the number of elements
-
-    Returns the number of elements in a JSON value.
-
-    @return The return value depends on the different types and is
-            defined as follows:
-            Value type  | return value
-            ----------- | -------------
-            null        | `0`
-            boolean     | `1`
-            string      | `1`
-            number      | `1`
-            object      | result of function object_t::size()
-            array       | result of function array_t::size()
-
-    @liveexample{The following code calls `size()` on the different value
-    types.,size}
-
-    @complexity Constant, as long as @ref array_t and @ref object_t satisfy
-    the Container concept; that is, their size() functions have constant
-    complexity.
-
-    @iterators No changes.
-
-    @exceptionsafety No-throw guarantee: this function never throws exceptions.
-
-    @note This function does not return the length of a string stored as JSON
-    value - it returns the number of elements in the JSON value which is 1 in
-    the case of a string.
-
-    @requirement This function helps `json` satisfying the
-    [Container](http://en.cppreference.com/w/cpp/concept/Container)
-    requirements:
-    - The complexity is constant.
-    - Has the semantics of `std::distance(begin(), end())`.
-
-    @sa @ref empty() -- checks whether the container is empty
-    @sa @ref max_size() -- returns the maximal number of elements
-
-    @since version 1.0.0
-    */
-    size_type size() const noexcept;
-
-    /*!
-    @brief returns the maximum possible number of elements
-
-    Returns the maximum number of elements a JSON value is able to hold due to
-    system or library implementation limitations, i.e. `std::distance(begin(),
-    end())` for the JSON value.
-
-    @return The return value depends on the different types and is
-            defined as follows:
-            Value type  | return value
-            ----------- | -------------
-            null        | `0` (same as `size()`)
-            boolean     | `1` (same as `size()`)
-            string      | `1` (same as `size()`)
-            number      | `1` (same as `size()`)
-            object      | result of function `object_t::max_size()`
-            array       | result of function `array_t::max_size()`
-
-    @liveexample{The following code calls `max_size()` on the different value
-    types. Note the output is implementation specific.,max_size}
-
-    @complexity Constant, as long as @ref array_t and @ref object_t satisfy
-    the Container concept; that is, their `max_size()` functions have constant
-    complexity.
-
-    @iterators No changes.
-
-    @exceptionsafety No-throw guarantee: this function never throws exceptions.
-
-    @requirement This function helps `json` satisfying the
-    [Container](http://en.cppreference.com/w/cpp/concept/Container)
-    requirements:
-    - The complexity is constant.
-    - Has the semantics of returning `b.size()` where `b` is the largest
-      possible JSON value.
-
-    @sa @ref size() -- returns the number of elements
-
-    @since version 1.0.0
-    */
-    size_type max_size() const noexcept;
-
-    /// @}
-
-
-    ///////////////
-    // modifiers //
-    ///////////////
-
-    /// @name modifiers
-    /// @{
-
-    /*!
-    @brief clears the contents
-
-    Clears the content of a JSON value and resets it to the default value as
-    if @ref json(value_t) would have been called with the current value
-    type from @ref type():
-
-    Value type  | initial value
-    ----------- | -------------
-    null        | `null`
-    boolean     | `false`
-    string      | `""`
-    number      | `0`
-    object      | `{}`
-    array       | `[]`
-
-    @post Has the same effect as calling
-    @code {.cpp}
-    *this = json(type());
-    @endcode
-
-    @liveexample{The example below shows the effect of `clear()` to different
-    JSON types.,clear}
-
-    @complexity Linear in the size of the JSON value.
-
-    @iterators All iterators, pointers and references related to this container
-               are invalidated.
-
-    @exceptionsafety No-throw guarantee: this function never throws exceptions.
-
-    @sa @ref json(value_t) -- constructor that creates an object with the
-        same value than calling `clear()`
-
-    @since version 1.0.0
-    */
-    void clear() noexcept;
-
-    /*!
-    @brief add an object to an array
-
-    Appends the given element @a val to the end of the JSON value. If the
-    function is called on a JSON null value, an empty array is created before
-    appending @a val.
-
-    @param[in] val the value to add to the JSON array
-
-    @throw type_error.308 when called on a type other than JSON array or
-    null; example: `"cannot use push_back() with number"`
-
-    @complexity Amortized constant.
-
-    @liveexample{The example shows how `push_back()` and `+=` can be used to
-    add elements to a JSON array. Note how the `null` value was silently
-    converted to a JSON array.,push_back}
-
-    @since version 1.0.0
-    */
-    void push_back(json&& val);
-
-    /*!
-    @brief add an object to an array
-    @copydoc push_back(json&&)
-    */
-    reference operator+=(json&& val)
-    {
-        push_back(std::move(val));
-        return *this;
-    }
-
-    /*!
-    @brief add an object to an array
-    @copydoc push_back(json&&)
-    */
-    void push_back(const json& val);
-
-    /*!
-    @brief add an object to an array
-    @copydoc push_back(json&&)
-    */
-    reference operator+=(const json& val)
-    {
-        push_back(val);
-        return *this;
-    }
-
-    /*!
-    @brief add an object to an object
-
-    Inserts the given element @a val to the JSON object. If the function is
-    called on a JSON null value, an empty object is created before inserting
-    @a val.
-
-    @param[in] val the value to add to the JSON object
-
-    @throw type_error.308 when called on a type other than JSON object or
-    null; example: `"cannot use push_back() with number"`
-
-    @complexity Logarithmic in the size of the container, O(log(`size()`)).
-
-    @liveexample{The example shows how `push_back()` and `+=` can be used to
-    add elements to a JSON object. Note how the `null` value was silently
-    converted to a JSON object.,push_back__object_t__value}
-
-    @since version 1.0.0
-    */
-    template<typename T, typename U>
-    void push_back(const std::pair<T, U>& val)
-    {
-        // push_back only works for null objects or objects
-        if (JSON_UNLIKELY(not(is_null() or is_object())))
-        {
-            JSON_THROW(type_error::create(308, "cannot use push_back() with", type_name()));
-        }
-
-        // transform null object into an object
-        if (is_null())
-        {
-            m_type = value_t::object;
-            m_value = value_t::object;
-            assert_invariant();
-        }
-
-        // add element to array
-        m_value.object->try_emplace(val.first, std::move(val.second));
-    }
-
-    /*!
-    @brief add an object to an object
-    @copydoc push_back(const typename object_t::value_type&)
-    */
-    template<typename T, typename U>
-    reference operator+=(const std::pair<T, U>& val)
-    {
-        push_back(val);
-        return *this;
-    }
-
-    /*!
-    @brief add an object to an object
-
-    This function allows to use `push_back` with an initializer list. In case
-
-    1. the current value is an object,
-    2. the initializer list @a init contains only two elements, and
-    3. the first element of @a init is a string,
-
-    @a init is converted into an object element and added using
-    @ref push_back(const typename object_t::value_type&). Otherwise, @a init
-    is converted to a JSON value and added using @ref push_back(json&&).
-
-    @param[in] init  an initializer list
-
-    @complexity Linear in the size of the initializer list @a init.
-
-    @note This function is required to resolve an ambiguous overload error,
-          because pairs like `{"key", "value"}` can be both interpreted as
-          `object_t::value_type` or `std::initializer_list<json>`, see
-          https://github.com/nlohmann/json/issues/235 for more information.
-
-    @liveexample{The example shows how initializer lists are treated as
-    objects when possible.,push_back__initializer_list}
-    */
-    void push_back(initializer_list_t init);
-
-    /*!
-    @brief add an object to an object
-    @copydoc push_back(initializer_list_t)
-    */
-    reference operator+=(initializer_list_t init)
-    {
-        push_back(init);
-        return *this;
-    }
-
-    /*!
-    @brief add an object to an array
-
-    Creates a JSON value from the passed parameters @a args to the end of the
-    JSON value. If the function is called on a JSON null value, an empty array
-    is created before appending the value created from @a args.
-
-    @param[in] args arguments to forward to a constructor of @ref json
-    @tparam Args compatible types to create a @ref json object
-
-    @throw type_error.311 when called on a type other than JSON array or
-    null; example: `"cannot use emplace_back() with number"`
-
-    @complexity Amortized constant.
-
-    @liveexample{The example shows how `push_back()` can be used to add
-    elements to a JSON array. Note how the `null` value was silently converted
-    to a JSON array.,emplace_back}
-
-    @since version 2.0.8
-    */
-    template<class... Args>
-    void emplace_back(Args&& ... args)
-    {
-        // emplace_back only works for null objects or arrays
-        if (JSON_UNLIKELY(not(is_null() or is_array())))
-        {
-            JSON_THROW(type_error::create(311, "cannot use emplace_back() with", type_name()));
-        }
-
-        // transform null object into an array
-        if (is_null())
-        {
-            m_type = value_t::array;
-            m_value = value_t::array;
-            assert_invariant();
-        }
-
-        // add element to array (perfect forwarding)
-        m_value.array->emplace_back(std::forward<Args>(args)...);
-    }
-
-    /*!
-    @brief add an object to an object if key does not exist
-
-    Inserts a new element into a JSON object constructed in-place with the
-    given @a args if there is no element with the key in the container. If the
-    function is called on a JSON null value, an empty object is created before
-    appending the value created from @a args.
-
-    @param[in] args arguments to forward to a constructor of @ref json
-    @tparam Args compatible types to create a @ref json object
-
-    @return a pair consisting of an iterator to the inserted element, or the
-            already-existing element if no insertion happened, and a bool
-            denoting whether the insertion took place.
-
-    @throw type_error.311 when called on a type other than JSON object or
-    null; example: `"cannot use emplace() with number"`
-
-    @complexity Logarithmic in the size of the container, O(log(`size()`)).
-
-    @liveexample{The example shows how `emplace()` can be used to add elements
-    to a JSON object. Note how the `null` value was silently converted to a
-    JSON object. Further note how no value is added if there was already one
-    value stored with the same key.,emplace}
-
-    @since version 2.0.8
-    */
-    template<class... Args>
-    std::pair<iterator, bool> emplace(std::string_view key, Args&& ... args)
-    {
-        // emplace only works for null objects or arrays
-        if (JSON_UNLIKELY(not(is_null() or is_object())))
-        {
-            JSON_THROW(type_error::create(311, "cannot use emplace() with", type_name()));
-        }
-
-        // transform null object into an object
-        if (is_null())
-        {
-            m_type = value_t::object;
-            m_value = value_t::object;
-            assert_invariant();
-        }
-
-        // add element to array (perfect forwarding)
-        auto res = m_value.object->try_emplace(key, std::forward<Args>(args)...);
-        // create result iterator and set iterator to the result of emplace
-        auto it = begin();
-        it.m_it.object_iterator = res.first;
-
-        // return pair of iterator and boolean
-        return {it, res.second};
-    }
-
-    /*!
-    @brief inserts element
-
-    Inserts element @a val before iterator @a pos.
-
-    @param[in] pos iterator before which the content will be inserted; may be
-    the end() iterator
-    @param[in] val element to insert
-    @return iterator pointing to the inserted @a val.
-
-    @throw type_error.309 if called on JSON values other than arrays;
-    example: `"cannot use insert() with string"`
-    @throw invalid_iterator.202 if @a pos is not an iterator of *this;
-    example: `"iterator does not fit current value"`
-
-    @complexity Constant plus linear in the distance between @a pos and end of
-    the container.
-
-    @liveexample{The example shows how `insert()` is used.,insert}
-
-    @since version 1.0.0
-    */
-    iterator insert(const_iterator pos, const json& val);
-
-    /*!
-    @brief inserts element
-    @copydoc insert(const_iterator, const json&)
-    */
-    iterator insert(const_iterator pos, json&& val)
-    {
-        return insert(pos, val);
-    }
-
-    /*!
-    @brief inserts elements
-
-    Inserts @a cnt copies of @a val before iterator @a pos.
-
-    @param[in] pos iterator before which the content will be inserted; may be
-    the end() iterator
-    @param[in] cnt number of copies of @a val to insert
-    @param[in] val element to insert
-    @return iterator pointing to the first element inserted, or @a pos if
-    `cnt==0`
-
-    @throw type_error.309 if called on JSON values other than arrays; example:
-    `"cannot use insert() with string"`
-    @throw invalid_iterator.202 if @a pos is not an iterator of *this;
-    example: `"iterator does not fit current value"`
-
-    @complexity Linear in @a cnt plus linear in the distance between @a pos
-    and end of the container.
-
-    @liveexample{The example shows how `insert()` is used.,insert__count}
-
-    @since version 1.0.0
-    */
-    iterator insert(const_iterator pos, size_type cnt, const json& val);
-
-    /*!
-    @brief inserts elements
-
-    Inserts elements from range `[first, last)` before iterator @a pos.
-
-    @param[in] pos iterator before which the content will be inserted; may be
-    the end() iterator
-    @param[in] first begin of the range of elements to insert
-    @param[in] last end of the range of elements to insert
-
-    @throw type_error.309 if called on JSON values other than arrays; example:
-    `"cannot use insert() with string"`
-    @throw invalid_iterator.202 if @a pos is not an iterator of *this;
-    example: `"iterator does not fit current value"`
-    @throw invalid_iterator.210 if @a first and @a last do not belong to the
-    same JSON value; example: `"iterators do not fit"`
-    @throw invalid_iterator.211 if @a first or @a last are iterators into
-    container for which insert is called; example: `"passed iterators may not
-    belong to container"`
-
-    @return iterator pointing to the first element inserted, or @a pos if
-    `first==last`
-
-    @complexity Linear in `std::distance(first, last)` plus linear in the
-    distance between @a pos and end of the container.
-
-    @liveexample{The example shows how `insert()` is used.,insert__range}
-
-    @since version 1.0.0
-    */
-    iterator insert(const_iterator pos, const_iterator first, const_iterator last);
-
-    /*!
-    @brief inserts elements
-
-    Inserts elements from initializer list @a ilist before iterator @a pos.
-
-    @param[in] pos iterator before which the content will be inserted; may be
-    the end() iterator
-    @param[in] ilist initializer list to insert the values from
-
-    @throw type_error.309 if called on JSON values other than arrays; example:
-    `"cannot use insert() with string"`
-    @throw invalid_iterator.202 if @a pos is not an iterator of *this;
-    example: `"iterator does not fit current value"`
-
-    @return iterator pointing to the first element inserted, or @a pos if
-    `ilist` is empty
-
-    @complexity Linear in `ilist.size()` plus linear in the distance between
-    @a pos and end of the container.
-
-    @liveexample{The example shows how `insert()` is used.,insert__ilist}
-
-    @since version 1.0.0
-    */
-    iterator insert(const_iterator pos, initializer_list_t ilist);
-
-    /*!
-    @brief inserts elements
-
-    Inserts elements from range `[first, last)`.
-
-    @param[in] first begin of the range of elements to insert
-    @param[in] last end of the range of elements to insert
-
-    @throw type_error.309 if called on JSON values other than objects; example:
-    `"cannot use insert() with string"`
-    @throw invalid_iterator.202 if iterator @a first or @a last does does not
-    point to an object; example: `"iterators first and last must point to
-    objects"`
-    @throw invalid_iterator.210 if @a first and @a last do not belong to the
-    same JSON value; example: `"iterators do not fit"`
-
-    @complexity Logarithmic: `O(N*log(size() + N))`, where `N` is the number
-    of elements to insert.
-
-    @liveexample{The example shows how `insert()` is used.,insert__range_object}
-
-    @since version 3.0.0
-    */
-    void insert(const_iterator first, const_iterator last);
-
-    /*!
-    @brief updates a JSON object from another object, overwriting existing keys
-
-    Inserts all values from JSON object @a j and overwrites existing keys.
-
-    @param[in] j  JSON object to read values from
-
-    @throw type_error.312 if called on JSON values other than objects; example:
-    `"cannot use update() with string"`
-
-    @complexity O(N*log(size() + N)), where N is the number of elements to
-                insert.
-
-    @liveexample{The example shows how `update()` is used.,update}
-
-    @sa https://docs.python.org/3.6/library/stdtypes.html#dict.update
-
-    @since version 3.0.0
-    */
-    void update(const_reference j);
-
-    /*!
-    @brief updates a JSON object from another object, overwriting existing keys
-
-    Inserts all values from from range `[first, last)` and overwrites existing
-    keys.
-
-    @param[in] first begin of the range of elements to insert
-    @param[in] last end of the range of elements to insert
-
-    @throw type_error.312 if called on JSON values other than objects; example:
-    `"cannot use update() with string"`
-    @throw invalid_iterator.202 if iterator @a first or @a last does does not
-    point to an object; example: `"iterators first and last must point to
-    objects"`
-    @throw invalid_iterator.210 if @a first and @a last do not belong to the
-    same JSON value; example: `"iterators do not fit"`
-
-    @complexity O(N*log(size() + N)), where N is the number of elements to
-                insert.
-
-    @liveexample{The example shows how `update()` is used__range.,update}
-
-    @sa https://docs.python.org/3.6/library/stdtypes.html#dict.update
-
-    @since version 3.0.0
-    */
-    void update(const_iterator first, const_iterator last);
-
-    /*!
-    @brief exchanges the values
-
-    Exchanges the contents of the JSON value with those of @a other. Does not
-    invoke any move, copy, or swap operations on individual elements. All
-    iterators and references remain valid. The past-the-end iterator is
-    invalidated.
-
-    @param[in,out] other JSON value to exchange the contents with
-
-    @complexity Constant.
-
-    @liveexample{The example below shows how JSON values can be swapped with
-    `swap()`.,swap__reference}
-
-    @since version 1.0.0
-    */
-    void swap(reference other) noexcept (
-        std::is_nothrow_move_constructible<value_t>::value and
-        std::is_nothrow_move_assignable<value_t>::value and
-        std::is_nothrow_move_constructible<json_value>::value and
-        std::is_nothrow_move_assignable<json_value>::value
-    )
-    {
-        std::swap(m_type, other.m_type);
-        std::swap(m_value, other.m_value);
-        assert_invariant();
-    }
-
-    /*!
-    @brief exchanges the values
-
-    Exchanges the contents of a JSON array with those of @a other. Does not
-    invoke any move, copy, or swap operations on individual elements. All
-    iterators and references remain valid. The past-the-end iterator is
-    invalidated.
-
-    @param[in,out] other array to exchange the contents with
-
-    @throw type_error.310 when JSON value is not an array; example: `"cannot
-    use swap() with string"`
-
-    @complexity Constant.
-
-    @liveexample{The example below shows how arrays can be swapped with
-    `swap()`.,swap__std_vector_json}
-
-    @since version 1.0.0
-    */
-    void swap(array_t& other)
-    {
-        // swap only works for arrays
-        if (JSON_LIKELY(is_array()))
-        {
-            std::swap(*(m_value.array), other);
-        }
-        else
-        {
-            JSON_THROW(type_error::create(310, "cannot use swap() with", type_name()));
-        }
-    }
-
-    /*!
-    @brief exchanges the values
-
-    Exchanges the contents of a JSON object with those of @a other. Does not
-    invoke any move, copy, or swap operations on individual elements. All
-    iterators and references remain valid. The past-the-end iterator is
-    invalidated.
-
-    @param[in,out] other object to exchange the contents with
-
-    @throw type_error.310 when JSON value is not an object; example:
-    `"cannot use swap() with string"`
-
-    @complexity Constant.
-
-    @liveexample{The example below shows how objects can be swapped with
-    `swap()`.,swap__object_t}
-
-    @since version 1.0.0
-    */
-    void swap(object_t& other)
-    {
-        // swap only works for objects
-        if (JSON_LIKELY(is_object()))
-        {
-            std::swap(*(m_value.object), other);
-        }
-        else
-        {
-            JSON_THROW(type_error::create(310, "cannot use swap() with", type_name()));
-        }
-    }
-
-    /*!
-    @brief exchanges the values
-
-    Exchanges the contents of a JSON string with those of @a other. Does not
-    invoke any move, copy, or swap operations on individual elements. All
-    iterators and references remain valid. The past-the-end iterator is
-    invalidated.
-
-    @param[in,out] other string to exchange the contents with
-
-    @throw type_error.310 when JSON value is not a string; example: `"cannot
-    use swap() with boolean"`
-
-    @complexity Constant.
-
-    @liveexample{The example below shows how strings can be swapped with
-    `swap()`.,swap__std_string}
-
-    @since version 1.0.0
-    */
-    void swap(std::string& other)
-    {
-        // swap only works for strings
-        if (JSON_LIKELY(is_string()))
-        {
-            std::swap(*(m_value.string), other);
-        }
-        else
-        {
-            JSON_THROW(type_error::create(310, "cannot use swap() with", type_name()));
-        }
-    }
-
-    /// @}
-
-  public:
-    //////////////////////////////////////////
-    // lexicographical comparison operators //
-    //////////////////////////////////////////
-
-    /// @name lexicographical comparison operators
-    /// @{
-
-    /*!
-    @brief comparison: equal
-
-    Compares two JSON values for equality according to the following rules:
-    - Two JSON values are equal if (1) they are from the same type and (2)
-      their stored values are the same according to their respective
-      `operator==`.
-    - Integer and floating-point numbers are automatically converted before
-      comparison. Note than two NaN values are always treated as unequal.
-    - Two JSON null values are equal.
-
-    @note Floating-point inside JSON values numbers are compared with
-    `double::operator==`.
-    To compare floating-point while respecting an epsilon, an alternative
-    [comparison function](https://github.com/mariokonrad/marnav/blob/master/src/marnav/math/floatingpoint.hpp#L34-#L39)
-    could be used, for instance
-    @code {.cpp}
-    template<typename T, typename = typename std::enable_if<std::is_floating_point<T>::value, T>::type>
-    inline bool is_same(T a, T b, T epsilon = std::numeric_limits<T>::epsilon()) noexcept
-    {
-        return std::abs(a - b) <= epsilon;
-    }
-    @endcode
-
-    @note NaN values never compare equal to themselves or to other NaN values.
-
-    @param[in] lhs  first JSON value to consider
-    @param[in] rhs  second JSON value to consider
-    @return whether the values @a lhs and @a rhs are equal
-
-    @exceptionsafety No-throw guarantee: this function never throws exceptions.
-
-    @complexity Linear.
-
-    @liveexample{The example demonstrates comparing several JSON
-    types.,operator__equal}
-
-    @since version 1.0.0
-    */
-    friend bool operator==(const_reference lhs, const_reference rhs) noexcept;
-
-    /*!
-    @brief comparison: equal
-    @copydoc operator==(const_reference, const_reference)
-    */
-    template<typename ScalarType, typename std::enable_if<
-                 std::is_scalar<ScalarType>::value, int>::type = 0>
-    friend bool operator==(const_reference lhs, const ScalarType rhs) noexcept
-    {
-        return (lhs == json(rhs));
-    }
-
-    /*!
-    @brief comparison: equal
-    @copydoc operator==(const_reference, const_reference)
-    */
-    template<typename ScalarType, typename std::enable_if<
-                 std::is_scalar<ScalarType>::value, int>::type = 0>
-    friend bool operator==(const ScalarType lhs, const_reference rhs) noexcept
-    {
-        return (json(lhs) == rhs);
-    }
-
-    /*!
-    @brief comparison: not equal
-
-    Compares two JSON values for inequality by calculating `not (lhs == rhs)`.
-
-    @param[in] lhs  first JSON value to consider
-    @param[in] rhs  second JSON value to consider
-    @return whether the values @a lhs and @a rhs are not equal
-
-    @complexity Linear.
-
-    @exceptionsafety No-throw guarantee: this function never throws exceptions.
-
-    @liveexample{The example demonstrates comparing several JSON
-    types.,operator__notequal}
-
-    @since version 1.0.0
-    */
-    friend bool operator!=(const_reference lhs, const_reference rhs) noexcept
-    {
-        return not (lhs == rhs);
-    }
-
-    /*!
-    @brief comparison: not equal
-    @copydoc operator!=(const_reference, const_reference)
-    */
-    template<typename ScalarType, typename std::enable_if<
-                 std::is_scalar<ScalarType>::value, int>::type = 0>
-    friend bool operator!=(const_reference lhs, const ScalarType rhs) noexcept
-    {
-        return (lhs != json(rhs));
-    }
-
-    /*!
-    @brief comparison: not equal
-    @copydoc operator!=(const_reference, const_reference)
-    */
-    template<typename ScalarType, typename std::enable_if<
-                 std::is_scalar<ScalarType>::value, int>::type = 0>
-    friend bool operator!=(const ScalarType lhs, const_reference rhs) noexcept
-    {
-        return (json(lhs) != rhs);
-    }
-
-    /*!
-    @brief comparison: less than
-
-    Compares whether one JSON value @a lhs is less than another JSON value @a
-    rhs according to the following rules:
-    - If @a lhs and @a rhs have the same type, the values are compared using
-      the default `<` operator.
-    - Integer and floating-point numbers are automatically converted before
-      comparison
-    - In case @a lhs and @a rhs have different types, the values are ignored
-      and the order of the types is considered, see
-      @ref operator<(const value_t, const value_t).
-
-    @param[in] lhs  first JSON value to consider
-    @param[in] rhs  second JSON value to consider
-    @return whether @a lhs is less than @a rhs
-
-    @complexity Linear.
-
-    @exceptionsafety No-throw guarantee: this function never throws exceptions.
-
-    @liveexample{The example demonstrates comparing several JSON
-    types.,operator__less}
-
-    @since version 1.0.0
-    */
-    friend bool operator<(const_reference lhs, const_reference rhs) noexcept;
-
-    /*!
-    @brief comparison: less than
-    @copydoc operator<(const_reference, const_reference)
-    */
-    template<typename ScalarType, typename std::enable_if<
-                 std::is_scalar<ScalarType>::value, int>::type = 0>
-    friend bool operator<(const_reference lhs, const ScalarType rhs) noexcept
-    {
-        return (lhs < json(rhs));
-    }
-
-    /*!
-    @brief comparison: less than
-    @copydoc operator<(const_reference, const_reference)
-    */
-    template<typename ScalarType, typename std::enable_if<
-                 std::is_scalar<ScalarType>::value, int>::type = 0>
-    friend bool operator<(const ScalarType lhs, const_reference rhs) noexcept
-    {
-        return (json(lhs) < rhs);
-    }
-
-    /*!
-    @brief comparison: less than or equal
-
-    Compares whether one JSON value @a lhs is less than or equal to another
-    JSON value by calculating `not (rhs < lhs)`.
-
-    @param[in] lhs  first JSON value to consider
-    @param[in] rhs  second JSON value to consider
-    @return whether @a lhs is less than or equal to @a rhs
-
-    @complexity Linear.
-
-    @exceptionsafety No-throw guarantee: this function never throws exceptions.
-
-    @liveexample{The example demonstrates comparing several JSON
-    types.,operator__greater}
-
-    @since version 1.0.0
-    */
-    friend bool operator<=(const_reference lhs, const_reference rhs) noexcept
-    {
-        return not (rhs < lhs);
-    }
-
-    /*!
-    @brief comparison: less than or equal
-    @copydoc operator<=(const_reference, const_reference)
-    */
-    template<typename ScalarType, typename std::enable_if<
-                 std::is_scalar<ScalarType>::value, int>::type = 0>
-    friend bool operator<=(const_reference lhs, const ScalarType rhs) noexcept
-    {
-        return (lhs <= json(rhs));
-    }
-
-    /*!
-    @brief comparison: less than or equal
-    @copydoc operator<=(const_reference, const_reference)
-    */
-    template<typename ScalarType, typename std::enable_if<
-                 std::is_scalar<ScalarType>::value, int>::type = 0>
-    friend bool operator<=(const ScalarType lhs, const_reference rhs) noexcept
-    {
-        return (json(lhs) <= rhs);
-    }
-
-    /*!
-    @brief comparison: greater than
-
-    Compares whether one JSON value @a lhs is greater than another
-    JSON value by calculating `not (lhs <= rhs)`.
-
-    @param[in] lhs  first JSON value to consider
-    @param[in] rhs  second JSON value to consider
-    @return whether @a lhs is greater than to @a rhs
-
-    @complexity Linear.
-
-    @exceptionsafety No-throw guarantee: this function never throws exceptions.
-
-    @liveexample{The example demonstrates comparing several JSON
-    types.,operator__lessequal}
-
-    @since version 1.0.0
-    */
-    friend bool operator>(const_reference lhs, const_reference rhs) noexcept
-    {
-        return not (lhs <= rhs);
-    }
-
-    /*!
-    @brief comparison: greater than
-    @copydoc operator>(const_reference, const_reference)
-    */
-    template<typename ScalarType, typename std::enable_if<
-                 std::is_scalar<ScalarType>::value, int>::type = 0>
-    friend bool operator>(const_reference lhs, const ScalarType rhs) noexcept
-    {
-        return (lhs > json(rhs));
-    }
-
-    /*!
-    @brief comparison: greater than
-    @copydoc operator>(const_reference, const_reference)
-    */
-    template<typename ScalarType, typename std::enable_if<
-                 std::is_scalar<ScalarType>::value, int>::type = 0>
-    friend bool operator>(const ScalarType lhs, const_reference rhs) noexcept
-    {
-        return (json(lhs) > rhs);
-    }
-
-    /*!
-    @brief comparison: greater than or equal
-
-    Compares whether one JSON value @a lhs is greater than or equal to another
-    JSON value by calculating `not (lhs < rhs)`.
-
-    @param[in] lhs  first JSON value to consider
-    @param[in] rhs  second JSON value to consider
-    @return whether @a lhs is greater than or equal to @a rhs
-
-    @complexity Linear.
-
-    @exceptionsafety No-throw guarantee: this function never throws exceptions.
-
-    @liveexample{The example demonstrates comparing several JSON
-    types.,operator__greaterequal}
-
-    @since version 1.0.0
-    */
-    friend bool operator>=(const_reference lhs, const_reference rhs) noexcept
-    {
-        return not (lhs < rhs);
-    }
-
-    /*!
-    @brief comparison: greater than or equal
-    @copydoc operator>=(const_reference, const_reference)
-    */
-    template<typename ScalarType, typename std::enable_if<
-                 std::is_scalar<ScalarType>::value, int>::type = 0>
-    friend bool operator>=(const_reference lhs, const ScalarType rhs) noexcept
-    {
-        return (lhs >= json(rhs));
-    }
-
-    /*!
-    @brief comparison: greater than or equal
-    @copydoc operator>=(const_reference, const_reference)
-    */
-    template<typename ScalarType, typename std::enable_if<
-                 std::is_scalar<ScalarType>::value, int>::type = 0>
-    friend bool operator>=(const ScalarType lhs, const_reference rhs) noexcept
-    {
-        return (json(lhs) >= rhs);
-    }
-
-    /// @}
-
-    ///////////////////
-    // serialization //
-    ///////////////////
-
-    /// @name serialization
-    /// @{
-
-    /*!
-    @brief serialize to stream
-
-    Serialize the given JSON value @a j to the output stream @a o. The JSON
-    value will be serialized using the @ref dump member function.
-
-    - The indentation of the output can be controlled with the member variable
-      `width` of the output stream @a o. For instance, using the manipulator
-      `std::setw(4)` on @a o sets the indentation level to `4` and the
-      serialization result is the same as calling `dump(4)`.
-
-    - The indentation character can be controlled with the member variable
-      `fill` of the output stream @a o. For instance, the manipulator
-      `std::setfill('\\t')` sets indentation to use a tab character rather than
-      the default space character.
-
-    @param[in,out] o  stream to serialize to
-    @param[in] j  JSON value to serialize
-
-    @return the stream @a o
-
-    @throw type_error.316 if a string stored inside the JSON value is not
-                          UTF-8 encoded
-
-    @complexity Linear.
-
-    @liveexample{The example below shows the serialization with different
-    parameters to `width` to adjust the indentation level.,operator_serialize}
-
-    @since version 1.0.0; indentation character added in version 3.0.0
-    */
-    friend raw_ostream& operator<<(raw_ostream& o, const json& j);
-
-    /// @}
-
-
-    /////////////////////
-    // deserialization //
-    /////////////////////
-
-    /// @name deserialization
-    /// @{
-
-    /*!
-    @brief deserialize from a compatible input
-
-    This function reads from a compatible input. Examples are:
-    - an array of 1-byte values
-    - strings with character/literal type with size of 1 byte
-    - input streams
-    - container with contiguous storage of 1-byte values. Compatible container
-      types include `std::vector`, `std::string`, `std::array`,
-      and `std::initializer_list`. Furthermore, C-style
-      arrays can be used with `std::begin()`/`std::end()`. User-defined
-      containers can be used as long as they implement random-access iterators
-      and a contiguous storage.
-
-    @pre Each element of the container has a size of 1 byte. Violating this
-    precondition yields undefined behavior. **This precondition is enforced
-    with a static assertion.**
-
-    @pre The container storage is contiguous. Violating this precondition
-    yields undefined behavior. **This precondition is enforced with an
-    assertion.**
-    @pre Each element of the container has a size of 1 byte. Violating this
-    precondition yields undefined behavior. **This precondition is enforced
-    with a static assertion.**
-
-    @warning There is no way to enforce all preconditions at compile-time. If
-             the function is called with a noncompliant container and with
-             assertions switched off, the behavior is undefined and will most
-             likely yield segmentation violation.
-
-    @param[in] i  input to read from
-    @param[in] cb  a parser callback function of type @ref parser_callback_t
-    which is used to control the deserialization by filtering unwanted values
-    (optional)
-
-    @return result of the deserialization
-
-    @throw parse_error.101 if a parse error occurs; example: `""unexpected end
-    of input; expected string literal""`
-    @throw parse_error.102 if to_unicode fails or surrogate error
-    @throw parse_error.103 if to_unicode fails
-
-    @complexity Linear in the length of the input. The parser is a predictive
-    LL(1) parser. The complexity can be higher if the parser callback function
-    @a cb has a super-linear complexity.
-
-    @note A UTF-8 byte order mark is silently ignored.
-
-    @liveexample{The example below demonstrates the `parse()` function reading
-    from an array.,parse__array__parser_callback_t}
-
-    @liveexample{The example below demonstrates the `parse()` function with
-    and without callback function.,parse__string__parser_callback_t}
-
-    @liveexample{The example below demonstrates the `parse()` function with
-    and without callback function.,parse__istream__parser_callback_t}
-
-    @liveexample{The example below demonstrates the `parse()` function reading
-    from a contiguous container.,parse__contiguouscontainer__parser_callback_t}
-
-    @since version 2.0.3 (contiguous containers)
-    */
-    static json parse(std::string_view s,
-                            const parser_callback_t cb = nullptr,
-                            const bool allow_exceptions = true);
-
-    static json parse(span<const uint8_t> arr,
-                            const parser_callback_t cb = nullptr,
-                            const bool allow_exceptions = true);
-
-    /*!
-    @copydoc json parse(raw_istream&, const parser_callback_t)
-    */
-    static json parse(raw_istream& i,
-                            const parser_callback_t cb = nullptr,
-                            const bool allow_exceptions = true);
-
-    static bool accept(std::string_view s);
-
-    static bool accept(span<const uint8_t> arr);
-
-    static bool accept(raw_istream& i);
-
-    /*!
-    @brief deserialize from stream
-
-    Deserializes an input stream to a JSON value.
-
-    @param[in,out] i  input stream to read a serialized JSON value from
-    @param[in,out] j  JSON value to write the deserialized input to
-
-    @throw parse_error.101 in case of an unexpected token
-    @throw parse_error.102 if to_unicode fails or surrogate error
-    @throw parse_error.103 if to_unicode fails
-
-    @complexity Linear in the length of the input. The parser is a predictive
-    LL(1) parser.
-
-    @note A UTF-8 byte order mark is silently ignored.
-
-    @liveexample{The example below shows how a JSON value is constructed by
-    reading a serialization from a stream.,operator_deserialize}
-
-    @sa parse(std::istream&, const parser_callback_t) for a variant with a
-    parser callback function to filter values while parsing
-
-    @since version 1.0.0
-    */
-    friend raw_istream& operator>>(raw_istream& i, json& j);
-
-    /// @}
-
-    ///////////////////////////
-    // convenience functions //
-    ///////////////////////////
-
-    /*!
-    @brief return the type as string
-
-    Returns the type name as string to be used in error messages - usually to
-    indicate that a function was called on a wrong JSON type.
-
-    @return a string representation of a the @a m_type member:
-            Value type  | return value
-            ----------- | -------------
-            null        | `"null"`
-            boolean     | `"boolean"`
-            string      | `"string"`
-            number      | `"number"` (for all number types)
-            object      | `"object"`
-            array       | `"array"`
-            discarded   | `"discarded"`
-
-    @exceptionsafety No-throw guarantee: this function never throws exceptions.
-
-    @complexity Constant.
-
-    @liveexample{The following code exemplifies `type_name()` for all JSON
-    types.,type_name}
-
-    @sa @ref type() -- return the type of the JSON value
-    @sa @ref operator value_t() -- return the type of the JSON value (implicit)
-
-    @since version 1.0.0, public since 2.1.0, `const char*` and `noexcept`
-    since 3.0.0
-    */
-    const char* type_name() const noexcept;
-
-
-  private:
-    //////////////////////
-    // member variables //
-    //////////////////////
-
-    /// the type of the current element
-    value_t m_type = value_t::null;
-
-    /// the value of the current element
-    json_value m_value = {};
-
-    //////////////////////////////////////////
-    // binary serialization/deserialization //
-    //////////////////////////////////////////
-
-    /// @name binary serialization/deserialization support
-    /// @{
-
-  public:
-    /*!
-    @brief create a CBOR serialization of a given JSON value
-
-    Serializes a given JSON value @a j to a byte vector using the CBOR (Concise
-    Binary Object Representation) serialization format. CBOR is a binary
-    serialization format which aims to be more compact than JSON itself, yet
-    more efficient to parse.
-
-    The library uses the following mapping from JSON values types to
-    CBOR types according to the CBOR specification (RFC 7049):
-
-    JSON value type | value/range                                | CBOR type                          | first byte
-    --------------- | ------------------------------------------ | ---------------------------------- | ---------------
-    null            | `null`                                     | Null                               | 0xF6
-    boolean         | `true`                                     | True                               | 0xF5
-    boolean         | `false`                                    | False                              | 0xF4
-    number_integer  | -9223372036854775808..-2147483649          | Negative integer (8 bytes follow)  | 0x3B
-    number_integer  | -2147483648..-32769                        | Negative integer (4 bytes follow)  | 0x3A
-    number_integer  | -32768..-129                               | Negative integer (2 bytes follow)  | 0x39
-    number_integer  | -128..-25                                  | Negative integer (1 byte follow)   | 0x38
-    number_integer  | -24..-1                                    | Negative integer                   | 0x20..0x37
-    number_integer  | 0..23                                      | Integer                            | 0x00..0x17
-    number_integer  | 24..255                                    | Unsigned integer (1 byte follow)   | 0x18
-    number_integer  | 256..65535                                 | Unsigned integer (2 bytes follow)  | 0x19
-    number_integer  | 65536..4294967295                          | Unsigned integer (4 bytes follow)  | 0x1A
-    number_integer  | 4294967296..18446744073709551615           | Unsigned integer (8 bytes follow)  | 0x1B
-    number_unsigned | 0..23                                      | Integer                            | 0x00..0x17
-    number_unsigned | 24..255                                    | Unsigned integer (1 byte follow)   | 0x18
-    number_unsigned | 256..65535                                 | Unsigned integer (2 bytes follow)  | 0x19
-    number_unsigned | 65536..4294967295                          | Unsigned integer (4 bytes follow)  | 0x1A
-    number_unsigned | 4294967296..18446744073709551615           | Unsigned integer (8 bytes follow)  | 0x1B
-    number_float    | *any value*                                | Double-Precision Float             | 0xFB
-    string          | *length*: 0..23                            | UTF-8 string                       | 0x60..0x77
-    string          | *length*: 23..255                          | UTF-8 string (1 byte follow)       | 0x78
-    string          | *length*: 256..65535                       | UTF-8 string (2 bytes follow)      | 0x79
-    string          | *length*: 65536..4294967295                | UTF-8 string (4 bytes follow)      | 0x7A
-    string          | *length*: 4294967296..18446744073709551615 | UTF-8 string (8 bytes follow)      | 0x7B
-    array           | *size*: 0..23                              | array                              | 0x80..0x97
-    array           | *size*: 23..255                            | array (1 byte follow)              | 0x98
-    array           | *size*: 256..65535                         | array (2 bytes follow)             | 0x99
-    array           | *size*: 65536..4294967295                  | array (4 bytes follow)             | 0x9A
-    array           | *size*: 4294967296..18446744073709551615   | array (8 bytes follow)             | 0x9B
-    object          | *size*: 0..23                              | map                                | 0xA0..0xB7
-    object          | *size*: 23..255                            | map (1 byte follow)                | 0xB8
-    object          | *size*: 256..65535                         | map (2 bytes follow)               | 0xB9
-    object          | *size*: 65536..4294967295                  | map (4 bytes follow)               | 0xBA
-    object          | *size*: 4294967296..18446744073709551615   | map (8 bytes follow)               | 0xBB
-
-    @note The mapping is **complete** in the sense that any JSON value type
-          can be converted to a CBOR value.
-
-    @note If NaN or Infinity are stored inside a JSON number, they are
-          serialized properly. This behavior differs from the @ref dump()
-          function which serializes NaN or Infinity to `null`.
-
-    @note The following CBOR types are not used in the conversion:
-          - byte strings (0x40..0x5F)
-          - UTF-8 strings terminated by "break" (0x7F)
-          - arrays terminated by "break" (0x9F)
-          - maps terminated by "break" (0xBF)
-          - date/time (0xC0..0xC1)
-          - bignum (0xC2..0xC3)
-          - decimal fraction (0xC4)
-          - bigfloat (0xC5)
-          - tagged items (0xC6..0xD4, 0xD8..0xDB)
-          - expected conversions (0xD5..0xD7)
-          - simple values (0xE0..0xF3, 0xF8)
-          - undefined (0xF7)
-          - half and single-precision floats (0xF9-0xFA)
-          - break (0xFF)
-
-    @param[in] j  JSON value to serialize
-    @return MessagePack serialization as byte vector
-
-    @complexity Linear in the size of the JSON value @a j.
-
-    @liveexample{The example shows the serialization of a JSON value to a byte
-    vector in CBOR format.,to_cbor}
-
-    @sa http://cbor.io
-    @sa @ref from_cbor(raw_istream&, const bool strict) for the
-        analogous deserialization
-    @sa @ref to_msgpack(const json&) for the related MessagePack format
-    @sa @ref to_ubjson(const json&, const bool, const bool) for the
-             related UBJSON format
-
-    @since version 2.0.9
-    */
-    static std::vector<uint8_t> to_cbor(const json& j);
-    static span<uint8_t> to_cbor(const json& j, std::vector<uint8_t>& buf);
-    static span<uint8_t> to_cbor(const json& j, SmallVectorImpl<uint8_t>& buf);
-    static void to_cbor(raw_ostream& os, const json& j);
-
-    /*!
-    @brief create a MessagePack serialization of a given JSON value
-
-    Serializes a given JSON value @a j to a byte vector using the MessagePack
-    serialization format. MessagePack is a binary serialization format which
-    aims to be more compact than JSON itself, yet more efficient to parse.
-
-    The library uses the following mapping from JSON values types to
-    MessagePack types according to the MessagePack specification:
-
-    JSON value type | value/range                       | MessagePack type | first byte
-    --------------- | --------------------------------- | ---------------- | ----------
-    null            | `null`                            | nil              | 0xC0
-    boolean         | `true`                            | true             | 0xC3
-    boolean         | `false`                           | false            | 0xC2
-    number_integer  | -9223372036854775808..-2147483649 | int64            | 0xD3
-    number_integer  | -2147483648..-32769               | int32            | 0xD2
-    number_integer  | -32768..-129                      | int16            | 0xD1
-    number_integer  | -128..-33                         | int8             | 0xD0
-    number_integer  | -32..-1                           | negative fixint  | 0xE0..0xFF
-    number_integer  | 0..127                            | positive fixint  | 0x00..0x7F
-    number_integer  | 128..255                          | uint 8           | 0xCC
-    number_integer  | 256..65535                        | uint 16          | 0xCD
-    number_integer  | 65536..4294967295                 | uint 32          | 0xCE
-    number_integer  | 4294967296..18446744073709551615  | uint 64          | 0xCF
-    number_unsigned | 0..127                            | positive fixint  | 0x00..0x7F
-    number_unsigned | 128..255                          | uint 8           | 0xCC
-    number_unsigned | 256..65535                        | uint 16          | 0xCD
-    number_unsigned | 65536..4294967295                 | uint 32          | 0xCE
-    number_unsigned | 4294967296..18446744073709551615  | uint 64          | 0xCF
-    number_float    | *any value*                       | float 64         | 0xCB
-    string          | *length*: 0..31                   | fixstr           | 0xA0..0xBF
-    string          | *length*: 32..255                 | str 8            | 0xD9
-    string          | *length*: 256..65535              | str 16           | 0xDA
-    string          | *length*: 65536..4294967295       | str 32           | 0xDB
-    array           | *size*: 0..15                     | fixarray         | 0x90..0x9F
-    array           | *size*: 16..65535                 | array 16         | 0xDC
-    array           | *size*: 65536..4294967295         | array 32         | 0xDD
-    object          | *size*: 0..15                     | fix map          | 0x80..0x8F
-    object          | *size*: 16..65535                 | map 16           | 0xDE
-    object          | *size*: 65536..4294967295         | map 32           | 0xDF
-
-    @note The mapping is **complete** in the sense that any JSON value type
-          can be converted to a MessagePack value.
-
-    @note The following values can **not** be converted to a MessagePack value:
-          - strings with more than 4294967295 bytes
-          - arrays with more than 4294967295 elements
-          - objects with more than 4294967295 elements
-
-    @note The following MessagePack types are not used in the conversion:
-          - bin 8 - bin 32 (0xC4..0xC6)
-          - ext 8 - ext 32 (0xC7..0xC9)
-          - float 32 (0xCA)
-          - fixext 1 - fixext 16 (0xD4..0xD8)
-
-    @note Any MessagePack output created @ref to_msgpack can be successfully
-          parsed by @ref from_msgpack.
-
-    @note If NaN or Infinity are stored inside a JSON number, they are
-          serialized properly. This behavior differs from the @ref dump()
-          function which serializes NaN or Infinity to `null`.
-
-    @param[in] j  JSON value to serialize
-    @return MessagePack serialization as byte vector
-
-    @complexity Linear in the size of the JSON value @a j.
-
-    @liveexample{The example shows the serialization of a JSON value to a byte
-    vector in MessagePack format.,to_msgpack}
-
-    @sa http://msgpack.org
-    @sa @ref from_msgpack(const std::vector<uint8_t>&, const size_t) for the
-        analogous deserialization
-    @sa @ref to_cbor(const json& for the related CBOR format
-    @sa @ref to_ubjson(const json&, const bool, const bool) for the
-             related UBJSON format
-
-    @since version 2.0.9
-    */
-    static std::vector<uint8_t> to_msgpack(const json& j);
-    static span<uint8_t> to_msgpack(const json& j, std::vector<uint8_t>& buf);
-    static span<uint8_t> to_msgpack(const json& j, SmallVectorImpl<uint8_t>& buf);
-    static void to_msgpack(raw_ostream& os, const json& j);
-
-    /*!
-    @brief create a UBJSON serialization of a given JSON value
-
-    Serializes a given JSON value @a j to a byte vector using the UBJSON
-    (Universal Binary JSON) serialization format. UBJSON aims to be more compact
-    than JSON itself, yet more efficient to parse.
-
-    The library uses the following mapping from JSON values types to
-    UBJSON types according to the UBJSON specification:
-
-    JSON value type | value/range                       | UBJSON type | marker
-    --------------- | --------------------------------- | ----------- | ------
-    null            | `null`                            | null        | `Z`
-    boolean         | `true`                            | true        | `T`
-    boolean         | `false`                           | false       | `F`
-    number_integer  | -9223372036854775808..-2147483649 | int64       | `L`
-    number_integer  | -2147483648..-32769               | int32       | `l`
-    number_integer  | -32768..-129                      | int16       | `I`
-    number_integer  | -128..127                         | int8        | `i`
-    number_integer  | 128..255                          | uint8       | `U`
-    number_integer  | 256..32767                        | int16       | `I`
-    number_integer  | 32768..2147483647                 | int32       | `l`
-    number_integer  | 2147483648..9223372036854775807   | int64       | `L`
-    number_unsigned | 0..127                            | int8        | `i`
-    number_unsigned | 128..255                          | uint8       | `U`
-    number_unsigned | 256..32767                        | int16       | `I`
-    number_unsigned | 32768..2147483647                 | int32       | `l`
-    number_unsigned | 2147483648..9223372036854775807   | int64       | `L`
-    number_float    | *any value*                       | float64     | `D`
-    string          | *with shortest length indicator*  | string      | `S`
-    array           | *see notes on optimized format*   | array       | `[`
-    object          | *see notes on optimized format*   | map         | `{`
-
-    @note The mapping is **complete** in the sense that any JSON value type
-          can be converted to a UBJSON value.
-
-    @note The following values can **not** be converted to a UBJSON value:
-          - strings with more than 9223372036854775807 bytes (theoretical)
-          - unsigned integer numbers above 9223372036854775807
-
-    @note The following markers are not used in the conversion:
-          - `Z`: no-op values are not created.
-          - `C`: single-byte strings are serialized with `S` markers.
-
-    @note Any UBJSON output created @ref to_ubjson can be successfully parsed
-          by @ref from_ubjson.
-
-    @note If NaN or Infinity are stored inside a JSON number, they are
-          serialized properly. This behavior differs from the @ref dump()
-          function which serializes NaN or Infinity to `null`.
-
-    @note The optimized formats for containers are supported: Parameter
-          @a use_size adds size information to the beginning of a container and
-          removes the closing marker. Parameter @a use_type further checks
-          whether all elements of a container have the same type and adds the
-          type marker to the beginning of the container. The @a use_type
-          parameter must only be used together with @a use_size = true. Note
-          that @a use_size = true alone may result in larger representations -
-          the benefit of this parameter is that the receiving side is
-          immediately informed on the number of elements of the container.
-
-    @param[in] j  JSON value to serialize
-    @param[in] use_size  whether to add size annotations to container types
-    @param[in] use_type  whether to add type annotations to container types
-                         (must be combined with @a use_size = true)
-    @return UBJSON serialization as byte vector
-
-    @complexity Linear in the size of the JSON value @a j.
-
-    @liveexample{The example shows the serialization of a JSON value to a byte
-    vector in UBJSON format.,to_ubjson}
-
-    @sa http://ubjson.org
-    @sa @ref from_ubjson(raw_istream&, const bool strict) for the
-        analogous deserialization
-    @sa @ref to_cbor(const json& for the related CBOR format
-    @sa @ref to_msgpack(const json&) for the related MessagePack format
-
-    @since version 3.1.0
-    */
-    static std::vector<uint8_t> to_ubjson(const json& j,
-                                          const bool use_size = false,
-                                          const bool use_type = false);
-    static span<uint8_t> to_ubjson(const json& j, std::vector<uint8_t>& buf,
-                                   const bool use_size = false, const bool use_type = false);
-    static span<uint8_t> to_ubjson(const json& j, SmallVectorImpl<uint8_t>& buf,
-                                   const bool use_size = false, const bool use_type = false);
-    static void to_ubjson(raw_ostream& os, const json& j,
-                          const bool use_size = false, const bool use_type = false);
-
-    /*!
-    @brief create a JSON value from an input in CBOR format
-
-    Deserializes a given input @a i to a JSON value using the CBOR (Concise
-    Binary Object Representation) serialization format.
-
-    The library maps CBOR types to JSON value types as follows:
-
-    CBOR type              | JSON value type | first byte
-    ---------------------- | --------------- | ----------
-    Integer                | number_unsigned | 0x00..0x17
-    Unsigned integer       | number_unsigned | 0x18
-    Unsigned integer       | number_unsigned | 0x19
-    Unsigned integer       | number_unsigned | 0x1A
-    Unsigned integer       | number_unsigned | 0x1B
-    Negative integer       | number_integer  | 0x20..0x37
-    Negative integer       | number_integer  | 0x38
-    Negative integer       | number_integer  | 0x39
-    Negative integer       | number_integer  | 0x3A
-    Negative integer       | number_integer  | 0x3B
-    Negative integer       | number_integer  | 0x40..0x57
-    UTF-8 string           | string          | 0x60..0x77
-    UTF-8 string           | string          | 0x78
-    UTF-8 string           | string          | 0x79
-    UTF-8 string           | string          | 0x7A
-    UTF-8 string           | string          | 0x7B
-    UTF-8 string           | string          | 0x7F
-    array                  | array           | 0x80..0x97
-    array                  | array           | 0x98
-    array                  | array           | 0x99
-    array                  | array           | 0x9A
-    array                  | array           | 0x9B
-    array                  | array           | 0x9F
-    map                    | object          | 0xA0..0xB7
-    map                    | object          | 0xB8
-    map                    | object          | 0xB9
-    map                    | object          | 0xBA
-    map                    | object          | 0xBB
-    map                    | object          | 0xBF
-    False                  | `false`         | 0xF4
-    True                   | `true`          | 0xF5
-    Nill                   | `null`          | 0xF6
-    Half-Precision Float   | number_float    | 0xF9
-    Single-Precision Float | number_float    | 0xFA
-    Double-Precision Float | number_float    | 0xFB
-
-    @warning The mapping is **incomplete** in the sense that not all CBOR
-             types can be converted to a JSON value. The following CBOR types
-             are not supported and will yield parse errors (parse_error.112):
-             - byte strings (0x40..0x5F)
-             - date/time (0xC0..0xC1)
-             - bignum (0xC2..0xC3)
-             - decimal fraction (0xC4)
-             - bigfloat (0xC5)
-             - tagged items (0xC6..0xD4, 0xD8..0xDB)
-             - expected conversions (0xD5..0xD7)
-             - simple values (0xE0..0xF3, 0xF8)
-             - undefined (0xF7)
-
-    @warning CBOR allows map keys of any type, whereas JSON only allows
-             strings as keys in object values. Therefore, CBOR maps with keys
-             other than UTF-8 strings are rejected (parse_error.113).
-
-    @note Any CBOR output created @ref to_cbor can be successfully parsed by
-          @ref from_cbor.
-
-    @param[in] i  an input in CBOR format convertible to an input adapter
-    @param[in] strict  whether to expect the input to be consumed until EOF
-                       (true by default)
-    @return deserialized JSON value
-
-    @throw parse_error.110 if the given input ends prematurely or the end of
-    file was not reached when @a strict was set to true
-    @throw parse_error.112 if unsupported features from CBOR were
-    used in the given input @a v or if the input is not valid CBOR
-    @throw parse_error.113 if a string was expected as map key, but not found
-
-    @complexity Linear in the size of the input @a i.
-
-    @liveexample{The example shows the deserialization of a byte vector in CBOR
-    format to a JSON value.,from_cbor}
-
-    @sa http://cbor.io
-    @sa @ref to_cbor(const json&) for the analogous serialization
-    @sa @ref from_msgpack(raw_istream&, const bool) for the
-        related MessagePack format
-    @sa @ref from_ubjson(raw_istream&, const bool) for the related
-        UBJSON format
-
-    @since version 2.0.9; parameter @a start_index since 2.1.1; changed to
-           consume input adapters, removed start_index parameter, and added
-           @a strict parameter since 3.0.0
-    */
-    static json from_cbor(raw_istream& is,
-                                const bool strict = true);
-
-    /*!
-    @copydoc from_cbor(raw_istream&, const bool)
-    */
-    static json from_cbor(span<const uint8_t> arr, const bool strict = true);
-
-    /*!
-    @brief create a JSON value from an input in MessagePack format
-
-    Deserializes a given input @a i to a JSON value using the MessagePack
-    serialization format.
-
-    The library maps MessagePack types to JSON value types as follows:
-
-    MessagePack type | JSON value type | first byte
-    ---------------- | --------------- | ----------
-    positive fixint  | number_unsigned | 0x00..0x7F
-    fixmap           | object          | 0x80..0x8F
-    fixarray         | array           | 0x90..0x9F
-    fixstr           | string          | 0xA0..0xBF
-    nil              | `null`          | 0xC0
-    false            | `false`         | 0xC2
-    true             | `true`          | 0xC3
-    float 32         | number_float    | 0xCA
-    float 64         | number_float    | 0xCB
-    uint 8           | number_unsigned | 0xCC
-    uint 16          | number_unsigned | 0xCD
-    uint 32          | number_unsigned | 0xCE
-    uint 64          | number_unsigned | 0xCF
-    int 8            | number_integer  | 0xD0
-    int 16           | number_integer  | 0xD1
-    int 32           | number_integer  | 0xD2
-    int 64           | number_integer  | 0xD3
-    str 8            | string          | 0xD9
-    str 16           | string          | 0xDA
-    str 32           | string          | 0xDB
-    array 16         | array           | 0xDC
-    array 32         | array           | 0xDD
-    map 16           | object          | 0xDE
-    map 32           | object          | 0xDF
-    negative fixint  | number_integer  | 0xE0-0xFF
-
-    @warning The mapping is **incomplete** in the sense that not all
-             MessagePack types can be converted to a JSON value. The following
-             MessagePack types are not supported and will yield parse errors:
-              - bin 8 - bin 32 (0xC4..0xC6)
-              - ext 8 - ext 32 (0xC7..0xC9)
-              - fixext 1 - fixext 16 (0xD4..0xD8)
-
-    @note Any MessagePack output created @ref to_msgpack can be successfully
-          parsed by @ref from_msgpack.
-
-    @param[in] i  an input in MessagePack format convertible to an input
-                  adapter
-    @param[in] strict  whether to expect the input to be consumed until EOF
-                       (true by default)
-
-    @throw parse_error.110 if the given input ends prematurely or the end of
-    file was not reached when @a strict was set to true
-    @throw parse_error.112 if unsupported features from MessagePack were
-    used in the given input @a i or if the input is not valid MessagePack
-    @throw parse_error.113 if a string was expected as map key, but not found
-
-    @complexity Linear in the size of the input @a i.
-
-    @liveexample{The example shows the deserialization of a byte vector in
-    MessagePack format to a JSON value.,from_msgpack}
-
-    @sa http://msgpack.org
-    @sa @ref to_msgpack(const json&) for the analogous serialization
-    @sa @ref from_cbor(raw_istream&, const bool) for the related CBOR
-        format
-    @sa @ref from_ubjson(raw_istream&, const bool) for the related
-        UBJSON format
-
-    @since version 2.0.9; parameter @a start_index since 2.1.1; changed to
-           consume input adapters, removed start_index parameter, and added
-           @a strict parameter since 3.0.0
-    */
-    static json from_msgpack(raw_istream& is,
-                                   const bool strict = true);
-
-    /*!
-    @copydoc from_msgpack(raw_istream&, const bool)
-    */
-    static json from_msgpack(span<const uint8_t> arr, const bool strict = true);
-
-    /*!
-    @brief create a JSON value from an input in UBJSON format
-
-    Deserializes a given input @a i to a JSON value using the UBJSON (Universal
-    Binary JSON) serialization format.
-
-    The library maps UBJSON types to JSON value types as follows:
-
-    UBJSON type | JSON value type                         | marker
-    ----------- | --------------------------------------- | ------
-    no-op       | *no value, next value is read*          | `N`
-    null        | `null`                                  | `Z`
-    false       | `false`                                 | `F`
-    true        | `true`                                  | `T`
-    float32     | number_float                            | `d`
-    float64     | number_float                            | `D`
-    uint8       | number_unsigned                         | `U`
-    int8        | number_integer                          | `i`
-    int16       | number_integer                          | `I`
-    int32       | number_integer                          | `l`
-    int64       | number_integer                          | `L`
-    string      | string                                  | `S`
-    char        | string                                  | `C`
-    array       | array (optimized values are supported)  | `[`
-    object      | object (optimized values are supported) | `{`
-
-    @note The mapping is **complete** in the sense that any UBJSON value can
-          be converted to a JSON value.
-
-    @param[in] i  an input in UBJSON format convertible to an input adapter
-    @param[in] strict  whether to expect the input to be consumed until EOF
-                       (true by default)
-
-    @throw parse_error.110 if the given input ends prematurely or the end of
-    file was not reached when @a strict was set to true
-    @throw parse_error.112 if a parse error occurs
-    @throw parse_error.113 if a string could not be parsed successfully
-
-    @complexity Linear in the size of the input @a i.
-
-    @liveexample{The example shows the deserialization of a byte vector in
-    UBJSON format to a JSON value.,from_ubjson}
-
-    @sa http://ubjson.org
-    @sa @ref to_ubjson(const json&, const bool, const bool) for the
-             analogous serialization
-    @sa @ref from_cbor(raw_istream&, const bool) for the related CBOR
-        format
-    @sa @ref from_msgpack(raw_istream&, const bool) for the related
-        MessagePack format
-
-    @since version 3.1.0
-    */
-    static json from_ubjson(raw_istream& is,
-                                  const bool strict = true);
-
-    static json from_ubjson(span<const uint8_t> arr, const bool strict = true);
-
-    /// @}
-
-    //////////////////////////
-    // JSON Pointer support //
-    //////////////////////////
-
-    /// @name JSON Pointer functions
-    /// @{
-
-    /*!
-    @brief access specified element via JSON Pointer
-
-    Uses a JSON pointer to retrieve a reference to the respective JSON value.
-    No bound checking is performed. Similar to @ref operator[](const typename
-    object_t::key_type&), `null` values are created in arrays and objects if
-    necessary.
-
-    In particular:
-    - If the JSON pointer points to an object key that does not exist, it
-      is created an filled with a `null` value before a reference to it
-      is returned.
-    - If the JSON pointer points to an array index that does not exist, it
-      is created an filled with a `null` value before a reference to it
-      is returned. All indices between the current maximum and the given
-      index are also filled with `null`.
-    - The special value `-` is treated as a synonym for the index past the
-      end.
-
-    @param[in] ptr  a JSON pointer
-
-    @return reference to the element pointed to by @a ptr
-
-    @complexity Constant.
-
-    @throw parse_error.106   if an array index begins with '0'
-    @throw parse_error.109   if an array index was not a number
-    @throw out_of_range.404  if the JSON pointer can not be resolved
-
-    @liveexample{The behavior is shown in the example.,operatorjson_pointer}
-
-    @since version 2.0.0
-    */
-    reference operator[](const json_pointer& ptr)
-    {
-        return ptr.get_unchecked(this);
-    }
-
-    /*!
-    @brief access specified element via JSON Pointer
-
-    Uses a JSON pointer to retrieve a reference to the respective JSON value.
-    No bound checking is performed. The function does not change the JSON
-    value; no `null` values are created. In particular, the the special value
-    `-` yields an exception.
-
-    @param[in] ptr  JSON pointer to the desired element
-
-    @return const reference to the element pointed to by @a ptr
-
-    @complexity Constant.
-
-    @throw parse_error.106   if an array index begins with '0'
-    @throw parse_error.109   if an array index was not a number
-    @throw out_of_range.402  if the array index '-' is used
-    @throw out_of_range.404  if the JSON pointer can not be resolved
-
-    @liveexample{The behavior is shown in the example.,operatorjson_pointer_const}
-
-    @since version 2.0.0
-    */
-    const_reference operator[](const json_pointer& ptr) const
-    {
-        return ptr.get_unchecked(this);
-    }
-
-    /*!
-    @brief access specified element via JSON Pointer
-
-    Returns a reference to the element at with specified JSON pointer @a ptr,
-    with bounds checking.
-
-    @param[in] ptr  JSON pointer to the desired element
-
-    @return reference to the element pointed to by @a ptr
-
-    @throw parse_error.106 if an array index in the passed JSON pointer @a ptr
-    begins with '0'. See example below.
-
-    @throw parse_error.109 if an array index in the passed JSON pointer @a ptr
-    is not a number. See example below.
-
-    @throw out_of_range.401 if an array index in the passed JSON pointer @a ptr
-    is out of range. See example below.
-
-    @throw out_of_range.402 if the array index '-' is used in the passed JSON
-    pointer @a ptr. As `at` provides checked access (and no elements are
-    implicitly inserted), the index '-' is always invalid. See example below.
-
-    @throw out_of_range.403 if the JSON pointer describes a key of an object
-    which cannot be found. See example below.
-
-    @throw out_of_range.404 if the JSON pointer @a ptr can not be resolved.
-    See example below.
-
-    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
-    changes in the JSON value.
-
-    @complexity Constant.
-
-    @since version 2.0.0
-
-    @liveexample{The behavior is shown in the example.,at_json_pointer}
-    */
-    reference at(const json_pointer& ptr)
-    {
-        return ptr.get_checked(this);
-    }
-
-    /*!
-    @brief access specified element via JSON Pointer
-
-    Returns a const reference to the element at with specified JSON pointer @a
-    ptr, with bounds checking.
-
-    @param[in] ptr  JSON pointer to the desired element
-
-    @return reference to the element pointed to by @a ptr
-
-    @throw parse_error.106 if an array index in the passed JSON pointer @a ptr
-    begins with '0'. See example below.
-
-    @throw parse_error.109 if an array index in the passed JSON pointer @a ptr
-    is not a number. See example below.
-
-    @throw out_of_range.401 if an array index in the passed JSON pointer @a ptr
-    is out of range. See example below.
-
-    @throw out_of_range.402 if the array index '-' is used in the passed JSON
-    pointer @a ptr. As `at` provides checked access (and no elements are
-    implicitly inserted), the index '-' is always invalid. See example below.
-
-    @throw out_of_range.403 if the JSON pointer describes a key of an object
-    which cannot be found. See example below.
-
-    @throw out_of_range.404 if the JSON pointer @a ptr can not be resolved.
-    See example below.
-
-    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
-    changes in the JSON value.
-
-    @complexity Constant.
-
-    @since version 2.0.0
-
-    @liveexample{The behavior is shown in the example.,at_json_pointer_const}
-    */
-    const_reference at(const json_pointer& ptr) const
-    {
-        return ptr.get_checked(this);
-    }
-
-    /*!
-    @brief return flattened JSON value
-
-    The function creates a JSON object whose keys are JSON pointers (see [RFC
-    6901](https://tools.ietf.org/html/rfc6901)) and whose values are all
-    primitive. The original JSON value can be restored using the @ref
-    unflatten() function.
-
-    @return an object that maps JSON pointers to primitive values
-
-    @note Empty objects and arrays are flattened to `null` and will not be
-          reconstructed correctly by the @ref unflatten() function.
-
-    @complexity Linear in the size the JSON value.
-
-    @liveexample{The following code shows how a JSON object is flattened to an
-    object whose keys consist of JSON pointers.,flatten}
-
-    @sa @ref unflatten() for the reverse function
-
-    @since version 2.0.0
-    */
-    json flatten() const
-    {
-        json result(value_t::object);
-        json_pointer::flatten("", *this, result);
-        return result;
-    }
-
-    /*!
-    @brief unflatten a previously flattened JSON value
-
-    The function restores the arbitrary nesting of a JSON value that has been
-    flattened before using the @ref flatten() function. The JSON value must
-    meet certain constraints:
-    1. The value must be an object.
-    2. The keys must be JSON pointers (see
-       [RFC 6901](https://tools.ietf.org/html/rfc6901))
-    3. The mapped values must be primitive JSON types.
-
-    @return the original JSON from a flattened version
-
-    @note Empty objects and arrays are flattened by @ref flatten() to `null`
-          values and can not unflattened to their original type. Apart from
-          this example, for a JSON value `j`, the following is always true:
-          `j == j.flatten().unflatten()`.
-
-    @complexity Linear in the size the JSON value.
-
-    @throw type_error.314  if value is not an object
-    @throw type_error.315  if object values are not primitive
-
-    @liveexample{The following code shows how a flattened JSON object is
-    unflattened into the original nested JSON object.,unflatten}
-
-    @sa @ref flatten() for the reverse function
-
-    @since version 2.0.0
-    */
-    json unflatten() const
-    {
-        return json_pointer::unflatten(*this);
-    }
-
-    /// @}
-
-    //////////////////////////
-    // JSON Patch functions //
-    //////////////////////////
-
-    /// @name JSON Patch functions
-    /// @{
-
-    /*!
-    @brief applies a JSON patch
-
-    [JSON Patch](http://jsonpatch.com) defines a JSON document structure for
-    expressing a sequence of operations to apply to a JSON) document. With
-    this function, a JSON Patch is applied to the current JSON value by
-    executing all operations from the patch.
-
-    @param[in] json_patch  JSON patch document
-    @return patched document
-
-    @note The application of a patch is atomic: Either all operations succeed
-          and the patched document is returned or an exception is thrown. In
-          any case, the original value is not changed: the patch is applied
-          to a copy of the value.
-
-    @throw parse_error.104 if the JSON patch does not consist of an array of
-    objects
-
-    @throw parse_error.105 if the JSON patch is malformed (e.g., mandatory
-    attributes are missing); example: `"operation add must have member path"`
-
-    @throw out_of_range.401 if an array index is out of range.
-
-    @throw out_of_range.403 if a JSON pointer inside the patch could not be
-    resolved successfully in the current JSON value; example: `"key baz not
-    found"`
-
-    @throw out_of_range.405 if JSON pointer has no parent ("add", "remove",
-    "move")
-
-    @throw other_error.501 if "test" operation was unsuccessful
-
-    @complexity Linear in the size of the JSON value and the length of the
-    JSON patch. As usually only a fraction of the JSON value is affected by
-    the patch, the complexity can usually be neglected.
-
-    @liveexample{The following code shows how a JSON patch is applied to a
-    value.,patch}
-
-    @sa @ref diff -- create a JSON patch by comparing two JSON values
-
-    @sa [RFC 6902 (JSON Patch)](https://tools.ietf.org/html/rfc6902)
-    @sa [RFC 6901 (JSON Pointer)](https://tools.ietf.org/html/rfc6901)
-
-    @since version 2.0.0
-    */
-    json patch(const json& json_patch) const;
-
-    /*!
-    @brief creates a diff as a JSON patch
-
-    Creates a [JSON Patch](http://jsonpatch.com) so that value @a source can
-    be changed into the value @a target by calling @ref patch function.
-
-    @invariant For two JSON values @a source and @a target, the following code
-    yields always `true`:
-    @code {.cpp}
-    source.patch(diff(source, target)) == target;
-    @endcode
-
-    @note Currently, only `remove`, `add`, and `replace` operations are
-          generated.
-
-    @param[in] source  JSON value to compare from
-    @param[in] target  JSON value to compare against
-    @param[in] path    helper value to create JSON pointers
-
-    @return a JSON patch to convert the @a source to @a target
-
-    @complexity Linear in the lengths of @a source and @a target.
-
-    @liveexample{The following code shows how a JSON patch is created as a
-    diff for two JSON values.,diff}
-
-    @sa @ref patch -- apply a JSON patch
-    @sa @ref merge_patch -- apply a JSON Merge Patch
-
-    @sa [RFC 6902 (JSON Patch)](https://tools.ietf.org/html/rfc6902)
-
-    @since version 2.0.0
-    */
-    static json diff(const json& source, const json& target,
-                           const std::string& path = "");
-
-    /// @}
-
-    ////////////////////////////////
-    // JSON Merge Patch functions //
-    ////////////////////////////////
-
-    /// @name JSON Merge Patch functions
-    /// @{
-
-    /*!
-    @brief applies a JSON Merge Patch
-
-    The merge patch format is primarily intended for use with the HTTP PATCH
-    method as a means of describing a set of modifications to a target
-    resource's content. This function applies a merge patch to the current
-    JSON value.
-
-    The function implements the following algorithm from Section 2 of
-    [RFC 7396 (JSON Merge Patch)](https://tools.ietf.org/html/rfc7396):
-
-    ```
-    define MergePatch(Target, Patch):
-      if Patch is an Object:
-        if Target is not an Object:
-          Target = {} // Ignore the contents and set it to an empty Object
-        for each Name/Value pair in Patch:
-          if Value is null:
-            if Name exists in Target:
-              remove the Name/Value pair from Target
-          else:
-            Target[Name] = MergePatch(Target[Name], Value)
-        return Target
-      else:
-        return Patch
-    ```
-
-    Thereby, `Target` is the current object; that is, the patch is applied to
-    the current value.
-
-    @param[in] patch  the patch to apply
-
-    @complexity Linear in the lengths of @a patch.
-
-    @liveexample{The following code shows how a JSON Merge Patch is applied to
-    a JSON document.,merge_patch}
-
-    @sa @ref patch -- apply a JSON patch
-    @sa [RFC 7396 (JSON Merge Patch)](https://tools.ietf.org/html/rfc7396)
-
-    @since version 3.0.0
-    */
-    void merge_patch(const json& patch);
-
-    /// @}
-};
-} // namespace wpi
-
-///////////////////////
-// nonmember support //
-///////////////////////
-
-// specialization of std::swap, and std::hash
-namespace std
-{
-/*!
-@brief exchanges the values of two JSON objects
-
-@since version 1.0.0
-*/
-template<>
-inline void swap<wpi::json>(wpi::json& j1,
-                 wpi::json& j2) noexcept(
-                     is_nothrow_move_constructible<wpi::json>::value and
-                     is_nothrow_move_assignable<wpi::json>::value
-                 )
-{
-    j1.swap(j2);
-}
-
-/// hash value for JSON objects
-template<>
-struct hash<wpi::json>
-{
-    /*!
-    @brief return a hash value for a JSON object
-
-    @since version 1.0.0
-    */
-    std::size_t operator()(const wpi::json& j) const
-    {
-        // a naive hashing via the string representation
-        const auto& h = hash<std::string>();
-        return h(j.dump());
-    }
-};
-
-/// specialization for std::less<value_t>
-/// @note: do not remove the space after '<',
-///        see https://github.com/nlohmann/json/pull/679
-template<>
-struct less< ::wpi::detail::value_t>
-{
-    /*!
-    @brief compare two value_t enum values
-    @since version 3.0.0
-    */
-    bool operator()(wpi::detail::value_t lhs,
-                    wpi::detail::value_t rhs) const noexcept
-    {
-        return wpi::detail::operator<(lhs, rhs);
-    }
-};
-
-} // namespace std
-
-/*!
-@brief user-defined string literal for JSON values
-
-This operator implements a user-defined string literal for JSON objects. It
-can be used by adding `"_json"` to a string literal and returns a JSON object
-if no parse error occurred.
-
-@param[in] s  a string representation of a JSON object
-@param[in] n  the length of string @a s
-@return a JSON object
-
-@since version 1.0.0
-*/
-inline wpi::json operator "" _json(const char* s, std::size_t n)
-{
-    return wpi::json::parse(std::string_view(s, n));
-}
-
-/*!
-@brief user-defined string literal for JSON pointer
-
-This operator implements a user-defined string literal for JSON Pointers. It
-can be used by adding `"_json_pointer"` to a string literal and returns a JSON pointer
-object if no parse error occurred.
-
-@param[in] s  a string representation of a JSON Pointer
-@param[in] n  the length of string @a s
-@return a JSON pointer object
-
-@since version 2.0.0
-*/
-inline wpi::json::json_pointer operator "" _json_pointer(const char* s, std::size_t n)
-{
-    return wpi::json::json_pointer(std::string_view(s, n));
-}
-
-#ifndef WPI_JSON_IMPLEMENTATION
-
-// restore GCC/clang diagnostic settings
-#if defined(__clang__) || defined(__GNUC__) || defined(__GNUG__)
-    #pragma GCC diagnostic pop
-#endif
-#if defined(__clang__)
-    #pragma GCC diagnostic pop
-#endif
-
-// clean up
-#undef JSON_CATCH
-#undef JSON_THROW
-#undef JSON_TRY
-#undef JSON_LIKELY
-#undef JSON_UNLIKELY
-#undef NLOHMANN_BASIC_JSON_TPL_DECLARATION
-#undef NLOHMANN_BASIC_JSON_TPL
-#undef NLOHMANN_JSON_HAS_HELPER
-
-#endif  // WPI_JSON_IMPLEMENTATION
-
-#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/leb128.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/leb128.h
index 04752c6..e89d505 100644
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/leb128.h
+++ b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/leb128.h
@@ -8,8 +8,7 @@
 #include <stdint.h>
 
 #include <optional>
-
-#include "wpi/span.h"
+#include <span>
 
 namespace wpi {
 
@@ -100,7 +99,7 @@
    *           is left when function returns).
    * @return value (in std::optional)
    */
-  std::optional<uint64_t> ReadOne(span<const uint8_t>* in);
+  std::optional<uint64_t> ReadOne(std::span<const uint8_t>* in);
 
  private:
   uint64_t m_result = 0;
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/math b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/math
deleted file mode 100644
index 25f2a64..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/math
+++ /dev/null
@@ -1,20 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include "wpi/numbers"
-
-// clang-format off
-#ifdef _MSC_VER
-#pragma message("warning: Use <wpi/numbers> and wpi::numbers instead to reflect C++20 <numbers> and std::numbers")
-#else
-#warning "Use <wpi/numbers> and wpi::numbers instead to reflect C++20 <numbers> and std::numbers"
-#endif
-
-// clang-format on
-
-namespace wpi::math {
-using namespace wpi::numbers;
-}  // namespace wpi::math
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/numbers b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/numbers
deleted file mode 100644
index d45aee0..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/numbers
+++ /dev/null
@@ -1,64 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <type_traits>
-
-namespace wpi::numbers {
-
-template <typename T, typename = std::enable_if_t<std::is_floating_point_v<T>>>
-inline constexpr T e_v = 2.718281828459045235360287471352662498L;
-
-template <typename T, typename = std::enable_if_t<std::is_floating_point_v<T>>>
-inline constexpr T log2e_v = 1.442695040888963407359924681001892137L;
-
-template <typename T, typename = std::enable_if_t<std::is_floating_point_v<T>>>
-inline constexpr T log10e_v = 0.434294481903251827651128918916605082L;
-
-template <typename T, typename = std::enable_if_t<std::is_floating_point_v<T>>>
-inline constexpr T pi_v = 3.141592653589793238462643383279502884L;
-
-template <typename T, typename = std::enable_if_t<std::is_floating_point_v<T>>>
-inline constexpr T inv_pi_v = 0.318309886183790671537767526745028724L;
-
-template <typename T, typename = std::enable_if_t<std::is_floating_point_v<T>>>
-inline constexpr T inv_sqrtpi_v = 0.564189583547756286948079451560772586L;
-
-template <typename T, typename = std::enable_if_t<std::is_floating_point_v<T>>>
-inline constexpr T ln2_v = 0.693147180559945309417232121458176568L;
-
-template <typename T, typename = std::enable_if_t<std::is_floating_point_v<T>>>
-inline constexpr T ln10_v = 2.302585092994045684017991454684364208L;
-
-template <typename T, typename = std::enable_if_t<std::is_floating_point_v<T>>>
-inline constexpr T sqrt2_v = 1.414213562373095048801688724209698078L;
-
-template <typename T, typename = std::enable_if_t<std::is_floating_point_v<T>>>
-inline constexpr T sqrt3_v = 1.732050807568877293527446341505872366L;
-
-template <typename T, typename = std::enable_if_t<std::is_floating_point_v<T>>>
-inline constexpr T inv_sqrt3_v = 0.577350269189625764509148780501957456L;
-
-template <typename T, typename = std::enable_if_t<std::is_floating_point_v<T>>>
-inline constexpr T egamma_v = 0.577215664901532860606512090082402431L;
-
-template <typename T, typename = std::enable_if_t<std::is_floating_point_v<T>>>
-inline constexpr T phi_v = 1.618033988749894848204586834365638117L;
-
-inline constexpr double e = e_v<double>;
-inline constexpr double log2e = log2e_v<double>;
-inline constexpr double log10e = log10e_v<double>;
-inline constexpr double pi = pi_v<double>;
-inline constexpr double inv_pi = inv_pi_v<double>;
-inline constexpr double inv_sqrtpi = inv_sqrtpi_v<double>;
-inline constexpr double ln2 = ln2_v<double>;
-inline constexpr double ln10 = ln10_v<double>;
-inline constexpr double sqrt2 = sqrt2_v<double>;
-inline constexpr double sqrt3 = sqrt3_v<double>;
-inline constexpr double inv_sqrt3 = inv_sqrt3_v<double>;
-inline constexpr double egamma = egamma_v<double>;
-inline constexpr double phi = phi_v<double>;
-
-}  // namespace wpi::numbers
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/raw_istream.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/raw_istream.h
index 2371fc6..2f278c8 100644
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/raw_istream.h
+++ b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/raw_istream.h
@@ -9,13 +9,13 @@
 
 #include <algorithm>
 #include <cstddef>
+#include <span>
 #include <string>
 #include <string_view>
 #include <system_error>
 #include <vector>
 
 #include "wpi/SmallVector.h"
-#include "wpi/span.h"
 
 namespace wpi {
 
@@ -133,9 +133,9 @@
   // not const as we don't want to allow temporaries
   explicit raw_mem_istream(std::string& str)
       : raw_mem_istream(str.data(), str.size()) {}
-  explicit raw_mem_istream(span<const char> mem)
+  explicit raw_mem_istream(std::span<const char> mem)
       : raw_mem_istream(mem.data(), mem.size()) {}
-  explicit raw_mem_istream(span<const uint8_t> mem)
+  explicit raw_mem_istream(std::span<const uint8_t> mem)
       : raw_mem_istream(reinterpret_cast<const char*>(mem.data()), mem.size()) {
   }
   explicit raw_mem_istream(const char* str)
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/raw_os_ostream.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/raw_os_ostream.h
deleted file mode 100644
index 4335e02..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/raw_os_ostream.h
+++ /dev/null
@@ -1,42 +0,0 @@
-//===- raw_os_ostream.h - std::ostream adaptor for raw_ostream --*- C++ -*-===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-//
-//  This file defines the raw_os_ostream class.
-//
-//===----------------------------------------------------------------------===//
-
-#ifndef WPIUTIL_WPI_RAW_OS_OSTREAM_H
-#define WPIUTIL_WPI_RAW_OS_OSTREAM_H
-
-#include "wpi/raw_ostream.h"
-#include <iosfwd>
-
-namespace wpi {
-
-/// raw_os_ostream - A raw_ostream that writes to an std::ostream.  This is a
-/// simple adaptor class.  It does not check for output errors; clients should
-/// use the underlying stream to detect errors.
-class raw_os_ostream : public raw_ostream {
-  std::ostream &OS;
-
-  /// write_impl - See raw_ostream::write_impl.
-  void write_impl(const char *Ptr, size_t Size) override;
-
-  /// current_pos - Return the current position within the stream, not
-  /// counting the bytes currently in the buffer.
-  uint64_t current_pos() const override;
-
-public:
-  raw_os_ostream(std::ostream &O) : OS(O) {}
-  ~raw_os_ostream() override;
-};
-
-} // end wpi namespace
-
-#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/raw_ostream.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/raw_ostream.h
deleted file mode 100644
index 84ec925..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/raw_ostream.h
+++ /dev/null
@@ -1,644 +0,0 @@
-//===--- raw_ostream.h - Raw output stream ----------------------*- C++ -*-===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-//
-//  This file defines the raw_ostream class.
-//
-//===----------------------------------------------------------------------===//
-
-#ifndef WPIUTIL_WPI_RAW_OSTREAM_H
-#define WPIUTIL_WPI_RAW_OSTREAM_H
-
-#include "wpi/SmallVector.h"
-#include "wpi/span.h"
-#include <cassert>
-#include <cstddef>
-#include <cstdint>
-#include <cstring>
-#include <string>
-#include <string_view>
-#include <vector>
-#include <system_error>
-
-namespace fs {
-enum FileAccess : unsigned;
-enum OpenFlags : unsigned;
-enum CreationDisposition : unsigned;
-} // end namespace fs
-
-namespace wpi {
-
-/// This class implements an extremely fast bulk output stream that can *only*
-/// output to a stream.  It does not support seeking, reopening, rewinding, line
-/// buffered disciplines etc. It is a simple buffer that outputs
-/// a chunk at a time.
-class raw_ostream {
-private:
-  /// The buffer is handled in such a way that the buffer is
-  /// uninitialized, unbuffered, or out of space when OutBufCur >=
-  /// OutBufEnd. Thus a single comparison suffices to determine if we
-  /// need to take the slow path to write a single character.
-  ///
-  /// The buffer is in one of three states:
-  ///  1. Unbuffered (BufferMode == Unbuffered)
-  ///  1. Uninitialized (BufferMode != Unbuffered && OutBufStart == 0).
-  ///  2. Buffered (BufferMode != Unbuffered && OutBufStart != 0 &&
-  ///               OutBufEnd - OutBufStart >= 1).
-  ///
-  /// If buffered, then the raw_ostream owns the buffer if (BufferMode ==
-  /// InternalBuffer); otherwise the buffer has been set via SetBuffer and is
-  /// managed by the subclass.
-  ///
-  /// If a subclass installs an external buffer using SetBuffer then it can wait
-  /// for a \see write_impl() call to handle the data which has been put into
-  /// this buffer.
-  char *OutBufStart, *OutBufEnd, *OutBufCur;
-
-  enum BufferKind {
-    Unbuffered = 0,
-    InternalBuffer,
-    ExternalBuffer
-  } BufferMode;
-
-public:
-  // color order matches ANSI escape sequence, don't change
-  enum Colors {
-    BLACK = 0,
-    RED,
-    GREEN,
-    YELLOW,
-    BLUE,
-    MAGENTA,
-    CYAN,
-    WHITE,
-    SAVEDCOLOR
-  };
-
-  explicit raw_ostream(bool unbuffered = false)
-      : BufferMode(unbuffered ? Unbuffered : InternalBuffer) {
-    // Start out ready to flush.
-    OutBufStart = OutBufEnd = OutBufCur = nullptr;
-  }
-
-  raw_ostream(const raw_ostream &) = delete;
-  void operator=(const raw_ostream &) = delete;
-
-  virtual ~raw_ostream();
-
-  /// tell - Return the current offset with the file.
-  uint64_t tell() const { return current_pos() + GetNumBytesInBuffer(); }
-
-  //===--------------------------------------------------------------------===//
-  // Configuration Interface
-  //===--------------------------------------------------------------------===//
-
-  /// Set the stream to be buffered, with an automatically determined buffer
-  /// size.
-  void SetBuffered();
-
-  /// Set the stream to be buffered, using the specified buffer size.
-  void SetBufferSize(size_t Size) {
-    flush();
-    SetBufferAndMode(new char[Size], Size, InternalBuffer);
-  }
-
-  size_t GetBufferSize() const {
-    // If we're supposed to be buffered but haven't actually gotten around
-    // to allocating the buffer yet, return the value that would be used.
-    if (BufferMode != Unbuffered && OutBufStart == nullptr)
-      return preferred_buffer_size();
-
-    // Otherwise just return the size of the allocated buffer.
-    return OutBufEnd - OutBufStart;
-  }
-
-  /// Set the stream to be unbuffered. When unbuffered, the stream will flush
-  /// after every write. This routine will also flush the buffer immediately
-  /// when the stream is being set to unbuffered.
-  void SetUnbuffered() {
-    flush();
-    SetBufferAndMode(nullptr, 0, Unbuffered);
-  }
-
-  size_t GetNumBytesInBuffer() const {
-    return OutBufCur - OutBufStart;
-  }
-
-  //===--------------------------------------------------------------------===//
-  // Data Output Interface
-  //===--------------------------------------------------------------------===//
-
-  void flush() {
-    if (OutBufCur != OutBufStart)
-      flush_nonempty();
-  }
-
-  raw_ostream &operator<<(char C) {
-    if (OutBufCur >= OutBufEnd)
-      return write(C);
-    *OutBufCur++ = C;
-    return *this;
-  }
-
-  raw_ostream &operator<<(unsigned char C) {
-    if (OutBufCur >= OutBufEnd)
-      return write(C);
-    *OutBufCur++ = C;
-    return *this;
-  }
-
-  raw_ostream &operator<<(signed char C) {
-    if (OutBufCur >= OutBufEnd)
-      return write(C);
-    *OutBufCur++ = C;
-    return *this;
-  }
-
-  raw_ostream &operator<<(span<const uint8_t> Arr) {
-    // Inline fast path, particularly for arrays with a known length.
-    size_t Size = Arr.size();
-
-    // Make sure we can use the fast path.
-    if (Size > (size_t)(OutBufEnd - OutBufCur))
-      return write(Arr.data(), Size);
-
-    if (Size) {
-      memcpy(OutBufCur, Arr.data(), Size);
-      OutBufCur += Size;
-    }
-    return *this;
-  }
-
-  raw_ostream &operator<<(std::string_view Str) {
-    // Inline fast path, particularly for strings with a known length.
-    size_t Size = Str.size();
-
-    // Make sure we can use the fast path.
-    if (Size > (size_t)(OutBufEnd - OutBufCur))
-      return write(Str.data(), Size);
-
-    if (Size) {
-      memcpy(OutBufCur, Str.data(), Size);
-      OutBufCur += Size;
-    }
-    return *this;
-  }
-
-  raw_ostream &operator<<(const char *Str) {
-    // Inline fast path, particularly for constant strings where a sufficiently
-    // smart compiler will simplify strlen.
-
-    return this->operator<<(std::string_view(Str));
-  }
-
-  raw_ostream &operator<<(const std::string &Str) {
-    // Avoid the fast path, it would only increase code size for a marginal win.
-    return write(Str.data(), Str.length());
-  }
-
-  raw_ostream &operator<<(const SmallVectorImpl<char> &Str) {
-    return write(Str.data(), Str.size());
-  }
-
-  raw_ostream &operator<<(const std::vector<uint8_t> &Arr) {
-    // Avoid the fast path, it would only increase code size for a marginal win.
-    return write(Arr.data(), Arr.size());
-  }
-
-  raw_ostream &operator<<(const SmallVectorImpl<uint8_t> &Arr) {
-    return write(Arr.data(), Arr.size());
-  }
-
-  /// Output \p Str, turning '\\', '\t', '\n', '"', and anything that doesn't
-  /// satisfy wpi::isPrint into an escape sequence.
-  raw_ostream &write_escaped(std::string_view Str, bool UseHexEscapes = false);
-
-  raw_ostream &write(unsigned char C);
-  raw_ostream &write(const char *Ptr, size_t Size);
-  raw_ostream &write(const uint8_t *Ptr, size_t Size) {
-    return write(reinterpret_cast<const char *>(Ptr), Size);
-  }
-
-  /// indent - Insert 'NumSpaces' spaces.
-  raw_ostream &indent(unsigned NumSpaces);
-
-  /// write_zeros - Insert 'NumZeros' nulls.
-  raw_ostream &write_zeros(unsigned NumZeros);
-
-  /// Changes the foreground color of text that will be output from this point
-  /// forward.
-  /// @param Color ANSI color to use, the special SAVEDCOLOR can be used to
-  /// change only the bold attribute, and keep colors untouched
-  /// @param Bold bold/brighter text, default false
-  /// @param BG if true change the background, default: change foreground
-  /// @returns itself so it can be used within << invocations
-  virtual raw_ostream &changeColor(enum Colors Color,
-                                   bool Bold = false,
-                                   bool BG = false) {
-    (void)Color;
-    (void)Bold;
-    (void)BG;
-    return *this;
-  }
-
-  /// Resets the colors to terminal defaults. Call this when you are done
-  /// outputting colored text, or before program exit.
-  virtual raw_ostream &resetColor() { return *this; }
-
-  /// Reverses the foreground and background colors.
-  virtual raw_ostream &reverseColor() { return *this; }
-
-  /// This function determines if this stream is connected to a "tty" or
-  /// "console" window. That is, the output would be displayed to the user
-  /// rather than being put on a pipe or stored in a file.
-  virtual bool is_displayed() const { return false; }
-
-  /// This function determines if this stream is displayed and supports colors.
-  virtual bool has_colors() const { return is_displayed(); }
-
-  //===--------------------------------------------------------------------===//
-  // Subclass Interface
-  //===--------------------------------------------------------------------===//
-
-private:
-  /// The is the piece of the class that is implemented by subclasses.  This
-  /// writes the \p Size bytes starting at
-  /// \p Ptr to the underlying stream.
-  ///
-  /// This function is guaranteed to only be called at a point at which it is
-  /// safe for the subclass to install a new buffer via SetBuffer.
-  ///
-  /// \param Ptr The start of the data to be written. For buffered streams this
-  /// is guaranteed to be the start of the buffer.
-  ///
-  /// \param Size The number of bytes to be written.
-  ///
-  /// \invariant { Size > 0 }
-  virtual void write_impl(const char *Ptr, size_t Size) = 0;
-
-  // An out of line virtual method to provide a home for the class vtable.
-  virtual void handle();
-
-  /// Return the current position within the stream, not counting the bytes
-  /// currently in the buffer.
-  virtual uint64_t current_pos() const = 0;
-
-protected:
-  /// Use the provided buffer as the raw_ostream buffer. This is intended for
-  /// use only by subclasses which can arrange for the output to go directly
-  /// into the desired output buffer, instead of being copied on each flush.
-  void SetBuffer(char *BufferStart, size_t Size) {
-    SetBufferAndMode(BufferStart, Size, ExternalBuffer);
-  }
-
-  /// Return an efficient buffer size for the underlying output mechanism.
-  virtual size_t preferred_buffer_size() const;
-
-  /// Return the beginning of the current stream buffer, or 0 if the stream is
-  /// unbuffered.
-  const char *getBufferStart() const { return OutBufStart; }
-
-  //===--------------------------------------------------------------------===//
-  // Private Interface
-  //===--------------------------------------------------------------------===//
-private:
-  /// Install the given buffer and mode.
-  void SetBufferAndMode(char *BufferStart, size_t Size, BufferKind Mode);
-
-  /// Flush the current buffer, which is known to be non-empty. This outputs the
-  /// currently buffered data and resets the buffer to empty.
-  void flush_nonempty();
-
-  /// Copy data into the buffer. Size must not be greater than the number of
-  /// unused bytes in the buffer.
-  void copy_to_buffer(const char *Ptr, size_t Size);
-
-  virtual void anchor();
-};
-
-/// An abstract base class for streams implementations that also support a
-/// pwrite operation. This is useful for code that can mostly stream out data,
-/// but needs to patch in a header that needs to know the output size.
-class raw_pwrite_stream : public raw_ostream {
-  virtual void pwrite_impl(const char *Ptr, size_t Size, uint64_t Offset) = 0;
-  void anchor() override;
-
-public:
-  explicit raw_pwrite_stream(bool Unbuffered = false)
-      : raw_ostream(Unbuffered) {}
-  void pwrite(const char *Ptr, size_t Size, uint64_t Offset) {
-#ifndef NDBEBUG
-    uint64_t Pos = tell();
-    // /dev/null always reports a pos of 0, so we cannot perform this check
-    // in that case.
-    if (Pos)
-      assert(Size + Offset <= Pos && "We don't support extending the stream");
-#endif
-    pwrite_impl(Ptr, Size, Offset);
-  }
-};
-
-//===----------------------------------------------------------------------===//
-// File Output Streams
-//===----------------------------------------------------------------------===//
-
-/// A raw_ostream that writes to a file descriptor.
-///
-class raw_fd_ostream : public raw_pwrite_stream {
-  int FD;
-  bool ShouldClose;
-
-  bool SupportsSeeking;
-
-#ifdef _WIN32
-  /// True if this fd refers to a Windows console device. Mintty and other
-  /// terminal emulators are TTYs, but they are not consoles.
-  bool IsWindowsConsole = false;
-#endif
-
-  std::error_code EC;
-
-  uint64_t pos;
-
-  /// See raw_ostream::write_impl.
-  void write_impl(const char *Ptr, size_t Size) override;
-
-  void pwrite_impl(const char *Ptr, size_t Size, uint64_t Offset) override;
-
-  /// Return the current position within the stream, not counting the bytes
-  /// currently in the buffer.
-  uint64_t current_pos() const override { return pos; }
-
-  /// Determine an efficient buffer size.
-  size_t preferred_buffer_size() const override;
-
-  /// Set the flag indicating that an output error has been encountered.
-  void error_detected(std::error_code EC) { this->EC = EC; }
-
-  void anchor() override;
-
-public:
-  /// Open the specified file for writing. If an error occurs, information
-  /// about the error is put into EC, and the stream should be immediately
-  /// destroyed;
-  /// \p Flags allows optional flags to control how the file will be opened.
-  ///
-  /// As a special case, if Filename is "-", then the stream will use
-  /// STDOUT_FILENO instead of opening a file. This will not close the stdout
-  /// descriptor.
-  raw_fd_ostream(std::string_view Filename, std::error_code &EC);
-  raw_fd_ostream(std::string_view Filename, std::error_code &EC,
-                 fs::CreationDisposition Disp);
-  raw_fd_ostream(std::string_view Filename, std::error_code &EC,
-                 fs::FileAccess Access);
-  raw_fd_ostream(std::string_view Filename, std::error_code &EC,
-                 fs::OpenFlags Flags);
-  raw_fd_ostream(std::string_view Filename, std::error_code &EC,
-                 fs::CreationDisposition Disp, fs::FileAccess Access,
-                 fs::OpenFlags Flags);
-
-  /// FD is the file descriptor that this writes to.  If ShouldClose is true,
-  /// this closes the file when the stream is destroyed. If FD is for stdout or
-  /// stderr, it will not be closed.
-  raw_fd_ostream(int fd, bool shouldClose, bool unbuffered=false);
-
-  ~raw_fd_ostream() override;
-
-  /// Manually flush the stream and close the file. Note that this does not call
-  /// fsync.
-  void close();
-
-  bool supportsSeeking() { return SupportsSeeking; }
-
-  /// Flushes the stream and repositions the underlying file descriptor position
-  /// to the offset specified from the beginning of the file.
-  uint64_t seek(uint64_t off);
-
-  std::error_code error() const { return EC; }
-
-  /// Return the value of the flag in this raw_fd_ostream indicating whether an
-  /// output error has been encountered.
-  /// This doesn't implicitly flush any pending output.  Also, it doesn't
-  /// guarantee to detect all errors unless the stream has been closed.
-  bool has_error() const { return bool(EC); }
-
-  /// Set the flag read by has_error() to false. If the error flag is set at the
-  /// time when this raw_ostream's destructor is called, report_fatal_error is
-  /// called to report the error. Use clear_error() after handling the error to
-  /// avoid this behavior.
-  ///
-  ///   "Errors should never pass silently.
-  ///    Unless explicitly silenced."
-  ///      - from The Zen of Python, by Tim Peters
-  ///
-  void clear_error() { EC = std::error_code(); }
-};
-
-/// This returns a reference to a raw_ostream for standard output. Use it like:
-/// outs() << "foo" << "bar";
-raw_ostream &outs();
-
-/// This returns a reference to a raw_ostream for standard error. Use it like:
-/// errs() << "foo" << "bar";
-raw_ostream &errs();
-
-/// This returns a reference to a raw_ostream which simply discards output.
-raw_ostream &nulls();
-
-//===----------------------------------------------------------------------===//
-// Output Stream Adaptors
-//===----------------------------------------------------------------------===//
-
-/// A raw_ostream that writes to an std::string.  This is a simple adaptor
-/// class. This class does not encounter output errors.
-class raw_string_ostream : public raw_ostream {
-  std::string &OS;
-
-  /// See raw_ostream::write_impl.
-  void write_impl(const char *Ptr, size_t Size) override;
-
-  /// Return the current position within the stream, not counting the bytes
-  /// currently in the buffer.
-  uint64_t current_pos() const override { return OS.size(); }
-
-public:
-  explicit raw_string_ostream(std::string &O) : OS(O) {}
-  ~raw_string_ostream() override;
-
-  /// Flushes the stream contents to the target string and returns  the string's
-  /// reference.
-  std::string& str() {
-    flush();
-    return OS;
-  }
-};
-
-/// A raw_ostream that writes to an SmallVector or SmallString.  This is a
-/// simple adaptor class. This class does not encounter output errors.
-/// raw_svector_ostream operates without a buffer, delegating all memory
-/// management to the SmallString. Thus the SmallString is always up-to-date,
-/// may be used directly and there is no need to call flush().
-class raw_svector_ostream : public raw_pwrite_stream {
-  SmallVectorImpl<char> &OS;
-
-  /// See raw_ostream::write_impl.
-  void write_impl(const char *Ptr, size_t Size) override;
-
-  void pwrite_impl(const char *Ptr, size_t Size, uint64_t Offset) override;
-
-  /// Return the current position within the stream.
-  uint64_t current_pos() const override;
-
-public:
-  /// Construct a new raw_svector_ostream.
-  ///
-  /// \param O The vector to write to; this should generally have at least 128
-  /// bytes free to avoid any extraneous memory overhead.
-  explicit raw_svector_ostream(SmallVectorImpl<char> &O) : OS(O) {
-    SetUnbuffered();
-  }
-
-  ~raw_svector_ostream() override = default;
-
-  void flush() = delete;
-
-  /// Return a std::string_view for the vector contents.
-  std::string_view str() { return std::string_view(OS.data(), OS.size()); }
-};
-
-/// A raw_ostream that writes to a vector.  This is a
-/// simple adaptor class. This class does not encounter output errors.
-/// raw_vector_ostream operates without a buffer, delegating all memory
-/// management to the vector. Thus the vector is always up-to-date,
-/// may be used directly and there is no need to call flush().
-class raw_vector_ostream : public raw_pwrite_stream {
-  std::vector<char> &OS;
-
-  /// See raw_ostream::write_impl.
-  void write_impl(const char *Ptr, size_t Size) override;
-
-  void pwrite_impl(const char *Ptr, size_t Size, uint64_t Offset) override;
-
-  /// Return the current position within the stream.
-  uint64_t current_pos() const override;
-
-public:
-  /// Construct a new raw_svector_ostream.
-  ///
-  /// \param O The vector to write to; this should generally have at least 128
-  /// bytes free to avoid any extraneous memory overhead.
-  explicit raw_vector_ostream(std::vector<char> &O) : OS(O) {
-    SetUnbuffered();
-  }
-
-  ~raw_vector_ostream() override = default;
-
-  void flush() = delete;
-
-  /// Return a std::string_view for the vector contents.
-  std::string_view str() { return std::string_view(OS.data(), OS.size()); }
-};
-
-/// A raw_ostream that writes to an SmallVector or SmallString.  This is a
-/// simple adaptor class. This class does not encounter output errors.
-/// raw_svector_ostream operates without a buffer, delegating all memory
-/// management to the SmallString. Thus the SmallString is always up-to-date,
-/// may be used directly and there is no need to call flush().
-class raw_usvector_ostream : public raw_pwrite_stream {
-  SmallVectorImpl<uint8_t> &OS;
-
-  /// See raw_ostream::write_impl.
-  void write_impl(const char *Ptr, size_t Size) override;
-
-  void pwrite_impl(const char *Ptr, size_t Size, uint64_t Offset) override;
-
-  /// Return the current position within the stream.
-  uint64_t current_pos() const override;
-
-public:
-  /// Construct a new raw_svector_ostream.
-  ///
-  /// \param O The vector to write to; this should generally have at least 128
-  /// bytes free to avoid any extraneous memory overhead.
-  explicit raw_usvector_ostream(SmallVectorImpl<uint8_t> &O) : OS(O) {
-    SetUnbuffered();
-  }
-
-  ~raw_usvector_ostream() override = default;
-
-  void flush() = delete;
-
-  /// Return an span for the vector contents.
-  span<uint8_t> array() { return {OS.data(), OS.size()}; }
-  span<const uint8_t> array() const { return {OS.data(), OS.size()}; }
-};
-
-/// A raw_ostream that writes to a vector.  This is a
-/// simple adaptor class. This class does not encounter output errors.
-/// raw_vector_ostream operates without a buffer, delegating all memory
-/// management to the vector. Thus the vector is always up-to-date,
-/// may be used directly and there is no need to call flush().
-class raw_uvector_ostream : public raw_pwrite_stream {
-  std::vector<uint8_t> &OS;
-
-  /// See raw_ostream::write_impl.
-  void write_impl(const char *Ptr, size_t Size) override;
-
-  void pwrite_impl(const char *Ptr, size_t Size, uint64_t Offset) override;
-
-  /// Return the current position within the stream.
-  uint64_t current_pos() const override;
-
-public:
-  /// Construct a new raw_svector_ostream.
-  ///
-  /// \param O The vector to write to; this should generally have at least 128
-  /// bytes free to avoid any extraneous memory overhead.
-  explicit raw_uvector_ostream(std::vector<uint8_t> &O) : OS(O) {
-    SetUnbuffered();
-  }
-
-  ~raw_uvector_ostream() override = default;
-
-  void flush() = delete;
-
-  /// Return a span for the vector contents.
-  span<uint8_t> array() { return {OS.data(), OS.size()}; }
-  span<const uint8_t> array() const { return {OS.data(), OS.size()}; }
-};
-
-
-/// A raw_ostream that discards all output.
-class raw_null_ostream : public raw_pwrite_stream {
-  /// See raw_ostream::write_impl.
-  void write_impl(const char *Ptr, size_t size) override;
-  void pwrite_impl(const char *Ptr, size_t Size, uint64_t Offset) override;
-
-  /// Return the current position within the stream, not counting the bytes
-  /// currently in the buffer.
-  uint64_t current_pos() const override;
-
-public:
-  explicit raw_null_ostream() = default;
-  ~raw_null_ostream() override;
-};
-
-class buffer_ostream : public raw_svector_ostream {
-  raw_ostream &OS;
-  SmallVector<char, 0> Buffer;
-
-  virtual void anchor() override;
-
-public:
-  buffer_ostream(raw_ostream &OS) : raw_svector_ostream(Buffer), OS(OS) {}
-  ~buffer_ostream() override { OS << str(); }
-};
-
-} // end namespace wpi
-
-#endif // LLVM_SUPPORT_RAW_OSTREAM_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/raw_socket_istream.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/raw_socket_istream.h
deleted file mode 100644
index f6899e2..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/raw_socket_istream.h
+++ /dev/null
@@ -1,31 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_RAW_SOCKET_ISTREAM_H_
-#define WPIUTIL_WPI_RAW_SOCKET_ISTREAM_H_
-
-#include "wpi/raw_istream.h"
-
-namespace wpi {
-
-class NetworkStream;
-
-class raw_socket_istream : public raw_istream {
- public:
-  explicit raw_socket_istream(NetworkStream& stream, int timeout = 0)
-      : m_stream(stream), m_timeout(timeout) {}
-
-  void close() override;
-  size_t in_avail() const override;
-
- private:
-  void read_impl(void* data, size_t len) override;
-
-  NetworkStream& m_stream;
-  int m_timeout;
-};
-
-}  // namespace wpi
-
-#endif  // WPIUTIL_WPI_RAW_SOCKET_ISTREAM_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/raw_socket_ostream.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/raw_socket_ostream.h
deleted file mode 100644
index 5cdeb41..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/raw_socket_ostream.h
+++ /dev/null
@@ -1,39 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_RAW_SOCKET_OSTREAM_H_
-#define WPIUTIL_WPI_RAW_SOCKET_OSTREAM_H_
-
-#include "wpi/raw_ostream.h"
-
-namespace wpi {
-
-class NetworkStream;
-
-class raw_socket_ostream : public raw_ostream {
- public:
-  raw_socket_ostream(NetworkStream& stream, bool shouldClose)
-      : m_stream(stream), m_shouldClose(shouldClose) {}
-  ~raw_socket_ostream() override;
-
-  void close();
-
-  bool has_error() const { return m_error; }
-  void clear_error() { m_error = false; }
-
- protected:
-  void error_detected() { m_error = true; }
-
- private:
-  void write_impl(const char* data, size_t len) override;
-  uint64_t current_pos() const override;
-
-  NetworkStream& m_stream;
-  bool m_error = false;
-  bool m_shouldClose;
-};
-
-}  // namespace wpi
-
-#endif  // WPIUTIL_WPI_RAW_SOCKET_OSTREAM_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/raw_uv_ostream.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/raw_uv_ostream.h
deleted file mode 100644
index 4773c61..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/raw_uv_ostream.h
+++ /dev/null
@@ -1,74 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_RAW_UV_OSTREAM_H_
-#define WPIUTIL_WPI_RAW_UV_OSTREAM_H_
-
-#include <functional>
-#include <utility>
-
-#include "wpi/SmallVector.h"
-#include "wpi/raw_ostream.h"
-#include "wpi/span.h"
-#include "wpi/uv/Buffer.h"
-
-namespace wpi {
-
-/**
- * raw_ostream style output to a SmallVector of uv::Buffer buffers.  Fixed-size
- * buffers are allocated and appended as necessary to fit the data being output.
- * The SmallVector need not be empty at start.
- */
-class raw_uv_ostream : public raw_ostream {
- public:
-  /**
-   * Construct a new raw_uv_ostream.
-   * @param bufs Buffers vector.  NOT cleared on construction.
-   * @param allocSize Size to allocate for each buffer; allocation will be
-   *                  performed using Buffer::Allocate().
-   */
-  raw_uv_ostream(SmallVectorImpl<uv::Buffer>& bufs, size_t allocSize)
-      : m_bufs(bufs), m_alloc([=] { return uv::Buffer::Allocate(allocSize); }) {
-    SetUnbuffered();
-  }
-
-  /**
-   * Construct a new raw_uv_ostream.
-   * @param bufs Buffers vector.  NOT cleared on construction.
-   * @param alloc Allocator.
-   */
-  raw_uv_ostream(SmallVectorImpl<uv::Buffer>& bufs,
-                 std::function<uv::Buffer()> alloc)
-      : m_bufs(bufs), m_alloc(std::move(alloc)) {
-    SetUnbuffered();
-  }
-
-  ~raw_uv_ostream() override = default;
-
-  /**
-   * Returns an span to the buffers.
-   */
-  span<uv::Buffer> bufs() { return m_bufs; }
-
-  void flush() = delete;
-
-  /**
-   * Resets the amount of allocated space.
-   */
-  void reset() { m_left = 0; }
-
- private:
-  void write_impl(const char* data, size_t len) override;
-  uint64_t current_pos() const override;
-
-  SmallVectorImpl<uv::Buffer>& m_bufs;
-  std::function<uv::Buffer()> m_alloc;
-
-  // How much allocated space is left in the current buffer.
-  size_t m_left = 0;
-};
-
-}  // namespace wpi
-
-#endif  // WPIUTIL_WPI_RAW_UV_OSTREAM_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/scope b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/scope
new file mode 100644
index 0000000..e25badb
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/scope
@@ -0,0 +1,37 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include <utility>
+
+namespace wpi {
+
+template <typename F>
+class scope_exit {
+ public:
+  explicit scope_exit(F&& f) noexcept : m_f{std::forward<F>(f)} {}
+
+  ~scope_exit() {
+    if (m_active) {
+      m_f();
+    }
+  }
+
+  scope_exit(scope_exit&& rhs) noexcept
+      : m_f{std::move(rhs.m_f)}, m_active{rhs.m_active} {
+    rhs.release();
+  }
+
+  scope_exit(const scope_exit&) = delete;
+  scope_exit& operator=(const scope_exit&) = delete;
+
+  void release() noexcept { m_active = false; }
+
+ private:
+  F m_f;
+  bool m_active = true;
+};
+
+}  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/sendable/SendableBuilder.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/sendable/SendableBuilder.h
index e092a1e..2287b73 100644
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/sendable/SendableBuilder.h
+++ b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/sendable/SendableBuilder.h
@@ -6,12 +6,12 @@
 
 #include <functional>
 #include <memory>
+#include <span>
 #include <string>
 #include <string_view>
 #include <vector>
 
 #include "wpi/SmallVector.h"
-#include "wpi/span.h"
 
 namespace wpi {
 
@@ -60,6 +60,28 @@
                                   std::function<void(bool)> setter) = 0;
 
   /**
+   * Add an integer property.
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  virtual void AddIntegerProperty(std::string_view key,
+                                  std::function<int64_t()> getter,
+                                  std::function<void(int64_t)> setter) = 0;
+
+  /**
+   * Add a float property.
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  virtual void AddFloatProperty(std::string_view key,
+                                std::function<float()> getter,
+                                std::function<void(float)> setter) = 0;
+
+  /**
    * Add a double property.
    *
    * @param key     property name
@@ -90,7 +112,29 @@
    */
   virtual void AddBooleanArrayProperty(
       std::string_view key, std::function<std::vector<int>()> getter,
-      std::function<void(wpi::span<const int>)> setter) = 0;
+      std::function<void(std::span<const int>)> setter) = 0;
+
+  /**
+   * Add an integer array property.
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  virtual void AddIntegerArrayProperty(
+      std::string_view key, std::function<std::vector<int64_t>()> getter,
+      std::function<void(std::span<const int64_t>)> setter) = 0;
+
+  /**
+   * Add a float array property.
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  virtual void AddFloatArrayProperty(
+      std::string_view key, std::function<std::vector<float>()> getter,
+      std::function<void(std::span<const float>)> setter) = 0;
 
   /**
    * Add a double array property.
@@ -101,7 +145,7 @@
    */
   virtual void AddDoubleArrayProperty(
       std::string_view key, std::function<std::vector<double>()> getter,
-      std::function<void(wpi::span<const double>)> setter) = 0;
+      std::function<void(std::span<const double>)> setter) = 0;
 
   /**
    * Add a string array property.
@@ -112,18 +156,20 @@
    */
   virtual void AddStringArrayProperty(
       std::string_view key, std::function<std::vector<std::string>()> getter,
-      std::function<void(wpi::span<const std::string>)> setter) = 0;
+      std::function<void(std::span<const std::string>)> setter) = 0;
 
   /**
    * Add a raw property.
    *
-   * @param key     property name
-   * @param getter  getter function (returns current value)
-   * @param setter  setter function (sets new value)
+   * @param key         property name
+   * @param typeString  type string
+   * @param getter      getter function (returns current value)
+   * @param setter      setter function (sets new value)
    */
-  virtual void AddRawProperty(std::string_view key,
-                              std::function<std::string()> getter,
-                              std::function<void(std::string_view)> setter) = 0;
+  virtual void AddRawProperty(
+      std::string_view key, std::string_view typeString,
+      std::function<std::vector<uint8_t>()> getter,
+      std::function<void(std::span<const uint8_t>)> setter) = 0;
 
   /**
    * Add a string property (SmallString form).
@@ -146,9 +192,36 @@
    */
   virtual void AddSmallBooleanArrayProperty(
       std::string_view key,
-      std::function<wpi::span<const int>(wpi::SmallVectorImpl<int>& buf)>
+      std::function<std::span<const int>(wpi::SmallVectorImpl<int>& buf)>
           getter,
-      std::function<void(wpi::span<const int>)> setter) = 0;
+      std::function<void(std::span<const int>)> setter) = 0;
+
+  /**
+   * Add an integer array property (SmallVector form).
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  virtual void AddSmallIntegerArrayProperty(
+      std::string_view key,
+      std::function<
+          std::span<const int64_t>(wpi::SmallVectorImpl<int64_t>& buf)>
+          getter,
+      std::function<void(std::span<const int64_t>)> setter) = 0;
+
+  /**
+   * Add a float array property (SmallVector form).
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  virtual void AddSmallFloatArrayProperty(
+      std::string_view key,
+      std::function<std::span<const float>(wpi::SmallVectorImpl<float>& buf)>
+          getter,
+      std::function<void(std::span<const float>)> setter) = 0;
 
   /**
    * Add a double array property (SmallVector form).
@@ -159,9 +232,9 @@
    */
   virtual void AddSmallDoubleArrayProperty(
       std::string_view key,
-      std::function<wpi::span<const double>(wpi::SmallVectorImpl<double>& buf)>
+      std::function<std::span<const double>(wpi::SmallVectorImpl<double>& buf)>
           getter,
-      std::function<void(wpi::span<const double>)> setter) = 0;
+      std::function<void(std::span<const double>)> setter) = 0;
 
   /**
    * Add a string array property (SmallVector form).
@@ -173,21 +246,23 @@
   virtual void AddSmallStringArrayProperty(
       std::string_view key,
       std::function<
-          wpi::span<const std::string>(wpi::SmallVectorImpl<std::string>& buf)>
+          std::span<const std::string>(wpi::SmallVectorImpl<std::string>& buf)>
           getter,
-      std::function<void(wpi::span<const std::string>)> setter) = 0;
+      std::function<void(std::span<const std::string>)> setter) = 0;
 
   /**
    * Add a raw property (SmallVector form).
    *
    * @param key     property name
+   * @param typeString  type string
    * @param getter  getter function (returns current value)
    * @param setter  setter function (sets new value)
    */
   virtual void AddSmallRawProperty(
-      std::string_view key,
-      std::function<std::string_view(wpi::SmallVectorImpl<char>& buf)> getter,
-      std::function<void(std::string_view)> setter) = 0;
+      std::string_view key, std::string_view typeString,
+      std::function<std::span<uint8_t>(wpi::SmallVectorImpl<uint8_t>& buf)>
+          getter,
+      std::function<void(std::span<const uint8_t>)> setter) = 0;
 
   /**
    * Gets the kind of backend being used.
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/sendable/SendableHelper.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/sendable/SendableHelper.h
index 5b6bbe3..f8dd703 100644
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/sendable/SendableHelper.h
+++ b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/sendable/SendableHelper.h
@@ -4,11 +4,6 @@
 
 #pragma once
 
-#include <memory>
-#include <string>
-#include <string_view>
-
-#include "wpi/deprecated.h"
 #include "wpi/sendable/SendableRegistry.h"
 
 namespace wpi {
@@ -48,123 +43,6 @@
     return *this;
   }
 
-  /**
-   * Gets the name of this Sendable object.
-   *
-   * @deprecated use SendableRegistry::GetName()
-   *
-   * @return Name
-   */
-  WPI_DEPRECATED("use SendableRegistry::GetName()")
-  std::string GetName() const {
-    return SendableRegistry::GetName(static_cast<const Derived*>(this));
-  }
-
-  /**
-   * Sets the name of this Sendable object.
-   *
-   * @deprecated use SendableRegistry::SetName()
-   *
-   * @param name name
-   */
-  WPI_DEPRECATED("use SendableRegistry::SetName()")
-  void SetName(std::string_view name) {
-    SendableRegistry::SetName(static_cast<Derived*>(this), name);
-  }
-
-  /**
-   * Sets both the subsystem name and device name of this Sendable object.
-   *
-   * @deprecated use SendableRegistry::SetName()
-   *
-   * @param subsystem subsystem name
-   * @param name device name
-   */
-  WPI_DEPRECATED("use SendableRegistry::SetName()")
-  void SetName(std::string_view subsystem, std::string_view name) {
-    SendableRegistry::SetName(static_cast<Derived*>(this), subsystem, name);
-  }
-
-  /**
-   * Gets the subsystem name of this Sendable object.
-   *
-   * @deprecated use SendableRegistry::GetSubsystem().
-   *
-   * @return Subsystem name
-   */
-  WPI_DEPRECATED("use SendableRegistry::GetSubsystem()")
-  std::string GetSubsystem() const {
-    return SendableRegistry::GetSubsystem(static_cast<const Derived*>(this));
-  }
-
-  /**
-   * Sets the subsystem name of this Sendable object.
-   *
-   * @deprecated use SendableRegistry::SetSubsystem()
-   *
-   * @param subsystem subsystem name
-   */
-  WPI_DEPRECATED("use SendableRegistry::SetSubsystem()")
-  void SetSubsystem(std::string_view subsystem) {
-    SendableRegistry::SetSubsystem(static_cast<Derived*>(this), subsystem);
-  }
-
- protected:
-  /**
-   * Add a child component.
-   *
-   * @deprecated use SendableRegistry::AddChild()
-   *
-   * @param child child component
-   */
-  WPI_DEPRECATED("use SendableRegistry::AddChild()")
-  void AddChild(std::shared_ptr<Sendable> child) {
-    SendableRegistry::AddChild(static_cast<Derived*>(this), child.get());
-  }
-
-  /**
-   * Add a child component.
-   *
-   * @deprecated use SendableRegistry::AddChild()
-   *
-   * @param child child component
-   */
-  WPI_DEPRECATED("use SendableRegistry::AddChild()")
-  void AddChild(void* child) {
-    SendableRegistry::AddChild(static_cast<Derived*>(this), child);
-  }
-
-  /**
-   * Sets the name of the sensor with a channel number.
-   *
-   * @deprecated use SendableRegistry::SetName()
-   *
-   * @param moduleType A string that defines the module name in the label for
-   *                   the value
-   * @param channel    The channel number the device is plugged into
-   */
-  WPI_DEPRECATED("use SendableRegistry::SetName()")
-  void SetName(std::string_view moduleType, int channel) {
-    SendableRegistry::SetName(static_cast<Derived*>(this), moduleType, channel);
-  }
-
-  /**
-   * Sets the name of the sensor with a module and channel number.
-   *
-   * @deprecated use SendableRegistry::SetName()
-   *
-   * @param moduleType   A string that defines the module name in the label for
-   *                     the value
-   * @param moduleNumber The number of the particular module type
-   * @param channel      The channel number the device is plugged into (usually
-   * PWM)
-   */
-  WPI_DEPRECATED("use SendableRegistry::SetName()")
-  void SetName(std::string_view moduleType, int moduleNumber, int channel) {
-    SendableRegistry::SetName(static_cast<Derived*>(this), moduleType,
-                              moduleNumber, channel);
-  }
-
  protected:
   SendableHelper() = default;
 
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/sendable/SendableRegistry.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/sendable/SendableRegistry.h
index a08f9e9..4639749 100644
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/sendable/SendableRegistry.h
+++ b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/sendable/SendableRegistry.h
@@ -20,7 +20,7 @@
  * The SendableRegistry class is the public interface for registering sensors
  * and actuators for use on dashboards and LiveWindow.
  */
-class SendableRegistry {
+class SendableRegistry final {
  public:
   SendableRegistry() = delete;
 
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/span.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/span.h
deleted file mode 100644
index cf71d79..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/span.h
+++ /dev/null
@@ -1,415 +0,0 @@
-
-/*
-This is an implementation of C++20's std::span
-http://www.open-std.org/jtc1/sc22/wg21/docs/papers/2019/n4820.pdf
-*/
-
-//          Copyright Tristan Brindle 2018.
-// Distributed under the Boost Software License, Version 1.0.
-//    (See accompanying file ../../LICENSE_1_0.txt or copy at
-//          https://www.boost.org/LICENSE_1_0.txt)
-
-#ifndef WPIUTIL_WPI_SPAN_HPP_INCLUDED
-#define WPIUTIL_WPI_SPAN_HPP_INCLUDED
-
-#include <array>
-#include <cassert>
-#include <cstddef>
-#include <cstdint>
-#include <type_traits>
-#if __cplusplus >= 202002L && __has_include(<span>)
-#include <span>
-#endif
-
-namespace wpi {
-
-inline constexpr std::size_t dynamic_extent = SIZE_MAX;
-
-template <typename ElementType, std::size_t Extent = dynamic_extent>
-class span;
-
-namespace detail {
-
-template <typename E, std::size_t S>
-struct span_storage {
-    constexpr span_storage() noexcept = default;
-
-    constexpr span_storage(E* p_ptr, std::size_t /*unused*/) noexcept
-       : ptr(p_ptr)
-    {}
-
-    E* ptr = nullptr;
-    static constexpr std::size_t size = S;
-};
-
-template <typename E>
-struct span_storage<E, dynamic_extent> {
-    constexpr span_storage() noexcept = default;
-
-    constexpr span_storage(E* p_ptr, std::size_t p_size) noexcept
-        : ptr(p_ptr), size(p_size)
-    {}
-
-    E* ptr = nullptr;
-    std::size_t size = 0;
-};
-
-template <typename T>
-using uncvref_t =
-    typename std::remove_cv<typename std::remove_reference<T>::type>::type;
-
-template <typename>
-struct is_span : std::false_type {};
-
-template <typename T, std::size_t S>
-struct is_span<span<T, S>> : std::true_type {};
-
-template <typename>
-struct is_std_array : std::false_type {};
-
-template <typename T, std::size_t N>
-struct is_std_array<std::array<T, N>> : std::true_type {};
-
-template <typename, typename = void>
-struct has_size_and_data : std::false_type {};
-
-template <typename T>
-struct has_size_and_data<T, std::void_t<decltype(std::size(std::declval<T>())),
-                                   decltype(std::data(std::declval<T>()))>>
-    : std::true_type {};
-
-template <typename C, typename U = uncvref_t<C>>
-struct is_container {
-    static constexpr bool value =
-        !is_span<U>::value && !is_std_array<U>::value &&
-        !std::is_array<U>::value && has_size_and_data<C>::value;
-};
-
-template <typename T>
-using remove_pointer_t = typename std::remove_pointer<T>::type;
-
-template <typename, typename, typename = void>
-struct is_container_element_type_compatible : std::false_type {};
-
-template <typename T, typename E>
-struct is_container_element_type_compatible<
-    T, E,
-    typename std::enable_if<
-        !std::is_same<typename std::remove_cv<decltype(
-                          std::data(std::declval<T>()))>::type,
-                      void>::value>::type>
-    : std::is_convertible<
-          remove_pointer_t<decltype(std::data(std::declval<T>()))> (*)[],
-          E (*)[]> {};
-
-template <typename, typename = size_t>
-struct is_complete : std::false_type {};
-
-template <typename T>
-struct is_complete<T, decltype(sizeof(T))> : std::true_type {};
-
-} // namespace detail
-
-template <typename ElementType, std::size_t Extent>
-class span {
-    static_assert(std::is_object<ElementType>::value,
-                  "A span's ElementType must be an object type (not a "
-                  "reference type or void)");
-    static_assert(detail::is_complete<ElementType>::value,
-                  "A span's ElementType must be a complete type (not a forward "
-                  "declaration)");
-    static_assert(!std::is_abstract<ElementType>::value,
-                  "A span's ElementType cannot be an abstract class type");
-
-    using storage_type = detail::span_storage<ElementType, Extent>;
-
-public:
-    // constants and types
-    using element_type = ElementType;
-    using value_type = typename std::remove_cv<ElementType>::type;
-    using size_type = std::size_t;
-    using difference_type = std::ptrdiff_t;
-    using pointer = element_type*;
-    using const_pointer = const element_type*;
-    using reference = element_type&;
-    using const_reference = const element_type&;
-    using iterator = pointer;
-    using reverse_iterator = std::reverse_iterator<iterator>;
-
-    static constexpr size_type extent = Extent;
-
-    // [span.cons], span constructors, copy, assignment, and destructor
-    template <
-        std::size_t E = Extent,
-        typename std::enable_if<(E == dynamic_extent || E <= 0), int>::type = 0>
-    constexpr span() noexcept
-    {}
-
-    constexpr span(pointer ptr, size_type count)
-        : storage_(ptr, count)
-    {
-        assert(extent == dynamic_extent || count == extent);
-    }
-
-    constexpr span(pointer first_elem, pointer last_elem)
-        : storage_(first_elem, last_elem - first_elem)
-    {
-        assert(extent == dynamic_extent ||
-                        last_elem - first_elem ==
-                            static_cast<std::ptrdiff_t>(extent));
-    }
-
-    template <std::size_t N, std::size_t E = Extent,
-              typename std::enable_if<
-                  (E == dynamic_extent || N == E) &&
-                      detail::is_container_element_type_compatible<
-                          element_type (&)[N], ElementType>::value,
-                  int>::type = 0>
-    constexpr span(element_type (&arr)[N]) noexcept : storage_(arr, N)
-    {}
-
-    template <std::size_t N, std::size_t E = Extent,
-              typename std::enable_if<
-                  (E == dynamic_extent || N == E) &&
-                      detail::is_container_element_type_compatible<
-                          std::array<value_type, N>&, ElementType>::value,
-                  int>::type = 0>
-    constexpr span(std::array<value_type, N>& arr) noexcept
-        : storage_(arr.data(), N)
-    {}
-
-    template <std::size_t N, std::size_t E = Extent,
-              typename std::enable_if<
-                  (E == dynamic_extent || N == E) &&
-                      detail::is_container_element_type_compatible<
-                          const std::array<value_type, N>&, ElementType>::value,
-                  int>::type = 0>
-    constexpr span(const std::array<value_type, N>& arr) noexcept
-        : storage_(arr.data(), N)
-    {}
-
-    template <
-        typename Container, std::size_t E = Extent,
-        typename std::enable_if<
-            E == dynamic_extent && detail::is_container<Container>::value &&
-                detail::is_container_element_type_compatible<
-                    Container&, ElementType>::value,
-            int>::type = 0>
-    constexpr span(Container& cont)
-        : storage_(std::data(cont), std::size(cont))
-    {}
-
-    template <
-        typename Container, std::size_t E = Extent,
-        typename std::enable_if<
-            E == dynamic_extent && detail::is_container<Container>::value &&
-                detail::is_container_element_type_compatible<
-                    const Container&, ElementType>::value,
-            int>::type = 0>
-    constexpr span(const Container& cont)
-        : storage_(std::data(cont), std::size(cont))
-    {}
-
-    constexpr span(const span& other) noexcept = default;
-
-    template <typename OtherElementType, std::size_t OtherExtent,
-              typename std::enable_if<
-                  (Extent == OtherExtent || Extent == dynamic_extent) &&
-                      std::is_convertible<OtherElementType (*)[],
-                                          ElementType (*)[]>::value,
-                  int>::type = 0>
-    constexpr span(const span<OtherElementType, OtherExtent>& other) noexcept
-        : storage_(other.data(), other.size())
-    {}
-
-#ifdef __cpp_lib_span
-    constexpr span(std::span<ElementType> other) noexcept
-        : storage_(other.data(), other.size())
-    {}
-#endif
-
-    ~span() noexcept = default;
-
-    constexpr span&
-    operator=(const span& other) noexcept = default;
-
-    // [span.sub], span subviews
-    template <std::size_t Count>
-    constexpr span<element_type, Count> first() const
-    {
-        assert(Count <= size());
-        return {data(), Count};
-    }
-
-    template <std::size_t Count>
-    constexpr span<element_type, Count> last() const
-    {
-        assert(Count <= size());
-        return {data() + (size() - Count), Count};
-    }
-
-    template <std::size_t Offset, std::size_t Count = dynamic_extent>
-    using subspan_return_t =
-        span<ElementType, Count != dynamic_extent
-                              ? Count
-                              : (Extent != dynamic_extent ? Extent - Offset
-                                                          : dynamic_extent)>;
-
-    template <std::size_t Offset, std::size_t Count = dynamic_extent>
-    constexpr subspan_return_t<Offset, Count> subspan() const
-    {
-        assert(Offset <= size() &&
-                        (Count == dynamic_extent || Offset + Count <= size()));
-        return {data() + Offset,
-                Count != dynamic_extent ? Count : size() - Offset};
-    }
-
-    constexpr span<element_type, dynamic_extent>
-    first(size_type count) const
-    {
-        assert(count <= size());
-        return {data(), count};
-    }
-
-    constexpr span<element_type, dynamic_extent>
-    last(size_type count) const
-    {
-        assert(count <= size());
-        return {data() + (size() - count), count};
-    }
-
-    constexpr span<element_type, dynamic_extent>
-    subspan(size_type offset, size_type count = dynamic_extent) const
-    {
-        assert(offset <= size() &&
-                        (count == dynamic_extent || offset + count <= size()));
-        return {data() + offset,
-                count == dynamic_extent ? size() - offset : count};
-    }
-
-    // [span.obs], span observers
-    constexpr size_type size() const noexcept { return storage_.size; }
-
-    constexpr size_type size_bytes() const noexcept
-    {
-        return size() * sizeof(element_type);
-    }
-
-    [[nodiscard]] constexpr bool empty() const noexcept
-    {
-        return size() == 0;
-    }
-
-    // [span.elem], span element access
-    constexpr reference operator[](size_type idx) const
-    {
-        assert(idx < size());
-        return *(data() + idx);
-    }
-
-    constexpr reference front() const
-    {
-        assert(!empty());
-        return *data();
-    }
-
-    constexpr reference back() const
-    {
-        assert(!empty());
-        return *(data() + (size() - 1));
-    }
-
-    constexpr pointer data() const noexcept { return storage_.ptr; }
-
-    // [span.iterators], span iterator support
-    constexpr iterator begin() const noexcept { return data(); }
-
-    constexpr iterator end() const noexcept { return data() + size(); }
-
-    constexpr reverse_iterator rbegin() const noexcept
-    {
-        return reverse_iterator(end());
-    }
-
-    constexpr reverse_iterator rend() const noexcept
-    {
-        return reverse_iterator(begin());
-    }
-
-#ifdef __cpp_lib_span
-    constexpr operator auto() const {
-      return std::span < ElementType,
-             (Extent == dynamic_extent)
-                 ? std::dynamic_extent
-                 : Extent > (storage_.ptr, storage_.size);
-    }
-#endif
-
-private:
-    storage_type storage_{};
-};
-
-/* Deduction Guides */
-template <class T, size_t N>
-span(T (&)[N])->span<T, N>;
-
-template <class T, size_t N>
-span(std::array<T, N>&)->span<T, N>;
-
-template <class T, size_t N>
-span(const std::array<T, N>&)->span<const T, N>;
-
-template <class Container>
-span(Container&)->span<typename Container::value_type>;
-
-template <class Container>
-span(const Container&)->span<const typename Container::value_type>;
-
-template <typename ElementType, std::size_t Extent>
-span<const std::byte, ((Extent == dynamic_extent) ? dynamic_extent
-                                             : sizeof(ElementType) * Extent)>
-as_bytes(span<ElementType, Extent> s) noexcept
-{
-    return {reinterpret_cast<const std::byte*>(s.data()), s.size_bytes()};
-}
-
-template <
-    class ElementType, size_t Extent,
-    typename std::enable_if<!std::is_const<ElementType>::value, int>::type = 0>
-span<std::byte, ((Extent == dynamic_extent) ? dynamic_extent
-                                       : sizeof(ElementType) * Extent)>
-as_writable_bytes(span<ElementType, Extent> s) noexcept
-{
-    return {reinterpret_cast<std::byte*>(s.data()), s.size_bytes()};
-}
-
-template <std::size_t N, typename E, std::size_t S>
-constexpr auto get(span<E, S> s) -> decltype(s[N])
-{
-    return s[N];
-}
-
-} // namespace wpi
-
-namespace std {
-
-template <typename ElementType, size_t Extent>
-class tuple_size<wpi::span<ElementType, Extent>>
-    : public integral_constant<size_t, Extent> {};
-
-template <typename ElementType>
-class tuple_size<wpi::span<
-    ElementType, wpi::dynamic_extent>>; // not defined
-
-template <size_t I, typename ElementType, size_t Extent>
-class tuple_element<I, wpi::span<ElementType, Extent>> {
-public:
-    static_assert(Extent != wpi::dynamic_extent &&
-                      I < Extent,
-                  "");
-    using type = ElementType;
-};
-
-} // end namespace std
-
-#endif // WPIUTIL_WPI_SPAN_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/spinlock.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/spinlock.h
index 9e777fa..7128a18 100644
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/spinlock.h
+++ b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/spinlock.h
@@ -9,7 +9,7 @@
 #include <mutex>
 #include <thread>
 
-#include "Compiler.h"
+#include "wpi/Compiler.h"
 
 namespace wpi {
 
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/static_circular_buffer.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/static_circular_buffer.h
index 8cbf3fe..76498a1 100644
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/static_circular_buffer.h
+++ b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/static_circular_buffer.h
@@ -38,10 +38,7 @@
       ++(*this);
       return retval;
     }
-    bool operator==(const iterator& other) const {
-      return m_buffer == other.m_buffer && m_index == other.m_index;
-    }
-    bool operator!=(const iterator& other) const { return !(*this == other); }
+    bool operator==(const iterator&) const = default;
     reference operator*() { return (*m_buffer)[m_index]; }
 
    private:
@@ -69,12 +66,7 @@
       ++(*this);
       return retval;
     }
-    bool operator==(const const_iterator& other) const {
-      return m_buffer == other.m_buffer && m_index == other.m_index;
-    }
-    bool operator!=(const const_iterator& other) const {
-      return !(*this == other);
-    }
+    bool operator==(const const_iterator&) const = default;
     const_reference operator*() const { return (*m_buffer)[m_index]; }
 
    private:
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/type_traits.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/type_traits.h
deleted file mode 100644
index 5d35ee1..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/type_traits.h
+++ /dev/null
@@ -1,125 +0,0 @@
-//===- llvm/Support/type_traits.h - Simplfied type traits -------*- C++ -*-===//
-//
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
-//
-//===----------------------------------------------------------------------===//
-//
-// This file provides useful additions to the standard type_traits library.
-//
-//===----------------------------------------------------------------------===//
-
-#ifndef WPIUTIL_WPI_TYPE_TRAITS_H
-#define WPIUTIL_WPI_TYPE_TRAITS_H
-
-#include "wpi/Compiler.h"
-#include <type_traits>
-#include <utility>
-
-#ifndef __has_feature
-#define WPI_DEFINED_HAS_FEATURE
-#define __has_feature(x) 0
-#endif
-
-namespace wpi {
-
-/// isPodLike - This is a type trait that is used to determine whether a given
-/// type can be copied around with memcpy instead of running ctors etc.
-template <typename T>
-struct isPodLike {
-  // std::is_trivially_copyable is available in libc++ with clang, libstdc++
-  // that comes with GCC 5.
-#if (__has_feature(is_trivially_copyable) && defined(_LIBCPP_VERSION)) ||      \
-    (defined(__GNUC__) && __GNUC__ >= 5)
-  // If the compiler supports the is_trivially_copyable trait use it, as it
-  // matches the definition of isPodLike closely.
-  static const bool value = std::is_trivially_copyable<T>::value;
-#elif __has_feature(is_trivially_copyable)
-  // Use the internal name if the compiler supports is_trivially_copyable but we
-  // don't know if the standard library does. This is the case for clang in
-  // conjunction with libstdc++ from GCC 4.x.
-  static const bool value = __is_trivially_copyable(T);
-#else
-  // If we don't know anything else, we can (at least) assume that all non-class
-  // types are PODs.
-  static const bool value = !std::is_class<T>::value;
-#endif
-};
-
-// std::pair's are pod-like if their elements are.
-template<typename T, typename U>
-struct isPodLike<std::pair<T, U>> {
-  static const bool value = isPodLike<T>::value && isPodLike<U>::value;
-};
-
-/// Metafunction that determines whether the given type is either an
-/// integral type or an enumeration type, including enum classes.
-///
-/// Note that this accepts potentially more integral types than is_integral
-/// because it is based on being implicitly convertible to an integral type.
-/// Also note that enum classes aren't implicitly convertible to integral types,
-/// the value may therefore need to be explicitly converted before being used.
-template <typename T> class is_integral_or_enum {
-  using UnderlyingT = typename std::remove_reference<T>::type;
-
-public:
-  static const bool value =
-      !std::is_class<UnderlyingT>::value && // Filter conversion operators.
-      !std::is_pointer<UnderlyingT>::value &&
-      !std::is_floating_point<UnderlyingT>::value &&
-      (std::is_enum<UnderlyingT>::value ||
-       std::is_convertible<UnderlyingT, unsigned long long>::value);
-};
-
-/// If T is a pointer, just return it. If it is not, return T&.
-template<typename T, typename Enable = void>
-struct add_lvalue_reference_if_not_pointer { using type = T &; };
-
-template <typename T>
-struct add_lvalue_reference_if_not_pointer<
-    T, typename std::enable_if<std::is_pointer<T>::value>::type> {
-  using type = T;
-};
-
-/// If T is a pointer to X, return a pointer to const X. If it is not,
-/// return const T.
-template<typename T, typename Enable = void>
-struct add_const_past_pointer { using type = const T; };
-
-template <typename T>
-struct add_const_past_pointer<
-    T, typename std::enable_if<std::is_pointer<T>::value>::type> {
-  using type = const typename std::remove_pointer<T>::type *;
-};
-
-template <typename T, typename Enable = void>
-struct const_pointer_or_const_ref {
-  using type = const T &;
-};
-template <typename T>
-struct const_pointer_or_const_ref<
-    T, typename std::enable_if<std::is_pointer<T>::value>::type> {
-  using type = typename add_const_past_pointer<T>::type;
-};
-
-} // namespace wpi
-
-// If the compiler supports detecting whether a class is final, define
-// an LLVM_IS_FINAL macro. If it cannot be defined properly, this
-// macro will be left undefined.
-#ifndef LLVM_IS_FINAL
-#if __cplusplus >= 201402L || defined(_MSC_VER)
-#define LLVM_IS_FINAL(Ty) std::is_final<Ty>()
-#elif __has_feature(is_final) || LLVM_GNUC_PREREQ(4, 7, 0)
-#define LLVM_IS_FINAL(Ty) __is_final(Ty)
-#endif
-#endif
-
-#ifdef WPI_DEFINED_HAS_FEATURE
-#undef __has_feature
-#undef WPI_DEFINED_HAS_FEATURE
-#endif
-
-#endif // LLVM_SUPPORT_TYPE_TRAITS_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Async.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Async.h
deleted file mode 100644
index 49f3dde..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Async.h
+++ /dev/null
@@ -1,174 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_UV_ASYNC_H_
-#define WPIUTIL_WPI_UV_ASYNC_H_
-
-#include <uv.h>
-
-#include <memory>
-#include <thread>
-#include <tuple>
-#include <utility>
-#include <vector>
-
-#include "wpi/Signal.h"
-#include "wpi/mutex.h"
-#include "wpi/uv/Handle.h"
-#include "wpi/uv/Loop.h"
-
-namespace wpi::uv {
-
-/**
- * Async handle.
- * Async handles allow the user to "wakeup" the event loop and have a signal
- * generated from another thread.
- *
- * Data may be passed into the callback called on the event loop by using
- * template parameters.  If data parameters are used, the async callback will
- * be called once for every call to Send().  If no data parameters are used,
- * the async callback may or may not be called for every call to Send() (e.g.
- * the calls may be coaleasced).
- */
-template <typename... T>
-class Async final : public HandleImpl<Async<T...>, uv_async_t> {
-  struct private_init {};
-
- public:
-  Async(const std::shared_ptr<Loop>& loop, const private_init&)
-      : m_loop{loop} {}
-  ~Async() noexcept override {
-    if (auto loop = m_loop.lock()) {
-      this->Close();
-    } else {
-      this->ForceClosed();
-    }
-  }
-
-  /**
-   * Create an async handle.
-   *
-   * @param loop Loop object where this handle runs.
-   */
-  static std::shared_ptr<Async> Create(Loop& loop) {
-    return Create(loop.shared_from_this());
-  }
-
-  /**
-   * Create an async handle.
-   *
-   * @param loop Loop object where this handle runs.
-   */
-  static std::shared_ptr<Async> Create(const std::shared_ptr<Loop>& loop) {
-    auto h = std::make_shared<Async>(loop, private_init{});
-    int err =
-        uv_async_init(loop->GetRaw(), h->GetRaw(), [](uv_async_t* handle) {
-          auto& h = *static_cast<Async*>(handle->data);
-          std::scoped_lock lock(h.m_mutex);
-          for (auto&& v : h.m_data) {
-            std::apply(h.wakeup, v);
-          }
-          h.m_data.clear();
-        });
-    if (err < 0) {
-      loop->ReportError(err);
-      return nullptr;
-    }
-    h->Keep();
-    return h;
-  }
-
-  /**
-   * Wakeup the event loop and emit the event.
-   *
-   * It’s safe to call this function from any thread including the loop thread.
-   * An async event will be emitted on the loop thread.
-   */
-  template <typename... U>
-  void Send(U&&... u) {
-    auto loop = m_loop.lock();
-    if (loop && loop->GetThreadId() == std::this_thread::get_id()) {
-      // called from within the loop, just call the function directly
-      wakeup(std::forward<U>(u)...);
-      return;
-    }
-
-    {
-      std::scoped_lock lock(m_mutex);
-      m_data.emplace_back(std::forward_as_tuple(std::forward<U>(u)...));
-    }
-    if (loop) {
-      this->Invoke(&uv_async_send, this->GetRaw());
-    }
-  }
-
-  /**
-   * Signal generated (on event loop thread) when the async event occurs.
-   */
-  sig::Signal<T...> wakeup;
-
- private:
-  wpi::mutex m_mutex;
-  std::vector<std::tuple<T...>> m_data;
-  std::weak_ptr<Loop> m_loop;
-};
-
-/**
- * Async specialization for no data parameters.  The async callback may or may
- * not be called for every call to Send() (e.g. the calls may be coaleasced).
- */
-template <>
-class Async<> final : public HandleImpl<Async<>, uv_async_t> {
-  struct private_init {};
-
- public:
-  Async(const std::shared_ptr<Loop>& loop, const private_init&)
-      : m_loop(loop) {}
-  ~Async() noexcept override;
-
-  /**
-   * Create an async handle.
-   *
-   * @param loop Loop object where this handle runs.
-   */
-  static std::shared_ptr<Async> Create(Loop& loop) {
-    return Create(loop.shared_from_this());
-  }
-
-  /**
-   * Create an async handle.
-   *
-   * @param loop Loop object where this handle runs.
-   */
-  static std::shared_ptr<Async> Create(const std::shared_ptr<Loop>& loop);
-
-  /**
-   * Wakeup the event loop and emit the event.
-   *
-   * It’s safe to call this function from any thread.
-   * An async event will be emitted on the loop thread.
-   */
-  void Send() {
-    if (auto loop = m_loop.lock()) {
-      if (loop->GetThreadId() == std::this_thread::get_id()) {
-        // called from within the loop, just call the function directly
-        wakeup();
-      } else {
-        Invoke(&uv_async_send, GetRaw());
-      }
-    }
-  }
-
-  /**
-   * Signal generated (on event loop thread) when the async event occurs.
-   */
-  sig::Signal<> wakeup;
-
- private:
-  std::weak_ptr<Loop> m_loop;
-};
-
-}  // namespace wpi::uv
-
-#endif  // WPIUTIL_WPI_UV_ASYNC_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/AsyncFunction.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/AsyncFunction.h
deleted file mode 100644
index fa4eb90..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/AsyncFunction.h
+++ /dev/null
@@ -1,167 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_UV_ASYNCFUNCTION_H_
-#define WPIUTIL_WPI_UV_ASYNCFUNCTION_H_
-
-#include <stdint.h>
-#include <uv.h>
-
-#include <functional>
-#include <memory>
-#include <thread>
-#include <tuple>
-#include <utility>
-#include <vector>
-
-#include "wpi/future.h"
-#include "wpi/mutex.h"
-#include "wpi/uv/Handle.h"
-#include "wpi/uv/Loop.h"
-
-namespace wpi::uv {
-
-template <typename T>
-class AsyncFunction;
-
-/**
- * Function async handle.
- * Async handles allow the user to "wakeup" the event loop and have a function
- * called from another thread that returns a result to the calling thread.
- */
-template <typename R, typename... T>
-class AsyncFunction<R(T...)> final
-    : public HandleImpl<AsyncFunction<R(T...)>, uv_async_t> {
-  struct private_init {};
-
- public:
-  AsyncFunction(const std::shared_ptr<Loop>& loop,
-                std::function<void(promise<R>, T...)> func, const private_init&)
-      : wakeup{std::move(func)}, m_loop{loop} {}
-  ~AsyncFunction() noexcept override {
-    if (auto loop = m_loop.lock()) {
-      this->Close();
-    } else {
-      this->ForceClosed();
-    }
-  }
-
-  /**
-   * Create an async handle.
-   *
-   * @param loop Loop object where this handle runs.
-   * @param func wakeup function to be called (sets wakeup value); the function
-   *             needs to return void, and its first parameter is the promise
-   *             for the result.  If no value is set on the promise by the
-   *             wakeup function, a default-constructed value is "returned".
-   */
-  static std::shared_ptr<AsyncFunction> Create(
-      Loop& loop, std::function<void(promise<R>, T...)> func = nullptr) {
-    return Create(loop.shared_from_this(), std::move(func));
-  }
-
-  /**
-   * Create an async handle.
-   *
-   * @param loop Loop object where this handle runs.
-   * @param func wakeup function to be called (sets wakeup value); the function
-   *             needs to return void, and its first parameter is the promise
-   *             for the result.  If no value is set on the promise by the
-   *             wakeup function, a default-constructed value is "returned".
-   */
-  static std::shared_ptr<AsyncFunction> Create(
-      const std::shared_ptr<Loop>& loop,
-      std::function<void(promise<R>, T...)> func = nullptr) {
-    auto h =
-        std::make_shared<AsyncFunction>(loop, std::move(func), private_init{});
-    int err =
-        uv_async_init(loop->GetRaw(), h->GetRaw(), [](uv_async_t* handle) {
-          auto& h = *static_cast<AsyncFunction*>(handle->data);
-          std::unique_lock lock(h.m_mutex);
-
-          if (!h.m_params.empty()) {
-            // for each set of parameters in the input queue, call the wakeup
-            // function and put the result in the output queue if the caller is
-            // waiting for it
-            for (auto&& v : h.m_params) {
-              auto p = h.m_promises.CreatePromise(v.first);
-              if (h.wakeup) {
-                std::apply(h.wakeup,
-                           std::tuple_cat(std::make_tuple(std::move(p)),
-                                          std::move(v.second)));
-              }
-            }
-            h.m_params.clear();
-            // wake up any threads that might be waiting for the result
-            lock.unlock();
-            h.m_promises.Notify();
-          }
-        });
-    if (err < 0) {
-      loop->ReportError(err);
-      return nullptr;
-    }
-    h->Keep();
-    return h;
-  }
-
-  /**
-   * Wakeup the event loop, call the async function, and return a future for
-   * the result.
-   *
-   * It’s safe to call this function from any thread including the loop thread.
-   * The async function will be called on the loop thread.
-   *
-   * The future will return a default-constructed result if this handle is
-   * destroyed while waiting for a result.
-   */
-  template <typename... U>
-  future<R> Call(U&&... u) {
-    // create the future
-    uint64_t req = m_promises.CreateRequest();
-
-    auto loop = m_loop.lock();
-    if (loop && loop->GetThreadId() == std::this_thread::get_id()) {
-      // called from within the loop, just call the function directly
-      wakeup(m_promises.CreatePromise(req), std::forward<U>(u)...);
-      return m_promises.CreateFuture(req);
-    }
-
-    // add the parameters to the input queue
-    {
-      std::scoped_lock lock(m_mutex);
-      m_params.emplace_back(std::piecewise_construct,
-                            std::forward_as_tuple(req),
-                            std::forward_as_tuple(std::forward<U>(u)...));
-    }
-
-    // signal the loop
-    if (loop) {
-      this->Invoke(&uv_async_send, this->GetRaw());
-    }
-
-    // return future
-    return m_promises.CreateFuture(req);
-  }
-
-  template <typename... U>
-  future<R> operator()(U&&... u) {
-    return Call(std::forward<U>(u)...);
-  }
-
-  /**
-   * Function called (on event loop thread) when the async is called.
-   */
-  std::function<void(promise<R>, T...)> wakeup;
-
- private:
-  wpi::mutex m_mutex;
-  std::vector<std::pair<uint64_t, std::tuple<T...>>> m_params;
-  PromiseFactory<R> m_promises;
-  std::weak_ptr<Loop> m_loop;
-};
-
-}  // namespace wpi::uv
-
-#endif  // WPIUTIL_WPI_UV_ASYNCFUNCTION_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Buffer.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Buffer.h
deleted file mode 100644
index 5126841..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Buffer.h
+++ /dev/null
@@ -1,163 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_UV_BUFFER_H_
-#define WPIUTIL_WPI_UV_BUFFER_H_
-
-#include <uv.h>
-
-#include <cstring>
-#include <initializer_list>
-#include <string_view>
-#include <utility>
-
-#include "wpi/SmallVector.h"
-#include "wpi/span.h"
-
-namespace wpi::uv {
-
-/**
- * Data buffer.  Convenience wrapper around uv_buf_t.
- */
-class Buffer : public uv_buf_t {
- public:
-  Buffer() {
-    base = nullptr;
-    len = 0;
-  }
-  /*implicit*/ Buffer(const uv_buf_t& oth) {  // NOLINT
-    base = oth.base;
-    len = oth.len;
-  }
-  /*implicit*/ Buffer(std::string_view str)  // NOLINT
-      : Buffer{str.data(), str.size()} {}
-  /*implicit*/ Buffer(span<const uint8_t> arr)  // NOLINT
-      : Buffer{reinterpret_cast<const char*>(arr.data()), arr.size()} {}
-  Buffer(char* base_, size_t len_) {
-    base = base_;
-    len = static_cast<decltype(len)>(len_);
-  }
-  Buffer(const char* base_, size_t len_) {
-    base = const_cast<char*>(base_);
-    len = static_cast<decltype(len)>(len_);
-  }
-
-  span<const char> data() const { return {base, len}; }
-  span<char> data() { return {base, len}; }
-
-  operator span<const char>() const { return data(); }  // NOLINT
-  operator span<char>() { return data(); }              // NOLINT
-
-  static Buffer Allocate(size_t size) { return Buffer{new char[size], size}; }
-
-  static Buffer Dup(std::string_view in) {
-    Buffer buf = Allocate(in.size());
-    std::memcpy(buf.base, in.data(), in.size());
-    return buf;
-  }
-
-  static Buffer Dup(span<const uint8_t> in) {
-    Buffer buf = Allocate(in.size());
-    std::memcpy(buf.base, in.begin(), in.size());
-    return buf;
-  }
-
-  Buffer Dup() const {
-    Buffer buf = Allocate(len);
-    std::memcpy(buf.base, base, len);
-    return buf;
-  }
-
-  void Deallocate() {
-    delete[] base;
-    base = nullptr;
-    len = 0;
-  }
-
-  Buffer Move() {
-    Buffer buf = *this;
-    base = nullptr;
-    len = 0;
-    return buf;
-  }
-
-  friend void swap(Buffer& a, Buffer& b) {
-    using std::swap;
-    swap(a.base, b.base);
-    swap(a.len, b.len);
-  }
-};
-
-/**
- * A simple pool allocator for Buffers.
- * Buffers are allocated individually but are reused rather than returned
- * to the heap.
- * @tparam DEPTH depth of pool
- */
-template <size_t DEPTH = 4>
-class SimpleBufferPool {
- public:
-  /**
-   * Constructor.
-   * @param size Size of each buffer to allocate.
-   */
-  explicit SimpleBufferPool(size_t size = 4096) : m_size{size} {}
-  ~SimpleBufferPool() { Clear(); }
-
-  SimpleBufferPool(const SimpleBufferPool& other) = delete;
-  SimpleBufferPool& operator=(const SimpleBufferPool& other) = delete;
-
-  /**
-   * Allocate a buffer.
-   */
-  Buffer Allocate() {
-    if (m_pool.empty()) {
-      return Buffer::Allocate(m_size);
-    }
-    auto buf = m_pool.back();
-    m_pool.pop_back();
-    buf.len = m_size;
-    return buf;
-  }
-
-  /**
-   * Allocate a buffer.
-   */
-  Buffer operator()() { return Allocate(); }
-
-  /**
-   * Release allocated buffers back into the pool.
-   * This is NOT safe to use with arbitrary buffers unless they were
-   * allocated with the same size as the buffer pool allocation size.
-   */
-  void Release(span<Buffer> bufs) {
-    for (auto& buf : bufs) {
-      m_pool.emplace_back(buf.Move());
-    }
-  }
-
-  /**
-   * Clear the pool, releasing all buffers.
-   */
-  void Clear() {
-    for (auto& buf : m_pool) {
-      buf.Deallocate();
-    }
-    m_pool.clear();
-  }
-
-  /**
-   * Get number of buffers left in the pool before a new buffer will be
-   * allocated from the heap.
-   */
-  size_t Remaining() const { return m_pool.size(); }
-
- private:
-  SmallVector<Buffer, DEPTH> m_pool;
-  size_t m_size;  // NOLINT
-};
-
-}  // namespace wpi::uv
-
-#endif  // WPIUTIL_WPI_UV_BUFFER_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Check.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Check.h
deleted file mode 100644
index 7555452..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Check.h
+++ /dev/null
@@ -1,65 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_UV_CHECK_H_
-#define WPIUTIL_WPI_UV_CHECK_H_
-
-#include <uv.h>
-
-#include <memory>
-
-#include "wpi/Signal.h"
-#include "wpi/uv/Handle.h"
-
-namespace wpi::uv {
-
-class Loop;
-
-/**
- * Check handle.
- * Check handles will generate a signal once per loop iteration, right
- * after polling for I/O.
- */
-class Check final : public HandleImpl<Check, uv_check_t> {
-  struct private_init {};
-
- public:
-  explicit Check(const private_init&) {}
-  ~Check() noexcept override = default;
-
-  /**
-   * Create a check handle.
-   *
-   * @param loop Loop object where this handle runs.
-   */
-  static std::shared_ptr<Check> Create(Loop& loop);
-
-  /**
-   * Create a check handle.
-   *
-   * @param loop Loop object where this handle runs.
-   */
-  static std::shared_ptr<Check> Create(const std::shared_ptr<Loop>& loop) {
-    return Create(*loop);
-  }
-
-  /**
-   * Start the handle.
-   */
-  void Start();
-
-  /**
-   * Stop the handle.  The signal will no longer be generated.
-   */
-  void Stop() { Invoke(&uv_check_stop, GetRaw()); }
-
-  /**
-   * Signal generated once per loop iteration after polling for I/O.
-   */
-  sig::Signal<> check;
-};
-
-}  // namespace wpi::uv
-
-#endif  // WPIUTIL_WPI_UV_CHECK_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Error.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Error.h
deleted file mode 100644
index 1e717a4..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Error.h
+++ /dev/null
@@ -1,46 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_UV_ERROR_H_
-#define WPIUTIL_WPI_UV_ERROR_H_
-
-#include <uv.h>
-
-namespace wpi::uv {
-
-/**
- * Error code.
- */
-class Error {
- public:
-  Error() = default;
-  explicit Error(int err) : m_err(err) {}
-
-  /**
-   * Boolean conversion.  Returns true if error, false if ok.
-   */
-  explicit operator bool() const { return m_err < 0; }
-
-  /**
-   * Returns the error code.
-   */
-  int code() const { return m_err; }
-
-  /**
-   * Returns the error message.
-   */
-  const char* str() const { return uv_strerror(m_err); }
-
-  /**
-   * Returns the error name.
-   */
-  const char* name() const { return uv_err_name(m_err); }
-
- private:
-  int m_err{UV_UNKNOWN};
-};
-
-}  // namespace wpi::uv
-
-#endif  // WPIUTIL_WPI_UV_ERROR_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/FsEvent.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/FsEvent.h
deleted file mode 100644
index 0ed2dcb..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/FsEvent.h
+++ /dev/null
@@ -1,79 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_UV_FSEVENT_H_
-#define WPIUTIL_WPI_UV_FSEVENT_H_
-
-#include <uv.h>
-
-#include <memory>
-#include <string>
-#include <string_view>
-
-#include "wpi/Signal.h"
-#include "wpi/uv/Handle.h"
-
-namespace wpi::uv {
-
-class Loop;
-
-/**
- * Filesystem Event handle.
- */
-class FsEvent final : public HandleImpl<FsEvent, uv_fs_event_t> {
-  struct private_init {};
-
- public:
-  explicit FsEvent(const private_init&) {}
-  ~FsEvent() noexcept override = default;
-
-  /**
-   * Create a filesystem event handle.
-   *
-   * @param loop Loop object where this handle runs.
-   */
-  static std::shared_ptr<FsEvent> Create(Loop& loop);
-
-  /**
-   * Create a filesystem event handle.
-   *
-   * @param loop Loop object where this handle runs.
-   */
-  static std::shared_ptr<FsEvent> Create(const std::shared_ptr<Loop>& loop) {
-    return Create(*loop);
-  }
-
-  /**
-   * Start watching the specified path for changes.
-   *
-   * @param path Path to watch for changes
-   * @param events Bitmask of event flags.  Only UV_FS_EVENT_RECURSIVE is
-   *               supported (and only on OSX and Windows).
-   */
-  void Start(std::string_view path, unsigned int flags = 0);
-
-  /**
-   * Stop watching for changes.
-   */
-  void Stop() { Invoke(&uv_fs_event_stop, GetRaw()); }
-
-  /**
-   * Get the path being monitored.  Signals error and returns empty string if
-   * an error occurs.
-   * @return Monitored path.
-   */
-  std::string GetPath();
-
-  /**
-   * Signal generated when a filesystem change occurs.  The first parameter
-   * is the filename (if a directory was passed to Start(), the filename is
-   * relative to that directory).  The second parameter is an ORed mask of
-   * UV_RENAME and UV_CHANGE.
-   */
-  sig::Signal<const char*, int> fsEvent;
-};
-
-}  // namespace wpi::uv
-
-#endif  // WPIUTIL_WPI_UV_FSEVENT_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/GetAddrInfo.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/GetAddrInfo.h
deleted file mode 100644
index 18d4f32..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/GetAddrInfo.h
+++ /dev/null
@@ -1,119 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_UV_GETADDRINFO_H_
-#define WPIUTIL_WPI_UV_GETADDRINFO_H_
-
-#include <uv.h>
-
-#include <functional>
-#include <memory>
-#include <string_view>
-#include <utility>
-
-#include "wpi/Signal.h"
-#include "wpi/uv/Request.h"
-
-namespace wpi::uv {
-
-class Loop;
-
-/**
- * GetAddrInfo request.
- * For use with `GetAddrInfo()` function family.
- */
-class GetAddrInfoReq : public RequestImpl<GetAddrInfoReq, uv_getaddrinfo_t> {
- public:
-  GetAddrInfoReq();
-
-  Loop& GetLoop() const { return *static_cast<Loop*>(GetRaw()->loop->data); }
-
-  /**
-   * Resolved lookup signal.
-   * Parameter is resolved address info.
-   */
-  sig::Signal<const addrinfo&> resolved;
-};
-
-/**
- * Asynchronous getaddrinfo(3).  HandleResolvedAddress() is called on the
- * request when the resolution completes.  HandleError() is called on the
- * request if any errors occur.
- *
- * Either node or service may be empty but not both.
- *
- * @param loop Event loop
- * @param req request
- * @param node Either a numerical network address or a network hostname.
- * @param service Either a service name or a port number as a string.
- * @param hints Optional `addrinfo` data structure with additional address
- *              type constraints.
- */
-void GetAddrInfo(Loop& loop, const std::shared_ptr<GetAddrInfoReq>& req,
-                 std::string_view node, std::string_view service = {},
-                 const addrinfo* hints = nullptr);
-
-/**
- * Asynchronous getaddrinfo(3).  HandleResolvedAddress() is called on the
- * request when the resolution completes.  HandleError() is called on the
- * request if any errors occur.
- *
- * Either node or service may be empty but not both.
- *
- * @param loop Event loop
- * @param req request
- * @param node Either a numerical network address or a network hostname.
- * @param service Either a service name or a port number as a string.
- * @param hints Optional `addrinfo` data structure with additional address
- *              type constraints.
- */
-inline void GetAddrInfo(const std::shared_ptr<Loop>& loop,
-                        const std::shared_ptr<GetAddrInfoReq>& req,
-                        std::string_view node, std::string_view service = {},
-                        const addrinfo* hints = nullptr) {
-  GetAddrInfo(*loop, req, node, service, hints);
-}
-
-/**
- * Asynchronous getaddrinfo(3).  The callback is called when the resolution
- * completes, and errors are forwarded to the loop.  This is a convenience
- * wrapper.
- *
- * Either node or service may be empty but not both.
- *
- * @param loop Event loop
- * @param callback Callback function to call when resolution completes
- * @param node Either a numerical network address or a network hostname.
- * @param service Either a service name or a port number as a string.
- * @param hints Optional `addrinfo` data structure with additional address
- *              type constraints.
- */
-void GetAddrInfo(Loop& loop, std::function<void(const addrinfo&)> callback,
-                 std::string_view node, std::string_view service = {},
-                 const addrinfo* hints = nullptr);
-
-/**
- * Asynchronous getaddrinfo(3).  The callback is called when the resolution
- * completes, and errors are forwarded to the loop.  This is a convenience
- * wrapper.
- *
- * Either node or service may be empty but not both.
- *
- * @param loop Event loop
- * @param callback Callback function to call when resolution completes
- * @param node Either a numerical network address or a network hostname.
- * @param service Either a service name or a port number as a string.
- * @param hints Optional `addrinfo` data structure with additional address
- *              type constraints.
- */
-inline void GetAddrInfo(const std::shared_ptr<Loop>& loop,
-                        std::function<void(const addrinfo&)> callback,
-                        std::string_view node, std::string_view service = {},
-                        const addrinfo* hints = nullptr) {
-  GetAddrInfo(*loop, std::move(callback), node, service, hints);
-}
-
-}  // namespace wpi::uv
-
-#endif  // WPIUTIL_WPI_UV_GETADDRINFO_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/GetNameInfo.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/GetNameInfo.h
deleted file mode 100644
index d35dd95..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/GetNameInfo.h
+++ /dev/null
@@ -1,228 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_UV_GETNAMEINFO_H_
-#define WPIUTIL_WPI_UV_GETNAMEINFO_H_
-
-#include <uv.h>
-
-#include <functional>
-#include <memory>
-#include <string_view>
-#include <utility>
-
-#include "wpi/Signal.h"
-#include "wpi/uv/Request.h"
-
-namespace wpi::uv {
-
-class Loop;
-
-/**
- * GetNameInfo request.
- * For use with `GetNameInfo()` function family.
- */
-class GetNameInfoReq : public RequestImpl<GetNameInfoReq, uv_getnameinfo_t> {
- public:
-  GetNameInfoReq();
-
-  Loop& GetLoop() const { return *static_cast<Loop*>(GetRaw()->loop->data); }
-
-  /**
-   * Resolved lookup signal.
-   * Parameters are hostname and service.
-   */
-  sig::Signal<const char*, const char*> resolved;
-};
-
-/**
- * Asynchronous getnameinfo(3).  HandleResolvedName() is called on the
- * request when the resolution completes.  HandleError() is called on the
- * request if any errors occur.
- *
- * @param loop Event loop
- * @param req request
- * @param addr Initialized `sockaddr_in` or `sockaddr_in6` data structure.
- * @param flags Optional flags to modify the behavior of `getnameinfo`.
- */
-void GetNameInfo(Loop& loop, const std::shared_ptr<GetNameInfoReq>& req,
-                 const sockaddr& addr, int flags = 0);
-
-/**
- * Asynchronous getnameinfo(3).  HandleResolvedName() is called on the
- * request when the resolution completes.  HandleError() is called on the
- * request if any errors occur.
- *
- * @param loop Event loop
- * @param req request
- * @param addr Initialized `sockaddr_in` or `sockaddr_in6` data structure.
- * @param flags Optional flags to modify the behavior of `getnameinfo`.
- */
-inline void GetNameInfo(const std::shared_ptr<Loop>& loop,
-                        const std::shared_ptr<GetNameInfoReq>& req,
-                        const sockaddr& addr, int flags = 0) {
-  GetNameInfo(*loop, req, addr, flags);
-}
-
-/**
- * Asynchronous getnameinfo(3).  The callback is called when the resolution
- * completes, and errors are forwarded to the loop.
- *
- * @param loop Event loop
- * @param callback Callback function to call when resolution completes
- * @param addr Initialized `sockaddr_in` or `sockaddr_in6` data structure.
- * @param flags Optional flags to modify the behavior of `getnameinfo`.
- */
-void GetNameInfo(Loop& loop,
-                 std::function<void(const char*, const char*)> callback,
-                 const sockaddr& addr, int flags = 0);
-
-/**
- * Asynchronous getnameinfo(3).  The callback is called when the resolution
- * completes, and errors are forwarded to the loop.
- *
- * @param loop Event loop
- * @param callback Callback function to call when resolution completes
- * @param addr Initialized `sockaddr_in` or `sockaddr_in6` data structure.
- * @param flags Optional flags to modify the behavior of `getnameinfo`.
- * @return Connection object for the callback
- */
-inline void GetNameInfo(const std::shared_ptr<Loop>& loop,
-                        std::function<void(const char*, const char*)> callback,
-                        const sockaddr& addr, int flags = 0) {
-  GetNameInfo(*loop, std::move(callback), addr, flags);
-}
-
-/**
- * Asynchronous IPv4 getnameinfo(3).  HandleResolvedName() is called on the
- * request when the resolution completes.  HandleError() is called on the
- * request if any errors occur.
- *
- * @param loop Event loop
- * @param req request
- * @param ip A valid IPv4 address
- * @param port A valid port number
- * @param flags Optional flags to modify the behavior of `getnameinfo`.
- */
-void GetNameInfo4(Loop& loop, const std::shared_ptr<GetNameInfoReq>& req,
-                  std::string_view ip, unsigned int port, int flags = 0);
-
-/**
- * Asynchronous IPv4 getnameinfo(3).  HandleResolvedName() is called on the
- * request when the resolution completes.  HandleError() is called on the
- * request if any errors occur.
- *
- * @param loop Event loop
- * @param req request
- * @param ip A valid IPv4 address
- * @param port A valid port number
- * @param flags Optional flags to modify the behavior of `getnameinfo`.
- */
-inline void GetNameInfo4(const std::shared_ptr<Loop>& loop,
-                         const std::shared_ptr<GetNameInfoReq>& req,
-                         std::string_view ip, unsigned int port,
-                         int flags = 0) {
-  return GetNameInfo4(*loop, req, ip, port, flags);
-}
-
-/**
- * Asynchronous IPv4 getnameinfo(3).  The callback is called when the resolution
- * completes, and errors are forwarded to the loop.
- *
- * @param loop Event loop
- * @param callback Callback function to call when resolution completes
- * @param ip A valid IPv4 address
- * @param port A valid port number
- * @param flags Optional flags to modify the behavior of `getnameinfo`.
- */
-void GetNameInfo4(Loop& loop,
-                  std::function<void(const char*, const char*)> callback,
-                  std::string_view ip, unsigned int port, int flags = 0);
-
-/**
- * Asynchronous IPv4 getnameinfo(3).  The callback is called when the resolution
- * completes, and errors are forwarded to the loop.  This is a convenience
- * wrapper.
- *
- * @param loop Event loop
- * @param ip A valid IPv4 address
- * @param port A valid port number
- * @param callback Callback function to call when resolution completes
- * @param flags Optional flags to modify the behavior of `getnameinfo`.
- */
-inline void GetNameInfo4(const std::shared_ptr<Loop>& loop,
-                         std::function<void(const char*, const char*)> callback,
-                         std::string_view ip, unsigned int port,
-                         int flags = 0) {
-  return GetNameInfo4(*loop, std::move(callback), ip, port, flags);
-}
-
-/**
- * Asynchronous IPv6 getnameinfo(3).  HandleResolvedName() is called on the
- * request when the resolution completes.  HandleError() is called on the
- * request if any errors occur.
- *
- * @param loop Event loop
- * @param req request
- * @param ip A valid IPv6 address
- * @param port A valid port number
- * @param flags Optional flags to modify the behavior of `getnameinfo`.
- */
-void GetNameInfo6(Loop& loop, const std::shared_ptr<GetNameInfoReq>& req,
-                  std::string_view ip, unsigned int port, int flags = 0);
-
-/**
- * Asynchronous IPv6 getnameinfo(3).  HandleResolvedName() is called on the
- * request when the resolution completes.  HandleError() is called on the
- * request if any errors occur.
- *
- * @param loop Event loop
- * @param req request
- * @param ip A valid IPv6 address
- * @param port A valid port number
- * @param flags Optional flags to modify the behavior of `getnameinfo`.
- */
-inline void GetNameInfo6(const std::shared_ptr<Loop>& loop,
-                         const std::shared_ptr<GetNameInfoReq>& req,
-                         std::string_view ip, unsigned int port,
-                         int flags = 0) {
-  GetNameInfo6(*loop, req, ip, port, flags);
-}
-
-/**
- * Asynchronous IPv6 getnameinfo(3).  The callback is called when the resolution
- * completes, and errors are forwarded to the loop.  This is a convenience
- * wrapper.
- *
- * @param loop Event loop
- * @param callback Callback function to call when resolution completes
- * @param ip A valid IPv6 address
- * @param port A valid port number
- * @param flags Optional flags to modify the behavior of `getnameinfo`.
- */
-void GetNameInfo6(Loop& loop,
-                  std::function<void(const char*, const char*)> callback,
-                  std::string_view ip, unsigned int port, int flags = 0);
-
-/**
- * Asynchronous IPv6 getnameinfo(3).  The callback is called when the resolution
- * completes, and errors are forwarded to the loop.  This is a convenience
- * wrapper.
- *
- * @param loop Event loop
- * @param callback Callback function to call when resolution completes
- * @param ip A valid IPv6 address
- * @param port A valid port number
- * @param flags Optional flags to modify the behavior of `getnameinfo`.
- */
-inline void GetNameInfo6(const std::shared_ptr<Loop>& loop,
-                         std::function<void(const char*, const char*)> callback,
-                         std::string_view ip, unsigned int port,
-                         int flags = 0) {
-  return GetNameInfo6(*loop, std::move(callback), ip, port, flags);
-}
-
-}  // namespace wpi::uv
-
-#endif  // WPIUTIL_WPI_UV_GETNAMEINFO_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Handle.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Handle.h
deleted file mode 100644
index b61cd81..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Handle.h
+++ /dev/null
@@ -1,297 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_UV_HANDLE_H_
-#define WPIUTIL_WPI_UV_HANDLE_H_
-
-#include <uv.h>
-
-#include <cstdlib>
-#include <functional>
-#include <memory>
-#include <string_view>
-#include <utility>
-
-#include "wpi/Signal.h"
-#include "wpi/uv/Buffer.h"
-#include "wpi/uv/Error.h"
-#include "wpi/uv/Loop.h"
-
-namespace wpi::uv {
-
-/**
- * Handle.
- * Handles are not moveable or copyable and cannot be directly constructed.
- * This class provides shared_ptr ownership and shared_from_this.
- * Use the specific handle type Create() functions to create handles.
- */
-class Handle : public std::enable_shared_from_this<Handle> {
- public:
-  using Type = uv_handle_type;
-
-  Handle(const Handle&) = delete;
-  Handle(Handle&&) = delete;
-  Handle& operator=(const Handle&) = delete;
-  Handle& operator=(Handle&&) = delete;
-  virtual ~Handle() noexcept;
-
-  /**
-   * Get the type of the handle.
-   *
-   * A base handle offers no functionality to promote it to the actual handle
-   * type. By means of this function, the type of the underlying handle as
-   * specified by Type is made available.
-   *
-   * @return The actual type of the handle.
-   */
-  Type GetType() const noexcept { return m_uv_handle->type; }
-
-  /**
-   * Get the name of the type of the handle.  E.g. "pipe" for pipe handles.
-   */
-  std::string_view GetTypeName() const noexcept {
-    return uv_handle_type_name(m_uv_handle->type);
-  }
-
-  /**
-   * Get the loop where this handle runs.
-   *
-   * @return The loop.
-   */
-  std::shared_ptr<Loop> GetLoop() const noexcept {
-    return GetLoopRef().shared_from_this();
-  }
-
-  /**
-   * Get the loop where this handle runs.
-   *
-   * @return The loop.
-   */
-  Loop& GetLoopRef() const noexcept {
-    return *static_cast<Loop*>(m_uv_handle->loop->data);
-  }
-
-  /**
-   * Check if the handle is active.
-   *
-   * What _active_ means depends on the type of handle:
-   *
-   * * An AsyncHandle handle is always active and cannot be deactivated,
-   * except by closing it with uv_close().
-   * * A PipeHandle, TcpHandle, UDPHandle, etc. handle - basically any handle
-   * that deals with I/O - is active when it is doing something that involves
-   * I/O, like reading, writing, connecting, accepting new connections, etc.
-   * * A CheckHandle, IdleHandle, TimerHandle, etc. handle is active when it
-   * has been started with a call to `Start()`.
-   *
-   * Rule of thumb: if a handle of type `FooHandle` has a `Start()` member
-   * method, then it’s active from the moment that method is called. Likewise,
-   * `Stop()` deactivates the handle again.
-   *
-   * @return True if the handle is active, false otherwise.
-   */
-  bool IsActive() const noexcept { return uv_is_active(m_uv_handle) != 0; }
-
-  /**
-   * Check if a handle is closing or closed.
-   *
-   * This function should only be used between the initialization of the
-   * handle and the arrival of the close callback.
-   *
-   * @return True if the handle is closing or closed, false otherwise.
-   */
-  bool IsClosing() const noexcept {
-    return m_closed || uv_is_closing(m_uv_handle) != 0;
-  }
-
-  /**
-   * Request handle to be closed.
-   *
-   * This **must** be called on each handle before memory is released.
-   * In-progress requests are cancelled and this can result in error() being
-   * emitted.
-   *
-   * The handle will emit closed() when finished.
-   */
-  void Close() noexcept;
-
-  /**
-   * Set if the loop is closing.
-   *
-   * This is set during EventLoopRunner.Stop(), and can be used for other cases
-   * to indicate the loop should be closing. For instance for a uv_walk loop can
-   * use this to close existing handles.
-   *
-   * @param loopClosing true to set the loop currently in closing stages.
-   */
-  void SetLoopClosing(bool loopClosing) noexcept {
-    m_loopClosing = loopClosing;
-  }
-
-  /**
-   * Get the loop closing status.
-   *
-   * This can be used from closed() in order to tell if a closing loop is the
-   * reason for the close, or another reason.
-   *
-   * @return true if the loop is closing, otherwise false.
-   */
-  bool IsLoopClosing() const noexcept { return m_loopClosing; }
-
-  /**
-   * Reference the given handle.
-   *
-   * References are idempotent, that is, if a handle is already referenced
-   * calling this function again will have no effect.
-   */
-  void Reference() noexcept { uv_ref(m_uv_handle); }
-
-  /**
-   * Unreference the given handle.
-   *
-   * References are idempotent, that is, if a handle is not referenced calling
-   * this function again will have no effect.
-   */
-  void Unreference() noexcept { uv_unref(m_uv_handle); }
-
-  /**
-   * Check if the given handle is referenced.
-   * @return True if the handle is referenced, false otherwise.
-   */
-  bool HasReference() const noexcept { return uv_has_ref(m_uv_handle) != 0; }
-
-  /**
-   * Return the size of the underlying handle type.
-   * @return The size of the underlying handle type.
-   */
-  size_t RawSize() const noexcept { return uv_handle_size(m_uv_handle->type); }
-
-  /**
-   * Get the underlying handle data structure.
-   *
-   * @return The underlying handle data structure.
-   */
-  uv_handle_t* GetRawHandle() const noexcept { return m_uv_handle; }
-
-  /**
-   * Set the functions used for allocating and releasing buffers.  The size
-   * passed to the allocator function is a "suggested" size--it's just an
-   * indication, not related in any way to the pending data to be read.  The
-   * user is free to allocate the amount of memory they decide.  For example,
-   * applications with custom allocation schemes may decide to use a different
-   * size which matches the memory chunks they already have for other purposes.
-   *
-   * @warning Be very careful changing the allocator after the loop has started
-   * running; there are no interlocks between this and buffers currently in
-   * flight.
-   *
-   * @param alloc Allocation function
-   * @param dealloc Deallocation function
-   */
-  void SetBufferAllocator(std::function<Buffer(size_t)> alloc,
-                          std::function<void(Buffer&)> dealloc) {
-    m_allocBuf = std::move(alloc);
-    m_freeBuf = std::move(dealloc);
-  }
-
-  /**
-   * Free a buffer.  Uses the function provided to SetBufFree() or
-   * Buffer::Deallocate by default.
-   *
-   * @param buf The buffer
-   */
-  void FreeBuf(Buffer& buf) const noexcept { m_freeBuf(buf); }
-
-  /**
-   * Gets user-defined data.
-   * @return User-defined data if any, nullptr otherwise.
-   */
-  template <typename T = void>
-  std::shared_ptr<T> GetData() const {
-    return std::static_pointer_cast<T>(m_data);
-  }
-
-  /**
-   * Sets user-defined data.
-   * @param data User-defined arbitrary data.
-   */
-  void SetData(std::shared_ptr<void> data) { m_data = std::move(data); }
-
-  /**
-   * Error signal
-   */
-  sig::Signal<Error> error;
-
-  /**
-   * Closed signal
-   */
-  sig::Signal<> closed;
-
-  /**
-   * Report an error.
-   * @param err Error code
-   */
-  void ReportError(int err) const { error(Error(err)); }
-
- protected:
-  explicit Handle(uv_handle_t* uv_handle) : m_uv_handle{uv_handle} {
-    m_uv_handle->data = this;
-  }
-
-  void Keep() noexcept { m_self = shared_from_this(); }
-  void Release() noexcept { m_self.reset(); }
-  void ForceClosed() noexcept { m_closed = true; }
-
-  static void AllocBuf(uv_handle_t* handle, size_t size, uv_buf_t* buf);
-  static void DefaultFreeBuf(Buffer& buf);
-
-  template <typename F, typename... Args>
-  bool Invoke(F&& f, Args&&... args) const {
-    auto err = std::forward<F>(f)(std::forward<Args>(args)...);
-    if (err < 0) {
-      ReportError(err);
-    }
-    return err == 0;
-  }
-
- private:
-  std::shared_ptr<Handle> m_self;
-  uv_handle_t* m_uv_handle;
-  bool m_closed = false;
-  bool m_loopClosing = false;
-  std::function<Buffer(size_t)> m_allocBuf{&Buffer::Allocate};
-  std::function<void(Buffer&)> m_freeBuf{&DefaultFreeBuf};
-  std::shared_ptr<void> m_data;
-};
-
-/**
- * Handle.
- */
-template <typename T, typename U>
-class HandleImpl : public Handle {
- public:
-  std::shared_ptr<T> shared_from_this() {
-    return std::static_pointer_cast<T>(Handle::shared_from_this());
-  }
-
-  std::shared_ptr<const T> shared_from_this() const {
-    return std::static_pointer_cast<const T>(Handle::shared_from_this());
-  }
-
-  /**
-   * Get the underlying handle data structure.
-   *
-   * @return The underlying handle data structure.
-   */
-  U* GetRaw() const noexcept {
-    return reinterpret_cast<U*>(this->GetRawHandle());
-  }
-
- protected:
-  HandleImpl() : Handle{static_cast<uv_handle_t*>(std::malloc(sizeof(U)))} {}
-};
-
-}  // namespace wpi::uv
-
-#endif  // WPIUTIL_WPI_UV_HANDLE_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Idle.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Idle.h
deleted file mode 100644
index 869d43d..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Idle.h
+++ /dev/null
@@ -1,74 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_UV_IDLE_H_
-#define WPIUTIL_WPI_UV_IDLE_H_
-
-#include <uv.h>
-
-#include <memory>
-
-#include "wpi/Signal.h"
-#include "wpi/uv/Handle.h"
-
-namespace wpi::uv {
-
-class Loop;
-
-/**
- * Idle handle.
- *
- * Idle handles will generate a signal once per loop iteration, right
- * before the Prepare handles.
- *
- * The notable difference with Prepare handles is that when there are active
- * idle handles, the loop will perform a zero timeout poll instead of blocking
- * for I/O.
- *
- * @warning Despite the name, idle handles will signal every loop iteration,
- * not when the loop is actually "idle".  This also means they can easly become
- * CPU hogs.
- */
-class Idle final : public HandleImpl<Idle, uv_idle_t> {
-  struct private_init {};
-
- public:
-  explicit Idle(const private_init&) {}
-  ~Idle() noexcept override = default;
-
-  /**
-   * Create an idle handle.
-   *
-   * @param loop Loop object where this handle runs.
-   */
-  static std::shared_ptr<Idle> Create(Loop& loop);
-
-  /**
-   * Create an idle handle.
-   *
-   * @param loop Loop object where this handle runs.
-   */
-  static std::shared_ptr<Idle> Create(const std::shared_ptr<Loop>& loop) {
-    return Create(*loop);
-  }
-
-  /**
-   * Start the handle.
-   */
-  void Start();
-
-  /**
-   * Stop the handle.  The signal will no longer be generated.
-   */
-  void Stop() { Invoke(&uv_idle_stop, GetRaw()); }
-
-  /**
-   * Signal generated once per loop iteration prior to Prepare signals.
-   */
-  sig::Signal<> idle;
-};
-
-}  // namespace wpi::uv
-
-#endif  // WPIUTIL_WPI_UV_IDLE_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Loop.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Loop.h
deleted file mode 100644
index 9693053..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Loop.h
+++ /dev/null
@@ -1,253 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_UV_LOOP_H_
-#define WPIUTIL_WPI_UV_LOOP_H_
-
-#include <uv.h>
-
-#include <atomic>
-#include <chrono>
-#include <functional>
-#include <memory>
-#include <thread>
-#include <utility>
-
-#include "wpi/Signal.h"
-#include "wpi/function_ref.h"
-#include "wpi/uv/Error.h"
-
-namespace wpi::uv {
-
-class Handle;
-
-/**
- * Event loop.
- *
- * The event loop is the central part of uv functionality.  It takes care of
- * polling for I/O and scheduling signals to be generated based on different
- * sources of events.
- *
- * The event loop is not moveable, copyable, or directly constructible.  Use
- * Create() to create an event loop, or GetDefault() to get the default loop
- * if you know your program will only have a single one.
- */
-class Loop final : public std::enable_shared_from_this<Loop> {
-  struct private_init {};
-
- public:
-  using Time = std::chrono::duration<uint64_t, std::milli>;
-
-  enum Mode {
-    kDefault = UV_RUN_DEFAULT,
-    kOnce = UV_RUN_ONCE,
-    kNoWait = UV_RUN_NOWAIT
-  };
-
-  explicit Loop(const private_init&) noexcept;
-
-  Loop(const Loop&) = delete;
-  Loop& operator=(const Loop&) = delete;
-  Loop(Loop&& oth) = delete;
-  Loop& operator=(Loop&& oth) = delete;
-
-  ~Loop() noexcept;
-
-  /**
-   * Create a new event loop.  The created loop is not the default event loop.
-   *
-   * @return The newly created loop.  May return nullptr if a failure occurs.
-   */
-  static std::shared_ptr<Loop> Create();
-
-  /**
-   * Create the default event loop.  Only use this event loop if a single loop
-   * is needed for the entire application.
-   *
-   * @return The newly created loop.  May return nullptr if a failure occurs.
-   */
-  static std::shared_ptr<Loop> GetDefault();
-
-  /**
-   * Release all internal loop resources.
-   *
-   * Call this function only when the loop has finished executing and all open
-   * handles and requests have been closed, or the loop will emit an error.
-   *
-   * error() will be emitted in case of errors.
-   */
-  void Close();
-
-  /**
-   * Run the event loop.
-   *
-   * Available modes are:
-   *
-   * * `Loop::kDefault`: Run the event loop until there are no
-   *                     active and referenced handles or requests.
-   * * `Loop::kOnce`: Run a single event loop iteration. Note that this
-   *                  function blocksif there are no pending callbacks.
-   * * `Loop::kNoWait`: Run a single event loop iteration, but don't block
-   *                    if there are no pending callbacks.
-   *
-   * @return True when done, false in all other cases.
-   */
-  bool Run(Mode mode = kDefault) {
-    m_tid = std::this_thread::get_id();
-    int rv = uv_run(m_loop, static_cast<uv_run_mode>(static_cast<int>(mode)));
-    m_tid = std::thread::id{};
-    return rv == 0;
-  }
-
-  /**
-   * Check if there are active resources.
-   *
-   * @return True if there are active resources in the loop.
-   */
-  bool IsAlive() const noexcept { return uv_loop_alive(m_loop) != 0; }
-
-  /**
-   * Stop the event loop.
-   *
-   * This will cause Run() to end as soon as possible.
-   * This will happen not sooner than the next loop iteration.
-   * If this function was called before blocking for I/O, the loop won’t block
-   * for I/O on this iteration.
-   */
-  void Stop() noexcept { uv_stop(m_loop); }
-
-  /**
-   * Get backend file descriptor.
-   *
-   * Only kqueue, epoll and event ports are supported.
-   * This can be used in conjunction with `run(Loop::kNoWait)` to poll
-   * in one thread and run the event loop’s callbacks in another.
-   *
-   * @return The backend file descriptor.
-   */
-  int GetDescriptor() const noexcept { return uv_backend_fd(m_loop); }
-
-  /**
-   * Get the poll timeout.
-   *
-   * @return A `std::pair` composed of a boolean value that is true in case of
-   * valid timeout, false otherwise, and the timeout
-   * (`std::chrono::duration<uint64_t, std::milli>`).
-   */
-  std::pair<bool, Time> GetTimeout() const noexcept {
-    auto to = uv_backend_timeout(m_loop);
-    return std::make_pair(to == -1, Time{to});
-  }
-
-  /**
-   * Return the current timestamp in milliseconds.
-   *
-   * The timestamp is cached at the start of the event loop tick.
-   * The timestamp increases monotonically from some arbitrary point in
-   * time.
-   * Don’t make assumptions about the starting point, you will only get
-   * disappointed.
-   *
-   * @return The current timestamp in milliseconds (actual type is
-   * `std::chrono::duration<uint64_t, std::milli>`).
-   */
-  Time Now() const noexcept { return Time{uv_now(m_loop)}; }
-
-  /**
-   * Update the event loop’s concept of _now_.
-   *
-   * The current time is cached at the start of the event loop tick in order
-   * to reduce the number of time-related system calls.
-   * You won’t normally need to call this function unless you have callbacks
-   * that block the event loop for longer periods of time, where _longer_ is
-   * somewhat subjective but probably on the order of a millisecond or more.
-   */
-  void UpdateTime() noexcept { uv_update_time(m_loop); }
-
-  /**
-   * Walk the list of handles.
-   *
-   * The callback will be executed once for each handle that is still active.
-   *
-   * @param callback A function to be invoked once for each active handle.
-   */
-  void Walk(function_ref<void(Handle&)> callback);
-
-  /**
-   * Reinitialize any kernel state necessary in the child process after
-   * a fork(2) system call.
-   *
-   * Previously started watchers will continue to be started in the child
-   * process.
-   *
-   * It is necessary to explicitly call this function on every event loop
-   * created in the parent process that you plan to continue to use in the
-   * child, including the default loop (even if you don’t continue to use it
-   * in the parent). This function must be called before calling any API
-   * function using the loop in the child. Failure to do so will result in
-   * undefined behaviour, possibly including duplicate events delivered to
-   * both parent and child or aborting the child process.
-   *
-   * When possible, it is preferred to create a new loop in the child process
-   * instead of reusing a loop created in the parent. New loops created in the
-   * child process after the fork should not use this function.
-   *
-   * Note that this function is not implemented on Windows.
-   * Note also that this function is experimental in `libuv`. It may contain
-   * bugs, and is subject to change or removal. API and ABI stability is not
-   * guaranteed.
-   *
-   * error() will be emitted in case of errors.
-   */
-  void Fork();
-
-  /**
-   * Get the underlying event loop data structure.
-   *
-   * @return The underlying event loop data structure.
-   */
-  uv_loop_t* GetRaw() const noexcept { return m_loop; }
-
-  /**
-   * Gets user-defined data.
-   * @return User-defined data if any, nullptr otherwise.
-   */
-  template <typename T = void>
-  std::shared_ptr<T> GetData() const {
-    return std::static_pointer_cast<T>(m_data);
-  }
-
-  /**
-   * Sets user-defined data.
-   * @param data User-defined arbitrary data.
-   */
-  void SetData(std::shared_ptr<void> data) { m_data = std::move(data); }
-
-  /**
-   * Get the thread id of the loop thread.  If the loop is not currently
-   * running, returns default-constructed thread id.
-   */
-  std::thread::id GetThreadId() const { return m_tid; }
-
-  /**
-   * Error signal
-   */
-  sig::Signal<Error> error;
-
-  /**
-   * Reports error.
-   * @param err Error code
-   */
-  void ReportError(int err) { error(Error(err)); }
-
- private:
-  std::shared_ptr<void> m_data;
-  uv_loop_t* m_loop;
-  uv_loop_t m_loopStruct;
-  std::atomic<std::thread::id> m_tid;
-};
-
-}  // namespace wpi::uv
-
-#endif  // WPIUTIL_WPI_UV_LOOP_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/NetworkStream.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/NetworkStream.h
deleted file mode 100644
index faac9fe..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/NetworkStream.h
+++ /dev/null
@@ -1,153 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_UV_NETWORKSTREAM_H_
-#define WPIUTIL_WPI_UV_NETWORKSTREAM_H_
-
-#include <uv.h>
-
-#include <cstdlib>
-#include <functional>
-#include <memory>
-
-#include "wpi/Signal.h"
-#include "wpi/uv/Stream.h"
-
-namespace wpi::uv {
-
-class NetworkStream;
-
-/**
- * Connection request.
- */
-class ConnectReq : public RequestImpl<ConnectReq, uv_connect_t> {
- public:
-  ConnectReq();
-
-  NetworkStream& GetStream() const {
-    return *static_cast<NetworkStream*>(GetRaw()->handle->data);
-  }
-
-  /**
-   * Connection completed signal.
-   */
-  sig::Signal<> connected;
-};
-
-/**
- * Network stream handle.
- * This is an abstract type; there are two network stream implementations (Tcp
- * and Pipe).
- */
-class NetworkStream : public Stream {
- public:
-  static constexpr int kDefaultBacklog = 128;
-
-  std::shared_ptr<NetworkStream> shared_from_this() {
-    return std::static_pointer_cast<NetworkStream>(Handle::shared_from_this());
-  }
-
-  std::shared_ptr<const NetworkStream> shared_from_this() const {
-    return std::static_pointer_cast<const NetworkStream>(
-        Handle::shared_from_this());
-  }
-
-  /**
-   * Start listening for incoming connections.  When a new incoming connection
-   * is received the connection signal is generated.
-   * @param backlog the number of connections the kernel might queue, same as
-   *        listen(2).
-   */
-  void Listen(int backlog = kDefaultBacklog);
-
-  /**
-   * Start listening for incoming connections.  This is a convenience wrapper
-   * around `Listen(int)` that also connects a callback to the connection
-   * signal.  When a new incoming connection is received the connection signal
-   * is generated (and the callback is called).
-   * @param callback the callback to call when a connection is received.
-   *        `Accept()` should be called from this callback.
-   * @param backlog the number of connections the kernel might queue, same as
-   *        listen(2).
-   */
-  void Listen(std::function<void()> callback, int backlog = kDefaultBacklog);
-
-  /**
-   * Accept incoming connection.
-   *
-   * This call is used in conjunction with `Listen()` to accept incoming
-   * connections. Call this function after receiving a ListenEvent event to
-   * accept the connection.
-   * An error signal will be emitted in case of errors.
-   *
-   * When the connection signal is emitted it is guaranteed that this
-   * function will complete successfully the first time. If you attempt to use
-   * it more than once, it may fail.
-   * It is suggested to only call this function once per connection signal.
-   *
-   * @return The stream handle for the accepted connection, or nullptr on error.
-   */
-  std::shared_ptr<NetworkStream> Accept() {
-    return DoAccept()->shared_from_this();
-  }
-
-  /**
-   * Accept incoming connection.
-   *
-   * This call is used in conjunction with `Listen()` to accept incoming
-   * connections. Call this function after receiving a connection signal to
-   * accept the connection.
-   * An error signal will be emitted in case of errors.
-   *
-   * When the connection signal is emitted it is guaranteed that this
-   * function will complete successfully the first time. If you attempt to use
-   * it more than once, it may fail.
-   * It is suggested to only call this function once per connection signal.
-   *
-   * @param client Client stream object.
-   * @return False on error.
-   */
-  bool Accept(const std::shared_ptr<NetworkStream>& client) {
-    return Invoke(&uv_accept, GetRawStream(), client->GetRawStream());
-  }
-
-  /**
-   * Signal generated when an incoming connection is received.
-   */
-  sig::Signal<> connection;
-
- protected:
-  explicit NetworkStream(uv_stream_t* uv_stream) : Stream{uv_stream} {}
-
-  virtual NetworkStream* DoAccept() = 0;
-};
-
-template <typename T, typename U>
-class NetworkStreamImpl : public NetworkStream {
- public:
-  std::shared_ptr<T> shared_from_this() {
-    return std::static_pointer_cast<T>(Handle::shared_from_this());
-  }
-
-  std::shared_ptr<const T> shared_from_this() const {
-    return std::static_pointer_cast<const T>(Handle::shared_from_this());
-  }
-
-  /**
-   * Get the underlying handle data structure.
-   *
-   * @return The underlying handle data structure.
-   */
-  U* GetRaw() const noexcept {
-    return reinterpret_cast<U*>(this->GetRawHandle());
-  }
-
- protected:
-  NetworkStreamImpl()
-      : NetworkStream{static_cast<uv_stream_t*>(std::malloc(sizeof(U)))} {}
-};
-
-}  // namespace wpi::uv
-
-#endif  // WPIUTIL_WPI_UV_NETWORKSTREAM_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Pipe.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Pipe.h
deleted file mode 100644
index e223268..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Pipe.h
+++ /dev/null
@@ -1,208 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_UV_PIPE_H_
-#define WPIUTIL_WPI_UV_PIPE_H_
-
-#include <uv.h>
-
-#include <functional>
-#include <memory>
-#include <string>
-#include <string_view>
-
-#include "wpi/uv/NetworkStream.h"
-
-namespace wpi::uv {
-
-class Loop;
-class PipeConnectReq;
-
-/**
- * Pipe handle.
- * Pipe handles provide an abstraction over local domain sockets on Unix and
- * named pipes on Windows.
- */
-class Pipe final : public NetworkStreamImpl<Pipe, uv_pipe_t> {
-  struct private_init {};
-
- public:
-  explicit Pipe(const private_init&) {}
-  ~Pipe() noexcept override = default;
-
-  /**
-   * Create a pipe handle.
-   *
-   * @param loop Loop object where this handle runs.
-   * @param ipc Indicates if this pipe will be used for handle passing between
-   *            processes.
-   */
-  static std::shared_ptr<Pipe> Create(Loop& loop, bool ipc = false);
-
-  /**
-   * Create a pipe handle.
-   *
-   * @param loop Loop object where this handle runs.
-   * @param ipc Indicates if this pipe will be used for handle passing between
-   *            processes.
-   */
-  static std::shared_ptr<Pipe> Create(const std::shared_ptr<Loop>& loop,
-                                      bool ipc = false) {
-    return Create(*loop, ipc);
-  }
-
-  /**
-   * Reuse this handle.  This closes the handle, and after the close completes,
-   * reinitializes it (identically to Create) and calls the provided callback.
-   * Unlike Close(), it does NOT emit the closed signal, however, IsClosing()
-   * will return true until the callback is called.  This does nothing if
-   * IsClosing() is true (e.g. if Close() was called).
-   *
-   * @param ipc IPC
-   * @param callback Callback
-   */
-  void Reuse(std::function<void()> callback, bool ipc = false);
-
-  /**
-   * Accept incoming connection.
-   *
-   * This call is used in conjunction with `Listen()` to accept incoming
-   * connections. Call this function after receiving a ListenEvent event to
-   * accept the connection.
-   * An error signal will be emitted in case of errors.
-   *
-   * When the connection signal is emitted it is guaranteed that this
-   * function will complete successfully the first time. If you attempt to use
-   * it more than once, it may fail.
-   * It is suggested to only call this function once per connection signal.
-   *
-   * @return The stream handle for the accepted connection, or nullptr on error.
-   */
-  std::shared_ptr<Pipe> Accept();
-
-  /**
-   * Accept incoming connection.
-   *
-   * This call is used in conjunction with `Listen()` to accept incoming
-   * connections. Call this function after receiving a connection signal to
-   * accept the connection.
-   * An error signal will be emitted in case of errors.
-   *
-   * When the connection signal is emitted it is guaranteed that this
-   * function will complete successfully the first time. If you attempt to use
-   * it more than once, it may fail.
-   * It is suggested to only call this function once per connection signal.
-   *
-   * @param client Client stream object.
-   * @return False on error.
-   */
-  bool Accept(const std::shared_ptr<Pipe>& client) {
-    return NetworkStream::Accept(client);
-  }
-
-  /**
-   * Open an existing file descriptor or HANDLE as a pipe.
-   *
-   * @note The passed file descriptor or HANDLE is not checked for its type, but
-   * it's required that it represents a valid pipe.
-   *
-   * @param file A valid file handle (either a file descriptor or a HANDLE).
-   */
-  void Open(uv_file file) { Invoke(&uv_pipe_open, GetRaw(), file); }
-
-  /**
-   * Bind the pipe to a file path (Unix) or a name (Windows).
-   *
-   * @note Paths on Unix get truncated to `sizeof(sockaddr_un.sun_path)` bytes,
-   * typically between 92 and 108 bytes.
-   *
-   * @param name File path (Unix) or name (Windows).
-   */
-  void Bind(std::string_view name);
-
-  /**
-   * Connect to the Unix domain socket or the named pipe.
-   *
-   * @note Paths on Unix get truncated to `sizeof(sockaddr_un.sun_path)` bytes,
-   * typically between 92 and 108 bytes.
-   *
-   * HandleConnected() is called on the request when the connection has been
-   * established.
-   * HandleError() is called on the request in case of errors during the
-   * connection.
-   *
-   * @param name File path (Unix) or name (Windows).
-   * @param req connection request
-   */
-  void Connect(std::string_view name,
-               const std::shared_ptr<PipeConnectReq>& req);
-
-  /**
-   * Connect to the Unix domain socket or the named pipe.
-   *
-   * @note Paths on Unix get truncated to `sizeof(sockaddr_un.sun_path)` bytes,
-   * typically between 92 and 108 bytes.
-   *
-   * The callback is called when the connection has been established.  Errors
-   * are reported to the stream error handler.
-   *
-   * @param name File path (Unix) or name (Windows).
-   * @param callback Callback function to call when connection established
-   */
-  void Connect(std::string_view name, std::function<void()> callback);
-
-  /**
-   * Get the name of the Unix domain socket or the named pipe.
-   * @return The name (will be empty if an error occurred).
-   */
-  std::string GetSock();
-
-  /**
-   * Get the name of the Unix domain socket or the named pipe to which the
-   * handle is connected.
-   * @return The name (will be empty if an error occurred).
-   */
-  std::string GetPeer();
-
-  /**
-   * Set the number of pending pipe instance handles when the pipe server is
-   * waiting for connections.
-   * @note This setting applies to Windows only.
-   * @param count Number of pending handles.
-   */
-  void SetPendingInstances(int count) {
-    uv_pipe_pending_instances(GetRaw(), count);
-  }
-
-  /**
-   * Alters pipe permissions, allowing it to be accessed from processes run
-   * by different users.  Makes the pipe writable or readable by all users.
-   * Mode can be UV_WRITABLE, UV_READABLE, or both.  This function is blocking.
-   * @param flags chmod flags
-   */
-  void Chmod(int flags) { Invoke(&uv_pipe_chmod, GetRaw(), flags); }
-
- private:
-  Pipe* DoAccept() override;
-
-  struct ReuseData {
-    std::function<void()> callback;
-    bool ipc;
-  };
-  std::unique_ptr<ReuseData> m_reuseData;
-};
-
-/**
- * Pipe connection request.
- */
-class PipeConnectReq : public ConnectReq {
- public:
-  Pipe& GetStream() const {
-    return *static_cast<Pipe*>(&ConnectReq::GetStream());
-  }
-};
-
-}  // namespace wpi::uv
-
-#endif  // WPIUTIL_WPI_UV_PIPE_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Poll.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Poll.h
deleted file mode 100644
index 6e1e26d..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Poll.h
+++ /dev/null
@@ -1,121 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_UV_POLL_H_
-#define WPIUTIL_WPI_UV_POLL_H_
-
-#include <uv.h>
-
-#include <memory>
-
-#include "wpi/Signal.h"
-#include "wpi/uv/Handle.h"
-
-namespace wpi::uv {
-
-class Loop;
-
-/**
- * Poll handle.
- */
-class Poll final : public HandleImpl<Poll, uv_poll_t> {
-  struct private_init {};
-
- public:
-  explicit Poll(const private_init&) {}
-  ~Poll() noexcept override = default;
-
-  /**
-   * Create a poll handle using a file descriptor.
-   *
-   * @param loop Loop object where this handle runs.
-   * @param fd File descriptor.
-   */
-  static std::shared_ptr<Poll> Create(Loop& loop, int fd);
-
-  /**
-   * Create a poll handle using a file descriptor.
-   *
-   * @param loop Loop object where this handle runs.
-   * @param fd File descriptor.
-   */
-  static std::shared_ptr<Poll> Create(const std::shared_ptr<Loop>& loop,
-                                      int fd) {
-    return Create(*loop, fd);
-  }
-
-  /**
-   * Create a poll handle using a socket descriptor.
-   *
-   * @param loop Loop object where this handle runs.
-   * @param sock Socket descriptor.
-   */
-  static std::shared_ptr<Poll> CreateSocket(Loop& loop, uv_os_sock_t sock);
-
-  /**
-   * Create a poll handle using a socket descriptor.
-   *
-   * @param loop Loop object where this handle runs.
-   * @param sock Socket descriptor.
-   */
-  static std::shared_ptr<Poll> CreateSocket(const std::shared_ptr<Loop>& loop,
-                                            uv_os_sock_t sock) {
-    return CreateSocket(*loop, sock);
-  }
-
-  /**
-   * Reuse this handle.  This closes the handle, and after the close completes,
-   * reinitializes it (identically to Create) and calls the provided callback.
-   * Unlike Close(), it does NOT emit the closed signal, however, IsClosing()
-   * will return true until the callback is called.  This does nothing if
-   * IsClosing() is true (e.g. if Close() was called).
-   *
-   * @param fd File descriptor
-   * @param callback Callback
-   */
-  void Reuse(int fd, std::function<void()> callback);
-
-  /**
-   * Reuse this handle.  This closes the handle, and after the close completes,
-   * reinitializes it (identically to CreateSocket) and calls the provided
-   * callback.  Unlike Close(), it does NOT emit the closed signal, however,
-   * IsClosing() will return true until the callback is called.  This does
-   * nothing if IsClosing() is true (e.g. if Close() was called).
-   *
-   * @param sock Socket descriptor.
-   * @param callback Callback
-   */
-  void ReuseSocket(uv_os_sock_t sock, std::function<void()> callback);
-
-  /**
-   * Start polling the file descriptor.
-   *
-   * @param events Bitmask of events (UV_READABLE, UV_WRITEABLE, UV_PRIORITIZED,
-   *               and UV_DISCONNECT).
-   */
-  void Start(int events);
-
-  /**
-   * Stop polling the file descriptor.
-   */
-  void Stop() { Invoke(&uv_poll_stop, GetRaw()); }
-
-  /**
-   * Signal generated when a poll event occurs.
-   */
-  sig::Signal<int> pollEvent;
-
- private:
-  struct ReuseData {
-    std::function<void()> callback;
-    bool isSocket;
-    int fd;
-    uv_os_sock_t sock;
-  };
-  std::unique_ptr<ReuseData> m_reuseData;
-};
-
-}  // namespace wpi::uv
-
-#endif  // WPIUTIL_WPI_UV_POLL_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Prepare.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Prepare.h
deleted file mode 100644
index 88ae2d9..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Prepare.h
+++ /dev/null
@@ -1,65 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_UV_PREPARE_H_
-#define WPIUTIL_WPI_UV_PREPARE_H_
-
-#include <uv.h>
-
-#include <memory>
-
-#include "wpi/Signal.h"
-#include "wpi/uv/Handle.h"
-
-namespace wpi::uv {
-
-class Loop;
-
-/**
- * Prepare handle.
- * Prepare handles will generate a signal once per loop iteration, right
- * before polling for I/O.
- */
-class Prepare final : public HandleImpl<Prepare, uv_prepare_t> {
-  struct private_init {};
-
- public:
-  explicit Prepare(const private_init&) {}
-  ~Prepare() noexcept override = default;
-
-  /**
-   * Create a prepare handle.
-   *
-   * @param loop Loop object where this handle runs.
-   */
-  static std::shared_ptr<Prepare> Create(Loop& loop);
-
-  /**
-   * Create a prepare handle.
-   *
-   * @param loop Loop object where this handle runs.
-   */
-  static std::shared_ptr<Prepare> Create(const std::shared_ptr<Loop>& loop) {
-    return Create(*loop);
-  }
-
-  /**
-   * Start the handle.
-   */
-  void Start();
-
-  /**
-   * Stop the handle.  The signal will no longer be generated.
-   */
-  void Stop() { Invoke(&uv_prepare_stop, GetRaw()); }
-
-  /**
-   * Signal generated once per loop iteration prior to polling for I/O.
-   */
-  sig::Signal<> prepare;
-};
-
-}  // namespace wpi::uv
-
-#endif  // WPIUTIL_WPI_UV_PREPARE_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Process.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Process.h
deleted file mode 100644
index fc2315e..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Process.h
+++ /dev/null
@@ -1,310 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_UV_PROCESS_H_
-#define WPIUTIL_WPI_UV_PROCESS_H_
-
-#include <uv.h>
-
-#include <initializer_list>
-#include <memory>
-#include <string>
-#include <string_view>
-
-#include "wpi/Signal.h"
-#include "wpi/SmallVector.h"
-#include "wpi/span.h"
-#include "wpi/uv/Handle.h"
-
-namespace wpi::uv {
-
-class Loop;
-class Pipe;
-
-/**
- * Process handle.
- * Process handles will spawn a new process and allow the user to control it
- * and establish communication channels with it using streams.
- */
-class Process final : public HandleImpl<Process, uv_process_t> {
-  struct private_init {};
-
- public:
-  explicit Process(const private_init&) {}
-  ~Process() noexcept override = default;
-
-  /**
-   * Structure for Spawn() option temporaries.  This is a reference type, so if
-   * this value is stored outside of a temporary, be careful about overwriting
-   * what it points to.
-   */
-  struct Option {
-    enum Type {
-      kNone,
-      kArg,
-      kEnv,
-      kCwd,
-      kUid,
-      kGid,
-      kSetFlags,
-      kClearFlags,
-      kStdioIgnore,
-      kStdioInheritFd,
-      kStdioInheritPipe,
-      kStdioCreatePipe
-    };
-
-    Option() : m_type(kNone) {}
-
-    /*implicit*/ Option(const char* arg) {  // NOLINT
-      m_data.str = arg;
-    }
-
-    /*implicit*/ Option(const std::string& arg) {  // NOLINT
-      m_data.str = arg.data();
-    }
-
-    /*implicit*/ Option(std::string_view arg)  // NOLINT
-        : m_strData(arg) {
-      m_data.str = m_strData.c_str();
-    }
-
-    /*implicit*/ Option(const SmallVectorImpl<char>& arg)  // NOLINT
-        : m_strData(arg.data(), arg.size()) {
-      m_data.str = m_strData.c_str();
-    }
-
-    explicit Option(Type type) : m_type(type) {}
-
-    Type m_type = kArg;
-    std::string m_strData;
-    union {
-      const char* str;
-      uv_uid_t uid;
-      uv_gid_t gid;
-      unsigned int flags;
-      struct {
-        size_t index;
-        union {
-          int fd;
-          Pipe* pipe;
-        };
-        unsigned int flags;
-      } stdio;
-    } m_data;
-  };
-
-  /**
-   * Set environment variable for the subprocess.  If not set, the parent's
-   * environment is used.
-   * @param env environment variable
-   */
-  static Option Env(std::string_view env) {
-    Option o(Option::kEnv);
-    o.m_strData = env;
-    o.m_data.str = o.m_strData.c_str();
-    return o;
-  }
-
-  /**
-   * Set the current working directory for the subprocess.
-   * @param cwd current working directory
-   */
-  static Option Cwd(std::string_view cwd) {
-    Option o(Option::kCwd);
-    o.m_strData = cwd;
-    o.m_data.str = o.m_strData.c_str();
-    return o;
-  }
-
-  /**
-   * Set the child process' user id.
-   * @param uid user id
-   */
-  static Option Uid(uv_uid_t uid) {
-    Option o(Option::kUid);
-    o.m_data.uid = uid;
-    return o;
-  }
-
-  /**
-   * Set the child process' group id.
-   * @param gid group id
-   */
-  static Option Gid(uv_gid_t gid) {
-    Option o(Option::kGid);
-    o.m_data.gid = gid;
-    return o;
-  }
-
-  /**
-   * Set spawn flags.
-   * @param flags Bitmask values from uv_process_flags.
-   */
-  static Option SetFlags(unsigned int flags) {
-    Option o(Option::kSetFlags);
-    o.m_data.flags = flags;
-    return o;
-  }
-
-  /**
-   * Clear spawn flags.
-   * @param flags Bitmask values from uv_process_flags.
-   */
-  static Option ClearFlags(unsigned int flags) {
-    Option o(Option::kClearFlags);
-    o.m_data.flags = flags;
-    return o;
-  }
-
-  /**
-   * Explicitly ignore a stdio.
-   * @param index stdio index
-   */
-  static Option StdioIgnore(size_t index) {
-    Option o(Option::kStdioIgnore);
-    o.m_data.stdio.index = index;
-    return o;
-  }
-
-  /**
-   * Inherit a file descriptor from the parent process.
-   * @param index stdio index
-   * @param fd parent file descriptor
-   */
-  static Option StdioInherit(size_t index, int fd) {
-    Option o(Option::kStdioInheritFd);
-    o.m_data.stdio.index = index;
-    o.m_data.stdio.fd = fd;
-    return o;
-  }
-
-  /**
-   * Inherit a pipe from the parent process.
-   * @param index stdio index
-   * @param pipe pipe
-   */
-  static Option StdioInherit(size_t index, Pipe& pipe) {
-    Option o(Option::kStdioInheritPipe);
-    o.m_data.stdio.index = index;
-    o.m_data.stdio.pipe = &pipe;
-    return o;
-  }
-
-  /**
-   * Create a pipe between the child and the parent.
-   * @param index stdio index
-   * @param pipe pipe
-   * @param flags Some combination of UV_READABLE_PIPE, UV_WRITABLE_PIPE, and
-   *              UV_OVERLAPPED_PIPE (Windows only, ignored on Unix).
-   */
-  static Option StdioCreatePipe(size_t index, Pipe& pipe, unsigned int flags) {
-    Option o(Option::kStdioCreatePipe);
-    o.m_data.stdio.index = index;
-    o.m_data.stdio.pipe = &pipe;
-    o.m_data.stdio.flags = flags;
-    return o;
-  }
-
-  /**
-   * Disables inheritance for file descriptors / handles that this process
-   * inherited from its parent.  The effect is that child processes spawned
-   * by this process don't accidentally inherit these handles.
-   *
-   * It is recommended to call this function as early in your program as
-   * possible, before the inherited file descriptors can be closed or
-   * duplicated.
-   */
-  static void DisableStdioInheritance() { uv_disable_stdio_inheritance(); }
-
-  /**
-   * Starts a process.  If the process is not successfully spawned, an error
-   * is generated on the loop and this function returns nullptr.
-   *
-   * Possible reasons for failing to spawn would include (but not be limited to)
-   * the file to execute not existing, not having permissions to use the setuid
-   * or setgid specified, or not having enough memory to allocate for the new
-   * process.
-   *
-   * @param loop Loop object where this handle runs.
-   * @param file Path pointing to the program to be executed
-   * @param options Process options
-   */
-  static std::shared_ptr<Process> SpawnArray(Loop& loop, std::string_view file,
-                                             span<const Option> options);
-
-  static std::shared_ptr<Process> SpawnArray(
-      Loop& loop, std::string_view file,
-      std::initializer_list<Option> options) {
-    return SpawnArray(loop, file, {options.begin(), options.end()});
-  }
-
-  template <typename... Args>
-  static std::shared_ptr<Process> Spawn(Loop& loop, std::string_view file,
-                                        const Args&... options) {
-    return SpawnArray(loop, file, {options...});
-  }
-
-  /**
-   * Starts a process.  If the process is not successfully spawned, an error
-   * is generated on the loop and this function returns nullptr.
-   *
-   * Possible reasons for failing to spawn would include (but not be limited to)
-   * the file to execute not existing, not having permissions to use the setuid
-   * or setgid specified, or not having enough memory to allocate for the new
-   * process.
-   *
-   * @param loop Loop object where this handle runs.
-   * @param file Path pointing to the program to be executed
-   * @param options Process options
-   */
-  static std::shared_ptr<Process> SpawnArray(const std::shared_ptr<Loop>& loop,
-                                             std::string_view file,
-                                             span<const Option> options) {
-    return SpawnArray(*loop, file, options);
-  }
-
-  static std::shared_ptr<Process> SpawnArray(
-      const std::shared_ptr<Loop>& loop, std::string_view file,
-      std::initializer_list<Option> options) {
-    return SpawnArray(*loop, file, options);
-  }
-
-  template <typename... Args>
-  static std::shared_ptr<Process> Spawn(const std::shared_ptr<Loop>& loop,
-                                        std::string_view file,
-                                        const Args&... options) {
-    return SpawnArray(*loop, file, {options...});
-  }
-
-  /**
-   * Sends the specified signal to the process.
-   * @param signum signal number
-   */
-  void Kill(int signum) { Invoke(&uv_process_kill, GetRaw(), signum); }
-
-  /**
-   * Sends the specified signal to the given PID.
-   * @param pid process ID
-   * @param signum signal number
-   * @return 0 on success, otherwise error code.
-   */
-  static int Kill(int pid, int signum) noexcept { return uv_kill(pid, signum); }
-
-  /**
-   * Get the process ID.
-   * @return Process ID.
-   */
-  uv_pid_t GetPid() const noexcept { return GetRaw()->pid; }
-
-  /**
-   * Signal generated when the process exits.  The parameters are the exit
-   * status and the signal that caused the process to terminate, if any.
-   */
-  sig::Signal<int64_t, int> exited;
-};
-
-}  // namespace wpi::uv
-
-#endif  // WPIUTIL_WPI_UV_PROCESS_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Request.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Request.h
deleted file mode 100644
index 3f6a19d..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Request.h
+++ /dev/null
@@ -1,166 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_UV_REQUEST_H_
-#define WPIUTIL_WPI_UV_REQUEST_H_
-
-#include <uv.h>
-
-#include <functional>
-#include <memory>
-
-#include "wpi/uv/Error.h"
-
-namespace wpi::uv {
-
-/**
- * Request.  Requests are not moveable or copyable.
- * This class provides shared_ptr ownership and shared_from_this.
- */
-class Request : public std::enable_shared_from_this<Request> {
- public:
-  using Type = uv_req_type;
-
-  Request(const Request&) = delete;
-  Request(Request&&) = delete;
-  Request& operator=(const Request&) = delete;
-  Request& operator=(Request&&) = delete;
-  virtual ~Request() noexcept = default;
-
-  /**
-   * Get the type of the request.
-   *
-   * A base request offers no functionality to promote it to the actual request
-   * type. By means of this function, the type of the underlying request as
-   * specified by Type is made available.
-   *
-   * @return The actual type of the request.
-   */
-  Type GetType() const noexcept { return m_uv_req->type; }
-
-  /**
-   * Get the name of the type of the request.  E.g. "connect" for connect.
-   */
-  const char* GetTypeName() const noexcept {
-    return uv_req_type_name(m_uv_req->type);
-  }
-
-  /**
-   * Cancel a pending request.
-   *
-   * This method fails if the request is executing or has finished
-   * executing.
-   * It can emit an error signal in case of errors.
-   *
-   * @return True in case of success, false otherwise.
-   */
-  bool Cancel() { return uv_cancel(m_uv_req) == 0; }
-
-  /**
-   * Return the size of the underlying request type.
-   * @return The size of the underlying request type.
-   */
-  size_t RawSize() const noexcept { return uv_req_size(m_uv_req->type); }
-
-  /**
-   * Get the underlying request data structure.
-   *
-   * @return The underlying request data structure.
-   */
-  uv_req_t* GetRawReq() noexcept { return m_uv_req; }
-
-  /**
-   * Get the underlying request data structure.
-   *
-   * @return The underlying request data structure.
-   */
-  const uv_req_t* GetRawReq() const noexcept { return m_uv_req; }
-
-  /**
-   * Keep this request in memory even if no outside shared_ptr references
-   * remain.  To release call Release().
-   *
-   * Derived classes can override this method for different memory management
-   * approaches (e.g. pooled storage of requests).
-   */
-  virtual void Keep() noexcept { m_self = shared_from_this(); }
-
-  /**
-   * No longer force holding this request in memory.  Does not immediately
-   * destroy the object unless no outside shared_ptr references remain.
-   *
-   * Derived classes can override this method for different memory management
-   * approaches (e.g. pooled storage of requests).
-   */
-  virtual void Release() noexcept { m_self.reset(); }
-
-  /**
-   * Error callback.  By default, this is set up to report errors to the handle
-   * that created this request.
-   * @param err error code
-   */
-  std::function<void(Error)> error;
-
-  /**
-   * Report an error.
-   * @param err Error code
-   */
-  void ReportError(int err) { error(Error(err)); }
-
- protected:
-  /**
-   * Constructor.
-   */
-  explicit Request(uv_req_t* uv_req) : m_uv_req{uv_req} {
-    m_uv_req->data = this;
-  }
-
- private:
-  std::shared_ptr<Request> m_self;
-  uv_req_t* m_uv_req;
-};
-
-/**
- * Request.  Requests are not moveable or copyable.
- * @tparam T CRTP derived class
- * @tparam U underlying libuv request type
- */
-template <typename T, typename U>
-class RequestImpl : public Request {
- public:
-  std::shared_ptr<T> shared_from_this() {
-    return std::static_pointer_cast<T>(this->shared_from_this());
-  }
-
-  std::shared_ptr<const T> shared_from_this() const {
-    return std::static_pointer_cast<const T>(this->shared_from_this());
-  }
-
-  /**
-   * Get the underlying request data structure.
-   *
-   * @return The underlying request data structure.
-   */
-  U* GetRaw() noexcept { return &m_uv_req; }
-
-  /**
-   * Get the underlying request data structure.
-   *
-   * @return The underlying request data structure.
-   */
-  const U* GetRaw() const noexcept { return &m_uv_req; }
-
- protected:
-  /**
-   * Constructor.
-   */
-  RequestImpl() : Request{reinterpret_cast<uv_req_t*>(&m_uv_req)} {}
-
- private:
-  U m_uv_req;
-};
-
-}  // namespace wpi::uv
-
-#endif  // WPIUTIL_WPI_UV_REQUEST_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Signal.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Signal.h
deleted file mode 100644
index 9abcad3..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Signal.h
+++ /dev/null
@@ -1,79 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_UV_SIGNAL_H_
-#define WPIUTIL_WPI_UV_SIGNAL_H_
-
-#include <uv.h>
-
-#include <memory>
-
-#include "wpi/Signal.h"
-#include "wpi/uv/Handle.h"
-
-namespace wpi::uv {
-
-class Loop;
-
-/**
- * Signal handle.
- */
-class Signal final : public HandleImpl<Signal, uv_signal_t> {
-  struct private_init {};
-
- public:
-  explicit Signal(const private_init&) {}
-  ~Signal() noexcept override = default;
-
-  /**
-   * Create a signal handle.
-   *
-   * @param loop Loop object where this handle runs.
-   */
-  static std::shared_ptr<Signal> Create(Loop& loop);
-
-  /**
-   * Create a signal handle.
-   *
-   * @param loop Loop object where this handle runs.
-   */
-  static std::shared_ptr<Signal> Create(const std::shared_ptr<Loop>& loop) {
-    return Create(*loop);
-  }
-
-  /**
-   * Start watching for the given signal.
-   *
-   * @param signum Signal to watch for.
-   */
-  void Start(int signum);
-
-  /**
-   * Start watching for the given signal.  Same as Start() but the signal
-   * handler is reset the moment the signal is received.
-   *
-   * @param signum Signal to watch for.
-   */
-  void StartOneshot(int signum);
-
-  /**
-   * Stop watching for the signal.
-   */
-  void Stop() { Invoke(&uv_signal_stop, GetRaw()); }
-
-  /**
-   * Get the signal being monitored.
-   * @return Signal number.
-   */
-  int GetSignal() const { return GetRaw()->signum; }
-
-  /**
-   * Signal generated when a signal occurs.
-   */
-  sig::Signal<int> signal;
-};
-
-}  // namespace wpi::uv
-
-#endif  // WPIUTIL_WPI_UV_SIGNAL_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Stream.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Stream.h
deleted file mode 100644
index 0ade972..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Stream.h
+++ /dev/null
@@ -1,302 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_UV_STREAM_H_
-#define WPIUTIL_WPI_UV_STREAM_H_
-
-#include <uv.h>
-
-#include <cstdlib>
-#include <functional>
-#include <initializer_list>
-#include <memory>
-#include <utility>
-
-#include "wpi/Signal.h"
-#include "wpi/span.h"
-#include "wpi/uv/Buffer.h"
-#include "wpi/uv/Handle.h"
-#include "wpi/uv/Request.h"
-
-namespace wpi::uv {
-
-class Stream;
-
-/**
- * Shutdown request.
- */
-class ShutdownReq : public RequestImpl<ShutdownReq, uv_shutdown_t> {
- public:
-  ShutdownReq();
-
-  Stream& GetStream() const {
-    return *static_cast<Stream*>(GetRaw()->handle->data);
-  }
-
-  /**
-   * Shutdown completed signal.
-   */
-  sig::Signal<> complete;
-};
-
-/**
- * Write request.
- */
-class WriteReq : public RequestImpl<WriteReq, uv_write_t> {
- public:
-  WriteReq();
-
-  Stream& GetStream() const {
-    return *static_cast<Stream*>(GetRaw()->handle->data);
-  }
-
-  /**
-   * Write completed signal.  This is called even if an error occurred.
-   * @param err error value
-   */
-  sig::Signal<Error> finish;
-};
-
-/**
- * Stream handle.
- * Stream handles provide an abstraction of a duplex communication channel.
- * This is an abstract type; there are three stream implementations (Tcp,
- * Pipe, and Tty).
- */
-class Stream : public Handle {
- public:
-  std::shared_ptr<Stream> shared_from_this() {
-    return std::static_pointer_cast<Stream>(Handle::shared_from_this());
-  }
-
-  std::shared_ptr<const Stream> shared_from_this() const {
-    return std::static_pointer_cast<const Stream>(Handle::shared_from_this());
-  }
-
-  /**
-   * Shutdown the outgoing (write) side of a duplex stream. It waits for pending
-   * write requests to complete.  HandleShutdownComplete() is called on the
-   * request after shutdown is complete.
-   *
-   * @param req shutdown request
-   */
-  void Shutdown(const std::shared_ptr<ShutdownReq>& req);
-
-  /**
-   * Shutdown the outgoing (write) side of a duplex stream. It waits for pending
-   * write requests to complete.  The callback is called after shutdown is
-   * complete.  Errors will be reported to the stream error handler.
-   *
-   * @param callback Callback function to call when shutdown completes
-   * @return Connection object for the callback
-   */
-  void Shutdown(std::function<void()> callback = nullptr);
-
-  /**
-   * Start reading data from an incoming stream.
-   *
-   * This will only succeed after a connection has been established.
-   *
-   * A data signal will be emitted several times until there is no more
-   * data to read or `StopRead()` is called.
-   * An end signal will be emitted when there is no more data to read.
-   */
-  void StartRead();
-
-  /**
-   * Stop reading data from the stream.
-   *
-   * This function is idempotent and may be safely called on a stopped stream.
-   */
-  void StopRead() { Invoke(&uv_read_stop, GetRawStream()); }
-
-  /**
-   * Write data to the stream.
-   *
-   * Data are written in order. The lifetime of the data pointers passed in
-   * the `bufs` parameter must exceed the lifetime of the write request.
-   * An easy way to ensure this is to have the write request keep track of
-   * the data and use either its Complete() function or destructor to free the
-   * data.
-   *
-   * The finish signal will be emitted on the request object when the data
-   * has been written (or if an error occurs).
-   * The error signal will be emitted on the request object in case of errors.
-   *
-   * @param bufs The buffers to be written to the stream.
-   * @param req write request
-   */
-  void Write(span<const Buffer> bufs, const std::shared_ptr<WriteReq>& req);
-
-  /**
-   * Write data to the stream.
-   *
-   * Data are written in order. The lifetime of the data pointers passed in
-   * the `bufs` parameter must exceed the lifetime of the write request.
-   * An easy way to ensure this is to have the write request keep track of
-   * the data and use either its Complete() function or destructor to free the
-   * data.
-   *
-   * The finish signal will be emitted on the request object when the data
-   * has been written (or if an error occurs).
-   * The error signal will be emitted on the request object in case of errors.
-   *
-   * @param bufs The buffers to be written to the stream.
-   * @param req write request
-   */
-  void Write(std::initializer_list<Buffer> bufs,
-             const std::shared_ptr<WriteReq>& req) {
-    Write({bufs.begin(), bufs.end()}, req);
-  }
-
-  /**
-   * Write data to the stream.
-   *
-   * Data are written in order. The lifetime of the data pointers passed in
-   * the `bufs` parameter must exceed the lifetime of the write request.
-   * The callback can be used to free data after the request completes.
-   *
-   * The callback will be called when the data has been written (even if an
-   * error occurred).  Errors will be reported to the stream error handler.
-   *
-   * @param bufs The buffers to be written to the stream.
-   * @param callback Callback function to call when the write completes
-   */
-  void Write(span<const Buffer> bufs,
-             std::function<void(span<Buffer>, Error)> callback);
-
-  /**
-   * Write data to the stream.
-   *
-   * Data are written in order. The lifetime of the data pointers passed in
-   * the `bufs` parameter must exceed the lifetime of the write request.
-   * The callback can be used to free data after the request completes.
-   *
-   * The callback will be called when the data has been written (even if an
-   * error occurred).  Errors will be reported to the stream error handler.
-   *
-   * @param bufs The buffers to be written to the stream.
-   * @param callback Callback function to call when the write completes
-   */
-  void Write(std::initializer_list<Buffer> bufs,
-             std::function<void(span<Buffer>, Error)> callback) {
-    Write({bufs.begin(), bufs.end()}, std::move(callback));
-  }
-
-  /**
-   * Queue a write request if it can be completed immediately.
-   *
-   * Same as `Write()`, but won’t queue a write request if it can’t be
-   * completed immediately.
-   * An error signal will be emitted in case of errors.
-   *
-   * @param bufs The buffers to be written to the stream.
-   * @return Number of bytes written.
-   */
-  int TryWrite(span<const Buffer> bufs);
-
-  /**
-   * Queue a write request if it can be completed immediately.
-   *
-   * Same as `Write()`, but won’t queue a write request if it can’t be
-   * completed immediately.
-   * An error signal will be emitted in case of errors.
-   *
-   * @param bufs The buffers to be written to the stream.
-   * @return Number of bytes written.
-   */
-  int TryWrite(std::initializer_list<Buffer> bufs) {
-    return TryWrite({bufs.begin(), bufs.end()});
-  }
-
-  /**
-   * Check if the stream is readable.
-   * @return True if the stream is readable, false otherwise.
-   */
-  bool IsReadable() const noexcept {
-    return uv_is_readable(GetRawStream()) == 1;
-  }
-
-  /**
-   * @brief Checks if the stream is writable.
-   * @return True if the stream is writable, false otherwise.
-   */
-  bool IsWritable() const noexcept {
-    return uv_is_writable(GetRawStream()) == 1;
-  }
-
-  /**
-   * Enable or disable blocking mode for a stream.
-   *
-   * When blocking mode is enabled all writes complete synchronously. The
-   * interface remains unchanged otherwise, e.g. completion or failure of the
-   * operation will still be reported through events which are emitted
-   * asynchronously.
-   *
-   * @param enable True to enable blocking mode, false otherwise.
-   * @return True in case of success, false otherwise.
-   */
-  bool SetBlocking(bool enable) noexcept {
-    return uv_stream_set_blocking(GetRawStream(), enable) == 0;
-  }
-
-  /**
-   * Gets the amount of queued bytes waiting to be sent.
-   * @return Amount of queued bytes waiting to be sent.
-   */
-  size_t GetWriteQueueSize() const noexcept {
-    return GetRawStream()->write_queue_size;
-  }
-
-  /**
-   * Get the underlying stream data structure.
-   *
-   * @return The underlying stream data structure.
-   */
-  uv_stream_t* GetRawStream() const noexcept {
-    return reinterpret_cast<uv_stream_t*>(GetRawHandle());
-  }
-
-  /**
-   * Signal generated when data was read on a stream.
-   */
-  sig::Signal<Buffer&, size_t> data;
-
-  /**
-   * Signal generated when no more read data is available.
-   */
-  sig::Signal<> end;
-
- protected:
-  explicit Stream(uv_stream_t* uv_stream)
-      : Handle{reinterpret_cast<uv_handle_t*>(uv_stream)} {}
-};
-
-template <typename T, typename U>
-class StreamImpl : public Stream {
- public:
-  std::shared_ptr<T> shared_from_this() {
-    return std::static_pointer_cast<T>(Handle::shared_from_this());
-  }
-
-  std::shared_ptr<const T> shared_from_this() const {
-    return std::static_pointer_cast<const T>(Handle::shared_from_this());
-  }
-
-  /**
-   * Get the underlying handle data structure.
-   *
-   * @return The underlying handle data structure.
-   */
-  U* GetRaw() const noexcept {
-    return reinterpret_cast<U*>(this->GetRawHandle());
-  }
-
- protected:
-  StreamImpl() : Stream{static_cast<uv_stream_t*>(std::malloc(sizeof(U)))} {}
-};
-
-}  // namespace wpi::uv
-
-#endif  // WPIUTIL_WPI_UV_STREAM_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Tcp.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Tcp.h
deleted file mode 100644
index c712f0b..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Tcp.h
+++ /dev/null
@@ -1,363 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_UV_TCP_H_
-#define WPIUTIL_WPI_UV_TCP_H_
-
-#include <uv.h>
-
-#include <chrono>
-#include <functional>
-#include <memory>
-#include <string_view>
-#include <utility>
-
-#include "wpi/uv/NetworkStream.h"
-
-namespace wpi::uv {
-
-class Loop;
-class TcpConnectReq;
-
-/**
- * TCP handle.
- * TCP handles are used to represent both TCP streams and servers.
- */
-class Tcp final : public NetworkStreamImpl<Tcp, uv_tcp_t> {
-  struct private_init {};
-
- public:
-  using Time = std::chrono::duration<uint64_t, std::milli>;
-
-  explicit Tcp(const private_init&) {}
-  ~Tcp() noexcept override = default;
-
-  /**
-   * Create a TCP handle.
-   *
-   * @param loop Loop object where this handle runs.
-   * @param flags Flags
-   */
-  static std::shared_ptr<Tcp> Create(Loop& loop,
-                                     unsigned int flags = AF_UNSPEC);
-
-  /**
-   * Create a TCP handle.
-   *
-   * @param loop Loop object where this handle runs.
-   * @param flags Flags
-   */
-  static std::shared_ptr<Tcp> Create(const std::shared_ptr<Loop>& loop,
-                                     unsigned int flags = AF_UNSPEC) {
-    return Create(*loop, flags);
-  }
-
-  /**
-   * Reuse this handle.  This closes the handle, and after the close completes,
-   * reinitializes it (identically to Create) and calls the provided callback.
-   * Unlike Close(), it does NOT emit the closed signal, however, IsClosing()
-   * will return true until the callback is called.  This does nothing if
-   * IsClosing() is true (e.g. if Close() was called).
-   *
-   * @param flags Flags
-   * @param callback Callback
-   */
-  void Reuse(std::function<void()> callback, unsigned int flags = AF_UNSPEC);
-
-  /**
-   * Accept incoming connection.
-   *
-   * This call is used in conjunction with `Listen()` to accept incoming
-   * connections. Call this function after receiving a ListenEvent event to
-   * accept the connection.
-   * An error signal will be emitted in case of errors.
-   *
-   * When the connection signal is emitted it is guaranteed that this
-   * function will complete successfully the first time. If you attempt to use
-   * it more than once, it may fail.
-   * It is suggested to only call this function once per connection signal.
-   *
-   * @return The stream handle for the accepted connection, or nullptr on error.
-   */
-  std::shared_ptr<Tcp> Accept();
-
-  /**
-   * Accept incoming connection.
-   *
-   * This call is used in conjunction with `Listen()` to accept incoming
-   * connections. Call this function after receiving a connection signal to
-   * accept the connection.
-   * An error signal will be emitted in case of errors.
-   *
-   * When the connection signal is emitted it is guaranteed that this
-   * function will complete successfully the first time. If you attempt to use
-   * it more than once, it may fail.
-   * It is suggested to only call this function once per connection signal.
-   *
-   * @param client Client stream object.
-   * @return False on error.
-   */
-  bool Accept(const std::shared_ptr<Tcp>& client) {
-    return NetworkStream::Accept(client);
-  }
-
-  /**
-   * Open an existing file descriptor or SOCKET as a TCP handle.
-   *
-   * @note The passed file descriptor or SOCKET is not checked for its type, but
-   * it's required that it represents a valid stream socket.
-   *
-   * @param sock A valid socket handle (either a file descriptor or a SOCKET).
-   */
-  void Open(uv_os_sock_t sock) { Invoke(&uv_tcp_open, GetRaw(), sock); }
-
-  /**
-   * Enable no delay operation (turns off Nagle's algorithm).
-   * @param enable True to enable it, false otherwise.
-   * @return True in case of success, false otherwise.
-   */
-  bool SetNoDelay(bool enable) { return uv_tcp_nodelay(GetRaw(), enable) == 0; }
-
-  /**
-   * Enable/Disable TCP keep-alive.
-   * @param enable True to enable it, false otherwise.
-   * @param time Initial delay in seconds (use
-   * `std::chrono::duration<unsigned int>`).
-   * @return True in case of success, false otherwise.
-   */
-  bool SetKeepAlive(bool enable, Time time = Time{0}) {
-    return uv_tcp_keepalive(GetRaw(), enable,
-                            static_cast<unsigned>(time.count())) == 0;
-  }
-
-  /**
-   * Enable/Disable simultaneous asynchronous accept requests.
-   *
-   * Enable/Disable simultaneous asynchronous accept requests that are
-   * queued by the operating system when listening for new TCP
-   * connections.
-   * This setting is used to tune a TCP server for the desired performance.
-   * Having simultaneous accepts can significantly improve the rate of
-   * accepting connections (which is why it is enabled by default) but may
-   * lead to uneven load distribution in multi-process setups.
-   *
-   * @param enable True to enable it, false otherwise.
-   * @return True in case of success, false otherwise.
-   */
-  bool SetSimultaneousAccepts(bool enable) {
-    return uv_tcp_simultaneous_accepts(GetRaw(), enable) == 0;
-  }
-
-  /**
-   * Bind the handle to an IPv4 or IPv6 address and port.
-   *
-   * A successful call to this function does not guarantee that the call to
-   * `Listen()` or `Connect()` will work properly.
-   * An error signal can be emitted because of either this function or the
-   * ones mentioned above.
-   *
-   * @param addr Initialized `sockaddr_in` or `sockaddr_in6` data structure.
-   * @param flags Optional additional flags.
-   */
-  void Bind(const sockaddr& addr, unsigned int flags = 0) {
-    Invoke(&uv_tcp_bind, GetRaw(), &addr, flags);
-  }
-
-  void Bind(const sockaddr_in& addr, unsigned int flags = 0) {
-    Bind(reinterpret_cast<const sockaddr&>(addr), flags);
-  }
-
-  void Bind(const sockaddr_in6& addr, unsigned int flags = 0) {
-    Bind(reinterpret_cast<const sockaddr&>(addr), flags);
-  }
-
-  /**
-   * Bind the handle to an IPv4 address and port.
-   *
-   * A successful call to this function does not guarantee that the call to
-   * `Listen()` or `Connect()` will work properly.
-   * An error signal can be emitted because of either this function or the
-   * ones mentioned above.
-   *
-   * Available flags are:
-   *
-   * @param ip The address to which to bind.
-   * @param port The port to which to bind.
-   * @param flags Optional additional flags.
-   */
-  void Bind(std::string_view ip, unsigned int port, unsigned int flags = 0);
-
-  /**
-   * Bind the handle to an IPv6 address and port.
-   *
-   * A successful call to this function does not guarantee that the call to
-   * `Listen()` or `Connect()` will work properly.
-   * An error signal can be emitted because of either this function or the
-   * ones mentioned above.
-   *
-   * Available flags are:
-   *
-   * @param ip The address to which to bind.
-   * @param port The port to which to bind.
-   * @param flags Optional additional flags.
-   */
-  void Bind6(std::string_view ip, unsigned int port, unsigned int flags = 0);
-
-  /**
-   * Get the current address to which the handle is bound.
-   * @return The address (will be zeroed if an error occurred).
-   */
-  sockaddr_storage GetSock();
-
-  /**
-   * Get the address of the peer connected to the handle.
-   * @return The address (will be zeroed if an error occurred).
-   */
-  sockaddr_storage GetPeer();
-
-  /**
-   * Establish an IPv4 or IPv6 TCP connection.
-   *
-   * On Windows if the addr is initialized to point to an unspecified address
-   * (`0.0.0.0` or `::`) it will be changed to point to localhost. This is
-   * done to match the behavior of Linux systems.
-   *
-   * The connected signal is emitted on the request when the connection has been
-   * established.
-   * The error signal is emitted on the request in case of errors during the
-   * connection.
-   *
-   * @param addr Initialized `sockaddr_in` or `sockaddr_in6` data structure.
-   * @param req connection request
-   */
-  void Connect(const sockaddr& addr, const std::shared_ptr<TcpConnectReq>& req);
-
-  void Connect(const sockaddr_in& addr,
-               const std::shared_ptr<TcpConnectReq>& req) {
-    Connect(reinterpret_cast<const sockaddr&>(addr), req);
-  }
-
-  void Connect(const sockaddr_in6& addr,
-               const std::shared_ptr<TcpConnectReq>& req) {
-    Connect(reinterpret_cast<const sockaddr&>(addr), req);
-  }
-
-  /**
-   * Establish an IPv4 or IPv6 TCP connection.
-   *
-   * On Windows if the addr is initialized to point to an unspecified address
-   * (`0.0.0.0` or `::`) it will be changed to point to localhost. This is
-   * done to match the behavior of Linux systems.
-   *
-   * The callback is called when the connection has been established.  Errors
-   * are reported to the stream error handler.
-   *
-   * @param addr Initialized `sockaddr_in` or `sockaddr_in6` data structure.
-   * @param callback Callback function to call when connection established
-   */
-  void Connect(const sockaddr& addr, std::function<void()> callback);
-
-  void Connect(const sockaddr_in& addr, std::function<void()> callback) {
-    Connect(reinterpret_cast<const sockaddr&>(addr), std::move(callback));
-  }
-
-  void Connect(const sockaddr_in6& addr, std::function<void()> callback) {
-    Connect(reinterpret_cast<const sockaddr&>(addr), std::move(callback));
-  }
-
-  /**
-   * Establish an IPv4 TCP connection.
-   *
-   * On Windows if the addr is initialized to point to an unspecified address
-   * (`0.0.0.0` or `::`) it will be changed to point to localhost. This is
-   * done to match the behavior of Linux systems.
-   *
-   * The connected signal is emitted on the request when the connection has been
-   * established.
-   * The error signal is emitted on the request in case of errors during the
-   * connection.
-   *
-   * @param ip The address to which to connect to.
-   * @param port The port to which to connect to.
-   * @param req connection request
-   */
-  void Connect(std::string_view ip, unsigned int port,
-               const std::shared_ptr<TcpConnectReq>& req);
-
-  /**
-   * Establish an IPv4 TCP connection.
-   *
-   * On Windows if the addr is initialized to point to an unspecified address
-   * (`0.0.0.0` or `::`) it will be changed to point to localhost. This is
-   * done to match the behavior of Linux systems.
-   *
-   * The callback is called when the connection has been established.  Errors
-   * are reported to the stream error handler.
-   *
-   * @param ip The address to which to connect to.
-   * @param port The port to which to connect to.
-   * @param callback Callback function to call when connection established
-   */
-  void Connect(std::string_view ip, unsigned int port,
-               std::function<void()> callback);
-
-  /**
-   * Establish an IPv6 TCP connection.
-   *
-   * On Windows if the addr is initialized to point to an unspecified address
-   * (`0.0.0.0` or `::`) it will be changed to point to localhost. This is
-   * done to match the behavior of Linux systems.
-   *
-   * The connected signal is emitted on the request when the connection has been
-   * established.
-   * The error signal is emitted on the request in case of errors during the
-   * connection.
-   *
-   * @param ip The address to which to connect to.
-   * @param port The port to which to connect to.
-   * @param req connection request
-   */
-  void Connect6(std::string_view ip, unsigned int port,
-                const std::shared_ptr<TcpConnectReq>& req);
-
-  /**
-   * Establish an IPv6 TCP connection.
-   *
-   * On Windows if the addr is initialized to point to an unspecified address
-   * (`0.0.0.0` or `::`) it will be changed to point to localhost. This is
-   * done to match the behavior of Linux systems.
-   *
-   * The callback is called when the connection has been established.  Errors
-   * are reported to the stream error handler.
-   *
-   * @param ip The address to which to connect to.
-   * @param port The port to which to connect to.
-   * @param callback Callback function to call when connection established
-   */
-  void Connect6(std::string_view ip, unsigned int port,
-                std::function<void()> callback);
-
- private:
-  Tcp* DoAccept() override;
-
-  struct ReuseData {
-    std::function<void()> callback;
-    unsigned int flags;
-  };
-  std::unique_ptr<ReuseData> m_reuseData;
-};
-
-/**
- * TCP connection request.
- */
-class TcpConnectReq : public ConnectReq {
- public:
-  Tcp& GetStream() const {
-    return *static_cast<Tcp*>(&ConnectReq::GetStream());
-  }
-};
-
-}  // namespace wpi::uv
-
-#endif  // WPIUTIL_WPI_UV_TCP_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Timer.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Timer.h
deleted file mode 100644
index 00363a5..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Timer.h
+++ /dev/null
@@ -1,135 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_UV_TIMER_H_
-#define WPIUTIL_WPI_UV_TIMER_H_
-
-#include <uv.h>
-
-#include <chrono>
-#include <functional>
-#include <memory>
-#include <utility>
-
-#include "wpi/Signal.h"
-#include "wpi/uv/Handle.h"
-
-namespace wpi::uv {
-
-class Loop;
-
-/**
- * Timer handle.
- * Timer handles are used to schedule signals to be called in the future.
- */
-class Timer final : public HandleImpl<Timer, uv_timer_t> {
-  struct private_init {};
-
- public:
-  using Time = std::chrono::duration<uint64_t, std::milli>;
-
-  explicit Timer(const private_init&) {}
-  ~Timer() noexcept override = default;
-
-  /**
-   * Create a timer handle.
-   *
-   * @param loop Loop object where this handle runs.
-   */
-  static std::shared_ptr<Timer> Create(Loop& loop);
-
-  /**
-   * Create a timer handle.
-   *
-   * @param loop Loop object where this handle runs.
-   */
-  static std::shared_ptr<Timer> Create(const std::shared_ptr<Loop>& loop) {
-    return Create(*loop);
-  }
-
-  /**
-   * Create a timer that calls a functor after a given time interval.
-   *
-   * @param loop Loop object where the timer should run.
-   * @param timeout Time interval
-   * @param func Functor
-   */
-  static void SingleShot(Loop& loop, Time timeout, std::function<void()> func);
-
-  /**
-   * Create a timer that calls a functor after a given time interval.
-   *
-   * @param loop Loop object where the timer should run.
-   * @param timeout Time interval
-   * @param func Functor
-   */
-  static void SingleShot(const std::shared_ptr<Loop>& loop, Time timeout,
-                         std::function<void()> func) {
-    return SingleShot(*loop, timeout, std::move(func));
-  }
-
-  /**
-   * Start the timer.
-   *
-   * If timeout is zero, an event is emitted on the next event loop
-   * iteration. If repeat is non-zero, an event is emitted first
-   * after timeout milliseconds and then repeatedly after repeat milliseconds.
-   *
-   * @param timeout Milliseconds before to emit an event (use
-   * `std::chrono::duration<uint64_t, std::milli>`).
-   * @param repeat Milliseconds between successive events (use
-   * `std::chrono::duration<uint64_t, std::milli>`).
-   */
-  void Start(Time timeout, Time repeat = Time{0});
-
-  /**
-   * Stop the timer.
-   */
-  void Stop() { Invoke(&uv_timer_stop, GetRaw()); }
-
-  /**
-   * Stop the timer and restart it if it was repeating.
-   *
-   * Stop the timer, and if it is repeating restart it using the repeat value
-   * as the timeout.
-   * If the timer has never been started before it emits sigError.
-   */
-  void Again() { Invoke(&uv_timer_again, GetRaw()); }
-
-  /**
-   * Set the repeat interval value.
-   *
-   * The timer will be scheduled to run on the given interval and will follow
-   * normal timer semantics in the case of a time-slice overrun.
-   * For example, if a 50ms repeating timer first runs for 17ms, it will be
-   * scheduled to run again 33ms later. If other tasks consume more than the
-   * 33ms following the first timer event, then another event will be emitted
-   * as soon as possible.
-   *
-   * If the repeat value is set from a listener bound to an event, it does
-   * not immediately take effect. If the timer was non-repeating before, it
-   * will have been stopped. If it was repeating, then the old repeat value
-   * will have been used to schedule the next timeout.
-   *
-   * @param repeat Repeat interval in milliseconds (use
-   * `std::chrono::duration<uint64_t, std::milli>`).
-   */
-  void SetRepeat(Time repeat) { uv_timer_set_repeat(GetRaw(), repeat.count()); }
-
-  /**
-   * Get the timer repeat value.
-   * @return Timer repeat value in milliseconds (as a
-   * `std::chrono::duration<uint64_t, std::milli>`).
-   */
-  Time GetRepeat() const { return Time{uv_timer_get_repeat(GetRaw())}; }
-
-  /**
-   * Signal generated when the timeout event occurs.
-   */
-  sig::Signal<> timeout;
-};
-
-}  // namespace wpi::uv
-
-#endif  // WPIUTIL_WPI_UV_TIMER_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Tty.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Tty.h
deleted file mode 100644
index bb0a6db..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Tty.h
+++ /dev/null
@@ -1,85 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_UV_TTY_H_
-#define WPIUTIL_WPI_UV_TTY_H_
-
-#include <uv.h>
-
-#include <memory>
-#include <utility>
-
-#include "wpi/uv/Stream.h"
-
-namespace wpi::uv {
-
-class Loop;
-class Tty;
-
-/**
- * TTY handle.
- * TTY handles represent a stream for the console.
- */
-class Tty final : public StreamImpl<Tty, uv_tty_t> {
-  struct private_init {};
-
- public:
-  explicit Tty(const private_init&) {}
-  ~Tty() noexcept override = default;
-
-  /**
-   * Create a TTY handle.
-   *
-   * @param loop Loop object where this handle runs.
-   * @param fd File descriptor, usually 0=stdin, 1=stdout, 2=stderr
-   * @param readable Specifies if you plan on calling StartRead().  stdin is
-   *                 readable, stdout is not.
-   */
-  static std::shared_ptr<Tty> Create(Loop& loop, uv_file fd, bool readable);
-
-  /**
-   * Create a TTY handle.
-   *
-   * @param loop Loop object where this handle runs.
-   * @param fd File descriptor, usually 0=stdin, 1=stdout, 2=stderr
-   * @param readable Specifies if you plan on calling StartRead().  stdin is
-   *                 readable, stdout is not.
-   */
-  static std::shared_ptr<Tty> Create(const std::shared_ptr<Loop>& loop,
-                                     uv_file fd, bool readable) {
-    return Create(*loop, fd, readable);
-  }
-
-  /**
-   * Set the TTY using the specified terminal mode.
-   *
-   * @param mode terminal mode
-   */
-  void SetMode(uv_tty_mode_t mode) {
-    int err = uv_tty_set_mode(GetRaw(), mode);
-    if (err < 0) {
-      ReportError(err);
-    }
-  }
-
-  /**
-   * Reset TTY settings to default values for the next process to take over.
-   * Typically called when the program exits.
-   */
-  void ResetMode() { Invoke(&uv_tty_reset_mode); }
-
-  /**
-   * Gets the current window size.
-   * @return Window size (pair of width and height).
-   */
-  std::pair<int, int> GetWindowSize() {
-    int width = 0, height = 0;
-    Invoke(&uv_tty_get_winsize, GetRaw(), &width, &height);
-    return std::make_pair(width, height);
-  }
-};
-
-}  // namespace wpi::uv
-
-#endif  // WPIUTIL_WPI_UV_TTY_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Udp.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Udp.h
deleted file mode 100644
index 71fab13..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Udp.h
+++ /dev/null
@@ -1,378 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_UV_UDP_H_
-#define WPIUTIL_WPI_UV_UDP_H_
-
-#include <uv.h>
-
-#include <functional>
-#include <memory>
-#include <string_view>
-#include <utility>
-
-#include "wpi/Signal.h"
-#include "wpi/span.h"
-#include "wpi/uv/Handle.h"
-#include "wpi/uv/Request.h"
-
-namespace wpi::uv {
-
-class Loop;
-class Udp;
-
-/**
- * UDP send request.
- */
-class UdpSendReq : public RequestImpl<UdpSendReq, uv_udp_send_t> {
- public:
-  UdpSendReq();
-
-  Udp& GetUdp() const { return *static_cast<Udp*>(GetRaw()->handle->data); }
-
-  /**
-   * Send completed signal.  This is called even if an error occurred.
-   * @param err error value
-   */
-  sig::Signal<Error> complete;
-};
-
-/**
- * UDP handle.
- * UDP handles encapsulate UDP communication for both clients and servers.
- */
-class Udp final : public HandleImpl<Udp, uv_udp_t> {
-  struct private_init {};
-
- public:
-  explicit Udp(const private_init&) {}
-  ~Udp() noexcept override = default;
-
-  /**
-   * Create a UDP handle.
-   *
-   * @param loop Loop object where this handle runs.
-   * @param flags Flags
-   */
-  static std::shared_ptr<Udp> Create(Loop& loop,
-                                     unsigned int flags = AF_UNSPEC);
-
-  /**
-   * Create a UDP handle.
-   *
-   * @param loop Loop object where this handle runs.
-   * @param flags Flags
-   */
-  static std::shared_ptr<Udp> Create(const std::shared_ptr<Loop>& loop,
-                                     unsigned int flags = AF_UNSPEC) {
-    return Create(*loop, flags);
-  }
-
-  /**
-   * Open an existing file descriptor or SOCKET as a UDP handle.
-   *
-   * @param sock A valid socket handle (either a file descriptor or a SOCKET).
-   */
-  void Open(uv_os_sock_t sock) { Invoke(&uv_udp_open, GetRaw(), sock); }
-
-  /**
-   * Bind the handle to an IPv4 or IPv6 address and port.
-   *
-   * @param addr Initialized `sockaddr_in` or `sockaddr_in6` data structure.
-   * @param flags Optional additional flags.
-   */
-  void Bind(const sockaddr& addr, unsigned int flags = 0) {
-    Invoke(&uv_udp_bind, GetRaw(), &addr, flags);
-  }
-
-  void Bind(const sockaddr_in& addr, unsigned int flags = 0) {
-    Bind(reinterpret_cast<const sockaddr&>(addr), flags);
-  }
-
-  void Bind(const sockaddr_in6& addr, unsigned int flags = 0) {
-    Bind(reinterpret_cast<const sockaddr&>(addr), flags);
-  }
-
-  /**
-   * Bind the handle to an IPv4 address and port.
-   *
-   * @param ip The address to which to bind.
-   * @param port The port to which to bind.
-   * @param flags Optional additional flags.
-   */
-  void Bind(std::string_view ip, unsigned int port, unsigned int flags = 0);
-
-  /**
-   * Bind the handle to an IPv6 address and port.
-   *
-   * @param ip The address to which to bind.
-   * @param port The port to which to bind.
-   * @param flags Optional additional flags.
-   */
-  void Bind6(std::string_view ip, unsigned int port, unsigned int flags = 0);
-
-  /**
-   * Associate the handle to a remote address and port, so every message sent
-   * by this handle is automatically sent to that destination.
-   *
-   * @param addr Initialized `sockaddr_in` or `sockaddr_in6` data structure.
-   */
-  void Connect(const sockaddr& addr) {
-    Invoke(&uv_udp_connect, GetRaw(), &addr);
-  }
-
-  void Connect(const sockaddr_in& addr) {
-    Connect(reinterpret_cast<const sockaddr&>(addr));
-  }
-
-  void Connect(const sockaddr_in6& addr) {
-    Connect(reinterpret_cast<const sockaddr&>(addr));
-  }
-
-  /**
-   * Associate the handle to an IPv4 address and port, so every message sent
-   * by this handle is automatically sent to that destination.
-   *
-   * @param ip The address to which to bind.
-   * @param port The port to which to bind.
-   */
-  void Connect(std::string_view ip, unsigned int port);
-
-  /**
-   * Associate the handle to an IPv6 address and port, so every message sent
-   * by this handle is automatically sent to that destination.
-   *
-   * @param ip The address to which to bind.
-   * @param port The port to which to bind.
-   * @param flags Optional additional flags.
-   */
-  void Connect6(std::string_view ip, unsigned int port);
-
-  /**
-   * Get the remote IP and port on connected UDP handles.
-   * @return The address (will be zeroed if an error occurred).
-   */
-  sockaddr_storage GetPeer();
-
-  /**
-   * Get the current address to which the handle is bound.
-   * @return The address (will be zeroed if an error occurred).
-   */
-  sockaddr_storage GetSock();
-
-  /**
-   * Set membership for a multicast address.
-   *
-   * @param multicastAddr Multicast address to set membership for
-   * @param interfaceAddr Interface address
-   * @param membership Should be UV_JOIN_GROUP or UV_LEAVE_GROUP
-   */
-  void SetMembership(std::string_view multicastAddr,
-                     std::string_view interfaceAddr, uv_membership membership);
-
-  /**
-   * Set IP multicast loop flag.  Makes multicast packets loop back to local
-   * sockets.
-   *
-   * @param enabled True for enabled, false for disabled
-   */
-  void SetMulticastLoop(bool enabled) {
-    Invoke(&uv_udp_set_multicast_loop, GetRaw(), enabled ? 1 : 0);
-  }
-
-  /**
-   * Set the multicast TTL.
-   *
-   * @param ttl Time to live (1-255)
-   */
-  void SetMulticastTtl(int ttl) {
-    Invoke(&uv_udp_set_multicast_ttl, GetRaw(), ttl);
-  }
-
-  /**
-   * Set the multicast interface to send or receive data on.
-   *
-   * @param interfaceAddr Interface address
-   */
-  void SetMulticastInterface(std::string_view interfaceAddr);
-
-  /**
-   * Set broadcast on or off.
-   *
-   * @param enabled True for enabled, false for disabled
-   */
-  void SetBroadcast(bool enabled) {
-    Invoke(&uv_udp_set_broadcast, GetRaw(), enabled ? 1 : 0);
-  }
-
-  /**
-   * Set the time to live (TTL).
-   *
-   * @param ttl Time to live (1-255)
-   */
-  void SetTtl(int ttl) { Invoke(&uv_udp_set_ttl, GetRaw(), ttl); }
-
-  /**
-   * Send data over the UDP socket.  If the socket has not previously been bound
-   * with Bind() it will be bound to 0.0.0.0 (the "all interfaces" IPv4 address)
-   * and a random port number.
-   *
-   * Data are written in order. The lifetime of the data pointers passed in
-   * the `bufs` parameter must exceed the lifetime of the send request.
-   * The callback can be used to free data after the request completes.
-   *
-   * HandleSendComplete() will be called on the request object when the data
-   * has been written.  HandleSendComplete() is called even if an error occurs.
-   * HandleError() will be called on the request object in case of errors.
-   *
-   * @param addr sockaddr_in or sockaddr_in6 with the address and port of the
-   *             remote peer.
-   * @param bufs The buffers to be written to the stream.
-   * @param req write request
-   */
-  void Send(const sockaddr& addr, span<const Buffer> bufs,
-            const std::shared_ptr<UdpSendReq>& req);
-
-  void Send(const sockaddr_in& addr, span<const Buffer> bufs,
-            const std::shared_ptr<UdpSendReq>& req) {
-    Send(reinterpret_cast<const sockaddr&>(addr), bufs, req);
-  }
-
-  void Send(const sockaddr_in6& addr, span<const Buffer> bufs,
-            const std::shared_ptr<UdpSendReq>& req) {
-    Send(reinterpret_cast<const sockaddr&>(addr), bufs, req);
-  }
-
-  /**
-   * Variant of Send() for connected sockets.  Cannot be used with
-   * connectionless sockets.
-   *
-   * @param bufs The buffers to be written to the stream.
-   * @param req write request
-   */
-  void Send(span<const Buffer> bufs, const std::shared_ptr<UdpSendReq>& req);
-
-  /**
-   * Send data over the UDP socket.  If the socket has not previously been bound
-   * with Bind() it will be bound to 0.0.0.0 (the "all interfaces" IPv4 address)
-   * and a random port number.
-   *
-   * Data are written in order. The lifetime of the data pointers passed in
-   * the `bufs` parameter must exceed the lifetime of the send request.
-   * The callback can be used to free data after the request completes.
-   *
-   * The callback will be called when the data has been sent.  Errors will
-   * be reported via the error signal.
-   *
-   * @param addr sockaddr_in or sockaddr_in6 with the address and port of the
-   *             remote peer.
-   * @param bufs The buffers to be sent.
-   * @param callback Callback function to call when the data has been sent.
-   */
-  void Send(const sockaddr& addr, span<const Buffer> bufs,
-            std::function<void(span<Buffer>, Error)> callback);
-
-  void Send(const sockaddr_in& addr, span<const Buffer> bufs,
-            std::function<void(span<Buffer>, Error)> callback) {
-    Send(reinterpret_cast<const sockaddr&>(addr), bufs, std::move(callback));
-  }
-
-  void Send(const sockaddr_in6& addr, span<const Buffer> bufs,
-            std::function<void(span<Buffer>, Error)> callback) {
-    Send(reinterpret_cast<const sockaddr&>(addr), bufs, std::move(callback));
-  }
-
-  /**
-   * Variant of Send() for connected sockets.  Cannot be used with
-   * connectionless sockets.
-   *
-   * @param bufs The buffers to be written to the stream.
-   * @param callback Callback function to call when the data has been sent.
-   */
-  void Send(span<const Buffer> bufs,
-            std::function<void(span<Buffer>, Error)> callback);
-
-  /**
-   * Same as Send(), but won't queue a send request if it can't be completed
-   * immediately.
-   *
-   * @param addr sockaddr_in or sockaddr_in6 with the address and port of the
-   *             remote peer.
-   * @param bufs The buffers to be send.
-   * @return Number of bytes sent.
-   */
-  int TrySend(const sockaddr& addr, span<const Buffer> bufs) {
-    int val = uv_udp_try_send(GetRaw(), bufs.data(),
-                              static_cast<unsigned>(bufs.size()), &addr);
-    if (val < 0) {
-      this->ReportError(val);
-      return 0;
-    }
-    return val;
-  }
-
-  int TrySend(const sockaddr_in& addr, span<const Buffer> bufs) {
-    return TrySend(reinterpret_cast<const sockaddr&>(addr), bufs);
-  }
-
-  int TrySend(const sockaddr_in6& addr, span<const Buffer> bufs) {
-    return TrySend(reinterpret_cast<const sockaddr&>(addr), bufs);
-  }
-
-  /**
-   * Variant of TrySend() for connected sockets.  Cannot be used with
-   * connectionless sockets.
-   *
-   * @param bufs The buffers to be written to the stream.
-   * @return Number of bytes sent.
-   */
-  int TrySend(span<const Buffer> bufs) {
-    int val = uv_udp_try_send(GetRaw(), bufs.data(),
-                              static_cast<unsigned>(bufs.size()), nullptr);
-    if (val < 0) {
-      this->ReportError(val);
-      return 0;
-    }
-    return val;
-  }
-
-  /**
-   * Prepare for receiving data.  If the socket has not previously been bound
-   * with Bind() it is bound to 0.0.0.0 (the "all interfaces" IPv4 address) and
-   * a random port number.
-   *
-   * A received signal will be emitted for each received data packet until
-   * `StopRecv()` is called.
-   */
-  void StartRecv();
-
-  /**
-   * Stop listening for incoming datagrams.
-   */
-  void StopRecv() { Invoke(&uv_udp_recv_stop, GetRaw()); }
-
-  /**
-   * Gets the amount of queued bytes waiting to be sent.
-   * @return Amount of queued bytes waiting to be sent.
-   */
-  size_t GetSendQueueSize() const noexcept { return GetRaw()->send_queue_size; }
-
-  /**
-   * Gets the amount of queued packets waiting to be sent.
-   * @return Amount of queued packets waiting to be sent.
-   */
-  size_t GetSendQueueCount() const noexcept {
-    return GetRaw()->send_queue_count;
-  }
-
-  /**
-   * Signal generated for each incoming datagram.  Parameters are the buffer,
-   * the number of bytes received, the address of the sender, and flags.
-   */
-  sig::Signal<Buffer&, size_t, const sockaddr&, unsigned> received;
-};
-
-}  // namespace wpi::uv
-
-#endif  // WPIUTIL_WPI_UV_UDP_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Work.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Work.h
deleted file mode 100644
index 5a3a5d2..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/Work.h
+++ /dev/null
@@ -1,93 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_UV_WORK_H_
-#define WPIUTIL_WPI_UV_WORK_H_
-
-#include <uv.h>
-
-#include <functional>
-#include <memory>
-#include <utility>
-
-#include "wpi/Signal.h"
-#include "wpi/uv/Request.h"
-
-namespace wpi::uv {
-
-class Loop;
-
-/**
- * Work request.
- * For use with `QueueWork()` function family.
- */
-class WorkReq : public RequestImpl<WorkReq, uv_work_t> {
- public:
-  WorkReq();
-
-  Loop& GetLoop() const { return *static_cast<Loop*>(GetRaw()->loop->data); }
-
-  /**
-   * Function(s) that will be run on the thread pool.
-   */
-  sig::Signal<> work;
-
-  /**
-   * Function(s) that will be run on the loop thread after the work on the
-   * thread pool has been completed by the work callback.
-   */
-  sig::Signal<> afterWork;
-};
-
-/**
- * Initializes a work request which will run on the thread pool.
- *
- * @param loop Event loop
- * @param req request
- */
-void QueueWork(Loop& loop, const std::shared_ptr<WorkReq>& req);
-
-/**
- * Initializes a work request which will run on the thread pool.
- *
- * @param loop Event loop
- * @param req request
- */
-inline void QueueWork(const std::shared_ptr<Loop>& loop,
-                      const std::shared_ptr<WorkReq>& req) {
-  QueueWork(*loop, req);
-}
-
-/**
- * Initializes a work request which will run on the thread pool.  The work
- * callback will be run on a thread from the thread pool, and the afterWork
- * callback will be called on the loop thread after the work completes.  Any
- * errors are forwarded to the loop.
- *
- * @param loop Event loop
- * @param work Work callback (called from separate thread)
- * @param afterWork After work callback (called on loop thread)
- */
-void QueueWork(Loop& loop, std::function<void()> work,
-               std::function<void()> afterWork);
-
-/**
- * Initializes a work request which will run on the thread pool.  The work
- * callback will be run on a thread from the thread pool, and the afterWork
- * callback will be called on the loop thread after the work completes.  Any
- * errors are forwarded to the loop.
- *
- * @param loop Event loop
- * @param work Work callback (called from separate thread)
- * @param afterWork After work callback (called on loop thread)
- */
-inline void QueueWork(const std::shared_ptr<Loop>& loop,
-                      std::function<void()> work,
-                      std::function<void()> afterWork) {
-  QueueWork(*loop, std::move(work), std::move(afterWork));
-}
-
-}  // namespace wpi::uv
-
-#endif  // WPIUTIL_WPI_UV_WORK_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/util.h b/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/util.h
deleted file mode 100644
index 01dec0b..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/uv/util.h
+++ /dev/null
@@ -1,147 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef WPIUTIL_WPI_UV_UTIL_H_
-#define WPIUTIL_WPI_UV_UTIL_H_
-
-#include <uv.h>
-
-#include <cstring>
-#include <string_view>
-
-namespace wpi::uv {
-
-/**
- * Convert a binary structure containing an IPv4 address to a string.
- * @param addr Binary structure
- * @param ip Output string (any type that has `assign(char*, char*)`)
- * @param port Output port number
- * @return Error (same as `uv_ip4_name()`).
- */
-template <typename T>
-int AddrToName(const sockaddr_in& addr, T* ip, unsigned int* port) {
-  char name[128];
-  int err = uv_ip4_name(&addr, name, 128);
-  if (err == 0) {
-    ip->assign(name, name + std::strlen(name));
-    *port = ntohs(addr.sin_port);
-  } else {
-    ip->assign(name, name);
-  }
-  return err;
-}
-
-/**
- * Convert a binary structure containing an IPv6 address to a string.
- * @param addr Binary structure
- * @param ip Output string (any type that has `assign(char*, char*)`)
- * @param port Output port number
- * @return Error (same as `uv_ip6_name()`).
- */
-template <typename T>
-int AddrToName(const sockaddr_in6& addr, T* ip, unsigned int* port) {
-  char name[128];
-  int err = uv_ip6_name(&addr, name, 128);
-  if (err == 0) {
-    ip->assign(name, name + std::strlen(name));
-    *port = ntohs(addr.sin6_port);
-  } else {
-    ip->assign(name, name);
-  }
-  return err;
-}
-
-/**
- * Convert a binary structure containing an IPv4 or IPv6 address to a string.
- * @param addr Binary structure
- * @param ip Output string (any type that has `assign(char*, char*)`)
- * @param port Output port number
- * @return Error (same as `uv_ip6_name()`).
- */
-template <typename T>
-int AddrToName(const sockaddr_storage& addr, T* ip, unsigned int* port) {
-  if (addr.ss_family == AF_INET) {
-    return AddrToName(reinterpret_cast<const sockaddr_in&>(addr), ip, port);
-  }
-  if (addr.ss_family == AF_INET6) {
-    return AddrToName(reinterpret_cast<const sockaddr_in6&>(addr), ip, port);
-  }
-  char name[1];
-  ip->assign(name, name);
-  return -1;
-}
-
-/**
- * Convert a binary IPv4 address to a string.
- * @param addr Binary address
- * @param ip Output string (any type that has `assign(char*, char*)`)
- * @return Error (same as `uv_inet_ntop()`).
- */
-template <typename T>
-int AddrToName(const in_addr& addr, T* ip) {
-  char name[128];
-  int err = uv_inet_ntop(AF_INET, &addr, name, 128);
-  if (err == 0) {
-    ip->assign(name, name + std::strlen(name));
-  } else {
-    ip->assign(name, name);
-  }
-  return err;
-}
-
-/**
- * Convert a binary IPv6 address to a string.
- * @param addr Binary address
- * @param ip Output string (any type that has `assign(char*, char*)`)
- * @return Error (same as `uv_inet_ntop()`).
- */
-template <typename T>
-int AddrToName(const in6_addr& addr, T* ip) {
-  char name[128];
-  int err = uv_inet_ntop(AF_INET6, &addr, name, 128);
-  if (err == 0) {
-    ip->assign(name, name + std::strlen(name));
-  } else {
-    ip->assign(name, name);
-  }
-  return err;
-}
-
-/**
- * Convert a string containing an IPv4 address to a binary structure.
- * @param ip IPv4 address string
- * @param port Port number
- * @param addr Output binary structure
- * @return Error (same as `uv_ip4_addr()`).
- */
-int NameToAddr(std::string_view ip, unsigned int port, sockaddr_in* addr);
-
-/**
- * Convert a string containing an IPv6 address to a binary structure.
- * @param ip IPv6 address string
- * @param port Port number
- * @param addr Output binary structure
- * @return Error (same as `uv_ip6_addr()`).
- */
-int NameToAddr(std::string_view ip, unsigned int port, sockaddr_in6* addr);
-
-/**
- * Convert a string containing an IPv4 address to binary format.
- * @param ip IPv4 address string
- * @param addr Output binary
- * @return Error (same as `uv_inet_pton()`).
- */
-int NameToAddr(std::string_view ip, in_addr* addr);
-
-/**
- * Convert a string containing an IPv6 address to binary format.
- * @param ip IPv6 address string
- * @param addr Output binary
- * @return Error (same as `uv_inet_pton()`).
- */
-int NameToAddr(std::string_view ip, in6_addr* addr);
-
-}  // namespace wpi::uv
-
-#endif  // WPIUTIL_WPI_UV_UTIL_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/include/uv.h b/third_party/allwpilib/wpiutil/src/main/native/libuv/include/uv.h
deleted file mode 100644
index ccf62c8..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/include/uv.h
+++ /dev/null
@@ -1,1683 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-/* See https://github.com/libuv/libuv#documentation for documentation. */
-
-#ifndef UV_H
-#define UV_H
-
-#ifdef _WIN32
-  /* Windows - set up dll import/export decorators. */
-# if defined(BUILDING_UV_SHARED)
-    /* Building shared library. */
-#   define UV_EXTERN __declspec(dllexport)
-# elif defined(USING_UV_SHARED)
-    /* Using shared library. */
-#   define UV_EXTERN __declspec(dllimport)
-# else
-    /* Building static library. */
-#   define UV_EXTERN /* nothing */
-# endif
-#elif __GNUC__ >= 4
-# define UV_EXTERN __attribute__((visibility("default")))
-#else
-# define UV_EXTERN /* nothing */
-#endif
-
-#include "uv/errno.h"
-#include "uv/version.h"
-#include <stddef.h>
-#include <stdio.h>
-
-#include <stdint.h>
-
-#if defined(_WIN32)
-# include "uv/win.h"
-#else
-# include "uv/unix.h"
-#endif
-
-/* Expand this list if necessary. */
-#define UV_ERRNO_MAP(XX)                                                      \
-  XX(E2BIG, "argument list too long")                                         \
-  XX(EACCES, "permission denied")                                             \
-  XX(EADDRINUSE, "address already in use")                                    \
-  XX(EADDRNOTAVAIL, "address not available")                                  \
-  XX(EAFNOSUPPORT, "address family not supported")                            \
-  XX(EAGAIN, "resource temporarily unavailable")                              \
-  XX(EAI_ADDRFAMILY, "address family not supported")                          \
-  XX(EAI_AGAIN, "temporary failure")                                          \
-  XX(EAI_BADFLAGS, "bad ai_flags value")                                      \
-  XX(EAI_BADHINTS, "invalid value for hints")                                 \
-  XX(EAI_CANCELED, "request canceled")                                        \
-  XX(EAI_FAIL, "permanent failure")                                           \
-  XX(EAI_FAMILY, "ai_family not supported")                                   \
-  XX(EAI_MEMORY, "out of memory")                                             \
-  XX(EAI_NODATA, "no address")                                                \
-  XX(EAI_NONAME, "unknown node or service")                                   \
-  XX(EAI_OVERFLOW, "argument buffer overflow")                                \
-  XX(EAI_PROTOCOL, "resolved protocol is unknown")                            \
-  XX(EAI_SERVICE, "service not available for socket type")                    \
-  XX(EAI_SOCKTYPE, "socket type not supported")                               \
-  XX(EALREADY, "connection already in progress")                              \
-  XX(EBADF, "bad file descriptor")                                            \
-  XX(EBUSY, "resource busy or locked")                                        \
-  XX(ECANCELED, "operation canceled")                                         \
-  XX(ECHARSET, "invalid Unicode character")                                   \
-  XX(ECONNABORTED, "software caused connection abort")                        \
-  XX(ECONNREFUSED, "connection refused")                                      \
-  XX(ECONNRESET, "connection reset by peer")                                  \
-  XX(EDESTADDRREQ, "destination address required")                            \
-  XX(EEXIST, "file already exists")                                           \
-  XX(EFAULT, "bad address in system call argument")                           \
-  XX(EFBIG, "file too large")                                                 \
-  XX(EHOSTUNREACH, "host is unreachable")                                     \
-  XX(EINTR, "interrupted system call")                                        \
-  XX(EINVAL, "invalid argument")                                              \
-  XX(EIO, "i/o error")                                                        \
-  XX(EISCONN, "socket is already connected")                                  \
-  XX(EISDIR, "illegal operation on a directory")                              \
-  XX(ELOOP, "too many symbolic links encountered")                            \
-  XX(EMFILE, "too many open files")                                           \
-  XX(EMSGSIZE, "message too long")                                            \
-  XX(ENAMETOOLONG, "name too long")                                           \
-  XX(ENETDOWN, "network is down")                                             \
-  XX(ENETUNREACH, "network is unreachable")                                   \
-  XX(ENFILE, "file table overflow")                                           \
-  XX(ENOBUFS, "no buffer space available")                                    \
-  XX(ENODEV, "no such device")                                                \
-  XX(ENOENT, "no such file or directory")                                     \
-  XX(ENOMEM, "not enough memory")                                             \
-  XX(ENONET, "machine is not on the network")                                 \
-  XX(ENOPROTOOPT, "protocol not available")                                   \
-  XX(ENOSPC, "no space left on device")                                       \
-  XX(ENOSYS, "function not implemented")                                      \
-  XX(ENOTCONN, "socket is not connected")                                     \
-  XX(ENOTDIR, "not a directory")                                              \
-  XX(ENOTEMPTY, "directory not empty")                                        \
-  XX(ENOTSOCK, "socket operation on non-socket")                              \
-  XX(ENOTSUP, "operation not supported on socket")                            \
-  XX(EPERM, "operation not permitted")                                        \
-  XX(EPIPE, "broken pipe")                                                    \
-  XX(EPROTO, "protocol error")                                                \
-  XX(EPROTONOSUPPORT, "protocol not supported")                               \
-  XX(EPROTOTYPE, "protocol wrong type for socket")                            \
-  XX(ERANGE, "result too large")                                              \
-  XX(EROFS, "read-only file system")                                          \
-  XX(ESHUTDOWN, "cannot send after transport endpoint shutdown")              \
-  XX(ESPIPE, "invalid seek")                                                  \
-  XX(ESRCH, "no such process")                                                \
-  XX(ETIMEDOUT, "connection timed out")                                       \
-  XX(ETXTBSY, "text file is busy")                                            \
-  XX(EXDEV, "cross-device link not permitted")                                \
-  XX(UNKNOWN, "unknown error")                                                \
-  XX(EOF, "end of file")                                                      \
-  XX(ENXIO, "no such device or address")                                      \
-  XX(EMLINK, "too many links")                                                \
-  XX(EHOSTDOWN, "host is down")                                               \
-  XX(EREMOTEIO, "remote I/O error")                                           \
-  XX(ENOTTY, "inappropriate ioctl for device")                                \
-  XX(EFTYPE, "inappropriate file type or format")                             \
-
-#define UV_HANDLE_TYPE_MAP(XX)                                                \
-  XX(ASYNC, async)                                                            \
-  XX(CHECK, check)                                                            \
-  XX(FS_EVENT, fs_event)                                                      \
-  XX(FS_POLL, fs_poll)                                                        \
-  XX(HANDLE, handle)                                                          \
-  XX(IDLE, idle)                                                              \
-  XX(NAMED_PIPE, pipe)                                                        \
-  XX(POLL, poll)                                                              \
-  XX(PREPARE, prepare)                                                        \
-  XX(PROCESS, process)                                                        \
-  XX(STREAM, stream)                                                          \
-  XX(TCP, tcp)                                                                \
-  XX(TIMER, timer)                                                            \
-  XX(TTY, tty)                                                                \
-  XX(UDP, udp)                                                                \
-  XX(SIGNAL, signal)                                                          \
-
-#define UV_REQ_TYPE_MAP(XX)                                                   \
-  XX(REQ, req)                                                                \
-  XX(CONNECT, connect)                                                        \
-  XX(WRITE, write)                                                            \
-  XX(SHUTDOWN, shutdown)                                                      \
-  XX(UDP_SEND, udp_send)                                                      \
-  XX(FS, fs)                                                                  \
-  XX(WORK, work)                                                              \
-  XX(GETADDRINFO, getaddrinfo)                                                \
-  XX(GETNAMEINFO, getnameinfo)                                                \
-
-typedef enum {
-#define XX(code, _) UV_ ## code = UV__ ## code,
-  UV_ERRNO_MAP(XX)
-#undef XX
-  UV_ERRNO_MAX = UV__EOF - 1
-} uv_errno_t;
-
-typedef enum {
-  UV_UNKNOWN_HANDLE = 0,
-#define XX(uc, lc) UV_##uc,
-  UV_HANDLE_TYPE_MAP(XX)
-#undef XX
-  UV_FILE,
-  UV_HANDLE_TYPE_MAX
-} uv_handle_type;
-
-typedef enum {
-  UV_UNKNOWN_REQ = 0,
-#define XX(uc, lc) UV_##uc,
-  UV_REQ_TYPE_MAP(XX)
-#undef XX
-  UV_REQ_TYPE_PRIVATE
-  UV_REQ_TYPE_MAX
-} uv_req_type;
-
-
-/* Handle types. */
-typedef struct uv_loop_s uv_loop_t;
-typedef struct uv_handle_s uv_handle_t;
-typedef struct uv_dir_s uv_dir_t;
-typedef struct uv_stream_s uv_stream_t;
-typedef struct uv_tcp_s uv_tcp_t;
-typedef struct uv_udp_s uv_udp_t;
-typedef struct uv_pipe_s uv_pipe_t;
-typedef struct uv_tty_s uv_tty_t;
-typedef struct uv_poll_s uv_poll_t;
-typedef struct uv_timer_s uv_timer_t;
-typedef struct uv_prepare_s uv_prepare_t;
-typedef struct uv_check_s uv_check_t;
-typedef struct uv_idle_s uv_idle_t;
-typedef struct uv_async_s uv_async_t;
-typedef struct uv_process_s uv_process_t;
-typedef struct uv_fs_event_s uv_fs_event_t;
-typedef struct uv_fs_poll_s uv_fs_poll_t;
-typedef struct uv_signal_s uv_signal_t;
-
-/* Request types. */
-typedef struct uv_req_s uv_req_t;
-typedef struct uv_getaddrinfo_s uv_getaddrinfo_t;
-typedef struct uv_getnameinfo_s uv_getnameinfo_t;
-typedef struct uv_shutdown_s uv_shutdown_t;
-typedef struct uv_write_s uv_write_t;
-typedef struct uv_connect_s uv_connect_t;
-typedef struct uv_udp_send_s uv_udp_send_t;
-typedef struct uv_fs_s uv_fs_t;
-typedef struct uv_work_s uv_work_t;
-
-/* None of the above. */
-typedef struct uv_cpu_info_s uv_cpu_info_t;
-typedef struct uv_interface_address_s uv_interface_address_t;
-typedef struct uv_dirent_s uv_dirent_t;
-typedef struct uv_passwd_s uv_passwd_t;
-typedef struct uv_utsname_s uv_utsname_t;
-
-typedef enum {
-  UV_LOOP_BLOCK_SIGNAL
-} uv_loop_option;
-
-typedef enum {
-  UV_RUN_DEFAULT = 0,
-  UV_RUN_ONCE,
-  UV_RUN_NOWAIT
-} uv_run_mode;
-
-
-UV_EXTERN unsigned int uv_version(void);
-UV_EXTERN const char* uv_version_string(void);
-
-typedef void* (*uv_malloc_func)(size_t size);
-typedef void* (*uv_realloc_func)(void* ptr, size_t size);
-typedef void* (*uv_calloc_func)(size_t count, size_t size);
-typedef void (*uv_free_func)(void* ptr);
-
-UV_EXTERN int uv_replace_allocator(uv_malloc_func malloc_func,
-                                   uv_realloc_func realloc_func,
-                                   uv_calloc_func calloc_func,
-                                   uv_free_func free_func);
-
-UV_EXTERN uv_loop_t* uv_default_loop(void);
-UV_EXTERN int uv_loop_init(uv_loop_t* loop);
-UV_EXTERN int uv_loop_close(uv_loop_t* loop);
-/*
- * NOTE:
- *  This function is DEPRECATED (to be removed after 0.12), users should
- *  allocate the loop manually and use uv_loop_init instead.
- */
-UV_EXTERN uv_loop_t* uv_loop_new(void);
-/*
- * NOTE:
- *  This function is DEPRECATED (to be removed after 0.12). Users should use
- *  uv_loop_close and free the memory manually instead.
- */
-UV_EXTERN void uv_loop_delete(uv_loop_t*);
-UV_EXTERN size_t uv_loop_size(void);
-UV_EXTERN int uv_loop_alive(const uv_loop_t* loop);
-UV_EXTERN int uv_loop_configure(uv_loop_t* loop, uv_loop_option option, ...);
-UV_EXTERN int uv_loop_fork(uv_loop_t* loop);
-
-UV_EXTERN int uv_run(uv_loop_t*, uv_run_mode mode);
-UV_EXTERN void uv_stop(uv_loop_t*);
-
-UV_EXTERN void uv_ref(uv_handle_t*);
-UV_EXTERN void uv_unref(uv_handle_t*);
-UV_EXTERN int uv_has_ref(const uv_handle_t*);
-
-UV_EXTERN void uv_update_time(uv_loop_t*);
-UV_EXTERN uint64_t uv_now(const uv_loop_t*);
-
-UV_EXTERN int uv_backend_fd(const uv_loop_t*);
-UV_EXTERN int uv_backend_timeout(const uv_loop_t*);
-
-typedef void (*uv_alloc_cb)(uv_handle_t* handle,
-                            size_t suggested_size,
-                            uv_buf_t* buf);
-typedef void (*uv_read_cb)(uv_stream_t* stream,
-                           ssize_t nread,
-                           const uv_buf_t* buf);
-typedef void (*uv_write_cb)(uv_write_t* req, int status);
-typedef void (*uv_connect_cb)(uv_connect_t* req, int status);
-typedef void (*uv_shutdown_cb)(uv_shutdown_t* req, int status);
-typedef void (*uv_connection_cb)(uv_stream_t* server, int status);
-typedef void (*uv_close_cb)(uv_handle_t* handle);
-typedef void (*uv_poll_cb)(uv_poll_t* handle, int status, int events);
-typedef void (*uv_timer_cb)(uv_timer_t* handle);
-typedef void (*uv_async_cb)(uv_async_t* handle);
-typedef void (*uv_prepare_cb)(uv_prepare_t* handle);
-typedef void (*uv_check_cb)(uv_check_t* handle);
-typedef void (*uv_idle_cb)(uv_idle_t* handle);
-typedef void (*uv_exit_cb)(uv_process_t*, int64_t exit_status, int term_signal);
-typedef void (*uv_walk_cb)(uv_handle_t* handle, void* arg);
-typedef void (*uv_fs_cb)(uv_fs_t* req);
-typedef void (*uv_work_cb)(uv_work_t* req);
-typedef void (*uv_after_work_cb)(uv_work_t* req, int status);
-typedef void (*uv_getaddrinfo_cb)(uv_getaddrinfo_t* req,
-                                  int status,
-                                  struct addrinfo* res);
-typedef void (*uv_getnameinfo_cb)(uv_getnameinfo_t* req,
-                                  int status,
-                                  const char* hostname,
-                                  const char* service);
-
-typedef struct {
-  long tv_sec;
-  long tv_nsec;
-} uv_timespec_t;
-
-
-typedef struct {
-  uint64_t st_dev;
-  uint64_t st_mode;
-  uint64_t st_nlink;
-  uint64_t st_uid;
-  uint64_t st_gid;
-  uint64_t st_rdev;
-  uint64_t st_ino;
-  uint64_t st_size;
-  uint64_t st_blksize;
-  uint64_t st_blocks;
-  uint64_t st_flags;
-  uint64_t st_gen;
-  uv_timespec_t st_atim;
-  uv_timespec_t st_mtim;
-  uv_timespec_t st_ctim;
-  uv_timespec_t st_birthtim;
-} uv_stat_t;
-
-
-typedef void (*uv_fs_event_cb)(uv_fs_event_t* handle,
-                               const char* filename,
-                               int events,
-                               int status);
-
-typedef void (*uv_fs_poll_cb)(uv_fs_poll_t* handle,
-                              int status,
-                              const uv_stat_t* prev,
-                              const uv_stat_t* curr);
-
-typedef void (*uv_signal_cb)(uv_signal_t* handle, int signum);
-
-
-typedef enum {
-  UV_LEAVE_GROUP = 0,
-  UV_JOIN_GROUP
-} uv_membership;
-
-
-UV_EXTERN int uv_translate_sys_error(int sys_errno);
-
-UV_EXTERN const char* uv_strerror(int err);
-UV_EXTERN char* uv_strerror_r(int err, char* buf, size_t buflen);
-
-UV_EXTERN const char* uv_err_name(int err);
-UV_EXTERN char* uv_err_name_r(int err, char* buf, size_t buflen);
-
-
-#define UV_REQ_FIELDS                                                         \
-  /* public */                                                                \
-  void* data;                                                                 \
-  /* read-only */                                                             \
-  uv_req_type type;                                                           \
-  /* private */                                                               \
-  void* reserved[6];                                                          \
-  UV_REQ_PRIVATE_FIELDS                                                       \
-
-/* Abstract base class of all requests. */
-struct uv_req_s {
-  UV_REQ_FIELDS
-};
-
-
-/* Platform-specific request types. */
-UV_PRIVATE_REQ_TYPES
-
-
-UV_EXTERN int uv_shutdown(uv_shutdown_t* req,
-                          uv_stream_t* handle,
-                          uv_shutdown_cb cb);
-
-struct uv_shutdown_s {
-  UV_REQ_FIELDS
-  uv_stream_t* handle;
-  uv_shutdown_cb cb;
-  UV_SHUTDOWN_PRIVATE_FIELDS
-};
-
-
-#define UV_HANDLE_FIELDS                                                      \
-  /* public */                                                                \
-  void* data;                                                                 \
-  /* read-only */                                                             \
-  uv_loop_t* loop;                                                            \
-  uv_handle_type type;                                                        \
-  /* private */                                                               \
-  uv_close_cb close_cb;                                                       \
-  void* handle_queue[2];                                                      \
-  union {                                                                     \
-    int fd;                                                                   \
-    void* reserved[4];                                                        \
-  } u;                                                                        \
-  UV_HANDLE_PRIVATE_FIELDS                                                    \
-
-/* The abstract base class of all handles. */
-struct uv_handle_s {
-  UV_HANDLE_FIELDS
-};
-
-UV_EXTERN size_t uv_handle_size(uv_handle_type type);
-UV_EXTERN uv_handle_type uv_handle_get_type(const uv_handle_t* handle);
-UV_EXTERN const char* uv_handle_type_name(uv_handle_type type);
-UV_EXTERN void* uv_handle_get_data(const uv_handle_t* handle);
-UV_EXTERN uv_loop_t* uv_handle_get_loop(const uv_handle_t* handle);
-UV_EXTERN void uv_handle_set_data(uv_handle_t* handle, void* data);
-
-UV_EXTERN size_t uv_req_size(uv_req_type type);
-UV_EXTERN void* uv_req_get_data(const uv_req_t* req);
-UV_EXTERN void uv_req_set_data(uv_req_t* req, void* data);
-UV_EXTERN uv_req_type uv_req_get_type(const uv_req_t* req);
-UV_EXTERN const char* uv_req_type_name(uv_req_type type);
-
-UV_EXTERN int uv_is_active(const uv_handle_t* handle);
-
-UV_EXTERN void uv_walk(uv_loop_t* loop, uv_walk_cb walk_cb, void* arg);
-
-/* Helpers for ad hoc debugging, no API/ABI stability guaranteed. */
-UV_EXTERN void uv_print_all_handles(uv_loop_t* loop, FILE* stream);
-UV_EXTERN void uv_print_active_handles(uv_loop_t* loop, FILE* stream);
-
-UV_EXTERN void uv_close(uv_handle_t* handle, uv_close_cb close_cb);
-
-UV_EXTERN int uv_send_buffer_size(uv_handle_t* handle, int* value);
-UV_EXTERN int uv_recv_buffer_size(uv_handle_t* handle, int* value);
-
-UV_EXTERN int uv_fileno(const uv_handle_t* handle, uv_os_fd_t* fd);
-
-UV_EXTERN uv_buf_t uv_buf_init(char* base, unsigned int len);
-
-
-#define UV_STREAM_FIELDS                                                      \
-  /* number of bytes queued for writing */                                    \
-  size_t write_queue_size;                                                    \
-  uv_alloc_cb alloc_cb;                                                       \
-  uv_read_cb read_cb;                                                         \
-  /* private */                                                               \
-  UV_STREAM_PRIVATE_FIELDS
-
-/*
- * uv_stream_t is a subclass of uv_handle_t.
- *
- * uv_stream is an abstract class.
- *
- * uv_stream_t is the parent class of uv_tcp_t, uv_pipe_t and uv_tty_t.
- */
-struct uv_stream_s {
-  UV_HANDLE_FIELDS
-  UV_STREAM_FIELDS
-};
-
-UV_EXTERN size_t uv_stream_get_write_queue_size(const uv_stream_t* stream);
-
-UV_EXTERN int uv_listen(uv_stream_t* stream, int backlog, uv_connection_cb cb);
-UV_EXTERN int uv_accept(uv_stream_t* server, uv_stream_t* client);
-
-UV_EXTERN int uv_read_start(uv_stream_t*,
-                            uv_alloc_cb alloc_cb,
-                            uv_read_cb read_cb);
-UV_EXTERN int uv_read_stop(uv_stream_t*);
-
-UV_EXTERN int uv_write(uv_write_t* req,
-                       uv_stream_t* handle,
-                       const uv_buf_t bufs[],
-                       unsigned int nbufs,
-                       uv_write_cb cb);
-UV_EXTERN int uv_write2(uv_write_t* req,
-                        uv_stream_t* handle,
-                        const uv_buf_t bufs[],
-                        unsigned int nbufs,
-                        uv_stream_t* send_handle,
-                        uv_write_cb cb);
-UV_EXTERN int uv_try_write(uv_stream_t* handle,
-                           const uv_buf_t bufs[],
-                           unsigned int nbufs);
-
-/* uv_write_t is a subclass of uv_req_t. */
-struct uv_write_s {
-  UV_REQ_FIELDS
-  uv_write_cb cb;
-  uv_stream_t* send_handle; /* TODO: make private and unix-only in v2.x. */
-  uv_stream_t* handle;
-  UV_WRITE_PRIVATE_FIELDS
-};
-
-
-UV_EXTERN int uv_is_readable(const uv_stream_t* handle);
-UV_EXTERN int uv_is_writable(const uv_stream_t* handle);
-
-UV_EXTERN int uv_stream_set_blocking(uv_stream_t* handle, int blocking);
-
-UV_EXTERN int uv_is_closing(const uv_handle_t* handle);
-
-
-/*
- * uv_tcp_t is a subclass of uv_stream_t.
- *
- * Represents a TCP stream or TCP server.
- */
-struct uv_tcp_s {
-  UV_HANDLE_FIELDS
-  UV_STREAM_FIELDS
-  UV_TCP_PRIVATE_FIELDS
-};
-
-UV_EXTERN int uv_tcp_init(uv_loop_t*, uv_tcp_t* handle);
-UV_EXTERN int uv_tcp_init_ex(uv_loop_t*, uv_tcp_t* handle, unsigned int flags);
-UV_EXTERN int uv_tcp_open(uv_tcp_t* handle, uv_os_sock_t sock);
-UV_EXTERN int uv_tcp_nodelay(uv_tcp_t* handle, int enable);
-UV_EXTERN int uv_tcp_keepalive(uv_tcp_t* handle,
-                               int enable,
-                               unsigned int delay);
-UV_EXTERN int uv_tcp_simultaneous_accepts(uv_tcp_t* handle, int enable);
-
-enum uv_tcp_flags {
-  /* Used with uv_tcp_bind, when an IPv6 address is used. */
-  UV_TCP_IPV6ONLY = 1
-};
-
-UV_EXTERN int uv_tcp_bind(uv_tcp_t* handle,
-                          const struct sockaddr* addr,
-                          unsigned int flags);
-UV_EXTERN int uv_tcp_getsockname(const uv_tcp_t* handle,
-                                 struct sockaddr* name,
-                                 int* namelen);
-UV_EXTERN int uv_tcp_getpeername(const uv_tcp_t* handle,
-                                 struct sockaddr* name,
-                                 int* namelen);
-UV_EXTERN int uv_tcp_connect(uv_connect_t* req,
-                             uv_tcp_t* handle,
-                             const struct sockaddr* addr,
-                             uv_connect_cb cb);
-
-/* uv_connect_t is a subclass of uv_req_t. */
-struct uv_connect_s {
-  UV_REQ_FIELDS
-  uv_connect_cb cb;
-  uv_stream_t* handle;
-  UV_CONNECT_PRIVATE_FIELDS
-};
-
-
-/*
- * UDP support.
- */
-
-enum uv_udp_flags {
-  /* Disables dual stack mode. */
-  UV_UDP_IPV6ONLY = 1,
-  /*
-   * Indicates message was truncated because read buffer was too small. The
-   * remainder was discarded by the OS. Used in uv_udp_recv_cb.
-   */
-  UV_UDP_PARTIAL = 2,
-  /*
-   * Indicates if SO_REUSEADDR will be set when binding the handle.
-   * This sets the SO_REUSEPORT socket flag on the BSDs and OS X. On other
-   * Unix platforms, it sets the SO_REUSEADDR flag.  What that means is that
-   * multiple threads or processes can bind to the same address without error
-   * (provided they all set the flag) but only the last one to bind will receive
-   * any traffic, in effect "stealing" the port from the previous listener.
-   */
-  UV_UDP_REUSEADDR = 4
-};
-
-typedef void (*uv_udp_send_cb)(uv_udp_send_t* req, int status);
-typedef void (*uv_udp_recv_cb)(uv_udp_t* handle,
-                               ssize_t nread,
-                               const uv_buf_t* buf,
-                               const struct sockaddr* addr,
-                               unsigned flags);
-
-/* uv_udp_t is a subclass of uv_handle_t. */
-struct uv_udp_s {
-  UV_HANDLE_FIELDS
-  /* read-only */
-  /*
-   * Number of bytes queued for sending. This field strictly shows how much
-   * information is currently queued.
-   */
-  size_t send_queue_size;
-  /*
-   * Number of send requests currently in the queue awaiting to be processed.
-   */
-  size_t send_queue_count;
-  UV_UDP_PRIVATE_FIELDS
-};
-
-/* uv_udp_send_t is a subclass of uv_req_t. */
-struct uv_udp_send_s {
-  UV_REQ_FIELDS
-  uv_udp_t* handle;
-  uv_udp_send_cb cb;
-  UV_UDP_SEND_PRIVATE_FIELDS
-};
-
-UV_EXTERN int uv_udp_init(uv_loop_t*, uv_udp_t* handle);
-UV_EXTERN int uv_udp_init_ex(uv_loop_t*, uv_udp_t* handle, unsigned int flags);
-UV_EXTERN int uv_udp_open(uv_udp_t* handle, uv_os_sock_t sock);
-UV_EXTERN int uv_udp_bind(uv_udp_t* handle,
-                          const struct sockaddr* addr,
-                          unsigned int flags);
-UV_EXTERN int uv_udp_connect(uv_udp_t* handle, const struct sockaddr* addr);
-
-UV_EXTERN int uv_udp_getpeername(const uv_udp_t* handle,
-                                 struct sockaddr* name,
-                                 int* namelen);
-UV_EXTERN int uv_udp_getsockname(const uv_udp_t* handle,
-                                 struct sockaddr* name,
-                                 int* namelen);
-UV_EXTERN int uv_udp_set_membership(uv_udp_t* handle,
-                                    const char* multicast_addr,
-                                    const char* interface_addr,
-                                    uv_membership membership);
-UV_EXTERN int uv_udp_set_multicast_loop(uv_udp_t* handle, int on);
-UV_EXTERN int uv_udp_set_multicast_ttl(uv_udp_t* handle, int ttl);
-UV_EXTERN int uv_udp_set_multicast_interface(uv_udp_t* handle,
-                                             const char* interface_addr);
-UV_EXTERN int uv_udp_set_broadcast(uv_udp_t* handle, int on);
-UV_EXTERN int uv_udp_set_ttl(uv_udp_t* handle, int ttl);
-UV_EXTERN int uv_udp_send(uv_udp_send_t* req,
-                          uv_udp_t* handle,
-                          const uv_buf_t bufs[],
-                          unsigned int nbufs,
-                          const struct sockaddr* addr,
-                          uv_udp_send_cb send_cb);
-UV_EXTERN int uv_udp_try_send(uv_udp_t* handle,
-                              const uv_buf_t bufs[],
-                              unsigned int nbufs,
-                              const struct sockaddr* addr);
-UV_EXTERN int uv_udp_recv_start(uv_udp_t* handle,
-                                uv_alloc_cb alloc_cb,
-                                uv_udp_recv_cb recv_cb);
-UV_EXTERN int uv_udp_recv_stop(uv_udp_t* handle);
-UV_EXTERN size_t uv_udp_get_send_queue_size(const uv_udp_t* handle);
-UV_EXTERN size_t uv_udp_get_send_queue_count(const uv_udp_t* handle);
-
-
-/*
- * uv_tty_t is a subclass of uv_stream_t.
- *
- * Representing a stream for the console.
- */
-struct uv_tty_s {
-  UV_HANDLE_FIELDS
-  UV_STREAM_FIELDS
-  UV_TTY_PRIVATE_FIELDS
-};
-
-typedef enum {
-  /* Initial/normal terminal mode */
-  UV_TTY_MODE_NORMAL,
-  /* Raw input mode (On Windows, ENABLE_WINDOW_INPUT is also enabled) */
-  UV_TTY_MODE_RAW,
-  /* Binary-safe I/O mode for IPC (Unix-only) */
-  UV_TTY_MODE_IO
-} uv_tty_mode_t;
-
-UV_EXTERN int uv_tty_init(uv_loop_t*, uv_tty_t*, uv_file fd, int readable);
-UV_EXTERN int uv_tty_set_mode(uv_tty_t*, uv_tty_mode_t mode);
-UV_EXTERN int uv_tty_reset_mode(void);
-UV_EXTERN int uv_tty_get_winsize(uv_tty_t*, int* width, int* height);
-
-inline int uv_tty_set_mode(uv_tty_t* handle, int mode) {
-  return uv_tty_set_mode(handle, static_cast<uv_tty_mode_t>(mode));
-}
-
-UV_EXTERN uv_handle_type uv_guess_handle(uv_file file);
-
-/*
- * uv_pipe_t is a subclass of uv_stream_t.
- *
- * Representing a pipe stream or pipe server. On Windows this is a Named
- * Pipe. On Unix this is a Unix domain socket.
- */
-struct uv_pipe_s {
-  UV_HANDLE_FIELDS
-  UV_STREAM_FIELDS
-  int ipc; /* non-zero if this pipe is used for passing handles */
-  UV_PIPE_PRIVATE_FIELDS
-};
-
-UV_EXTERN int uv_pipe_init(uv_loop_t*, uv_pipe_t* handle, int ipc);
-UV_EXTERN int uv_pipe_open(uv_pipe_t*, uv_file file);
-UV_EXTERN int uv_pipe_bind(uv_pipe_t* handle, const char* name);
-UV_EXTERN void uv_pipe_connect(uv_connect_t* req,
-                               uv_pipe_t* handle,
-                               const char* name,
-                               uv_connect_cb cb);
-UV_EXTERN int uv_pipe_getsockname(const uv_pipe_t* handle,
-                                  char* buffer,
-                                  size_t* size);
-UV_EXTERN int uv_pipe_getpeername(const uv_pipe_t* handle,
-                                  char* buffer,
-                                  size_t* size);
-UV_EXTERN void uv_pipe_pending_instances(uv_pipe_t* handle, int count);
-UV_EXTERN int uv_pipe_pending_count(uv_pipe_t* handle);
-UV_EXTERN uv_handle_type uv_pipe_pending_type(uv_pipe_t* handle);
-UV_EXTERN int uv_pipe_chmod(uv_pipe_t* handle, int flags);
-
-
-struct uv_poll_s {
-  UV_HANDLE_FIELDS
-  uv_poll_cb poll_cb;
-  UV_POLL_PRIVATE_FIELDS
-};
-
-enum uv_poll_event {
-  UV_READABLE = 1,
-  UV_WRITABLE = 2,
-  UV_DISCONNECT = 4,
-  UV_PRIORITIZED = 8
-};
-
-UV_EXTERN int uv_poll_init(uv_loop_t* loop, uv_poll_t* handle, int fd);
-UV_EXTERN int uv_poll_init_socket(uv_loop_t* loop,
-                                  uv_poll_t* handle,
-                                  uv_os_sock_t socket);
-UV_EXTERN int uv_poll_start(uv_poll_t* handle, int events, uv_poll_cb cb);
-UV_EXTERN int uv_poll_stop(uv_poll_t* handle);
-
-
-struct uv_prepare_s {
-  UV_HANDLE_FIELDS
-  UV_PREPARE_PRIVATE_FIELDS
-};
-
-UV_EXTERN int uv_prepare_init(uv_loop_t*, uv_prepare_t* prepare);
-UV_EXTERN int uv_prepare_start(uv_prepare_t* prepare, uv_prepare_cb cb);
-UV_EXTERN int uv_prepare_stop(uv_prepare_t* prepare);
-
-
-struct uv_check_s {
-  UV_HANDLE_FIELDS
-  UV_CHECK_PRIVATE_FIELDS
-};
-
-UV_EXTERN int uv_check_init(uv_loop_t*, uv_check_t* check);
-UV_EXTERN int uv_check_start(uv_check_t* check, uv_check_cb cb);
-UV_EXTERN int uv_check_stop(uv_check_t* check);
-
-
-struct uv_idle_s {
-  UV_HANDLE_FIELDS
-  UV_IDLE_PRIVATE_FIELDS
-};
-
-UV_EXTERN int uv_idle_init(uv_loop_t*, uv_idle_t* idle);
-UV_EXTERN int uv_idle_start(uv_idle_t* idle, uv_idle_cb cb);
-UV_EXTERN int uv_idle_stop(uv_idle_t* idle);
-
-
-struct uv_async_s {
-  UV_HANDLE_FIELDS
-  UV_ASYNC_PRIVATE_FIELDS
-};
-
-UV_EXTERN int uv_async_init(uv_loop_t*,
-                            uv_async_t* async,
-                            uv_async_cb async_cb);
-UV_EXTERN int uv_async_send(uv_async_t* async);
-
-
-/*
- * uv_timer_t is a subclass of uv_handle_t.
- *
- * Used to get woken up at a specified time in the future.
- */
-struct uv_timer_s {
-  UV_HANDLE_FIELDS
-  UV_TIMER_PRIVATE_FIELDS
-};
-
-UV_EXTERN int uv_timer_init(uv_loop_t*, uv_timer_t* handle);
-UV_EXTERN int uv_timer_start(uv_timer_t* handle,
-                             uv_timer_cb cb,
-                             uint64_t timeout,
-                             uint64_t repeat);
-UV_EXTERN int uv_timer_stop(uv_timer_t* handle);
-UV_EXTERN int uv_timer_again(uv_timer_t* handle);
-UV_EXTERN void uv_timer_set_repeat(uv_timer_t* handle, uint64_t repeat);
-UV_EXTERN uint64_t uv_timer_get_repeat(const uv_timer_t* handle);
-
-
-/*
- * uv_getaddrinfo_t is a subclass of uv_req_t.
- *
- * Request object for uv_getaddrinfo.
- */
-struct uv_getaddrinfo_s {
-  UV_REQ_FIELDS
-  /* read-only */
-  uv_loop_t* loop;
-  /* struct addrinfo* addrinfo is marked as private, but it really isn't. */
-  UV_GETADDRINFO_PRIVATE_FIELDS
-};
-
-
-UV_EXTERN int uv_getaddrinfo(uv_loop_t* loop,
-                             uv_getaddrinfo_t* req,
-                             uv_getaddrinfo_cb getaddrinfo_cb,
-                             const char* node,
-                             const char* service,
-                             const struct addrinfo* hints);
-UV_EXTERN void uv_freeaddrinfo(struct addrinfo* ai);
-
-
-/*
-* uv_getnameinfo_t is a subclass of uv_req_t.
-*
-* Request object for uv_getnameinfo.
-*/
-struct uv_getnameinfo_s {
-  UV_REQ_FIELDS
-  /* read-only */
-  uv_loop_t* loop;
-  /* host and service are marked as private, but they really aren't. */
-  UV_GETNAMEINFO_PRIVATE_FIELDS
-};
-
-UV_EXTERN int uv_getnameinfo(uv_loop_t* loop,
-                             uv_getnameinfo_t* req,
-                             uv_getnameinfo_cb getnameinfo_cb,
-                             const struct sockaddr* addr,
-                             int flags);
-
-
-/* uv_spawn() options. */
-typedef enum {
-  UV_IGNORE         = 0x00,
-  UV_CREATE_PIPE    = 0x01,
-  UV_INHERIT_FD     = 0x02,
-  UV_INHERIT_STREAM = 0x04,
-
-  /*
-   * When UV_CREATE_PIPE is specified, UV_READABLE_PIPE and UV_WRITABLE_PIPE
-   * determine the direction of flow, from the child process' perspective. Both
-   * flags may be specified to create a duplex data stream.
-   */
-  UV_READABLE_PIPE  = 0x10,
-  UV_WRITABLE_PIPE  = 0x20,
-
-  /*
-   * Open the child pipe handle in overlapped mode on Windows.
-   * On Unix it is silently ignored.
-   */
-  UV_OVERLAPPED_PIPE = 0x40
-} uv_stdio_flags;
-
-typedef struct uv_stdio_container_s {
-  uv_stdio_flags flags;
-
-  union {
-    uv_stream_t* stream;
-    int fd;
-  } data;
-} uv_stdio_container_t;
-
-typedef struct uv_process_options_s {
-  uv_exit_cb exit_cb; /* Called after the process exits. */
-  const char* file;   /* Path to program to execute. */
-  /*
-   * Command line arguments. args[0] should be the path to the program. On
-   * Windows this uses CreateProcess which concatenates the arguments into a
-   * string this can cause some strange errors. See the note at
-   * windows_verbatim_arguments.
-   */
-  char** args;
-  /*
-   * This will be set as the environ variable in the subprocess. If this is
-   * NULL then the parents environ will be used.
-   */
-  char** env;
-  /*
-   * If non-null this represents a directory the subprocess should execute
-   * in. Stands for current working directory.
-   */
-  const char* cwd;
-  /*
-   * Various flags that control how uv_spawn() behaves. See the definition of
-   * `enum uv_process_flags` below.
-   */
-  unsigned int flags;
-  /*
-   * The `stdio` field points to an array of uv_stdio_container_t structs that
-   * describe the file descriptors that will be made available to the child
-   * process. The convention is that stdio[0] points to stdin, fd 1 is used for
-   * stdout, and fd 2 is stderr.
-   *
-   * Note that on windows file descriptors greater than 2 are available to the
-   * child process only if the child processes uses the MSVCRT runtime.
-   */
-  int stdio_count;
-  uv_stdio_container_t* stdio;
-  /*
-   * Libuv can change the child process' user/group id. This happens only when
-   * the appropriate bits are set in the flags fields. This is not supported on
-   * windows; uv_spawn() will fail and set the error to UV_ENOTSUP.
-   */
-  uv_uid_t uid;
-  uv_gid_t gid;
-} uv_process_options_t;
-
-/*
- * These are the flags that can be used for the uv_process_options.flags field.
- */
-enum uv_process_flags {
-  /*
-   * Set the child process' user id. The user id is supplied in the `uid` field
-   * of the options struct. This does not work on windows; setting this flag
-   * will cause uv_spawn() to fail.
-   */
-  UV_PROCESS_SETUID = (1 << 0),
-  /*
-   * Set the child process' group id. The user id is supplied in the `gid`
-   * field of the options struct. This does not work on windows; setting this
-   * flag will cause uv_spawn() to fail.
-   */
-  UV_PROCESS_SETGID = (1 << 1),
-  /*
-   * Do not wrap any arguments in quotes, or perform any other escaping, when
-   * converting the argument list into a command line string. This option is
-   * only meaningful on Windows systems. On Unix it is silently ignored.
-   */
-  UV_PROCESS_WINDOWS_VERBATIM_ARGUMENTS = (1 << 2),
-  /*
-   * Spawn the child process in a detached state - this will make it a process
-   * group leader, and will effectively enable the child to keep running after
-   * the parent exits.  Note that the child process will still keep the
-   * parent's event loop alive unless the parent process calls uv_unref() on
-   * the child's process handle.
-   */
-  UV_PROCESS_DETACHED = (1 << 3),
-  /*
-   * Hide the subprocess window that would normally be created. This option is
-   * only meaningful on Windows systems. On Unix it is silently ignored.
-   */
-  UV_PROCESS_WINDOWS_HIDE = (1 << 4),
-  /*
-   * Hide the subprocess console window that would normally be created. This
-   * option is only meaningful on Windows systems. On Unix it is silently
-   * ignored.
-   */
-  UV_PROCESS_WINDOWS_HIDE_CONSOLE = (1 << 5),
-  /*
-   * Hide the subprocess GUI window that would normally be created. This
-   * option is only meaningful on Windows systems. On Unix it is silently
-   * ignored.
-   */
-  UV_PROCESS_WINDOWS_HIDE_GUI = (1 << 6)
-};
-
-/*
- * uv_process_t is a subclass of uv_handle_t.
- */
-struct uv_process_s {
-  UV_HANDLE_FIELDS
-  uv_exit_cb exit_cb;
-  int pid;
-  UV_PROCESS_PRIVATE_FIELDS
-};
-
-UV_EXTERN int uv_spawn(uv_loop_t* loop,
-                       uv_process_t* handle,
-                       const uv_process_options_t* options);
-UV_EXTERN int uv_process_kill(uv_process_t*, int signum);
-UV_EXTERN int uv_kill(int pid, int signum);
-UV_EXTERN uv_pid_t uv_process_get_pid(const uv_process_t*);
-
-
-/*
- * uv_work_t is a subclass of uv_req_t.
- */
-struct uv_work_s {
-  UV_REQ_FIELDS
-  uv_loop_t* loop;
-  uv_work_cb work_cb;
-  uv_after_work_cb after_work_cb;
-  UV_WORK_PRIVATE_FIELDS
-};
-
-UV_EXTERN int uv_queue_work(uv_loop_t* loop,
-                            uv_work_t* req,
-                            uv_work_cb work_cb,
-                            uv_after_work_cb after_work_cb);
-
-UV_EXTERN int uv_cancel(uv_req_t* req);
-
-
-struct uv_cpu_times_s {
-  uint64_t user;
-  uint64_t nice;
-  uint64_t sys;
-  uint64_t idle;
-  uint64_t irq;
-};
-
-struct uv_cpu_info_s {
-  char* model;
-  int speed;
-  struct uv_cpu_times_s cpu_times;
-};
-
-struct uv_interface_address_s {
-  char* name;
-  char phys_addr[6];
-  int is_internal;
-  union {
-    struct sockaddr_in address4;
-    struct sockaddr_in6 address6;
-  } address;
-  union {
-    struct sockaddr_in netmask4;
-    struct sockaddr_in6 netmask6;
-  } netmask;
-};
-
-struct uv_passwd_s {
-  char* username;
-  long uid;
-  long gid;
-  char* shell;
-  char* homedir;
-};
-
-struct uv_utsname_s {
-  char sysname[256];
-  char release[256];
-  char version[256];
-  char machine[256];
-  /* This struct does not contain the nodename and domainname fields present in
-     the utsname type. domainname is a GNU extension. Both fields are referred
-     to as meaningless in the docs. */
-};
-
-typedef enum {
-  UV_DIRENT_UNKNOWN,
-  UV_DIRENT_FILE,
-  UV_DIRENT_DIR,
-  UV_DIRENT_LINK,
-  UV_DIRENT_FIFO,
-  UV_DIRENT_SOCKET,
-  UV_DIRENT_CHAR,
-  UV_DIRENT_BLOCK
-} uv_dirent_type_t;
-
-struct uv_dirent_s {
-  const char* name;
-  uv_dirent_type_t type;
-};
-
-UV_EXTERN char** uv_setup_args(int argc, char** argv);
-UV_EXTERN int uv_get_process_title(char* buffer, size_t size);
-UV_EXTERN int uv_set_process_title(const char* title);
-UV_EXTERN int uv_resident_set_memory(size_t* rss);
-UV_EXTERN int uv_uptime(double* uptime);
-UV_EXTERN uv_os_fd_t uv_get_osfhandle(int fd);
-UV_EXTERN int uv_open_osfhandle(uv_os_fd_t os_fd);
-
-typedef struct {
-  long tv_sec;
-  long tv_usec;
-} uv_timeval_t;
-
-typedef struct {
-  int64_t tv_sec;
-  int32_t tv_usec;
-} uv_timeval64_t;
-
-typedef struct {
-   uv_timeval_t ru_utime; /* user CPU time used */
-   uv_timeval_t ru_stime; /* system CPU time used */
-   uint64_t ru_maxrss;    /* maximum resident set size */
-   uint64_t ru_ixrss;     /* integral shared memory size */
-   uint64_t ru_idrss;     /* integral unshared data size */
-   uint64_t ru_isrss;     /* integral unshared stack size */
-   uint64_t ru_minflt;    /* page reclaims (soft page faults) */
-   uint64_t ru_majflt;    /* page faults (hard page faults) */
-   uint64_t ru_nswap;     /* swaps */
-   uint64_t ru_inblock;   /* block input operations */
-   uint64_t ru_oublock;   /* block output operations */
-   uint64_t ru_msgsnd;    /* IPC messages sent */
-   uint64_t ru_msgrcv;    /* IPC messages received */
-   uint64_t ru_nsignals;  /* signals received */
-   uint64_t ru_nvcsw;     /* voluntary context switches */
-   uint64_t ru_nivcsw;    /* involuntary context switches */
-} uv_rusage_t;
-
-UV_EXTERN int uv_getrusage(uv_rusage_t* rusage);
-
-UV_EXTERN int uv_os_homedir(char* buffer, size_t* size);
-UV_EXTERN int uv_os_tmpdir(char* buffer, size_t* size);
-UV_EXTERN int uv_os_get_passwd(uv_passwd_t* pwd);
-UV_EXTERN void uv_os_free_passwd(uv_passwd_t* pwd);
-UV_EXTERN uv_pid_t uv_os_getpid(void);
-UV_EXTERN uv_pid_t uv_os_getppid(void);
-
-#define UV_PRIORITY_LOW 19
-#define UV_PRIORITY_BELOW_NORMAL 10
-#define UV_PRIORITY_NORMAL 0
-#define UV_PRIORITY_ABOVE_NORMAL -7
-#define UV_PRIORITY_HIGH -14
-#define UV_PRIORITY_HIGHEST -20
-
-UV_EXTERN int uv_os_getpriority(uv_pid_t pid, int* priority);
-UV_EXTERN int uv_os_setpriority(uv_pid_t pid, int priority);
-
-UV_EXTERN int uv_cpu_info(uv_cpu_info_t** cpu_infos, int* count);
-UV_EXTERN void uv_free_cpu_info(uv_cpu_info_t* cpu_infos, int count);
-
-UV_EXTERN int uv_interface_addresses(uv_interface_address_t** addresses,
-                                     int* count);
-UV_EXTERN void uv_free_interface_addresses(uv_interface_address_t* addresses,
-                                           int count);
-
-UV_EXTERN int uv_os_getenv(const char* name, char* buffer, size_t* size);
-UV_EXTERN int uv_os_setenv(const char* name, const char* value);
-UV_EXTERN int uv_os_unsetenv(const char* name);
-
-#ifdef MAXHOSTNAMELEN
-# define UV_MAXHOSTNAMESIZE (MAXHOSTNAMELEN + 1)
-#else
-  /*
-    Fallback for the maximum hostname size, including the null terminator. The
-    Windows gethostname() documentation states that 256 bytes will always be
-    large enough to hold the null-terminated hostname.
-  */
-# define UV_MAXHOSTNAMESIZE 256
-#endif
-
-UV_EXTERN int uv_os_gethostname(char* buffer, size_t* size);
-
-UV_EXTERN int uv_os_uname(uv_utsname_t* buffer);
-
-
-typedef enum {
-  UV_FS_UNKNOWN = -1,
-  UV_FS_CUSTOM,
-  UV_FS_OPEN,
-  UV_FS_CLOSE,
-  UV_FS_READ,
-  UV_FS_WRITE,
-  UV_FS_SENDFILE,
-  UV_FS_STAT,
-  UV_FS_LSTAT,
-  UV_FS_FSTAT,
-  UV_FS_FTRUNCATE,
-  UV_FS_UTIME,
-  UV_FS_FUTIME,
-  UV_FS_ACCESS,
-  UV_FS_CHMOD,
-  UV_FS_FCHMOD,
-  UV_FS_FSYNC,
-  UV_FS_FDATASYNC,
-  UV_FS_UNLINK,
-  UV_FS_RMDIR,
-  UV_FS_MKDIR,
-  UV_FS_MKDTEMP,
-  UV_FS_RENAME,
-  UV_FS_SCANDIR,
-  UV_FS_LINK,
-  UV_FS_SYMLINK,
-  UV_FS_READLINK,
-  UV_FS_CHOWN,
-  UV_FS_FCHOWN,
-  UV_FS_REALPATH,
-  UV_FS_COPYFILE,
-  UV_FS_LCHOWN,
-  UV_FS_OPENDIR,
-  UV_FS_READDIR,
-  UV_FS_CLOSEDIR
-} uv_fs_type;
-
-struct uv_dir_s {
-  uv_dirent_t* dirents;
-  size_t nentries;
-  void* reserved[4];
-  UV_DIR_PRIVATE_FIELDS
-};
-
-/* uv_fs_t is a subclass of uv_req_t. */
-struct uv_fs_s {
-  UV_REQ_FIELDS
-  uv_fs_type fs_type;
-  uv_loop_t* loop;
-  uv_fs_cb cb;
-  ssize_t result;
-  void* ptr;
-  const char* path;
-  uv_stat_t statbuf;  /* Stores the result of uv_fs_stat() and uv_fs_fstat(). */
-  UV_FS_PRIVATE_FIELDS
-};
-
-UV_EXTERN uv_fs_type uv_fs_get_type(const uv_fs_t*);
-UV_EXTERN ssize_t uv_fs_get_result(const uv_fs_t*);
-UV_EXTERN void* uv_fs_get_ptr(const uv_fs_t*);
-UV_EXTERN const char* uv_fs_get_path(const uv_fs_t*);
-UV_EXTERN uv_stat_t* uv_fs_get_statbuf(uv_fs_t*);
-
-UV_EXTERN void uv_fs_req_cleanup(uv_fs_t* req);
-UV_EXTERN int uv_fs_close(uv_loop_t* loop,
-                          uv_fs_t* req,
-                          uv_file file,
-                          uv_fs_cb cb);
-UV_EXTERN int uv_fs_open(uv_loop_t* loop,
-                         uv_fs_t* req,
-                         const char* path,
-                         int flags,
-                         int mode,
-                         uv_fs_cb cb);
-UV_EXTERN int uv_fs_read(uv_loop_t* loop,
-                         uv_fs_t* req,
-                         uv_file file,
-                         const uv_buf_t bufs[],
-                         unsigned int nbufs,
-                         int64_t offset,
-                         uv_fs_cb cb);
-UV_EXTERN int uv_fs_unlink(uv_loop_t* loop,
-                           uv_fs_t* req,
-                           const char* path,
-                           uv_fs_cb cb);
-UV_EXTERN int uv_fs_write(uv_loop_t* loop,
-                          uv_fs_t* req,
-                          uv_file file,
-                          const uv_buf_t bufs[],
-                          unsigned int nbufs,
-                          int64_t offset,
-                          uv_fs_cb cb);
-/*
- * This flag can be used with uv_fs_copyfile() to return an error if the
- * destination already exists.
- */
-#define UV_FS_COPYFILE_EXCL   0x0001
-
-/*
- * This flag can be used with uv_fs_copyfile() to attempt to create a reflink.
- * If copy-on-write is not supported, a fallback copy mechanism is used.
- */
-#define UV_FS_COPYFILE_FICLONE 0x0002
-
-/*
- * This flag can be used with uv_fs_copyfile() to attempt to create a reflink.
- * If copy-on-write is not supported, an error is returned.
- */
-#define UV_FS_COPYFILE_FICLONE_FORCE 0x0004
-
-UV_EXTERN int uv_fs_copyfile(uv_loop_t* loop,
-                             uv_fs_t* req,
-                             const char* path,
-                             const char* new_path,
-                             int flags,
-                             uv_fs_cb cb);
-UV_EXTERN int uv_fs_mkdir(uv_loop_t* loop,
-                          uv_fs_t* req,
-                          const char* path,
-                          int mode,
-                          uv_fs_cb cb);
-UV_EXTERN int uv_fs_mkdtemp(uv_loop_t* loop,
-                            uv_fs_t* req,
-                            const char* tpl,
-                            uv_fs_cb cb);
-UV_EXTERN int uv_fs_rmdir(uv_loop_t* loop,
-                          uv_fs_t* req,
-                          const char* path,
-                          uv_fs_cb cb);
-UV_EXTERN int uv_fs_scandir(uv_loop_t* loop,
-                            uv_fs_t* req,
-                            const char* path,
-                            int flags,
-                            uv_fs_cb cb);
-UV_EXTERN int uv_fs_scandir_next(uv_fs_t* req,
-                                 uv_dirent_t* ent);
-UV_EXTERN int uv_fs_opendir(uv_loop_t* loop,
-                            uv_fs_t* req,
-                            const char* path,
-                            uv_fs_cb cb);
-UV_EXTERN int uv_fs_readdir(uv_loop_t* loop,
-                            uv_fs_t* req,
-                            uv_dir_t* dir,
-                            uv_fs_cb cb);
-UV_EXTERN int uv_fs_closedir(uv_loop_t* loop,
-                             uv_fs_t* req,
-                             uv_dir_t* dir,
-                             uv_fs_cb cb);
-UV_EXTERN int uv_fs_stat(uv_loop_t* loop,
-                         uv_fs_t* req,
-                         const char* path,
-                         uv_fs_cb cb);
-UV_EXTERN int uv_fs_fstat(uv_loop_t* loop,
-                          uv_fs_t* req,
-                          uv_file file,
-                          uv_fs_cb cb);
-UV_EXTERN int uv_fs_rename(uv_loop_t* loop,
-                           uv_fs_t* req,
-                           const char* path,
-                           const char* new_path,
-                           uv_fs_cb cb);
-UV_EXTERN int uv_fs_fsync(uv_loop_t* loop,
-                          uv_fs_t* req,
-                          uv_file file,
-                          uv_fs_cb cb);
-UV_EXTERN int uv_fs_fdatasync(uv_loop_t* loop,
-                              uv_fs_t* req,
-                              uv_file file,
-                              uv_fs_cb cb);
-UV_EXTERN int uv_fs_ftruncate(uv_loop_t* loop,
-                              uv_fs_t* req,
-                              uv_file file,
-                              int64_t offset,
-                              uv_fs_cb cb);
-UV_EXTERN int uv_fs_sendfile(uv_loop_t* loop,
-                             uv_fs_t* req,
-                             uv_file out_fd,
-                             uv_file in_fd,
-                             int64_t in_offset,
-                             size_t length,
-                             uv_fs_cb cb);
-UV_EXTERN int uv_fs_access(uv_loop_t* loop,
-                           uv_fs_t* req,
-                           const char* path,
-                           int mode,
-                           uv_fs_cb cb);
-UV_EXTERN int uv_fs_chmod(uv_loop_t* loop,
-                          uv_fs_t* req,
-                          const char* path,
-                          int mode,
-                          uv_fs_cb cb);
-UV_EXTERN int uv_fs_utime(uv_loop_t* loop,
-                          uv_fs_t* req,
-                          const char* path,
-                          double atime,
-                          double mtime,
-                          uv_fs_cb cb);
-UV_EXTERN int uv_fs_futime(uv_loop_t* loop,
-                           uv_fs_t* req,
-                           uv_file file,
-                           double atime,
-                           double mtime,
-                           uv_fs_cb cb);
-UV_EXTERN int uv_fs_lstat(uv_loop_t* loop,
-                          uv_fs_t* req,
-                          const char* path,
-                          uv_fs_cb cb);
-UV_EXTERN int uv_fs_link(uv_loop_t* loop,
-                         uv_fs_t* req,
-                         const char* path,
-                         const char* new_path,
-                         uv_fs_cb cb);
-
-/*
- * This flag can be used with uv_fs_symlink() on Windows to specify whether
- * path argument points to a directory.
- */
-#define UV_FS_SYMLINK_DIR          0x0001
-
-/*
- * This flag can be used with uv_fs_symlink() on Windows to specify whether
- * the symlink is to be created using junction points.
- */
-#define UV_FS_SYMLINK_JUNCTION     0x0002
-
-UV_EXTERN int uv_fs_symlink(uv_loop_t* loop,
-                            uv_fs_t* req,
-                            const char* path,
-                            const char* new_path,
-                            int flags,
-                            uv_fs_cb cb);
-UV_EXTERN int uv_fs_readlink(uv_loop_t* loop,
-                             uv_fs_t* req,
-                             const char* path,
-                             uv_fs_cb cb);
-UV_EXTERN int uv_fs_realpath(uv_loop_t* loop,
-                             uv_fs_t* req,
-                             const char* path,
-                             uv_fs_cb cb);
-UV_EXTERN int uv_fs_fchmod(uv_loop_t* loop,
-                           uv_fs_t* req,
-                           uv_file file,
-                           int mode,
-                           uv_fs_cb cb);
-UV_EXTERN int uv_fs_chown(uv_loop_t* loop,
-                          uv_fs_t* req,
-                          const char* path,
-                          uv_uid_t uid,
-                          uv_gid_t gid,
-                          uv_fs_cb cb);
-UV_EXTERN int uv_fs_fchown(uv_loop_t* loop,
-                           uv_fs_t* req,
-                           uv_file file,
-                           uv_uid_t uid,
-                           uv_gid_t gid,
-                           uv_fs_cb cb);
-UV_EXTERN int uv_fs_lchown(uv_loop_t* loop,
-                           uv_fs_t* req,
-                           const char* path,
-                           uv_uid_t uid,
-                           uv_gid_t gid,
-                           uv_fs_cb cb);
-
-
-enum uv_fs_event {
-  UV_RENAME = 1,
-  UV_CHANGE = 2
-};
-
-
-struct uv_fs_event_s {
-  UV_HANDLE_FIELDS
-  /* private */
-  char* path;
-  UV_FS_EVENT_PRIVATE_FIELDS
-};
-
-
-/*
- * uv_fs_stat() based polling file watcher.
- */
-struct uv_fs_poll_s {
-  UV_HANDLE_FIELDS
-  /* Private, don't touch. */
-  void* poll_ctx;
-};
-
-UV_EXTERN int uv_fs_poll_init(uv_loop_t* loop, uv_fs_poll_t* handle);
-UV_EXTERN int uv_fs_poll_start(uv_fs_poll_t* handle,
-                               uv_fs_poll_cb poll_cb,
-                               const char* path,
-                               unsigned int interval);
-UV_EXTERN int uv_fs_poll_stop(uv_fs_poll_t* handle);
-UV_EXTERN int uv_fs_poll_getpath(uv_fs_poll_t* handle,
-                                 char* buffer,
-                                 size_t* size);
-
-
-struct uv_signal_s {
-  UV_HANDLE_FIELDS
-  uv_signal_cb signal_cb;
-  int signum;
-  UV_SIGNAL_PRIVATE_FIELDS
-};
-
-UV_EXTERN int uv_signal_init(uv_loop_t* loop, uv_signal_t* handle);
-UV_EXTERN int uv_signal_start(uv_signal_t* handle,
-                              uv_signal_cb signal_cb,
-                              int signum);
-UV_EXTERN int uv_signal_start_oneshot(uv_signal_t* handle,
-                                      uv_signal_cb signal_cb,
-                                      int signum);
-UV_EXTERN int uv_signal_stop(uv_signal_t* handle);
-
-UV_EXTERN void uv_loadavg(double avg[3]);
-
-
-/*
- * Flags to be passed to uv_fs_event_start().
- */
-enum uv_fs_event_flags {
-  /*
-   * By default, if the fs event watcher is given a directory name, we will
-   * watch for all events in that directory. This flags overrides this behavior
-   * and makes fs_event report only changes to the directory entry itself. This
-   * flag does not affect individual files watched.
-   * This flag is currently not implemented yet on any backend.
-   */
-  UV_FS_EVENT_WATCH_ENTRY = 1,
-
-  /*
-   * By default uv_fs_event will try to use a kernel interface such as inotify
-   * or kqueue to detect events. This may not work on remote filesystems such
-   * as NFS mounts. This flag makes fs_event fall back to calling stat() on a
-   * regular interval.
-   * This flag is currently not implemented yet on any backend.
-   */
-  UV_FS_EVENT_STAT = 2,
-
-  /*
-   * By default, event watcher, when watching directory, is not registering
-   * (is ignoring) changes in it's subdirectories.
-   * This flag will override this behaviour on platforms that support it.
-   */
-  UV_FS_EVENT_RECURSIVE = 4
-};
-
-
-UV_EXTERN int uv_fs_event_init(uv_loop_t* loop, uv_fs_event_t* handle);
-UV_EXTERN int uv_fs_event_start(uv_fs_event_t* handle,
-                                uv_fs_event_cb cb,
-                                const char* path,
-                                unsigned int flags);
-UV_EXTERN int uv_fs_event_stop(uv_fs_event_t* handle);
-UV_EXTERN int uv_fs_event_getpath(uv_fs_event_t* handle,
-                                  char* buffer,
-                                  size_t* size);
-
-UV_EXTERN int uv_ip4_addr(const char* ip, int port, struct sockaddr_in* addr);
-UV_EXTERN int uv_ip6_addr(const char* ip, int port, struct sockaddr_in6* addr);
-
-UV_EXTERN int uv_ip4_name(const struct sockaddr_in* src, char* dst, size_t size);
-UV_EXTERN int uv_ip6_name(const struct sockaddr_in6* src, char* dst, size_t size);
-
-UV_EXTERN int uv_inet_ntop(int af, const void* src, char* dst, size_t size);
-UV_EXTERN int uv_inet_pton(int af, const char* src, void* dst);
-
-#if defined(IF_NAMESIZE)
-# define UV_IF_NAMESIZE (IF_NAMESIZE + 1)
-#elif defined(IFNAMSIZ)
-# define UV_IF_NAMESIZE (IFNAMSIZ + 1)
-#else
-# define UV_IF_NAMESIZE (16 + 1)
-#endif
-
-UV_EXTERN int uv_if_indextoname(unsigned int ifindex,
-                                char* buffer,
-                                size_t* size);
-UV_EXTERN int uv_if_indextoiid(unsigned int ifindex,
-                               char* buffer,
-                               size_t* size);
-
-UV_EXTERN int uv_exepath(char* buffer, size_t* size);
-
-UV_EXTERN int uv_cwd(char* buffer, size_t* size);
-
-UV_EXTERN int uv_chdir(const char* dir);
-
-UV_EXTERN uint64_t uv_get_free_memory(void);
-UV_EXTERN uint64_t uv_get_total_memory(void);
-UV_EXTERN uint64_t uv_get_constrained_memory(void);
-
-UV_EXTERN uint64_t uv_hrtime(void);
-
-UV_EXTERN void uv_disable_stdio_inheritance(void);
-
-UV_EXTERN int uv_dlopen(const char* filename, uv_lib_t* lib);
-UV_EXTERN void uv_dlclose(uv_lib_t* lib);
-UV_EXTERN int uv_dlsym(uv_lib_t* lib, const char* name, void** ptr);
-UV_EXTERN const char* uv_dlerror(const uv_lib_t* lib);
-
-UV_EXTERN int uv_mutex_init(uv_mutex_t* handle);
-UV_EXTERN int uv_mutex_init_recursive(uv_mutex_t* handle);
-UV_EXTERN void uv_mutex_destroy(uv_mutex_t* handle);
-UV_EXTERN void uv_mutex_lock(uv_mutex_t* handle);
-UV_EXTERN int uv_mutex_trylock(uv_mutex_t* handle);
-UV_EXTERN void uv_mutex_unlock(uv_mutex_t* handle);
-
-UV_EXTERN int uv_rwlock_init(uv_rwlock_t* rwlock);
-UV_EXTERN void uv_rwlock_destroy(uv_rwlock_t* rwlock);
-UV_EXTERN void uv_rwlock_rdlock(uv_rwlock_t* rwlock);
-UV_EXTERN int uv_rwlock_tryrdlock(uv_rwlock_t* rwlock);
-UV_EXTERN void uv_rwlock_rdunlock(uv_rwlock_t* rwlock);
-UV_EXTERN void uv_rwlock_wrlock(uv_rwlock_t* rwlock);
-UV_EXTERN int uv_rwlock_trywrlock(uv_rwlock_t* rwlock);
-UV_EXTERN void uv_rwlock_wrunlock(uv_rwlock_t* rwlock);
-
-UV_EXTERN int uv_sem_init(uv_sem_t* sem, unsigned int value);
-UV_EXTERN void uv_sem_destroy(uv_sem_t* sem);
-UV_EXTERN void uv_sem_post(uv_sem_t* sem);
-UV_EXTERN void uv_sem_wait(uv_sem_t* sem);
-UV_EXTERN int uv_sem_trywait(uv_sem_t* sem);
-
-UV_EXTERN int uv_cond_init(uv_cond_t* cond);
-UV_EXTERN void uv_cond_destroy(uv_cond_t* cond);
-UV_EXTERN void uv_cond_signal(uv_cond_t* cond);
-UV_EXTERN void uv_cond_broadcast(uv_cond_t* cond);
-
-UV_EXTERN int uv_barrier_init(uv_barrier_t* barrier, unsigned int count);
-UV_EXTERN void uv_barrier_destroy(uv_barrier_t* barrier);
-UV_EXTERN int uv_barrier_wait(uv_barrier_t* barrier);
-
-UV_EXTERN void uv_cond_wait(uv_cond_t* cond, uv_mutex_t* mutex);
-UV_EXTERN int uv_cond_timedwait(uv_cond_t* cond,
-                                uv_mutex_t* mutex,
-                                uint64_t timeout);
-
-UV_EXTERN void uv_once(uv_once_t* guard, void (*callback)(void));
-
-UV_EXTERN int uv_key_create(uv_key_t* key);
-UV_EXTERN void uv_key_delete(uv_key_t* key);
-UV_EXTERN void* uv_key_get(uv_key_t* key);
-UV_EXTERN void uv_key_set(uv_key_t* key, void* value);
-
-UV_EXTERN int uv_gettimeofday(uv_timeval64_t* tv);
-
-typedef void (*uv_thread_cb)(void* arg);
-
-UV_EXTERN int uv_thread_create(uv_thread_t* tid, uv_thread_cb entry, void* arg);
-
-typedef enum {
-  UV_THREAD_NO_FLAGS = 0x00,
-  UV_THREAD_HAS_STACK_SIZE = 0x01
-} uv_thread_create_flags;
-
-struct uv_thread_options_s {
-  unsigned int flags;
-  size_t stack_size;
-  /* More fields may be added at any time. */
-};
-
-typedef struct uv_thread_options_s uv_thread_options_t;
-
-UV_EXTERN int uv_thread_create_ex(uv_thread_t* tid,
-                                  const uv_thread_options_t* params,
-                                  uv_thread_cb entry,
-                                  void* arg);
-UV_EXTERN uv_thread_t uv_thread_self(void);
-UV_EXTERN int uv_thread_join(uv_thread_t *tid);
-UV_EXTERN int uv_thread_equal(const uv_thread_t* t1, const uv_thread_t* t2);
-
-/* The presence of these unions force similar struct layout. */
-#define XX(_, name) uv_ ## name ## _t name;
-union uv_any_handle {
-  UV_HANDLE_TYPE_MAP(XX)
-};
-
-union uv_any_req {
-  UV_REQ_TYPE_MAP(XX)
-};
-#undef XX
-
-
-struct uv_loop_s {
-  /* User data - use this for whatever. */
-  void* data;
-  /* Loop reference counting. */
-  unsigned int active_handles;
-  void* handle_queue[2];
-  union {
-    void* unused[2];
-    unsigned int count;
-  } active_reqs;
-  /* Internal flag to signal loop stop. */
-  unsigned int stop_flag;
-  UV_LOOP_PRIVATE_FIELDS
-};
-
-UV_EXTERN void* uv_loop_get_data(const uv_loop_t*);
-UV_EXTERN void uv_loop_set_data(uv_loop_t*, void* data);
-
-/* Don't export the private CPP symbols. */
-#undef UV_HANDLE_TYPE_PRIVATE
-#undef UV_REQ_TYPE_PRIVATE
-#undef UV_REQ_PRIVATE_FIELDS
-#undef UV_STREAM_PRIVATE_FIELDS
-#undef UV_TCP_PRIVATE_FIELDS
-#undef UV_PREPARE_PRIVATE_FIELDS
-#undef UV_CHECK_PRIVATE_FIELDS
-#undef UV_IDLE_PRIVATE_FIELDS
-#undef UV_ASYNC_PRIVATE_FIELDS
-#undef UV_TIMER_PRIVATE_FIELDS
-#undef UV_GETADDRINFO_PRIVATE_FIELDS
-#undef UV_GETNAMEINFO_PRIVATE_FIELDS
-#undef UV_FS_REQ_PRIVATE_FIELDS
-#undef UV_WORK_PRIVATE_FIELDS
-#undef UV_FS_EVENT_PRIVATE_FIELDS
-#undef UV_SIGNAL_PRIVATE_FIELDS
-#undef UV_LOOP_PRIVATE_FIELDS
-#undef UV_LOOP_PRIVATE_PLATFORM_FIELDS
-#undef UV__ERR
-
-#endif /* UV_H */
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/include/uv/android-ifaddrs.h b/third_party/allwpilib/wpiutil/src/main/native/libuv/include/uv/android-ifaddrs.h
deleted file mode 100644
index 9cd19fe..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/include/uv/android-ifaddrs.h
+++ /dev/null
@@ -1,54 +0,0 @@
-/*
- * Copyright (c) 1995, 1999
- *	Berkeley Software Design, Inc.  All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- * 1. Redistributions of source code must retain the above copyright
- *    notice, this list of conditions and the following disclaimer.
- *
- * THIS SOFTWARE IS PROVIDED BY Berkeley Software Design, Inc. ``AS IS'' AND
- * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
- * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
- * ARE DISCLAIMED.  IN NO EVENT SHALL Berkeley Software Design, Inc. BE LIABLE
- * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
- * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
- * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
- * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
- * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
- * SUCH DAMAGE.
- *
- *	BSDI ifaddrs.h,v 2.5 2000/02/23 14:51:59 dab Exp
- */
-
-#ifndef	_IFADDRS_H_
-#define	_IFADDRS_H_
-
-struct ifaddrs {
-	struct ifaddrs  *ifa_next;
-	char		*ifa_name;
-	unsigned int	 ifa_flags;
-	struct sockaddr	*ifa_addr;
-	struct sockaddr	*ifa_netmask;
-	struct sockaddr	*ifa_dstaddr;
-	void		*ifa_data;
-};
-
-/*
- * This may have been defined in <net/if.h>.  Note that if <net/if.h> is
- * to be included it must be included before this header file.
- */
-#ifndef	ifa_broadaddr
-#define	ifa_broadaddr	ifa_dstaddr	/* broadcast address interface */
-#endif
-
-#include <sys/cdefs.h>
-
-__BEGIN_DECLS
-extern int getifaddrs(struct ifaddrs **ifap);
-extern void freeifaddrs(struct ifaddrs *ifa);
-__END_DECLS
-
-#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/include/uv/errno.h b/third_party/allwpilib/wpiutil/src/main/native/libuv/include/uv/errno.h
deleted file mode 100644
index 8eeb95d..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/include/uv/errno.h
+++ /dev/null
@@ -1,443 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#ifndef UV_ERRNO_H_
-#define UV_ERRNO_H_
-
-#include <errno.h>
-#if EDOM > 0
-# define UV__ERR(x) (-(x))
-#else
-# define UV__ERR(x) (x)
-#endif
-
-#define UV__EOF     (-4095)
-#define UV__UNKNOWN (-4094)
-
-#define UV__EAI_ADDRFAMILY  (-3000)
-#define UV__EAI_AGAIN       (-3001)
-#define UV__EAI_BADFLAGS    (-3002)
-#define UV__EAI_CANCELED    (-3003)
-#define UV__EAI_FAIL        (-3004)
-#define UV__EAI_FAMILY      (-3005)
-#define UV__EAI_MEMORY      (-3006)
-#define UV__EAI_NODATA      (-3007)
-#define UV__EAI_NONAME      (-3008)
-#define UV__EAI_OVERFLOW    (-3009)
-#define UV__EAI_SERVICE     (-3010)
-#define UV__EAI_SOCKTYPE    (-3011)
-#define UV__EAI_BADHINTS    (-3013)
-#define UV__EAI_PROTOCOL    (-3014)
-
-/* Only map to the system errno on non-Windows platforms. It's apparently
- * a fairly common practice for Windows programmers to redefine errno codes.
- */
-#if defined(E2BIG) && !defined(_WIN32)
-# define UV__E2BIG UV__ERR(E2BIG)
-#else
-# define UV__E2BIG (-4093)
-#endif
-
-#if defined(EACCES) && !defined(_WIN32)
-# define UV__EACCES UV__ERR(EACCES)
-#else
-# define UV__EACCES (-4092)
-#endif
-
-#if defined(EADDRINUSE) && !defined(_WIN32)
-# define UV__EADDRINUSE UV__ERR(EADDRINUSE)
-#else
-# define UV__EADDRINUSE (-4091)
-#endif
-
-#if defined(EADDRNOTAVAIL) && !defined(_WIN32)
-# define UV__EADDRNOTAVAIL UV__ERR(EADDRNOTAVAIL)
-#else
-# define UV__EADDRNOTAVAIL (-4090)
-#endif
-
-#if defined(EAFNOSUPPORT) && !defined(_WIN32)
-# define UV__EAFNOSUPPORT UV__ERR(EAFNOSUPPORT)
-#else
-# define UV__EAFNOSUPPORT (-4089)
-#endif
-
-#if defined(EAGAIN) && !defined(_WIN32)
-# define UV__EAGAIN UV__ERR(EAGAIN)
-#else
-# define UV__EAGAIN (-4088)
-#endif
-
-#if defined(EALREADY) && !defined(_WIN32)
-# define UV__EALREADY UV__ERR(EALREADY)
-#else
-# define UV__EALREADY (-4084)
-#endif
-
-#if defined(EBADF) && !defined(_WIN32)
-# define UV__EBADF UV__ERR(EBADF)
-#else
-# define UV__EBADF (-4083)
-#endif
-
-#if defined(EBUSY) && !defined(_WIN32)
-# define UV__EBUSY UV__ERR(EBUSY)
-#else
-# define UV__EBUSY (-4082)
-#endif
-
-#if defined(ECANCELED) && !defined(_WIN32)
-# define UV__ECANCELED UV__ERR(ECANCELED)
-#else
-# define UV__ECANCELED (-4081)
-#endif
-
-#if defined(ECHARSET) && !defined(_WIN32)
-# define UV__ECHARSET UV__ERR(ECHARSET)
-#else
-# define UV__ECHARSET (-4080)
-#endif
-
-#if defined(ECONNABORTED) && !defined(_WIN32)
-# define UV__ECONNABORTED UV__ERR(ECONNABORTED)
-#else
-# define UV__ECONNABORTED (-4079)
-#endif
-
-#if defined(ECONNREFUSED) && !defined(_WIN32)
-# define UV__ECONNREFUSED UV__ERR(ECONNREFUSED)
-#else
-# define UV__ECONNREFUSED (-4078)
-#endif
-
-#if defined(ECONNRESET) && !defined(_WIN32)
-# define UV__ECONNRESET UV__ERR(ECONNRESET)
-#else
-# define UV__ECONNRESET (-4077)
-#endif
-
-#if defined(EDESTADDRREQ) && !defined(_WIN32)
-# define UV__EDESTADDRREQ UV__ERR(EDESTADDRREQ)
-#else
-# define UV__EDESTADDRREQ (-4076)
-#endif
-
-#if defined(EEXIST) && !defined(_WIN32)
-# define UV__EEXIST UV__ERR(EEXIST)
-#else
-# define UV__EEXIST (-4075)
-#endif
-
-#if defined(EFAULT) && !defined(_WIN32)
-# define UV__EFAULT UV__ERR(EFAULT)
-#else
-# define UV__EFAULT (-4074)
-#endif
-
-#if defined(EHOSTUNREACH) && !defined(_WIN32)
-# define UV__EHOSTUNREACH UV__ERR(EHOSTUNREACH)
-#else
-# define UV__EHOSTUNREACH (-4073)
-#endif
-
-#if defined(EINTR) && !defined(_WIN32)
-# define UV__EINTR UV__ERR(EINTR)
-#else
-# define UV__EINTR (-4072)
-#endif
-
-#if defined(EINVAL) && !defined(_WIN32)
-# define UV__EINVAL UV__ERR(EINVAL)
-#else
-# define UV__EINVAL (-4071)
-#endif
-
-#if defined(EIO) && !defined(_WIN32)
-# define UV__EIO UV__ERR(EIO)
-#else
-# define UV__EIO (-4070)
-#endif
-
-#if defined(EISCONN) && !defined(_WIN32)
-# define UV__EISCONN UV__ERR(EISCONN)
-#else
-# define UV__EISCONN (-4069)
-#endif
-
-#if defined(EISDIR) && !defined(_WIN32)
-# define UV__EISDIR UV__ERR(EISDIR)
-#else
-# define UV__EISDIR (-4068)
-#endif
-
-#if defined(ELOOP) && !defined(_WIN32)
-# define UV__ELOOP UV__ERR(ELOOP)
-#else
-# define UV__ELOOP (-4067)
-#endif
-
-#if defined(EMFILE) && !defined(_WIN32)
-# define UV__EMFILE UV__ERR(EMFILE)
-#else
-# define UV__EMFILE (-4066)
-#endif
-
-#if defined(EMSGSIZE) && !defined(_WIN32)
-# define UV__EMSGSIZE UV__ERR(EMSGSIZE)
-#else
-# define UV__EMSGSIZE (-4065)
-#endif
-
-#if defined(ENAMETOOLONG) && !defined(_WIN32)
-# define UV__ENAMETOOLONG UV__ERR(ENAMETOOLONG)
-#else
-# define UV__ENAMETOOLONG (-4064)
-#endif
-
-#if defined(ENETDOWN) && !defined(_WIN32)
-# define UV__ENETDOWN UV__ERR(ENETDOWN)
-#else
-# define UV__ENETDOWN (-4063)
-#endif
-
-#if defined(ENETUNREACH) && !defined(_WIN32)
-# define UV__ENETUNREACH UV__ERR(ENETUNREACH)
-#else
-# define UV__ENETUNREACH (-4062)
-#endif
-
-#if defined(ENFILE) && !defined(_WIN32)
-# define UV__ENFILE UV__ERR(ENFILE)
-#else
-# define UV__ENFILE (-4061)
-#endif
-
-#if defined(ENOBUFS) && !defined(_WIN32)
-# define UV__ENOBUFS UV__ERR(ENOBUFS)
-#else
-# define UV__ENOBUFS (-4060)
-#endif
-
-#if defined(ENODEV) && !defined(_WIN32)
-# define UV__ENODEV UV__ERR(ENODEV)
-#else
-# define UV__ENODEV (-4059)
-#endif
-
-#if defined(ENOENT) && !defined(_WIN32)
-# define UV__ENOENT UV__ERR(ENOENT)
-#else
-# define UV__ENOENT (-4058)
-#endif
-
-#if defined(ENOMEM) && !defined(_WIN32)
-# define UV__ENOMEM UV__ERR(ENOMEM)
-#else
-# define UV__ENOMEM (-4057)
-#endif
-
-#if defined(ENONET) && !defined(_WIN32)
-# define UV__ENONET UV__ERR(ENONET)
-#else
-# define UV__ENONET (-4056)
-#endif
-
-#if defined(ENOSPC) && !defined(_WIN32)
-# define UV__ENOSPC UV__ERR(ENOSPC)
-#else
-# define UV__ENOSPC (-4055)
-#endif
-
-#if defined(ENOSYS) && !defined(_WIN32)
-# define UV__ENOSYS UV__ERR(ENOSYS)
-#else
-# define UV__ENOSYS (-4054)
-#endif
-
-#if defined(ENOTCONN) && !defined(_WIN32)
-# define UV__ENOTCONN UV__ERR(ENOTCONN)
-#else
-# define UV__ENOTCONN (-4053)
-#endif
-
-#if defined(ENOTDIR) && !defined(_WIN32)
-# define UV__ENOTDIR UV__ERR(ENOTDIR)
-#else
-# define UV__ENOTDIR (-4052)
-#endif
-
-#if defined(ENOTEMPTY) && !defined(_WIN32)
-# define UV__ENOTEMPTY UV__ERR(ENOTEMPTY)
-#else
-# define UV__ENOTEMPTY (-4051)
-#endif
-
-#if defined(ENOTSOCK) && !defined(_WIN32)
-# define UV__ENOTSOCK UV__ERR(ENOTSOCK)
-#else
-# define UV__ENOTSOCK (-4050)
-#endif
-
-#if defined(ENOTSUP) && !defined(_WIN32)
-# define UV__ENOTSUP UV__ERR(ENOTSUP)
-#else
-# define UV__ENOTSUP (-4049)
-#endif
-
-#if defined(EPERM) && !defined(_WIN32)
-# define UV__EPERM UV__ERR(EPERM)
-#else
-# define UV__EPERM (-4048)
-#endif
-
-#if defined(EPIPE) && !defined(_WIN32)
-# define UV__EPIPE UV__ERR(EPIPE)
-#else
-# define UV__EPIPE (-4047)
-#endif
-
-#if defined(EPROTO) && !defined(_WIN32)
-# define UV__EPROTO UV__ERR(EPROTO)
-#else
-# define UV__EPROTO UV__ERR(4046)
-#endif
-
-#if defined(EPROTONOSUPPORT) && !defined(_WIN32)
-# define UV__EPROTONOSUPPORT UV__ERR(EPROTONOSUPPORT)
-#else
-# define UV__EPROTONOSUPPORT (-4045)
-#endif
-
-#if defined(EPROTOTYPE) && !defined(_WIN32)
-# define UV__EPROTOTYPE UV__ERR(EPROTOTYPE)
-#else
-# define UV__EPROTOTYPE (-4044)
-#endif
-
-#if defined(EROFS) && !defined(_WIN32)
-# define UV__EROFS UV__ERR(EROFS)
-#else
-# define UV__EROFS (-4043)
-#endif
-
-#if defined(ESHUTDOWN) && !defined(_WIN32)
-# define UV__ESHUTDOWN UV__ERR(ESHUTDOWN)
-#else
-# define UV__ESHUTDOWN (-4042)
-#endif
-
-#if defined(ESPIPE) && !defined(_WIN32)
-# define UV__ESPIPE UV__ERR(ESPIPE)
-#else
-# define UV__ESPIPE (-4041)
-#endif
-
-#if defined(ESRCH) && !defined(_WIN32)
-# define UV__ESRCH UV__ERR(ESRCH)
-#else
-# define UV__ESRCH (-4040)
-#endif
-
-#if defined(ETIMEDOUT) && !defined(_WIN32)
-# define UV__ETIMEDOUT UV__ERR(ETIMEDOUT)
-#else
-# define UV__ETIMEDOUT (-4039)
-#endif
-
-#if defined(ETXTBSY) && !defined(_WIN32)
-# define UV__ETXTBSY UV__ERR(ETXTBSY)
-#else
-# define UV__ETXTBSY (-4038)
-#endif
-
-#if defined(EXDEV) && !defined(_WIN32)
-# define UV__EXDEV UV__ERR(EXDEV)
-#else
-# define UV__EXDEV (-4037)
-#endif
-
-#if defined(EFBIG) && !defined(_WIN32)
-# define UV__EFBIG UV__ERR(EFBIG)
-#else
-# define UV__EFBIG (-4036)
-#endif
-
-#if defined(ENOPROTOOPT) && !defined(_WIN32)
-# define UV__ENOPROTOOPT UV__ERR(ENOPROTOOPT)
-#else
-# define UV__ENOPROTOOPT (-4035)
-#endif
-
-#if defined(ERANGE) && !defined(_WIN32)
-# define UV__ERANGE UV__ERR(ERANGE)
-#else
-# define UV__ERANGE (-4034)
-#endif
-
-#if defined(ENXIO) && !defined(_WIN32)
-# define UV__ENXIO UV__ERR(ENXIO)
-#else
-# define UV__ENXIO (-4033)
-#endif
-
-#if defined(EMLINK) && !defined(_WIN32)
-# define UV__EMLINK UV__ERR(EMLINK)
-#else
-# define UV__EMLINK (-4032)
-#endif
-
-/* EHOSTDOWN is not visible on BSD-like systems when _POSIX_C_SOURCE is
- * defined. Fortunately, its value is always 64 so it's possible albeit
- * icky to hard-code it.
- */
-#if defined(EHOSTDOWN) && !defined(_WIN32)
-# define UV__EHOSTDOWN UV__ERR(EHOSTDOWN)
-#elif defined(__APPLE__) || \
-      defined(__DragonFly__) || \
-      defined(__FreeBSD__) || \
-      defined(__FreeBSD_kernel__) || \
-      defined(__NetBSD__) || \
-      defined(__OpenBSD__)
-# define UV__EHOSTDOWN (-64)
-#else
-# define UV__EHOSTDOWN (-4031)
-#endif
-
-#if defined(EREMOTEIO) && !defined(_WIN32)
-# define UV__EREMOTEIO UV__ERR(EREMOTEIO)
-#else
-# define UV__EREMOTEIO (-4030)
-#endif
-
-#if defined(ENOTTY) && !defined(_WIN32)
-# define UV__ENOTTY UV__ERR(ENOTTY)
-#else
-# define UV__ENOTTY (-4029)
-#endif
-
-#if defined(EFTYPE) && !defined(_WIN32)
-# define UV__EFTYPE UV__ERR(EFTYPE)
-#else
-# define UV__EFTYPE (-4028)
-#endif
-
-
-#endif /* UV_ERRNO_H_ */
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/include/uv/tree.h b/third_party/allwpilib/wpiutil/src/main/native/libuv/include/uv/tree.h
deleted file mode 100644
index f936416..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/include/uv/tree.h
+++ /dev/null
@@ -1,768 +0,0 @@
-/*-
- * Copyright 2002 Niels Provos <provos@citi.umich.edu>
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- * 1. Redistributions of source code must retain the above copyright
- *    notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- *    notice, this list of conditions and the following disclaimer in the
- *    documentation and/or other materials provided with the distribution.
- *
- * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR
- * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES
- * OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
- * IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
- * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
- * DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
- * THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
- * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
- * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
- */
-
-#ifndef  UV_TREE_H_
-#define  UV_TREE_H_
-
-#ifndef UV__UNUSED
-# if __GNUC__
-#  define UV__UNUSED __attribute__((unused))
-# else
-#  define UV__UNUSED
-# endif
-#endif
-
-/*
- * This file defines data structures for different types of trees:
- * splay trees and red-black trees.
- *
- * A splay tree is a self-organizing data structure.  Every operation
- * on the tree causes a splay to happen.  The splay moves the requested
- * node to the root of the tree and partly rebalances it.
- *
- * This has the benefit that request locality causes faster lookups as
- * the requested nodes move to the top of the tree.  On the other hand,
- * every lookup causes memory writes.
- *
- * The Balance Theorem bounds the total access time for m operations
- * and n inserts on an initially empty tree as O((m + n)lg n).  The
- * amortized cost for a sequence of m accesses to a splay tree is O(lg n);
- *
- * A red-black tree is a binary search tree with the node color as an
- * extra attribute.  It fulfills a set of conditions:
- *  - every search path from the root to a leaf consists of the
- *    same number of black nodes,
- *  - each red node (except for the root) has a black parent,
- *  - each leaf node is black.
- *
- * Every operation on a red-black tree is bounded as O(lg n).
- * The maximum height of a red-black tree is 2lg (n+1).
- */
-
-#define SPLAY_HEAD(name, type)                                                \
-struct name {                                                                 \
-  struct type *sph_root; /* root of the tree */                               \
-}
-
-#define SPLAY_INITIALIZER(root)                                               \
-  { NULL }
-
-#define SPLAY_INIT(root) do {                                                 \
-  (root)->sph_root = NULL;                                                    \
-} while (/*CONSTCOND*/ 0)
-
-#define SPLAY_ENTRY(type)                                                     \
-struct {                                                                      \
-  struct type *spe_left;          /* left element */                          \
-  struct type *spe_right;         /* right element */                         \
-}
-
-#define SPLAY_LEFT(elm, field)    (elm)->field.spe_left
-#define SPLAY_RIGHT(elm, field)   (elm)->field.spe_right
-#define SPLAY_ROOT(head)          (head)->sph_root
-#define SPLAY_EMPTY(head)         (SPLAY_ROOT(head) == NULL)
-
-/* SPLAY_ROTATE_{LEFT,RIGHT} expect that tmp hold SPLAY_{RIGHT,LEFT} */
-#define SPLAY_ROTATE_RIGHT(head, tmp, field) do {                             \
-  SPLAY_LEFT((head)->sph_root, field) = SPLAY_RIGHT(tmp, field);              \
-  SPLAY_RIGHT(tmp, field) = (head)->sph_root;                                 \
-  (head)->sph_root = tmp;                                                     \
-} while (/*CONSTCOND*/ 0)
-
-#define SPLAY_ROTATE_LEFT(head, tmp, field) do {                              \
-  SPLAY_RIGHT((head)->sph_root, field) = SPLAY_LEFT(tmp, field);              \
-  SPLAY_LEFT(tmp, field) = (head)->sph_root;                                  \
-  (head)->sph_root = tmp;                                                     \
-} while (/*CONSTCOND*/ 0)
-
-#define SPLAY_LINKLEFT(head, tmp, field) do {                                 \
-  SPLAY_LEFT(tmp, field) = (head)->sph_root;                                  \
-  tmp = (head)->sph_root;                                                     \
-  (head)->sph_root = SPLAY_LEFT((head)->sph_root, field);                     \
-} while (/*CONSTCOND*/ 0)
-
-#define SPLAY_LINKRIGHT(head, tmp, field) do {                                \
-  SPLAY_RIGHT(tmp, field) = (head)->sph_root;                                 \
-  tmp = (head)->sph_root;                                                     \
-  (head)->sph_root = SPLAY_RIGHT((head)->sph_root, field);                    \
-} while (/*CONSTCOND*/ 0)
-
-#define SPLAY_ASSEMBLE(head, node, left, right, field) do {                   \
-  SPLAY_RIGHT(left, field) = SPLAY_LEFT((head)->sph_root, field);             \
-  SPLAY_LEFT(right, field) = SPLAY_RIGHT((head)->sph_root, field);            \
-  SPLAY_LEFT((head)->sph_root, field) = SPLAY_RIGHT(node, field);             \
-  SPLAY_RIGHT((head)->sph_root, field) = SPLAY_LEFT(node, field);             \
-} while (/*CONSTCOND*/ 0)
-
-/* Generates prototypes and inline functions */
-
-#define SPLAY_PROTOTYPE(name, type, field, cmp)                               \
-void name##_SPLAY(struct name *, struct type *);                              \
-void name##_SPLAY_MINMAX(struct name *, int);                                 \
-struct type *name##_SPLAY_INSERT(struct name *, struct type *);               \
-struct type *name##_SPLAY_REMOVE(struct name *, struct type *);               \
-                                                                              \
-/* Finds the node with the same key as elm */                                 \
-static __inline struct type *                                                 \
-name##_SPLAY_FIND(struct name *head, struct type *elm)                        \
-{                                                                             \
-  if (SPLAY_EMPTY(head))                                                      \
-    return(NULL);                                                             \
-  name##_SPLAY(head, elm);                                                    \
-  if ((cmp)(elm, (head)->sph_root) == 0)                                      \
-    return (head->sph_root);                                                  \
-  return (NULL);                                                              \
-}                                                                             \
-                                                                              \
-static __inline struct type *                                                 \
-name##_SPLAY_NEXT(struct name *head, struct type *elm)                        \
-{                                                                             \
-  name##_SPLAY(head, elm);                                                    \
-  if (SPLAY_RIGHT(elm, field) != NULL) {                                      \
-    elm = SPLAY_RIGHT(elm, field);                                            \
-    while (SPLAY_LEFT(elm, field) != NULL) {                                  \
-      elm = SPLAY_LEFT(elm, field);                                           \
-    }                                                                         \
-  } else                                                                      \
-    elm = NULL;                                                               \
-  return (elm);                                                               \
-}                                                                             \
-                                                                              \
-static __inline struct type *                                                 \
-name##_SPLAY_MIN_MAX(struct name *head, int val)                              \
-{                                                                             \
-  name##_SPLAY_MINMAX(head, val);                                             \
-  return (SPLAY_ROOT(head));                                                  \
-}
-
-/* Main splay operation.
- * Moves node close to the key of elm to top
- */
-#define SPLAY_GENERATE(name, type, field, cmp)                                \
-struct type *                                                                 \
-name##_SPLAY_INSERT(struct name *head, struct type *elm)                      \
-{                                                                             \
-    if (SPLAY_EMPTY(head)) {                                                  \
-      SPLAY_LEFT(elm, field) = SPLAY_RIGHT(elm, field) = NULL;                \
-    } else {                                                                  \
-      int __comp;                                                             \
-      name##_SPLAY(head, elm);                                                \
-      __comp = (cmp)(elm, (head)->sph_root);                                  \
-      if(__comp < 0) {                                                        \
-        SPLAY_LEFT(elm, field) = SPLAY_LEFT((head)->sph_root, field);         \
-        SPLAY_RIGHT(elm, field) = (head)->sph_root;                           \
-        SPLAY_LEFT((head)->sph_root, field) = NULL;                           \
-      } else if (__comp > 0) {                                                \
-        SPLAY_RIGHT(elm, field) = SPLAY_RIGHT((head)->sph_root, field);       \
-        SPLAY_LEFT(elm, field) = (head)->sph_root;                            \
-        SPLAY_RIGHT((head)->sph_root, field) = NULL;                          \
-      } else                                                                  \
-        return ((head)->sph_root);                                            \
-    }                                                                         \
-    (head)->sph_root = (elm);                                                 \
-    return (NULL);                                                            \
-}                                                                             \
-                                                                              \
-struct type *                                                                 \
-name##_SPLAY_REMOVE(struct name *head, struct type *elm)                      \
-{                                                                             \
-  struct type *__tmp;                                                         \
-  if (SPLAY_EMPTY(head))                                                      \
-    return (NULL);                                                            \
-  name##_SPLAY(head, elm);                                                    \
-  if ((cmp)(elm, (head)->sph_root) == 0) {                                    \
-    if (SPLAY_LEFT((head)->sph_root, field) == NULL) {                        \
-      (head)->sph_root = SPLAY_RIGHT((head)->sph_root, field);                \
-    } else {                                                                  \
-      __tmp = SPLAY_RIGHT((head)->sph_root, field);                           \
-      (head)->sph_root = SPLAY_LEFT((head)->sph_root, field);                 \
-      name##_SPLAY(head, elm);                                                \
-      SPLAY_RIGHT((head)->sph_root, field) = __tmp;                           \
-    }                                                                         \
-    return (elm);                                                             \
-  }                                                                           \
-  return (NULL);                                                              \
-}                                                                             \
-                                                                              \
-void                                                                          \
-name##_SPLAY(struct name *head, struct type *elm)                             \
-{                                                                             \
-  struct type __node, *__left, *__right, *__tmp;                              \
-  int __comp;                                                                 \
-                                                                              \
-  SPLAY_LEFT(&__node, field) = SPLAY_RIGHT(&__node, field) = NULL;            \
-  __left = __right = &__node;                                                 \
-                                                                              \
-  while ((__comp = (cmp)(elm, (head)->sph_root)) != 0) {                      \
-    if (__comp < 0) {                                                         \
-      __tmp = SPLAY_LEFT((head)->sph_root, field);                            \
-      if (__tmp == NULL)                                                      \
-        break;                                                                \
-      if ((cmp)(elm, __tmp) < 0){                                             \
-        SPLAY_ROTATE_RIGHT(head, __tmp, field);                               \
-        if (SPLAY_LEFT((head)->sph_root, field) == NULL)                      \
-          break;                                                              \
-      }                                                                       \
-      SPLAY_LINKLEFT(head, __right, field);                                   \
-    } else if (__comp > 0) {                                                  \
-      __tmp = SPLAY_RIGHT((head)->sph_root, field);                           \
-      if (__tmp == NULL)                                                      \
-        break;                                                                \
-      if ((cmp)(elm, __tmp) > 0){                                             \
-        SPLAY_ROTATE_LEFT(head, __tmp, field);                                \
-        if (SPLAY_RIGHT((head)->sph_root, field) == NULL)                     \
-          break;                                                              \
-      }                                                                       \
-      SPLAY_LINKRIGHT(head, __left, field);                                   \
-    }                                                                         \
-  }                                                                           \
-  SPLAY_ASSEMBLE(head, &__node, __left, __right, field);                      \
-}                                                                             \
-                                                                              \
-/* Splay with either the minimum or the maximum element                       \
- * Used to find minimum or maximum element in tree.                           \
- */                                                                           \
-void name##_SPLAY_MINMAX(struct name *head, int __comp)                       \
-{                                                                             \
-  struct type __node, *__left, *__right, *__tmp;                              \
-                                                                              \
-  SPLAY_LEFT(&__node, field) = SPLAY_RIGHT(&__node, field) = NULL;            \
-  __left = __right = &__node;                                                 \
-                                                                              \
-  while (1) {                                                                 \
-    if (__comp < 0) {                                                         \
-      __tmp = SPLAY_LEFT((head)->sph_root, field);                            \
-      if (__tmp == NULL)                                                      \
-        break;                                                                \
-      if (__comp < 0){                                                        \
-        SPLAY_ROTATE_RIGHT(head, __tmp, field);                               \
-        if (SPLAY_LEFT((head)->sph_root, field) == NULL)                      \
-          break;                                                              \
-      }                                                                       \
-      SPLAY_LINKLEFT(head, __right, field);                                   \
-    } else if (__comp > 0) {                                                  \
-      __tmp = SPLAY_RIGHT((head)->sph_root, field);                           \
-      if (__tmp == NULL)                                                      \
-        break;                                                                \
-      if (__comp > 0) {                                                       \
-        SPLAY_ROTATE_LEFT(head, __tmp, field);                                \
-        if (SPLAY_RIGHT((head)->sph_root, field) == NULL)                     \
-          break;                                                              \
-      }                                                                       \
-      SPLAY_LINKRIGHT(head, __left, field);                                   \
-    }                                                                         \
-  }                                                                           \
-  SPLAY_ASSEMBLE(head, &__node, __left, __right, field);                      \
-}
-
-#define SPLAY_NEGINF  -1
-#define SPLAY_INF     1
-
-#define SPLAY_INSERT(name, x, y)  name##_SPLAY_INSERT(x, y)
-#define SPLAY_REMOVE(name, x, y)  name##_SPLAY_REMOVE(x, y)
-#define SPLAY_FIND(name, x, y)    name##_SPLAY_FIND(x, y)
-#define SPLAY_NEXT(name, x, y)    name##_SPLAY_NEXT(x, y)
-#define SPLAY_MIN(name, x)        (SPLAY_EMPTY(x) ? NULL                      \
-                                  : name##_SPLAY_MIN_MAX(x, SPLAY_NEGINF))
-#define SPLAY_MAX(name, x)        (SPLAY_EMPTY(x) ? NULL                      \
-                                  : name##_SPLAY_MIN_MAX(x, SPLAY_INF))
-
-#define SPLAY_FOREACH(x, name, head)                                          \
-  for ((x) = SPLAY_MIN(name, head);                                           \
-       (x) != NULL;                                                           \
-       (x) = SPLAY_NEXT(name, head, x))
-
-/* Macros that define a red-black tree */
-#define RB_HEAD(name, type)                                                   \
-struct name {                                                                 \
-  struct type *rbh_root; /* root of the tree */                               \
-}
-
-#define RB_INITIALIZER(root)                                                  \
-  { NULL }
-
-#define RB_INIT(root) do {                                                    \
-  (root)->rbh_root = NULL;                                                    \
-} while (/*CONSTCOND*/ 0)
-
-#define RB_BLACK  0
-#define RB_RED    1
-#define RB_ENTRY(type)                                                        \
-struct {                                                                      \
-  struct type *rbe_left;        /* left element */                            \
-  struct type *rbe_right;       /* right element */                           \
-  struct type *rbe_parent;      /* parent element */                          \
-  int rbe_color;                /* node color */                              \
-}
-
-#define RB_LEFT(elm, field)     (elm)->field.rbe_left
-#define RB_RIGHT(elm, field)    (elm)->field.rbe_right
-#define RB_PARENT(elm, field)   (elm)->field.rbe_parent
-#define RB_COLOR(elm, field)    (elm)->field.rbe_color
-#define RB_ROOT(head)           (head)->rbh_root
-#define RB_EMPTY(head)          (RB_ROOT(head) == NULL)
-
-#define RB_SET(elm, parent, field) do {                                       \
-  RB_PARENT(elm, field) = parent;                                             \
-  RB_LEFT(elm, field) = RB_RIGHT(elm, field) = NULL;                          \
-  RB_COLOR(elm, field) = RB_RED;                                              \
-} while (/*CONSTCOND*/ 0)
-
-#define RB_SET_BLACKRED(black, red, field) do {                               \
-  RB_COLOR(black, field) = RB_BLACK;                                          \
-  RB_COLOR(red, field) = RB_RED;                                              \
-} while (/*CONSTCOND*/ 0)
-
-#ifndef RB_AUGMENT
-#define RB_AUGMENT(x)  do {} while (0)
-#endif
-
-#define RB_ROTATE_LEFT(head, elm, tmp, field) do {                            \
-  (tmp) = RB_RIGHT(elm, field);                                               \
-  if ((RB_RIGHT(elm, field) = RB_LEFT(tmp, field)) != NULL) {                 \
-    RB_PARENT(RB_LEFT(tmp, field), field) = (elm);                            \
-  }                                                                           \
-  RB_AUGMENT(elm);                                                            \
-  if ((RB_PARENT(tmp, field) = RB_PARENT(elm, field)) != NULL) {              \
-    if ((elm) == RB_LEFT(RB_PARENT(elm, field), field))                       \
-      RB_LEFT(RB_PARENT(elm, field), field) = (tmp);                          \
-    else                                                                      \
-      RB_RIGHT(RB_PARENT(elm, field), field) = (tmp);                         \
-  } else                                                                      \
-    (head)->rbh_root = (tmp);                                                 \
-  RB_LEFT(tmp, field) = (elm);                                                \
-  RB_PARENT(elm, field) = (tmp);                                              \
-  RB_AUGMENT(tmp);                                                            \
-  if ((RB_PARENT(tmp, field)))                                                \
-    RB_AUGMENT(RB_PARENT(tmp, field));                                        \
-} while (/*CONSTCOND*/ 0)
-
-#define RB_ROTATE_RIGHT(head, elm, tmp, field) do {                           \
-  (tmp) = RB_LEFT(elm, field);                                                \
-  if ((RB_LEFT(elm, field) = RB_RIGHT(tmp, field)) != NULL) {                 \
-    RB_PARENT(RB_RIGHT(tmp, field), field) = (elm);                           \
-  }                                                                           \
-  RB_AUGMENT(elm);                                                            \
-  if ((RB_PARENT(tmp, field) = RB_PARENT(elm, field)) != NULL) {              \
-    if ((elm) == RB_LEFT(RB_PARENT(elm, field), field))                       \
-      RB_LEFT(RB_PARENT(elm, field), field) = (tmp);                          \
-    else                                                                      \
-      RB_RIGHT(RB_PARENT(elm, field), field) = (tmp);                         \
-  } else                                                                      \
-    (head)->rbh_root = (tmp);                                                 \
-  RB_RIGHT(tmp, field) = (elm);                                               \
-  RB_PARENT(elm, field) = (tmp);                                              \
-  RB_AUGMENT(tmp);                                                            \
-  if ((RB_PARENT(tmp, field)))                                                \
-    RB_AUGMENT(RB_PARENT(tmp, field));                                        \
-} while (/*CONSTCOND*/ 0)
-
-/* Generates prototypes and inline functions */
-#define  RB_PROTOTYPE(name, type, field, cmp)                                 \
-  RB_PROTOTYPE_INTERNAL(name, type, field, cmp,)
-#define  RB_PROTOTYPE_STATIC(name, type, field, cmp)                          \
-  RB_PROTOTYPE_INTERNAL(name, type, field, cmp, UV__UNUSED static)
-#define RB_PROTOTYPE_INTERNAL(name, type, field, cmp, attr)                   \
-attr void name##_RB_INSERT_COLOR(struct name *, struct type *);               \
-attr void name##_RB_REMOVE_COLOR(struct name *, struct type *, struct type *);\
-attr struct type *name##_RB_REMOVE(struct name *, struct type *);             \
-attr struct type *name##_RB_INSERT(struct name *, struct type *);             \
-attr struct type *name##_RB_FIND(struct name *, struct type *);               \
-attr struct type *name##_RB_NFIND(struct name *, struct type *);              \
-attr struct type *name##_RB_NEXT(struct type *);                              \
-attr struct type *name##_RB_PREV(struct type *);                              \
-attr struct type *name##_RB_MINMAX(struct name *, int);                       \
-                                                                              \
-
-/* Main rb operation.
- * Moves node close to the key of elm to top
- */
-#define  RB_GENERATE(name, type, field, cmp)                                  \
-  RB_GENERATE_INTERNAL(name, type, field, cmp,)
-#define  RB_GENERATE_STATIC(name, type, field, cmp)                           \
-  RB_GENERATE_INTERNAL(name, type, field, cmp, UV__UNUSED static)
-#define RB_GENERATE_INTERNAL(name, type, field, cmp, attr)                    \
-attr void                                                                     \
-name##_RB_INSERT_COLOR(struct name *head, struct type *elm)                   \
-{                                                                             \
-  struct type *parent, *gparent, *tmp;                                        \
-  while ((parent = RB_PARENT(elm, field)) != NULL &&                          \
-      RB_COLOR(parent, field) == RB_RED) {                                    \
-    gparent = RB_PARENT(parent, field);                                       \
-    if (parent == RB_LEFT(gparent, field)) {                                  \
-      tmp = RB_RIGHT(gparent, field);                                         \
-      if (tmp && RB_COLOR(tmp, field) == RB_RED) {                            \
-        RB_COLOR(tmp, field) = RB_BLACK;                                      \
-        RB_SET_BLACKRED(parent, gparent, field);                              \
-        elm = gparent;                                                        \
-        continue;                                                             \
-      }                                                                       \
-      if (RB_RIGHT(parent, field) == elm) {                                   \
-        RB_ROTATE_LEFT(head, parent, tmp, field);                             \
-        tmp = parent;                                                         \
-        parent = elm;                                                         \
-        elm = tmp;                                                            \
-      }                                                                       \
-      RB_SET_BLACKRED(parent, gparent, field);                                \
-      RB_ROTATE_RIGHT(head, gparent, tmp, field);                             \
-    } else {                                                                  \
-      tmp = RB_LEFT(gparent, field);                                          \
-      if (tmp && RB_COLOR(tmp, field) == RB_RED) {                            \
-        RB_COLOR(tmp, field) = RB_BLACK;                                      \
-        RB_SET_BLACKRED(parent, gparent, field);                              \
-        elm = gparent;                                                        \
-        continue;                                                             \
-      }                                                                       \
-      if (RB_LEFT(parent, field) == elm) {                                    \
-        RB_ROTATE_RIGHT(head, parent, tmp, field);                            \
-        tmp = parent;                                                         \
-        parent = elm;                                                         \
-        elm = tmp;                                                            \
-      }                                                                       \
-      RB_SET_BLACKRED(parent, gparent, field);                                \
-      RB_ROTATE_LEFT(head, gparent, tmp, field);                              \
-    }                                                                         \
-  }                                                                           \
-  RB_COLOR(head->rbh_root, field) = RB_BLACK;                                 \
-}                                                                             \
-                                                                              \
-attr void                                                                     \
-name##_RB_REMOVE_COLOR(struct name *head, struct type *parent,                \
-    struct type *elm)                                                         \
-{                                                                             \
-  struct type *tmp;                                                           \
-  while ((elm == NULL || RB_COLOR(elm, field) == RB_BLACK) &&                 \
-      elm != RB_ROOT(head)) {                                                 \
-    if (RB_LEFT(parent, field) == elm) {                                      \
-      tmp = RB_RIGHT(parent, field);                                          \
-      if (RB_COLOR(tmp, field) == RB_RED) {                                   \
-        RB_SET_BLACKRED(tmp, parent, field);                                  \
-        RB_ROTATE_LEFT(head, parent, tmp, field);                             \
-        tmp = RB_RIGHT(parent, field);                                        \
-      }                                                                       \
-      if ((RB_LEFT(tmp, field) == NULL ||                                     \
-          RB_COLOR(RB_LEFT(tmp, field), field) == RB_BLACK) &&                \
-          (RB_RIGHT(tmp, field) == NULL ||                                    \
-          RB_COLOR(RB_RIGHT(tmp, field), field) == RB_BLACK)) {               \
-        RB_COLOR(tmp, field) = RB_RED;                                        \
-        elm = parent;                                                         \
-        parent = RB_PARENT(elm, field);                                       \
-      } else {                                                                \
-        if (RB_RIGHT(tmp, field) == NULL ||                                   \
-            RB_COLOR(RB_RIGHT(tmp, field), field) == RB_BLACK) {              \
-          struct type *oleft;                                                 \
-          if ((oleft = RB_LEFT(tmp, field))                                   \
-              != NULL)                                                        \
-            RB_COLOR(oleft, field) = RB_BLACK;                                \
-          RB_COLOR(tmp, field) = RB_RED;                                      \
-          RB_ROTATE_RIGHT(head, tmp, oleft, field);                           \
-          tmp = RB_RIGHT(parent, field);                                      \
-        }                                                                     \
-        RB_COLOR(tmp, field) = RB_COLOR(parent, field);                       \
-        RB_COLOR(parent, field) = RB_BLACK;                                   \
-        if (RB_RIGHT(tmp, field))                                             \
-          RB_COLOR(RB_RIGHT(tmp, field), field) = RB_BLACK;                   \
-        RB_ROTATE_LEFT(head, parent, tmp, field);                             \
-        elm = RB_ROOT(head);                                                  \
-        break;                                                                \
-      }                                                                       \
-    } else {                                                                  \
-      tmp = RB_LEFT(parent, field);                                           \
-      if (RB_COLOR(tmp, field) == RB_RED) {                                   \
-        RB_SET_BLACKRED(tmp, parent, field);                                  \
-        RB_ROTATE_RIGHT(head, parent, tmp, field);                            \
-        tmp = RB_LEFT(parent, field);                                         \
-      }                                                                       \
-      if ((RB_LEFT(tmp, field) == NULL ||                                     \
-          RB_COLOR(RB_LEFT(tmp, field), field) == RB_BLACK) &&                \
-          (RB_RIGHT(tmp, field) == NULL ||                                    \
-          RB_COLOR(RB_RIGHT(tmp, field), field) == RB_BLACK)) {               \
-        RB_COLOR(tmp, field) = RB_RED;                                        \
-        elm = parent;                                                         \
-        parent = RB_PARENT(elm, field);                                       \
-      } else {                                                                \
-        if (RB_LEFT(tmp, field) == NULL ||                                    \
-            RB_COLOR(RB_LEFT(tmp, field), field) == RB_BLACK) {               \
-          struct type *oright;                                                \
-          if ((oright = RB_RIGHT(tmp, field))                                 \
-              != NULL)                                                        \
-            RB_COLOR(oright, field) = RB_BLACK;                               \
-          RB_COLOR(tmp, field) = RB_RED;                                      \
-          RB_ROTATE_LEFT(head, tmp, oright, field);                           \
-          tmp = RB_LEFT(parent, field);                                       \
-        }                                                                     \
-        RB_COLOR(tmp, field) = RB_COLOR(parent, field);                       \
-        RB_COLOR(parent, field) = RB_BLACK;                                   \
-        if (RB_LEFT(tmp, field))                                              \
-          RB_COLOR(RB_LEFT(tmp, field), field) = RB_BLACK;                    \
-        RB_ROTATE_RIGHT(head, parent, tmp, field);                            \
-        elm = RB_ROOT(head);                                                  \
-        break;                                                                \
-      }                                                                       \
-    }                                                                         \
-  }                                                                           \
-  if (elm)                                                                    \
-    RB_COLOR(elm, field) = RB_BLACK;                                          \
-}                                                                             \
-                                                                              \
-attr struct type *                                                            \
-name##_RB_REMOVE(struct name *head, struct type *elm)                         \
-{                                                                             \
-  struct type *child, *parent, *old = elm;                                    \
-  int color;                                                                  \
-  if (RB_LEFT(elm, field) == NULL)                                            \
-    child = RB_RIGHT(elm, field);                                             \
-  else if (RB_RIGHT(elm, field) == NULL)                                      \
-    child = RB_LEFT(elm, field);                                              \
-  else {                                                                      \
-    struct type *left;                                                        \
-    elm = RB_RIGHT(elm, field);                                               \
-    while ((left = RB_LEFT(elm, field)) != NULL)                              \
-      elm = left;                                                             \
-    child = RB_RIGHT(elm, field);                                             \
-    parent = RB_PARENT(elm, field);                                           \
-    color = RB_COLOR(elm, field);                                             \
-    if (child)                                                                \
-      RB_PARENT(child, field) = parent;                                       \
-    if (parent) {                                                             \
-      if (RB_LEFT(parent, field) == elm)                                      \
-        RB_LEFT(parent, field) = child;                                       \
-      else                                                                    \
-        RB_RIGHT(parent, field) = child;                                      \
-      RB_AUGMENT(parent);                                                     \
-    } else                                                                    \
-      RB_ROOT(head) = child;                                                  \
-    if (RB_PARENT(elm, field) == old)                                         \
-      parent = elm;                                                           \
-    (elm)->field = (old)->field;                                              \
-    if (RB_PARENT(old, field)) {                                              \
-      if (RB_LEFT(RB_PARENT(old, field), field) == old)                       \
-        RB_LEFT(RB_PARENT(old, field), field) = elm;                          \
-      else                                                                    \
-        RB_RIGHT(RB_PARENT(old, field), field) = elm;                         \
-      RB_AUGMENT(RB_PARENT(old, field));                                      \
-    } else                                                                    \
-      RB_ROOT(head) = elm;                                                    \
-    RB_PARENT(RB_LEFT(old, field), field) = elm;                              \
-    if (RB_RIGHT(old, field))                                                 \
-      RB_PARENT(RB_RIGHT(old, field), field) = elm;                           \
-    if (parent) {                                                             \
-      left = parent;                                                          \
-      do {                                                                    \
-        RB_AUGMENT(left);                                                     \
-      } while ((left = RB_PARENT(left, field)) != NULL);                      \
-    }                                                                         \
-    goto color;                                                               \
-  }                                                                           \
-  parent = RB_PARENT(elm, field);                                             \
-  color = RB_COLOR(elm, field);                                               \
-  if (child)                                                                  \
-    RB_PARENT(child, field) = parent;                                         \
-  if (parent) {                                                               \
-    if (RB_LEFT(parent, field) == elm)                                        \
-      RB_LEFT(parent, field) = child;                                         \
-    else                                                                      \
-      RB_RIGHT(parent, field) = child;                                        \
-    RB_AUGMENT(parent);                                                       \
-  } else                                                                      \
-    RB_ROOT(head) = child;                                                    \
-color:                                                                        \
-  if (color == RB_BLACK)                                                      \
-    name##_RB_REMOVE_COLOR(head, parent, child);                              \
-  return (old);                                                               \
-}                                                                             \
-                                                                              \
-/* Inserts a node into the RB tree */                                         \
-attr struct type *                                                            \
-name##_RB_INSERT(struct name *head, struct type *elm)                         \
-{                                                                             \
-  struct type *tmp;                                                           \
-  struct type *parent = NULL;                                                 \
-  int comp = 0;                                                               \
-  tmp = RB_ROOT(head);                                                        \
-  while (tmp) {                                                               \
-    parent = tmp;                                                             \
-    comp = (cmp)(elm, parent);                                                \
-    if (comp < 0)                                                             \
-      tmp = RB_LEFT(tmp, field);                                              \
-    else if (comp > 0)                                                        \
-      tmp = RB_RIGHT(tmp, field);                                             \
-    else                                                                      \
-      return (tmp);                                                           \
-  }                                                                           \
-  RB_SET(elm, parent, field);                                                 \
-  if (parent != NULL) {                                                       \
-    if (comp < 0)                                                             \
-      RB_LEFT(parent, field) = elm;                                           \
-    else                                                                      \
-      RB_RIGHT(parent, field) = elm;                                          \
-    RB_AUGMENT(parent);                                                       \
-  } else                                                                      \
-    RB_ROOT(head) = elm;                                                      \
-  name##_RB_INSERT_COLOR(head, elm);                                          \
-  return (NULL);                                                              \
-}                                                                             \
-                                                                              \
-/* Finds the node with the same key as elm */                                 \
-attr struct type *                                                            \
-name##_RB_FIND(struct name *head, struct type *elm)                           \
-{                                                                             \
-  struct type *tmp = RB_ROOT(head);                                           \
-  int comp;                                                                   \
-  while (tmp) {                                                               \
-    comp = cmp(elm, tmp);                                                     \
-    if (comp < 0)                                                             \
-      tmp = RB_LEFT(tmp, field);                                              \
-    else if (comp > 0)                                                        \
-      tmp = RB_RIGHT(tmp, field);                                             \
-    else                                                                      \
-      return (tmp);                                                           \
-  }                                                                           \
-  return (NULL);                                                              \
-}                                                                             \
-                                                                              \
-/* Finds the first node greater than or equal to the search key */            \
-attr struct type *                                                            \
-name##_RB_NFIND(struct name *head, struct type *elm)                          \
-{                                                                             \
-  struct type *tmp = RB_ROOT(head);                                           \
-  struct type *res = NULL;                                                    \
-  int comp;                                                                   \
-  while (tmp) {                                                               \
-    comp = cmp(elm, tmp);                                                     \
-    if (comp < 0) {                                                           \
-      res = tmp;                                                              \
-      tmp = RB_LEFT(tmp, field);                                              \
-    }                                                                         \
-    else if (comp > 0)                                                        \
-      tmp = RB_RIGHT(tmp, field);                                             \
-    else                                                                      \
-      return (tmp);                                                           \
-  }                                                                           \
-  return (res);                                                               \
-}                                                                             \
-                                                                              \
-/* ARGSUSED */                                                                \
-attr struct type *                                                            \
-name##_RB_NEXT(struct type *elm)                                              \
-{                                                                             \
-  if (RB_RIGHT(elm, field)) {                                                 \
-    elm = RB_RIGHT(elm, field);                                               \
-    while (RB_LEFT(elm, field))                                               \
-      elm = RB_LEFT(elm, field);                                              \
-  } else {                                                                    \
-    if (RB_PARENT(elm, field) &&                                              \
-        (elm == RB_LEFT(RB_PARENT(elm, field), field)))                       \
-      elm = RB_PARENT(elm, field);                                            \
-    else {                                                                    \
-      while (RB_PARENT(elm, field) &&                                         \
-          (elm == RB_RIGHT(RB_PARENT(elm, field), field)))                    \
-        elm = RB_PARENT(elm, field);                                          \
-      elm = RB_PARENT(elm, field);                                            \
-    }                                                                         \
-  }                                                                           \
-  return (elm);                                                               \
-}                                                                             \
-                                                                              \
-/* ARGSUSED */                                                                \
-attr struct type *                                                            \
-name##_RB_PREV(struct type *elm)                                              \
-{                                                                             \
-  if (RB_LEFT(elm, field)) {                                                  \
-    elm = RB_LEFT(elm, field);                                                \
-    while (RB_RIGHT(elm, field))                                              \
-      elm = RB_RIGHT(elm, field);                                             \
-  } else {                                                                    \
-    if (RB_PARENT(elm, field) &&                                              \
-        (elm == RB_RIGHT(RB_PARENT(elm, field), field)))                      \
-      elm = RB_PARENT(elm, field);                                            \
-    else {                                                                    \
-      while (RB_PARENT(elm, field) &&                                         \
-          (elm == RB_LEFT(RB_PARENT(elm, field), field)))                     \
-        elm = RB_PARENT(elm, field);                                          \
-      elm = RB_PARENT(elm, field);                                            \
-    }                                                                         \
-  }                                                                           \
-  return (elm);                                                               \
-}                                                                             \
-                                                                              \
-attr struct type *                                                            \
-name##_RB_MINMAX(struct name *head, int val)                                  \
-{                                                                             \
-  struct type *tmp = RB_ROOT(head);                                           \
-  struct type *parent = NULL;                                                 \
-  while (tmp) {                                                               \
-    parent = tmp;                                                             \
-    if (val < 0)                                                              \
-      tmp = RB_LEFT(tmp, field);                                              \
-    else                                                                      \
-      tmp = RB_RIGHT(tmp, field);                                             \
-  }                                                                           \
-  return (parent);                                                            \
-}
-
-#define RB_NEGINF   -1
-#define RB_INF      1
-
-#define RB_INSERT(name, x, y)   name##_RB_INSERT(x, y)
-#define RB_REMOVE(name, x, y)   name##_RB_REMOVE(x, y)
-#define RB_FIND(name, x, y)     name##_RB_FIND(x, y)
-#define RB_NFIND(name, x, y)    name##_RB_NFIND(x, y)
-#define RB_NEXT(name, x, y)     name##_RB_NEXT(y)
-#define RB_PREV(name, x, y)     name##_RB_PREV(y)
-#define RB_MIN(name, x)         name##_RB_MINMAX(x, RB_NEGINF)
-#define RB_MAX(name, x)         name##_RB_MINMAX(x, RB_INF)
-
-#define RB_FOREACH(x, name, head)                                             \
-  for ((x) = RB_MIN(name, head);                                              \
-       (x) != NULL;                                                           \
-       (x) = name##_RB_NEXT(x))
-
-#define RB_FOREACH_FROM(x, name, y)                                           \
-  for ((x) = (y);                                                             \
-      ((x) != NULL) && ((y) = name##_RB_NEXT(x), (x) != NULL);                \
-       (x) = (y))
-
-#define RB_FOREACH_SAFE(x, name, head, y)                                     \
-  for ((x) = RB_MIN(name, head);                                              \
-      ((x) != NULL) && ((y) = name##_RB_NEXT(x), (x) != NULL);                \
-       (x) = (y))
-
-#define RB_FOREACH_REVERSE(x, name, head)                                     \
-  for ((x) = RB_MAX(name, head);                                              \
-       (x) != NULL;                                                           \
-       (x) = name##_RB_PREV(x))
-
-#define RB_FOREACH_REVERSE_FROM(x, name, y)                                   \
-  for ((x) = (y);                                                             \
-      ((x) != NULL) && ((y) = name##_RB_PREV(x), (x) != NULL);                \
-       (x) = (y))
-
-#define RB_FOREACH_REVERSE_SAFE(x, name, head, y)                             \
-  for ((x) = RB_MAX(name, head);                                              \
-      ((x) != NULL) && ((y) = name##_RB_PREV(x), (x) != NULL);                \
-       (x) = (y))
-
-#endif  /* UV_TREE_H_ */
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/include/uv/unix.h b/third_party/allwpilib/wpiutil/src/main/native/libuv/include/uv/unix.h
deleted file mode 100644
index 504bab7..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/include/uv/unix.h
+++ /dev/null
@@ -1,483 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#ifndef UV_UNIX_H
-#define UV_UNIX_H
-
-#include <sys/types.h>
-#include <sys/stat.h>
-#include <fcntl.h>
-#include <dirent.h>
-
-#include <sys/socket.h>
-#include <netinet/in.h>
-#include <netinet/tcp.h>
-#include <arpa/inet.h>
-#include <netdb.h>  /* MAXHOSTNAMELEN on Solaris */
-
-#include <termios.h>
-#include <pwd.h>
-
-#if !defined(__MVS__)
-#include <semaphore.h>
-#include <sys/param.h> /* MAXHOSTNAMELEN on Linux and the BSDs */
-#endif
-#include <pthread.h>
-#include <signal.h>
-
-#include "uv/threadpool.h"
-
-#if defined(__linux__)
-# include "uv/linux.h"
-#elif defined(__APPLE__)
-# include "uv/darwin.h"
-#elif defined(__DragonFly__)       || \
-      defined(__FreeBSD__)         || \
-      defined(__FreeBSD_kernel__)  || \
-      defined(__OpenBSD__)         || \
-      defined(__NetBSD__)
-# include "uv/bsd.h"
-#elif defined(__PASE__)   || \
-      defined(__CYGWIN__) || \
-      defined(__MSYS__)   || \
-      defined(__GNU__)
-# include "uv/posix.h"
-#elif defined(__HAIKU__)
-# include "uv/posix.h"
-#endif
-
-#ifndef NI_MAXHOST
-# define NI_MAXHOST 1025
-#endif
-
-#ifndef NI_MAXSERV
-# define NI_MAXSERV 32
-#endif
-
-#ifndef UV_IO_PRIVATE_PLATFORM_FIELDS
-# define UV_IO_PRIVATE_PLATFORM_FIELDS /* empty */
-#endif
-
-struct uv__io_s;
-struct uv_loop_s;
-
-typedef void (*uv__io_cb)(struct uv_loop_s* loop,
-                          struct uv__io_s* w,
-                          unsigned int events);
-typedef struct uv__io_s uv__io_t;
-
-struct uv__io_s {
-  uv__io_cb cb;
-  void* pending_queue[2];
-  void* watcher_queue[2];
-  unsigned int pevents; /* Pending event mask i.e. mask at next tick. */
-  unsigned int events;  /* Current event mask. */
-  int fd;
-  UV_IO_PRIVATE_PLATFORM_FIELDS
-};
-
-#ifndef UV_PLATFORM_SEM_T
-# define UV_PLATFORM_SEM_T sem_t
-#endif
-
-#ifndef UV_PLATFORM_LOOP_FIELDS
-# define UV_PLATFORM_LOOP_FIELDS /* empty */
-#endif
-
-#ifndef UV_PLATFORM_FS_EVENT_FIELDS
-# define UV_PLATFORM_FS_EVENT_FIELDS /* empty */
-#endif
-
-#ifndef UV_STREAM_PRIVATE_PLATFORM_FIELDS
-# define UV_STREAM_PRIVATE_PLATFORM_FIELDS /* empty */
-#endif
-
-/* Note: May be cast to struct iovec. See writev(2). */
-typedef struct uv_buf_t {
-  char* base;
-  size_t len;
-} uv_buf_t;
-
-typedef int uv_file;
-typedef int uv_os_sock_t;
-typedef int uv_os_fd_t;
-typedef pid_t uv_pid_t;
-
-#define UV_ONCE_INIT PTHREAD_ONCE_INIT
-
-typedef pthread_once_t uv_once_t;
-typedef pthread_t uv_thread_t;
-typedef pthread_mutex_t uv_mutex_t;
-typedef pthread_rwlock_t uv_rwlock_t;
-typedef UV_PLATFORM_SEM_T uv_sem_t;
-typedef pthread_cond_t uv_cond_t;
-typedef pthread_key_t uv_key_t;
-
-/* Note: guard clauses should match uv_barrier_init's in src/unix/thread.c. */
-#if defined(_AIX) || \
-    defined(__OpenBSD__) || \
-    !defined(PTHREAD_BARRIER_SERIAL_THREAD)
-/* TODO(bnoordhuis) Merge into uv_barrier_t in v2. */
-struct _uv_barrier {
-  uv_mutex_t mutex;
-  uv_cond_t cond;
-  unsigned threshold;
-  unsigned in;
-  unsigned out;
-};
-
-typedef struct {
-  struct _uv_barrier* b;
-# if defined(PTHREAD_BARRIER_SERIAL_THREAD)
-  /* TODO(bnoordhuis) Remove padding in v2. */
-  char pad[sizeof(pthread_barrier_t) - sizeof(struct _uv_barrier*)];
-# endif
-} uv_barrier_t;
-#else
-typedef pthread_barrier_t uv_barrier_t;
-#endif
-
-/* Platform-specific definitions for uv_spawn support. */
-typedef gid_t uv_gid_t;
-typedef uid_t uv_uid_t;
-
-typedef struct dirent uv__dirent_t;
-
-#define UV_DIR_PRIVATE_FIELDS \
-  DIR* dir;
-
-#if defined(DT_UNKNOWN)
-# define HAVE_DIRENT_TYPES
-# if defined(DT_REG)
-#  define UV__DT_FILE DT_REG
-# else
-#  define UV__DT_FILE -1
-# endif
-# if defined(DT_DIR)
-#  define UV__DT_DIR DT_DIR
-# else
-#  define UV__DT_DIR -2
-# endif
-# if defined(DT_LNK)
-#  define UV__DT_LINK DT_LNK
-# else
-#  define UV__DT_LINK -3
-# endif
-# if defined(DT_FIFO)
-#  define UV__DT_FIFO DT_FIFO
-# else
-#  define UV__DT_FIFO -4
-# endif
-# if defined(DT_SOCK)
-#  define UV__DT_SOCKET DT_SOCK
-# else
-#  define UV__DT_SOCKET -5
-# endif
-# if defined(DT_CHR)
-#  define UV__DT_CHAR DT_CHR
-# else
-#  define UV__DT_CHAR -6
-# endif
-# if defined(DT_BLK)
-#  define UV__DT_BLOCK DT_BLK
-# else
-#  define UV__DT_BLOCK -7
-# endif
-#endif
-
-/* Platform-specific definitions for uv_dlopen support. */
-#define UV_DYNAMIC /* empty */
-
-typedef struct {
-  void* handle;
-  char* errmsg;
-} uv_lib_t;
-
-#define UV_LOOP_PRIVATE_FIELDS                                                \
-  unsigned long flags;                                                        \
-  int backend_fd;                                                             \
-  void* pending_queue[2];                                                     \
-  void* watcher_queue[2];                                                     \
-  void** watchers;                                                            \
-  unsigned int nwatchers;                                                     \
-  unsigned int nfds;                                                          \
-  void* wq[2];                                                                \
-  uv_mutex_t wq_mutex;                                                        \
-  uv_async_t wq_async;                                                        \
-  uv_rwlock_t cloexec_lock;                                                   \
-  uv_handle_t* closing_handles;                                               \
-  void* process_handles[2];                                                   \
-  void* prepare_handles[2];                                                   \
-  void* check_handles[2];                                                     \
-  void* idle_handles[2];                                                      \
-  void* async_handles[2];                                                     \
-  void (*async_unused)(void);  /* TODO(bnoordhuis) Remove in libuv v2. */     \
-  uv__io_t async_io_watcher;                                                  \
-  int async_wfd;                                                              \
-  struct {                                                                    \
-    void* min;                                                                \
-    unsigned int nelts;                                                       \
-  } timer_heap;                                                               \
-  uint64_t timer_counter;                                                     \
-  uint64_t time;                                                              \
-  int signal_pipefd[2];                                                       \
-  uv__io_t signal_io_watcher;                                                 \
-  uv_signal_t child_watcher;                                                  \
-  int emfile_fd;                                                              \
-  UV_PLATFORM_LOOP_FIELDS                                                     \
-
-#define UV_REQ_TYPE_PRIVATE /* empty */
-
-#define UV_REQ_PRIVATE_FIELDS  /* empty */
-
-#define UV_PRIVATE_REQ_TYPES /* empty */
-
-#define UV_WRITE_PRIVATE_FIELDS                                               \
-  void* queue[2];                                                             \
-  unsigned int write_index;                                                   \
-  uv_buf_t* bufs;                                                             \
-  unsigned int nbufs;                                                         \
-  int error;                                                                  \
-  uv_buf_t bufsml[4];                                                         \
-
-#define UV_CONNECT_PRIVATE_FIELDS                                             \
-  void* queue[2];                                                             \
-
-#define UV_SHUTDOWN_PRIVATE_FIELDS /* empty */
-
-#define UV_UDP_SEND_PRIVATE_FIELDS                                            \
-  void* queue[2];                                                             \
-  struct sockaddr_storage addr;                                               \
-  unsigned int nbufs;                                                         \
-  uv_buf_t* bufs;                                                             \
-  ssize_t status;                                                             \
-  uv_udp_send_cb send_cb;                                                     \
-  uv_buf_t bufsml[4];                                                         \
-
-#define UV_HANDLE_PRIVATE_FIELDS                                              \
-  uv_handle_t* next_closing;                                                  \
-  unsigned int flags;                                                         \
-
-#define UV_STREAM_PRIVATE_FIELDS                                              \
-  uv_connect_t *connect_req;                                                  \
-  uv_shutdown_t *shutdown_req;                                                \
-  uv__io_t io_watcher;                                                        \
-  void* write_queue[2];                                                       \
-  void* write_completed_queue[2];                                             \
-  uv_connection_cb connection_cb;                                             \
-  int delayed_error;                                                          \
-  int accepted_fd;                                                            \
-  void* queued_fds;                                                           \
-  UV_STREAM_PRIVATE_PLATFORM_FIELDS                                           \
-
-#define UV_TCP_PRIVATE_FIELDS /* empty */
-
-#define UV_UDP_PRIVATE_FIELDS                                                 \
-  uv_alloc_cb alloc_cb;                                                       \
-  uv_udp_recv_cb recv_cb;                                                     \
-  uv__io_t io_watcher;                                                        \
-  void* write_queue[2];                                                       \
-  void* write_completed_queue[2];                                             \
-
-#define UV_PIPE_PRIVATE_FIELDS                                                \
-  const char* pipe_fname; /* strdup'ed */
-
-#define UV_POLL_PRIVATE_FIELDS                                                \
-  uv__io_t io_watcher;
-
-#define UV_PREPARE_PRIVATE_FIELDS                                             \
-  uv_prepare_cb prepare_cb;                                                   \
-  void* queue[2];                                                             \
-
-#define UV_CHECK_PRIVATE_FIELDS                                               \
-  uv_check_cb check_cb;                                                       \
-  void* queue[2];                                                             \
-
-#define UV_IDLE_PRIVATE_FIELDS                                                \
-  uv_idle_cb idle_cb;                                                         \
-  void* queue[2];                                                             \
-
-#define UV_ASYNC_PRIVATE_FIELDS                                               \
-  uv_async_cb async_cb;                                                       \
-  void* queue[2];                                                             \
-  int pending;                                                                \
-
-#define UV_TIMER_PRIVATE_FIELDS                                               \
-  uv_timer_cb timer_cb;                                                       \
-  void* heap_node[3];                                                         \
-  uint64_t timeout;                                                           \
-  uint64_t repeat;                                                            \
-  uint64_t start_id;
-
-#define UV_GETADDRINFO_PRIVATE_FIELDS                                         \
-  struct uv__work work_req;                                                   \
-  uv_getaddrinfo_cb cb;                                                       \
-  struct addrinfo* hints;                                                     \
-  char* hostname;                                                             \
-  char* service;                                                              \
-  struct addrinfo* addrinfo;                                                  \
-  int retcode;
-
-#define UV_GETNAMEINFO_PRIVATE_FIELDS                                         \
-  struct uv__work work_req;                                                   \
-  uv_getnameinfo_cb getnameinfo_cb;                                           \
-  struct sockaddr_storage storage;                                            \
-  int flags;                                                                  \
-  char host[NI_MAXHOST];                                                      \
-  char service[NI_MAXSERV];                                                   \
-  int retcode;
-
-#define UV_PROCESS_PRIVATE_FIELDS                                             \
-  void* queue[2];                                                             \
-  int status;                                                                 \
-
-#define UV_FS_PRIVATE_FIELDS                                                  \
-  const char *new_path;                                                       \
-  uv_file file;                                                               \
-  int flags;                                                                  \
-  mode_t mode;                                                                \
-  unsigned int nbufs;                                                         \
-  uv_buf_t* bufs;                                                             \
-  off_t off;                                                                  \
-  uv_uid_t uid;                                                               \
-  uv_gid_t gid;                                                               \
-  double atime;                                                               \
-  double mtime;                                                               \
-  struct uv__work work_req;                                                   \
-  uv_buf_t bufsml[4];                                                         \
-
-#define UV_WORK_PRIVATE_FIELDS                                                \
-  struct uv__work work_req;
-
-#define UV_TTY_PRIVATE_FIELDS                                                 \
-  struct termios orig_termios;                                                \
-  int mode;
-
-#define UV_SIGNAL_PRIVATE_FIELDS                                              \
-  /* RB_ENTRY(uv_signal_s) tree_entry; */                                     \
-  struct {                                                                    \
-    struct uv_signal_s* rbe_left;                                             \
-    struct uv_signal_s* rbe_right;                                            \
-    struct uv_signal_s* rbe_parent;                                           \
-    int rbe_color;                                                            \
-  } tree_entry;                                                               \
-  /* Use two counters here so we don have to fiddle with atomics. */          \
-  unsigned int caught_signals;                                                \
-  unsigned int dispatched_signals;
-
-#define UV_FS_EVENT_PRIVATE_FIELDS                                            \
-  uv_fs_event_cb cb;                                                          \
-  UV_PLATFORM_FS_EVENT_FIELDS                                                 \
-
-/* fs open() flags supported on this platform: */
-#if defined(O_APPEND)
-# define UV_FS_O_APPEND       O_APPEND
-#else
-# define UV_FS_O_APPEND       0
-#endif
-#if defined(O_CREAT)
-# define UV_FS_O_CREAT        O_CREAT
-#else
-# define UV_FS_O_CREAT        0
-#endif
-#if defined(O_DIRECT)
-# define UV_FS_O_DIRECT       O_DIRECT
-#else
-# define UV_FS_O_DIRECT       0
-#endif
-#if defined(O_DIRECTORY)
-# define UV_FS_O_DIRECTORY    O_DIRECTORY
-#else
-# define UV_FS_O_DIRECTORY    0
-#endif
-#if defined(O_DSYNC)
-# define UV_FS_O_DSYNC        O_DSYNC
-#else
-# define UV_FS_O_DSYNC        0
-#endif
-#if defined(O_EXCL)
-# define UV_FS_O_EXCL         O_EXCL
-#else
-# define UV_FS_O_EXCL         0
-#endif
-#if defined(O_EXLOCK)
-# define UV_FS_O_EXLOCK       O_EXLOCK
-#else
-# define UV_FS_O_EXLOCK       0
-#endif
-#if defined(O_NOATIME)
-# define UV_FS_O_NOATIME      O_NOATIME
-#else
-# define UV_FS_O_NOATIME      0
-#endif
-#if defined(O_NOCTTY)
-# define UV_FS_O_NOCTTY       O_NOCTTY
-#else
-# define UV_FS_O_NOCTTY       0
-#endif
-#if defined(O_NOFOLLOW)
-# define UV_FS_O_NOFOLLOW     O_NOFOLLOW
-#else
-# define UV_FS_O_NOFOLLOW     0
-#endif
-#if defined(O_NONBLOCK)
-# define UV_FS_O_NONBLOCK     O_NONBLOCK
-#else
-# define UV_FS_O_NONBLOCK     0
-#endif
-#if defined(O_RDONLY)
-# define UV_FS_O_RDONLY       O_RDONLY
-#else
-# define UV_FS_O_RDONLY       0
-#endif
-#if defined(O_RDWR)
-# define UV_FS_O_RDWR         O_RDWR
-#else
-# define UV_FS_O_RDWR         0
-#endif
-#if defined(O_SYMLINK)
-# define UV_FS_O_SYMLINK      O_SYMLINK
-#else
-# define UV_FS_O_SYMLINK      0
-#endif
-#if defined(O_SYNC)
-# define UV_FS_O_SYNC         O_SYNC
-#else
-# define UV_FS_O_SYNC         0
-#endif
-#if defined(O_TRUNC)
-# define UV_FS_O_TRUNC        O_TRUNC
-#else
-# define UV_FS_O_TRUNC        0
-#endif
-#if defined(O_WRONLY)
-# define UV_FS_O_WRONLY       O_WRONLY
-#else
-# define UV_FS_O_WRONLY       0
-#endif
-
-/* fs open() flags supported on other platforms: */
-#define UV_FS_O_RANDOM        0
-#define UV_FS_O_SHORT_LIVED   0
-#define UV_FS_O_SEQUENTIAL    0
-#define UV_FS_O_TEMPORARY     0
-
-#endif /* UV_UNIX_H */
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/include/uv/version.h b/third_party/allwpilib/wpiutil/src/main/native/libuv/include/uv/version.h
deleted file mode 100644
index bf992d2..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/include/uv/version.h
+++ /dev/null
@@ -1,43 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#ifndef UV_VERSION_H
-#define UV_VERSION_H
-
- /*
- * Versions with the same major number are ABI stable. API is allowed to
- * evolve between minor releases, but only in a backwards compatible way.
- * Make sure you update the -soname directives in configure.ac
- * and uv.gyp whenever you bump UV_VERSION_MAJOR or UV_VERSION_MINOR (but
- * not UV_VERSION_PATCH.)
- */
-
-#define UV_VERSION_MAJOR 1
-#define UV_VERSION_MINOR 30
-#define UV_VERSION_PATCH 1
-#define UV_VERSION_IS_RELEASE 1
-#define UV_VERSION_SUFFIX ""
-
-#define UV_VERSION_HEX  ((UV_VERSION_MAJOR << 16) | \
-                         (UV_VERSION_MINOR <<  8) | \
-                         (UV_VERSION_PATCH))
-
-#endif /* UV_VERSION_H */
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/include/uv/win.h b/third_party/allwpilib/wpiutil/src/main/native/libuv/include/uv/win.h
deleted file mode 100644
index ca5242f..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/include/uv/win.h
+++ /dev/null
@@ -1,691 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#ifndef _WIN32_WINNT
-# define _WIN32_WINNT   0x0600
-#endif
-
-#if !defined(_SSIZE_T_) && !defined(_SSIZE_T_DEFINED)
-typedef intptr_t ssize_t;
-# define SSIZE_MAX INTPTR_MAX
-# define _SSIZE_T_
-# define _SSIZE_T_DEFINED
-#endif
-
-#include <winsock2.h>
-
-#if defined(__MINGW32__) && !defined(__MINGW64_VERSION_MAJOR)
-typedef struct pollfd {
-  SOCKET fd;
-  short  events;
-  short  revents;
-} WSAPOLLFD, *PWSAPOLLFD, *LPWSAPOLLFD;
-#endif
-
-#ifndef LOCALE_INVARIANT
-# define LOCALE_INVARIANT 0x007f
-#endif
-
-#include <mswsock.h>
-#include <ws2tcpip.h>
-#include <windows.h>
-
-#include <process.h>
-#include <signal.h>
-#include <fcntl.h>
-#include <sys/stat.h>
-
-#include <stdint.h>
-
-#include "uv/tree.h"
-#include "uv/threadpool.h"
-
-#define MAX_PIPENAME_LEN 256
-
-#ifndef S_IFLNK
-# define S_IFLNK 0xA000
-#endif
-
-/* Additional signals supported by uv_signal and or uv_kill. The CRT defines
- * the following signals already:
- *
- *   #define SIGINT           2
- *   #define SIGILL           4
- *   #define SIGABRT_COMPAT   6
- *   #define SIGFPE           8
- *   #define SIGSEGV         11
- *   #define SIGTERM         15
- *   #define SIGBREAK        21
- *   #define SIGABRT         22
- *
- * The additional signals have values that are common on other Unix
- * variants (Linux and Darwin)
- */
-#define SIGHUP                1
-#define SIGKILL               9
-#define SIGWINCH             28
-
-/* Redefine NSIG to take SIGWINCH into consideration */
-#if defined(NSIG) && NSIG <= SIGWINCH
-# undef NSIG
-#endif
-#ifndef NSIG
-# define NSIG SIGWINCH + 1
-#endif
-
-/* The CRT defines SIGABRT_COMPAT as 6, which equals SIGABRT on many unix-like
- * platforms. However MinGW doesn't define it, so we do. */
-#ifndef SIGABRT_COMPAT
-# define SIGABRT_COMPAT       6
-#endif
-
-/*
- * Guids and typedefs for winsock extension functions
- * Mingw32 doesn't have these :-(
- */
-#ifndef WSAID_ACCEPTEX
-# define WSAID_ACCEPTEX                                                       \
-         {0xb5367df1, 0xcbac, 0x11cf,                                         \
-         {0x95, 0xca, 0x00, 0x80, 0x5f, 0x48, 0xa1, 0x92}}
-
-# define WSAID_CONNECTEX                                                      \
-         {0x25a207b9, 0xddf3, 0x4660,                                         \
-         {0x8e, 0xe9, 0x76, 0xe5, 0x8c, 0x74, 0x06, 0x3e}}
-
-# define WSAID_GETACCEPTEXSOCKADDRS                                           \
-         {0xb5367df2, 0xcbac, 0x11cf,                                         \
-         {0x95, 0xca, 0x00, 0x80, 0x5f, 0x48, 0xa1, 0x92}}
-
-# define WSAID_DISCONNECTEX                                                   \
-         {0x7fda2e11, 0x8630, 0x436f,                                         \
-         {0xa0, 0x31, 0xf5, 0x36, 0xa6, 0xee, 0xc1, 0x57}}
-
-# define WSAID_TRANSMITFILE                                                   \
-         {0xb5367df0, 0xcbac, 0x11cf,                                         \
-         {0x95, 0xca, 0x00, 0x80, 0x5f, 0x48, 0xa1, 0x92}}
-
-  typedef BOOL (PASCAL *LPFN_ACCEPTEX)
-                      (SOCKET sListenSocket,
-                       SOCKET sAcceptSocket,
-                       PVOID lpOutputBuffer,
-                       DWORD dwReceiveDataLength,
-                       DWORD dwLocalAddressLength,
-                       DWORD dwRemoteAddressLength,
-                       LPDWORD lpdwBytesReceived,
-                       LPOVERLAPPED lpOverlapped);
-
-  typedef BOOL (PASCAL *LPFN_CONNECTEX)
-                      (SOCKET s,
-                       const struct sockaddr* name,
-                       int namelen,
-                       PVOID lpSendBuffer,
-                       DWORD dwSendDataLength,
-                       LPDWORD lpdwBytesSent,
-                       LPOVERLAPPED lpOverlapped);
-
-  typedef void (PASCAL *LPFN_GETACCEPTEXSOCKADDRS)
-                      (PVOID lpOutputBuffer,
-                       DWORD dwReceiveDataLength,
-                       DWORD dwLocalAddressLength,
-                       DWORD dwRemoteAddressLength,
-                       LPSOCKADDR* LocalSockaddr,
-                       LPINT LocalSockaddrLength,
-                       LPSOCKADDR* RemoteSockaddr,
-                       LPINT RemoteSockaddrLength);
-
-  typedef BOOL (PASCAL *LPFN_DISCONNECTEX)
-                      (SOCKET hSocket,
-                       LPOVERLAPPED lpOverlapped,
-                       DWORD dwFlags,
-                       DWORD reserved);
-
-  typedef BOOL (PASCAL *LPFN_TRANSMITFILE)
-                      (SOCKET hSocket,
-                       HANDLE hFile,
-                       DWORD nNumberOfBytesToWrite,
-                       DWORD nNumberOfBytesPerSend,
-                       LPOVERLAPPED lpOverlapped,
-                       LPTRANSMIT_FILE_BUFFERS lpTransmitBuffers,
-                       DWORD dwFlags);
-
-  typedef PVOID RTL_SRWLOCK;
-  typedef RTL_SRWLOCK SRWLOCK, *PSRWLOCK;
-#endif
-
-typedef int (WSAAPI* LPFN_WSARECV)
-            (SOCKET socket,
-             LPWSABUF buffers,
-             DWORD buffer_count,
-             LPDWORD bytes,
-             LPDWORD flags,
-             LPWSAOVERLAPPED overlapped,
-             LPWSAOVERLAPPED_COMPLETION_ROUTINE completion_routine);
-
-typedef int (WSAAPI* LPFN_WSARECVFROM)
-            (SOCKET socket,
-             LPWSABUF buffers,
-             DWORD buffer_count,
-             LPDWORD bytes,
-             LPDWORD flags,
-             struct sockaddr* addr,
-             LPINT addr_len,
-             LPWSAOVERLAPPED overlapped,
-             LPWSAOVERLAPPED_COMPLETION_ROUTINE completion_routine);
-
-#pragma warning(push)
-#pragma warning(disable : 28251)
-
-#ifndef _NTDEF_
-  typedef LONG NTSTATUS;
-  typedef NTSTATUS *PNTSTATUS;
-#endif
-
-#pragma warning(pop)
-
-#ifndef RTL_CONDITION_VARIABLE_INIT
-  typedef PVOID CONDITION_VARIABLE, *PCONDITION_VARIABLE;
-#endif
-
-typedef struct _AFD_POLL_HANDLE_INFO {
-  HANDLE Handle;
-  ULONG Events;
-  NTSTATUS Status;
-} AFD_POLL_HANDLE_INFO, *PAFD_POLL_HANDLE_INFO;
-
-typedef struct _AFD_POLL_INFO {
-  LARGE_INTEGER Timeout;
-  ULONG NumberOfHandles;
-  ULONG Exclusive;
-  AFD_POLL_HANDLE_INFO Handles[1];
-} AFD_POLL_INFO, *PAFD_POLL_INFO;
-
-#define UV_MSAFD_PROVIDER_COUNT 3
-
-
-/**
- * It should be possible to cast uv_buf_t[] to WSABUF[]
- * see http://msdn.microsoft.com/en-us/library/ms741542(v=vs.85).aspx
- */
-typedef struct uv_buf_t {
-  ULONG len;
-  char* base;
-} uv_buf_t;
-
-typedef int uv_file;
-typedef SOCKET uv_os_sock_t;
-typedef HANDLE uv_os_fd_t;
-typedef int uv_pid_t;
-
-typedef HANDLE uv_thread_t;
-
-typedef HANDLE uv_sem_t;
-
-typedef CRITICAL_SECTION uv_mutex_t;
-
-/* This condition variable implementation is based on the SetEvent solution
- * (section 3.2) at http://www.cs.wustl.edu/~schmidt/win32-cv-1.html
- * We could not use the SignalObjectAndWait solution (section 3.4) because
- * it want the 2nd argument (type uv_mutex_t) of uv_cond_wait() and
- * uv_cond_timedwait() to be HANDLEs, but we use CRITICAL_SECTIONs.
- */
-
-typedef union {
-  CONDITION_VARIABLE cond_var;
-  struct {
-    unsigned int waiters_count;
-    CRITICAL_SECTION waiters_count_lock;
-    HANDLE signal_event;
-    HANDLE broadcast_event;
-  } unused_; /* TODO: retained for ABI compatibility; remove me in v2.x. */
-} uv_cond_t;
-
-typedef union {
-  struct {
-    unsigned int num_readers_;
-    CRITICAL_SECTION num_readers_lock_;
-    HANDLE write_semaphore_;
-  } state_;
-  /* TODO: remove me in v2.x. */
-  struct {
-    SRWLOCK unused_;
-  } unused1_;
-  /* TODO: remove me in v2.x. */
-  struct {
-    uv_mutex_t unused1_;
-    uv_mutex_t unused2_;
-  } unused2_;
-} uv_rwlock_t;
-
-typedef struct {
-  unsigned int n;
-  unsigned int count;
-  uv_mutex_t mutex;
-  uv_sem_t turnstile1;
-  uv_sem_t turnstile2;
-} uv_barrier_t;
-
-typedef struct {
-  DWORD tls_index;
-} uv_key_t;
-
-#define UV_ONCE_INIT { 0, NULL }
-
-typedef struct uv_once_s {
-  unsigned char ran;
-  HANDLE event;
-} uv_once_t;
-
-/* Platform-specific definitions for uv_spawn support. */
-typedef unsigned char uv_uid_t;
-typedef unsigned char uv_gid_t;
-
-typedef struct uv__dirent_s {
-  int d_type;
-  char d_name[1];
-} uv__dirent_t;
-
-#define UV_DIR_PRIVATE_FIELDS \
-  HANDLE dir_handle;          \
-  WIN32_FIND_DATAW find_data; \
-  BOOL need_find_call;
-
-#define HAVE_DIRENT_TYPES
-#define UV__DT_DIR     UV_DIRENT_DIR
-#define UV__DT_FILE    UV_DIRENT_FILE
-#define UV__DT_LINK    UV_DIRENT_LINK
-#define UV__DT_FIFO    UV_DIRENT_FIFO
-#define UV__DT_SOCKET  UV_DIRENT_SOCKET
-#define UV__DT_CHAR    UV_DIRENT_CHAR
-#define UV__DT_BLOCK   UV_DIRENT_BLOCK
-
-/* Platform-specific definitions for uv_dlopen support. */
-#define UV_DYNAMIC FAR WINAPI
-typedef struct {
-  HMODULE handle;
-  char* errmsg;
-} uv_lib_t;
-
-#define UV_LOOP_PRIVATE_FIELDS                                                \
-    /* The loop's I/O completion port */                                      \
-  HANDLE iocp;                                                                \
-  /* The current time according to the event loop. in msecs. */               \
-  uint64_t time;                                                              \
-  /* Tail of a single-linked circular queue of pending reqs. If the queue */  \
-  /* is empty, tail_ is NULL. If there is only one item, */                   \
-  /* tail_->next_req == tail_ */                                              \
-  uv_req_t* pending_reqs_tail;                                                \
-  /* Head of a single-linked list of closed handles */                        \
-  uv_handle_t* endgame_handles;                                               \
-  /* TODO(bnoordhuis) Stop heap-allocating |timer_heap| in libuv v2.x. */     \
-  void* timer_heap;                                                           \
-    /* Lists of active loop (prepare / check / idle) watchers */              \
-  uv_prepare_t* prepare_handles;                                              \
-  uv_check_t* check_handles;                                                  \
-  uv_idle_t* idle_handles;                                                    \
-  /* This pointer will refer to the prepare/check/idle handle whose */        \
-  /* callback is scheduled to be called next. This is needed to allow */      \
-  /* safe removal from one of the lists above while that list being */        \
-  /* iterated over. */                                                        \
-  uv_prepare_t* next_prepare_handle;                                          \
-  uv_check_t* next_check_handle;                                              \
-  uv_idle_t* next_idle_handle;                                                \
-  /* This handle holds the peer sockets for the fast variant of uv_poll_t */  \
-  SOCKET poll_peer_sockets[UV_MSAFD_PROVIDER_COUNT];                          \
-  /* Counter to keep track of active tcp streams */                           \
-  unsigned int active_tcp_streams;                                            \
-  /* Counter to keep track of active udp streams */                           \
-  unsigned int active_udp_streams;                                            \
-  /* Counter to started timer */                                              \
-  uint64_t timer_counter;                                                     \
-  /* Threadpool */                                                            \
-  void* wq[2];                                                                \
-  uv_mutex_t wq_mutex;                                                        \
-  uv_async_t wq_async;
-
-#define UV_REQ_TYPE_PRIVATE                                                   \
-  /* TODO: remove the req suffix */                                           \
-  UV_ACCEPT,                                                                  \
-  UV_FS_EVENT_REQ,                                                            \
-  UV_POLL_REQ,                                                                \
-  UV_PROCESS_EXIT,                                                            \
-  UV_READ,                                                                    \
-  UV_UDP_RECV,                                                                \
-  UV_WAKEUP,                                                                  \
-  UV_SIGNAL_REQ,
-
-#define UV_REQ_PRIVATE_FIELDS                                                 \
-  union {                                                                     \
-    /* Used by I/O operations */                                              \
-    struct {                                                                  \
-      OVERLAPPED overlapped;                                                  \
-      size_t queued_bytes;                                                    \
-    } io;                                                                     \
-  } u;                                                                        \
-  struct uv_req_s* next_req;
-
-#define UV_WRITE_PRIVATE_FIELDS \
-  int coalesced;                \
-  uv_buf_t write_buffer;        \
-  HANDLE event_handle;          \
-  HANDLE wait_handle;
-
-#define UV_CONNECT_PRIVATE_FIELDS                                             \
-  /* empty */
-
-#define UV_SHUTDOWN_PRIVATE_FIELDS                                            \
-  /* empty */
-
-#define UV_UDP_SEND_PRIVATE_FIELDS                                            \
-  /* empty */
-
-#define UV_PRIVATE_REQ_TYPES                                                  \
-  typedef struct uv_pipe_accept_s {                                           \
-    UV_REQ_FIELDS                                                             \
-    HANDLE pipeHandle;                                                        \
-    struct uv_pipe_accept_s* next_pending;                                    \
-  } uv_pipe_accept_t;                                                         \
-                                                                              \
-  typedef struct uv_tcp_accept_s {                                            \
-    UV_REQ_FIELDS                                                             \
-    SOCKET accept_socket;                                                     \
-    char accept_buffer[sizeof(struct sockaddr_storage) * 2 + 32];             \
-    HANDLE event_handle;                                                      \
-    HANDLE wait_handle;                                                       \
-    struct uv_tcp_accept_s* next_pending;                                     \
-  } uv_tcp_accept_t;                                                          \
-                                                                              \
-  typedef struct uv_read_s {                                                  \
-    UV_REQ_FIELDS                                                             \
-    HANDLE event_handle;                                                      \
-    HANDLE wait_handle;                                                       \
-  } uv_read_t;
-
-#define uv_stream_connection_fields                                           \
-  unsigned int write_reqs_pending;                                            \
-  uv_shutdown_t* shutdown_req;
-
-#define uv_stream_server_fields                                               \
-  uv_connection_cb connection_cb;
-
-#define UV_STREAM_PRIVATE_FIELDS                                              \
-  unsigned int reqs_pending;                                                  \
-  int activecnt;                                                              \
-  uv_read_t read_req;                                                         \
-  union {                                                                     \
-    struct { uv_stream_connection_fields } conn;                              \
-    struct { uv_stream_server_fields     } serv;                              \
-  } stream;
-
-#define uv_tcp_server_fields                                                  \
-  uv_tcp_accept_t* accept_reqs;                                               \
-  unsigned int processed_accepts;                                             \
-  uv_tcp_accept_t* pending_accepts;                                           \
-  LPFN_ACCEPTEX func_acceptex;
-
-#define uv_tcp_connection_fields                                              \
-  uv_buf_t read_buffer;                                                       \
-  LPFN_CONNECTEX func_connectex;
-
-#define UV_TCP_PRIVATE_FIELDS                                                 \
-  SOCKET socket;                                                              \
-  int delayed_error;                                                          \
-  union {                                                                     \
-    struct { uv_tcp_server_fields } serv;                                     \
-    struct { uv_tcp_connection_fields } conn;                                 \
-  } tcp;
-
-#define UV_UDP_PRIVATE_FIELDS                                                 \
-  SOCKET socket;                                                              \
-  unsigned int reqs_pending;                                                  \
-  int activecnt;                                                              \
-  uv_req_t recv_req;                                                          \
-  uv_buf_t recv_buffer;                                                       \
-  struct sockaddr_storage recv_from;                                          \
-  int recv_from_len;                                                          \
-  uv_udp_recv_cb recv_cb;                                                     \
-  uv_alloc_cb alloc_cb;                                                       \
-  LPFN_WSARECV func_wsarecv;                                                  \
-  LPFN_WSARECVFROM func_wsarecvfrom;
-
-#define uv_pipe_server_fields                                                 \
-  int pending_instances;                                                      \
-  uv_pipe_accept_t* accept_reqs;                                              \
-  uv_pipe_accept_t* pending_accepts;
-
-#define uv_pipe_connection_fields                                             \
-  uv_timer_t* eof_timer;                                                      \
-  uv_write_t dummy; /* TODO: retained for ABI compat; remove this in v2.x. */ \
-  DWORD ipc_remote_pid;                                                       \
-  union {                                                                     \
-    uint32_t payload_remaining;                                               \
-    uint64_t dummy; /* TODO: retained for ABI compat; remove this in v2.x. */ \
-  } ipc_data_frame;                                                           \
-  void* ipc_xfer_queue[2];                                                    \
-  int ipc_xfer_queue_length;                                                  \
-  uv_write_t* non_overlapped_writes_tail;                                     \
-  CRITICAL_SECTION readfile_thread_lock;                                      \
-  volatile HANDLE readfile_thread_handle;
-
-#define UV_PIPE_PRIVATE_FIELDS                                                \
-  HANDLE handle;                                                              \
-  WCHAR* name;                                                                \
-  union {                                                                     \
-    struct { uv_pipe_server_fields } serv;                                    \
-    struct { uv_pipe_connection_fields } conn;                                \
-  } pipe;
-
-/* TODO: put the parser states in an union - TTY handles are always half-duplex
- * so read-state can safely overlap write-state. */
-#define UV_TTY_PRIVATE_FIELDS                                                 \
-  HANDLE handle;                                                              \
-  union {                                                                     \
-    struct {                                                                  \
-      /* Used for readable TTY handles */                                     \
-      /* TODO: remove me in v2.x. */                                          \
-      HANDLE unused_;                                                         \
-      uv_buf_t read_line_buffer;                                              \
-      HANDLE read_raw_wait;                                                   \
-      /* Fields used for translating win keystrokes into vt100 characters */  \
-      char last_key[8];                                                       \
-      unsigned char last_key_offset;                                          \
-      unsigned char last_key_len;                                             \
-      WCHAR last_utf16_high_surrogate;                                        \
-      INPUT_RECORD last_input_record;                                         \
-    } rd;                                                                     \
-    struct {                                                                  \
-      /* Used for writable TTY handles */                                     \
-      /* utf8-to-utf16 conversion state */                                    \
-      unsigned int utf8_codepoint;                                            \
-      unsigned char utf8_bytes_left;                                          \
-      /* eol conversion state */                                              \
-      unsigned char previous_eol;                                             \
-      /* ansi parser state */                                                 \
-      unsigned char ansi_parser_state;                                        \
-      unsigned char ansi_csi_argc;                                            \
-      unsigned short ansi_csi_argv[4];                                        \
-      COORD saved_position;                                                   \
-      WORD saved_attributes;                                                  \
-    } wr;                                                                     \
-  } tty;
-
-#define UV_POLL_PRIVATE_FIELDS                                                \
-  SOCKET socket;                                                              \
-  /* Used in fast mode */                                                     \
-  SOCKET peer_socket;                                                         \
-  AFD_POLL_INFO afd_poll_info_1;                                              \
-  AFD_POLL_INFO afd_poll_info_2;                                              \
-  /* Used in fast and slow mode. */                                           \
-  uv_req_t poll_req_1;                                                        \
-  uv_req_t poll_req_2;                                                        \
-  unsigned char submitted_events_1;                                           \
-  unsigned char submitted_events_2;                                           \
-  unsigned char mask_events_1;                                                \
-  unsigned char mask_events_2;                                                \
-  unsigned char events;
-
-#define UV_TIMER_PRIVATE_FIELDS                                               \
-  void* heap_node[3];                                                         \
-  int unused;                                                                 \
-  uint64_t timeout;                                                           \
-  uint64_t repeat;                                                            \
-  uint64_t start_id;                                                          \
-  uv_timer_cb timer_cb;
-
-#define UV_ASYNC_PRIVATE_FIELDS                                               \
-  struct uv_req_s async_req;                                                  \
-  uv_async_cb async_cb;                                                       \
-  /* char to avoid alignment issues */                                        \
-  char volatile async_sent;
-
-#define UV_PREPARE_PRIVATE_FIELDS                                             \
-  uv_prepare_t* prepare_prev;                                                 \
-  uv_prepare_t* prepare_next;                                                 \
-  uv_prepare_cb prepare_cb;
-
-#define UV_CHECK_PRIVATE_FIELDS                                               \
-  uv_check_t* check_prev;                                                     \
-  uv_check_t* check_next;                                                     \
-  uv_check_cb check_cb;
-
-#define UV_IDLE_PRIVATE_FIELDS                                                \
-  uv_idle_t* idle_prev;                                                       \
-  uv_idle_t* idle_next;                                                       \
-  uv_idle_cb idle_cb;
-
-#define UV_HANDLE_PRIVATE_FIELDS                                              \
-  uv_handle_t* endgame_next;                                                  \
-  unsigned int flags;
-
-#define UV_GETADDRINFO_PRIVATE_FIELDS                                         \
-  struct uv__work work_req;                                                   \
-  uv_getaddrinfo_cb getaddrinfo_cb;                                           \
-  void* alloc;                                                                \
-  WCHAR* node;                                                                \
-  WCHAR* service;                                                             \
-  /* The addrinfoW field is used to store a pointer to the hints, and    */   \
-  /* later on to store the result of GetAddrInfoW. The final result will */   \
-  /* be converted to struct addrinfo* and stored in the addrinfo field.  */   \
-  struct addrinfoW* addrinfow;                                                \
-  struct addrinfo* addrinfo;                                                  \
-  int retcode;
-
-#define UV_GETNAMEINFO_PRIVATE_FIELDS                                         \
-  struct uv__work work_req;                                                   \
-  uv_getnameinfo_cb getnameinfo_cb;                                           \
-  struct sockaddr_storage storage;                                            \
-  int flags;                                                                  \
-  char host[NI_MAXHOST];                                                      \
-  char service[NI_MAXSERV];                                                   \
-  int retcode;
-
-#define UV_PROCESS_PRIVATE_FIELDS                                             \
-  struct uv_process_exit_s {                                                  \
-    UV_REQ_FIELDS                                                             \
-  } exit_req;                                                                 \
-  BYTE* child_stdio_buffer;                                                   \
-  int exit_signal;                                                            \
-  HANDLE wait_handle;                                                         \
-  HANDLE process_handle;                                                      \
-  volatile char exit_cb_pending;
-
-#define UV_FS_PRIVATE_FIELDS                                                  \
-  struct uv__work work_req;                                                   \
-  int flags;                                                                  \
-  DWORD sys_errno_;                                                           \
-  union {                                                                     \
-    /* TODO: remove me in 0.9. */                                             \
-    WCHAR* pathw;                                                             \
-    int fd;                                                                   \
-  } file;                                                                     \
-  union {                                                                     \
-    struct {                                                                  \
-      int mode;                                                               \
-      WCHAR* new_pathw;                                                       \
-      int file_flags;                                                         \
-      int fd_out;                                                             \
-      unsigned int nbufs;                                                     \
-      uv_buf_t* bufs;                                                         \
-      int64_t offset;                                                         \
-      uv_buf_t bufsml[4];                                                     \
-    } info;                                                                   \
-    struct {                                                                  \
-      double atime;                                                           \
-      double mtime;                                                           \
-    } time;                                                                   \
-  } fs;
-
-#define UV_WORK_PRIVATE_FIELDS                                                \
-  struct uv__work work_req;
-
-#define UV_FS_EVENT_PRIVATE_FIELDS                                            \
-  struct uv_fs_event_req_s {                                                  \
-    UV_REQ_FIELDS                                                             \
-  } req;                                                                      \
-  HANDLE dir_handle;                                                          \
-  int req_pending;                                                            \
-  uv_fs_event_cb cb;                                                          \
-  WCHAR* filew;                                                               \
-  WCHAR* short_filew;                                                         \
-  WCHAR* dirw;                                                                \
-  char* buffer;
-
-#define UV_SIGNAL_PRIVATE_FIELDS                                              \
-  RB_ENTRY(uv_signal_s) tree_entry;                                           \
-  struct uv_req_s signal_req;                                                 \
-  unsigned long pending_signum;
-
-#ifndef F_OK
-#define F_OK 0
-#endif
-#ifndef R_OK
-#define R_OK 4
-#endif
-#ifndef W_OK
-#define W_OK 2
-#endif
-#ifndef X_OK
-#define X_OK 1
-#endif
-
-/* fs open() flags supported on this platform: */
-#define UV_FS_O_APPEND       _O_APPEND
-#define UV_FS_O_CREAT        _O_CREAT
-#define UV_FS_O_EXCL         _O_EXCL
-#define UV_FS_O_RANDOM       _O_RANDOM
-#define UV_FS_O_RDONLY       _O_RDONLY
-#define UV_FS_O_RDWR         _O_RDWR
-#define UV_FS_O_SEQUENTIAL   _O_SEQUENTIAL
-#define UV_FS_O_SHORT_LIVED  _O_SHORT_LIVED
-#define UV_FS_O_TEMPORARY    _O_TEMPORARY
-#define UV_FS_O_TRUNC        _O_TRUNC
-#define UV_FS_O_WRONLY       _O_WRONLY
-
-/* fs open() flags supported on other platforms (or mapped on this platform): */
-#define UV_FS_O_DIRECT       0x02000000 /* FILE_FLAG_NO_BUFFERING */
-#define UV_FS_O_DIRECTORY    0
-#define UV_FS_O_DSYNC        0x04000000 /* FILE_FLAG_WRITE_THROUGH */
-#define UV_FS_O_EXLOCK       0x10000000 /* EXCLUSIVE SHARING MODE */
-#define UV_FS_O_NOATIME      0
-#define UV_FS_O_NOCTTY       0
-#define UV_FS_O_NOFOLLOW     0
-#define UV_FS_O_NONBLOCK     0
-#define UV_FS_O_SYMLINK      0
-#define UV_FS_O_SYNC         0x08000000 /* FILE_FLAG_WRITE_THROUGH */
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/fs-poll.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/fs-poll.cpp
deleted file mode 100644
index 14d64de..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/fs-poll.cpp
+++ /dev/null
@@ -1,288 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include "uv.h"
-#include "uv-common.h"
-
-#ifdef _WIN32
-#include "win/internal.h"
-#include "win/handle-inl.h"
-#define uv__make_close_pending(h) uv_want_endgame((h)->loop, (h))
-#else
-#include "unix/internal.h"
-#endif
-
-#include <assert.h>
-#include <stdlib.h>
-#include <string.h>
-
-
-struct poll_ctx {
-  uv_fs_poll_t* parent_handle;
-  int busy_polling;
-  unsigned int interval;
-  uint64_t start_time;
-  uv_loop_t* loop;
-  uv_fs_poll_cb poll_cb;
-  uv_timer_t timer_handle;
-  uv_fs_t fs_req; /* TODO(bnoordhuis) mark fs_req internal */
-  uv_stat_t statbuf;
-  struct poll_ctx* previous; /* context from previous start()..stop() period */
-  char path[1]; /* variable length */
-};
-
-static int statbuf_eq(const uv_stat_t* a, const uv_stat_t* b);
-static void poll_cb(uv_fs_t* req);
-static void timer_cb(uv_timer_t* timer);
-static void timer_close_cb(uv_handle_t* handle);
-
-static uv_stat_t zero_statbuf;
-
-
-int uv_fs_poll_init(uv_loop_t* loop, uv_fs_poll_t* handle) {
-  uv__handle_init(loop, (uv_handle_t*)handle, UV_FS_POLL);
-  handle->poll_ctx = NULL;
-  return 0;
-}
-
-
-int uv_fs_poll_start(uv_fs_poll_t* handle,
-                     uv_fs_poll_cb cb,
-                     const char* path,
-                     unsigned int interval) {
-  struct poll_ctx* ctx;
-  uv_loop_t* loop;
-  size_t len;
-  int err;
-
-  if (uv_is_active((uv_handle_t*)handle))
-    return 0;
-
-  loop = handle->loop;
-  len = strlen(path);
-  ctx = (struct poll_ctx*)uv__calloc(1, sizeof(*ctx) + len);
-
-  if (ctx == NULL)
-    return UV_ENOMEM;
-
-  ctx->loop = loop;
-  ctx->poll_cb = cb;
-  ctx->interval = interval ? interval : 1;
-  ctx->start_time = uv_now(loop);
-  ctx->parent_handle = handle;
-  memcpy(ctx->path, path, len + 1);
-
-  err = uv_timer_init(loop, &ctx->timer_handle);
-  if (err < 0)
-    goto error;
-
-  ctx->timer_handle.flags |= UV_HANDLE_INTERNAL;
-  uv__handle_unref(&ctx->timer_handle);
-
-  err = uv_fs_stat(loop, &ctx->fs_req, ctx->path, poll_cb);
-  if (err < 0)
-    goto error;
-
-  if (handle->poll_ctx != NULL)
-    ctx->previous = (struct poll_ctx*)handle->poll_ctx;
-  handle->poll_ctx = ctx;
-  uv__handle_start(handle);
-
-  return 0;
-
-error:
-  uv__free(ctx);
-  return err;
-}
-
-
-int uv_fs_poll_stop(uv_fs_poll_t* handle) {
-  struct poll_ctx* ctx;
-
-  if (!uv_is_active((uv_handle_t*)handle))
-    return 0;
-
-  ctx = (struct poll_ctx*)handle->poll_ctx;
-  assert(ctx != NULL);
-  assert(ctx->parent_handle == handle);
-
-  /* Close the timer if it's active. If it's inactive, there's a stat request
-   * in progress and poll_cb will take care of the cleanup.
-   */
-  if (uv_is_active((uv_handle_t*)&ctx->timer_handle))
-    uv_close((uv_handle_t*)&ctx->timer_handle, timer_close_cb);
-
-  uv__handle_stop(handle);
-
-  return 0;
-}
-
-
-int uv_fs_poll_getpath(uv_fs_poll_t* handle, char* buffer, size_t* size) {
-  struct poll_ctx* ctx;
-  size_t required_len;
-
-  if (!uv_is_active((uv_handle_t*)handle)) {
-    *size = 0;
-    return UV_EINVAL;
-  }
-
-  ctx = (struct poll_ctx*)handle->poll_ctx;
-  assert(ctx != NULL);
-
-  required_len = strlen(ctx->path);
-  if (required_len >= *size) {
-    *size = required_len + 1;
-    return UV_ENOBUFS;
-  }
-
-  memcpy(buffer, ctx->path, required_len);
-  *size = required_len;
-  buffer[required_len] = '\0';
-
-  return 0;
-}
-
-
-void uv__fs_poll_close(uv_fs_poll_t* handle) {
-  uv_fs_poll_stop(handle);
-
-  if (handle->poll_ctx == NULL)
-    uv__make_close_pending((uv_handle_t*)handle);
-}
-
-
-static void timer_cb(uv_timer_t* timer) {
-  struct poll_ctx* ctx;
-
-  ctx = container_of(timer, struct poll_ctx, timer_handle);
-  assert(ctx->parent_handle != NULL);
-  assert(ctx->parent_handle->poll_ctx == ctx);
-  ctx->start_time = uv_now(ctx->loop);
-
-  if (uv_fs_stat(ctx->loop, &ctx->fs_req, ctx->path, poll_cb))
-    abort();
-}
-
-
-static void poll_cb(uv_fs_t* req) {
-  uv_stat_t* statbuf;
-  struct poll_ctx* ctx;
-  uint64_t interval;
-  uv_fs_poll_t* handle;
-
-  ctx = container_of(req, struct poll_ctx, fs_req);
-  handle = ctx->parent_handle;
-
-  if (!uv_is_active((uv_handle_t*)handle) || uv__is_closing(handle))
-    goto out;
-
-  if (req->result != 0) {
-    if (ctx->busy_polling != req->result) {
-      ctx->poll_cb(ctx->parent_handle,
-                   req->result,
-                   &ctx->statbuf,
-                   &zero_statbuf);
-      ctx->busy_polling = req->result;
-    }
-    goto out;
-  }
-
-  statbuf = &req->statbuf;
-
-  if (ctx->busy_polling != 0)
-    if (ctx->busy_polling < 0 || !statbuf_eq(&ctx->statbuf, statbuf))
-      ctx->poll_cb(ctx->parent_handle, 0, &ctx->statbuf, statbuf);
-
-  ctx->statbuf = *statbuf;
-  ctx->busy_polling = 1;
-
-out:
-  uv_fs_req_cleanup(req);
-
-  if (!uv_is_active((uv_handle_t*)handle) || uv__is_closing(handle)) {
-    uv_close((uv_handle_t*)&ctx->timer_handle, timer_close_cb);
-    return;
-  }
-
-  /* Reschedule timer, subtract the delay from doing the stat(). */
-  interval = ctx->interval;
-  interval -= (uv_now(ctx->loop) - ctx->start_time) % interval;
-
-  if (uv_timer_start(&ctx->timer_handle, timer_cb, interval, 0))
-    abort();
-}
-
-
-static void timer_close_cb(uv_handle_t* timer) {
-  struct poll_ctx* ctx;
-  struct poll_ctx* it;
-  struct poll_ctx* last;
-  uv_fs_poll_t* handle;
-
-  ctx = container_of(timer, struct poll_ctx, timer_handle);
-  handle = ctx->parent_handle;
-  if (ctx == handle->poll_ctx) {
-    handle->poll_ctx = ctx->previous;
-    if (handle->poll_ctx == NULL && uv__is_closing(handle))
-      uv__make_close_pending((uv_handle_t*)handle);
-  } else {
-    for (last = (struct poll_ctx*)handle->poll_ctx, it = last->previous;
-         it != ctx;
-         last = it, it = it->previous) {
-      assert(last->previous != NULL);
-    }
-    last->previous = ctx->previous;
-  }
-  uv__free(ctx);
-}
-
-
-static int statbuf_eq(const uv_stat_t* a, const uv_stat_t* b) {
-  return a->st_ctim.tv_nsec == b->st_ctim.tv_nsec
-      && a->st_mtim.tv_nsec == b->st_mtim.tv_nsec
-      && a->st_birthtim.tv_nsec == b->st_birthtim.tv_nsec
-      && a->st_ctim.tv_sec == b->st_ctim.tv_sec
-      && a->st_mtim.tv_sec == b->st_mtim.tv_sec
-      && a->st_birthtim.tv_sec == b->st_birthtim.tv_sec
-      && a->st_size == b->st_size
-      && a->st_mode == b->st_mode
-      && a->st_uid == b->st_uid
-      && a->st_gid == b->st_gid
-      && a->st_ino == b->st_ino
-      && a->st_dev == b->st_dev
-      && a->st_flags == b->st_flags
-      && a->st_gen == b->st_gen;
-}
-
-
-#if defined(_WIN32)
-
-#include "win/internal.h"
-#include "win/handle-inl.h"
-
-void uv__fs_poll_endgame(uv_loop_t* loop, uv_fs_poll_t* handle) {
-  assert(handle->flags & UV_HANDLE_CLOSING);
-  assert(!(handle->flags & UV_HANDLE_CLOSED));
-  uv__handle_close(handle);
-}
-
-#endif /* _WIN32 */
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/idna.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/idna.cpp
deleted file mode 100644
index 6b2406c..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/idna.cpp
+++ /dev/null
@@ -1,291 +0,0 @@
-/* Copyright (c) 2011, 2018 Ben Noordhuis <info@bnoordhuis.nl>
- *
- * Permission to use, copy, modify, and/or distribute this software for any
- * purpose with or without fee is hereby granted, provided that the above
- * copyright notice and this permission notice appear in all copies.
- *
- * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
- * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
- * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
- * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
- * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
- * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
- * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
- */
-
-/* Derived from https://github.com/bnoordhuis/punycode
- * but updated to support IDNA 2008.
- */
-
-#include "uv.h"
-#include "idna.h"
-#include <string.h>
-
-static unsigned uv__utf8_decode1_slow(const char** p,
-                                      const char* pe,
-                                      unsigned a) {
-  unsigned b;
-  unsigned c;
-  unsigned d;
-  unsigned min;
-
-  if (a > 0xF7)
-    return -1;
-
-  switch (*p - pe) {
-  default:
-    if (a > 0xEF) {
-      min = 0x10000;
-      a = a & 7;
-      b = (unsigned char) *(*p)++;
-      c = (unsigned char) *(*p)++;
-      d = (unsigned char) *(*p)++;
-      break;
-    }
-    /* Fall through. */
-  case 2:
-    if (a > 0xDF) {
-      min = 0x800;
-      b = 0x80 | (a & 15);
-      c = (unsigned char) *(*p)++;
-      d = (unsigned char) *(*p)++;
-      a = 0;
-      break;
-    }
-    /* Fall through. */
-  case 1:
-    if (a > 0xBF) {
-      min = 0x80;
-      b = 0x80;
-      c = 0x80 | (a & 31);
-      d = (unsigned char) *(*p)++;
-      a = 0;
-      break;
-    }
-    return -1;  /* Invalid continuation byte. */
-  }
-
-  if (0x80 != (0xC0 & (b ^ c ^ d)))
-    return -1;  /* Invalid sequence. */
-
-  b &= 63;
-  c &= 63;
-  d &= 63;
-  a = (a << 18) | (b << 12) | (c << 6) | d;
-
-  if (a < min)
-    return -1;  /* Overlong sequence. */
-
-  if (a > 0x10FFFF)
-    return -1;  /* Four-byte sequence > U+10FFFF. */
-
-  if (a >= 0xD800 && a <= 0xDFFF)
-    return -1;  /* Surrogate pair. */
-
-  return a;
-}
-
-unsigned uv__utf8_decode1(const char** p, const char* pe) {
-  unsigned a;
-
-  a = (unsigned char) *(*p)++;
-
-  if (a < 128)
-    return a;  /* ASCII, common case. */
-
-  return uv__utf8_decode1_slow(p, pe, a);
-}
-
-#define foreach_codepoint(c, p, pe) \
-  for (; (void) (*p <= pe && (c = uv__utf8_decode1(p, pe))), *p <= pe;)
-
-static int uv__idna_toascii_label(const char* s, const char* se,
-                                  char** d, char* de) {
-  static const char alphabet[] = "abcdefghijklmnopqrstuvwxyz0123456789";
-  const char* ss;
-  unsigned c = 0;
-  unsigned h;
-  unsigned k;
-  unsigned n;
-  unsigned m;
-  unsigned q;
-  unsigned t;
-  unsigned x;
-  unsigned y;
-  unsigned bias;
-  unsigned delta;
-  unsigned todo;
-  int first;
-
-  h = 0;
-  ss = s;
-  todo = 0;
-
-  foreach_codepoint(c, &s, se) {
-    if (c < 128)
-      h++;
-    else if (c == (unsigned) -1)
-      return UV_EINVAL;
-    else
-      todo++;
-  }
-
-  if (todo > 0) {
-    if (*d < de) *(*d)++ = 'x';
-    if (*d < de) *(*d)++ = 'n';
-    if (*d < de) *(*d)++ = '-';
-    if (*d < de) *(*d)++ = '-';
-  }
-
-  x = 0;
-  s = ss;
-  foreach_codepoint(c, &s, se) {
-    if (c > 127)
-      continue;
-
-    if (*d < de)
-      *(*d)++ = c;
-
-    if (++x == h)
-      break;  /* Visited all ASCII characters. */
-  }
-
-  if (todo == 0)
-    return h;
-
-  /* Only write separator when we've written ASCII characters first. */
-  if (h > 0)
-    if (*d < de)
-      *(*d)++ = '-';
-
-  n = 128;
-  bias = 72;
-  delta = 0;
-  first = 1;
-
-  while (todo > 0) {
-    m = -1;
-    s = ss;
-    foreach_codepoint(c, &s, se)
-      if (c >= n)
-        if (c < m)
-          m = c;
-
-    x = m - n;
-    y = h + 1;
-
-    if (x > ~delta / y)
-      return UV_E2BIG;  /* Overflow. */
-
-    delta += x * y;
-    n = m;
-
-    s = ss;
-    foreach_codepoint(c, &s, se) {
-      if (c < n)
-        if (++delta == 0)
-          return UV_E2BIG;  /* Overflow. */
-
-      if (c != n)
-        continue;
-
-      for (k = 36, q = delta; /* empty */; k += 36) {
-        t = 1;
-
-        if (k > bias)
-          t = k - bias;
-
-        if (t > 26)
-          t = 26;
-
-        if (q < t)
-          break;
-
-        /* TODO(bnoordhuis) Since 1 <= t <= 26 and therefore
-         * 10 <= y <= 35, we can optimize the long division
-         * into a table-based reciprocal multiplication.
-         */
-        x = q - t;
-        y = 36 - t;  /* 10 <= y <= 35 since 1 <= t <= 26. */
-        q = x / y;
-        t = t + x % y;  /* 1 <= t <= 35 because of y. */
-
-        if (*d < de)
-          *(*d)++ = alphabet[t];
-      }
-
-      if (*d < de)
-        *(*d)++ = alphabet[q];
-
-      delta /= 2;
-
-      if (first) {
-        delta /= 350;
-        first = 0;
-      }
-
-      /* No overflow check is needed because |delta| was just
-       * divided by 2 and |delta+delta >= delta + delta/h|.
-       */
-      h++;
-      delta += delta / h;
-
-      for (bias = 0; delta > 35 * 26 / 2; bias += 36)
-        delta /= 35;
-
-      bias += 36 * delta / (delta + 38);
-      delta = 0;
-      todo--;
-    }
-
-    delta++;
-    n++;
-  }
-
-  return 0;
-}
-
-#undef foreach_codepoint
-
-long uv__idna_toascii(const char* s, const char* se, char* d, char* de) {
-  const char* si;
-  const char* st;
-  unsigned c;
-  char* ds;
-  int rc;
-
-  ds = d;
-
-  for (si = s; si < se; /* empty */) {
-    st = si;
-    c = uv__utf8_decode1(&si, se);
-
-    if (c != '.')
-      if (c != 0x3002)  /* 。 */
-        if (c != 0xFF0E)  /* . */
-          if (c != 0xFF61)  /* 。 */
-            continue;
-
-    rc = uv__idna_toascii_label(s, st, &d, de);
-
-    if (rc < 0)
-      return rc;
-
-    if (d < de)
-      *d++ = '.';
-
-    s = si;
-  }
-
-  if (s < se) {
-    rc = uv__idna_toascii_label(s, se, &d, de);
-
-    if (rc < 0)
-      return rc;
-  }
-
-  if (d < de)
-    *d++ = '\0';
-
-  return d - ds;  /* Number of bytes written. */
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/inet.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/inet.cpp
deleted file mode 100644
index 167ec11..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/inet.cpp
+++ /dev/null
@@ -1,307 +0,0 @@
-/*
- * Copyright (c) 2004 by Internet Systems Consortium, Inc. ("ISC")
- * Copyright (c) 1996-1999 by Internet Software Consortium.
- *
- * Permission to use, copy, modify, and distribute this software for any
- * purpose with or without fee is hereby granted, provided that the above
- * copyright notice and this permission notice appear in all copies.
- *
- * THE SOFTWARE IS PROVIDED "AS IS" AND ISC DISCLAIMS ALL WARRANTIES
- * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
- * MERCHANTABILITY AND FITNESS.  IN NO EVENT SHALL ISC BE LIABLE FOR
- * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
- * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
- * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT
- * OF OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
- */
-
-#include <stdio.h>
-#include <string.h>
-
-#if defined(_MSC_VER) && _MSC_VER < 1600
-# include "uv/stdint-msvc2008.h"
-#else
-# include <stdint.h>
-#endif
-
-#include "uv.h"
-#include "uv-common.h"
-
-#ifdef _WIN32
-#pragma warning(disable : 6001)
-#endif
-
-#define UV__INET_ADDRSTRLEN         16
-#define UV__INET6_ADDRSTRLEN        46
-
-
-static int inet_ntop4(const unsigned char *src, char *dst, size_t size);
-static int inet_ntop6(const unsigned char *src, char *dst, size_t size);
-static int inet_pton4(const char *src, unsigned char *dst);
-static int inet_pton6(const char *src, unsigned char *dst);
-
-
-int uv_inet_ntop(int af, const void* src, char* dst, size_t size) {
-  switch (af) {
-  case AF_INET:
-    return (inet_ntop4((const unsigned char*)src, dst, size));
-  case AF_INET6:
-    return (inet_ntop6((const unsigned char*)src, dst, size));
-  default:
-    return UV_EAFNOSUPPORT;
-  }
-  /* NOTREACHED */
-}
-
-
-static int inet_ntop4(const unsigned char *src, char *dst, size_t size) {
-  static const char fmt[] = "%u.%u.%u.%u";
-  char tmp[UV__INET_ADDRSTRLEN];
-  int l;
-
-  l = snprintf(tmp, sizeof(tmp), fmt, src[0], src[1], src[2], src[3]);
-  if (l <= 0 || (size_t) l >= size) {
-    return UV_ENOSPC;
-  }
-  uv__strscpy(dst, tmp, size);
-  return 0;
-}
-
-
-static int inet_ntop6(const unsigned char *src, char *dst, size_t size) {
-  /*
-   * Note that int32_t and int16_t need only be "at least" large enough
-   * to contain a value of the specified size.  On some systems, like
-   * Crays, there is no such thing as an integer variable with 16 bits.
-   * Keep this in mind if you think this function should have been coded
-   * to use pointer overlays.  All the world's not a VAX.
-   */
-  char tmp[UV__INET6_ADDRSTRLEN], *tp;
-  struct { int base, len; } best, cur;
-  unsigned int words[sizeof(struct in6_addr) / sizeof(uint16_t)];
-  int i;
-
-  /*
-   * Preprocess:
-   *  Copy the input (bytewise) array into a wordwise array.
-   *  Find the longest run of 0x00's in src[] for :: shorthanding.
-   */
-  memset(words, '\0', sizeof words);
-  for (i = 0; i < (int) sizeof(struct in6_addr); i++)
-    words[i / 2] |= (src[i] << ((1 - (i % 2)) << 3));
-  best.base = -1;
-  best.len = 0;
-  cur.base = -1;
-  cur.len = 0;
-  for (i = 0; i < (int) ARRAY_SIZE(words); i++) {
-    if (words[i] == 0) {
-      if (cur.base == -1)
-        cur.base = i, cur.len = 1;
-      else
-        cur.len++;
-    } else {
-      if (cur.base != -1) {
-        if (best.base == -1 || cur.len > best.len)
-          best = cur;
-        cur.base = -1;
-      }
-    }
-  }
-  if (cur.base != -1) {
-    if (best.base == -1 || cur.len > best.len)
-      best = cur;
-  }
-  if (best.base != -1 && best.len < 2)
-    best.base = -1;
-
-  /*
-   * Format the result.
-   */
-  tp = tmp;
-  for (i = 0; i < (int) ARRAY_SIZE(words); i++) {
-    /* Are we inside the best run of 0x00's? */
-    if (best.base != -1 && i >= best.base &&
-        i < (best.base + best.len)) {
-      if (i == best.base)
-        *tp++ = ':';
-      continue;
-    }
-    /* Are we following an initial run of 0x00s or any real hex? */
-    if (i != 0)
-      *tp++ = ':';
-    /* Is this address an encapsulated IPv4? */
-    if (i == 6 && best.base == 0 && (best.len == 6 ||
-        (best.len == 7 && words[7] != 0x0001) ||
-        (best.len == 5 && words[5] == 0xffff))) {
-      int err = inet_ntop4(src+12, tp, sizeof tmp - (tp - tmp));
-      if (err)
-        return err;
-      tp += strlen(tp);
-      break;
-    }
-    tp += sprintf(tp, "%x", words[i]);
-  }
-  /* Was it a trailing run of 0x00's? */
-  if (best.base != -1 && (best.base + best.len) == ARRAY_SIZE(words))
-    *tp++ = ':';
-  *tp++ = '\0';
-  if (UV_E2BIG == uv__strscpy(dst, tmp, size))
-    return UV_ENOSPC;
-  return 0;
-}
-
-
-int uv_inet_pton(int af, const char* src, void* dst) {
-  if (src == NULL || dst == NULL)
-    return UV_EINVAL;
-
-  switch (af) {
-  case AF_INET:
-    return (inet_pton4(src, (unsigned char*)dst));
-  case AF_INET6: {
-    int len;
-    char tmp[UV__INET6_ADDRSTRLEN], *s;
-    const char *p;
-    s = (char*) src;
-    p = strchr(src, '%');
-    if (p != NULL) {
-      s = tmp;
-      len = p - src;
-      if (len > UV__INET6_ADDRSTRLEN-1)
-        return UV_EINVAL;
-      memcpy(s, src, len);
-      s[len] = '\0';
-    }
-    return inet_pton6(s, (unsigned char*)dst);
-  }
-  default:
-    return UV_EAFNOSUPPORT;
-  }
-  /* NOTREACHED */
-}
-
-
-static int inet_pton4(const char *src, unsigned char *dst) {
-  static const char digits[] = "0123456789";
-  int saw_digit, octets, ch;
-  unsigned char tmp[sizeof(struct in_addr)], *tp;
-
-  saw_digit = 0;
-  octets = 0;
-  *(tp = tmp) = 0;
-  while ((ch = *src++) != '\0') {
-    const char *pch;
-
-    if ((pch = strchr(digits, ch)) != NULL) {
-      unsigned int nw = *tp * 10 + (pch - digits);
-
-      if (saw_digit && *tp == 0)
-        return UV_EINVAL;
-      if (nw > 255)
-        return UV_EINVAL;
-      *tp = nw;
-      if (!saw_digit) {
-        if (++octets > 4)
-          return UV_EINVAL;
-        saw_digit = 1;
-      }
-    } else if (ch == '.' && saw_digit) {
-      if (octets == 4)
-        return UV_EINVAL;
-      *++tp = 0;
-      saw_digit = 0;
-    } else
-      return UV_EINVAL;
-  }
-  if (octets < 4)
-    return UV_EINVAL;
-  memcpy(dst, tmp, sizeof(struct in_addr));
-  return 0;
-}
-
-
-static int inet_pton6(const char *src, unsigned char *dst) {
-  static const char xdigits_l[] = "0123456789abcdef",
-                    xdigits_u[] = "0123456789ABCDEF";
-  unsigned char tmp[sizeof(struct in6_addr)], *tp, *endp, *colonp;
-  const char *xdigits, *curtok;
-  int ch, seen_xdigits;
-  unsigned int val;
-
-  memset((tp = tmp), '\0', sizeof tmp);
-  endp = tp + sizeof tmp;
-  colonp = NULL;
-  /* Leading :: requires some special handling. */
-  if (*src == ':')
-    if (*++src != ':')
-      return UV_EINVAL;
-  curtok = src;
-  seen_xdigits = 0;
-  val = 0;
-  while ((ch = *src++) != '\0') {
-    const char *pch;
-
-    if ((pch = strchr((xdigits = xdigits_l), ch)) == NULL)
-      pch = strchr((xdigits = xdigits_u), ch);
-    if (pch != NULL) {
-      val <<= 4;
-      val |= (pch - xdigits);
-      if (++seen_xdigits > 4)
-        return UV_EINVAL;
-      continue;
-    }
-    if (ch == ':') {
-      curtok = src;
-      if (!seen_xdigits) {
-        if (colonp)
-          return UV_EINVAL;
-        colonp = tp;
-        continue;
-      } else if (*src == '\0') {
-        return UV_EINVAL;
-      }
-      if (tp + sizeof(uint16_t) > endp)
-        return UV_EINVAL;
-      *tp++ = (unsigned char) (val >> 8) & 0xff;
-      *tp++ = (unsigned char) val & 0xff;
-      seen_xdigits = 0;
-      val = 0;
-      continue;
-    }
-    if (ch == '.' && ((tp + sizeof(struct in_addr)) <= endp)) {
-      int err = inet_pton4(curtok, tp);
-      if (err == 0) {
-        tp += sizeof(struct in_addr);
-        seen_xdigits = 0;
-        break;  /*%< '\\0' was seen by inet_pton4(). */
-      }
-    }
-    return UV_EINVAL;
-  }
-  if (seen_xdigits) {
-    if (tp + sizeof(uint16_t) > endp)
-      return UV_EINVAL;
-    *tp++ = (unsigned char) (val >> 8) & 0xff;
-    *tp++ = (unsigned char) val & 0xff;
-  }
-  if (colonp != NULL) {
-    /*
-     * Since some memmove()'s erroneously fail to handle
-     * overlapping regions, we'll do the shift by hand.
-     */
-    const int n = tp - colonp;
-    int i;
-
-    if (tp == endp)
-      return UV_EINVAL;
-    for (i = 1; i <= n; i++) {
-      endp[- i] = colonp[n - i];
-      colonp[n - i] = 0;
-    }
-    tp = endp;
-  }
-  if (tp != endp)
-    return UV_EINVAL;
-  memcpy(dst, tmp, sizeof tmp);
-  return 0;
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/strscpy.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/strscpy.cpp
deleted file mode 100644
index 4a9e863..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/strscpy.cpp
+++ /dev/null
@@ -1,17 +0,0 @@
-#include "strscpy.h"
-#include <limits.h>  /* SSIZE_MAX */
-
-ssize_t uv__strscpy(char* d, const char* s, size_t n) {
-  size_t i;
-
-  for (i = 0; i < n; i++)
-    if ('\0' == (d[i] = s[i]))
-      return i > SSIZE_MAX ? (ssize_t) UV_E2BIG : (ssize_t) i;
-
-  if (i == 0)
-    return 0;
-
-  d[--i] = '\0';
-
-  return UV_E2BIG;
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/strscpy.h b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/strscpy.h
deleted file mode 100644
index fbe0a39..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/strscpy.h
+++ /dev/null
@@ -1,18 +0,0 @@
-#ifndef UV_STRSCPY_H_
-#define UV_STRSCPY_H_
-
-/* Include uv.h for its definitions of size_t and ssize_t.
- * size_t can be obtained directly from <stddef.h> but ssize_t requires
- * some hoop jumping on Windows that I didn't want to duplicate here.
- */
-#include "uv.h"
-
-/* Copies up to |n-1| bytes from |d| to |s| and always zero-terminates
- * the result, except when |n==0|. Returns the number of bytes copied
- * or UV_E2BIG if |d| is too small.
- *
- * See https://www.kernel.org/doc/htmldocs/kernel-api/API-strscpy.html
- */
-ssize_t uv__strscpy(char* d, const char* s, size_t n);
-
-#endif  /* UV_STRSCPY_H_ */
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/threadpool.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/threadpool.cpp
deleted file mode 100644
index 515bf40..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/threadpool.cpp
+++ /dev/null
@@ -1,388 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include "uv-common.h"
-
-#if !defined(_WIN32)
-# include "unix/internal.h"
-#endif
-
-#include <stdlib.h>
-
-#ifdef _WIN32
-#pragma warning(disable: 6001 6011)
-#endif
-
-#define MAX_THREADPOOL_SIZE 1024
-
-static uv_once_t once = UV_ONCE_INIT;
-static uv_cond_t cond;
-static uv_mutex_t mutex;
-static unsigned int idle_threads;
-static unsigned int slow_io_work_running;
-static unsigned int nthreads;
-static uv_thread_t* threads;
-static uv_thread_t default_threads[4];
-static QUEUE exit_message;
-static QUEUE wq;
-static QUEUE run_slow_work_message;
-static QUEUE slow_io_pending_wq;
-
-static unsigned int slow_work_thread_threshold(void) {
-  return (nthreads + 1) / 2;
-}
-
-static void uv__cancelled(struct uv__work* w) {
-  abort();
-}
-
-
-/* To avoid deadlock with uv_cancel() it's crucial that the worker
- * never holds the global mutex and the loop-local mutex at the same time.
- */
-static void worker(void* arg) {
-  struct uv__work* w;
-  QUEUE* q;
-  int is_slow_work;
-
-  uv_sem_post((uv_sem_t*) arg);
-  arg = NULL;
-
-  uv_mutex_lock(&mutex);
-  for (;;) {
-    /* `mutex` should always be locked at this point. */
-
-    /* Keep waiting while either no work is present or only slow I/O
-       and we're at the threshold for that. */
-    while (QUEUE_EMPTY(&wq) ||
-           (QUEUE_HEAD(&wq) == &run_slow_work_message &&
-            QUEUE_NEXT(&run_slow_work_message) == &wq &&
-            slow_io_work_running >= slow_work_thread_threshold())) {
-      idle_threads += 1;
-      uv_cond_wait(&cond, &mutex);
-      idle_threads -= 1;
-    }
-
-    q = QUEUE_HEAD(&wq);
-    if (q == &exit_message) {
-      uv_cond_signal(&cond);
-      uv_mutex_unlock(&mutex);
-      break;
-    }
-
-    QUEUE_REMOVE(q);
-    QUEUE_INIT(q);  /* Signal uv_cancel() that the work req is executing. */
-
-    is_slow_work = 0;
-    if (q == &run_slow_work_message) {
-      /* If we're at the slow I/O threshold, re-schedule until after all
-         other work in the queue is done. */
-      if (slow_io_work_running >= slow_work_thread_threshold()) {
-        QUEUE_INSERT_TAIL(&wq, q);
-        continue;
-      }
-
-      /* If we encountered a request to run slow I/O work but there is none
-         to run, that means it's cancelled => Start over. */
-      if (QUEUE_EMPTY(&slow_io_pending_wq))
-        continue;
-
-      is_slow_work = 1;
-      slow_io_work_running++;
-
-      q = QUEUE_HEAD(&slow_io_pending_wq);
-      QUEUE_REMOVE(q);
-      QUEUE_INIT(q);
-
-      /* If there is more slow I/O work, schedule it to be run as well. */
-      if (!QUEUE_EMPTY(&slow_io_pending_wq)) {
-        QUEUE_INSERT_TAIL(&wq, &run_slow_work_message);
-        if (idle_threads > 0)
-          uv_cond_signal(&cond);
-      }
-    }
-
-    uv_mutex_unlock(&mutex);
-
-    w = QUEUE_DATA(q, struct uv__work, wq);
-    w->work(w);
-
-    uv_mutex_lock(&w->loop->wq_mutex);
-    w->work = NULL;  /* Signal uv_cancel() that the work req is done
-                        executing. */
-    QUEUE_INSERT_TAIL(&w->loop->wq, &w->wq);
-    uv_async_send(&w->loop->wq_async);
-    uv_mutex_unlock(&w->loop->wq_mutex);
-
-    /* Lock `mutex` since that is expected at the start of the next
-     * iteration. */
-    uv_mutex_lock(&mutex);
-    if (is_slow_work) {
-      /* `slow_io_work_running` is protected by `mutex`. */
-      slow_io_work_running--;
-    }
-  }
-}
-
-
-static void post(QUEUE* q, enum uv__work_kind kind) {
-  uv_mutex_lock(&mutex);
-  if (kind == UV__WORK_SLOW_IO) {
-    /* Insert into a separate queue. */
-    QUEUE_INSERT_TAIL(&slow_io_pending_wq, q);
-    if (!QUEUE_EMPTY(&run_slow_work_message)) {
-      /* Running slow I/O tasks is already scheduled => Nothing to do here.
-         The worker that runs said other task will schedule this one as well. */
-      uv_mutex_unlock(&mutex);
-      return;
-    }
-    q = &run_slow_work_message;
-  }
-
-  QUEUE_INSERT_TAIL(&wq, q);
-  if (idle_threads > 0)
-    uv_cond_signal(&cond);
-  uv_mutex_unlock(&mutex);
-}
-
-
-#ifndef _WIN32
-UV_DESTRUCTOR(static void cleanup(void)) {
-  unsigned int i;
-
-  if (nthreads == 0)
-    return;
-
-  post(&exit_message, UV__WORK_CPU);
-
-  for (i = 0; i < nthreads; i++)
-    if (uv_thread_join(threads + i))
-      abort();
-
-  if (threads != default_threads)
-    uv__free(threads);
-
-  uv_mutex_destroy(&mutex);
-  uv_cond_destroy(&cond);
-
-  threads = NULL;
-  nthreads = 0;
-}
-#endif
-
-
-static void init_threads(void) {
-  unsigned int i;
-  const char* val;
-  uv_sem_t sem;
-
-  nthreads = ARRAY_SIZE(default_threads);
-  val = getenv("UV_THREADPOOL_SIZE");
-  if (val != NULL)
-    nthreads = atoi(val);
-  if (nthreads == 0)
-    nthreads = 1;
-  if (nthreads > MAX_THREADPOOL_SIZE)
-    nthreads = MAX_THREADPOOL_SIZE;
-
-  threads = default_threads;
-  if (nthreads > ARRAY_SIZE(default_threads)) {
-    threads = (uv_thread_t*)uv__malloc(nthreads * sizeof(threads[0]));
-    if (threads == NULL) {
-      nthreads = ARRAY_SIZE(default_threads);
-      threads = default_threads;
-    }
-  }
-
-  if (uv_cond_init(&cond))
-    abort();
-
-  if (uv_mutex_init(&mutex))
-    abort();
-
-  QUEUE_INIT(&wq);
-  QUEUE_INIT(&slow_io_pending_wq);
-  QUEUE_INIT(&run_slow_work_message);
-
-  if (uv_sem_init(&sem, 0))
-    abort();
-
-  for (i = 0; i < nthreads; i++)
-    if (uv_thread_create(threads + i, worker, &sem))
-      abort();
-
-  for (i = 0; i < nthreads; i++)
-    uv_sem_wait(&sem);
-
-  uv_sem_destroy(&sem);
-}
-
-
-#ifndef _WIN32
-static void reset_once(void) {
-  uv_once_t child_once = UV_ONCE_INIT;
-  memcpy(&once, &child_once, sizeof(child_once));
-}
-#endif
-
-
-static void init_once(void) {
-#ifndef _WIN32
-  /* Re-initialize the threadpool after fork.
-   * Note that this discards the global mutex and condition as well
-   * as the work queue.
-   */
-  if (pthread_atfork(NULL, NULL, &reset_once))
-    abort();
-#endif
-  init_threads();
-}
-
-
-void uv__work_submit(uv_loop_t* loop,
-                     struct uv__work* w,
-                     enum uv__work_kind kind,
-                     void (*work)(struct uv__work* w),
-                     void (*done)(struct uv__work* w, int status)) {
-  uv_once(&once, init_once);
-  w->loop = loop;
-  w->work = work;
-  w->done = done;
-  post(&w->wq, kind);
-}
-
-
-static int uv__work_cancel(uv_loop_t* loop, uv_req_t* req, struct uv__work* w) {
-  int cancelled;
-
-  uv_mutex_lock(&mutex);
-  uv_mutex_lock(&w->loop->wq_mutex);
-
-  cancelled = !QUEUE_EMPTY(&w->wq) && w->work != NULL;
-  if (cancelled)
-    QUEUE_REMOVE(&w->wq);
-
-  uv_mutex_unlock(&w->loop->wq_mutex);
-  uv_mutex_unlock(&mutex);
-
-  if (!cancelled)
-    return UV_EBUSY;
-
-  w->work = uv__cancelled;
-  uv_mutex_lock(&loop->wq_mutex);
-  QUEUE_INSERT_TAIL(&loop->wq, &w->wq);
-  uv_async_send(&loop->wq_async);
-  uv_mutex_unlock(&loop->wq_mutex);
-
-  return 0;
-}
-
-
-void uv__work_done(uv_async_t* handle) {
-  struct uv__work* w;
-  uv_loop_t* loop;
-  QUEUE* q;
-  QUEUE wq;
-  int err;
-
-  loop = container_of(handle, uv_loop_t, wq_async);
-  uv_mutex_lock(&loop->wq_mutex);
-  QUEUE_MOVE(&loop->wq, &wq);
-  uv_mutex_unlock(&loop->wq_mutex);
-
-  while (!QUEUE_EMPTY(&wq)) {
-    q = QUEUE_HEAD(&wq);
-    QUEUE_REMOVE(q);
-
-    w = container_of(q, struct uv__work, wq);
-    err = (w->work == uv__cancelled) ? UV_ECANCELED : 0;
-    w->done(w, err);
-  }
-}
-
-
-static void uv__queue_work(struct uv__work* w) {
-  uv_work_t* req = container_of(w, uv_work_t, work_req);
-
-  req->work_cb(req);
-}
-
-
-static void uv__queue_done(struct uv__work* w, int err) {
-  uv_work_t* req;
-
-  req = container_of(w, uv_work_t, work_req);
-  uv__req_unregister(req->loop, req);
-
-  if (req->after_work_cb == NULL)
-    return;
-
-  req->after_work_cb(req, err);
-}
-
-
-int uv_queue_work(uv_loop_t* loop,
-                  uv_work_t* req,
-                  uv_work_cb work_cb,
-                  uv_after_work_cb after_work_cb) {
-  if (work_cb == NULL)
-    return UV_EINVAL;
-
-  uv__req_init(loop, req, UV_WORK);
-  req->loop = loop;
-  req->work_cb = work_cb;
-  req->after_work_cb = after_work_cb;
-  uv__work_submit(loop,
-                  &req->work_req,
-                  UV__WORK_CPU,
-                  uv__queue_work,
-                  uv__queue_done);
-  return 0;
-}
-
-
-int uv_cancel(uv_req_t* req) {
-  struct uv__work* wreq;
-  uv_loop_t* loop;
-
-  switch (req->type) {
-  case UV_FS:
-    loop =  ((uv_fs_t*) req)->loop;
-    wreq = &((uv_fs_t*) req)->work_req;
-    break;
-  case UV_GETADDRINFO:
-    loop =  ((uv_getaddrinfo_t*) req)->loop;
-    wreq = &((uv_getaddrinfo_t*) req)->work_req;
-    break;
-  case UV_GETNAMEINFO:
-    loop = ((uv_getnameinfo_t*) req)->loop;
-    wreq = &((uv_getnameinfo_t*) req)->work_req;
-    break;
-  case UV_WORK:
-    loop =  ((uv_work_t*) req)->loop;
-    wreq = &((uv_work_t*) req)->work_req;
-    break;
-  default:
-    return UV_EINVAL;
-  }
-
-  return uv__work_cancel(loop, req, wreq);
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/timer.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/timer.cpp
deleted file mode 100644
index dd78bcb..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/timer.cpp
+++ /dev/null
@@ -1,181 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include "uv.h"
-#include "uv-common.h"
-#include "heap-inl.h"
-
-#include <assert.h>
-#include <limits.h>
-
-
-static struct heap *timer_heap(const uv_loop_t* loop) {
-#ifdef _WIN32
-  return (struct heap*) loop->timer_heap;
-#else
-  return (struct heap*) &loop->timer_heap;
-#endif
-}
-
-
-static int timer_less_than(const struct heap_node* ha,
-                           const struct heap_node* hb) {
-  const uv_timer_t* a;
-  const uv_timer_t* b;
-
-  a = container_of(ha, uv_timer_t, heap_node);
-  b = container_of(hb, uv_timer_t, heap_node);
-
-  if (a->timeout < b->timeout)
-    return 1;
-  if (b->timeout < a->timeout)
-    return 0;
-
-  /* Compare start_id when both have the same timeout. start_id is
-   * allocated with loop->timer_counter in uv_timer_start().
-   */
-  if (a->start_id < b->start_id)
-    return 1;
-  if (b->start_id < a->start_id)
-    return 0;
-
-  return 0;
-}
-
-
-int uv_timer_init(uv_loop_t* loop, uv_timer_t* handle) {
-  uv__handle_init(loop, (uv_handle_t*)handle, UV_TIMER);
-  handle->timer_cb = NULL;
-  handle->repeat = 0;
-  return 0;
-}
-
-
-int uv_timer_start(uv_timer_t* handle,
-                   uv_timer_cb cb,
-                   uint64_t timeout,
-                   uint64_t repeat) {
-  uint64_t clamped_timeout;
-
-  if (cb == NULL)
-    return UV_EINVAL;
-
-  if (uv__is_active(handle))
-    uv_timer_stop(handle);
-
-  clamped_timeout = handle->loop->time + timeout;
-  if (clamped_timeout < timeout)
-    clamped_timeout = (uint64_t) -1;
-
-  handle->timer_cb = cb;
-  handle->timeout = clamped_timeout;
-  handle->repeat = repeat;
-  /* start_id is the second index to be compared in uv__timer_cmp() */
-  handle->start_id = handle->loop->timer_counter++;
-
-  heap_insert(timer_heap(handle->loop),
-              (struct heap_node*) &handle->heap_node,
-              timer_less_than);
-  uv__handle_start(handle);
-
-  return 0;
-}
-
-
-int uv_timer_stop(uv_timer_t* handle) {
-  if (!uv__is_active(handle))
-    return 0;
-
-  heap_remove(timer_heap(handle->loop),
-              (struct heap_node*) &handle->heap_node,
-              timer_less_than);
-  uv__handle_stop(handle);
-
-  return 0;
-}
-
-
-int uv_timer_again(uv_timer_t* handle) {
-  if (handle->timer_cb == NULL)
-    return UV_EINVAL;
-
-  if (handle->repeat) {
-    uv_timer_stop(handle);
-    uv_timer_start(handle, handle->timer_cb, handle->repeat, handle->repeat);
-  }
-
-  return 0;
-}
-
-
-void uv_timer_set_repeat(uv_timer_t* handle, uint64_t repeat) {
-  handle->repeat = repeat;
-}
-
-
-uint64_t uv_timer_get_repeat(const uv_timer_t* handle) {
-  return handle->repeat;
-}
-
-
-int uv__next_timeout(const uv_loop_t* loop) {
-  const struct heap_node* heap_node;
-  const uv_timer_t* handle;
-  uint64_t diff;
-
-  heap_node = heap_min(timer_heap(loop));
-  if (heap_node == NULL)
-    return -1; /* block indefinitely */
-
-  handle = container_of(heap_node, uv_timer_t, heap_node);
-  if (handle->timeout <= loop->time)
-    return 0;
-
-  diff = handle->timeout - loop->time;
-  if (diff > INT_MAX)
-    diff = INT_MAX;
-
-  return (int) diff;
-}
-
-
-void uv__run_timers(uv_loop_t* loop) {
-  struct heap_node* heap_node;
-  uv_timer_t* handle;
-
-  for (;;) {
-    heap_node = heap_min(timer_heap(loop));
-    if (heap_node == NULL)
-      break;
-
-    handle = container_of(heap_node, uv_timer_t, heap_node);
-    if (handle->timeout > loop->time)
-      break;
-
-    uv_timer_stop(handle);
-    uv_timer_again(handle);
-    handle->timer_cb(handle);
-  }
-}
-
-
-void uv__timer_close(uv_timer_t* handle) {
-  uv_timer_stop(handle);
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/android-ifaddrs.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/android-ifaddrs.cpp
deleted file mode 100644
index ab6b029..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/android-ifaddrs.cpp
+++ /dev/null
@@ -1,710 +0,0 @@
-/*
-Copyright (c) 2013, Kenneth MacKay
-Copyright (c) 2014, Emergya (Cloud4all, FP7/2007-2013 grant agreement #289016)
-All rights reserved.
-
-Redistribution and use in source and binary forms, with or without modification,
-are permitted provided that the following conditions are met:
- * Redistributions of source code must retain the above copyright notice, this
-   list of conditions and the following disclaimer.
- * Redistributions in binary form must reproduce the above copyright notice,
-   this list of conditions and the following disclaimer in the documentation
-   and/or other materials provided with the distribution.
-
-THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
-ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
-WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
-DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
-ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
-(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
-LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
-ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
-(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
-SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
-*/
-
-#include "uv/android-ifaddrs.h"
-#include "uv-common.h"
-
-#include <string.h>
-#include <stdlib.h>
-#include <errno.h>
-#include <unistd.h>
-#include <sys/socket.h>
-#include <net/if_arp.h>
-#include <netinet/in.h>
-#include <linux/netlink.h>
-#include <linux/rtnetlink.h>
-
-typedef struct NetlinkList
-{
-    struct NetlinkList *m_next;
-    struct nlmsghdr *m_data;
-    unsigned int m_size;
-} NetlinkList;
-
-static int netlink_socket(pid_t *p_pid)
-{
-    struct sockaddr_nl l_addr;
-    socklen_t l_len;
-
-    int l_socket = socket(PF_NETLINK, SOCK_RAW, NETLINK_ROUTE);
-    if(l_socket < 0)
-    {
-        return -1;
-    }
-
-    memset(&l_addr, 0, sizeof(l_addr));
-    l_addr.nl_family = AF_NETLINK;
-    if(bind(l_socket, (struct sockaddr *)&l_addr, sizeof(l_addr)) < 0)
-    {
-        close(l_socket);
-        return -1;
-    }
-
-    l_len = sizeof(l_addr);
-    if(getsockname(l_socket, (struct sockaddr *)&l_addr, &l_len) < 0)
-    {
-        close(l_socket);
-        return -1;
-    }
-    *p_pid = l_addr.nl_pid;
-
-    return l_socket;
-}
-
-static int netlink_send(int p_socket, int p_request)
-{
-    char l_buffer[NLMSG_ALIGN(sizeof(struct nlmsghdr)) + NLMSG_ALIGN(sizeof(struct rtgenmsg))];
-
-    struct nlmsghdr *l_hdr;
-    struct rtgenmsg *l_msg;
-    struct sockaddr_nl l_addr;
-
-    memset(l_buffer, 0, sizeof(l_buffer));
-
-    l_hdr = (struct nlmsghdr *)l_buffer;
-    l_msg = (struct rtgenmsg *)NLMSG_DATA(l_hdr);
-
-    l_hdr->nlmsg_len = NLMSG_LENGTH(sizeof(*l_msg));
-    l_hdr->nlmsg_type = p_request;
-    l_hdr->nlmsg_flags = NLM_F_ROOT | NLM_F_MATCH | NLM_F_REQUEST;
-    l_hdr->nlmsg_pid = 0;
-    l_hdr->nlmsg_seq = p_socket;
-    l_msg->rtgen_family = AF_UNSPEC;
-
-    memset(&l_addr, 0, sizeof(l_addr));
-    l_addr.nl_family = AF_NETLINK;
-    return (sendto(p_socket, l_hdr, l_hdr->nlmsg_len, 0, (struct sockaddr *)&l_addr, sizeof(l_addr)));
-}
-
-static int netlink_recv(int p_socket, void *p_buffer, size_t p_len)
-{
-    struct sockaddr_nl l_addr;
-    struct msghdr l_msg;
-
-    struct iovec l_iov;
-    l_iov.iov_base = p_buffer;
-    l_iov.iov_len = p_len;
-
-    for(;;)
-    {
-        int l_result;
-        l_msg.msg_name = (void *)&l_addr;
-        l_msg.msg_namelen = sizeof(l_addr);
-        l_msg.msg_iov = &l_iov;
-        l_msg.msg_iovlen = 1;
-        l_msg.msg_control = NULL;
-        l_msg.msg_controllen = 0;
-        l_msg.msg_flags = 0;
-        l_result = recvmsg(p_socket, &l_msg, 0);
-
-        if(l_result < 0)
-        {
-            if(errno == EINTR)
-            {
-                continue;
-            }
-            return -2;
-        }
-
-        /* Buffer was too small */
-        if(l_msg.msg_flags & MSG_TRUNC)
-        {
-            return -1;
-        }
-        return l_result;
-    }
-}
-
-static struct nlmsghdr *getNetlinkResponse(int p_socket, pid_t p_pid, int *p_size, int *p_done)
-{
-    size_t l_size = 4096;
-    void *l_buffer = NULL;
-
-    for(;;)
-    {
-        int l_read;
-
-        uv__free(l_buffer);
-        l_buffer = uv__malloc(l_size);
-        if (l_buffer == NULL)
-        {
-            return NULL;
-        }
-
-        l_read = netlink_recv(p_socket, l_buffer, l_size);
-        *p_size = l_read;
-        if(l_read == -2)
-        {
-            uv__free(l_buffer);
-            return NULL;
-        }
-        if(l_read >= 0)
-        {
-            struct nlmsghdr *l_hdr;
-            for(l_hdr = (struct nlmsghdr *)l_buffer; NLMSG_OK(l_hdr, (unsigned int)l_read); l_hdr = (struct nlmsghdr *)NLMSG_NEXT(l_hdr, l_read))
-            {
-                if((pid_t)l_hdr->nlmsg_pid != p_pid || (int)l_hdr->nlmsg_seq != p_socket)
-                {
-                    continue;
-                }
-
-                if(l_hdr->nlmsg_type == NLMSG_DONE)
-                {
-                    *p_done = 1;
-                    break;
-                }
-
-                if(l_hdr->nlmsg_type == NLMSG_ERROR)
-                {
-                    uv__free(l_buffer);
-                    return NULL;
-                }
-            }
-            return l_buffer;
-        }
-
-        l_size *= 2;
-    }
-}
-
-static NetlinkList *newListItem(struct nlmsghdr *p_data, unsigned int p_size)
-{
-    NetlinkList *l_item = (NetlinkList*)uv__malloc(sizeof(NetlinkList));
-    if (l_item == NULL)
-    {
-        return NULL;
-    }
-
-    l_item->m_next = NULL;
-    l_item->m_data = p_data;
-    l_item->m_size = p_size;
-    return l_item;
-}
-
-static void freeResultList(NetlinkList *p_list)
-{
-    NetlinkList *l_cur;
-    while(p_list)
-    {
-        l_cur = p_list;
-        p_list = p_list->m_next;
-        uv__free(l_cur->m_data);
-        uv__free(l_cur);
-    }
-}
-
-static NetlinkList *getResultList(int p_socket, int p_request, pid_t p_pid)
-{
-    int l_size;
-    int l_done;
-    NetlinkList *l_list;
-    NetlinkList *l_end;
-
-    if(netlink_send(p_socket, p_request) < 0)
-    {
-        return NULL;
-    }
-
-    l_list = NULL;
-    l_end = NULL;
-
-    l_done = 0;
-    while(!l_done)
-    {
-        NetlinkList *l_item;
-
-        struct nlmsghdr *l_hdr = getNetlinkResponse(p_socket, p_pid, &l_size, &l_done);
-        /* Error */
-        if(!l_hdr)
-        {
-            freeResultList(l_list);
-            return NULL;
-        }
-
-        l_item = newListItem(l_hdr, l_size);
-        if (!l_item)
-        {
-            freeResultList(l_list);
-            return NULL;
-        }
-        if(!l_list)
-        {
-            l_list = l_item;
-        }
-        else
-        {
-            l_end->m_next = l_item;
-        }
-        l_end = l_item;
-    }
-    return l_list;
-}
-
-static size_t maxSize(size_t a, size_t b)
-{
-    return (a > b ? a : b);
-}
-
-static size_t calcAddrLen(sa_family_t p_family, int p_dataSize)
-{
-    switch(p_family)
-    {
-        case AF_INET:
-            return sizeof(struct sockaddr_in);
-        case AF_INET6:
-            return sizeof(struct sockaddr_in6);
-        case AF_PACKET:
-            return maxSize(sizeof(struct sockaddr_ll), offsetof(struct sockaddr_ll, sll_addr) + p_dataSize);
-        default:
-            return maxSize(sizeof(struct sockaddr), offsetof(struct sockaddr, sa_data) + p_dataSize);
-    }
-}
-
-static void makeSockaddr(sa_family_t p_family, struct sockaddr *p_dest, void *p_data, size_t p_size)
-{
-    switch(p_family)
-    {
-        case AF_INET:
-            memcpy(&((struct sockaddr_in*)p_dest)->sin_addr, p_data, p_size);
-            break;
-        case AF_INET6:
-            memcpy(&((struct sockaddr_in6*)p_dest)->sin6_addr, p_data, p_size);
-            break;
-        case AF_PACKET:
-            memcpy(((struct sockaddr_ll*)p_dest)->sll_addr, p_data, p_size);
-            ((struct sockaddr_ll*)p_dest)->sll_halen = p_size;
-            break;
-        default:
-            memcpy(p_dest->sa_data, p_data, p_size);
-            break;
-    }
-    p_dest->sa_family = p_family;
-}
-
-static void addToEnd(struct ifaddrs **p_resultList, struct ifaddrs *p_entry)
-{
-    if(!*p_resultList)
-    {
-        *p_resultList = p_entry;
-    }
-    else
-    {
-        struct ifaddrs *l_cur = *p_resultList;
-        while(l_cur->ifa_next)
-        {
-            l_cur = l_cur->ifa_next;
-        }
-        l_cur->ifa_next = p_entry;
-    }
-}
-
-static int interpretLink(struct nlmsghdr *p_hdr, struct ifaddrs **p_resultList)
-{
-    struct ifaddrs *l_entry;
-
-    char *l_index;
-    char *l_name;
-    char *l_addr;
-    char *l_data;
-
-    struct ifinfomsg *l_info = (struct ifinfomsg *)NLMSG_DATA(p_hdr);
-
-    size_t l_nameSize = 0;
-    size_t l_addrSize = 0;
-    size_t l_dataSize = 0;
-
-    size_t l_rtaSize = NLMSG_PAYLOAD(p_hdr, sizeof(struct ifinfomsg));
-    struct rtattr *l_rta;
-    for(l_rta = IFLA_RTA(l_info); RTA_OK(l_rta, l_rtaSize); l_rta = RTA_NEXT(l_rta, l_rtaSize))
-    {
-        size_t l_rtaDataSize = RTA_PAYLOAD(l_rta);
-        switch(l_rta->rta_type)
-        {
-            case IFLA_ADDRESS:
-            case IFLA_BROADCAST:
-                l_addrSize += NLMSG_ALIGN(calcAddrLen(AF_PACKET, l_rtaDataSize));
-                break;
-            case IFLA_IFNAME:
-                l_nameSize += NLMSG_ALIGN(l_rtaSize + 1);
-                break;
-            case IFLA_STATS:
-                l_dataSize += NLMSG_ALIGN(l_rtaSize);
-                break;
-            default:
-                break;
-        }
-    }
-
-    l_entry = (struct ifaddrs*)uv__malloc(sizeof(struct ifaddrs) + sizeof(int) + l_nameSize + l_addrSize + l_dataSize);
-    if (l_entry == NULL)
-    {
-        return -1;
-    }
-    memset(l_entry, 0, sizeof(struct ifaddrs));
-    l_entry->ifa_name = "";
-
-    l_index = ((char *)l_entry) + sizeof(struct ifaddrs);
-    l_name = l_index + sizeof(int);
-    l_addr = l_name + l_nameSize;
-    l_data = l_addr + l_addrSize;
-
-    /* Save the interface index so we can look it up when handling the
-     * addresses.
-     */
-    memcpy(l_index, &l_info->ifi_index, sizeof(int));
-
-    l_entry->ifa_flags = l_info->ifi_flags;
-
-    l_rtaSize = NLMSG_PAYLOAD(p_hdr, sizeof(struct ifinfomsg));
-    for(l_rta = IFLA_RTA(l_info); RTA_OK(l_rta, l_rtaSize); l_rta = RTA_NEXT(l_rta, l_rtaSize))
-    {
-        void *l_rtaData = RTA_DATA(l_rta);
-        size_t l_rtaDataSize = RTA_PAYLOAD(l_rta);
-        switch(l_rta->rta_type)
-        {
-            case IFLA_ADDRESS:
-            case IFLA_BROADCAST:
-            {
-                size_t l_addrLen = calcAddrLen(AF_PACKET, l_rtaDataSize);
-                makeSockaddr(AF_PACKET, (struct sockaddr *)l_addr, l_rtaData, l_rtaDataSize);
-                ((struct sockaddr_ll *)l_addr)->sll_ifindex = l_info->ifi_index;
-                ((struct sockaddr_ll *)l_addr)->sll_hatype = l_info->ifi_type;
-                if(l_rta->rta_type == IFLA_ADDRESS)
-                {
-                    l_entry->ifa_addr = (struct sockaddr *)l_addr;
-                }
-                else
-                {
-                    l_entry->ifa_broadaddr = (struct sockaddr *)l_addr;
-                }
-                l_addr += NLMSG_ALIGN(l_addrLen);
-                break;
-            }
-            case IFLA_IFNAME:
-                strncpy(l_name, l_rtaData, l_rtaDataSize);
-                l_name[l_rtaDataSize] = '\0';
-                l_entry->ifa_name = l_name;
-                break;
-            case IFLA_STATS:
-                memcpy(l_data, l_rtaData, l_rtaDataSize);
-                l_entry->ifa_data = l_data;
-                break;
-            default:
-                break;
-        }
-    }
-
-    addToEnd(p_resultList, l_entry);
-    return 0;
-}
-
-static struct ifaddrs *findInterface(int p_index, struct ifaddrs **p_links, int p_numLinks)
-{
-    int l_num = 0;
-    struct ifaddrs *l_cur = *p_links;
-    while(l_cur && l_num < p_numLinks)
-    {
-        char *l_indexPtr = ((char *)l_cur) + sizeof(struct ifaddrs);
-        int l_index;
-        memcpy(&l_index, l_indexPtr, sizeof(int));
-        if(l_index == p_index)
-        {
-            return l_cur;
-        }
-
-        l_cur = l_cur->ifa_next;
-        ++l_num;
-    }
-    return NULL;
-}
-
-static int interpretAddr(struct nlmsghdr *p_hdr, struct ifaddrs **p_resultList, int p_numLinks)
-{
-    struct ifaddrmsg *l_info = (struct ifaddrmsg *)NLMSG_DATA(p_hdr);
-    struct ifaddrs *l_interface = findInterface(l_info->ifa_index, p_resultList, p_numLinks);
-
-    size_t l_nameSize = 0;
-    size_t l_addrSize = 0;
-
-    int l_addedNetmask = 0;
-
-    size_t l_rtaSize = NLMSG_PAYLOAD(p_hdr, sizeof(struct ifaddrmsg));
-    struct rtattr *l_rta;
-    struct ifaddrs *l_entry;
-
-    char *l_name;
-    char *l_addr;
-
-    for(l_rta = IFA_RTA(l_info); RTA_OK(l_rta, l_rtaSize); l_rta = RTA_NEXT(l_rta, l_rtaSize))
-    {
-        size_t l_rtaDataSize = RTA_PAYLOAD(l_rta);
-        if(l_info->ifa_family == AF_PACKET)
-        {
-            continue;
-        }
-
-        switch(l_rta->rta_type)
-        {
-            case IFA_ADDRESS:
-            case IFA_LOCAL:
-                if((l_info->ifa_family == AF_INET || l_info->ifa_family == AF_INET6) && !l_addedNetmask)
-                {
-                    /* Make room for netmask */
-                    l_addrSize += NLMSG_ALIGN(calcAddrLen(l_info->ifa_family, l_rtaDataSize));
-                    l_addedNetmask = 1;
-                }
-            case IFA_BROADCAST:
-                l_addrSize += NLMSG_ALIGN(calcAddrLen(l_info->ifa_family, l_rtaDataSize));
-                break;
-            case IFA_LABEL:
-                l_nameSize += NLMSG_ALIGN(l_rtaDataSize + 1);
-                break;
-            default:
-                break;
-        }
-    }
-
-    l_entry = (struct ifaddrs*)uv__malloc(sizeof(struct ifaddrs) + l_nameSize + l_addrSize);
-    if (l_entry == NULL)
-    {
-        return -1;
-    }
-    memset(l_entry, 0, sizeof(struct ifaddrs));
-    l_entry->ifa_name = (l_interface ? l_interface->ifa_name : "");
-
-    l_name = ((char *)l_entry) + sizeof(struct ifaddrs);
-    l_addr = l_name + l_nameSize;
-
-    l_entry->ifa_flags = l_info->ifa_flags;
-    if(l_interface)
-    {
-        l_entry->ifa_flags |= l_interface->ifa_flags;
-    }
-
-    l_rtaSize = NLMSG_PAYLOAD(p_hdr, sizeof(struct ifaddrmsg));
-    for(l_rta = IFA_RTA(l_info); RTA_OK(l_rta, l_rtaSize); l_rta = RTA_NEXT(l_rta, l_rtaSize))
-    {
-        void *l_rtaData = RTA_DATA(l_rta);
-        size_t l_rtaDataSize = RTA_PAYLOAD(l_rta);
-        switch(l_rta->rta_type)
-        {
-            case IFA_ADDRESS:
-            case IFA_BROADCAST:
-            case IFA_LOCAL:
-            {
-                size_t l_addrLen = calcAddrLen(l_info->ifa_family, l_rtaDataSize);
-                makeSockaddr(l_info->ifa_family, (struct sockaddr *)l_addr, l_rtaData, l_rtaDataSize);
-                if(l_info->ifa_family == AF_INET6)
-                {
-                    if(IN6_IS_ADDR_LINKLOCAL((struct in6_addr *)l_rtaData) || IN6_IS_ADDR_MC_LINKLOCAL((struct in6_addr *)l_rtaData))
-                    {
-                        ((struct sockaddr_in6 *)l_addr)->sin6_scope_id = l_info->ifa_index;
-                    }
-                }
-
-                /* Apparently in a point-to-point network IFA_ADDRESS contains
-                 * the dest address and IFA_LOCAL contains the local address
-                 */
-                if(l_rta->rta_type == IFA_ADDRESS)
-                {
-                    if(l_entry->ifa_addr)
-                    {
-                        l_entry->ifa_dstaddr = (struct sockaddr *)l_addr;
-                    }
-                    else
-                    {
-                        l_entry->ifa_addr = (struct sockaddr *)l_addr;
-                    }
-                }
-                else if(l_rta->rta_type == IFA_LOCAL)
-                {
-                    if(l_entry->ifa_addr)
-                    {
-                        l_entry->ifa_dstaddr = l_entry->ifa_addr;
-                    }
-                    l_entry->ifa_addr = (struct sockaddr *)l_addr;
-                }
-                else
-                {
-                    l_entry->ifa_broadaddr = (struct sockaddr *)l_addr;
-                }
-                l_addr += NLMSG_ALIGN(l_addrLen);
-                break;
-            }
-            case IFA_LABEL:
-                strncpy(l_name, l_rtaData, l_rtaDataSize);
-                l_name[l_rtaDataSize] = '\0';
-                l_entry->ifa_name = l_name;
-                break;
-            default:
-                break;
-        }
-    }
-
-    if(l_entry->ifa_addr && (l_entry->ifa_addr->sa_family == AF_INET || l_entry->ifa_addr->sa_family == AF_INET6))
-    {
-        unsigned l_maxPrefix = (l_entry->ifa_addr->sa_family == AF_INET ? 32 : 128);
-        unsigned l_prefix = (l_info->ifa_prefixlen > l_maxPrefix ? l_maxPrefix : l_info->ifa_prefixlen);
-        unsigned char l_mask[16] = {0};
-        unsigned i;
-        for(i=0; i<(l_prefix/8); ++i)
-        {
-            l_mask[i] = 0xff;
-        }
-        if(l_prefix % 8)
-        {
-            l_mask[i] = 0xff << (8 - (l_prefix % 8));
-        }
-
-        makeSockaddr(l_entry->ifa_addr->sa_family, (struct sockaddr *)l_addr, l_mask, l_maxPrefix / 8);
-        l_entry->ifa_netmask = (struct sockaddr *)l_addr;
-    }
-
-    addToEnd(p_resultList, l_entry);
-    return 0;
-}
-
-static int interpretLinks(int p_socket, pid_t p_pid, NetlinkList *p_netlinkList, struct ifaddrs **p_resultList)
-{
-
-    int l_numLinks = 0;
-    for(; p_netlinkList; p_netlinkList = p_netlinkList->m_next)
-    {
-        unsigned int l_nlsize = p_netlinkList->m_size;
-        struct nlmsghdr *l_hdr;
-        for(l_hdr = p_netlinkList->m_data; NLMSG_OK(l_hdr, l_nlsize); l_hdr = NLMSG_NEXT(l_hdr, l_nlsize))
-        {
-            if((pid_t)l_hdr->nlmsg_pid != p_pid || (int)l_hdr->nlmsg_seq != p_socket)
-            {
-                continue;
-            }
-
-            if(l_hdr->nlmsg_type == NLMSG_DONE)
-            {
-                break;
-            }
-
-            if(l_hdr->nlmsg_type == RTM_NEWLINK)
-            {
-                if(interpretLink(l_hdr, p_resultList) == -1)
-                {
-                    return -1;
-                }
-                ++l_numLinks;
-            }
-        }
-    }
-    return l_numLinks;
-}
-
-static int interpretAddrs(int p_socket, pid_t p_pid, NetlinkList *p_netlinkList, struct ifaddrs **p_resultList, int p_numLinks)
-{
-    for(; p_netlinkList; p_netlinkList = p_netlinkList->m_next)
-    {
-        unsigned int l_nlsize = p_netlinkList->m_size;
-        struct nlmsghdr *l_hdr;
-        for(l_hdr = p_netlinkList->m_data; NLMSG_OK(l_hdr, l_nlsize); l_hdr = NLMSG_NEXT(l_hdr, l_nlsize))
-        {
-            if((pid_t)l_hdr->nlmsg_pid != p_pid || (int)l_hdr->nlmsg_seq != p_socket)
-            {
-                continue;
-            }
-
-            if(l_hdr->nlmsg_type == NLMSG_DONE)
-            {
-                break;
-            }
-
-            if(l_hdr->nlmsg_type == RTM_NEWADDR)
-            {
-                if (interpretAddr(l_hdr, p_resultList, p_numLinks) == -1)
-                {
-                    return -1;
-                }
-            }
-        }
-    }
-    return 0;
-}
-
-int getifaddrs(struct ifaddrs **ifap)
-{
-    int l_socket;
-    int l_result;
-    int l_numLinks;
-    pid_t l_pid;
-    NetlinkList *l_linkResults;
-    NetlinkList *l_addrResults;
-
-    if(!ifap)
-    {
-        return -1;
-    }
-    *ifap = NULL;
-
-    l_socket = netlink_socket(&l_pid);
-    if(l_socket < 0)
-    {
-        return -1;
-    }
-
-    l_linkResults = getResultList(l_socket, RTM_GETLINK, l_pid);
-    if(!l_linkResults)
-    {
-        close(l_socket);
-        return -1;
-    }
-
-    l_addrResults = getResultList(l_socket, RTM_GETADDR, l_pid);
-    if(!l_addrResults)
-    {
-        close(l_socket);
-        freeResultList(l_linkResults);
-        return -1;
-    }
-
-    l_result = 0;
-    l_numLinks = interpretLinks(l_socket, l_pid, l_linkResults, ifap);
-    if(l_numLinks == -1 || interpretAddrs(l_socket, l_pid, l_addrResults, ifap, l_numLinks) == -1)
-    {
-        l_result = -1;
-    }
-
-    freeResultList(l_linkResults);
-    freeResultList(l_addrResults);
-    close(l_socket);
-    return l_result;
-}
-
-void freeifaddrs(struct ifaddrs *ifa)
-{
-    struct ifaddrs *l_cur;
-    while(ifa)
-    {
-        l_cur = ifa;
-        ifa = ifa->ifa_next;
-        uv__free(l_cur);
-    }
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/async.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/async.cpp
deleted file mode 100644
index a5c47bc..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/async.cpp
+++ /dev/null
@@ -1,298 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-/* This file contains both the uv__async internal infrastructure and the
- * user-facing uv_async_t functions.
- */
-
-#include "uv.h"
-#include "internal.h"
-#include "atomic-ops.h"
-
-#include <errno.h>
-#include <stdio.h>  /* snprintf() */
-#include <assert.h>
-#include <stdlib.h>
-#include <string.h>
-#include <unistd.h>
-
-static void uv__async_send(uv_loop_t* loop);
-static int uv__async_start(uv_loop_t* loop);
-static int uv__async_eventfd(void);
-
-
-int uv_async_init(uv_loop_t* loop, uv_async_t* handle, uv_async_cb async_cb) {
-  int err;
-
-  err = uv__async_start(loop);
-  if (err)
-    return err;
-
-  uv__handle_init(loop, (uv_handle_t*)handle, UV_ASYNC);
-  handle->async_cb = async_cb;
-  handle->pending = 0;
-
-  QUEUE_INSERT_TAIL(&loop->async_handles, &handle->queue);
-  uv__handle_start(handle);
-
-  return 0;
-}
-
-
-int uv_async_send(uv_async_t* handle) {
-  /* Do a cheap read first. */
-  if (ACCESS_ONCE(int, handle->pending) != 0)
-    return 0;
-
-  /* Tell the other thread we're busy with the handle. */
-  if (cmpxchgi(&handle->pending, 0, 1) != 0)
-    return 0;
-
-  /* Wake up the other thread's event loop. */
-  uv__async_send(handle->loop);
-
-  /* Tell the other thread we're done. */
-  if (cmpxchgi(&handle->pending, 1, 2) != 1)
-    abort();
-
-  return 0;
-}
-
-
-/* Only call this from the event loop thread. */
-static int uv__async_spin(uv_async_t* handle) {
-  int rc;
-
-  for (;;) {
-    /* rc=0 -- handle is not pending.
-     * rc=1 -- handle is pending, other thread is still working with it.
-     * rc=2 -- handle is pending, other thread is done.
-     */
-    rc = cmpxchgi(&handle->pending, 2, 0);
-
-    if (rc != 1)
-      return rc;
-
-    /* Other thread is busy with this handle, spin until it's done. */
-    cpu_relax();
-  }
-}
-
-
-void uv__async_close(uv_async_t* handle) {
-  uv__async_spin(handle);
-  QUEUE_REMOVE(&handle->queue);
-  uv__handle_stop(handle);
-}
-
-
-static void uv__async_io(uv_loop_t* loop, uv__io_t* w, unsigned int events) {
-  char buf[1024];
-  ssize_t r;
-  QUEUE queue;
-  QUEUE* q;
-  uv_async_t* h;
-
-  assert(w == &loop->async_io_watcher);
-
-  for (;;) {
-    r = read(w->fd, buf, sizeof(buf));
-
-    if (r == sizeof(buf))
-      continue;
-
-    if (r != -1)
-      break;
-
-    if (errno == EAGAIN || errno == EWOULDBLOCK)
-      break;
-
-    if (errno == EINTR)
-      continue;
-
-    abort();
-  }
-
-  QUEUE_MOVE(&loop->async_handles, &queue);
-  while (!QUEUE_EMPTY(&queue)) {
-    q = QUEUE_HEAD(&queue);
-    h = QUEUE_DATA(q, uv_async_t, queue);
-
-    QUEUE_REMOVE(q);
-    QUEUE_INSERT_TAIL(&loop->async_handles, q);
-
-    if (0 == uv__async_spin(h))
-      continue;  /* Not pending. */
-
-    if (h->async_cb == NULL)
-      continue;
-
-    h->async_cb(h);
-  }
-}
-
-
-static void uv__async_send(uv_loop_t* loop) {
-  const void* buf;
-  ssize_t len;
-  int fd;
-  int r;
-
-  buf = "";
-  len = 1;
-  fd = loop->async_wfd;
-
-#if defined(__linux__)
-  if (fd == -1) {
-    static const uint64_t val = 1;
-    buf = &val;
-    len = sizeof(val);
-    fd = loop->async_io_watcher.fd;  /* eventfd */
-  }
-#endif
-
-  do
-    r = write(fd, buf, len);
-  while (r == -1 && errno == EINTR);
-
-  if (r == len)
-    return;
-
-  if (r == -1)
-    if (errno == EAGAIN || errno == EWOULDBLOCK)
-      return;
-
-  abort();
-}
-
-
-static int uv__async_start(uv_loop_t* loop) {
-  int pipefd[2];
-  int err;
-
-  if (loop->async_io_watcher.fd != -1)
-    return 0;
-
-  err = uv__async_eventfd();
-  if (err >= 0) {
-    pipefd[0] = err;
-    pipefd[1] = -1;
-  }
-  else if (err == UV_ENOSYS) {
-    err = uv__make_pipe(pipefd, UV__F_NONBLOCK);
-#if defined(__linux__)
-    /* Save a file descriptor by opening one of the pipe descriptors as
-     * read/write through the procfs.  That file descriptor can then
-     * function as both ends of the pipe.
-     */
-    if (err == 0) {
-      char buf[32];
-      int fd;
-
-      snprintf(buf, sizeof(buf), "/proc/self/fd/%d", pipefd[0]);
-      fd = uv__open_cloexec(buf, O_RDWR);
-      if (fd >= 0) {
-        uv__close(pipefd[0]);
-        uv__close(pipefd[1]);
-        pipefd[0] = fd;
-        pipefd[1] = fd;
-      }
-    }
-#endif
-  }
-
-  if (err < 0)
-    return err;
-
-  uv__io_init(&loop->async_io_watcher, uv__async_io, pipefd[0]);
-  uv__io_start(loop, &loop->async_io_watcher, POLLIN);
-  loop->async_wfd = pipefd[1];
-
-  return 0;
-}
-
-
-int uv__async_fork(uv_loop_t* loop) {
-  if (loop->async_io_watcher.fd == -1) /* never started */
-    return 0;
-
-  uv__async_stop(loop);
-
-  return uv__async_start(loop);
-}
-
-
-void uv__async_stop(uv_loop_t* loop) {
-  if (loop->async_io_watcher.fd == -1)
-    return;
-
-  if (loop->async_wfd != -1) {
-    if (loop->async_wfd != loop->async_io_watcher.fd)
-      uv__close(loop->async_wfd);
-    loop->async_wfd = -1;
-  }
-
-  uv__io_stop(loop, &loop->async_io_watcher, POLLIN);
-  uv__close(loop->async_io_watcher.fd);
-  loop->async_io_watcher.fd = -1;
-}
-
-
-static int uv__async_eventfd(void) {
-#if defined(__linux__)
-  static int no_eventfd2;
-  static int no_eventfd;
-  int fd;
-
-  if (no_eventfd2)
-    goto skip_eventfd2;
-
-  fd = uv__eventfd2(0, UV__EFD_CLOEXEC | UV__EFD_NONBLOCK);
-  if (fd != -1)
-    return fd;
-
-  if (errno != ENOSYS)
-    return UV__ERR(errno);
-
-  no_eventfd2 = 1;
-
-skip_eventfd2:
-
-  if (no_eventfd)
-    goto skip_eventfd;
-
-  fd = uv__eventfd(0);
-  if (fd != -1) {
-    uv__cloexec(fd, 1);
-    uv__nonblock(fd, 1);
-    return fd;
-  }
-
-  if (errno != ENOSYS)
-    return UV__ERR(errno);
-
-  no_eventfd = 1;
-
-skip_eventfd:
-
-#endif
-
-  return UV_ENOSYS;
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/atomic-ops.h b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/atomic-ops.h
deleted file mode 100644
index 541a6c8..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/atomic-ops.h
+++ /dev/null
@@ -1,63 +0,0 @@
-/* Copyright (c) 2013, Ben Noordhuis <info@bnoordhuis.nl>
- *
- * Permission to use, copy, modify, and/or distribute this software for any
- * purpose with or without fee is hereby granted, provided that the above
- * copyright notice and this permission notice appear in all copies.
- *
- * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
- * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
- * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
- * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
- * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
- * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
- * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
- */
-
-#ifndef UV_ATOMIC_OPS_H_
-#define UV_ATOMIC_OPS_H_
-
-#include "internal.h"  /* UV_UNUSED */
-
-#if defined(__SUNPRO_C) || defined(__SUNPRO_CC)
-#include <atomic.h>
-#endif
-
-UV_UNUSED(static int cmpxchgi(int* ptr, int oldval, int newval));
-UV_UNUSED(static void cpu_relax(void));
-
-/* Prefer hand-rolled assembly over the gcc builtins because the latter also
- * issue full memory barriers.
- */
-UV_UNUSED(static int cmpxchgi(int* ptr, int oldval, int newval)) {
-#if defined(__i386__) || defined(__x86_64__)
-  int out;
-  __asm__ __volatile__ ("lock; cmpxchg %2, %1;"
-                        : "=a" (out), "+m" (*(volatile int*) ptr)
-                        : "r" (newval), "0" (oldval)
-                        : "memory");
-  return out;
-#elif defined(_AIX) && defined(__xlC__)
-  const int out = (*(volatile int*) ptr);
-  __compare_and_swap(ptr, &oldval, newval);
-  return out;
-#elif defined(__MVS__)
-  unsigned int op4;
-  if (__plo_CSST(ptr, (unsigned int*) &oldval, newval,
-                (unsigned int*) ptr, *ptr, &op4))
-    return oldval;
-  else
-    return op4;
-#elif defined(__SUNPRO_C) || defined(__SUNPRO_CC)
-  return atomic_cas_uint((uint_t *)ptr, (uint_t)oldval, (uint_t)newval);
-#else
-  return __sync_val_compare_and_swap(ptr, oldval, newval);
-#endif
-}
-
-UV_UNUSED(static void cpu_relax(void)) {
-#if defined(__i386__) || defined(__x86_64__)
-  __asm__ __volatile__ ("rep; nop");  /* a.k.a. PAUSE */
-#endif
-}
-
-#endif  /* UV_ATOMIC_OPS_H_ */
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/bsd-ifaddrs.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/bsd-ifaddrs.cpp
deleted file mode 100644
index a01aa8d..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/bsd-ifaddrs.cpp
+++ /dev/null
@@ -1,159 +0,0 @@
-/* Copyright libuv project contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include "uv.h"
-#include "internal.h"
-
-#include <errno.h>
-#include <stddef.h>
-
-#include <ifaddrs.h>
-#include <net/if.h>
-#if !defined(__CYGWIN__) && !defined(__MSYS__)
-#include <net/if_dl.h>
-#endif
-
-#if defined(__HAIKU__)
-#define IFF_RUNNING IFF_LINK
-#endif
-
-static int uv__ifaddr_exclude(struct ifaddrs *ent, int exclude_type) {
-  if (!((ent->ifa_flags & IFF_UP) && (ent->ifa_flags & IFF_RUNNING)))
-    return 1;
-  if (ent->ifa_addr == NULL)
-    return 1;
-#if !defined(__CYGWIN__) && !defined(__MSYS__)
-  /*
-   * If `exclude_type` is `UV__EXCLUDE_IFPHYS`, just see whether `sa_family`
-   * equals to `AF_LINK` or not. Otherwise, the result depends on the operation
-   * system with `AF_LINK` or `PF_INET`.
-   */
-  if (exclude_type == UV__EXCLUDE_IFPHYS)
-    return (ent->ifa_addr->sa_family != AF_LINK);
-#endif
-#if defined(__APPLE__) || defined(__FreeBSD__) || defined(__DragonFly__) || \
-    defined(__HAIKU__)
-  /*
-   * On BSD getifaddrs returns information related to the raw underlying
-   * devices.  We're not interested in this information.
-   */
-  if (ent->ifa_addr->sa_family == AF_LINK)
-    return 1;
-#elif defined(__NetBSD__) || defined(__OpenBSD__)
-  if (ent->ifa_addr->sa_family != PF_INET &&
-      ent->ifa_addr->sa_family != PF_INET6)
-    return 1;
-#endif
-  return 0;
-}
-
-int uv_interface_addresses(uv_interface_address_t** addresses, int* count) {
-  struct ifaddrs* addrs;
-  struct ifaddrs* ent;
-  uv_interface_address_t* address;
-  int i;
-
-  *count = 0;
-  *addresses = NULL;
-
-  if (getifaddrs(&addrs) != 0)
-    return UV__ERR(errno);
-
-  /* Count the number of interfaces */
-  for (ent = addrs; ent != NULL; ent = ent->ifa_next) {
-    if (uv__ifaddr_exclude(ent, UV__EXCLUDE_IFADDR))
-      continue;
-    (*count)++;
-  }
-
-  if (*count == 0) {
-    freeifaddrs(addrs);
-    return 0;
-  }
-
-  /* Make sure the memory is initiallized to zero using calloc() */
-  *addresses = (uv_interface_address_t*)uv__calloc(*count, sizeof(**addresses));
-
-  if (*addresses == NULL) {
-    freeifaddrs(addrs);
-    return UV_ENOMEM;
-  }
-
-  address = *addresses;
-
-  for (ent = addrs; ent != NULL; ent = ent->ifa_next) {
-    if (uv__ifaddr_exclude(ent, UV__EXCLUDE_IFADDR))
-      continue;
-
-    address->name = uv__strdup(ent->ifa_name);
-
-    if (ent->ifa_addr->sa_family == AF_INET6) {
-      address->address.address6 = *((struct sockaddr_in6*) ent->ifa_addr);
-    } else {
-      address->address.address4 = *((struct sockaddr_in*) ent->ifa_addr);
-    }
-
-    if (ent->ifa_netmask->sa_family == AF_INET6) {
-      address->netmask.netmask6 = *((struct sockaddr_in6*) ent->ifa_netmask);
-    } else {
-      address->netmask.netmask4 = *((struct sockaddr_in*) ent->ifa_netmask);
-    }
-
-    address->is_internal = !!(ent->ifa_flags & IFF_LOOPBACK);
-
-    address++;
-  }
-
-#if !(defined(__CYGWIN__) || defined(__MSYS__))
-  /* Fill in physical addresses for each interface */
-  for (ent = addrs; ent != NULL; ent = ent->ifa_next) {
-    if (uv__ifaddr_exclude(ent, UV__EXCLUDE_IFPHYS))
-      continue;
-
-    address = *addresses;
-
-    for (i = 0; i < *count; i++) {
-      if (strcmp(address->name, ent->ifa_name) == 0) {
-        struct sockaddr_dl* sa_addr;
-        sa_addr = (struct sockaddr_dl*)(ent->ifa_addr);
-        memcpy(address->phys_addr, LLADDR(sa_addr), sizeof(address->phys_addr));
-      }
-      address++;
-    }
-  }
-#endif
-
-  freeifaddrs(addrs);
-
-  return 0;
-}
-
-
-void uv_free_interface_addresses(uv_interface_address_t* addresses,
-                                 int count) {
-  int i;
-
-  for (i = 0; i < count; i++) {
-    uv__free(addresses[i].name);
-  }
-
-  uv__free(addresses);
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/core.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/core.cpp
deleted file mode 100644
index 77bb337..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/core.cpp
+++ /dev/null
@@ -1,1509 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include "uv.h"
-#include "internal.h"
-
-#include <stddef.h> /* NULL */
-#include <stdio.h> /* printf */
-#include <stdlib.h>
-#include <string.h> /* strerror */
-#include <errno.h>
-#include <assert.h>
-#include <unistd.h>
-#include <sys/types.h>
-#include <sys/stat.h>
-#include <fcntl.h>
-#include <sys/ioctl.h>
-#include <sys/socket.h>
-#include <sys/un.h>
-#include <netinet/in.h>
-#include <arpa/inet.h>
-#include <limits.h> /* INT_MAX, PATH_MAX, IOV_MAX */
-#include <sys/uio.h> /* writev */
-#include <sys/resource.h> /* getrusage */
-#include <pwd.h>
-#include <sys/utsname.h>
-#include <sys/time.h>
-
-#ifdef __sun
-# include <sys/filio.h>
-# include <sys/types.h>
-# include <sys/wait.h>
-#endif
-
-#ifdef __APPLE__
-# include <mach-o/dyld.h> /* _NSGetExecutablePath */
-# include <sys/filio.h>
-# if defined(O_CLOEXEC)
-#  define UV__O_CLOEXEC O_CLOEXEC
-# endif
-#endif
-
-#if defined(__DragonFly__)      || \
-    defined(__FreeBSD__)        || \
-    defined(__FreeBSD_kernel__) || \
-    defined(__NetBSD__)
-# include <sys/sysctl.h>
-# include <sys/filio.h>
-# include <sys/wait.h>
-# define UV__O_CLOEXEC O_CLOEXEC
-# if defined(__FreeBSD__) && __FreeBSD__ >= 10
-#  define uv__accept4 accept4
-# endif
-# if defined(__NetBSD__)
-#  define uv__accept4(a, b, c, d) paccept((a), (b), (c), NULL, (d))
-# endif
-# if (defined(__FreeBSD__) && __FreeBSD__ >= 10) || defined(__NetBSD__)
-#  define UV__SOCK_NONBLOCK SOCK_NONBLOCK
-#  define UV__SOCK_CLOEXEC  SOCK_CLOEXEC
-# endif
-# if !defined(F_DUP2FD_CLOEXEC) && defined(_F_DUP2FD_CLOEXEC)
-#  define F_DUP2FD_CLOEXEC  _F_DUP2FD_CLOEXEC
-# endif
-#endif
-
-#if defined(__ANDROID_API__) && __ANDROID_API__ < 21
-# include <dlfcn.h>  /* for dlsym */
-#endif
-
-#if defined(__MVS__)
-#include <sys/ioctl.h>
-#endif
-
-#if defined(__linux__)
-#include <sys/syscall.h>
-#endif
-
-static int uv__run_pending(uv_loop_t* loop);
-
-/* Verify that uv_buf_t is ABI-compatible with struct iovec. */
-STATIC_ASSERT(sizeof(uv_buf_t) == sizeof(struct iovec));
-STATIC_ASSERT(sizeof(&((uv_buf_t*) 0)->base) ==
-              sizeof(((struct iovec*) 0)->iov_base));
-STATIC_ASSERT(sizeof(&((uv_buf_t*) 0)->len) ==
-              sizeof(((struct iovec*) 0)->iov_len));
-STATIC_ASSERT(offsetof(uv_buf_t, base) == offsetof(struct iovec, iov_base));
-STATIC_ASSERT(offsetof(uv_buf_t, len) == offsetof(struct iovec, iov_len));
-
-
-uint64_t uv_hrtime(void) {
-  return uv__hrtime(UV_CLOCK_PRECISE);
-}
-
-
-void uv_close(uv_handle_t* handle, uv_close_cb close_cb) {
-  assert(!uv__is_closing(handle));
-
-  handle->flags |= UV_HANDLE_CLOSING;
-  handle->close_cb = close_cb;
-
-  switch (handle->type) {
-  case UV_NAMED_PIPE:
-    uv__pipe_close((uv_pipe_t*)handle);
-    break;
-
-  case UV_TTY:
-    uv__stream_close((uv_stream_t*)handle);
-    break;
-
-  case UV_TCP:
-    uv__tcp_close((uv_tcp_t*)handle);
-    break;
-
-  case UV_UDP:
-    uv__udp_close((uv_udp_t*)handle);
-    break;
-
-  case UV_PREPARE:
-    uv__prepare_close((uv_prepare_t*)handle);
-    break;
-
-  case UV_CHECK:
-    uv__check_close((uv_check_t*)handle);
-    break;
-
-  case UV_IDLE:
-    uv__idle_close((uv_idle_t*)handle);
-    break;
-
-  case UV_ASYNC:
-    uv__async_close((uv_async_t*)handle);
-    break;
-
-  case UV_TIMER:
-    uv__timer_close((uv_timer_t*)handle);
-    break;
-
-  case UV_PROCESS:
-    uv__process_close((uv_process_t*)handle);
-    break;
-
-  case UV_FS_EVENT:
-    uv__fs_event_close((uv_fs_event_t*)handle);
-    break;
-
-  case UV_POLL:
-    uv__poll_close((uv_poll_t*)handle);
-    break;
-
-  case UV_FS_POLL:
-    uv__fs_poll_close((uv_fs_poll_t*)handle);
-    /* Poll handles use file system requests, and one of them may still be
-     * running. The poll code will call uv__make_close_pending() for us. */
-    return;
-
-  case UV_SIGNAL:
-    uv__signal_close((uv_signal_t*) handle);
-    /* Signal handles may not be closed immediately. The signal code will
-     * itself close uv__make_close_pending whenever appropriate. */
-    return;
-
-  default:
-    assert(0);
-  }
-
-  uv__make_close_pending(handle);
-}
-
-int uv__socket_sockopt(uv_handle_t* handle, int optname, int* value) {
-  int r;
-  int fd;
-  socklen_t len;
-
-  if (handle == NULL || value == NULL)
-    return UV_EINVAL;
-
-  if (handle->type == UV_TCP || handle->type == UV_NAMED_PIPE)
-    fd = uv__stream_fd((uv_stream_t*) handle);
-  else if (handle->type == UV_UDP)
-    fd = ((uv_udp_t *) handle)->io_watcher.fd;
-  else
-    return UV_ENOTSUP;
-
-  len = sizeof(*value);
-
-  if (*value == 0)
-    r = getsockopt(fd, SOL_SOCKET, optname, value, &len);
-  else
-    r = setsockopt(fd, SOL_SOCKET, optname, (const void*) value, len);
-
-  if (r < 0)
-    return UV__ERR(errno);
-
-  return 0;
-}
-
-void uv__make_close_pending(uv_handle_t* handle) {
-  assert(handle->flags & UV_HANDLE_CLOSING);
-  assert(!(handle->flags & UV_HANDLE_CLOSED));
-  handle->next_closing = handle->loop->closing_handles;
-  handle->loop->closing_handles = handle;
-}
-
-int uv__getiovmax(void) {
-#if defined(IOV_MAX)
-  return IOV_MAX;
-#elif defined(_SC_IOV_MAX)
-  static int iovmax = -1;
-  if (iovmax == -1) {
-    iovmax = sysconf(_SC_IOV_MAX);
-    /* On some embedded devices (arm-linux-uclibc based ip camera),
-     * sysconf(_SC_IOV_MAX) can not get the correct value. The return
-     * value is -1 and the errno is EINPROGRESS. Degrade the value to 1.
-     */
-    if (iovmax == -1) iovmax = 1;
-  }
-  return iovmax;
-#else
-  return 1024;
-#endif
-}
-
-
-static void uv__finish_close(uv_handle_t* handle) {
-  /* Note: while the handle is in the UV_HANDLE_CLOSING state now, it's still
-   * possible for it to be active in the sense that uv__is_active() returns
-   * true.
-   *
-   * A good example is when the user calls uv_shutdown(), immediately followed
-   * by uv_close(). The handle is considered active at this point because the
-   * completion of the shutdown req is still pending.
-   */
-  assert(handle->flags & UV_HANDLE_CLOSING);
-  assert(!(handle->flags & UV_HANDLE_CLOSED));
-  handle->flags |= UV_HANDLE_CLOSED;
-
-  switch (handle->type) {
-    case UV_PREPARE:
-    case UV_CHECK:
-    case UV_IDLE:
-    case UV_ASYNC:
-    case UV_TIMER:
-    case UV_PROCESS:
-    case UV_FS_EVENT:
-    case UV_FS_POLL:
-    case UV_POLL:
-    case UV_SIGNAL:
-      break;
-
-    case UV_NAMED_PIPE:
-    case UV_TCP:
-    case UV_TTY:
-      uv__stream_destroy((uv_stream_t*)handle);
-      break;
-
-    case UV_UDP:
-      uv__udp_finish_close((uv_udp_t*)handle);
-      break;
-
-    default:
-      assert(0);
-      break;
-  }
-
-  uv__handle_unref(handle);
-  QUEUE_REMOVE(&handle->handle_queue);
-
-  if (handle->close_cb) {
-    handle->close_cb(handle);
-  }
-}
-
-
-static void uv__run_closing_handles(uv_loop_t* loop) {
-  uv_handle_t* p;
-  uv_handle_t* q;
-
-  p = loop->closing_handles;
-  loop->closing_handles = NULL;
-
-  while (p) {
-    q = p->next_closing;
-    uv__finish_close(p);
-    p = q;
-  }
-}
-
-
-int uv_is_closing(const uv_handle_t* handle) {
-  return uv__is_closing(handle);
-}
-
-
-int uv_backend_fd(const uv_loop_t* loop) {
-  return loop->backend_fd;
-}
-
-
-int uv_backend_timeout(const uv_loop_t* loop) {
-  if (loop->stop_flag != 0)
-    return 0;
-
-  if (!uv__has_active_handles(loop) && !uv__has_active_reqs(loop))
-    return 0;
-
-  if (!QUEUE_EMPTY(&loop->idle_handles))
-    return 0;
-
-  if (!QUEUE_EMPTY(&loop->pending_queue))
-    return 0;
-
-  if (loop->closing_handles)
-    return 0;
-
-  return uv__next_timeout(loop);
-}
-
-
-static int uv__loop_alive(const uv_loop_t* loop) {
-  return uv__has_active_handles(loop) ||
-         uv__has_active_reqs(loop) ||
-         loop->closing_handles != NULL;
-}
-
-
-int uv_loop_alive(const uv_loop_t* loop) {
-    return uv__loop_alive(loop);
-}
-
-
-int uv_run(uv_loop_t* loop, uv_run_mode mode) {
-  int timeout;
-  int r;
-  int ran_pending;
-
-  r = uv__loop_alive(loop);
-  if (!r)
-    uv__update_time(loop);
-
-  while (r != 0 && loop->stop_flag == 0) {
-    uv__update_time(loop);
-    uv__run_timers(loop);
-    ran_pending = uv__run_pending(loop);
-    uv__run_idle(loop);
-    uv__run_prepare(loop);
-
-    timeout = 0;
-    if ((mode == UV_RUN_ONCE && !ran_pending) || mode == UV_RUN_DEFAULT)
-      timeout = uv_backend_timeout(loop);
-
-    uv__io_poll(loop, timeout);
-    uv__run_check(loop);
-    uv__run_closing_handles(loop);
-
-    if (mode == UV_RUN_ONCE) {
-      /* UV_RUN_ONCE implies forward progress: at least one callback must have
-       * been invoked when it returns. uv__io_poll() can return without doing
-       * I/O (meaning: no callbacks) when its timeout expires - which means we
-       * have pending timers that satisfy the forward progress constraint.
-       *
-       * UV_RUN_NOWAIT makes no guarantees about progress so it's omitted from
-       * the check.
-       */
-      uv__update_time(loop);
-      uv__run_timers(loop);
-    }
-
-    r = uv__loop_alive(loop);
-    if (mode == UV_RUN_ONCE || mode == UV_RUN_NOWAIT)
-      break;
-  }
-
-  /* The if statement lets gcc compile it to a conditional store. Avoids
-   * dirtying a cache line.
-   */
-  if (loop->stop_flag != 0)
-    loop->stop_flag = 0;
-
-  return r;
-}
-
-
-void uv_update_time(uv_loop_t* loop) {
-  uv__update_time(loop);
-}
-
-
-int uv_is_active(const uv_handle_t* handle) {
-  return uv__is_active(handle);
-}
-
-
-/* Open a socket in non-blocking close-on-exec mode, atomically if possible. */
-int uv__socket(int domain, int type, int protocol) {
-  int sockfd;
-  int err;
-
-#if defined(SOCK_NONBLOCK) && defined(SOCK_CLOEXEC)
-  sockfd = socket(domain, type | SOCK_NONBLOCK | SOCK_CLOEXEC, protocol);
-  if (sockfd != -1)
-    return sockfd;
-
-  if (errno != EINVAL)
-    return UV__ERR(errno);
-#endif
-
-  sockfd = socket(domain, type, protocol);
-  if (sockfd == -1)
-    return UV__ERR(errno);
-
-  err = uv__nonblock(sockfd, 1);
-  if (err == 0)
-    err = uv__cloexec(sockfd, 1);
-
-  if (err) {
-    uv__close(sockfd);
-    return err;
-  }
-
-#if defined(SO_NOSIGPIPE)
-  {
-    int on = 1;
-    setsockopt(sockfd, SOL_SOCKET, SO_NOSIGPIPE, &on, sizeof(on));
-  }
-#endif
-
-  return sockfd;
-}
-
-/* get a file pointer to a file in read-only and close-on-exec mode */
-FILE* uv__open_file(const char* path) {
-  int fd;
-  FILE* fp;
-
-  fd = uv__open_cloexec(path, O_RDONLY);
-  if (fd < 0)
-    return NULL;
-
-   fp = fdopen(fd, "r");
-   if (fp == NULL)
-     uv__close(fd);
-
-   return fp;
-}
-
-
-int uv__accept(int sockfd) {
-  int peerfd;
-  int err;
-
-  assert(sockfd >= 0);
-
-  while (1) {
-#if defined(__linux__)                          || \
-    (defined(__FreeBSD__) && __FreeBSD__ >= 10) || \
-    defined(__NetBSD__)
-    static int no_accept4;
-
-    if (no_accept4)
-      goto skip;
-
-    peerfd = uv__accept4(sockfd,
-                         NULL,
-                         NULL,
-                         UV__SOCK_NONBLOCK|UV__SOCK_CLOEXEC);
-    if (peerfd != -1)
-      return peerfd;
-
-    if (errno == EINTR)
-      continue;
-
-    if (errno != ENOSYS)
-      return UV__ERR(errno);
-
-    no_accept4 = 1;
-skip:
-#endif
-
-    peerfd = accept(sockfd, NULL, NULL);
-    if (peerfd == -1) {
-      if (errno == EINTR)
-        continue;
-      return UV__ERR(errno);
-    }
-
-    err = uv__cloexec(peerfd, 1);
-    if (err == 0)
-      err = uv__nonblock(peerfd, 1);
-
-    if (err) {
-      uv__close(peerfd);
-      return err;
-    }
-
-    return peerfd;
-  }
-}
-
-
-#if defined(__APPLE__)
-#pragma GCC diagnostic push
-#pragma GCC diagnostic ignored "-Wdollar-in-identifier-extension"
-#if defined(__LP64__)
-  extern "C" int close$NOCANCEL(int);
-#else
-  extern "C" int close$NOCANCEL$UNIX2003(int);
-#endif
-#pragma GCC diagnostic pop
-#endif
-
-/* close() on macos has the "interesting" quirk that it fails with EINTR
- * without closing the file descriptor when a thread is in the cancel state.
- * That's why libuv calls close$NOCANCEL() instead.
- *
- * glibc on linux has a similar issue: close() is a cancellation point and
- * will unwind the thread when it's in the cancel state. Work around that
- * by making the system call directly. Musl libc is unaffected.
- */
-int uv__close_nocancel(int fd) {
-#if defined(__APPLE__)
-#pragma GCC diagnostic push
-#pragma GCC diagnostic ignored "-Wdollar-in-identifier-extension"
-#if defined(__LP64__)
-  return close$NOCANCEL(fd);
-#else
-  return close$NOCANCEL$UNIX2003(fd);
-#endif
-#pragma GCC diagnostic pop
-#elif defined(__linux__)
-  return syscall(SYS_close, fd);
-#else
-  return close(fd);
-#endif
-}
-
-
-int uv__close_nocheckstdio(int fd) {
-  int saved_errno;
-  int rc;
-
-  assert(fd > -1);  /* Catch uninitialized io_watcher.fd bugs. */
-
-  saved_errno = errno;
-  rc = uv__close_nocancel(fd);
-  if (rc == -1) {
-    rc = UV__ERR(errno);
-    if (rc == UV_EINTR || rc == UV__ERR(EINPROGRESS))
-      rc = 0;    /* The close is in progress, not an error. */
-    errno = saved_errno;
-  }
-
-  return rc;
-}
-
-
-int uv__close(int fd) {
-  assert(fd > STDERR_FILENO);  /* Catch stdio close bugs. */
-#if defined(__MVS__)
-  SAVE_ERRNO(epoll_file_close(fd));
-#endif
-  return uv__close_nocheckstdio(fd);
-}
-
-
-int uv__nonblock_ioctl(int fd, int set) {
-  int r;
-
-  do
-    r = ioctl(fd, FIONBIO, &set);
-  while (r == -1 && errno == EINTR);
-
-  if (r)
-    return UV__ERR(errno);
-
-  return 0;
-}
-
-
-#if !defined(__CYGWIN__) && !defined(__MSYS__) && !defined(__HAIKU__)
-int uv__cloexec_ioctl(int fd, int set) {
-  int r;
-
-  do
-    r = ioctl(fd, set ? FIOCLEX : FIONCLEX);
-  while (r == -1 && errno == EINTR);
-
-  if (r)
-    return UV__ERR(errno);
-
-  return 0;
-}
-#endif
-
-
-int uv__nonblock_fcntl(int fd, int set) {
-  int flags;
-  int r;
-
-  do
-    r = fcntl(fd, F_GETFL);
-  while (r == -1 && errno == EINTR);
-
-  if (r == -1)
-    return UV__ERR(errno);
-
-  /* Bail out now if already set/clear. */
-  if (!!(r & O_NONBLOCK) == !!set)
-    return 0;
-
-  if (set)
-    flags = r | O_NONBLOCK;
-  else
-    flags = r & ~O_NONBLOCK;
-
-  do
-    r = fcntl(fd, F_SETFL, flags);
-  while (r == -1 && errno == EINTR);
-
-  if (r)
-    return UV__ERR(errno);
-
-  return 0;
-}
-
-
-int uv__cloexec_fcntl(int fd, int set) {
-  int flags;
-  int r;
-
-  do
-    r = fcntl(fd, F_GETFD);
-  while (r == -1 && errno == EINTR);
-
-  if (r == -1)
-    return UV__ERR(errno);
-
-  /* Bail out now if already set/clear. */
-  if (!!(r & FD_CLOEXEC) == !!set)
-    return 0;
-
-  if (set)
-    flags = r | FD_CLOEXEC;
-  else
-    flags = r & ~FD_CLOEXEC;
-
-  do
-    r = fcntl(fd, F_SETFD, flags);
-  while (r == -1 && errno == EINTR);
-
-  if (r)
-    return UV__ERR(errno);
-
-  return 0;
-}
-
-
-ssize_t uv__recvmsg(int fd, struct msghdr* msg, int flags) {
-  struct cmsghdr* cmsg;
-  ssize_t rc;
-  int* pfd;
-  int* end;
-#if defined(__linux__)
-  static int no_msg_cmsg_cloexec;
-  if (no_msg_cmsg_cloexec == 0) {
-    rc = recvmsg(fd, msg, flags | 0x40000000);  /* MSG_CMSG_CLOEXEC */
-    if (rc != -1)
-      return rc;
-    if (errno != EINVAL)
-      return UV__ERR(errno);
-    rc = recvmsg(fd, msg, flags);
-    if (rc == -1)
-      return UV__ERR(errno);
-    no_msg_cmsg_cloexec = 1;
-  } else {
-    rc = recvmsg(fd, msg, flags);
-  }
-#else
-  rc = recvmsg(fd, msg, flags);
-#endif
-  if (rc == -1)
-    return UV__ERR(errno);
-  if (msg->msg_controllen == 0)
-    return rc;
-  for (cmsg = CMSG_FIRSTHDR(msg); cmsg != NULL; cmsg = CMSG_NXTHDR(msg, cmsg))
-    if (cmsg->cmsg_type == SCM_RIGHTS)
-      for (pfd = (int*) CMSG_DATA(cmsg),
-           end = (int*) ((char*) cmsg + cmsg->cmsg_len);
-           pfd < end;
-           pfd += 1)
-        uv__cloexec(*pfd, 1);
-  return rc;
-}
-
-
-int uv_cwd(char* buffer, size_t* size) {
-  char scratch[1 + UV__PATH_MAX];
-
-  if (buffer == NULL || size == NULL)
-    return UV_EINVAL;
-
-  /* Try to read directly into the user's buffer first... */
-  if (getcwd(buffer, *size) != NULL)
-    goto fixup;
-
-  if (errno != ERANGE)
-    return UV__ERR(errno);
-
-  /* ...or into scratch space if the user's buffer is too small
-   * so we can report how much space to provide on the next try.
-   */
-  if (getcwd(scratch, sizeof(scratch)) == NULL)
-    return UV__ERR(errno);
-
-  buffer = scratch;
-
-fixup:
-
-  *size = strlen(buffer);
-
-  if (*size > 1 && buffer[*size - 1] == '/') {
-    *size -= 1;
-    buffer[*size] = '\0';
-  }
-
-  if (buffer == scratch) {
-    *size += 1;
-    return UV_ENOBUFS;
-  }
-
-  return 0;
-}
-
-
-int uv_chdir(const char* dir) {
-  if (chdir(dir))
-    return UV__ERR(errno);
-
-  return 0;
-}
-
-
-void uv_disable_stdio_inheritance(void) {
-  int fd;
-
-  /* Set the CLOEXEC flag on all open descriptors. Unconditionally try the
-   * first 16 file descriptors. After that, bail out after the first error.
-   */
-  for (fd = 0; ; fd++)
-    if (uv__cloexec(fd, 1) && fd > 15)
-      break;
-}
-
-
-int uv_fileno(const uv_handle_t* handle, uv_os_fd_t* fd) {
-  int fd_out;
-
-  switch (handle->type) {
-  case UV_TCP:
-  case UV_NAMED_PIPE:
-  case UV_TTY:
-    fd_out = uv__stream_fd((uv_stream_t*) handle);
-    break;
-
-  case UV_UDP:
-    fd_out = ((uv_udp_t *) handle)->io_watcher.fd;
-    break;
-
-  case UV_POLL:
-    fd_out = ((uv_poll_t *) handle)->io_watcher.fd;
-    break;
-
-  default:
-    return UV_EINVAL;
-  }
-
-  if (uv__is_closing(handle) || fd_out == -1)
-    return UV_EBADF;
-
-  *fd = fd_out;
-  return 0;
-}
-
-
-static int uv__run_pending(uv_loop_t* loop) {
-  QUEUE* q;
-  QUEUE pq;
-  uv__io_t* w;
-
-  if (QUEUE_EMPTY(&loop->pending_queue))
-    return 0;
-
-  QUEUE_MOVE(&loop->pending_queue, &pq);
-
-  while (!QUEUE_EMPTY(&pq)) {
-    q = QUEUE_HEAD(&pq);
-    QUEUE_REMOVE(q);
-    QUEUE_INIT(q);
-    w = QUEUE_DATA(q, uv__io_t, pending_queue);
-    w->cb(loop, w, POLLOUT);
-  }
-
-  return 1;
-}
-
-
-static unsigned int next_power_of_two(unsigned int val) {
-  val -= 1;
-  val |= val >> 1;
-  val |= val >> 2;
-  val |= val >> 4;
-  val |= val >> 8;
-  val |= val >> 16;
-  val += 1;
-  return val;
-}
-
-static void maybe_resize(uv_loop_t* loop, unsigned int len) {
-  void** watchers;
-  void* fake_watcher_list;
-  void* fake_watcher_count;
-  unsigned int nwatchers;
-  unsigned int i;
-
-  if (len <= loop->nwatchers)
-    return;
-
-  /* Preserve fake watcher list and count at the end of the watchers */
-  if (loop->watchers != NULL) {
-    fake_watcher_list = loop->watchers[loop->nwatchers];
-    fake_watcher_count = loop->watchers[loop->nwatchers + 1];
-  } else {
-    fake_watcher_list = NULL;
-    fake_watcher_count = NULL;
-  }
-
-  nwatchers = next_power_of_two(len + 2) - 2;
-  watchers = (void**)
-      uv__realloc(loop->watchers, (nwatchers + 2) * sizeof(loop->watchers[0]));
-
-  if (watchers == NULL)
-    abort();
-  for (i = loop->nwatchers; i < nwatchers; i++)
-    watchers[i] = NULL;
-  watchers[nwatchers] = fake_watcher_list;
-  watchers[nwatchers + 1] = fake_watcher_count;
-
-  loop->watchers = watchers;
-  loop->nwatchers = nwatchers;
-}
-
-
-void uv__io_init(uv__io_t* w, uv__io_cb cb, int fd) {
-  assert(cb != NULL);
-  assert(fd >= -1);
-  QUEUE_INIT(&w->pending_queue);
-  QUEUE_INIT(&w->watcher_queue);
-  w->cb = cb;
-  w->fd = fd;
-  w->events = 0;
-  w->pevents = 0;
-
-#if defined(UV_HAVE_KQUEUE)
-  w->rcount = 0;
-  w->wcount = 0;
-#endif /* defined(UV_HAVE_KQUEUE) */
-}
-
-
-void uv__io_start(uv_loop_t* loop, uv__io_t* w, unsigned int events) {
-  assert(0 == (events & ~(POLLIN | POLLOUT | UV__POLLRDHUP | UV__POLLPRI)));
-  assert(0 != events);
-  assert(w->fd >= 0);
-  assert(w->fd < INT_MAX);
-
-  w->pevents |= events;
-  maybe_resize(loop, w->fd + 1);
-
-#if !defined(__sun)
-  /* The event ports backend needs to rearm all file descriptors on each and
-   * every tick of the event loop but the other backends allow us to
-   * short-circuit here if the event mask is unchanged.
-   */
-  if (w->events == w->pevents)
-    return;
-#endif
-
-  if (QUEUE_EMPTY(&w->watcher_queue))
-    QUEUE_INSERT_TAIL(&loop->watcher_queue, &w->watcher_queue);
-
-  if (loop->watchers[w->fd] == NULL) {
-    loop->watchers[w->fd] = w;
-    loop->nfds++;
-  }
-}
-
-
-void uv__io_stop(uv_loop_t* loop, uv__io_t* w, unsigned int events) {
-  assert(0 == (events & ~(POLLIN | POLLOUT | UV__POLLRDHUP | UV__POLLPRI)));
-  assert(0 != events);
-
-  if (w->fd == -1)
-    return;
-
-  assert(w->fd >= 0);
-
-  /* Happens when uv__io_stop() is called on a handle that was never started. */
-  if ((unsigned) w->fd >= loop->nwatchers)
-    return;
-
-  w->pevents &= ~events;
-
-  if (w->pevents == 0) {
-    QUEUE_REMOVE(&w->watcher_queue);
-    QUEUE_INIT(&w->watcher_queue);
-
-    if (loop->watchers[w->fd] != NULL) {
-      assert(loop->watchers[w->fd] == w);
-      assert(loop->nfds > 0);
-      loop->watchers[w->fd] = NULL;
-      loop->nfds--;
-      w->events = 0;
-    }
-  }
-  else if (QUEUE_EMPTY(&w->watcher_queue))
-    QUEUE_INSERT_TAIL(&loop->watcher_queue, &w->watcher_queue);
-}
-
-
-void uv__io_close(uv_loop_t* loop, uv__io_t* w) {
-  uv__io_stop(loop, w, POLLIN | POLLOUT | UV__POLLRDHUP | UV__POLLPRI);
-  QUEUE_REMOVE(&w->pending_queue);
-
-  /* Remove stale events for this file descriptor */
-  if (w->fd != -1)
-    uv__platform_invalidate_fd(loop, w->fd);
-}
-
-
-void uv__io_feed(uv_loop_t* loop, uv__io_t* w) {
-  if (QUEUE_EMPTY(&w->pending_queue))
-    QUEUE_INSERT_TAIL(&loop->pending_queue, &w->pending_queue);
-}
-
-
-int uv__io_active(const uv__io_t* w, unsigned int events) {
-  assert(0 == (events & ~(POLLIN | POLLOUT | UV__POLLRDHUP | UV__POLLPRI)));
-  assert(0 != events);
-  return 0 != (w->pevents & events);
-}
-
-
-int uv__fd_exists(uv_loop_t* loop, int fd) {
-  return (unsigned) fd < loop->nwatchers && loop->watchers[fd] != NULL;
-}
-
-
-int uv_getrusage(uv_rusage_t* rusage) {
-  struct rusage usage;
-
-  if (getrusage(RUSAGE_SELF, &usage))
-    return UV__ERR(errno);
-
-  rusage->ru_utime.tv_sec = usage.ru_utime.tv_sec;
-  rusage->ru_utime.tv_usec = usage.ru_utime.tv_usec;
-
-  rusage->ru_stime.tv_sec = usage.ru_stime.tv_sec;
-  rusage->ru_stime.tv_usec = usage.ru_stime.tv_usec;
-
-#if !defined(__MVS__) && !defined(__HAIKU__)
-  rusage->ru_maxrss = usage.ru_maxrss;
-  rusage->ru_ixrss = usage.ru_ixrss;
-  rusage->ru_idrss = usage.ru_idrss;
-  rusage->ru_isrss = usage.ru_isrss;
-  rusage->ru_minflt = usage.ru_minflt;
-  rusage->ru_majflt = usage.ru_majflt;
-  rusage->ru_nswap = usage.ru_nswap;
-  rusage->ru_inblock = usage.ru_inblock;
-  rusage->ru_oublock = usage.ru_oublock;
-  rusage->ru_msgsnd = usage.ru_msgsnd;
-  rusage->ru_msgrcv = usage.ru_msgrcv;
-  rusage->ru_nsignals = usage.ru_nsignals;
-  rusage->ru_nvcsw = usage.ru_nvcsw;
-  rusage->ru_nivcsw = usage.ru_nivcsw;
-#endif
-
-  return 0;
-}
-
-
-int uv__open_cloexec(const char* path, int flags) {
-  int err;
-  int fd;
-
-#if defined(UV__O_CLOEXEC)
-  static int no_cloexec;
-
-  if (!no_cloexec) {
-    fd = open(path, flags | UV__O_CLOEXEC);
-    if (fd != -1)
-      return fd;
-
-    if (errno != EINVAL)
-      return UV__ERR(errno);
-
-    /* O_CLOEXEC not supported. */
-    no_cloexec = 1;
-  }
-#endif
-
-  fd = open(path, flags);
-  if (fd == -1)
-    return UV__ERR(errno);
-
-  err = uv__cloexec(fd, 1);
-  if (err) {
-    uv__close(fd);
-    return err;
-  }
-
-  return fd;
-}
-
-
-int uv__dup2_cloexec(int oldfd, int newfd) {
-  int r;
-#if (defined(__FreeBSD__) && __FreeBSD__ >= 10) || defined(__NetBSD__)
-  r = dup3(oldfd, newfd, O_CLOEXEC);
-  if (r == -1)
-    return UV__ERR(errno);
-  return r;
-#elif defined(__FreeBSD__) && defined(F_DUP2FD_CLOEXEC)
-  r = fcntl(oldfd, F_DUP2FD_CLOEXEC, newfd);
-  if (r != -1)
-    return r;
-  if (errno != EINVAL)
-    return UV__ERR(errno);
-  /* Fall through. */
-#elif defined(__linux__)
-  static int no_dup3;
-  if (!no_dup3) {
-    do
-      r = uv__dup3(oldfd, newfd, UV__O_CLOEXEC);
-    while (r == -1 && errno == EBUSY);
-    if (r != -1)
-      return r;
-    if (errno != ENOSYS)
-      return UV__ERR(errno);
-    /* Fall through. */
-    no_dup3 = 1;
-  }
-#endif
-  {
-    int err;
-    do
-      r = dup2(oldfd, newfd);
-#if defined(__linux__)
-    while (r == -1 && errno == EBUSY);
-#else
-    while (0);  /* Never retry. */
-#endif
-
-    if (r == -1)
-      return UV__ERR(errno);
-
-    err = uv__cloexec(newfd, 1);
-    if (err) {
-      uv__close(newfd);
-      return err;
-    }
-
-    return r;
-  }
-}
-
-
-int uv_os_homedir(char* buffer, size_t* size) {
-  uv_passwd_t pwd;
-  size_t len;
-  int r;
-
-  /* Check if the HOME environment variable is set first. The task of
-     performing input validation on buffer and size is taken care of by
-     uv_os_getenv(). */
-  r = uv_os_getenv("HOME", buffer, size);
-
-  if (r != UV_ENOENT)
-    return r;
-
-  /* HOME is not set, so call uv__getpwuid_r() */
-  r = uv__getpwuid_r(&pwd);
-
-  if (r != 0) {
-    return r;
-  }
-
-  len = strlen(pwd.homedir);
-
-  if (len >= *size) {
-    *size = len + 1;
-    uv_os_free_passwd(&pwd);
-    return UV_ENOBUFS;
-  }
-
-  memcpy(buffer, pwd.homedir, len + 1);
-  *size = len;
-  uv_os_free_passwd(&pwd);
-
-  return 0;
-}
-
-
-int uv_os_tmpdir(char* buffer, size_t* size) {
-  const char* buf;
-  size_t len;
-
-  if (buffer == NULL || size == NULL || *size == 0)
-    return UV_EINVAL;
-
-#define CHECK_ENV_VAR(name)                                                   \
-  do {                                                                        \
-    buf = getenv(name);                                                       \
-    if (buf != NULL)                                                          \
-      goto return_buffer;                                                     \
-  }                                                                           \
-  while (0)
-
-  /* Check the TMPDIR, TMP, TEMP, and TEMPDIR environment variables in order */
-  CHECK_ENV_VAR("TMPDIR");
-  CHECK_ENV_VAR("TMP");
-  CHECK_ENV_VAR("TEMP");
-  CHECK_ENV_VAR("TEMPDIR");
-
-#undef CHECK_ENV_VAR
-
-  /* No temp environment variables defined */
-  #if defined(__ANDROID__)
-    buf = "/data/local/tmp";
-  #else
-    buf = "/tmp";
-  #endif
-
-return_buffer:
-  len = strlen(buf);
-
-  if (len >= *size) {
-    *size = len + 1;
-    return UV_ENOBUFS;
-  }
-
-  /* The returned directory should not have a trailing slash. */
-  if (len > 1 && buf[len - 1] == '/') {
-    len--;
-  }
-
-  memcpy(buffer, buf, len + 1);
-  buffer[len] = '\0';
-  *size = len;
-
-  return 0;
-}
-
-
-int uv__getpwuid_r(uv_passwd_t* pwd) {
-  struct passwd pw;
-  struct passwd* result;
-  char* buf;
-  uid_t uid;
-  size_t bufsize;
-  size_t name_size;
-  size_t homedir_size;
-  size_t shell_size;
-  long initsize;
-  int r;
-#if defined(__ANDROID_API__) && __ANDROID_API__ < 21
-  int (*getpwuid_r)(uid_t, struct passwd*, char*, size_t, struct passwd**);
-
-  getpwuid_r = dlsym(RTLD_DEFAULT, "getpwuid_r");
-  if (getpwuid_r == NULL)
-    return UV_ENOSYS;
-#endif
-
-  if (pwd == NULL)
-    return UV_EINVAL;
-
-  initsize = sysconf(_SC_GETPW_R_SIZE_MAX);
-
-  if (initsize <= 0)
-    bufsize = 4096;
-  else
-    bufsize = (size_t) initsize;
-
-  uid = geteuid();
-  buf = NULL;
-
-  for (;;) {
-    uv__free(buf);
-    buf = (char*)uv__malloc(bufsize);
-
-    if (buf == NULL)
-      return UV_ENOMEM;
-
-    r = getpwuid_r(uid, &pw, buf, bufsize, &result);
-
-    if (r != ERANGE)
-      break;
-
-    bufsize *= 2;
-  }
-
-  if (r != 0) {
-    uv__free(buf);
-    return -r;
-  }
-
-  if (result == NULL) {
-    uv__free(buf);
-    return UV_ENOENT;
-  }
-
-  /* Allocate memory for the username, shell, and home directory */
-  name_size = strlen(pw.pw_name) + 1;
-  homedir_size = strlen(pw.pw_dir) + 1;
-  shell_size = strlen(pw.pw_shell) + 1;
-  pwd->username = (char*)uv__malloc(name_size + homedir_size + shell_size);
-
-  if (pwd->username == NULL) {
-    uv__free(buf);
-    return UV_ENOMEM;
-  }
-
-  /* Copy the username */
-  memcpy(pwd->username, pw.pw_name, name_size);
-
-  /* Copy the home directory */
-  pwd->homedir = pwd->username + name_size;
-  memcpy(pwd->homedir, pw.pw_dir, homedir_size);
-
-  /* Copy the shell */
-  pwd->shell = pwd->homedir + homedir_size;
-  memcpy(pwd->shell, pw.pw_shell, shell_size);
-
-  /* Copy the uid and gid */
-  pwd->uid = pw.pw_uid;
-  pwd->gid = pw.pw_gid;
-
-  uv__free(buf);
-
-  return 0;
-}
-
-
-void uv_os_free_passwd(uv_passwd_t* pwd) {
-  if (pwd == NULL)
-    return;
-
-  /*
-    The memory for name, shell, and homedir are allocated in a single
-    uv__malloc() call. The base of the pointer is stored in pwd->username, so
-    that is the field that needs to be freed.
-  */
-  uv__free(pwd->username);
-  pwd->username = NULL;
-  pwd->shell = NULL;
-  pwd->homedir = NULL;
-}
-
-
-int uv_os_get_passwd(uv_passwd_t* pwd) {
-  return uv__getpwuid_r(pwd);
-}
-
-
-int uv_translate_sys_error(int sys_errno) {
-  /* If < 0 then it's already a libuv error. */
-  return sys_errno <= 0 ? sys_errno : -sys_errno;
-}
-
-
-int uv_os_getenv(const char* name, char* buffer, size_t* size) {
-  char* var;
-  size_t len;
-
-  if (name == NULL || buffer == NULL || size == NULL || *size == 0)
-    return UV_EINVAL;
-
-  var = getenv(name);
-
-  if (var == NULL)
-    return UV_ENOENT;
-
-  len = strlen(var);
-
-  if (len >= *size) {
-    *size = len + 1;
-    return UV_ENOBUFS;
-  }
-
-  memcpy(buffer, var, len + 1);
-  *size = len;
-
-  return 0;
-}
-
-
-int uv_os_setenv(const char* name, const char* value) {
-  if (name == NULL || value == NULL)
-    return UV_EINVAL;
-
-  if (setenv(name, value, 1) != 0)
-    return UV__ERR(errno);
-
-  return 0;
-}
-
-
-int uv_os_unsetenv(const char* name) {
-  if (name == NULL)
-    return UV_EINVAL;
-
-  if (unsetenv(name) != 0)
-    return UV__ERR(errno);
-
-  return 0;
-}
-
-
-int uv_os_gethostname(char* buffer, size_t* size) {
-  /*
-    On some platforms, if the input buffer is not large enough, gethostname()
-    succeeds, but truncates the result. libuv can detect this and return ENOBUFS
-    instead by creating a large enough buffer and comparing the hostname length
-    to the size input.
-  */
-  char buf[UV_MAXHOSTNAMESIZE];
-  size_t len;
-
-  if (buffer == NULL || size == NULL || *size == 0)
-    return UV_EINVAL;
-
-  if (gethostname(buf, sizeof(buf)) != 0)
-    return UV__ERR(errno);
-
-  buf[sizeof(buf) - 1] = '\0'; /* Null terminate, just to be safe. */
-  len = strlen(buf);
-
-  if (len >= *size) {
-    *size = len + 1;
-    return UV_ENOBUFS;
-  }
-
-  memcpy(buffer, buf, len + 1);
-  *size = len;
-  return 0;
-}
-
-
-uv_os_fd_t uv_get_osfhandle(int fd) {
-  return fd;
-}
-
-int uv_open_osfhandle(uv_os_fd_t os_fd) {
-  return os_fd;
-}
-
-uv_pid_t uv_os_getpid(void) {
-  return getpid();
-}
-
-
-uv_pid_t uv_os_getppid(void) {
-  return getppid();
-}
-
-
-int uv_os_getpriority(uv_pid_t pid, int* priority) {
-  int r;
-
-  if (priority == NULL)
-    return UV_EINVAL;
-
-  errno = 0;
-  r = getpriority(PRIO_PROCESS, (int) pid);
-
-  if (r == -1 && errno != 0)
-    return UV__ERR(errno);
-
-  *priority = r;
-  return 0;
-}
-
-
-int uv_os_setpriority(uv_pid_t pid, int priority) {
-  if (priority < UV_PRIORITY_HIGHEST || priority > UV_PRIORITY_LOW)
-    return UV_EINVAL;
-
-  if (setpriority(PRIO_PROCESS, (int) pid, priority) != 0)
-    return UV__ERR(errno);
-
-  return 0;
-}
-
-
-int uv_os_uname(uv_utsname_t* buffer) {
-  struct utsname buf;
-  int r;
-
-  if (buffer == NULL)
-    return UV_EINVAL;
-
-  if (uname(&buf) == -1) {
-    r = UV__ERR(errno);
-    goto error;
-  }
-
-  r = uv__strscpy(buffer->sysname, buf.sysname, sizeof(buffer->sysname));
-  if (r == UV_E2BIG)
-    goto error;
-
-#ifdef _AIX
-  r = snprintf(buffer->release,
-               sizeof(buffer->release),
-               "%s.%s",
-               buf.version,
-               buf.release);
-  if (r >= sizeof(buffer->release)) {
-    r = UV_E2BIG;
-    goto error;
-  }
-#else
-  r = uv__strscpy(buffer->release, buf.release, sizeof(buffer->release));
-  if (r == UV_E2BIG)
-    goto error;
-#endif
-
-  r = uv__strscpy(buffer->version, buf.version, sizeof(buffer->version));
-  if (r == UV_E2BIG)
-    goto error;
-
-#if defined(_AIX) || defined(__PASE__)
-  r = uv__strscpy(buffer->machine, "ppc64", sizeof(buffer->machine));
-#else
-  r = uv__strscpy(buffer->machine, buf.machine, sizeof(buffer->machine));
-#endif
-
-  if (r == UV_E2BIG)
-    goto error;
-
-  return 0;
-
-error:
-  buffer->sysname[0] = '\0';
-  buffer->release[0] = '\0';
-  buffer->version[0] = '\0';
-  buffer->machine[0] = '\0';
-  return r;
-}
-
-int uv__getsockpeername(const uv_handle_t* handle,
-                        uv__peersockfunc func,
-                        struct sockaddr* name,
-                        int* namelen) {
-  socklen_t socklen;
-  uv_os_fd_t fd;
-  int r;
-
-  r = uv_fileno(handle, &fd);
-  if (r < 0)
-    return r;
-
-  /* sizeof(socklen_t) != sizeof(int) on some systems. */
-  socklen = (socklen_t) *namelen;
-
-  if (func(fd, name, &socklen))
-    return UV__ERR(errno);
-
-  *namelen = (int) socklen;
-  return 0;
-}
-
-int uv_gettimeofday(uv_timeval64_t* tv) {
-  struct timeval time;
-
-  if (tv == NULL)
-    return UV_EINVAL;
-
-  if (gettimeofday(&time, NULL) != 0)
-    return UV__ERR(errno);
-
-  tv->tv_sec = (int64_t) time.tv_sec;
-  tv->tv_usec = (int32_t) time.tv_usec;
-  return 0;
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/cygwin.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/cygwin.cpp
deleted file mode 100644
index 6b5cfb7..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/cygwin.cpp
+++ /dev/null
@@ -1,58 +0,0 @@
-/* Copyright libuv project contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include "uv.h"
-#include "internal.h"
-
-#include <sys/sysinfo.h>
-#include <unistd.h>
-
-int uv_uptime(double* uptime) {
-  struct sysinfo info;
-
-  if (sysinfo(&info) < 0)
-    return UV__ERR(errno);
-
-  *uptime = info.uptime;
-  return 0;
-}
-
-int uv_resident_set_memory(size_t* rss) {
-  /* FIXME: read /proc/meminfo? */
-  *rss = 0;
-  return 0;
-}
-
-int uv_cpu_info(uv_cpu_info_t** cpu_infos, int* count) {
-  /* FIXME: read /proc/stat? */
-  *cpu_infos = NULL;
-  *count = 0;
-  return UV_ENOSYS;
-}
-
-void uv_free_cpu_info(uv_cpu_info_t* cpu_infos, int count) {
-  (void)cpu_infos;
-  (void)count;
-}
-
-uint64_t uv_get_constrained_memory(void) {
-  return 0;  /* Memory constraints are unknown. */
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/darwin-proctitle.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/darwin-proctitle.cpp
deleted file mode 100644
index f05d9f9..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/darwin-proctitle.cpp
+++ /dev/null
@@ -1,199 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include "uv.h"
-#include "internal.h"
-
-#include <dlfcn.h>
-#include <errno.h>
-#include <stdlib.h>
-#include <string.h>
-
-#include <TargetConditionals.h>
-
-#if !TARGET_OS_IPHONE
-# include <CoreFoundation/CoreFoundation.h>
-# include <ApplicationServices/ApplicationServices.h>
-#endif
-
-#define S(s) pCFStringCreateWithCString(NULL, (s), kCFStringEncodingUTF8)
-
-
-static int (*dynamic_pthread_setname_np)(const char* name);
-#if !TARGET_OS_IPHONE
-static CFStringRef (*pCFStringCreateWithCString)(CFAllocatorRef,
-                                                 const char*,
-                                                 CFStringEncoding);
-static CFBundleRef (*pCFBundleGetBundleWithIdentifier)(CFStringRef);
-static void *(*pCFBundleGetDataPointerForName)(CFBundleRef, CFStringRef);
-static void *(*pCFBundleGetFunctionPointerForName)(CFBundleRef, CFStringRef);
-static CFTypeRef (*pLSGetCurrentApplicationASN)(void);
-static OSStatus (*pLSSetApplicationInformationItem)(int,
-                                                    CFTypeRef,
-                                                    CFStringRef,
-                                                    CFStringRef,
-                                                    CFDictionaryRef*);
-static void* application_services_handle;
-static void* core_foundation_handle;
-static CFBundleRef launch_services_bundle;
-static CFStringRef* display_name_key;
-static CFDictionaryRef (*pCFBundleGetInfoDictionary)(CFBundleRef);
-static CFBundleRef (*pCFBundleGetMainBundle)(void);
-static CFBundleRef hi_services_bundle;
-static OSStatus (*pSetApplicationIsDaemon)(int);
-static CFDictionaryRef (*pLSApplicationCheckIn)(int, CFDictionaryRef);
-static void (*pLSSetApplicationLaunchServicesServerConnectionStatus)(uint64_t,
-                                                                     void*);
-
-
-UV_DESTRUCTOR(static void uv__set_process_title_platform_fini(void)) {
-  if (core_foundation_handle != NULL) {
-    dlclose(core_foundation_handle);
-    core_foundation_handle = NULL;
-  }
-
-  if (application_services_handle != NULL) {
-    dlclose(application_services_handle);
-    application_services_handle = NULL;
-  }
-}
-#endif  /* !TARGET_OS_IPHONE */
-
-
-void uv__set_process_title_platform_init(void) {
-  /* pthread_setname_np() first appeared in OS X 10.6 and iOS 3.2. */
-  *(void **)(&dynamic_pthread_setname_np) =
-      dlsym(RTLD_DEFAULT, "pthread_setname_np");
-
-#if !TARGET_OS_IPHONE
-  application_services_handle = dlopen("/System/Library/Frameworks/"
-                                       "ApplicationServices.framework/"
-                                       "Versions/A/ApplicationServices",
-                                       RTLD_LAZY | RTLD_LOCAL);
-  core_foundation_handle = dlopen("/System/Library/Frameworks/"
-                                  "CoreFoundation.framework/"
-                                  "Versions/A/CoreFoundation",
-                                  RTLD_LAZY | RTLD_LOCAL);
-
-  if (application_services_handle == NULL || core_foundation_handle == NULL)
-    goto out;
-
-  *(void **)(&pCFStringCreateWithCString) =
-      dlsym(core_foundation_handle, "CFStringCreateWithCString");
-  *(void **)(&pCFBundleGetBundleWithIdentifier) =
-      dlsym(core_foundation_handle, "CFBundleGetBundleWithIdentifier");
-  *(void **)(&pCFBundleGetDataPointerForName) =
-      dlsym(core_foundation_handle, "CFBundleGetDataPointerForName");
-  *(void **)(&pCFBundleGetFunctionPointerForName) =
-      dlsym(core_foundation_handle, "CFBundleGetFunctionPointerForName");
-
-  if (pCFStringCreateWithCString == NULL ||
-      pCFBundleGetBundleWithIdentifier == NULL ||
-      pCFBundleGetDataPointerForName == NULL ||
-      pCFBundleGetFunctionPointerForName == NULL) {
-    goto out;
-  }
-
-  launch_services_bundle =
-      pCFBundleGetBundleWithIdentifier(S("com.apple.LaunchServices"));
-
-  if (launch_services_bundle == NULL)
-    goto out;
-
-  *(void **)(&pLSGetCurrentApplicationASN) =
-      pCFBundleGetFunctionPointerForName(launch_services_bundle,
-                                         S("_LSGetCurrentApplicationASN"));
-
-  if (pLSGetCurrentApplicationASN == NULL)
-    goto out;
-
-  *(void **)(&pLSSetApplicationInformationItem) =
-      pCFBundleGetFunctionPointerForName(launch_services_bundle,
-                                         S("_LSSetApplicationInformationItem"));
-
-  if (pLSSetApplicationInformationItem == NULL)
-    goto out;
-
-  display_name_key = (CFStringRef*)
-      pCFBundleGetDataPointerForName(launch_services_bundle,
-                                     S("_kLSDisplayNameKey"));
-
-  if (display_name_key == NULL || *display_name_key == NULL)
-    goto out;
-
-  *(void **)(&pCFBundleGetInfoDictionary) = dlsym(core_foundation_handle,
-                                     "CFBundleGetInfoDictionary");
-  *(void **)(&pCFBundleGetMainBundle) = dlsym(core_foundation_handle,
-                                 "CFBundleGetMainBundle");
-
-  if (pCFBundleGetInfoDictionary == NULL || pCFBundleGetMainBundle == NULL)
-    goto out;
-
-  /* Black 10.9 magic, to remove (Not responding) mark in Activity Monitor */
-  hi_services_bundle =
-      pCFBundleGetBundleWithIdentifier(S("com.apple.HIServices"));
-
-  if (hi_services_bundle == NULL)
-    goto out;
-
-  *(void **)(&pSetApplicationIsDaemon) = pCFBundleGetFunctionPointerForName(
-      hi_services_bundle,
-      S("SetApplicationIsDaemon"));
-  *(void **)(&pLSApplicationCheckIn) = pCFBundleGetFunctionPointerForName(
-      launch_services_bundle,
-      S("_LSApplicationCheckIn"));
-  *(void **)(&pLSSetApplicationLaunchServicesServerConnectionStatus) =
-      pCFBundleGetFunctionPointerForName(
-          launch_services_bundle,
-          S("_LSSetApplicationLaunchServicesServerConnectionStatus"));
-
-  if (pSetApplicationIsDaemon == NULL ||
-      pLSApplicationCheckIn == NULL ||
-      pLSSetApplicationLaunchServicesServerConnectionStatus == NULL) {
-    goto out;
-  }
-
-  return;
-
-out:
-  uv__set_process_title_platform_fini();
-#endif  /* !TARGET_OS_IPHONE */
-}
-
-
-void uv__set_process_title(const char* title) {
-#if !TARGET_OS_IPHONE
-  if (core_foundation_handle != NULL && pSetApplicationIsDaemon(1) != noErr) {
-    CFTypeRef asn;
-    pLSSetApplicationLaunchServicesServerConnectionStatus(0, NULL);
-    pLSApplicationCheckIn(/* Magic value */ -2,
-                          pCFBundleGetInfoDictionary(pCFBundleGetMainBundle()));
-    asn = pLSGetCurrentApplicationASN();
-    pLSSetApplicationInformationItem(/* Magic value */ -2, asn,
-                                     *display_name_key, S(title), NULL);
-  }
-#endif  /* !TARGET_OS_IPHONE */
-
-  if (dynamic_pthread_setname_np != NULL) {
-    char namebuf[64];  /* MAXTHREADNAMESIZE */
-    uv__strscpy(namebuf, title, sizeof(namebuf));
-    dynamic_pthread_setname_np(namebuf);
-  }
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/darwin.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/darwin.cpp
deleted file mode 100644
index 2282d91..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/darwin.cpp
+++ /dev/null
@@ -1,236 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include "uv.h"
-#include "internal.h"
-
-#include <assert.h>
-#include <stdint.h>
-#include <errno.h>
-
-#include <mach/mach.h>
-#include <mach/mach_time.h>
-#include <mach-o/dyld.h> /* _NSGetExecutablePath */
-#include <sys/resource.h>
-#include <sys/sysctl.h>
-#include <unistd.h>  /* sysconf */
-
-
-int uv__platform_loop_init(uv_loop_t* loop) {
-  loop->cf_state = NULL;
-
-  if (uv__kqueue_init(loop))
-    return UV__ERR(errno);
-
-  return 0;
-}
-
-
-void uv__platform_loop_delete(uv_loop_t* loop) {
-  uv__fsevents_loop_delete(loop);
-}
-
-
-uint64_t uv__hrtime(uv_clocktype_t type) {
-  static mach_timebase_info_data_t info;
-
-  if ((ACCESS_ONCE(uint32_t, info.numer) == 0 ||
-       ACCESS_ONCE(uint32_t, info.denom) == 0) &&
-      mach_timebase_info(&info) != KERN_SUCCESS)
-    abort();
-
-  return mach_absolute_time() * info.numer / info.denom;
-}
-
-
-int uv_exepath(char* buffer, size_t* size) {
-  /* realpath(exepath) may be > PATH_MAX so double it to be on the safe side. */
-  char abspath[PATH_MAX * 2 + 1];
-  char exepath[PATH_MAX + 1];
-  uint32_t exepath_size;
-  size_t abspath_size;
-
-  if (buffer == NULL || size == NULL || *size == 0)
-    return UV_EINVAL;
-
-  exepath_size = sizeof(exepath);
-  if (_NSGetExecutablePath(exepath, &exepath_size))
-    return UV_EIO;
-
-  if (realpath(exepath, abspath) != abspath)
-    return UV__ERR(errno);
-
-  abspath_size = strlen(abspath);
-  if (abspath_size == 0)
-    return UV_EIO;
-
-  *size -= 1;
-  if (*size > abspath_size)
-    *size = abspath_size;
-
-  memcpy(buffer, abspath, *size);
-  buffer[*size] = '\0';
-
-  return 0;
-}
-
-
-uint64_t uv_get_free_memory(void) {
-  vm_statistics_data_t info;
-  mach_msg_type_number_t count = sizeof(info) / sizeof(integer_t);
-
-  if (host_statistics(mach_host_self(), HOST_VM_INFO,
-                      (host_info_t)&info, &count) != KERN_SUCCESS) {
-    return UV_EINVAL;  /* FIXME(bnoordhuis) Translate error. */
-  }
-
-  return (uint64_t) info.free_count * sysconf(_SC_PAGESIZE);
-}
-
-
-uint64_t uv_get_total_memory(void) {
-  uint64_t info;
-  int which[] = {CTL_HW, HW_MEMSIZE};
-  size_t size = sizeof(info);
-
-  if (sysctl(which, 2, &info, &size, NULL, 0))
-    return UV__ERR(errno);
-
-  return (uint64_t) info;
-}
-
-
-uint64_t uv_get_constrained_memory(void) {
-  return 0;  /* Memory constraints are unknown. */
-}
-
-
-void uv_loadavg(double avg[3]) {
-  struct loadavg info;
-  size_t size = sizeof(info);
-  int which[] = {CTL_VM, VM_LOADAVG};
-
-  if (sysctl(which, 2, &info, &size, NULL, 0) < 0) return;
-
-  avg[0] = (double) info.ldavg[0] / info.fscale;
-  avg[1] = (double) info.ldavg[1] / info.fscale;
-  avg[2] = (double) info.ldavg[2] / info.fscale;
-}
-
-
-int uv_resident_set_memory(size_t* rss) {
-  mach_msg_type_number_t count;
-  task_basic_info_data_t info;
-  kern_return_t err;
-
-  count = TASK_BASIC_INFO_COUNT;
-  err = task_info(mach_task_self(),
-                  TASK_BASIC_INFO,
-                  (task_info_t) &info,
-                  &count);
-  (void) &err;
-  /* task_info(TASK_BASIC_INFO) cannot really fail. Anything other than
-   * KERN_SUCCESS implies a libuv bug.
-   */
-  assert(err == KERN_SUCCESS);
-  *rss = info.resident_size;
-
-  return 0;
-}
-
-
-int uv_uptime(double* uptime) {
-  time_t now;
-  struct timeval info;
-  size_t size = sizeof(info);
-  static int which[] = {CTL_KERN, KERN_BOOTTIME};
-
-  if (sysctl(which, 2, &info, &size, NULL, 0))
-    return UV__ERR(errno);
-
-  now = time(NULL);
-  *uptime = now - info.tv_sec;
-
-  return 0;
-}
-
-int uv_cpu_info(uv_cpu_info_t** cpu_infos, int* count) {
-  unsigned int ticks = (unsigned int)sysconf(_SC_CLK_TCK),
-               multiplier = ((uint64_t)1000L / ticks);
-  char model[512];
-  uint64_t cpuspeed;
-  size_t size;
-  unsigned int i;
-  natural_t numcpus;
-  mach_msg_type_number_t msg_type;
-  processor_cpu_load_info_data_t *info;
-  uv_cpu_info_t* cpu_info;
-
-  size = sizeof(model);
-  if (sysctlbyname("machdep.cpu.brand_string", &model, &size, NULL, 0) &&
-      sysctlbyname("hw.model", &model, &size, NULL, 0)) {
-    return UV__ERR(errno);
-  }
-
-  size = sizeof(cpuspeed);
-  if (sysctlbyname("hw.cpufrequency", &cpuspeed, &size, NULL, 0))
-    return UV__ERR(errno);
-
-  if (host_processor_info(mach_host_self(), PROCESSOR_CPU_LOAD_INFO, &numcpus,
-                          (processor_info_array_t*)&info,
-                          &msg_type) != KERN_SUCCESS) {
-    return UV_EINVAL;  /* FIXME(bnoordhuis) Translate error. */
-  }
-
-  *cpu_infos = (uv_cpu_info_t*)uv__malloc(numcpus * sizeof(**cpu_infos));
-  if (!(*cpu_infos)) {
-    vm_deallocate(mach_task_self(), (vm_address_t)info, msg_type);
-    return UV_ENOMEM;
-  }
-
-  *count = numcpus;
-
-  for (i = 0; i < numcpus; i++) {
-    cpu_info = &(*cpu_infos)[i];
-
-    cpu_info->cpu_times.user = (uint64_t)(info[i].cpu_ticks[0]) * multiplier;
-    cpu_info->cpu_times.nice = (uint64_t)(info[i].cpu_ticks[3]) * multiplier;
-    cpu_info->cpu_times.sys = (uint64_t)(info[i].cpu_ticks[1]) * multiplier;
-    cpu_info->cpu_times.idle = (uint64_t)(info[i].cpu_ticks[2]) * multiplier;
-    cpu_info->cpu_times.irq = 0;
-
-    cpu_info->model = uv__strdup(model);
-    cpu_info->speed = cpuspeed/1000000;
-  }
-  vm_deallocate(mach_task_self(), (vm_address_t)info, msg_type);
-
-  return 0;
-}
-
-
-void uv_free_cpu_info(uv_cpu_info_t* cpu_infos, int count) {
-  int i;
-
-  for (i = 0; i < count; i++) {
-    uv__free(cpu_infos[i].model);
-  }
-
-  uv__free(cpu_infos);
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/dl.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/dl.cpp
deleted file mode 100644
index fc1c052..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/dl.cpp
+++ /dev/null
@@ -1,80 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include "uv.h"
-#include "internal.h"
-
-#include <dlfcn.h>
-#include <errno.h>
-#include <string.h>
-#include <locale.h>
-
-static int uv__dlerror(uv_lib_t* lib);
-
-
-int uv_dlopen(const char* filename, uv_lib_t* lib) {
-  dlerror(); /* Reset error status. */
-  lib->errmsg = NULL;
-  lib->handle = dlopen(filename, RTLD_LAZY);
-  return lib->handle ? 0 : uv__dlerror(lib);
-}
-
-
-void uv_dlclose(uv_lib_t* lib) {
-  uv__free(lib->errmsg);
-  lib->errmsg = NULL;
-
-  if (lib->handle) {
-    /* Ignore errors. No good way to signal them without leaking memory. */
-    dlclose(lib->handle);
-    lib->handle = NULL;
-  }
-}
-
-
-int uv_dlsym(uv_lib_t* lib, const char* name, void** ptr) {
-  dlerror(); /* Reset error status. */
-  *ptr = dlsym(lib->handle, name);
-  return uv__dlerror(lib);
-}
-
-
-const char* uv_dlerror(const uv_lib_t* lib) {
-  return lib->errmsg ? lib->errmsg : "no error";
-}
-
-
-static int uv__dlerror(uv_lib_t* lib) {
-  const char* errmsg;
-
-  uv__free(lib->errmsg);
-
-  errmsg = dlerror();
-
-  if (errmsg) {
-    lib->errmsg = uv__strdup(errmsg);
-    return -1;
-  }
-  else {
-    lib->errmsg = NULL;
-    return 0;
-  }
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/freebsd.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/freebsd.cpp
deleted file mode 100644
index c401145..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/freebsd.cpp
+++ /dev/null
@@ -1,301 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include "uv.h"
-#include "internal.h"
-
-#include <assert.h>
-#include <string.h>
-#include <errno.h>
-
-#include <paths.h>
-#include <sys/user.h>
-#include <sys/types.h>
-#include <sys/resource.h>
-#include <sys/sysctl.h>
-#include <vm/vm_param.h> /* VM_LOADAVG */
-#include <time.h>
-#include <stdlib.h>
-#include <unistd.h> /* sysconf */
-#include <fcntl.h>
-
-#ifndef CPUSTATES
-# define CPUSTATES 5U
-#endif
-#ifndef CP_USER
-# define CP_USER 0
-# define CP_NICE 1
-# define CP_SYS 2
-# define CP_IDLE 3
-# define CP_INTR 4
-#endif
-
-
-int uv__platform_loop_init(uv_loop_t* loop) {
-  return uv__kqueue_init(loop);
-}
-
-
-void uv__platform_loop_delete(uv_loop_t* loop) {
-}
-
-
-#ifdef __DragonFly__
-int uv_exepath(char* buffer, size_t* size) {
-  char abspath[PATH_MAX * 2 + 1];
-  ssize_t abspath_size;
-
-  if (buffer == NULL || size == NULL || *size == 0)
-    return UV_EINVAL;
-
-  abspath_size = readlink("/proc/curproc/file", abspath, sizeof(abspath));
-  if (abspath_size < 0)
-    return UV__ERR(errno);
-
-  assert(abspath_size > 0);
-  *size -= 1;
-
-  if (*size > abspath_size)
-    *size = abspath_size;
-
-  memcpy(buffer, abspath, *size);
-  buffer[*size] = '\0';
-
-  return 0;
-}
-#else
-int uv_exepath(char* buffer, size_t* size) {
-  char abspath[PATH_MAX * 2 + 1];
-  int mib[4];
-  size_t abspath_size;
-
-  if (buffer == NULL || size == NULL || *size == 0)
-    return UV_EINVAL;
-
-  mib[0] = CTL_KERN;
-  mib[1] = KERN_PROC;
-  mib[2] = KERN_PROC_PATHNAME;
-  mib[3] = -1;
-
-  abspath_size = sizeof abspath;
-  if (sysctl(mib, 4, abspath, &abspath_size, NULL, 0))
-    return UV__ERR(errno);
-
-  assert(abspath_size > 0);
-  abspath_size -= 1;
-  *size -= 1;
-
-  if (*size > abspath_size)
-    *size = abspath_size;
-
-  memcpy(buffer, abspath, *size);
-  buffer[*size] = '\0';
-
-  return 0;
-}
-#endif
-
-uint64_t uv_get_free_memory(void) {
-  int freecount;
-  size_t size = sizeof(freecount);
-
-  if (sysctlbyname("vm.stats.vm.v_free_count", &freecount, &size, NULL, 0))
-    return UV__ERR(errno);
-
-  return (uint64_t) freecount * sysconf(_SC_PAGESIZE);
-
-}
-
-
-uint64_t uv_get_total_memory(void) {
-  unsigned long info;
-  int which[] = {CTL_HW, HW_PHYSMEM};
-
-  size_t size = sizeof(info);
-
-  if (sysctl(which, 2, &info, &size, NULL, 0))
-    return UV__ERR(errno);
-
-  return (uint64_t) info;
-}
-
-
-uint64_t uv_get_constrained_memory(void) {
-  return 0;  /* Memory constraints are unknown. */
-}
-
-
-void uv_loadavg(double avg[3]) {
-  struct loadavg info;
-  size_t size = sizeof(info);
-  int which[] = {CTL_VM, VM_LOADAVG};
-
-  if (sysctl(which, 2, &info, &size, NULL, 0) < 0) return;
-
-  avg[0] = (double) info.ldavg[0] / info.fscale;
-  avg[1] = (double) info.ldavg[1] / info.fscale;
-  avg[2] = (double) info.ldavg[2] / info.fscale;
-}
-
-
-int uv_resident_set_memory(size_t* rss) {
-  struct kinfo_proc kinfo;
-  size_t page_size;
-  size_t kinfo_size;
-  int mib[4];
-
-  mib[0] = CTL_KERN;
-  mib[1] = KERN_PROC;
-  mib[2] = KERN_PROC_PID;
-  mib[3] = getpid();
-
-  kinfo_size = sizeof(kinfo);
-
-  if (sysctl(mib, 4, &kinfo, &kinfo_size, NULL, 0))
-    return UV__ERR(errno);
-
-  page_size = getpagesize();
-
-#ifdef __DragonFly__
-  *rss = kinfo.kp_vm_rssize * page_size;
-#else
-  *rss = kinfo.ki_rssize * page_size;
-#endif
-
-  return 0;
-}
-
-
-int uv_uptime(double* uptime) {
-  int r;
-  struct timespec sp;
-  r = clock_gettime(CLOCK_MONOTONIC, &sp);
-  if (r)
-    return UV__ERR(errno);
-
-  *uptime = sp.tv_sec;
-  return 0;
-}
-
-
-int uv_cpu_info(uv_cpu_info_t** cpu_infos, int* count) {
-  unsigned int ticks = (unsigned int)sysconf(_SC_CLK_TCK),
-               multiplier = ((uint64_t)1000L / ticks), cpuspeed, maxcpus,
-               cur = 0;
-  uv_cpu_info_t* cpu_info;
-  const char* maxcpus_key;
-  const char* cptimes_key;
-  const char* model_key;
-  char model[512];
-  long* cp_times;
-  int numcpus;
-  size_t size;
-  int i;
-
-#if defined(__DragonFly__)
-  /* This is not quite correct but DragonFlyBSD doesn't seem to have anything
-   * comparable to kern.smp.maxcpus or kern.cp_times (kern.cp_time is a total,
-   * not per CPU). At least this stops uv_cpu_info() from failing completely.
-   */
-  maxcpus_key = "hw.ncpu";
-  cptimes_key = "kern.cp_time";
-#else
-  maxcpus_key = "kern.smp.maxcpus";
-  cptimes_key = "kern.cp_times";
-#endif
-
-#if defined(__arm__) || defined(__aarch64__)
-  /* The key hw.model and hw.clockrate are not available on FreeBSD ARM. */
-  model_key = "hw.machine";
-  cpuspeed = 0;
-#else
-  model_key = "hw.model";
-
-  size = sizeof(cpuspeed);
-  if (sysctlbyname("hw.clockrate", &cpuspeed, &size, NULL, 0))
-    return -errno;
-#endif
-
-  size = sizeof(model);
-  if (sysctlbyname(model_key, &model, &size, NULL, 0))
-    return UV__ERR(errno);
-
-  size = sizeof(numcpus);
-  if (sysctlbyname("hw.ncpu", &numcpus, &size, NULL, 0))
-    return UV__ERR(errno);
-
-  *cpu_infos = (uv_cpu_info_t*)uv__malloc(numcpus * sizeof(**cpu_infos));
-  if (!(*cpu_infos))
-    return UV_ENOMEM;
-
-  *count = numcpus;
-
-  /* kern.cp_times on FreeBSD i386 gives an array up to maxcpus instead of
-   * ncpu.
-   */
-  size = sizeof(maxcpus);
-  if (sysctlbyname(maxcpus_key, &maxcpus, &size, NULL, 0)) {
-    uv__free(*cpu_infos);
-    return UV__ERR(errno);
-  }
-
-  size = maxcpus * CPUSTATES * sizeof(long);
-
-  cp_times = (long*)uv__malloc(size);
-  if (cp_times == NULL) {
-    uv__free(*cpu_infos);
-    return UV_ENOMEM;
-  }
-
-  if (sysctlbyname(cptimes_key, cp_times, &size, NULL, 0)) {
-    uv__free(cp_times);
-    uv__free(*cpu_infos);
-    return UV__ERR(errno);
-  }
-
-  for (i = 0; i < numcpus; i++) {
-    cpu_info = &(*cpu_infos)[i];
-
-    cpu_info->cpu_times.user = (uint64_t)(cp_times[CP_USER+cur]) * multiplier;
-    cpu_info->cpu_times.nice = (uint64_t)(cp_times[CP_NICE+cur]) * multiplier;
-    cpu_info->cpu_times.sys = (uint64_t)(cp_times[CP_SYS+cur]) * multiplier;
-    cpu_info->cpu_times.idle = (uint64_t)(cp_times[CP_IDLE+cur]) * multiplier;
-    cpu_info->cpu_times.irq = (uint64_t)(cp_times[CP_INTR+cur]) * multiplier;
-
-    cpu_info->model = uv__strdup(model);
-    cpu_info->speed = cpuspeed;
-
-    cur+=CPUSTATES;
-  }
-
-  uv__free(cp_times);
-  return 0;
-}
-
-
-void uv_free_cpu_info(uv_cpu_info_t* cpu_infos, int count) {
-  int i;
-
-  for (i = 0; i < count; i++) {
-    uv__free(cpu_infos[i].model);
-  }
-
-  uv__free(cpu_infos);
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/fs.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/fs.cpp
deleted file mode 100644
index 36871ee..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/fs.cpp
+++ /dev/null
@@ -1,1860 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-/* Caveat emptor: this file deviates from the libuv convention of returning
- * negated errno codes. Most uv_fs_*() functions map directly to the system
- * call of the same name. For more complex wrappers, it's easier to just
- * return -1 with errno set. The dispatcher in uv__fs_work() takes care of
- * getting the errno to the right place (req->result or as the return value.)
- */
-
-#include "uv.h"
-#include "internal.h"
-
-#include <errno.h>
-#include <stdio.h>
-#include <stdlib.h>
-#include <string.h>
-#include <limits.h> /* PATH_MAX */
-
-#include <sys/types.h>
-#include <sys/socket.h>
-#include <sys/stat.h>
-#include <sys/time.h>
-#include <sys/uio.h>
-#include <pthread.h>
-#include <unistd.h>
-#include <fcntl.h>
-#include <poll.h>
-
-#if defined(__DragonFly__)        ||                                      \
-    defined(__FreeBSD__)          ||                                      \
-    defined(__FreeBSD_kernel__)   ||                                      \
-    defined(__OpenBSD__)          ||                                      \
-    defined(__NetBSD__)
-# define HAVE_PREADV 1
-#else
-# define HAVE_PREADV 0
-#endif
-
-#if defined(__linux__) || defined(__sun)
-# include <sys/sendfile.h>
-#endif
-
-#if defined(__APPLE__)
-# include <sys/sysctl.h>
-#elif defined(__linux__) && !defined(FICLONE)
-# include <sys/ioctl.h>
-# define FICLONE _IOW(0x94, 9, int)
-#endif
-
-#if defined(_AIX) && !defined(_AIX71)
-# include <utime.h>
-#endif
-
-#if defined(_AIX) && _XOPEN_SOURCE <= 600
-extern char *mkdtemp(char *template); /* See issue #740 on AIX < 7 */
-#endif
-
-#define INIT(subtype)                                                         \
-  do {                                                                        \
-    if (req == NULL)                                                          \
-      return UV_EINVAL;                                                       \
-    UV_REQ_INIT(req, UV_FS);                                                  \
-    req->fs_type = UV_FS_ ## subtype;                                         \
-    req->result = 0;                                                          \
-    req->ptr = NULL;                                                          \
-    req->loop = loop;                                                         \
-    req->path = NULL;                                                         \
-    req->new_path = NULL;                                                     \
-    req->bufs = NULL;                                                         \
-    req->cb = cb;                                                             \
-  }                                                                           \
-  while (0)
-
-#define PATH                                                                  \
-  do {                                                                        \
-    assert(path != NULL);                                                     \
-    if (cb == NULL) {                                                         \
-      req->path = path;                                                       \
-    } else {                                                                  \
-      req->path = uv__strdup(path);                                           \
-      if (req->path == NULL)                                                  \
-        return UV_ENOMEM;                                                     \
-    }                                                                         \
-  }                                                                           \
-  while (0)
-
-#define PATH2                                                                 \
-  do {                                                                        \
-    if (cb == NULL) {                                                         \
-      req->path = path;                                                       \
-      req->new_path = new_path;                                               \
-    } else {                                                                  \
-      size_t path_len;                                                        \
-      size_t new_path_len;                                                    \
-      path_len = strlen(path) + 1;                                            \
-      new_path_len = strlen(new_path) + 1;                                    \
-      req->path = (char*)uv__malloc(path_len + new_path_len);                 \
-      if (req->path == NULL)                                                  \
-        return UV_ENOMEM;                                                     \
-      req->new_path = req->path + path_len;                                   \
-      memcpy((void*) req->path, path, path_len);                              \
-      memcpy((void*) req->new_path, new_path, new_path_len);                  \
-    }                                                                         \
-  }                                                                           \
-  while (0)
-
-#define POST                                                                  \
-  do {                                                                        \
-    if (cb != NULL) {                                                         \
-      uv__req_register(loop, req);                                            \
-      uv__work_submit(loop,                                                   \
-                      &req->work_req,                                         \
-                      UV__WORK_FAST_IO,                                       \
-                      uv__fs_work,                                            \
-                      uv__fs_done);                                           \
-      return 0;                                                               \
-    }                                                                         \
-    else {                                                                    \
-      uv__fs_work(&req->work_req);                                            \
-      return req->result;                                                     \
-    }                                                                         \
-  }                                                                           \
-  while (0)
-
-
-static int uv__fs_close(int fd) {
-  int rc;
-
-  rc = uv__close_nocancel(fd);
-  if (rc == -1)
-    if (errno == EINTR || errno == EINPROGRESS)
-      rc = 0;  /* The close is in progress, not an error. */
-
-  return rc;
-}
-
-
-static ssize_t uv__fs_fsync(uv_fs_t* req) {
-#if defined(__APPLE__)
-  /* Apple's fdatasync and fsync explicitly do NOT flush the drive write cache
-   * to the drive platters. This is in contrast to Linux's fdatasync and fsync
-   * which do, according to recent man pages. F_FULLFSYNC is Apple's equivalent
-   * for flushing buffered data to permanent storage. If F_FULLFSYNC is not
-   * supported by the file system we fall back to F_BARRIERFSYNC or fsync().
-   * This is the same approach taken by sqlite, except sqlite does not issue
-   * an F_BARRIERFSYNC call.
-   */
-  int r;
-
-  r = fcntl(req->file, F_FULLFSYNC);
-  if (r != 0)
-    r = fcntl(req->file, 85 /* F_BARRIERFSYNC */);  /* fsync + barrier */
-  if (r != 0)
-    r = fsync(req->file);
-  return r;
-#else
-  return fsync(req->file);
-#endif
-}
-
-
-static ssize_t uv__fs_fdatasync(uv_fs_t* req) {
-#if defined(__linux__) || defined(__sun) || defined(__NetBSD__)
-  return fdatasync(req->file);
-#elif defined(__APPLE__)
-  /* See the comment in uv__fs_fsync. */
-  return uv__fs_fsync(req);
-#else
-  return fsync(req->file);
-#endif
-}
-
-
-static ssize_t uv__fs_futime(uv_fs_t* req) {
-#if defined(__linux__)                                                        \
-    || defined(_AIX71)                                                        \
-    || defined(__HAIKU__)
-  /* utimesat() has nanosecond resolution but we stick to microseconds
-   * for the sake of consistency with other platforms.
-   */
-  struct timespec ts[2];
-  ts[0].tv_sec  = req->atime;
-  ts[0].tv_nsec = (uint64_t)(req->atime * 1000000) % 1000000 * 1000;
-  ts[1].tv_sec  = req->mtime;
-  ts[1].tv_nsec = (uint64_t)(req->mtime * 1000000) % 1000000 * 1000;
-  return futimens(req->file, ts);
-#elif defined(__APPLE__)                                                      \
-    || defined(__DragonFly__)                                                 \
-    || defined(__FreeBSD__)                                                   \
-    || defined(__FreeBSD_kernel__)                                            \
-    || defined(__NetBSD__)                                                    \
-    || defined(__OpenBSD__)                                                   \
-    || defined(__sun)
-  struct timeval tv[2];
-  tv[0].tv_sec  = req->atime;
-  tv[0].tv_usec = (uint64_t)(req->atime * 1000000) % 1000000;
-  tv[1].tv_sec  = req->mtime;
-  tv[1].tv_usec = (uint64_t)(req->mtime * 1000000) % 1000000;
-# if defined(__sun)
-  return futimesat(req->file, NULL, tv);
-# else
-  return futimes(req->file, tv);
-# endif
-#elif defined(__MVS__)
-  attrib_t atr;
-  memset(&atr, 0, sizeof(atr));
-  atr.att_mtimechg = 1;
-  atr.att_atimechg = 1;
-  atr.att_mtime = req->mtime;
-  atr.att_atime = req->atime;
-  return __fchattr(req->file, &atr, sizeof(atr));
-#else
-  errno = ENOSYS;
-  return -1;
-#endif
-}
-
-
-static ssize_t uv__fs_mkdtemp(uv_fs_t* req) {
-  return mkdtemp((char*) req->path) ? 0 : -1;
-}
-
-
-static ssize_t uv__fs_open(uv_fs_t* req) {
-  static int no_cloexec_support;
-  int r;
-
-  /* Try O_CLOEXEC before entering locks */
-  if (no_cloexec_support == 0) {
-#ifdef O_CLOEXEC
-    r = open(req->path, req->flags | O_CLOEXEC, req->mode);
-    if (r >= 0)
-      return r;
-    if (errno != EINVAL)
-      return r;
-    no_cloexec_support = 1;
-#endif  /* O_CLOEXEC */
-  }
-
-  if (req->cb != NULL)
-    uv_rwlock_rdlock(&req->loop->cloexec_lock);
-
-  r = open(req->path, req->flags, req->mode);
-
-  /* In case of failure `uv__cloexec` will leave error in `errno`,
-   * so it is enough to just set `r` to `-1`.
-   */
-  if (r >= 0 && uv__cloexec(r, 1) != 0) {
-    r = uv__close(r);
-    if (r != 0)
-      abort();
-    r = -1;
-  }
-
-  if (req->cb != NULL)
-    uv_rwlock_rdunlock(&req->loop->cloexec_lock);
-
-  return r;
-}
-
-
-static ssize_t uv__fs_preadv(uv_file fd,
-                             uv_buf_t* bufs,
-                             unsigned int nbufs,
-                             off_t off) {
-  uv_buf_t* buf;
-  uv_buf_t* end;
-  ssize_t result;
-  ssize_t rc;
-  size_t pos;
-
-  assert(nbufs > 0);
-
-  result = 0;
-  pos = 0;
-  buf = bufs + 0;
-  end = bufs + nbufs;
-
-  for (;;) {
-    do
-      rc = pread(fd, buf->base + pos, buf->len - pos, off + result);
-    while (rc == -1 && errno == EINTR);
-
-    if (rc == 0)
-      break;
-
-    if (rc == -1 && result == 0)
-      return UV__ERR(errno);
-
-    if (rc == -1)
-      break;  /* We read some data so return that, ignore the error. */
-
-    pos += rc;
-    result += rc;
-
-    if (pos < buf->len)
-      continue;
-
-    pos = 0;
-    buf += 1;
-
-    if (buf == end)
-      break;
-  }
-
-  return result;
-}
-
-
-static ssize_t uv__fs_read(uv_fs_t* req) {
-#if defined(__linux__)
-  static int no_preadv;
-#endif
-  unsigned int iovmax;
-  ssize_t result;
-
-  iovmax = uv__getiovmax();
-  if (req->nbufs > iovmax)
-    req->nbufs = iovmax;
-
-  if (req->off < 0) {
-    if (req->nbufs == 1)
-      result = read(req->file, req->bufs[0].base, req->bufs[0].len);
-    else
-      result = readv(req->file, (struct iovec*) req->bufs, req->nbufs);
-  } else {
-    if (req->nbufs == 1) {
-      result = pread(req->file, req->bufs[0].base, req->bufs[0].len, req->off);
-      goto done;
-    }
-
-#if HAVE_PREADV
-    result = preadv(req->file, (struct iovec*) req->bufs, req->nbufs, req->off);
-#else
-# if defined(__linux__)
-    if (no_preadv) retry:
-# endif
-    {
-      result = uv__fs_preadv(req->file, req->bufs, req->nbufs, req->off);
-    }
-# if defined(__linux__)
-    else {
-      result = uv__preadv(req->file,
-                          (struct iovec*)req->bufs,
-                          req->nbufs,
-                          req->off);
-      if (result == -1 && errno == ENOSYS) {
-        no_preadv = 1;
-        goto retry;
-      }
-    }
-# endif
-#endif
-  }
-
-done:
-  /* Early cleanup of bufs allocation, since we're done with it. */
-  if (req->bufs != req->bufsml)
-    uv__free(req->bufs);
-
-  req->bufs = NULL;
-  req->nbufs = 0;
-
-#ifdef __PASE__
-  /* PASE returns EOPNOTSUPP when reading a directory, convert to EISDIR */
-  if (result == -1 && errno == EOPNOTSUPP) {
-    struct stat buf;
-    ssize_t rc;
-    rc = fstat(req->file, &buf);
-    if (rc == 0 && S_ISDIR(buf.st_mode)) {
-      errno = EISDIR;
-    }
-  }
-#endif
-
-  return result;
-}
-
-
-#if defined(__APPLE__) && !defined(MAC_OS_X_VERSION_10_8)
-#define UV_CONST_DIRENT uv__dirent_t
-#else
-#define UV_CONST_DIRENT const uv__dirent_t
-#endif
-
-
-static int uv__fs_scandir_filter(UV_CONST_DIRENT* dent) {
-  return strcmp(dent->d_name, ".") != 0 && strcmp(dent->d_name, "..") != 0;
-}
-
-
-static int uv__fs_scandir_sort(UV_CONST_DIRENT** a, UV_CONST_DIRENT** b) {
-  return strcmp((*a)->d_name, (*b)->d_name);
-}
-
-
-static ssize_t uv__fs_scandir(uv_fs_t* req) {
-  uv__dirent_t** dents;
-  int n;
-
-  dents = NULL;
-  n = scandir(req->path, &dents, uv__fs_scandir_filter, uv__fs_scandir_sort);
-
-  /* NOTE: We will use nbufs as an index field */
-  req->nbufs = 0;
-
-  if (n == 0) {
-    /* OS X still needs to deallocate some memory.
-     * Memory was allocated using the system allocator, so use free() here.
-     */
-    free(dents);
-    dents = NULL;
-  } else if (n == -1) {
-    return n;
-  }
-
-  req->ptr = dents;
-
-  return n;
-}
-
-static int uv__fs_opendir(uv_fs_t* req) {
-  uv_dir_t* dir;
-
-  dir = (uv_dir_t*)uv__malloc(sizeof(*dir));
-  if (dir == NULL)
-    goto error;
-
-  dir->dir = opendir(req->path);
-  if (dir->dir == NULL)
-    goto error;
-
-  req->ptr = dir;
-  return 0;
-
-error:
-  uv__free(dir);
-  req->ptr = NULL;
-  return -1;
-}
-
-static int uv__fs_readdir(uv_fs_t* req) {
-  uv_dir_t* dir;
-  uv_dirent_t* dirent;
-  struct dirent* res;
-  unsigned int dirent_idx;
-  unsigned int i;
-
-  dir = (uv_dir_t*)req->ptr;
-  dirent_idx = 0;
-
-  while (dirent_idx < dir->nentries) {
-    /* readdir() returns NULL on end of directory, as well as on error. errno
-       is used to differentiate between the two conditions. */
-    errno = 0;
-    res = readdir(dir->dir);
-
-    if (res == NULL) {
-      if (errno != 0)
-        goto error;
-      break;
-    }
-
-    if (strcmp(res->d_name, ".") == 0 || strcmp(res->d_name, "..") == 0)
-      continue;
-
-    dirent = &dir->dirents[dirent_idx];
-    dirent->name = uv__strdup(res->d_name);
-
-    if (dirent->name == NULL)
-      goto error;
-
-    dirent->type = uv__fs_get_dirent_type(res);
-    ++dirent_idx;
-  }
-
-  return dirent_idx;
-
-error:
-  for (i = 0; i < dirent_idx; ++i) {
-    uv__free((char*) dir->dirents[i].name);
-    dir->dirents[i].name = NULL;
-  }
-
-  return -1;
-}
-
-static int uv__fs_closedir(uv_fs_t* req) {
-  uv_dir_t* dir;
-
-  dir = (uv_dir_t*)req->ptr;
-
-  if (dir->dir != NULL) {
-    closedir(dir->dir);
-    dir->dir = NULL;
-  }
-
-  uv__free(req->ptr);
-  req->ptr = NULL;
-  return 0;
-}
-
-static ssize_t uv__fs_pathmax_size(const char* path) {
-  ssize_t pathmax;
-
-  pathmax = pathconf(path, _PC_PATH_MAX);
-
-  if (pathmax == -1)
-    pathmax = UV__PATH_MAX;
-
-  return pathmax;
-}
-
-static ssize_t uv__fs_readlink(uv_fs_t* req) {
-  ssize_t maxlen;
-  ssize_t len;
-  char* buf;
-  char* newbuf;
-
-#if defined(_POSIX_PATH_MAX) || defined(PATH_MAX)
-  maxlen = uv__fs_pathmax_size(req->path);
-#else
-  /* We may not have a real PATH_MAX.  Read size of link.  */
-  struct stat st;
-  int ret;
-  ret = lstat(req->path, &st);
-  if (ret != 0)
-    return -1;
-  if (!S_ISLNK(st.st_mode)) {
-    errno = EINVAL;
-    return -1;
-  }
-
-  maxlen = st.st_size;
-
-  /* According to readlink(2) lstat can report st_size == 0
-     for some symlinks, such as those in /proc or /sys.  */
-  if (maxlen == 0)
-    maxlen = uv__fs_pathmax_size(req->path);
-#endif
-
-  buf = (char*)uv__malloc(maxlen);
-
-  if (buf == NULL) {
-    errno = ENOMEM;
-    return -1;
-  }
-
-#if defined(__MVS__)
-  len = os390_readlink(req->path, buf, maxlen);
-#else
-  len = readlink(req->path, buf, maxlen);
-#endif
-
-  if (len == -1) {
-    uv__free(buf);
-    return -1;
-  }
-
-  /* Uncommon case: resize to make room for the trailing nul byte. */
-  if (len == maxlen) {
-    newbuf = (char*)uv__realloc(buf, len + 1);
-
-    if (newbuf == NULL) {
-      uv__free(buf);
-      return -1;
-    }
-
-    buf = newbuf;
-  }
-
-  buf[len] = '\0';
-  req->ptr = buf;
-
-  return 0;
-}
-
-static ssize_t uv__fs_realpath(uv_fs_t* req) {
-  char* buf;
-
-#if defined(_POSIX_VERSION) && _POSIX_VERSION >= 200809L
-  buf = realpath(req->path, NULL);
-  if (buf == NULL)
-    return -1;
-#else
-  ssize_t len;
-
-  len = uv__fs_pathmax_size(req->path);
-  buf = (char*)uv__malloc(len + 1);
-
-  if (buf == NULL) {
-    errno = ENOMEM;
-    return -1;
-  }
-
-  if (realpath(req->path, buf) == NULL) {
-    uv__free(buf);
-    return -1;
-  }
-#endif
-
-  req->ptr = buf;
-
-  return 0;
-}
-
-static ssize_t uv__fs_sendfile_emul(uv_fs_t* req) {
-  struct pollfd pfd;
-  int use_pread;
-  off_t offset;
-  ssize_t nsent;
-  ssize_t nread;
-  ssize_t nwritten;
-  size_t buflen;
-  size_t len;
-  ssize_t n;
-  int in_fd;
-  int out_fd;
-  char buf[8192];
-
-  len = req->bufsml[0].len;
-  in_fd = req->flags;
-  out_fd = req->file;
-  offset = req->off;
-  use_pread = 1;
-
-  /* Here are the rules regarding errors:
-   *
-   * 1. Read errors are reported only if nsent==0, otherwise we return nsent.
-   *    The user needs to know that some data has already been sent, to stop
-   *    them from sending it twice.
-   *
-   * 2. Write errors are always reported. Write errors are bad because they
-   *    mean data loss: we've read data but now we can't write it out.
-   *
-   * We try to use pread() and fall back to regular read() if the source fd
-   * doesn't support positional reads, for example when it's a pipe fd.
-   *
-   * If we get EAGAIN when writing to the target fd, we poll() on it until
-   * it becomes writable again.
-   *
-   * FIXME: If we get a write error when use_pread==1, it should be safe to
-   *        return the number of sent bytes instead of an error because pread()
-   *        is, in theory, idempotent. However, special files in /dev or /proc
-   *        may support pread() but not necessarily return the same data on
-   *        successive reads.
-   *
-   * FIXME: There is no way now to signal that we managed to send *some* data
-   *        before a write error.
-   */
-  for (nsent = 0; (size_t) nsent < len; ) {
-    buflen = len - nsent;
-
-    if (buflen > sizeof(buf))
-      buflen = sizeof(buf);
-
-    do
-      if (use_pread)
-        nread = pread(in_fd, buf, buflen, offset);
-      else
-        nread = read(in_fd, buf, buflen);
-    while (nread == -1 && errno == EINTR);
-
-    if (nread == 0)
-      goto out;
-
-    if (nread == -1) {
-      if (use_pread && nsent == 0 && (errno == EIO || errno == ESPIPE)) {
-        use_pread = 0;
-        continue;
-      }
-
-      if (nsent == 0)
-        nsent = -1;
-
-      goto out;
-    }
-
-    for (nwritten = 0; nwritten < nread; ) {
-      do
-        n = write(out_fd, buf + nwritten, nread - nwritten);
-      while (n == -1 && errno == EINTR);
-
-      if (n != -1) {
-        nwritten += n;
-        continue;
-      }
-
-      if (errno != EAGAIN && errno != EWOULDBLOCK) {
-        nsent = -1;
-        goto out;
-      }
-
-      pfd.fd = out_fd;
-      pfd.events = POLLOUT;
-      pfd.revents = 0;
-
-      do
-        n = poll(&pfd, 1, -1);
-      while (n == -1 && errno == EINTR);
-
-      if (n == -1 || (pfd.revents & ~POLLOUT) != 0) {
-        errno = EIO;
-        nsent = -1;
-        goto out;
-      }
-    }
-
-    offset += nread;
-    nsent += nread;
-  }
-
-out:
-  if (nsent != -1)
-    req->off = offset;
-
-  return nsent;
-}
-
-
-static ssize_t uv__fs_sendfile(uv_fs_t* req) {
-  int in_fd;
-  int out_fd;
-
-  in_fd = req->flags;
-  out_fd = req->file;
-
-#if defined(__linux__) || defined(__sun)
-  {
-    off_t off;
-    ssize_t r;
-
-    off = req->off;
-    r = sendfile(out_fd, in_fd, &off, req->bufsml[0].len);
-
-    /* sendfile() on SunOS returns EINVAL if the target fd is not a socket but
-     * it still writes out data. Fortunately, we can detect it by checking if
-     * the offset has been updated.
-     */
-    if (r != -1 || off > req->off) {
-      r = off - req->off;
-      req->off = off;
-      return r;
-    }
-
-    if (errno == EINVAL ||
-        errno == EIO ||
-        errno == ENOTSOCK ||
-        errno == EXDEV) {
-      errno = 0;
-      return uv__fs_sendfile_emul(req);
-    }
-
-    return -1;
-  }
-#elif defined(__APPLE__)           || \
-      defined(__DragonFly__)       || \
-      defined(__FreeBSD__)         || \
-      defined(__FreeBSD_kernel__)
-  {
-    off_t len;
-    ssize_t r;
-
-    /* sendfile() on FreeBSD and Darwin returns EAGAIN if the target fd is in
-     * non-blocking mode and not all data could be written. If a non-zero
-     * number of bytes have been sent, we don't consider it an error.
-     */
-
-#if defined(__FreeBSD__) || defined(__DragonFly__)
-    len = 0;
-    r = sendfile(in_fd, out_fd, req->off, req->bufsml[0].len, NULL, &len, 0);
-#elif defined(__FreeBSD_kernel__)
-    len = 0;
-    r = bsd_sendfile(in_fd,
-                     out_fd,
-                     req->off,
-                     req->bufsml[0].len,
-                     NULL,
-                     &len,
-                     0);
-#else
-    /* The darwin sendfile takes len as an input for the length to send,
-     * so make sure to initialize it with the caller's value. */
-    len = req->bufsml[0].len;
-    r = sendfile(in_fd, out_fd, req->off, &len, NULL, 0);
-#endif
-
-     /*
-     * The man page for sendfile(2) on DragonFly states that `len` contains
-     * a meaningful value ONLY in case of EAGAIN and EINTR.
-     * Nothing is said about it's value in case of other errors, so better
-     * not depend on the potential wrong assumption that is was not modified
-     * by the syscall.
-     */
-    if (r == 0 || ((errno == EAGAIN || errno == EINTR) && len != 0)) {
-      req->off += len;
-      return (ssize_t) len;
-    }
-
-    if (errno == EINVAL ||
-        errno == EIO ||
-        errno == ENOTSOCK ||
-        errno == EXDEV) {
-      errno = 0;
-      return uv__fs_sendfile_emul(req);
-    }
-
-    return -1;
-  }
-#else
-  /* Squelch compiler warnings. */
-  (void) &in_fd;
-  (void) &out_fd;
-
-  return uv__fs_sendfile_emul(req);
-#endif
-}
-
-
-static ssize_t uv__fs_utime(uv_fs_t* req) {
-#if defined(__linux__)                                                         \
-    || defined(_AIX71)                                                         \
-    || defined(__sun)                                                          \
-    || defined(__HAIKU__)
-  /* utimesat() has nanosecond resolution but we stick to microseconds
-   * for the sake of consistency with other platforms.
-   */
-  struct timespec ts[2];
-  ts[0].tv_sec  = req->atime;
-  ts[0].tv_nsec = (uint64_t)(req->atime * 1000000) % 1000000 * 1000;
-  ts[1].tv_sec  = req->mtime;
-  ts[1].tv_nsec = (uint64_t)(req->mtime * 1000000) % 1000000 * 1000;
-  return utimensat(AT_FDCWD, req->path, ts, 0);
-#elif defined(__APPLE__)                                                      \
-    || defined(__DragonFly__)                                                 \
-    || defined(__FreeBSD__)                                                   \
-    || defined(__FreeBSD_kernel__)                                            \
-    || defined(__NetBSD__)                                                    \
-    || defined(__OpenBSD__)
-  struct timeval tv[2];
-  tv[0].tv_sec  = req->atime;
-  tv[0].tv_usec = (uint64_t)(req->atime * 1000000) % 1000000;
-  tv[1].tv_sec  = req->mtime;
-  tv[1].tv_usec = (uint64_t)(req->mtime * 1000000) % 1000000;
-  return utimes(req->path, tv);
-#elif defined(_AIX)                                                           \
-    && !defined(_AIX71)
-  struct utimbuf buf;
-  buf.actime = req->atime;
-  buf.modtime = req->mtime;
-  return utime(req->path, &buf);
-#elif defined(__MVS__)
-  attrib_t atr;
-  memset(&atr, 0, sizeof(atr));
-  atr.att_mtimechg = 1;
-  atr.att_atimechg = 1;
-  atr.att_mtime = req->mtime;
-  atr.att_atime = req->atime;
-  return __lchattr((char*) req->path, &atr, sizeof(atr));
-#else
-  errno = ENOSYS;
-  return -1;
-#endif
-}
-
-
-static ssize_t uv__fs_write(uv_fs_t* req) {
-#if defined(__linux__)
-  static int no_pwritev;
-#endif
-  ssize_t r;
-
-  /* Serialize writes on OS X, concurrent write() and pwrite() calls result in
-   * data loss. We can't use a per-file descriptor lock, the descriptor may be
-   * a dup().
-   */
-#if defined(__APPLE__)
-  static pthread_mutex_t lock = PTHREAD_MUTEX_INITIALIZER;
-
-  if (pthread_mutex_lock(&lock))
-    abort();
-#endif
-
-  if (req->off < 0) {
-    if (req->nbufs == 1)
-      r = write(req->file, req->bufs[0].base, req->bufs[0].len);
-    else
-      r = writev(req->file, (struct iovec*) req->bufs, req->nbufs);
-  } else {
-    if (req->nbufs == 1) {
-      r = pwrite(req->file, req->bufs[0].base, req->bufs[0].len, req->off);
-      goto done;
-    }
-#if HAVE_PREADV
-    r = pwritev(req->file, (struct iovec*) req->bufs, req->nbufs, req->off);
-#else
-# if defined(__linux__)
-    if (no_pwritev) retry:
-# endif
-    {
-      r = pwrite(req->file, req->bufs[0].base, req->bufs[0].len, req->off);
-    }
-# if defined(__linux__)
-    else {
-      r = uv__pwritev(req->file,
-                      (struct iovec*) req->bufs,
-                      req->nbufs,
-                      req->off);
-      if (r == -1 && errno == ENOSYS) {
-        no_pwritev = 1;
-        goto retry;
-      }
-    }
-# endif
-#endif
-  }
-
-done:
-#if defined(__APPLE__)
-  if (pthread_mutex_unlock(&lock))
-    abort();
-#endif
-
-  return r;
-}
-
-static ssize_t uv__fs_copyfile(uv_fs_t* req) {
-  uv_fs_t fs_req;
-  uv_file srcfd;
-  uv_file dstfd;
-  struct stat src_statsbuf;
-  struct stat dst_statsbuf;
-  int dst_flags;
-  int result;
-  int err;
-  size_t bytes_to_send;
-  int64_t in_offset;
-
-  dstfd = -1;
-  err = 0;
-
-  /* Open the source file. */
-  srcfd = uv_fs_open(NULL, &fs_req, req->path, O_RDONLY, 0, NULL);
-  uv_fs_req_cleanup(&fs_req);
-
-  if (srcfd < 0)
-    return srcfd;
-
-  /* Get the source file's mode. */
-  if (fstat(srcfd, &src_statsbuf)) {
-    err = UV__ERR(errno);
-    goto out;
-  }
-
-  dst_flags = O_WRONLY | O_CREAT | O_TRUNC;
-
-  if (req->flags & UV_FS_COPYFILE_EXCL)
-    dst_flags |= O_EXCL;
-
-  /* Open the destination file. */
-  dstfd = uv_fs_open(NULL,
-                     &fs_req,
-                     req->new_path,
-                     dst_flags,
-                     src_statsbuf.st_mode,
-                     NULL);
-  uv_fs_req_cleanup(&fs_req);
-
-  if (dstfd < 0) {
-    err = dstfd;
-    goto out;
-  }
-
-  /* Get the destination file's mode. */
-  if (fstat(dstfd, &dst_statsbuf)) {
-    err = UV__ERR(errno);
-    goto out;
-  }
-
-  /* Check if srcfd and dstfd refer to the same file */
-  if (src_statsbuf.st_dev == dst_statsbuf.st_dev &&
-      src_statsbuf.st_ino == dst_statsbuf.st_ino) {
-    goto out;
-  }
-
-  if (fchmod(dstfd, src_statsbuf.st_mode) == -1) {
-    err = UV__ERR(errno);
-    goto out;
-  }
-
-#ifdef FICLONE
-  if (req->flags & UV_FS_COPYFILE_FICLONE ||
-      req->flags & UV_FS_COPYFILE_FICLONE_FORCE) {
-    if (ioctl(dstfd, FICLONE, srcfd) == -1) {
-      /* If an error occurred that the sendfile fallback also won't handle, or
-         this is a force clone then exit. Otherwise, fall through to try using
-         sendfile(). */
-      if (errno != ENOTTY && errno != EOPNOTSUPP && errno != EXDEV) {
-        err = UV__ERR(errno);
-        goto out;
-      } else if (req->flags & UV_FS_COPYFILE_FICLONE_FORCE) {
-        err = UV_ENOTSUP;
-        goto out;
-      }
-    } else {
-      goto out;
-    }
-  }
-#else
-  if (req->flags & UV_FS_COPYFILE_FICLONE_FORCE) {
-    err = UV_ENOSYS;
-    goto out;
-  }
-#endif
-
-  bytes_to_send = src_statsbuf.st_size;
-  in_offset = 0;
-  while (bytes_to_send != 0) {
-    err = uv_fs_sendfile(NULL,
-                         &fs_req,
-                         dstfd,
-                         srcfd,
-                         in_offset,
-                         bytes_to_send,
-                         NULL);
-    uv_fs_req_cleanup(&fs_req);
-    if (err < 0)
-      break;
-    bytes_to_send -= fs_req.result;
-    in_offset += fs_req.result;
-  }
-
-out:
-  if (err < 0)
-    result = err;
-  else
-    result = 0;
-
-  /* Close the source file. */
-  err = uv__close_nocheckstdio(srcfd);
-
-  /* Don't overwrite any existing errors. */
-  if (err != 0 && result == 0)
-    result = err;
-
-  /* Close the destination file if it is open. */
-  if (dstfd >= 0) {
-    err = uv__close_nocheckstdio(dstfd);
-
-    /* Don't overwrite any existing errors. */
-    if (err != 0 && result == 0)
-      result = err;
-
-    /* Remove the destination file if something went wrong. */
-    if (result != 0) {
-      uv_fs_unlink(NULL, &fs_req, req->new_path, NULL);
-      /* Ignore the unlink return value, as an error already happened. */
-      uv_fs_req_cleanup(&fs_req);
-    }
-  }
-
-  if (result == 0)
-    return 0;
-
-  errno = UV__ERR(result);
-  return -1;
-}
-
-static void uv__to_stat(struct stat* src, uv_stat_t* dst) {
-  dst->st_dev = src->st_dev;
-  dst->st_mode = src->st_mode;
-  dst->st_nlink = src->st_nlink;
-  dst->st_uid = src->st_uid;
-  dst->st_gid = src->st_gid;
-  dst->st_rdev = src->st_rdev;
-  dst->st_ino = src->st_ino;
-  dst->st_size = src->st_size;
-  dst->st_blksize = src->st_blksize;
-  dst->st_blocks = src->st_blocks;
-
-#if defined(__APPLE__)
-  dst->st_atim.tv_sec = src->st_atimespec.tv_sec;
-  dst->st_atim.tv_nsec = src->st_atimespec.tv_nsec;
-  dst->st_mtim.tv_sec = src->st_mtimespec.tv_sec;
-  dst->st_mtim.tv_nsec = src->st_mtimespec.tv_nsec;
-  dst->st_ctim.tv_sec = src->st_ctimespec.tv_sec;
-  dst->st_ctim.tv_nsec = src->st_ctimespec.tv_nsec;
-  dst->st_birthtim.tv_sec = src->st_birthtimespec.tv_sec;
-  dst->st_birthtim.tv_nsec = src->st_birthtimespec.tv_nsec;
-  dst->st_flags = src->st_flags;
-  dst->st_gen = src->st_gen;
-#elif defined(__ANDROID__)
-  dst->st_atim.tv_sec = src->st_atime;
-  dst->st_atim.tv_nsec = src->st_atimensec;
-  dst->st_mtim.tv_sec = src->st_mtime;
-  dst->st_mtim.tv_nsec = src->st_mtimensec;
-  dst->st_ctim.tv_sec = src->st_ctime;
-  dst->st_ctim.tv_nsec = src->st_ctimensec;
-  dst->st_birthtim.tv_sec = src->st_ctime;
-  dst->st_birthtim.tv_nsec = src->st_ctimensec;
-  dst->st_flags = 0;
-  dst->st_gen = 0;
-#elif !defined(_AIX) && (       \
-    defined(__DragonFly__)   || \
-    defined(__FreeBSD__)     || \
-    defined(__OpenBSD__)     || \
-    defined(__NetBSD__)      || \
-    defined(_GNU_SOURCE)     || \
-    defined(_BSD_SOURCE)     || \
-    defined(_SVID_SOURCE)    || \
-    defined(_XOPEN_SOURCE)   || \
-    defined(_DEFAULT_SOURCE))
-  dst->st_atim.tv_sec = src->st_atim.tv_sec;
-  dst->st_atim.tv_nsec = src->st_atim.tv_nsec;
-  dst->st_mtim.tv_sec = src->st_mtim.tv_sec;
-  dst->st_mtim.tv_nsec = src->st_mtim.tv_nsec;
-  dst->st_ctim.tv_sec = src->st_ctim.tv_sec;
-  dst->st_ctim.tv_nsec = src->st_ctim.tv_nsec;
-# if defined(__FreeBSD__)    || \
-     defined(__NetBSD__)
-  dst->st_birthtim.tv_sec = src->st_birthtim.tv_sec;
-  dst->st_birthtim.tv_nsec = src->st_birthtim.tv_nsec;
-  dst->st_flags = src->st_flags;
-  dst->st_gen = src->st_gen;
-# else
-  dst->st_birthtim.tv_sec = src->st_ctim.tv_sec;
-  dst->st_birthtim.tv_nsec = src->st_ctim.tv_nsec;
-  dst->st_flags = 0;
-  dst->st_gen = 0;
-# endif
-#else
-  dst->st_atim.tv_sec = src->st_atime;
-  dst->st_atim.tv_nsec = 0;
-  dst->st_mtim.tv_sec = src->st_mtime;
-  dst->st_mtim.tv_nsec = 0;
-  dst->st_ctim.tv_sec = src->st_ctime;
-  dst->st_ctim.tv_nsec = 0;
-  dst->st_birthtim.tv_sec = src->st_ctime;
-  dst->st_birthtim.tv_nsec = 0;
-  dst->st_flags = 0;
-  dst->st_gen = 0;
-#endif
-}
-
-
-static int uv__fs_statx(int fd,
-                        const char* path,
-                        int is_fstat,
-                        int is_lstat,
-                        uv_stat_t* buf) {
-  STATIC_ASSERT(UV_ENOSYS != -1);
-#ifdef __linux__
-  static int no_statx;
-  struct uv__statx statxbuf;
-  int dirfd;
-  int flags;
-  int mode;
-  int rc;
-
-  if (no_statx)
-    return UV_ENOSYS;
-
-  dirfd = AT_FDCWD;
-  flags = 0; /* AT_STATX_SYNC_AS_STAT */
-  mode = 0xFFF; /* STATX_BASIC_STATS + STATX_BTIME */
-
-  if (is_fstat) {
-    dirfd = fd;
-    flags |= 0x1000; /* AT_EMPTY_PATH */
-  }
-
-  if (is_lstat)
-    flags |= AT_SYMLINK_NOFOLLOW;
-
-  rc = uv__statx(dirfd, path, flags, mode, &statxbuf);
-
-  if (rc == -1) {
-    /* EPERM happens when a seccomp filter rejects the system call.
-     * Has been observed with libseccomp < 2.3.3 and docker < 18.04.
-     */
-    if (errno != EINVAL && errno != EPERM && errno != ENOSYS)
-      return -1;
-
-    no_statx = 1;
-    return UV_ENOSYS;
-  }
-
-  buf->st_dev = 256 * statxbuf.stx_dev_major + statxbuf.stx_dev_minor;
-  buf->st_mode = statxbuf.stx_mode;
-  buf->st_nlink = statxbuf.stx_nlink;
-  buf->st_uid = statxbuf.stx_uid;
-  buf->st_gid = statxbuf.stx_gid;
-  buf->st_rdev = statxbuf.stx_rdev_major;
-  buf->st_ino = statxbuf.stx_ino;
-  buf->st_size = statxbuf.stx_size;
-  buf->st_blksize = statxbuf.stx_blksize;
-  buf->st_blocks = statxbuf.stx_blocks;
-  buf->st_atim.tv_sec = statxbuf.stx_atime.tv_sec;
-  buf->st_atim.tv_nsec = statxbuf.stx_atime.tv_nsec;
-  buf->st_mtim.tv_sec = statxbuf.stx_mtime.tv_sec;
-  buf->st_mtim.tv_nsec = statxbuf.stx_mtime.tv_nsec;
-  buf->st_ctim.tv_sec = statxbuf.stx_ctime.tv_sec;
-  buf->st_ctim.tv_nsec = statxbuf.stx_ctime.tv_nsec;
-  buf->st_birthtim.tv_sec = statxbuf.stx_btime.tv_sec;
-  buf->st_birthtim.tv_nsec = statxbuf.stx_btime.tv_nsec;
-  buf->st_flags = 0;
-  buf->st_gen = 0;
-
-  return 0;
-#else
-  return UV_ENOSYS;
-#endif /* __linux__ */
-}
-
-
-static int uv__fs_stat(const char *path, uv_stat_t *buf) {
-  struct stat pbuf;
-  int ret;
-
-  ret = uv__fs_statx(-1, path, /* is_fstat */ 0, /* is_lstat */ 0, buf);
-  if (ret != UV_ENOSYS)
-    return ret;
-
-  ret = stat(path, &pbuf);
-  if (ret == 0)
-    uv__to_stat(&pbuf, buf);
-
-  return ret;
-}
-
-
-static int uv__fs_lstat(const char *path, uv_stat_t *buf) {
-  struct stat pbuf;
-  int ret;
-
-  ret = uv__fs_statx(-1, path, /* is_fstat */ 0, /* is_lstat */ 1, buf);
-  if (ret != UV_ENOSYS)
-    return ret;
-
-  ret = lstat(path, &pbuf);
-  if (ret == 0)
-    uv__to_stat(&pbuf, buf);
-
-  return ret;
-}
-
-
-static int uv__fs_fstat(int fd, uv_stat_t *buf) {
-  struct stat pbuf;
-  int ret;
-
-  ret = uv__fs_statx(fd, "", /* is_fstat */ 1, /* is_lstat */ 0, buf);
-  if (ret != UV_ENOSYS)
-    return ret;
-
-  ret = fstat(fd, &pbuf);
-  if (ret == 0)
-    uv__to_stat(&pbuf, buf);
-
-  return ret;
-}
-
-static size_t uv__fs_buf_offset(uv_buf_t* bufs, size_t size) {
-  size_t offset;
-  /* Figure out which bufs are done */
-  for (offset = 0; size > 0 && bufs[offset].len <= size; ++offset)
-    size -= bufs[offset].len;
-
-  /* Fix a partial read/write */
-  if (size > 0) {
-    bufs[offset].base += size;
-    bufs[offset].len -= size;
-  }
-  return offset;
-}
-
-static ssize_t uv__fs_write_all(uv_fs_t* req) {
-  unsigned int iovmax;
-  unsigned int nbufs;
-  uv_buf_t* bufs;
-  ssize_t total;
-  ssize_t result;
-
-  iovmax = uv__getiovmax();
-  nbufs = req->nbufs;
-  bufs = req->bufs;
-  total = 0;
-
-  while (nbufs > 0) {
-    req->nbufs = nbufs;
-    if (req->nbufs > iovmax)
-      req->nbufs = iovmax;
-
-    do
-      result = uv__fs_write(req);
-    while (result < 0 && errno == EINTR);
-
-    if (result <= 0) {
-      if (total == 0)
-        total = result;
-      break;
-    }
-
-    if (req->off >= 0)
-      req->off += result;
-
-    req->nbufs = uv__fs_buf_offset(req->bufs, result);
-    req->bufs += req->nbufs;
-    nbufs -= req->nbufs;
-    total += result;
-  }
-
-  if (bufs != req->bufsml)
-    uv__free(bufs);
-
-  req->bufs = NULL;
-  req->nbufs = 0;
-
-  return total;
-}
-
-
-static void uv__fs_work(struct uv__work* w) {
-  int retry_on_eintr;
-  uv_fs_t* req;
-  ssize_t r;
-
-  req = container_of(w, uv_fs_t, work_req);
-  retry_on_eintr = !(req->fs_type == UV_FS_CLOSE ||
-                     req->fs_type == UV_FS_READ);
-
-  do {
-    errno = 0;
-
-#define X(type, action)                                                       \
-  case UV_FS_ ## type:                                                        \
-    r = action;                                                               \
-    break;
-
-    switch (req->fs_type) {
-    X(ACCESS, access(req->path, req->flags));
-    X(CHMOD, chmod(req->path, req->mode));
-    X(CHOWN, chown(req->path, req->uid, req->gid));
-    X(CLOSE, uv__fs_close(req->file));
-    X(COPYFILE, uv__fs_copyfile(req));
-    X(FCHMOD, fchmod(req->file, req->mode));
-    X(FCHOWN, fchown(req->file, req->uid, req->gid));
-    X(LCHOWN, lchown(req->path, req->uid, req->gid));
-    X(FDATASYNC, uv__fs_fdatasync(req));
-    X(FSTAT, uv__fs_fstat(req->file, &req->statbuf));
-    X(FSYNC, uv__fs_fsync(req));
-    X(FTRUNCATE, ftruncate(req->file, req->off));
-    X(FUTIME, uv__fs_futime(req));
-    X(LSTAT, uv__fs_lstat(req->path, &req->statbuf));
-    X(LINK, link(req->path, req->new_path));
-    X(MKDIR, mkdir(req->path, req->mode));
-    X(MKDTEMP, uv__fs_mkdtemp(req));
-    X(OPEN, uv__fs_open(req));
-    X(READ, uv__fs_read(req));
-    X(SCANDIR, uv__fs_scandir(req));
-    X(OPENDIR, uv__fs_opendir(req));
-    X(READDIR, uv__fs_readdir(req));
-    X(CLOSEDIR, uv__fs_closedir(req));
-    X(READLINK, uv__fs_readlink(req));
-    X(REALPATH, uv__fs_realpath(req));
-    X(RENAME, rename(req->path, req->new_path));
-    X(RMDIR, rmdir(req->path));
-    X(SENDFILE, uv__fs_sendfile(req));
-    X(STAT, uv__fs_stat(req->path, &req->statbuf));
-    X(SYMLINK, symlink(req->path, req->new_path));
-    X(UNLINK, unlink(req->path));
-    X(UTIME, uv__fs_utime(req));
-    X(WRITE, uv__fs_write_all(req));
-    default: abort();
-    }
-#undef X
-  } while (r == -1 && errno == EINTR && retry_on_eintr);
-
-  if (r == -1)
-    req->result = UV__ERR(errno);
-  else
-    req->result = r;
-
-  if (r == 0 && (req->fs_type == UV_FS_STAT ||
-                 req->fs_type == UV_FS_FSTAT ||
-                 req->fs_type == UV_FS_LSTAT)) {
-    req->ptr = &req->statbuf;
-  }
-}
-
-
-static void uv__fs_done(struct uv__work* w, int status) {
-  uv_fs_t* req;
-
-  req = container_of(w, uv_fs_t, work_req);
-  uv__req_unregister(req->loop, req);
-
-  if (status == UV_ECANCELED) {
-    assert(req->result == 0);
-    req->result = UV_ECANCELED;
-  }
-
-  req->cb(req);
-}
-
-
-int uv_fs_access(uv_loop_t* loop,
-                 uv_fs_t* req,
-                 const char* path,
-                 int flags,
-                 uv_fs_cb cb) {
-  INIT(ACCESS);
-  PATH;
-  req->flags = flags;
-  POST;
-}
-
-
-int uv_fs_chmod(uv_loop_t* loop,
-                uv_fs_t* req,
-                const char* path,
-                int mode,
-                uv_fs_cb cb) {
-  INIT(CHMOD);
-  PATH;
-  req->mode = mode;
-  POST;
-}
-
-
-int uv_fs_chown(uv_loop_t* loop,
-                uv_fs_t* req,
-                const char* path,
-                uv_uid_t uid,
-                uv_gid_t gid,
-                uv_fs_cb cb) {
-  INIT(CHOWN);
-  PATH;
-  req->uid = uid;
-  req->gid = gid;
-  POST;
-}
-
-
-int uv_fs_close(uv_loop_t* loop, uv_fs_t* req, uv_file file, uv_fs_cb cb) {
-  INIT(CLOSE);
-  req->file = file;
-  POST;
-}
-
-
-int uv_fs_fchmod(uv_loop_t* loop,
-                 uv_fs_t* req,
-                 uv_file file,
-                 int mode,
-                 uv_fs_cb cb) {
-  INIT(FCHMOD);
-  req->file = file;
-  req->mode = mode;
-  POST;
-}
-
-
-int uv_fs_fchown(uv_loop_t* loop,
-                 uv_fs_t* req,
-                 uv_file file,
-                 uv_uid_t uid,
-                 uv_gid_t gid,
-                 uv_fs_cb cb) {
-  INIT(FCHOWN);
-  req->file = file;
-  req->uid = uid;
-  req->gid = gid;
-  POST;
-}
-
-
-int uv_fs_lchown(uv_loop_t* loop,
-                 uv_fs_t* req,
-                 const char* path,
-                 uv_uid_t uid,
-                 uv_gid_t gid,
-                 uv_fs_cb cb) {
-  INIT(LCHOWN);
-  PATH;
-  req->uid = uid;
-  req->gid = gid;
-  POST;
-}
-
-
-int uv_fs_fdatasync(uv_loop_t* loop, uv_fs_t* req, uv_file file, uv_fs_cb cb) {
-  INIT(FDATASYNC);
-  req->file = file;
-  POST;
-}
-
-
-int uv_fs_fstat(uv_loop_t* loop, uv_fs_t* req, uv_file file, uv_fs_cb cb) {
-  INIT(FSTAT);
-  req->file = file;
-  POST;
-}
-
-
-int uv_fs_fsync(uv_loop_t* loop, uv_fs_t* req, uv_file file, uv_fs_cb cb) {
-  INIT(FSYNC);
-  req->file = file;
-  POST;
-}
-
-
-int uv_fs_ftruncate(uv_loop_t* loop,
-                    uv_fs_t* req,
-                    uv_file file,
-                    int64_t off,
-                    uv_fs_cb cb) {
-  INIT(FTRUNCATE);
-  req->file = file;
-  req->off = off;
-  POST;
-}
-
-
-int uv_fs_futime(uv_loop_t* loop,
-                 uv_fs_t* req,
-                 uv_file file,
-                 double atime,
-                 double mtime,
-                 uv_fs_cb cb) {
-  INIT(FUTIME);
-  req->file = file;
-  req->atime = atime;
-  req->mtime = mtime;
-  POST;
-}
-
-
-int uv_fs_lstat(uv_loop_t* loop, uv_fs_t* req, const char* path, uv_fs_cb cb) {
-  INIT(LSTAT);
-  PATH;
-  POST;
-}
-
-
-int uv_fs_link(uv_loop_t* loop,
-               uv_fs_t* req,
-               const char* path,
-               const char* new_path,
-               uv_fs_cb cb) {
-  INIT(LINK);
-  PATH2;
-  POST;
-}
-
-
-int uv_fs_mkdir(uv_loop_t* loop,
-                uv_fs_t* req,
-                const char* path,
-                int mode,
-                uv_fs_cb cb) {
-  INIT(MKDIR);
-  PATH;
-  req->mode = mode;
-  POST;
-}
-
-
-int uv_fs_mkdtemp(uv_loop_t* loop,
-                  uv_fs_t* req,
-                  const char* tpl,
-                  uv_fs_cb cb) {
-  INIT(MKDTEMP);
-  req->path = uv__strdup(tpl);
-  if (req->path == NULL)
-    return UV_ENOMEM;
-  POST;
-}
-
-
-int uv_fs_open(uv_loop_t* loop,
-               uv_fs_t* req,
-               const char* path,
-               int flags,
-               int mode,
-               uv_fs_cb cb) {
-  INIT(OPEN);
-  PATH;
-  req->flags = flags;
-  req->mode = mode;
-  POST;
-}
-
-
-int uv_fs_read(uv_loop_t* loop, uv_fs_t* req,
-               uv_file file,
-               const uv_buf_t bufs[],
-               unsigned int nbufs,
-               int64_t off,
-               uv_fs_cb cb) {
-  INIT(READ);
-
-  if (bufs == NULL || nbufs == 0)
-    return UV_EINVAL;
-
-  req->file = file;
-
-  req->nbufs = nbufs;
-  req->bufs = req->bufsml;
-  if (nbufs > ARRAY_SIZE(req->bufsml))
-    req->bufs = (uv_buf_t*)uv__malloc(nbufs * sizeof(*bufs));
-
-  if (req->bufs == NULL)
-    return UV_ENOMEM;
-
-  memcpy(req->bufs, bufs, nbufs * sizeof(*bufs));
-
-  req->off = off;
-  POST;
-}
-
-
-int uv_fs_scandir(uv_loop_t* loop,
-                  uv_fs_t* req,
-                  const char* path,
-                  int flags,
-                  uv_fs_cb cb) {
-  INIT(SCANDIR);
-  PATH;
-  req->flags = flags;
-  POST;
-}
-
-int uv_fs_opendir(uv_loop_t* loop,
-                  uv_fs_t* req,
-                  const char* path,
-                  uv_fs_cb cb) {
-  INIT(OPENDIR);
-  PATH;
-  POST;
-}
-
-int uv_fs_readdir(uv_loop_t* loop,
-                  uv_fs_t* req,
-                  uv_dir_t* dir,
-                  uv_fs_cb cb) {
-  INIT(READDIR);
-
-  if (dir == NULL || dir->dir == NULL || dir->dirents == NULL)
-    return UV_EINVAL;
-
-  req->ptr = dir;
-  POST;
-}
-
-int uv_fs_closedir(uv_loop_t* loop,
-                   uv_fs_t* req,
-                   uv_dir_t* dir,
-                   uv_fs_cb cb) {
-  INIT(CLOSEDIR);
-
-  if (dir == NULL)
-    return UV_EINVAL;
-
-  req->ptr = dir;
-  POST;
-}
-
-int uv_fs_readlink(uv_loop_t* loop,
-                   uv_fs_t* req,
-                   const char* path,
-                   uv_fs_cb cb) {
-  INIT(READLINK);
-  PATH;
-  POST;
-}
-
-
-int uv_fs_realpath(uv_loop_t* loop,
-                  uv_fs_t* req,
-                  const char * path,
-                  uv_fs_cb cb) {
-  INIT(REALPATH);
-  PATH;
-  POST;
-}
-
-
-int uv_fs_rename(uv_loop_t* loop,
-                 uv_fs_t* req,
-                 const char* path,
-                 const char* new_path,
-                 uv_fs_cb cb) {
-  INIT(RENAME);
-  PATH2;
-  POST;
-}
-
-
-int uv_fs_rmdir(uv_loop_t* loop, uv_fs_t* req, const char* path, uv_fs_cb cb) {
-  INIT(RMDIR);
-  PATH;
-  POST;
-}
-
-
-int uv_fs_sendfile(uv_loop_t* loop,
-                   uv_fs_t* req,
-                   uv_file out_fd,
-                   uv_file in_fd,
-                   int64_t off,
-                   size_t len,
-                   uv_fs_cb cb) {
-  INIT(SENDFILE);
-  req->flags = in_fd; /* hack */
-  req->file = out_fd;
-  req->off = off;
-  req->bufsml[0].len = len;
-  POST;
-}
-
-
-int uv_fs_stat(uv_loop_t* loop, uv_fs_t* req, const char* path, uv_fs_cb cb) {
-  INIT(STAT);
-  PATH;
-  POST;
-}
-
-
-int uv_fs_symlink(uv_loop_t* loop,
-                  uv_fs_t* req,
-                  const char* path,
-                  const char* new_path,
-                  int flags,
-                  uv_fs_cb cb) {
-  INIT(SYMLINK);
-  PATH2;
-  req->flags = flags;
-  POST;
-}
-
-
-int uv_fs_unlink(uv_loop_t* loop, uv_fs_t* req, const char* path, uv_fs_cb cb) {
-  INIT(UNLINK);
-  PATH;
-  POST;
-}
-
-
-int uv_fs_utime(uv_loop_t* loop,
-                uv_fs_t* req,
-                const char* path,
-                double atime,
-                double mtime,
-                uv_fs_cb cb) {
-  INIT(UTIME);
-  PATH;
-  req->atime = atime;
-  req->mtime = mtime;
-  POST;
-}
-
-
-int uv_fs_write(uv_loop_t* loop,
-                uv_fs_t* req,
-                uv_file file,
-                const uv_buf_t bufs[],
-                unsigned int nbufs,
-                int64_t off,
-                uv_fs_cb cb) {
-  INIT(WRITE);
-
-  if (bufs == NULL || nbufs == 0)
-    return UV_EINVAL;
-
-  req->file = file;
-
-  req->nbufs = nbufs;
-  req->bufs = req->bufsml;
-  if (nbufs > ARRAY_SIZE(req->bufsml))
-    req->bufs = (uv_buf_t*)uv__malloc(nbufs * sizeof(*bufs));
-
-  if (req->bufs == NULL)
-    return UV_ENOMEM;
-
-  memcpy(req->bufs, bufs, nbufs * sizeof(*bufs));
-
-  req->off = off;
-  POST;
-}
-
-
-void uv_fs_req_cleanup(uv_fs_t* req) {
-  if (req == NULL)
-    return;
-
-  /* Only necessary for asychronous requests, i.e., requests with a callback.
-   * Synchronous ones don't copy their arguments and have req->path and
-   * req->new_path pointing to user-owned memory.  UV_FS_MKDTEMP is the
-   * exception to the rule, it always allocates memory.
-   */
-  if (req->path != NULL && (req->cb != NULL || req->fs_type == UV_FS_MKDTEMP))
-    uv__free((void*) req->path);  /* Memory is shared with req->new_path. */
-
-  req->path = NULL;
-  req->new_path = NULL;
-
-  if (req->fs_type == UV_FS_READDIR && req->ptr != NULL)
-    uv__fs_readdir_cleanup(req);
-
-  if (req->fs_type == UV_FS_SCANDIR && req->ptr != NULL)
-    uv__fs_scandir_cleanup(req);
-
-  if (req->bufs != req->bufsml)
-    uv__free(req->bufs);
-  req->bufs = NULL;
-
-  if (req->fs_type != UV_FS_OPENDIR && req->ptr != &req->statbuf)
-    uv__free(req->ptr);
-  req->ptr = NULL;
-}
-
-
-int uv_fs_copyfile(uv_loop_t* loop,
-                   uv_fs_t* req,
-                   const char* path,
-                   const char* new_path,
-                   int flags,
-                   uv_fs_cb cb) {
-  INIT(COPYFILE);
-
-  if (flags & ~(UV_FS_COPYFILE_EXCL |
-                UV_FS_COPYFILE_FICLONE |
-                UV_FS_COPYFILE_FICLONE_FORCE)) {
-    return UV_EINVAL;
-  }
-
-  PATH2;
-  req->flags = flags;
-  POST;
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/fsevents.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/fsevents.cpp
deleted file mode 100644
index 32d280f..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/fsevents.cpp
+++ /dev/null
@@ -1,922 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include "uv.h"
-#include "internal.h"
-
-#if TARGET_OS_IPHONE || MAC_OS_X_VERSION_MAX_ALLOWED < 1070
-
-/* iOS (currently) doesn't provide the FSEvents-API (nor CoreServices) */
-/* macOS prior to 10.7 doesn't provide the full FSEvents API so use kqueue */
-
-int uv__fsevents_init(uv_fs_event_t* handle) {
-  return 0;
-}
-
-
-int uv__fsevents_close(uv_fs_event_t* handle) {
-  return 0;
-}
-
-
-void uv__fsevents_loop_delete(uv_loop_t* loop) {
-}
-
-#else /* TARGET_OS_IPHONE */
-
-#include <dlfcn.h>
-#include <assert.h>
-#include <stdlib.h>
-#include <pthread.h>
-
-#include <CoreFoundation/CFRunLoop.h>
-#include <CoreServices/CoreServices.h>
-
-/* These are macros to avoid "initializer element is not constant" errors
- * with old versions of gcc.
- */
-#define kFSEventsModified (kFSEventStreamEventFlagItemFinderInfoMod |         \
-                           kFSEventStreamEventFlagItemModified |              \
-                           kFSEventStreamEventFlagItemInodeMetaMod |          \
-                           kFSEventStreamEventFlagItemChangeOwner |           \
-                           kFSEventStreamEventFlagItemXattrMod)
-
-#define kFSEventsRenamed  (kFSEventStreamEventFlagItemCreated |               \
-                           kFSEventStreamEventFlagItemRemoved |               \
-                           kFSEventStreamEventFlagItemRenamed)
-
-#define kFSEventsSystem   (kFSEventStreamEventFlagUserDropped |               \
-                           kFSEventStreamEventFlagKernelDropped |             \
-                           kFSEventStreamEventFlagEventIdsWrapped |           \
-                           kFSEventStreamEventFlagHistoryDone |               \
-                           kFSEventStreamEventFlagMount |                     \
-                           kFSEventStreamEventFlagUnmount |                   \
-                           kFSEventStreamEventFlagRootChanged)
-
-typedef struct uv__fsevents_event_s uv__fsevents_event_t;
-typedef struct uv__cf_loop_signal_s uv__cf_loop_signal_t;
-typedef struct uv__cf_loop_state_s uv__cf_loop_state_t;
-
-enum uv__cf_loop_signal_type_e {
-  kUVCFLoopSignalRegular,
-  kUVCFLoopSignalClosing
-};
-typedef enum uv__cf_loop_signal_type_e uv__cf_loop_signal_type_t;
-
-struct uv__cf_loop_signal_s {
-  QUEUE member;
-  uv_fs_event_t* handle;
-  uv__cf_loop_signal_type_t type;
-};
-
-struct uv__fsevents_event_s {
-  QUEUE member;
-  int events;
-  char path[1];
-};
-
-struct uv__cf_loop_state_s {
-  CFRunLoopRef loop;
-  CFRunLoopSourceRef signal_source;
-  int fsevent_need_reschedule;
-  FSEventStreamRef fsevent_stream;
-  uv_sem_t fsevent_sem;
-  uv_mutex_t fsevent_mutex;
-  void* fsevent_handles[2];
-  unsigned int fsevent_handle_count;
-};
-
-/* Forward declarations */
-static void uv__cf_loop_cb(void* arg);
-static void* uv__cf_loop_runner(void* arg);
-static int uv__cf_loop_signal(uv_loop_t* loop,
-                              uv_fs_event_t* handle,
-                              uv__cf_loop_signal_type_t type);
-
-/* Lazy-loaded by uv__fsevents_global_init(). */
-static CFArrayRef (*pCFArrayCreate)(CFAllocatorRef,
-                                    const void**,
-                                    CFIndex,
-                                    const CFArrayCallBacks*);
-static void (*pCFRelease)(CFTypeRef);
-static void (*pCFRunLoopAddSource)(CFRunLoopRef,
-                                   CFRunLoopSourceRef,
-                                   CFStringRef);
-static CFRunLoopRef (*pCFRunLoopGetCurrent)(void);
-static void (*pCFRunLoopRemoveSource)(CFRunLoopRef,
-                                      CFRunLoopSourceRef,
-                                      CFStringRef);
-static void (*pCFRunLoopRun)(void);
-static CFRunLoopSourceRef (*pCFRunLoopSourceCreate)(CFAllocatorRef,
-                                                    CFIndex,
-                                                    CFRunLoopSourceContext*);
-static void (*pCFRunLoopSourceSignal)(CFRunLoopSourceRef);
-static void (*pCFRunLoopStop)(CFRunLoopRef);
-static void (*pCFRunLoopWakeUp)(CFRunLoopRef);
-static CFStringRef (*pCFStringCreateWithFileSystemRepresentation)(
-    CFAllocatorRef,
-    const char*);
-static CFStringEncoding (*pCFStringGetSystemEncoding)(void);
-static CFStringRef (*pkCFRunLoopDefaultMode);
-static FSEventStreamRef (*pFSEventStreamCreate)(CFAllocatorRef,
-                                                FSEventStreamCallback,
-                                                FSEventStreamContext*,
-                                                CFArrayRef,
-                                                FSEventStreamEventId,
-                                                CFTimeInterval,
-                                                FSEventStreamCreateFlags);
-static void (*pFSEventStreamFlushSync)(FSEventStreamRef);
-static void (*pFSEventStreamInvalidate)(FSEventStreamRef);
-static void (*pFSEventStreamRelease)(FSEventStreamRef);
-static void (*pFSEventStreamScheduleWithRunLoop)(FSEventStreamRef,
-                                                 CFRunLoopRef,
-                                                 CFStringRef);
-static Boolean (*pFSEventStreamStart)(FSEventStreamRef);
-static void (*pFSEventStreamStop)(FSEventStreamRef);
-
-#define UV__FSEVENTS_PROCESS(handle, block)                                   \
-    do {                                                                      \
-      QUEUE events;                                                           \
-      QUEUE* q;                                                               \
-      uv__fsevents_event_t* event;                                            \
-      int err;                                                                \
-      uv_mutex_lock(&(handle)->cf_mutex);                                     \
-      /* Split-off all events and empty original queue */                     \
-      QUEUE_MOVE(&(handle)->cf_events, &events);                              \
-      /* Get error (if any) and zero original one */                          \
-      err = (handle)->cf_error;                                               \
-      (handle)->cf_error = 0;                                                 \
-      uv_mutex_unlock(&(handle)->cf_mutex);                                   \
-      /* Loop through events, deallocating each after processing */           \
-      while (!QUEUE_EMPTY(&events)) {                                         \
-        q = QUEUE_HEAD(&events);                                              \
-        event = QUEUE_DATA(q, uv__fsevents_event_t, member);                  \
-        QUEUE_REMOVE(q);                                                      \
-        /* NOTE: Checking uv__is_active() is required here, because handle    \
-         * callback may close handle and invoking it after it will lead to    \
-         * incorrect behaviour */                                             \
-        if (!uv__is_closing((handle)) && uv__is_active((handle)))             \
-          block                                                               \
-        /* Free allocated data */                                             \
-        uv__free(event);                                                      \
-      }                                                                       \
-      if (err != 0 && !uv__is_closing((handle)) && uv__is_active((handle)))   \
-        (handle)->cb((handle), NULL, 0, err);                                 \
-    } while (0)
-
-
-/* Runs in UV loop's thread, when there're events to report to handle */
-static void uv__fsevents_cb(uv_async_t* cb) {
-  uv_fs_event_t* handle;
-
-  handle = (uv_fs_event_t*)cb->data;
-
-  UV__FSEVENTS_PROCESS(handle, {
-    handle->cb(handle, event->path[0] ? event->path : NULL, event->events, 0);
-  });
-}
-
-
-/* Runs in CF thread, pushed event into handle's event list */
-static void uv__fsevents_push_event(uv_fs_event_t* handle,
-                                    QUEUE* events,
-                                    int err) {
-  assert(events != NULL || err != 0);
-  uv_mutex_lock(&handle->cf_mutex);
-
-  /* Concatenate two queues */
-  if (events != NULL)
-    QUEUE_ADD(&handle->cf_events, events);
-
-  /* Propagate error */
-  if (err != 0)
-    handle->cf_error = err;
-  uv_mutex_unlock(&handle->cf_mutex);
-
-  uv_async_send(handle->cf_cb);
-}
-
-
-/* Runs in CF thread, when there're events in FSEventStream */
-static void uv__fsevents_event_cb(ConstFSEventStreamRef streamRef,
-                                  void* info,
-                                  size_t numEvents,
-                                  void* eventPaths,
-                                  const FSEventStreamEventFlags eventFlags[],
-                                  const FSEventStreamEventId eventIds[]) {
-  size_t i;
-  int len;
-  char** paths;
-  char* path;
-  char* pos;
-  uv_fs_event_t* handle;
-  QUEUE* q;
-  uv_loop_t* loop;
-  uv__cf_loop_state_t* state;
-  uv__fsevents_event_t* event;
-  FSEventStreamEventFlags flags;
-  QUEUE head;
-
-  loop = (uv_loop_t*)info;
-  state = (uv__cf_loop_state_t*)loop->cf_state;
-  assert(state != NULL);
-  paths = (char**)eventPaths;
-
-  /* For each handle */
-  uv_mutex_lock(&state->fsevent_mutex);
-  QUEUE_FOREACH(q, &state->fsevent_handles) {
-    handle = QUEUE_DATA(q, uv_fs_event_t, cf_member);
-    QUEUE_INIT(&head);
-
-    /* Process and filter out events */
-    for (i = 0; i < numEvents; i++) {
-      flags = eventFlags[i];
-
-      /* Ignore system events */
-      if (flags & kFSEventsSystem)
-        continue;
-
-      path = paths[i];
-      len = strlen(path);
-
-      if (handle->realpath_len == 0)
-        continue; /* This should be unreachable */
-
-      /* Filter out paths that are outside handle's request */
-      if (len < handle->realpath_len)
-        continue;
-
-      if (handle->realpath_len != len &&
-          path[handle->realpath_len] != '/')
-        /* Make sure that realpath actually named a directory,
-         * or that we matched the whole string */
-        continue;
-
-      if (memcmp(path, handle->realpath, handle->realpath_len) != 0)
-        continue;
-
-      if (!(handle->realpath_len == 1 && handle->realpath[0] == '/')) {
-        /* Remove common prefix, unless the watched folder is "/" */
-        path += handle->realpath_len;
-        len -= handle->realpath_len;
-
-        /* Ignore events with path equal to directory itself */
-        if (len <= 1 && (flags & kFSEventStreamEventFlagItemIsDir))
-          continue;
-
-        if (len == 0) {
-          /* Since we're using fsevents to watch the file itself,
-           * realpath == path, and we now need to get the basename of the file back
-           * (for commonality with other codepaths and platforms). */
-          while (len < handle->realpath_len && path[-1] != '/') {
-            path--;
-            len++;
-          }
-          /* Created and Removed seem to be always set, but don't make sense */
-          flags &= ~kFSEventsRenamed;
-        } else {
-          /* Skip forward slash */
-          path++;
-          len--;
-        }
-      }
-
-      /* Do not emit events from subdirectories (without option set) */
-      if ((handle->cf_flags & UV_FS_EVENT_RECURSIVE) == 0 && *path != '\0') {
-        pos = strchr(path + 1, '/');
-        if (pos != NULL)
-          continue;
-      }
-
-      event = (uv__fsevents_event_t*)uv__malloc(sizeof(*event) + len);
-      if (event == NULL)
-        break;
-
-      memset(event, 0, sizeof(*event));
-      memcpy(event->path, path, len + 1);
-      event->events = UV_RENAME;
-
-      if (0 == (flags & kFSEventsRenamed)) {
-        if (0 != (flags & kFSEventsModified) ||
-            0 == (flags & kFSEventStreamEventFlagItemIsDir))
-          event->events = UV_CHANGE;
-      }
-
-      QUEUE_INSERT_TAIL(&head, &event->member);
-    }
-
-    if (!QUEUE_EMPTY(&head))
-      uv__fsevents_push_event(handle, &head, 0);
-  }
-  uv_mutex_unlock(&state->fsevent_mutex);
-}
-
-
-/* Runs in CF thread */
-static int uv__fsevents_create_stream(uv_loop_t* loop, CFArrayRef paths) {
-  uv__cf_loop_state_t* state;
-  FSEventStreamContext ctx;
-  FSEventStreamRef ref;
-  CFAbsoluteTime latency;
-  FSEventStreamCreateFlags flags;
-
-  /* Initialize context */
-  ctx.version = 0;
-  ctx.info = loop;
-  ctx.retain = NULL;
-  ctx.release = NULL;
-  ctx.copyDescription = NULL;
-
-  latency = 0.05;
-
-  /* Explanation of selected flags:
-   * 1. NoDefer - without this flag, events that are happening continuously
-   *    (i.e. each event is happening after time interval less than `latency`,
-   *    counted from previous event), will be deferred and passed to callback
-   *    once they'll either fill whole OS buffer, or when this continuous stream
-   *    will stop (i.e. there'll be delay between events, bigger than
-   *    `latency`).
-   *    Specifying this flag will invoke callback after `latency` time passed
-   *    since event.
-   * 2. FileEvents - fire callback for file changes too (by default it is firing
-   *    it only for directory changes).
-   */
-  flags = kFSEventStreamCreateFlagNoDefer | kFSEventStreamCreateFlagFileEvents;
-
-  /*
-   * NOTE: It might sound like a good idea to remember last seen StreamEventId,
-   * but in reality one dir might have last StreamEventId less than, the other,
-   * that is being watched now. Which will cause FSEventStream API to report
-   * changes to files from the past.
-   */
-  ref = pFSEventStreamCreate(NULL,
-                             &uv__fsevents_event_cb,
-                             &ctx,
-                             paths,
-                             kFSEventStreamEventIdSinceNow,
-                             latency,
-                             flags);
-  assert(ref != NULL);
-
-  state = (uv__cf_loop_state_t*)loop->cf_state;
-  pFSEventStreamScheduleWithRunLoop(ref,
-                                    state->loop,
-                                    *pkCFRunLoopDefaultMode);
-  if (!pFSEventStreamStart(ref)) {
-    pFSEventStreamInvalidate(ref);
-    pFSEventStreamRelease(ref);
-    return UV_EMFILE;
-  }
-
-  state->fsevent_stream = ref;
-  return 0;
-}
-
-
-/* Runs in CF thread */
-static void uv__fsevents_destroy_stream(uv_loop_t* loop) {
-  uv__cf_loop_state_t* state;
-
-  state = (uv__cf_loop_state_t*)loop->cf_state;
-
-  if (state->fsevent_stream == NULL)
-    return;
-
-  /* Stop emitting events */
-  pFSEventStreamStop(state->fsevent_stream);
-
-  /* Release stream */
-  pFSEventStreamInvalidate(state->fsevent_stream);
-  pFSEventStreamRelease(state->fsevent_stream);
-  state->fsevent_stream = NULL;
-}
-
-
-/* Runs in CF thread, when there're new fsevent handles to add to stream */
-static void uv__fsevents_reschedule(uv_fs_event_t* handle,
-                                    uv__cf_loop_signal_type_t type) {
-  uv__cf_loop_state_t* state;
-  QUEUE* q;
-  uv_fs_event_t* curr;
-  CFArrayRef cf_paths;
-  CFStringRef* paths;
-  unsigned int i;
-  int err;
-  unsigned int path_count;
-
-  state = (uv__cf_loop_state_t*)handle->loop->cf_state;
-  paths = NULL;
-  cf_paths = NULL;
-  err = 0;
-  /* NOTE: `i` is used in deallocation loop below */
-  i = 0;
-
-  /* Optimization to prevent O(n^2) time spent when starting to watch
-   * many files simultaneously
-   */
-  uv_mutex_lock(&state->fsevent_mutex);
-  if (state->fsevent_need_reschedule == 0) {
-    uv_mutex_unlock(&state->fsevent_mutex);
-    goto final;
-  }
-  state->fsevent_need_reschedule = 0;
-  uv_mutex_unlock(&state->fsevent_mutex);
-
-  /* Destroy previous FSEventStream */
-  uv__fsevents_destroy_stream(handle->loop);
-
-  /* Any failure below will be a memory failure */
-  err = UV_ENOMEM;
-
-  /* Create list of all watched paths */
-  uv_mutex_lock(&state->fsevent_mutex);
-  path_count = state->fsevent_handle_count;
-  if (path_count != 0) {
-    paths = (CFStringRef*)uv__malloc(sizeof(*paths) * path_count);
-    if (paths == NULL) {
-      uv_mutex_unlock(&state->fsevent_mutex);
-      goto final;
-    }
-
-    q = &state->fsevent_handles;
-    for (; i < path_count; i++) {
-      q = QUEUE_NEXT(q);
-      assert(q != &state->fsevent_handles);
-      curr = QUEUE_DATA(q, uv_fs_event_t, cf_member);
-
-      assert(curr->realpath != NULL);
-      paths[i] =
-          pCFStringCreateWithFileSystemRepresentation(NULL, curr->realpath);
-      if (paths[i] == NULL) {
-        uv_mutex_unlock(&state->fsevent_mutex);
-        goto final;
-      }
-    }
-  }
-  uv_mutex_unlock(&state->fsevent_mutex);
-  err = 0;
-
-  if (path_count != 0) {
-    /* Create new FSEventStream */
-    cf_paths = pCFArrayCreate(NULL, (const void**) paths, path_count, NULL);
-    if (cf_paths == NULL) {
-      err = UV_ENOMEM;
-      goto final;
-    }
-    err = uv__fsevents_create_stream(handle->loop, cf_paths);
-  }
-
-final:
-  /* Deallocate all paths in case of failure */
-  if (err != 0) {
-    if (cf_paths == NULL) {
-      while (i != 0)
-        pCFRelease(paths[--i]);
-      uv__free(paths);
-    } else {
-      /* CFArray takes ownership of both strings and original C-array */
-      pCFRelease(cf_paths);
-    }
-
-    /* Broadcast error to all handles */
-    uv_mutex_lock(&state->fsevent_mutex);
-    QUEUE_FOREACH(q, &state->fsevent_handles) {
-      curr = QUEUE_DATA(q, uv_fs_event_t, cf_member);
-      uv__fsevents_push_event(curr, NULL, err);
-    }
-    uv_mutex_unlock(&state->fsevent_mutex);
-  }
-
-  /*
-   * Main thread will block until the removal of handle from the list,
-   * we must tell it when we're ready.
-   *
-   * NOTE: This is coupled with `uv_sem_wait()` in `uv__fsevents_close`
-   */
-  if (type == kUVCFLoopSignalClosing)
-    uv_sem_post(&state->fsevent_sem);
-}
-
-
-static int uv__fsevents_global_init(void) {
-  static pthread_mutex_t global_init_mutex = PTHREAD_MUTEX_INITIALIZER;
-  static void* core_foundation_handle;
-  static void* core_services_handle;
-  int err;
-
-  err = 0;
-  pthread_mutex_lock(&global_init_mutex);
-  if (core_foundation_handle != NULL)
-    goto out;
-
-  /* The libraries are never unloaded because we currently don't have a good
-   * mechanism for keeping a reference count. It's unlikely to be an issue
-   * but if it ever becomes one, we can turn the dynamic library handles into
-   * per-event loop properties and have the dynamic linker keep track for us.
-   */
-  err = UV_ENOSYS;
-  core_foundation_handle = dlopen("/System/Library/Frameworks/"
-                                  "CoreFoundation.framework/"
-                                  "Versions/A/CoreFoundation",
-                                  RTLD_LAZY | RTLD_LOCAL);
-  if (core_foundation_handle == NULL)
-    goto out;
-
-  core_services_handle = dlopen("/System/Library/Frameworks/"
-                                "CoreServices.framework/"
-                                "Versions/A/CoreServices",
-                                RTLD_LAZY | RTLD_LOCAL);
-  if (core_services_handle == NULL)
-    goto out;
-
-  err = UV_ENOENT;
-#define V(handle, symbol)                                                     \
-  do {                                                                        \
-    *(void **)(&p ## symbol) = dlsym((handle), #symbol);                      \
-    if (p ## symbol == NULL)                                                  \
-      goto out;                                                               \
-  }                                                                           \
-  while (0)
-  V(core_foundation_handle, CFArrayCreate);
-  V(core_foundation_handle, CFRelease);
-  V(core_foundation_handle, CFRunLoopAddSource);
-  V(core_foundation_handle, CFRunLoopGetCurrent);
-  V(core_foundation_handle, CFRunLoopRemoveSource);
-  V(core_foundation_handle, CFRunLoopRun);
-  V(core_foundation_handle, CFRunLoopSourceCreate);
-  V(core_foundation_handle, CFRunLoopSourceSignal);
-  V(core_foundation_handle, CFRunLoopStop);
-  V(core_foundation_handle, CFRunLoopWakeUp);
-  V(core_foundation_handle, CFStringCreateWithFileSystemRepresentation);
-  V(core_foundation_handle, CFStringGetSystemEncoding);
-  V(core_foundation_handle, kCFRunLoopDefaultMode);
-  V(core_services_handle, FSEventStreamCreate);
-  V(core_services_handle, FSEventStreamFlushSync);
-  V(core_services_handle, FSEventStreamInvalidate);
-  V(core_services_handle, FSEventStreamRelease);
-  V(core_services_handle, FSEventStreamScheduleWithRunLoop);
-  V(core_services_handle, FSEventStreamStart);
-  V(core_services_handle, FSEventStreamStop);
-#undef V
-  err = 0;
-
-out:
-  if (err && core_services_handle != NULL) {
-    dlclose(core_services_handle);
-    core_services_handle = NULL;
-  }
-
-  if (err && core_foundation_handle != NULL) {
-    dlclose(core_foundation_handle);
-    core_foundation_handle = NULL;
-  }
-
-  pthread_mutex_unlock(&global_init_mutex);
-  return err;
-}
-
-
-/* Runs in UV loop */
-static int uv__fsevents_loop_init(uv_loop_t* loop) {
-  CFRunLoopSourceContext ctx;
-  uv__cf_loop_state_t* state;
-  pthread_attr_t attr_storage;
-  pthread_attr_t* attr;
-  int err;
-
-  if (loop->cf_state != NULL)
-    return 0;
-
-  err = uv__fsevents_global_init();
-  if (err)
-    return err;
-
-  state = (uv__cf_loop_state_t*)uv__calloc(1, sizeof(*state));
-  if (state == NULL)
-    return UV_ENOMEM;
-
-  err = uv_mutex_init(&loop->cf_mutex);
-  if (err)
-    goto fail_mutex_init;
-
-  err = uv_sem_init(&loop->cf_sem, 0);
-  if (err)
-    goto fail_sem_init;
-
-  QUEUE_INIT(&loop->cf_signals);
-
-  err = uv_sem_init(&state->fsevent_sem, 0);
-  if (err)
-    goto fail_fsevent_sem_init;
-
-  err = uv_mutex_init(&state->fsevent_mutex);
-  if (err)
-    goto fail_fsevent_mutex_init;
-
-  QUEUE_INIT(&state->fsevent_handles);
-  state->fsevent_need_reschedule = 0;
-  state->fsevent_handle_count = 0;
-
-  memset(&ctx, 0, sizeof(ctx));
-  ctx.info = loop;
-  ctx.perform = uv__cf_loop_cb;
-  state->signal_source = pCFRunLoopSourceCreate(NULL, 0, &ctx);
-  if (state->signal_source == NULL) {
-    err = UV_ENOMEM;
-    goto fail_signal_source_create;
-  }
-
-  /* In the unlikely event that pthread_attr_init() fails, create the thread
-   * with the default stack size. We'll use a little more address space but
-   * that in itself is not a fatal error.
-   */
-  attr = &attr_storage;
-  if (pthread_attr_init(attr))
-    attr = NULL;
-
-  if (attr != NULL)
-    if (pthread_attr_setstacksize(attr, 4 * PTHREAD_STACK_MIN))
-      abort();
-
-  loop->cf_state = state;
-
-  /* uv_thread_t is an alias for pthread_t. */
-  err = UV__ERR(pthread_create(&loop->cf_thread, attr, uv__cf_loop_runner, loop));
-
-  if (attr != NULL)
-    pthread_attr_destroy(attr);
-
-  if (err)
-    goto fail_thread_create;
-
-  /* Synchronize threads */
-  uv_sem_wait(&loop->cf_sem);
-  return 0;
-
-fail_thread_create:
-  loop->cf_state = NULL;
-
-fail_signal_source_create:
-  uv_mutex_destroy(&state->fsevent_mutex);
-
-fail_fsevent_mutex_init:
-  uv_sem_destroy(&state->fsevent_sem);
-
-fail_fsevent_sem_init:
-  uv_sem_destroy(&loop->cf_sem);
-
-fail_sem_init:
-  uv_mutex_destroy(&loop->cf_mutex);
-
-fail_mutex_init:
-  uv__free(state);
-  return err;
-}
-
-
-/* Runs in UV loop */
-void uv__fsevents_loop_delete(uv_loop_t* loop) {
-  uv__cf_loop_signal_t* s;
-  uv__cf_loop_state_t* state;
-  QUEUE* q;
-
-  if (loop->cf_state == NULL)
-    return;
-
-  if (uv__cf_loop_signal(loop, NULL, kUVCFLoopSignalRegular) != 0)
-    abort();
-
-  uv_thread_join(&loop->cf_thread);
-  uv_sem_destroy(&loop->cf_sem);
-  uv_mutex_destroy(&loop->cf_mutex);
-
-  /* Free any remaining data */
-  while (!QUEUE_EMPTY(&loop->cf_signals)) {
-    q = QUEUE_HEAD(&loop->cf_signals);
-    s = QUEUE_DATA(q, uv__cf_loop_signal_t, member);
-    QUEUE_REMOVE(q);
-    uv__free(s);
-  }
-
-  /* Destroy state */
-  state = (uv__cf_loop_state_t*)loop->cf_state;
-  uv_sem_destroy(&state->fsevent_sem);
-  uv_mutex_destroy(&state->fsevent_mutex);
-  pCFRelease(state->signal_source);
-  uv__free(state);
-  loop->cf_state = NULL;
-}
-
-
-/* Runs in CF thread. This is the CF loop's body */
-static void* uv__cf_loop_runner(void* arg) {
-  uv_loop_t* loop;
-  uv__cf_loop_state_t* state;
-
-  loop = (uv_loop_t*)arg;
-  state = (uv__cf_loop_state_t*)loop->cf_state;
-  state->loop = pCFRunLoopGetCurrent();
-
-  pCFRunLoopAddSource(state->loop,
-                      state->signal_source,
-                      *pkCFRunLoopDefaultMode);
-
-  uv_sem_post(&loop->cf_sem);
-
-  pCFRunLoopRun();
-  pCFRunLoopRemoveSource(state->loop,
-                         state->signal_source,
-                         *pkCFRunLoopDefaultMode);
-
-  return NULL;
-}
-
-
-/* Runs in CF thread, executed after `uv__cf_loop_signal()` */
-static void uv__cf_loop_cb(void* arg) {
-  uv_loop_t* loop;
-  uv__cf_loop_state_t* state;
-  QUEUE* item;
-  QUEUE split_head;
-  uv__cf_loop_signal_t* s;
-
-  loop = (uv_loop_t*)arg;
-  state = (uv__cf_loop_state_t*)loop->cf_state;
-
-  uv_mutex_lock(&loop->cf_mutex);
-  QUEUE_MOVE(&loop->cf_signals, &split_head);
-  uv_mutex_unlock(&loop->cf_mutex);
-
-  while (!QUEUE_EMPTY(&split_head)) {
-    item = QUEUE_HEAD(&split_head);
-    QUEUE_REMOVE(item);
-
-    s = QUEUE_DATA(item, uv__cf_loop_signal_t, member);
-
-    /* This was a termination signal */
-    if (s->handle == NULL)
-      pCFRunLoopStop(state->loop);
-    else
-      uv__fsevents_reschedule(s->handle, s->type);
-
-    uv__free(s);
-  }
-}
-
-
-/* Runs in UV loop to notify CF thread */
-int uv__cf_loop_signal(uv_loop_t* loop,
-                       uv_fs_event_t* handle,
-                       uv__cf_loop_signal_type_t type) {
-  uv__cf_loop_signal_t* item;
-  uv__cf_loop_state_t* state;
-
-  item = (uv__cf_loop_signal_t*)uv__malloc(sizeof(*item));
-  if (item == NULL)
-    return UV_ENOMEM;
-
-  item->handle = handle;
-  item->type = type;
-
-  uv_mutex_lock(&loop->cf_mutex);
-  QUEUE_INSERT_TAIL(&loop->cf_signals, &item->member);
-  uv_mutex_unlock(&loop->cf_mutex);
-
-  state = (uv__cf_loop_state_t*)loop->cf_state;
-  assert(state != NULL);
-  pCFRunLoopSourceSignal(state->signal_source);
-  pCFRunLoopWakeUp(state->loop);
-
-  return 0;
-}
-
-
-/* Runs in UV loop to initialize handle */
-int uv__fsevents_init(uv_fs_event_t* handle) {
-  int err;
-  uv__cf_loop_state_t* state;
-
-  err = uv__fsevents_loop_init(handle->loop);
-  if (err)
-    return err;
-
-  /* Get absolute path to file */
-  handle->realpath = realpath(handle->path, NULL);
-  if (handle->realpath == NULL)
-    return UV__ERR(errno);
-  handle->realpath_len = strlen(handle->realpath);
-
-  /* Initialize event queue */
-  QUEUE_INIT(&handle->cf_events);
-  handle->cf_error = 0;
-
-  /*
-   * Events will occur in other thread.
-   * Initialize callback for getting them back into event loop's thread
-   */
-  handle->cf_cb = (uv_async_t*)uv__malloc(sizeof(*handle->cf_cb));
-  if (handle->cf_cb == NULL) {
-    err = UV_ENOMEM;
-    goto fail_cf_cb_malloc;
-  }
-
-  handle->cf_cb->data = handle;
-  uv_async_init(handle->loop, handle->cf_cb, uv__fsevents_cb);
-  handle->cf_cb->flags |= UV_HANDLE_INTERNAL;
-  uv_unref((uv_handle_t*) handle->cf_cb);
-
-  err = uv_mutex_init(&handle->cf_mutex);
-  if (err)
-    goto fail_cf_mutex_init;
-
-  /* Insert handle into the list */
-  state = (uv__cf_loop_state_t*)handle->loop->cf_state;
-  uv_mutex_lock(&state->fsevent_mutex);
-  QUEUE_INSERT_TAIL(&state->fsevent_handles, &handle->cf_member);
-  state->fsevent_handle_count++;
-  state->fsevent_need_reschedule = 1;
-  uv_mutex_unlock(&state->fsevent_mutex);
-
-  /* Reschedule FSEventStream */
-  assert(handle != NULL);
-  err = uv__cf_loop_signal(handle->loop, handle, kUVCFLoopSignalRegular);
-  if (err)
-    goto fail_loop_signal;
-
-  return 0;
-
-fail_loop_signal:
-  uv_mutex_destroy(&handle->cf_mutex);
-
-fail_cf_mutex_init:
-  uv__free(handle->cf_cb);
-  handle->cf_cb = NULL;
-
-fail_cf_cb_malloc:
-  uv__free(handle->realpath);
-  handle->realpath = NULL;
-  handle->realpath_len = 0;
-
-  return err;
-}
-
-
-/* Runs in UV loop to de-initialize handle */
-int uv__fsevents_close(uv_fs_event_t* handle) {
-  int err;
-  uv__cf_loop_state_t* state;
-
-  if (handle->cf_cb == NULL)
-    return UV_EINVAL;
-
-  /* Remove handle from  the list */
-  state = (uv__cf_loop_state_t*)handle->loop->cf_state;
-  uv_mutex_lock(&state->fsevent_mutex);
-  QUEUE_REMOVE(&handle->cf_member);
-  state->fsevent_handle_count--;
-  state->fsevent_need_reschedule = 1;
-  uv_mutex_unlock(&state->fsevent_mutex);
-
-  /* Reschedule FSEventStream */
-  assert(handle != NULL);
-  err = uv__cf_loop_signal(handle->loop, handle, kUVCFLoopSignalClosing);
-  if (err)
-    return UV__ERR(err);
-
-  /* Wait for deinitialization */
-  uv_sem_wait(&state->fsevent_sem);
-
-  uv_close((uv_handle_t*) handle->cf_cb, (uv_close_cb) uv__free);
-  handle->cf_cb = NULL;
-
-  /* Free data in queue */
-  UV__FSEVENTS_PROCESS(handle, {
-    /* NOP */
-  });
-
-  uv_mutex_destroy(&handle->cf_mutex);
-  uv__free(handle->realpath);
-  handle->realpath = NULL;
-  handle->realpath_len = 0;
-
-  return 0;
-}
-
-#endif /* TARGET_OS_IPHONE */
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/getaddrinfo.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/getaddrinfo.cpp
deleted file mode 100644
index 9a26b45..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/getaddrinfo.cpp
+++ /dev/null
@@ -1,255 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-/* Expose glibc-specific EAI_* error codes. Needs to be defined before we
- * include any headers.
- */
-#ifndef _GNU_SOURCE
-# define _GNU_SOURCE
-#endif
-
-#include "uv.h"
-#include "internal.h"
-#include "idna.h"
-
-#include <errno.h>
-#include <stddef.h> /* NULL */
-#include <stdlib.h>
-#include <string.h>
-#include <net/if.h> /* if_indextoname() */
-
-/* EAI_* constants. */
-#include <netdb.h>
-
-
-int uv__getaddrinfo_translate_error(int sys_err) {
-  switch (sys_err) {
-  case 0: return 0;
-#if defined(EAI_ADDRFAMILY)
-  case EAI_ADDRFAMILY: return UV_EAI_ADDRFAMILY;
-#endif
-#if defined(EAI_AGAIN)
-  case EAI_AGAIN: return UV_EAI_AGAIN;
-#endif
-#if defined(EAI_BADFLAGS)
-  case EAI_BADFLAGS: return UV_EAI_BADFLAGS;
-#endif
-#if defined(EAI_BADHINTS)
-  case EAI_BADHINTS: return UV_EAI_BADHINTS;
-#endif
-#if defined(EAI_CANCELED)
-  case EAI_CANCELED: return UV_EAI_CANCELED;
-#endif
-#if defined(EAI_FAIL)
-  case EAI_FAIL: return UV_EAI_FAIL;
-#endif
-#if defined(EAI_FAMILY)
-  case EAI_FAMILY: return UV_EAI_FAMILY;
-#endif
-#if defined(EAI_MEMORY)
-  case EAI_MEMORY: return UV_EAI_MEMORY;
-#endif
-#if defined(EAI_NODATA)
-  case EAI_NODATA: return UV_EAI_NODATA;
-#endif
-#if defined(EAI_NONAME)
-# if !defined(EAI_NODATA) || EAI_NODATA != EAI_NONAME
-  case EAI_NONAME: return UV_EAI_NONAME;
-# endif
-#endif
-#if defined(EAI_OVERFLOW)
-  case EAI_OVERFLOW: return UV_EAI_OVERFLOW;
-#endif
-#if defined(EAI_PROTOCOL)
-  case EAI_PROTOCOL: return UV_EAI_PROTOCOL;
-#endif
-#if defined(EAI_SERVICE)
-  case EAI_SERVICE: return UV_EAI_SERVICE;
-#endif
-#if defined(EAI_SOCKTYPE)
-  case EAI_SOCKTYPE: return UV_EAI_SOCKTYPE;
-#endif
-#if defined(EAI_SYSTEM)
-  case EAI_SYSTEM: return UV__ERR(errno);
-#endif
-  }
-  assert(!"unknown EAI_* error code");
-  abort();
-#ifndef __SUNPRO_C
-  return 0;  /* Pacify compiler. */
-#endif
-}
-
-
-static void uv__getaddrinfo_work(struct uv__work* w) {
-  uv_getaddrinfo_t* req;
-  int err;
-
-  req = container_of(w, uv_getaddrinfo_t, work_req);
-  err = getaddrinfo(req->hostname, req->service, req->hints, &req->addrinfo);
-  req->retcode = uv__getaddrinfo_translate_error(err);
-}
-
-
-static void uv__getaddrinfo_done(struct uv__work* w, int status) {
-  uv_getaddrinfo_t* req;
-
-  req = container_of(w, uv_getaddrinfo_t, work_req);
-  uv__req_unregister(req->loop, req);
-
-  /* See initialization in uv_getaddrinfo(). */
-  if (req->hints)
-    uv__free(req->hints);
-  else if (req->service)
-    uv__free(req->service);
-  else if (req->hostname)
-    uv__free(req->hostname);
-  else
-    assert(0);
-
-  req->hints = NULL;
-  req->service = NULL;
-  req->hostname = NULL;
-
-  if (status == UV_ECANCELED) {
-    assert(req->retcode == 0);
-    req->retcode = UV_EAI_CANCELED;
-  }
-
-  if (req->cb)
-    req->cb(req, req->retcode, req->addrinfo);
-}
-
-
-int uv_getaddrinfo(uv_loop_t* loop,
-                   uv_getaddrinfo_t* req,
-                   uv_getaddrinfo_cb cb,
-                   const char* hostname,
-                   const char* service,
-                   const struct addrinfo* hints) {
-  char hostname_ascii[256];
-  size_t hostname_len;
-  size_t service_len;
-  size_t hints_len;
-  size_t len;
-  char* buf;
-  long rc;
-
-  if (req == NULL || (hostname == NULL && service == NULL))
-    return UV_EINVAL;
-
-  /* FIXME(bnoordhuis) IDNA does not seem to work z/OS,
-   * probably because it uses EBCDIC rather than ASCII.
-   */
-#ifdef __MVS__
-  (void) &hostname_ascii;
-#else
-  if (hostname != NULL) {
-    rc = uv__idna_toascii(hostname,
-                          hostname + strlen(hostname),
-                          hostname_ascii,
-                          hostname_ascii + sizeof(hostname_ascii));
-    if (rc < 0)
-      return rc;
-    hostname = hostname_ascii;
-  }
-#endif
-
-  hostname_len = hostname ? strlen(hostname) + 1 : 0;
-  service_len = service ? strlen(service) + 1 : 0;
-  hints_len = hints ? sizeof(*hints) : 0;
-  buf = (char*)uv__malloc(hostname_len + service_len + hints_len);
-
-  if (buf == NULL)
-    return UV_ENOMEM;
-
-  uv__req_init(loop, req, UV_GETADDRINFO);
-  req->loop = loop;
-  req->cb = cb;
-  req->addrinfo = NULL;
-  req->hints = NULL;
-  req->service = NULL;
-  req->hostname = NULL;
-  req->retcode = 0;
-
-  /* order matters, see uv_getaddrinfo_done() */
-  len = 0;
-
-  if (hints) {
-    req->hints = (struct addrinfo*)memcpy(buf + len, hints, sizeof(*hints));
-    len += sizeof(*hints);
-  }
-
-  if (service) {
-    req->service = (char*)memcpy(buf + len, service, service_len);
-    len += service_len;
-  }
-
-  if (hostname)
-    req->hostname = (char*)memcpy(buf + len, hostname, hostname_len);
-
-  if (cb) {
-    uv__work_submit(loop,
-                    &req->work_req,
-                    UV__WORK_SLOW_IO,
-                    uv__getaddrinfo_work,
-                    uv__getaddrinfo_done);
-    return 0;
-  } else {
-    uv__getaddrinfo_work(&req->work_req);
-    uv__getaddrinfo_done(&req->work_req, 0);
-    return req->retcode;
-  }
-}
-
-
-void uv_freeaddrinfo(struct addrinfo* ai) {
-  if (ai)
-    freeaddrinfo(ai);
-}
-
-
-int uv_if_indextoname(unsigned int ifindex, char* buffer, size_t* size) {
-  char ifname_buf[UV_IF_NAMESIZE];
-  size_t len;
-
-  if (buffer == NULL || size == NULL || *size == 0)
-    return UV_EINVAL;
-
-  if (if_indextoname(ifindex, ifname_buf) == NULL)
-    return UV__ERR(errno);
-
-  len = strnlen(ifname_buf, sizeof(ifname_buf));
-
-  if (*size <= len) {
-    *size = len + 1;
-    return UV_ENOBUFS;
-  }
-
-  memcpy(buffer, ifname_buf, len);
-  buffer[len] = '\0';
-  *size = len;
-
-  return 0;
-}
-
-int uv_if_indextoiid(unsigned int ifindex, char* buffer, size_t* size) {
-  return uv_if_indextoname(ifindex, buffer, size);
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/ibmi.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/ibmi.cpp
deleted file mode 100644
index 4b0be2d..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/ibmi.cpp
+++ /dev/null
@@ -1,249 +0,0 @@
-/* Copyright libuv project contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include "uv.h"
-#include "internal.h"
-
-#include <stdio.h>
-#include <stdint.h>
-#include <stdlib.h>
-#include <string.h>
-#include <assert.h>
-#include <errno.h>
-
-#include <sys/types.h>
-#include <sys/socket.h>
-#include <sys/ioctl.h>
-#include <net/if.h>
-#include <netinet/in.h>
-#include <arpa/inet.h>
-
-#include <sys/time.h>
-#include <unistd.h>
-#include <fcntl.h>
-#include <utmp.h>
-#include <libgen.h>
-
-#include <sys/protosw.h>
-#include <procinfo.h>
-#include <sys/proc.h>
-#include <sys/procfs.h>
-
-#include <ctype.h>
-
-#include <sys/mntctl.h>
-#include <sys/vmount.h>
-#include <limits.h>
-#include <strings.h>
-#include <sys/vnode.h>
-
-#include <as400_protos.h>
-
-
-typedef struct {
-  int bytes_available;
-  int bytes_returned;
-  char current_date_and_time[8];
-  char system_name[8];
-  char elapsed_time[6];
-  char restricted_state_flag;
-  char reserved;
-  int percent_processing_unit_used;
-  int jobs_in_system;
-  int percent_permanent_addresses;
-  int percent_temporary_addresses;
-  int system_asp;
-  int percent_system_asp_used;
-  int total_auxiliary_storage;
-  int current_unprotected_storage_used;
-  int maximum_unprotected_storage_used;
-  int percent_db_capability;
-  int main_storage_size;
-  int number_of_partitions;
-  int partition_identifier;
-  int reserved1;
-  int current_processing_capacity;
-  char processor_sharing_attribute;
-  char reserved2[3];
-  int number_of_processors;
-  int active_jobs_in_system;
-  int active_threads_in_system;
-  int maximum_jobs_in_system;
-  int percent_temporary_256mb_segments_used;
-  int percent_temporary_4gb_segments_used;
-  int percent_permanent_256mb_segments_used;
-  int percent_permanent_4gb_segments_used;
-  int percent_current_interactive_performance;
-  int percent_uncapped_cpu_capacity_used;
-  int percent_shared_processor_pool_used;
-  long main_storage_size_long;
-} SSTS0200;
-
-
-static int get_ibmi_system_status(SSTS0200* rcvr) {
-  /* rcvrlen is input parameter 2 to QWCRSSTS */
-  unsigned int rcvrlen = sizeof(*rcvr);
-
-  /* format is input parameter 3 to QWCRSSTS ("SSTS0200" in EBCDIC) */
-  unsigned char format[] = {0xE2, 0xE2, 0xE3, 0xE2, 0xF0, 0xF2, 0xF0, 0xF0};
-
-  /* reset_status is input parameter 4 to QWCRSSTS ("*NO       " in EBCDIC) */
-  unsigned char reset_status[] = {
-    0x5C, 0xD5, 0xD6, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40
-  };
-
-  /* errcode is input parameter 5 to QWCRSSTS */
-  struct _errcode {
-    int bytes_provided;
-    int bytes_available;
-    char msgid[7];
-  } errcode;
-
-  /* qwcrssts_pointer is the 16-byte tagged system pointer to QWCRSSTS */
-  ILEpointer __attribute__((aligned(16))) qwcrssts_pointer;
-
-  /* qwcrssts_argv is the array of argument pointers to QWCRSSTS */
-  void* qwcrssts_argv[6];
-
-  /* Set the IBM i pointer to the QSYS/QWCRSSTS *PGM object */
-  int rc = _RSLOBJ2(&qwcrssts_pointer, RSLOBJ_TS_PGM, "QWCRSSTS", "QSYS");
-
-  if (rc != 0)
-    return rc;
-
-  /* initialize the QWCRSSTS returned info structure */
-  memset(rcvr, 0, sizeof(*rcvr));
-
-  /* initialize the QWCRSSTS error code structure */
-  memset(&errcode, 0, sizeof(errcode));
-  errcode.bytes_provided = sizeof(errcode);
-
-  /* initialize the array of argument pointers for the QWCRSSTS API */
-  qwcrssts_argv[0] = rcvr;
-  qwcrssts_argv[1] = &rcvrlen;
-  qwcrssts_argv[2] = &format;
-  qwcrssts_argv[3] = &reset_status;
-  qwcrssts_argv[4] = &errcode;
-  qwcrssts_argv[5] = NULL;
-
-  /* Call the IBM i QWCRSSTS API from PASE */
-  rc = _PGMCALL(&qwcrssts_pointer, (void**)&qwcrssts_argv, 0);
-
-  return rc;
-}
-
-
-uint64_t uv_get_free_memory(void) {
-  SSTS0200 rcvr;
-
-  if (get_ibmi_system_status(&rcvr))
-    return 0;
-
-  /* The amount of main storage, in kilobytes, in the system. */
-  uint64_t main_storage_size = rcvr.main_storage_size;
-
-  /* The current amount of storage in use for temporary objects.
-   * in millions (M) of bytes.
-   */
-  uint64_t current_unprotected_storage_used =
-    rcvr.current_unprotected_storage_used * 1024ULL;
-
-  uint64_t free_storage_size =
-    (main_storage_size - current_unprotected_storage_used) * 1024ULL;
-
-  return free_storage_size < 0 ? 0 : free_storage_size;
-}
-
-
-uint64_t uv_get_total_memory(void) {
-  SSTS0200 rcvr;
-
-  if (get_ibmi_system_status(&rcvr))
-    return 0;
-
-  return (uint64_t)rcvr.main_storage_size * 1024ULL;
-}
-
-
-uint64_t uv_get_constrained_memory(void) {
-  return 0;  /* Memory constraints are unknown. */
-}
-
-
-void uv_loadavg(double avg[3]) {
-  SSTS0200 rcvr;
-
-  if (get_ibmi_system_status(&rcvr)) {
-    avg[0] = avg[1] = avg[2] = 0;
-    return;
-  }
-
-  /* The average (in tenths) of the elapsed time during which the processing
-   * units were in use. For example, a value of 411 in binary would be 41.1%.
-   * This percentage could be greater than 100% for an uncapped partition.
-   */
-  double processing_unit_used_percent =
-    rcvr.percent_processing_unit_used / 1000.0;
-
-  avg[0] = avg[1] = avg[2] = processing_unit_used_percent;
-}
-
-
-int uv_resident_set_memory(size_t* rss) {
-  *rss = 0;
-  return 0;
-}
-
-
-int uv_uptime(double* uptime) {
-  return UV_ENOSYS;
-}
-
-
-int uv_cpu_info(uv_cpu_info_t** cpu_infos, int* count) {
-  unsigned int numcpus, idx = 0;
-  uv_cpu_info_t* cpu_info;
-
-  *cpu_infos = NULL;
-  *count = 0;
-
-  numcpus = sysconf(_SC_NPROCESSORS_ONLN);
-
-  *cpu_infos = (uv_cpu_info_t*)uv__malloc(numcpus * sizeof(uv_cpu_info_t));
-  if (!*cpu_infos) {
-    return UV_ENOMEM;
-  }
-
-  cpu_info = *cpu_infos;
-  for (idx = 0; idx < numcpus; idx++) {
-    cpu_info->speed = 0;
-    cpu_info->model = uv__strdup("unknown");
-    cpu_info->cpu_times.user = 0;
-    cpu_info->cpu_times.sys = 0;
-    cpu_info->cpu_times.idle = 0;
-    cpu_info->cpu_times.irq = 0;
-    cpu_info->cpu_times.nice = 0;
-    cpu_info++;
-  }
-  *count = numcpus;
-
-  return 0;
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/internal.h b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/internal.h
deleted file mode 100644
index 13ca2e6..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/internal.h
+++ /dev/null
@@ -1,329 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#ifndef UV_UNIX_INTERNAL_H_
-#define UV_UNIX_INTERNAL_H_
-
-#include "uv-common.h"
-
-#include <assert.h>
-#include <limits.h> /* _POSIX_PATH_MAX, PATH_MAX */
-#include <stdlib.h> /* abort */
-#include <string.h> /* strrchr */
-#include <fcntl.h>  /* O_CLOEXEC, may be */
-#include <stdio.h>
-#include <errno.h>
-
-#if defined(__STRICT_ANSI__)
-# define inline __inline
-#endif
-
-#if defined(__linux__)
-# include "linux-syscalls.h"
-#endif /* __linux__ */
-
-#if defined(__MVS__)
-# include "os390-syscalls.h"
-#endif /* __MVS__ */
-
-#if defined(__sun)
-# include <sys/port.h>
-# include <port.h>
-#endif /* __sun */
-
-#if defined(_AIX)
-# define reqevents events
-# define rtnevents revents
-# include <sys/poll.h>
-#else
-# include <poll.h>
-#endif /* _AIX */
-
-#if defined(__APPLE__) && !TARGET_OS_IPHONE
-# include <AvailabilityMacros.h>
-#endif
-
-#if defined(_POSIX_PATH_MAX)
-# define UV__PATH_MAX _POSIX_PATH_MAX
-#elif defined(PATH_MAX)
-# define UV__PATH_MAX PATH_MAX
-#else
-# define UV__PATH_MAX 8192
-#endif
-
-#if defined(__ANDROID__)
-int uv__pthread_sigmask(int how, const sigset_t* set, sigset_t* oset);
-# ifdef pthread_sigmask
-# undef pthread_sigmask
-# endif
-# define pthread_sigmask(how, set, oldset) uv__pthread_sigmask(how, set, oldset)
-#endif
-
-#define ACCESS_ONCE(type, var)                                                \
-  (*(volatile type*) &(var))
-
-#define ROUND_UP(a, b)                                                        \
-  ((a) % (b) ? ((a) + (b)) - ((a) % (b)) : (a))
-
-#define UNREACHABLE()                                                         \
-  do {                                                                        \
-    assert(0 && "unreachable code");                                          \
-    abort();                                                                  \
-  }                                                                           \
-  while (0)
-
-#define SAVE_ERRNO(block)                                                     \
-  do {                                                                        \
-    int _saved_errno = errno;                                                 \
-    do { block; } while (0);                                                  \
-    errno = _saved_errno;                                                     \
-  }                                                                           \
-  while (0)
-
-/* The __clang__ and __INTEL_COMPILER checks are superfluous because they
- * define __GNUC__. They are here to convey to you, dear reader, that these
- * macros are enabled when compiling with clang or icc.
- */
-#if defined(__clang__) ||                                                     \
-    defined(__GNUC__) ||                                                      \
-    defined(__INTEL_COMPILER)
-# define UV_DESTRUCTOR(declaration) __attribute__((destructor)) declaration
-# define UV_UNUSED(declaration)     __attribute__((unused)) declaration
-#else
-# define UV_DESTRUCTOR(declaration) declaration
-# define UV_UNUSED(declaration)     declaration
-#endif
-
-/* Leans on the fact that, on Linux, POLLRDHUP == EPOLLRDHUP. */
-#ifdef POLLRDHUP
-# define UV__POLLRDHUP POLLRDHUP
-#else
-# define UV__POLLRDHUP 0x2000
-#endif
-
-#ifdef POLLPRI
-# define UV__POLLPRI POLLPRI
-#else
-# define UV__POLLPRI 0
-#endif
-
-#if !defined(O_CLOEXEC) && defined(__FreeBSD__)
-/*
- * It may be that we are just missing `__POSIX_VISIBLE >= 200809`.
- * Try using fixed value const and give up, if it doesn't work
- */
-# define O_CLOEXEC 0x00100000
-#endif
-
-typedef struct uv__stream_queued_fds_s uv__stream_queued_fds_t;
-
-/* loop flags */
-enum {
-  UV_LOOP_BLOCK_SIGPROF = 1
-};
-
-/* flags of excluding ifaddr */
-enum {
-  UV__EXCLUDE_IFPHYS,
-  UV__EXCLUDE_IFADDR
-};
-
-typedef enum {
-  UV_CLOCK_PRECISE = 0,  /* Use the highest resolution clock available. */
-  UV_CLOCK_FAST = 1      /* Use the fastest clock with <= 1ms granularity. */
-} uv_clocktype_t;
-
-struct uv__stream_queued_fds_s {
-  unsigned int size;
-  unsigned int offset;
-  int fds[1];
-};
-
-
-#if defined(_AIX) || \
-    defined(__APPLE__) || \
-    defined(__DragonFly__) || \
-    defined(__FreeBSD__) || \
-    defined(__FreeBSD_kernel__) || \
-    defined(__linux__) || \
-    defined(__OpenBSD__) || \
-    defined(__NetBSD__)
-#define uv__cloexec uv__cloexec_ioctl
-#define uv__nonblock uv__nonblock_ioctl
-#define UV__NONBLOCK_IS_IOCTL
-#else
-#define uv__cloexec uv__cloexec_fcntl
-#define uv__nonblock uv__nonblock_fcntl
-#define UV__NONBLOCK_IS_FCNTL
-#endif
-
-/* On Linux, uv__nonblock_fcntl() and uv__nonblock_ioctl() do not commute
- * when O_NDELAY is not equal to O_NONBLOCK.  Case in point: linux/sparc32
- * and linux/sparc64, where O_NDELAY is O_NONBLOCK + another bit.
- *
- * Libuv uses uv__nonblock_fcntl() directly sometimes so ensure that it
- * commutes with uv__nonblock().
- */
-#if defined(__linux__) && O_NDELAY != O_NONBLOCK
-#undef uv__nonblock
-#define uv__nonblock uv__nonblock_fcntl
-#undef UV__NONBLOCK_IS_IOCTL
-#define UV__NONBLOCK_IS_FCNTL
-#endif
-
-/* core */
-int uv__cloexec_ioctl(int fd, int set);
-int uv__cloexec_fcntl(int fd, int set);
-int uv__nonblock_ioctl(int fd, int set);
-int uv__nonblock_fcntl(int fd, int set);
-int uv__close(int fd); /* preserves errno */
-int uv__close_nocheckstdio(int fd);
-int uv__close_nocancel(int fd);
-int uv__socket(int domain, int type, int protocol);
-ssize_t uv__recvmsg(int fd, struct msghdr *msg, int flags);
-void uv__make_close_pending(uv_handle_t* handle);
-int uv__getiovmax(void);
-
-void uv__io_init(uv__io_t* w, uv__io_cb cb, int fd);
-void uv__io_start(uv_loop_t* loop, uv__io_t* w, unsigned int events);
-void uv__io_stop(uv_loop_t* loop, uv__io_t* w, unsigned int events);
-void uv__io_close(uv_loop_t* loop, uv__io_t* w);
-void uv__io_feed(uv_loop_t* loop, uv__io_t* w);
-int uv__io_active(const uv__io_t* w, unsigned int events);
-int uv__io_check_fd(uv_loop_t* loop, int fd);
-void uv__io_poll(uv_loop_t* loop, int timeout); /* in milliseconds or -1 */
-int uv__io_fork(uv_loop_t* loop);
-int uv__fd_exists(uv_loop_t* loop, int fd);
-
-/* async */
-void uv__async_stop(uv_loop_t* loop);
-int uv__async_fork(uv_loop_t* loop);
-
-
-/* loop */
-void uv__run_idle(uv_loop_t* loop);
-void uv__run_check(uv_loop_t* loop);
-void uv__run_prepare(uv_loop_t* loop);
-
-/* stream */
-void uv__stream_init(uv_loop_t* loop, uv_stream_t* stream,
-    uv_handle_type type);
-int uv__stream_open(uv_stream_t*, int fd, int flags);
-void uv__stream_destroy(uv_stream_t* stream);
-#if defined(__APPLE__)
-int uv__stream_try_select(uv_stream_t* stream, int* fd);
-#endif /* defined(__APPLE__) */
-void uv__server_io(uv_loop_t* loop, uv__io_t* w, unsigned int events);
-int uv__accept(int sockfd);
-int uv__dup2_cloexec(int oldfd, int newfd);
-int uv__open_cloexec(const char* path, int flags);
-
-/* tcp */
-int uv_tcp_listen(uv_tcp_t* tcp, int backlog, uv_connection_cb cb);
-int uv__tcp_nodelay(int fd, int on);
-int uv__tcp_keepalive(int fd, int on, unsigned int delay);
-
-/* pipe */
-int uv_pipe_listen(uv_pipe_t* handle, int backlog, uv_connection_cb cb);
-
-/* signal */
-void uv__signal_close(uv_signal_t* handle);
-void uv__signal_global_once_init(void);
-void uv__signal_loop_cleanup(uv_loop_t* loop);
-int uv__signal_loop_fork(uv_loop_t* loop);
-
-/* platform specific */
-uint64_t uv__hrtime(uv_clocktype_t type);
-int uv__kqueue_init(uv_loop_t* loop);
-int uv__platform_loop_init(uv_loop_t* loop);
-void uv__platform_loop_delete(uv_loop_t* loop);
-void uv__platform_invalidate_fd(uv_loop_t* loop, int fd);
-
-/* various */
-void uv__async_close(uv_async_t* handle);
-void uv__check_close(uv_check_t* handle);
-void uv__fs_event_close(uv_fs_event_t* handle);
-void uv__idle_close(uv_idle_t* handle);
-void uv__pipe_close(uv_pipe_t* handle);
-void uv__poll_close(uv_poll_t* handle);
-void uv__prepare_close(uv_prepare_t* handle);
-void uv__process_close(uv_process_t* handle);
-void uv__stream_close(uv_stream_t* handle);
-void uv__tcp_close(uv_tcp_t* handle);
-void uv__udp_close(uv_udp_t* handle);
-void uv__udp_finish_close(uv_udp_t* handle);
-uv_handle_type uv__handle_type(int fd);
-FILE* uv__open_file(const char* path);
-int uv__getpwuid_r(uv_passwd_t* pwd);
-
-
-#if defined(__APPLE__)
-int uv___stream_fd(const uv_stream_t* handle);
-#define uv__stream_fd(handle) (uv___stream_fd((const uv_stream_t*) (handle)))
-#else
-#define uv__stream_fd(handle) ((handle)->io_watcher.fd)
-#endif /* defined(__APPLE__) */
-
-#ifdef UV__O_NONBLOCK
-# define UV__F_NONBLOCK UV__O_NONBLOCK
-#else
-# define UV__F_NONBLOCK 1
-#endif
-
-int uv__make_socketpair(int fds[2], int flags);
-int uv__make_pipe(int fds[2], int flags);
-
-#if defined(__APPLE__)
-
-int uv__fsevents_init(uv_fs_event_t* handle);
-int uv__fsevents_close(uv_fs_event_t* handle);
-void uv__fsevents_loop_delete(uv_loop_t* loop);
-
-#endif /* defined(__APPLE__) */
-
-UV_UNUSED(static void uv__update_time(uv_loop_t* loop)) {
-  /* Use a fast time source if available.  We only need millisecond precision.
-   */
-  loop->time = uv__hrtime(UV_CLOCK_FAST) / 1000000;
-}
-
-UV_UNUSED(static const char* uv__basename_r(const char* path)) {
-  const char* s;
-
-  s = strrchr(path, '/');
-  if (s == NULL)
-    return (char*) path;
-
-  return s + 1;
-}
-
-#if defined(__linux__)
-int uv__inotify_fork(uv_loop_t* loop, void* old_watchers);
-#endif
-
-typedef int (*uv__peersockfunc)(int, struct sockaddr*, socklen_t*);
-
-int uv__getsockpeername(const uv_handle_t* handle,
-                        uv__peersockfunc func,
-                        struct sockaddr* name,
-                        int* namelen);
-
-#endif /* UV_UNIX_INTERNAL_H_ */
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/kqueue.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/kqueue.cpp
deleted file mode 100644
index 4c4268b..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/kqueue.cpp
+++ /dev/null
@@ -1,536 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include "uv.h"
-#include "internal.h"
-
-#include <assert.h>
-#include <stdlib.h>
-#include <string.h>
-#include <errno.h>
-
-#include <sys/sysctl.h>
-#include <sys/types.h>
-#include <sys/event.h>
-#include <sys/time.h>
-#include <unistd.h>
-#include <fcntl.h>
-#include <time.h>
-
-/*
- * Required on
- * - Until at least FreeBSD 11.0
- * - Older versions of Mac OS X
- *
- * http://www.boost.org/doc/libs/1_61_0/boost/asio/detail/kqueue_reactor.hpp
- */
-#ifndef EV_OOBAND
-#define EV_OOBAND  EV_FLAG1
-#endif
-
-static void uv__fs_event(uv_loop_t* loop, uv__io_t* w, unsigned int fflags);
-
-
-int uv__kqueue_init(uv_loop_t* loop) {
-  loop->backend_fd = kqueue();
-  if (loop->backend_fd == -1)
-    return UV__ERR(errno);
-
-  uv__cloexec(loop->backend_fd, 1);
-
-  return 0;
-}
-
-
-#if defined(__APPLE__) && MAC_OS_X_VERSION_MAX_ALLOWED >= 1070
-static int uv__has_forked_with_cfrunloop;
-#endif
-
-int uv__io_fork(uv_loop_t* loop) {
-  int err;
-  loop->backend_fd = -1;
-  err = uv__kqueue_init(loop);
-  if (err)
-    return err;
-
-#if defined(__APPLE__) && MAC_OS_X_VERSION_MAX_ALLOWED >= 1070
-  if (loop->cf_state != NULL) {
-    /* We cannot start another CFRunloop and/or thread in the child
-       process; CF aborts if you try or if you try to touch the thread
-       at all to kill it. So the best we can do is ignore it from now
-       on. This means we can't watch directories in the same way
-       anymore (like other BSDs). It also means we cannot properly
-       clean up the allocated resources; calling
-       uv__fsevents_loop_delete from uv_loop_close will crash the
-       process. So we sidestep the issue by pretending like we never
-       started it in the first place.
-    */
-    uv__has_forked_with_cfrunloop = 1;
-    uv__free(loop->cf_state);
-    loop->cf_state = NULL;
-  }
-#endif /* #if defined(__APPLE__) && MAC_OS_X_VERSION_MAX_ALLOWED >= 1070 */
-  return err;
-}
-
-
-int uv__io_check_fd(uv_loop_t* loop, int fd) {
-  struct kevent ev;
-  int rc;
-
-  rc = 0;
-  EV_SET(&ev, fd, EVFILT_READ, EV_ADD, 0, 0, 0);
-  if (kevent(loop->backend_fd, &ev, 1, NULL, 0, NULL))
-    rc = UV__ERR(errno);
-
-  EV_SET(&ev, fd, EVFILT_READ, EV_DELETE, 0, 0, 0);
-  if (rc == 0)
-    if (kevent(loop->backend_fd, &ev, 1, NULL, 0, NULL))
-      abort();
-
-  return rc;
-}
-
-
-void uv__io_poll(uv_loop_t* loop, int timeout) {
-  struct kevent events[1024];
-  struct kevent* ev;
-  struct timespec spec;
-  unsigned int nevents;
-  unsigned int revents;
-  QUEUE* q;
-  uv__io_t* w;
-  sigset_t* pset;
-  sigset_t set;
-  uint64_t base;
-  uint64_t diff;
-  int have_signals;
-  int filter;
-  int fflags;
-  int count;
-  int nfds;
-  int fd;
-  int op;
-  int i;
-
-  if (loop->nfds == 0) {
-    assert(QUEUE_EMPTY(&loop->watcher_queue));
-    return;
-  }
-
-  nevents = 0;
-
-  while (!QUEUE_EMPTY(&loop->watcher_queue)) {
-    q = QUEUE_HEAD(&loop->watcher_queue);
-    QUEUE_REMOVE(q);
-    QUEUE_INIT(q);
-
-    w = QUEUE_DATA(q, uv__io_t, watcher_queue);
-    assert(w->pevents != 0);
-    assert(w->fd >= 0);
-    assert(w->fd < (int) loop->nwatchers);
-
-    if ((w->events & POLLIN) == 0 && (w->pevents & POLLIN) != 0) {
-      filter = EVFILT_READ;
-      fflags = 0;
-      op = EV_ADD;
-
-      if (w->cb == uv__fs_event) {
-        filter = EVFILT_VNODE;
-        fflags = NOTE_ATTRIB | NOTE_WRITE  | NOTE_RENAME
-               | NOTE_DELETE | NOTE_EXTEND | NOTE_REVOKE;
-        op = EV_ADD | EV_ONESHOT; /* Stop the event from firing repeatedly. */
-      }
-
-      EV_SET(events + nevents, w->fd, filter, op, fflags, 0, 0);
-
-      if (++nevents == ARRAY_SIZE(events)) {
-        if (kevent(loop->backend_fd, events, nevents, NULL, 0, NULL))
-          abort();
-        nevents = 0;
-      }
-    }
-
-    if ((w->events & POLLOUT) == 0 && (w->pevents & POLLOUT) != 0) {
-      EV_SET(events + nevents, w->fd, EVFILT_WRITE, EV_ADD, 0, 0, 0);
-
-      if (++nevents == ARRAY_SIZE(events)) {
-        if (kevent(loop->backend_fd, events, nevents, NULL, 0, NULL))
-          abort();
-        nevents = 0;
-      }
-    }
-
-   if ((w->events & UV__POLLPRI) == 0 && (w->pevents & UV__POLLPRI) != 0) {
-      EV_SET(events + nevents, w->fd, EV_OOBAND, EV_ADD, 0, 0, 0);
-
-      if (++nevents == ARRAY_SIZE(events)) {
-        if (kevent(loop->backend_fd, events, nevents, NULL, 0, NULL))
-          abort();
-        nevents = 0;
-      }
-    }
-
-    w->events = w->pevents;
-  }
-
-  pset = NULL;
-  if (loop->flags & UV_LOOP_BLOCK_SIGPROF) {
-    pset = &set;
-    sigemptyset(pset);
-    sigaddset(pset, SIGPROF);
-  }
-
-  assert(timeout >= -1);
-  base = loop->time;
-  count = 48; /* Benchmarks suggest this gives the best throughput. */
-
-  for (;; nevents = 0) {
-    if (timeout != -1) {
-      spec.tv_sec = timeout / 1000;
-      spec.tv_nsec = (timeout % 1000) * 1000000;
-    }
-
-    if (pset != NULL)
-      pthread_sigmask(SIG_BLOCK, pset, NULL);
-
-    nfds = kevent(loop->backend_fd,
-                  events,
-                  nevents,
-                  events,
-                  ARRAY_SIZE(events),
-                  timeout == -1 ? NULL : &spec);
-
-    if (pset != NULL)
-      pthread_sigmask(SIG_UNBLOCK, pset, NULL);
-
-    /* Update loop->time unconditionally. It's tempting to skip the update when
-     * timeout == 0 (i.e. non-blocking poll) but there is no guarantee that the
-     * operating system didn't reschedule our process while in the syscall.
-     */
-    SAVE_ERRNO(uv__update_time(loop));
-
-    if (nfds == 0) {
-      assert(timeout != -1);
-      return;
-    }
-
-    if (nfds == -1) {
-      if (errno != EINTR)
-        abort();
-
-      if (timeout == 0)
-        return;
-
-      if (timeout == -1)
-        continue;
-
-      /* Interrupted by a signal. Update timeout and poll again. */
-      goto update_timeout;
-    }
-
-    have_signals = 0;
-    nevents = 0;
-
-    assert(loop->watchers != NULL);
-    loop->watchers[loop->nwatchers] = (uv__io_t*) events;
-    loop->watchers[loop->nwatchers + 1] = (uv__io_t*) (uintptr_t) nfds;
-    for (i = 0; i < nfds; i++) {
-      ev = events + i;
-      fd = ev->ident;
-      /* Skip invalidated events, see uv__platform_invalidate_fd */
-      if (fd == -1)
-        continue;
-      w = (uv__io_t*)loop->watchers[fd];
-
-      if (w == NULL) {
-        /* File descriptor that we've stopped watching, disarm it.
-         * TODO: batch up. */
-        struct kevent events[1];
-
-        EV_SET(events + 0, fd, ev->filter, EV_DELETE, 0, 0, 0);
-        if (kevent(loop->backend_fd, events, 1, NULL, 0, NULL))
-          if (errno != EBADF && errno != ENOENT)
-            abort();
-
-        continue;
-      }
-
-      if (ev->filter == EVFILT_VNODE) {
-        assert(w->events == POLLIN);
-        assert(w->pevents == POLLIN);
-        w->cb(loop, w, ev->fflags); /* XXX always uv__fs_event() */
-        nevents++;
-        continue;
-      }
-
-      revents = 0;
-
-      if (ev->filter == EVFILT_READ) {
-        if (w->pevents & POLLIN) {
-          revents |= POLLIN;
-          w->rcount = ev->data;
-        } else {
-          /* TODO batch up */
-          struct kevent events[1];
-          EV_SET(events + 0, fd, ev->filter, EV_DELETE, 0, 0, 0);
-          if (kevent(loop->backend_fd, events, 1, NULL, 0, NULL))
-            if (errno != ENOENT)
-              abort();
-        }
-      }
-
-      if (ev->filter == EV_OOBAND) {
-        if (w->pevents & UV__POLLPRI) {
-          revents |= UV__POLLPRI;
-          w->rcount = ev->data;
-        } else {
-          /* TODO batch up */
-          struct kevent events[1];
-          EV_SET(events + 0, fd, ev->filter, EV_DELETE, 0, 0, 0);
-          if (kevent(loop->backend_fd, events, 1, NULL, 0, NULL))
-            if (errno != ENOENT)
-              abort();
-        }
-      }
-
-      if (ev->filter == EVFILT_WRITE) {
-        if (w->pevents & POLLOUT) {
-          revents |= POLLOUT;
-          w->wcount = ev->data;
-        } else {
-          /* TODO batch up */
-          struct kevent events[1];
-          EV_SET(events + 0, fd, ev->filter, EV_DELETE, 0, 0, 0);
-          if (kevent(loop->backend_fd, events, 1, NULL, 0, NULL))
-            if (errno != ENOENT)
-              abort();
-        }
-      }
-
-      if (ev->flags & EV_ERROR)
-        revents |= POLLERR;
-
-      if ((ev->flags & EV_EOF) && (w->pevents & UV__POLLRDHUP))
-        revents |= UV__POLLRDHUP;
-
-      if (revents == 0)
-        continue;
-
-      /* Run signal watchers last.  This also affects child process watchers
-       * because those are implemented in terms of signal watchers.
-       */
-      if (w == &loop->signal_io_watcher)
-        have_signals = 1;
-      else
-        w->cb(loop, w, revents);
-
-      nevents++;
-    }
-
-    if (have_signals != 0)
-      loop->signal_io_watcher.cb(loop, &loop->signal_io_watcher, POLLIN);
-
-    loop->watchers[loop->nwatchers] = NULL;
-    loop->watchers[loop->nwatchers + 1] = NULL;
-
-    if (have_signals != 0)
-      return;  /* Event loop should cycle now so don't poll again. */
-
-    if (nevents != 0) {
-      if (nfds == ARRAY_SIZE(events) && --count != 0) {
-        /* Poll for more events but don't block this time. */
-        timeout = 0;
-        continue;
-      }
-      return;
-    }
-
-    if (timeout == 0)
-      return;
-
-    if (timeout == -1)
-      continue;
-
-update_timeout:
-    assert(timeout > 0);
-
-    diff = loop->time - base;
-    if (diff >= (uint64_t) timeout)
-      return;
-
-    timeout -= diff;
-  }
-}
-
-
-void uv__platform_invalidate_fd(uv_loop_t* loop, int fd) {
-  struct kevent* events;
-  uintptr_t i;
-  uintptr_t nfds;
-
-  assert(loop->watchers != NULL);
-  assert(fd >= 0);
-
-  events = (struct kevent*) loop->watchers[loop->nwatchers];
-  nfds = (uintptr_t) loop->watchers[loop->nwatchers + 1];
-  if (events == NULL)
-    return;
-
-  /* Invalidate events with same file descriptor */
-  for (i = 0; i < nfds; i++)
-    if ((int) events[i].ident == fd)
-      events[i].ident = -1;
-}
-
-
-static void uv__fs_event(uv_loop_t* loop, uv__io_t* w, unsigned int fflags) {
-  uv_fs_event_t* handle;
-  struct kevent ev;
-  int events;
-  const char* path;
-#if defined(F_GETPATH)
-  /* MAXPATHLEN == PATH_MAX but the former is what XNU calls it internally. */
-  char pathbuf[MAXPATHLEN];
-#endif
-
-  handle = container_of(w, uv_fs_event_t, event_watcher);
-
-  if (fflags & (NOTE_ATTRIB | NOTE_EXTEND))
-    events = UV_CHANGE;
-  else
-    events = UV_RENAME;
-
-  path = NULL;
-#if defined(F_GETPATH)
-  /* Also works when the file has been unlinked from the file system. Passing
-   * in the path when the file has been deleted is arguably a little strange
-   * but it's consistent with what the inotify backend does.
-   */
-  if (fcntl(handle->event_watcher.fd, F_GETPATH, pathbuf) == 0)
-    path = uv__basename_r(pathbuf);
-#endif
-  handle->cb(handle, path, events, 0);
-
-  if (handle->event_watcher.fd == -1)
-    return;
-
-  /* Watcher operates in one-shot mode, re-arm it. */
-  fflags = NOTE_ATTRIB | NOTE_WRITE  | NOTE_RENAME
-         | NOTE_DELETE | NOTE_EXTEND | NOTE_REVOKE;
-
-  EV_SET(&ev, w->fd, EVFILT_VNODE, EV_ADD | EV_ONESHOT, fflags, 0, 0);
-
-  if (kevent(loop->backend_fd, &ev, 1, NULL, 0, NULL))
-    abort();
-}
-
-
-int uv_fs_event_init(uv_loop_t* loop, uv_fs_event_t* handle) {
-  uv__handle_init(loop, (uv_handle_t*)handle, UV_FS_EVENT);
-  return 0;
-}
-
-
-int uv_fs_event_start(uv_fs_event_t* handle,
-                      uv_fs_event_cb cb,
-                      const char* path,
-                      unsigned int flags) {
-  int fd;
-
-  if (uv__is_active(handle))
-    return UV_EINVAL;
-
-#if defined(__APPLE__) && MAC_OS_X_VERSION_MAX_ALLOWED >= 1070
-  /* Nullify field to perform checks later */
-  handle->cf_cb = NULL;
-  handle->realpath = NULL;
-  handle->realpath_len = 0;
-  handle->cf_flags = flags;
-
-  if (!uv__has_forked_with_cfrunloop) {
-    int r;
-    /* The fallback fd is not used */
-    handle->event_watcher.fd = -1;
-    handle->path = uv__strdup(path);
-    if (handle->path == NULL)
-      return UV_ENOMEM;
-    handle->cb = cb;
-    r = uv__fsevents_init(handle);
-    if (r == 0) {
-      uv__handle_start(handle);
-    } else {
-      uv__free(handle->path);
-      handle->path = NULL;
-    }
-    return r;
-  }
-#endif /* #if defined(__APPLE__) && MAC_OS_X_VERSION_MAX_ALLOWED >= 1070 */
-
-  /* TODO open asynchronously - but how do we report back errors? */
-  fd = open(path, O_RDONLY);
-  if (fd == -1)
-    return UV__ERR(errno);
-
-  handle->path = uv__strdup(path);
-  if (handle->path == NULL) {
-    uv__close_nocheckstdio(fd);
-    return UV_ENOMEM;
-  }
-
-  handle->cb = cb;
-  uv__handle_start(handle);
-  uv__io_init(&handle->event_watcher, uv__fs_event, fd);
-  uv__io_start(handle->loop, &handle->event_watcher, POLLIN);
-
-  return 0;
-}
-
-
-int uv_fs_event_stop(uv_fs_event_t* handle) {
-  int r;
-  r = 0;
-
-  if (!uv__is_active(handle))
-    return 0;
-
-  uv__handle_stop(handle);
-
-#if defined(__APPLE__) && MAC_OS_X_VERSION_MAX_ALLOWED >= 1070
-  if (!uv__has_forked_with_cfrunloop)
-    r = uv__fsevents_close(handle);
-#endif
-
-  if (handle->event_watcher.fd != -1) {
-    uv__io_close(handle->loop, &handle->event_watcher);
-    uv__close(handle->event_watcher.fd);
-    handle->event_watcher.fd = -1;
-  }
-
-  uv__free(handle->path);
-  handle->path = NULL;
-
-  return r;
-}
-
-
-void uv__fs_event_close(uv_fs_event_t* handle) {
-  uv_fs_event_stop(handle);
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/linux-core.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/linux-core.cpp
deleted file mode 100644
index 8a26782..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/linux-core.cpp
+++ /dev/null
@@ -1,1062 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-/* We lean on the fact that POLL{IN,OUT,ERR,HUP} correspond with their
- * EPOLL* counterparts.  We use the POLL* variants in this file because that
- * is what libuv uses elsewhere.
- */
-
-#include "uv.h"
-#include "internal.h"
-
-#include <inttypes.h>
-#include <stdint.h>
-#include <stdio.h>
-#include <stdlib.h>
-#include <string.h>
-#include <assert.h>
-#include <errno.h>
-
-#include <net/if.h>
-#include <sys/epoll.h>
-#include <sys/param.h>
-#include <sys/prctl.h>
-#include <sys/sysinfo.h>
-#include <unistd.h>
-#include <fcntl.h>
-#include <time.h>
-
-#define HAVE_IFADDRS_H 1
-
-#ifdef __UCLIBC__
-# if __UCLIBC_MAJOR__ < 0 && __UCLIBC_MINOR__ < 9 && __UCLIBC_SUBLEVEL__ < 32
-#  undef HAVE_IFADDRS_H
-# endif
-#endif
-
-#ifdef HAVE_IFADDRS_H
-# if defined(__ANDROID__)
-#  include "uv/android-ifaddrs.h"
-# else
-#  include <ifaddrs.h>
-# endif
-# include <sys/socket.h>
-# include <net/ethernet.h>
-# include <netpacket/packet.h>
-#endif /* HAVE_IFADDRS_H */
-
-/* Available from 2.6.32 onwards. */
-#ifndef CLOCK_MONOTONIC_COARSE
-# define CLOCK_MONOTONIC_COARSE 6
-#endif
-
-#ifdef __FRC_ROBORIO__
-#include "wpi/timestamp.h"
-#endif
-
-/* This is rather annoying: CLOCK_BOOTTIME lives in <linux/time.h> but we can't
- * include that file because it conflicts with <time.h>. We'll just have to
- * define it ourselves.
- */
-#ifndef CLOCK_BOOTTIME
-# define CLOCK_BOOTTIME 7
-#endif
-
-static int read_models(unsigned int numcpus, uv_cpu_info_t* ci);
-static int read_times(FILE* statfile_fp,
-                      unsigned int numcpus,
-                      uv_cpu_info_t* ci);
-static void read_speeds(unsigned int numcpus, uv_cpu_info_t* ci);
-static uint64_t read_cpufreq(unsigned int cpunum);
-
-
-int uv__platform_loop_init(uv_loop_t* loop) {
-  int fd;
-
-  /* It was reported that EPOLL_CLOEXEC is not defined on Android API < 21,
-   * a.k.a. Lollipop. Since EPOLL_CLOEXEC is an alias for O_CLOEXEC on all
-   * architectures, we just use that instead.
-   */
-  fd = epoll_create1(O_CLOEXEC);
-
-  /* epoll_create1() can fail either because it's not implemented (old kernel)
-   * or because it doesn't understand the O_CLOEXEC flag.
-   */
-  if (fd == -1 && (errno == ENOSYS || errno == EINVAL)) {
-    fd = epoll_create(256);
-
-    if (fd != -1)
-      uv__cloexec(fd, 1);
-  }
-
-  loop->backend_fd = fd;
-  loop->inotify_fd = -1;
-  loop->inotify_watchers = NULL;
-
-  if (fd == -1)
-    return UV__ERR(errno);
-
-  return 0;
-}
-
-
-int uv__io_fork(uv_loop_t* loop) {
-  int err;
-  void* old_watchers;
-
-  old_watchers = loop->inotify_watchers;
-
-  uv__close(loop->backend_fd);
-  loop->backend_fd = -1;
-  uv__platform_loop_delete(loop);
-
-  err = uv__platform_loop_init(loop);
-  if (err)
-    return err;
-
-  return uv__inotify_fork(loop, old_watchers);
-}
-
-
-void uv__platform_loop_delete(uv_loop_t* loop) {
-  if (loop->inotify_fd == -1) return;
-  uv__io_stop(loop, &loop->inotify_read_watcher, POLLIN);
-  uv__close(loop->inotify_fd);
-  loop->inotify_fd = -1;
-}
-
-
-void uv__platform_invalidate_fd(uv_loop_t* loop, int fd) {
-  struct epoll_event* events;
-  struct epoll_event dummy;
-  uintptr_t i;
-  uintptr_t nfds;
-
-  assert(loop->watchers != NULL);
-  assert(fd >= 0);
-
-  events = (struct epoll_event*) loop->watchers[loop->nwatchers];
-  nfds = (uintptr_t) loop->watchers[loop->nwatchers + 1];
-  if (events != NULL)
-    /* Invalidate events with same file descriptor */
-    for (i = 0; i < nfds; i++)
-      if (events[i].data.fd == fd)
-        events[i].data.fd = -1;
-
-  /* Remove the file descriptor from the epoll.
-   * This avoids a problem where the same file description remains open
-   * in another process, causing repeated junk epoll events.
-   *
-   * We pass in a dummy epoll_event, to work around a bug in old kernels.
-   */
-  if (loop->backend_fd >= 0) {
-    /* Work around a bug in kernels 3.10 to 3.19 where passing a struct that
-     * has the EPOLLWAKEUP flag set generates spurious audit syslog warnings.
-     */
-    memset(&dummy, 0, sizeof(dummy));
-    epoll_ctl(loop->backend_fd, EPOLL_CTL_DEL, fd, &dummy);
-  }
-}
-
-
-int uv__io_check_fd(uv_loop_t* loop, int fd) {
-  struct epoll_event e;
-  int rc;
-
-  memset(&e, 0, sizeof(e));
-  e.events = POLLIN;
-  e.data.fd = -1;
-
-  rc = 0;
-  if (epoll_ctl(loop->backend_fd, EPOLL_CTL_ADD, fd, &e))
-    if (errno != EEXIST)
-      rc = UV__ERR(errno);
-
-  if (rc == 0)
-    if (epoll_ctl(loop->backend_fd, EPOLL_CTL_DEL, fd, &e))
-      abort();
-
-  return rc;
-}
-
-
-void uv__io_poll(uv_loop_t* loop, int timeout) {
-  /* A bug in kernels < 2.6.37 makes timeouts larger than ~30 minutes
-   * effectively infinite on 32 bits architectures.  To avoid blocking
-   * indefinitely, we cap the timeout and poll again if necessary.
-   *
-   * Note that "30 minutes" is a simplification because it depends on
-   * the value of CONFIG_HZ.  The magic constant assumes CONFIG_HZ=1200,
-   * that being the largest value I have seen in the wild (and only once.)
-   */
-  static const int max_safe_timeout = 1789569;
-  struct epoll_event events[1024];
-  struct epoll_event* pe;
-  struct epoll_event e;
-  int real_timeout;
-  QUEUE* q;
-  uv__io_t* w;
-  sigset_t sigset;
-  sigset_t* psigset;
-  uint64_t base;
-  int have_signals;
-  int nevents;
-  int count;
-  int nfds;
-  int fd;
-  int op;
-  int i;
-
-  if (loop->nfds == 0) {
-    assert(QUEUE_EMPTY(&loop->watcher_queue));
-    return;
-  }
-
-  memset(&e, 0, sizeof(e));
-
-  while (!QUEUE_EMPTY(&loop->watcher_queue)) {
-    q = QUEUE_HEAD(&loop->watcher_queue);
-    QUEUE_REMOVE(q);
-    QUEUE_INIT(q);
-
-    w = QUEUE_DATA(q, uv__io_t, watcher_queue);
-    assert(w->pevents != 0);
-    assert(w->fd >= 0);
-    assert(w->fd < (int) loop->nwatchers);
-
-    e.events = w->pevents;
-    e.data.fd = w->fd;
-
-    if (w->events == 0)
-      op = EPOLL_CTL_ADD;
-    else
-      op = EPOLL_CTL_MOD;
-
-    /* XXX Future optimization: do EPOLL_CTL_MOD lazily if we stop watching
-     * events, skip the syscall and squelch the events after epoll_wait().
-     */
-    if (epoll_ctl(loop->backend_fd, op, w->fd, &e)) {
-      if (errno != EEXIST)
-        abort();
-
-      assert(op == EPOLL_CTL_ADD);
-
-      /* We've reactivated a file descriptor that's been watched before. */
-      if (epoll_ctl(loop->backend_fd, EPOLL_CTL_MOD, w->fd, &e))
-        abort();
-    }
-
-    w->events = w->pevents;
-  }
-
-  psigset = NULL;
-  if (loop->flags & UV_LOOP_BLOCK_SIGPROF) {
-    sigemptyset(&sigset);
-    sigaddset(&sigset, SIGPROF);
-    psigset = &sigset;
-  }
-
-  assert(timeout >= -1);
-  base = loop->time;
-  count = 48; /* Benchmarks suggest this gives the best throughput. */
-  real_timeout = timeout;
-
-  for (;;) {
-    /* See the comment for max_safe_timeout for an explanation of why
-     * this is necessary.  Executive summary: kernel bug workaround.
-     */
-    if (sizeof(int32_t) == sizeof(long) && timeout >= max_safe_timeout)
-      timeout = max_safe_timeout;
-
-    nfds = epoll_pwait(loop->backend_fd,
-                       events,
-                       ARRAY_SIZE(events),
-                       timeout,
-                       psigset);
-
-    /* Update loop->time unconditionally. It's tempting to skip the update when
-     * timeout == 0 (i.e. non-blocking poll) but there is no guarantee that the
-     * operating system didn't reschedule our process while in the syscall.
-     */
-    SAVE_ERRNO(uv__update_time(loop));
-
-    if (nfds == 0) {
-      assert(timeout != -1);
-
-      if (timeout == 0)
-        return;
-
-      /* We may have been inside the system call for longer than |timeout|
-       * milliseconds so we need to update the timestamp to avoid drift.
-       */
-      goto update_timeout;
-    }
-
-    if (nfds == -1) {
-      if (errno != EINTR)
-        abort();
-
-      if (timeout == -1)
-        continue;
-
-      if (timeout == 0)
-        return;
-
-      /* Interrupted by a signal. Update timeout and poll again. */
-      goto update_timeout;
-    }
-
-    have_signals = 0;
-    nevents = 0;
-
-    assert(loop->watchers != NULL);
-    loop->watchers[loop->nwatchers] = events;
-    loop->watchers[loop->nwatchers + 1] = (void*) (uintptr_t) nfds;
-    for (i = 0; i < nfds; i++) {
-      pe = events + i;
-      fd = pe->data.fd;
-
-      /* Skip invalidated events, see uv__platform_invalidate_fd */
-      if (fd == -1)
-        continue;
-
-      assert(fd >= 0);
-      assert((unsigned) fd < loop->nwatchers);
-
-      w = (uv__io_t*)loop->watchers[fd];
-
-      if (w == NULL) {
-        /* File descriptor that we've stopped watching, disarm it.
-         *
-         * Ignore all errors because we may be racing with another thread
-         * when the file descriptor is closed.
-         */
-        epoll_ctl(loop->backend_fd, EPOLL_CTL_DEL, fd, pe);
-        continue;
-      }
-
-      /* Give users only events they're interested in. Prevents spurious
-       * callbacks when previous callback invocation in this loop has stopped
-       * the current watcher. Also, filters out events that users has not
-       * requested us to watch.
-       */
-      pe->events &= w->pevents | POLLERR | POLLHUP;
-
-      /* Work around an epoll quirk where it sometimes reports just the
-       * EPOLLERR or EPOLLHUP event.  In order to force the event loop to
-       * move forward, we merge in the read/write events that the watcher
-       * is interested in; uv__read() and uv__write() will then deal with
-       * the error or hangup in the usual fashion.
-       *
-       * Note to self: happens when epoll reports EPOLLIN|EPOLLHUP, the user
-       * reads the available data, calls uv_read_stop(), then sometime later
-       * calls uv_read_start() again.  By then, libuv has forgotten about the
-       * hangup and the kernel won't report EPOLLIN again because there's
-       * nothing left to read.  If anything, libuv is to blame here.  The
-       * current hack is just a quick bandaid; to properly fix it, libuv
-       * needs to remember the error/hangup event.  We should get that for
-       * free when we switch over to edge-triggered I/O.
-       */
-      if (pe->events == POLLERR || pe->events == POLLHUP)
-        pe->events |=
-          w->pevents & (POLLIN | POLLOUT | UV__POLLRDHUP | UV__POLLPRI);
-
-      if (pe->events != 0) {
-        /* Run signal watchers last.  This also affects child process watchers
-         * because those are implemented in terms of signal watchers.
-         */
-        if (w == &loop->signal_io_watcher)
-          have_signals = 1;
-        else
-          w->cb(loop, w, pe->events);
-
-        nevents++;
-      }
-    }
-
-    if (have_signals != 0)
-      loop->signal_io_watcher.cb(loop, &loop->signal_io_watcher, POLLIN);
-
-    loop->watchers[loop->nwatchers] = NULL;
-    loop->watchers[loop->nwatchers + 1] = NULL;
-
-    if (have_signals != 0)
-      return;  /* Event loop should cycle now so don't poll again. */
-
-    if (nevents != 0) {
-      if (nfds == ARRAY_SIZE(events) && --count != 0) {
-        /* Poll for more events but don't block this time. */
-        timeout = 0;
-        continue;
-      }
-      return;
-    }
-
-    if (timeout == 0)
-      return;
-
-    if (timeout == -1)
-      continue;
-
-update_timeout:
-    assert(timeout > 0);
-
-    real_timeout -= (loop->time - base);
-    if (real_timeout <= 0)
-      return;
-
-    timeout = real_timeout;
-  }
-}
-
-
-uint64_t uv__hrtime(uv_clocktype_t type) {
-#ifdef __FRC_ROBORIO__
-  return wpi::Now() * 1000u;
-#else
-  static clock_t fast_clock_id = -1;
-  struct timespec t;
-  clock_t clock_id;
-
-  /* Prefer CLOCK_MONOTONIC_COARSE if available but only when it has
-   * millisecond granularity or better.  CLOCK_MONOTONIC_COARSE is
-   * serviced entirely from the vDSO, whereas CLOCK_MONOTONIC may
-   * decide to make a costly system call.
-   */
-  /* TODO(bnoordhuis) Use CLOCK_MONOTONIC_COARSE for UV_CLOCK_PRECISE
-   * when it has microsecond granularity or better (unlikely).
-   */
-  if (type == UV_CLOCK_FAST && fast_clock_id == -1) {
-    if (clock_getres(CLOCK_MONOTONIC_COARSE, &t) == 0 &&
-        t.tv_nsec <= 1 * 1000 * 1000) {
-      fast_clock_id = CLOCK_MONOTONIC_COARSE;
-    } else {
-      fast_clock_id = CLOCK_MONOTONIC;
-    }
-  }
-
-  clock_id = CLOCK_MONOTONIC;
-  if (type == UV_CLOCK_FAST)
-    clock_id = fast_clock_id;
-
-  if (clock_gettime(clock_id, &t))
-    return 0;  /* Not really possible. */
-
-  return t.tv_sec * (uint64_t) 1e9 + t.tv_nsec;
-#endif
-}
-
-
-int uv_resident_set_memory(size_t* rss) {
-  char buf[1024];
-  const char* s;
-  ssize_t n;
-  long val;
-  int fd;
-  int i;
-
-  do
-    fd = open("/proc/self/stat", O_RDONLY);
-  while (fd == -1 && errno == EINTR);
-
-  if (fd == -1)
-    return UV__ERR(errno);
-
-  do
-    n = read(fd, buf, sizeof(buf) - 1);
-  while (n == -1 && errno == EINTR);
-
-  uv__close(fd);
-  if (n == -1)
-    return UV__ERR(errno);
-  buf[n] = '\0';
-
-  s = strchr(buf, ' ');
-  if (s == NULL)
-    goto err;
-
-  s += 1;
-  if (*s != '(')
-    goto err;
-
-  s = strchr(s, ')');
-  if (s == NULL)
-    goto err;
-
-  for (i = 1; i <= 22; i++) {
-    s = strchr(s + 1, ' ');
-    if (s == NULL)
-      goto err;
-  }
-
-  errno = 0;
-  val = strtol(s, NULL, 10);
-  if (errno != 0)
-    goto err;
-  if (val < 0)
-    goto err;
-
-  *rss = val * getpagesize();
-  return 0;
-
-err:
-  return UV_EINVAL;
-}
-
-
-int uv_uptime(double* uptime) {
-  static volatile int no_clock_boottime;
-  struct timespec now;
-  int r;
-
-  /* Try CLOCK_BOOTTIME first, fall back to CLOCK_MONOTONIC if not available
-   * (pre-2.6.39 kernels). CLOCK_MONOTONIC doesn't increase when the system
-   * is suspended.
-   */
-  if (no_clock_boottime) {
-    retry: r = clock_gettime(CLOCK_MONOTONIC, &now);
-  }
-  else if ((r = clock_gettime(CLOCK_BOOTTIME, &now)) && errno == EINVAL) {
-    no_clock_boottime = 1;
-    goto retry;
-  }
-
-  if (r)
-    return UV__ERR(errno);
-
-  *uptime = now.tv_sec;
-  return 0;
-}
-
-
-static int uv__cpu_num(FILE* statfile_fp, unsigned int* numcpus) {
-  unsigned int num;
-  char buf[1024];
-
-  if (!fgets(buf, sizeof(buf), statfile_fp))
-    return UV_EIO;
-
-  num = 0;
-  while (fgets(buf, sizeof(buf), statfile_fp)) {
-    if (strncmp(buf, "cpu", 3))
-      break;
-    num++;
-  }
-
-  if (num == 0)
-    return UV_EIO;
-
-  *numcpus = num;
-  return 0;
-}
-
-
-int uv_cpu_info(uv_cpu_info_t** cpu_infos, int* count) {
-  unsigned int numcpus;
-  uv_cpu_info_t* ci;
-  int err;
-  FILE* statfile_fp;
-
-  *cpu_infos = NULL;
-  *count = 0;
-
-  statfile_fp = uv__open_file("/proc/stat");
-  if (statfile_fp == NULL)
-    return UV__ERR(errno);
-
-  err = uv__cpu_num(statfile_fp, &numcpus);
-  if (err < 0)
-    goto out;
-
-  err = UV_ENOMEM;
-  ci = (uv_cpu_info_t*)uv__calloc(numcpus, sizeof(*ci));
-  if (ci == NULL)
-    goto out;
-
-  err = read_models(numcpus, ci);
-  if (err == 0)
-    err = read_times(statfile_fp, numcpus, ci);
-
-  if (err) {
-    uv_free_cpu_info(ci, numcpus);
-    goto out;
-  }
-
-  /* read_models() on x86 also reads the CPU speed from /proc/cpuinfo.
-   * We don't check for errors here. Worst case, the field is left zero.
-   */
-  if (ci[0].speed == 0)
-    read_speeds(numcpus, ci);
-
-  *cpu_infos = ci;
-  *count = numcpus;
-  err = 0;
-
-out:
-
-  if (fclose(statfile_fp))
-    if (errno != EINTR && errno != EINPROGRESS)
-      abort();
-
-  return err;
-}
-
-
-static void read_speeds(unsigned int numcpus, uv_cpu_info_t* ci) {
-  unsigned int num;
-
-  for (num = 0; num < numcpus; num++)
-    ci[num].speed = read_cpufreq(num) / 1000;
-}
-
-
-/* Also reads the CPU frequency on x86. The other architectures only have
- * a BogoMIPS field, which may not be very accurate.
- *
- * Note: Simply returns on error, uv_cpu_info() takes care of the cleanup.
- */
-static int read_models(unsigned int numcpus, uv_cpu_info_t* ci) {
-  static const char model_marker[] = "model name\t: ";
-  static const char speed_marker[] = "cpu MHz\t\t: ";
-  const char* inferred_model;
-  unsigned int model_idx;
-  unsigned int speed_idx;
-  char buf[1024];
-  char* model;
-  FILE* fp;
-
-  /* Most are unused on non-ARM, non-MIPS and non-x86 architectures. */
-  (void) &model_marker;
-  (void) &speed_marker;
-  (void) &speed_idx;
-  (void) &model;
-  (void) &buf;
-  (void) &fp;
-
-  model_idx = 0;
-  speed_idx = 0;
-
-#if defined(__arm__) || \
-    defined(__i386__) || \
-    defined(__mips__) || \
-    defined(__x86_64__)
-  fp = uv__open_file("/proc/cpuinfo");
-  if (fp == NULL)
-    return UV__ERR(errno);
-
-  while (fgets(buf, sizeof(buf), fp)) {
-    if (model_idx < numcpus) {
-      if (strncmp(buf, model_marker, sizeof(model_marker) - 1) == 0) {
-        model = buf + sizeof(model_marker) - 1;
-        model = uv__strndup(model, strlen(model) - 1);  /* Strip newline. */
-        if (model == NULL) {
-          fclose(fp);
-          return UV_ENOMEM;
-        }
-        ci[model_idx++].model = model;
-        continue;
-      }
-    }
-#if defined(__arm__) || defined(__mips__)
-    if (model_idx < numcpus) {
-#if defined(__arm__)
-      /* Fallback for pre-3.8 kernels. */
-      static const char model_marker[] = "Processor\t: ";
-#else	/* defined(__mips__) */
-      static const char model_marker[] = "cpu model\t\t: ";
-#endif
-      if (strncmp(buf, model_marker, sizeof(model_marker) - 1) == 0) {
-        model = buf + sizeof(model_marker) - 1;
-        model = uv__strndup(model, strlen(model) - 1);  /* Strip newline. */
-        if (model == NULL) {
-          fclose(fp);
-          return UV_ENOMEM;
-        }
-        ci[model_idx++].model = model;
-        continue;
-      }
-    }
-#else  /* !__arm__ && !__mips__ */
-    if (speed_idx < numcpus) {
-      if (strncmp(buf, speed_marker, sizeof(speed_marker) - 1) == 0) {
-        ci[speed_idx++].speed = atoi(buf + sizeof(speed_marker) - 1);
-        continue;
-      }
-    }
-#endif  /* __arm__ || __mips__ */
-  }
-
-  fclose(fp);
-#endif  /* __arm__ || __i386__ || __mips__ || __x86_64__ */
-
-  /* Now we want to make sure that all the models contain *something* because
-   * it's not safe to leave them as null. Copy the last entry unless there
-   * isn't one, in that case we simply put "unknown" into everything.
-   */
-  inferred_model = "unknown";
-  if (model_idx > 0)
-    inferred_model = ci[model_idx - 1].model;
-
-  while (model_idx < numcpus) {
-    model = uv__strndup(inferred_model, strlen(inferred_model));
-    if (model == NULL)
-      return UV_ENOMEM;
-    ci[model_idx++].model = model;
-  }
-
-  return 0;
-}
-
-
-static int read_times(FILE* statfile_fp,
-                      unsigned int numcpus,
-                      uv_cpu_info_t* ci) {
-  struct uv_cpu_times_s ts;
-  uint64_t clock_ticks;
-  uint64_t user;
-  uint64_t nice;
-  uint64_t sys;
-  uint64_t idle;
-  uint64_t dummy;
-  uint64_t irq;
-  uint64_t num;
-  uint64_t len;
-  char buf[1024];
-
-  clock_ticks = sysconf(_SC_CLK_TCK);
-  assert(clock_ticks != (uint64_t) -1);
-  assert(clock_ticks != 0);
-
-  rewind(statfile_fp);
-
-  if (!fgets(buf, sizeof(buf), statfile_fp))
-    abort();
-
-  num = 0;
-
-  while (fgets(buf, sizeof(buf), statfile_fp)) {
-    if (num >= numcpus)
-      break;
-
-    if (strncmp(buf, "cpu", 3))
-      break;
-
-    /* skip "cpu<num> " marker */
-    {
-      unsigned int n;
-      int r = sscanf(buf, "cpu%u ", &n);
-      assert(r == 1);
-      (void) r;  /* silence build warning */
-      for (len = sizeof("cpu0"); n /= 10; len++);
-    }
-
-    /* Line contains user, nice, system, idle, iowait, irq, softirq, steal,
-     * guest, guest_nice but we're only interested in the first four + irq.
-     *
-     * Don't use %*s to skip fields or %ll to read straight into the uint64_t
-     * fields, they're not allowed in C89 mode.
-     */
-    if (6 != sscanf(buf + len,
-                    "%" PRIu64 " %" PRIu64 " %" PRIu64
-                    "%" PRIu64 " %" PRIu64 " %" PRIu64,
-                    &user,
-                    &nice,
-                    &sys,
-                    &idle,
-                    &dummy,
-                    &irq))
-      abort();
-
-    ts.user = clock_ticks * user;
-    ts.nice = clock_ticks * nice;
-    ts.sys  = clock_ticks * sys;
-    ts.idle = clock_ticks * idle;
-    ts.irq  = clock_ticks * irq;
-    ci[num++].cpu_times = ts;
-  }
-  assert(num == numcpus);
-
-  return 0;
-}
-
-
-static uint64_t read_cpufreq(unsigned int cpunum) {
-  uint64_t val;
-  char buf[1024];
-  FILE* fp;
-
-  snprintf(buf,
-           sizeof(buf),
-           "/sys/devices/system/cpu/cpu%u/cpufreq/scaling_cur_freq",
-           cpunum);
-
-  fp = uv__open_file(buf);
-  if (fp == NULL)
-    return 0;
-
-  if (fscanf(fp, "%" PRIu64, &val) != 1)
-    val = 0;
-
-  fclose(fp);
-
-  return val;
-}
-
-
-void uv_free_cpu_info(uv_cpu_info_t* cpu_infos, int count) {
-  int i;
-
-  for (i = 0; i < count; i++) {
-    uv__free(cpu_infos[i].model);
-  }
-
-  uv__free(cpu_infos);
-}
-
-static int uv__ifaddr_exclude(struct ifaddrs *ent, int exclude_type) {
-  if (!((ent->ifa_flags & IFF_UP) && (ent->ifa_flags & IFF_RUNNING)))
-    return 1;
-  if (ent->ifa_addr == NULL)
-    return 1;
-  /*
-   * On Linux getifaddrs returns information related to the raw underlying
-   * devices. We're not interested in this information yet.
-   */
-  if (ent->ifa_addr->sa_family == PF_PACKET)
-    return exclude_type;
-  return !exclude_type;
-}
-
-int uv_interface_addresses(uv_interface_address_t** addresses, int* count) {
-#ifndef HAVE_IFADDRS_H
-  *count = 0;
-  *addresses = NULL;
-  return UV_ENOSYS;
-#else
-  struct ifaddrs *addrs, *ent;
-  uv_interface_address_t* address;
-  int i;
-  struct sockaddr_ll *sll;
-
-  *count = 0;
-  *addresses = NULL;
-
-  if (getifaddrs(&addrs))
-    return UV__ERR(errno);
-
-  /* Count the number of interfaces */
-  for (ent = addrs; ent != NULL; ent = ent->ifa_next) {
-    if (uv__ifaddr_exclude(ent, UV__EXCLUDE_IFADDR))
-      continue;
-
-    (*count)++;
-  }
-
-  if (*count == 0) {
-    freeifaddrs(addrs);
-    return 0;
-  }
-
-  /* Make sure the memory is initiallized to zero using calloc() */
-  *addresses = (uv_interface_address_t*)uv__calloc(*count, sizeof(**addresses));
-  if (!(*addresses)) {
-    freeifaddrs(addrs);
-    return UV_ENOMEM;
-  }
-
-  address = *addresses;
-
-  for (ent = addrs; ent != NULL; ent = ent->ifa_next) {
-    if (uv__ifaddr_exclude(ent, UV__EXCLUDE_IFADDR))
-      continue;
-
-    address->name = uv__strdup(ent->ifa_name);
-
-    if (ent->ifa_addr->sa_family == AF_INET6) {
-      address->address.address6 = *((struct sockaddr_in6*) ent->ifa_addr);
-    } else {
-      address->address.address4 = *((struct sockaddr_in*) ent->ifa_addr);
-    }
-
-    if (ent->ifa_netmask->sa_family == AF_INET6) {
-      address->netmask.netmask6 = *((struct sockaddr_in6*) ent->ifa_netmask);
-    } else {
-      address->netmask.netmask4 = *((struct sockaddr_in*) ent->ifa_netmask);
-    }
-
-    address->is_internal = !!(ent->ifa_flags & IFF_LOOPBACK);
-
-    address++;
-  }
-
-  /* Fill in physical addresses for each interface */
-  for (ent = addrs; ent != NULL; ent = ent->ifa_next) {
-    if (uv__ifaddr_exclude(ent, UV__EXCLUDE_IFPHYS))
-      continue;
-
-    address = *addresses;
-
-    for (i = 0; i < (*count); i++) {
-      size_t namelen = strlen(ent->ifa_name);
-      /* Alias interface share the same physical address */
-      if (strncmp(address->name, ent->ifa_name, namelen) == 0 &&
-          (address->name[namelen] == 0 || address->name[namelen] == ':')) {
-        sll = (struct sockaddr_ll*)ent->ifa_addr;
-        memcpy(address->phys_addr, sll->sll_addr, sizeof(address->phys_addr));
-      }
-      address++;
-    }
-  }
-
-  freeifaddrs(addrs);
-
-  return 0;
-#endif
-}
-
-
-void uv_free_interface_addresses(uv_interface_address_t* addresses,
-  int count) {
-  int i;
-
-  for (i = 0; i < count; i++) {
-    uv__free(addresses[i].name);
-  }
-
-  uv__free(addresses);
-}
-
-
-void uv__set_process_title(const char* title) {
-#if defined(PR_SET_NAME)
-  prctl(PR_SET_NAME, title);  /* Only copies first 16 characters. */
-#endif
-}
-
-
-static uint64_t uv__read_proc_meminfo(const char* what) {
-  uint64_t rc;
-  ssize_t n;
-  char* p;
-  int fd;
-  char buf[4096];  /* Large enough to hold all of /proc/meminfo. */
-
-  rc = 0;
-  fd = uv__open_cloexec("/proc/meminfo", O_RDONLY);
-
-  if (fd == -1)
-    return 0;
-
-  n = read(fd, buf, sizeof(buf) - 1);
-
-  if (n <= 0)
-    goto out;
-
-  buf[n] = '\0';
-  p = strstr(buf, what);
-
-  if (p == NULL)
-    goto out;
-
-  p += strlen(what);
-
-  if (1 != sscanf(p, "%" PRIu64 " kB", &rc))
-    goto out;
-
-  rc *= 1024;
-
-out:
-
-  if (uv__close_nocheckstdio(fd))
-    abort();
-
-  return rc;
-}
-
-
-uint64_t uv_get_free_memory(void) {
-  struct sysinfo info;
-  uint64_t rc;
-
-  rc = uv__read_proc_meminfo("MemFree:");
-
-  if (rc != 0)
-    return rc;
-
-  if (0 == sysinfo(&info))
-    return (uint64_t) info.freeram * info.mem_unit;
-
-  return 0;
-}
-
-
-uint64_t uv_get_total_memory(void) {
-  struct sysinfo info;
-  uint64_t rc;
-
-  rc = uv__read_proc_meminfo("MemTotal:");
-
-  if (rc != 0)
-    return rc;
-
-  if (0 == sysinfo(&info))
-    return (uint64_t) info.totalram * info.mem_unit;
-
-  return 0;
-}
-
-
-static uint64_t uv__read_cgroups_uint64(const char* cgroup, const char* param) {
-  char filename[256];
-  uint64_t rc;
-  int fd;
-  ssize_t n;
-  char buf[32];  /* Large enough to hold an encoded uint64_t. */
-
-  snprintf(filename, 256, "/sys/fs/cgroup/%s/%s", cgroup, param);
-
-  rc = 0;
-  fd = uv__open_cloexec(filename, O_RDONLY);
-
-  if (fd < 0)
-    return 0;
-
-  n = read(fd, buf, sizeof(buf) - 1);
-
-  if (n > 0) {
-    buf[n] = '\0';
-    sscanf(buf, "%" PRIu64, &rc);
-  }
-
-  if (uv__close_nocheckstdio(fd))
-    abort();
-
-  return rc;
-}
-
-
-uint64_t uv_get_constrained_memory(void) {
-  /*
-   * This might return 0 if there was a problem getting the memory limit from
-   * cgroups. This is OK because a return value of 0 signifies that the memory
-   * limit is unknown.
-   */
-  return uv__read_cgroups_uint64("memory", "memory.limit_in_bytes");
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/linux-inotify.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/linux-inotify.cpp
deleted file mode 100644
index ed484cc..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/linux-inotify.cpp
+++ /dev/null
@@ -1,354 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include "uv.h"
-#include "uv/tree.h"
-#include "internal.h"
-
-#include <stdint.h>
-#include <stdio.h>
-#include <stdlib.h>
-#include <string.h>
-#include <assert.h>
-#include <errno.h>
-
-#include <sys/types.h>
-#include <unistd.h>
-
-struct watcher_list {
-  RB_ENTRY(watcher_list) entry;
-  QUEUE watchers;
-  int iterating;
-  char* path;
-  int wd;
-};
-
-struct watcher_root {
-  struct watcher_list* rbh_root;
-};
-#define CAST(p) ((struct watcher_root*)(p))
-
-
-static int compare_watchers(const struct watcher_list* a,
-                            const struct watcher_list* b) {
-  if (a->wd < b->wd) return -1;
-  if (a->wd > b->wd) return 1;
-  return 0;
-}
-
-
-RB_GENERATE_STATIC(watcher_root, watcher_list, entry, compare_watchers)
-
-
-static void uv__inotify_read(uv_loop_t* loop,
-                             uv__io_t* w,
-                             unsigned int revents);
-
-static void maybe_free_watcher_list(struct watcher_list* w,
-                                    uv_loop_t* loop);
-
-static int new_inotify_fd(void) {
-  int err;
-  int fd;
-
-  fd = uv__inotify_init1(UV__IN_NONBLOCK | UV__IN_CLOEXEC);
-  if (fd != -1)
-    return fd;
-
-  if (errno != ENOSYS)
-    return UV__ERR(errno);
-
-  fd = uv__inotify_init();
-  if (fd == -1)
-    return UV__ERR(errno);
-
-  err = uv__cloexec(fd, 1);
-  if (err == 0)
-    err = uv__nonblock(fd, 1);
-
-  if (err) {
-    uv__close(fd);
-    return err;
-  }
-
-  return fd;
-}
-
-
-static int init_inotify(uv_loop_t* loop) {
-  int err;
-
-  if (loop->inotify_fd != -1)
-    return 0;
-
-  err = new_inotify_fd();
-  if (err < 0)
-    return err;
-
-  loop->inotify_fd = err;
-  uv__io_init(&loop->inotify_read_watcher, uv__inotify_read, loop->inotify_fd);
-  uv__io_start(loop, &loop->inotify_read_watcher, POLLIN);
-
-  return 0;
-}
-
-
-int uv__inotify_fork(uv_loop_t* loop, void* old_watchers) {
-  /* Open the inotify_fd, and re-arm all the inotify watchers. */
-  int err;
-  struct watcher_list* tmp_watcher_list_iter;
-  struct watcher_list* watcher_list;
-  struct watcher_list tmp_watcher_list;
-  QUEUE queue;
-  QUEUE* q;
-  uv_fs_event_t* handle;
-  char* tmp_path;
-
-  if (old_watchers != NULL) {
-    /* We must restore the old watcher list to be able to close items
-     * out of it.
-     */
-    loop->inotify_watchers = old_watchers;
-
-    QUEUE_INIT(&tmp_watcher_list.watchers);
-    /* Note that the queue we use is shared with the start and stop()
-     * functions, making QUEUE_FOREACH unsafe to use. So we use the
-     * QUEUE_MOVE trick to safely iterate. Also don't free the watcher
-     * list until we're done iterating. c.f. uv__inotify_read.
-     */
-    RB_FOREACH_SAFE(watcher_list, watcher_root,
-                    CAST(&old_watchers), tmp_watcher_list_iter) {
-      watcher_list->iterating = 1;
-      QUEUE_MOVE(&watcher_list->watchers, &queue);
-      while (!QUEUE_EMPTY(&queue)) {
-        q = QUEUE_HEAD(&queue);
-        handle = QUEUE_DATA(q, uv_fs_event_t, watchers);
-        /* It's critical to keep a copy of path here, because it
-         * will be set to NULL by stop() and then deallocated by
-         * maybe_free_watcher_list
-         */
-        tmp_path = uv__strdup(handle->path);
-        assert(tmp_path != NULL);
-        QUEUE_REMOVE(q);
-        QUEUE_INSERT_TAIL(&watcher_list->watchers, q);
-        uv_fs_event_stop(handle);
-
-        QUEUE_INSERT_TAIL(&tmp_watcher_list.watchers, &handle->watchers);
-        handle->path = tmp_path;
-      }
-      watcher_list->iterating = 0;
-      maybe_free_watcher_list(watcher_list, loop);
-    }
-
-    QUEUE_MOVE(&tmp_watcher_list.watchers, &queue);
-    while (!QUEUE_EMPTY(&queue)) {
-        q = QUEUE_HEAD(&queue);
-        QUEUE_REMOVE(q);
-        handle = QUEUE_DATA(q, uv_fs_event_t, watchers);
-        tmp_path = handle->path;
-        handle->path = NULL;
-        err = uv_fs_event_start(handle, handle->cb, tmp_path, 0);
-        uv__free(tmp_path);
-        if (err)
-          return err;
-    }
-  }
-
-  return 0;
-}
-
-
-static struct watcher_list* find_watcher(uv_loop_t* loop, int wd) {
-  struct watcher_list w;
-  w.wd = wd;
-  return RB_FIND(watcher_root, CAST(&loop->inotify_watchers), &w);
-}
-
-static void maybe_free_watcher_list(struct watcher_list* w, uv_loop_t* loop) {
-  /* if the watcher_list->watchers is being iterated over, we can't free it. */
-  if ((!w->iterating) && QUEUE_EMPTY(&w->watchers)) {
-    /* No watchers left for this path. Clean up. */
-    RB_REMOVE(watcher_root, CAST(&loop->inotify_watchers), w);
-    uv__inotify_rm_watch(loop->inotify_fd, w->wd);
-    uv__free(w);
-  }
-}
-
-static void uv__inotify_read(uv_loop_t* loop,
-                             uv__io_t* dummy,
-                             unsigned int events) {
-  const struct uv__inotify_event* e;
-  struct watcher_list* w;
-  uv_fs_event_t* h;
-  QUEUE queue;
-  QUEUE* q;
-  const char* path;
-  ssize_t size;
-  const char *p;
-  /* needs to be large enough for sizeof(inotify_event) + strlen(path) */
-  char buf[4096];
-
-  while (1) {
-    do
-      size = read(loop->inotify_fd, buf, sizeof(buf));
-    while (size == -1 && errno == EINTR);
-
-    if (size == -1) {
-      assert(errno == EAGAIN || errno == EWOULDBLOCK);
-      break;
-    }
-
-    assert(size > 0); /* pre-2.6.21 thing, size=0 == read buffer too small */
-
-    /* Now we have one or more inotify_event structs. */
-    for (p = buf; p < buf + size; p += sizeof(*e) + e->len) {
-      e = (const struct uv__inotify_event*)p;
-
-      events = 0;
-      if (e->mask & (UV__IN_ATTRIB|UV__IN_MODIFY))
-        events |= UV_CHANGE;
-      if (e->mask & ~(UV__IN_ATTRIB|UV__IN_MODIFY))
-        events |= UV_RENAME;
-
-      w = find_watcher(loop, e->wd);
-      if (w == NULL)
-        continue; /* Stale event, no watchers left. */
-
-      /* inotify does not return the filename when monitoring a single file
-       * for modifications. Repurpose the filename for API compatibility.
-       * I'm not convinced this is a good thing, maybe it should go.
-       */
-      path = e->len ? (const char*) (e + 1) : uv__basename_r(w->path);
-
-      /* We're about to iterate over the queue and call user's callbacks.
-       * What can go wrong?
-       * A callback could call uv_fs_event_stop()
-       * and the queue can change under our feet.
-       * So, we use QUEUE_MOVE() trick to safely iterate over the queue.
-       * And we don't free the watcher_list until we're done iterating.
-       *
-       * First,
-       * tell uv_fs_event_stop() (that could be called from a user's callback)
-       * not to free watcher_list.
-       */
-      w->iterating = 1;
-      QUEUE_MOVE(&w->watchers, &queue);
-      while (!QUEUE_EMPTY(&queue)) {
-        q = QUEUE_HEAD(&queue);
-        h = QUEUE_DATA(q, uv_fs_event_t, watchers);
-
-        QUEUE_REMOVE(q);
-        QUEUE_INSERT_TAIL(&w->watchers, q);
-
-        h->cb(h, path, events, 0);
-      }
-      /* done iterating, time to (maybe) free empty watcher_list */
-      w->iterating = 0;
-      maybe_free_watcher_list(w, loop);
-    }
-  }
-}
-
-
-int uv_fs_event_init(uv_loop_t* loop, uv_fs_event_t* handle) {
-  uv__handle_init(loop, (uv_handle_t*)handle, UV_FS_EVENT);
-  return 0;
-}
-
-
-int uv_fs_event_start(uv_fs_event_t* handle,
-                      uv_fs_event_cb cb,
-                      const char* path,
-                      unsigned int flags) {
-  struct watcher_list* w;
-  size_t len;
-  int events;
-  int err;
-  int wd;
-
-  if (uv__is_active(handle))
-    return UV_EINVAL;
-
-  err = init_inotify(handle->loop);
-  if (err)
-    return err;
-
-  events = UV__IN_ATTRIB
-         | UV__IN_CREATE
-         | UV__IN_MODIFY
-         | UV__IN_DELETE
-         | UV__IN_DELETE_SELF
-         | UV__IN_MOVE_SELF
-         | UV__IN_MOVED_FROM
-         | UV__IN_MOVED_TO;
-
-  wd = uv__inotify_add_watch(handle->loop->inotify_fd, path, events);
-  if (wd == -1)
-    return UV__ERR(errno);
-
-  w = find_watcher(handle->loop, wd);
-  if (w)
-    goto no_insert;
-
-  len = strlen(path) + 1;
-  w = (watcher_list*)uv__malloc(sizeof(*w) + len);
-  if (w == NULL)
-    return UV_ENOMEM;
-
-  w->wd = wd;
-  w->path = (char*)memcpy(w + 1, path, len);
-  QUEUE_INIT(&w->watchers);
-  w->iterating = 0;
-  RB_INSERT(watcher_root, CAST(&handle->loop->inotify_watchers), w);
-
-no_insert:
-  uv__handle_start(handle);
-  QUEUE_INSERT_TAIL(&w->watchers, &handle->watchers);
-  handle->path = w->path;
-  handle->cb = cb;
-  handle->wd = wd;
-
-  return 0;
-}
-
-
-int uv_fs_event_stop(uv_fs_event_t* handle) {
-  struct watcher_list* w;
-
-  if (!uv__is_active(handle))
-    return 0;
-
-  w = find_watcher(handle->loop, handle->wd);
-  assert(w != NULL);
-
-  handle->wd = -1;
-  handle->path = NULL;
-  uv__handle_stop(handle);
-  QUEUE_REMOVE(&handle->watchers);
-
-  maybe_free_watcher_list(w, handle->loop);
-
-  return 0;
-}
-
-
-void uv__fs_event_close(uv_fs_event_t* handle) {
-  uv_fs_event_stop(handle);
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/linux-syscalls.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/linux-syscalls.cpp
deleted file mode 100644
index 5637cf9..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/linux-syscalls.cpp
+++ /dev/null
@@ -1,369 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include "linux-syscalls.h"
-#include <unistd.h>
-#include <signal.h>
-#include <sys/syscall.h>
-#include <sys/types.h>
-#include <errno.h>
-
-#if defined(__has_feature)
-# if __has_feature(memory_sanitizer)
-#  define MSAN_ACTIVE 1
-#  include <sanitizer/msan_interface.h>
-# endif
-#endif
-
-#if defined(__i386__)
-# ifndef __NR_socketcall
-#  define __NR_socketcall 102
-# endif
-#endif
-
-#if defined(__arm__)
-# if defined(__thumb__) || defined(__ARM_EABI__)
-#  define UV_SYSCALL_BASE 0
-# else
-#  define UV_SYSCALL_BASE 0x900000
-# endif
-#endif /* __arm__ */
-
-#ifndef __NR_accept4
-# if defined(__x86_64__)
-#  define __NR_accept4 288
-# elif defined(__i386__)
-   /* Nothing. Handled through socketcall(). */
-# elif defined(__arm__)
-#  define __NR_accept4 (UV_SYSCALL_BASE + 366)
-# endif
-#endif /* __NR_accept4 */
-
-#ifndef __NR_eventfd
-# if defined(__x86_64__)
-#  define __NR_eventfd 284
-# elif defined(__i386__)
-#  define __NR_eventfd 323
-# elif defined(__arm__)
-#  define __NR_eventfd (UV_SYSCALL_BASE + 351)
-# endif
-#endif /* __NR_eventfd */
-
-#ifndef __NR_eventfd2
-# if defined(__x86_64__)
-#  define __NR_eventfd2 290
-# elif defined(__i386__)
-#  define __NR_eventfd2 328
-# elif defined(__arm__)
-#  define __NR_eventfd2 (UV_SYSCALL_BASE + 356)
-# endif
-#endif /* __NR_eventfd2 */
-
-#ifndef __NR_inotify_init
-# if defined(__x86_64__)
-#  define __NR_inotify_init 253
-# elif defined(__i386__)
-#  define __NR_inotify_init 291
-# elif defined(__arm__)
-#  define __NR_inotify_init (UV_SYSCALL_BASE + 316)
-# endif
-#endif /* __NR_inotify_init */
-
-#ifndef __NR_inotify_init1
-# if defined(__x86_64__)
-#  define __NR_inotify_init1 294
-# elif defined(__i386__)
-#  define __NR_inotify_init1 332
-# elif defined(__arm__)
-#  define __NR_inotify_init1 (UV_SYSCALL_BASE + 360)
-# endif
-#endif /* __NR_inotify_init1 */
-
-#ifndef __NR_inotify_add_watch
-# if defined(__x86_64__)
-#  define __NR_inotify_add_watch 254
-# elif defined(__i386__)
-#  define __NR_inotify_add_watch 292
-# elif defined(__arm__)
-#  define __NR_inotify_add_watch (UV_SYSCALL_BASE + 317)
-# endif
-#endif /* __NR_inotify_add_watch */
-
-#ifndef __NR_inotify_rm_watch
-# if defined(__x86_64__)
-#  define __NR_inotify_rm_watch 255
-# elif defined(__i386__)
-#  define __NR_inotify_rm_watch 293
-# elif defined(__arm__)
-#  define __NR_inotify_rm_watch (UV_SYSCALL_BASE + 318)
-# endif
-#endif /* __NR_inotify_rm_watch */
-
-#ifndef __NR_pipe2
-# if defined(__x86_64__)
-#  define __NR_pipe2 293
-# elif defined(__i386__)
-#  define __NR_pipe2 331
-# elif defined(__arm__)
-#  define __NR_pipe2 (UV_SYSCALL_BASE + 359)
-# endif
-#endif /* __NR_pipe2 */
-
-#ifndef __NR_recvmmsg
-# if defined(__x86_64__)
-#  define __NR_recvmmsg 299
-# elif defined(__i386__)
-#  define __NR_recvmmsg 337
-# elif defined(__arm__)
-#  define __NR_recvmmsg (UV_SYSCALL_BASE + 365)
-# endif
-#endif /* __NR_recvmsg */
-
-#ifndef __NR_sendmmsg
-# if defined(__x86_64__)
-#  define __NR_sendmmsg 307
-# elif defined(__i386__)
-#  define __NR_sendmmsg 345
-# elif defined(__arm__)
-#  define __NR_sendmmsg (UV_SYSCALL_BASE + 374)
-# endif
-#endif /* __NR_sendmmsg */
-
-#ifndef __NR_utimensat
-# if defined(__x86_64__)
-#  define __NR_utimensat 280
-# elif defined(__i386__)
-#  define __NR_utimensat 320
-# elif defined(__arm__)
-#  define __NR_utimensat (UV_SYSCALL_BASE + 348)
-# endif
-#endif /* __NR_utimensat */
-
-#ifndef __NR_preadv
-# if defined(__x86_64__)
-#  define __NR_preadv 295
-# elif defined(__i386__)
-#  define __NR_preadv 333
-# elif defined(__arm__)
-#  define __NR_preadv (UV_SYSCALL_BASE + 361)
-# endif
-#endif /* __NR_preadv */
-
-#ifndef __NR_pwritev
-# if defined(__x86_64__)
-#  define __NR_pwritev 296
-# elif defined(__i386__)
-#  define __NR_pwritev 334
-# elif defined(__arm__)
-#  define __NR_pwritev (UV_SYSCALL_BASE + 362)
-# endif
-#endif /* __NR_pwritev */
-
-#ifndef __NR_dup3
-# if defined(__x86_64__)
-#  define __NR_dup3 292
-# elif defined(__i386__)
-#  define __NR_dup3 330
-# elif defined(__arm__)
-#  define __NR_dup3 (UV_SYSCALL_BASE + 358)
-# endif
-#endif /* __NR_pwritev */
-
-#ifndef __NR_statx
-# if defined(__x86_64__)
-#  define __NR_statx 332
-# elif defined(__i386__)
-#  define __NR_statx 383
-# elif defined(__aarch64__)
-#  define __NR_statx 397
-# elif defined(__arm__)
-#  define __NR_statx (UV_SYSCALL_BASE + 397)
-# elif defined(__ppc__)
-#  define __NR_statx 383
-# elif defined(__s390__)
-#  define __NR_statx 379
-# endif
-#endif /* __NR_statx */
-
-int uv__accept4(int fd, struct sockaddr* addr, socklen_t* addrlen, int flags) {
-#if defined(__i386__)
-  unsigned long args[4];
-  int r;
-
-  args[0] = (unsigned long) fd;
-  args[1] = (unsigned long) addr;
-  args[2] = (unsigned long) addrlen;
-  args[3] = (unsigned long) flags;
-
-  r = syscall(__NR_socketcall, 18 /* SYS_ACCEPT4 */, args);
-
-  /* socketcall() raises EINVAL when SYS_ACCEPT4 is not supported but so does
-   * a bad flags argument. Try to distinguish between the two cases.
-   */
-  if (r == -1)
-    if (errno == EINVAL)
-      if ((flags & ~(UV__SOCK_CLOEXEC|UV__SOCK_NONBLOCK)) == 0)
-        errno = ENOSYS;
-
-  return r;
-#elif defined(__NR_accept4)
-  return syscall(__NR_accept4, fd, addr, addrlen, flags);
-#else
-  return errno = ENOSYS, -1;
-#endif
-}
-
-
-int uv__eventfd(unsigned int count) {
-#if defined(__NR_eventfd)
-  return syscall(__NR_eventfd, count);
-#else
-  return errno = ENOSYS, -1;
-#endif
-}
-
-
-int uv__eventfd2(unsigned int count, int flags) {
-#if defined(__NR_eventfd2)
-  return syscall(__NR_eventfd2, count, flags);
-#else
-  return errno = ENOSYS, -1;
-#endif
-}
-
-
-int uv__inotify_init(void) {
-#if defined(__NR_inotify_init)
-  return syscall(__NR_inotify_init);
-#else
-  return errno = ENOSYS, -1;
-#endif
-}
-
-
-int uv__inotify_init1(int flags) {
-#if defined(__NR_inotify_init1)
-  return syscall(__NR_inotify_init1, flags);
-#else
-  return errno = ENOSYS, -1;
-#endif
-}
-
-
-int uv__inotify_add_watch(int fd, const char* path, uint32_t mask) {
-#if defined(__NR_inotify_add_watch)
-  return syscall(__NR_inotify_add_watch, fd, path, mask);
-#else
-  return errno = ENOSYS, -1;
-#endif
-}
-
-
-int uv__inotify_rm_watch(int fd, int32_t wd) {
-#if defined(__NR_inotify_rm_watch)
-  return syscall(__NR_inotify_rm_watch, fd, wd);
-#else
-  return errno = ENOSYS, -1;
-#endif
-}
-
-
-int uv__pipe2(int pipefd[2], int flags) {
-#if defined(__NR_pipe2)
-  int result;
-  result = syscall(__NR_pipe2, pipefd, flags);
-#if MSAN_ACTIVE
-  if (!result)
-    __msan_unpoison(pipefd, sizeof(int[2]));
-#endif
-  return result;
-#else
-  return errno = ENOSYS, -1;
-#endif
-}
-
-
-int uv__sendmmsg(int fd,
-                 struct uv__mmsghdr* mmsg,
-                 unsigned int vlen,
-                 unsigned int flags) {
-#if defined(__NR_sendmmsg)
-  return syscall(__NR_sendmmsg, fd, mmsg, vlen, flags);
-#else
-  return errno = ENOSYS, -1;
-#endif
-}
-
-
-int uv__recvmmsg(int fd,
-                 struct uv__mmsghdr* mmsg,
-                 unsigned int vlen,
-                 unsigned int flags,
-                 struct timespec* timeout) {
-#if defined(__NR_recvmmsg)
-  return syscall(__NR_recvmmsg, fd, mmsg, vlen, flags, timeout);
-#else
-  return errno = ENOSYS, -1;
-#endif
-}
-
-
-ssize_t uv__preadv(int fd, const struct iovec *iov, int iovcnt, int64_t offset) {
-#if defined(__NR_preadv)
-  return syscall(__NR_preadv, fd, iov, iovcnt, (long)offset, (long)(offset >> 32));
-#else
-  return errno = ENOSYS, -1;
-#endif
-}
-
-
-ssize_t uv__pwritev(int fd, const struct iovec *iov, int iovcnt, int64_t offset) {
-#if defined(__NR_pwritev)
-  return syscall(__NR_pwritev, fd, iov, iovcnt, (long)offset, (long)(offset >> 32));
-#else
-  return errno = ENOSYS, -1;
-#endif
-}
-
-
-int uv__dup3(int oldfd, int newfd, int flags) {
-#if defined(__NR_dup3)
-  return syscall(__NR_dup3, oldfd, newfd, flags);
-#else
-  return errno = ENOSYS, -1;
-#endif
-}
-
-
-int uv__statx(int dirfd,
-              const char* path,
-              int flags,
-              unsigned int mask,
-              struct uv__statx* statxbuf) {
-  /* __NR_statx make Android box killed by SIGSYS.
-   * That looks like a seccomp2 sandbox filter rejecting the system call.
-   */
-#if defined(__NR_statx) && !defined(__ANDROID__)
-  return syscall(__NR_statx, dirfd, path, flags, mask, statxbuf);
-#else
-  return errno = ENOSYS, -1;
-#endif
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/linux-syscalls.h b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/linux-syscalls.h
deleted file mode 100644
index 7e58bfa..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/linux-syscalls.h
+++ /dev/null
@@ -1,152 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#ifndef UV_LINUX_SYSCALL_H_
-#define UV_LINUX_SYSCALL_H_
-
-#undef  _GNU_SOURCE
-#define _GNU_SOURCE
-
-#include <stdint.h>
-#include <signal.h>
-#include <sys/types.h>
-#include <sys/time.h>
-#include <sys/socket.h>
-
-#if defined(__alpha__)
-# define UV__O_CLOEXEC        0x200000
-#elif defined(__hppa__)
-# define UV__O_CLOEXEC        0x200000
-#elif defined(__sparc__)
-# define UV__O_CLOEXEC        0x400000
-#else
-# define UV__O_CLOEXEC        0x80000
-#endif
-
-#if defined(__alpha__)
-# define UV__O_NONBLOCK       0x4
-#elif defined(__hppa__)
-# define UV__O_NONBLOCK       O_NONBLOCK
-#elif defined(__mips__)
-# define UV__O_NONBLOCK       0x80
-#elif defined(__sparc__)
-# define UV__O_NONBLOCK       0x4000
-#else
-# define UV__O_NONBLOCK       0x800
-#endif
-
-#define UV__EFD_CLOEXEC       UV__O_CLOEXEC
-#define UV__EFD_NONBLOCK      UV__O_NONBLOCK
-
-#define UV__IN_CLOEXEC        UV__O_CLOEXEC
-#define UV__IN_NONBLOCK       UV__O_NONBLOCK
-
-#define UV__SOCK_CLOEXEC      UV__O_CLOEXEC
-#if defined(SOCK_NONBLOCK)
-# define UV__SOCK_NONBLOCK    SOCK_NONBLOCK
-#else
-# define UV__SOCK_NONBLOCK    UV__O_NONBLOCK
-#endif
-
-/* inotify flags */
-#define UV__IN_ACCESS         0x001
-#define UV__IN_MODIFY         0x002
-#define UV__IN_ATTRIB         0x004
-#define UV__IN_CLOSE_WRITE    0x008
-#define UV__IN_CLOSE_NOWRITE  0x010
-#define UV__IN_OPEN           0x020
-#define UV__IN_MOVED_FROM     0x040
-#define UV__IN_MOVED_TO       0x080
-#define UV__IN_CREATE         0x100
-#define UV__IN_DELETE         0x200
-#define UV__IN_DELETE_SELF    0x400
-#define UV__IN_MOVE_SELF      0x800
-
-struct uv__statx_timestamp {
-  int64_t tv_sec;
-  uint32_t tv_nsec;
-  int32_t unused0;
-};
-
-struct uv__statx {
-  uint32_t stx_mask;
-  uint32_t stx_blksize;
-  uint64_t stx_attributes;
-  uint32_t stx_nlink;
-  uint32_t stx_uid;
-  uint32_t stx_gid;
-  uint16_t stx_mode;
-  uint16_t unused0;
-  uint64_t stx_ino;
-  uint64_t stx_size;
-  uint64_t stx_blocks;
-  uint64_t stx_attributes_mask;
-  struct uv__statx_timestamp stx_atime;
-  struct uv__statx_timestamp stx_btime;
-  struct uv__statx_timestamp stx_ctime;
-  struct uv__statx_timestamp stx_mtime;
-  uint32_t stx_rdev_major;
-  uint32_t stx_rdev_minor;
-  uint32_t stx_dev_major;
-  uint32_t stx_dev_minor;
-  uint64_t unused1[14];
-};
-
-struct uv__inotify_event {
-  int32_t wd;
-  uint32_t mask;
-  uint32_t cookie;
-  uint32_t len;
-  /* char name[0]; */
-};
-
-struct uv__mmsghdr {
-  struct msghdr msg_hdr;
-  unsigned int msg_len;
-};
-
-int uv__accept4(int fd, struct sockaddr* addr, socklen_t* addrlen, int flags);
-int uv__eventfd(unsigned int count);
-int uv__eventfd2(unsigned int count, int flags);
-int uv__inotify_init(void);
-int uv__inotify_init1(int flags);
-int uv__inotify_add_watch(int fd, const char* path, uint32_t mask);
-int uv__inotify_rm_watch(int fd, int32_t wd);
-int uv__pipe2(int pipefd[2], int flags);
-int uv__recvmmsg(int fd,
-                 struct uv__mmsghdr* mmsg,
-                 unsigned int vlen,
-                 unsigned int flags,
-                 struct timespec* timeout);
-int uv__sendmmsg(int fd,
-                 struct uv__mmsghdr* mmsg,
-                 unsigned int vlen,
-                 unsigned int flags);
-ssize_t uv__preadv(int fd, const struct iovec *iov, int iovcnt, int64_t offset);
-ssize_t uv__pwritev(int fd, const struct iovec *iov, int iovcnt, int64_t offset);
-int uv__dup3(int oldfd, int newfd, int flags);
-int uv__statx(int dirfd,
-              const char* path,
-              int flags,
-              unsigned int mask,
-              struct uv__statx* statxbuf);
-
-#endif /* UV_LINUX_SYSCALL_H_ */
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/loop.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/loop.cpp
deleted file mode 100644
index 7a037d1..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/loop.cpp
+++ /dev/null
@@ -1,194 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include "uv.h"
-#include "uv/tree.h"
-#include "internal.h"
-#include "heap-inl.h"
-#include <stdlib.h>
-#include <string.h>
-#include <unistd.h>
-
-int uv_loop_init(uv_loop_t* loop) {
-  void* saved_data;
-  int err;
-
-
-  saved_data = loop->data;
-  memset(loop, 0, sizeof(*loop));
-  loop->data = saved_data;
-
-  heap_init((struct heap*) &loop->timer_heap);
-  QUEUE_INIT(&loop->wq);
-  QUEUE_INIT(&loop->idle_handles);
-  QUEUE_INIT(&loop->async_handles);
-  QUEUE_INIT(&loop->check_handles);
-  QUEUE_INIT(&loop->prepare_handles);
-  QUEUE_INIT(&loop->handle_queue);
-
-  loop->active_handles = 0;
-  loop->active_reqs.count = 0;
-  loop->nfds = 0;
-  loop->watchers = NULL;
-  loop->nwatchers = 0;
-  QUEUE_INIT(&loop->pending_queue);
-  QUEUE_INIT(&loop->watcher_queue);
-
-  loop->closing_handles = NULL;
-  uv__update_time(loop);
-  loop->async_io_watcher.fd = -1;
-  loop->async_wfd = -1;
-  loop->signal_pipefd[0] = -1;
-  loop->signal_pipefd[1] = -1;
-  loop->backend_fd = -1;
-  loop->emfile_fd = -1;
-
-  loop->timer_counter = 0;
-  loop->stop_flag = 0;
-
-  err = uv__platform_loop_init(loop);
-  if (err)
-    return err;
-
-  uv__signal_global_once_init();
-  err = uv_signal_init(loop, &loop->child_watcher);
-  if (err)
-    goto fail_signal_init;
-
-  uv__handle_unref(&loop->child_watcher);
-  loop->child_watcher.flags |= UV_HANDLE_INTERNAL;
-  QUEUE_INIT(&loop->process_handles);
-
-  err = uv_rwlock_init(&loop->cloexec_lock);
-  if (err)
-    goto fail_rwlock_init;
-
-  err = uv_mutex_init(&loop->wq_mutex);
-  if (err)
-    goto fail_mutex_init;
-
-  err = uv_async_init(loop, &loop->wq_async, uv__work_done);
-  if (err)
-    goto fail_async_init;
-
-  uv__handle_unref(&loop->wq_async);
-  loop->wq_async.flags |= UV_HANDLE_INTERNAL;
-
-  return 0;
-
-fail_async_init:
-  uv_mutex_destroy(&loop->wq_mutex);
-
-fail_mutex_init:
-  uv_rwlock_destroy(&loop->cloexec_lock);
-
-fail_rwlock_init:
-  uv__signal_loop_cleanup(loop);
-
-fail_signal_init:
-  uv__platform_loop_delete(loop);
-
-  return err;
-}
-
-
-int uv_loop_fork(uv_loop_t* loop) {
-  int err;
-  unsigned int i;
-  uv__io_t* w;
-
-  err = uv__io_fork(loop);
-  if (err)
-    return err;
-
-  err = uv__async_fork(loop);
-  if (err)
-    return err;
-
-  err = uv__signal_loop_fork(loop);
-  if (err)
-    return err;
-
-  /* Rearm all the watchers that aren't re-queued by the above. */
-  for (i = 0; i < loop->nwatchers; i++) {
-    w = (uv__io_t*)loop->watchers[i];
-    if (w == NULL)
-      continue;
-
-    if (w->pevents != 0 && QUEUE_EMPTY(&w->watcher_queue)) {
-      w->events = 0; /* Force re-registration in uv__io_poll. */
-      QUEUE_INSERT_TAIL(&loop->watcher_queue, &w->watcher_queue);
-    }
-  }
-
-  return 0;
-}
-
-
-void uv__loop_close(uv_loop_t* loop) {
-  uv__signal_loop_cleanup(loop);
-  uv__platform_loop_delete(loop);
-  uv__async_stop(loop);
-
-  if (loop->emfile_fd != -1) {
-    uv__close(loop->emfile_fd);
-    loop->emfile_fd = -1;
-  }
-
-  if (loop->backend_fd != -1) {
-    uv__close(loop->backend_fd);
-    loop->backend_fd = -1;
-  }
-
-  uv_mutex_lock(&loop->wq_mutex);
-  assert(QUEUE_EMPTY(&loop->wq) && "thread pool work queue not empty!");
-  assert(!uv__has_active_reqs(loop));
-  uv_mutex_unlock(&loop->wq_mutex);
-  uv_mutex_destroy(&loop->wq_mutex);
-
-  /*
-   * Note that all thread pool stuff is finished at this point and
-   * it is safe to just destroy rw lock
-   */
-  uv_rwlock_destroy(&loop->cloexec_lock);
-
-#if 0
-  assert(QUEUE_EMPTY(&loop->pending_queue));
-  assert(QUEUE_EMPTY(&loop->watcher_queue));
-  assert(loop->nfds == 0);
-#endif
-
-  uv__free(loop->watchers);
-  loop->watchers = NULL;
-  loop->nwatchers = 0;
-}
-
-
-int uv__loop_configure(uv_loop_t* loop, uv_loop_option option, va_list ap) {
-  if (option != UV_LOOP_BLOCK_SIGNAL)
-    return UV_ENOSYS;
-
-  if (va_arg(ap, int) != SIGPROF)
-    return UV_EINVAL;
-
-  loop->flags |= UV_LOOP_BLOCK_SIGPROF;
-  return 0;
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/netbsd.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/netbsd.cpp
deleted file mode 100644
index fb89843..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/netbsd.cpp
+++ /dev/null
@@ -1,247 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include "uv.h"
-#include "internal.h"
-
-#include <assert.h>
-#include <string.h>
-#include <errno.h>
-
-#include <kvm.h>
-#include <paths.h>
-#include <unistd.h>
-#include <time.h>
-#include <stdlib.h>
-#include <fcntl.h>
-
-#include <sys/resource.h>
-#include <sys/types.h>
-#include <sys/sysctl.h>
-#include <uvm/uvm_extern.h>
-
-#include <unistd.h>
-#include <time.h>
-
-
-int uv__platform_loop_init(uv_loop_t* loop) {
-  return uv__kqueue_init(loop);
-}
-
-
-void uv__platform_loop_delete(uv_loop_t* loop) {
-}
-
-
-void uv_loadavg(double avg[3]) {
-  struct loadavg info;
-  size_t size = sizeof(info);
-  int which[] = {CTL_VM, VM_LOADAVG};
-
-  if (sysctl(which, 2, &info, &size, NULL, 0) == -1) return;
-
-  avg[0] = (double) info.ldavg[0] / info.fscale;
-  avg[1] = (double) info.ldavg[1] / info.fscale;
-  avg[2] = (double) info.ldavg[2] / info.fscale;
-}
-
-
-int uv_exepath(char* buffer, size_t* size) {
-  /* Intermediate buffer, retrieving partial path name does not work
-   * As of NetBSD-8(beta), vnode->path translator does not handle files
-   * with longer names than 31 characters.
-   */
-  char int_buf[PATH_MAX];
-  size_t int_size;
-  int mib[4];
-
-  if (buffer == NULL || size == NULL || *size == 0)
-    return UV_EINVAL;
-
-  mib[0] = CTL_KERN;
-  mib[1] = KERN_PROC_ARGS;
-  mib[2] = -1;
-  mib[3] = KERN_PROC_PATHNAME;
-  int_size = ARRAY_SIZE(int_buf);
-
-  if (sysctl(mib, 4, int_buf, &int_size, NULL, 0))
-    return UV__ERR(errno);
-
-  /* Copy string from the intermediate buffer to outer one with appropriate
-   * length.
-   */
-  /* TODO(bnoordhuis) Check uv__strscpy() return value. */
-  uv__strscpy(buffer, int_buf, *size);
-
-  /* Set new size. */
-  *size = strlen(buffer);
-
-  return 0;
-}
-
-
-uint64_t uv_get_free_memory(void) {
-  struct uvmexp info;
-  size_t size = sizeof(info);
-  int which[] = {CTL_VM, VM_UVMEXP};
-
-  if (sysctl(which, 2, &info, &size, NULL, 0))
-    return UV__ERR(errno);
-
-  return (uint64_t) info.free * sysconf(_SC_PAGESIZE);
-}
-
-
-uint64_t uv_get_total_memory(void) {
-#if defined(HW_PHYSMEM64)
-  uint64_t info;
-  int which[] = {CTL_HW, HW_PHYSMEM64};
-#else
-  unsigned int info;
-  int which[] = {CTL_HW, HW_PHYSMEM};
-#endif
-  size_t size = sizeof(info);
-
-  if (sysctl(which, 2, &info, &size, NULL, 0))
-    return UV__ERR(errno);
-
-  return (uint64_t) info;
-}
-
-
-uint64_t uv_get_constrained_memory(void) {
-  return 0;  /* Memory constraints are unknown. */
-}
-
-
-int uv_resident_set_memory(size_t* rss) {
-  kvm_t *kd = NULL;
-  struct kinfo_proc2 *kinfo = NULL;
-  pid_t pid;
-  int nprocs;
-  int max_size = sizeof(struct kinfo_proc2);
-  int page_size;
-
-  page_size = getpagesize();
-  pid = getpid();
-
-  kd = kvm_open(NULL, NULL, NULL, KVM_NO_FILES, "kvm_open");
-
-  if (kd == NULL) goto error;
-
-  kinfo = kvm_getproc2(kd, KERN_PROC_PID, pid, max_size, &nprocs);
-  if (kinfo == NULL) goto error;
-
-  *rss = kinfo->p_vm_rssize * page_size;
-
-  kvm_close(kd);
-
-  return 0;
-
-error:
-  if (kd) kvm_close(kd);
-  return UV_EPERM;
-}
-
-
-int uv_uptime(double* uptime) {
-  time_t now;
-  struct timeval info;
-  size_t size = sizeof(info);
-  static int which[] = {CTL_KERN, KERN_BOOTTIME};
-
-  if (sysctl(which, 2, &info, &size, NULL, 0))
-    return UV__ERR(errno);
-
-  now = time(NULL);
-
-  *uptime = (double)(now - info.tv_sec);
-  return 0;
-}
-
-
-int uv_cpu_info(uv_cpu_info_t** cpu_infos, int* count) {
-  unsigned int ticks = (unsigned int)sysconf(_SC_CLK_TCK);
-  unsigned int multiplier = ((uint64_t)1000L / ticks);
-  unsigned int cur = 0;
-  uv_cpu_info_t* cpu_info;
-  u_int64_t* cp_times;
-  char model[512];
-  u_int64_t cpuspeed;
-  int numcpus;
-  size_t size;
-  int i;
-
-  size = sizeof(model);
-  if (sysctlbyname("machdep.cpu_brand", &model, &size, NULL, 0) &&
-      sysctlbyname("hw.model", &model, &size, NULL, 0)) {
-    return UV__ERR(errno);
-  }
-
-  size = sizeof(numcpus);
-  if (sysctlbyname("hw.ncpu", &numcpus, &size, NULL, 0))
-    return UV__ERR(errno);
-  *count = numcpus;
-
-  /* Only i386 and amd64 have machdep.tsc_freq */
-  size = sizeof(cpuspeed);
-  if (sysctlbyname("machdep.tsc_freq", &cpuspeed, &size, NULL, 0))
-    cpuspeed = 0;
-
-  size = numcpus * CPUSTATES * sizeof(*cp_times);
-  cp_times = (u_int64_t*)uv__malloc(size);
-  if (cp_times == NULL)
-    return UV_ENOMEM;
-
-  if (sysctlbyname("kern.cp_time", cp_times, &size, NULL, 0))
-    return UV__ERR(errno);
-
-  *cpu_infos = (uv_cpu_info_t*)uv__malloc(numcpus * sizeof(**cpu_infos));
-  if (!(*cpu_infos)) {
-    uv__free(cp_times);
-    uv__free(*cpu_infos);
-    return UV_ENOMEM;
-  }
-
-  for (i = 0; i < numcpus; i++) {
-    cpu_info = &(*cpu_infos)[i];
-    cpu_info->cpu_times.user = (uint64_t)(cp_times[CP_USER+cur]) * multiplier;
-    cpu_info->cpu_times.nice = (uint64_t)(cp_times[CP_NICE+cur]) * multiplier;
-    cpu_info->cpu_times.sys = (uint64_t)(cp_times[CP_SYS+cur]) * multiplier;
-    cpu_info->cpu_times.idle = (uint64_t)(cp_times[CP_IDLE+cur]) * multiplier;
-    cpu_info->cpu_times.irq = (uint64_t)(cp_times[CP_INTR+cur]) * multiplier;
-    cpu_info->model = uv__strdup(model);
-    cpu_info->speed = (int)(cpuspeed/(uint64_t) 1e6);
-    cur += CPUSTATES;
-  }
-  uv__free(cp_times);
-  return 0;
-}
-
-
-void uv_free_cpu_info(uv_cpu_info_t* cpu_infos, int count) {
-  int i;
-
-  for (i = 0; i < count; i++) {
-    uv__free(cpu_infos[i].model);
-  }
-
-  uv__free(cpu_infos);
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/no-proctitle.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/no-proctitle.cpp
deleted file mode 100644
index 165740c..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/no-proctitle.cpp
+++ /dev/null
@@ -1,42 +0,0 @@
-/* Copyright libuv project contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include "uv.h"
-#include "internal.h"
-
-#include <errno.h>
-#include <stddef.h>
-
-char** uv_setup_args(int argc, char** argv) {
-  return argv;
-}
-
-int uv_set_process_title(const char* title) {
-  return 0;
-}
-
-int uv_get_process_title(char* buffer, size_t size) {
-  if (buffer == NULL || size == 0)
-    return UV_EINVAL;
-
-  buffer[0] = '\0';
-  return 0;
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/openbsd.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/openbsd.cpp
deleted file mode 100644
index f13ad8c..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/openbsd.cpp
+++ /dev/null
@@ -1,249 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include "uv.h"
-#include "internal.h"
-
-#include <sys/types.h>
-#include <sys/param.h>
-#include <sys/resource.h>
-#include <sys/sched.h>
-#include <sys/time.h>
-#include <sys/sysctl.h>
-
-#include <errno.h>
-#include <fcntl.h>
-#include <paths.h>
-#include <stdlib.h>
-#include <string.h>
-#include <unistd.h>
-
-
-int uv__platform_loop_init(uv_loop_t* loop) {
-  return uv__kqueue_init(loop);
-}
-
-
-void uv__platform_loop_delete(uv_loop_t* loop) {
-}
-
-
-void uv_loadavg(double avg[3]) {
-  struct loadavg info;
-  size_t size = sizeof(info);
-  int which[] = {CTL_VM, VM_LOADAVG};
-
-  if (sysctl(which, 2, &info, &size, NULL, 0) < 0) return;
-
-  avg[0] = (double) info.ldavg[0] / info.fscale;
-  avg[1] = (double) info.ldavg[1] / info.fscale;
-  avg[2] = (double) info.ldavg[2] / info.fscale;
-}
-
-
-int uv_exepath(char* buffer, size_t* size) {
-  int mib[4];
-  char **argsbuf = NULL;
-  char **argsbuf_tmp;
-  size_t argsbuf_size = 100U;
-  size_t exepath_size;
-  pid_t mypid;
-  int err;
-
-  if (buffer == NULL || size == NULL || *size == 0)
-    return UV_EINVAL;
-
-  mypid = getpid();
-  for (;;) {
-    err = UV_ENOMEM;
-    argsbuf_tmp = (char**)uv__realloc(argsbuf, argsbuf_size);
-    if (argsbuf_tmp == NULL)
-      goto out;
-    argsbuf = argsbuf_tmp;
-    mib[0] = CTL_KERN;
-    mib[1] = KERN_PROC_ARGS;
-    mib[2] = mypid;
-    mib[3] = KERN_PROC_ARGV;
-    if (sysctl(mib, 4, argsbuf, &argsbuf_size, NULL, 0) == 0) {
-      break;
-    }
-    if (errno != ENOMEM) {
-      err = UV__ERR(errno);
-      goto out;
-    }
-    argsbuf_size *= 2U;
-  }
-
-  if (argsbuf[0] == NULL) {
-    err = UV_EINVAL;  /* FIXME(bnoordhuis) More appropriate error. */
-    goto out;
-  }
-
-  *size -= 1;
-  exepath_size = strlen(argsbuf[0]);
-  if (*size > exepath_size)
-    *size = exepath_size;
-
-  memcpy(buffer, argsbuf[0], *size);
-  buffer[*size] = '\0';
-  err = 0;
-
-out:
-  uv__free(argsbuf);
-
-  return err;
-}
-
-
-uint64_t uv_get_free_memory(void) {
-  struct uvmexp info;
-  size_t size = sizeof(info);
-  int which[] = {CTL_VM, VM_UVMEXP};
-
-  if (sysctl(which, 2, &info, &size, NULL, 0))
-    return UV__ERR(errno);
-
-  return (uint64_t) info.free * sysconf(_SC_PAGESIZE);
-}
-
-
-uint64_t uv_get_total_memory(void) {
-  uint64_t info;
-  int which[] = {CTL_HW, HW_PHYSMEM64};
-  size_t size = sizeof(info);
-
-  if (sysctl(which, 2, &info, &size, NULL, 0))
-    return UV__ERR(errno);
-
-  return (uint64_t) info;
-}
-
-
-uint64_t uv_get_constrained_memory(void) {
-  return 0;  /* Memory constraints are unknown. */
-}
-
-
-int uv_resident_set_memory(size_t* rss) {
-  struct kinfo_proc kinfo;
-  size_t page_size = getpagesize();
-  size_t size = sizeof(struct kinfo_proc);
-  int mib[6];
-
-  mib[0] = CTL_KERN;
-  mib[1] = KERN_PROC;
-  mib[2] = KERN_PROC_PID;
-  mib[3] = getpid();
-  mib[4] = sizeof(struct kinfo_proc);
-  mib[5] = 1;
-
-  if (sysctl(mib, 6, &kinfo, &size, NULL, 0) < 0)
-    return UV__ERR(errno);
-
-  *rss = kinfo.p_vm_rssize * page_size;
-  return 0;
-}
-
-
-int uv_uptime(double* uptime) {
-  time_t now;
-  struct timeval info;
-  size_t size = sizeof(info);
-  static int which[] = {CTL_KERN, KERN_BOOTTIME};
-
-  if (sysctl(which, 2, &info, &size, NULL, 0))
-    return UV__ERR(errno);
-
-  now = time(NULL);
-
-  *uptime = (double)(now - info.tv_sec);
-  return 0;
-}
-
-
-int uv_cpu_info(uv_cpu_info_t** cpu_infos, int* count) {
-  unsigned int ticks = (unsigned int)sysconf(_SC_CLK_TCK),
-               multiplier = ((uint64_t)1000L / ticks), cpuspeed;
-  uint64_t info[CPUSTATES];
-  char model[512];
-  int numcpus = 1;
-  int which[] = {CTL_HW,HW_MODEL,0};
-  size_t size;
-  int i;
-  uv_cpu_info_t* cpu_info;
-
-  size = sizeof(model);
-  if (sysctl(which, 2, &model, &size, NULL, 0))
-    return UV__ERR(errno);
-
-  which[1] = HW_NCPU;
-  size = sizeof(numcpus);
-  if (sysctl(which, 2, &numcpus, &size, NULL, 0))
-    return UV__ERR(errno);
-
-  *cpu_infos = (uv_cpu_info_t*)uv__malloc(numcpus * sizeof(**cpu_infos));
-  if (!(*cpu_infos))
-    return UV_ENOMEM;
-
-  *count = numcpus;
-
-  which[1] = HW_CPUSPEED;
-  size = sizeof(cpuspeed);
-  if (sysctl(which, 2, &cpuspeed, &size, NULL, 0)) {
-    uv__free(*cpu_infos);
-    return UV__ERR(errno);
-  }
-
-  size = sizeof(info);
-  which[0] = CTL_KERN;
-  which[1] = KERN_CPTIME2;
-  for (i = 0; i < numcpus; i++) {
-    which[2] = i;
-    size = sizeof(info);
-    if (sysctl(which, 3, &info, &size, NULL, 0)) {
-      uv__free(*cpu_infos);
-      return UV__ERR(errno);
-    }
-
-    cpu_info = &(*cpu_infos)[i];
-
-    cpu_info->cpu_times.user = (uint64_t)(info[CP_USER]) * multiplier;
-    cpu_info->cpu_times.nice = (uint64_t)(info[CP_NICE]) * multiplier;
-    cpu_info->cpu_times.sys = (uint64_t)(info[CP_SYS]) * multiplier;
-    cpu_info->cpu_times.idle = (uint64_t)(info[CP_IDLE]) * multiplier;
-    cpu_info->cpu_times.irq = (uint64_t)(info[CP_INTR]) * multiplier;
-
-    cpu_info->model = uv__strdup(model);
-    cpu_info->speed = cpuspeed;
-  }
-
-  return 0;
-}
-
-
-void uv_free_cpu_info(uv_cpu_info_t* cpu_infos, int count) {
-  int i;
-
-  for (i = 0; i < count; i++) {
-    uv__free(cpu_infos[i].model);
-  }
-
-  uv__free(cpu_infos);
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/pipe.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/pipe.cpp
deleted file mode 100644
index c21033a..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/pipe.cpp
+++ /dev/null
@@ -1,377 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include "uv.h"
-#include "internal.h"
-
-#include <assert.h>
-#include <errno.h>
-#include <string.h>
-#include <sys/un.h>
-#include <unistd.h>
-#include <stdlib.h>
-
-
-int uv_pipe_init(uv_loop_t* loop, uv_pipe_t* handle, int ipc) {
-  uv__stream_init(loop, (uv_stream_t*)handle, UV_NAMED_PIPE);
-  handle->shutdown_req = NULL;
-  handle->connect_req = NULL;
-  handle->pipe_fname = NULL;
-  handle->ipc = ipc;
-  return 0;
-}
-
-
-int uv_pipe_bind(uv_pipe_t* handle, const char* name) {
-  struct sockaddr_un saddr;
-  const char* pipe_fname;
-  int sockfd;
-  int err;
-
-  pipe_fname = NULL;
-
-  /* Already bound? */
-  if (uv__stream_fd(handle) >= 0)
-    return UV_EINVAL;
-
-  /* Make a copy of the file name, it outlives this function's scope. */
-  pipe_fname = uv__strdup(name);
-  if (pipe_fname == NULL)
-    return UV_ENOMEM;
-
-  /* We've got a copy, don't touch the original any more. */
-  name = NULL;
-
-  err = uv__socket(AF_UNIX, SOCK_STREAM, 0);
-  if (err < 0)
-    goto err_socket;
-  sockfd = err;
-
-  memset(&saddr, 0, sizeof saddr);
-  uv__strscpy(saddr.sun_path, pipe_fname, sizeof(saddr.sun_path));
-  saddr.sun_family = AF_UNIX;
-
-  if (bind(sockfd, (struct sockaddr*)&saddr, sizeof saddr)) {
-    err = UV__ERR(errno);
-    /* Convert ENOENT to EACCES for compatibility with Windows. */
-    if (err == UV_ENOENT)
-      err = UV_EACCES;
-
-    uv__close(sockfd);
-    goto err_socket;
-  }
-
-  /* Success. */
-  handle->flags |= UV_HANDLE_BOUND;
-  handle->pipe_fname = pipe_fname; /* Is a strdup'ed copy. */
-  handle->io_watcher.fd = sockfd;
-  return 0;
-
-err_socket:
-  uv__free((void*)pipe_fname);
-  return err;
-}
-
-
-int uv_pipe_listen(uv_pipe_t* handle, int backlog, uv_connection_cb cb) {
-  if (uv__stream_fd(handle) == -1)
-    return UV_EINVAL;
-
-#if defined(__MVS__)
-  /* On zOS, backlog=0 has undefined behaviour */
-  if (backlog == 0)
-    backlog = 1;
-  else if (backlog < 0)
-    backlog = SOMAXCONN;
-#endif
-
-  if (listen(uv__stream_fd(handle), backlog))
-    return UV__ERR(errno);
-
-  handle->connection_cb = cb;
-  handle->io_watcher.cb = uv__server_io;
-  uv__io_start(handle->loop, &handle->io_watcher, POLLIN);
-  return 0;
-}
-
-
-void uv__pipe_close(uv_pipe_t* handle) {
-  if (handle->pipe_fname) {
-    /*
-     * Unlink the file system entity before closing the file descriptor.
-     * Doing it the other way around introduces a race where our process
-     * unlinks a socket with the same name that's just been created by
-     * another thread or process.
-     */
-    unlink(handle->pipe_fname);
-    uv__free((void*)handle->pipe_fname);
-    handle->pipe_fname = NULL;
-  }
-
-  uv__stream_close((uv_stream_t*)handle);
-}
-
-
-int uv_pipe_open(uv_pipe_t* handle, uv_file fd) {
-  int flags;
-  int mode;
-  int err;
-  flags = 0;
-
-  if (uv__fd_exists(handle->loop, fd))
-    return UV_EEXIST;
-
-  do
-    mode = fcntl(fd, F_GETFL);
-  while (mode == -1 && errno == EINTR);
-
-  if (mode == -1)
-    return UV__ERR(errno); /* according to docs, must be EBADF */
-
-  err = uv__nonblock(fd, 1);
-  if (err)
-    return err;
-
-#if defined(__APPLE__)
-  err = uv__stream_try_select((uv_stream_t*) handle, &fd);
-  if (err)
-    return err;
-#endif /* defined(__APPLE__) */
-
-  mode &= O_ACCMODE;
-  if (mode != O_WRONLY)
-    flags |= UV_HANDLE_READABLE;
-  if (mode != O_RDONLY)
-    flags |= UV_HANDLE_WRITABLE;
-
-  return uv__stream_open((uv_stream_t*)handle, fd, flags);
-}
-
-
-void uv_pipe_connect(uv_connect_t* req,
-                    uv_pipe_t* handle,
-                    const char* name,
-                    uv_connect_cb cb) {
-  struct sockaddr_un saddr;
-  int new_sock;
-  int err;
-  int r;
-
-  new_sock = (uv__stream_fd(handle) == -1);
-
-  if (new_sock) {
-    err = uv__socket(AF_UNIX, SOCK_STREAM, 0);
-    if (err < 0)
-      goto out;
-    handle->io_watcher.fd = err;
-  }
-
-  memset(&saddr, 0, sizeof saddr);
-  uv__strscpy(saddr.sun_path, name, sizeof(saddr.sun_path));
-  saddr.sun_family = AF_UNIX;
-
-  do {
-    r = connect(uv__stream_fd(handle),
-                (struct sockaddr*)&saddr, sizeof saddr);
-  }
-  while (r == -1 && errno == EINTR);
-
-  if (r == -1 && errno != EINPROGRESS) {
-    err = UV__ERR(errno);
-#if defined(__CYGWIN__) || defined(__MSYS__)
-    /* EBADF is supposed to mean that the socket fd is bad, but
-       Cygwin reports EBADF instead of ENOTSOCK when the file is
-       not a socket.  We do not expect to see a bad fd here
-       (e.g. due to new_sock), so translate the error.  */
-    if (err == UV_EBADF)
-      err = UV_ENOTSOCK;
-#endif
-    goto out;
-  }
-
-  err = 0;
-  if (new_sock) {
-    err = uv__stream_open((uv_stream_t*)handle,
-                          uv__stream_fd(handle),
-                          UV_HANDLE_READABLE | UV_HANDLE_WRITABLE);
-  }
-
-  if (err == 0)
-    uv__io_start(handle->loop, &handle->io_watcher, POLLOUT);
-
-out:
-  handle->delayed_error = err;
-  handle->connect_req = req;
-
-  uv__req_init(handle->loop, req, UV_CONNECT);
-  req->handle = (uv_stream_t*)handle;
-  req->cb = cb;
-  QUEUE_INIT(&req->queue);
-
-  /* Force callback to run on next tick in case of error. */
-  if (err)
-    uv__io_feed(handle->loop, &handle->io_watcher);
-
-}
-
-
-static int uv__pipe_getsockpeername(const uv_pipe_t* handle,
-                                    uv__peersockfunc func,
-                                    char* buffer,
-                                    size_t* size) {
-  struct sockaddr_un sa;
-  socklen_t addrlen;
-  int err;
-
-  addrlen = sizeof(sa);
-  memset(&sa, 0, addrlen);
-  err = uv__getsockpeername((const uv_handle_t*) handle,
-                            func,
-                            (struct sockaddr*) &sa,
-                            (int*) &addrlen);
-  if (err < 0) {
-    *size = 0;
-    return err;
-  }
-
-#if defined(__linux__)
-  if (sa.sun_path[0] == 0)
-    /* Linux abstract namespace */
-    addrlen -= offsetof(struct sockaddr_un, sun_path);
-  else
-#endif
-    addrlen = strlen(sa.sun_path);
-
-
-  if (addrlen >= *size) {
-    *size = addrlen + 1;
-    return UV_ENOBUFS;
-  }
-
-  memcpy(buffer, sa.sun_path, addrlen);
-  *size = addrlen;
-
-  /* only null-terminate if it's not an abstract socket */
-  if (buffer[0] != '\0')
-    buffer[addrlen] = '\0';
-
-  return 0;
-}
-
-
-int uv_pipe_getsockname(const uv_pipe_t* handle, char* buffer, size_t* size) {
-  return uv__pipe_getsockpeername(handle, getsockname, buffer, size);
-}
-
-
-int uv_pipe_getpeername(const uv_pipe_t* handle, char* buffer, size_t* size) {
-  return uv__pipe_getsockpeername(handle, getpeername, buffer, size);
-}
-
-
-void uv_pipe_pending_instances(uv_pipe_t* handle, int count) {
-}
-
-
-int uv_pipe_pending_count(uv_pipe_t* handle) {
-  uv__stream_queued_fds_t* queued_fds;
-
-  if (!handle->ipc)
-    return 0;
-
-  if (handle->accepted_fd == -1)
-    return 0;
-
-  if (handle->queued_fds == NULL)
-    return 1;
-
-  queued_fds = (uv__stream_queued_fds_t*)(handle->queued_fds);
-  return queued_fds->offset + 1;
-}
-
-
-uv_handle_type uv_pipe_pending_type(uv_pipe_t* handle) {
-  if (!handle->ipc)
-    return UV_UNKNOWN_HANDLE;
-
-  if (handle->accepted_fd == -1)
-    return UV_UNKNOWN_HANDLE;
-  else
-    return uv__handle_type(handle->accepted_fd);
-}
-
-
-int uv_pipe_chmod(uv_pipe_t* handle, int mode) {
-  unsigned desired_mode;
-  struct stat pipe_stat;
-  char* name_buffer;
-  size_t name_len;
-  int r;
-
-  if (handle == NULL || uv__stream_fd(handle) == -1)
-    return UV_EBADF;
-
-  if (mode != UV_READABLE &&
-      mode != UV_WRITABLE &&
-      mode != (UV_WRITABLE | UV_READABLE))
-    return UV_EINVAL;
-
-  /* Unfortunately fchmod does not work on all platforms, we will use chmod. */
-  name_len = 0;
-  r = uv_pipe_getsockname(handle, NULL, &name_len);
-  if (r != UV_ENOBUFS)
-    return r;
-
-  name_buffer = (char*)uv__malloc(name_len);
-  if (name_buffer == NULL)
-    return UV_ENOMEM;
-
-  r = uv_pipe_getsockname(handle, name_buffer, &name_len);
-  if (r != 0) {
-    uv__free(name_buffer);
-    return r;
-  }
-
-  /* stat must be used as fstat has a bug on Darwin */
-  if (stat(name_buffer, &pipe_stat) == -1) {
-    uv__free(name_buffer);
-    return -errno;
-  }
-
-  desired_mode = 0;
-  if (mode & UV_READABLE)
-    desired_mode |= S_IRUSR | S_IRGRP | S_IROTH;
-  if (mode & UV_WRITABLE)
-    desired_mode |= S_IWUSR | S_IWGRP | S_IWOTH;
-
-  /* Exit early if pipe already has desired mode. */
-  if ((pipe_stat.st_mode & desired_mode) == desired_mode) {
-    uv__free(name_buffer);
-    return 0;
-  }
-
-  pipe_stat.st_mode |= desired_mode;
-
-  r = chmod(name_buffer, pipe_stat.st_mode);
-  uv__free(name_buffer);
-
-  return r != -1 ? 0 : UV__ERR(errno);
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/poll.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/poll.cpp
deleted file mode 100644
index d578611..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/poll.cpp
+++ /dev/null
@@ -1,151 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include "uv.h"
-#include "internal.h"
-
-#include <unistd.h>
-#include <assert.h>
-#include <errno.h>
-
-
-static void uv__poll_io(uv_loop_t* loop, uv__io_t* w, unsigned int events) {
-  uv_poll_t* handle;
-  int pevents;
-
-  handle = container_of(w, uv_poll_t, io_watcher);
-
-  /*
-   * As documented in the kernel source fs/kernfs/file.c #780
-   * poll will return POLLERR|POLLPRI in case of sysfs
-   * polling. This does not happen in case of out-of-band
-   * TCP messages.
-   *
-   * The above is the case on (at least) FreeBSD and Linux.
-   *
-   * So to properly determine a POLLPRI or a POLLERR we need
-   * to check for both.
-   */
-  if ((events & POLLERR) && !(events & UV__POLLPRI)) {
-    uv__io_stop(loop, w, POLLIN | POLLOUT | UV__POLLRDHUP | UV__POLLPRI);
-    uv__handle_stop(handle);
-    handle->poll_cb(handle, UV_EBADF, 0);
-    return;
-  }
-
-  pevents = 0;
-  if (events & POLLIN)
-    pevents |= UV_READABLE;
-  if (events & UV__POLLPRI)
-    pevents |= UV_PRIORITIZED;
-  if (events & POLLOUT)
-    pevents |= UV_WRITABLE;
-  if (events & UV__POLLRDHUP)
-    pevents |= UV_DISCONNECT;
-
-  handle->poll_cb(handle, 0, pevents);
-}
-
-
-int uv_poll_init(uv_loop_t* loop, uv_poll_t* handle, int fd) {
-  int err;
-
-  if (uv__fd_exists(loop, fd))
-    return UV_EEXIST;
-
-  err = uv__io_check_fd(loop, fd);
-  if (err)
-    return err;
-
-  /* If ioctl(FIONBIO) reports ENOTTY, try fcntl(F_GETFL) + fcntl(F_SETFL).
-   * Workaround for e.g. kqueue fds not supporting ioctls.
-   */
-  err = uv__nonblock(fd, 1);
-#ifdef UV__NONBLOCK_IS_IOCTL
-  if (err == UV_ENOTTY)
-    err = uv__nonblock_fcntl(fd, 1);
-#endif
-
-  if (err)
-    return err;
-
-  uv__handle_init(loop, (uv_handle_t*) handle, UV_POLL);
-  uv__io_init(&handle->io_watcher, uv__poll_io, fd);
-  handle->poll_cb = NULL;
-  return 0;
-}
-
-
-int uv_poll_init_socket(uv_loop_t* loop, uv_poll_t* handle,
-    uv_os_sock_t socket) {
-  return uv_poll_init(loop, handle, socket);
-}
-
-
-static void uv__poll_stop(uv_poll_t* handle) {
-  uv__io_stop(handle->loop,
-              &handle->io_watcher,
-              POLLIN | POLLOUT | UV__POLLRDHUP | UV__POLLPRI);
-  uv__handle_stop(handle);
-  uv__platform_invalidate_fd(handle->loop, handle->io_watcher.fd);
-}
-
-
-int uv_poll_stop(uv_poll_t* handle) {
-  assert(!uv__is_closing(handle));
-  uv__poll_stop(handle);
-  return 0;
-}
-
-
-int uv_poll_start(uv_poll_t* handle, int pevents, uv_poll_cb poll_cb) {
-  int events;
-
-  assert((pevents & ~(UV_READABLE | UV_WRITABLE | UV_DISCONNECT |
-                      UV_PRIORITIZED)) == 0);
-  assert(!uv__is_closing(handle));
-
-  uv__poll_stop(handle);
-
-  if (pevents == 0)
-    return 0;
-
-  events = 0;
-  if (pevents & UV_READABLE)
-    events |= POLLIN;
-  if (pevents & UV_PRIORITIZED)
-    events |= UV__POLLPRI;
-  if (pevents & UV_WRITABLE)
-    events |= POLLOUT;
-  if (pevents & UV_DISCONNECT)
-    events |= UV__POLLRDHUP;
-
-  uv__io_start(handle->loop, &handle->io_watcher, events);
-  uv__handle_start(handle);
-  handle->poll_cb = poll_cb;
-
-  return 0;
-}
-
-
-void uv__poll_close(uv_poll_t* handle) {
-  uv__poll_stop(handle);
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/posix-poll.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/posix-poll.cpp
deleted file mode 100644
index b932f91..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/posix-poll.cpp
+++ /dev/null
@@ -1,336 +0,0 @@
-/* Copyright libuv project contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include "uv.h"
-#include "internal.h"
-
-/* POSIX defines poll() as a portable way to wait on file descriptors.
- * Here we maintain a dynamically sized array of file descriptors and
- * events to pass as the first argument to poll().
- */
-
-#include <assert.h>
-#include <stddef.h>
-#include <stdint.h>
-#include <errno.h>
-#include <unistd.h>
-
-int uv__platform_loop_init(uv_loop_t* loop) {
-  loop->poll_fds = NULL;
-  loop->poll_fds_used = 0;
-  loop->poll_fds_size = 0;
-  loop->poll_fds_iterating = 0;
-  return 0;
-}
-
-void uv__platform_loop_delete(uv_loop_t* loop) {
-  uv__free(loop->poll_fds);
-  loop->poll_fds = NULL;
-}
-
-int uv__io_fork(uv_loop_t* loop) {
-  uv__platform_loop_delete(loop);
-  return uv__platform_loop_init(loop);
-}
-
-/* Allocate or dynamically resize our poll fds array.  */
-static void uv__pollfds_maybe_resize(uv_loop_t* loop) {
-  size_t i;
-  size_t n;
-  struct pollfd* p;
-
-  if (loop->poll_fds_used < loop->poll_fds_size)
-    return;
-
-  n = loop->poll_fds_size ? loop->poll_fds_size * 2 : 64;
-  p = (struct pollfd*)uv__realloc(loop->poll_fds, n * sizeof(*loop->poll_fds));
-  if (p == NULL)
-    abort();
-
-  loop->poll_fds = p;
-  for (i = loop->poll_fds_size; i < n; i++) {
-    loop->poll_fds[i].fd = -1;
-    loop->poll_fds[i].events = 0;
-    loop->poll_fds[i].revents = 0;
-  }
-  loop->poll_fds_size = n;
-}
-
-/* Primitive swap operation on poll fds array elements.  */
-static void uv__pollfds_swap(uv_loop_t* loop, size_t l, size_t r) {
-  struct pollfd pfd;
-  pfd = loop->poll_fds[l];
-  loop->poll_fds[l] = loop->poll_fds[r];
-  loop->poll_fds[r] = pfd;
-}
-
-/* Add a watcher's fd to our poll fds array with its pending events.  */
-static void uv__pollfds_add(uv_loop_t* loop, uv__io_t* w) {
-  size_t i;
-  struct pollfd* pe;
-
-  /* If the fd is already in the set just update its events.  */
-  assert(!loop->poll_fds_iterating);
-  for (i = 0; i < loop->poll_fds_used; ++i) {
-    if (loop->poll_fds[i].fd == w->fd) {
-      loop->poll_fds[i].events = w->pevents;
-      return;
-    }
-  }
-
-  /* Otherwise, allocate a new slot in the set for the fd.  */
-  uv__pollfds_maybe_resize(loop);
-  pe = &loop->poll_fds[loop->poll_fds_used++];
-  pe->fd = w->fd;
-  pe->events = w->pevents;
-}
-
-/* Remove a watcher's fd from our poll fds array.  */
-static void uv__pollfds_del(uv_loop_t* loop, int fd) {
-  size_t i;
-  assert(!loop->poll_fds_iterating);
-  for (i = 0; i < loop->poll_fds_used;) {
-    if (loop->poll_fds[i].fd == fd) {
-      /* swap to last position and remove */
-      --loop->poll_fds_used;
-      uv__pollfds_swap(loop, i, loop->poll_fds_used);
-      loop->poll_fds[loop->poll_fds_used].fd = -1;
-      loop->poll_fds[loop->poll_fds_used].events = 0;
-      loop->poll_fds[loop->poll_fds_used].revents = 0;
-      /* This method is called with an fd of -1 to purge the invalidated fds,
-       * so we may possibly have multiples to remove.
-       */
-      if (-1 != fd)
-        return;
-    } else {
-      /* We must only increment the loop counter when the fds do not match.
-       * Otherwise, when we are purging an invalidated fd, the value just
-       * swapped here from the previous end of the array will be skipped.
-       */
-       ++i;
-    }
-  }
-}
-
-
-void uv__io_poll(uv_loop_t* loop, int timeout) {
-  sigset_t* pset;
-  sigset_t set;
-  uint64_t time_base;
-  uint64_t time_diff;
-  QUEUE* q;
-  uv__io_t* w;
-  size_t i;
-  unsigned int nevents;
-  int nfds;
-  int have_signals;
-  struct pollfd* pe;
-  int fd;
-
-  if (loop->nfds == 0) {
-    assert(QUEUE_EMPTY(&loop->watcher_queue));
-    return;
-  }
-
-  /* Take queued watchers and add their fds to our poll fds array.  */
-  while (!QUEUE_EMPTY(&loop->watcher_queue)) {
-    q = QUEUE_HEAD(&loop->watcher_queue);
-    QUEUE_REMOVE(q);
-    QUEUE_INIT(q);
-
-    w = QUEUE_DATA(q, uv__io_t, watcher_queue);
-    assert(w->pevents != 0);
-    assert(w->fd >= 0);
-    assert(w->fd < (int) loop->nwatchers);
-
-    uv__pollfds_add(loop, w);
-
-    w->events = w->pevents;
-  }
-
-  /* Prepare a set of signals to block around poll(), if any.  */
-  pset = NULL;
-  if (loop->flags & UV_LOOP_BLOCK_SIGPROF) {
-    pset = &set;
-    sigemptyset(pset);
-    sigaddset(pset, SIGPROF);
-  }
-
-  assert(timeout >= -1);
-  time_base = loop->time;
-
-  /* Loop calls to poll() and processing of results.  If we get some
-   * results from poll() but they turn out not to be interesting to
-   * our caller then we need to loop around and poll() again.
-   */
-  for (;;) {
-    if (pset != NULL)
-      if (pthread_sigmask(SIG_BLOCK, pset, NULL))
-        abort();
-    nfds = poll(loop->poll_fds, (nfds_t)loop->poll_fds_used, timeout);
-    if (pset != NULL)
-      if (pthread_sigmask(SIG_UNBLOCK, pset, NULL))
-        abort();
-
-    /* Update loop->time unconditionally. It's tempting to skip the update when
-     * timeout == 0 (i.e. non-blocking poll) but there is no guarantee that the
-     * operating system didn't reschedule our process while in the syscall.
-     */
-    SAVE_ERRNO(uv__update_time(loop));
-
-    if (nfds == 0) {
-      assert(timeout != -1);
-      return;
-    }
-
-    if (nfds == -1) {
-      if (errno != EINTR)
-        abort();
-
-      if (timeout == -1)
-        continue;
-
-      if (timeout == 0)
-        return;
-
-      /* Interrupted by a signal. Update timeout and poll again. */
-      goto update_timeout;
-    }
-
-    /* Tell uv__platform_invalidate_fd not to manipulate our array
-     * while we are iterating over it.
-     */
-    loop->poll_fds_iterating = 1;
-
-    /* Initialize a count of events that we care about.  */
-    nevents = 0;
-    have_signals = 0;
-
-    /* Loop over the entire poll fds array looking for returned events.  */
-    for (i = 0; i < loop->poll_fds_used; i++) {
-      pe = loop->poll_fds + i;
-      fd = pe->fd;
-
-      /* Skip invalidated events, see uv__platform_invalidate_fd.  */
-      if (fd == -1)
-        continue;
-
-      assert(fd >= 0);
-      assert((unsigned) fd < loop->nwatchers);
-
-      w = loop->watchers[fd];
-
-      if (w == NULL) {
-        /* File descriptor that we've stopped watching, ignore.  */
-        uv__platform_invalidate_fd(loop, fd);
-        continue;
-      }
-
-      /* Filter out events that user has not requested us to watch
-       * (e.g. POLLNVAL).
-       */
-      pe->revents &= w->pevents | POLLERR | POLLHUP;
-
-      if (pe->revents != 0) {
-        /* Run signal watchers last.  */
-        if (w == &loop->signal_io_watcher) {
-          have_signals = 1;
-        } else {
-          w->cb(loop, w, pe->revents);
-        }
-
-        nevents++;
-      }
-    }
-
-    if (have_signals != 0)
-      loop->signal_io_watcher.cb(loop, &loop->signal_io_watcher, POLLIN);
-
-    loop->poll_fds_iterating = 0;
-
-    /* Purge invalidated fds from our poll fds array.  */
-    uv__pollfds_del(loop, -1);
-
-    if (have_signals != 0)
-      return;  /* Event loop should cycle now so don't poll again. */
-
-    if (nevents != 0)
-      return;
-
-    if (timeout == 0)
-      return;
-
-    if (timeout == -1)
-      continue;
-
-update_timeout:
-    assert(timeout > 0);
-
-    time_diff = loop->time - time_base;
-    if (time_diff >= (uint64_t) timeout)
-      return;
-
-    timeout -= time_diff;
-  }
-}
-
-/* Remove the given fd from our poll fds array because no one
- * is interested in its events anymore.
- */
-void uv__platform_invalidate_fd(uv_loop_t* loop, int fd) {
-  size_t i;
-
-  assert(fd >= 0);
-
-  if (loop->poll_fds_iterating) {
-    /* uv__io_poll is currently iterating.  Just invalidate fd.  */
-    for (i = 0; i < loop->poll_fds_used; i++)
-      if (loop->poll_fds[i].fd == fd) {
-        loop->poll_fds[i].fd = -1;
-        loop->poll_fds[i].events = 0;
-        loop->poll_fds[i].revents = 0;
-      }
-  } else {
-    /* uv__io_poll is not iterating.  Delete fd from the set.  */
-    uv__pollfds_del(loop, fd);
-  }
-}
-
-/* Check whether the given fd is supported by poll().  */
-int uv__io_check_fd(uv_loop_t* loop, int fd) {
-  struct pollfd p[1];
-  int rv;
-
-  p[0].fd = fd;
-  p[0].events = POLLIN;
-
-  do
-    rv = poll(p, 1, 0);
-  while (rv == -1 && (errno == EINTR || errno == EAGAIN));
-
-  if (rv == -1)
-    return UV__ERR(errno);
-
-  if (p[0].revents & POLLNVAL)
-    return UV_EINVAL;
-
-  return 0;
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/process.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/process.cpp
deleted file mode 100644
index 87dac7f..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/process.cpp
+++ /dev/null
@@ -1,603 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include "uv.h"
-#include "internal.h"
-
-#include <stdio.h>
-#include <stdlib.h>
-#include <assert.h>
-#include <errno.h>
-
-#include <sys/types.h>
-#include <sys/wait.h>
-#include <unistd.h>
-#include <fcntl.h>
-#include <poll.h>
-
-#if defined(__APPLE__) && !TARGET_OS_IPHONE
-# include <crt_externs.h>
-# define environ (*_NSGetEnviron())
-#else
-extern char **environ;
-#endif
-
-#if defined(__linux__) || defined(__GLIBC__)
-# include <grp.h>
-#endif
-
-
-static void uv__chld(uv_signal_t* handle, int signum) {
-  uv_process_t* process;
-  uv_loop_t* loop;
-  int exit_status;
-  int term_signal;
-  int status;
-  pid_t pid;
-  QUEUE pending;
-  QUEUE* q;
-  QUEUE* h;
-
-  assert(signum == SIGCHLD);
-
-  QUEUE_INIT(&pending);
-  loop = handle->loop;
-
-  h = &loop->process_handles;
-  q = QUEUE_HEAD(h);
-  while (q != h) {
-    process = QUEUE_DATA(q, uv_process_t, queue);
-    q = QUEUE_NEXT(q);
-
-    do
-      pid = waitpid(process->pid, &status, WNOHANG);
-    while (pid == -1 && errno == EINTR);
-
-    if (pid == 0)
-      continue;
-
-    if (pid == -1) {
-      if (errno != ECHILD)
-        abort();
-      continue;
-    }
-
-    process->status = status;
-    QUEUE_REMOVE(&process->queue);
-    QUEUE_INSERT_TAIL(&pending, &process->queue);
-  }
-
-  h = &pending;
-  q = QUEUE_HEAD(h);
-  while (q != h) {
-    process = QUEUE_DATA(q, uv_process_t, queue);
-    q = QUEUE_NEXT(q);
-
-    QUEUE_REMOVE(&process->queue);
-    QUEUE_INIT(&process->queue);
-    uv__handle_stop(process);
-
-    if (process->exit_cb == NULL)
-      continue;
-
-    exit_status = 0;
-    if (WIFEXITED(process->status))
-      exit_status = WEXITSTATUS(process->status);
-
-    term_signal = 0;
-    if (WIFSIGNALED(process->status))
-      term_signal = WTERMSIG(process->status);
-
-    process->exit_cb(process, exit_status, term_signal);
-  }
-  assert(QUEUE_EMPTY(&pending));
-}
-
-
-int uv__make_socketpair(int fds[2], int flags) {
-#if defined(__linux__)
-  static int no_cloexec;
-
-  if (no_cloexec)
-    goto skip;
-
-  if (socketpair(AF_UNIX, SOCK_STREAM | UV__SOCK_CLOEXEC | flags, 0, fds) == 0)
-    return 0;
-
-  /* Retry on EINVAL, it means SOCK_CLOEXEC is not supported.
-   * Anything else is a genuine error.
-   */
-  if (errno != EINVAL)
-    return UV__ERR(errno);
-
-  no_cloexec = 1;
-
-skip:
-#endif
-
-  if (socketpair(AF_UNIX, SOCK_STREAM, 0, fds))
-    return UV__ERR(errno);
-
-  uv__cloexec(fds[0], 1);
-  uv__cloexec(fds[1], 1);
-
-  if (flags & UV__F_NONBLOCK) {
-    uv__nonblock(fds[0], 1);
-    uv__nonblock(fds[1], 1);
-  }
-
-  return 0;
-}
-
-
-int uv__make_pipe(int fds[2], int flags) {
-#if defined(__linux__)
-  static int no_pipe2;
-
-  if (no_pipe2)
-    goto skip;
-
-  if (uv__pipe2(fds, flags | UV__O_CLOEXEC) == 0)
-    return 0;
-
-  if (errno != ENOSYS)
-    return UV__ERR(errno);
-
-  no_pipe2 = 1;
-
-skip:
-#endif
-
-  if (pipe(fds))
-    return UV__ERR(errno);
-
-  uv__cloexec(fds[0], 1);
-  uv__cloexec(fds[1], 1);
-
-  if (flags & UV__F_NONBLOCK) {
-    uv__nonblock(fds[0], 1);
-    uv__nonblock(fds[1], 1);
-  }
-
-  return 0;
-}
-
-
-/*
- * Used for initializing stdio streams like options.stdin_stream. Returns
- * zero on success. See also the cleanup section in uv_spawn().
- */
-static int uv__process_init_stdio(uv_stdio_container_t* container, int fds[2]) {
-  int mask;
-  int fd;
-
-  mask = UV_IGNORE | UV_CREATE_PIPE | UV_INHERIT_FD | UV_INHERIT_STREAM;
-
-  switch (container->flags & mask) {
-  case UV_IGNORE:
-    return 0;
-
-  case UV_CREATE_PIPE:
-    assert(container->data.stream != NULL);
-    if (container->data.stream->type != UV_NAMED_PIPE)
-      return UV_EINVAL;
-    else
-      return uv__make_socketpair(fds, 0);
-
-  case UV_INHERIT_FD:
-  case UV_INHERIT_STREAM:
-    if (container->flags & UV_INHERIT_FD)
-      fd = container->data.fd;
-    else
-      fd = uv__stream_fd(container->data.stream);
-
-    if (fd == -1)
-      return UV_EINVAL;
-
-    fds[1] = fd;
-    return 0;
-
-  default:
-    assert(0 && "Unexpected flags");
-    return UV_EINVAL;
-  }
-}
-
-
-static int uv__process_open_stream(uv_stdio_container_t* container,
-                                   int pipefds[2]) {
-  int flags;
-  int err;
-
-  if (!(container->flags & UV_CREATE_PIPE) || pipefds[0] < 0)
-    return 0;
-
-  err = uv__close(pipefds[1]);
-  if (err != 0)
-    abort();
-
-  pipefds[1] = -1;
-  uv__nonblock(pipefds[0], 1);
-
-  flags = 0;
-  if (container->flags & UV_WRITABLE_PIPE)
-    flags |= UV_HANDLE_READABLE;
-  if (container->flags & UV_READABLE_PIPE)
-    flags |= UV_HANDLE_WRITABLE;
-
-  return uv__stream_open(container->data.stream, pipefds[0], flags);
-}
-
-
-static void uv__process_close_stream(uv_stdio_container_t* container) {
-  if (!(container->flags & UV_CREATE_PIPE)) return;
-  uv__stream_close(container->data.stream);
-}
-
-
-static void uv__write_int(int fd, int val) {
-  ssize_t n;
-
-  do
-    n = write(fd, &val, sizeof(val));
-  while (n == -1 && errno == EINTR);
-
-  if (n == -1 && errno == EPIPE)
-    return; /* parent process has quit */
-
-  assert(n == sizeof(val));
-}
-
-
-#if !(defined(__APPLE__) && (TARGET_OS_TV || TARGET_OS_WATCH))
-/* execvp is marked __WATCHOS_PROHIBITED __TVOS_PROHIBITED, so must be
- * avoided. Since this isn't called on those targets, the function
- * doesn't even need to be defined for them.
- */
-static void uv__process_child_init(const uv_process_options_t* options,
-                                   int stdio_count,
-                                   int (*pipes)[2],
-                                   int error_fd) {
-  sigset_t set;
-  int close_fd;
-  int use_fd;
-  int err;
-  int fd;
-  int n;
-
-  if (options->flags & UV_PROCESS_DETACHED)
-    setsid();
-
-  /* First duplicate low numbered fds, since it's not safe to duplicate them,
-   * they could get replaced. Example: swapping stdout and stderr; without
-   * this fd 2 (stderr) would be duplicated into fd 1, thus making both
-   * stdout and stderr go to the same fd, which was not the intention. */
-  for (fd = 0; fd < stdio_count; fd++) {
-    use_fd = pipes[fd][1];
-    if (use_fd < 0 || use_fd >= fd)
-      continue;
-    pipes[fd][1] = fcntl(use_fd, F_DUPFD, stdio_count);
-    if (pipes[fd][1] == -1) {
-      uv__write_int(error_fd, UV__ERR(errno));
-      _exit(127);
-    }
-  }
-
-  for (fd = 0; fd < stdio_count; fd++) {
-    close_fd = pipes[fd][0];
-    use_fd = pipes[fd][1];
-
-    if (use_fd < 0) {
-      if (fd >= 3)
-        continue;
-      else {
-        /* redirect stdin, stdout and stderr to /dev/null even if UV_IGNORE is
-         * set
-         */
-        use_fd = open("/dev/null", fd == 0 ? O_RDONLY : O_RDWR);
-        close_fd = use_fd;
-
-        if (use_fd < 0) {
-          uv__write_int(error_fd, UV__ERR(errno));
-          _exit(127);
-        }
-      }
-    }
-
-    if (fd == use_fd)
-      uv__cloexec_fcntl(use_fd, 0);
-    else
-      fd = dup2(use_fd, fd);
-
-    if (fd == -1) {
-      uv__write_int(error_fd, UV__ERR(errno));
-      _exit(127);
-    }
-
-    if (fd <= 2)
-      uv__nonblock_fcntl(fd, 0);
-
-    if (close_fd >= stdio_count)
-      uv__close(close_fd);
-  }
-
-  for (fd = 0; fd < stdio_count; fd++) {
-    use_fd = pipes[fd][1];
-
-    if (use_fd >= stdio_count)
-      uv__close(use_fd);
-  }
-
-  if (options->cwd != NULL && chdir(options->cwd)) {
-    uv__write_int(error_fd, UV__ERR(errno));
-    _exit(127);
-  }
-
-  if (options->flags & (UV_PROCESS_SETUID | UV_PROCESS_SETGID)) {
-    /* When dropping privileges from root, the `setgroups` call will
-     * remove any extraneous groups. If we don't call this, then
-     * even though our uid has dropped, we may still have groups
-     * that enable us to do super-user things. This will fail if we
-     * aren't root, so don't bother checking the return value, this
-     * is just done as an optimistic privilege dropping function.
-     */
-    SAVE_ERRNO(setgroups(0, NULL));
-  }
-
-  if ((options->flags & UV_PROCESS_SETGID) && setgid(options->gid)) {
-    uv__write_int(error_fd, UV__ERR(errno));
-    _exit(127);
-  }
-
-  if ((options->flags & UV_PROCESS_SETUID) && setuid(options->uid)) {
-    uv__write_int(error_fd, UV__ERR(errno));
-    _exit(127);
-  }
-
-  if (options->env != NULL) {
-    environ = options->env;
-  }
-
-  /* Reset signal disposition.  Use a hard-coded limit because NSIG
-   * is not fixed on Linux: it's either 32, 34 or 64, depending on
-   * whether RT signals are enabled.  We are not allowed to touch
-   * RT signal handlers, glibc uses them internally.
-   */
-  for (n = 1; n < 32; n += 1) {
-    if (n == SIGKILL || n == SIGSTOP)
-      continue;  /* Can't be changed. */
-
-#if defined(__HAIKU__)
-    if (n == SIGKILLTHR)
-      continue;  /* Can't be changed. */
-#endif
-
-    if (SIG_ERR != signal(n, SIG_DFL))
-      continue;
-
-    uv__write_int(error_fd, UV__ERR(errno));
-    _exit(127);
-  }
-
-  /* Reset signal mask. */
-  sigemptyset(&set);
-  err = pthread_sigmask(SIG_SETMASK, &set, NULL);
-
-  if (err != 0) {
-    uv__write_int(error_fd, UV__ERR(err));
-    _exit(127);
-  }
-
-  execvp(options->file, options->args);
-  uv__write_int(error_fd, UV__ERR(errno));
-  _exit(127);
-}
-#endif
-
-
-int uv_spawn(uv_loop_t* loop,
-             uv_process_t* process,
-             const uv_process_options_t* options) {
-#if defined(__APPLE__) && (TARGET_OS_TV || TARGET_OS_WATCH)
-  /* fork is marked __WATCHOS_PROHIBITED __TVOS_PROHIBITED. */
-  return UV_ENOSYS;
-#else
-  int signal_pipe[2] = { -1, -1 };
-  int pipes_storage[8][2];
-  int (*pipes)[2];
-  int stdio_count;
-  ssize_t r;
-  pid_t pid;
-  int err;
-  int exec_errorno;
-  int i;
-  int status;
-
-  assert(options->file != NULL);
-  assert(!(options->flags & ~(UV_PROCESS_DETACHED |
-                              UV_PROCESS_SETGID |
-                              UV_PROCESS_SETUID |
-                              UV_PROCESS_WINDOWS_HIDE |
-                              UV_PROCESS_WINDOWS_HIDE_CONSOLE |
-                              UV_PROCESS_WINDOWS_HIDE_GUI |
-                              UV_PROCESS_WINDOWS_VERBATIM_ARGUMENTS)));
-
-  uv__handle_init(loop, (uv_handle_t*)process, UV_PROCESS);
-  QUEUE_INIT(&process->queue);
-
-  stdio_count = options->stdio_count;
-  if (stdio_count < 3)
-    stdio_count = 3;
-
-  err = UV_ENOMEM;
-  pipes = pipes_storage;
-  if (stdio_count > (int) ARRAY_SIZE(pipes_storage))
-    pipes = (int (*)[2])uv__malloc(stdio_count * sizeof(*pipes));
-
-  if (pipes == NULL)
-    goto error;
-
-  for (i = 0; i < stdio_count; i++) {
-    pipes[i][0] = -1;
-    pipes[i][1] = -1;
-  }
-
-  for (i = 0; i < options->stdio_count; i++) {
-    err = uv__process_init_stdio(options->stdio + i, pipes[i]);
-    if (err)
-      goto error;
-  }
-
-  /* This pipe is used by the parent to wait until
-   * the child has called `execve()`. We need this
-   * to avoid the following race condition:
-   *
-   *    if ((pid = fork()) > 0) {
-   *      kill(pid, SIGTERM);
-   *    }
-   *    else if (pid == 0) {
-   *      execve("/bin/cat", argp, envp);
-   *    }
-   *
-   * The parent sends a signal immediately after forking.
-   * Since the child may not have called `execve()` yet,
-   * there is no telling what process receives the signal,
-   * our fork or /bin/cat.
-   *
-   * To avoid ambiguity, we create a pipe with both ends
-   * marked close-on-exec. Then, after the call to `fork()`,
-   * the parent polls the read end until it EOFs or errors with EPIPE.
-   */
-  err = uv__make_pipe(signal_pipe, 0);
-  if (err)
-    goto error;
-
-  uv_signal_start(&loop->child_watcher, uv__chld, SIGCHLD);
-
-  /* Acquire write lock to prevent opening new fds in worker threads */
-  uv_rwlock_wrlock(&loop->cloexec_lock);
-  pid = fork();
-
-  if (pid == -1) {
-    err = UV__ERR(errno);
-    uv_rwlock_wrunlock(&loop->cloexec_lock);
-    uv__close(signal_pipe[0]);
-    uv__close(signal_pipe[1]);
-    goto error;
-  }
-
-  if (pid == 0) {
-    uv__process_child_init(options, stdio_count, pipes, signal_pipe[1]);
-    abort();
-  }
-
-  /* Release lock in parent process */
-  uv_rwlock_wrunlock(&loop->cloexec_lock);
-  uv__close(signal_pipe[1]);
-
-  process->status = 0;
-  exec_errorno = 0;
-  do
-    r = read(signal_pipe[0], &exec_errorno, sizeof(exec_errorno));
-  while (r == -1 && errno == EINTR);
-
-  if (r == 0)
-    ; /* okay, EOF */
-  else if (r == sizeof(exec_errorno)) {
-    do
-      err = waitpid(pid, &status, 0); /* okay, read errorno */
-    while (err == -1 && errno == EINTR);
-    assert(err == pid);
-  } else if (r == -1 && errno == EPIPE) {
-    do
-      err = waitpid(pid, &status, 0); /* okay, got EPIPE */
-    while (err == -1 && errno == EINTR);
-    assert(err == pid);
-  } else
-    abort();
-
-  uv__close_nocheckstdio(signal_pipe[0]);
-
-  for (i = 0; i < options->stdio_count; i++) {
-    err = uv__process_open_stream(options->stdio + i, pipes[i]);
-    if (err == 0)
-      continue;
-
-    while (i--)
-      uv__process_close_stream(options->stdio + i);
-
-    goto error;
-  }
-
-  /* Only activate this handle if exec() happened successfully */
-  if (exec_errorno == 0) {
-    QUEUE_INSERT_TAIL(&loop->process_handles, &process->queue);
-    uv__handle_start(process);
-  }
-
-  process->pid = pid;
-  process->exit_cb = options->exit_cb;
-
-  if (pipes != pipes_storage)
-    uv__free(pipes);
-
-  return exec_errorno;
-
-error:
-  if (pipes != NULL) {
-    for (i = 0; i < stdio_count; i++) {
-      if (i < options->stdio_count)
-        if (options->stdio[i].flags & (UV_INHERIT_FD | UV_INHERIT_STREAM))
-          continue;
-      if (pipes[i][0] != -1)
-        uv__close_nocheckstdio(pipes[i][0]);
-      if (pipes[i][1] != -1)
-        uv__close_nocheckstdio(pipes[i][1]);
-    }
-
-    if (pipes != pipes_storage)
-      uv__free(pipes);
-  }
-
-  return err;
-#endif
-}
-
-
-int uv_process_kill(uv_process_t* process, int signum) {
-  return uv_kill(process->pid, signum);
-}
-
-
-int uv_kill(int pid, int signum) {
-  if (kill(pid, signum))
-    return UV__ERR(errno);
-  else
-    return 0;
-}
-
-
-void uv__process_close(uv_process_t* handle) {
-  QUEUE_REMOVE(&handle->queue);
-  uv__handle_stop(handle);
-  if (QUEUE_EMPTY(&handle->loop->process_handles))
-    uv_signal_stop(&handle->loop->child_watcher);
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/proctitle.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/proctitle.cpp
deleted file mode 100644
index b09808f..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/proctitle.cpp
+++ /dev/null
@@ -1,136 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include "uv.h"
-#include "internal.h"
-
-#include <stdlib.h>
-#include <string.h>
-
-extern void uv__set_process_title_platform_init(void);
-extern void uv__set_process_title(const char* title);
-
-static uv_mutex_t process_title_mutex;
-static uv_once_t process_title_mutex_once = UV_ONCE_INIT;
-static void* args_mem;
-
-static struct {
-  char* str;
-  size_t len;
-} process_title;
-
-
-static void init_process_title_mutex_once(void) {
-  uv_mutex_init(&process_title_mutex);
-#ifdef __APPLE__
-  uv__set_process_title_platform_init();
-#endif
-}
-
-
-char** uv_setup_args(int argc, char** argv) {
-  char** new_argv;
-  size_t size;
-  char* s;
-  int i;
-
-  if (argc <= 0)
-    return argv;
-
-  /* Calculate how much memory we need for the argv strings. */
-  size = 0;
-  for (i = 0; i < argc; i++)
-    size += strlen(argv[i]) + 1;
-
-#if defined(__MVS__)
-  /* argv is not adjacent. So just use argv[0] */
-  process_title.str = argv[0];
-  process_title.len = strlen(argv[0]);
-#else
-  process_title.str = argv[0];
-  process_title.len = argv[argc - 1] + strlen(argv[argc - 1]) - argv[0];
-  assert(process_title.len + 1 == size);  /* argv memory should be adjacent. */
-#endif
-
-  /* Add space for the argv pointers. */
-  size += (argc + 1) * sizeof(char*);
-
-  new_argv = (char**)uv__malloc(size);
-  if (new_argv == NULL)
-    return argv;
-  args_mem = new_argv;
-
-  /* Copy over the strings and set up the pointer table. */
-  s = (char*) &new_argv[argc + 1];
-  for (i = 0; i < argc; i++) {
-    size = strlen(argv[i]) + 1;
-    memcpy(s, argv[i], size);
-    new_argv[i] = s;
-    s += size;
-  }
-  new_argv[i] = NULL;
-
-  return new_argv;
-}
-
-
-int uv_set_process_title(const char* title) {
-  uv_once(&process_title_mutex_once, init_process_title_mutex_once);
-  uv_mutex_lock(&process_title_mutex);
-
-  if (process_title.len != 0) {
-    /* No need to terminate, byte after is always '\0'. */
-    strncpy(process_title.str, title, process_title.len);
-    uv__set_process_title(title);
-  }
-
-  uv_mutex_unlock(&process_title_mutex);
-
-  return 0;
-}
-
-
-int uv_get_process_title(char* buffer, size_t size) {
-  if (buffer == NULL || size == 0)
-    return UV_EINVAL;
-
-  uv_once(&process_title_mutex_once, init_process_title_mutex_once);
-  uv_mutex_lock(&process_title_mutex);
-
-  if (size <= process_title.len) {
-    uv_mutex_unlock(&process_title_mutex);
-    return UV_ENOBUFS;
-  }
-
-  if (process_title.len != 0)
-    memcpy(buffer, process_title.str, process_title.len + 1);
-
-  buffer[process_title.len] = '\0';
-
-  uv_mutex_unlock(&process_title_mutex);
-
-  return 0;
-}
-
-
-UV_DESTRUCTOR(static void free_args_mem(void)) {
-  uv__free(args_mem);  /* Keep valgrind happy. */
-  args_mem = NULL;
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/pthread-fixes.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/pthread-fixes.cpp
deleted file mode 100644
index fb17995..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/pthread-fixes.cpp
+++ /dev/null
@@ -1,56 +0,0 @@
-/* Copyright (c) 2013, Sony Mobile Communications AB
- * Copyright (c) 2012, Google Inc.
-   All rights reserved.
-
-   Redistribution and use in source and binary forms, with or without
-   modification, are permitted provided that the following conditions are
-   met:
-
-     * Redistributions of source code must retain the above copyright
-   notice, this list of conditions and the following disclaimer.
-       * Redistributions in binary form must reproduce the above
-   copyright notice, this list of conditions and the following disclaimer
-   in the documentation and/or other materials provided with the
-   distribution.
-       * Neither the name of Google Inc. nor the names of its
-   contributors may be used to endorse or promote products derived from
-   this software without specific prior written permission.
-
-   THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
-   "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
-   LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
-   A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
-   OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
-   SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
-   LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
-   DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
-   THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
-   (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
-   OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
-*/
-
-/* Android versions < 4.1 have a broken pthread_sigmask. */
-#include <errno.h>
-#include <pthread.h>
-#include <signal.h>
-
-int uv__pthread_sigmask(int how, const sigset_t* set, sigset_t* oset) {
-  static int workaround;
-  int err;
-
-  if (workaround) {
-    return sigprocmask(how, set, oset);
-  } else {
-    err = pthread_sigmask(how, set, oset);
-    if (err) {
-      if (err == EINVAL && sigprocmask(how, set, oset) == 0) {
-        workaround = 1;
-        return 0;
-      } else {
-        return -1;
-      }
-    }
-  }
-
-  return 0;
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/signal.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/signal.cpp
deleted file mode 100644
index ec2639a..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/signal.cpp
+++ /dev/null
@@ -1,574 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include "uv.h"
-#include "internal.h"
-
-#include <assert.h>
-#include <errno.h>
-#include <signal.h>
-#include <stdlib.h>
-#include <string.h>
-#include <unistd.h>
-
-#ifndef SA_RESTART
-# define SA_RESTART 0
-#endif
-
-typedef struct {
-  uv_signal_t* handle;
-  int signum;
-} uv__signal_msg_t;
-
-RB_HEAD(uv__signal_tree_s, uv_signal_s);
-
-
-static int uv__signal_unlock(void);
-static int uv__signal_start(uv_signal_t* handle,
-                            uv_signal_cb signal_cb,
-                            int signum,
-                            int oneshot);
-static void uv__signal_event(uv_loop_t* loop, uv__io_t* w, unsigned int events);
-static int uv__signal_compare(uv_signal_t* w1, uv_signal_t* w2);
-static void uv__signal_stop(uv_signal_t* handle);
-static void uv__signal_unregister_handler(int signum);
-
-
-static uv_once_t uv__signal_global_init_guard = UV_ONCE_INIT;
-static struct uv__signal_tree_s uv__signal_tree =
-    RB_INITIALIZER(uv__signal_tree);
-static int uv__signal_lock_pipefd[2] = { -1, -1 };
-
-RB_GENERATE_STATIC(uv__signal_tree_s,
-                   uv_signal_s, tree_entry,
-                   uv__signal_compare)
-
-static void uv__signal_global_reinit(void);
-
-static void uv__signal_global_init(void) {
-  if (uv__signal_lock_pipefd[0] == -1)
-    /* pthread_atfork can register before and after handlers, one
-     * for each child. This only registers one for the child. That
-     * state is both persistent and cumulative, so if we keep doing
-     * it the handler functions will be called multiple times. Thus
-     * we only want to do it once.
-     */
-    if (pthread_atfork(NULL, NULL, &uv__signal_global_reinit))
-      abort();
-
-  uv__signal_global_reinit();
-}
-
-
-UV_DESTRUCTOR(static void uv__signal_global_fini(void)) {
-  /* We can only use signal-safe functions here.
-   * That includes read/write and close, fortunately.
-   * We do all of this directly here instead of resetting
-   * uv__signal_global_init_guard because
-   * uv__signal_global_once_init is only called from uv_loop_init
-   * and this needs to function in existing loops.
-   */
-  if (uv__signal_lock_pipefd[0] != -1) {
-    uv__close(uv__signal_lock_pipefd[0]);
-    uv__signal_lock_pipefd[0] = -1;
-  }
-
-  if (uv__signal_lock_pipefd[1] != -1) {
-    uv__close(uv__signal_lock_pipefd[1]);
-    uv__signal_lock_pipefd[1] = -1;
-  }
-}
-
-
-static void uv__signal_global_reinit(void) {
-  uv__signal_global_fini();
-
-  if (uv__make_pipe(uv__signal_lock_pipefd, 0))
-    abort();
-
-  if (uv__signal_unlock())
-    abort();
-}
-
-
-void uv__signal_global_once_init(void) {
-  uv_once(&uv__signal_global_init_guard, uv__signal_global_init);
-}
-
-
-static int uv__signal_lock(void) {
-  int r;
-  char data;
-
-  do {
-    r = read(uv__signal_lock_pipefd[0], &data, sizeof data);
-  } while (r < 0 && errno == EINTR);
-
-  return (r < 0) ? -1 : 0;
-}
-
-
-static int uv__signal_unlock(void) {
-  int r;
-  char data = 42;
-
-  do {
-    r = write(uv__signal_lock_pipefd[1], &data, sizeof data);
-  } while (r < 0 && errno == EINTR);
-
-  return (r < 0) ? -1 : 0;
-}
-
-
-static void uv__signal_block_and_lock(sigset_t* saved_sigmask) {
-  sigset_t new_mask;
-
-  if (sigfillset(&new_mask))
-    abort();
-
-  if (pthread_sigmask(SIG_SETMASK, &new_mask, saved_sigmask))
-    abort();
-
-  if (uv__signal_lock())
-    abort();
-}
-
-
-static void uv__signal_unlock_and_unblock(sigset_t* saved_sigmask) {
-  if (uv__signal_unlock())
-    abort();
-
-  if (pthread_sigmask(SIG_SETMASK, saved_sigmask, NULL))
-    abort();
-}
-
-
-static uv_signal_t* uv__signal_first_handle(int signum) {
-  /* This function must be called with the signal lock held. */
-  uv_signal_t lookup;
-  uv_signal_t* handle;
-
-  lookup.signum = signum;
-  lookup.flags = 0;
-  lookup.loop = NULL;
-
-  handle = RB_NFIND(uv__signal_tree_s, &uv__signal_tree, &lookup);
-
-  if (handle != NULL && handle->signum == signum)
-    return handle;
-
-  return NULL;
-}
-
-
-static void uv__signal_handler(int signum) {
-  uv__signal_msg_t msg;
-  uv_signal_t* handle;
-  int saved_errno;
-
-  saved_errno = errno;
-  memset(&msg, 0, sizeof msg);
-
-  if (uv__signal_lock()) {
-    errno = saved_errno;
-    return;
-  }
-
-  for (handle = uv__signal_first_handle(signum);
-       handle != NULL && handle->signum == signum;
-       handle = RB_NEXT(uv__signal_tree_s, &uv__signal_tree, handle)) {
-    int r;
-
-    msg.signum = signum;
-    msg.handle = handle;
-
-    /* write() should be atomic for small data chunks, so the entire message
-     * should be written at once. In theory the pipe could become full, in
-     * which case the user is out of luck.
-     */
-    do {
-      r = write(handle->loop->signal_pipefd[1], &msg, sizeof msg);
-    } while (r == -1 && errno == EINTR);
-
-    assert(r == sizeof msg ||
-           (r == -1 && (errno == EAGAIN || errno == EWOULDBLOCK)));
-
-    if (r != -1)
-      handle->caught_signals++;
-  }
-
-  uv__signal_unlock();
-  errno = saved_errno;
-}
-
-
-static int uv__signal_register_handler(int signum, int oneshot) {
-  /* When this function is called, the signal lock must be held. */
-  struct sigaction sa;
-
-  /* XXX use a separate signal stack? */
-  memset(&sa, 0, sizeof(sa));
-  if (sigfillset(&sa.sa_mask))
-    abort();
-  sa.sa_handler = uv__signal_handler;
-  sa.sa_flags = SA_RESTART;
-  if (oneshot)
-    sa.sa_flags |= SA_RESETHAND;
-
-  /* XXX save old action so we can restore it later on? */
-  if (sigaction(signum, &sa, NULL))
-    return UV__ERR(errno);
-
-  return 0;
-}
-
-
-static void uv__signal_unregister_handler(int signum) {
-  /* When this function is called, the signal lock must be held. */
-  struct sigaction sa;
-
-  memset(&sa, 0, sizeof(sa));
-  sa.sa_handler = SIG_DFL;
-
-  /* sigaction can only fail with EINVAL or EFAULT; an attempt to deregister a
-   * signal implies that it was successfully registered earlier, so EINVAL
-   * should never happen.
-   */
-  if (sigaction(signum, &sa, NULL))
-    abort();
-}
-
-
-static int uv__signal_loop_once_init(uv_loop_t* loop) {
-  int err;
-
-  /* Return if already initialized. */
-  if (loop->signal_pipefd[0] != -1)
-    return 0;
-
-  err = uv__make_pipe(loop->signal_pipefd, UV__F_NONBLOCK);
-  if (err)
-    return err;
-
-  uv__io_init(&loop->signal_io_watcher,
-              uv__signal_event,
-              loop->signal_pipefd[0]);
-  uv__io_start(loop, &loop->signal_io_watcher, POLLIN);
-
-  return 0;
-}
-
-
-int uv__signal_loop_fork(uv_loop_t* loop) {
-  uv__io_stop(loop, &loop->signal_io_watcher, POLLIN);
-  uv__close(loop->signal_pipefd[0]);
-  uv__close(loop->signal_pipefd[1]);
-  loop->signal_pipefd[0] = -1;
-  loop->signal_pipefd[1] = -1;
-  return uv__signal_loop_once_init(loop);
-}
-
-
-void uv__signal_loop_cleanup(uv_loop_t* loop) {
-  QUEUE* q;
-
-  /* Stop all the signal watchers that are still attached to this loop. This
-   * ensures that the (shared) signal tree doesn't contain any invalid entries
-   * entries, and that signal handlers are removed when appropriate.
-   * It's safe to use QUEUE_FOREACH here because the handles and the handle
-   * queue are not modified by uv__signal_stop().
-   */
-  QUEUE_FOREACH(q, &loop->handle_queue) {
-    uv_handle_t* handle = QUEUE_DATA(q, uv_handle_t, handle_queue);
-
-    if (handle->type == UV_SIGNAL)
-      uv__signal_stop((uv_signal_t*) handle);
-  }
-
-  if (loop->signal_pipefd[0] != -1) {
-    uv__close(loop->signal_pipefd[0]);
-    loop->signal_pipefd[0] = -1;
-  }
-
-  if (loop->signal_pipefd[1] != -1) {
-    uv__close(loop->signal_pipefd[1]);
-    loop->signal_pipefd[1] = -1;
-  }
-}
-
-
-int uv_signal_init(uv_loop_t* loop, uv_signal_t* handle) {
-  int err;
-
-  err = uv__signal_loop_once_init(loop);
-  if (err)
-    return err;
-
-  uv__handle_init(loop, (uv_handle_t*) handle, UV_SIGNAL);
-  handle->signum = 0;
-  handle->caught_signals = 0;
-  handle->dispatched_signals = 0;
-
-  return 0;
-}
-
-
-void uv__signal_close(uv_signal_t* handle) {
-
-  uv__signal_stop(handle);
-
-  /* If there are any caught signals "trapped" in the signal pipe, we can't
-   * call the close callback yet. Otherwise, add the handle to the finish_close
-   * queue.
-   */
-  if (handle->caught_signals == handle->dispatched_signals) {
-    uv__make_close_pending((uv_handle_t*) handle);
-  }
-}
-
-
-int uv_signal_start(uv_signal_t* handle, uv_signal_cb signal_cb, int signum) {
-  return uv__signal_start(handle, signal_cb, signum, 0);
-}
-
-
-int uv_signal_start_oneshot(uv_signal_t* handle,
-                            uv_signal_cb signal_cb,
-                            int signum) {
-  return uv__signal_start(handle, signal_cb, signum, 1);
-}
-
-
-static int uv__signal_start(uv_signal_t* handle,
-                            uv_signal_cb signal_cb,
-                            int signum,
-                            int oneshot) {
-  sigset_t saved_sigmask;
-  int err;
-  uv_signal_t* first_handle;
-
-  assert(!uv__is_closing(handle));
-
-  /* If the user supplies signum == 0, then return an error already. If the
-   * signum is otherwise invalid then uv__signal_register will find out
-   * eventually.
-   */
-  if (signum == 0)
-    return UV_EINVAL;
-
-  /* Short circuit: if the signal watcher is already watching {signum} don't
-   * go through the process of deregistering and registering the handler.
-   * Additionally, this avoids pending signals getting lost in the small
-   * time frame that handle->signum == 0.
-   */
-  if (signum == handle->signum) {
-    handle->signal_cb = signal_cb;
-    return 0;
-  }
-
-  /* If the signal handler was already active, stop it first. */
-  if (handle->signum != 0) {
-    uv__signal_stop(handle);
-  }
-
-  uv__signal_block_and_lock(&saved_sigmask);
-
-  /* If at this point there are no active signal watchers for this signum (in
-   * any of the loops), it's time to try and register a handler for it here.
-   * Also in case there's only one-shot handlers and a regular handler comes in.
-   */
-  first_handle = uv__signal_first_handle(signum);
-  if (first_handle == NULL ||
-      (!oneshot && (first_handle->flags & UV_SIGNAL_ONE_SHOT))) {
-    err = uv__signal_register_handler(signum, oneshot);
-    if (err) {
-      /* Registering the signal handler failed. Must be an invalid signal. */
-      uv__signal_unlock_and_unblock(&saved_sigmask);
-      return err;
-    }
-  }
-
-  handle->signum = signum;
-  if (oneshot)
-    handle->flags |= UV_SIGNAL_ONE_SHOT;
-
-  RB_INSERT(uv__signal_tree_s, &uv__signal_tree, handle);
-
-  uv__signal_unlock_and_unblock(&saved_sigmask);
-
-  handle->signal_cb = signal_cb;
-  uv__handle_start(handle);
-
-  return 0;
-}
-
-
-static void uv__signal_event(uv_loop_t* loop,
-                             uv__io_t* w,
-                             unsigned int events) {
-  uv__signal_msg_t* msg;
-  uv_signal_t* handle;
-  char buf[sizeof(uv__signal_msg_t) * 32];
-  size_t bytes, end, i;
-  int r;
-
-  bytes = 0;
-  end = 0;
-
-  do {
-    r = read(loop->signal_pipefd[0], buf + bytes, sizeof(buf) - bytes);
-
-    if (r == -1 && errno == EINTR)
-      continue;
-
-    if (r == -1 && (errno == EAGAIN || errno == EWOULDBLOCK)) {
-      /* If there are bytes in the buffer already (which really is extremely
-       * unlikely if possible at all) we can't exit the function here. We'll
-       * spin until more bytes are read instead.
-       */
-      if (bytes > 0)
-        continue;
-
-      /* Otherwise, there was nothing there. */
-      return;
-    }
-
-    /* Other errors really should never happen. */
-    if (r == -1)
-      abort();
-
-    bytes += r;
-
-    /* `end` is rounded down to a multiple of sizeof(uv__signal_msg_t). */
-    end = (bytes / sizeof(uv__signal_msg_t)) * sizeof(uv__signal_msg_t);
-
-    for (i = 0; i < end; i += sizeof(uv__signal_msg_t)) {
-      msg = (uv__signal_msg_t*) (buf + i);
-      handle = msg->handle;
-
-      if (msg->signum == handle->signum) {
-        assert(!(handle->flags & UV_HANDLE_CLOSING));
-        handle->signal_cb(handle, handle->signum);
-      }
-
-      handle->dispatched_signals++;
-
-      if (handle->flags & UV_SIGNAL_ONE_SHOT)
-        uv__signal_stop(handle);
-
-      /* If uv_close was called while there were caught signals that were not
-       * yet dispatched, the uv__finish_close was deferred. Make close pending
-       * now if this has happened.
-       */
-      if ((handle->flags & UV_HANDLE_CLOSING) &&
-          (handle->caught_signals == handle->dispatched_signals)) {
-        uv__make_close_pending((uv_handle_t*) handle);
-      }
-    }
-
-    bytes -= end;
-
-    /* If there are any "partial" messages left, move them to the start of the
-     * the buffer, and spin. This should not happen.
-     */
-    if (bytes) {
-      memmove(buf, buf + end, bytes);
-      continue;
-    }
-  } while (end == sizeof buf);
-}
-
-
-static int uv__signal_compare(uv_signal_t* w1, uv_signal_t* w2) {
-  int f1;
-  int f2;
-  /* Compare signums first so all watchers with the same signnum end up
-   * adjacent.
-   */
-  if (w1->signum < w2->signum) return -1;
-  if (w1->signum > w2->signum) return 1;
-
-  /* Handlers without UV_SIGNAL_ONE_SHOT set will come first, so if the first
-   * handler returned is a one-shot handler, the rest will be too.
-   */
-  f1 = w1->flags & UV_SIGNAL_ONE_SHOT;
-  f2 = w2->flags & UV_SIGNAL_ONE_SHOT;
-  if (f1 < f2) return -1;
-  if (f1 > f2) return 1;
-
-  /* Sort by loop pointer, so we can easily look up the first item after
-   * { .signum = x, .loop = NULL }.
-   */
-  if (w1->loop < w2->loop) return -1;
-  if (w1->loop > w2->loop) return 1;
-
-  if (w1 < w2) return -1;
-  if (w1 > w2) return 1;
-
-  return 0;
-}
-
-
-int uv_signal_stop(uv_signal_t* handle) {
-  assert(!uv__is_closing(handle));
-  uv__signal_stop(handle);
-  return 0;
-}
-
-
-static void uv__signal_stop(uv_signal_t* handle) {
-  uv_signal_t* removed_handle;
-  sigset_t saved_sigmask;
-  uv_signal_t* first_handle;
-  int rem_oneshot;
-  int first_oneshot;
-  int ret;
-
-  /* If the watcher wasn't started, this is a no-op. */
-  if (handle->signum == 0)
-    return;
-
-  uv__signal_block_and_lock(&saved_sigmask);
-
-  removed_handle = RB_REMOVE(uv__signal_tree_s, &uv__signal_tree, handle);
-  assert(removed_handle == handle);
-  (void) removed_handle;
-
-  /* Check if there are other active signal watchers observing this signal. If
-   * not, unregister the signal handler.
-   */
-  first_handle = uv__signal_first_handle(handle->signum);
-  if (first_handle == NULL) {
-    uv__signal_unregister_handler(handle->signum);
-  } else {
-    rem_oneshot = handle->flags & UV_SIGNAL_ONE_SHOT;
-    first_oneshot = first_handle->flags & UV_SIGNAL_ONE_SHOT;
-    if (first_oneshot && !rem_oneshot) {
-      ret = uv__signal_register_handler(handle->signum, 1);
-      assert(ret == 0);
-      (void) ret;
-    }
-  }
-
-  uv__signal_unlock_and_unblock(&saved_sigmask);
-
-  handle->signum = 0;
-  uv__handle_stop(handle);
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/stream.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/stream.cpp
deleted file mode 100644
index f3a8e66..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/stream.cpp
+++ /dev/null
@@ -1,1689 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include "uv.h"
-#include "internal.h"
-
-#include <stdio.h>
-#include <stdlib.h>
-#include <string.h>
-#include <assert.h>
-#include <errno.h>
-
-#include <sys/types.h>
-#include <sys/socket.h>
-#include <sys/uio.h>
-#include <sys/un.h>
-#include <unistd.h>
-#include <limits.h> /* IOV_MAX */
-
-#if defined(__APPLE__)
-# include <sys/event.h>
-# include <sys/time.h>
-# include <sys/select.h>
-
-/* Forward declaration */
-typedef struct uv__stream_select_s uv__stream_select_t;
-
-struct uv__stream_select_s {
-  uv_stream_t* stream;
-  uv_thread_t thread;
-  uv_sem_t close_sem;
-  uv_sem_t async_sem;
-  uv_async_t async;
-  int events;
-  int fake_fd;
-  int int_fd;
-  int fd;
-  fd_set* sread;
-  size_t sread_sz;
-  fd_set* swrite;
-  size_t swrite_sz;
-};
-
-/* Due to a possible kernel bug at least in OS X 10.10 "Yosemite",
- * EPROTOTYPE can be returned while trying to write to a socket that is
- * shutting down. If we retry the write, we should get the expected EPIPE
- * instead.
- */
-# define RETRY_ON_WRITE_ERROR(errno) (errno == EINTR || errno == EPROTOTYPE)
-# define IS_TRANSIENT_WRITE_ERROR(errno, send_handle) \
-    (errno == EAGAIN || errno == EWOULDBLOCK || errno == ENOBUFS || \
-     (errno == EMSGSIZE && send_handle != NULL))
-#else
-# define RETRY_ON_WRITE_ERROR(errno) (errno == EINTR)
-# define IS_TRANSIENT_WRITE_ERROR(errno, send_handle) \
-    (errno == EAGAIN || errno == EWOULDBLOCK || errno == ENOBUFS)
-#endif /* defined(__APPLE__) */
-
-static void uv__stream_connect(uv_stream_t*);
-static void uv__write(uv_stream_t* stream);
-static void uv__read(uv_stream_t* stream);
-static void uv__stream_io(uv_loop_t* loop, uv__io_t* w, unsigned int events);
-static void uv__write_callbacks(uv_stream_t* stream);
-static size_t uv__write_req_size(uv_write_t* req);
-
-
-void uv__stream_init(uv_loop_t* loop,
-                     uv_stream_t* stream,
-                     uv_handle_type type) {
-  int err;
-
-  uv__handle_init(loop, (uv_handle_t*)stream, type);
-  stream->read_cb = NULL;
-  stream->alloc_cb = NULL;
-  stream->close_cb = NULL;
-  stream->connection_cb = NULL;
-  stream->connect_req = NULL;
-  stream->shutdown_req = NULL;
-  stream->accepted_fd = -1;
-  stream->queued_fds = NULL;
-  stream->delayed_error = 0;
-  QUEUE_INIT(&stream->write_queue);
-  QUEUE_INIT(&stream->write_completed_queue);
-  stream->write_queue_size = 0;
-
-  if (loop->emfile_fd == -1) {
-    err = uv__open_cloexec("/dev/null", O_RDONLY);
-    if (err < 0)
-        /* In the rare case that "/dev/null" isn't mounted open "/"
-         * instead.
-         */
-        err = uv__open_cloexec("/", O_RDONLY);
-    if (err >= 0)
-      loop->emfile_fd = err;
-  }
-
-#if defined(__APPLE__)
-  stream->select = NULL;
-#endif /* defined(__APPLE_) */
-
-  uv__io_init(&stream->io_watcher, uv__stream_io, -1);
-}
-
-
-static void uv__stream_osx_interrupt_select(uv_stream_t* stream) {
-#if defined(__APPLE__)
-  /* Notify select() thread about state change */
-  uv__stream_select_t* s;
-  int r;
-
-  s = (uv__stream_select_t*)stream->select;
-  if (s == NULL)
-    return;
-
-  /* Interrupt select() loop
-   * NOTE: fake_fd and int_fd are socketpair(), thus writing to one will
-   * emit read event on other side
-   */
-  do
-    r = write(s->fake_fd, "x", 1);
-  while (r == -1 && errno == EINTR);
-
-  assert(r == 1);
-#else  /* !defined(__APPLE__) */
-  /* No-op on any other platform */
-#endif  /* !defined(__APPLE__) */
-}
-
-
-#if defined(__APPLE__)
-static void uv__stream_osx_select(void* arg) {
-  uv_stream_t* stream;
-  uv__stream_select_t* s;
-  char buf[1024];
-  int events;
-  int fd;
-  int r;
-  int max_fd;
-
-  stream = (uv_stream_t*)arg;
-  s = (uv__stream_select_t*)stream->select;
-  fd = s->fd;
-
-  if (fd > s->int_fd)
-    max_fd = fd;
-  else
-    max_fd = s->int_fd;
-
-  while (1) {
-    /* Terminate on semaphore */
-    if (uv_sem_trywait(&s->close_sem) == 0)
-      break;
-
-    /* Watch fd using select(2) */
-    memset(s->sread, 0, s->sread_sz);
-    memset(s->swrite, 0, s->swrite_sz);
-
-    if (uv__io_active(&stream->io_watcher, POLLIN))
-      FD_SET(fd, s->sread);
-    if (uv__io_active(&stream->io_watcher, POLLOUT))
-      FD_SET(fd, s->swrite);
-    FD_SET(s->int_fd, s->sread);
-
-    /* Wait indefinitely for fd events */
-    r = select(max_fd + 1, s->sread, s->swrite, NULL, NULL);
-    if (r == -1) {
-      if (errno == EINTR)
-        continue;
-
-      /* XXX: Possible?! */
-      abort();
-    }
-
-    /* Ignore timeouts */
-    if (r == 0)
-      continue;
-
-    /* Empty socketpair's buffer in case of interruption */
-    if (FD_ISSET(s->int_fd, s->sread))
-      while (1) {
-        r = read(s->int_fd, buf, sizeof(buf));
-
-        if (r == sizeof(buf))
-          continue;
-
-        if (r != -1)
-          break;
-
-        if (errno == EAGAIN || errno == EWOULDBLOCK)
-          break;
-
-        if (errno == EINTR)
-          continue;
-
-        abort();
-      }
-
-    /* Handle events */
-    events = 0;
-    if (FD_ISSET(fd, s->sread))
-      events |= POLLIN;
-    if (FD_ISSET(fd, s->swrite))
-      events |= POLLOUT;
-
-    assert(events != 0 || FD_ISSET(s->int_fd, s->sread));
-    if (events != 0) {
-      ACCESS_ONCE(int, s->events) = events;
-
-      uv_async_send(&s->async);
-      uv_sem_wait(&s->async_sem);
-
-      /* Should be processed at this stage */
-      assert((s->events == 0) || (stream->flags & UV_HANDLE_CLOSING));
-    }
-  }
-}
-
-
-static void uv__stream_osx_select_cb(uv_async_t* handle) {
-  uv__stream_select_t* s;
-  uv_stream_t* stream;
-  int events;
-
-  s = container_of(handle, uv__stream_select_t, async);
-  stream = s->stream;
-
-  /* Get and reset stream's events */
-  events = s->events;
-  ACCESS_ONCE(int, s->events) = 0;
-
-  assert(events != 0);
-  assert(events == (events & (POLLIN | POLLOUT)));
-
-  /* Invoke callback on event-loop */
-  if ((events & POLLIN) && uv__io_active(&stream->io_watcher, POLLIN))
-    uv__stream_io(stream->loop, &stream->io_watcher, POLLIN);
-
-  if ((events & POLLOUT) && uv__io_active(&stream->io_watcher, POLLOUT))
-    uv__stream_io(stream->loop, &stream->io_watcher, POLLOUT);
-
-  if (stream->flags & UV_HANDLE_CLOSING)
-    return;
-
-  /* NOTE: It is important to do it here, otherwise `select()` might be called
-   * before the actual `uv__read()`, leading to the blocking syscall
-   */
-  uv_sem_post(&s->async_sem);
-}
-
-
-static void uv__stream_osx_cb_close(uv_handle_t* async) {
-  uv__stream_select_t* s;
-
-  s = container_of(async, uv__stream_select_t, async);
-  uv__free(s);
-}
-
-
-int uv__stream_try_select(uv_stream_t* stream, int* fd) {
-  /*
-   * kqueue doesn't work with some files from /dev mount on osx.
-   * select(2) in separate thread for those fds
-   */
-
-  struct kevent filter[1];
-  struct kevent events[1];
-  struct timespec timeout;
-  uv__stream_select_t* s;
-  int fds[2];
-  int err;
-  int ret;
-  int kq;
-  int old_fd;
-  int max_fd;
-  size_t sread_sz;
-  size_t swrite_sz;
-
-  kq = kqueue();
-  if (kq == -1) {
-    perror("(libuv) kqueue()");
-    return UV__ERR(errno);
-  }
-
-  EV_SET(&filter[0], *fd, EVFILT_READ, EV_ADD | EV_ENABLE, 0, 0, 0);
-
-  /* Use small timeout, because we only want to capture EINVALs */
-  timeout.tv_sec = 0;
-  timeout.tv_nsec = 1;
-
-  do
-    ret = kevent(kq, filter, 1, events, 1, &timeout);
-  while (ret == -1 && errno == EINTR);
-
-  uv__close(kq);
-
-  if (ret == -1)
-    return UV__ERR(errno);
-
-  if (ret == 0 || (events[0].flags & EV_ERROR) == 0 || events[0].data != EINVAL)
-    return 0;
-
-  /* At this point we definitely know that this fd won't work with kqueue */
-
-  /*
-   * Create fds for io watcher and to interrupt the select() loop.
-   * NOTE: do it ahead of malloc below to allocate enough space for fd_sets
-   */
-  if (socketpair(AF_UNIX, SOCK_STREAM, 0, fds))
-    return UV__ERR(errno);
-
-  max_fd = *fd;
-  if (fds[1] > max_fd)
-    max_fd = fds[1];
-
-  sread_sz = ROUND_UP(max_fd + 1, sizeof(uint32_t) * NBBY) / NBBY;
-  swrite_sz = sread_sz;
-
-  s = (uv__stream_select_t*)uv__malloc(sizeof(*s) + sread_sz + swrite_sz);
-  if (s == NULL) {
-    err = UV_ENOMEM;
-    goto failed_malloc;
-  }
-
-  s->events = 0;
-  s->fd = *fd;
-  s->sread = (fd_set*) ((char*) s + sizeof(*s));
-  s->sread_sz = sread_sz;
-  s->swrite = (fd_set*) ((char*) s->sread + sread_sz);
-  s->swrite_sz = swrite_sz;
-
-  err = uv_async_init(stream->loop, &s->async, uv__stream_osx_select_cb);
-  if (err)
-    goto failed_async_init;
-
-  s->async.flags |= UV_HANDLE_INTERNAL;
-  uv__handle_unref(&s->async);
-
-  err = uv_sem_init(&s->close_sem, 0);
-  if (err != 0)
-    goto failed_close_sem_init;
-
-  err = uv_sem_init(&s->async_sem, 0);
-  if (err != 0)
-    goto failed_async_sem_init;
-
-  s->fake_fd = fds[0];
-  s->int_fd = fds[1];
-
-  old_fd = *fd;
-  s->stream = stream;
-  stream->select = s;
-  *fd = s->fake_fd;
-
-  err = uv_thread_create(&s->thread, uv__stream_osx_select, stream);
-  if (err != 0)
-    goto failed_thread_create;
-
-  return 0;
-
-failed_thread_create:
-  s->stream = NULL;
-  stream->select = NULL;
-  *fd = old_fd;
-
-  uv_sem_destroy(&s->async_sem);
-
-failed_async_sem_init:
-  uv_sem_destroy(&s->close_sem);
-
-failed_close_sem_init:
-  uv__close(fds[0]);
-  uv__close(fds[1]);
-  uv_close((uv_handle_t*) &s->async, uv__stream_osx_cb_close);
-  return err;
-
-failed_async_init:
-  uv__free(s);
-
-failed_malloc:
-  uv__close(fds[0]);
-  uv__close(fds[1]);
-
-  return err;
-}
-#endif /* defined(__APPLE__) */
-
-
-int uv__stream_open(uv_stream_t* stream, int fd, int flags) {
-#if defined(__APPLE__)
-  int enable;
-#endif
-
-  if (!(stream->io_watcher.fd == -1 || stream->io_watcher.fd == fd))
-    return UV_EBUSY;
-
-  assert(fd >= 0);
-  stream->flags |= flags;
-
-  if (stream->type == UV_TCP) {
-    if ((stream->flags & UV_HANDLE_TCP_NODELAY) && uv__tcp_nodelay(fd, 1))
-      return UV__ERR(errno);
-
-    /* TODO Use delay the user passed in. */
-    if ((stream->flags & UV_HANDLE_TCP_KEEPALIVE) &&
-        uv__tcp_keepalive(fd, 1, 60)) {
-      return UV__ERR(errno);
-    }
-  }
-
-#if defined(__APPLE__)
-  enable = 1;
-  if (setsockopt(fd, SOL_SOCKET, SO_OOBINLINE, &enable, sizeof(enable)) &&
-      errno != ENOTSOCK &&
-      errno != EINVAL) {
-    return UV__ERR(errno);
-  }
-#endif
-
-  stream->io_watcher.fd = fd;
-
-  return 0;
-}
-
-
-void uv__stream_flush_write_queue(uv_stream_t* stream, int error) {
-  uv_write_t* req;
-  QUEUE* q;
-  while (!QUEUE_EMPTY(&stream->write_queue)) {
-    q = QUEUE_HEAD(&stream->write_queue);
-    QUEUE_REMOVE(q);
-
-    req = QUEUE_DATA(q, uv_write_t, queue);
-    req->error = error;
-
-    QUEUE_INSERT_TAIL(&stream->write_completed_queue, &req->queue);
-  }
-}
-
-
-void uv__stream_destroy(uv_stream_t* stream) {
-  assert(!uv__io_active(&stream->io_watcher, POLLIN | POLLOUT));
-  assert(stream->flags & UV_HANDLE_CLOSED);
-
-  if (stream->connect_req) {
-    uv__req_unregister(stream->loop, stream->connect_req);
-    stream->connect_req->cb(stream->connect_req, UV_ECANCELED);
-    stream->connect_req = NULL;
-  }
-
-  uv__stream_flush_write_queue(stream, UV_ECANCELED);
-  uv__write_callbacks(stream);
-
-  if (stream->shutdown_req) {
-    /* The ECANCELED error code is a lie, the shutdown(2) syscall is a
-     * fait accompli at this point. Maybe we should revisit this in v0.11.
-     * A possible reason for leaving it unchanged is that it informs the
-     * callee that the handle has been destroyed.
-     */
-    uv__req_unregister(stream->loop, stream->shutdown_req);
-    stream->shutdown_req->cb(stream->shutdown_req, UV_ECANCELED);
-    stream->shutdown_req = NULL;
-  }
-
-  assert(stream->write_queue_size == 0);
-}
-
-
-/* Implements a best effort approach to mitigating accept() EMFILE errors.
- * We have a spare file descriptor stashed away that we close to get below
- * the EMFILE limit. Next, we accept all pending connections and close them
- * immediately to signal the clients that we're overloaded - and we are, but
- * we still keep on trucking.
- *
- * There is one caveat: it's not reliable in a multi-threaded environment.
- * The file descriptor limit is per process. Our party trick fails if another
- * thread opens a file or creates a socket in the time window between us
- * calling close() and accept().
- */
-static int uv__emfile_trick(uv_loop_t* loop, int accept_fd) {
-  int err;
-  int emfile_fd;
-
-  if (loop->emfile_fd == -1)
-    return UV_EMFILE;
-
-  uv__close(loop->emfile_fd);
-  loop->emfile_fd = -1;
-
-  do {
-    err = uv__accept(accept_fd);
-    if (err >= 0)
-      uv__close(err);
-  } while (err >= 0 || err == UV_EINTR);
-
-  emfile_fd = uv__open_cloexec("/", O_RDONLY);
-  if (emfile_fd >= 0)
-    loop->emfile_fd = emfile_fd;
-
-  return err;
-}
-
-
-#if defined(UV_HAVE_KQUEUE)
-# define UV_DEC_BACKLOG(w) w->rcount--;
-#else
-# define UV_DEC_BACKLOG(w) /* no-op */
-#endif /* defined(UV_HAVE_KQUEUE) */
-
-
-void uv__server_io(uv_loop_t* loop, uv__io_t* w, unsigned int events) {
-  uv_stream_t* stream;
-  int err;
-
-  stream = container_of(w, uv_stream_t, io_watcher);
-  assert(events & POLLIN);
-  assert(stream->accepted_fd == -1);
-  assert(!(stream->flags & UV_HANDLE_CLOSING));
-
-  uv__io_start(stream->loop, &stream->io_watcher, POLLIN);
-
-  /* connection_cb can close the server socket while we're
-   * in the loop so check it on each iteration.
-   */
-  while (uv__stream_fd(stream) != -1) {
-    assert(stream->accepted_fd == -1);
-
-#if defined(UV_HAVE_KQUEUE)
-    if (w->rcount <= 0)
-      return;
-#endif /* defined(UV_HAVE_KQUEUE) */
-
-    err = uv__accept(uv__stream_fd(stream));
-    if (err < 0) {
-      if (err == UV_EAGAIN || err == UV__ERR(EWOULDBLOCK))
-        return;  /* Not an error. */
-
-      if (err == UV_ECONNABORTED)
-        continue;  /* Ignore. Nothing we can do about that. */
-
-      if (err == UV_EMFILE || err == UV_ENFILE) {
-        err = uv__emfile_trick(loop, uv__stream_fd(stream));
-        if (err == UV_EAGAIN || err == UV__ERR(EWOULDBLOCK))
-          break;
-      }
-
-      stream->connection_cb(stream, err);
-      continue;
-    }
-
-    UV_DEC_BACKLOG(w)
-    stream->accepted_fd = err;
-    stream->connection_cb(stream, 0);
-
-    if (stream->accepted_fd != -1) {
-      /* The user hasn't yet accepted called uv_accept() */
-      uv__io_stop(loop, &stream->io_watcher, POLLIN);
-      return;
-    }
-
-    if (stream->type == UV_TCP &&
-        (stream->flags & UV_HANDLE_TCP_SINGLE_ACCEPT)) {
-      /* Give other processes a chance to accept connections. */
-      struct timespec timeout = { 0, 1 };
-      nanosleep(&timeout, NULL);
-    }
-  }
-}
-
-
-#undef UV_DEC_BACKLOG
-
-
-int uv_accept(uv_stream_t* server, uv_stream_t* client) {
-  int err;
-
-  assert(server->loop == client->loop);
-
-  if (server->accepted_fd == -1)
-    return UV_EAGAIN;
-
-  switch (client->type) {
-    case UV_NAMED_PIPE:
-    case UV_TCP:
-      err = uv__stream_open(client,
-                            server->accepted_fd,
-                            UV_HANDLE_READABLE | UV_HANDLE_WRITABLE);
-      if (err) {
-        /* TODO handle error */
-        uv__close(server->accepted_fd);
-        goto done;
-      }
-      break;
-
-    case UV_UDP:
-      err = uv_udp_open((uv_udp_t*) client, server->accepted_fd);
-      if (err) {
-        uv__close(server->accepted_fd);
-        goto done;
-      }
-      break;
-
-    default:
-      return UV_EINVAL;
-  }
-
-  client->flags |= UV_HANDLE_BOUND;
-
-done:
-  /* Process queued fds */
-  if (server->queued_fds != NULL) {
-    uv__stream_queued_fds_t* queued_fds;
-
-    queued_fds = (uv__stream_queued_fds_t*)(server->queued_fds);
-
-    /* Read first */
-    server->accepted_fd = queued_fds->fds[0];
-
-    /* All read, free */
-    assert(queued_fds->offset > 0);
-    if (--queued_fds->offset == 0) {
-      uv__free(queued_fds);
-      server->queued_fds = NULL;
-    } else {
-      /* Shift rest */
-      memmove(queued_fds->fds,
-              queued_fds->fds + 1,
-              queued_fds->offset * sizeof(*queued_fds->fds));
-    }
-  } else {
-    server->accepted_fd = -1;
-    if (err == 0)
-      uv__io_start(server->loop, &server->io_watcher, POLLIN);
-  }
-  return err;
-}
-
-
-int uv_listen(uv_stream_t* stream, int backlog, uv_connection_cb cb) {
-  int err;
-
-  switch (stream->type) {
-  case UV_TCP:
-    err = uv_tcp_listen((uv_tcp_t*)stream, backlog, cb);
-    break;
-
-  case UV_NAMED_PIPE:
-    err = uv_pipe_listen((uv_pipe_t*)stream, backlog, cb);
-    break;
-
-  default:
-    err = UV_EINVAL;
-  }
-
-  if (err == 0)
-    uv__handle_start(stream);
-
-  return err;
-}
-
-
-static void uv__drain(uv_stream_t* stream) {
-  uv_shutdown_t* req;
-  int err;
-
-  assert(QUEUE_EMPTY(&stream->write_queue));
-  uv__io_stop(stream->loop, &stream->io_watcher, POLLOUT);
-  uv__stream_osx_interrupt_select(stream);
-
-  /* Shutdown? */
-  if ((stream->flags & UV_HANDLE_SHUTTING) &&
-      !(stream->flags & UV_HANDLE_CLOSING) &&
-      !(stream->flags & UV_HANDLE_SHUT)) {
-    assert(stream->shutdown_req);
-
-    req = stream->shutdown_req;
-    stream->shutdown_req = NULL;
-    stream->flags &= ~UV_HANDLE_SHUTTING;
-    uv__req_unregister(stream->loop, req);
-
-    err = 0;
-    if (shutdown(uv__stream_fd(stream), SHUT_WR))
-      err = UV__ERR(errno);
-
-    if (err == 0)
-      stream->flags |= UV_HANDLE_SHUT;
-
-    if (req->cb != NULL)
-      req->cb(req, err);
-  }
-}
-
-
-static ssize_t uv__writev(int fd, struct iovec* vec, size_t n) {
-  if (n == 1)
-    return write(fd, vec->iov_base, vec->iov_len);
-  else
-    return writev(fd, vec, n);
-}
-
-
-static size_t uv__write_req_size(uv_write_t* req) {
-  size_t size;
-
-  assert(req->bufs != NULL);
-  size = uv__count_bufs(req->bufs + req->write_index,
-                        req->nbufs - req->write_index);
-  assert(req->handle->write_queue_size >= size);
-
-  return size;
-}
-
-
-/* Returns 1 if all write request data has been written, or 0 if there is still
- * more data to write.
- *
- * Note: the return value only says something about the *current* request.
- * There may still be other write requests sitting in the queue.
- */
-static int uv__write_req_update(uv_stream_t* stream,
-                                uv_write_t* req,
-                                size_t n) {
-  uv_buf_t* buf;
-  size_t len;
-
-  assert(n <= stream->write_queue_size);
-  stream->write_queue_size -= n;
-
-  buf = req->bufs + req->write_index;
-
-  do {
-    len = n < buf->len ? n : buf->len;
-    buf->base += len;
-    buf->len -= len;
-    buf += (buf->len == 0);  /* Advance to next buffer if this one is empty. */
-    n -= len;
-  } while (n > 0);
-
-  req->write_index = buf - req->bufs;
-
-  return req->write_index == req->nbufs;
-}
-
-
-static void uv__write_req_finish(uv_write_t* req) {
-  uv_stream_t* stream = req->handle;
-
-  /* Pop the req off tcp->write_queue. */
-  QUEUE_REMOVE(&req->queue);
-
-  /* Only free when there was no error. On error, we touch up write_queue_size
-   * right before making the callback. The reason we don't do that right away
-   * is that a write_queue_size > 0 is our only way to signal to the user that
-   * they should stop writing - which they should if we got an error. Something
-   * to revisit in future revisions of the libuv API.
-   */
-  if (req->error == 0) {
-    if (req->bufs != req->bufsml)
-      uv__free(req->bufs);
-    req->bufs = NULL;
-  }
-
-  /* Add it to the write_completed_queue where it will have its
-   * callback called in the near future.
-   */
-  QUEUE_INSERT_TAIL(&stream->write_completed_queue, &req->queue);
-  uv__io_feed(stream->loop, &stream->io_watcher);
-}
-
-
-static int uv__handle_fd(uv_handle_t* handle) {
-  switch (handle->type) {
-    case UV_NAMED_PIPE:
-    case UV_TCP:
-      return ((uv_stream_t*) handle)->io_watcher.fd;
-
-    case UV_UDP:
-      return ((uv_udp_t*) handle)->io_watcher.fd;
-
-    default:
-      return -1;
-  }
-}
-
-static void uv__write(uv_stream_t* stream) {
-  struct iovec* iov;
-  QUEUE* q;
-  uv_write_t* req;
-  int iovmax;
-  int iovcnt;
-  ssize_t n;
-  int err;
-
-start:
-
-  assert(uv__stream_fd(stream) >= 0);
-
-  if (QUEUE_EMPTY(&stream->write_queue))
-    return;
-
-  q = QUEUE_HEAD(&stream->write_queue);
-  req = QUEUE_DATA(q, uv_write_t, queue);
-  assert(req->handle == stream);
-
-  /*
-   * Cast to iovec. We had to have our own uv_buf_t instead of iovec
-   * because Windows's WSABUF is not an iovec.
-   */
-  assert(sizeof(uv_buf_t) == sizeof(struct iovec));
-  iov = (struct iovec*) &(req->bufs[req->write_index]);
-  iovcnt = req->nbufs - req->write_index;
-
-  iovmax = uv__getiovmax();
-
-  /* Limit iov count to avoid EINVALs from writev() */
-  if (iovcnt > iovmax)
-    iovcnt = iovmax;
-
-  /*
-   * Now do the actual writev. Note that we've been updating the pointers
-   * inside the iov each time we write. So there is no need to offset it.
-   */
-
-  if (req->send_handle) {
-    int fd_to_send;
-    struct msghdr msg;
-    struct cmsghdr *cmsg;
-    union {
-      char data[64];
-      struct cmsghdr alias;
-    } scratch;
-
-    if (uv__is_closing(req->send_handle)) {
-      err = UV_EBADF;
-      goto error;
-    }
-
-    fd_to_send = uv__handle_fd((uv_handle_t*) req->send_handle);
-
-    memset(&scratch, 0, sizeof(scratch));
-
-    assert(fd_to_send >= 0);
-
-    msg.msg_name = NULL;
-    msg.msg_namelen = 0;
-    msg.msg_iov = iov;
-    msg.msg_iovlen = iovcnt;
-    msg.msg_flags = 0;
-
-    msg.msg_control = &scratch.alias;
-    msg.msg_controllen = CMSG_SPACE(sizeof(fd_to_send));
-
-    cmsg = CMSG_FIRSTHDR(&msg);
-    cmsg->cmsg_level = SOL_SOCKET;
-    cmsg->cmsg_type = SCM_RIGHTS;
-    cmsg->cmsg_len = CMSG_LEN(sizeof(fd_to_send));
-
-    /* silence aliasing warning */
-    {
-      void* pv = CMSG_DATA(cmsg);
-      int* pi = (int*)pv;
-      *pi = fd_to_send;
-    }
-
-    do
-      n = sendmsg(uv__stream_fd(stream), &msg, 0);
-    while (n == -1 && RETRY_ON_WRITE_ERROR(errno));
-
-    /* Ensure the handle isn't sent again in case this is a partial write. */
-    if (n >= 0)
-      req->send_handle = NULL;
-  } else {
-    do
-      n = uv__writev(uv__stream_fd(stream), iov, iovcnt);
-    while (n == -1 && RETRY_ON_WRITE_ERROR(errno));
-  }
-
-  if (n == -1 && !IS_TRANSIENT_WRITE_ERROR(errno, req->send_handle)) {
-    err = UV__ERR(errno);
-    goto error;
-  }
-
-  if (n >= 0 && uv__write_req_update(stream, req, n)) {
-    uv__write_req_finish(req);
-    return;  /* TODO(bnoordhuis) Start trying to write the next request. */
-  }
-
-  /* If this is a blocking stream, try again. */
-  if (stream->flags & UV_HANDLE_BLOCKING_WRITES)
-    goto start;
-
-  /* We're not done. */
-  uv__io_start(stream->loop, &stream->io_watcher, POLLOUT);
-
-  /* Notify select() thread about state change */
-  uv__stream_osx_interrupt_select(stream);
-
-  return;
-
-error:
-  req->error = err;
-  uv__write_req_finish(req);
-  uv__io_stop(stream->loop, &stream->io_watcher, POLLOUT);
-  if (!uv__io_active(&stream->io_watcher, POLLIN))
-    uv__handle_stop(stream);
-  uv__stream_osx_interrupt_select(stream);
-}
-
-
-static void uv__write_callbacks(uv_stream_t* stream) {
-  uv_write_t* req;
-  QUEUE* q;
-  QUEUE pq;
-
-  if (QUEUE_EMPTY(&stream->write_completed_queue))
-    return;
-
-  QUEUE_MOVE(&stream->write_completed_queue, &pq);
-
-  while (!QUEUE_EMPTY(&pq)) {
-    /* Pop a req off write_completed_queue. */
-    q = QUEUE_HEAD(&pq);
-    req = QUEUE_DATA(q, uv_write_t, queue);
-    QUEUE_REMOVE(q);
-    uv__req_unregister(stream->loop, req);
-
-    if (req->bufs != NULL) {
-      stream->write_queue_size -= uv__write_req_size(req);
-      if (req->bufs != req->bufsml)
-        uv__free(req->bufs);
-      req->bufs = NULL;
-    }
-
-    /* NOTE: call callback AFTER freeing the request data. */
-    if (req->cb)
-      req->cb(req, req->error);
-  }
-}
-
-
-uv_handle_type uv__handle_type(int fd) {
-  struct sockaddr_storage ss;
-  socklen_t sslen;
-  socklen_t len;
-  int type;
-
-  memset(&ss, 0, sizeof(ss));
-  sslen = sizeof(ss);
-
-  if (getsockname(fd, (struct sockaddr*)&ss, &sslen))
-    return UV_UNKNOWN_HANDLE;
-
-  len = sizeof type;
-
-  if (getsockopt(fd, SOL_SOCKET, SO_TYPE, &type, &len))
-    return UV_UNKNOWN_HANDLE;
-
-  if (type == SOCK_STREAM) {
-#if defined(_AIX) || defined(__DragonFly__)
-    /* on AIX/DragonFly the getsockname call returns an empty sa structure
-     * for sockets of type AF_UNIX.  For all other types it will
-     * return a properly filled in structure.
-     */
-    if (sslen == 0)
-      return UV_NAMED_PIPE;
-#endif
-    switch (ss.ss_family) {
-      case AF_UNIX:
-        return UV_NAMED_PIPE;
-      case AF_INET:
-      case AF_INET6:
-        return UV_TCP;
-      }
-  }
-
-  if (type == SOCK_DGRAM &&
-      (ss.ss_family == AF_INET || ss.ss_family == AF_INET6))
-    return UV_UDP;
-
-  return UV_UNKNOWN_HANDLE;
-}
-
-
-static void uv__stream_eof(uv_stream_t* stream, const uv_buf_t* buf) {
-  stream->flags |= UV_HANDLE_READ_EOF;
-  uv__io_stop(stream->loop, &stream->io_watcher, POLLIN);
-  if (!uv__io_active(&stream->io_watcher, POLLOUT))
-    uv__handle_stop(stream);
-  uv__stream_osx_interrupt_select(stream);
-  stream->read_cb(stream, UV_EOF, buf);
-  stream->flags &= ~UV_HANDLE_READING;
-}
-
-
-static int uv__stream_queue_fd(uv_stream_t* stream, int fd) {
-  uv__stream_queued_fds_t* queued_fds;
-  unsigned int queue_size;
-
-  queued_fds = (uv__stream_queued_fds_t*)stream->queued_fds;
-  if (queued_fds == NULL) {
-    queue_size = 8;
-    queued_fds = (uv__stream_queued_fds_t*)
-        uv__malloc((queue_size - 1) * sizeof(*queued_fds->fds) +
-                   sizeof(*queued_fds));
-    if (queued_fds == NULL)
-      return UV_ENOMEM;
-    queued_fds->size = queue_size;
-    queued_fds->offset = 0;
-    stream->queued_fds = queued_fds;
-
-    /* Grow */
-  } else if (queued_fds->size == queued_fds->offset) {
-    queue_size = queued_fds->size + 8;
-    queued_fds = (uv__stream_queued_fds_t*)
-        uv__realloc(queued_fds, (queue_size - 1) * sizeof(*queued_fds->fds) +
-                    sizeof(*queued_fds));
-
-    /*
-     * Allocation failure, report back.
-     * NOTE: if it is fatal - sockets will be closed in uv__stream_close
-     */
-    if (queued_fds == NULL)
-      return UV_ENOMEM;
-    queued_fds->size = queue_size;
-    stream->queued_fds = queued_fds;
-  }
-
-  /* Put fd in a queue */
-  queued_fds->fds[queued_fds->offset++] = fd;
-
-  return 0;
-}
-
-
-#define UV__CMSG_FD_COUNT 64
-#define UV__CMSG_FD_SIZE (UV__CMSG_FD_COUNT * sizeof(int))
-
-
-static int uv__stream_recv_cmsg(uv_stream_t* stream, struct msghdr* msg) {
-  struct cmsghdr* cmsg;
-
-  for (cmsg = CMSG_FIRSTHDR(msg); cmsg != NULL; cmsg = CMSG_NXTHDR(msg, cmsg)) {
-    char* start;
-    char* end;
-    int err;
-    void* pv;
-    int* pi;
-    unsigned int i;
-    unsigned int count;
-
-    if (cmsg->cmsg_type != SCM_RIGHTS) {
-      fprintf(stderr, "ignoring non-SCM_RIGHTS ancillary data: %d\n",
-          cmsg->cmsg_type);
-      continue;
-    }
-
-    /* silence aliasing warning */
-    pv = CMSG_DATA(cmsg);
-    pi = (int*)pv;
-
-    /* Count available fds */
-    start = (char*) cmsg;
-    end = (char*) cmsg + cmsg->cmsg_len;
-    count = 0;
-    while (start + CMSG_LEN(count * sizeof(*pi)) < end)
-      count++;
-    assert(start + CMSG_LEN(count * sizeof(*pi)) == end);
-
-    for (i = 0; i < count; i++) {
-      /* Already has accepted fd, queue now */
-      if (stream->accepted_fd != -1) {
-        err = uv__stream_queue_fd(stream, pi[i]);
-        if (err != 0) {
-          /* Close rest */
-          for (; i < count; i++)
-            uv__close(pi[i]);
-          return err;
-        }
-      } else {
-        stream->accepted_fd = pi[i];
-      }
-    }
-  }
-
-  return 0;
-}
-
-
-#ifdef __clang__
-# pragma clang diagnostic push
-# pragma clang diagnostic ignored "-Wgnu-folding-constant"
-# pragma clang diagnostic ignored "-Wvla-extension"
-#endif
-
-static void uv__read(uv_stream_t* stream) {
-  uv_buf_t buf;
-  ssize_t nread;
-  struct msghdr msg;
-  char cmsg_space[CMSG_SPACE(UV__CMSG_FD_SIZE)];
-  int count;
-  int err;
-  int is_ipc;
-
-  stream->flags &= ~UV_HANDLE_READ_PARTIAL;
-
-  /* Prevent loop starvation when the data comes in as fast as (or faster than)
-   * we can read it. XXX Need to rearm fd if we switch to edge-triggered I/O.
-   */
-  count = 32;
-
-  is_ipc = stream->type == UV_NAMED_PIPE && ((uv_pipe_t*) stream)->ipc;
-
-  /* XXX: Maybe instead of having UV_HANDLE_READING we just test if
-   * tcp->read_cb is NULL or not?
-   */
-  while (stream->read_cb
-      && (stream->flags & UV_HANDLE_READING)
-      && (count-- > 0)) {
-    assert(stream->alloc_cb != NULL);
-
-    buf = uv_buf_init(NULL, 0);
-    stream->alloc_cb((uv_handle_t*)stream, 64 * 1024, &buf);
-    if (buf.base == NULL || buf.len == 0) {
-      /* User indicates it can't or won't handle the read. */
-      stream->read_cb(stream, UV_ENOBUFS, &buf);
-      return;
-    }
-
-    assert(buf.base != NULL);
-    assert(uv__stream_fd(stream) >= 0);
-
-    if (!is_ipc) {
-      do {
-        nread = read(uv__stream_fd(stream), buf.base, buf.len);
-      }
-      while (nread < 0 && errno == EINTR);
-    } else {
-      /* ipc uses recvmsg */
-      msg.msg_flags = 0;
-      msg.msg_iov = (struct iovec*) &buf;
-      msg.msg_iovlen = 1;
-      msg.msg_name = NULL;
-      msg.msg_namelen = 0;
-      /* Set up to receive a descriptor even if one isn't in the message */
-      msg.msg_controllen = sizeof(cmsg_space);
-      msg.msg_control = cmsg_space;
-
-      do {
-        nread = uv__recvmsg(uv__stream_fd(stream), &msg, 0);
-      }
-      while (nread < 0 && errno == EINTR);
-    }
-
-    if (nread < 0) {
-      /* Error */
-      if (errno == EAGAIN || errno == EWOULDBLOCK) {
-        /* Wait for the next one. */
-        if (stream->flags & UV_HANDLE_READING) {
-          uv__io_start(stream->loop, &stream->io_watcher, POLLIN);
-          uv__stream_osx_interrupt_select(stream);
-        }
-        stream->read_cb(stream, 0, &buf);
-#if defined(__CYGWIN__) || defined(__MSYS__)
-      } else if (errno == ECONNRESET && stream->type == UV_NAMED_PIPE) {
-        uv__stream_eof(stream, &buf);
-        return;
-#endif
-      } else {
-        /* Error. User should call uv_close(). */
-        stream->read_cb(stream, UV__ERR(errno), &buf);
-        if (stream->flags & UV_HANDLE_READING) {
-          stream->flags &= ~UV_HANDLE_READING;
-          uv__io_stop(stream->loop, &stream->io_watcher, POLLIN);
-          if (!uv__io_active(&stream->io_watcher, POLLOUT))
-            uv__handle_stop(stream);
-          uv__stream_osx_interrupt_select(stream);
-        }
-      }
-      return;
-    } else if (nread == 0) {
-      uv__stream_eof(stream, &buf);
-      return;
-    } else {
-      /* Successful read */
-      ssize_t buflen = buf.len;
-
-      if (is_ipc) {
-        err = uv__stream_recv_cmsg(stream, &msg);
-        if (err != 0) {
-          stream->read_cb(stream, err, &buf);
-          return;
-        }
-      }
-
-#if defined(__MVS__)
-      if (is_ipc && msg.msg_controllen > 0) {
-        uv_buf_t blankbuf;
-        int nread;
-        struct iovec *old;
-
-        blankbuf.base = 0;
-        blankbuf.len = 0;
-        old = msg.msg_iov;
-        msg.msg_iov = (struct iovec*) &blankbuf;
-        nread = 0;
-        do {
-          nread = uv__recvmsg(uv__stream_fd(stream), &msg, 0);
-          err = uv__stream_recv_cmsg(stream, &msg);
-          if (err != 0) {
-            stream->read_cb(stream, err, &buf);
-            msg.msg_iov = old;
-            return;
-          }
-        } while (nread == 0 && msg.msg_controllen > 0);
-        msg.msg_iov = old;
-      }
-#endif
-      stream->read_cb(stream, nread, &buf);
-
-      /* Return if we didn't fill the buffer, there is no more data to read. */
-      if (nread < buflen) {
-        stream->flags |= UV_HANDLE_READ_PARTIAL;
-        return;
-      }
-    }
-  }
-}
-
-
-#ifdef __clang__
-# pragma clang diagnostic pop
-#endif
-
-#undef UV__CMSG_FD_COUNT
-#undef UV__CMSG_FD_SIZE
-
-
-int uv_shutdown(uv_shutdown_t* req, uv_stream_t* stream, uv_shutdown_cb cb) {
-  assert(stream->type == UV_TCP ||
-         stream->type == UV_TTY ||
-         stream->type == UV_NAMED_PIPE);
-
-  if (!(stream->flags & UV_HANDLE_WRITABLE) ||
-      stream->flags & UV_HANDLE_SHUT ||
-      stream->flags & UV_HANDLE_SHUTTING ||
-      uv__is_closing(stream)) {
-    return UV_ENOTCONN;
-  }
-
-  assert(uv__stream_fd(stream) >= 0);
-
-  /* Initialize request */
-  uv__req_init(stream->loop, req, UV_SHUTDOWN);
-  req->handle = stream;
-  req->cb = cb;
-  stream->shutdown_req = req;
-  stream->flags |= UV_HANDLE_SHUTTING;
-
-  uv__io_start(stream->loop, &stream->io_watcher, POLLOUT);
-  uv__stream_osx_interrupt_select(stream);
-
-  return 0;
-}
-
-
-static void uv__stream_io(uv_loop_t* loop, uv__io_t* w, unsigned int events) {
-  uv_stream_t* stream;
-
-  stream = container_of(w, uv_stream_t, io_watcher);
-
-  assert(stream->type == UV_TCP ||
-         stream->type == UV_NAMED_PIPE ||
-         stream->type == UV_TTY);
-  assert(!(stream->flags & UV_HANDLE_CLOSING));
-
-  if (stream->connect_req) {
-    uv__stream_connect(stream);
-    return;
-  }
-
-  assert(uv__stream_fd(stream) >= 0);
-
-  /* Ignore POLLHUP here. Even if it's set, there may still be data to read. */
-  if (events & (POLLIN | POLLERR | POLLHUP))
-    uv__read(stream);
-
-  if (uv__stream_fd(stream) == -1)
-    return;  /* read_cb closed stream. */
-
-  /* Short-circuit iff POLLHUP is set, the user is still interested in read
-   * events and uv__read() reported a partial read but not EOF. If the EOF
-   * flag is set, uv__read() called read_cb with err=UV_EOF and we don't
-   * have to do anything. If the partial read flag is not set, we can't
-   * report the EOF yet because there is still data to read.
-   */
-  if ((events & POLLHUP) &&
-      (stream->flags & UV_HANDLE_READING) &&
-      (stream->flags & UV_HANDLE_READ_PARTIAL) &&
-      !(stream->flags & UV_HANDLE_READ_EOF)) {
-    uv_buf_t buf = { NULL, 0 };
-    uv__stream_eof(stream, &buf);
-  }
-
-  if (uv__stream_fd(stream) == -1)
-    return;  /* read_cb closed stream. */
-
-  if (events & (POLLOUT | POLLERR | POLLHUP)) {
-    uv__write(stream);
-    uv__write_callbacks(stream);
-
-    /* Write queue drained. */
-    if (QUEUE_EMPTY(&stream->write_queue))
-      uv__drain(stream);
-  }
-}
-
-
-/**
- * We get called here from directly following a call to connect(2).
- * In order to determine if we've errored out or succeeded must call
- * getsockopt.
- */
-static void uv__stream_connect(uv_stream_t* stream) {
-  int error;
-  uv_connect_t* req = stream->connect_req;
-  socklen_t errorsize = sizeof(int);
-
-  assert(stream->type == UV_TCP || stream->type == UV_NAMED_PIPE);
-  assert(req);
-
-  if (stream->delayed_error) {
-    /* To smooth over the differences between unixes errors that
-     * were reported synchronously on the first connect can be delayed
-     * until the next tick--which is now.
-     */
-    error = stream->delayed_error;
-    stream->delayed_error = 0;
-  } else {
-    /* Normal situation: we need to get the socket error from the kernel. */
-    assert(uv__stream_fd(stream) >= 0);
-    getsockopt(uv__stream_fd(stream),
-               SOL_SOCKET,
-               SO_ERROR,
-               &error,
-               &errorsize);
-    error = UV__ERR(error);
-  }
-
-  if (error == UV__ERR(EINPROGRESS))
-    return;
-
-  stream->connect_req = NULL;
-  uv__req_unregister(stream->loop, req);
-
-  if (error < 0 || QUEUE_EMPTY(&stream->write_queue)) {
-    uv__io_stop(stream->loop, &stream->io_watcher, POLLOUT);
-  }
-
-  if (req->cb)
-    req->cb(req, error);
-
-  if (uv__stream_fd(stream) == -1)
-    return;
-
-  if (error < 0) {
-    uv__stream_flush_write_queue(stream, UV_ECANCELED);
-    uv__write_callbacks(stream);
-  }
-}
-
-
-int uv_write2(uv_write_t* req,
-              uv_stream_t* stream,
-              const uv_buf_t bufs[],
-              unsigned int nbufs,
-              uv_stream_t* send_handle,
-              uv_write_cb cb) {
-  int empty_queue;
-
-  assert(nbufs > 0);
-  assert((stream->type == UV_TCP ||
-          stream->type == UV_NAMED_PIPE ||
-          stream->type == UV_TTY) &&
-         "uv_write (unix) does not yet support other types of streams");
-
-  if (uv__stream_fd(stream) < 0)
-    return UV_EBADF;
-
-  if (!(stream->flags & UV_HANDLE_WRITABLE))
-    return -EPIPE;
-
-  if (send_handle) {
-    if (stream->type != UV_NAMED_PIPE || !((uv_pipe_t*)stream)->ipc)
-      return UV_EINVAL;
-
-    /* XXX We abuse uv_write2() to send over UDP handles to child processes.
-     * Don't call uv__stream_fd() on those handles, it's a macro that on OS X
-     * evaluates to a function that operates on a uv_stream_t with a couple of
-     * OS X specific fields. On other Unices it does (handle)->io_watcher.fd,
-     * which works but only by accident.
-     */
-    if (uv__handle_fd((uv_handle_t*) send_handle) < 0)
-      return UV_EBADF;
-
-#if defined(__CYGWIN__) || defined(__MSYS__)
-    /* Cygwin recvmsg always sets msg_controllen to zero, so we cannot send it.
-       See https://github.com/mirror/newlib-cygwin/blob/86fc4bf0/winsup/cygwin/fhandler_socket.cc#L1736-L1743 */
-    return UV_ENOSYS;
-#endif
-  }
-
-  /* It's legal for write_queue_size > 0 even when the write_queue is empty;
-   * it means there are error-state requests in the write_completed_queue that
-   * will touch up write_queue_size later, see also uv__write_req_finish().
-   * We could check that write_queue is empty instead but that implies making
-   * a write() syscall when we know that the handle is in error mode.
-   */
-  empty_queue = (stream->write_queue_size == 0);
-
-  /* Initialize the req */
-  uv__req_init(stream->loop, req, UV_WRITE);
-  req->cb = cb;
-  req->handle = stream;
-  req->error = 0;
-  req->send_handle = send_handle;
-  QUEUE_INIT(&req->queue);
-
-  req->bufs = req->bufsml;
-  if (nbufs > ARRAY_SIZE(req->bufsml))
-    req->bufs = (uv_buf_t*)uv__malloc(nbufs * sizeof(bufs[0]));
-
-  if (req->bufs == NULL)
-    return UV_ENOMEM;
-
-  memcpy(req->bufs, bufs, nbufs * sizeof(bufs[0]));
-  req->nbufs = nbufs;
-  req->write_index = 0;
-  stream->write_queue_size += uv__count_bufs(bufs, nbufs);
-
-  /* Append the request to write_queue. */
-  QUEUE_INSERT_TAIL(&stream->write_queue, &req->queue);
-
-  /* If the queue was empty when this function began, we should attempt to
-   * do the write immediately. Otherwise start the write_watcher and wait
-   * for the fd to become writable.
-   */
-  if (stream->connect_req) {
-    /* Still connecting, do nothing. */
-  }
-  else if (empty_queue) {
-    uv__write(stream);
-  }
-  else {
-    /*
-     * blocking streams should never have anything in the queue.
-     * if this assert fires then somehow the blocking stream isn't being
-     * sufficiently flushed in uv__write.
-     */
-    assert(!(stream->flags & UV_HANDLE_BLOCKING_WRITES));
-    uv__io_start(stream->loop, &stream->io_watcher, POLLOUT);
-    uv__stream_osx_interrupt_select(stream);
-  }
-
-  return 0;
-}
-
-
-/* The buffers to be written must remain valid until the callback is called.
- * This is not required for the uv_buf_t array.
- */
-int uv_write(uv_write_t* req,
-             uv_stream_t* handle,
-             const uv_buf_t bufs[],
-             unsigned int nbufs,
-             uv_write_cb cb) {
-  return uv_write2(req, handle, bufs, nbufs, NULL, cb);
-}
-
-
-void uv_try_write_cb(uv_write_t* req, int status) {
-  /* Should not be called */
-  abort();
-}
-
-
-int uv_try_write(uv_stream_t* stream,
-                 const uv_buf_t bufs[],
-                 unsigned int nbufs) {
-  int r;
-  int has_pollout;
-  size_t written;
-  size_t req_size;
-  uv_write_t req;
-
-  /* Connecting or already writing some data */
-  if (stream->connect_req != NULL || stream->write_queue_size != 0)
-    return UV_EAGAIN;
-
-  has_pollout = uv__io_active(&stream->io_watcher, POLLOUT);
-
-  r = uv_write(&req, stream, bufs, nbufs, uv_try_write_cb);
-  if (r != 0)
-    return r;
-
-  /* Remove not written bytes from write queue size */
-  written = uv__count_bufs(bufs, nbufs);
-  if (req.bufs != NULL)
-    req_size = uv__write_req_size(&req);
-  else
-    req_size = 0;
-  written -= req_size;
-  stream->write_queue_size -= req_size;
-
-  /* Unqueue request, regardless of immediateness */
-  QUEUE_REMOVE(&req.queue);
-  uv__req_unregister(stream->loop, &req);
-  if (req.bufs != req.bufsml)
-    uv__free(req.bufs);
-  req.bufs = NULL;
-
-  /* Do not poll for writable, if we wasn't before calling this */
-  if (!has_pollout) {
-    uv__io_stop(stream->loop, &stream->io_watcher, POLLOUT);
-    uv__stream_osx_interrupt_select(stream);
-  }
-
-  if (written == 0 && req_size != 0)
-    return req.error < 0 ? req.error : UV_EAGAIN;
-  else
-    return written;
-}
-
-
-int uv_read_start(uv_stream_t* stream,
-                  uv_alloc_cb alloc_cb,
-                  uv_read_cb read_cb) {
-  assert(stream->type == UV_TCP || stream->type == UV_NAMED_PIPE ||
-      stream->type == UV_TTY);
-
-  if (stream->flags & UV_HANDLE_CLOSING)
-    return UV_EINVAL;
-
-  if (!(stream->flags & UV_HANDLE_READABLE))
-    return -ENOTCONN;
-
-  /* The UV_HANDLE_READING flag is irrelevant of the state of the tcp - it just
-   * expresses the desired state of the user.
-   */
-  stream->flags |= UV_HANDLE_READING;
-
-  /* TODO: try to do the read inline? */
-  /* TODO: keep track of tcp state. If we've gotten a EOF then we should
-   * not start the IO watcher.
-   */
-  assert(uv__stream_fd(stream) >= 0);
-  assert(alloc_cb);
-
-  stream->read_cb = read_cb;
-  stream->alloc_cb = alloc_cb;
-
-  uv__io_start(stream->loop, &stream->io_watcher, POLLIN);
-  uv__handle_start(stream);
-  uv__stream_osx_interrupt_select(stream);
-
-  return 0;
-}
-
-
-int uv_read_stop(uv_stream_t* stream) {
-  if (!(stream->flags & UV_HANDLE_READING))
-    return 0;
-
-  stream->flags &= ~UV_HANDLE_READING;
-  uv__io_stop(stream->loop, &stream->io_watcher, POLLIN);
-  if (!uv__io_active(&stream->io_watcher, POLLOUT))
-    uv__handle_stop(stream);
-  uv__stream_osx_interrupt_select(stream);
-
-  stream->read_cb = NULL;
-  stream->alloc_cb = NULL;
-  return 0;
-}
-
-
-int uv_is_readable(const uv_stream_t* stream) {
-  return !!(stream->flags & UV_HANDLE_READABLE);
-}
-
-
-int uv_is_writable(const uv_stream_t* stream) {
-  return !!(stream->flags & UV_HANDLE_WRITABLE);
-}
-
-
-#if defined(__APPLE__)
-int uv___stream_fd(const uv_stream_t* handle) {
-  const uv__stream_select_t* s;
-
-  assert(handle->type == UV_TCP ||
-         handle->type == UV_TTY ||
-         handle->type == UV_NAMED_PIPE);
-
-  s = (const uv__stream_select_t*)handle->select;
-  if (s != NULL)
-    return s->fd;
-
-  return handle->io_watcher.fd;
-}
-#endif /* defined(__APPLE__) */
-
-
-void uv__stream_close(uv_stream_t* handle) {
-  unsigned int i;
-  uv__stream_queued_fds_t* queued_fds;
-
-#if defined(__APPLE__)
-  /* Terminate select loop first */
-  if (handle->select != NULL) {
-    uv__stream_select_t* s;
-
-    s = (uv__stream_select_t*)handle->select;
-
-    uv_sem_post(&s->close_sem);
-    uv_sem_post(&s->async_sem);
-    uv__stream_osx_interrupt_select(handle);
-    uv_thread_join(&s->thread);
-    uv_sem_destroy(&s->close_sem);
-    uv_sem_destroy(&s->async_sem);
-    uv__close(s->fake_fd);
-    uv__close(s->int_fd);
-    uv_close((uv_handle_t*) &s->async, uv__stream_osx_cb_close);
-
-    handle->select = NULL;
-  }
-#endif /* defined(__APPLE__) */
-
-  uv__io_close(handle->loop, &handle->io_watcher);
-  uv_read_stop(handle);
-  uv__handle_stop(handle);
-  handle->flags &= ~(UV_HANDLE_READABLE | UV_HANDLE_WRITABLE);
-
-  if (handle->io_watcher.fd != -1) {
-    /* Don't close stdio file descriptors.  Nothing good comes from it. */
-    if (handle->io_watcher.fd > STDERR_FILENO)
-      uv__close(handle->io_watcher.fd);
-    handle->io_watcher.fd = -1;
-  }
-
-  if (handle->accepted_fd != -1) {
-    uv__close(handle->accepted_fd);
-    handle->accepted_fd = -1;
-  }
-
-  /* Close all queued fds */
-  if (handle->queued_fds != NULL) {
-    queued_fds = (uv__stream_queued_fds_t*)(handle->queued_fds);
-    for (i = 0; i < queued_fds->offset; i++)
-      uv__close(queued_fds->fds[i]);
-    uv__free(handle->queued_fds);
-    handle->queued_fds = NULL;
-  }
-
-  assert(!uv__io_active(&handle->io_watcher, POLLIN | POLLOUT));
-}
-
-
-int uv_stream_set_blocking(uv_stream_t* handle, int blocking) {
-  /* Don't need to check the file descriptor, uv__nonblock()
-   * will fail with EBADF if it's not valid.
-   */
-  return uv__nonblock(uv__stream_fd(handle), !blocking);
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/sysinfo-loadavg.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/sysinfo-loadavg.cpp
deleted file mode 100644
index ebad0e8..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/sysinfo-loadavg.cpp
+++ /dev/null
@@ -1,36 +0,0 @@
-/* Copyright libuv project contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include "uv.h"
-#include "internal.h"
-
-#include <stdint.h>
-#include <sys/sysinfo.h>
-
-void uv_loadavg(double avg[3]) {
-  struct sysinfo info;
-
-  if (sysinfo(&info) < 0) return;
-
-  avg[0] = (double) info.loads[0] / 65536.0;
-  avg[1] = (double) info.loads[1] / 65536.0;
-  avg[2] = (double) info.loads[2] / 65536.0;
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/tcp.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/tcp.cpp
deleted file mode 100644
index 8cedcd6..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/tcp.cpp
+++ /dev/null
@@ -1,433 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include "uv.h"
-#include "internal.h"
-
-#include <stdlib.h>
-#include <unistd.h>
-#include <assert.h>
-#include <errno.h>
-
-
-static int new_socket(uv_tcp_t* handle, int domain, unsigned long flags) {
-  struct sockaddr_storage saddr;
-  socklen_t slen;
-  int sockfd;
-  int err;
-
-  err = uv__socket(domain, SOCK_STREAM, 0);
-  if (err < 0)
-    return err;
-  sockfd = err;
-
-  err = uv__stream_open((uv_stream_t*) handle, sockfd, flags);
-  if (err) {
-    uv__close(sockfd);
-    return err;
-  }
-
-  if (flags & UV_HANDLE_BOUND) {
-    /* Bind this new socket to an arbitrary port */
-    slen = sizeof(saddr);
-    memset(&saddr, 0, sizeof(saddr));
-    if (getsockname(uv__stream_fd(handle), (struct sockaddr*) &saddr, &slen)) {
-      uv__close(sockfd);
-      return UV__ERR(errno);
-    }
-
-    if (bind(uv__stream_fd(handle), (struct sockaddr*) &saddr, slen)) {
-      uv__close(sockfd);
-      return UV__ERR(errno);
-    }
-  }
-
-  return 0;
-}
-
-
-static int maybe_new_socket(uv_tcp_t* handle, int domain, unsigned long flags) {
-  struct sockaddr_storage saddr;
-  socklen_t slen;
-
-  if (domain == AF_UNSPEC) {
-    handle->flags |= flags;
-    return 0;
-  }
-
-  if (uv__stream_fd(handle) != -1) {
-
-    if (flags & UV_HANDLE_BOUND) {
-
-      if (handle->flags & UV_HANDLE_BOUND) {
-        /* It is already bound to a port. */
-        handle->flags |= flags;
-        return 0;
-      }
-
-      /* Query to see if tcp socket is bound. */
-      slen = sizeof(saddr);
-      memset(&saddr, 0, sizeof(saddr));
-      if (getsockname(uv__stream_fd(handle), (struct sockaddr*) &saddr, &slen))
-        return UV__ERR(errno);
-
-      if ((saddr.ss_family == AF_INET6 &&
-          ((struct sockaddr_in6*) &saddr)->sin6_port != 0) ||
-          (saddr.ss_family == AF_INET &&
-          ((struct sockaddr_in*) &saddr)->sin_port != 0)) {
-        /* Handle is already bound to a port. */
-        handle->flags |= flags;
-        return 0;
-      }
-
-      /* Bind to arbitrary port */
-      if (bind(uv__stream_fd(handle), (struct sockaddr*) &saddr, slen))
-        return UV__ERR(errno);
-    }
-
-    handle->flags |= flags;
-    return 0;
-  }
-
-  return new_socket(handle, domain, flags);
-}
-
-
-int uv_tcp_init_ex(uv_loop_t* loop, uv_tcp_t* tcp, unsigned int flags) {
-  int domain;
-
-  /* Use the lower 8 bits for the domain */
-  domain = flags & 0xFF;
-  if (domain != AF_INET && domain != AF_INET6 && domain != AF_UNSPEC)
-    return UV_EINVAL;
-
-  if (flags & ~0xFF)
-    return UV_EINVAL;
-
-  uv__stream_init(loop, (uv_stream_t*)tcp, UV_TCP);
-
-  /* If anything fails beyond this point we need to remove the handle from
-   * the handle queue, since it was added by uv__handle_init in uv_stream_init.
-   */
-
-  if (domain != AF_UNSPEC) {
-    int err = maybe_new_socket(tcp, domain, 0);
-    if (err) {
-      QUEUE_REMOVE(&tcp->handle_queue);
-      return err;
-    }
-  }
-
-  return 0;
-}
-
-
-int uv_tcp_init(uv_loop_t* loop, uv_tcp_t* tcp) {
-  return uv_tcp_init_ex(loop, tcp, AF_UNSPEC);
-}
-
-
-int uv__tcp_bind(uv_tcp_t* tcp,
-                 const struct sockaddr* addr,
-                 unsigned int addrlen,
-                 unsigned int flags) {
-  int err;
-  int on;
-
-  /* Cannot set IPv6-only mode on non-IPv6 socket. */
-  if ((flags & UV_TCP_IPV6ONLY) && addr->sa_family != AF_INET6)
-    return UV_EINVAL;
-
-  err = maybe_new_socket(tcp, addr->sa_family, 0);
-  if (err)
-    return err;
-
-  on = 1;
-  if (setsockopt(tcp->io_watcher.fd, SOL_SOCKET, SO_REUSEADDR, &on, sizeof(on)))
-    return UV__ERR(errno);
-
-#ifndef __OpenBSD__
-#ifdef IPV6_V6ONLY
-  if (addr->sa_family == AF_INET6) {
-    on = (flags & UV_TCP_IPV6ONLY) != 0;
-    if (setsockopt(tcp->io_watcher.fd,
-                   IPPROTO_IPV6,
-                   IPV6_V6ONLY,
-                   &on,
-                   sizeof on) == -1) {
-#if defined(__MVS__)
-      if (errno == EOPNOTSUPP)
-        return UV_EINVAL;
-#endif
-      return UV__ERR(errno);
-    }
-  }
-#endif
-#endif
-
-  errno = 0;
-  if (bind(tcp->io_watcher.fd, addr, addrlen) && errno != EADDRINUSE) {
-    if (errno == EAFNOSUPPORT)
-      /* OSX, other BSDs and SunoS fail with EAFNOSUPPORT when binding a
-       * socket created with AF_INET to an AF_INET6 address or vice versa. */
-      return UV_EINVAL;
-    return UV__ERR(errno);
-  }
-  tcp->delayed_error = UV__ERR(errno);
-
-  tcp->flags |= UV_HANDLE_BOUND;
-  if (addr->sa_family == AF_INET6)
-    tcp->flags |= UV_HANDLE_IPV6;
-
-  return 0;
-}
-
-
-int uv__tcp_connect(uv_connect_t* req,
-                    uv_tcp_t* handle,
-                    const struct sockaddr* addr,
-                    unsigned int addrlen,
-                    uv_connect_cb cb) {
-  int err;
-  int r;
-
-  assert(handle->type == UV_TCP);
-
-  if (handle->connect_req != NULL)
-    return UV_EALREADY;  /* FIXME(bnoordhuis) UV_EINVAL or maybe UV_EBUSY. */
-
-  err = maybe_new_socket(handle,
-                         addr->sa_family,
-                         UV_HANDLE_READABLE | UV_HANDLE_WRITABLE);
-  if (err)
-    return err;
-
-  handle->delayed_error = 0;
-
-  do {
-    errno = 0;
-    r = connect(uv__stream_fd(handle), addr, addrlen);
-  } while (r == -1 && errno == EINTR);
-
-  /* We not only check the return value, but also check the errno != 0.
-   * Because in rare cases connect() will return -1 but the errno
-   * is 0 (for example, on Android 4.3, OnePlus phone A0001_12_150227)
-   * and actually the tcp three-way handshake is completed.
-   */
-  if (r == -1 && errno != 0) {
-    if (errno == EINPROGRESS)
-      ; /* not an error */
-    else if (errno == ECONNREFUSED
-#if defined(__OpenBSD__)
-      || errno == EINVAL
-#endif
-      )
-    /* If we get ECONNREFUSED (Solaris) or EINVAL (OpenBSD) wait until the
-     * next tick to report the error. Solaris and OpenBSD wants to report
-     * immediately -- other unixes want to wait.
-     */
-      handle->delayed_error = UV__ERR(ECONNREFUSED);
-    else
-      return UV__ERR(errno);
-  }
-
-  uv__req_init(handle->loop, req, UV_CONNECT);
-  req->cb = cb;
-  req->handle = (uv_stream_t*) handle;
-  QUEUE_INIT(&req->queue);
-  handle->connect_req = req;
-
-  uv__io_start(handle->loop, &handle->io_watcher, POLLOUT);
-
-  if (handle->delayed_error)
-    uv__io_feed(handle->loop, &handle->io_watcher);
-
-  return 0;
-}
-
-
-int uv_tcp_open(uv_tcp_t* handle, uv_os_sock_t sock) {
-  int err;
-
-  if (uv__fd_exists(handle->loop, sock))
-    return UV_EEXIST;
-
-  err = uv__nonblock(sock, 1);
-  if (err)
-    return err;
-
-  return uv__stream_open((uv_stream_t*)handle,
-                         sock,
-                         UV_HANDLE_READABLE | UV_HANDLE_WRITABLE);
-}
-
-
-int uv_tcp_getsockname(const uv_tcp_t* handle,
-                       struct sockaddr* name,
-                       int* namelen) {
-
-  if (handle->delayed_error)
-    return handle->delayed_error;
-
-  return uv__getsockpeername((const uv_handle_t*) handle,
-                             getsockname,
-                             name,
-                             namelen);
-}
-
-
-int uv_tcp_getpeername(const uv_tcp_t* handle,
-                       struct sockaddr* name,
-                       int* namelen) {
-
-  if (handle->delayed_error)
-    return handle->delayed_error;
-
-  return uv__getsockpeername((const uv_handle_t*) handle,
-                             getpeername,
-                             name,
-                             namelen);
-}
-
-
-int uv_tcp_listen(uv_tcp_t* tcp, int backlog, uv_connection_cb cb) {
-  static int single_accept = -1;
-  unsigned long flags;
-  int err;
-
-  if (tcp->delayed_error)
-    return tcp->delayed_error;
-
-  if (single_accept == -1) {
-    const char* val = getenv("UV_TCP_SINGLE_ACCEPT");
-    single_accept = (val != NULL && atoi(val) != 0);  /* Off by default. */
-  }
-
-  if (single_accept)
-    tcp->flags |= UV_HANDLE_TCP_SINGLE_ACCEPT;
-
-  flags = 0;
-#if defined(__MVS__)
-  /* on zOS the listen call does not bind automatically
-     if the socket is unbound. Hence the manual binding to
-     an arbitrary port is required to be done manually
-  */
-  flags |= UV_HANDLE_BOUND;
-#endif
-  err = maybe_new_socket(tcp, AF_INET, flags);
-  if (err)
-    return err;
-
-  if (listen(tcp->io_watcher.fd, backlog))
-    return UV__ERR(errno);
-
-  tcp->connection_cb = cb;
-  tcp->flags |= UV_HANDLE_BOUND;
-
-  /* Start listening for connections. */
-  tcp->io_watcher.cb = uv__server_io;
-  uv__io_start(tcp->loop, &tcp->io_watcher, POLLIN);
-
-  return 0;
-}
-
-
-int uv__tcp_nodelay(int fd, int on) {
-  if (setsockopt(fd, IPPROTO_TCP, TCP_NODELAY, &on, sizeof(on)))
-    return UV__ERR(errno);
-  return 0;
-}
-
-
-int uv__tcp_keepalive(int fd, int on, unsigned int delay) {
-  if (setsockopt(fd, SOL_SOCKET, SO_KEEPALIVE, &on, sizeof(on)))
-    return UV__ERR(errno);
-
-#ifdef TCP_KEEPIDLE
-  if (on && setsockopt(fd, IPPROTO_TCP, TCP_KEEPIDLE, &delay, sizeof(delay)))
-    return UV__ERR(errno);
-#endif
-
-  /* Solaris/SmartOS, if you don't support keep-alive,
-   * then don't advertise it in your system headers...
-   */
-  /* FIXME(bnoordhuis) That's possibly because sizeof(delay) should be 1. */
-#if defined(TCP_KEEPALIVE) && !defined(__sun)
-  if (on && setsockopt(fd, IPPROTO_TCP, TCP_KEEPALIVE, &delay, sizeof(delay)))
-    return UV__ERR(errno);
-#endif
-
-  return 0;
-}
-
-
-int uv_tcp_nodelay(uv_tcp_t* handle, int on) {
-  int err;
-
-  if (uv__stream_fd(handle) != -1) {
-    err = uv__tcp_nodelay(uv__stream_fd(handle), on);
-    if (err)
-      return err;
-  }
-
-  if (on)
-    handle->flags |= UV_HANDLE_TCP_NODELAY;
-  else
-    handle->flags &= ~UV_HANDLE_TCP_NODELAY;
-
-  return 0;
-}
-
-
-int uv_tcp_keepalive(uv_tcp_t* handle, int on, unsigned int delay) {
-  int err;
-
-  if (uv__stream_fd(handle) != -1) {
-    err =uv__tcp_keepalive(uv__stream_fd(handle), on, delay);
-    if (err)
-      return err;
-  }
-
-  if (on)
-    handle->flags |= UV_HANDLE_TCP_KEEPALIVE;
-  else
-    handle->flags &= ~UV_HANDLE_TCP_KEEPALIVE;
-
-  /* TODO Store delay if uv__stream_fd(handle) == -1 but don't want to enlarge
-   *      uv_tcp_t with an int that's almost never used...
-   */
-
-  return 0;
-}
-
-
-int uv_tcp_simultaneous_accepts(uv_tcp_t* handle, int enable) {
-  if (enable)
-    handle->flags &= ~UV_HANDLE_TCP_SINGLE_ACCEPT;
-  else
-    handle->flags |= UV_HANDLE_TCP_SINGLE_ACCEPT;
-  return 0;
-}
-
-
-void uv__tcp_close(uv_tcp_t* handle) {
-  uv__stream_close((uv_stream_t*)handle);
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/thread.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/thread.cpp
deleted file mode 100644
index 012cd6a..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/thread.cpp
+++ /dev/null
@@ -1,844 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include "uv.h"
-#include "internal.h"
-
-#include <pthread.h>
-#include <assert.h>
-#include <errno.h>
-
-#include <sys/time.h>
-#include <sys/resource.h>  /* getrlimit() */
-#include <unistd.h>  /* getpagesize() */
-
-#include <limits.h>
-
-#ifdef __MVS__
-#include <sys/ipc.h>
-#include <sys/sem.h>
-#endif
-
-#if defined(__GLIBC__) && !defined(__UCLIBC__)
-#include <gnu/libc-version.h>  /* gnu_get_libc_version() */
-#endif
-
-#undef NANOSEC
-#define NANOSEC ((uint64_t) 1e9)
-
-#if defined(PTHREAD_BARRIER_SERIAL_THREAD)
-STATIC_ASSERT(sizeof(uv_barrier_t) == sizeof(pthread_barrier_t));
-#endif
-
-/* Note: guard clauses should match uv_barrier_t's in include/uv/unix.h. */
-#if defined(_AIX) || \
-    defined(__OpenBSD__) || \
-    !defined(PTHREAD_BARRIER_SERIAL_THREAD)
-int uv_barrier_init(uv_barrier_t* barrier, unsigned int count) {
-  struct _uv_barrier* b;
-  int rc;
-
-  if (barrier == NULL || count == 0)
-    return UV_EINVAL;
-
-  b = (_uv_barrier*)uv__malloc(sizeof(*b));
-  if (b == NULL)
-    return UV_ENOMEM;
-
-  b->in = 0;
-  b->out = 0;
-  b->threshold = count;
-
-  rc = uv_mutex_init(&b->mutex);
-  if (rc != 0)
-    goto error2;
-
-  rc = uv_cond_init(&b->cond);
-  if (rc != 0)
-    goto error;
-
-  barrier->b = b;
-  return 0;
-
-error:
-  uv_mutex_destroy(&b->mutex);
-error2:
-  uv__free(b);
-  return rc;
-}
-
-int uv_barrier_wait(uv_barrier_t* barrier) {
-  struct _uv_barrier* b;
-  int last;
-
-  if (barrier == NULL || barrier->b == NULL)
-    return UV_EINVAL;
-
-  b = barrier->b;
-  /* Lock the mutex*/
-  uv_mutex_lock(&b->mutex);
-
-  if (++b->in == b->threshold) {
-    b->in = 0;
-    b->out = b->threshold;
-    uv_cond_signal(&b->cond);
-  } else {
-    do
-      uv_cond_wait(&b->cond, &b->mutex);
-    while (b->in != 0);
-  }
-
-  last = (--b->out == 0);
-  if (!last)
-    uv_cond_signal(&b->cond);  /* Not needed for last thread. */
-
-  uv_mutex_unlock(&b->mutex);
-  return last;
-}
-
-void uv_barrier_destroy(uv_barrier_t* barrier) {
-  struct _uv_barrier* b;
-
-  b = barrier->b;
-  uv_mutex_lock(&b->mutex);
-
-  assert(b->in == 0);
-  assert(b->out == 0);
-
-  if (b->in != 0 || b->out != 0)
-    abort();
-
-  uv_mutex_unlock(&b->mutex);
-  uv_mutex_destroy(&b->mutex);
-  uv_cond_destroy(&b->cond);
-
-  uv__free(barrier->b);
-  barrier->b = NULL;
-}
-
-#else
-
-int uv_barrier_init(uv_barrier_t* barrier, unsigned int count) {
-  return UV__ERR(pthread_barrier_init(barrier, NULL, count));
-}
-
-
-int uv_barrier_wait(uv_barrier_t* barrier) {
-  int rc;
-
-  rc = pthread_barrier_wait(barrier);
-  if (rc != 0)
-    if (rc != PTHREAD_BARRIER_SERIAL_THREAD)
-      abort();
-
-  return rc == PTHREAD_BARRIER_SERIAL_THREAD;
-}
-
-
-void uv_barrier_destroy(uv_barrier_t* barrier) {
-  if (pthread_barrier_destroy(barrier))
-    abort();
-}
-
-#endif
-
-
-/* On MacOS, threads other than the main thread are created with a reduced
- * stack size by default.  Adjust to RLIMIT_STACK aligned to the page size.
- *
- * On Linux, threads created by musl have a much smaller stack than threads
- * created by glibc (80 vs. 2048 or 4096 kB.)  Follow glibc for consistency.
- */
-static size_t thread_stack_size(void) {
-#if defined(__APPLE__) || defined(__linux__)
-  struct rlimit lim;
-
-  if (getrlimit(RLIMIT_STACK, &lim))
-    abort();
-
-  if (lim.rlim_cur != RLIM_INFINITY) {
-    /* pthread_attr_setstacksize() expects page-aligned values. */
-    lim.rlim_cur -= lim.rlim_cur % (rlim_t) getpagesize();
-
-    /* Musl's PTHREAD_STACK_MIN is 2 KB on all architectures, which is
-     * too small to safely receive signals on.
-     *
-     * Musl's PTHREAD_STACK_MIN + MINSIGSTKSZ == 8192 on arm64 (which has
-     * the largest MINSIGSTKSZ of the architectures that musl supports) so
-     * let's use that as a lower bound.
-     *
-     * We use a hardcoded value because PTHREAD_STACK_MIN + MINSIGSTKSZ
-     * is between 28 and 133 KB when compiling against glibc, depending
-     * on the architecture.
-     */
-    if (lim.rlim_cur >= 8192)
-      if (lim.rlim_cur >= (rlim_t) PTHREAD_STACK_MIN)
-        return lim.rlim_cur;
-  }
-#endif
-
-#if !defined(__linux__)
-  return 0;
-#elif defined(__PPC__) || defined(__ppc__) || defined(__powerpc__)
-  return 4 << 20;  /* glibc default. */
-#else
-  return 2 << 20;  /* glibc default. */
-#endif
-}
-
-
-int uv_thread_create(uv_thread_t *tid, void (*entry)(void *arg), void *arg) {
-  uv_thread_options_t params;
-  params.flags = UV_THREAD_NO_FLAGS;
-  return uv_thread_create_ex(tid, &params, entry, arg);
-}
-
-int uv_thread_create_ex(uv_thread_t* tid,
-                        const uv_thread_options_t* params,
-                        void (*entry)(void *arg),
-                        void *arg) {
-  int err;
-  pthread_attr_t* attr;
-  pthread_attr_t attr_storage;
-  size_t pagesize;
-  size_t stack_size;
-
-  stack_size =
-      params->flags & UV_THREAD_HAS_STACK_SIZE ? params->stack_size : 0;
-
-  attr = NULL;
-  if (stack_size == 0) {
-    stack_size = thread_stack_size();
-  } else {
-    pagesize = (size_t)getpagesize();
-    /* Round up to the nearest page boundary. */
-    stack_size = (stack_size + pagesize - 1) &~ (pagesize - 1);
-#ifdef PTHREAD_STACK_MIN
-    if (stack_size < (size_t) PTHREAD_STACK_MIN)
-      stack_size = PTHREAD_STACK_MIN;
-#endif
-  }
-
-  if (stack_size > 0) {
-    attr = &attr_storage;
-
-    if (pthread_attr_init(attr))
-      abort();
-
-    if (pthread_attr_setstacksize(attr, stack_size))
-      abort();
-  }
-
-  err = pthread_create(tid, attr, (void*(*)(void*)) (void(*)(void)) entry, arg);
-
-  if (attr != NULL)
-    pthread_attr_destroy(attr);
-
-  return UV__ERR(err);
-}
-
-
-uv_thread_t uv_thread_self(void) {
-  return pthread_self();
-}
-
-int uv_thread_join(uv_thread_t *tid) {
-  return UV__ERR(pthread_join(*tid, NULL));
-}
-
-
-int uv_thread_equal(const uv_thread_t* t1, const uv_thread_t* t2) {
-  return pthread_equal(*t1, *t2);
-}
-
-
-int uv_mutex_init(uv_mutex_t* mutex) {
-#if defined(NDEBUG) || !defined(PTHREAD_MUTEX_ERRORCHECK)
-  return UV__ERR(pthread_mutex_init(mutex, NULL));
-#else
-  pthread_mutexattr_t attr;
-  int err;
-
-  if (pthread_mutexattr_init(&attr))
-    abort();
-
-  if (pthread_mutexattr_settype(&attr, PTHREAD_MUTEX_ERRORCHECK))
-    abort();
-
-  err = pthread_mutex_init(mutex, &attr);
-
-  if (pthread_mutexattr_destroy(&attr))
-    abort();
-
-  return UV__ERR(err);
-#endif
-}
-
-
-int uv_mutex_init_recursive(uv_mutex_t* mutex) {
-  pthread_mutexattr_t attr;
-  int err;
-
-  if (pthread_mutexattr_init(&attr))
-    abort();
-
-  if (pthread_mutexattr_settype(&attr, PTHREAD_MUTEX_RECURSIVE))
-    abort();
-
-  err = pthread_mutex_init(mutex, &attr);
-
-  if (pthread_mutexattr_destroy(&attr))
-    abort();
-
-  return UV__ERR(err);
-}
-
-
-void uv_mutex_destroy(uv_mutex_t* mutex) {
-  if (pthread_mutex_destroy(mutex))
-    abort();
-}
-
-
-void uv_mutex_lock(uv_mutex_t* mutex) {
-  if (pthread_mutex_lock(mutex))
-    abort();
-}
-
-
-int uv_mutex_trylock(uv_mutex_t* mutex) {
-  int err;
-
-  err = pthread_mutex_trylock(mutex);
-  if (err) {
-    if (err != EBUSY && err != EAGAIN)
-      abort();
-    return UV_EBUSY;
-  }
-
-  return 0;
-}
-
-
-void uv_mutex_unlock(uv_mutex_t* mutex) {
-  if (pthread_mutex_unlock(mutex))
-    abort();
-}
-
-
-int uv_rwlock_init(uv_rwlock_t* rwlock) {
-  return UV__ERR(pthread_rwlock_init(rwlock, NULL));
-}
-
-
-void uv_rwlock_destroy(uv_rwlock_t* rwlock) {
-  if (pthread_rwlock_destroy(rwlock))
-    abort();
-}
-
-
-void uv_rwlock_rdlock(uv_rwlock_t* rwlock) {
-  if (pthread_rwlock_rdlock(rwlock))
-    abort();
-}
-
-
-int uv_rwlock_tryrdlock(uv_rwlock_t* rwlock) {
-  int err;
-
-  err = pthread_rwlock_tryrdlock(rwlock);
-  if (err) {
-    if (err != EBUSY && err != EAGAIN)
-      abort();
-    return UV_EBUSY;
-  }
-
-  return 0;
-}
-
-
-void uv_rwlock_rdunlock(uv_rwlock_t* rwlock) {
-  if (pthread_rwlock_unlock(rwlock))
-    abort();
-}
-
-
-void uv_rwlock_wrlock(uv_rwlock_t* rwlock) {
-  if (pthread_rwlock_wrlock(rwlock))
-    abort();
-}
-
-
-int uv_rwlock_trywrlock(uv_rwlock_t* rwlock) {
-  int err;
-
-  err = pthread_rwlock_trywrlock(rwlock);
-  if (err) {
-    if (err != EBUSY && err != EAGAIN)
-      abort();
-    return UV_EBUSY;
-  }
-
-  return 0;
-}
-
-
-void uv_rwlock_wrunlock(uv_rwlock_t* rwlock) {
-  if (pthread_rwlock_unlock(rwlock))
-    abort();
-}
-
-
-void uv_once(uv_once_t* guard, void (*callback)(void)) {
-  if (pthread_once(guard, callback))
-    abort();
-}
-
-#if defined(__APPLE__) && defined(__MACH__)
-
-int uv_sem_init(uv_sem_t* sem, unsigned int value) {
-  kern_return_t err;
-
-  err = semaphore_create(mach_task_self(), sem, SYNC_POLICY_FIFO, value);
-  if (err == KERN_SUCCESS)
-    return 0;
-  if (err == KERN_INVALID_ARGUMENT)
-    return UV_EINVAL;
-  if (err == KERN_RESOURCE_SHORTAGE)
-    return UV_ENOMEM;
-
-  abort();
-  return UV_EINVAL;  /* Satisfy the compiler. */
-}
-
-
-void uv_sem_destroy(uv_sem_t* sem) {
-  if (semaphore_destroy(mach_task_self(), *sem))
-    abort();
-}
-
-
-void uv_sem_post(uv_sem_t* sem) {
-  if (semaphore_signal(*sem))
-    abort();
-}
-
-
-void uv_sem_wait(uv_sem_t* sem) {
-  int r;
-
-  do
-    r = semaphore_wait(*sem);
-  while (r == KERN_ABORTED);
-
-  if (r != KERN_SUCCESS)
-    abort();
-}
-
-
-int uv_sem_trywait(uv_sem_t* sem) {
-  mach_timespec_t interval;
-  kern_return_t err;
-
-  interval.tv_sec = 0;
-  interval.tv_nsec = 0;
-
-  err = semaphore_timedwait(*sem, interval);
-  if (err == KERN_SUCCESS)
-    return 0;
-  if (err == KERN_OPERATION_TIMED_OUT)
-    return UV_EAGAIN;
-
-  abort();
-  return UV_EINVAL;  /* Satisfy the compiler. */
-}
-
-#else /* !(defined(__APPLE__) && defined(__MACH__)) */
-
-#if defined(__GLIBC__) && !defined(__UCLIBC__)
-
-/* Hack around https://sourceware.org/bugzilla/show_bug.cgi?id=12674
- * by providing a custom implementation for glibc < 2.21 in terms of other
- * concurrency primitives.
- * Refs: https://github.com/nodejs/node/issues/19903 */
-
-/* To preserve ABI compatibility, we treat the uv_sem_t as storage for
- * a pointer to the actual struct we're using underneath. */
-
-static uv_once_t glibc_version_check_once = UV_ONCE_INIT;
-static int platform_needs_custom_semaphore = 0;
-
-static void glibc_version_check(void) {
-  const char* version = gnu_get_libc_version();
-  platform_needs_custom_semaphore =
-      version[0] == '2' && version[1] == '.' &&
-      atoi(version + 2) < 21;
-}
-
-#elif defined(__MVS__)
-
-#define platform_needs_custom_semaphore 1
-
-#else /* !defined(__GLIBC__) && !defined(__MVS__) */
-
-#define platform_needs_custom_semaphore 0
-
-#endif
-
-typedef struct uv_semaphore_s {
-  uv_mutex_t mutex;
-  uv_cond_t cond;
-  unsigned int value;
-} uv_semaphore_t;
-
-#if (defined(__GLIBC__) && !defined(__UCLIBC__)) || \
-    platform_needs_custom_semaphore
-STATIC_ASSERT(sizeof(uv_sem_t) >= sizeof(uv_semaphore_t*));
-#endif
-
-static int uv__custom_sem_init(uv_sem_t* sem_, unsigned int value) {
-  int err;
-  uv_semaphore_t* sem;
-
-  sem = (uv_semaphore_t*)uv__malloc(sizeof(*sem));
-  if (sem == NULL)
-    return UV_ENOMEM;
-
-  if ((err = uv_mutex_init(&sem->mutex)) != 0) {
-    uv__free(sem);
-    return err;
-  }
-
-  if ((err = uv_cond_init(&sem->cond)) != 0) {
-    uv_mutex_destroy(&sem->mutex);
-    uv__free(sem);
-    return err;
-  }
-
-  sem->value = value;
-  *(uv_semaphore_t**)sem_ = sem;
-  return 0;
-}
-
-
-static void uv__custom_sem_destroy(uv_sem_t* sem_) {
-  uv_semaphore_t* sem;
-
-  sem = *(uv_semaphore_t**)sem_;
-  uv_cond_destroy(&sem->cond);
-  uv_mutex_destroy(&sem->mutex);
-  uv__free(sem);
-}
-
-
-static void uv__custom_sem_post(uv_sem_t* sem_) {
-  uv_semaphore_t* sem;
-
-  sem = *(uv_semaphore_t**)sem_;
-  uv_mutex_lock(&sem->mutex);
-  sem->value++;
-  if (sem->value == 1)
-    uv_cond_signal(&sem->cond);
-  uv_mutex_unlock(&sem->mutex);
-}
-
-
-static void uv__custom_sem_wait(uv_sem_t* sem_) {
-  uv_semaphore_t* sem;
-
-  sem = *(uv_semaphore_t**)sem_;
-  uv_mutex_lock(&sem->mutex);
-  while (sem->value == 0)
-    uv_cond_wait(&sem->cond, &sem->mutex);
-  sem->value--;
-  uv_mutex_unlock(&sem->mutex);
-}
-
-
-static int uv__custom_sem_trywait(uv_sem_t* sem_) {
-  uv_semaphore_t* sem;
-
-  sem = *(uv_semaphore_t**)sem_;
-  if (uv_mutex_trylock(&sem->mutex) != 0)
-    return UV_EAGAIN;
-
-  if (sem->value == 0) {
-    uv_mutex_unlock(&sem->mutex);
-    return UV_EAGAIN;
-  }
-
-  sem->value--;
-  uv_mutex_unlock(&sem->mutex);
-
-  return 0;
-}
-
-static int uv__sem_init(uv_sem_t* sem, unsigned int value) {
-  if (sem_init(sem, 0, value))
-    return UV__ERR(errno);
-  return 0;
-}
-
-
-static void uv__sem_destroy(uv_sem_t* sem) {
-  if (sem_destroy(sem))
-    abort();
-}
-
-
-static void uv__sem_post(uv_sem_t* sem) {
-  if (sem_post(sem))
-    abort();
-}
-
-
-static void uv__sem_wait(uv_sem_t* sem) {
-  int r;
-
-  do
-    r = sem_wait(sem);
-  while (r == -1 && errno == EINTR);
-
-  if (r)
-    abort();
-}
-
-
-static int uv__sem_trywait(uv_sem_t* sem) {
-  int r;
-
-  do
-    r = sem_trywait(sem);
-  while (r == -1 && errno == EINTR);
-
-  if (r) {
-    if (errno == EAGAIN)
-      return UV_EAGAIN;
-    abort();
-  }
-
-  return 0;
-}
-
-int uv_sem_init(uv_sem_t* sem, unsigned int value) {
-#if defined(__GLIBC__) && !defined(__UCLIBC__)
-  uv_once(&glibc_version_check_once, glibc_version_check);
-#endif
-
-  if (platform_needs_custom_semaphore)
-    return uv__custom_sem_init(sem, value);
-  else
-    return uv__sem_init(sem, value);
-}
-
-
-void uv_sem_destroy(uv_sem_t* sem) {
-  if (platform_needs_custom_semaphore)
-    uv__custom_sem_destroy(sem);
-  else
-    uv__sem_destroy(sem);
-}
-
-
-void uv_sem_post(uv_sem_t* sem) {
-  if (platform_needs_custom_semaphore)
-    uv__custom_sem_post(sem);
-  else
-    uv__sem_post(sem);
-}
-
-
-void uv_sem_wait(uv_sem_t* sem) {
-  if (platform_needs_custom_semaphore)
-    uv__custom_sem_wait(sem);
-  else
-    uv__sem_wait(sem);
-}
-
-
-int uv_sem_trywait(uv_sem_t* sem) {
-  if (platform_needs_custom_semaphore)
-    return uv__custom_sem_trywait(sem);
-  else
-    return uv__sem_trywait(sem);
-}
-
-#endif /* defined(__APPLE__) && defined(__MACH__) */
-
-
-#if defined(__APPLE__) && defined(__MACH__) || defined(__MVS__)
-
-int uv_cond_init(uv_cond_t* cond) {
-  return UV__ERR(pthread_cond_init(cond, NULL));
-}
-
-#else /* !(defined(__APPLE__) && defined(__MACH__)) */
-
-int uv_cond_init(uv_cond_t* cond) {
-  pthread_condattr_t attr;
-  int err;
-
-  err = pthread_condattr_init(&attr);
-  if (err)
-    return UV__ERR(err);
-
-#if !(defined(__ANDROID_API__) && __ANDROID_API__ < 21)
-  err = pthread_condattr_setclock(&attr, CLOCK_MONOTONIC);
-  if (err)
-    goto error2;
-#endif
-
-  err = pthread_cond_init(cond, &attr);
-  if (err)
-    goto error2;
-
-  err = pthread_condattr_destroy(&attr);
-  if (err)
-    goto error;
-
-  return 0;
-
-error:
-  pthread_cond_destroy(cond);
-error2:
-  pthread_condattr_destroy(&attr);
-  return UV__ERR(err);
-}
-
-#endif /* defined(__APPLE__) && defined(__MACH__) */
-
-void uv_cond_destroy(uv_cond_t* cond) {
-#if defined(__APPLE__) && defined(__MACH__)
-  /* It has been reported that destroying condition variables that have been
-   * signalled but not waited on can sometimes result in application crashes.
-   * See https://codereview.chromium.org/1323293005.
-   */
-  pthread_mutex_t mutex;
-  struct timespec ts;
-  int err;
-
-  if (pthread_mutex_init(&mutex, NULL))
-    abort();
-
-  if (pthread_mutex_lock(&mutex))
-    abort();
-
-  ts.tv_sec = 0;
-  ts.tv_nsec = 1;
-
-  err = pthread_cond_timedwait_relative_np(cond, &mutex, &ts);
-  if (err != 0 && err != ETIMEDOUT)
-    abort();
-
-  if (pthread_mutex_unlock(&mutex))
-    abort();
-
-  if (pthread_mutex_destroy(&mutex))
-    abort();
-#endif /* defined(__APPLE__) && defined(__MACH__) */
-
-  if (pthread_cond_destroy(cond))
-    abort();
-}
-
-void uv_cond_signal(uv_cond_t* cond) {
-  if (pthread_cond_signal(cond))
-    abort();
-}
-
-void uv_cond_broadcast(uv_cond_t* cond) {
-  if (pthread_cond_broadcast(cond))
-    abort();
-}
-
-void uv_cond_wait(uv_cond_t* cond, uv_mutex_t* mutex) {
-  if (pthread_cond_wait(cond, mutex))
-    abort();
-}
-
-
-int uv_cond_timedwait(uv_cond_t* cond, uv_mutex_t* mutex, uint64_t timeout) {
-  int r;
-  struct timespec ts;
-#if defined(__MVS__)
-  struct timeval tv;
-#endif
-
-#if defined(__APPLE__) && defined(__MACH__)
-  ts.tv_sec = timeout / NANOSEC;
-  ts.tv_nsec = timeout % NANOSEC;
-  r = pthread_cond_timedwait_relative_np(cond, mutex, &ts);
-#else
-#if defined(__MVS__)
-  if (gettimeofday(&tv, NULL))
-    abort();
-  timeout += tv.tv_sec * NANOSEC + tv.tv_usec * 1e3;
-#else
-  timeout += uv__hrtime(UV_CLOCK_PRECISE);
-#endif
-  ts.tv_sec = timeout / NANOSEC;
-  ts.tv_nsec = timeout % NANOSEC;
-#if defined(__ANDROID_API__) && __ANDROID_API__ < 21
-
-  /*
-   * The bionic pthread implementation doesn't support CLOCK_MONOTONIC,
-   * but has this alternative function instead.
-   */
-  r = pthread_cond_timedwait_monotonic_np(cond, mutex, &ts);
-#else
-  r = pthread_cond_timedwait(cond, mutex, &ts);
-#endif /* __ANDROID_API__ */
-#endif
-
-
-  if (r == 0)
-    return 0;
-
-  if (r == ETIMEDOUT)
-    return UV_ETIMEDOUT;
-
-  abort();
-#ifndef __SUNPRO_C
-  return UV_EINVAL;  /* Satisfy the compiler. */
-#endif
-}
-
-
-int uv_key_create(uv_key_t* key) {
-  return UV__ERR(pthread_key_create(key, NULL));
-}
-
-
-void uv_key_delete(uv_key_t* key) {
-  if (pthread_key_delete(*key))
-    abort();
-}
-
-
-void* uv_key_get(uv_key_t* key) {
-  return pthread_getspecific(*key);
-}
-
-
-void uv_key_set(uv_key_t* key, void* value) {
-  if (pthread_setspecific(*key, value))
-    abort();
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/tty.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/tty.cpp
deleted file mode 100644
index 5f68140..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/tty.cpp
+++ /dev/null
@@ -1,368 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include "uv.h"
-#include "internal.h"
-#include "spinlock.h"
-
-#include <stdlib.h>
-#include <assert.h>
-#include <unistd.h>
-#include <termios.h>
-#include <errno.h>
-#include <sys/ioctl.h>
-
-#if defined(__MVS__) && !defined(IMAXBEL)
-#define IMAXBEL 0
-#endif
-
-static int orig_termios_fd = -1;
-static struct termios orig_termios;
-static uv_spinlock_t termios_spinlock = UV_SPINLOCK_INITIALIZER;
-
-static int uv__tty_is_peripheral(const int fd) {
-  int result;
-#if defined(__linux__) || defined(__FreeBSD__) || defined(__FreeBSD_kernel__)
-  int dummy;
-
-  result = ioctl(fd, TIOCGPTN, &dummy) != 0;
-#elif defined(__APPLE__)
-  char dummy[256];
-
-  result = ioctl(fd, TIOCPTYGNAME, &dummy) != 0;
-#elif defined(__NetBSD__)
-  /*
-   * NetBSD as an extension returns with ptsname(3) and ptsname_r(3) the
-   * peripheral device name for both descriptors, the controller one and
-   * peripheral one.
-   *
-   * Implement function to compare major device number with pts devices.
-   *
-   * The major numbers are machine-dependent, on NetBSD/amd64 they are
-   * respectively:
-   *  - controller tty: ptc - major 6
-   *  - peripheral tty:  pts - major 5
-   */
-
-  struct stat sb;
-  /* Lookup device's major for the pts driver and cache it. */
-  static devmajor_t pts = NODEVMAJOR;
-
-  if (pts == NODEVMAJOR) {
-    pts = getdevmajor("pts", S_IFCHR);
-    if (pts == NODEVMAJOR)
-      abort();
-  }
-
-  /* Lookup stat structure behind the file descriptor. */
-  if (fstat(fd, &sb) != 0)
-    abort();
-
-  /* Assert character device. */
-  if (!S_ISCHR(sb.st_mode))
-    abort();
-
-  /* Assert valid major. */
-  if (major(sb.st_rdev) == NODEVMAJOR)
-    abort();
-
-  result = (pts == major(sb.st_rdev));
-#else
-  /* Fallback to ptsname
-   */
-  result = ptsname(fd) == NULL;
-#endif
-  return result;
-}
-
-int uv_tty_init(uv_loop_t* loop, uv_tty_t* tty, int fd, int unused) {
-  uv_handle_type type;
-  int flags;
-  int newfd;
-  int r;
-  int saved_flags;
-  int mode;
-  char path[256];
-  (void)unused; /* deprecated parameter is no longer needed */
-
-  /* File descriptors that refer to files cannot be monitored with epoll.
-   * That restriction also applies to character devices like /dev/random
-   * (but obviously not /dev/tty.)
-   */
-  type = uv_guess_handle(fd);
-  if (type == UV_FILE || type == UV_UNKNOWN_HANDLE)
-    return UV_EINVAL;
-
-  flags = 0;
-  newfd = -1;
-
-  /* Save the fd flags in case we need to restore them due to an error. */
-  do
-    saved_flags = fcntl(fd, F_GETFL);
-  while (saved_flags == -1 && errno == EINTR);
-
-  if (saved_flags == -1)
-    return UV__ERR(errno);
-  mode = saved_flags & O_ACCMODE;
-
-  /* Reopen the file descriptor when it refers to a tty. This lets us put the
-   * tty in non-blocking mode without affecting other processes that share it
-   * with us.
-   *
-   * Example: `node | cat` - if we put our fd 0 in non-blocking mode, it also
-   * affects fd 1 of `cat` because both file descriptors refer to the same
-   * struct file in the kernel. When we reopen our fd 0, it points to a
-   * different struct file, hence changing its properties doesn't affect
-   * other processes.
-   */
-  if (type == UV_TTY) {
-    /* Reopening a pty in controller mode won't work either because the reopened
-     * pty will be in peripheral mode (*BSD) or reopening will allocate a new
-     * controller/peripheral pair (Linux). Therefore check if the fd points to a
-     * peripheral device.
-     */
-    if (uv__tty_is_peripheral(fd) && ttyname_r(fd, path, sizeof(path)) == 0)
-      r = uv__open_cloexec(path, mode);
-    else
-      r = -1;
-
-    if (r < 0) {
-      /* fallback to using blocking writes */
-      if (mode != O_RDONLY)
-        flags |= UV_HANDLE_BLOCKING_WRITES;
-      goto skip;
-    }
-
-    newfd = r;
-
-    r = uv__dup2_cloexec(newfd, fd);
-    if (r < 0 && r != UV_EINVAL) {
-      /* EINVAL means newfd == fd which could conceivably happen if another
-       * thread called close(fd) between our calls to isatty() and open().
-       * That's a rather unlikely event but let's handle it anyway.
-       */
-      uv__close(newfd);
-      return r;
-    }
-
-    fd = newfd;
-  }
-
-skip:
-  uv__stream_init(loop, (uv_stream_t*) tty, UV_TTY);
-
-  /* If anything fails beyond this point we need to remove the handle from
-   * the handle queue, since it was added by uv__handle_init in uv_stream_init.
-   */
-
-  if (!(flags & UV_HANDLE_BLOCKING_WRITES))
-    uv__nonblock(fd, 1);
-
-#if defined(__APPLE__)
-  r = uv__stream_try_select((uv_stream_t*) tty, &fd);
-  if (r) {
-    int rc = r;
-    if (newfd != -1)
-      uv__close(newfd);
-    QUEUE_REMOVE(&tty->handle_queue);
-    do
-      r = fcntl(fd, F_SETFL, saved_flags);
-    while (r == -1 && errno == EINTR);
-    return rc;
-  }
-#endif
-
-  if (mode != O_WRONLY)
-    flags |= UV_HANDLE_READABLE;
-  if (mode != O_RDONLY)
-    flags |= UV_HANDLE_WRITABLE;
-
-  uv__stream_open((uv_stream_t*) tty, fd, flags);
-  tty->mode = UV_TTY_MODE_NORMAL;
-
-  return 0;
-}
-
-static void uv__tty_make_raw(struct termios* tio) {
-  assert(tio != NULL);
-
-#if defined __sun || defined __MVS__
-  /*
-   * This implementation of cfmakeraw for Solaris and derivatives is taken from
-   * http://www.perkin.org.uk/posts/solaris-portability-cfmakeraw.html.
-   */
-  tio->c_iflag &= ~(IMAXBEL | IGNBRK | BRKINT | PARMRK | ISTRIP | INLCR |
-                    IGNCR | ICRNL | IXON);
-  tio->c_oflag &= ~OPOST;
-  tio->c_lflag &= ~(ECHO | ECHONL | ICANON | ISIG | IEXTEN);
-  tio->c_cflag &= ~(CSIZE | PARENB);
-  tio->c_cflag |= CS8;
-#else
-  cfmakeraw(tio);
-#endif /* #ifdef __sun */
-}
-
-int uv_tty_set_mode(uv_tty_t* tty, uv_tty_mode_t mode) {
-  struct termios tmp;
-  int fd;
-
-  if (tty->mode == (int) mode)
-    return 0;
-
-  fd = uv__stream_fd(tty);
-  if (tty->mode == UV_TTY_MODE_NORMAL && mode != UV_TTY_MODE_NORMAL) {
-    if (tcgetattr(fd, &tty->orig_termios))
-      return UV__ERR(errno);
-
-    /* This is used for uv_tty_reset_mode() */
-    uv_spinlock_lock(&termios_spinlock);
-    if (orig_termios_fd == -1) {
-      orig_termios = tty->orig_termios;
-      orig_termios_fd = fd;
-    }
-    uv_spinlock_unlock(&termios_spinlock);
-  }
-
-  tmp = tty->orig_termios;
-  switch (mode) {
-    case UV_TTY_MODE_NORMAL:
-      break;
-    case UV_TTY_MODE_RAW:
-      tmp.c_iflag &= ~(BRKINT | ICRNL | INPCK | ISTRIP | IXON);
-      tmp.c_oflag |= (ONLCR);
-      tmp.c_cflag |= (CS8);
-      tmp.c_lflag &= ~(ECHO | ICANON | IEXTEN | ISIG);
-      tmp.c_cc[VMIN] = 1;
-      tmp.c_cc[VTIME] = 0;
-      break;
-    case UV_TTY_MODE_IO:
-      uv__tty_make_raw(&tmp);
-      break;
-  }
-
-  /* Apply changes after draining */
-  if (tcsetattr(fd, TCSADRAIN, &tmp))
-    return UV__ERR(errno);
-
-  tty->mode = mode;
-  return 0;
-}
-
-
-int uv_tty_get_winsize(uv_tty_t* tty, int* width, int* height) {
-  struct winsize ws;
-  int err;
-
-  do
-    err = ioctl(uv__stream_fd(tty), TIOCGWINSZ, &ws);
-  while (err == -1 && errno == EINTR);
-
-  if (err == -1)
-    return UV__ERR(errno);
-
-  *width = ws.ws_col;
-  *height = ws.ws_row;
-
-  return 0;
-}
-
-
-uv_handle_type uv_guess_handle(uv_file file) {
-  struct sockaddr sa;
-  struct stat s;
-  socklen_t len;
-  int type;
-
-  if (file < 0)
-    return UV_UNKNOWN_HANDLE;
-
-  if (isatty(file))
-    return UV_TTY;
-
-  if (fstat(file, &s))
-    return UV_UNKNOWN_HANDLE;
-
-  if (S_ISREG(s.st_mode))
-    return UV_FILE;
-
-  if (S_ISCHR(s.st_mode))
-    return UV_FILE;  /* XXX UV_NAMED_PIPE? */
-
-  if (S_ISFIFO(s.st_mode))
-    return UV_NAMED_PIPE;
-
-  if (!S_ISSOCK(s.st_mode))
-    return UV_UNKNOWN_HANDLE;
-
-  len = sizeof(type);
-  if (getsockopt(file, SOL_SOCKET, SO_TYPE, &type, &len))
-    return UV_UNKNOWN_HANDLE;
-
-  len = sizeof(sa);
-  if (getsockname(file, &sa, &len))
-    return UV_UNKNOWN_HANDLE;
-
-  if (type == SOCK_DGRAM)
-    if (sa.sa_family == AF_INET || sa.sa_family == AF_INET6)
-      return UV_UDP;
-
-  if (type == SOCK_STREAM) {
-#if defined(_AIX) || defined(__DragonFly__)
-    /* on AIX/DragonFly the getsockname call returns an empty sa structure
-     * for sockets of type AF_UNIX.  For all other types it will
-     * return a properly filled in structure.
-     */
-    if (len == 0)
-      return UV_NAMED_PIPE;
-#endif /* defined(_AIX) || defined(__DragonFly__) */
-
-    if (sa.sa_family == AF_INET || sa.sa_family == AF_INET6)
-      return UV_TCP;
-    if (sa.sa_family == AF_UNIX)
-      return UV_NAMED_PIPE;
-  }
-
-  return UV_UNKNOWN_HANDLE;
-}
-
-
-/* This function is async signal-safe, meaning that it's safe to call from
- * inside a signal handler _unless_ execution was inside uv_tty_set_mode()'s
- * critical section when the signal was raised.
- */
-int uv_tty_reset_mode(void) {
-  int saved_errno;
-  int err;
-
-  saved_errno = errno;
-  if (!uv_spinlock_trylock(&termios_spinlock))
-    return UV_EBUSY;  /* In uv_tty_set_mode(). */
-
-  err = 0;
-  if (orig_termios_fd != -1)
-    if (tcsetattr(orig_termios_fd, TCSANOW, &orig_termios))
-      err = UV__ERR(errno);
-
-  uv_spinlock_unlock(&termios_spinlock);
-  errno = saved_errno;
-
-  return err;
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/udp.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/udp.cpp
deleted file mode 100644
index 5c03ae1..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/unix/udp.cpp
+++ /dev/null
@@ -1,999 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include "uv.h"
-#include "internal.h"
-
-#include <assert.h>
-#include <string.h>
-#include <errno.h>
-#include <stdlib.h>
-#include <unistd.h>
-#if defined(__MVS__)
-#include <xti.h>
-#endif
-#include <sys/un.h>
-
-#if defined(IPV6_JOIN_GROUP) && !defined(IPV6_ADD_MEMBERSHIP)
-# define IPV6_ADD_MEMBERSHIP IPV6_JOIN_GROUP
-#endif
-
-#if defined(IPV6_LEAVE_GROUP) && !defined(IPV6_DROP_MEMBERSHIP)
-# define IPV6_DROP_MEMBERSHIP IPV6_LEAVE_GROUP
-#endif
-
-
-static void uv__udp_run_completed(uv_udp_t* handle);
-static void uv__udp_io(uv_loop_t* loop, uv__io_t* w, unsigned int revents);
-static void uv__udp_recvmsg(uv_udp_t* handle);
-static void uv__udp_sendmsg(uv_udp_t* handle);
-static int uv__udp_maybe_deferred_bind(uv_udp_t* handle,
-                                       int domain,
-                                       unsigned int flags);
-
-
-void uv__udp_close(uv_udp_t* handle) {
-  uv__io_close(handle->loop, &handle->io_watcher);
-  uv__handle_stop(handle);
-
-  if (handle->io_watcher.fd != -1) {
-    uv__close(handle->io_watcher.fd);
-    handle->io_watcher.fd = -1;
-  }
-}
-
-
-void uv__udp_finish_close(uv_udp_t* handle) {
-  uv_udp_send_t* req;
-  QUEUE* q;
-
-  assert(!uv__io_active(&handle->io_watcher, POLLIN | POLLOUT));
-  assert(handle->io_watcher.fd == -1);
-
-  while (!QUEUE_EMPTY(&handle->write_queue)) {
-    q = QUEUE_HEAD(&handle->write_queue);
-    QUEUE_REMOVE(q);
-
-    req = QUEUE_DATA(q, uv_udp_send_t, queue);
-    req->status = UV_ECANCELED;
-    QUEUE_INSERT_TAIL(&handle->write_completed_queue, &req->queue);
-  }
-
-  uv__udp_run_completed(handle);
-
-  assert(handle->send_queue_size == 0);
-  assert(handle->send_queue_count == 0);
-
-  /* Now tear down the handle. */
-  handle->recv_cb = NULL;
-  handle->alloc_cb = NULL;
-  /* but _do not_ touch close_cb */
-}
-
-
-static void uv__udp_run_completed(uv_udp_t* handle) {
-  uv_udp_send_t* req;
-  QUEUE* q;
-
-  assert(!(handle->flags & UV_HANDLE_UDP_PROCESSING));
-  handle->flags |= UV_HANDLE_UDP_PROCESSING;
-
-  while (!QUEUE_EMPTY(&handle->write_completed_queue)) {
-    q = QUEUE_HEAD(&handle->write_completed_queue);
-    QUEUE_REMOVE(q);
-
-    req = QUEUE_DATA(q, uv_udp_send_t, queue);
-    uv__req_unregister(handle->loop, req);
-
-    handle->send_queue_size -= uv__count_bufs(req->bufs, req->nbufs);
-    handle->send_queue_count--;
-
-    if (req->bufs != req->bufsml)
-      uv__free(req->bufs);
-    req->bufs = NULL;
-
-    if (req->send_cb == NULL)
-      continue;
-
-    /* req->status >= 0 == bytes written
-     * req->status <  0 == errno
-     */
-    if (req->status >= 0)
-      req->send_cb(req, 0);
-    else
-      req->send_cb(req, req->status);
-  }
-
-  if (QUEUE_EMPTY(&handle->write_queue)) {
-    /* Pending queue and completion queue empty, stop watcher. */
-    uv__io_stop(handle->loop, &handle->io_watcher, POLLOUT);
-    if (!uv__io_active(&handle->io_watcher, POLLIN))
-      uv__handle_stop(handle);
-  }
-
-  handle->flags &= ~UV_HANDLE_UDP_PROCESSING;
-}
-
-
-static void uv__udp_io(uv_loop_t* loop, uv__io_t* w, unsigned int revents) {
-  uv_udp_t* handle;
-
-  handle = container_of(w, uv_udp_t, io_watcher);
-  assert(handle->type == UV_UDP);
-
-  if (revents & POLLIN)
-    uv__udp_recvmsg(handle);
-
-  if (revents & POLLOUT) {
-    uv__udp_sendmsg(handle);
-    uv__udp_run_completed(handle);
-  }
-}
-
-
-static void uv__udp_recvmsg(uv_udp_t* handle) {
-  struct sockaddr_storage peer;
-  struct msghdr h;
-  ssize_t nread;
-  uv_buf_t buf;
-  int flags;
-  int count;
-
-  assert(handle->recv_cb != NULL);
-  assert(handle->alloc_cb != NULL);
-
-  /* Prevent loop starvation when the data comes in as fast as (or faster than)
-   * we can read it. XXX Need to rearm fd if we switch to edge-triggered I/O.
-   */
-  count = 32;
-
-  memset(&h, 0, sizeof(h));
-  h.msg_name = &peer;
-
-  do {
-    buf = uv_buf_init(NULL, 0);
-    handle->alloc_cb((uv_handle_t*) handle, 64 * 1024, &buf);
-    if (buf.base == NULL || buf.len == 0) {
-      handle->recv_cb(handle, UV_ENOBUFS, &buf, NULL, 0);
-      return;
-    }
-    assert(buf.base != NULL);
-
-    h.msg_namelen = sizeof(peer);
-    h.msg_iov = (iovec*) &buf;
-    h.msg_iovlen = 1;
-
-    do {
-      nread = recvmsg(handle->io_watcher.fd, &h, 0);
-    }
-    while (nread == -1 && errno == EINTR);
-
-    if (nread == -1) {
-      if (errno == EAGAIN || errno == EWOULDBLOCK)
-        handle->recv_cb(handle, 0, &buf, NULL, 0);
-      else
-        handle->recv_cb(handle, UV__ERR(errno), &buf, NULL, 0);
-    }
-    else {
-      const struct sockaddr *addr;
-      if (h.msg_namelen == 0)
-        addr = NULL;
-      else
-        addr = (const struct sockaddr*) &peer;
-
-      flags = 0;
-      if (h.msg_flags & MSG_TRUNC)
-        flags |= UV_UDP_PARTIAL;
-
-      handle->recv_cb(handle, nread, &buf, addr, flags);
-    }
-  }
-  /* recv_cb callback may decide to pause or close the handle */
-  while (nread != -1
-      && count-- > 0
-      && handle->io_watcher.fd != -1
-      && handle->recv_cb != NULL);
-}
-
-
-static void uv__udp_sendmsg(uv_udp_t* handle) {
-  uv_udp_send_t* req;
-  QUEUE* q;
-  struct msghdr h;
-  ssize_t size;
-
-  while (!QUEUE_EMPTY(&handle->write_queue)) {
-    q = QUEUE_HEAD(&handle->write_queue);
-    assert(q != NULL);
-
-    req = QUEUE_DATA(q, uv_udp_send_t, queue);
-    assert(req != NULL);
-
-    memset(&h, 0, sizeof h);
-    if (req->addr.ss_family == AF_UNSPEC) {
-      h.msg_name = NULL;
-      h.msg_namelen = 0;
-    } else {
-      h.msg_name = &req->addr;
-      if (req->addr.ss_family == AF_INET6)
-        h.msg_namelen = sizeof(struct sockaddr_in6);
-      else if (req->addr.ss_family == AF_INET)
-        h.msg_namelen = sizeof(struct sockaddr_in);
-      else if (req->addr.ss_family == AF_UNIX)
-        h.msg_namelen = sizeof(struct sockaddr_un);
-      else {
-        assert(0 && "unsupported address family");
-        abort();
-      }
-    }
-    h.msg_iov = (struct iovec*) req->bufs;
-    h.msg_iovlen = req->nbufs;
-
-    do {
-      size = sendmsg(handle->io_watcher.fd, &h, 0);
-    } while (size == -1 && errno == EINTR);
-
-    if (size == -1) {
-      if (errno == EAGAIN || errno == EWOULDBLOCK || errno == ENOBUFS)
-        break;
-    }
-
-    req->status = (size == -1 ? UV__ERR(errno) : size);
-
-    /* Sending a datagram is an atomic operation: either all data
-     * is written or nothing is (and EMSGSIZE is raised). That is
-     * why we don't handle partial writes. Just pop the request
-     * off the write queue and onto the completed queue, done.
-     */
-    QUEUE_REMOVE(&req->queue);
-    QUEUE_INSERT_TAIL(&handle->write_completed_queue, &req->queue);
-    uv__io_feed(handle->loop, &handle->io_watcher);
-  }
-}
-
-
-/* On the BSDs, SO_REUSEPORT implies SO_REUSEADDR but with some additional
- * refinements for programs that use multicast.
- *
- * Linux as of 3.9 has a SO_REUSEPORT socket option but with semantics that
- * are different from the BSDs: it _shares_ the port rather than steal it
- * from the current listener.  While useful, it's not something we can emulate
- * on other platforms so we don't enable it.
- *
- * zOS does not support getsockname with SO_REUSEPORT option when using
- * AF_UNIX.
- */
-static int uv__set_reuse(int fd) {
-  int yes;
-  yes = 1;
-
-#if defined(SO_REUSEPORT) && defined(__MVS__)
-  struct sockaddr_in sockfd;
-  unsigned int sockfd_len = sizeof(sockfd);
-  if (getsockname(fd, (struct sockaddr*) &sockfd, &sockfd_len) == -1)
-      return UV__ERR(errno);
-  if (sockfd.sin_family == AF_UNIX) {
-    if (setsockopt(fd, SOL_SOCKET, SO_REUSEADDR, &yes, sizeof(yes)))
-      return UV__ERR(errno);
-  } else {
-    if (setsockopt(fd, SOL_SOCKET, SO_REUSEPORT, &yes, sizeof(yes)))
-       return UV__ERR(errno);
-  }
-#elif defined(SO_REUSEPORT) && !defined(__linux__)
-  if (setsockopt(fd, SOL_SOCKET, SO_REUSEPORT, &yes, sizeof(yes)))
-    return UV__ERR(errno);
-#else
-  if (setsockopt(fd, SOL_SOCKET, SO_REUSEADDR, &yes, sizeof(yes)))
-    return UV__ERR(errno);
-#endif
-
-  return 0;
-}
-
-
-int uv__udp_bind(uv_udp_t* handle,
-                 const struct sockaddr* addr,
-                 unsigned int addrlen,
-                 unsigned int flags) {
-  int err;
-  int yes;
-  int fd;
-
-  /* Check for bad flags. */
-  if (flags & ~(UV_UDP_IPV6ONLY | UV_UDP_REUSEADDR))
-    return UV_EINVAL;
-
-  /* Cannot set IPv6-only mode on non-IPv6 socket. */
-  if ((flags & UV_UDP_IPV6ONLY) && addr->sa_family != AF_INET6)
-    return UV_EINVAL;
-
-  fd = handle->io_watcher.fd;
-  if (fd == -1) {
-    err = uv__socket(addr->sa_family, SOCK_DGRAM, 0);
-    if (err < 0)
-      return err;
-    fd = err;
-    handle->io_watcher.fd = fd;
-  }
-
-  if (flags & UV_UDP_REUSEADDR) {
-    err = uv__set_reuse(fd);
-    if (err)
-      return err;
-  }
-
-  if (flags & UV_UDP_IPV6ONLY) {
-#ifdef IPV6_V6ONLY
-    yes = 1;
-    if (setsockopt(fd, IPPROTO_IPV6, IPV6_V6ONLY, &yes, sizeof yes) == -1) {
-      err = UV__ERR(errno);
-      return err;
-    }
-#else
-    err = UV_ENOTSUP;
-    return err;
-#endif
-  }
-
-  if (bind(fd, addr, addrlen)) {
-    err = UV__ERR(errno);
-    if (errno == EAFNOSUPPORT)
-      /* OSX, other BSDs and SunoS fail with EAFNOSUPPORT when binding a
-       * socket created with AF_INET to an AF_INET6 address or vice versa. */
-      err = UV_EINVAL;
-    return err;
-  }
-
-  if (addr->sa_family == AF_INET6)
-    handle->flags |= UV_HANDLE_IPV6;
-
-  handle->flags |= UV_HANDLE_BOUND;
-  return 0;
-}
-
-
-static int uv__udp_maybe_deferred_bind(uv_udp_t* handle,
-                                       int domain,
-                                       unsigned int flags) {
-  union {
-    struct sockaddr_in6 in6;
-    struct sockaddr_in in;
-    struct sockaddr addr;
-  } taddr;
-  socklen_t addrlen;
-
-  if (handle->io_watcher.fd != -1)
-    return 0;
-
-  switch (domain) {
-  case AF_INET:
-  {
-    struct sockaddr_in* addr = &taddr.in;
-    memset(addr, 0, sizeof *addr);
-    addr->sin_family = AF_INET;
-    addr->sin_addr.s_addr = INADDR_ANY;
-    addrlen = sizeof *addr;
-    break;
-  }
-  case AF_INET6:
-  {
-    struct sockaddr_in6* addr = &taddr.in6;
-    memset(addr, 0, sizeof *addr);
-    addr->sin6_family = AF_INET6;
-    addr->sin6_addr = in6addr_any;
-    addrlen = sizeof *addr;
-    break;
-  }
-  default:
-    assert(0 && "unsupported address family");
-    abort();
-  }
-
-  return uv__udp_bind(handle, &taddr.addr, addrlen, flags);
-}
-
-
-int uv__udp_connect(uv_udp_t* handle,
-                    const struct sockaddr* addr,
-                    unsigned int addrlen) {
-  int err;
-
-  err = uv__udp_maybe_deferred_bind(handle, addr->sa_family, 0);
-  if (err)
-    return err;
-
-  do {
-    errno = 0;
-    err = connect(handle->io_watcher.fd, addr, addrlen);
-  } while (err == -1 && errno == EINTR);
-
-  if (err)
-    return UV__ERR(errno);
-
-  handle->flags |= UV_HANDLE_UDP_CONNECTED;
-
-  return 0;
-}
-
-
-int uv__udp_disconnect(uv_udp_t* handle) {
-    int r;
-    struct sockaddr addr;
-
-    memset(&addr, 0, sizeof(addr));
-
-    addr.sa_family = AF_UNSPEC;
-
-    do {
-      errno = 0;
-      r = connect(handle->io_watcher.fd, &addr, sizeof(addr));
-    } while (r == -1 && errno == EINTR);
-
-    if (r == -1 && errno != EAFNOSUPPORT)
-      return UV__ERR(errno);
-
-    handle->flags &= ~UV_HANDLE_UDP_CONNECTED;
-    return 0;
-}
-
-
-int uv__udp_send(uv_udp_send_t* req,
-                 uv_udp_t* handle,
-                 const uv_buf_t bufs[],
-                 unsigned int nbufs,
-                 const struct sockaddr* addr,
-                 unsigned int addrlen,
-                 uv_udp_send_cb send_cb) {
-  int err;
-  int empty_queue;
-
-  assert(nbufs > 0);
-
-  if (addr) {
-    err = uv__udp_maybe_deferred_bind(handle, addr->sa_family, 0);
-    if (err)
-      return err;
-  }
-
-  /* It's legal for send_queue_count > 0 even when the write_queue is empty;
-   * it means there are error-state requests in the write_completed_queue that
-   * will touch up send_queue_size/count later.
-   */
-  empty_queue = (handle->send_queue_count == 0);
-
-  uv__req_init(handle->loop, req, UV_UDP_SEND);
-  assert(addrlen <= sizeof(req->addr));
-  if (addr == NULL)
-    req->addr.ss_family = AF_UNSPEC;
-  else
-    memcpy(&req->addr, addr, addrlen);
-  req->send_cb = send_cb;
-  req->handle = handle;
-  req->nbufs = nbufs;
-
-  req->bufs = req->bufsml;
-  if (nbufs > ARRAY_SIZE(req->bufsml))
-    req->bufs = (uv_buf_t*)uv__malloc(nbufs * sizeof(bufs[0]));
-
-  if (req->bufs == NULL) {
-    uv__req_unregister(handle->loop, req);
-    return UV_ENOMEM;
-  }
-
-  memcpy(req->bufs, bufs, nbufs * sizeof(bufs[0]));
-  handle->send_queue_size += uv__count_bufs(req->bufs, req->nbufs);
-  handle->send_queue_count++;
-  QUEUE_INSERT_TAIL(&handle->write_queue, &req->queue);
-  uv__handle_start(handle);
-
-  if (empty_queue && !(handle->flags & UV_HANDLE_UDP_PROCESSING)) {
-    uv__udp_sendmsg(handle);
-
-    /* `uv__udp_sendmsg` may not be able to do non-blocking write straight
-     * away. In such cases the `io_watcher` has to be queued for asynchronous
-     * write.
-     */
-    if (!QUEUE_EMPTY(&handle->write_queue))
-      uv__io_start(handle->loop, &handle->io_watcher, POLLOUT);
-  } else {
-    uv__io_start(handle->loop, &handle->io_watcher, POLLOUT);
-  }
-
-  return 0;
-}
-
-
-int uv__udp_try_send(uv_udp_t* handle,
-                     const uv_buf_t bufs[],
-                     unsigned int nbufs,
-                     const struct sockaddr* addr,
-                     unsigned int addrlen) {
-  int err;
-  struct msghdr h;
-  ssize_t size;
-
-  assert(nbufs > 0);
-
-  /* already sending a message */
-  if (handle->send_queue_count != 0)
-    return UV_EAGAIN;
-
-  if (addr) {
-    err = uv__udp_maybe_deferred_bind(handle, addr->sa_family, 0);
-    if (err)
-      return err;
-  } else {
-    assert(handle->flags & UV_HANDLE_UDP_CONNECTED);
-  }
-
-  memset(&h, 0, sizeof h);
-  h.msg_name = (struct sockaddr*) addr;
-  h.msg_namelen = addrlen;
-  h.msg_iov = (struct iovec*) bufs;
-  h.msg_iovlen = nbufs;
-
-  do {
-    size = sendmsg(handle->io_watcher.fd, &h, 0);
-  } while (size == -1 && errno == EINTR);
-
-  if (size == -1) {
-    if (errno == EAGAIN || errno == EWOULDBLOCK || errno == ENOBUFS)
-      return UV_EAGAIN;
-    else
-      return UV__ERR(errno);
-  }
-
-  return size;
-}
-
-
-static int uv__udp_set_membership4(uv_udp_t* handle,
-                                   const struct sockaddr_in* multicast_addr,
-                                   const char* interface_addr,
-                                   uv_membership membership) {
-  struct ip_mreq mreq;
-  int optname;
-  int err;
-
-  memset(&mreq, 0, sizeof mreq);
-
-  if (interface_addr) {
-    err = uv_inet_pton(AF_INET, interface_addr, &mreq.imr_interface.s_addr);
-    if (err)
-      return err;
-  } else {
-    mreq.imr_interface.s_addr = htonl(INADDR_ANY);
-  }
-
-  mreq.imr_multiaddr.s_addr = multicast_addr->sin_addr.s_addr;
-
-  switch (membership) {
-  case UV_JOIN_GROUP:
-    optname = IP_ADD_MEMBERSHIP;
-    break;
-  case UV_LEAVE_GROUP:
-    optname = IP_DROP_MEMBERSHIP;
-    break;
-  default:
-    return UV_EINVAL;
-  }
-
-  if (setsockopt(handle->io_watcher.fd,
-                 IPPROTO_IP,
-                 optname,
-                 &mreq,
-                 sizeof(mreq))) {
-#if defined(__MVS__)
-  if (errno == ENXIO)
-    return UV_ENODEV;
-#endif
-    return UV__ERR(errno);
-  }
-
-  return 0;
-}
-
-
-static int uv__udp_set_membership6(uv_udp_t* handle,
-                                   const struct sockaddr_in6* multicast_addr,
-                                   const char* interface_addr,
-                                   uv_membership membership) {
-  int optname;
-  struct ipv6_mreq mreq;
-  struct sockaddr_in6 addr6;
-
-  memset(&mreq, 0, sizeof mreq);
-
-  if (interface_addr) {
-    if (uv_ip6_addr(interface_addr, 0, &addr6))
-      return UV_EINVAL;
-    mreq.ipv6mr_interface = addr6.sin6_scope_id;
-  } else {
-    mreq.ipv6mr_interface = 0;
-  }
-
-  mreq.ipv6mr_multiaddr = multicast_addr->sin6_addr;
-
-  switch (membership) {
-  case UV_JOIN_GROUP:
-    optname = IPV6_ADD_MEMBERSHIP;
-    break;
-  case UV_LEAVE_GROUP:
-    optname = IPV6_DROP_MEMBERSHIP;
-    break;
-  default:
-    return UV_EINVAL;
-  }
-
-  if (setsockopt(handle->io_watcher.fd,
-                 IPPROTO_IPV6,
-                 optname,
-                 &mreq,
-                 sizeof(mreq))) {
-#if defined(__MVS__)
-  if (errno == ENXIO)
-    return UV_ENODEV;
-#endif
-    return UV__ERR(errno);
-  }
-
-  return 0;
-}
-
-
-int uv_udp_init_ex(uv_loop_t* loop, uv_udp_t* handle, unsigned int flags) {
-  int domain;
-  int err;
-  int fd;
-
-  /* Use the lower 8 bits for the domain */
-  domain = flags & 0xFF;
-  if (domain != AF_INET && domain != AF_INET6 && domain != AF_UNSPEC)
-    return UV_EINVAL;
-
-  if (flags & ~0xFF)
-    return UV_EINVAL;
-
-  if (domain != AF_UNSPEC) {
-    err = uv__socket(domain, SOCK_DGRAM, 0);
-    if (err < 0)
-      return err;
-    fd = err;
-  } else {
-    fd = -1;
-  }
-
-  uv__handle_init(loop, (uv_handle_t*)handle, UV_UDP);
-  handle->alloc_cb = NULL;
-  handle->recv_cb = NULL;
-  handle->send_queue_size = 0;
-  handle->send_queue_count = 0;
-  uv__io_init(&handle->io_watcher, uv__udp_io, fd);
-  QUEUE_INIT(&handle->write_queue);
-  QUEUE_INIT(&handle->write_completed_queue);
-
-  return 0;
-}
-
-
-int uv_udp_init(uv_loop_t* loop, uv_udp_t* handle) {
-  return uv_udp_init_ex(loop, handle, AF_UNSPEC);
-}
-
-
-int uv_udp_open(uv_udp_t* handle, uv_os_sock_t sock) {
-  int err;
-
-  /* Check for already active socket. */
-  if (handle->io_watcher.fd != -1)
-    return UV_EBUSY;
-
-  if (uv__fd_exists(handle->loop, sock))
-    return UV_EEXIST;
-
-  err = uv__nonblock(sock, 1);
-  if (err)
-    return err;
-
-  err = uv__set_reuse(sock);
-  if (err)
-    return err;
-
-  handle->io_watcher.fd = sock;
-  if (uv__udp_is_connected(handle))
-    handle->flags |= UV_HANDLE_UDP_CONNECTED;
-
-  return 0;
-}
-
-
-int uv_udp_set_membership(uv_udp_t* handle,
-                          const char* multicast_addr,
-                          const char* interface_addr,
-                          uv_membership membership) {
-  int err;
-  struct sockaddr_in addr4;
-  struct sockaddr_in6 addr6;
-
-  if (uv_ip4_addr(multicast_addr, 0, &addr4) == 0) {
-    err = uv__udp_maybe_deferred_bind(handle, AF_INET, UV_UDP_REUSEADDR);
-    if (err)
-      return err;
-    return uv__udp_set_membership4(handle, &addr4, interface_addr, membership);
-  } else if (uv_ip6_addr(multicast_addr, 0, &addr6) == 0) {
-    err = uv__udp_maybe_deferred_bind(handle, AF_INET6, UV_UDP_REUSEADDR);
-    if (err)
-      return err;
-    return uv__udp_set_membership6(handle, &addr6, interface_addr, membership);
-  } else {
-    return UV_EINVAL;
-  }
-}
-
-static int uv__setsockopt(uv_udp_t* handle,
-                         int option4,
-                         int option6,
-                         const void* val,
-                         size_t size) {
-  int r;
-
-  if (handle->flags & UV_HANDLE_IPV6)
-    r = setsockopt(handle->io_watcher.fd,
-                   IPPROTO_IPV6,
-                   option6,
-                   val,
-                   size);
-  else
-    r = setsockopt(handle->io_watcher.fd,
-                   IPPROTO_IP,
-                   option4,
-                   val,
-                   size);
-  if (r)
-    return UV__ERR(errno);
-
-  return 0;
-}
-
-static int uv__setsockopt_maybe_char(uv_udp_t* handle,
-                                     int option4,
-                                     int option6,
-                                     int val) {
-#if defined(__sun) || defined(_AIX) || defined(__MVS__)
-  char arg = val;
-#elif defined(__OpenBSD__)
-  unsigned char arg = val;
-#else
-  int arg = val;
-#endif
-
-  if (val < 0 || val > 255)
-    return UV_EINVAL;
-
-  return uv__setsockopt(handle, option4, option6, &arg, sizeof(arg));
-}
-
-
-int uv_udp_set_broadcast(uv_udp_t* handle, int on) {
-  if (setsockopt(handle->io_watcher.fd,
-                 SOL_SOCKET,
-                 SO_BROADCAST,
-                 &on,
-                 sizeof(on))) {
-    return UV__ERR(errno);
-  }
-
-  return 0;
-}
-
-
-int uv_udp_set_ttl(uv_udp_t* handle, int ttl) {
-  if (ttl < 1 || ttl > 255)
-    return UV_EINVAL;
-
-#if defined(__MVS__)
-  if (!(handle->flags & UV_HANDLE_IPV6))
-    return UV_ENOTSUP;  /* zOS does not support setting ttl for IPv4 */
-#endif
-
-/*
- * On Solaris and derivatives such as SmartOS, the length of socket options
- * is sizeof(int) for IP_TTL and IPV6_UNICAST_HOPS,
- * so hardcode the size of these options on this platform,
- * and use the general uv__setsockopt_maybe_char call on other platforms.
- */
-#if defined(__sun) || defined(_AIX) || defined(__OpenBSD__) || \
-    defined(__MVS__)
-
-  return uv__setsockopt(handle,
-                        IP_TTL,
-                        IPV6_UNICAST_HOPS,
-                        &ttl,
-                        sizeof(ttl));
-
-#else /* !(defined(__sun) || defined(_AIX) || defined (__OpenBSD__) ||
-           defined(__MVS__)) */
-
-  return uv__setsockopt_maybe_char(handle,
-                                   IP_TTL,
-                                   IPV6_UNICAST_HOPS,
-                                   ttl);
-
-#endif /* defined(__sun) || defined(_AIX) || defined (__OpenBSD__) ||
-          defined(__MVS__) */
-}
-
-
-int uv_udp_set_multicast_ttl(uv_udp_t* handle, int ttl) {
-/*
- * On Solaris and derivatives such as SmartOS, the length of socket options
- * is sizeof(int) for IPV6_MULTICAST_HOPS and sizeof(char) for
- * IP_MULTICAST_TTL, so hardcode the size of the option in the IPv6 case,
- * and use the general uv__setsockopt_maybe_char call otherwise.
- */
-#if defined(__sun) || defined(_AIX) || defined(__OpenBSD__) || \
-    defined(__MVS__)
-  if (handle->flags & UV_HANDLE_IPV6)
-    return uv__setsockopt(handle,
-                          IP_MULTICAST_TTL,
-                          IPV6_MULTICAST_HOPS,
-                          &ttl,
-                          sizeof(ttl));
-#endif /* defined(__sun) || defined(_AIX) || defined(__OpenBSD__) || \
-    defined(__MVS__) */
-
-  return uv__setsockopt_maybe_char(handle,
-                                   IP_MULTICAST_TTL,
-                                   IPV6_MULTICAST_HOPS,
-                                   ttl);
-}
-
-
-int uv_udp_set_multicast_loop(uv_udp_t* handle, int on) {
-/*
- * On Solaris and derivatives such as SmartOS, the length of socket options
- * is sizeof(int) for IPV6_MULTICAST_LOOP and sizeof(char) for
- * IP_MULTICAST_LOOP, so hardcode the size of the option in the IPv6 case,
- * and use the general uv__setsockopt_maybe_char call otherwise.
- */
-#if defined(__sun) || defined(_AIX) || defined(__OpenBSD__) || \
-    defined(__MVS__) 
-  if (handle->flags & UV_HANDLE_IPV6)
-    return uv__setsockopt(handle,
-                          IP_MULTICAST_LOOP,
-                          IPV6_MULTICAST_LOOP,
-                          &on,
-                          sizeof(on));
-#endif /* defined(__sun) || defined(_AIX) ||defined(__OpenBSD__) ||
-    defined(__MVS__) */
-
-  return uv__setsockopt_maybe_char(handle,
-                                   IP_MULTICAST_LOOP,
-                                   IPV6_MULTICAST_LOOP,
-                                   on);
-}
-
-int uv_udp_set_multicast_interface(uv_udp_t* handle, const char* interface_addr) {
-  struct sockaddr_storage addr_st;
-  struct sockaddr_in* addr4;
-  struct sockaddr_in6* addr6;
-
-  addr4 = (struct sockaddr_in*) &addr_st;
-  addr6 = (struct sockaddr_in6*) &addr_st;
-
-  if (!interface_addr) {
-    memset(&addr_st, 0, sizeof addr_st);
-    if (handle->flags & UV_HANDLE_IPV6) {
-      addr_st.ss_family = AF_INET6;
-      addr6->sin6_scope_id = 0;
-    } else {
-      addr_st.ss_family = AF_INET;
-      addr4->sin_addr.s_addr = htonl(INADDR_ANY);
-    }
-  } else if (uv_ip4_addr(interface_addr, 0, addr4) == 0) {
-    /* nothing, address was parsed */
-  } else if (uv_ip6_addr(interface_addr, 0, addr6) == 0) {
-    /* nothing, address was parsed */
-  } else {
-    return UV_EINVAL;
-  }
-
-  if (addr_st.ss_family == AF_INET) {
-    if (setsockopt(handle->io_watcher.fd,
-                   IPPROTO_IP,
-                   IP_MULTICAST_IF,
-                   (void*) &addr4->sin_addr,
-                   sizeof(addr4->sin_addr)) == -1) {
-      return UV__ERR(errno);
-    }
-  } else if (addr_st.ss_family == AF_INET6) {
-    if (setsockopt(handle->io_watcher.fd,
-                   IPPROTO_IPV6,
-                   IPV6_MULTICAST_IF,
-                   &addr6->sin6_scope_id,
-                   sizeof(addr6->sin6_scope_id)) == -1) {
-      return UV__ERR(errno);
-    }
-  } else {
-    assert(0 && "unexpected address family");
-    abort();
-  }
-
-  return 0;
-}
-
-int uv_udp_getpeername(const uv_udp_t* handle,
-                       struct sockaddr* name,
-                       int* namelen) {
-
-  return uv__getsockpeername((const uv_handle_t*) handle,
-                             getpeername,
-                             name,
-                             namelen);
-}
-
-int uv_udp_getsockname(const uv_udp_t* handle,
-                       struct sockaddr* name,
-                       int* namelen) {
-
-  return uv__getsockpeername((const uv_handle_t*) handle,
-                             getsockname,
-                             name,
-                             namelen);
-}
-
-
-int uv__udp_recv_start(uv_udp_t* handle,
-                       uv_alloc_cb alloc_cb,
-                       uv_udp_recv_cb recv_cb) {
-  int err;
-
-  if (alloc_cb == NULL || recv_cb == NULL)
-    return UV_EINVAL;
-
-  if (uv__io_active(&handle->io_watcher, POLLIN))
-    return UV_EALREADY;  /* FIXME(bnoordhuis) Should be UV_EBUSY. */
-
-  err = uv__udp_maybe_deferred_bind(handle, AF_INET, 0);
-  if (err)
-    return err;
-
-  handle->alloc_cb = alloc_cb;
-  handle->recv_cb = recv_cb;
-
-  uv__io_start(handle->loop, &handle->io_watcher, POLLIN);
-  uv__handle_start(handle);
-
-  return 0;
-}
-
-
-int uv__udp_recv_stop(uv_udp_t* handle) {
-  uv__io_stop(handle->loop, &handle->io_watcher, POLLIN);
-
-  if (!uv__io_active(&handle->io_watcher, POLLOUT))
-    uv__handle_stop(handle);
-
-  handle->alloc_cb = NULL;
-  handle->recv_cb = NULL;
-
-  return 0;
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/uv-common.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/uv-common.cpp
deleted file mode 100644
index 3c65476..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/uv-common.cpp
+++ /dev/null
@@ -1,797 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include "uv.h"
-#include "uv-common.h"
-
-#include <assert.h>
-#include <errno.h>
-#include <stdarg.h>
-#include <stddef.h> /* NULL */
-#include <stdio.h>
-#include <stdlib.h> /* malloc */
-#include <string.h> /* memset */
-
-#if defined(_WIN32)
-# include <malloc.h> /* malloc */
-#else
-# include <net/if.h> /* if_nametoindex */
-# include <sys/un.h> /* AF_UNIX, sockaddr_un */
-#endif
-
-
-typedef struct {
-  uv_malloc_func local_malloc;
-  uv_realloc_func local_realloc;
-  uv_calloc_func local_calloc;
-  uv_free_func local_free;
-} uv__allocator_t;
-
-static uv__allocator_t uv__allocator = {
-  malloc,
-  realloc,
-  calloc,
-  free,
-};
-
-char* uv__strdup(const char* s) {
-  size_t len = strlen(s) + 1;
-  char* m = (char*)uv__malloc(len);
-  if (m == NULL)
-    return NULL;
-  return (char*)memcpy(m, s, len);
-}
-
-char* uv__strndup(const char* s, size_t n) {
-  char* m;
-  size_t len = strlen(s);
-  if (n < len)
-    len = n;
-  m = (char*)uv__malloc(len + 1);
-  if (m == NULL)
-    return NULL;
-  m[len] = '\0';
-  return (char*)memcpy(m, s, len);
-}
-
-void* uv__malloc(size_t size) {
-  if (size > 0)
-    return uv__allocator.local_malloc(size);
-  return NULL;
-}
-
-void uv__free(void* ptr) {
-  int saved_errno;
-
-  /* Libuv expects that free() does not clobber errno.  The system allocator
-   * honors that assumption but custom allocators may not be so careful.
-   */
-  saved_errno = errno;
-  uv__allocator.local_free(ptr);
-  errno = saved_errno;
-}
-
-void* uv__calloc(size_t count, size_t size) {
-  return uv__allocator.local_calloc(count, size);
-}
-
-void* uv__realloc(void* ptr, size_t size) {
-  if (size > 0)
-    return uv__allocator.local_realloc(ptr, size);
-  uv__free(ptr);
-  return NULL;
-}
-
-int uv_replace_allocator(uv_malloc_func malloc_func,
-                         uv_realloc_func realloc_func,
-                         uv_calloc_func calloc_func,
-                         uv_free_func free_func) {
-  if (malloc_func == NULL || realloc_func == NULL ||
-      calloc_func == NULL || free_func == NULL) {
-    return UV_EINVAL;
-  }
-
-  uv__allocator.local_malloc = malloc_func;
-  uv__allocator.local_realloc = realloc_func;
-  uv__allocator.local_calloc = calloc_func;
-  uv__allocator.local_free = free_func;
-
-  return 0;
-}
-
-#define XX(uc, lc) case UV_##uc: return sizeof(uv_##lc##_t);
-
-size_t uv_handle_size(uv_handle_type type) {
-  switch (type) {
-    UV_HANDLE_TYPE_MAP(XX)
-    default:
-      return -1;
-  }
-}
-
-size_t uv_req_size(uv_req_type type) {
-  switch(type) {
-    UV_REQ_TYPE_MAP(XX)
-    default:
-      return -1;
-  }
-}
-
-#undef XX
-
-
-size_t uv_loop_size(void) {
-  return sizeof(uv_loop_t);
-}
-
-
-uv_buf_t uv_buf_init(char* base, unsigned int len) {
-  uv_buf_t buf;
-  buf.base = base;
-  buf.len = len;
-  return buf;
-}
-
-
-static const char* uv__unknown_err_code(int err) {
-  char buf[32];
-  char* copy;
-
-  snprintf(buf, sizeof(buf), "Unknown system error %d", err);
-  copy = uv__strdup(buf);
-
-  return copy != NULL ? copy : "Unknown system error";
-}
-
-#define UV_ERR_NAME_GEN_R(name, _) \
-case UV_## name: \
-  uv__strscpy(buf, #name, buflen); break;
-char* uv_err_name_r(int err, char* buf, size_t buflen) {
-  switch (err) {
-    UV_ERRNO_MAP(UV_ERR_NAME_GEN_R)
-    default: snprintf(buf, buflen, "Unknown system error %d", err);
-  }
-  return buf;
-}
-#undef UV_ERR_NAME_GEN_R
-
-
-#define UV_ERR_NAME_GEN(name, _) case UV_ ## name: return #name;
-const char* uv_err_name(int err) {
-  switch (err) {
-    UV_ERRNO_MAP(UV_ERR_NAME_GEN)
-  }
-  return uv__unknown_err_code(err);
-}
-#undef UV_ERR_NAME_GEN
-
-
-#define UV_STRERROR_GEN_R(name, msg) \
-case UV_ ## name: \
-  snprintf(buf, buflen, "%s", msg); break;
-char* uv_strerror_r(int err, char* buf, size_t buflen) {
-  switch (err) {
-    UV_ERRNO_MAP(UV_STRERROR_GEN_R)
-    default: snprintf(buf, buflen, "Unknown system error %d", err);
-  }
-  return buf;
-}
-#undef UV_STRERROR_GEN_R
-
-
-#define UV_STRERROR_GEN(name, msg) case UV_ ## name: return msg;
-const char* uv_strerror(int err) {
-  switch (err) {
-    UV_ERRNO_MAP(UV_STRERROR_GEN)
-  }
-  return uv__unknown_err_code(err);
-}
-#undef UV_STRERROR_GEN
-
-
-int uv_ip4_addr(const char* ip, int port, struct sockaddr_in* addr) {
-  memset(addr, 0, sizeof(*addr));
-  addr->sin_family = AF_INET;
-  addr->sin_port = htons(port);
-  return uv_inet_pton(AF_INET, ip, &(addr->sin_addr.s_addr));
-}
-
-
-int uv_ip6_addr(const char* ip, int port, struct sockaddr_in6* addr) {
-  char address_part[40];
-  size_t address_part_size;
-  const char* zone_index;
-
-  memset(addr, 0, sizeof(*addr));
-  addr->sin6_family = AF_INET6;
-  addr->sin6_port = htons(port);
-#ifdef SIN6_LEN
-  addr->sin6_len = sizeof(*addr);
-#endif
-
-  zone_index = strchr(ip, '%');
-  if (zone_index != NULL) {
-    address_part_size = zone_index - ip;
-    if (address_part_size >= sizeof(address_part))
-      address_part_size = sizeof(address_part) - 1;
-
-    memcpy(address_part, ip, address_part_size);
-    address_part[address_part_size] = '\0';
-    ip = address_part;
-
-    zone_index++; /* skip '%' */
-    /* NOTE: unknown interface (id=0) is silently ignored */
-#ifdef _WIN32
-    addr->sin6_scope_id = atoi(zone_index);
-#else
-    addr->sin6_scope_id = if_nametoindex(zone_index);
-#endif
-  }
-
-  return uv_inet_pton(AF_INET6, ip, &addr->sin6_addr);
-}
-
-
-int uv_ip4_name(const struct sockaddr_in* src, char* dst, size_t size) {
-  return uv_inet_ntop(AF_INET, &src->sin_addr, dst, size);
-}
-
-
-int uv_ip6_name(const struct sockaddr_in6* src, char* dst, size_t size) {
-  return uv_inet_ntop(AF_INET6, &src->sin6_addr, dst, size);
-}
-
-
-int uv_tcp_bind(uv_tcp_t* handle,
-                const struct sockaddr* addr,
-                unsigned int flags) {
-  unsigned int addrlen;
-
-  if (handle->type != UV_TCP)
-    return UV_EINVAL;
-
-  if (addr->sa_family == AF_INET)
-    addrlen = sizeof(struct sockaddr_in);
-  else if (addr->sa_family == AF_INET6)
-    addrlen = sizeof(struct sockaddr_in6);
-  else
-    return UV_EINVAL;
-
-  return uv__tcp_bind(handle, addr, addrlen, flags);
-}
-
-
-int uv_udp_bind(uv_udp_t* handle,
-                const struct sockaddr* addr,
-                unsigned int flags) {
-  unsigned int addrlen;
-
-  if (handle->type != UV_UDP)
-    return UV_EINVAL;
-
-  if (addr->sa_family == AF_INET)
-    addrlen = sizeof(struct sockaddr_in);
-  else if (addr->sa_family == AF_INET6)
-    addrlen = sizeof(struct sockaddr_in6);
-  else
-    return UV_EINVAL;
-
-  return uv__udp_bind(handle, addr, addrlen, flags);
-}
-
-
-int uv_tcp_connect(uv_connect_t* req,
-                   uv_tcp_t* handle,
-                   const struct sockaddr* addr,
-                   uv_connect_cb cb) {
-  unsigned int addrlen;
-
-  if (handle->type != UV_TCP)
-    return UV_EINVAL;
-
-  if (addr->sa_family == AF_INET)
-    addrlen = sizeof(struct sockaddr_in);
-  else if (addr->sa_family == AF_INET6)
-    addrlen = sizeof(struct sockaddr_in6);
-  else
-    return UV_EINVAL;
-
-  return uv__tcp_connect(req, handle, addr, addrlen, cb);
-}
-
-
-int uv_udp_connect(uv_udp_t* handle, const struct sockaddr* addr) {
-  unsigned int addrlen;
-
-  if (handle->type != UV_UDP)
-    return UV_EINVAL;
-
-  /* Disconnect the handle */
-  if (addr == NULL) {
-    if (!(handle->flags & UV_HANDLE_UDP_CONNECTED))
-      return UV_ENOTCONN;
-
-    return uv__udp_disconnect(handle);
-  }
-
-  if (addr->sa_family == AF_INET)
-    addrlen = sizeof(struct sockaddr_in);
-  else if (addr->sa_family == AF_INET6)
-    addrlen = sizeof(struct sockaddr_in6);
-  else
-    return UV_EINVAL;
-
-  if (handle->flags & UV_HANDLE_UDP_CONNECTED)
-    return UV_EISCONN;
-
-  return uv__udp_connect(handle, addr, addrlen);
-}
-
-
-int uv__udp_is_connected(uv_udp_t* handle) {
-  struct sockaddr_storage addr;
-  int addrlen;
-  if (handle->type != UV_UDP)
-    return 0;
-
-  addrlen = sizeof(addr);
-  if (uv_udp_getpeername(handle, (struct sockaddr*) &addr, &addrlen) != 0)
-    return 0;
-
-  return addrlen > 0;
-}
-
-
-int uv__udp_check_before_send(uv_udp_t* handle, const struct sockaddr* addr) {
-  unsigned int addrlen;
-
-  if (handle->type != UV_UDP)
-    return UV_EINVAL;
-
-  if (addr != NULL && (handle->flags & UV_HANDLE_UDP_CONNECTED))
-    return UV_EISCONN;
-
-  if (addr == NULL && !(handle->flags & UV_HANDLE_UDP_CONNECTED))
-    return UV_EDESTADDRREQ;
-
-  if (addr != NULL) {
-    if (addr->sa_family == AF_INET)
-      addrlen = sizeof(struct sockaddr_in);
-    else if (addr->sa_family == AF_INET6)
-      addrlen = sizeof(struct sockaddr_in6);
-#if defined(AF_UNIX) && !defined(_WIN32)
-    else if (addr->sa_family == AF_UNIX)
-      addrlen = sizeof(struct sockaddr_un);
-#endif
-    else
-      return UV_EINVAL;
-  } else {
-    addrlen = 0;
-  }
-
-  return addrlen;
-}
-
-
-int uv_udp_send(uv_udp_send_t* req,
-                uv_udp_t* handle,
-                const uv_buf_t bufs[],
-                unsigned int nbufs,
-                const struct sockaddr* addr,
-                uv_udp_send_cb send_cb) {
-  int addrlen;
-
-  addrlen = uv__udp_check_before_send(handle, addr);
-  if (addrlen < 0)
-    return addrlen;
-
-  return uv__udp_send(req, handle, bufs, nbufs, addr, addrlen, send_cb);
-}
-
-
-int uv_udp_try_send(uv_udp_t* handle,
-                    const uv_buf_t bufs[],
-                    unsigned int nbufs,
-                    const struct sockaddr* addr) {
-  int addrlen;
-
-  addrlen = uv__udp_check_before_send(handle, addr);
-  if (addrlen < 0)
-    return addrlen;
-
-  return uv__udp_try_send(handle, bufs, nbufs, addr, addrlen);
-}
-
-
-int uv_udp_recv_start(uv_udp_t* handle,
-                      uv_alloc_cb alloc_cb,
-                      uv_udp_recv_cb recv_cb) {
-  if (handle->type != UV_UDP || alloc_cb == NULL || recv_cb == NULL)
-    return UV_EINVAL;
-  else
-    return uv__udp_recv_start(handle, alloc_cb, recv_cb);
-}
-
-
-int uv_udp_recv_stop(uv_udp_t* handle) {
-  if (handle->type != UV_UDP)
-    return UV_EINVAL;
-  else
-    return uv__udp_recv_stop(handle);
-}
-
-
-void uv_walk(uv_loop_t* loop, uv_walk_cb walk_cb, void* arg) {
-  QUEUE queue;
-  QUEUE* q;
-  uv_handle_t* h;
-
-  QUEUE_MOVE(&loop->handle_queue, &queue);
-  while (!QUEUE_EMPTY(&queue)) {
-    q = QUEUE_HEAD(&queue);
-    h = QUEUE_DATA(q, uv_handle_t, handle_queue);
-
-    QUEUE_REMOVE(q);
-    QUEUE_INSERT_TAIL(&loop->handle_queue, q);
-
-    if (h->flags & UV_HANDLE_INTERNAL) continue;
-    walk_cb(h, arg);
-  }
-}
-
-
-static void uv__print_handles(uv_loop_t* loop, int only_active, FILE* stream) {
-  const char* type;
-  QUEUE* q;
-  uv_handle_t* h;
-
-  if (loop == NULL)
-    loop = uv_default_loop();
-
-  QUEUE_FOREACH(q, &loop->handle_queue) {
-    h = QUEUE_DATA(q, uv_handle_t, handle_queue);
-
-    if (only_active && !uv__is_active(h))
-      continue;
-
-    switch (h->type) {
-#define X(uc, lc) case UV_##uc: type = #lc; break;
-      UV_HANDLE_TYPE_MAP(X)
-#undef X
-      default: type = "<unknown>";
-    }
-
-    fprintf(stream,
-            "[%c%c%c] %-8s %p\n",
-            "R-"[!(h->flags & UV_HANDLE_REF)],
-            "A-"[!(h->flags & UV_HANDLE_ACTIVE)],
-            "I-"[!(h->flags & UV_HANDLE_INTERNAL)],
-            type,
-            (void*)h);
-  }
-}
-
-
-void uv_print_all_handles(uv_loop_t* loop, FILE* stream) {
-  uv__print_handles(loop, 0, stream);
-}
-
-
-void uv_print_active_handles(uv_loop_t* loop, FILE* stream) {
-  uv__print_handles(loop, 1, stream);
-}
-
-
-void uv_ref(uv_handle_t* handle) {
-  uv__handle_ref(handle);
-}
-
-
-void uv_unref(uv_handle_t* handle) {
-  uv__handle_unref(handle);
-}
-
-
-int uv_has_ref(const uv_handle_t* handle) {
-  return uv__has_ref(handle);
-}
-
-
-void uv_stop(uv_loop_t* loop) {
-  loop->stop_flag = 1;
-}
-
-
-uint64_t uv_now(const uv_loop_t* loop) {
-  return loop->time;
-}
-
-
-
-size_t uv__count_bufs(const uv_buf_t bufs[], unsigned int nbufs) {
-  unsigned int i;
-  size_t bytes;
-
-  bytes = 0;
-  for (i = 0; i < nbufs; i++)
-    bytes += (size_t) bufs[i].len;
-
-  return bytes;
-}
-
-int uv_recv_buffer_size(uv_handle_t* handle, int* value) {
-  return uv__socket_sockopt(handle, SO_RCVBUF, value);
-}
-
-int uv_send_buffer_size(uv_handle_t* handle, int *value) {
-  return uv__socket_sockopt(handle, SO_SNDBUF, value);
-}
-
-int uv_fs_event_getpath(uv_fs_event_t* handle, char* buffer, size_t* size) {
-  size_t required_len;
-
-  if (!uv__is_active(handle)) {
-    *size = 0;
-    return UV_EINVAL;
-  }
-
-  required_len = strlen(handle->path);
-  if (required_len >= *size) {
-    *size = required_len + 1;
-    return UV_ENOBUFS;
-  }
-
-  memcpy(buffer, handle->path, required_len);
-  *size = required_len;
-  buffer[required_len] = '\0';
-
-  return 0;
-}
-
-/* The windows implementation does not have the same structure layout as
- * the unix implementation (nbufs is not directly inside req but is
- * contained in a nested union/struct) so this function locates it.
-*/
-static unsigned int* uv__get_nbufs(uv_fs_t* req) {
-#ifdef _WIN32
-  return &req->fs.info.nbufs;
-#else
-  return &req->nbufs;
-#endif
-}
-
-/* uv_fs_scandir() uses the system allocator to allocate memory on non-Windows
- * systems. So, the memory should be released using free(). On Windows,
- * uv__malloc() is used, so use uv__free() to free memory.
-*/
-#ifdef _WIN32
-# define uv__fs_scandir_free uv__free
-#else
-# define uv__fs_scandir_free free
-#endif
-
-void uv__fs_scandir_cleanup(uv_fs_t* req) {
-  uv__dirent_t** dents;
-
-  unsigned int* nbufs = uv__get_nbufs(req);
-
-  dents = (uv__dirent_t**)(req->ptr);
-  if (*nbufs > 0 && *nbufs != (unsigned int) req->result)
-    (*nbufs)--;
-  for (; *nbufs < (unsigned int) req->result; (*nbufs)++)
-    uv__fs_scandir_free(dents[*nbufs]);
-
-  uv__fs_scandir_free(req->ptr);
-  req->ptr = NULL;
-}
-
-
-int uv_fs_scandir_next(uv_fs_t* req, uv_dirent_t* ent) {
-  uv__dirent_t** dents;
-  uv__dirent_t* dent;
-  unsigned int* nbufs;
-
-  /* Check to see if req passed */
-  if (req->result < 0)
-    return req->result;
-
-  /* Ptr will be null if req was canceled or no files found */
-  if (!req->ptr)
-    return UV_EOF;
-
-  nbufs = uv__get_nbufs(req);
-  assert(nbufs);
-
-  dents = (uv__dirent_t**)(req->ptr);
-
-  /* Free previous entity */
-  if (*nbufs > 0)
-    uv__fs_scandir_free(dents[*nbufs - 1]);
-
-  /* End was already reached */
-  if (*nbufs == (unsigned int) req->result) {
-    uv__fs_scandir_free(dents);
-    req->ptr = NULL;
-    return UV_EOF;
-  }
-
-  dent = dents[(*nbufs)++];
-
-  ent->name = dent->d_name;
-  ent->type = uv__fs_get_dirent_type(dent);
-
-  return 0;
-}
-
-uv_dirent_type_t uv__fs_get_dirent_type(uv__dirent_t* dent) {
-  uv_dirent_type_t type;
-
-#ifdef HAVE_DIRENT_TYPES
-  switch (dent->d_type) {
-    case UV__DT_DIR:
-      type = UV_DIRENT_DIR;
-      break;
-    case UV__DT_FILE:
-      type = UV_DIRENT_FILE;
-      break;
-    case UV__DT_LINK:
-      type = UV_DIRENT_LINK;
-      break;
-    case UV__DT_FIFO:
-      type = UV_DIRENT_FIFO;
-      break;
-    case UV__DT_SOCKET:
-      type = UV_DIRENT_SOCKET;
-      break;
-    case UV__DT_CHAR:
-      type = UV_DIRENT_CHAR;
-      break;
-    case UV__DT_BLOCK:
-      type = UV_DIRENT_BLOCK;
-      break;
-    default:
-      type = UV_DIRENT_UNKNOWN;
-  }
-#else
-  type = UV_DIRENT_UNKNOWN;
-#endif
-
-  return type;
-}
-
-void uv__fs_readdir_cleanup(uv_fs_t* req) {
-  uv_dir_t* dir;
-  uv_dirent_t* dirents;
-  int i;
-
-  if (req->ptr == NULL)
-    return;
-
-  dir = (uv_dir_t*)req->ptr;
-  dirents = dir->dirents;
-  req->ptr = NULL;
-
-  if (dirents == NULL)
-    return;
-
-  for (i = 0; i < req->result; ++i) {
-    uv__free((char*) dirents[i].name);
-    dirents[i].name = NULL;
-  }
-}
-
-
-#ifdef __clang__
-# pragma clang diagnostic push
-# pragma clang diagnostic ignored "-Wvarargs"
-#endif
-
-int uv_loop_configure(uv_loop_t* loop, uv_loop_option option, ...) {
-  va_list ap;
-  int err;
-
-  va_start(ap, option);
-  /* Any platform-agnostic options should be handled here. */
-  err = uv__loop_configure(loop, option, ap);
-  va_end(ap);
-
-  return err;
-}
-
-#ifdef __clang__
-# pragma clang diagnostic pop
-#endif
-
-
-static uv_loop_t default_loop_struct;
-static uv_loop_t* default_loop_ptr;
-
-
-uv_loop_t* uv_default_loop(void) {
-  if (default_loop_ptr != NULL)
-    return default_loop_ptr;
-
-  if (uv_loop_init(&default_loop_struct))
-    return NULL;
-
-  default_loop_ptr = &default_loop_struct;
-  return default_loop_ptr;
-}
-
-
-uv_loop_t* uv_loop_new(void) {
-  uv_loop_t* loop;
-
-  loop = (uv_loop_t*)uv__malloc(sizeof(*loop));
-  if (loop == NULL)
-    return NULL;
-
-  if (uv_loop_init(loop)) {
-    uv__free(loop);
-    return NULL;
-  }
-
-  return loop;
-}
-
-
-int uv_loop_close(uv_loop_t* loop) {
-  QUEUE* q;
-  uv_handle_t* h;
-#ifndef NDEBUG
-  void* saved_data;
-#endif
-
-  if (uv__has_active_reqs(loop))
-    return UV_EBUSY;
-
-  QUEUE_FOREACH(q, &loop->handle_queue) {
-    h = QUEUE_DATA(q, uv_handle_t, handle_queue);
-    if (!(h->flags & UV_HANDLE_INTERNAL))
-      return UV_EBUSY;
-  }
-
-  uv__loop_close(loop);
-
-#ifndef NDEBUG
-  saved_data = loop->data;
-  memset(loop, -1, sizeof(*loop));
-  loop->data = saved_data;
-#endif
-  if (loop == default_loop_ptr)
-    default_loop_ptr = NULL;
-
-  return 0;
-}
-
-
-void uv_loop_delete(uv_loop_t* loop) {
-  uv_loop_t* default_loop;
-  int err;
-
-  default_loop = default_loop_ptr;
-
-  err = uv_loop_close(loop);
-  (void) err;    /* Squelch compiler warnings. */
-  assert(err == 0);
-  if (loop != default_loop)
-    uv__free(loop);
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/uv-common.h b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/uv-common.h
deleted file mode 100644
index f788161..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/uv-common.h
+++ /dev/null
@@ -1,326 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-/*
- * This file is private to libuv. It provides common functionality to both
- * Windows and Unix backends.
- */
-
-#ifndef UV_COMMON_H_
-#define UV_COMMON_H_
-
-#include <assert.h>
-#include <stdarg.h>
-#include <stddef.h>
-
-#if defined(_MSC_VER) && _MSC_VER < 1600
-# include "uv/stdint-msvc2008.h"
-#else
-# include <stdint.h>
-#endif
-
-#include "uv.h"
-#include "uv/tree.h"
-#include "queue.h"
-#include "strscpy.h"
-
-#if EDOM > 0
-# define UV__ERR(x) (-(x))
-#else
-# define UV__ERR(x) (x)
-#endif
-
-#if !defined(snprintf) && defined(_MSC_VER) && _MSC_VER < 1900
-extern int snprintf(char*, size_t, const char*, ...);
-#endif
-
-#define ARRAY_SIZE(a) (sizeof(a) / sizeof((a)[0]))
-
-#define container_of(ptr, type, member) \
-  ((type *) ((char *) (ptr) - offsetof(type, member)))
-
-#define STATIC_ASSERT(expr)                                                   \
-  void uv__static_assert(int static_assert_failed[1 - 2 * !(expr)])
-
-/* Handle flags. Some flags are specific to Windows or UNIX. */
-enum {
-  /* Used by all handles. */
-  UV_HANDLE_CLOSING                     = 0x00000001,
-  UV_HANDLE_CLOSED                      = 0x00000002,
-  UV_HANDLE_ACTIVE                      = 0x00000004,
-  UV_HANDLE_REF                         = 0x00000008,
-  UV_HANDLE_INTERNAL                    = 0x00000010,
-  UV_HANDLE_ENDGAME_QUEUED              = 0x00000020,
-
-  /* Used by streams. */
-  UV_HANDLE_LISTENING                   = 0x00000040,
-  UV_HANDLE_CONNECTION                  = 0x00000080,
-  UV_HANDLE_SHUTTING                    = 0x00000100,
-  UV_HANDLE_SHUT                        = 0x00000200,
-  UV_HANDLE_READ_PARTIAL                = 0x00000400,
-  UV_HANDLE_READ_EOF                    = 0x00000800,
-
-  /* Used by streams and UDP handles. */
-  UV_HANDLE_READING                     = 0x00001000,
-  UV_HANDLE_BOUND                       = 0x00002000,
-  UV_HANDLE_READABLE                    = 0x00004000,
-  UV_HANDLE_WRITABLE                    = 0x00008000,
-  UV_HANDLE_READ_PENDING                = 0x00010000,
-  UV_HANDLE_SYNC_BYPASS_IOCP            = 0x00020000,
-  UV_HANDLE_ZERO_READ                   = 0x00040000,
-  UV_HANDLE_EMULATE_IOCP                = 0x00080000,
-  UV_HANDLE_BLOCKING_WRITES             = 0x00100000,
-  UV_HANDLE_CANCELLATION_PENDING        = 0x00200000,
-
-  /* Used by uv_tcp_t and uv_udp_t handles */
-  UV_HANDLE_IPV6                        = 0x00400000,
-
-  /* Only used by uv_tcp_t handles. */
-  UV_HANDLE_TCP_NODELAY                 = 0x01000000,
-  UV_HANDLE_TCP_KEEPALIVE               = 0x02000000,
-  UV_HANDLE_TCP_SINGLE_ACCEPT           = 0x04000000,
-  UV_HANDLE_TCP_ACCEPT_STATE_CHANGING   = 0x08000000,
-  UV_HANDLE_TCP_SOCKET_CLOSED           = 0x10000000,
-  UV_HANDLE_SHARED_TCP_SOCKET           = 0x20000000,
-
-  /* Only used by uv_udp_t handles. */
-  UV_HANDLE_UDP_PROCESSING              = 0x01000000,
-  UV_HANDLE_UDP_CONNECTED               = 0x02000000,
-
-  /* Only used by uv_pipe_t handles. */
-  UV_HANDLE_NON_OVERLAPPED_PIPE         = 0x01000000,
-  UV_HANDLE_PIPESERVER                  = 0x02000000,
-
-  /* Only used by uv_tty_t handles. */
-  UV_HANDLE_TTY_READABLE                = 0x01000000,
-  UV_HANDLE_TTY_RAW                     = 0x02000000,
-  UV_HANDLE_TTY_SAVED_POSITION          = 0x04000000,
-  UV_HANDLE_TTY_SAVED_ATTRIBUTES        = 0x08000000,
-
-  /* Only used by uv_signal_t handles. */
-  UV_SIGNAL_ONE_SHOT_DISPATCHED         = 0x01000000,
-  UV_SIGNAL_ONE_SHOT                    = 0x02000000,
-
-  /* Only used by uv_poll_t handles. */
-  UV_HANDLE_POLL_SLOW                   = 0x01000000
-};
-
-int uv__loop_configure(uv_loop_t* loop, uv_loop_option option, va_list ap);
-
-void uv__loop_close(uv_loop_t* loop);
-
-int uv__tcp_bind(uv_tcp_t* tcp,
-                 const struct sockaddr* addr,
-                 unsigned int addrlen,
-                 unsigned int flags);
-
-int uv__tcp_connect(uv_connect_t* req,
-                   uv_tcp_t* handle,
-                   const struct sockaddr* addr,
-                   unsigned int addrlen,
-                   uv_connect_cb cb);
-
-int uv__udp_bind(uv_udp_t* handle,
-                 const struct sockaddr* addr,
-                 unsigned int  addrlen,
-                 unsigned int flags);
-
-int uv__udp_connect(uv_udp_t* handle,
-                    const struct sockaddr* addr,
-                    unsigned int addrlen);
-
-int uv__udp_disconnect(uv_udp_t* handle);
-
-int uv__udp_is_connected(uv_udp_t* handle);
-
-int uv__udp_send(uv_udp_send_t* req,
-                 uv_udp_t* handle,
-                 const uv_buf_t bufs[],
-                 unsigned int nbufs,
-                 const struct sockaddr* addr,
-                 unsigned int addrlen,
-                 uv_udp_send_cb send_cb);
-
-int uv__udp_try_send(uv_udp_t* handle,
-                     const uv_buf_t bufs[],
-                     unsigned int nbufs,
-                     const struct sockaddr* addr,
-                     unsigned int addrlen);
-
-int uv__udp_recv_start(uv_udp_t* handle, uv_alloc_cb alloccb,
-                       uv_udp_recv_cb recv_cb);
-
-int uv__udp_recv_stop(uv_udp_t* handle);
-
-void uv__fs_poll_close(uv_fs_poll_t* handle);
-
-int uv__getaddrinfo_translate_error(int sys_err);    /* EAI_* error. */
-
-enum uv__work_kind {
-  UV__WORK_CPU,
-  UV__WORK_FAST_IO,
-  UV__WORK_SLOW_IO
-};
-
-void uv__work_submit(uv_loop_t* loop,
-                     struct uv__work *w,
-                     enum uv__work_kind kind,
-                     void (*work)(struct uv__work *w),
-                     void (*done)(struct uv__work *w, int status));
-
-void uv__work_done(uv_async_t* handle);
-
-size_t uv__count_bufs(const uv_buf_t bufs[], unsigned int nbufs);
-
-int uv__socket_sockopt(uv_handle_t* handle, int optname, int* value);
-
-void uv__fs_scandir_cleanup(uv_fs_t* req);
-void uv__fs_readdir_cleanup(uv_fs_t* req);
-uv_dirent_type_t uv__fs_get_dirent_type(uv__dirent_t* dent);
-
-int uv__next_timeout(const uv_loop_t* loop);
-void uv__run_timers(uv_loop_t* loop);
-void uv__timer_close(uv_timer_t* handle);
-
-#define uv__has_active_reqs(loop)                                             \
-  ((loop)->active_reqs.count > 0)
-
-#define uv__req_register(loop, req)                                           \
-  do {                                                                        \
-    (loop)->active_reqs.count++;                                              \
-  }                                                                           \
-  while (0)
-
-#define uv__req_unregister(loop, req)                                         \
-  do {                                                                        \
-    assert(uv__has_active_reqs(loop));                                        \
-    (loop)->active_reqs.count--;                                              \
-  }                                                                           \
-  while (0)
-
-#define uv__has_active_handles(loop)                                          \
-  ((loop)->active_handles > 0)
-
-#define uv__active_handle_add(h)                                              \
-  do {                                                                        \
-    (h)->loop->active_handles++;                                              \
-  }                                                                           \
-  while (0)
-
-#define uv__active_handle_rm(h)                                               \
-  do {                                                                        \
-    (h)->loop->active_handles--;                                              \
-  }                                                                           \
-  while (0)
-
-#define uv__is_active(h)                                                      \
-  (((h)->flags & UV_HANDLE_ACTIVE) != 0)
-
-#define uv__is_closing(h)                                                     \
-  (((h)->flags & (UV_HANDLE_CLOSING | UV_HANDLE_CLOSED)) != 0)
-
-#define uv__handle_start(h)                                                   \
-  do {                                                                        \
-    if (((h)->flags & UV_HANDLE_ACTIVE) != 0) break;                          \
-    (h)->flags |= UV_HANDLE_ACTIVE;                                           \
-    if (((h)->flags & UV_HANDLE_REF) != 0) uv__active_handle_add(h);          \
-  }                                                                           \
-  while (0)
-
-#define uv__handle_stop(h)                                                    \
-  do {                                                                        \
-    if (((h)->flags & UV_HANDLE_ACTIVE) == 0) break;                          \
-    (h)->flags &= ~UV_HANDLE_ACTIVE;                                          \
-    if (((h)->flags & UV_HANDLE_REF) != 0) uv__active_handle_rm(h);           \
-  }                                                                           \
-  while (0)
-
-#define uv__handle_ref(h)                                                     \
-  do {                                                                        \
-    if (((h)->flags & UV_HANDLE_REF) != 0) break;                             \
-    (h)->flags |= UV_HANDLE_REF;                                              \
-    if (((h)->flags & UV_HANDLE_CLOSING) != 0) break;                         \
-    if (((h)->flags & UV_HANDLE_ACTIVE) != 0) uv__active_handle_add(h);       \
-  }                                                                           \
-  while (0)
-
-#define uv__handle_unref(h)                                                   \
-  do {                                                                        \
-    if (((h)->flags & UV_HANDLE_REF) == 0) break;                             \
-    (h)->flags &= ~UV_HANDLE_REF;                                             \
-    if (((h)->flags & UV_HANDLE_CLOSING) != 0) break;                         \
-    if (((h)->flags & UV_HANDLE_ACTIVE) != 0) uv__active_handle_rm(h);        \
-  }                                                                           \
-  while (0)
-
-#define uv__has_ref(h)                                                        \
-  (((h)->flags & UV_HANDLE_REF) != 0)
-
-#if defined(_WIN32)
-# define uv__handle_platform_init(h) ((h)->u.fd = -1)
-#else
-# define uv__handle_platform_init(h) ((h)->next_closing = NULL)
-#endif
-
-#define uv__handle_init(loop_, h, type_)                                      \
-  do {                                                                        \
-    (h)->loop = (loop_);                                                      \
-    (h)->type = (type_);                                                      \
-    (h)->flags = UV_HANDLE_REF;  /* Ref the loop when active. */              \
-    QUEUE_INSERT_TAIL(&(loop_)->handle_queue, &(h)->handle_queue);            \
-    uv__handle_platform_init(h);                                              \
-  }                                                                           \
-  while (0)
-
-/* Note: uses an open-coded version of SET_REQ_SUCCESS() because of
- * a circular dependency between src/uv-common.h and src/win/internal.h.
- */
-#if defined(_WIN32)
-# define UV_REQ_INIT(req, typ)                                                \
-  do {                                                                        \
-    (req)->type = (typ);                                                      \
-    (req)->u.io.overlapped.Internal = 0;  /* SET_REQ_SUCCESS() */             \
-  }                                                                           \
-  while (0)
-#else
-# define UV_REQ_INIT(req, typ)                                                \
-  do {                                                                        \
-    (req)->type = (typ);                                                      \
-  }                                                                           \
-  while (0)
-#endif
-
-#define uv__req_init(loop, req, typ)                                          \
-  do {                                                                        \
-    UV_REQ_INIT(req, typ);                                                    \
-    uv__req_register(loop, req);                                              \
-  }                                                                           \
-  while (0)
-
-/* Allocator prototypes */
-void *uv__calloc(size_t count, size_t size);
-char *uv__strdup(const char* s);
-char *uv__strndup(const char* s, size_t n);
-void* uv__malloc(size_t size);
-void uv__free(void* ptr);
-void* uv__realloc(void* ptr, size_t size);
-
-#endif /* UV_COMMON_H_ */
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/uv-data-getter-setters.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/uv-data-getter-setters.cpp
deleted file mode 100644
index c302566..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/uv-data-getter-setters.cpp
+++ /dev/null
@@ -1,98 +0,0 @@
-#include "uv.h"
-
-const char* uv_handle_type_name(uv_handle_type type) {
-  switch (type) {
-#define XX(uc,lc) case UV_##uc: return #lc;
-  UV_HANDLE_TYPE_MAP(XX)
-#undef XX
-  case UV_FILE: return "file";
-  case UV_HANDLE_TYPE_MAX:
-  case UV_UNKNOWN_HANDLE: return NULL;
-  }
-  return NULL;
-}
-
-uv_handle_type uv_handle_get_type(const uv_handle_t* handle) {
-  return handle->type;
-}
-
-void* uv_handle_get_data(const uv_handle_t* handle) {
-  return handle->data;
-}
-
-uv_loop_t* uv_handle_get_loop(const uv_handle_t* handle) {
-  return handle->loop;
-}
-
-void uv_handle_set_data(uv_handle_t* handle, void* data) {
-  handle->data = data;
-}
-
-const char* uv_req_type_name(uv_req_type type) {
-  switch (type) {
-#define XX(uc,lc) case UV_##uc: return #lc;
-  UV_REQ_TYPE_MAP(XX)
-#undef XX
-  case UV_REQ_TYPE_MAX:
-  case UV_UNKNOWN_REQ:
-  default: /* UV_REQ_TYPE_PRIVATE */
-    break;
-  }
-  return NULL;
-}
-
-uv_req_type uv_req_get_type(const uv_req_t* req) {
-  return req->type;
-}
-
-void* uv_req_get_data(const uv_req_t* req) {
-  return req->data;
-}
-
-void uv_req_set_data(uv_req_t* req, void* data) {
-  req->data = data;
-}
-
-size_t uv_stream_get_write_queue_size(const uv_stream_t* stream) {
-  return stream->write_queue_size;
-}
-
-size_t uv_udp_get_send_queue_size(const uv_udp_t* handle) {
-  return handle->send_queue_size;
-}
-
-size_t uv_udp_get_send_queue_count(const uv_udp_t* handle) {
-  return handle->send_queue_count;
-}
-
-uv_pid_t uv_process_get_pid(const uv_process_t* proc) {
-  return proc->pid;
-}
-
-uv_fs_type uv_fs_get_type(const uv_fs_t* req) {
-  return req->fs_type;
-}
-
-ssize_t uv_fs_get_result(const uv_fs_t* req) {
-  return req->result;
-}
-
-void* uv_fs_get_ptr(const uv_fs_t* req) {
-  return req->ptr;
-}
-
-const char* uv_fs_get_path(const uv_fs_t* req) {
-  return req->path;
-}
-
-uv_stat_t* uv_fs_get_statbuf(uv_fs_t* req) {
-  return &req->statbuf;
-}
-
-void* uv_loop_get_data(const uv_loop_t* loop) {
-  return loop->data;
-}
-
-void uv_loop_set_data(uv_loop_t* loop, void* data) {
-  loop->data = data;
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/async.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/async.cpp
deleted file mode 100644
index d787f66..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/async.cpp
+++ /dev/null
@@ -1,98 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include <assert.h>
-
-#include "uv.h"
-#include "internal.h"
-#include "atomicops-inl.h"
-#include "handle-inl.h"
-#include "req-inl.h"
-
-
-void uv_async_endgame(uv_loop_t* loop, uv_async_t* handle) {
-  if (handle->flags & UV_HANDLE_CLOSING &&
-      !handle->async_sent) {
-    assert(!(handle->flags & UV_HANDLE_CLOSED));
-    uv__handle_close(handle);
-  }
-}
-
-
-int uv_async_init(uv_loop_t* loop, uv_async_t* handle, uv_async_cb async_cb) {
-  uv_req_t* req;
-
-  uv__handle_init(loop, (uv_handle_t*) handle, UV_ASYNC);
-  handle->async_sent = 0;
-  handle->async_cb = async_cb;
-
-  req = &handle->async_req;
-  UV_REQ_INIT(req, UV_WAKEUP);
-  req->data = handle;
-
-  uv__handle_start(handle);
-
-  return 0;
-}
-
-
-void uv_async_close(uv_loop_t* loop, uv_async_t* handle) {
-  if (!((uv_async_t*)handle)->async_sent) {
-    uv_want_endgame(loop, (uv_handle_t*) handle);
-  }
-
-  uv__handle_closing(handle);
-}
-
-
-int uv_async_send(uv_async_t* handle) {
-  uv_loop_t* loop = handle->loop;
-
-  if (handle->type != UV_ASYNC) {
-    /* Can't set errno because that's not thread-safe. */
-    return -1;
-  }
-
-  /* The user should make sure never to call uv_async_send to a closing or
-   * closed handle. */
-  assert(!(handle->flags & UV_HANDLE_CLOSING));
-
-  if (!uv__atomic_exchange_set(&handle->async_sent)) {
-    POST_COMPLETION_FOR_REQ(loop, &handle->async_req);
-  }
-
-  return 0;
-}
-
-
-void uv_process_async_wakeup_req(uv_loop_t* loop, uv_async_t* handle,
-    uv_req_t* req) {
-  assert(handle->type == UV_ASYNC);
-  assert(req->type == UV_WAKEUP);
-
-  handle->async_sent = 0;
-
-  if (handle->flags & UV_HANDLE_CLOSING) {
-    uv_want_endgame(loop, (uv_handle_t*)handle);
-  } else if (handle->async_cb != NULL) {
-    handle->async_cb(handle);
-  }
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/atomicops-inl.h b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/atomicops-inl.h
deleted file mode 100644
index 52713cf..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/atomicops-inl.h
+++ /dev/null
@@ -1,57 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#ifndef UV_WIN_ATOMICOPS_INL_H_
-#define UV_WIN_ATOMICOPS_INL_H_
-
-#include "uv.h"
-#include "internal.h"
-
-
-/* Atomic set operation on char */
-#ifdef _MSC_VER /* MSVC */
-
-/* _InterlockedOr8 is supported by MSVC on x32 and x64. It is slightly less
- * efficient than InterlockedExchange, but InterlockedExchange8 does not exist,
- * and interlocked operations on larger targets might require the target to be
- * aligned. */
-#pragma intrinsic(_InterlockedOr8)
-
-static char INLINE uv__atomic_exchange_set(char volatile* target) {
-  return _InterlockedOr8(target, 1);
-}
-
-#else /* GCC */
-
-/* Mingw-32 version, hopefully this works for 64-bit gcc as well. */
-static inline char uv__atomic_exchange_set(char volatile* target) {
-  const char one = 1;
-  char old_value;
-  __asm__ __volatile__ ("lock xchgb %0, %1\n\t"
-                        : "=r"(old_value), "=m"(*target)
-                        : "0"(one), "m"(*target)
-                        : "memory");
-  return old_value;
-}
-
-#endif
-
-#endif /* UV_WIN_ATOMICOPS_INL_H_ */
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/core.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/core.cpp
deleted file mode 100644
index 1e162dd..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/core.cpp
+++ /dev/null
@@ -1,654 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include <assert.h>
-#include <errno.h>
-#include <limits.h>
-#include <stdio.h>
-#include <stdlib.h>
-#include <string.h>
-#if defined(_MSC_VER) || defined(__MINGW64_VERSION_MAJOR)
-#include <crtdbg.h>
-#endif
-
-#include "uv.h"
-#include "internal.h"
-#include "queue.h"
-#include "handle-inl.h"
-#include "heap-inl.h"
-#include "req-inl.h"
-
-/* uv_once initialization guards */
-static uv_once_t uv_init_guard_ = UV_ONCE_INIT;
-
-
-#if defined(_DEBUG) && (defined(_MSC_VER) || defined(__MINGW64_VERSION_MAJOR))
-/* Our crt debug report handler allows us to temporarily disable asserts
- * just for the current thread.
- */
-
-UV_THREAD_LOCAL int uv__crt_assert_enabled = TRUE;
-
-static int uv__crt_dbg_report_handler(int report_type, char *message, int *ret_val) {
-  if (uv__crt_assert_enabled || report_type != _CRT_ASSERT)
-    return FALSE;
-
-  if (ret_val) {
-    /* Set ret_val to 0 to continue with normal execution.
-     * Set ret_val to 1 to trigger a breakpoint.
-    */
-
-    if(IsDebuggerPresent())
-      *ret_val = 1;
-    else
-      *ret_val = 0;
-  }
-
-  /* Don't call _CrtDbgReport. */
-  return TRUE;
-}
-#else
-UV_THREAD_LOCAL int uv__crt_assert_enabled = FALSE;
-#endif
-
-
-#if !defined(__MINGW32__) || __MSVCRT_VERSION__ >= 0x800
-static void uv__crt_invalid_parameter_handler(const wchar_t* expression,
-    const wchar_t* function, const wchar_t * file, unsigned int line,
-    uintptr_t reserved) {
-  /* No-op. */
-}
-#endif
-
-static uv_loop_t** uv__loops;
-static int uv__loops_size;
-static int uv__loops_capacity;
-#define UV__LOOPS_CHUNK_SIZE 8
-static uv_mutex_t uv__loops_lock;
-
-static void uv__loops_init(void) {
-  uv_mutex_init(&uv__loops_lock);
-}
-
-static int uv__loops_add(uv_loop_t* loop) {
-  uv_loop_t** new_loops;
-  int new_capacity, i;
-
-  uv_mutex_lock(&uv__loops_lock);
-
-  if (uv__loops_size == uv__loops_capacity) {
-    new_capacity = uv__loops_capacity + UV__LOOPS_CHUNK_SIZE;
-    new_loops = (uv_loop_t**)
-        uv__realloc(uv__loops, sizeof(uv_loop_t*) * new_capacity);
-    if (!new_loops)
-      goto failed_loops_realloc;
-    uv__loops = new_loops;
-    for (i = uv__loops_capacity; i < new_capacity; ++i)
-      uv__loops[i] = NULL;
-    uv__loops_capacity = new_capacity;
-  }
-  uv__loops[uv__loops_size] = loop;
-  ++uv__loops_size;
-
-  uv_mutex_unlock(&uv__loops_lock);
-  return 0;
-
-failed_loops_realloc:
-  uv_mutex_unlock(&uv__loops_lock);
-  return ERROR_OUTOFMEMORY;
-}
-
-static void uv__loops_remove(uv_loop_t* loop) {
-  int loop_index;
-  int smaller_capacity;
-  uv_loop_t** new_loops;
-
-  uv_mutex_lock(&uv__loops_lock);
-
-  for (loop_index = 0; loop_index < uv__loops_size; ++loop_index) {
-    if (uv__loops[loop_index] == loop)
-      break;
-  }
-  /* If loop was not found, ignore */
-  if (loop_index == uv__loops_size)
-    goto loop_removed;
-
-  uv__loops[loop_index] = uv__loops[uv__loops_size - 1];
-  uv__loops[uv__loops_size - 1] = NULL;
-  --uv__loops_size;
-
-  if (uv__loops_size == 0) {
-    uv__loops_capacity = 0;
-    uv__free(uv__loops);
-    uv__loops = NULL;
-    goto loop_removed;
-  }
-
-  /* If we didn't grow to big skip downsizing */
-  if (uv__loops_capacity < 4 * UV__LOOPS_CHUNK_SIZE)
-    goto loop_removed;
-
-  /* Downsize only if more than half of buffer is free */
-  smaller_capacity = uv__loops_capacity / 2;
-  if (uv__loops_size >= smaller_capacity)
-    goto loop_removed;
-  new_loops = (uv_loop_t**)
-      uv__realloc(uv__loops, sizeof(uv_loop_t*) * smaller_capacity);
-  if (!new_loops)
-    goto loop_removed;
-  uv__loops = new_loops;
-  uv__loops_capacity = smaller_capacity;
-
-loop_removed:
-  uv_mutex_unlock(&uv__loops_lock);
-}
-
-void uv__wake_all_loops(void) {
-  int i;
-  uv_loop_t* loop;
-
-  uv_mutex_lock(&uv__loops_lock);
-  for (i = 0; i < uv__loops_size; ++i) {
-    loop = uv__loops[i];
-    assert(loop);
-    if (loop->iocp != INVALID_HANDLE_VALUE)
-      PostQueuedCompletionStatus(loop->iocp, 0, 0, NULL);
-  }
-  uv_mutex_unlock(&uv__loops_lock);
-}
-
-static void uv_init(void) {
-  /* Tell Windows that we will handle critical errors. */
-  SetErrorMode(SEM_FAILCRITICALERRORS | SEM_NOGPFAULTERRORBOX |
-               SEM_NOOPENFILEERRORBOX);
-
-  /* Tell the CRT to not exit the application when an invalid parameter is
-   * passed. The main issue is that invalid FDs will trigger this behavior.
-   */
-#if !defined(__MINGW32__) || __MSVCRT_VERSION__ >= 0x800
-  _set_invalid_parameter_handler(uv__crt_invalid_parameter_handler);
-#endif
-
-  /* We also need to setup our debug report handler because some CRT
-   * functions (eg _get_osfhandle) raise an assert when called with invalid
-   * FDs even though they return the proper error code in the release build.
-   */
-#if defined(_DEBUG) && (defined(_MSC_VER) || defined(__MINGW64_VERSION_MAJOR))
-  _CrtSetReportHook(uv__crt_dbg_report_handler);
-#endif
-
-  /* Initialize tracking of all uv loops */
-  uv__loops_init();
-
-  /* Fetch winapi function pointers. This must be done first because other
-   * initialization code might need these function pointers to be loaded.
-   */
-  uv_winapi_init();
-
-  /* Initialize winsock */
-  uv_winsock_init();
-
-  /* Initialize FS */
-  uv_fs_init();
-
-  /* Initialize signal stuff */
-  uv_signals_init();
-
-  /* Initialize console */
-  uv_console_init();
-
-  /* Initialize utilities */
-  uv__util_init();
-
-  /* Initialize system wakeup detection */
-  uv__init_detect_system_wakeup();
-}
-
-
-int uv_loop_init(uv_loop_t* loop) {
-  struct heap* timer_heap;
-  int err;
-
-  /* Initialize libuv itself first */
-  uv__once_init();
-
-  /* Create an I/O completion port */
-  loop->iocp = CreateIoCompletionPort(INVALID_HANDLE_VALUE, NULL, 0, 1);
-  if (loop->iocp == NULL)
-    return uv_translate_sys_error(GetLastError());
-
-  /* To prevent uninitialized memory access, loop->time must be initialized
-   * to zero before calling uv_update_time for the first time.
-   */
-  loop->time = 0;
-  uv_update_time(loop);
-
-  QUEUE_INIT(&loop->wq);
-  QUEUE_INIT(&loop->handle_queue);
-  loop->active_reqs.count = 0;
-  loop->active_handles = 0;
-
-  loop->pending_reqs_tail = NULL;
-
-  loop->endgame_handles = NULL;
-
-  loop->timer_heap = timer_heap = (heap*)uv__malloc(sizeof(*timer_heap));
-  if (timer_heap == NULL) {
-    err = UV_ENOMEM;
-    goto fail_timers_alloc;
-  }
-
-  heap_init(timer_heap);
-
-  loop->check_handles = NULL;
-  loop->prepare_handles = NULL;
-  loop->idle_handles = NULL;
-
-  loop->next_prepare_handle = NULL;
-  loop->next_check_handle = NULL;
-  loop->next_idle_handle = NULL;
-
-  memset(&loop->poll_peer_sockets, 0, sizeof loop->poll_peer_sockets);
-
-  loop->active_tcp_streams = 0;
-  loop->active_udp_streams = 0;
-
-  loop->timer_counter = 0;
-  loop->stop_flag = 0;
-
-  err = uv_mutex_init(&loop->wq_mutex);
-  if (err)
-    goto fail_mutex_init;
-
-  err = uv_async_init(loop, &loop->wq_async, uv__work_done);
-  if (err)
-    goto fail_async_init;
-
-  uv__handle_unref(&loop->wq_async);
-  loop->wq_async.flags |= UV_HANDLE_INTERNAL;
-
-  err = uv__loops_add(loop);
-  if (err)
-    goto fail_async_init;
-
-  return 0;
-
-fail_async_init:
-  uv_mutex_destroy(&loop->wq_mutex);
-
-fail_mutex_init:
-  uv__free(timer_heap);
-  loop->timer_heap = NULL;
-
-fail_timers_alloc:
-  CloseHandle(loop->iocp);
-  loop->iocp = INVALID_HANDLE_VALUE;
-
-  return err;
-}
-
-
-void uv_update_time(uv_loop_t* loop) {
-  uint64_t new_time = uv__hrtime(1000);
-  assert(new_time >= loop->time);
-  loop->time = new_time;
-}
-
-
-void uv__once_init(void) {
-  uv_once(&uv_init_guard_, uv_init);
-}
-
-
-void uv__loop_close(uv_loop_t* loop) {
-  size_t i;
-
-  uv__loops_remove(loop);
-
-  /* close the async handle without needing an extra loop iteration */
-  assert(!loop->wq_async.async_sent);
-  loop->wq_async.close_cb = NULL;
-  uv__handle_closing(&loop->wq_async);
-  uv__handle_close(&loop->wq_async);
-
-  for (i = 0; i < ARRAY_SIZE(loop->poll_peer_sockets); i++) {
-    SOCKET sock = loop->poll_peer_sockets[i];
-    if (sock != 0 && sock != INVALID_SOCKET)
-      closesocket(sock);
-  }
-
-  uv_mutex_lock(&loop->wq_mutex);
-  assert(QUEUE_EMPTY(&loop->wq) && "thread pool work queue not empty!");
-  assert(!uv__has_active_reqs(loop));
-  uv_mutex_unlock(&loop->wq_mutex);
-  uv_mutex_destroy(&loop->wq_mutex);
-
-  uv__free(loop->timer_heap);
-  loop->timer_heap = NULL;
-
-  CloseHandle(loop->iocp);
-}
-
-
-int uv__loop_configure(uv_loop_t* loop, uv_loop_option option, va_list ap) {
-  return UV_ENOSYS;
-}
-
-
-int uv_backend_fd(const uv_loop_t* loop) {
-  return -1;
-}
-
-
-int uv_loop_fork(uv_loop_t* loop) {
-  return UV_ENOSYS;
-}
-
-
-int uv_backend_timeout(const uv_loop_t* loop) {
-  if (loop->stop_flag != 0)
-    return 0;
-
-  if (!uv__has_active_handles(loop) && !uv__has_active_reqs(loop))
-    return 0;
-
-  if (loop->pending_reqs_tail)
-    return 0;
-
-  if (loop->endgame_handles)
-    return 0;
-
-  if (loop->idle_handles)
-    return 0;
-
-  return uv__next_timeout(loop);
-}
-
-
-static void uv__poll_wine(uv_loop_t* loop, DWORD timeout) {
-  DWORD bytes;
-  ULONG_PTR key;
-  OVERLAPPED* overlapped;
-  uv_req_t* req;
-  int repeat;
-  uint64_t timeout_time;
-
-  timeout_time = loop->time + timeout;
-
-  for (repeat = 0; ; repeat++) {
-    GetQueuedCompletionStatus(loop->iocp,
-                              &bytes,
-                              &key,
-                              &overlapped,
-                              timeout);
-
-    if (overlapped) {
-      /* Package was dequeued */
-      req = uv_overlapped_to_req(overlapped);
-      uv_insert_pending_req(loop, req);
-
-      /* Some time might have passed waiting for I/O,
-       * so update the loop time here.
-       */
-      uv_update_time(loop);
-    } else if (GetLastError() != WAIT_TIMEOUT) {
-      /* Serious error */
-      uv_fatal_error(GetLastError(), "GetQueuedCompletionStatus");
-    } else if (timeout > 0) {
-      /* GetQueuedCompletionStatus can occasionally return a little early.
-       * Make sure that the desired timeout target time is reached.
-       */
-      uv_update_time(loop);
-      if (timeout_time > loop->time) {
-        timeout = (DWORD)(timeout_time - loop->time);
-        /* The first call to GetQueuedCompletionStatus should return very
-         * close to the target time and the second should reach it, but
-         * this is not stated in the documentation. To make sure a busy
-         * loop cannot happen, the timeout is increased exponentially
-         * starting on the third round.
-         */
-        timeout += repeat ? (1 << (repeat - 1)) : 0;
-        continue;
-      }
-    }
-    break;
-  }
-}
-
-
-static void uv__poll(uv_loop_t* loop, DWORD timeout) {
-  BOOL success;
-  uv_req_t* req;
-  OVERLAPPED_ENTRY overlappeds[128];
-  ULONG count;
-  ULONG i;
-  int repeat;
-  uint64_t timeout_time;
-
-  timeout_time = loop->time + timeout;
-
-  for (repeat = 0; ; repeat++) {
-    success = GetQueuedCompletionStatusEx(loop->iocp,
-                                          overlappeds,
-                                          ARRAY_SIZE(overlappeds),
-                                          &count,
-                                          timeout,
-                                          FALSE);
-
-    if (success) {
-      for (i = 0; i < count; i++) {
-        /* Package was dequeued, but see if it is not a empty package
-         * meant only to wake us up.
-         */
-        if (overlappeds[i].lpOverlapped) {
-          req = uv_overlapped_to_req(overlappeds[i].lpOverlapped);
-          uv_insert_pending_req(loop, req);
-        }
-      }
-
-      /* Some time might have passed waiting for I/O,
-       * so update the loop time here.
-       */
-      uv_update_time(loop);
-    } else if (GetLastError() != WAIT_TIMEOUT) {
-      /* Serious error */
-      uv_fatal_error(GetLastError(), "GetQueuedCompletionStatusEx");
-    } else if (timeout > 0) {
-      /* GetQueuedCompletionStatus can occasionally return a little early.
-       * Make sure that the desired timeout target time is reached.
-       */
-      uv_update_time(loop);
-      if (timeout_time > loop->time) {
-        timeout = (DWORD)(timeout_time - loop->time);
-        /* The first call to GetQueuedCompletionStatus should return very
-         * close to the target time and the second should reach it, but
-         * this is not stated in the documentation. To make sure a busy
-         * loop cannot happen, the timeout is increased exponentially
-         * starting on the third round.
-         */
-        timeout += repeat ? (1 << (repeat - 1)) : 0;
-        continue;
-      }
-    }
-    break;
-  }
-}
-
-
-static int uv__loop_alive(const uv_loop_t* loop) {
-  return uv__has_active_handles(loop) ||
-         uv__has_active_reqs(loop) ||
-         loop->endgame_handles != NULL;
-}
-
-
-int uv_loop_alive(const uv_loop_t* loop) {
-    return uv__loop_alive(loop);
-}
-
-
-int uv_run(uv_loop_t *loop, uv_run_mode mode) {
-  DWORD timeout;
-  int r;
-  int ran_pending;
-
-  r = uv__loop_alive(loop);
-  if (!r)
-    uv_update_time(loop);
-
-  while (r != 0 && loop->stop_flag == 0) {
-    uv_update_time(loop);
-    uv__run_timers(loop);
-
-    ran_pending = uv_process_reqs(loop);
-    uv_idle_invoke(loop);
-    uv_prepare_invoke(loop);
-
-    timeout = 0;
-    if ((mode == UV_RUN_ONCE && !ran_pending) || mode == UV_RUN_DEFAULT)
-      timeout = uv_backend_timeout(loop);
-
-    if (pGetQueuedCompletionStatusEx)
-      uv__poll(loop, timeout);
-    else
-      uv__poll_wine(loop, timeout);
-
-
-    uv_check_invoke(loop);
-    uv_process_endgames(loop);
-
-    if (mode == UV_RUN_ONCE) {
-      /* UV_RUN_ONCE implies forward progress: at least one callback must have
-       * been invoked when it returns. uv__io_poll() can return without doing
-       * I/O (meaning: no callbacks) when its timeout expires - which means we
-       * have pending timers that satisfy the forward progress constraint.
-       *
-       * UV_RUN_NOWAIT makes no guarantees about progress so it's omitted from
-       * the check.
-       */
-      uv__run_timers(loop);
-    }
-
-    r = uv__loop_alive(loop);
-    if (mode == UV_RUN_ONCE || mode == UV_RUN_NOWAIT)
-      break;
-  }
-
-  /* The if statement lets the compiler compile it to a conditional store.
-   * Avoids dirtying a cache line.
-   */
-  if (loop->stop_flag != 0)
-    loop->stop_flag = 0;
-
-  return r;
-}
-
-
-int uv_fileno(const uv_handle_t* handle, uv_os_fd_t* fd) {
-  uv_os_fd_t fd_out;
-
-  switch (handle->type) {
-  case UV_TCP:
-    fd_out = (uv_os_fd_t)((uv_tcp_t*) handle)->socket;
-    break;
-
-  case UV_NAMED_PIPE:
-    fd_out = ((uv_pipe_t*) handle)->handle;
-    break;
-
-  case UV_TTY:
-    fd_out = ((uv_tty_t*) handle)->handle;
-    break;
-
-  case UV_UDP:
-    fd_out = (uv_os_fd_t)((uv_udp_t*) handle)->socket;
-    break;
-
-  case UV_POLL:
-    fd_out = (uv_os_fd_t)((uv_poll_t*) handle)->socket;
-    break;
-
-  default:
-    return UV_EINVAL;
-  }
-
-  if (uv_is_closing(handle) || fd_out == INVALID_HANDLE_VALUE)
-    return UV_EBADF;
-
-  *fd = fd_out;
-  return 0;
-}
-
-
-int uv__socket_sockopt(uv_handle_t* handle, int optname, int* value) {
-  int r;
-  int len;
-  SOCKET socket;
-
-  if (handle == NULL || value == NULL)
-    return UV_EINVAL;
-
-  if (handle->type == UV_TCP)
-    socket = ((uv_tcp_t*) handle)->socket;
-  else if (handle->type == UV_UDP)
-    socket = ((uv_udp_t*) handle)->socket;
-  else
-    return UV_ENOTSUP;
-
-  len = sizeof(*value);
-
-  if (*value == 0)
-    r = getsockopt(socket, SOL_SOCKET, optname, (char*) value, &len);
-  else
-    r = setsockopt(socket, SOL_SOCKET, optname, (const char*) value, len);
-
-  if (r == SOCKET_ERROR)
-    return uv_translate_sys_error(WSAGetLastError());
-
-  return 0;
-}
-
-int uv_cpumask_size(void) {
-  return (int)(sizeof(DWORD_PTR) * 8);
-}
-
-int uv__getsockpeername(const uv_handle_t* handle,
-                        uv__peersockfunc func,
-                        struct sockaddr* name,
-                        int* namelen,
-                        int delayed_error) {
-
-  int result;
-  uv_os_fd_t fd;
-
-  result = uv_fileno(handle, &fd);
-  if (result != 0)
-    return result;
-
-  if (delayed_error)
-    return uv_translate_sys_error(delayed_error);
-
-  result = func((SOCKET) fd, name, namelen);
-  if (result != 0)
-    return uv_translate_sys_error(WSAGetLastError());
-
-  return 0;
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/detect-wakeup.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/detect-wakeup.cpp
deleted file mode 100644
index 72dfb7a..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/detect-wakeup.cpp
+++ /dev/null
@@ -1,35 +0,0 @@
-#include "uv.h"
-#include "internal.h"
-#include "winapi.h"
-
-static void uv__register_system_resume_callback(void);
-
-void uv__init_detect_system_wakeup(void) {
-  /* Try registering system power event callback. This is the cleanest
-   * method, but it will only work on Win8 and above.
-   */
-  uv__register_system_resume_callback();
-}
-
-static ULONG CALLBACK uv__system_resume_callback(PVOID Context,
-                                                 ULONG Type,
-                                                 PVOID Setting) {
-  if (Type == PBT_APMRESUMESUSPEND || Type == PBT_APMRESUMEAUTOMATIC)
-    uv__wake_all_loops();
-
-  return 0;
-}
-
-static void uv__register_system_resume_callback(void) {
-  _DEVICE_NOTIFY_SUBSCRIBE_PARAMETERS recipient;
-  _HPOWERNOTIFY registration_handle;
-
-  if (pPowerRegisterSuspendResumeNotification == NULL)
-    return;
-
-  recipient.Callback = uv__system_resume_callback;
-  recipient.Context = NULL;
-  (*pPowerRegisterSuspendResumeNotification)(DEVICE_NOTIFY_CALLBACK,
-                                             &recipient,
-                                             &registration_handle);
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/error.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/error.cpp
deleted file mode 100644
index 24924ba..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/error.cpp
+++ /dev/null
@@ -1,171 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include <assert.h>
-#include <errno.h>
-#include <stdio.h>
-#include <string.h>
-#include <stdlib.h>
-
-#include "uv.h"
-#include "internal.h"
-
-
-/*
- * Display an error message and abort the event loop.
- */
-void uv_fatal_error(const int errorno, const char* syscall) {
-  char* buf = NULL;
-  const char* errmsg;
-
-  FormatMessageA(FORMAT_MESSAGE_ALLOCATE_BUFFER | FORMAT_MESSAGE_FROM_SYSTEM |
-      FORMAT_MESSAGE_IGNORE_INSERTS, NULL, errorno,
-      MAKELANGID(LANG_NEUTRAL, SUBLANG_DEFAULT), (LPSTR)&buf, 0, NULL);
-
-  if (buf) {
-    errmsg = buf;
-  } else {
-    errmsg = "Unknown error";
-  }
-
-  /* FormatMessage messages include a newline character already, so don't add
-   * another. */
-  if (syscall) {
-    fprintf(stderr, "%s: (%d) %s", syscall, errorno, errmsg);
-  } else {
-    fprintf(stderr, "(%d) %s", errorno, errmsg);
-  }
-
-  if (buf) {
-    LocalFree(buf);
-  }
-
-  DebugBreak();
-  abort();
-}
-
-
-int uv_translate_sys_error(int sys_errno) {
-  if (sys_errno <= 0) {
-    return sys_errno;  /* If < 0 then it's already a libuv error. */
-  }
-
-  switch (sys_errno) {
-    case ERROR_NOACCESS:                    return UV_EACCES;
-    case WSAEACCES:                         return UV_EACCES;
-    case ERROR_ELEVATION_REQUIRED:          return UV_EACCES;
-    case ERROR_ADDRESS_ALREADY_ASSOCIATED:  return UV_EADDRINUSE;
-    case WSAEADDRINUSE:                     return UV_EADDRINUSE;
-    case WSAEADDRNOTAVAIL:                  return UV_EADDRNOTAVAIL;
-    case WSAEAFNOSUPPORT:                   return UV_EAFNOSUPPORT;
-    case WSAEWOULDBLOCK:                    return UV_EAGAIN;
-    case WSAEALREADY:                       return UV_EALREADY;
-    case ERROR_INVALID_FLAGS:               return UV_EBADF;
-    case ERROR_INVALID_HANDLE:              return UV_EBADF;
-    case ERROR_LOCK_VIOLATION:              return UV_EBUSY;
-    case ERROR_PIPE_BUSY:                   return UV_EBUSY;
-    case ERROR_SHARING_VIOLATION:           return UV_EBUSY;
-    case ERROR_OPERATION_ABORTED:           return UV_ECANCELED;
-    case WSAEINTR:                          return UV_ECANCELED;
-    case ERROR_NO_UNICODE_TRANSLATION:      return UV_ECHARSET;
-    case ERROR_CONNECTION_ABORTED:          return UV_ECONNABORTED;
-    case WSAECONNABORTED:                   return UV_ECONNABORTED;
-    case ERROR_CONNECTION_REFUSED:          return UV_ECONNREFUSED;
-    case WSAECONNREFUSED:                   return UV_ECONNREFUSED;
-    case ERROR_NETNAME_DELETED:             return UV_ECONNRESET;
-    case WSAECONNRESET:                     return UV_ECONNRESET;
-    case ERROR_ALREADY_EXISTS:              return UV_EEXIST;
-    case ERROR_FILE_EXISTS:                 return UV_EEXIST;
-    case ERROR_BUFFER_OVERFLOW:             return UV_EFAULT;
-    case WSAEFAULT:                         return UV_EFAULT;
-    case ERROR_HOST_UNREACHABLE:            return UV_EHOSTUNREACH;
-    case WSAEHOSTUNREACH:                   return UV_EHOSTUNREACH;
-    case ERROR_INSUFFICIENT_BUFFER:         return UV_EINVAL;
-    case ERROR_INVALID_DATA:                return UV_EINVAL;
-    case ERROR_INVALID_PARAMETER:           return UV_EINVAL;
-    case ERROR_SYMLINK_NOT_SUPPORTED:       return UV_EINVAL;
-    case WSAEINVAL:                         return UV_EINVAL;
-    case WSAEPFNOSUPPORT:                   return UV_EINVAL;
-    case WSAESOCKTNOSUPPORT:                return UV_EINVAL;
-    case ERROR_BEGINNING_OF_MEDIA:          return UV_EIO;
-    case ERROR_BUS_RESET:                   return UV_EIO;
-    case ERROR_CRC:                         return UV_EIO;
-    case ERROR_DEVICE_DOOR_OPEN:            return UV_EIO;
-    case ERROR_DEVICE_REQUIRES_CLEANING:    return UV_EIO;
-    case ERROR_DISK_CORRUPT:                return UV_EIO;
-    case ERROR_EOM_OVERFLOW:                return UV_EIO;
-    case ERROR_FILEMARK_DETECTED:           return UV_EIO;
-    case ERROR_GEN_FAILURE:                 return UV_EIO;
-    case ERROR_INVALID_BLOCK_LENGTH:        return UV_EIO;
-    case ERROR_IO_DEVICE:                   return UV_EIO;
-    case ERROR_NO_DATA_DETECTED:            return UV_EIO;
-    case ERROR_NO_SIGNAL_SENT:              return UV_EIO;
-    case ERROR_OPEN_FAILED:                 return UV_EIO;
-    case ERROR_SETMARK_DETECTED:            return UV_EIO;
-    case ERROR_SIGNAL_REFUSED:              return UV_EIO;
-    case WSAEISCONN:                        return UV_EISCONN;
-    case ERROR_CANT_RESOLVE_FILENAME:       return UV_ELOOP;
-    case ERROR_TOO_MANY_OPEN_FILES:         return UV_EMFILE;
-    case WSAEMFILE:                         return UV_EMFILE;
-    case WSAEMSGSIZE:                       return UV_EMSGSIZE;
-    case ERROR_FILENAME_EXCED_RANGE:        return UV_ENAMETOOLONG;
-    case ERROR_NETWORK_UNREACHABLE:         return UV_ENETUNREACH;
-    case WSAENETUNREACH:                    return UV_ENETUNREACH;
-    case WSAENOBUFS:                        return UV_ENOBUFS;
-    case ERROR_BAD_PATHNAME:                return UV_ENOENT;
-    case ERROR_DIRECTORY:                   return UV_ENOENT;
-    case ERROR_FILE_NOT_FOUND:              return UV_ENOENT;
-    case ERROR_INVALID_NAME:                return UV_ENOENT;
-    case ERROR_INVALID_DRIVE:               return UV_ENOENT;
-    case ERROR_INVALID_REPARSE_DATA:        return UV_ENOENT;
-    case ERROR_MOD_NOT_FOUND:               return UV_ENOENT;
-    case ERROR_PATH_NOT_FOUND:              return UV_ENOENT;
-    case WSAHOST_NOT_FOUND:                 return UV_ENOENT;
-    case WSANO_DATA:                        return UV_ENOENT;
-    case ERROR_NOT_ENOUGH_MEMORY:           return UV_ENOMEM;
-    case ERROR_OUTOFMEMORY:                 return UV_ENOMEM;
-    case ERROR_CANNOT_MAKE:                 return UV_ENOSPC;
-    case ERROR_DISK_FULL:                   return UV_ENOSPC;
-    case ERROR_EA_TABLE_FULL:               return UV_ENOSPC;
-    case ERROR_END_OF_MEDIA:                return UV_ENOSPC;
-    case ERROR_HANDLE_DISK_FULL:            return UV_ENOSPC;
-    case ERROR_NOT_CONNECTED:               return UV_ENOTCONN;
-    case WSAENOTCONN:                       return UV_ENOTCONN;
-    case ERROR_DIR_NOT_EMPTY:               return UV_ENOTEMPTY;
-    case WSAENOTSOCK:                       return UV_ENOTSOCK;
-    case ERROR_NOT_SUPPORTED:               return UV_ENOTSUP;
-    case ERROR_BROKEN_PIPE:                 return UV_EOF;
-    case ERROR_ACCESS_DENIED:               return UV_EPERM;
-    case ERROR_PRIVILEGE_NOT_HELD:          return UV_EPERM;
-    case ERROR_BAD_PIPE:                    return UV_EPIPE;
-    case ERROR_NO_DATA:                     return UV_EPIPE;
-    case ERROR_PIPE_NOT_CONNECTED:          return UV_EPIPE;
-    case WSAESHUTDOWN:                      return UV_EPIPE;
-    case WSAEPROTONOSUPPORT:                return UV_EPROTONOSUPPORT;
-    case ERROR_WRITE_PROTECT:               return UV_EROFS;
-    case ERROR_SEM_TIMEOUT:                 return UV_ETIMEDOUT;
-    case WSAETIMEDOUT:                      return UV_ETIMEDOUT;
-    case ERROR_NOT_SAME_DEVICE:             return UV_EXDEV;
-    case ERROR_INVALID_FUNCTION:            return UV_EISDIR;
-    case ERROR_META_EXPANSION_TOO_LONG:     return UV_E2BIG;
-    default:                                return UV_UNKNOWN;
-  }
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/fs-event.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/fs-event.cpp
deleted file mode 100644
index b9ec025..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/fs-event.cpp
+++ /dev/null
@@ -1,591 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#define _CRT_NONSTDC_NO_WARNINGS
-
-#include <assert.h>
-#include <errno.h>
-#include <stdio.h>
-#include <string.h>
-
-#include "uv.h"
-#include "internal.h"
-#include "handle-inl.h"
-#include "req-inl.h"
-
-
-const unsigned int uv_directory_watcher_buffer_size = 4096;
-
-
-static void uv_fs_event_queue_readdirchanges(uv_loop_t* loop,
-    uv_fs_event_t* handle) {
-  assert(handle->dir_handle != INVALID_HANDLE_VALUE);
-  assert(!handle->req_pending);
-
-  memset(&(handle->req.u.io.overlapped), 0,
-         sizeof(handle->req.u.io.overlapped));
-  if (!ReadDirectoryChangesW(handle->dir_handle,
-                             handle->buffer,
-                             uv_directory_watcher_buffer_size,
-                             (handle->flags & UV_FS_EVENT_RECURSIVE) ? TRUE : FALSE,
-                             FILE_NOTIFY_CHANGE_FILE_NAME      |
-                               FILE_NOTIFY_CHANGE_DIR_NAME     |
-                               FILE_NOTIFY_CHANGE_ATTRIBUTES   |
-                               FILE_NOTIFY_CHANGE_SIZE         |
-                               FILE_NOTIFY_CHANGE_LAST_WRITE   |
-                               FILE_NOTIFY_CHANGE_LAST_ACCESS  |
-                               FILE_NOTIFY_CHANGE_CREATION     |
-                               FILE_NOTIFY_CHANGE_SECURITY,
-                             NULL,
-                             &handle->req.u.io.overlapped,
-                             NULL)) {
-    /* Make this req pending reporting an error. */
-    SET_REQ_ERROR(&handle->req, GetLastError());
-    uv_insert_pending_req(loop, (uv_req_t*)&handle->req);
-  }
-
-  handle->req_pending = 1;
-}
-
-static void uv_relative_path(const WCHAR* filename,
-                             const WCHAR* dir,
-                             WCHAR** relpath) {
-  size_t relpathlen;
-  size_t filenamelen = wcslen(filename);
-  size_t dirlen = wcslen(dir);
-  assert(!_wcsnicmp(filename, dir, dirlen));
-  if (dirlen > 0 && dir[dirlen - 1] == '\\')
-    dirlen--;
-  relpathlen = filenamelen - dirlen - 1;
-  *relpath = (WCHAR*)uv__malloc((relpathlen + 1) * sizeof(WCHAR));
-  if (!*relpath)
-    uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
-  wcsncpy(*relpath, filename + dirlen + 1, relpathlen);
-  (*relpath)[relpathlen] = L'\0';
-}
-
-static int uv_split_path(const WCHAR* filename, WCHAR** dir,
-    WCHAR** file) {
-  size_t len, i;
-
-  if (filename == NULL) {
-    if (dir != NULL)
-      *dir = NULL;
-    *file = NULL;
-    return 0;
-  }
-
-  len = wcslen(filename);
-  i = len;
-  while (i > 0 && filename[--i] != '\\' && filename[i] != '/');
-
-  if (i == 0) {
-    if (dir) {
-      *dir = (WCHAR*)uv__malloc((MAX_PATH + 1) * sizeof(WCHAR));
-      if (!*dir) {
-        uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
-      }
-
-      if (!GetCurrentDirectoryW(MAX_PATH, *dir)) {
-        uv__free(*dir);
-        *dir = NULL;
-        return -1;
-      }
-    }
-
-    *file = wcsdup(filename);
-  } else {
-    if (dir) {
-      *dir = (WCHAR*)uv__malloc((i + 2) * sizeof(WCHAR));
-      if (!*dir) {
-        uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
-      }
-      wcsncpy(*dir, filename, i + 1);
-      (*dir)[i + 1] = L'\0';
-    }
-
-    *file = (WCHAR*)uv__malloc((len - i) * sizeof(WCHAR));
-    if (!*file) {
-      uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
-    }
-    wcsncpy(*file, filename + i + 1, len - i - 1);
-    (*file)[len - i - 1] = L'\0';
-  }
-
-  return 0;
-}
-
-
-int uv_fs_event_init(uv_loop_t* loop, uv_fs_event_t* handle) {
-  uv__handle_init(loop, (uv_handle_t*) handle, UV_FS_EVENT);
-  handle->dir_handle = INVALID_HANDLE_VALUE;
-  handle->buffer = NULL;
-  handle->req_pending = 0;
-  handle->filew = NULL;
-  handle->short_filew = NULL;
-  handle->dirw = NULL;
-
-  UV_REQ_INIT(&handle->req, UV_FS_EVENT_REQ);
-  handle->req.data = handle;
-
-  return 0;
-}
-
-
-int uv_fs_event_start(uv_fs_event_t* handle,
-                      uv_fs_event_cb cb,
-                      const char* path,
-                      unsigned int flags) {
-  int name_size, is_path_dir, size;
-  DWORD attr, last_error;
-  WCHAR* dir = NULL, *dir_to_watch, *pathw = NULL;
-  WCHAR short_path_buffer[MAX_PATH];
-  WCHAR* short_path, *long_path;
-
-  if (uv__is_active(handle))
-    return UV_EINVAL;
-
-  handle->cb = cb;
-  handle->path = uv__strdup(path);
-  if (!handle->path) {
-    uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
-  }
-
-  uv__handle_start(handle);
-
-  /* Convert name to UTF16. */
-
-  name_size = MultiByteToWideChar(CP_UTF8, 0, path, -1, NULL, 0) *
-              sizeof(WCHAR);
-  pathw = (WCHAR*)uv__malloc(name_size);
-  if (!pathw) {
-    uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
-  }
-
-  if (!MultiByteToWideChar(CP_UTF8,
-                           0,
-                           path,
-                           -1,
-                           pathw,
-                           name_size / sizeof(WCHAR))) {
-    return uv_translate_sys_error(GetLastError());
-  }
-
-  /* Determine whether path is a file or a directory. */
-  attr = GetFileAttributesW(pathw);
-  if (attr == INVALID_FILE_ATTRIBUTES) {
-    last_error = GetLastError();
-    goto error;
-  }
-
-  is_path_dir = (attr & FILE_ATTRIBUTE_DIRECTORY) ? 1 : 0;
-
-  if (is_path_dir) {
-     /* path is a directory, so that's the directory that we will watch. */
-
-    /* Convert to long path. */
-    size = GetLongPathNameW(pathw, NULL, 0);
-
-    if (size) {
-      long_path = (WCHAR*)uv__malloc(size * sizeof(WCHAR));
-      if (!long_path) {
-        uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
-      }
-
-      size = GetLongPathNameW(pathw, long_path, size);
-      if (size) {
-        long_path[size] = '\0';
-      } else {
-        uv__free(long_path);
-        long_path = NULL;
-      }
-
-      if (long_path) {
-        uv__free(pathw);
-        pathw = long_path;
-      }
-    }
-
-    dir_to_watch = pathw;
-  } else {
-    /*
-     * path is a file.  So we split path into dir & file parts, and
-     * watch the dir directory.
-     */
-
-    /* Convert to short path. */
-    if (GetShortPathNameW(pathw,
-                          short_path_buffer,
-                          ARRAY_SIZE(short_path_buffer))) {
-      short_path = short_path_buffer;
-    } else {
-      short_path = NULL;
-    }
-
-    if (uv_split_path(pathw, &dir, &handle->filew) != 0) {
-      last_error = GetLastError();
-      goto error;
-    }
-
-    if (uv_split_path(short_path, NULL, &handle->short_filew) != 0) {
-      last_error = GetLastError();
-      goto error;
-    }
-
-    dir_to_watch = dir;
-    uv__free(pathw);
-    pathw = NULL;
-  }
-
-  handle->dir_handle = CreateFileW(dir_to_watch,
-                                   FILE_LIST_DIRECTORY,
-                                   FILE_SHARE_READ | FILE_SHARE_DELETE |
-                                     FILE_SHARE_WRITE,
-                                   NULL,
-                                   OPEN_EXISTING,
-                                   FILE_FLAG_BACKUP_SEMANTICS |
-                                     FILE_FLAG_OVERLAPPED,
-                                   NULL);
-
-  if (dir) {
-    uv__free(dir);
-    dir = NULL;
-  }
-
-  if (handle->dir_handle == INVALID_HANDLE_VALUE) {
-    last_error = GetLastError();
-    goto error;
-  }
-
-  if (CreateIoCompletionPort(handle->dir_handle,
-                             handle->loop->iocp,
-                             (ULONG_PTR)handle,
-                             0) == NULL) {
-    last_error = GetLastError();
-    goto error;
-  }
-
-  if (!handle->buffer) {
-    handle->buffer = (char*)uv__malloc(uv_directory_watcher_buffer_size);
-  }
-  if (!handle->buffer) {
-    uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
-  }
-
-  memset(&(handle->req.u.io.overlapped), 0,
-         sizeof(handle->req.u.io.overlapped));
-
-  if (!ReadDirectoryChangesW(handle->dir_handle,
-                             handle->buffer,
-                             uv_directory_watcher_buffer_size,
-                             (flags & UV_FS_EVENT_RECURSIVE) ? TRUE : FALSE,
-                             FILE_NOTIFY_CHANGE_FILE_NAME      |
-                               FILE_NOTIFY_CHANGE_DIR_NAME     |
-                               FILE_NOTIFY_CHANGE_ATTRIBUTES   |
-                               FILE_NOTIFY_CHANGE_SIZE         |
-                               FILE_NOTIFY_CHANGE_LAST_WRITE   |
-                               FILE_NOTIFY_CHANGE_LAST_ACCESS  |
-                               FILE_NOTIFY_CHANGE_CREATION     |
-                               FILE_NOTIFY_CHANGE_SECURITY,
-                             NULL,
-                             &handle->req.u.io.overlapped,
-                             NULL)) {
-    last_error = GetLastError();
-    goto error;
-  }
-
-  assert(is_path_dir ? pathw != NULL : pathw == NULL);
-  handle->dirw = pathw;
-  handle->req_pending = 1;
-  return 0;
-
-error:
-  if (handle->path) {
-    uv__free(handle->path);
-    handle->path = NULL;
-  }
-
-  if (handle->filew) {
-    uv__free(handle->filew);
-    handle->filew = NULL;
-  }
-
-  if (handle->short_filew) {
-    uv__free(handle->short_filew);
-    handle->short_filew = NULL;
-  }
-
-  uv__free(pathw);
-
-  if (handle->dir_handle != INVALID_HANDLE_VALUE) {
-    CloseHandle(handle->dir_handle);
-    handle->dir_handle = INVALID_HANDLE_VALUE;
-  }
-
-  if (handle->buffer) {
-    uv__free(handle->buffer);
-    handle->buffer = NULL;
-  }
-
-  if (uv__is_active(handle))
-    uv__handle_stop(handle);
-
-  return uv_translate_sys_error(last_error);
-}
-
-
-int uv_fs_event_stop(uv_fs_event_t* handle) {
-  if (!uv__is_active(handle))
-    return 0;
-
-  if (handle->dir_handle != INVALID_HANDLE_VALUE) {
-    CloseHandle(handle->dir_handle);
-    handle->dir_handle = INVALID_HANDLE_VALUE;
-  }
-
-  uv__handle_stop(handle);
-
-  if (handle->filew) {
-    uv__free(handle->filew);
-    handle->filew = NULL;
-  }
-
-  if (handle->short_filew) {
-    uv__free(handle->short_filew);
-    handle->short_filew = NULL;
-  }
-
-  if (handle->path) {
-    uv__free(handle->path);
-    handle->path = NULL;
-  }
-
-  if (handle->dirw) {
-    uv__free(handle->dirw);
-    handle->dirw = NULL;
-  }
-
-  return 0;
-}
-
-
-static int file_info_cmp(WCHAR* str, WCHAR* file_name, size_t file_name_len) {
-  size_t str_len;
-
-  if (str == NULL)
-    return -1;
-
-  str_len = wcslen(str);
-
-  /*
-    Since we only care about equality, return early if the strings
-    aren't the same length
-  */
-  if (str_len != (file_name_len / sizeof(WCHAR)))
-    return -1;
-
-  return _wcsnicmp(str, file_name, str_len);
-}
-
-
-void uv_process_fs_event_req(uv_loop_t* loop, uv_req_t* req,
-    uv_fs_event_t* handle) {
-  FILE_NOTIFY_INFORMATION* file_info;
-  int err, sizew, size;
-  char* filename = NULL;
-  WCHAR* filenamew = NULL;
-  WCHAR* long_filenamew = NULL;
-  DWORD offset = 0;
-
-  assert(req->type == UV_FS_EVENT_REQ);
-  assert(handle->req_pending);
-  handle->req_pending = 0;
-
-  /* Don't report any callbacks if:
-   * - We're closing, just push the handle onto the endgame queue
-   * - We are not active, just ignore the callback
-   */
-  if (!uv__is_active(handle)) {
-    if (handle->flags & UV_HANDLE_CLOSING) {
-      uv_want_endgame(loop, (uv_handle_t*) handle);
-    }
-    return;
-  }
-
-  file_info = (FILE_NOTIFY_INFORMATION*)(handle->buffer + offset);
-
-  if (REQ_SUCCESS(req)) {
-    if (req->u.io.overlapped.InternalHigh > 0) {
-      do {
-        file_info = (FILE_NOTIFY_INFORMATION*)((char*)file_info + offset);
-        assert(!filename);
-        assert(!filenamew);
-        assert(!long_filenamew);
-
-        /*
-         * Fire the event only if we were asked to watch a directory,
-         * or if the filename filter matches.
-         */
-        if (handle->dirw ||
-            file_info_cmp(handle->filew,
-                          file_info->FileName,
-                          file_info->FileNameLength) == 0 ||
-            file_info_cmp(handle->short_filew,
-                          file_info->FileName,
-                          file_info->FileNameLength) == 0) {
-
-          if (handle->dirw) {
-            /*
-             * We attempt to resolve the long form of the file name explicitly.
-             * We only do this for file names that might still exist on disk.
-             * If this fails, we use the name given by ReadDirectoryChangesW.
-             * This may be the long form or the 8.3 short name in some cases.
-             */
-            if (file_info->Action != FILE_ACTION_REMOVED &&
-              file_info->Action != FILE_ACTION_RENAMED_OLD_NAME) {
-              /* Construct a full path to the file. */
-              size = wcslen(handle->dirw) +
-                file_info->FileNameLength / sizeof(WCHAR) + 2;
-
-              filenamew = (WCHAR*)uv__malloc(size * sizeof(WCHAR));
-              if (!filenamew) {
-                uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
-              }
-
-              _snwprintf(filenamew, size, L"%s\\%.*s", handle->dirw,
-                file_info->FileNameLength / (DWORD)sizeof(WCHAR),
-                file_info->FileName);
-
-              filenamew[size - 1] = L'\0';
-
-              /* Convert to long name. */
-              size = GetLongPathNameW(filenamew, NULL, 0);
-
-              if (size) {
-                long_filenamew = (WCHAR*)uv__malloc(size * sizeof(WCHAR));
-                if (!long_filenamew) {
-                  uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
-                }
-
-                size = GetLongPathNameW(filenamew, long_filenamew, size);
-                if (size) {
-                  long_filenamew[size] = '\0';
-                } else {
-                  uv__free(long_filenamew);
-                  long_filenamew = NULL;
-                }
-              }
-
-              uv__free(filenamew);
-
-              if (long_filenamew) {
-                /* Get the file name out of the long path. */
-                uv_relative_path(long_filenamew,
-                                 handle->dirw,
-                                 &filenamew);
-                uv__free(long_filenamew);
-                long_filenamew = filenamew;
-                sizew = -1;
-              } else {
-                /* We couldn't get the long filename, use the one reported. */
-                filenamew = file_info->FileName;
-                sizew = file_info->FileNameLength / sizeof(WCHAR);
-              }
-            } else {
-              /*
-               * Removed or renamed events cannot be resolved to the long form.
-               * We therefore use the name given by ReadDirectoryChangesW.
-               * This may be the long form or the 8.3 short name in some cases.
-               */
-              filenamew = file_info->FileName;
-              sizew = file_info->FileNameLength / sizeof(WCHAR);
-            }
-          } else {
-            /* We already have the long name of the file, so just use it. */
-            filenamew = handle->filew;
-            sizew = -1;
-          }
-
-          /* Convert the filename to utf8. */
-          uv__convert_utf16_to_utf8(filenamew, sizew, &filename);
-
-          switch (file_info->Action) {
-            case FILE_ACTION_ADDED:
-            case FILE_ACTION_REMOVED:
-            case FILE_ACTION_RENAMED_OLD_NAME:
-            case FILE_ACTION_RENAMED_NEW_NAME:
-              handle->cb(handle, filename, UV_RENAME, 0);
-              break;
-
-            case FILE_ACTION_MODIFIED:
-              handle->cb(handle, filename, UV_CHANGE, 0);
-              break;
-          }
-
-          uv__free(filename);
-          filename = NULL;
-          uv__free(long_filenamew);
-          long_filenamew = NULL;
-          filenamew = NULL;
-        }
-
-        offset = file_info->NextEntryOffset;
-      } while (offset && !(handle->flags & UV_HANDLE_CLOSING));
-    } else {
-      handle->cb(handle, NULL, UV_CHANGE, 0);
-    }
-  } else {
-    err = GET_REQ_ERROR(req);
-    handle->cb(handle, NULL, 0, uv_translate_sys_error(err));
-  }
-
-  if (!(handle->flags & UV_HANDLE_CLOSING)) {
-    uv_fs_event_queue_readdirchanges(loop, handle);
-  } else {
-    uv_want_endgame(loop, (uv_handle_t*)handle);
-  }
-}
-
-
-void uv_fs_event_close(uv_loop_t* loop, uv_fs_event_t* handle) {
-  uv_fs_event_stop(handle);
-
-  uv__handle_closing(handle);
-
-  if (!handle->req_pending) {
-    uv_want_endgame(loop, (uv_handle_t*)handle);
-  }
-
-}
-
-
-void uv_fs_event_endgame(uv_loop_t* loop, uv_fs_event_t* handle) {
-  if ((handle->flags & UV_HANDLE_CLOSING) && !handle->req_pending) {
-    assert(!(handle->flags & UV_HANDLE_CLOSED));
-
-    if (handle->buffer) {
-      uv__free(handle->buffer);
-      handle->buffer = NULL;
-    }
-
-    uv__handle_close(handle);
-  }
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/fs.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/fs.cpp
deleted file mode 100644
index 6b9e37b..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/fs.cpp
+++ /dev/null
@@ -1,2721 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#define _CRT_NONSTDC_NO_WARNINGS
-
-#include <assert.h>
-#include <stdlib.h>
-#include <direct.h>
-#include <errno.h>
-#include <fcntl.h>
-#include <io.h>
-#include <limits.h>
-#include <sys/stat.h>
-#include <sys/utime.h>
-#include <stdio.h>
-
-#include "uv.h"
-#include "internal.h"
-#include "req-inl.h"
-#include "handle-inl.h"
-
-#include <wincrypt.h>
-
-#pragma comment(lib, "Advapi32.lib")
-
-#define UV_FS_FREE_PATHS         0x0002
-#define UV_FS_FREE_PTR           0x0008
-#define UV_FS_CLEANEDUP          0x0010
-
-
-#define INIT(subtype)                                                         \
-  do {                                                                        \
-    if (req == NULL)                                                          \
-      return UV_EINVAL;                                                       \
-    uv_fs_req_init(loop, req, subtype, cb);                                   \
-  }                                                                           \
-  while (0)
-
-#define POST                                                                  \
-  do {                                                                        \
-    if (cb != NULL) {                                                         \
-      uv__req_register(loop, req);                                            \
-      uv__work_submit(loop,                                                   \
-                      &req->work_req,                                         \
-                      UV__WORK_FAST_IO,                                       \
-                      uv__fs_work,                                            \
-                      uv__fs_done);                                           \
-      return 0;                                                               \
-    } else {                                                                  \
-      uv__fs_work(&req->work_req);                                            \
-      return req->result;                                                     \
-    }                                                                         \
-  }                                                                           \
-  while (0)
-
-#define SET_REQ_RESULT(req, result_value)                                   \
-  do {                                                                      \
-    req->result = (result_value);                                           \
-    if (req->result == -1) {                                                \
-      req->sys_errno_ = _doserrno;                                          \
-      req->result = uv_translate_sys_error(req->sys_errno_);                \
-    }                                                                       \
-  } while (0)
-
-#define SET_REQ_WIN32_ERROR(req, sys_errno)                                 \
-  do {                                                                      \
-    req->sys_errno_ = (sys_errno);                                          \
-    req->result = uv_translate_sys_error(req->sys_errno_);                  \
-  } while (0)
-
-#define SET_REQ_UV_ERROR(req, uv_errno, sys_errno)                          \
-  do {                                                                      \
-    req->result = (uv_errno);                                               \
-    req->sys_errno_ = (sys_errno);                                          \
-  } while (0)
-
-#define VERIFY_FD(fd, req)                                                  \
-  if (fd == -1) {                                                           \
-    req->result = UV_EBADF;                                                 \
-    req->sys_errno_ = ERROR_INVALID_HANDLE;                                 \
-    return;                                                                 \
-  }
-
-#define MILLIONu (1000U * 1000U)
-#define BILLIONu (1000U * 1000U * 1000U)
-
-#define FILETIME_TO_UINT(filetime)                                          \
-   (*((uint64_t*) &(filetime)) - (uint64_t) 116444736 * BILLIONu)
-
-#define FILETIME_TO_TIME_T(filetime)                                        \
-   (FILETIME_TO_UINT(filetime) / (10u * MILLIONu))
-
-#define FILETIME_TO_TIME_NS(filetime, secs)                                 \
-   ((FILETIME_TO_UINT(filetime) - (secs * (uint64_t) 10 * MILLIONu)) * 100U)
-
-#define FILETIME_TO_TIMESPEC(ts, filetime)                                  \
-   do {                                                                     \
-     (ts).tv_sec = (long) FILETIME_TO_TIME_T(filetime);                     \
-     (ts).tv_nsec = (long) FILETIME_TO_TIME_NS(filetime, (ts).tv_sec);      \
-   } while(0)
-
-#define TIME_T_TO_FILETIME(time, filetime_ptr)                              \
-  do {                                                                      \
-    uint64_t bigtime = ((uint64_t) ((time) * (uint64_t) 10 * MILLIONu)) +   \
-                       (uint64_t) 116444736 * BILLIONu;                     \
-    (filetime_ptr)->dwLowDateTime = bigtime & 0xFFFFFFFF;                   \
-    (filetime_ptr)->dwHighDateTime = bigtime >> 32;                         \
-  } while(0)
-
-#define IS_SLASH(c) ((c) == L'\\' || (c) == L'/')
-#define IS_LETTER(c) (((c) >= L'a' && (c) <= L'z') || \
-  ((c) >= L'A' && (c) <= L'Z'))
-
-const WCHAR JUNCTION_PREFIX[] = L"\\??\\";
-const WCHAR JUNCTION_PREFIX_LEN = 4;
-
-const WCHAR LONG_PATH_PREFIX[] = L"\\\\?\\";
-const WCHAR LONG_PATH_PREFIX_LEN = 4;
-
-const WCHAR UNC_PATH_PREFIX[] = L"\\\\?\\UNC\\";
-const WCHAR UNC_PATH_PREFIX_LEN = 8;
-
-static int uv__file_symlink_usermode_flag = SYMBOLIC_LINK_FLAG_ALLOW_UNPRIVILEGED_CREATE;
-
-void uv_fs_init(void) {
-  _fmode = _O_BINARY;
-}
-
-
-INLINE static int fs__capture_path(uv_fs_t* req, const char* path,
-    const char* new_path, const int copy_path) {
-  char* buf;
-  char* pos;
-  ssize_t buf_sz = 0, path_len = 0, pathw_len = 0, new_pathw_len = 0;
-
-  /* new_path can only be set if path is also set. */
-  assert(new_path == NULL || path != NULL);
-
-  if (path != NULL) {
-    pathw_len = MultiByteToWideChar(CP_UTF8,
-                                    0,
-                                    path,
-                                    -1,
-                                    NULL,
-                                    0);
-    if (pathw_len == 0) {
-      return GetLastError();
-    }
-
-    buf_sz += pathw_len * sizeof(WCHAR);
-  }
-
-  if (path != NULL && copy_path) {
-    path_len = 1 + strlen(path);
-    buf_sz += path_len;
-  }
-
-  if (new_path != NULL) {
-    new_pathw_len = MultiByteToWideChar(CP_UTF8,
-                                        0,
-                                        new_path,
-                                        -1,
-                                        NULL,
-                                        0);
-    if (new_pathw_len == 0) {
-      return GetLastError();
-    }
-
-    buf_sz += new_pathw_len * sizeof(WCHAR);
-  }
-
-
-  if (buf_sz == 0) {
-    req->file.pathw = NULL;
-    req->fs.info.new_pathw = NULL;
-    req->path = NULL;
-    return 0;
-  }
-
-  buf = (char*) uv__malloc(buf_sz);
-  if (buf == NULL) {
-    return ERROR_OUTOFMEMORY;
-  }
-
-  pos = buf;
-
-  if (path != NULL) {
-    DWORD r = MultiByteToWideChar(CP_UTF8,
-                                  0,
-                                  path,
-                                  -1,
-                                  (WCHAR*) pos,
-                                  pathw_len);
-    assert(r == (DWORD) pathw_len);
-    req->file.pathw = (WCHAR*) pos;
-    pos += r * sizeof(WCHAR);
-  } else {
-    req->file.pathw = NULL;
-  }
-
-  if (new_path != NULL) {
-    DWORD r = MultiByteToWideChar(CP_UTF8,
-                                  0,
-                                  new_path,
-                                  -1,
-                                  (WCHAR*) pos,
-                                  new_pathw_len);
-    assert(r == (DWORD) new_pathw_len);
-    req->fs.info.new_pathw = (WCHAR*) pos;
-    pos += r * sizeof(WCHAR);
-  } else {
-    req->fs.info.new_pathw = NULL;
-  }
-
-  req->path = path;
-  if (path != NULL && copy_path) {
-    memcpy(pos, path, path_len);
-    assert(path_len == buf_sz - (pos - buf));
-    req->path = pos;
-  }
-
-  req->flags |= UV_FS_FREE_PATHS;
-
-  return 0;
-}
-
-
-
-INLINE static void uv_fs_req_init(uv_loop_t* loop, uv_fs_t* req,
-    uv_fs_type fs_type, const uv_fs_cb cb) {
-  uv__once_init();
-  UV_REQ_INIT(req, UV_FS);
-  req->loop = loop;
-  req->flags = 0;
-  req->fs_type = fs_type;
-  req->result = 0;
-  req->ptr = NULL;
-  req->path = NULL;
-  req->cb = cb;
-  memset(&req->fs, 0, sizeof(req->fs));
-}
-
-
-static int fs__wide_to_utf8(WCHAR* w_source_ptr,
-                               DWORD w_source_len,
-                               char** target_ptr,
-                               uint64_t* target_len_ptr) {
-  int r;
-  int target_len;
-  char* target;
-  target_len = WideCharToMultiByte(CP_UTF8,
-                                   0,
-                                   w_source_ptr,
-                                   w_source_len,
-                                   NULL,
-                                   0,
-                                   NULL,
-                                   NULL);
-
-  if (target_len == 0) {
-    return -1;
-  }
-
-  if (target_len_ptr != NULL) {
-    *target_len_ptr = target_len;
-  }
-
-  if (target_ptr == NULL) {
-    return 0;
-  }
-
-  target = (char*)uv__malloc(target_len + 1);
-  if (target == NULL) {
-    SetLastError(ERROR_OUTOFMEMORY);
-    return -1;
-  }
-
-  r = WideCharToMultiByte(CP_UTF8,
-                          0,
-                          w_source_ptr,
-                          w_source_len,
-                          target,
-                          target_len,
-                          NULL,
-                          NULL);
-  assert(r == target_len);
-  target[target_len] = '\0';
-  *target_ptr = target;
-  return 0;
-}
-
-
-INLINE static int fs__readlink_handle(HANDLE handle, char** target_ptr,
-    uint64_t* target_len_ptr) {
-  char buffer[MAXIMUM_REPARSE_DATA_BUFFER_SIZE];
-  REPARSE_DATA_BUFFER* reparse_data = (REPARSE_DATA_BUFFER*) buffer;
-  WCHAR* w_target;
-  DWORD w_target_len;
-  DWORD bytes;
-
-  if (!DeviceIoControl(handle,
-                       FSCTL_GET_REPARSE_POINT,
-                       NULL,
-                       0,
-                       buffer,
-                       sizeof buffer,
-                       &bytes,
-                       NULL)) {
-    return -1;
-  }
-
-  if (reparse_data->ReparseTag == IO_REPARSE_TAG_SYMLINK) {
-    /* Real symlink */
-    w_target = reparse_data->SymbolicLinkReparseBuffer.PathBuffer +
-        (reparse_data->SymbolicLinkReparseBuffer.SubstituteNameOffset /
-        sizeof(WCHAR));
-    w_target_len =
-        reparse_data->SymbolicLinkReparseBuffer.SubstituteNameLength /
-        sizeof(WCHAR);
-
-    /* Real symlinks can contain pretty much everything, but the only thing we
-     * really care about is undoing the implicit conversion to an NT namespaced
-     * path that CreateSymbolicLink will perform on absolute paths. If the path
-     * is win32-namespaced then the user must have explicitly made it so, and
-     * we better just return the unmodified reparse data. */
-    if (w_target_len >= 4 &&
-        w_target[0] == L'\\' &&
-        w_target[1] == L'?' &&
-        w_target[2] == L'?' &&
-        w_target[3] == L'\\') {
-      /* Starts with \??\ */
-      if (w_target_len >= 6 &&
-          ((w_target[4] >= L'A' && w_target[4] <= L'Z') ||
-           (w_target[4] >= L'a' && w_target[4] <= L'z')) &&
-          w_target[5] == L':' &&
-          (w_target_len == 6 || w_target[6] == L'\\')) {
-        /* \??\<drive>:\ */
-        w_target += 4;
-        w_target_len -= 4;
-
-      } else if (w_target_len >= 8 &&
-                 (w_target[4] == L'U' || w_target[4] == L'u') &&
-                 (w_target[5] == L'N' || w_target[5] == L'n') &&
-                 (w_target[6] == L'C' || w_target[6] == L'c') &&
-                 w_target[7] == L'\\') {
-        /* \??\UNC\<server>\<share>\ - make sure the final path looks like
-         * \\<server>\<share>\ */
-        w_target += 6;
-        w_target[0] = L'\\';
-        w_target_len -= 6;
-      }
-    }
-
-  } else if (reparse_data->ReparseTag == IO_REPARSE_TAG_MOUNT_POINT) {
-    /* Junction. */
-    w_target = reparse_data->MountPointReparseBuffer.PathBuffer +
-        (reparse_data->MountPointReparseBuffer.SubstituteNameOffset /
-        sizeof(WCHAR));
-    w_target_len = reparse_data->MountPointReparseBuffer.SubstituteNameLength /
-        sizeof(WCHAR);
-
-    /* Only treat junctions that look like \??\<drive>:\ as symlink. Junctions
-     * can also be used as mount points, like \??\Volume{<guid>}, but that's
-     * confusing for programs since they wouldn't be able to actually
-     * understand such a path when returned by uv_readlink(). UNC paths are
-     * never valid for junctions so we don't care about them. */
-    if (!(w_target_len >= 6 &&
-          w_target[0] == L'\\' &&
-          w_target[1] == L'?' &&
-          w_target[2] == L'?' &&
-          w_target[3] == L'\\' &&
-          ((w_target[4] >= L'A' && w_target[4] <= L'Z') ||
-           (w_target[4] >= L'a' && w_target[4] <= L'z')) &&
-          w_target[5] == L':' &&
-          (w_target_len == 6 || w_target[6] == L'\\'))) {
-      SetLastError(ERROR_SYMLINK_NOT_SUPPORTED);
-      return -1;
-    }
-
-    /* Remove leading \??\ */
-    w_target += 4;
-    w_target_len -= 4;
-
-  } else {
-    /* Reparse tag does not indicate a symlink. */
-    SetLastError(ERROR_SYMLINK_NOT_SUPPORTED);
-    return -1;
-  }
-
-  return fs__wide_to_utf8(w_target, w_target_len, target_ptr, target_len_ptr);
-}
-
-
-void fs__open(uv_fs_t* req) {
-  DWORD access;
-  DWORD share;
-  DWORD disposition;
-  DWORD attributes = 0;
-  HANDLE file;
-  int fd, current_umask;
-  int flags = req->fs.info.file_flags;
-
-  /* Obtain the active umask. umask() never fails and returns the previous
-   * umask. */
-  current_umask = umask(0);
-  umask(current_umask);
-
-  /* convert flags and mode to CreateFile parameters */
-  switch (flags & (UV_FS_O_RDONLY | UV_FS_O_WRONLY | UV_FS_O_RDWR)) {
-  case UV_FS_O_RDONLY:
-    access = FILE_GENERIC_READ;
-    break;
-  case UV_FS_O_WRONLY:
-    access = FILE_GENERIC_WRITE;
-    break;
-  case UV_FS_O_RDWR:
-    access = FILE_GENERIC_READ | FILE_GENERIC_WRITE;
-    break;
-  default:
-    goto einval;
-  }
-
-  if (flags & UV_FS_O_APPEND) {
-    access &= ~FILE_WRITE_DATA;
-    access |= FILE_APPEND_DATA;
-  }
-
-  /*
-   * Here is where we deviate significantly from what CRT's _open()
-   * does. We indiscriminately use all the sharing modes, to match
-   * UNIX semantics. In particular, this ensures that the file can
-   * be deleted even whilst it's open, fixing issue #1449.
-   * We still support exclusive sharing mode, since it is necessary
-   * for opening raw block devices, otherwise Windows will prevent
-   * any attempt to write past the master boot record.
-   */
-  if (flags & UV_FS_O_EXLOCK) {
-    share = 0;
-  } else {
-    share = FILE_SHARE_READ | FILE_SHARE_WRITE | FILE_SHARE_DELETE;
-  }
-
-  switch (flags & (UV_FS_O_CREAT | UV_FS_O_EXCL | UV_FS_O_TRUNC)) {
-  case 0:
-  case UV_FS_O_EXCL:
-    disposition = OPEN_EXISTING;
-    break;
-  case UV_FS_O_CREAT:
-    disposition = OPEN_ALWAYS;
-    break;
-  case UV_FS_O_CREAT | UV_FS_O_EXCL:
-  case UV_FS_O_CREAT | UV_FS_O_TRUNC | UV_FS_O_EXCL:
-    disposition = CREATE_NEW;
-    break;
-  case UV_FS_O_TRUNC:
-  case UV_FS_O_TRUNC | UV_FS_O_EXCL:
-    disposition = TRUNCATE_EXISTING;
-    break;
-  case UV_FS_O_CREAT | UV_FS_O_TRUNC:
-    disposition = CREATE_ALWAYS;
-    break;
-  default:
-    goto einval;
-  }
-
-  attributes |= FILE_ATTRIBUTE_NORMAL;
-  if (flags & UV_FS_O_CREAT) {
-    if (!((req->fs.info.mode & ~current_umask) & _S_IWRITE)) {
-      attributes |= FILE_ATTRIBUTE_READONLY;
-    }
-  }
-
-  if (flags & UV_FS_O_TEMPORARY ) {
-    attributes |= FILE_FLAG_DELETE_ON_CLOSE | FILE_ATTRIBUTE_TEMPORARY;
-    access |= DELETE;
-  }
-
-  if (flags & UV_FS_O_SHORT_LIVED) {
-    attributes |= FILE_ATTRIBUTE_TEMPORARY;
-  }
-
-  switch (flags & (UV_FS_O_SEQUENTIAL | UV_FS_O_RANDOM)) {
-  case 0:
-    break;
-  case UV_FS_O_SEQUENTIAL:
-    attributes |= FILE_FLAG_SEQUENTIAL_SCAN;
-    break;
-  case UV_FS_O_RANDOM:
-    attributes |= FILE_FLAG_RANDOM_ACCESS;
-    break;
-  default:
-    goto einval;
-  }
-
-  if (flags & UV_FS_O_DIRECT) {
-    /*
-     * FILE_APPEND_DATA and FILE_FLAG_NO_BUFFERING are mutually exclusive.
-     * Windows returns 87, ERROR_INVALID_PARAMETER if these are combined.
-     *
-     * FILE_APPEND_DATA is included in FILE_GENERIC_WRITE:
-     *
-     * FILE_GENERIC_WRITE = STANDARD_RIGHTS_WRITE |
-     *                      FILE_WRITE_DATA |
-     *                      FILE_WRITE_ATTRIBUTES |
-     *                      FILE_WRITE_EA |
-     *                      FILE_APPEND_DATA |
-     *                      SYNCHRONIZE
-     *
-     * Note: Appends are also permitted by FILE_WRITE_DATA.
-     *
-     * In order for direct writes and direct appends to succeed, we therefore
-     * exclude FILE_APPEND_DATA if FILE_WRITE_DATA is specified, and otherwise
-     * fail if the user's sole permission is a direct append, since this
-     * particular combination is invalid.
-     */
-    if (access & FILE_APPEND_DATA) {
-      if (access & FILE_WRITE_DATA) {
-        access &= ~FILE_APPEND_DATA;
-      } else {
-        goto einval;
-      }
-    }
-    attributes |= FILE_FLAG_NO_BUFFERING;
-  }
-
-  switch (flags & (UV_FS_O_DSYNC | UV_FS_O_SYNC)) {
-  case 0:
-    break;
-  case UV_FS_O_DSYNC:
-  case UV_FS_O_SYNC:
-    attributes |= FILE_FLAG_WRITE_THROUGH;
-    break;
-  default:
-    goto einval;
-  }
-
-  /* Setting this flag makes it possible to open a directory. */
-  attributes |= FILE_FLAG_BACKUP_SEMANTICS;
-
-  file = CreateFileW(req->file.pathw,
-                     access,
-                     share,
-                     NULL,
-                     disposition,
-                     attributes,
-                     NULL);
-  if (file == INVALID_HANDLE_VALUE) {
-    DWORD error = GetLastError();
-    if (error == ERROR_FILE_EXISTS && (flags & UV_FS_O_CREAT) &&
-        !(flags & UV_FS_O_EXCL)) {
-      /* Special case: when ERROR_FILE_EXISTS happens and UV_FS_O_CREAT was
-       * specified, it means the path referred to a directory. */
-      SET_REQ_UV_ERROR(req, UV_EISDIR, error);
-    } else {
-      SET_REQ_WIN32_ERROR(req, GetLastError());
-    }
-    return;
-  }
-
-  fd = _open_osfhandle((intptr_t) file, flags);
-  if (fd < 0) {
-    /* The only known failure mode for _open_osfhandle() is EMFILE, in which
-     * case GetLastError() will return zero. However we'll try to handle other
-     * errors as well, should they ever occur.
-     */
-    if (errno == EMFILE)
-      SET_REQ_UV_ERROR(req, UV_EMFILE, ERROR_TOO_MANY_OPEN_FILES);
-    else if (GetLastError() != ERROR_SUCCESS)
-      SET_REQ_WIN32_ERROR(req, GetLastError());
-    else
-      SET_REQ_WIN32_ERROR(req, UV_UNKNOWN);
-    CloseHandle(file);
-    return;
-  }
-
-  SET_REQ_RESULT(req, fd);
-  return;
-
- einval:
-  SET_REQ_UV_ERROR(req, UV_EINVAL, ERROR_INVALID_PARAMETER);
-}
-
-void fs__close(uv_fs_t* req) {
-  int fd = req->file.fd;
-  int result;
-
-  VERIFY_FD(fd, req);
-
-  if (fd > 2)
-    result = _close(fd);
-  else
-    result = 0;
-
-  /* _close doesn't set _doserrno on failure, but it does always set errno
-   * to EBADF on failure.
-   */
-  if (result == -1) {
-    assert(errno == EBADF);
-    SET_REQ_UV_ERROR(req, UV_EBADF, ERROR_INVALID_HANDLE);
-  } else {
-    req->result = 0;
-  }
-}
-
-
-void fs__read(uv_fs_t* req) {
-  int fd = req->file.fd;
-  int64_t offset = req->fs.info.offset;
-  HANDLE handle;
-  OVERLAPPED overlapped, *overlapped_ptr;
-  LARGE_INTEGER offset_;
-  DWORD bytes;
-  DWORD error;
-  int result;
-  unsigned int index;
-  LARGE_INTEGER original_position;
-  LARGE_INTEGER zero_offset;
-  int restore_position;
-
-  VERIFY_FD(fd, req);
-
-  zero_offset.QuadPart = 0;
-  restore_position = 0;
-  handle = uv__get_osfhandle(fd);
-
-  if (handle == INVALID_HANDLE_VALUE) {
-    SET_REQ_WIN32_ERROR(req, ERROR_INVALID_HANDLE);
-    return;
-  }
-
-  if (offset != -1) {
-    memset(&overlapped, 0, sizeof overlapped);
-    overlapped_ptr = &overlapped;
-    if (SetFilePointerEx(handle, zero_offset, &original_position,
-                         FILE_CURRENT)) {
-      restore_position = 1;
-    }
-  } else {
-    overlapped_ptr = NULL;
-  }
-
-  index = 0;
-  bytes = 0;
-  do {
-    DWORD incremental_bytes;
-
-    if (offset != -1) {
-      offset_.QuadPart = offset + bytes;
-      overlapped.Offset = offset_.LowPart;
-      overlapped.OffsetHigh = offset_.HighPart;
-    }
-
-    result = ReadFile(handle,
-                      req->fs.info.bufs[index].base,
-                      req->fs.info.bufs[index].len,
-                      &incremental_bytes,
-                      overlapped_ptr);
-    bytes += incremental_bytes;
-    ++index;
-  } while (result && index < req->fs.info.nbufs);
-
-  if (restore_position)
-    SetFilePointerEx(handle, original_position, NULL, FILE_BEGIN);
-
-  if (result || bytes > 0) {
-    SET_REQ_RESULT(req, bytes);
-  } else {
-    error = GetLastError();
-    if (error == ERROR_HANDLE_EOF) {
-      SET_REQ_RESULT(req, bytes);
-    } else {
-      SET_REQ_WIN32_ERROR(req, error);
-    }
-  }
-}
-
-
-void fs__write(uv_fs_t* req) {
-  int fd = req->file.fd;
-  int64_t offset = req->fs.info.offset;
-  HANDLE handle;
-  OVERLAPPED overlapped, *overlapped_ptr;
-  LARGE_INTEGER offset_;
-  DWORD bytes;
-  int result;
-  unsigned int index;
-  LARGE_INTEGER original_position;
-  LARGE_INTEGER zero_offset;
-  int restore_position;
-
-  VERIFY_FD(fd, req);
-
-  zero_offset.QuadPart = 0;
-  restore_position = 0;
-  handle = uv__get_osfhandle(fd);
-  if (handle == INVALID_HANDLE_VALUE) {
-    SET_REQ_WIN32_ERROR(req, ERROR_INVALID_HANDLE);
-    return;
-  }
-
-  if (offset != -1) {
-    memset(&overlapped, 0, sizeof overlapped);
-    overlapped_ptr = &overlapped;
-    if (SetFilePointerEx(handle, zero_offset, &original_position,
-                         FILE_CURRENT)) {
-      restore_position = 1;
-    }
-  } else {
-    overlapped_ptr = NULL;
-  }
-
-  index = 0;
-  bytes = 0;
-  do {
-    DWORD incremental_bytes;
-
-    if (offset != -1) {
-      offset_.QuadPart = offset + bytes;
-      overlapped.Offset = offset_.LowPart;
-      overlapped.OffsetHigh = offset_.HighPart;
-    }
-
-    result = WriteFile(handle,
-                       req->fs.info.bufs[index].base,
-                       req->fs.info.bufs[index].len,
-                       &incremental_bytes,
-                       overlapped_ptr);
-    bytes += incremental_bytes;
-    ++index;
-  } while (result && index < req->fs.info.nbufs);
-
-  if (restore_position)
-    SetFilePointerEx(handle, original_position, NULL, FILE_BEGIN);
-
-  if (result || bytes > 0) {
-    SET_REQ_RESULT(req, bytes);
-  } else {
-    SET_REQ_WIN32_ERROR(req, GetLastError());
-  }
-}
-
-
-void fs__rmdir(uv_fs_t* req) {
-  int result = _wrmdir(req->file.pathw);
-  SET_REQ_RESULT(req, result);
-}
-
-
-void fs__unlink(uv_fs_t* req) {
-  const WCHAR* pathw = req->file.pathw;
-  HANDLE handle;
-  BY_HANDLE_FILE_INFORMATION info;
-  FILE_DISPOSITION_INFORMATION disposition;
-  IO_STATUS_BLOCK iosb;
-  NTSTATUS status;
-
-  handle = CreateFileW(pathw,
-                       FILE_READ_ATTRIBUTES | FILE_WRITE_ATTRIBUTES | DELETE,
-                       FILE_SHARE_READ | FILE_SHARE_WRITE | FILE_SHARE_DELETE,
-                       NULL,
-                       OPEN_EXISTING,
-                       FILE_FLAG_OPEN_REPARSE_POINT | FILE_FLAG_BACKUP_SEMANTICS,
-                       NULL);
-
-  if (handle == INVALID_HANDLE_VALUE) {
-    SET_REQ_WIN32_ERROR(req, GetLastError());
-    return;
-  }
-
-  if (!GetFileInformationByHandle(handle, &info)) {
-    SET_REQ_WIN32_ERROR(req, GetLastError());
-    CloseHandle(handle);
-    return;
-  }
-
-  if (info.dwFileAttributes & FILE_ATTRIBUTE_DIRECTORY) {
-    /* Do not allow deletion of directories, unless it is a symlink. When the
-     * path refers to a non-symlink directory, report EPERM as mandated by
-     * POSIX.1. */
-
-    /* Check if it is a reparse point. If it's not, it's a normal directory. */
-    if (!(info.dwFileAttributes & FILE_ATTRIBUTE_REPARSE_POINT)) {
-      SET_REQ_WIN32_ERROR(req, ERROR_ACCESS_DENIED);
-      CloseHandle(handle);
-      return;
-    }
-
-    /* Read the reparse point and check if it is a valid symlink. If not, don't
-     * unlink. */
-    if (fs__readlink_handle(handle, NULL, NULL) < 0) {
-      DWORD error = GetLastError();
-      if (error == ERROR_SYMLINK_NOT_SUPPORTED)
-        error = ERROR_ACCESS_DENIED;
-      SET_REQ_WIN32_ERROR(req, error);
-      CloseHandle(handle);
-      return;
-    }
-  }
-
-  if (info.dwFileAttributes & FILE_ATTRIBUTE_READONLY) {
-    /* Remove read-only attribute */
-    FILE_BASIC_INFORMATION basic = { 0 };
-
-    basic.FileAttributes = (info.dwFileAttributes & ~FILE_ATTRIBUTE_READONLY) |
-                           FILE_ATTRIBUTE_ARCHIVE;
-
-    status = pNtSetInformationFile(handle,
-                                   &iosb,
-                                   &basic,
-                                   sizeof basic,
-                                   FileBasicInformation);
-    if (!NT_SUCCESS(status)) {
-      SET_REQ_WIN32_ERROR(req, pRtlNtStatusToDosError(status));
-      CloseHandle(handle);
-      return;
-    }
-  }
-
-  /* Try to set the delete flag. */
-  disposition.DeleteFile = TRUE;
-  status = pNtSetInformationFile(handle,
-                                 &iosb,
-                                 &disposition,
-                                 sizeof disposition,
-                                 FileDispositionInformation);
-  if (NT_SUCCESS(status)) {
-    SET_REQ_SUCCESS(req);
-  } else {
-    SET_REQ_WIN32_ERROR(req, pRtlNtStatusToDosError(status));
-  }
-
-  CloseHandle(handle);
-}
-
-
-void fs__mkdir(uv_fs_t* req) {
-  /* TODO: use req->mode. */
-  int result = _wmkdir(req->file.pathw);
-  SET_REQ_RESULT(req, result);
-}
-
-
-/* OpenBSD original: lib/libc/stdio/mktemp.c */
-void fs__mkdtemp(uv_fs_t* req) {
-  static const WCHAR *tempchars =
-    L"abcdefghijklmnopqrstuvwxyzABCDEFGHIJKLMNOPQRSTUVWXYZ0123456789";
-  static const size_t num_chars = 62;
-  static const size_t num_x = 6;
-  WCHAR *cp, *ep;
-  unsigned int tries, i;
-  size_t len;
-  HCRYPTPROV h_crypt_prov;
-  uint64_t v;
-  BOOL released;
-
-  len = wcslen(req->file.pathw);
-  ep = req->file.pathw + len;
-  if (len < num_x || wcsncmp(ep - num_x, L"XXXXXX", num_x)) {
-    SET_REQ_UV_ERROR(req, UV_EINVAL, ERROR_INVALID_PARAMETER);
-    return;
-  }
-
-  if (!CryptAcquireContext(&h_crypt_prov, NULL, NULL, PROV_RSA_FULL,
-                           CRYPT_VERIFYCONTEXT)) {
-    SET_REQ_WIN32_ERROR(req, GetLastError());
-    return;
-  }
-
-  tries = TMP_MAX;
-  do {
-    if (!CryptGenRandom(h_crypt_prov, sizeof(v), (BYTE*) &v)) {
-      SET_REQ_WIN32_ERROR(req, GetLastError());
-      break;
-    }
-
-    cp = ep - num_x;
-    for (i = 0; i < num_x; i++) {
-      *cp++ = tempchars[v % num_chars];
-      v /= num_chars;
-    }
-
-    if (_wmkdir(req->file.pathw) == 0) {
-      len = strlen(req->path);
-      wcstombs((char*) req->path + len - num_x, ep - num_x, num_x);
-      SET_REQ_RESULT(req, 0);
-      break;
-    } else if (errno != EEXIST) {
-      SET_REQ_RESULT(req, -1);
-      break;
-    }
-  } while (--tries);
-
-  released = CryptReleaseContext(h_crypt_prov, 0);
-  assert(released);
-  if (tries == 0) {
-    SET_REQ_RESULT(req, -1);
-  }
-}
-
-
-void fs__scandir(uv_fs_t* req) {
-  static const size_t dirents_initial_size = 32;
-
-  HANDLE dir_handle = INVALID_HANDLE_VALUE;
-
-  uv__dirent_t** dirents = NULL;
-  size_t dirents_size = 0;
-  size_t dirents_used = 0;
-
-  IO_STATUS_BLOCK iosb;
-  NTSTATUS status;
-
-  /* Buffer to hold directory entries returned by NtQueryDirectoryFile.
-   * It's important that this buffer can hold at least one entry, regardless
-   * of the length of the file names present in the enumerated directory.
-   * A file name is at most 256 WCHARs long.
-   * According to MSDN, the buffer must be aligned at an 8-byte boundary.
-   */
-#if _MSC_VER
-  __declspec(align(8)) char buffer[8192];
-#else
-  __attribute__ ((aligned (8))) char buffer[8192];
-#endif
-
-  STATIC_ASSERT(sizeof buffer >=
-                sizeof(FILE_DIRECTORY_INFORMATION) + 256 * sizeof(WCHAR));
-
-  /* Open the directory. */
-  dir_handle =
-      CreateFileW(req->file.pathw,
-                  FILE_LIST_DIRECTORY | SYNCHRONIZE,
-                  FILE_SHARE_READ | FILE_SHARE_WRITE | FILE_SHARE_DELETE,
-                  NULL,
-                  OPEN_EXISTING,
-                  FILE_FLAG_BACKUP_SEMANTICS,
-                  NULL);
-  if (dir_handle == INVALID_HANDLE_VALUE)
-    goto win32_error;
-
-  /* Read the first chunk. */
-  status = pNtQueryDirectoryFile(dir_handle,
-                                 NULL,
-                                 NULL,
-                                 NULL,
-                                 &iosb,
-                                 &buffer,
-                                 sizeof buffer,
-                                 FileDirectoryInformation,
-                                 FALSE,
-                                 NULL,
-                                 TRUE);
-
-  /* If the handle is not a directory, we'll get STATUS_INVALID_PARAMETER.
-   * This should be reported back as UV_ENOTDIR.
-   */
-  if (status == STATUS_INVALID_PARAMETER)
-    goto not_a_directory_error;
-
-  while (NT_SUCCESS(status)) {
-    char* position = buffer;
-    size_t next_entry_offset = 0;
-
-    do {
-      FILE_DIRECTORY_INFORMATION* info;
-      uv__dirent_t* dirent;
-
-      size_t wchar_len;
-      size_t utf8_len;
-
-      /* Obtain a pointer to the current directory entry. */
-      position += next_entry_offset;
-      info = (FILE_DIRECTORY_INFORMATION*) position;
-
-      /* Fetch the offset to the next directory entry. */
-      next_entry_offset = info->NextEntryOffset;
-
-      /* Compute the length of the filename in WCHARs. */
-      wchar_len = info->FileNameLength / sizeof info->FileName[0];
-
-      /* Skip over '.' and '..' entries.  It has been reported that
-       * the SharePoint driver includes the terminating zero byte in
-       * the filename length.  Strip those first.
-       */
-      while (wchar_len > 0 && info->FileName[wchar_len - 1] == L'\0')
-        wchar_len -= 1;
-
-      if (wchar_len == 0)
-        continue;
-      if (wchar_len == 1 && info->FileName[0] == L'.')
-        continue;
-      if (wchar_len == 2 && info->FileName[0] == L'.' &&
-          info->FileName[1] == L'.')
-        continue;
-
-      /* Compute the space required to store the filename as UTF-8. */
-      utf8_len = WideCharToMultiByte(
-          CP_UTF8, 0, &info->FileName[0], wchar_len, NULL, 0, NULL, NULL);
-      if (utf8_len == 0)
-        goto win32_error;
-
-      /* Resize the dirent array if needed. */
-      if (dirents_used >= dirents_size) {
-        size_t new_dirents_size =
-            dirents_size == 0 ? dirents_initial_size : dirents_size << 1;
-        uv__dirent_t** new_dirents = (uv__dirent_t**)
-            uv__realloc(dirents, new_dirents_size * sizeof *dirents);
-
-        if (new_dirents == NULL)
-          goto out_of_memory_error;
-
-        dirents_size = new_dirents_size;
-        dirents = new_dirents;
-      }
-
-      /* Allocate space for the uv dirent structure. The dirent structure
-       * includes room for the first character of the filename, but `utf8_len`
-       * doesn't count the NULL terminator at this point.
-       */
-      dirent = (uv__dirent_t*)uv__malloc(sizeof *dirent + utf8_len);
-      if (dirent == NULL)
-        goto out_of_memory_error;
-
-      dirents[dirents_used++] = dirent;
-
-      /* Convert file name to UTF-8. */
-      if (WideCharToMultiByte(CP_UTF8,
-                              0,
-                              &info->FileName[0],
-                              wchar_len,
-                              &dirent->d_name[0],
-                              utf8_len,
-                              NULL,
-                              NULL) == 0)
-        goto win32_error;
-
-      /* Add a null terminator to the filename. */
-      dirent->d_name[utf8_len] = '\0';
-
-      /* Fill out the type field. */
-      if (info->FileAttributes & FILE_ATTRIBUTE_DEVICE)
-        dirent->d_type = UV__DT_CHAR;
-      else if (info->FileAttributes & FILE_ATTRIBUTE_REPARSE_POINT)
-        dirent->d_type = UV__DT_LINK;
-      else if (info->FileAttributes & FILE_ATTRIBUTE_DIRECTORY)
-        dirent->d_type = UV__DT_DIR;
-      else
-        dirent->d_type = UV__DT_FILE;
-    } while (next_entry_offset != 0);
-
-    /* Read the next chunk. */
-    status = pNtQueryDirectoryFile(dir_handle,
-                                   NULL,
-                                   NULL,
-                                   NULL,
-                                   &iosb,
-                                   &buffer,
-                                   sizeof buffer,
-                                   FileDirectoryInformation,
-                                   FALSE,
-                                   NULL,
-                                   FALSE);
-
-    /* After the first pNtQueryDirectoryFile call, the function may return
-     * STATUS_SUCCESS even if the buffer was too small to hold at least one
-     * directory entry.
-     */
-    if (status == STATUS_SUCCESS && iosb.Information == 0)
-      status = STATUS_BUFFER_OVERFLOW;
-  }
-
-  if (status != STATUS_NO_MORE_FILES)
-    goto nt_error;
-
-  CloseHandle(dir_handle);
-
-  /* Store the result in the request object. */
-  req->ptr = dirents;
-  if (dirents != NULL)
-    req->flags |= UV_FS_FREE_PTR;
-
-  SET_REQ_RESULT(req, dirents_used);
-
-  /* `nbufs` will be used as index by uv_fs_scandir_next. */
-  req->fs.info.nbufs = 0;
-
-  return;
-
-nt_error:
-  SET_REQ_WIN32_ERROR(req, pRtlNtStatusToDosError(status));
-  goto cleanup;
-
-win32_error:
-  SET_REQ_WIN32_ERROR(req, GetLastError());
-  goto cleanup;
-
-not_a_directory_error:
-  SET_REQ_UV_ERROR(req, UV_ENOTDIR, ERROR_DIRECTORY);
-  goto cleanup;
-
-out_of_memory_error:
-  SET_REQ_UV_ERROR(req, UV_ENOMEM, ERROR_OUTOFMEMORY);
-  goto cleanup;
-
-cleanup:
-  if (dir_handle != INVALID_HANDLE_VALUE)
-    CloseHandle(dir_handle);
-  while (dirents_used > 0)
-    uv__free(dirents[--dirents_used]);
-  if (dirents != NULL)
-    uv__free(dirents);
-}
-
-void fs__opendir(uv_fs_t* req) {
-  WCHAR* pathw;
-  size_t len;
-  const WCHAR* fmt;
-  WCHAR* find_path;
-  uv_dir_t* dir;
-
-  pathw = req->file.pathw;
-  dir = NULL;
-  find_path = NULL;
-
-  /* Figure out whether path is a file or a directory. */
-  if (!(GetFileAttributesW(pathw) & FILE_ATTRIBUTE_DIRECTORY)) {
-    SET_REQ_UV_ERROR(req, UV_ENOTDIR, ERROR_DIRECTORY);
-    goto error;
-  }
-
-  dir = (uv_dir_t*)uv__malloc(sizeof(*dir));
-  if (dir == NULL) {
-    SET_REQ_UV_ERROR(req, UV_ENOMEM, ERROR_OUTOFMEMORY);
-    goto error;
-  }
-
-  len = wcslen(pathw);
-
-  if (len == 0)
-    fmt = L"./*";
-  else if (IS_SLASH(pathw[len - 1]))
-    fmt = L"%s*";
-  else
-    fmt = L"%s\\*";
-
-  find_path = (WCHAR*)uv__malloc(sizeof(WCHAR) * (len + 4));
-  if (find_path == NULL) {
-    SET_REQ_UV_ERROR(req, UV_ENOMEM, ERROR_OUTOFMEMORY);
-    goto error;
-  }
-
-  _snwprintf(find_path, len + 3, fmt, pathw);
-  dir->dir_handle = FindFirstFileW(find_path, &dir->find_data);
-  uv__free(find_path);
-  find_path = NULL;
-  if (dir->dir_handle == INVALID_HANDLE_VALUE &&
-      GetLastError() != ERROR_FILE_NOT_FOUND) {
-    SET_REQ_WIN32_ERROR(req, GetLastError());
-    goto error;
-  }
-
-  dir->need_find_call = FALSE;
-  req->ptr = dir;
-  SET_REQ_RESULT(req, 0);
-  return;
-
-error:
-  uv__free(dir);
-  uv__free(find_path);
-  req->ptr = NULL;
-}
-
-void fs__readdir(uv_fs_t* req) {
-  uv_dir_t* dir;
-  uv_dirent_t* dirents;
-  uv__dirent_t dent;
-  unsigned int dirent_idx;
-  PWIN32_FIND_DATAW find_data;
-  unsigned int i;
-  int r;
-
-  req->flags |= UV_FS_FREE_PTR;
-  dir = (uv_dir_t*)req->ptr;
-  dirents = dir->dirents;
-  memset(dirents, 0, dir->nentries * sizeof(*dir->dirents));
-  find_data = &dir->find_data;
-  dirent_idx = 0;
-
-  while (dirent_idx < dir->nentries) {
-    if (dir->need_find_call && FindNextFileW(dir->dir_handle, find_data) == 0) {
-      if (GetLastError() == ERROR_NO_MORE_FILES)
-        break;
-      goto error;
-    }
-
-    /* Skip "." and ".." entries. */
-    if (find_data->cFileName[0] == L'.' &&
-        (find_data->cFileName[1] == L'\0' ||
-        (find_data->cFileName[1] == L'.' &&
-        find_data->cFileName[2] == L'\0'))) {
-      dir->need_find_call = TRUE;
-      continue;
-    }
-
-    r = uv__convert_utf16_to_utf8((const WCHAR*) &find_data->cFileName,
-                                  -1,
-                                  (char**) &dirents[dirent_idx].name);
-    if (r != 0)
-      goto error;
-
-    /* Copy file type. */
-    if ((find_data->dwFileAttributes & FILE_ATTRIBUTE_DIRECTORY) != 0)
-      dent.d_type = UV__DT_DIR;
-    else if ((find_data->dwFileAttributes & FILE_ATTRIBUTE_REPARSE_POINT) != 0)
-      dent.d_type = UV__DT_LINK;
-    else if ((find_data->dwFileAttributes & FILE_ATTRIBUTE_DEVICE) != 0)
-      dent.d_type = UV__DT_CHAR;
-    else
-      dent.d_type = UV__DT_FILE;
-
-    dirents[dirent_idx].type = uv__fs_get_dirent_type(&dent);
-    dir->need_find_call = TRUE;
-    ++dirent_idx;
-  }
-
-  SET_REQ_RESULT(req, dirent_idx);
-  return;
-
-error:
-  SET_REQ_WIN32_ERROR(req, GetLastError());
-  for (i = 0; i < dirent_idx; ++i) {
-    uv__free((char*) dirents[i].name);
-    dirents[i].name = NULL;
-  }
-}
-
-void fs__closedir(uv_fs_t* req) {
-  uv_dir_t* dir;
-
-  dir = (uv_dir_t*)req->ptr;
-  FindClose(dir->dir_handle);
-  uv__free(req->ptr);
-  SET_REQ_RESULT(req, 0);
-}
-
-INLINE static int fs__stat_handle(HANDLE handle, uv_stat_t* statbuf,
-    int do_lstat) {
-  FILE_ALL_INFORMATION file_info;
-  FILE_FS_VOLUME_INFORMATION volume_info;
-  NTSTATUS nt_status;
-  IO_STATUS_BLOCK io_status;
-
-  nt_status = pNtQueryInformationFile(handle,
-                                      &io_status,
-                                      &file_info,
-                                      sizeof file_info,
-                                      FileAllInformation);
-
-  /* Buffer overflow (a warning status code) is expected here. */
-  if (NT_ERROR(nt_status)) {
-    SetLastError(pRtlNtStatusToDosError(nt_status));
-    return -1;
-  }
-
-  nt_status = pNtQueryVolumeInformationFile(handle,
-                                            &io_status,
-                                            &volume_info,
-                                            sizeof volume_info,
-                                            FileFsVolumeInformation);
-
-  /* Buffer overflow (a warning status code) is expected here. */
-  if (io_status.Status == STATUS_NOT_IMPLEMENTED) {
-    statbuf->st_dev = 0;
-  } else if (NT_ERROR(nt_status)) {
-    SetLastError(pRtlNtStatusToDosError(nt_status));
-    return -1;
-  } else {
-    statbuf->st_dev = volume_info.VolumeSerialNumber;
-  }
-
-  /* Todo: st_mode should probably always be 0666 for everyone. We might also
-   * want to report 0777 if the file is a .exe or a directory.
-   *
-   * Currently it's based on whether the 'readonly' attribute is set, which
-   * makes little sense because the semantics are so different: the 'read-only'
-   * flag is just a way for a user to protect against accidental deletion, and
-   * serves no security purpose. Windows uses ACLs for that.
-   *
-   * Also people now use uv_fs_chmod() to take away the writable bit for good
-   * reasons. Windows however just makes the file read-only, which makes it
-   * impossible to delete the file afterwards, since read-only files can't be
-   * deleted.
-   *
-   * IOW it's all just a clusterfuck and we should think of something that
-   * makes slightly more sense.
-   *
-   * And uv_fs_chmod should probably just fail on windows or be a total no-op.
-   * There's nothing sensible it can do anyway.
-   */
-  statbuf->st_mode = 0;
-
-  /*
-  * On Windows, FILE_ATTRIBUTE_REPARSE_POINT is a general purpose mechanism
-  * by which filesystem drivers can intercept and alter file system requests.
-  *
-  * The only reparse points we care about are symlinks and mount points, both
-  * of which are treated as POSIX symlinks. Further, we only care when
-  * invoked via lstat, which seeks information about the link instead of its
-  * target. Otherwise, reparse points must be treated as regular files.
-  */
-  if (do_lstat &&
-      (file_info.BasicInformation.FileAttributes & FILE_ATTRIBUTE_REPARSE_POINT)) {
-    /*
-     * If reading the link fails, the reparse point is not a symlink and needs
-     * to be treated as a regular file. The higher level lstat function will
-     * detect this failure and retry without do_lstat if appropriate.
-     */
-    if (fs__readlink_handle(handle, NULL, &statbuf->st_size) != 0)
-      return -1;
-    statbuf->st_mode |= S_IFLNK;
-  }
-
-  if (statbuf->st_mode == 0) {
-    if (file_info.BasicInformation.FileAttributes & FILE_ATTRIBUTE_DIRECTORY) {
-      statbuf->st_mode |= _S_IFDIR;
-      statbuf->st_size = 0;
-    } else {
-      statbuf->st_mode |= _S_IFREG;
-      statbuf->st_size = file_info.StandardInformation.EndOfFile.QuadPart;
-    }
-  }
-
-  if (file_info.BasicInformation.FileAttributes & FILE_ATTRIBUTE_READONLY)
-    statbuf->st_mode |= _S_IREAD | (_S_IREAD >> 3) | (_S_IREAD >> 6);
-  else
-    statbuf->st_mode |= (_S_IREAD | _S_IWRITE) | ((_S_IREAD | _S_IWRITE) >> 3) |
-                        ((_S_IREAD | _S_IWRITE) >> 6);
-
-  FILETIME_TO_TIMESPEC(statbuf->st_atim, file_info.BasicInformation.LastAccessTime);
-  FILETIME_TO_TIMESPEC(statbuf->st_ctim, file_info.BasicInformation.ChangeTime);
-  FILETIME_TO_TIMESPEC(statbuf->st_mtim, file_info.BasicInformation.LastWriteTime);
-  FILETIME_TO_TIMESPEC(statbuf->st_birthtim, file_info.BasicInformation.CreationTime);
-
-  statbuf->st_ino = file_info.InternalInformation.IndexNumber.QuadPart;
-
-  /* st_blocks contains the on-disk allocation size in 512-byte units. */
-  statbuf->st_blocks =
-      (uint64_t) file_info.StandardInformation.AllocationSize.QuadPart >> 9;
-
-  statbuf->st_nlink = file_info.StandardInformation.NumberOfLinks;
-
-  /* The st_blksize is supposed to be the 'optimal' number of bytes for reading
-   * and writing to the disk. That is, for any definition of 'optimal' - it's
-   * supposed to at least avoid read-update-write behavior when writing to the
-   * disk.
-   *
-   * However nobody knows this and even fewer people actually use this value,
-   * and in order to fill it out we'd have to make another syscall to query the
-   * volume for FILE_FS_SECTOR_SIZE_INFORMATION.
-   *
-   * Therefore we'll just report a sensible value that's quite commonly okay
-   * on modern hardware.
-   *
-   * 4096 is the minimum required to be compatible with newer Advanced Format
-   * drives (which have 4096 bytes per physical sector), and to be backwards
-   * compatible with older drives (which have 512 bytes per physical sector).
-   */
-  statbuf->st_blksize = 4096;
-
-  /* Todo: set st_flags to something meaningful. Also provide a wrapper for
-   * chattr(2).
-   */
-  statbuf->st_flags = 0;
-
-  /* Windows has nothing sensible to say about these values, so they'll just
-   * remain empty.
-   */
-  statbuf->st_gid = 0;
-  statbuf->st_uid = 0;
-  statbuf->st_rdev = 0;
-  statbuf->st_gen = 0;
-
-  return 0;
-}
-
-
-INLINE static void fs__stat_prepare_path(WCHAR* pathw) {
-  size_t len = wcslen(pathw);
-
-  /* TODO: ignore namespaced paths. */
-  if (len > 1 && pathw[len - 2] != L':' &&
-      (pathw[len - 1] == L'\\' || pathw[len - 1] == L'/')) {
-    pathw[len - 1] = '\0';
-  }
-}
-
-
-INLINE static DWORD fs__stat_impl_from_path(WCHAR* path,
-                                            int do_lstat,
-                                            uv_stat_t* statbuf) {
-  HANDLE handle;
-  DWORD flags;
-  DWORD ret;
-
-  flags = FILE_FLAG_BACKUP_SEMANTICS;
-  if (do_lstat)
-    flags |= FILE_FLAG_OPEN_REPARSE_POINT;
-
-  handle = CreateFileW(path,
-                       FILE_READ_ATTRIBUTES,
-                       FILE_SHARE_READ | FILE_SHARE_WRITE | FILE_SHARE_DELETE,
-                       NULL,
-                       OPEN_EXISTING,
-                       flags,
-                       NULL);
-
-  if (handle == INVALID_HANDLE_VALUE)
-    ret = GetLastError();
-  else if (fs__stat_handle(handle, statbuf, do_lstat) != 0)
-    ret = GetLastError();
-  else
-    ret = 0;
-
-  CloseHandle(handle);
-  return ret;
-}
-
-
-INLINE static void fs__stat_impl(uv_fs_t* req, int do_lstat) {
-  DWORD error;
-
-  error = fs__stat_impl_from_path(req->file.pathw, do_lstat, &req->statbuf);
-  if (error != 0) {
-    if (do_lstat &&
-        (error == ERROR_SYMLINK_NOT_SUPPORTED ||
-         error == ERROR_NOT_A_REPARSE_POINT)) {
-      /* We opened a reparse point but it was not a symlink. Try again. */
-      fs__stat_impl(req, 0);
-    } else {
-      /* Stat failed. */
-      SET_REQ_WIN32_ERROR(req, error);
-    }
-
-    return;
-  }
-
-  req->ptr = &req->statbuf;
-  req->result = 0;
-}
-
-
-static void fs__stat(uv_fs_t* req) {
-  fs__stat_prepare_path(req->file.pathw);
-  fs__stat_impl(req, 0);
-}
-
-
-static void fs__lstat(uv_fs_t* req) {
-  fs__stat_prepare_path(req->file.pathw);
-  fs__stat_impl(req, 1);
-}
-
-
-static void fs__fstat(uv_fs_t* req) {
-  int fd = req->file.fd;
-  HANDLE handle;
-
-  VERIFY_FD(fd, req);
-
-  handle = uv__get_osfhandle(fd);
-
-  if (handle == INVALID_HANDLE_VALUE) {
-    SET_REQ_WIN32_ERROR(req, ERROR_INVALID_HANDLE);
-    return;
-  }
-
-  if (fs__stat_handle(handle, &req->statbuf, 0) != 0) {
-    SET_REQ_WIN32_ERROR(req, GetLastError());
-    return;
-  }
-
-  req->ptr = &req->statbuf;
-  req->result = 0;
-}
-
-
-static void fs__rename(uv_fs_t* req) {
-  if (!MoveFileExW(req->file.pathw, req->fs.info.new_pathw, MOVEFILE_REPLACE_EXISTING)) {
-    SET_REQ_WIN32_ERROR(req, GetLastError());
-    return;
-  }
-
-  SET_REQ_RESULT(req, 0);
-}
-
-
-INLINE static void fs__sync_impl(uv_fs_t* req) {
-  int fd = req->file.fd;
-  int result;
-
-  VERIFY_FD(fd, req);
-
-  result = FlushFileBuffers(uv__get_osfhandle(fd)) ? 0 : -1;
-  if (result == -1) {
-    SET_REQ_WIN32_ERROR(req, GetLastError());
-  } else {
-    SET_REQ_RESULT(req, result);
-  }
-}
-
-
-static void fs__fsync(uv_fs_t* req) {
-  fs__sync_impl(req);
-}
-
-
-static void fs__fdatasync(uv_fs_t* req) {
-  fs__sync_impl(req);
-}
-
-
-static void fs__ftruncate(uv_fs_t* req) {
-  int fd = req->file.fd;
-  HANDLE handle;
-  NTSTATUS status;
-  IO_STATUS_BLOCK io_status;
-  FILE_END_OF_FILE_INFORMATION eof_info;
-
-  VERIFY_FD(fd, req);
-
-  handle = uv__get_osfhandle(fd);
-
-  eof_info.EndOfFile.QuadPart = req->fs.info.offset;
-
-  status = pNtSetInformationFile(handle,
-                                 &io_status,
-                                 &eof_info,
-                                 sizeof eof_info,
-                                 FileEndOfFileInformation);
-
-  if (NT_SUCCESS(status)) {
-    SET_REQ_RESULT(req, 0);
-  } else {
-    SET_REQ_WIN32_ERROR(req, pRtlNtStatusToDosError(status));
-  }
-}
-
-
-static void fs__copyfile(uv_fs_t* req) {
-  int flags;
-  int overwrite;
-  uv_stat_t statbuf;
-  uv_stat_t new_statbuf;
-
-  flags = req->fs.info.file_flags;
-
-  if (flags & UV_FS_COPYFILE_FICLONE_FORCE) {
-    SET_REQ_UV_ERROR(req, UV_ENOSYS, ERROR_NOT_SUPPORTED);
-    return;
-  }
-
-  overwrite = flags & UV_FS_COPYFILE_EXCL;
-
-  if (CopyFileW(req->file.pathw, req->fs.info.new_pathw, overwrite) != 0) {
-    SET_REQ_RESULT(req, 0);
-    return;
-  }
-
-  SET_REQ_WIN32_ERROR(req, GetLastError());
-  if (req->result != UV_EBUSY)
-    return;
-
-  /* if error UV_EBUSY check if src and dst file are the same */
-  if (fs__stat_impl_from_path(req->file.pathw, 0, &statbuf) != 0 ||
-      fs__stat_impl_from_path(req->fs.info.new_pathw, 0, &new_statbuf) != 0) {
-    return;
-  }
-
-  if (statbuf.st_dev == new_statbuf.st_dev &&
-      statbuf.st_ino == new_statbuf.st_ino) {
-    SET_REQ_RESULT(req, 0);
-  }
-}
-
-
-static void fs__sendfile(uv_fs_t* req) {
-  int fd_in = req->file.fd, fd_out = req->fs.info.fd_out;
-  size_t length = req->fs.info.bufsml[0].len;
-  int64_t offset = req->fs.info.offset;
-  const size_t max_buf_size = 65536;
-  size_t buf_size = length < max_buf_size ? length : max_buf_size;
-  int n, result = 0;
-  int64_t result_offset = 0;
-  char* buf = (char*) uv__malloc(buf_size);
-  if (!buf) {
-    uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
-  }
-
-  if (offset != -1) {
-    result_offset = _lseeki64(fd_in, offset, SEEK_SET);
-  }
-
-  if (result_offset == -1) {
-    result = -1;
-  } else {
-    while (length > 0) {
-      n = _read(fd_in, buf, length < buf_size ? length : buf_size);
-      if (n == 0) {
-        break;
-      } else if (n == -1) {
-        result = -1;
-        break;
-      }
-
-      length -= n;
-
-      n = _write(fd_out, buf, n);
-      if (n == -1) {
-        result = -1;
-        break;
-      }
-
-      result += n;
-    }
-  }
-
-  uv__free(buf);
-
-  SET_REQ_RESULT(req, result);
-}
-
-
-static void fs__access(uv_fs_t* req) {
-  DWORD attr = GetFileAttributesW(req->file.pathw);
-
-  if (attr == INVALID_FILE_ATTRIBUTES) {
-    SET_REQ_WIN32_ERROR(req, GetLastError());
-    return;
-  }
-
-  /*
-   * Access is possible if
-   * - write access wasn't requested,
-   * - or the file isn't read-only,
-   * - or it's a directory.
-   * (Directories cannot be read-only on Windows.)
-   */
-  if (!(req->fs.info.mode & W_OK) ||
-      !(attr & FILE_ATTRIBUTE_READONLY) ||
-      (attr & FILE_ATTRIBUTE_DIRECTORY)) {
-    SET_REQ_RESULT(req, 0);
-  } else {
-    SET_REQ_WIN32_ERROR(req, UV_EPERM);
-  }
-
-}
-
-
-static void fs__chmod(uv_fs_t* req) {
-  int result = _wchmod(req->file.pathw, req->fs.info.mode);
-  SET_REQ_RESULT(req, result);
-}
-
-
-static void fs__fchmod(uv_fs_t* req) {
-  int fd = req->file.fd;
-  int clear_archive_flag;
-  HANDLE handle;
-  NTSTATUS nt_status;
-  IO_STATUS_BLOCK io_status;
-  FILE_BASIC_INFORMATION file_info;
-
-  VERIFY_FD(fd, req);
-
-  handle = ReOpenFile(uv__get_osfhandle(fd), FILE_WRITE_ATTRIBUTES, 0, 0);
-  if (handle == INVALID_HANDLE_VALUE) {
-    SET_REQ_WIN32_ERROR(req, GetLastError());
-    return;
-  }
-
-  nt_status = pNtQueryInformationFile(handle,
-                                      &io_status,
-                                      &file_info,
-                                      sizeof file_info,
-                                      FileBasicInformation);
-
-  if (!NT_SUCCESS(nt_status)) {
-    SET_REQ_WIN32_ERROR(req, pRtlNtStatusToDosError(nt_status));
-    goto fchmod_cleanup;
-  }
-
-  /* Test if the Archive attribute is cleared */
-  if ((file_info.FileAttributes & FILE_ATTRIBUTE_ARCHIVE) == 0) {
-      /* Set Archive flag, otherwise setting or clearing the read-only
-         flag will not work */
-      file_info.FileAttributes |= FILE_ATTRIBUTE_ARCHIVE;
-      nt_status = pNtSetInformationFile(handle,
-                                        &io_status,
-                                        &file_info,
-                                        sizeof file_info,
-                                        FileBasicInformation);
-      if (!NT_SUCCESS(nt_status)) {
-        SET_REQ_WIN32_ERROR(req, pRtlNtStatusToDosError(nt_status));
-        goto fchmod_cleanup;
-      }
-      /* Remeber to clear the flag later on */
-      clear_archive_flag = 1;
-  } else {
-      clear_archive_flag = 0;
-  }
-
-  if (req->fs.info.mode & _S_IWRITE) {
-    file_info.FileAttributes &= ~FILE_ATTRIBUTE_READONLY;
-  } else {
-    file_info.FileAttributes |= FILE_ATTRIBUTE_READONLY;
-  }
-
-  nt_status = pNtSetInformationFile(handle,
-                                    &io_status,
-                                    &file_info,
-                                    sizeof file_info,
-                                    FileBasicInformation);
-
-  if (!NT_SUCCESS(nt_status)) {
-    SET_REQ_WIN32_ERROR(req, pRtlNtStatusToDosError(nt_status));
-    goto fchmod_cleanup;
-  }
-
-  if (clear_archive_flag) {
-      file_info.FileAttributes &= ~FILE_ATTRIBUTE_ARCHIVE;
-      if (file_info.FileAttributes == 0) {
-          file_info.FileAttributes = FILE_ATTRIBUTE_NORMAL;
-      }
-      nt_status = pNtSetInformationFile(handle,
-                                        &io_status,
-                                        &file_info,
-                                        sizeof file_info,
-                                        FileBasicInformation);
-      if (!NT_SUCCESS(nt_status)) {
-        SET_REQ_WIN32_ERROR(req, pRtlNtStatusToDosError(nt_status));
-        goto fchmod_cleanup;
-      }
-  }
-
-  SET_REQ_SUCCESS(req);
-fchmod_cleanup:
-  CloseHandle(handle);
-}
-
-
-INLINE static int fs__utime_handle(HANDLE handle, double atime, double mtime) {
-  FILETIME filetime_a, filetime_m;
-
-  TIME_T_TO_FILETIME(atime, &filetime_a);
-  TIME_T_TO_FILETIME(mtime, &filetime_m);
-
-  if (!SetFileTime(handle, NULL, &filetime_a, &filetime_m)) {
-    return -1;
-  }
-
-  return 0;
-}
-
-
-static void fs__utime(uv_fs_t* req) {
-  HANDLE handle;
-
-  handle = CreateFileW(req->file.pathw,
-                       FILE_WRITE_ATTRIBUTES,
-                       FILE_SHARE_READ | FILE_SHARE_WRITE | FILE_SHARE_DELETE,
-                       NULL,
-                       OPEN_EXISTING,
-                       FILE_FLAG_BACKUP_SEMANTICS,
-                       NULL);
-
-  if (handle == INVALID_HANDLE_VALUE) {
-    SET_REQ_WIN32_ERROR(req, GetLastError());
-    return;
-  }
-
-  if (fs__utime_handle(handle, req->fs.time.atime, req->fs.time.mtime) != 0) {
-    SET_REQ_WIN32_ERROR(req, GetLastError());
-    CloseHandle(handle);
-    return;
-  }
-
-  CloseHandle(handle);
-
-  req->result = 0;
-}
-
-
-static void fs__futime(uv_fs_t* req) {
-  int fd = req->file.fd;
-  HANDLE handle;
-  VERIFY_FD(fd, req);
-
-  handle = uv__get_osfhandle(fd);
-
-  if (handle == INVALID_HANDLE_VALUE) {
-    SET_REQ_WIN32_ERROR(req, ERROR_INVALID_HANDLE);
-    return;
-  }
-
-  if (fs__utime_handle(handle, req->fs.time.atime, req->fs.time.mtime) != 0) {
-    SET_REQ_WIN32_ERROR(req, GetLastError());
-    return;
-  }
-
-  req->result = 0;
-}
-
-
-static void fs__link(uv_fs_t* req) {
-  DWORD r = CreateHardLinkW(req->fs.info.new_pathw, req->file.pathw, NULL);
-  if (r == 0) {
-    SET_REQ_WIN32_ERROR(req, GetLastError());
-  } else {
-    req->result = 0;
-  }
-}
-
-
-static void fs__create_junction(uv_fs_t* req, const WCHAR* path,
-    const WCHAR* new_path) {
-  HANDLE handle = INVALID_HANDLE_VALUE;
-  REPARSE_DATA_BUFFER *buffer = NULL;
-  int created = 0;
-  int target_len;
-  int is_absolute, is_long_path;
-  int needed_buf_size, used_buf_size, used_data_size, path_buf_len;
-  int start, len, i;
-  int add_slash;
-  DWORD bytes;
-  WCHAR* path_buf;
-
-  target_len = wcslen(path);
-  is_long_path = wcsncmp(path, LONG_PATH_PREFIX, LONG_PATH_PREFIX_LEN) == 0;
-
-  if (is_long_path) {
-    is_absolute = 1;
-  } else {
-    is_absolute = target_len >= 3 && IS_LETTER(path[0]) &&
-      path[1] == L':' && IS_SLASH(path[2]);
-  }
-
-  if (!is_absolute) {
-    /* Not supporting relative paths */
-    SET_REQ_UV_ERROR(req, UV_EINVAL, ERROR_NOT_SUPPORTED);
-    return;
-  }
-
-  /* Do a pessimistic calculation of the required buffer size */
-  needed_buf_size =
-      FIELD_OFFSET(REPARSE_DATA_BUFFER, MountPointReparseBuffer.PathBuffer) +
-      JUNCTION_PREFIX_LEN * sizeof(WCHAR) +
-      2 * (target_len + 2) * sizeof(WCHAR);
-
-  /* Allocate the buffer */
-  buffer = (REPARSE_DATA_BUFFER*)uv__malloc(needed_buf_size);
-  if (!buffer) {
-    uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
-  }
-
-  /* Grab a pointer to the part of the buffer where filenames go */
-  path_buf = (WCHAR*)&(buffer->MountPointReparseBuffer.PathBuffer);
-  path_buf_len = 0;
-
-  /* Copy the substitute (internal) target path */
-  start = path_buf_len;
-
-  wcsncpy((WCHAR*)&path_buf[path_buf_len], JUNCTION_PREFIX,
-    JUNCTION_PREFIX_LEN);
-  path_buf_len += JUNCTION_PREFIX_LEN;
-
-  add_slash = 0;
-  for (i = is_long_path ? LONG_PATH_PREFIX_LEN : 0; path[i] != L'\0'; i++) {
-    if (IS_SLASH(path[i])) {
-      add_slash = 1;
-      continue;
-    }
-
-    if (add_slash) {
-      path_buf[path_buf_len++] = L'\\';
-      add_slash = 0;
-    }
-
-    path_buf[path_buf_len++] = path[i];
-  }
-  path_buf[path_buf_len++] = L'\\';
-  len = path_buf_len - start;
-
-  /* Set the info about the substitute name */
-  buffer->MountPointReparseBuffer.SubstituteNameOffset = start * sizeof(WCHAR);
-  buffer->MountPointReparseBuffer.SubstituteNameLength = len * sizeof(WCHAR);
-
-  /* Insert null terminator */
-  path_buf[path_buf_len++] = L'\0';
-
-  /* Copy the print name of the target path */
-  start = path_buf_len;
-  add_slash = 0;
-  for (i = is_long_path ? LONG_PATH_PREFIX_LEN : 0; path[i] != L'\0'; i++) {
-    if (IS_SLASH(path[i])) {
-      add_slash = 1;
-      continue;
-    }
-
-    if (add_slash) {
-      path_buf[path_buf_len++] = L'\\';
-      add_slash = 0;
-    }
-
-    path_buf[path_buf_len++] = path[i];
-  }
-  len = path_buf_len - start;
-  if (len == 2) {
-    path_buf[path_buf_len++] = L'\\';
-    len++;
-  }
-
-  /* Set the info about the print name */
-  buffer->MountPointReparseBuffer.PrintNameOffset = start * sizeof(WCHAR);
-  buffer->MountPointReparseBuffer.PrintNameLength = len * sizeof(WCHAR);
-
-  /* Insert another null terminator */
-  path_buf[path_buf_len++] = L'\0';
-
-  /* Calculate how much buffer space was actually used */
-  used_buf_size = FIELD_OFFSET(REPARSE_DATA_BUFFER, MountPointReparseBuffer.PathBuffer) +
-    path_buf_len * sizeof(WCHAR);
-  used_data_size = used_buf_size -
-    FIELD_OFFSET(REPARSE_DATA_BUFFER, MountPointReparseBuffer);
-
-  /* Put general info in the data buffer */
-  buffer->ReparseTag = IO_REPARSE_TAG_MOUNT_POINT;
-  buffer->ReparseDataLength = used_data_size;
-  buffer->Reserved = 0;
-
-  /* Create a new directory */
-  if (!CreateDirectoryW(new_path, NULL)) {
-    SET_REQ_WIN32_ERROR(req, GetLastError());
-    goto error;
-  }
-  created = 1;
-
-  /* Open the directory */
-  handle = CreateFileW(new_path,
-                       GENERIC_WRITE,
-                       0,
-                       NULL,
-                       OPEN_EXISTING,
-                       FILE_FLAG_BACKUP_SEMANTICS |
-                         FILE_FLAG_OPEN_REPARSE_POINT,
-                       NULL);
-  if (handle == INVALID_HANDLE_VALUE) {
-    SET_REQ_WIN32_ERROR(req, GetLastError());
-    goto error;
-  }
-
-  /* Create the actual reparse point */
-  if (!DeviceIoControl(handle,
-                       FSCTL_SET_REPARSE_POINT,
-                       buffer,
-                       used_buf_size,
-                       NULL,
-                       0,
-                       &bytes,
-                       NULL)) {
-    SET_REQ_WIN32_ERROR(req, GetLastError());
-    goto error;
-  }
-
-  /* Clean up */
-  CloseHandle(handle);
-  uv__free(buffer);
-
-  SET_REQ_RESULT(req, 0);
-  return;
-
-error:
-  uv__free(buffer);
-
-  if (handle != INVALID_HANDLE_VALUE) {
-    CloseHandle(handle);
-  }
-
-  if (created) {
-    RemoveDirectoryW(new_path);
-  }
-}
-
-
-static void fs__symlink(uv_fs_t* req) {
-  WCHAR* pathw;
-  WCHAR* new_pathw;
-  int flags;
-  int err;
-
-  pathw = req->file.pathw;
-  new_pathw = req->fs.info.new_pathw;
-
-  if (req->fs.info.file_flags & UV_FS_SYMLINK_JUNCTION) {
-    fs__create_junction(req, pathw, new_pathw);
-    return;
-  }
-
-  if (req->fs.info.file_flags & UV_FS_SYMLINK_DIR)
-    flags = SYMBOLIC_LINK_FLAG_DIRECTORY | uv__file_symlink_usermode_flag;
-  else
-    flags = uv__file_symlink_usermode_flag;
-
-  if (CreateSymbolicLinkW(new_pathw, pathw, flags)) {
-    SET_REQ_RESULT(req, 0);
-    return;
-  }
-
-  /* Something went wrong. We will test if it is because of user-mode
-   * symlinks.
-   */
-  err = GetLastError();
-  if (err == ERROR_INVALID_PARAMETER &&
-      flags & SYMBOLIC_LINK_FLAG_ALLOW_UNPRIVILEGED_CREATE) {
-    /* This system does not support user-mode symlinks. We will clear the
-     * unsupported flag and retry.
-     */
-    uv__file_symlink_usermode_flag = 0;
-    fs__symlink(req);
-  } else {
-    SET_REQ_WIN32_ERROR(req, err);
-  }
-}
-
-
-static void fs__readlink(uv_fs_t* req) {
-  HANDLE handle;
-
-  handle = CreateFileW(req->file.pathw,
-                       0,
-                       0,
-                       NULL,
-                       OPEN_EXISTING,
-                       FILE_FLAG_OPEN_REPARSE_POINT | FILE_FLAG_BACKUP_SEMANTICS,
-                       NULL);
-
-  if (handle == INVALID_HANDLE_VALUE) {
-    SET_REQ_WIN32_ERROR(req, GetLastError());
-    return;
-  }
-
-  if (fs__readlink_handle(handle, (char**) &req->ptr, NULL) != 0) {
-    SET_REQ_WIN32_ERROR(req, GetLastError());
-    CloseHandle(handle);
-    return;
-  }
-
-  req->flags |= UV_FS_FREE_PTR;
-  SET_REQ_RESULT(req, 0);
-
-  CloseHandle(handle);
-}
-
-
-static ssize_t fs__realpath_handle(HANDLE handle, char** realpath_ptr) {
-  int r;
-  DWORD w_realpath_len;
-  WCHAR* w_realpath_ptr = NULL;
-  WCHAR* w_realpath_buf;
-
-  w_realpath_len = GetFinalPathNameByHandleW(handle, NULL, 0, VOLUME_NAME_DOS);
-  if (w_realpath_len == 0) {
-    return -1;
-  }
-
-  w_realpath_buf = (WCHAR*)uv__malloc((w_realpath_len + 1) * sizeof(WCHAR));
-  if (w_realpath_buf == NULL) {
-    SetLastError(ERROR_OUTOFMEMORY);
-    return -1;
-  }
-  w_realpath_ptr = w_realpath_buf;
-
-  if (GetFinalPathNameByHandleW(
-          handle, w_realpath_ptr, w_realpath_len, VOLUME_NAME_DOS) == 0) {
-    uv__free(w_realpath_buf);
-    SetLastError(ERROR_INVALID_HANDLE);
-    return -1;
-  }
-
-  /* convert UNC path to long path */
-  if (wcsncmp(w_realpath_ptr,
-              UNC_PATH_PREFIX,
-              UNC_PATH_PREFIX_LEN) == 0) {
-    w_realpath_ptr += 6;
-    *w_realpath_ptr = L'\\';
-    w_realpath_len -= 6;
-  } else if (wcsncmp(w_realpath_ptr,
-                      LONG_PATH_PREFIX,
-                      LONG_PATH_PREFIX_LEN) == 0) {
-    w_realpath_ptr += 4;
-    w_realpath_len -= 4;
-  } else {
-    uv__free(w_realpath_buf);
-    SetLastError(ERROR_INVALID_HANDLE);
-    return -1;
-  }
-
-  r = fs__wide_to_utf8(w_realpath_ptr, w_realpath_len, realpath_ptr, NULL);
-  uv__free(w_realpath_buf);
-  return r;
-}
-
-static void fs__realpath(uv_fs_t* req) {
-  HANDLE handle;
-
-  handle = CreateFileW(req->file.pathw,
-                       0,
-                       0,
-                       NULL,
-                       OPEN_EXISTING,
-                       FILE_ATTRIBUTE_NORMAL | FILE_FLAG_BACKUP_SEMANTICS,
-                       NULL);
-  if (handle == INVALID_HANDLE_VALUE) {
-    SET_REQ_WIN32_ERROR(req, GetLastError());
-    return;
-  }
-
-  if (fs__realpath_handle(handle, (char**) &req->ptr) == -1) {
-    CloseHandle(handle);
-    SET_REQ_WIN32_ERROR(req, GetLastError());
-    return;
-  }
-
-  CloseHandle(handle);
-  req->flags |= UV_FS_FREE_PTR;
-  SET_REQ_RESULT(req, 0);
-}
-
-
-static void fs__chown(uv_fs_t* req) {
-  req->result = 0;
-}
-
-
-static void fs__fchown(uv_fs_t* req) {
-  req->result = 0;
-}
-
-
-static void fs__lchown(uv_fs_t* req) {
-  req->result = 0;
-}
-
-static void uv__fs_work(struct uv__work* w) {
-  uv_fs_t* req;
-
-  req = container_of(w, uv_fs_t, work_req);
-  assert(req->type == UV_FS);
-
-#define XX(uc, lc)  case UV_FS_##uc: fs__##lc(req); break;
-  switch (req->fs_type) {
-    XX(OPEN, open)
-    XX(CLOSE, close)
-    XX(READ, read)
-    XX(WRITE, write)
-    XX(COPYFILE, copyfile)
-    XX(SENDFILE, sendfile)
-    XX(STAT, stat)
-    XX(LSTAT, lstat)
-    XX(FSTAT, fstat)
-    XX(FTRUNCATE, ftruncate)
-    XX(UTIME, utime)
-    XX(FUTIME, futime)
-    XX(ACCESS, access)
-    XX(CHMOD, chmod)
-    XX(FCHMOD, fchmod)
-    XX(FSYNC, fsync)
-    XX(FDATASYNC, fdatasync)
-    XX(UNLINK, unlink)
-    XX(RMDIR, rmdir)
-    XX(MKDIR, mkdir)
-    XX(MKDTEMP, mkdtemp)
-    XX(RENAME, rename)
-    XX(SCANDIR, scandir)
-    XX(READDIR, readdir)
-    XX(OPENDIR, opendir)
-    XX(CLOSEDIR, closedir)
-    XX(LINK, link)
-    XX(SYMLINK, symlink)
-    XX(READLINK, readlink)
-    XX(REALPATH, realpath)
-    XX(CHOWN, chown)
-    XX(FCHOWN, fchown);
-    XX(LCHOWN, lchown);
-    default:
-      assert(!"bad uv_fs_type");
-  }
-}
-
-
-static void uv__fs_done(struct uv__work* w, int status) {
-  uv_fs_t* req;
-
-  req = container_of(w, uv_fs_t, work_req);
-  uv__req_unregister(req->loop, req);
-
-  if (status == UV_ECANCELED) {
-    assert(req->result == 0);
-    req->result = UV_ECANCELED;
-  }
-
-  req->cb(req);
-}
-
-
-void uv_fs_req_cleanup(uv_fs_t* req) {
-  if (req == NULL)
-    return;
-
-  if (req->flags & UV_FS_CLEANEDUP)
-    return;
-
-  if (req->flags & UV_FS_FREE_PATHS)
-    uv__free(req->file.pathw);
-
-  if (req->flags & UV_FS_FREE_PTR) {
-    if (req->fs_type == UV_FS_SCANDIR && req->ptr != NULL)
-      uv__fs_scandir_cleanup(req);
-    else if (req->fs_type == UV_FS_READDIR)
-      uv__fs_readdir_cleanup(req);
-    else
-      uv__free(req->ptr);
-  }
-
-  if (req->fs.info.bufs != req->fs.info.bufsml)
-    uv__free(req->fs.info.bufs);
-
-  req->path = NULL;
-  req->file.pathw = NULL;
-  req->fs.info.new_pathw = NULL;
-  req->fs.info.bufs = NULL;
-  req->ptr = NULL;
-
-  req->flags |= UV_FS_CLEANEDUP;
-}
-
-
-int uv_fs_open(uv_loop_t* loop, uv_fs_t* req, const char* path, int flags,
-    int mode, uv_fs_cb cb) {
-  int err;
-
-  INIT(UV_FS_OPEN);
-  err = fs__capture_path(req, path, NULL, cb != NULL);
-  if (err) {
-    return uv_translate_sys_error(err);
-  }
-
-  req->fs.info.file_flags = flags;
-  req->fs.info.mode = mode;
-  POST;
-}
-
-
-int uv_fs_close(uv_loop_t* loop, uv_fs_t* req, uv_file fd, uv_fs_cb cb) {
-  INIT(UV_FS_CLOSE);
-  req->file.fd = fd;
-  POST;
-}
-
-
-int uv_fs_read(uv_loop_t* loop,
-               uv_fs_t* req,
-               uv_file fd,
-               const uv_buf_t bufs[],
-               unsigned int nbufs,
-               int64_t offset,
-               uv_fs_cb cb) {
-  INIT(UV_FS_READ);
-
-  if (bufs == NULL || nbufs == 0)
-    return UV_EINVAL;
-
-  req->file.fd = fd;
-
-  req->fs.info.nbufs = nbufs;
-  req->fs.info.bufs = req->fs.info.bufsml;
-  if (nbufs > ARRAY_SIZE(req->fs.info.bufsml))
-    req->fs.info.bufs = (uv_buf_t*)uv__malloc(nbufs * sizeof(*bufs));
-
-  if (req->fs.info.bufs == NULL)
-    return UV_ENOMEM;
-
-  memcpy(req->fs.info.bufs, bufs, nbufs * sizeof(*bufs));
-
-  req->fs.info.offset = offset;
-  POST;
-}
-
-
-int uv_fs_write(uv_loop_t* loop,
-                uv_fs_t* req,
-                uv_file fd,
-                const uv_buf_t bufs[],
-                unsigned int nbufs,
-                int64_t offset,
-                uv_fs_cb cb) {
-  INIT(UV_FS_WRITE);
-
-  if (bufs == NULL || nbufs == 0)
-    return UV_EINVAL;
-
-  req->file.fd = fd;
-
-  req->fs.info.nbufs = nbufs;
-  req->fs.info.bufs = req->fs.info.bufsml;
-  if (nbufs > ARRAY_SIZE(req->fs.info.bufsml))
-    req->fs.info.bufs = (uv_buf_t*)uv__malloc(nbufs * sizeof(*bufs));
-
-  if (req->fs.info.bufs == NULL)
-    return UV_ENOMEM;
-
-  memcpy(req->fs.info.bufs, bufs, nbufs * sizeof(*bufs));
-
-  req->fs.info.offset = offset;
-  POST;
-}
-
-
-int uv_fs_unlink(uv_loop_t* loop, uv_fs_t* req, const char* path,
-    uv_fs_cb cb) {
-  int err;
-
-  INIT(UV_FS_UNLINK);
-  err = fs__capture_path(req, path, NULL, cb != NULL);
-  if (err) {
-    return uv_translate_sys_error(err);
-  }
-
-  POST;
-}
-
-
-int uv_fs_mkdir(uv_loop_t* loop, uv_fs_t* req, const char* path, int mode,
-    uv_fs_cb cb) {
-  int err;
-
-  INIT(UV_FS_MKDIR);
-  err = fs__capture_path(req, path, NULL, cb != NULL);
-  if (err) {
-    return uv_translate_sys_error(err);
-  }
-
-  req->fs.info.mode = mode;
-  POST;
-}
-
-
-int uv_fs_mkdtemp(uv_loop_t* loop, uv_fs_t* req, const char* tpl,
-    uv_fs_cb cb) {
-  int err;
-
-  INIT(UV_FS_MKDTEMP);
-  err = fs__capture_path(req, tpl, NULL, TRUE);
-  if (err)
-    return uv_translate_sys_error(err);
-
-  POST;
-}
-
-
-int uv_fs_rmdir(uv_loop_t* loop, uv_fs_t* req, const char* path, uv_fs_cb cb) {
-  int err;
-
-  INIT(UV_FS_RMDIR);
-  err = fs__capture_path(req, path, NULL, cb != NULL);
-  if (err) {
-    return uv_translate_sys_error(err);
-  }
-
-  POST;
-}
-
-
-int uv_fs_scandir(uv_loop_t* loop, uv_fs_t* req, const char* path, int flags,
-    uv_fs_cb cb) {
-  int err;
-
-  INIT(UV_FS_SCANDIR);
-  err = fs__capture_path(req, path, NULL, cb != NULL);
-  if (err) {
-    return uv_translate_sys_error(err);
-  }
-
-  req->fs.info.file_flags = flags;
-  POST;
-}
-
-int uv_fs_opendir(uv_loop_t* loop,
-                  uv_fs_t* req,
-                  const char* path,
-                  uv_fs_cb cb) {
-  int err;
-
-  INIT(UV_FS_OPENDIR);
-  err = fs__capture_path(req, path, NULL, cb != NULL);
-  if (err)
-    return uv_translate_sys_error(err);
-  POST;
-}
-
-int uv_fs_readdir(uv_loop_t* loop,
-                  uv_fs_t* req,
-                  uv_dir_t* dir,
-                  uv_fs_cb cb) {
-  INIT(UV_FS_READDIR);
-
-  if (dir == NULL ||
-      dir->dirents == NULL ||
-      dir->dir_handle == INVALID_HANDLE_VALUE) {
-    return UV_EINVAL;
-  }
-
-  req->ptr = dir;
-  POST;
-}
-
-int uv_fs_closedir(uv_loop_t* loop,
-                   uv_fs_t* req,
-                   uv_dir_t* dir,
-                   uv_fs_cb cb) {
-  INIT(UV_FS_CLOSEDIR);
-  if (dir == NULL)
-    return UV_EINVAL;
-  req->ptr = dir;
-  POST;
-}
-
-int uv_fs_link(uv_loop_t* loop, uv_fs_t* req, const char* path,
-    const char* new_path, uv_fs_cb cb) {
-  int err;
-
-  INIT(UV_FS_LINK);
-  err = fs__capture_path(req, path, new_path, cb != NULL);
-  if (err) {
-    return uv_translate_sys_error(err);
-  }
-
-  POST;
-}
-
-
-int uv_fs_symlink(uv_loop_t* loop, uv_fs_t* req, const char* path,
-    const char* new_path, int flags, uv_fs_cb cb) {
-  int err;
-
-  INIT(UV_FS_SYMLINK);
-  err = fs__capture_path(req, path, new_path, cb != NULL);
-  if (err) {
-    return uv_translate_sys_error(err);
-  }
-
-  req->fs.info.file_flags = flags;
-  POST;
-}
-
-
-int uv_fs_readlink(uv_loop_t* loop, uv_fs_t* req, const char* path,
-    uv_fs_cb cb) {
-  int err;
-
-  INIT(UV_FS_READLINK);
-  err = fs__capture_path(req, path, NULL, cb != NULL);
-  if (err) {
-    return uv_translate_sys_error(err);
-  }
-
-  POST;
-}
-
-
-int uv_fs_realpath(uv_loop_t* loop, uv_fs_t* req, const char* path,
-    uv_fs_cb cb) {
-  int err;
-
-  INIT(UV_FS_REALPATH);
-
-  if (!path) {
-    return UV_EINVAL;
-  }
-
-  err = fs__capture_path(req, path, NULL, cb != NULL);
-  if (err) {
-    return uv_translate_sys_error(err);
-  }
-
-  POST;
-}
-
-
-int uv_fs_chown(uv_loop_t* loop, uv_fs_t* req, const char* path, uv_uid_t uid,
-    uv_gid_t gid, uv_fs_cb cb) {
-  int err;
-
-  INIT(UV_FS_CHOWN);
-  err = fs__capture_path(req, path, NULL, cb != NULL);
-  if (err) {
-    return uv_translate_sys_error(err);
-  }
-
-  POST;
-}
-
-
-int uv_fs_fchown(uv_loop_t* loop, uv_fs_t* req, uv_file fd, uv_uid_t uid,
-    uv_gid_t gid, uv_fs_cb cb) {
-  INIT(UV_FS_FCHOWN);
-  POST;
-}
-
-
-int uv_fs_lchown(uv_loop_t* loop, uv_fs_t* req, const char* path, uv_uid_t uid,
-    uv_gid_t gid, uv_fs_cb cb) {
-  int err;
-
-  INIT(UV_FS_LCHOWN);
-  err = fs__capture_path(req, path, NULL, cb != NULL);
-  if (err) {
-    return uv_translate_sys_error(err);
-  }
-  POST;
-}
-
-
-int uv_fs_stat(uv_loop_t* loop, uv_fs_t* req, const char* path, uv_fs_cb cb) {
-  int err;
-
-  INIT(UV_FS_STAT);
-  err = fs__capture_path(req, path, NULL, cb != NULL);
-  if (err) {
-    return uv_translate_sys_error(err);
-  }
-
-  POST;
-}
-
-
-int uv_fs_lstat(uv_loop_t* loop, uv_fs_t* req, const char* path, uv_fs_cb cb) {
-  int err;
-
-  INIT(UV_FS_LSTAT);
-  err = fs__capture_path(req, path, NULL, cb != NULL);
-  if (err) {
-    return uv_translate_sys_error(err);
-  }
-
-  POST;
-}
-
-
-int uv_fs_fstat(uv_loop_t* loop, uv_fs_t* req, uv_file fd, uv_fs_cb cb) {
-  INIT(UV_FS_FSTAT);
-  req->file.fd = fd;
-  POST;
-}
-
-
-int uv_fs_rename(uv_loop_t* loop, uv_fs_t* req, const char* path,
-    const char* new_path, uv_fs_cb cb) {
-  int err;
-
-  INIT(UV_FS_RENAME);
-  err = fs__capture_path(req, path, new_path, cb != NULL);
-  if (err) {
-    return uv_translate_sys_error(err);
-  }
-
-  POST;
-}
-
-
-int uv_fs_fsync(uv_loop_t* loop, uv_fs_t* req, uv_file fd, uv_fs_cb cb) {
-  INIT(UV_FS_FSYNC);
-  req->file.fd = fd;
-  POST;
-}
-
-
-int uv_fs_fdatasync(uv_loop_t* loop, uv_fs_t* req, uv_file fd, uv_fs_cb cb) {
-  INIT(UV_FS_FDATASYNC);
-  req->file.fd = fd;
-  POST;
-}
-
-
-int uv_fs_ftruncate(uv_loop_t* loop, uv_fs_t* req, uv_file fd,
-    int64_t offset, uv_fs_cb cb) {
-  INIT(UV_FS_FTRUNCATE);
-  req->file.fd = fd;
-  req->fs.info.offset = offset;
-  POST;
-}
-
-
-int uv_fs_copyfile(uv_loop_t* loop,
-                   uv_fs_t* req,
-                   const char* path,
-                   const char* new_path,
-                   int flags,
-                   uv_fs_cb cb) {
-  int err;
-
-  INIT(UV_FS_COPYFILE);
-
-  if (flags & ~(UV_FS_COPYFILE_EXCL |
-                UV_FS_COPYFILE_FICLONE |
-                UV_FS_COPYFILE_FICLONE_FORCE)) {
-    return UV_EINVAL;
-  }
-
-  err = fs__capture_path(req, path, new_path, cb != NULL);
-
-  if (err)
-    return uv_translate_sys_error(err);
-
-  req->fs.info.file_flags = flags;
-  POST;
-}
-
-
-int uv_fs_sendfile(uv_loop_t* loop, uv_fs_t* req, uv_file fd_out,
-    uv_file fd_in, int64_t in_offset, size_t length, uv_fs_cb cb) {
-  INIT(UV_FS_SENDFILE);
-  req->file.fd = fd_in;
-  req->fs.info.fd_out = fd_out;
-  req->fs.info.offset = in_offset;
-  req->fs.info.bufsml[0].len = length;
-  POST;
-}
-
-
-int uv_fs_access(uv_loop_t* loop,
-                 uv_fs_t* req,
-                 const char* path,
-                 int flags,
-                 uv_fs_cb cb) {
-  int err;
-
-  INIT(UV_FS_ACCESS);
-  err = fs__capture_path(req, path, NULL, cb != NULL);
-  if (err)
-    return uv_translate_sys_error(err);
-
-  req->fs.info.mode = flags;
-  POST;
-}
-
-
-int uv_fs_chmod(uv_loop_t* loop, uv_fs_t* req, const char* path, int mode,
-    uv_fs_cb cb) {
-  int err;
-
-  INIT(UV_FS_CHMOD);
-  err = fs__capture_path(req, path, NULL, cb != NULL);
-  if (err) {
-    return uv_translate_sys_error(err);
-  }
-
-  req->fs.info.mode = mode;
-  POST;
-}
-
-
-int uv_fs_fchmod(uv_loop_t* loop, uv_fs_t* req, uv_file fd, int mode,
-    uv_fs_cb cb) {
-  INIT(UV_FS_FCHMOD);
-  req->file.fd = fd;
-  req->fs.info.mode = mode;
-  POST;
-}
-
-
-int uv_fs_utime(uv_loop_t* loop, uv_fs_t* req, const char* path, double atime,
-    double mtime, uv_fs_cb cb) {
-  int err;
-
-  INIT(UV_FS_UTIME);
-  err = fs__capture_path(req, path, NULL, cb != NULL);
-  if (err) {
-    return uv_translate_sys_error(err);
-  }
-
-  req->fs.time.atime = atime;
-  req->fs.time.mtime = mtime;
-  POST;
-}
-
-
-int uv_fs_futime(uv_loop_t* loop, uv_fs_t* req, uv_file fd, double atime,
-    double mtime, uv_fs_cb cb) {
-  INIT(UV_FS_FUTIME);
-  req->file.fd = fd;
-  req->fs.time.atime = atime;
-  req->fs.time.mtime = mtime;
-  POST;
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/handle-inl.h b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/handle-inl.h
deleted file mode 100644
index 82c657d..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/handle-inl.h
+++ /dev/null
@@ -1,180 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#ifndef UV_WIN_HANDLE_INL_H_
-#define UV_WIN_HANDLE_INL_H_
-
-#include <assert.h>
-#include <io.h>
-
-#include "uv.h"
-#include "internal.h"
-
-
-#define DECREASE_ACTIVE_COUNT(loop, handle)                             \
-  do {                                                                  \
-    if (--(handle)->activecnt == 0 &&                                   \
-        !((handle)->flags & UV_HANDLE_CLOSING)) {                       \
-      uv__handle_stop((handle));                                        \
-    }                                                                   \
-    assert((handle)->activecnt >= 0);                                   \
-  } while (0)
-
-
-#define INCREASE_ACTIVE_COUNT(loop, handle)                             \
-  do {                                                                  \
-    if ((handle)->activecnt++ == 0) {                                   \
-      uv__handle_start((handle));                                       \
-    }                                                                   \
-    assert((handle)->activecnt > 0);                                    \
-  } while (0)
-
-
-#define DECREASE_PENDING_REQ_COUNT(handle)                              \
-  do {                                                                  \
-    assert(handle->reqs_pending > 0);                                   \
-    handle->reqs_pending--;                                             \
-                                                                        \
-    if (handle->flags & UV_HANDLE_CLOSING &&                            \
-        handle->reqs_pending == 0) {                                    \
-      uv_want_endgame(loop, (uv_handle_t*)handle);                      \
-    }                                                                   \
-  } while (0)
-
-
-#define uv__handle_closing(handle)                                      \
-  do {                                                                  \
-    assert(!((handle)->flags & UV_HANDLE_CLOSING));                     \
-                                                                        \
-    if (!(((handle)->flags & UV_HANDLE_ACTIVE) &&                       \
-          ((handle)->flags & UV_HANDLE_REF)))                           \
-      uv__active_handle_add((uv_handle_t*) (handle));                   \
-                                                                        \
-    (handle)->flags |= UV_HANDLE_CLOSING;                               \
-    (handle)->flags &= ~UV_HANDLE_ACTIVE;                               \
-  } while (0)
-
-
-#define uv__handle_close(handle)                                        \
-  do {                                                                  \
-    QUEUE_REMOVE(&(handle)->handle_queue);                              \
-    uv__active_handle_rm((uv_handle_t*) (handle));                      \
-                                                                        \
-    (handle)->flags |= UV_HANDLE_CLOSED;                                \
-                                                                        \
-    if ((handle)->close_cb)                                             \
-      (handle)->close_cb((uv_handle_t*) (handle));                      \
-  } while (0)
-
-
-INLINE static void uv_want_endgame(uv_loop_t* loop, uv_handle_t* handle) {
-  if (!(handle->flags & UV_HANDLE_ENDGAME_QUEUED)) {
-    handle->flags |= UV_HANDLE_ENDGAME_QUEUED;
-
-    handle->endgame_next = loop->endgame_handles;
-    loop->endgame_handles = handle;
-  }
-}
-
-
-INLINE static void uv_process_endgames(uv_loop_t* loop) {
-  uv_handle_t* handle;
-
-  while (loop->endgame_handles) {
-    handle = loop->endgame_handles;
-    loop->endgame_handles = handle->endgame_next;
-
-    handle->flags &= ~UV_HANDLE_ENDGAME_QUEUED;
-
-    switch (handle->type) {
-      case UV_TCP:
-        uv_tcp_endgame(loop, (uv_tcp_t*) handle);
-        break;
-
-      case UV_NAMED_PIPE:
-        uv_pipe_endgame(loop, (uv_pipe_t*) handle);
-        break;
-
-      case UV_TTY:
-        uv_tty_endgame(loop, (uv_tty_t*) handle);
-        break;
-
-      case UV_UDP:
-        uv_udp_endgame(loop, (uv_udp_t*) handle);
-        break;
-
-      case UV_POLL:
-        uv_poll_endgame(loop, (uv_poll_t*) handle);
-        break;
-
-      case UV_TIMER:
-        uv__timer_close((uv_timer_t*) handle);
-        uv__handle_close(handle);
-        break;
-
-      case UV_PREPARE:
-      case UV_CHECK:
-      case UV_IDLE:
-        uv_loop_watcher_endgame(loop, handle);
-        break;
-
-      case UV_ASYNC:
-        uv_async_endgame(loop, (uv_async_t*) handle);
-        break;
-
-      case UV_SIGNAL:
-        uv_signal_endgame(loop, (uv_signal_t*) handle);
-        break;
-
-      case UV_PROCESS:
-        uv_process_endgame(loop, (uv_process_t*) handle);
-        break;
-
-      case UV_FS_EVENT:
-        uv_fs_event_endgame(loop, (uv_fs_event_t*) handle);
-        break;
-
-      case UV_FS_POLL:
-        uv__fs_poll_endgame(loop, (uv_fs_poll_t*) handle);
-        break;
-
-      default:
-        assert(0);
-        break;
-    }
-  }
-}
-
-INLINE static HANDLE uv__get_osfhandle(int fd)
-{
-  /* _get_osfhandle() raises an assert in debug builds if the FD is invalid.
-   * But it also correctly checks the FD and returns INVALID_HANDLE_VALUE for
-   * invalid FDs in release builds (or if you let the assert continue). So this
-   * wrapper function disables asserts when calling _get_osfhandle. */
-
-  HANDLE handle;
-  UV_BEGIN_DISABLE_CRT_ASSERT();
-  handle = (HANDLE) _get_osfhandle(fd);
-  UV_END_DISABLE_CRT_ASSERT();
-  return handle;
-}
-
-#endif /* UV_WIN_HANDLE_INL_H_ */
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/handle.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/handle.cpp
deleted file mode 100644
index 61e4df6..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/handle.cpp
+++ /dev/null
@@ -1,162 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include <assert.h>
-#include <io.h>
-#include <stdlib.h>
-
-#include "uv.h"
-#include "internal.h"
-#include "handle-inl.h"
-
-
-uv_handle_type uv_guess_handle(uv_file file) {
-  HANDLE handle;
-  DWORD mode;
-
-  if (file < 0) {
-    return UV_UNKNOWN_HANDLE;
-  }
-
-  handle = uv__get_osfhandle(file);
-
-  switch (GetFileType(handle)) {
-    case FILE_TYPE_CHAR:
-      if (GetConsoleMode(handle, &mode)) {
-        return UV_TTY;
-      } else {
-        return UV_FILE;
-      }
-
-    case FILE_TYPE_PIPE:
-      return UV_NAMED_PIPE;
-
-    case FILE_TYPE_DISK:
-      return UV_FILE;
-
-    default:
-      return UV_UNKNOWN_HANDLE;
-  }
-}
-
-
-int uv_is_active(const uv_handle_t* handle) {
-  return (handle->flags & UV_HANDLE_ACTIVE) &&
-        !(handle->flags & UV_HANDLE_CLOSING);
-}
-
-
-void uv_close(uv_handle_t* handle, uv_close_cb cb) {
-  uv_loop_t* loop = handle->loop;
-
-  if (handle->flags & UV_HANDLE_CLOSING) {
-    assert(0);
-    return;
-  }
-
-  handle->close_cb = cb;
-
-  /* Handle-specific close actions */
-  switch (handle->type) {
-    case UV_TCP:
-      uv_tcp_close(loop, (uv_tcp_t*)handle);
-      return;
-
-    case UV_NAMED_PIPE:
-      uv_pipe_close(loop, (uv_pipe_t*) handle);
-      return;
-
-    case UV_TTY:
-      uv_tty_close((uv_tty_t*) handle);
-      return;
-
-    case UV_UDP:
-      uv_udp_close(loop, (uv_udp_t*) handle);
-      return;
-
-    case UV_POLL:
-      uv_poll_close(loop, (uv_poll_t*) handle);
-      return;
-
-    case UV_TIMER:
-      uv_timer_stop((uv_timer_t*)handle);
-      uv__handle_closing(handle);
-      uv_want_endgame(loop, handle);
-      return;
-
-    case UV_PREPARE:
-      uv_prepare_stop((uv_prepare_t*)handle);
-      uv__handle_closing(handle);
-      uv_want_endgame(loop, handle);
-      return;
-
-    case UV_CHECK:
-      uv_check_stop((uv_check_t*)handle);
-      uv__handle_closing(handle);
-      uv_want_endgame(loop, handle);
-      return;
-
-    case UV_IDLE:
-      uv_idle_stop((uv_idle_t*)handle);
-      uv__handle_closing(handle);
-      uv_want_endgame(loop, handle);
-      return;
-
-    case UV_ASYNC:
-      uv_async_close(loop, (uv_async_t*) handle);
-      return;
-
-    case UV_SIGNAL:
-      uv_signal_close(loop, (uv_signal_t*) handle);
-      return;
-
-    case UV_PROCESS:
-      uv_process_close(loop, (uv_process_t*) handle);
-      return;
-
-    case UV_FS_EVENT:
-      uv_fs_event_close(loop, (uv_fs_event_t*) handle);
-      return;
-
-    case UV_FS_POLL:
-      uv__fs_poll_close((uv_fs_poll_t*) handle);
-      uv__handle_closing(handle);
-      return;
-
-    default:
-      /* Not supported */
-      abort();
-  }
-}
-
-
-int uv_is_closing(const uv_handle_t* handle) {
-  return !!(handle->flags & (UV_HANDLE_CLOSING | UV_HANDLE_CLOSED));
-}
-
-
-uv_os_fd_t uv_get_osfhandle(int fd) {
-  return uv__get_osfhandle(fd);
-}
-
-int uv_open_osfhandle(uv_os_fd_t os_fd) {
-  return _open_osfhandle((intptr_t) os_fd, 0);
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/internal.h b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/internal.h
deleted file mode 100644
index 70ddaa5..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/internal.h
+++ /dev/null
@@ -1,342 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#ifndef UV_WIN_INTERNAL_H_
-#define UV_WIN_INTERNAL_H_
-
-#include "uv.h"
-#include "../uv-common.h"
-
-#include "uv/tree.h"
-#include "winapi.h"
-#include "winsock.h"
-
-#ifdef _MSC_VER
-# define INLINE __inline
-# define UV_THREAD_LOCAL __declspec( thread )
-#else
-# define INLINE inline
-# define UV_THREAD_LOCAL __thread
-#endif
-
-
-#ifdef _DEBUG
-
-extern UV_THREAD_LOCAL int uv__crt_assert_enabled;
-
-#define UV_BEGIN_DISABLE_CRT_ASSERT()                           \
-  {                                                             \
-    int uv__saved_crt_assert_enabled = uv__crt_assert_enabled;  \
-    uv__crt_assert_enabled = FALSE;
-
-
-#define UV_END_DISABLE_CRT_ASSERT()                             \
-    uv__crt_assert_enabled = uv__saved_crt_assert_enabled;      \
-  }
-
-#else
-#define UV_BEGIN_DISABLE_CRT_ASSERT()
-#define UV_END_DISABLE_CRT_ASSERT()
-#endif
-
-/*
- * TCP
- */
-
-typedef enum {
-  UV__IPC_SOCKET_XFER_NONE = 0,
-  UV__IPC_SOCKET_XFER_TCP_CONNECTION,
-  UV__IPC_SOCKET_XFER_TCP_SERVER
-} uv__ipc_socket_xfer_type_t;
-
-typedef struct {
-  WSAPROTOCOL_INFOW socket_info;
-  uint32_t delayed_error;
-} uv__ipc_socket_xfer_info_t;
-
-int uv_tcp_listen(uv_tcp_t* handle, int backlog, uv_connection_cb cb);
-int uv_tcp_accept(uv_tcp_t* server, uv_tcp_t* client);
-int uv_tcp_read_start(uv_tcp_t* handle, uv_alloc_cb alloc_cb,
-    uv_read_cb read_cb);
-int uv_tcp_write(uv_loop_t* loop, uv_write_t* req, uv_tcp_t* handle,
-    const uv_buf_t bufs[], unsigned int nbufs, uv_write_cb cb);
-int uv__tcp_try_write(uv_tcp_t* handle, const uv_buf_t bufs[],
-    unsigned int nbufs);
-
-void uv_process_tcp_read_req(uv_loop_t* loop, uv_tcp_t* handle, uv_req_t* req);
-void uv_process_tcp_write_req(uv_loop_t* loop, uv_tcp_t* handle,
-    uv_write_t* req);
-void uv_process_tcp_accept_req(uv_loop_t* loop, uv_tcp_t* handle,
-    uv_req_t* req);
-void uv_process_tcp_connect_req(uv_loop_t* loop, uv_tcp_t* handle,
-    uv_connect_t* req);
-
-void uv_tcp_close(uv_loop_t* loop, uv_tcp_t* tcp);
-void uv_tcp_endgame(uv_loop_t* loop, uv_tcp_t* handle);
-
-int uv__tcp_xfer_export(uv_tcp_t* handle,
-                        int pid,
-                        uv__ipc_socket_xfer_type_t* xfer_type,
-                        uv__ipc_socket_xfer_info_t* xfer_info);
-int uv__tcp_xfer_import(uv_tcp_t* tcp,
-                        uv__ipc_socket_xfer_type_t xfer_type,
-                        uv__ipc_socket_xfer_info_t* xfer_info);
-
-
-/*
- * UDP
- */
-void uv_process_udp_recv_req(uv_loop_t* loop, uv_udp_t* handle, uv_req_t* req);
-void uv_process_udp_send_req(uv_loop_t* loop, uv_udp_t* handle,
-    uv_udp_send_t* req);
-
-void uv_udp_close(uv_loop_t* loop, uv_udp_t* handle);
-void uv_udp_endgame(uv_loop_t* loop, uv_udp_t* handle);
-
-
-/*
- * Pipes
- */
-int uv_stdio_pipe_server(uv_loop_t* loop, uv_pipe_t* handle, DWORD access,
-    char* name, size_t nameSize);
-
-int uv_pipe_listen(uv_pipe_t* handle, int backlog, uv_connection_cb cb);
-int uv_pipe_accept(uv_pipe_t* server, uv_stream_t* client);
-int uv_pipe_read_start(uv_pipe_t* handle, uv_alloc_cb alloc_cb,
-    uv_read_cb read_cb);
-void uv__pipe_read_stop(uv_pipe_t* handle);
-int uv__pipe_write(uv_loop_t* loop,
-                   uv_write_t* req,
-                   uv_pipe_t* handle,
-                   const uv_buf_t bufs[],
-                   size_t nbufs,
-                   uv_stream_t* send_handle,
-                   uv_write_cb cb);
-
-void uv_process_pipe_read_req(uv_loop_t* loop, uv_pipe_t* handle,
-    uv_req_t* req);
-void uv_process_pipe_write_req(uv_loop_t* loop, uv_pipe_t* handle,
-    uv_write_t* req);
-void uv_process_pipe_accept_req(uv_loop_t* loop, uv_pipe_t* handle,
-    uv_req_t* raw_req);
-void uv_process_pipe_connect_req(uv_loop_t* loop, uv_pipe_t* handle,
-    uv_connect_t* req);
-void uv_process_pipe_shutdown_req(uv_loop_t* loop, uv_pipe_t* handle,
-    uv_shutdown_t* req);
-
-void uv_pipe_close(uv_loop_t* loop, uv_pipe_t* handle);
-void uv_pipe_cleanup(uv_loop_t* loop, uv_pipe_t* handle);
-void uv_pipe_endgame(uv_loop_t* loop, uv_pipe_t* handle);
-
-
-/*
- * TTY
- */
-void uv_console_init(void);
-
-int uv_tty_read_start(uv_tty_t* handle, uv_alloc_cb alloc_cb,
-    uv_read_cb read_cb);
-int uv_tty_read_stop(uv_tty_t* handle);
-int uv_tty_write(uv_loop_t* loop, uv_write_t* req, uv_tty_t* handle,
-    const uv_buf_t bufs[], unsigned int nbufs, uv_write_cb cb);
-int uv__tty_try_write(uv_tty_t* handle, const uv_buf_t bufs[],
-    unsigned int nbufs);
-void uv_tty_close(uv_tty_t* handle);
-
-void uv_process_tty_read_req(uv_loop_t* loop, uv_tty_t* handle,
-    uv_req_t* req);
-void uv_process_tty_write_req(uv_loop_t* loop, uv_tty_t* handle,
-    uv_write_t* req);
-/*
- * uv_process_tty_accept_req() is a stub to keep DELEGATE_STREAM_REQ working
- * TODO: find a way to remove it
- */
-void uv_process_tty_accept_req(uv_loop_t* loop, uv_tty_t* handle,
-    uv_req_t* raw_req);
-/*
- * uv_process_tty_connect_req() is a stub to keep DELEGATE_STREAM_REQ working
- * TODO: find a way to remove it
- */
-void uv_process_tty_connect_req(uv_loop_t* loop, uv_tty_t* handle,
-    uv_connect_t* req);
-
-void uv_tty_endgame(uv_loop_t* loop, uv_tty_t* handle);
-
-
-/*
- * Poll watchers
- */
-void uv_process_poll_req(uv_loop_t* loop, uv_poll_t* handle,
-    uv_req_t* req);
-
-int uv_poll_close(uv_loop_t* loop, uv_poll_t* handle);
-void uv_poll_endgame(uv_loop_t* loop, uv_poll_t* handle);
-
-
-/*
- * Loop watchers
- */
-void uv_loop_watcher_endgame(uv_loop_t* loop, uv_handle_t* handle);
-
-void uv_prepare_invoke(uv_loop_t* loop);
-void uv_check_invoke(uv_loop_t* loop);
-void uv_idle_invoke(uv_loop_t* loop);
-
-void uv__once_init(void);
-
-
-/*
- * Async watcher
- */
-void uv_async_close(uv_loop_t* loop, uv_async_t* handle);
-void uv_async_endgame(uv_loop_t* loop, uv_async_t* handle);
-
-void uv_process_async_wakeup_req(uv_loop_t* loop, uv_async_t* handle,
-    uv_req_t* req);
-
-
-/*
- * Signal watcher
- */
-void uv_signals_init(void);
-int uv__signal_dispatch(int signum);
-
-void uv_signal_close(uv_loop_t* loop, uv_signal_t* handle);
-void uv_signal_endgame(uv_loop_t* loop, uv_signal_t* handle);
-
-void uv_process_signal_req(uv_loop_t* loop, uv_signal_t* handle,
-    uv_req_t* req);
-
-
-/*
- * Spawn
- */
-void uv_process_proc_exit(uv_loop_t* loop, uv_process_t* handle);
-void uv_process_close(uv_loop_t* loop, uv_process_t* handle);
-void uv_process_endgame(uv_loop_t* loop, uv_process_t* handle);
-
-
-/*
- * Error
- */
-int uv_translate_sys_error(int sys_errno);
-
-
-/*
- * FS
- */
-void uv_fs_init(void);
-
-
-/*
- * FS Event
- */
-void uv_process_fs_event_req(uv_loop_t* loop, uv_req_t* req,
-    uv_fs_event_t* handle);
-void uv_fs_event_close(uv_loop_t* loop, uv_fs_event_t* handle);
-void uv_fs_event_endgame(uv_loop_t* loop, uv_fs_event_t* handle);
-
-
-/*
- * Stat poller.
- */
-void uv__fs_poll_endgame(uv_loop_t* loop, uv_fs_poll_t* handle);
-
-
-/*
- * Utilities.
- */
-void uv__util_init(void);
-
-uint64_t uv__hrtime(double scale);
-__declspec(noreturn) void uv_fatal_error(const int errorno, const char* syscall);
-int uv__getpwuid_r(uv_passwd_t* pwd);
-int uv__convert_utf16_to_utf8(const WCHAR* utf16, int utf16len, char** utf8);
-int uv__convert_utf8_to_utf16(const char* utf8, int utf8len, WCHAR** utf16);
-
-typedef int (WINAPI *uv__peersockfunc)(SOCKET, struct sockaddr*, int*);
-
-int uv__getsockpeername(const uv_handle_t* handle,
-                        uv__peersockfunc func,
-                        struct sockaddr* name,
-                        int* namelen,
-                        int delayed_error);
-
-
-/*
- * Process stdio handles.
- */
-int uv__stdio_create(uv_loop_t* loop,
-                     const uv_process_options_t* options,
-                     BYTE** buffer_ptr);
-void uv__stdio_destroy(BYTE* buffer);
-void uv__stdio_noinherit(BYTE* buffer);
-int uv__stdio_verify(BYTE* buffer, WORD size);
-WORD uv__stdio_size(BYTE* buffer);
-HANDLE uv__stdio_handle(BYTE* buffer, int fd);
-
-
-/*
- * Winapi and ntapi utility functions
- */
-void uv_winapi_init(void);
-
-
-/*
- * Winsock utility functions
- */
-void uv_winsock_init(void);
-
-int uv_ntstatus_to_winsock_error(NTSTATUS status);
-
-BOOL uv_get_acceptex_function(SOCKET socket, LPFN_ACCEPTEX* target);
-BOOL uv_get_connectex_function(SOCKET socket, LPFN_CONNECTEX* target);
-
-int WSAAPI uv_wsarecv_workaround(SOCKET socket, WSABUF* buffers,
-    DWORD buffer_count, DWORD* bytes, DWORD* flags, WSAOVERLAPPED *overlapped,
-    LPWSAOVERLAPPED_COMPLETION_ROUTINE completion_routine);
-int WSAAPI uv_wsarecvfrom_workaround(SOCKET socket, WSABUF* buffers,
-    DWORD buffer_count, DWORD* bytes, DWORD* flags, struct sockaddr* addr,
-    int* addr_len, WSAOVERLAPPED *overlapped,
-    LPWSAOVERLAPPED_COMPLETION_ROUTINE completion_routine);
-
-int WSAAPI uv_msafd_poll(SOCKET socket, AFD_POLL_INFO* info_in,
-    AFD_POLL_INFO* info_out, OVERLAPPED* overlapped);
-
-/* Whether there are any non-IFS LSPs stacked on TCP */
-extern int uv_tcp_non_ifs_lsp_ipv4;
-extern int uv_tcp_non_ifs_lsp_ipv6;
-
-/* Ip address used to bind to any port at any interface */
-extern struct sockaddr_in uv_addr_ip4_any_;
-extern struct sockaddr_in6 uv_addr_ip6_any_;
-
-/*
- * Wake all loops with fake message
- */
-void uv__wake_all_loops(void);
-
-/*
- * Init system wake-up detection
- */
-void uv__init_detect_system_wakeup(void);
-
-#endif /* UV_WIN_INTERNAL_H_ */
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/loop-watcher.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/loop-watcher.cpp
deleted file mode 100644
index ad7fbea..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/loop-watcher.cpp
+++ /dev/null
@@ -1,122 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include <assert.h>
-
-#include "uv.h"
-#include "internal.h"
-#include "handle-inl.h"
-
-
-void uv_loop_watcher_endgame(uv_loop_t* loop, uv_handle_t* handle) {
-  if (handle->flags & UV_HANDLE_CLOSING) {
-    assert(!(handle->flags & UV_HANDLE_CLOSED));
-    handle->flags |= UV_HANDLE_CLOSED;
-    uv__handle_close(handle);
-  }
-}
-
-
-#define UV_LOOP_WATCHER_DEFINE(name, NAME)                                    \
-  int uv_##name##_init(uv_loop_t* loop, uv_##name##_t* handle) {              \
-    uv__handle_init(loop, (uv_handle_t*) handle, UV_##NAME);                  \
-                                                                              \
-    return 0;                                                                 \
-  }                                                                           \
-                                                                              \
-                                                                              \
-  int uv_##name##_start(uv_##name##_t* handle, uv_##name##_cb cb) {           \
-    uv_loop_t* loop = handle->loop;                                           \
-    uv_##name##_t* old_head;                                                  \
-                                                                              \
-    assert(handle->type == UV_##NAME);                                        \
-                                                                              \
-    if (uv__is_active(handle))                                                \
-      return 0;                                                               \
-                                                                              \
-    if (cb == NULL)                                                           \
-      return UV_EINVAL;                                                       \
-                                                                              \
-    old_head = loop->name##_handles;                                          \
-                                                                              \
-    handle->name##_next = old_head;                                           \
-    handle->name##_prev = NULL;                                               \
-                                                                              \
-    if (old_head) {                                                           \
-      old_head->name##_prev = handle;                                         \
-    }                                                                         \
-                                                                              \
-    loop->name##_handles = handle;                                            \
-                                                                              \
-    handle->name##_cb = cb;                                                   \
-    uv__handle_start(handle);                                                 \
-                                                                              \
-    return 0;                                                                 \
-  }                                                                           \
-                                                                              \
-                                                                              \
-  int uv_##name##_stop(uv_##name##_t* handle) {                               \
-    uv_loop_t* loop = handle->loop;                                           \
-                                                                              \
-    assert(handle->type == UV_##NAME);                                        \
-                                                                              \
-    if (!uv__is_active(handle))                                               \
-      return 0;                                                               \
-                                                                              \
-    /* Update loop head if needed */                                          \
-    if (loop->name##_handles == handle) {                                     \
-      loop->name##_handles = handle->name##_next;                             \
-    }                                                                         \
-                                                                              \
-    /* Update the iterator-next pointer of needed */                          \
-    if (loop->next_##name##_handle == handle) {                               \
-      loop->next_##name##_handle = handle->name##_next;                       \
-    }                                                                         \
-                                                                              \
-    if (handle->name##_prev) {                                                \
-      handle->name##_prev->name##_next = handle->name##_next;                 \
-    }                                                                         \
-    if (handle->name##_next) {                                                \
-      handle->name##_next->name##_prev = handle->name##_prev;                 \
-    }                                                                         \
-                                                                              \
-    uv__handle_stop(handle);                                                  \
-                                                                              \
-    return 0;                                                                 \
-  }                                                                           \
-                                                                              \
-                                                                              \
-  void uv_##name##_invoke(uv_loop_t* loop) {                                  \
-    uv_##name##_t* handle;                                                    \
-                                                                              \
-    (loop)->next_##name##_handle = (loop)->name##_handles;                    \
-                                                                              \
-    while ((loop)->next_##name##_handle != NULL) {                            \
-      handle = (loop)->next_##name##_handle;                                  \
-      (loop)->next_##name##_handle = handle->name##_next;                     \
-                                                                              \
-      handle->name##_cb(handle);                                              \
-    }                                                                         \
-  }
-
-UV_LOOP_WATCHER_DEFINE(prepare, PREPARE)
-UV_LOOP_WATCHER_DEFINE(check, CHECK)
-UV_LOOP_WATCHER_DEFINE(idle, IDLE)
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/pipe.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/pipe.cpp
deleted file mode 100644
index 0c03a06..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/pipe.cpp
+++ /dev/null
@@ -1,2388 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#define _CRT_NONSTDC_NO_WARNINGS
-
-#include <assert.h>
-#include <io.h>
-#include <stdio.h>
-#include <stdlib.h>
-#include <string.h>
-
-#include "handle-inl.h"
-#include "internal.h"
-#include "req-inl.h"
-#include "stream-inl.h"
-#include "uv-common.h"
-#include "uv.h"
-
-#include <aclapi.h>
-#include <accctrl.h>
-
-/* A zero-size buffer for use by uv_pipe_read */
-static char uv_zero_[] = "";
-
-/* Null uv_buf_t */
-static const uv_buf_t uv_null_buf_ = { 0, NULL };
-
-/* The timeout that the pipe will wait for the remote end to write data when
- * the local ends wants to shut it down. */
-static const int64_t eof_timeout = 50; /* ms */
-
-static const int default_pending_pipe_instances = 4;
-
-/* Pipe prefix */
-static char pipe_prefix[] = "\\\\?\\pipe";
-static const int pipe_prefix_len = sizeof(pipe_prefix) - 1;
-
-/* IPC incoming xfer queue item. */
-typedef struct {
-  uv__ipc_socket_xfer_type_t xfer_type;
-  uv__ipc_socket_xfer_info_t xfer_info;
-  QUEUE member;
-} uv__ipc_xfer_queue_item_t;
-
-/* IPC frame header flags. */
-/* clang-format off */
-enum {
-  UV__IPC_FRAME_HAS_DATA                = 0x01,
-  UV__IPC_FRAME_HAS_SOCKET_XFER         = 0x02,
-  UV__IPC_FRAME_XFER_IS_TCP_CONNECTION  = 0x04,
-  /* These are combinations of the flags above. */
-  UV__IPC_FRAME_XFER_FLAGS              = 0x06,
-  UV__IPC_FRAME_VALID_FLAGS             = 0x07
-};
-/* clang-format on */
-
-/* IPC frame header. */
-typedef struct {
-  uint32_t flags;
-  uint32_t reserved1;   /* Ignored. */
-  uint32_t data_length; /* Must be zero if there is no data. */
-  uint32_t reserved2;   /* Must be zero. */
-} uv__ipc_frame_header_t;
-
-/* To implement the IPC protocol correctly, these structures must have exactly
- * the right size. */
-STATIC_ASSERT(sizeof(uv__ipc_frame_header_t) == 16);
-STATIC_ASSERT(sizeof(uv__ipc_socket_xfer_info_t) == 632);
-
-/* Coalesced write request. */
-typedef struct {
-  uv_write_t req;       /* Internal heap-allocated write request. */
-  uv_write_t* user_req; /* Pointer to user-specified uv_write_t. */
-} uv__coalesced_write_t;
-
-
-static void eof_timer_init(uv_pipe_t* pipe);
-static void eof_timer_start(uv_pipe_t* pipe);
-static void eof_timer_stop(uv_pipe_t* pipe);
-static void eof_timer_cb(uv_timer_t* timer);
-static void eof_timer_destroy(uv_pipe_t* pipe);
-static void eof_timer_close_cb(uv_handle_t* handle);
-
-
-static void uv_unique_pipe_name(char* ptr, char* name, size_t size) {
-  snprintf(name, size, "\\\\?\\pipe\\uv\\%p-%lu", ptr, GetCurrentProcessId());
-}
-
-
-int uv_pipe_init(uv_loop_t* loop, uv_pipe_t* handle, int ipc) {
-  uv_stream_init(loop, (uv_stream_t*)handle, UV_NAMED_PIPE);
-
-  handle->reqs_pending = 0;
-  handle->handle = INVALID_HANDLE_VALUE;
-  handle->name = NULL;
-  handle->pipe.conn.ipc_remote_pid = 0;
-  handle->pipe.conn.ipc_data_frame.payload_remaining = 0;
-  QUEUE_INIT(&handle->pipe.conn.ipc_xfer_queue);
-  handle->pipe.conn.ipc_xfer_queue_length = 0;
-  handle->ipc = ipc;
-  handle->pipe.conn.non_overlapped_writes_tail = NULL;
-
-  return 0;
-}
-
-
-static void uv_pipe_connection_init(uv_pipe_t* handle) {
-  uv_connection_init((uv_stream_t*) handle);
-  handle->read_req.data = handle;
-  handle->pipe.conn.eof_timer = NULL;
-  assert(!(handle->flags & UV_HANDLE_PIPESERVER));
-  if (handle->flags & UV_HANDLE_NON_OVERLAPPED_PIPE) {
-    handle->pipe.conn.readfile_thread_handle = NULL;
-    InitializeCriticalSection(&handle->pipe.conn.readfile_thread_lock);
-  }
-}
-
-
-static HANDLE open_named_pipe(const WCHAR* name, DWORD* duplex_flags) {
-  HANDLE pipeHandle;
-
-  /*
-   * Assume that we have a duplex pipe first, so attempt to
-   * connect with GENERIC_READ | GENERIC_WRITE.
-   */
-  pipeHandle = CreateFileW(name,
-                           GENERIC_READ | GENERIC_WRITE,
-                           0,
-                           NULL,
-                           OPEN_EXISTING,
-                           FILE_FLAG_OVERLAPPED,
-                           NULL);
-  if (pipeHandle != INVALID_HANDLE_VALUE) {
-    *duplex_flags = UV_HANDLE_READABLE | UV_HANDLE_WRITABLE;
-    return pipeHandle;
-  }
-
-  /*
-   * If the pipe is not duplex CreateFileW fails with
-   * ERROR_ACCESS_DENIED.  In that case try to connect
-   * as a read-only or write-only.
-   */
-  if (GetLastError() == ERROR_ACCESS_DENIED) {
-    pipeHandle = CreateFileW(name,
-                             GENERIC_READ | FILE_WRITE_ATTRIBUTES,
-                             0,
-                             NULL,
-                             OPEN_EXISTING,
-                             FILE_FLAG_OVERLAPPED,
-                             NULL);
-
-    if (pipeHandle != INVALID_HANDLE_VALUE) {
-      *duplex_flags = UV_HANDLE_READABLE;
-      return pipeHandle;
-    }
-  }
-
-  if (GetLastError() == ERROR_ACCESS_DENIED) {
-    pipeHandle = CreateFileW(name,
-                             GENERIC_WRITE | FILE_READ_ATTRIBUTES,
-                             0,
-                             NULL,
-                             OPEN_EXISTING,
-                             FILE_FLAG_OVERLAPPED,
-                             NULL);
-
-    if (pipeHandle != INVALID_HANDLE_VALUE) {
-      *duplex_flags = UV_HANDLE_WRITABLE;
-      return pipeHandle;
-    }
-  }
-
-  return INVALID_HANDLE_VALUE;
-}
-
-
-static void close_pipe(uv_pipe_t* pipe) {
-  assert(pipe->u.fd == -1 || pipe->u.fd > 2);
-  if (pipe->u.fd == -1)
-    CloseHandle(pipe->handle);
-  else
-    close(pipe->u.fd);
-
-  pipe->u.fd = -1;
-  pipe->handle = INVALID_HANDLE_VALUE;
-}
-
-
-int uv_stdio_pipe_server(uv_loop_t* loop, uv_pipe_t* handle, DWORD access,
-    char* name, size_t nameSize) {
-  HANDLE pipeHandle;
-  int err;
-  char* ptr = (char*)handle;
-
-  for (;;) {
-    uv_unique_pipe_name(ptr, name, nameSize);
-
-    pipeHandle = CreateNamedPipeA(name,
-      access | FILE_FLAG_OVERLAPPED | FILE_FLAG_FIRST_PIPE_INSTANCE | WRITE_DAC,
-      PIPE_TYPE_BYTE | PIPE_READMODE_BYTE | PIPE_WAIT, 1, 65536, 65536, 0,
-      NULL);
-
-    if (pipeHandle != INVALID_HANDLE_VALUE) {
-      /* No name collisions.  We're done. */
-      break;
-    }
-
-    err = GetLastError();
-    if (err != ERROR_PIPE_BUSY && err != ERROR_ACCESS_DENIED) {
-      goto error;
-    }
-
-    /* Pipe name collision.  Increment the pointer and try again. */
-    ptr++;
-  }
-
-  if (CreateIoCompletionPort(pipeHandle,
-                             loop->iocp,
-                             (ULONG_PTR)handle,
-                             0) == NULL) {
-    err = GetLastError();
-    goto error;
-  }
-
-  uv_pipe_connection_init(handle);
-  handle->handle = pipeHandle;
-
-  return 0;
-
- error:
-  if (pipeHandle != INVALID_HANDLE_VALUE) {
-    CloseHandle(pipeHandle);
-  }
-
-  return err;
-}
-
-
-static int uv_set_pipe_handle(uv_loop_t* loop,
-                              uv_pipe_t* handle,
-                              HANDLE pipeHandle,
-                              int fd,
-                              DWORD duplex_flags) {
-  NTSTATUS nt_status;
-  IO_STATUS_BLOCK io_status;
-  FILE_MODE_INFORMATION mode_info;
-  DWORD mode = PIPE_READMODE_BYTE | PIPE_WAIT;
-  DWORD current_mode = 0;
-  DWORD err = 0;
-
-  if (!(handle->flags & UV_HANDLE_PIPESERVER) &&
-      handle->handle != INVALID_HANDLE_VALUE)
-    return UV_EBUSY;
-
-  if (!SetNamedPipeHandleState(pipeHandle, &mode, NULL, NULL)) {
-    err = GetLastError();
-    if (err == ERROR_ACCESS_DENIED) {
-      /*
-       * SetNamedPipeHandleState can fail if the handle doesn't have either
-       * GENERIC_WRITE  or FILE_WRITE_ATTRIBUTES.
-       * But if the handle already has the desired wait and blocking modes
-       * we can continue.
-       */
-      if (!GetNamedPipeHandleState(pipeHandle, &current_mode, NULL, NULL,
-                                   NULL, NULL, 0)) {
-        return -1;
-      } else if (current_mode & PIPE_NOWAIT) {
-        SetLastError(ERROR_ACCESS_DENIED);
-        return -1;
-      }
-    } else {
-      /* If this returns ERROR_INVALID_PARAMETER we probably opened
-       * something that is not a pipe. */
-      if (err == ERROR_INVALID_PARAMETER) {
-        SetLastError(WSAENOTSOCK);
-      }
-      return -1;
-    }
-  }
-
-  /* Check if the pipe was created with FILE_FLAG_OVERLAPPED. */
-  nt_status = pNtQueryInformationFile(pipeHandle,
-                                      &io_status,
-                                      &mode_info,
-                                      sizeof(mode_info),
-                                      FileModeInformation);
-  if (nt_status != STATUS_SUCCESS) {
-    return -1;
-  }
-
-  if (mode_info.Mode & FILE_SYNCHRONOUS_IO_ALERT ||
-      mode_info.Mode & FILE_SYNCHRONOUS_IO_NONALERT) {
-    /* Non-overlapped pipe. */
-    handle->flags |= UV_HANDLE_NON_OVERLAPPED_PIPE;
-  } else {
-    /* Overlapped pipe.  Try to associate with IOCP. */
-    if (CreateIoCompletionPort(pipeHandle,
-                               loop->iocp,
-                               (ULONG_PTR)handle,
-                               0) == NULL) {
-      handle->flags |= UV_HANDLE_EMULATE_IOCP;
-    }
-  }
-
-  handle->handle = pipeHandle;
-  handle->u.fd = fd;
-  handle->flags |= duplex_flags;
-
-  return 0;
-}
-
-
-static DWORD WINAPI pipe_shutdown_thread_proc(void* parameter) {
-  uv_loop_t* loop;
-  uv_pipe_t* handle;
-  uv_shutdown_t* req;
-
-  req = (uv_shutdown_t*) parameter;
-  assert(req);
-  handle = (uv_pipe_t*) req->handle;
-  assert(handle);
-  loop = handle->loop;
-  assert(loop);
-
-  FlushFileBuffers(handle->handle);
-
-  /* Post completed */
-  POST_COMPLETION_FOR_REQ(loop, req);
-
-  return 0;
-}
-
-
-void uv_pipe_endgame(uv_loop_t* loop, uv_pipe_t* handle) {
-  int err;
-  DWORD result;
-  uv_shutdown_t* req;
-  NTSTATUS nt_status;
-  IO_STATUS_BLOCK io_status;
-  FILE_PIPE_LOCAL_INFORMATION pipe_info;
-  uv__ipc_xfer_queue_item_t* xfer_queue_item;
-
-  if ((handle->flags & UV_HANDLE_CONNECTION) &&
-      handle->stream.conn.shutdown_req != NULL &&
-      handle->stream.conn.write_reqs_pending == 0) {
-    req = handle->stream.conn.shutdown_req;
-
-    /* Clear the shutdown_req field so we don't go here again. */
-    handle->stream.conn.shutdown_req = NULL;
-
-    if (handle->flags & UV_HANDLE_CLOSING) {
-      UNREGISTER_HANDLE_REQ(loop, handle, req);
-
-      /* Already closing. Cancel the shutdown. */
-      if (req->cb) {
-        req->cb(req, UV_ECANCELED);
-      }
-
-      DECREASE_PENDING_REQ_COUNT(handle);
-      return;
-    }
-
-    /* Try to avoid flushing the pipe buffer in the thread pool. */
-    nt_status = pNtQueryInformationFile(handle->handle,
-                                        &io_status,
-                                        &pipe_info,
-                                        sizeof pipe_info,
-                                        FilePipeLocalInformation);
-
-    if (nt_status != STATUS_SUCCESS) {
-      /* Failure */
-      UNREGISTER_HANDLE_REQ(loop, handle, req);
-
-      handle->flags |= UV_HANDLE_WRITABLE; /* Questionable */
-      if (req->cb) {
-        err = pRtlNtStatusToDosError(nt_status);
-        req->cb(req, uv_translate_sys_error(err));
-      }
-
-      DECREASE_PENDING_REQ_COUNT(handle);
-      return;
-    }
-
-    if (pipe_info.OutboundQuota == pipe_info.WriteQuotaAvailable) {
-      /* Short-circuit, no need to call FlushFileBuffers. */
-      uv_insert_pending_req(loop, (uv_req_t*) req);
-      return;
-    }
-
-    /* Run FlushFileBuffers in the thread pool. */
-    result = QueueUserWorkItem(pipe_shutdown_thread_proc,
-                               req,
-                               WT_EXECUTELONGFUNCTION);
-    if (result) {
-      return;
-
-    } else {
-      /* Failure. */
-      UNREGISTER_HANDLE_REQ(loop, handle, req);
-
-      handle->flags |= UV_HANDLE_WRITABLE; /* Questionable */
-      if (req->cb) {
-        err = GetLastError();
-        req->cb(req, uv_translate_sys_error(err));
-      }
-
-      DECREASE_PENDING_REQ_COUNT(handle);
-      return;
-    }
-  }
-
-  if (handle->flags & UV_HANDLE_CLOSING &&
-      handle->reqs_pending == 0) {
-    assert(!(handle->flags & UV_HANDLE_CLOSED));
-
-    if (handle->flags & UV_HANDLE_CONNECTION) {
-      /* Free pending sockets */
-      while (!QUEUE_EMPTY(&handle->pipe.conn.ipc_xfer_queue)) {
-        QUEUE* q;
-        SOCKET socket;
-
-        q = QUEUE_HEAD(&handle->pipe.conn.ipc_xfer_queue);
-        QUEUE_REMOVE(q);
-        xfer_queue_item = QUEUE_DATA(q, uv__ipc_xfer_queue_item_t, member);
-
-        /* Materialize socket and close it */
-        socket = WSASocketW(FROM_PROTOCOL_INFO,
-                            FROM_PROTOCOL_INFO,
-                            FROM_PROTOCOL_INFO,
-                            &xfer_queue_item->xfer_info.socket_info,
-                            0,
-                            WSA_FLAG_OVERLAPPED);
-        uv__free(xfer_queue_item);
-
-        if (socket != INVALID_SOCKET)
-          closesocket(socket);
-      }
-      handle->pipe.conn.ipc_xfer_queue_length = 0;
-
-      if (handle->flags & UV_HANDLE_EMULATE_IOCP) {
-        if (handle->read_req.wait_handle != INVALID_HANDLE_VALUE) {
-          UnregisterWait(handle->read_req.wait_handle);
-          handle->read_req.wait_handle = INVALID_HANDLE_VALUE;
-        }
-        if (handle->read_req.event_handle) {
-          CloseHandle(handle->read_req.event_handle);
-          handle->read_req.event_handle = NULL;
-        }
-      }
-
-      if (handle->flags & UV_HANDLE_NON_OVERLAPPED_PIPE)
-        DeleteCriticalSection(&handle->pipe.conn.readfile_thread_lock);
-    }
-
-    if (handle->flags & UV_HANDLE_PIPESERVER) {
-      assert(handle->pipe.serv.accept_reqs);
-      uv__free(handle->pipe.serv.accept_reqs);
-      handle->pipe.serv.accept_reqs = NULL;
-    }
-
-    uv__handle_close(handle);
-  }
-}
-
-
-void uv_pipe_pending_instances(uv_pipe_t* handle, int count) {
-  if (handle->flags & UV_HANDLE_BOUND)
-    return;
-  handle->pipe.serv.pending_instances = count;
-  handle->flags |= UV_HANDLE_PIPESERVER;
-}
-
-
-/* Creates a pipe server. */
-int uv_pipe_bind(uv_pipe_t* handle, const char* name) {
-  uv_loop_t* loop = handle->loop;
-  int i, err, nameSize;
-  uv_pipe_accept_t* req;
-
-  if (handle->flags & UV_HANDLE_BOUND) {
-    return UV_EINVAL;
-  }
-
-  if (!name) {
-    return UV_EINVAL;
-  }
-
-  if (!(handle->flags & UV_HANDLE_PIPESERVER)) {
-    handle->pipe.serv.pending_instances = default_pending_pipe_instances;
-  }
-
-  handle->pipe.serv.accept_reqs = (uv_pipe_accept_t*)
-    uv__malloc(sizeof(uv_pipe_accept_t) * handle->pipe.serv.pending_instances);
-  if (!handle->pipe.serv.accept_reqs) {
-    uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
-  }
-
-  for (i = 0; i < handle->pipe.serv.pending_instances; i++) {
-    req = &handle->pipe.serv.accept_reqs[i];
-    UV_REQ_INIT(req, UV_ACCEPT);
-    req->data = handle;
-    req->pipeHandle = INVALID_HANDLE_VALUE;
-    req->next_pending = NULL;
-  }
-
-  /* Convert name to UTF16. */
-  nameSize = MultiByteToWideChar(CP_UTF8, 0, name, -1, NULL, 0) * sizeof(WCHAR);
-  handle->name = (WCHAR*)uv__malloc(nameSize);
-  if (!handle->name) {
-    uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
-  }
-
-  if (!MultiByteToWideChar(CP_UTF8,
-                           0,
-                           name,
-                           -1,
-                           handle->name,
-                           nameSize / sizeof(WCHAR))) {
-    err = GetLastError();
-    goto error;
-  }
-
-  /*
-   * Attempt to create the first pipe with FILE_FLAG_FIRST_PIPE_INSTANCE.
-   * If this fails then there's already a pipe server for the given pipe name.
-   */
-  handle->pipe.serv.accept_reqs[0].pipeHandle = CreateNamedPipeW(handle->name,
-      PIPE_ACCESS_DUPLEX | FILE_FLAG_OVERLAPPED |
-      FILE_FLAG_FIRST_PIPE_INSTANCE | WRITE_DAC,
-      PIPE_TYPE_BYTE | PIPE_READMODE_BYTE | PIPE_WAIT,
-      PIPE_UNLIMITED_INSTANCES, 65536, 65536, 0, NULL);
-
-  if (handle->pipe.serv.accept_reqs[0].pipeHandle == INVALID_HANDLE_VALUE) {
-    err = GetLastError();
-    if (err == ERROR_ACCESS_DENIED) {
-      err = WSAEADDRINUSE;  /* Translates to UV_EADDRINUSE. */
-    } else if (err == ERROR_PATH_NOT_FOUND || err == ERROR_INVALID_NAME) {
-      err = WSAEACCES;  /* Translates to UV_EACCES. */
-    }
-    goto error;
-  }
-
-  if (uv_set_pipe_handle(loop,
-                         handle,
-                         handle->pipe.serv.accept_reqs[0].pipeHandle,
-                         -1,
-                         0)) {
-    err = GetLastError();
-    goto error;
-  }
-
-  handle->pipe.serv.pending_accepts = NULL;
-  handle->flags |= UV_HANDLE_PIPESERVER;
-  handle->flags |= UV_HANDLE_BOUND;
-
-  return 0;
-
-error:
-  if (handle->name) {
-    uv__free(handle->name);
-    handle->name = NULL;
-  }
-
-  if (handle->pipe.serv.accept_reqs[0].pipeHandle != INVALID_HANDLE_VALUE) {
-    CloseHandle(handle->pipe.serv.accept_reqs[0].pipeHandle);
-    handle->pipe.serv.accept_reqs[0].pipeHandle = INVALID_HANDLE_VALUE;
-  }
-
-  return uv_translate_sys_error(err);
-}
-
-
-static DWORD WINAPI pipe_connect_thread_proc(void* parameter) {
-  uv_loop_t* loop;
-  uv_pipe_t* handle;
-  uv_connect_t* req;
-  HANDLE pipeHandle = INVALID_HANDLE_VALUE;
-  DWORD duplex_flags;
-
-  req = (uv_connect_t*) parameter;
-  assert(req);
-  handle = (uv_pipe_t*) req->handle;
-  assert(handle);
-  loop = handle->loop;
-  assert(loop);
-
-  /* We're here because CreateFile on a pipe returned ERROR_PIPE_BUSY. We wait
-   * for the pipe to become available with WaitNamedPipe. */
-  while (WaitNamedPipeW(handle->name, 30000)) {
-    /* The pipe is now available, try to connect. */
-    pipeHandle = open_named_pipe(handle->name, &duplex_flags);
-    if (pipeHandle != INVALID_HANDLE_VALUE) {
-      break;
-    }
-
-    SwitchToThread();
-  }
-
-  if (pipeHandle != INVALID_HANDLE_VALUE &&
-      !uv_set_pipe_handle(loop, handle, pipeHandle, -1, duplex_flags)) {
-    SET_REQ_SUCCESS(req);
-  } else {
-    SET_REQ_ERROR(req, GetLastError());
-  }
-
-  /* Post completed */
-  POST_COMPLETION_FOR_REQ(loop, req);
-
-  return 0;
-}
-
-
-void uv_pipe_connect(uv_connect_t* req, uv_pipe_t* handle,
-    const char* name, uv_connect_cb cb) {
-  uv_loop_t* loop = handle->loop;
-  int err, nameSize;
-  HANDLE pipeHandle = INVALID_HANDLE_VALUE;
-  DWORD duplex_flags;
-
-  UV_REQ_INIT(req, UV_CONNECT);
-  req->handle = (uv_stream_t*) handle;
-  req->cb = cb;
-
-  /* Convert name to UTF16. */
-  nameSize = MultiByteToWideChar(CP_UTF8, 0, name, -1, NULL, 0) * sizeof(WCHAR);
-  handle->name = (WCHAR*)uv__malloc(nameSize);
-  if (!handle->name) {
-    uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
-  }
-
-  if (!MultiByteToWideChar(CP_UTF8,
-                           0,
-                           name,
-                           -1,
-                           handle->name,
-                           nameSize / sizeof(WCHAR))) {
-    err = GetLastError();
-    goto error;
-  }
-
-  pipeHandle = open_named_pipe(handle->name, &duplex_flags);
-  if (pipeHandle == INVALID_HANDLE_VALUE) {
-    if (GetLastError() == ERROR_PIPE_BUSY) {
-      /* Wait for the server to make a pipe instance available. */
-      if (!QueueUserWorkItem(&pipe_connect_thread_proc,
-                             req,
-                             WT_EXECUTELONGFUNCTION)) {
-        err = GetLastError();
-        goto error;
-      }
-
-      REGISTER_HANDLE_REQ(loop, handle, req);
-      handle->reqs_pending++;
-
-      return;
-    }
-
-    err = GetLastError();
-    goto error;
-  }
-
-  assert(pipeHandle != INVALID_HANDLE_VALUE);
-
-  if (uv_set_pipe_handle(loop,
-                         (uv_pipe_t*) req->handle,
-                         pipeHandle,
-                         -1,
-                         duplex_flags)) {
-    err = GetLastError();
-    goto error;
-  }
-
-  SET_REQ_SUCCESS(req);
-  uv_insert_pending_req(loop, (uv_req_t*) req);
-  handle->reqs_pending++;
-  REGISTER_HANDLE_REQ(loop, handle, req);
-  return;
-
-error:
-  if (handle->name) {
-    uv__free(handle->name);
-    handle->name = NULL;
-  }
-
-  if (pipeHandle != INVALID_HANDLE_VALUE) {
-    CloseHandle(pipeHandle);
-  }
-
-  /* Make this req pending reporting an error. */
-  SET_REQ_ERROR(req, err);
-  uv_insert_pending_req(loop, (uv_req_t*) req);
-  handle->reqs_pending++;
-  REGISTER_HANDLE_REQ(loop, handle, req);
-  return;
-}
-
-
-void uv__pipe_interrupt_read(uv_pipe_t* handle) {
-  BOOL r;
-
-  if (!(handle->flags & UV_HANDLE_READ_PENDING))
-    return; /* No pending reads. */
-  if (handle->flags & UV_HANDLE_CANCELLATION_PENDING)
-    return; /* Already cancelled. */
-  if (handle->handle == INVALID_HANDLE_VALUE)
-    return; /* Pipe handle closed. */
-
-  if (!(handle->flags & UV_HANDLE_NON_OVERLAPPED_PIPE)) {
-    /* Cancel asynchronous read. */
-    r = CancelIoEx(handle->handle, &handle->read_req.u.io.overlapped);
-    assert(r || GetLastError() == ERROR_NOT_FOUND);
-
-  } else {
-    /* Cancel synchronous read (which is happening in the thread pool). */
-    HANDLE thread;
-    volatile HANDLE* thread_ptr = &handle->pipe.conn.readfile_thread_handle;
-
-    EnterCriticalSection(&handle->pipe.conn.readfile_thread_lock);
-
-    thread = *thread_ptr;
-    if (thread == NULL) {
-      /* The thread pool thread has not yet reached the point of blocking, we
-       * can pre-empt it by setting thread_handle to INVALID_HANDLE_VALUE. */
-      *thread_ptr = INVALID_HANDLE_VALUE;
-
-    } else {
-      /* Spin until the thread has acknowledged (by setting the thread to
-       * INVALID_HANDLE_VALUE) that it is past the point of blocking. */
-      while (thread != INVALID_HANDLE_VALUE) {
-        r = CancelSynchronousIo(thread);
-        assert(r || GetLastError() == ERROR_NOT_FOUND);
-        SwitchToThread(); /* Yield thread. */
-        thread = *thread_ptr;
-      }
-    }
-
-    LeaveCriticalSection(&handle->pipe.conn.readfile_thread_lock);
-  }
-
-  /* Set flag to indicate that read has been cancelled. */
-  handle->flags |= UV_HANDLE_CANCELLATION_PENDING;
-}
-
-
-void uv__pipe_read_stop(uv_pipe_t* handle) {
-  handle->flags &= ~UV_HANDLE_READING;
-  DECREASE_ACTIVE_COUNT(handle->loop, handle);
-
-  uv__pipe_interrupt_read(handle);
-}
-
-
-/* Cleans up uv_pipe_t (server or connection) and all resources associated with
- * it. */
-void uv_pipe_cleanup(uv_loop_t* loop, uv_pipe_t* handle) {
-  int i;
-  HANDLE pipeHandle;
-
-  uv__pipe_interrupt_read(handle);
-
-  if (handle->name) {
-    uv__free(handle->name);
-    handle->name = NULL;
-  }
-
-  if (handle->flags & UV_HANDLE_PIPESERVER) {
-    for (i = 0; i < handle->pipe.serv.pending_instances; i++) {
-      pipeHandle = handle->pipe.serv.accept_reqs[i].pipeHandle;
-      if (pipeHandle != INVALID_HANDLE_VALUE) {
-        CloseHandle(pipeHandle);
-        handle->pipe.serv.accept_reqs[i].pipeHandle = INVALID_HANDLE_VALUE;
-      }
-    }
-    handle->handle = INVALID_HANDLE_VALUE;
-  }
-
-  if (handle->flags & UV_HANDLE_CONNECTION) {
-    handle->flags &= ~UV_HANDLE_WRITABLE;
-    eof_timer_destroy(handle);
-  }
-
-  if ((handle->flags & UV_HANDLE_CONNECTION)
-      && handle->handle != INVALID_HANDLE_VALUE)
-    close_pipe(handle);
-}
-
-
-void uv_pipe_close(uv_loop_t* loop, uv_pipe_t* handle) {
-  if (handle->flags & UV_HANDLE_READING) {
-    handle->flags &= ~UV_HANDLE_READING;
-    DECREASE_ACTIVE_COUNT(loop, handle);
-  }
-
-  if (handle->flags & UV_HANDLE_LISTENING) {
-    handle->flags &= ~UV_HANDLE_LISTENING;
-    DECREASE_ACTIVE_COUNT(loop, handle);
-  }
-
-  uv_pipe_cleanup(loop, handle);
-
-  if (handle->reqs_pending == 0) {
-    uv_want_endgame(loop, (uv_handle_t*) handle);
-  }
-
-  handle->flags &= ~(UV_HANDLE_READABLE | UV_HANDLE_WRITABLE);
-  uv__handle_closing(handle);
-}
-
-
-static void uv_pipe_queue_accept(uv_loop_t* loop, uv_pipe_t* handle,
-    uv_pipe_accept_t* req, BOOL firstInstance) {
-  assert(handle->flags & UV_HANDLE_LISTENING);
-
-  if (!firstInstance) {
-    assert(req->pipeHandle == INVALID_HANDLE_VALUE);
-
-    req->pipeHandle = CreateNamedPipeW(handle->name,
-        PIPE_ACCESS_DUPLEX | FILE_FLAG_OVERLAPPED | WRITE_DAC,
-        PIPE_TYPE_BYTE | PIPE_READMODE_BYTE | PIPE_WAIT,
-        PIPE_UNLIMITED_INSTANCES, 65536, 65536, 0, NULL);
-
-    if (req->pipeHandle == INVALID_HANDLE_VALUE) {
-      SET_REQ_ERROR(req, GetLastError());
-      uv_insert_pending_req(loop, (uv_req_t*) req);
-      handle->reqs_pending++;
-      return;
-    }
-
-    if (uv_set_pipe_handle(loop, handle, req->pipeHandle, -1, 0)) {
-      CloseHandle(req->pipeHandle);
-      req->pipeHandle = INVALID_HANDLE_VALUE;
-      SET_REQ_ERROR(req, GetLastError());
-      uv_insert_pending_req(loop, (uv_req_t*) req);
-      handle->reqs_pending++;
-      return;
-    }
-  }
-
-  assert(req->pipeHandle != INVALID_HANDLE_VALUE);
-
-  /* Prepare the overlapped structure. */
-  memset(&(req->u.io.overlapped), 0, sizeof(req->u.io.overlapped));
-
-  if (!ConnectNamedPipe(req->pipeHandle, &req->u.io.overlapped) &&
-      GetLastError() != ERROR_IO_PENDING) {
-    if (GetLastError() == ERROR_PIPE_CONNECTED) {
-      SET_REQ_SUCCESS(req);
-    } else {
-      CloseHandle(req->pipeHandle);
-      req->pipeHandle = INVALID_HANDLE_VALUE;
-      /* Make this req pending reporting an error. */
-      SET_REQ_ERROR(req, GetLastError());
-    }
-    uv_insert_pending_req(loop, (uv_req_t*) req);
-    handle->reqs_pending++;
-    return;
-  }
-
-  /* Wait for completion via IOCP */
-  handle->reqs_pending++;
-}
-
-
-int uv_pipe_accept(uv_pipe_t* server, uv_stream_t* client) {
-  uv_loop_t* loop = server->loop;
-  uv_pipe_t* pipe_client;
-  uv_pipe_accept_t* req;
-  QUEUE* q;
-  uv__ipc_xfer_queue_item_t* item;
-  int err;
-
-  if (server->ipc) {
-    if (QUEUE_EMPTY(&server->pipe.conn.ipc_xfer_queue)) {
-      /* No valid pending sockets. */
-      return WSAEWOULDBLOCK;
-    }
-
-    q = QUEUE_HEAD(&server->pipe.conn.ipc_xfer_queue);
-    QUEUE_REMOVE(q);
-    server->pipe.conn.ipc_xfer_queue_length--;
-    item = QUEUE_DATA(q, uv__ipc_xfer_queue_item_t, member);
-
-    err = uv__tcp_xfer_import(
-        (uv_tcp_t*) client, item->xfer_type, &item->xfer_info);
-    if (err != 0)
-      return err;
-
-    uv__free(item);
-
-  } else {
-    pipe_client = (uv_pipe_t*)client;
-
-    /* Find a connection instance that has been connected, but not yet
-     * accepted. */
-    req = server->pipe.serv.pending_accepts;
-
-    if (!req) {
-      /* No valid connections found, so we error out. */
-      return WSAEWOULDBLOCK;
-    }
-
-    /* Initialize the client handle and copy the pipeHandle to the client */
-    uv_pipe_connection_init(pipe_client);
-    pipe_client->handle = req->pipeHandle;
-    pipe_client->flags |= UV_HANDLE_READABLE | UV_HANDLE_WRITABLE;
-
-    /* Prepare the req to pick up a new connection */
-    server->pipe.serv.pending_accepts = req->next_pending;
-    req->next_pending = NULL;
-    req->pipeHandle = INVALID_HANDLE_VALUE;
-
-    if (!(server->flags & UV_HANDLE_CLOSING)) {
-      uv_pipe_queue_accept(loop, server, req, FALSE);
-    }
-  }
-
-  return 0;
-}
-
-
-/* Starts listening for connections for the given pipe. */
-int uv_pipe_listen(uv_pipe_t* handle, int backlog, uv_connection_cb cb) {
-  uv_loop_t* loop = handle->loop;
-  int i;
-
-  if (handle->flags & UV_HANDLE_LISTENING) {
-    handle->stream.serv.connection_cb = cb;
-  }
-
-  if (!(handle->flags & UV_HANDLE_BOUND)) {
-    return WSAEINVAL;
-  }
-
-  if (handle->flags & UV_HANDLE_READING) {
-    return WSAEISCONN;
-  }
-
-  if (!(handle->flags & UV_HANDLE_PIPESERVER)) {
-    return ERROR_NOT_SUPPORTED;
-  }
-
-  handle->flags |= UV_HANDLE_LISTENING;
-  INCREASE_ACTIVE_COUNT(loop, handle);
-  handle->stream.serv.connection_cb = cb;
-
-  /* First pipe handle should have already been created in uv_pipe_bind */
-  assert(handle->pipe.serv.accept_reqs[0].pipeHandle != INVALID_HANDLE_VALUE);
-
-  for (i = 0; i < handle->pipe.serv.pending_instances; i++) {
-    uv_pipe_queue_accept(loop, handle, &handle->pipe.serv.accept_reqs[i], i == 0);
-  }
-
-  return 0;
-}
-
-
-static DWORD WINAPI uv_pipe_zero_readfile_thread_proc(void* arg) {
-  uv_read_t* req = (uv_read_t*) arg;
-  uv_pipe_t* handle = (uv_pipe_t*) req->data;
-  uv_loop_t* loop = handle->loop;
-  volatile HANDLE* thread_ptr = &handle->pipe.conn.readfile_thread_handle;
-  CRITICAL_SECTION* lock = &handle->pipe.conn.readfile_thread_lock;
-  HANDLE thread;
-  DWORD bytes;
-  DWORD err;
-
-  assert(req->type == UV_READ);
-  assert(handle->type == UV_NAMED_PIPE);
-
-  err = 0;
-
-  /* Create a handle to the current thread. */
-  if (!DuplicateHandle(GetCurrentProcess(),
-                       GetCurrentThread(),
-                       GetCurrentProcess(),
-                       &thread,
-                       0,
-                       FALSE,
-                       DUPLICATE_SAME_ACCESS)) {
-    err = GetLastError();
-    goto out1;
-  }
-
-  /* The lock needs to be held when thread handle is modified. */
-  EnterCriticalSection(lock);
-  if (*thread_ptr == INVALID_HANDLE_VALUE) {
-    /* uv__pipe_interrupt_read() cancelled reading before we got here. */
-    err = ERROR_OPERATION_ABORTED;
-  } else {
-    /* Let main thread know which worker thread is doing the blocking read. */
-    assert(*thread_ptr == NULL);
-    *thread_ptr = thread;
-  }
-  LeaveCriticalSection(lock);
-
-  if (err)
-    goto out2;
-
-  /* Block the thread until data is available on the pipe, or the read is
-   * cancelled. */
-  if (!ReadFile(handle->handle, &uv_zero_, 0, &bytes, NULL))
-    err = GetLastError();
-
-  /* Let the main thread know the worker is past the point of blocking. */
-  assert(thread == *thread_ptr);
-  *thread_ptr = INVALID_HANDLE_VALUE;
-
-  /* Briefly acquire the mutex. Since the main thread holds the lock while it
-   * is spinning trying to cancel this thread's I/O, we will block here until
-   * it stops doing that. */
-  EnterCriticalSection(lock);
-  LeaveCriticalSection(lock);
-
-out2:
-  /* Close the handle to the current thread. */
-  CloseHandle(thread);
-
-out1:
-  /* Set request status and post a completion record to the IOCP. */
-  if (err)
-    SET_REQ_ERROR(req, err);
-  else
-    SET_REQ_SUCCESS(req);
-  POST_COMPLETION_FOR_REQ(loop, req);
-
-  return 0;
-}
-
-
-static DWORD WINAPI uv_pipe_writefile_thread_proc(void* parameter) {
-  int result;
-  DWORD bytes;
-  uv_write_t* req = (uv_write_t*) parameter;
-  uv_pipe_t* handle = (uv_pipe_t*) req->handle;
-  uv_loop_t* loop = handle->loop;
-
-  assert(req != NULL);
-  assert(req->type == UV_WRITE);
-  assert(handle->type == UV_NAMED_PIPE);
-  assert(req->write_buffer.base);
-
-  result = WriteFile(handle->handle,
-                     req->write_buffer.base,
-                     req->write_buffer.len,
-                     &bytes,
-                     NULL);
-
-  if (!result) {
-    SET_REQ_ERROR(req, GetLastError());
-  }
-
-  POST_COMPLETION_FOR_REQ(loop, req);
-  return 0;
-}
-
-
-static void CALLBACK post_completion_read_wait(void* context, BOOLEAN timed_out) {
-  uv_read_t* req;
-  uv_tcp_t* handle;
-
-  req = (uv_read_t*) context;
-  assert(req != NULL);
-  handle = (uv_tcp_t*)req->data;
-  assert(handle != NULL);
-  assert(!timed_out);
-
-  if (!PostQueuedCompletionStatus(handle->loop->iocp,
-                                  req->u.io.overlapped.InternalHigh,
-                                  0,
-                                  &req->u.io.overlapped)) {
-    uv_fatal_error(GetLastError(), "PostQueuedCompletionStatus");
-  }
-}
-
-
-static void CALLBACK post_completion_write_wait(void* context, BOOLEAN timed_out) {
-  uv_write_t* req;
-  uv_tcp_t* handle;
-
-  req = (uv_write_t*) context;
-  assert(req != NULL);
-  handle = (uv_tcp_t*)req->handle;
-  assert(handle != NULL);
-  assert(!timed_out);
-
-  if (!PostQueuedCompletionStatus(handle->loop->iocp,
-                                  req->u.io.overlapped.InternalHigh,
-                                  0,
-                                  &req->u.io.overlapped)) {
-    uv_fatal_error(GetLastError(), "PostQueuedCompletionStatus");
-  }
-}
-
-
-static void uv_pipe_queue_read(uv_loop_t* loop, uv_pipe_t* handle) {
-  uv_read_t* req;
-  int result;
-
-  assert(handle->flags & UV_HANDLE_READING);
-  assert(!(handle->flags & UV_HANDLE_READ_PENDING));
-
-  assert(handle->handle != INVALID_HANDLE_VALUE);
-
-  req = &handle->read_req;
-
-  if (handle->flags & UV_HANDLE_NON_OVERLAPPED_PIPE) {
-    handle->pipe.conn.readfile_thread_handle = NULL; /* Reset cancellation. */
-    if (!QueueUserWorkItem(&uv_pipe_zero_readfile_thread_proc,
-                           req,
-                           WT_EXECUTELONGFUNCTION)) {
-      /* Make this req pending reporting an error. */
-      SET_REQ_ERROR(req, GetLastError());
-      goto error;
-    }
-  } else {
-    memset(&req->u.io.overlapped, 0, sizeof(req->u.io.overlapped));
-    if (handle->flags & UV_HANDLE_EMULATE_IOCP) {
-      req->u.io.overlapped.hEvent = (HANDLE) ((uintptr_t) req->event_handle | 1);
-    }
-
-    /* Do 0-read */
-    result = ReadFile(handle->handle,
-                      &uv_zero_,
-                      0,
-                      NULL,
-                      &req->u.io.overlapped);
-
-    if (!result && GetLastError() != ERROR_IO_PENDING) {
-      /* Make this req pending reporting an error. */
-      SET_REQ_ERROR(req, GetLastError());
-      goto error;
-    }
-
-    if (handle->flags & UV_HANDLE_EMULATE_IOCP) {
-      if (!req->event_handle) {
-        req->event_handle = CreateEvent(NULL, 0, 0, NULL);
-        if (!req->event_handle) {
-          uv_fatal_error(GetLastError(), "CreateEvent");
-        }
-      }
-      if (req->wait_handle == INVALID_HANDLE_VALUE) {
-        if (!RegisterWaitForSingleObject(&req->wait_handle,
-            req->u.io.overlapped.hEvent, post_completion_read_wait, (void*) req,
-            INFINITE, WT_EXECUTEINWAITTHREAD)) {
-          SET_REQ_ERROR(req, GetLastError());
-          goto error;
-        }
-      }
-    }
-  }
-
-  /* Start the eof timer if there is one */
-  eof_timer_start(handle);
-  handle->flags |= UV_HANDLE_READ_PENDING;
-  handle->reqs_pending++;
-  return;
-
-error:
-  uv_insert_pending_req(loop, (uv_req_t*)req);
-  handle->flags |= UV_HANDLE_READ_PENDING;
-  handle->reqs_pending++;
-}
-
-
-int uv_pipe_read_start(uv_pipe_t* handle,
-                       uv_alloc_cb alloc_cb,
-                       uv_read_cb read_cb) {
-  uv_loop_t* loop = handle->loop;
-
-  handle->flags |= UV_HANDLE_READING;
-  INCREASE_ACTIVE_COUNT(loop, handle);
-  handle->read_cb = read_cb;
-  handle->alloc_cb = alloc_cb;
-
-  /* If reading was stopped and then started again, there could still be a read
-   * request pending. */
-  if (!(handle->flags & UV_HANDLE_READ_PENDING))
-    uv_pipe_queue_read(loop, handle);
-
-  return 0;
-}
-
-
-static void uv_insert_non_overlapped_write_req(uv_pipe_t* handle,
-    uv_write_t* req) {
-  req->next_req = NULL;
-  if (handle->pipe.conn.non_overlapped_writes_tail) {
-    req->next_req =
-      handle->pipe.conn.non_overlapped_writes_tail->next_req;
-    handle->pipe.conn.non_overlapped_writes_tail->next_req = (uv_req_t*)req;
-    handle->pipe.conn.non_overlapped_writes_tail = req;
-  } else {
-    req->next_req = (uv_req_t*)req;
-    handle->pipe.conn.non_overlapped_writes_tail = req;
-  }
-}
-
-
-static uv_write_t* uv_remove_non_overlapped_write_req(uv_pipe_t* handle) {
-  uv_write_t* req;
-
-  if (handle->pipe.conn.non_overlapped_writes_tail) {
-    req = (uv_write_t*)handle->pipe.conn.non_overlapped_writes_tail->next_req;
-
-    if (req == handle->pipe.conn.non_overlapped_writes_tail) {
-      handle->pipe.conn.non_overlapped_writes_tail = NULL;
-    } else {
-      handle->pipe.conn.non_overlapped_writes_tail->next_req =
-        req->next_req;
-    }
-
-    return req;
-  } else {
-    /* queue empty */
-    return NULL;
-  }
-}
-
-
-static void uv_queue_non_overlapped_write(uv_pipe_t* handle) {
-  uv_write_t* req = uv_remove_non_overlapped_write_req(handle);
-  if (req) {
-    if (!QueueUserWorkItem(&uv_pipe_writefile_thread_proc,
-                           req,
-                           WT_EXECUTELONGFUNCTION)) {
-      uv_fatal_error(GetLastError(), "QueueUserWorkItem");
-    }
-  }
-}
-
-
-static int uv__build_coalesced_write_req(uv_write_t* user_req,
-                                         const uv_buf_t bufs[],
-                                         size_t nbufs,
-                                         uv_write_t** req_out,
-                                         uv_buf_t* write_buf_out) {
-  /* Pack into a single heap-allocated buffer:
-   *   (a) a uv_write_t structure where libuv stores the actual state.
-   *   (b) a pointer to the original uv_write_t.
-   *   (c) data from all `bufs` entries.
-   */
-  char* heap_buffer;
-  size_t heap_buffer_length, heap_buffer_offset;
-  uv__coalesced_write_t* coalesced_write_req; /* (a) + (b) */
-  char* data_start;                           /* (c) */
-  size_t data_length;
-  unsigned int i;
-
-  /* Compute combined size of all combined buffers from `bufs`. */
-  data_length = 0;
-  for (i = 0; i < nbufs; i++)
-    data_length += bufs[i].len;
-
-  /* The total combined size of data buffers should not exceed UINT32_MAX,
-   * because WriteFile() won't accept buffers larger than that. */
-  if (data_length > UINT32_MAX)
-    return WSAENOBUFS; /* Maps to UV_ENOBUFS. */
-
-  /* Compute heap buffer size. */
-  heap_buffer_length = sizeof *coalesced_write_req + /* (a) + (b) */
-                       data_length;                  /* (c) */
-
-  /* Allocate buffer. */
-  heap_buffer = (char*)uv__malloc(heap_buffer_length);
-  if (heap_buffer == NULL)
-    return ERROR_NOT_ENOUGH_MEMORY; /* Maps to UV_ENOMEM. */
-
-  /* Copy uv_write_t information to the buffer. */
-  coalesced_write_req = (uv__coalesced_write_t*) heap_buffer;
-  coalesced_write_req->req = *user_req; /* copy (a) */
-  coalesced_write_req->req.coalesced = 1;
-  coalesced_write_req->user_req = user_req;         /* copy (b) */
-  heap_buffer_offset = sizeof *coalesced_write_req; /* offset (a) + (b) */
-
-  /* Copy data buffers to the heap buffer. */
-  data_start = &heap_buffer[heap_buffer_offset];
-  for (i = 0; i < nbufs; i++) {
-    memcpy(&heap_buffer[heap_buffer_offset],
-           bufs[i].base,
-           bufs[i].len);               /* copy (c) */
-    heap_buffer_offset += bufs[i].len; /* offset (c) */
-  }
-  assert(heap_buffer_offset == heap_buffer_length);
-
-  /* Set out arguments and return. */
-  *req_out = &coalesced_write_req->req;
-  *write_buf_out = uv_buf_init(data_start, (unsigned int) data_length);
-  return 0;
-}
-
-
-static int uv__pipe_write_data(uv_loop_t* loop,
-                               uv_write_t* req,
-                               uv_pipe_t* handle,
-                               const uv_buf_t bufs[],
-                               size_t nbufs,
-                               uv_write_cb cb,
-                               int copy_always) {
-  int err;
-  int result;
-  uv_buf_t write_buf;
-
-  assert(handle->handle != INVALID_HANDLE_VALUE);
-
-  UV_REQ_INIT(req, UV_WRITE);
-  req->handle = (uv_stream_t*) handle;
-  req->send_handle = NULL;
-  req->cb = cb;
-  /* Private fields. */
-  req->coalesced = 0;
-  req->event_handle = NULL;
-  req->wait_handle = INVALID_HANDLE_VALUE;
-  memset(&req->u.io.overlapped, 0, sizeof(req->u.io.overlapped));
-  req->write_buffer = uv_null_buf_;
-
-  if (nbufs == 0) {
-    /* Write empty buffer. */
-    write_buf = uv_null_buf_;
-  } else if (nbufs == 1 && !copy_always) {
-    /* Write directly from bufs[0]. */
-    write_buf = bufs[0];
-  } else {
-    /* Coalesce all `bufs` into one big buffer. This also creates a new
-     * write-request structure that replaces the old one. */
-    err = uv__build_coalesced_write_req(req, bufs, nbufs, &req, &write_buf);
-    if (err != 0)
-      return err;
-  }
-
-  if ((handle->flags &
-      (UV_HANDLE_BLOCKING_WRITES | UV_HANDLE_NON_OVERLAPPED_PIPE)) ==
-      (UV_HANDLE_BLOCKING_WRITES | UV_HANDLE_NON_OVERLAPPED_PIPE)) {
-    DWORD bytes;
-    result =
-        WriteFile(handle->handle, write_buf.base, write_buf.len, &bytes, NULL);
-
-    if (!result) {
-      err = GetLastError();
-      return err;
-    } else {
-      /* Request completed immediately. */
-      req->u.io.queued_bytes = 0;
-    }
-
-    REGISTER_HANDLE_REQ(loop, handle, req);
-    handle->reqs_pending++;
-    handle->stream.conn.write_reqs_pending++;
-    POST_COMPLETION_FOR_REQ(loop, req);
-    return 0;
-  } else if (handle->flags & UV_HANDLE_NON_OVERLAPPED_PIPE) {
-    req->write_buffer = write_buf;
-    uv_insert_non_overlapped_write_req(handle, req);
-    if (handle->stream.conn.write_reqs_pending == 0) {
-      uv_queue_non_overlapped_write(handle);
-    }
-
-    /* Request queued by the kernel. */
-    req->u.io.queued_bytes = write_buf.len;
-    handle->write_queue_size += req->u.io.queued_bytes;
-  } else if (handle->flags & UV_HANDLE_BLOCKING_WRITES) {
-    /* Using overlapped IO, but wait for completion before returning */
-    req->u.io.overlapped.hEvent = CreateEvent(NULL, 1, 0, NULL);
-    if (!req->u.io.overlapped.hEvent) {
-      uv_fatal_error(GetLastError(), "CreateEvent");
-    }
-
-    result = WriteFile(handle->handle,
-                       write_buf.base,
-                       write_buf.len,
-                       NULL,
-                       &req->u.io.overlapped);
-
-    if (!result && GetLastError() != ERROR_IO_PENDING) {
-      err = GetLastError();
-      CloseHandle(req->u.io.overlapped.hEvent);
-      return err;
-    }
-
-    if (result) {
-      /* Request completed immediately. */
-      req->u.io.queued_bytes = 0;
-    } else {
-      /* Request queued by the kernel. */
-      req->u.io.queued_bytes = write_buf.len;
-      handle->write_queue_size += req->u.io.queued_bytes;
-      if (WaitForSingleObject(req->u.io.overlapped.hEvent, INFINITE) !=
-          WAIT_OBJECT_0) {
-        err = GetLastError();
-        CloseHandle(req->u.io.overlapped.hEvent);
-        return err;
-      }
-    }
-    CloseHandle(req->u.io.overlapped.hEvent);
-
-    REGISTER_HANDLE_REQ(loop, handle, req);
-    handle->reqs_pending++;
-    handle->stream.conn.write_reqs_pending++;
-    return 0;
-  } else {
-    result = WriteFile(handle->handle,
-                       write_buf.base,
-                       write_buf.len,
-                       NULL,
-                       &req->u.io.overlapped);
-
-    if (!result && GetLastError() != ERROR_IO_PENDING) {
-      return GetLastError();
-    }
-
-    if (result) {
-      /* Request completed immediately. */
-      req->u.io.queued_bytes = 0;
-    } else {
-      /* Request queued by the kernel. */
-      req->u.io.queued_bytes = write_buf.len;
-      handle->write_queue_size += req->u.io.queued_bytes;
-    }
-
-    if (handle->flags & UV_HANDLE_EMULATE_IOCP) {
-      req->event_handle = CreateEvent(NULL, 0, 0, NULL);
-      if (!req->event_handle) {
-        uv_fatal_error(GetLastError(), "CreateEvent");
-      }
-      if (!RegisterWaitForSingleObject(&req->wait_handle,
-          req->u.io.overlapped.hEvent, post_completion_write_wait, (void*) req,
-          INFINITE, WT_EXECUTEINWAITTHREAD)) {
-        return GetLastError();
-      }
-    }
-  }
-
-  REGISTER_HANDLE_REQ(loop, handle, req);
-  handle->reqs_pending++;
-  handle->stream.conn.write_reqs_pending++;
-
-  return 0;
-}
-
-
-static DWORD uv__pipe_get_ipc_remote_pid(uv_pipe_t* handle) {
-  DWORD* pid = &handle->pipe.conn.ipc_remote_pid;
-
-  /* If the both ends of the IPC pipe are owned by the same process,
-   * the remote end pid may not yet be set. If so, do it here.
-   * TODO: this is weird; it'd probably better to use a handshake. */
-  if (*pid == 0)
-    *pid = GetCurrentProcessId();
-
-  return *pid;
-}
-
-
-int uv__pipe_write_ipc(uv_loop_t* loop,
-                       uv_write_t* req,
-                       uv_pipe_t* handle,
-                       const uv_buf_t data_bufs[],
-                       size_t data_buf_count,
-                       uv_stream_t* send_handle,
-                       uv_write_cb cb) {
-  uv_buf_t stack_bufs[6];
-  uv_buf_t* bufs;
-  size_t buf_count, buf_index;
-  uv__ipc_frame_header_t frame_header;
-  uv__ipc_socket_xfer_type_t xfer_type = UV__IPC_SOCKET_XFER_NONE;
-  uv__ipc_socket_xfer_info_t xfer_info;
-  uint64_t data_length;
-  size_t i;
-  int err;
-
-  /* Compute the combined size of data buffers. */
-  data_length = 0;
-  for (i = 0; i < data_buf_count; i++)
-    data_length += data_bufs[i].len;
-  if (data_length > UINT32_MAX)
-    return WSAENOBUFS; /* Maps to UV_ENOBUFS. */
-
-  /* Prepare the frame's socket xfer payload. */
-  if (send_handle != NULL) {
-    uv_tcp_t* send_tcp_handle = (uv_tcp_t*) send_handle;
-
-    /* Verify that `send_handle` it is indeed a tcp handle. */
-    if (send_tcp_handle->type != UV_TCP)
-      return ERROR_NOT_SUPPORTED;
-
-    /* Export the tcp handle. */
-    err = uv__tcp_xfer_export(send_tcp_handle,
-                              uv__pipe_get_ipc_remote_pid(handle),
-                              &xfer_type,
-                              &xfer_info);
-    if (err != 0)
-      return err;
-  }
-
-  /* Compute the number of uv_buf_t's required. */
-  buf_count = 1 + data_buf_count; /* Frame header and data buffers. */
-  if (send_handle != NULL)
-    buf_count += 1; /* One extra for the socket xfer information. */
-
-  /* Use the on-stack buffer array if it is big enough; otherwise allocate
-   * space for it on the heap. */
-  if (buf_count < ARRAY_SIZE(stack_bufs)) {
-    /* Use on-stack buffer array. */
-    bufs = stack_bufs;
-  } else {
-    /* Use heap-allocated buffer array. */
-    bufs = (uv_buf_t*)uv__calloc(buf_count, sizeof(uv_buf_t));
-    if (bufs == NULL)
-      return ERROR_NOT_ENOUGH_MEMORY; /* Maps to UV_ENOMEM. */
-  }
-  buf_index = 0;
-
-  /* Initialize frame header and add it to the buffers list. */
-  memset(&frame_header, 0, sizeof frame_header);
-  bufs[buf_index++] = uv_buf_init((char*) &frame_header, sizeof frame_header);
-
-  if (send_handle != NULL) {
-    /* Add frame header flags. */
-    switch (xfer_type) {
-      case UV__IPC_SOCKET_XFER_TCP_CONNECTION:
-        frame_header.flags |= UV__IPC_FRAME_HAS_SOCKET_XFER |
-                              UV__IPC_FRAME_XFER_IS_TCP_CONNECTION;
-        break;
-      case UV__IPC_SOCKET_XFER_TCP_SERVER:
-        frame_header.flags |= UV__IPC_FRAME_HAS_SOCKET_XFER;
-        break;
-      default:
-        assert(0);  /* Unreachable. */
-    }
-    /* Add xfer info buffer. */
-    bufs[buf_index++] = uv_buf_init((char*) &xfer_info, sizeof xfer_info);
-  }
-
-  if (data_length > 0) {
-    /* Update frame header. */
-    frame_header.flags |= UV__IPC_FRAME_HAS_DATA;
-    frame_header.data_length = (uint32_t) data_length;
-    /* Add data buffers to buffers list. */
-    for (i = 0; i < data_buf_count; i++)
-      bufs[buf_index++] = data_bufs[i];
-  }
-
-  /* Write buffers. We set the `always_copy` flag, so it is not a problem that
-   * some of the written data lives on the stack. */
-  err = uv__pipe_write_data(loop, req, handle, bufs, buf_count, cb, 1);
-
-  /* If we had to heap-allocate the bufs array, free it now. */
-  if (bufs != stack_bufs) {
-    uv__free(bufs);
-  }
-
-  return err;
-}
-
-
-int uv__pipe_write(uv_loop_t* loop,
-                   uv_write_t* req,
-                   uv_pipe_t* handle,
-                   const uv_buf_t bufs[],
-                   size_t nbufs,
-                   uv_stream_t* send_handle,
-                   uv_write_cb cb) {
-  if (handle->ipc) {
-    /* IPC pipe write: use framing protocol. */
-    return uv__pipe_write_ipc(loop, req, handle, bufs, nbufs, send_handle, cb);
-  } else {
-    /* Non-IPC pipe write: put data on the wire directly. */
-    assert(send_handle == NULL);
-    return uv__pipe_write_data(loop, req, handle, bufs, nbufs, cb, 0);
-  }
-}
-
-
-static void uv_pipe_read_eof(uv_loop_t* loop, uv_pipe_t* handle,
-    uv_buf_t buf) {
-  /* If there is an eof timer running, we don't need it any more, so discard
-   * it. */
-  eof_timer_destroy(handle);
-
-  handle->flags &= ~UV_HANDLE_READABLE;
-  uv_read_stop((uv_stream_t*) handle);
-
-  handle->read_cb((uv_stream_t*) handle, UV_EOF, &buf);
-}
-
-
-static void uv_pipe_read_error(uv_loop_t* loop, uv_pipe_t* handle, int error,
-    uv_buf_t buf) {
-  /* If there is an eof timer running, we don't need it any more, so discard
-   * it. */
-  eof_timer_destroy(handle);
-
-  uv_read_stop((uv_stream_t*) handle);
-
-  handle->read_cb((uv_stream_t*)handle, uv_translate_sys_error(error), &buf);
-}
-
-
-static void uv_pipe_read_error_or_eof(uv_loop_t* loop, uv_pipe_t* handle,
-    int error, uv_buf_t buf) {
-  if (error == ERROR_BROKEN_PIPE) {
-    uv_pipe_read_eof(loop, handle, buf);
-  } else {
-    uv_pipe_read_error(loop, handle, error, buf);
-  }
-}
-
-
-static void uv__pipe_queue_ipc_xfer_info(
-    uv_pipe_t* handle,
-    uv__ipc_socket_xfer_type_t xfer_type,
-    uv__ipc_socket_xfer_info_t* xfer_info) {
-  uv__ipc_xfer_queue_item_t* item;
-
-  item = (uv__ipc_xfer_queue_item_t*) uv__malloc(sizeof(*item));
-  if (item == NULL)
-    uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
-
-  item->xfer_type = xfer_type;
-  item->xfer_info = *xfer_info;
-
-  QUEUE_INSERT_TAIL(&handle->pipe.conn.ipc_xfer_queue, &item->member);
-  handle->pipe.conn.ipc_xfer_queue_length++;
-}
-
-
-/* Read an exact number of bytes from a pipe. If an error or end-of-file is
- * encountered before the requested number of bytes are read, an error is
- * returned. */
-static int uv__pipe_read_exactly(HANDLE h, void* buffer, DWORD count) {
-  DWORD bytes_read, bytes_read_now;
-
-  bytes_read = 0;
-  while (bytes_read < count) {
-    if (!ReadFile(h,
-                  (char*) buffer + bytes_read,
-                  count - bytes_read,
-                  &bytes_read_now,
-                  NULL)) {
-      return GetLastError();
-    }
-
-    bytes_read += bytes_read_now;
-  }
-
-  assert(bytes_read == count);
-  return 0;
-}
-
-
-static DWORD uv__pipe_read_data(uv_loop_t* loop,
-                                uv_pipe_t* handle,
-                                DWORD suggested_bytes,
-                                DWORD max_bytes) {
-  DWORD bytes_read;
-  uv_buf_t buf;
-
-  /* Ask the user for a buffer to read data into. */
-  buf = uv_buf_init(NULL, 0);
-  handle->alloc_cb((uv_handle_t*) handle, suggested_bytes, &buf);
-  if (buf.base == NULL || buf.len == 0) {
-    handle->read_cb((uv_stream_t*) handle, UV_ENOBUFS, &buf);
-    return 0; /* Break out of read loop. */
-  }
-
-  /* Ensure we read at most the smaller of:
-   *   (a) the length of the user-allocated buffer.
-   *   (b) the maximum data length as specified by the `max_bytes` argument.
-   */
-  if (max_bytes > buf.len)
-    max_bytes = buf.len;
-
-  /* Read into the user buffer. */
-  if (!ReadFile(handle->handle, buf.base, max_bytes, &bytes_read, NULL)) {
-    uv_pipe_read_error_or_eof(loop, handle, GetLastError(), buf);
-    return 0; /* Break out of read loop. */
-  }
-
-  /* Call the read callback. */
-  handle->read_cb((uv_stream_t*) handle, bytes_read, &buf);
-
-  return bytes_read;
-}
-
-
-static DWORD uv__pipe_read_ipc(uv_loop_t* loop, uv_pipe_t* handle) {
-  uint32_t* data_remaining = &handle->pipe.conn.ipc_data_frame.payload_remaining;
-  int err;
-
-  if (*data_remaining > 0) {
-    /* Read frame data payload. */
-    DWORD bytes_read =
-        uv__pipe_read_data(loop, handle, *data_remaining, *data_remaining);
-    *data_remaining -= bytes_read;
-    return bytes_read;
-
-  } else {
-    /* Start of a new IPC frame. */
-    uv__ipc_frame_header_t frame_header;
-    uint32_t xfer_flags;
-    uv__ipc_socket_xfer_type_t xfer_type;
-    uv__ipc_socket_xfer_info_t xfer_info;
-
-    /* Read the IPC frame header. */
-    err = uv__pipe_read_exactly(
-        handle->handle, &frame_header, sizeof frame_header);
-    if (err)
-      goto error;
-
-    /* Validate that flags are valid. */
-    if ((frame_header.flags & ~UV__IPC_FRAME_VALID_FLAGS) != 0)
-      goto invalid;
-    /* Validate that reserved2 is zero. */
-    if (frame_header.reserved2 != 0)
-      goto invalid;
-
-    /* Parse xfer flags. */
-    xfer_flags = frame_header.flags & UV__IPC_FRAME_XFER_FLAGS;
-    if (xfer_flags & UV__IPC_FRAME_HAS_SOCKET_XFER) {
-      /* Socket coming -- determine the type. */
-      xfer_type = xfer_flags & UV__IPC_FRAME_XFER_IS_TCP_CONNECTION
-                      ? UV__IPC_SOCKET_XFER_TCP_CONNECTION
-                      : UV__IPC_SOCKET_XFER_TCP_SERVER;
-    } else if (xfer_flags == 0) {
-      /* No socket. */
-      xfer_type = UV__IPC_SOCKET_XFER_NONE;
-    } else {
-      /* Invalid flags. */
-      goto invalid;
-    }
-
-    /* Parse data frame information. */
-    if (frame_header.flags & UV__IPC_FRAME_HAS_DATA) {
-      *data_remaining = frame_header.data_length;
-    } else if (frame_header.data_length != 0) {
-      /* Data length greater than zero but data flag not set -- invalid. */
-      goto invalid;
-    }
-
-    /* If no socket xfer info follows, return here. Data will be read in a
-     * subsequent invocation of uv__pipe_read_ipc(). */
-    if (xfer_type == UV__IPC_SOCKET_XFER_NONE)
-      return sizeof frame_header; /* Number of bytes read. */
-
-    /* Read transferred socket information. */
-    err = uv__pipe_read_exactly(handle->handle, &xfer_info, sizeof xfer_info);
-    if (err)
-      goto error;
-
-    /* Store the pending socket info. */
-    uv__pipe_queue_ipc_xfer_info(handle, xfer_type, &xfer_info);
-
-    /* Return number of bytes read. */
-    return sizeof frame_header + sizeof xfer_info;
-  }
-
-invalid:
-  /* Invalid frame. */
-  err = WSAECONNABORTED; /* Maps to UV_ECONNABORTED. */
-
-error:
-  uv_pipe_read_error_or_eof(loop, handle, err, uv_null_buf_);
-  return 0; /* Break out of read loop. */
-}
-
-
-void uv_process_pipe_read_req(uv_loop_t* loop,
-                              uv_pipe_t* handle,
-                              uv_req_t* req) {
-  assert(handle->type == UV_NAMED_PIPE);
-
-  handle->flags &= ~(UV_HANDLE_READ_PENDING | UV_HANDLE_CANCELLATION_PENDING);
-  DECREASE_PENDING_REQ_COUNT(handle);
-  eof_timer_stop(handle);
-
-  /* At this point, we're done with bookkeeping. If the user has stopped
-   * reading the pipe in the meantime, there is nothing left to do, since there
-   * is no callback that we can call. */
-  if (!(handle->flags & UV_HANDLE_READING))
-    return;
-
-  if (!REQ_SUCCESS(req)) {
-    /* An error occurred doing the zero-read. */
-    DWORD err = GET_REQ_ERROR(req);
-
-    /* If the read was cancelled by uv__pipe_interrupt_read(), the request may
-     * indicate an ERROR_OPERATION_ABORTED error. This error isn't relevant to
-     * the user; we'll start a new zero-read at the end of this function. */
-    if (err != ERROR_OPERATION_ABORTED)
-      uv_pipe_read_error_or_eof(loop, handle, err, uv_null_buf_);
-
-  } else {
-    /* The zero-read completed without error, indicating there is data
-     * available in the kernel buffer. */
-    DWORD avail;
-
-    /* Get the number of bytes available. */
-    avail = 0;
-    if (!PeekNamedPipe(handle->handle, NULL, 0, NULL, &avail, NULL))
-      uv_pipe_read_error_or_eof(loop, handle, GetLastError(), uv_null_buf_);
-
-    /* Read until we've either read all the bytes available, or the 'reading'
-     * flag is cleared. */
-    while (avail > 0 && handle->flags & UV_HANDLE_READING) {
-      /* Depending on the type of pipe, read either IPC frames or raw data. */
-      DWORD bytes_read =
-          handle->ipc ? uv__pipe_read_ipc(loop, handle)
-                      : uv__pipe_read_data(loop, handle, avail, (DWORD) -1);
-
-      /* If no bytes were read, treat this as an indication that an error
-       * occurred, and break out of the read loop. */
-      if (bytes_read == 0)
-        break;
-
-      /* It is possible that more bytes were read than we thought were
-       * available. To prevent `avail` from underflowing, break out of the loop
-       * if this is the case. */
-      if (bytes_read > avail)
-        break;
-
-      /* Recompute the number of bytes available. */
-      avail -= bytes_read;
-    }
-  }
-
-  /* Start another zero-read request if necessary. */
-  if ((handle->flags & UV_HANDLE_READING) &&
-      !(handle->flags & UV_HANDLE_READ_PENDING)) {
-    uv_pipe_queue_read(loop, handle);
-  }
-}
-
-
-void uv_process_pipe_write_req(uv_loop_t* loop, uv_pipe_t* handle,
-    uv_write_t* req) {
-  int err;
-
-  assert(handle->type == UV_NAMED_PIPE);
-
-  assert(handle->write_queue_size >= req->u.io.queued_bytes);
-  handle->write_queue_size -= req->u.io.queued_bytes;
-
-  UNREGISTER_HANDLE_REQ(loop, handle, req);
-
-  if (handle->flags & UV_HANDLE_EMULATE_IOCP) {
-    if (req->wait_handle != INVALID_HANDLE_VALUE) {
-      UnregisterWait(req->wait_handle);
-      req->wait_handle = INVALID_HANDLE_VALUE;
-    }
-    if (req->event_handle) {
-      CloseHandle(req->event_handle);
-      req->event_handle = NULL;
-    }
-  }
-
-  err = GET_REQ_ERROR(req);
-
-  /* If this was a coalesced write, extract pointer to the user_provided
-   * uv_write_t structure so we can pass the expected pointer to the callback,
-   * then free the heap-allocated write req. */
-  if (req->coalesced) {
-    uv__coalesced_write_t* coalesced_write =
-        container_of(req, uv__coalesced_write_t, req);
-    req = coalesced_write->user_req;
-    uv__free(coalesced_write);
-  }
-  if (req->cb) {
-    req->cb(req, uv_translate_sys_error(err));
-  }
-
-  handle->stream.conn.write_reqs_pending--;
-
-  if (handle->flags & UV_HANDLE_NON_OVERLAPPED_PIPE &&
-      handle->pipe.conn.non_overlapped_writes_tail) {
-    assert(handle->stream.conn.write_reqs_pending > 0);
-    uv_queue_non_overlapped_write(handle);
-  }
-
-  if (handle->stream.conn.shutdown_req != NULL &&
-      handle->stream.conn.write_reqs_pending == 0) {
-    uv_want_endgame(loop, (uv_handle_t*)handle);
-  }
-
-  DECREASE_PENDING_REQ_COUNT(handle);
-}
-
-
-void uv_process_pipe_accept_req(uv_loop_t* loop, uv_pipe_t* handle,
-    uv_req_t* raw_req) {
-  uv_pipe_accept_t* req = (uv_pipe_accept_t*) raw_req;
-
-  assert(handle->type == UV_NAMED_PIPE);
-
-  if (handle->flags & UV_HANDLE_CLOSING) {
-    /* The req->pipeHandle should be freed already in uv_pipe_cleanup(). */
-    assert(req->pipeHandle == INVALID_HANDLE_VALUE);
-    DECREASE_PENDING_REQ_COUNT(handle);
-    return;
-  }
-
-  if (REQ_SUCCESS(req)) {
-    assert(req->pipeHandle != INVALID_HANDLE_VALUE);
-    req->next_pending = handle->pipe.serv.pending_accepts;
-    handle->pipe.serv.pending_accepts = req;
-
-    if (handle->stream.serv.connection_cb) {
-      handle->stream.serv.connection_cb((uv_stream_t*)handle, 0);
-    }
-  } else {
-    if (req->pipeHandle != INVALID_HANDLE_VALUE) {
-      CloseHandle(req->pipeHandle);
-      req->pipeHandle = INVALID_HANDLE_VALUE;
-    }
-    if (!(handle->flags & UV_HANDLE_CLOSING)) {
-      uv_pipe_queue_accept(loop, handle, req, FALSE);
-    }
-  }
-
-  DECREASE_PENDING_REQ_COUNT(handle);
-}
-
-
-void uv_process_pipe_connect_req(uv_loop_t* loop, uv_pipe_t* handle,
-    uv_connect_t* req) {
-  int err;
-
-  assert(handle->type == UV_NAMED_PIPE);
-
-  UNREGISTER_HANDLE_REQ(loop, handle, req);
-
-  if (req->cb) {
-    err = 0;
-    if (REQ_SUCCESS(req)) {
-      uv_pipe_connection_init(handle);
-    } else {
-      err = GET_REQ_ERROR(req);
-    }
-    req->cb(req, uv_translate_sys_error(err));
-  }
-
-  DECREASE_PENDING_REQ_COUNT(handle);
-}
-
-
-void uv_process_pipe_shutdown_req(uv_loop_t* loop, uv_pipe_t* handle,
-    uv_shutdown_t* req) {
-  assert(handle->type == UV_NAMED_PIPE);
-
-  UNREGISTER_HANDLE_REQ(loop, handle, req);
-
-  if (handle->flags & UV_HANDLE_READABLE) {
-    /* Initialize and optionally start the eof timer. Only do this if the pipe
-     * is readable and we haven't seen EOF come in ourselves. */
-    eof_timer_init(handle);
-
-    /* If reading start the timer right now. Otherwise uv_pipe_queue_read will
-     * start it. */
-    if (handle->flags & UV_HANDLE_READ_PENDING) {
-      eof_timer_start(handle);
-    }
-
-  } else {
-    /* This pipe is not readable. We can just close it to let the other end
-     * know that we're done writing. */
-    close_pipe(handle);
-  }
-
-  if (req->cb) {
-    req->cb(req, 0);
-  }
-
-  DECREASE_PENDING_REQ_COUNT(handle);
-}
-
-
-static void eof_timer_init(uv_pipe_t* pipe) {
-  int r;
-
-  assert(pipe->pipe.conn.eof_timer == NULL);
-  assert(pipe->flags & UV_HANDLE_CONNECTION);
-
-  pipe->pipe.conn.eof_timer = (uv_timer_t*) uv__malloc(sizeof *pipe->pipe.conn.eof_timer);
-
-  r = uv_timer_init(pipe->loop, pipe->pipe.conn.eof_timer);
-  assert(r == 0); /* timers can't fail */
-  pipe->pipe.conn.eof_timer->data = pipe;
-  uv_unref((uv_handle_t*) pipe->pipe.conn.eof_timer);
-}
-
-
-static void eof_timer_start(uv_pipe_t* pipe) {
-  assert(pipe->flags & UV_HANDLE_CONNECTION);
-
-  if (pipe->pipe.conn.eof_timer != NULL) {
-    uv_timer_start(pipe->pipe.conn.eof_timer, eof_timer_cb, eof_timeout, 0);
-  }
-}
-
-
-static void eof_timer_stop(uv_pipe_t* pipe) {
-  assert(pipe->flags & UV_HANDLE_CONNECTION);
-
-  if (pipe->pipe.conn.eof_timer != NULL) {
-    uv_timer_stop(pipe->pipe.conn.eof_timer);
-  }
-}
-
-
-static void eof_timer_cb(uv_timer_t* timer) {
-  uv_pipe_t* pipe = (uv_pipe_t*) timer->data;
-  uv_loop_t* loop = timer->loop;
-
-  assert(pipe->type == UV_NAMED_PIPE);
-
-  /* This should always be true, since we start the timer only in
-   * uv_pipe_queue_read after successfully calling ReadFile, or in
-   * uv_process_pipe_shutdown_req if a read is pending, and we always
-   * immediately stop the timer in uv_process_pipe_read_req. */
-  assert(pipe->flags & UV_HANDLE_READ_PENDING);
-
-  /* If there are many packets coming off the iocp then the timer callback may
-   * be called before the read request is coming off the queue. Therefore we
-   * check here if the read request has completed but will be processed later.
-   */
-  if ((pipe->flags & UV_HANDLE_READ_PENDING) &&
-      HasOverlappedIoCompleted(&pipe->read_req.u.io.overlapped)) {
-    return;
-  }
-
-  /* Force both ends off the pipe. */
-  close_pipe(pipe);
-
-  /* Stop reading, so the pending read that is going to fail will not be
-   * reported to the user. */
-  uv_read_stop((uv_stream_t*) pipe);
-
-  /* Report the eof and update flags. This will get reported even if the user
-   * stopped reading in the meantime. TODO: is that okay? */
-  uv_pipe_read_eof(loop, pipe, uv_null_buf_);
-}
-
-
-static void eof_timer_destroy(uv_pipe_t* pipe) {
-  assert(pipe->flags & UV_HANDLE_CONNECTION);
-
-  if (pipe->pipe.conn.eof_timer) {
-    uv_close((uv_handle_t*) pipe->pipe.conn.eof_timer, eof_timer_close_cb);
-    pipe->pipe.conn.eof_timer = NULL;
-  }
-}
-
-
-static void eof_timer_close_cb(uv_handle_t* handle) {
-  assert(handle->type == UV_TIMER);
-  uv__free(handle);
-}
-
-
-int uv_pipe_open(uv_pipe_t* pipe, uv_file file) {
-  HANDLE os_handle = uv__get_osfhandle(file);
-  NTSTATUS nt_status;
-  IO_STATUS_BLOCK io_status;
-  FILE_ACCESS_INFORMATION access;
-  DWORD duplex_flags = 0;
-
-  if (os_handle == INVALID_HANDLE_VALUE)
-    return UV_EBADF;
-
-  uv__once_init();
-  /* In order to avoid closing a stdio file descriptor 0-2, duplicate the
-   * underlying OS handle and forget about the original fd.
-   * We could also opt to use the original OS handle and just never close it,
-   * but then there would be no reliable way to cancel pending read operations
-   * upon close.
-   */
-  if (file <= 2) {
-    if (!DuplicateHandle(INVALID_HANDLE_VALUE,
-                         os_handle,
-                         INVALID_HANDLE_VALUE,
-                         &os_handle,
-                         0,
-                         FALSE,
-                         DUPLICATE_SAME_ACCESS))
-      return uv_translate_sys_error(GetLastError());
-    file = -1;
-  }
-
-  /* Determine what kind of permissions we have on this handle.
-   * Cygwin opens the pipe in message mode, but we can support it,
-   * just query the access flags and set the stream flags accordingly.
-   */
-  nt_status = pNtQueryInformationFile(os_handle,
-                                      &io_status,
-                                      &access,
-                                      sizeof(access),
-                                      FileAccessInformation);
-  if (nt_status != STATUS_SUCCESS)
-    return UV_EINVAL;
-
-  if (pipe->ipc) {
-    if (!(access.AccessFlags & FILE_WRITE_DATA) ||
-        !(access.AccessFlags & FILE_READ_DATA)) {
-      return UV_EINVAL;
-    }
-  }
-
-  if (access.AccessFlags & FILE_WRITE_DATA)
-    duplex_flags |= UV_HANDLE_WRITABLE;
-  if (access.AccessFlags & FILE_READ_DATA)
-    duplex_flags |= UV_HANDLE_READABLE;
-
-  if (os_handle == INVALID_HANDLE_VALUE ||
-      uv_set_pipe_handle(pipe->loop,
-                         pipe,
-                         os_handle,
-                         file,
-                         duplex_flags) == -1) {
-    return UV_EINVAL;
-  }
-
-  uv_pipe_connection_init(pipe);
-
-  if (pipe->ipc) {
-    assert(!(pipe->flags & UV_HANDLE_NON_OVERLAPPED_PIPE));
-    pipe->pipe.conn.ipc_remote_pid = uv_os_getppid();
-    assert(pipe->pipe.conn.ipc_remote_pid != (DWORD) -1);
-  }
-  return 0;
-}
-
-
-static int uv__pipe_getname(const uv_pipe_t* handle, char* buffer, size_t* size) {
-  NTSTATUS nt_status;
-  IO_STATUS_BLOCK io_status;
-  FILE_NAME_INFORMATION tmp_name_info;
-  FILE_NAME_INFORMATION* name_info;
-  WCHAR* name_buf;
-  unsigned int addrlen;
-  unsigned int name_size;
-  unsigned int name_len;
-  int err;
-
-  uv__once_init();
-  name_info = NULL;
-
-  if (handle->handle == INVALID_HANDLE_VALUE) {
-    *size = 0;
-    return UV_EINVAL;
-  }
-
-  /* NtQueryInformationFile will block if another thread is performing a
-   * blocking operation on the queried handle. If the pipe handle is
-   * synchronous, there may be a worker thread currently calling ReadFile() on
-   * the pipe handle, which could cause a deadlock. To avoid this, interrupt
-   * the read. */
-  if (handle->flags & UV_HANDLE_CONNECTION &&
-      handle->flags & UV_HANDLE_NON_OVERLAPPED_PIPE) {
-    uv__pipe_interrupt_read((uv_pipe_t*) handle); /* cast away const warning */
-  }
-
-  nt_status = pNtQueryInformationFile(handle->handle,
-                                      &io_status,
-                                      &tmp_name_info,
-                                      sizeof tmp_name_info,
-                                      FileNameInformation);
-  if (nt_status == STATUS_BUFFER_OVERFLOW) {
-    name_size = sizeof(*name_info) + tmp_name_info.FileNameLength;
-    name_info = (FILE_NAME_INFORMATION*)uv__malloc(name_size);
-    if (!name_info) {
-      *size = 0;
-      err = UV_ENOMEM;
-      goto cleanup;
-    }
-
-    nt_status = pNtQueryInformationFile(handle->handle,
-                                        &io_status,
-                                        name_info,
-                                        name_size,
-                                        FileNameInformation);
-  }
-
-  if (nt_status != STATUS_SUCCESS) {
-    *size = 0;
-    err = uv_translate_sys_error(pRtlNtStatusToDosError(nt_status));
-    goto error;
-  }
-
-  if (!name_info) {
-    /* the struct on stack was used */
-    name_buf = tmp_name_info.FileName;
-    name_len = tmp_name_info.FileNameLength;
-  } else {
-    name_buf = name_info->FileName;
-    name_len = name_info->FileNameLength;
-  }
-
-  if (name_len == 0) {
-    *size = 0;
-    err = 0;
-    goto error;
-  }
-
-  name_len /= sizeof(WCHAR);
-
-  /* check how much space we need */
-  addrlen = WideCharToMultiByte(CP_UTF8,
-                                0,
-                                name_buf,
-                                name_len,
-                                NULL,
-                                0,
-                                NULL,
-                                NULL);
-  if (!addrlen) {
-    *size = 0;
-    err = uv_translate_sys_error(GetLastError());
-    goto error;
-  } else if (pipe_prefix_len + addrlen >= *size) {
-    /* "\\\\.\\pipe" + name */
-    *size = pipe_prefix_len + addrlen + 1;
-    err = UV_ENOBUFS;
-    goto error;
-  }
-
-  memcpy(buffer, pipe_prefix, pipe_prefix_len);
-  addrlen = WideCharToMultiByte(CP_UTF8,
-                                0,
-                                name_buf,
-                                name_len,
-                                buffer+pipe_prefix_len,
-                                *size-pipe_prefix_len,
-                                NULL,
-                                NULL);
-  if (!addrlen) {
-    *size = 0;
-    err = uv_translate_sys_error(GetLastError());
-    goto error;
-  }
-
-  addrlen += pipe_prefix_len;
-  *size = addrlen;
-  buffer[addrlen] = '\0';
-
-  err = 0;
-
-error:
-  uv__free(name_info);
-
-cleanup:
-  return err;
-}
-
-
-int uv_pipe_pending_count(uv_pipe_t* handle) {
-  if (!handle->ipc)
-    return 0;
-  return handle->pipe.conn.ipc_xfer_queue_length;
-}
-
-
-int uv_pipe_getsockname(const uv_pipe_t* handle, char* buffer, size_t* size) {
-  if (handle->flags & UV_HANDLE_BOUND)
-    return uv__pipe_getname(handle, buffer, size);
-
-  if (handle->flags & UV_HANDLE_CONNECTION ||
-      handle->handle != INVALID_HANDLE_VALUE) {
-    *size = 0;
-    return 0;
-  }
-
-  return UV_EBADF;
-}
-
-
-int uv_pipe_getpeername(const uv_pipe_t* handle, char* buffer, size_t* size) {
-  /* emulate unix behaviour */
-  if (handle->flags & UV_HANDLE_BOUND)
-    return UV_ENOTCONN;
-
-  if (handle->handle != INVALID_HANDLE_VALUE)
-    return uv__pipe_getname(handle, buffer, size);
-
-  return UV_EBADF;
-}
-
-
-uv_handle_type uv_pipe_pending_type(uv_pipe_t* handle) {
-  if (!handle->ipc)
-    return UV_UNKNOWN_HANDLE;
-  if (handle->pipe.conn.ipc_xfer_queue_length == 0)
-    return UV_UNKNOWN_HANDLE;
-  else
-    return UV_TCP;
-}
-
-int uv_pipe_chmod(uv_pipe_t* handle, int mode) {
-  SID_IDENTIFIER_AUTHORITY sid_world = { SECURITY_WORLD_SID_AUTHORITY };
-  PACL old_dacl, new_dacl;
-  PSECURITY_DESCRIPTOR sd;
-  EXPLICIT_ACCESS ea;
-  PSID everyone;
-  int error;
-
-  if (handle == NULL || handle->handle == INVALID_HANDLE_VALUE)
-    return UV_EBADF;
-
-  if (mode != UV_READABLE &&
-      mode != UV_WRITABLE &&
-      mode != (UV_WRITABLE | UV_READABLE))
-    return UV_EINVAL;
-
-  if (!AllocateAndInitializeSid(&sid_world,
-                                1,
-                                SECURITY_WORLD_RID,
-                                0, 0, 0, 0, 0, 0, 0,
-                                &everyone)) {
-    error = GetLastError();
-    goto done;
-  }
-
-  if (GetSecurityInfo(handle->handle,
-                      SE_KERNEL_OBJECT,
-                      DACL_SECURITY_INFORMATION,
-                      NULL,
-                      NULL,
-                      &old_dacl,
-                      NULL,
-                      &sd)) {
-    error = GetLastError();
-    goto clean_sid;
-  }
-
-  memset(&ea, 0, sizeof(EXPLICIT_ACCESS));
-  if (mode & UV_READABLE)
-    ea.grfAccessPermissions |= GENERIC_READ | FILE_WRITE_ATTRIBUTES;
-  if (mode & UV_WRITABLE)
-    ea.grfAccessPermissions |= GENERIC_WRITE | FILE_READ_ATTRIBUTES;
-  ea.grfAccessPermissions |= SYNCHRONIZE;
-  ea.grfAccessMode = SET_ACCESS;
-  ea.grfInheritance = NO_INHERITANCE;
-  ea.Trustee.TrusteeForm = TRUSTEE_IS_SID;
-  ea.Trustee.TrusteeType = TRUSTEE_IS_WELL_KNOWN_GROUP;
-  ea.Trustee.ptstrName = (LPTSTR)everyone;
-
-  if (SetEntriesInAcl(1, &ea, old_dacl, &new_dacl)) {
-    error = GetLastError();
-    goto clean_sd;
-  }
-
-  if (SetSecurityInfo(handle->handle,
-                      SE_KERNEL_OBJECT,
-                      DACL_SECURITY_INFORMATION,
-                      NULL,
-                      NULL,
-                      new_dacl,
-                      NULL)) {
-    error = GetLastError();
-    goto clean_dacl;
-  }
-
-  error = 0;
-
-clean_dacl:
-  LocalFree((HLOCAL) new_dacl);
-clean_sd:
-  LocalFree((HLOCAL) sd);
-clean_sid:
-  FreeSid(everyone);
-done:
-  return uv_translate_sys_error(error);
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/poll.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/poll.cpp
deleted file mode 100644
index 3c66786..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/poll.cpp
+++ /dev/null
@@ -1,643 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include <assert.h>
-#include <io.h>
-
-#include "uv.h"
-#include "internal.h"
-#include "handle-inl.h"
-#include "req-inl.h"
-
-
-static const GUID uv_msafd_provider_ids[UV_MSAFD_PROVIDER_COUNT] = {
-  {0xe70f1aa0, 0xab8b, 0x11cf,
-      {0x8c, 0xa3, 0x00, 0x80, 0x5f, 0x48, 0xa1, 0x92}},
-  {0xf9eab0c0, 0x26d4, 0x11d0,
-      {0xbb, 0xbf, 0x00, 0xaa, 0x00, 0x6c, 0x34, 0xe4}},
-  {0x9fc48064, 0x7298, 0x43e4,
-      {0xb7, 0xbd, 0x18, 0x1f, 0x20, 0x89, 0x79, 0x2a}}
-};
-
-typedef struct uv_single_fd_set_s {
-  unsigned int fd_count;
-  SOCKET fd_array[1];
-} uv_single_fd_set_t;
-
-
-static OVERLAPPED overlapped_dummy_;
-static uv_once_t overlapped_dummy_init_guard_ = UV_ONCE_INIT;
-
-static AFD_POLL_INFO afd_poll_info_dummy_;
-
-
-static void uv__init_overlapped_dummy(void) {
-  HANDLE event;
-
-  event = CreateEvent(NULL, TRUE, TRUE, NULL);
-  if (event == NULL)
-    uv_fatal_error(GetLastError(), "CreateEvent");
-
-  memset(&overlapped_dummy_, 0, sizeof overlapped_dummy_);
-  overlapped_dummy_.hEvent = (HANDLE) ((uintptr_t) event | 1);
-}
-
-
-static OVERLAPPED* uv__get_overlapped_dummy(void) {
-  uv_once(&overlapped_dummy_init_guard_, uv__init_overlapped_dummy);
-  return &overlapped_dummy_;
-}
-
-
-static AFD_POLL_INFO* uv__get_afd_poll_info_dummy(void) {
-  return &afd_poll_info_dummy_;
-}
-
-
-static void uv__fast_poll_submit_poll_req(uv_loop_t* loop, uv_poll_t* handle) {
-  uv_req_t* req;
-  AFD_POLL_INFO* afd_poll_info;
-  int result;
-
-  /* Find a yet unsubmitted req to submit. */
-  if (handle->submitted_events_1 == 0) {
-    req = &handle->poll_req_1;
-    afd_poll_info = &handle->afd_poll_info_1;
-    handle->submitted_events_1 = handle->events;
-    handle->mask_events_1 = 0;
-    handle->mask_events_2 = handle->events;
-  } else if (handle->submitted_events_2 == 0) {
-    req = &handle->poll_req_2;
-    afd_poll_info = &handle->afd_poll_info_2;
-    handle->submitted_events_2 = handle->events;
-    handle->mask_events_1 = handle->events;
-    handle->mask_events_2 = 0;
-  } else {
-    /* Just wait until there's an unsubmitted req. This will happen almost
-     * immediately as one of the 2 outstanding requests is about to return.
-     * When this happens, uv__fast_poll_process_poll_req will be called, and
-     * the pending events, if needed, will be processed in a subsequent
-     * request. */
-    return;
-  }
-
-  /* Setting Exclusive to TRUE makes the other poll request return if there is
-   * any. */
-  afd_poll_info->Exclusive = TRUE;
-  afd_poll_info->NumberOfHandles = 1;
-  afd_poll_info->Timeout.QuadPart = INT64_MAX;
-  afd_poll_info->Handles[0].Handle = (HANDLE) handle->socket;
-  afd_poll_info->Handles[0].Status = 0;
-  afd_poll_info->Handles[0].Events = 0;
-
-  if (handle->events & UV_READABLE) {
-    afd_poll_info->Handles[0].Events |= AFD_POLL_RECEIVE |
-        AFD_POLL_DISCONNECT | AFD_POLL_ACCEPT | AFD_POLL_ABORT;
-  } else {
-    if (handle->events & UV_DISCONNECT) {
-      afd_poll_info->Handles[0].Events |= AFD_POLL_DISCONNECT;
-    }
-  }
-  if (handle->events & UV_WRITABLE) {
-    afd_poll_info->Handles[0].Events |= AFD_POLL_SEND | AFD_POLL_CONNECT_FAIL;
-  }
-
-  memset(&req->u.io.overlapped, 0, sizeof req->u.io.overlapped);
-
-  result = uv_msafd_poll((SOCKET) handle->peer_socket,
-                         afd_poll_info,
-                         afd_poll_info,
-                         &req->u.io.overlapped);
-  if (result != 0 && WSAGetLastError() != WSA_IO_PENDING) {
-    /* Queue this req, reporting an error. */
-    SET_REQ_ERROR(req, WSAGetLastError());
-    uv_insert_pending_req(loop, req);
-  }
-}
-
-
-static int uv__fast_poll_cancel_poll_req(uv_loop_t* loop, uv_poll_t* handle) {
-  AFD_POLL_INFO afd_poll_info;
-  int result;
-
-  afd_poll_info.Exclusive = TRUE;
-  afd_poll_info.NumberOfHandles = 1;
-  afd_poll_info.Timeout.QuadPart = INT64_MAX;
-  afd_poll_info.Handles[0].Handle = (HANDLE) handle->socket;
-  afd_poll_info.Handles[0].Status = 0;
-  afd_poll_info.Handles[0].Events = AFD_POLL_ALL;
-
-  result = uv_msafd_poll(handle->socket,
-                         &afd_poll_info,
-                         uv__get_afd_poll_info_dummy(),
-                         uv__get_overlapped_dummy());
-
-  if (result == SOCKET_ERROR) {
-    DWORD error = WSAGetLastError();
-    if (error != WSA_IO_PENDING)
-      return error;
-  }
-
-  return 0;
-}
-
-
-static void uv__fast_poll_process_poll_req(uv_loop_t* loop, uv_poll_t* handle,
-    uv_req_t* req) {
-  unsigned char mask_events;
-  AFD_POLL_INFO* afd_poll_info;
-
-  if (req == &handle->poll_req_1) {
-    afd_poll_info = &handle->afd_poll_info_1;
-    handle->submitted_events_1 = 0;
-    mask_events = handle->mask_events_1;
-  } else if (req == &handle->poll_req_2) {
-    afd_poll_info = &handle->afd_poll_info_2;
-    handle->submitted_events_2 = 0;
-    mask_events = handle->mask_events_2;
-  } else {
-    assert(0);
-    return;
-  }
-
-  /* Report an error unless the select was just interrupted. */
-  if (!REQ_SUCCESS(req)) {
-    DWORD error = GET_REQ_SOCK_ERROR(req);
-    if (error != WSAEINTR && handle->events != 0) {
-      handle->events = 0; /* Stop the watcher */
-      handle->poll_cb(handle, uv_translate_sys_error(error), 0);
-    }
-
-  } else if (afd_poll_info->NumberOfHandles >= 1) {
-    unsigned char events = 0;
-
-    if ((afd_poll_info->Handles[0].Events & (AFD_POLL_RECEIVE |
-        AFD_POLL_DISCONNECT | AFD_POLL_ACCEPT | AFD_POLL_ABORT)) != 0) {
-      events |= UV_READABLE;
-      if ((afd_poll_info->Handles[0].Events & AFD_POLL_DISCONNECT) != 0) {
-        events |= UV_DISCONNECT;
-      }
-    }
-    if ((afd_poll_info->Handles[0].Events & (AFD_POLL_SEND |
-        AFD_POLL_CONNECT_FAIL)) != 0) {
-      events |= UV_WRITABLE;
-    }
-
-    events &= handle->events & ~mask_events;
-
-    if (afd_poll_info->Handles[0].Events & AFD_POLL_LOCAL_CLOSE) {
-      /* Stop polling. */
-      handle->events = 0;
-      if (uv__is_active(handle))
-        uv__handle_stop(handle);
-    }
-
-    if (events != 0) {
-      handle->poll_cb(handle, 0, events);
-    }
-  }
-
-  if ((handle->events & ~(handle->submitted_events_1 |
-      handle->submitted_events_2)) != 0) {
-    uv__fast_poll_submit_poll_req(loop, handle);
-  } else if ((handle->flags & UV_HANDLE_CLOSING) &&
-             handle->submitted_events_1 == 0 &&
-             handle->submitted_events_2 == 0) {
-    uv_want_endgame(loop, (uv_handle_t*) handle);
-  }
-}
-
-
-static int uv__fast_poll_set(uv_loop_t* loop, uv_poll_t* handle, int events) {
-  assert(handle->type == UV_POLL);
-  assert(!(handle->flags & UV_HANDLE_CLOSING));
-  assert((events & ~(UV_READABLE | UV_WRITABLE | UV_DISCONNECT)) == 0);
-
-  handle->events = events;
-
-  if (handle->events != 0) {
-    uv__handle_start(handle);
-  } else {
-    uv__handle_stop(handle);
-  }
-
-  if ((handle->events & ~(handle->submitted_events_1 |
-      handle->submitted_events_2)) != 0) {
-    uv__fast_poll_submit_poll_req(handle->loop, handle);
-  }
-
-  return 0;
-}
-
-
-static int uv__fast_poll_close(uv_loop_t* loop, uv_poll_t* handle) {
-  handle->events = 0;
-  uv__handle_closing(handle);
-
-  if (handle->submitted_events_1 == 0 &&
-      handle->submitted_events_2 == 0) {
-    uv_want_endgame(loop, (uv_handle_t*) handle);
-    return 0;
-  } else {
-    /* Cancel outstanding poll requests by executing another, unique poll
-     * request that forces the outstanding ones to return. */
-    return uv__fast_poll_cancel_poll_req(loop, handle);
-  }
-}
-
-
-static SOCKET uv__fast_poll_create_peer_socket(HANDLE iocp,
-    WSAPROTOCOL_INFOW* protocol_info) {
-  SOCKET sock = 0;
-
-  sock = WSASocketW(protocol_info->iAddressFamily,
-                    protocol_info->iSocketType,
-                    protocol_info->iProtocol,
-                    protocol_info,
-                    0,
-                    WSA_FLAG_OVERLAPPED);
-  if (sock == INVALID_SOCKET) {
-    return INVALID_SOCKET;
-  }
-
-  if (!SetHandleInformation((HANDLE) sock, HANDLE_FLAG_INHERIT, 0)) {
-    goto error;
-  };
-
-  if (CreateIoCompletionPort((HANDLE) sock,
-                             iocp,
-                             (ULONG_PTR) sock,
-                             0) == NULL) {
-    goto error;
-  }
-
-  return sock;
-
- error:
-  closesocket(sock);
-  return INVALID_SOCKET;
-}
-
-
-static SOCKET uv__fast_poll_get_peer_socket(uv_loop_t* loop,
-    WSAPROTOCOL_INFOW* protocol_info) {
-  int index, i;
-  SOCKET peer_socket;
-
-  index = -1;
-  for (i = 0; (size_t) i < ARRAY_SIZE(uv_msafd_provider_ids); i++) {
-    if (memcmp((void*) &protocol_info->ProviderId,
-               (void*) &uv_msafd_provider_ids[i],
-               sizeof protocol_info->ProviderId) == 0) {
-      index = i;
-    }
-  }
-
-  /* Check if the protocol uses an msafd socket. */
-  if (index < 0) {
-    return INVALID_SOCKET;
-  }
-
-  /* If we didn't (try) to create a peer socket yet, try to make one. Don't try
-   * again if the peer socket creation failed earlier for the same protocol. */
-  peer_socket = loop->poll_peer_sockets[index];
-  if (peer_socket == 0) {
-    peer_socket = uv__fast_poll_create_peer_socket(loop->iocp, protocol_info);
-    loop->poll_peer_sockets[index] = peer_socket;
-  }
-
-  return peer_socket;
-}
-
-
-static DWORD WINAPI uv__slow_poll_thread_proc(void* arg) {
-  uv_req_t* req = (uv_req_t*) arg;
-  uv_poll_t* handle = (uv_poll_t*) req->data;
-  unsigned char reported_events;
-  int r;
-  uv_single_fd_set_t rfds, wfds, efds;
-  struct timeval timeout;
-
-  assert(handle->type == UV_POLL);
-  assert(req->type == UV_POLL_REQ);
-
-  if (handle->events & UV_READABLE) {
-    rfds.fd_count = 1;
-    rfds.fd_array[0] = handle->socket;
-  } else {
-    rfds.fd_count = 0;
-  }
-
-  if (handle->events & UV_WRITABLE) {
-    wfds.fd_count = 1;
-    wfds.fd_array[0] = handle->socket;
-    efds.fd_count = 1;
-    efds.fd_array[0] = handle->socket;
-  } else {
-    wfds.fd_count = 0;
-    efds.fd_count = 0;
-  }
-
-  /* Make the select() time out after 3 minutes. If select() hangs because the
-   * user closed the socket, we will at least not hang indefinitely. */
-  timeout.tv_sec = 3 * 60;
-  timeout.tv_usec = 0;
-
-  r = select(1, (fd_set*) &rfds, (fd_set*) &wfds, (fd_set*) &efds, &timeout);
-  if (r == SOCKET_ERROR) {
-    /* Queue this req, reporting an error. */
-    SET_REQ_ERROR(&handle->poll_req_1, WSAGetLastError());
-    POST_COMPLETION_FOR_REQ(handle->loop, req);
-    return 0;
-  }
-
-  reported_events = 0;
-
-  if (r > 0) {
-    if (rfds.fd_count > 0) {
-      assert(rfds.fd_count == 1);
-      assert(rfds.fd_array[0] == handle->socket);
-      reported_events |= UV_READABLE;
-    }
-
-    if (wfds.fd_count > 0) {
-      assert(wfds.fd_count == 1);
-      assert(wfds.fd_array[0] == handle->socket);
-      reported_events |= UV_WRITABLE;
-    } else if (efds.fd_count > 0) {
-      assert(efds.fd_count == 1);
-      assert(efds.fd_array[0] == handle->socket);
-      reported_events |= UV_WRITABLE;
-    }
-  }
-
-  SET_REQ_SUCCESS(req);
-  req->u.io.overlapped.InternalHigh = (DWORD) reported_events;
-  POST_COMPLETION_FOR_REQ(handle->loop, req);
-
-  return 0;
-}
-
-
-static void uv__slow_poll_submit_poll_req(uv_loop_t* loop, uv_poll_t* handle) {
-  uv_req_t* req;
-
-  /* Find a yet unsubmitted req to submit. */
-  if (handle->submitted_events_1 == 0) {
-    req = &handle->poll_req_1;
-    handle->submitted_events_1 = handle->events;
-    handle->mask_events_1 = 0;
-    handle->mask_events_2 = handle->events;
-  } else if (handle->submitted_events_2 == 0) {
-    req = &handle->poll_req_2;
-    handle->submitted_events_2 = handle->events;
-    handle->mask_events_1 = handle->events;
-    handle->mask_events_2 = 0;
-  } else {
-    assert(0);
-    return;
-  }
-
-  if (!QueueUserWorkItem(uv__slow_poll_thread_proc,
-                         (void*) req,
-                         WT_EXECUTELONGFUNCTION)) {
-    /* Make this req pending, reporting an error. */
-    SET_REQ_ERROR(req, GetLastError());
-    uv_insert_pending_req(loop, req);
-  }
-}
-
-
-
-static void uv__slow_poll_process_poll_req(uv_loop_t* loop, uv_poll_t* handle,
-    uv_req_t* req) {
-  unsigned char mask_events;
-  int err;
-
-  if (req == &handle->poll_req_1) {
-    handle->submitted_events_1 = 0;
-    mask_events = handle->mask_events_1;
-  } else if (req == &handle->poll_req_2) {
-    handle->submitted_events_2 = 0;
-    mask_events = handle->mask_events_2;
-  } else {
-    assert(0);
-    return;
-  }
-
-  if (!REQ_SUCCESS(req)) {
-    /* Error. */
-    if (handle->events != 0) {
-      err = GET_REQ_ERROR(req);
-      handle->events = 0; /* Stop the watcher */
-      handle->poll_cb(handle, uv_translate_sys_error(err), 0);
-    }
-  } else {
-    /* Got some events. */
-    int events = req->u.io.overlapped.InternalHigh & handle->events & ~mask_events;
-    if (events != 0) {
-      handle->poll_cb(handle, 0, events);
-    }
-  }
-
-  if ((handle->events & ~(handle->submitted_events_1 |
-      handle->submitted_events_2)) != 0) {
-    uv__slow_poll_submit_poll_req(loop, handle);
-  } else if ((handle->flags & UV_HANDLE_CLOSING) &&
-             handle->submitted_events_1 == 0 &&
-             handle->submitted_events_2 == 0) {
-    uv_want_endgame(loop, (uv_handle_t*) handle);
-  }
-}
-
-
-static int uv__slow_poll_set(uv_loop_t* loop, uv_poll_t* handle, int events) {
-  assert(handle->type == UV_POLL);
-  assert(!(handle->flags & UV_HANDLE_CLOSING));
-  assert((events & ~(UV_READABLE | UV_WRITABLE)) == 0);
-
-  handle->events = events;
-
-  if (handle->events != 0) {
-    uv__handle_start(handle);
-  } else {
-    uv__handle_stop(handle);
-  }
-
-  if ((handle->events &
-      ~(handle->submitted_events_1 | handle->submitted_events_2)) != 0) {
-    uv__slow_poll_submit_poll_req(handle->loop, handle);
-  }
-
-  return 0;
-}
-
-
-static int uv__slow_poll_close(uv_loop_t* loop, uv_poll_t* handle) {
-  handle->events = 0;
-  uv__handle_closing(handle);
-
-  if (handle->submitted_events_1 == 0 &&
-      handle->submitted_events_2 == 0) {
-    uv_want_endgame(loop, (uv_handle_t*) handle);
-  }
-
-  return 0;
-}
-
-
-int uv_poll_init(uv_loop_t* loop, uv_poll_t* handle, int fd) {
-  return uv_poll_init_socket(loop, handle, (SOCKET) uv__get_osfhandle(fd));
-}
-
-
-int uv_poll_init_socket(uv_loop_t* loop, uv_poll_t* handle,
-    uv_os_sock_t socket) {
-  WSAPROTOCOL_INFOW protocol_info;
-  int len;
-  SOCKET peer_socket, base_socket;
-  DWORD bytes;
-  DWORD yes = 1;
-
-  /* Set the socket to nonblocking mode */
-  if (ioctlsocket(socket, FIONBIO, &yes) == SOCKET_ERROR)
-    return uv_translate_sys_error(WSAGetLastError());
-
-/* Try to obtain a base handle for the socket. This increases this chances that
- * we find an AFD handle and are able to use the fast poll mechanism. This will
- * always fail on windows XP/2k3, since they don't support the. SIO_BASE_HANDLE
- * ioctl. */
-#ifndef NDEBUG
-  base_socket = INVALID_SOCKET;
-#endif
-
-  if (WSAIoctl(socket,
-               SIO_BASE_HANDLE,
-               NULL,
-               0,
-               &base_socket,
-               sizeof base_socket,
-               &bytes,
-               NULL,
-               NULL) == 0) {
-    assert(base_socket != 0 && base_socket != INVALID_SOCKET);
-    socket = base_socket;
-  }
-
-  uv__handle_init(loop, (uv_handle_t*) handle, UV_POLL);
-  handle->socket = socket;
-  handle->events = 0;
-
-  /* Obtain protocol information about the socket. */
-  len = sizeof protocol_info;
-  if (getsockopt(socket,
-                 SOL_SOCKET,
-                 SO_PROTOCOL_INFOW,
-                 (char*) &protocol_info,
-                 &len) != 0) {
-    return uv_translate_sys_error(WSAGetLastError());
-  }
-
-  /* Get the peer socket that is needed to enable fast poll. If the returned
-   * value is NULL, the protocol is not implemented by MSAFD and we'll have to
-   * use slow mode. */
-  peer_socket = uv__fast_poll_get_peer_socket(loop, &protocol_info);
-
-  if (peer_socket != INVALID_SOCKET) {
-    /* Initialize fast poll specific fields. */
-    handle->peer_socket = peer_socket;
-  } else {
-    /* Initialize slow poll specific fields. */
-    handle->flags |= UV_HANDLE_POLL_SLOW;
-  }
-
-  /* Initialize 2 poll reqs. */
-  handle->submitted_events_1 = 0;
-  UV_REQ_INIT(&handle->poll_req_1, UV_POLL_REQ);
-  handle->poll_req_1.data = handle;
-
-  handle->submitted_events_2 = 0;
-  UV_REQ_INIT(&handle->poll_req_2, UV_POLL_REQ);
-  handle->poll_req_2.data = handle;
-
-  return 0;
-}
-
-
-int uv_poll_start(uv_poll_t* handle, int events, uv_poll_cb cb) {
-  int err;
-
-  if (!(handle->flags & UV_HANDLE_POLL_SLOW)) {
-    err = uv__fast_poll_set(handle->loop, handle, events);
-  } else {
-    err = uv__slow_poll_set(handle->loop, handle, events);
-  }
-
-  if (err) {
-    return uv_translate_sys_error(err);
-  }
-
-  handle->poll_cb = cb;
-
-  return 0;
-}
-
-
-int uv_poll_stop(uv_poll_t* handle) {
-  int err;
-
-  if (!(handle->flags & UV_HANDLE_POLL_SLOW)) {
-    err = uv__fast_poll_set(handle->loop, handle, 0);
-  } else {
-    err = uv__slow_poll_set(handle->loop, handle, 0);
-  }
-
-  return uv_translate_sys_error(err);
-}
-
-
-void uv_process_poll_req(uv_loop_t* loop, uv_poll_t* handle, uv_req_t* req) {
-  if (!(handle->flags & UV_HANDLE_POLL_SLOW)) {
-    uv__fast_poll_process_poll_req(loop, handle, req);
-  } else {
-    uv__slow_poll_process_poll_req(loop, handle, req);
-  }
-}
-
-
-int uv_poll_close(uv_loop_t* loop, uv_poll_t* handle) {
-  if (!(handle->flags & UV_HANDLE_POLL_SLOW)) {
-    return uv__fast_poll_close(loop, handle);
-  } else {
-    return uv__slow_poll_close(loop, handle);
-  }
-}
-
-
-void uv_poll_endgame(uv_loop_t* loop, uv_poll_t* handle) {
-  assert(handle->flags & UV_HANDLE_CLOSING);
-  assert(!(handle->flags & UV_HANDLE_CLOSED));
-
-  assert(handle->submitted_events_1 == 0);
-  assert(handle->submitted_events_2 == 0);
-
-  uv__handle_close(handle);
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/process-stdio.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/process-stdio.cpp
deleted file mode 100644
index 4701938..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/process-stdio.cpp
+++ /dev/null
@@ -1,512 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include <assert.h>
-#include <io.h>
-#include <stdio.h>
-#include <stdlib.h>
-
-#include "uv.h"
-#include "internal.h"
-#include "handle-inl.h"
-
-
-/*
- * The `child_stdio_buffer` buffer has the following layout:
- *   int number_of_fds
- *   unsigned char crt_flags[number_of_fds]
- *   HANDLE os_handle[number_of_fds]
- */
-#define CHILD_STDIO_SIZE(count)                     \
-    (sizeof(int) +                                  \
-     sizeof(unsigned char) * (count) +              \
-     sizeof(uintptr_t) * (count))
-
-#define CHILD_STDIO_COUNT(buffer)                   \
-    *((unsigned int*) (buffer))
-
-#define CHILD_STDIO_CRT_FLAGS(buffer, fd)           \
-    *((unsigned char*) (buffer) + sizeof(int) + fd)
-
-#define CHILD_STDIO_HANDLE(buffer, fd)              \
-    *((HANDLE*) ((unsigned char*) (buffer) +        \
-                 sizeof(int) +                      \
-                 sizeof(unsigned char) *            \
-                 CHILD_STDIO_COUNT((buffer)) +      \
-                 sizeof(HANDLE) * (fd)))
-
-
-/* CRT file descriptor mode flags */
-#define FOPEN       0x01
-#define FEOFLAG     0x02
-#define FCRLF       0x04
-#define FPIPE       0x08
-#define FNOINHERIT  0x10
-#define FAPPEND     0x20
-#define FDEV        0x40
-#define FTEXT       0x80
-
-
-/*
- * Clear the HANDLE_FLAG_INHERIT flag from all HANDLEs that were inherited
- * the parent process. Don't check for errors - the stdio handles may not be
- * valid, or may be closed already. There is no guarantee that this function
- * does a perfect job.
- */
-void uv_disable_stdio_inheritance(void) {
-  HANDLE handle;
-  STARTUPINFOW si;
-
-  /* Make the windows stdio handles non-inheritable. */
-  handle = GetStdHandle(STD_INPUT_HANDLE);
-  if (handle != NULL && handle != INVALID_HANDLE_VALUE)
-    SetHandleInformation(handle, HANDLE_FLAG_INHERIT, 0);
-
-  handle = GetStdHandle(STD_OUTPUT_HANDLE);
-  if (handle != NULL && handle != INVALID_HANDLE_VALUE)
-    SetHandleInformation(handle, HANDLE_FLAG_INHERIT, 0);
-
-  handle = GetStdHandle(STD_ERROR_HANDLE);
-  if (handle != NULL && handle != INVALID_HANDLE_VALUE)
-    SetHandleInformation(handle, HANDLE_FLAG_INHERIT, 0);
-
-  /* Make inherited CRT FDs non-inheritable. */
-  GetStartupInfoW(&si);
-  if (uv__stdio_verify(si.lpReserved2, si.cbReserved2))
-    uv__stdio_noinherit(si.lpReserved2);
-}
-
-
-static int uv__create_stdio_pipe_pair(uv_loop_t* loop,
-    uv_pipe_t* server_pipe, HANDLE* child_pipe_ptr, unsigned int flags) {
-  char pipe_name[64];
-  SECURITY_ATTRIBUTES sa;
-  DWORD server_access = 0;
-  DWORD client_access = 0;
-  HANDLE child_pipe = INVALID_HANDLE_VALUE;
-  int err;
-  BOOL overlap;
-
-  if (flags & UV_READABLE_PIPE) {
-    /* The server needs inbound access too, otherwise CreateNamedPipe() won't
-     * give us the FILE_READ_ATTRIBUTES permission. We need that to probe the
-     * state of the write buffer when we're trying to shutdown the pipe. */
-    server_access |= PIPE_ACCESS_OUTBOUND | PIPE_ACCESS_INBOUND;
-    client_access |= GENERIC_READ | FILE_WRITE_ATTRIBUTES;
-  }
-  if (flags & UV_WRITABLE_PIPE) {
-    server_access |= PIPE_ACCESS_INBOUND;
-    client_access |= GENERIC_WRITE | FILE_READ_ATTRIBUTES;
-  }
-
-  /* Create server pipe handle. */
-  err = uv_stdio_pipe_server(loop,
-                             server_pipe,
-                             server_access,
-                             pipe_name,
-                             sizeof(pipe_name));
-  if (err)
-    goto error;
-
-  /* Create child pipe handle. */
-  sa.nLength = sizeof sa;
-  sa.lpSecurityDescriptor = NULL;
-  sa.bInheritHandle = TRUE;
-
-  overlap = server_pipe->ipc || (flags & UV_OVERLAPPED_PIPE);
-  child_pipe = CreateFileA(pipe_name,
-                           client_access,
-                           0,
-                           &sa,
-                           OPEN_EXISTING,
-                           overlap ? FILE_FLAG_OVERLAPPED : 0,
-                           NULL);
-  if (child_pipe == INVALID_HANDLE_VALUE) {
-    err = GetLastError();
-    goto error;
-  }
-
-#ifndef NDEBUG
-  /* Validate that the pipe was opened in the right mode. */
-  {
-    DWORD mode;
-    BOOL r = GetNamedPipeHandleState(child_pipe,
-                                     &mode,
-                                     NULL,
-                                     NULL,
-                                     NULL,
-                                     NULL,
-                                     0);
-    assert(r == TRUE);
-    assert(mode == (PIPE_READMODE_BYTE | PIPE_WAIT));
-  }
-#endif
-
-  /* Do a blocking ConnectNamedPipe. This should not block because we have both
-   * ends of the pipe created. */
-  if (!ConnectNamedPipe(server_pipe->handle, NULL)) {
-    if (GetLastError() != ERROR_PIPE_CONNECTED) {
-      err = GetLastError();
-      goto error;
-    }
-  }
-
-  /* The server end is now readable and/or writable. */
-  if (flags & UV_READABLE_PIPE)
-    server_pipe->flags |= UV_HANDLE_WRITABLE;
-  if (flags & UV_WRITABLE_PIPE)
-    server_pipe->flags |= UV_HANDLE_READABLE;
-
-  *child_pipe_ptr = child_pipe;
-  return 0;
-
- error:
-  if (server_pipe->handle != INVALID_HANDLE_VALUE) {
-    uv_pipe_cleanup(loop, server_pipe);
-  }
-
-  if (child_pipe != INVALID_HANDLE_VALUE) {
-    CloseHandle(child_pipe);
-  }
-
-  return err;
-}
-
-
-static int uv__duplicate_handle(uv_loop_t* loop, HANDLE handle, HANDLE* dup) {
-  HANDLE current_process;
-
-
-  /* _get_osfhandle will sometimes return -2 in case of an error. This seems to
-   * happen when fd <= 2 and the process' corresponding stdio handle is set to
-   * NULL. Unfortunately DuplicateHandle will happily duplicate (HANDLE) -2, so
-   * this situation goes unnoticed until someone tries to use the duplicate.
-   * Therefore we filter out known-invalid handles here. */
-  if (handle == INVALID_HANDLE_VALUE ||
-      handle == NULL ||
-      handle == (HANDLE) -2) {
-    *dup = INVALID_HANDLE_VALUE;
-    return ERROR_INVALID_HANDLE;
-  }
-
-  current_process = GetCurrentProcess();
-
-  if (!DuplicateHandle(current_process,
-                       handle,
-                       current_process,
-                       dup,
-                       0,
-                       TRUE,
-                       DUPLICATE_SAME_ACCESS)) {
-    *dup = INVALID_HANDLE_VALUE;
-    return GetLastError();
-  }
-
-  return 0;
-}
-
-
-static int uv__duplicate_fd(uv_loop_t* loop, int fd, HANDLE* dup) {
-  HANDLE handle;
-
-  if (fd == -1) {
-    *dup = INVALID_HANDLE_VALUE;
-    return ERROR_INVALID_HANDLE;
-  }
-
-  handle = uv__get_osfhandle(fd);
-  return uv__duplicate_handle(loop, handle, dup);
-}
-
-
-int uv__create_nul_handle(HANDLE* handle_ptr,
-    DWORD access) {
-  HANDLE handle;
-  SECURITY_ATTRIBUTES sa;
-
-  sa.nLength = sizeof sa;
-  sa.lpSecurityDescriptor = NULL;
-  sa.bInheritHandle = TRUE;
-
-  handle = CreateFileW(L"NUL",
-                       access,
-                       FILE_SHARE_READ | FILE_SHARE_WRITE,
-                       &sa,
-                       OPEN_EXISTING,
-                       0,
-                       NULL);
-  if (handle == INVALID_HANDLE_VALUE) {
-    return GetLastError();
-  }
-
-  *handle_ptr = handle;
-  return 0;
-}
-
-
-int uv__stdio_create(uv_loop_t* loop,
-                     const uv_process_options_t* options,
-                     BYTE** buffer_ptr) {
-  BYTE* buffer;
-  int count, i;
-  int err;
-
-  count = options->stdio_count;
-
-  if (count < 0 || count > 255) {
-    /* Only support FDs 0-255 */
-    return ERROR_NOT_SUPPORTED;
-  } else if (count < 3) {
-    /* There should always be at least 3 stdio handles. */
-    count = 3;
-  }
-
-  /* Allocate the child stdio buffer */
-  buffer = (BYTE*) uv__malloc(CHILD_STDIO_SIZE(count));
-  if (buffer == NULL) {
-    return ERROR_OUTOFMEMORY;
-  }
-
-  /* Prepopulate the buffer with INVALID_HANDLE_VALUE handles so we can clean
-   * up on failure. */
-  CHILD_STDIO_COUNT(buffer) = count;
-  for (i = 0; i < count; i++) {
-    CHILD_STDIO_CRT_FLAGS(buffer, i) = 0;
-    CHILD_STDIO_HANDLE(buffer, i) = INVALID_HANDLE_VALUE;
-  }
-
-  for (i = 0; i < count; i++) {
-    uv_stdio_container_t fdopt;
-    if (i < options->stdio_count) {
-      fdopt = options->stdio[i];
-    } else {
-      fdopt.flags = UV_IGNORE;
-    }
-
-    switch (fdopt.flags & (UV_IGNORE | UV_CREATE_PIPE | UV_INHERIT_FD |
-            UV_INHERIT_STREAM)) {
-      case UV_IGNORE:
-        /* Starting a process with no stdin/stout/stderr can confuse it. So no
-         * matter what the user specified, we make sure the first three FDs are
-         * always open in their typical modes, e. g. stdin be readable and
-         * stdout/err should be writable. For FDs > 2, don't do anything - all
-         * handles in the stdio buffer are initialized with.
-         * INVALID_HANDLE_VALUE, which should be okay. */
-        if (i <= 2) {
-          DWORD access = (i == 0) ? FILE_GENERIC_READ :
-                                    FILE_GENERIC_WRITE | FILE_READ_ATTRIBUTES;
-
-          err = uv__create_nul_handle(&CHILD_STDIO_HANDLE(buffer, i),
-                                      access);
-          if (err)
-            goto error;
-
-          CHILD_STDIO_CRT_FLAGS(buffer, i) = FOPEN | FDEV;
-        }
-        break;
-
-      case UV_CREATE_PIPE: {
-        /* Create a pair of two connected pipe ends; one end is turned into an
-         * uv_pipe_t for use by the parent. The other one is given to the
-         * child. */
-        uv_pipe_t* parent_pipe = (uv_pipe_t*) fdopt.data.stream;
-        HANDLE child_pipe = INVALID_HANDLE_VALUE;
-
-        /* Create a new, connected pipe pair. stdio[i]. stream should point to
-         * an uninitialized, but not connected pipe handle. */
-        assert(fdopt.data.stream->type == UV_NAMED_PIPE);
-        assert(!(fdopt.data.stream->flags & UV_HANDLE_CONNECTION));
-        assert(!(fdopt.data.stream->flags & UV_HANDLE_PIPESERVER));
-
-        err = uv__create_stdio_pipe_pair(loop,
-                                         parent_pipe,
-                                         &child_pipe,
-                                         fdopt.flags);
-        if (err)
-          goto error;
-
-        CHILD_STDIO_HANDLE(buffer, i) = child_pipe;
-        CHILD_STDIO_CRT_FLAGS(buffer, i) = FOPEN | FPIPE;
-        break;
-      }
-
-      case UV_INHERIT_FD: {
-        /* Inherit a raw FD. */
-        HANDLE child_handle;
-
-        /* Make an inheritable duplicate of the handle. */
-        err = uv__duplicate_fd(loop, fdopt.data.fd, &child_handle);
-        if (err) {
-          /* If fdopt. data. fd is not valid and fd <= 2, then ignore the
-           * error. */
-          if (fdopt.data.fd <= 2 && err == ERROR_INVALID_HANDLE) {
-            CHILD_STDIO_CRT_FLAGS(buffer, i) = 0;
-            CHILD_STDIO_HANDLE(buffer, i) = INVALID_HANDLE_VALUE;
-            break;
-          }
-          goto error;
-        }
-
-        /* Figure out what the type is. */
-        switch (GetFileType(child_handle)) {
-          case FILE_TYPE_DISK:
-            CHILD_STDIO_CRT_FLAGS(buffer, i) = FOPEN;
-            break;
-
-          case FILE_TYPE_PIPE:
-            CHILD_STDIO_CRT_FLAGS(buffer, i) = FOPEN | FPIPE;
-            break;
-
-          case FILE_TYPE_CHAR:
-          case FILE_TYPE_REMOTE:
-            CHILD_STDIO_CRT_FLAGS(buffer, i) = FOPEN | FDEV;
-            break;
-
-          case FILE_TYPE_UNKNOWN:
-            if (GetLastError() != 0) {
-              err = GetLastError();
-              CloseHandle(child_handle);
-              goto error;
-            }
-            CHILD_STDIO_CRT_FLAGS(buffer, i) = FOPEN | FDEV;
-            break;
-
-          default:
-            assert(0);
-            return -1;
-        }
-
-        CHILD_STDIO_HANDLE(buffer, i) = child_handle;
-        break;
-      }
-
-      case UV_INHERIT_STREAM: {
-        /* Use an existing stream as the stdio handle for the child. */
-        HANDLE stream_handle, child_handle;
-        unsigned char crt_flags;
-        uv_stream_t* stream = fdopt.data.stream;
-
-        /* Leech the handle out of the stream. */
-        if (stream->type == UV_TTY) {
-          stream_handle = ((uv_tty_t*) stream)->handle;
-          crt_flags = FOPEN | FDEV;
-        } else if (stream->type == UV_NAMED_PIPE &&
-                   stream->flags & UV_HANDLE_CONNECTION) {
-          stream_handle = ((uv_pipe_t*) stream)->handle;
-          crt_flags = FOPEN | FPIPE;
-        } else {
-          stream_handle = INVALID_HANDLE_VALUE;
-          crt_flags = 0;
-        }
-
-        if (stream_handle == NULL ||
-            stream_handle == INVALID_HANDLE_VALUE) {
-          /* The handle is already closed, or not yet created, or the stream
-           * type is not supported. */
-          err = ERROR_NOT_SUPPORTED;
-          goto error;
-        }
-
-        /* Make an inheritable copy of the handle. */
-        err = uv__duplicate_handle(loop, stream_handle, &child_handle);
-        if (err)
-          goto error;
-
-        CHILD_STDIO_HANDLE(buffer, i) = child_handle;
-        CHILD_STDIO_CRT_FLAGS(buffer, i) = crt_flags;
-        break;
-      }
-
-      default:
-        assert(0);
-        return -1;
-    }
-  }
-
-  *buffer_ptr  = buffer;
-  return 0;
-
- error:
-  uv__stdio_destroy(buffer);
-  return err;
-}
-
-
-void uv__stdio_destroy(BYTE* buffer) {
-  int i, count;
-
-  count = CHILD_STDIO_COUNT(buffer);
-  for (i = 0; i < count; i++) {
-    HANDLE handle = CHILD_STDIO_HANDLE(buffer, i);
-    if (handle != INVALID_HANDLE_VALUE) {
-      CloseHandle(handle);
-    }
-  }
-
-  uv__free(buffer);
-}
-
-
-void uv__stdio_noinherit(BYTE* buffer) {
-  int i, count;
-
-  count = CHILD_STDIO_COUNT(buffer);
-  for (i = 0; i < count; i++) {
-    HANDLE handle = CHILD_STDIO_HANDLE(buffer, i);
-    if (handle != INVALID_HANDLE_VALUE) {
-      SetHandleInformation(handle, HANDLE_FLAG_INHERIT, 0);
-    }
-  }
-}
-
-
-int uv__stdio_verify(BYTE* buffer, WORD size) {
-  unsigned int count;
-
-  /* Check the buffer pointer. */
-  if (buffer == NULL)
-    return 0;
-
-  /* Verify that the buffer is at least big enough to hold the count. */
-  if (size < CHILD_STDIO_SIZE(0))
-    return 0;
-
-  /* Verify if the count is within range. */
-  count = CHILD_STDIO_COUNT(buffer);
-  if (count > 256)
-    return 0;
-
-  /* Verify that the buffer size is big enough to hold info for N FDs. */
-  if (size < CHILD_STDIO_SIZE(count))
-    return 0;
-
-  return 1;
-}
-
-
-WORD uv__stdio_size(BYTE* buffer) {
-  return (WORD) CHILD_STDIO_SIZE(CHILD_STDIO_COUNT((buffer)));
-}
-
-
-HANDLE uv__stdio_handle(BYTE* buffer, int fd) {
-  return CHILD_STDIO_HANDLE(buffer, fd);
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/process.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/process.cpp
deleted file mode 100644
index 3b8675a..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/process.cpp
+++ /dev/null
@@ -1,1284 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#define _CRT_NONSTDC_NO_WARNINGS
-
-#include <assert.h>
-#include <io.h>
-#include <stdio.h>
-#include <stdlib.h>
-#include <signal.h>
-#include <limits.h>
-#include <wchar.h>
-#include <malloc.h>    /* alloca */
-
-#include "uv.h"
-#include "internal.h"
-#include "handle-inl.h"
-#include "req-inl.h"
-
-#define SIGKILL         9
-
-
-typedef struct env_var {
-  const WCHAR* const wide;
-  const WCHAR* const wide_eq;
-  const size_t len; /* including null or '=' */
-} env_var_t;
-
-#define E_V(str) { L##str, L##str L"=", sizeof(str) }
-
-static const env_var_t required_vars[] = { /* keep me sorted */
-  E_V("HOMEDRIVE"),
-  E_V("HOMEPATH"),
-  E_V("LOGONSERVER"),
-  E_V("PATH"),
-  E_V("SYSTEMDRIVE"),
-  E_V("SYSTEMROOT"),
-  E_V("TEMP"),
-  E_V("USERDOMAIN"),
-  E_V("USERNAME"),
-  E_V("USERPROFILE"),
-  E_V("WINDIR"),
-};
-static size_t n_required_vars = ARRAY_SIZE(required_vars);
-
-
-static HANDLE uv_global_job_handle_;
-static uv_once_t uv_global_job_handle_init_guard_ = UV_ONCE_INIT;
-
-
-static void uv__init_global_job_handle(void) {
-  /* Create a job object and set it up to kill all contained processes when
-   * it's closed. Since this handle is made non-inheritable and we're not
-   * giving it to anyone, we're the only process holding a reference to it.
-   * That means that if this process exits it is closed and all the processes
-   * it contains are killed. All processes created with uv_spawn that are not
-   * spawned with the UV_PROCESS_DETACHED flag are assigned to this job.
-   *
-   * We're setting the JOB_OBJECT_LIMIT_SILENT_BREAKAWAY_OK flag so only the
-   * processes that we explicitly add are affected, and *their* subprocesses
-   * are not. This ensures that our child processes are not limited in their
-   * ability to use job control on Windows versions that don't deal with
-   * nested jobs (prior to Windows 8 / Server 2012). It also lets our child
-   * processes created detached processes without explicitly breaking away
-   * from job control (which uv_spawn doesn't, either).
-   */
-  SECURITY_ATTRIBUTES attr;
-  JOBOBJECT_EXTENDED_LIMIT_INFORMATION info;
-
-  memset(&attr, 0, sizeof attr);
-  attr.bInheritHandle = FALSE;
-
-  memset(&info, 0, sizeof info);
-  info.BasicLimitInformation.LimitFlags =
-      JOB_OBJECT_LIMIT_BREAKAWAY_OK |
-      JOB_OBJECT_LIMIT_SILENT_BREAKAWAY_OK |
-      JOB_OBJECT_LIMIT_DIE_ON_UNHANDLED_EXCEPTION |
-      JOB_OBJECT_LIMIT_KILL_ON_JOB_CLOSE;
-
-  uv_global_job_handle_ = CreateJobObjectW(&attr, NULL);
-  if (uv_global_job_handle_ == NULL)
-    uv_fatal_error(GetLastError(), "CreateJobObjectW");
-
-  if (!SetInformationJobObject(uv_global_job_handle_,
-                               JobObjectExtendedLimitInformation,
-                               &info,
-                               sizeof info))
-    uv_fatal_error(GetLastError(), "SetInformationJobObject");
-}
-
-
-static int uv_utf8_to_utf16_alloc(const char* s, WCHAR** ws_ptr) {
-  int ws_len, r;
-  WCHAR* ws;
-
-  ws_len = MultiByteToWideChar(CP_UTF8,
-                               0,
-                               s,
-                               -1,
-                               NULL,
-                               0);
-  if (ws_len <= 0) {
-    return GetLastError();
-  }
-
-  ws = (WCHAR*) uv__malloc(ws_len * sizeof(WCHAR));
-  if (ws == NULL) {
-    return ERROR_OUTOFMEMORY;
-  }
-
-  r = MultiByteToWideChar(CP_UTF8,
-                          0,
-                          s,
-                          -1,
-                          ws,
-                          ws_len);
-  assert(r == ws_len);
-
-  *ws_ptr = ws;
-  return 0;
-}
-
-
-static void uv_process_init(uv_loop_t* loop, uv_process_t* handle) {
-  uv__handle_init(loop, (uv_handle_t*) handle, UV_PROCESS);
-  handle->exit_cb = NULL;
-  handle->pid = 0;
-  handle->exit_signal = 0;
-  handle->wait_handle = INVALID_HANDLE_VALUE;
-  handle->process_handle = INVALID_HANDLE_VALUE;
-  handle->child_stdio_buffer = NULL;
-  handle->exit_cb_pending = 0;
-
-  UV_REQ_INIT(&handle->exit_req, UV_PROCESS_EXIT);
-  handle->exit_req.data = handle;
-}
-
-
-/*
- * Path search functions
- */
-
-/*
- * Helper function for search_path
- */
-static WCHAR* search_path_join_test(const WCHAR* dir,
-                                    size_t dir_len,
-                                    const WCHAR* name,
-                                    size_t name_len,
-                                    const WCHAR* ext,
-                                    size_t ext_len,
-                                    const WCHAR* cwd,
-                                    size_t cwd_len) {
-  WCHAR *result, *result_pos;
-  DWORD attrs;
-  if (dir_len > 2 && dir[0] == L'\\' && dir[1] == L'\\') {
-    /* It's a UNC path so ignore cwd */
-    cwd_len = 0;
-  } else if (dir_len >= 1 && (dir[0] == L'/' || dir[0] == L'\\')) {
-    /* It's a full path without drive letter, use cwd's drive letter only */
-    cwd_len = 2;
-  } else if (dir_len >= 2 && dir[1] == L':' &&
-      (dir_len < 3 || (dir[2] != L'/' && dir[2] != L'\\'))) {
-    /* It's a relative path with drive letter (ext.g. D:../some/file)
-     * Replace drive letter in dir by full cwd if it points to the same drive,
-     * otherwise use the dir only.
-     */
-    if (cwd_len < 2 || _wcsnicmp(cwd, dir, 2) != 0) {
-      cwd_len = 0;
-    } else {
-      dir += 2;
-      dir_len -= 2;
-    }
-  } else if (dir_len > 2 && dir[1] == L':') {
-    /* It's an absolute path with drive letter
-     * Don't use the cwd at all
-     */
-    cwd_len = 0;
-  }
-
-  /* Allocate buffer for output */
-  result = result_pos = (WCHAR*)uv__malloc(sizeof(WCHAR) *
-      (cwd_len + 1 + dir_len + 1 + name_len + 1 + ext_len + 1));
-
-  /* Copy cwd */
-  wcsncpy(result_pos, cwd, cwd_len);
-  result_pos += cwd_len;
-
-  /* Add a path separator if cwd didn't end with one */
-  if (cwd_len && wcsrchr(L"\\/:", result_pos[-1]) == NULL) {
-    result_pos[0] = L'\\';
-    result_pos++;
-  }
-
-  /* Copy dir */
-  wcsncpy(result_pos, dir, dir_len);
-  result_pos += dir_len;
-
-  /* Add a separator if the dir didn't end with one */
-  if (dir_len && wcsrchr(L"\\/:", result_pos[-1]) == NULL) {
-    result_pos[0] = L'\\';
-    result_pos++;
-  }
-
-  /* Copy filename */
-  wcsncpy(result_pos, name, name_len);
-  result_pos += name_len;
-
-  if (ext_len) {
-    /* Add a dot if the filename didn't end with one */
-    if (name_len && result_pos[-1] != '.') {
-      result_pos[0] = L'.';
-      result_pos++;
-    }
-
-    /* Copy extension */
-    wcsncpy(result_pos, ext, ext_len);
-    result_pos += ext_len;
-  }
-
-  /* Null terminator */
-  result_pos[0] = L'\0';
-
-  attrs = GetFileAttributesW(result);
-
-  if (attrs != INVALID_FILE_ATTRIBUTES &&
-      !(attrs & FILE_ATTRIBUTE_DIRECTORY)) {
-    return result;
-  }
-
-  uv__free(result);
-  return NULL;
-}
-
-
-/*
- * Helper function for search_path
- */
-static WCHAR* path_search_walk_ext(const WCHAR *dir,
-                                   size_t dir_len,
-                                   const WCHAR *name,
-                                   size_t name_len,
-                                   WCHAR *cwd,
-                                   size_t cwd_len,
-                                   int name_has_ext) {
-  WCHAR* result;
-
-  /* If the name itself has a nonempty extension, try this extension first */
-  if (name_has_ext) {
-    result = search_path_join_test(dir, dir_len,
-                                   name, name_len,
-                                   L"", 0,
-                                   cwd, cwd_len);
-    if (result != NULL) {
-      return result;
-    }
-  }
-
-  /* Try .com extension */
-  result = search_path_join_test(dir, dir_len,
-                                 name, name_len,
-                                 L"com", 3,
-                                 cwd, cwd_len);
-  if (result != NULL) {
-    return result;
-  }
-
-  /* Try .exe extension */
-  result = search_path_join_test(dir, dir_len,
-                                 name, name_len,
-                                 L"exe", 3,
-                                 cwd, cwd_len);
-  if (result != NULL) {
-    return result;
-  }
-
-  return NULL;
-}
-
-
-/*
- * search_path searches the system path for an executable filename -
- * the windows API doesn't provide this as a standalone function nor as an
- * option to CreateProcess.
- *
- * It tries to return an absolute filename.
- *
- * Furthermore, it tries to follow the semantics that cmd.exe, with this
- * exception that PATHEXT environment variable isn't used. Since CreateProcess
- * can start only .com and .exe files, only those extensions are tried. This
- * behavior equals that of msvcrt's spawn functions.
- *
- * - Do not search the path if the filename already contains a path (either
- *   relative or absolute).
- *
- * - If there's really only a filename, check the current directory for file,
- *   then search all path directories.
- *
- * - If filename specified has *any* extension, search for the file with the
- *   specified extension first.
- *
- * - If the literal filename is not found in a directory, try *appending*
- *   (not replacing) .com first and then .exe.
- *
- * - The path variable may contain relative paths; relative paths are relative
- *   to the cwd.
- *
- * - Directories in path may or may not end with a trailing backslash.
- *
- * - CMD does not trim leading/trailing whitespace from path/pathex entries
- *   nor from the environment variables as a whole.
- *
- * - When cmd.exe cannot read a directory, it will just skip it and go on
- *   searching. However, unlike posix-y systems, it will happily try to run a
- *   file that is not readable/executable; if the spawn fails it will not
- *   continue searching.
- *
- * UNC path support: we are dealing with UNC paths in both the path and the
- * filename. This is a deviation from what cmd.exe does (it does not let you
- * start a program by specifying an UNC path on the command line) but this is
- * really a pointless restriction.
- *
- */
-static WCHAR* search_path(const WCHAR *file,
-                            WCHAR *cwd,
-                            const WCHAR *path) {
-  int file_has_dir;
-  WCHAR* result = NULL;
-  WCHAR *file_name_start;
-  WCHAR *dot;
-  const WCHAR *dir_start, *dir_end, *dir_path;
-  size_t dir_len;
-  int name_has_ext;
-
-  size_t file_len = wcslen(file);
-  size_t cwd_len = wcslen(cwd);
-
-  /* If the caller supplies an empty filename,
-   * we're not gonna return c:\windows\.exe -- GFY!
-   */
-  if (file_len == 0
-      || (file_len == 1 && file[0] == L'.')) {
-    return NULL;
-  }
-
-  /* Find the start of the filename so we can split the directory from the
-   * name. */
-  for (file_name_start = (WCHAR*)file + file_len;
-       file_name_start > file
-           && file_name_start[-1] != L'\\'
-           && file_name_start[-1] != L'/'
-           && file_name_start[-1] != L':';
-       file_name_start--);
-
-  file_has_dir = file_name_start != file;
-
-  /* Check if the filename includes an extension */
-  dot = wcschr(file_name_start, L'.');
-  name_has_ext = (dot != NULL && dot[1] != L'\0');
-
-  if (file_has_dir) {
-    /* The file has a path inside, don't use path */
-    result = path_search_walk_ext(
-        file, file_name_start - file,
-        file_name_start, file_len - (file_name_start - file),
-        cwd, cwd_len,
-        name_has_ext);
-
-  } else {
-    dir_end = path;
-
-    /* The file is really only a name; look in cwd first, then scan path */
-    result = path_search_walk_ext(L"", 0,
-                                  file, file_len,
-                                  cwd, cwd_len,
-                                  name_has_ext);
-
-    while (result == NULL) {
-      if (*dir_end == L'\0') {
-        break;
-      }
-
-      /* Skip the separator that dir_end now points to */
-      if (dir_end != path || *path == L';') {
-        dir_end++;
-      }
-
-      /* Next slice starts just after where the previous one ended */
-      dir_start = dir_end;
-
-      /* If path is quoted, find quote end */
-      if (*dir_start == L'"' || *dir_start == L'\'') {
-        dir_end = wcschr(dir_start + 1, *dir_start);
-        if (dir_end == NULL) {
-          dir_end = wcschr(dir_start, L'\0');
-        }
-      }
-      /* Slice until the next ; or \0 is found */
-      dir_end = wcschr(dir_end, L';');
-      if (dir_end == NULL) {
-        dir_end = wcschr(dir_start, L'\0');
-      }
-
-      /* If the slice is zero-length, don't bother */
-      if (dir_end - dir_start == 0) {
-        continue;
-      }
-
-      dir_path = dir_start;
-      dir_len = dir_end - dir_start;
-
-      /* Adjust if the path is quoted. */
-      if (dir_path[0] == '"' || dir_path[0] == '\'') {
-        ++dir_path;
-        --dir_len;
-      }
-
-      if (dir_path[dir_len - 1] == '"' || dir_path[dir_len - 1] == '\'') {
-        --dir_len;
-      }
-
-      result = path_search_walk_ext(dir_path, dir_len,
-                                    file, file_len,
-                                    cwd, cwd_len,
-                                    name_has_ext);
-    }
-  }
-
-  return result;
-}
-
-
-/*
- * Quotes command line arguments
- * Returns a pointer to the end (next char to be written) of the buffer
- */
-WCHAR* quote_cmd_arg(const WCHAR *source, WCHAR *target) {
-  size_t len = wcslen(source);
-  size_t i;
-  int quote_hit;
-  WCHAR* start;
-
-  if (len == 0) {
-    /* Need double quotation for empty argument */
-    *(target++) = L'"';
-    *(target++) = L'"';
-    return target;
-  }
-
-  if (NULL == wcspbrk(source, L" \t\"")) {
-    /* No quotation needed */
-    wcsncpy(target, source, len);
-    target += len;
-    return target;
-  }
-
-  if (NULL == wcspbrk(source, L"\"\\")) {
-    /*
-     * No embedded double quotes or backlashes, so I can just wrap
-     * quote marks around the whole thing.
-     */
-    *(target++) = L'"';
-    wcsncpy(target, source, len);
-    target += len;
-    *(target++) = L'"';
-    return target;
-  }
-
-  /*
-   * Expected input/output:
-   *   input : hello"world
-   *   output: "hello\"world"
-   *   input : hello""world
-   *   output: "hello\"\"world"
-   *   input : hello\world
-   *   output: hello\world
-   *   input : hello\\world
-   *   output: hello\\world
-   *   input : hello\"world
-   *   output: "hello\\\"world"
-   *   input : hello\\"world
-   *   output: "hello\\\\\"world"
-   *   input : hello world\
-   *   output: "hello world\\"
-   */
-
-  *(target++) = L'"';
-  start = target;
-  quote_hit = 1;
-
-  for (i = len; i > 0; --i) {
-    *(target++) = source[i - 1];
-
-    if (quote_hit && source[i - 1] == L'\\') {
-      *(target++) = L'\\';
-    } else if(source[i - 1] == L'"') {
-      quote_hit = 1;
-      *(target++) = L'\\';
-    } else {
-      quote_hit = 0;
-    }
-  }
-  target[0] = L'\0';
-  wcsrev(start);
-  *(target++) = L'"';
-  return target;
-}
-
-
-int make_program_args(char** args, int verbatim_arguments, WCHAR** dst_ptr) {
-  char** arg;
-  WCHAR* dst = NULL;
-  WCHAR* temp_buffer = NULL;
-  size_t dst_len = 0;
-  size_t temp_buffer_len = 0;
-  WCHAR* pos;
-  int arg_count = 0;
-  int err = 0;
-
-  /* Count the required size. */
-  for (arg = args; *arg; arg++) {
-    DWORD arg_len;
-
-    arg_len = MultiByteToWideChar(CP_UTF8,
-                                  0,
-                                  *arg,
-                                  -1,
-                                  NULL,
-                                  0);
-    if (arg_len == 0) {
-      return GetLastError();
-    }
-
-    dst_len += arg_len;
-
-    if (arg_len > temp_buffer_len)
-      temp_buffer_len = arg_len;
-
-    arg_count++;
-  }
-
-  /* Adjust for potential quotes. Also assume the worst-case scenario that
-   * every character needs escaping, so we need twice as much space. */
-  dst_len = dst_len * 2 + arg_count * 2;
-
-  /* Allocate buffer for the final command line. */
-  dst = (WCHAR*) uv__malloc(dst_len * sizeof(WCHAR));
-  if (dst == NULL) {
-    err = ERROR_OUTOFMEMORY;
-    goto error;
-  }
-
-  /* Allocate temporary working buffer. */
-  temp_buffer = (WCHAR*) uv__malloc(temp_buffer_len * sizeof(WCHAR));
-  if (temp_buffer == NULL) {
-    err = ERROR_OUTOFMEMORY;
-    goto error;
-  }
-
-  pos = dst;
-  for (arg = args; *arg; arg++) {
-    DWORD arg_len;
-
-    /* Convert argument to wide char. */
-    arg_len = MultiByteToWideChar(CP_UTF8,
-                                  0,
-                                  *arg,
-                                  -1,
-                                  temp_buffer,
-                                  (int) (dst + dst_len - pos));
-    if (arg_len == 0) {
-      err = GetLastError();
-      goto error;
-    }
-
-    if (verbatim_arguments) {
-      /* Copy verbatim. */
-      wcscpy(pos, temp_buffer);
-      pos += arg_len - 1;
-    } else {
-      /* Quote/escape, if needed. */
-      pos = quote_cmd_arg(temp_buffer, pos);
-    }
-
-    *pos++ = *(arg + 1) ? L' ' : L'\0';
-  }
-
-  uv__free(temp_buffer);
-
-  *dst_ptr = dst;
-  return 0;
-
-error:
-  uv__free(dst);
-  uv__free(temp_buffer);
-  return err;
-}
-
-
-int env_strncmp(const wchar_t* a, int na, const wchar_t* b) {
-  const wchar_t* a_eq;
-  const wchar_t* b_eq;
-  wchar_t* A;
-  wchar_t* B;
-  int nb;
-  int r;
-
-  if (na < 0) {
-    a_eq = wcschr(a, L'=');
-    assert(a_eq);
-    na = (int)(long)(a_eq - a);
-  } else {
-    na--;
-  }
-  b_eq = wcschr(b, L'=');
-  assert(b_eq);
-  nb = b_eq - b;
-
-  A = (wchar_t*)alloca((na+1) * sizeof(wchar_t));
-  B = (wchar_t*)alloca((nb+1) * sizeof(wchar_t));
-
-  r = LCMapStringW(LOCALE_INVARIANT, LCMAP_UPPERCASE, a, na, A, na);
-  assert(r==na);
-  A[na] = L'\0';
-  r = LCMapStringW(LOCALE_INVARIANT, LCMAP_UPPERCASE, b, nb, B, nb);
-  assert(r==nb);
-  B[nb] = L'\0';
-
-  while (1) {
-    wchar_t AA = *A++;
-    wchar_t BB = *B++;
-    if (AA < BB) {
-      return -1;
-    } else if (AA > BB) {
-      return 1;
-    } else if (!AA && !BB) {
-      return 0;
-    }
-  }
-}
-
-
-static int qsort_wcscmp(const void *a, const void *b) {
-  wchar_t* astr = *(wchar_t* const*)a;
-  wchar_t* bstr = *(wchar_t* const*)b;
-  return env_strncmp(astr, -1, bstr);
-}
-
-
-/*
- * The way windows takes environment variables is different than what C does;
- * Windows wants a contiguous block of null-terminated strings, terminated
- * with an additional null.
- *
- * Windows has a few "essential" environment variables. winsock will fail
- * to initialize if SYSTEMROOT is not defined; some APIs make reference to
- * TEMP. SYSTEMDRIVE is probably also important. We therefore ensure that
- * these get defined if the input environment block does not contain any
- * values for them.
- *
- * Also add variables known to Cygwin to be required for correct
- * subprocess operation in many cases:
- * https://github.com/Alexpux/Cygwin/blob/b266b04fbbd3a595f02ea149e4306d3ab9b1fe3d/winsup/cygwin/environ.cc#L955
- *
- */
-int make_program_env(char* env_block[], WCHAR** dst_ptr) {
-  WCHAR* dst;
-  WCHAR* ptr;
-  char** env;
-  size_t env_len = 0;
-  int len;
-  size_t i;
-  DWORD var_size;
-  size_t env_block_count = 1; /* 1 for null-terminator */
-  WCHAR* dst_copy;
-  WCHAR** ptr_copy;
-  WCHAR** env_copy;
-  DWORD* required_vars_value_len =
-      (DWORD*)alloca(n_required_vars * sizeof(DWORD*));
-
-  /* first pass: determine size in UTF-16 */
-  for (env = env_block; *env; env++) {
-    int len;
-    if (strchr(*env, '=')) {
-      len = MultiByteToWideChar(CP_UTF8,
-                                0,
-                                *env,
-                                -1,
-                                NULL,
-                                0);
-      if (len <= 0) {
-        return GetLastError();
-      }
-      env_len += len;
-      env_block_count++;
-    }
-  }
-
-  /* second pass: copy to UTF-16 environment block */
-  dst_copy = (WCHAR*)uv__malloc(env_len * sizeof(WCHAR));
-  if (!dst_copy) {
-    return ERROR_OUTOFMEMORY;
-  }
-  env_copy = (WCHAR**)alloca(env_block_count * sizeof(WCHAR*));
-
-  ptr = dst_copy;
-  ptr_copy = env_copy;
-  for (env = env_block; *env; env++) {
-    if (strchr(*env, '=')) {
-      len = MultiByteToWideChar(CP_UTF8,
-                                0,
-                                *env,
-                                -1,
-                                ptr,
-                                (int) (env_len - (ptr - dst_copy)));
-      if (len <= 0) {
-        DWORD err = GetLastError();
-        uv__free(dst_copy);
-        return err;
-      }
-      *ptr_copy++ = ptr;
-      ptr += len;
-    }
-  }
-  *ptr_copy = NULL;
-  assert(env_len == (size_t) (ptr - dst_copy));
-
-  /* sort our (UTF-16) copy */
-  qsort(env_copy, env_block_count-1, sizeof(wchar_t*), qsort_wcscmp);
-
-  /* third pass: check for required variables */
-  for (ptr_copy = env_copy, i = 0; i < n_required_vars; ) {
-    int cmp;
-    if (!*ptr_copy) {
-      cmp = -1;
-    } else {
-      cmp = env_strncmp(required_vars[i].wide_eq,
-                       required_vars[i].len,
-                        *ptr_copy);
-    }
-    if (cmp < 0) {
-      /* missing required var */
-      var_size = GetEnvironmentVariableW(required_vars[i].wide, NULL, 0);
-      required_vars_value_len[i] = var_size;
-      if (var_size != 0) {
-        env_len += required_vars[i].len;
-        env_len += var_size;
-      }
-      i++;
-    } else {
-      ptr_copy++;
-      if (cmp == 0)
-        i++;
-    }
-  }
-
-  /* final pass: copy, in sort order, and inserting required variables */
-  dst = (WCHAR*)uv__malloc((1+env_len) * sizeof(WCHAR));
-  if (!dst) {
-    uv__free(dst_copy);
-    return ERROR_OUTOFMEMORY;
-  }
-
-  for (ptr = dst, ptr_copy = env_copy, i = 0;
-       *ptr_copy || i < n_required_vars;
-       ptr += len) {
-    int cmp;
-    if (i >= n_required_vars) {
-      cmp = 1;
-    } else if (!*ptr_copy) {
-      cmp = -1;
-    } else {
-      cmp = env_strncmp(required_vars[i].wide_eq,
-                        required_vars[i].len,
-                        *ptr_copy);
-    }
-    if (cmp < 0) {
-      /* missing required var */
-      len = required_vars_value_len[i];
-      if (len) {
-        wcscpy(ptr, required_vars[i].wide_eq);
-        ptr += required_vars[i].len;
-        var_size = GetEnvironmentVariableW(required_vars[i].wide,
-                                           ptr,
-                                           (int) (env_len - (ptr - dst)));
-        if (var_size != (DWORD) (len - 1)) { /* TODO: handle race condition? */
-          uv_fatal_error(GetLastError(), "GetEnvironmentVariableW");
-        }
-      }
-      i++;
-    } else {
-      /* copy var from env_block */
-      len = wcslen(*ptr_copy) + 1;
-      wmemcpy(ptr, *ptr_copy, len);
-      ptr_copy++;
-      if (cmp == 0)
-        i++;
-    }
-  }
-
-  /* Terminate with an extra NULL. */
-  assert(env_len == (size_t) (ptr - dst));
-  *ptr = L'\0';
-
-  uv__free(dst_copy);
-  *dst_ptr = dst;
-  return 0;
-}
-
-/*
- * Attempt to find the value of the PATH environment variable in the child's
- * preprocessed environment.
- *
- * If found, a pointer into `env` is returned. If not found, NULL is returned.
- */
-static WCHAR* find_path(WCHAR *env) {
-  for (; env != NULL && *env != 0; env += wcslen(env) + 1) {
-    if ((env[0] == L'P' || env[0] == L'p') &&
-        (env[1] == L'A' || env[1] == L'a') &&
-        (env[2] == L'T' || env[2] == L't') &&
-        (env[3] == L'H' || env[3] == L'h') &&
-        (env[4] == L'=')) {
-      return &env[5];
-    }
-  }
-
-  return NULL;
-}
-
-/*
- * Called on Windows thread-pool thread to indicate that
- * a child process has exited.
- */
-static void CALLBACK exit_wait_callback(void* data, BOOLEAN didTimeout) {
-  uv_process_t* process = (uv_process_t*) data;
-  uv_loop_t* loop = process->loop;
-
-  assert(didTimeout == FALSE);
-  assert(process);
-  assert(!process->exit_cb_pending);
-
-  process->exit_cb_pending = 1;
-
-  /* Post completed */
-  POST_COMPLETION_FOR_REQ(loop, &process->exit_req);
-}
-
-
-/* Called on main thread after a child process has exited. */
-void uv_process_proc_exit(uv_loop_t* loop, uv_process_t* handle) {
-  int64_t exit_code;
-  DWORD status;
-
-  assert(handle->exit_cb_pending);
-  handle->exit_cb_pending = 0;
-
-  /* If we're closing, don't call the exit callback. Just schedule a close
-   * callback now. */
-  if (handle->flags & UV_HANDLE_CLOSING) {
-    uv_want_endgame(loop, (uv_handle_t*) handle);
-    return;
-  }
-
-  /* Unregister from process notification. */
-  if (handle->wait_handle != INVALID_HANDLE_VALUE) {
-    UnregisterWait(handle->wait_handle);
-    handle->wait_handle = INVALID_HANDLE_VALUE;
-  }
-
-  /* Set the handle to inactive: no callbacks will be made after the exit
-   * callback. */
-  uv__handle_stop(handle);
-
-  if (GetExitCodeProcess(handle->process_handle, &status)) {
-    exit_code = status;
-  } else {
-    /* Unable to obtain the exit code. This should never happen. */
-    exit_code = uv_translate_sys_error(GetLastError());
-  }
-
-  /* Fire the exit callback. */
-  if (handle->exit_cb) {
-    handle->exit_cb(handle, exit_code, handle->exit_signal);
-  }
-}
-
-
-void uv_process_close(uv_loop_t* loop, uv_process_t* handle) {
-  uv__handle_closing(handle);
-
-  if (handle->wait_handle != INVALID_HANDLE_VALUE) {
-    /* This blocks until either the wait was cancelled, or the callback has
-     * completed. */
-    BOOL r = UnregisterWaitEx(handle->wait_handle, INVALID_HANDLE_VALUE);
-    if (!r) {
-      /* This should never happen, and if it happens, we can't recover... */
-      uv_fatal_error(GetLastError(), "UnregisterWaitEx");
-    }
-
-    handle->wait_handle = INVALID_HANDLE_VALUE;
-  }
-
-  if (!handle->exit_cb_pending) {
-    uv_want_endgame(loop, (uv_handle_t*)handle);
-  }
-}
-
-
-void uv_process_endgame(uv_loop_t* loop, uv_process_t* handle) {
-  assert(!handle->exit_cb_pending);
-  assert(handle->flags & UV_HANDLE_CLOSING);
-  assert(!(handle->flags & UV_HANDLE_CLOSED));
-
-  /* Clean-up the process handle. */
-  CloseHandle(handle->process_handle);
-
-  uv__handle_close(handle);
-}
-
-
-int uv_spawn(uv_loop_t* loop,
-             uv_process_t* process,
-             const uv_process_options_t* options) {
-  int i;
-  int err = 0;
-  WCHAR* path = NULL, *alloc_path = NULL;
-  BOOL result;
-  WCHAR* application_path = NULL, *application = NULL, *arguments = NULL,
-         *env = NULL, *cwd = NULL;
-  STARTUPINFOW startup;
-  PROCESS_INFORMATION info;
-  DWORD process_flags;
-
-  uv_process_init(loop, process);
-  process->exit_cb = options->exit_cb;
-
-  if (options->flags & (UV_PROCESS_SETGID | UV_PROCESS_SETUID)) {
-    return UV_ENOTSUP;
-  }
-
-  if (options->file == NULL ||
-      options->args == NULL) {
-    return UV_EINVAL;
-  }
-
-  assert(options->file != NULL);
-  assert(!(options->flags & ~(UV_PROCESS_DETACHED |
-                              UV_PROCESS_SETGID |
-                              UV_PROCESS_SETUID |
-                              UV_PROCESS_WINDOWS_HIDE |
-                              UV_PROCESS_WINDOWS_HIDE_CONSOLE |
-                              UV_PROCESS_WINDOWS_HIDE_GUI |
-                              UV_PROCESS_WINDOWS_VERBATIM_ARGUMENTS)));
-
-  err = uv_utf8_to_utf16_alloc(options->file, &application);
-  if (err)
-    goto done;
-
-  err = make_program_args(
-      options->args,
-      options->flags & UV_PROCESS_WINDOWS_VERBATIM_ARGUMENTS,
-      &arguments);
-  if (err)
-    goto done;
-
-  if (options->env) {
-     err = make_program_env(options->env, &env);
-     if (err)
-       goto done;
-  }
-
-  if (options->cwd) {
-    /* Explicit cwd */
-    err = uv_utf8_to_utf16_alloc(options->cwd, &cwd);
-    if (err)
-      goto done;
-
-  } else {
-    /* Inherit cwd */
-    DWORD cwd_len, r;
-
-    cwd_len = GetCurrentDirectoryW(0, NULL);
-    if (!cwd_len) {
-      err = GetLastError();
-      goto done;
-    }
-
-    cwd = (WCHAR*) uv__malloc(cwd_len * sizeof(WCHAR));
-    if (cwd == NULL) {
-      err = ERROR_OUTOFMEMORY;
-      goto done;
-    }
-
-    r = GetCurrentDirectoryW(cwd_len, cwd);
-    if (r == 0 || r >= cwd_len) {
-      err = GetLastError();
-      goto done;
-    }
-  }
-
-  /* Get PATH environment variable. */
-  path = find_path(env);
-  if (path == NULL) {
-    DWORD path_len, r;
-
-    path_len = GetEnvironmentVariableW(L"PATH", NULL, 0);
-    if (path_len == 0) {
-      err = GetLastError();
-      goto done;
-    }
-
-    alloc_path = (WCHAR*) uv__malloc(path_len * sizeof(WCHAR));
-    if (alloc_path == NULL) {
-      err = ERROR_OUTOFMEMORY;
-      goto done;
-    }
-    path = alloc_path;
-
-    r = GetEnvironmentVariableW(L"PATH", path, path_len);
-    if (r == 0 || r >= path_len) {
-      err = GetLastError();
-      goto done;
-    }
-  }
-
-  err = uv__stdio_create(loop, options, &process->child_stdio_buffer);
-  if (err)
-    goto done;
-
-  application_path = search_path(application,
-                                 cwd,
-                                 path);
-  if (application_path == NULL) {
-    /* Not found. */
-    err = ERROR_FILE_NOT_FOUND;
-    goto done;
-  }
-
-  startup.cb = sizeof(startup);
-  startup.lpReserved = NULL;
-  startup.lpDesktop = NULL;
-  startup.lpTitle = NULL;
-  startup.dwFlags = STARTF_USESTDHANDLES | STARTF_USESHOWWINDOW;
-
-  startup.cbReserved2 = uv__stdio_size(process->child_stdio_buffer);
-  startup.lpReserved2 = (BYTE*) process->child_stdio_buffer;
-
-  startup.hStdInput = uv__stdio_handle(process->child_stdio_buffer, 0);
-  startup.hStdOutput = uv__stdio_handle(process->child_stdio_buffer, 1);
-  startup.hStdError = uv__stdio_handle(process->child_stdio_buffer, 2);
-
-  process_flags = CREATE_UNICODE_ENVIRONMENT;
-
-  if ((options->flags & UV_PROCESS_WINDOWS_HIDE_CONSOLE) ||
-      (options->flags & UV_PROCESS_WINDOWS_HIDE)) {
-    /* Avoid creating console window if stdio is not inherited. */
-    for (i = 0; i < options->stdio_count; i++) {
-      if (options->stdio[i].flags & UV_INHERIT_FD)
-        break;
-      if (i == options->stdio_count - 1)
-        process_flags |= CREATE_NO_WINDOW;
-    }
-  }
-  if ((options->flags & UV_PROCESS_WINDOWS_HIDE_GUI) ||
-      (options->flags & UV_PROCESS_WINDOWS_HIDE)) {
-    /* Use SW_HIDE to avoid any potential process window. */
-    startup.wShowWindow = SW_HIDE;
-  } else {
-    startup.wShowWindow = SW_SHOWDEFAULT;
-  }
-
-  if (options->flags & UV_PROCESS_DETACHED) {
-    /* Note that we're not setting the CREATE_BREAKAWAY_FROM_JOB flag. That
-     * means that libuv might not let you create a fully daemonized process
-     * when run under job control. However the type of job control that libuv
-     * itself creates doesn't trickle down to subprocesses so they can still
-     * daemonize.
-     *
-     * A reason to not do this is that CREATE_BREAKAWAY_FROM_JOB makes the
-     * CreateProcess call fail if we're under job control that doesn't allow
-     * breakaway.
-     */
-    process_flags |= DETACHED_PROCESS | CREATE_NEW_PROCESS_GROUP;
-  }
-
-  if (!CreateProcessW(application_path,
-                     arguments,
-                     NULL,
-                     NULL,
-                     1,
-                     process_flags,
-                     env,
-                     cwd,
-                     &startup,
-                     &info)) {
-    /* CreateProcessW failed. */
-    err = GetLastError();
-    goto done;
-  }
-
-  /* Spawn succeeded. Beyond this point, failure is reported asynchronously. */
-
-  process->process_handle = info.hProcess;
-  process->pid = info.dwProcessId;
-
-  /* If the process isn't spawned as detached, assign to the global job object
-   * so windows will kill it when the parent process dies. */
-  if (!(options->flags & UV_PROCESS_DETACHED)) {
-    uv_once(&uv_global_job_handle_init_guard_, uv__init_global_job_handle);
-
-    if (!AssignProcessToJobObject(uv_global_job_handle_, info.hProcess)) {
-      /* AssignProcessToJobObject might fail if this process is under job
-       * control and the job doesn't have the
-       * JOB_OBJECT_LIMIT_SILENT_BREAKAWAY_OK flag set, on a Windows version
-       * that doesn't support nested jobs.
-       *
-       * When that happens we just swallow the error and continue without
-       * establishing a kill-child-on-parent-exit relationship, otherwise
-       * there would be no way for libuv applications run under job control
-       * to spawn processes at all.
-       */
-      DWORD err = GetLastError();
-      if (err != ERROR_ACCESS_DENIED)
-        uv_fatal_error(err, "AssignProcessToJobObject");
-    }
-  }
-
-  /* Set IPC pid to all IPC pipes. */
-  for (i = 0; i < options->stdio_count; i++) {
-    const uv_stdio_container_t* fdopt = &options->stdio[i];
-    if (fdopt->flags & UV_CREATE_PIPE &&
-        fdopt->data.stream->type == UV_NAMED_PIPE &&
-        ((uv_pipe_t*) fdopt->data.stream)->ipc) {
-      ((uv_pipe_t*) fdopt->data.stream)->pipe.conn.ipc_remote_pid =
-          info.dwProcessId;
-    }
-  }
-
-  /* Setup notifications for when the child process exits. */
-  result = RegisterWaitForSingleObject(&process->wait_handle,
-      process->process_handle, exit_wait_callback, (void*)process, INFINITE,
-      WT_EXECUTEINWAITTHREAD | WT_EXECUTEONLYONCE);
-  if (!result) {
-    uv_fatal_error(GetLastError(), "RegisterWaitForSingleObject");
-  }
-
-  CloseHandle(info.hThread);
-
-  assert(!err);
-
-  /* Make the handle active. It will remain active until the exit callback is
-   * made or the handle is closed, whichever happens first. */
-  uv__handle_start(process);
-
-  /* Cleanup, whether we succeeded or failed. */
- done:
-  uv__free(application);
-  uv__free(application_path);
-  uv__free(arguments);
-  uv__free(cwd);
-  uv__free(env);
-  uv__free(alloc_path);
-
-  if (process->child_stdio_buffer != NULL) {
-    /* Clean up child stdio handles. */
-    uv__stdio_destroy(process->child_stdio_buffer);
-    process->child_stdio_buffer = NULL;
-  }
-
-  return uv_translate_sys_error(err);
-}
-
-
-static int uv__kill(HANDLE process_handle, int signum) {
-  if (signum < 0 || signum >= NSIG) {
-    return UV_EINVAL;
-  }
-
-  switch (signum) {
-    case SIGTERM:
-    case SIGKILL:
-    case SIGINT: {
-      /* Unconditionally terminate the process. On Windows, killed processes
-       * normally return 1. */
-      DWORD status;
-      int err;
-
-      if (TerminateProcess(process_handle, 1))
-        return 0;
-
-      /* If the process already exited before TerminateProcess was called,.
-       * TerminateProcess will fail with ERROR_ACCESS_DENIED. */
-      err = GetLastError();
-      if (err == ERROR_ACCESS_DENIED &&
-          GetExitCodeProcess(process_handle, &status) &&
-          status != STILL_ACTIVE) {
-        return UV_ESRCH;
-      }
-
-      return uv_translate_sys_error(err);
-    }
-
-    case 0: {
-      /* Health check: is the process still alive? */
-      DWORD status;
-
-      if (!GetExitCodeProcess(process_handle, &status))
-        return uv_translate_sys_error(GetLastError());
-
-      if (status != STILL_ACTIVE)
-        return UV_ESRCH;
-
-      return 0;
-    }
-
-    default:
-      /* Unsupported signal. */
-      return UV_ENOSYS;
-  }
-}
-
-
-int uv_process_kill(uv_process_t* process, int signum) {
-  int err;
-
-  if (process->process_handle == INVALID_HANDLE_VALUE) {
-    return UV_EINVAL;
-  }
-
-  err = uv__kill(process->process_handle, signum);
-  if (err) {
-    return err;  /* err is already translated. */
-  }
-
-  process->exit_signal = signum;
-
-  return 0;
-}
-
-
-int uv_kill(int pid, int signum) {
-  int err;
-  HANDLE process_handle;
-
-  if (pid == 0) {
-    process_handle = GetCurrentProcess();
-  } else {
-    process_handle = OpenProcess(PROCESS_TERMINATE | PROCESS_QUERY_INFORMATION,
-                                 FALSE,
-                                 pid);
-  }
-
-  if (process_handle == NULL) {
-    err = GetLastError();
-    if (err == ERROR_INVALID_PARAMETER) {
-      return UV_ESRCH;
-    } else {
-      return uv_translate_sys_error(err);
-    }
-  }
-
-  err = uv__kill(process_handle, signum);
-  CloseHandle(process_handle);
-
-  return err;  /* err is already translated. */
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/req-inl.h b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/req-inl.h
deleted file mode 100644
index f2513b7..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/req-inl.h
+++ /dev/null
@@ -1,221 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#ifndef UV_WIN_REQ_INL_H_
-#define UV_WIN_REQ_INL_H_
-
-#include <assert.h>
-
-#include "uv.h"
-#include "internal.h"
-
-
-#define SET_REQ_STATUS(req, status)                                     \
-   (req)->u.io.overlapped.Internal = (ULONG_PTR) (status)
-
-#define SET_REQ_ERROR(req, error)                                       \
-  SET_REQ_STATUS((req), NTSTATUS_FROM_WIN32((error)))
-
-/* Note: used open-coded in UV_REQ_INIT() because of a circular dependency
- * between src/uv-common.h and src/win/internal.h.
- */
-#define SET_REQ_SUCCESS(req)                                            \
-  SET_REQ_STATUS((req), STATUS_SUCCESS)
-
-#define GET_REQ_STATUS(req)                                             \
-  ((NTSTATUS) (req)->u.io.overlapped.Internal)
-
-#define REQ_SUCCESS(req)                                                \
-  (NT_SUCCESS(GET_REQ_STATUS((req))))
-
-#define GET_REQ_ERROR(req)                                              \
-  (pRtlNtStatusToDosError(GET_REQ_STATUS((req))))
-
-#define GET_REQ_SOCK_ERROR(req)                                         \
-  (uv_ntstatus_to_winsock_error(GET_REQ_STATUS((req))))
-
-
-#define REGISTER_HANDLE_REQ(loop, handle, req)                          \
-  do {                                                                  \
-    INCREASE_ACTIVE_COUNT((loop), (handle));                            \
-    uv__req_register((loop), (req));                                    \
-  } while (0)
-
-#define UNREGISTER_HANDLE_REQ(loop, handle, req)                        \
-  do {                                                                  \
-    DECREASE_ACTIVE_COUNT((loop), (handle));                            \
-    uv__req_unregister((loop), (req));                                  \
-  } while (0)
-
-
-#define UV_SUCCEEDED_WITHOUT_IOCP(result)                               \
-  ((result) && (handle->flags & UV_HANDLE_SYNC_BYPASS_IOCP))
-
-#define UV_SUCCEEDED_WITH_IOCP(result)                                  \
-  ((result) || (GetLastError() == ERROR_IO_PENDING))
-
-
-#define POST_COMPLETION_FOR_REQ(loop, req)                              \
-  if (!PostQueuedCompletionStatus((loop)->iocp,                         \
-                                  0,                                    \
-                                  0,                                    \
-                                  &((req)->u.io.overlapped))) {         \
-    uv_fatal_error(GetLastError(), "PostQueuedCompletionStatus");       \
-  }
-
-
-INLINE static uv_req_t* uv_overlapped_to_req(OVERLAPPED* overlapped) {
-  return CONTAINING_RECORD(overlapped, uv_req_t, u.io.overlapped);
-}
-
-
-INLINE static void uv_insert_pending_req(uv_loop_t* loop, uv_req_t* req) {
-  req->next_req = NULL;
-  if (loop->pending_reqs_tail) {
-#ifdef _DEBUG
-    /* Ensure the request is not already in the queue, or the queue
-     * will get corrupted.
-     */
-    uv_req_t* current = loop->pending_reqs_tail;
-    do {
-      assert(req != current);
-      current = current->next_req;
-    } while(current != loop->pending_reqs_tail);
-#endif
-
-    req->next_req = loop->pending_reqs_tail->next_req;
-    loop->pending_reqs_tail->next_req = req;
-    loop->pending_reqs_tail = req;
-  } else {
-    req->next_req = req;
-    loop->pending_reqs_tail = req;
-  }
-}
-
-
-#define DELEGATE_STREAM_REQ(loop, req, method, handle_at)                     \
-  do {                                                                        \
-    switch (((uv_handle_t*) (req)->handle_at)->type) {                        \
-      case UV_TCP:                                                            \
-        uv_process_tcp_##method##_req(loop,                                   \
-                                      (uv_tcp_t*) ((req)->handle_at),         \
-                                      req);                                   \
-        break;                                                                \
-                                                                              \
-      case UV_NAMED_PIPE:                                                     \
-        uv_process_pipe_##method##_req(loop,                                  \
-                                       (uv_pipe_t*) ((req)->handle_at),       \
-                                       req);                                  \
-        break;                                                                \
-                                                                              \
-      case UV_TTY:                                                            \
-        uv_process_tty_##method##_req(loop,                                   \
-                                      (uv_tty_t*) ((req)->handle_at),         \
-                                      req);                                   \
-        break;                                                                \
-                                                                              \
-      default:                                                                \
-        assert(0);                                                            \
-    }                                                                         \
-  } while (0)
-
-
-INLINE static int uv_process_reqs(uv_loop_t* loop) {
-  uv_req_t* req;
-  uv_req_t* first;
-  uv_req_t* next;
-
-  if (loop->pending_reqs_tail == NULL)
-    return 0;
-
-  first = loop->pending_reqs_tail->next_req;
-  next = first;
-  loop->pending_reqs_tail = NULL;
-
-  while (next != NULL) {
-    req = next;
-    next = req->next_req != first ? req->next_req : NULL;
-
-    switch (req->type) {
-      case UV_READ:
-        DELEGATE_STREAM_REQ(loop, req, read, data);
-        break;
-
-      case UV_WRITE:
-        DELEGATE_STREAM_REQ(loop, (uv_write_t*) req, write, handle);
-        break;
-
-      case UV_ACCEPT:
-        DELEGATE_STREAM_REQ(loop, req, accept, data);
-        break;
-
-      case UV_CONNECT:
-        DELEGATE_STREAM_REQ(loop, (uv_connect_t*) req, connect, handle);
-        break;
-
-      case UV_SHUTDOWN:
-        /* Tcp shutdown requests don't come here. */
-        assert(((uv_shutdown_t*) req)->handle->type == UV_NAMED_PIPE);
-        uv_process_pipe_shutdown_req(
-            loop,
-            (uv_pipe_t*) ((uv_shutdown_t*) req)->handle,
-            (uv_shutdown_t*) req);
-        break;
-
-      case UV_UDP_RECV:
-        uv_process_udp_recv_req(loop, (uv_udp_t*) req->data, req);
-        break;
-
-      case UV_UDP_SEND:
-        uv_process_udp_send_req(loop,
-                                ((uv_udp_send_t*) req)->handle,
-                                (uv_udp_send_t*) req);
-        break;
-
-      case UV_WAKEUP:
-        uv_process_async_wakeup_req(loop, (uv_async_t*) req->data, req);
-        break;
-
-      case UV_SIGNAL_REQ:
-        uv_process_signal_req(loop, (uv_signal_t*) req->data, req);
-        break;
-
-      case UV_POLL_REQ:
-        uv_process_poll_req(loop, (uv_poll_t*) req->data, req);
-        break;
-
-      case UV_PROCESS_EXIT:
-        uv_process_proc_exit(loop, (uv_process_t*) req->data);
-        break;
-
-      case UV_FS_EVENT_REQ:
-        uv_process_fs_event_req(loop, req, (uv_fs_event_t*) req->data);
-        break;
-
-      default:
-        assert(0);
-    }
-  }
-
-  return 1;
-}
-
-#endif /* UV_WIN_REQ_INL_H_ */
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/signal.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/signal.cpp
deleted file mode 100644
index 276dc60..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/signal.cpp
+++ /dev/null
@@ -1,277 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include <assert.h>
-#include <signal.h>
-
-#include "uv.h"
-#include "internal.h"
-#include "handle-inl.h"
-#include "req-inl.h"
-
-
-RB_HEAD(uv_signal_tree_s, uv_signal_s);
-
-static struct uv_signal_tree_s uv__signal_tree = RB_INITIALIZER(uv__signal_tree);
-static CRITICAL_SECTION uv__signal_lock;
-
-static BOOL WINAPI uv__signal_control_handler(DWORD type);
-
-int uv__signal_start(uv_signal_t* handle,
-                     uv_signal_cb signal_cb,
-                     int signum,
-                     int oneshot);
-
-void uv_signals_init(void) {
-  InitializeCriticalSection(&uv__signal_lock);
-  if (!SetConsoleCtrlHandler(uv__signal_control_handler, TRUE))
-    abort();
-}
-
-
-static int uv__signal_compare(uv_signal_t* w1, uv_signal_t* w2) {
-  /* Compare signums first so all watchers with the same signnum end up
-   * adjacent. */
-  if (w1->signum < w2->signum) return -1;
-  if (w1->signum > w2->signum) return 1;
-
-  /* Sort by loop pointer, so we can easily look up the first item after
-   * { .signum = x, .loop = NULL }. */
-  if ((uintptr_t) w1->loop < (uintptr_t) w2->loop) return -1;
-  if ((uintptr_t) w1->loop > (uintptr_t) w2->loop) return 1;
-
-  if ((uintptr_t) w1 < (uintptr_t) w2) return -1;
-  if ((uintptr_t) w1 > (uintptr_t) w2) return 1;
-
-  return 0;
-}
-
-
-RB_GENERATE_STATIC(uv_signal_tree_s, uv_signal_s, tree_entry, uv__signal_compare)
-
-
-/*
- * Dispatches signal {signum} to all active uv_signal_t watchers in all loops.
- * Returns 1 if the signal was dispatched to any watcher, or 0 if there were
- * no active signal watchers observing this signal.
- */
-int uv__signal_dispatch(int signum) {
-  uv_signal_t lookup;
-  uv_signal_t* handle;
-  int dispatched;
-
-  dispatched = 0;
-
-  EnterCriticalSection(&uv__signal_lock);
-
-  lookup.signum = signum;
-  lookup.loop = NULL;
-
-  for (handle = RB_NFIND(uv_signal_tree_s, &uv__signal_tree, &lookup);
-       handle != NULL && handle->signum == signum;
-       handle = RB_NEXT(uv_signal_tree_s, &uv__signal_tree, handle)) {
-    unsigned long previous = InterlockedExchange(
-            (volatile LONG*) &handle->pending_signum, signum);
-
-    if (handle->flags & UV_SIGNAL_ONE_SHOT_DISPATCHED)
-      continue;
-
-    if (!previous) {
-      POST_COMPLETION_FOR_REQ(handle->loop, &handle->signal_req);
-    }
-
-    dispatched = 1;
-    if (handle->flags & UV_SIGNAL_ONE_SHOT)
-      handle->flags |= UV_SIGNAL_ONE_SHOT_DISPATCHED;
-  }
-
-  LeaveCriticalSection(&uv__signal_lock);
-
-  return dispatched;
-}
-
-
-static BOOL WINAPI uv__signal_control_handler(DWORD type) {
-  switch (type) {
-    case CTRL_C_EVENT:
-      return uv__signal_dispatch(SIGINT);
-
-    case CTRL_BREAK_EVENT:
-      return uv__signal_dispatch(SIGBREAK);
-
-    case CTRL_CLOSE_EVENT:
-      if (uv__signal_dispatch(SIGHUP)) {
-        /* Windows will terminate the process after the control handler
-         * returns. After that it will just terminate our process. Therefore
-         * block the signal handler so the main loop has some time to pick up
-         * the signal and do something for a few seconds. */
-        Sleep(INFINITE);
-        return TRUE;
-      }
-      return FALSE;
-
-    case CTRL_LOGOFF_EVENT:
-    case CTRL_SHUTDOWN_EVENT:
-      /* These signals are only sent to services. Services have their own
-       * notification mechanism, so there's no point in handling these. */
-
-    default:
-      /* We don't handle these. */
-      return FALSE;
-  }
-}
-
-
-int uv_signal_init(uv_loop_t* loop, uv_signal_t* handle) {
-  uv__handle_init(loop, (uv_handle_t*) handle, UV_SIGNAL);
-  handle->pending_signum = 0;
-  handle->signum = 0;
-  handle->signal_cb = NULL;
-
-  UV_REQ_INIT(&handle->signal_req, UV_SIGNAL_REQ);
-  handle->signal_req.data = handle;
-
-  return 0;
-}
-
-
-int uv_signal_stop(uv_signal_t* handle) {
-  uv_signal_t* removed_handle;
-
-  /* If the watcher wasn't started, this is a no-op. */
-  if (handle->signum == 0)
-    return 0;
-
-  EnterCriticalSection(&uv__signal_lock);
-
-  removed_handle = RB_REMOVE(uv_signal_tree_s, &uv__signal_tree, handle);
-  assert(removed_handle == handle);
-
-  LeaveCriticalSection(&uv__signal_lock);
-
-  handle->signum = 0;
-  uv__handle_stop(handle);
-
-  return 0;
-}
-
-
-int uv_signal_start(uv_signal_t* handle, uv_signal_cb signal_cb, int signum) {
-  return uv__signal_start(handle, signal_cb, signum, 0);
-}
-
-
-int uv_signal_start_oneshot(uv_signal_t* handle,
-                            uv_signal_cb signal_cb,
-                            int signum) {
-  return uv__signal_start(handle, signal_cb, signum, 1);
-}
-
-
-int uv__signal_start(uv_signal_t* handle,
-                            uv_signal_cb signal_cb,
-                            int signum,
-                            int oneshot) {
-  /* Test for invalid signal values. */
-  if (signum <= 0 || signum >= NSIG)
-    return UV_EINVAL;
-
-  /* Short circuit: if the signal watcher is already watching {signum} don't go
-   * through the process of deregistering and registering the handler.
-   * Additionally, this avoids pending signals getting lost in the (small) time
-   * frame that handle->signum == 0. */
-  if (signum == handle->signum) {
-    handle->signal_cb = signal_cb;
-    return 0;
-  }
-
-  /* If the signal handler was already active, stop it first. */
-  if (handle->signum != 0) {
-    int r = uv_signal_stop(handle);
-    /* uv_signal_stop is infallible. */
-    assert(r == 0);
-  }
-
-  EnterCriticalSection(&uv__signal_lock);
-
-  handle->signum = signum;
-  if (oneshot)
-    handle->flags |= UV_SIGNAL_ONE_SHOT;
-
-  RB_INSERT(uv_signal_tree_s, &uv__signal_tree, handle);
-
-  LeaveCriticalSection(&uv__signal_lock);
-
-  handle->signal_cb = signal_cb;
-  uv__handle_start(handle);
-
-  return 0;
-}
-
-
-void uv_process_signal_req(uv_loop_t* loop, uv_signal_t* handle,
-    uv_req_t* req) {
-  long dispatched_signum;
-
-  assert(handle->type == UV_SIGNAL);
-  assert(req->type == UV_SIGNAL_REQ);
-
-  dispatched_signum = InterlockedExchange(
-          (volatile LONG*) &handle->pending_signum, 0);
-  assert(dispatched_signum != 0);
-
-  /* Check if the pending signal equals the signum that we are watching for.
-   * These can get out of sync when the handler is stopped and restarted while
-   * the signal_req is pending. */
-  if (dispatched_signum == handle->signum)
-    handle->signal_cb(handle, dispatched_signum);
-
-  if (handle->flags & UV_SIGNAL_ONE_SHOT)
-    uv_signal_stop(handle);
-
-  if (handle->flags & UV_HANDLE_CLOSING) {
-    /* When it is closing, it must be stopped at this point. */
-    assert(handle->signum == 0);
-    uv_want_endgame(loop, (uv_handle_t*) handle);
-  }
-}
-
-
-void uv_signal_close(uv_loop_t* loop, uv_signal_t* handle) {
-  uv_signal_stop(handle);
-  uv__handle_closing(handle);
-
-  if (handle->pending_signum == 0) {
-    uv_want_endgame(loop, (uv_handle_t*) handle);
-  }
-}
-
-
-void uv_signal_endgame(uv_loop_t* loop, uv_signal_t* handle) {
-  assert(handle->flags & UV_HANDLE_CLOSING);
-  assert(!(handle->flags & UV_HANDLE_CLOSED));
-
-  assert(handle->signum == 0);
-  assert(handle->pending_signum == 0);
-
-  handle->flags |= UV_HANDLE_CLOSED;
-
-  uv__handle_close(handle);
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/stream-inl.h b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/stream-inl.h
deleted file mode 100644
index 40f5ddd..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/stream-inl.h
+++ /dev/null
@@ -1,54 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#ifndef UV_WIN_STREAM_INL_H_
-#define UV_WIN_STREAM_INL_H_
-
-#include <assert.h>
-
-#include "uv.h"
-#include "internal.h"
-#include "handle-inl.h"
-#include "req-inl.h"
-
-
-INLINE static void uv_stream_init(uv_loop_t* loop,
-                                  uv_stream_t* handle,
-                                  uv_handle_type type) {
-  uv__handle_init(loop, (uv_handle_t*) handle, type);
-  handle->write_queue_size = 0;
-  handle->activecnt = 0;
-  handle->stream.conn.shutdown_req = NULL;
-  handle->stream.conn.write_reqs_pending = 0;
-
-  UV_REQ_INIT(&handle->read_req, UV_READ);
-  handle->read_req.event_handle = NULL;
-  handle->read_req.wait_handle = INVALID_HANDLE_VALUE;
-  handle->read_req.data = handle;
-}
-
-
-INLINE static void uv_connection_init(uv_stream_t* handle) {
-  handle->flags |= UV_HANDLE_CONNECTION;
-}
-
-
-#endif /* UV_WIN_STREAM_INL_H_ */
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/stream.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/stream.cpp
deleted file mode 100644
index 7656627..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/stream.cpp
+++ /dev/null
@@ -1,240 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include <assert.h>
-
-#include "uv.h"
-#include "internal.h"
-#include "handle-inl.h"
-#include "req-inl.h"
-
-
-int uv_listen(uv_stream_t* stream, int backlog, uv_connection_cb cb) {
-  int err;
-
-  err = ERROR_INVALID_PARAMETER;
-  switch (stream->type) {
-    case UV_TCP:
-      err = uv_tcp_listen((uv_tcp_t*)stream, backlog, cb);
-      break;
-    case UV_NAMED_PIPE:
-      err = uv_pipe_listen((uv_pipe_t*)stream, backlog, cb);
-      break;
-    default:
-      assert(0);
-  }
-
-  return uv_translate_sys_error(err);
-}
-
-
-int uv_accept(uv_stream_t* server, uv_stream_t* client) {
-  int err;
-
-  err = ERROR_INVALID_PARAMETER;
-  switch (server->type) {
-    case UV_TCP:
-      err = uv_tcp_accept((uv_tcp_t*)server, (uv_tcp_t*)client);
-      break;
-    case UV_NAMED_PIPE:
-      err = uv_pipe_accept((uv_pipe_t*)server, client);
-      break;
-    default:
-      assert(0);
-  }
-
-  return uv_translate_sys_error(err);
-}
-
-
-int uv_read_start(uv_stream_t* handle, uv_alloc_cb alloc_cb,
-    uv_read_cb read_cb) {
-  int err;
-
-  if (handle->flags & UV_HANDLE_READING) {
-    return UV_EALREADY;
-  }
-
-  if (!(handle->flags & UV_HANDLE_READABLE)) {
-    return UV_ENOTCONN;
-  }
-
-  err = ERROR_INVALID_PARAMETER;
-  switch (handle->type) {
-    case UV_TCP:
-      err = uv_tcp_read_start((uv_tcp_t*)handle, alloc_cb, read_cb);
-      break;
-    case UV_NAMED_PIPE:
-      err = uv_pipe_read_start((uv_pipe_t*)handle, alloc_cb, read_cb);
-      break;
-    case UV_TTY:
-      err = uv_tty_read_start((uv_tty_t*) handle, alloc_cb, read_cb);
-      break;
-    default:
-      assert(0);
-  }
-
-  return uv_translate_sys_error(err);
-}
-
-
-int uv_read_stop(uv_stream_t* handle) {
-  int err;
-
-  if (!(handle->flags & UV_HANDLE_READING))
-    return 0;
-
-  err = 0;
-  if (handle->type == UV_TTY) {
-    err = uv_tty_read_stop((uv_tty_t*) handle);
-  } else if (handle->type == UV_NAMED_PIPE) {
-    uv__pipe_read_stop((uv_pipe_t*) handle);
-  } else {
-    handle->flags &= ~UV_HANDLE_READING;
-    DECREASE_ACTIVE_COUNT(handle->loop, handle);
-  }
-
-  return uv_translate_sys_error(err);
-}
-
-
-int uv_write(uv_write_t* req,
-             uv_stream_t* handle,
-             const uv_buf_t bufs[],
-             unsigned int nbufs,
-             uv_write_cb cb) {
-  uv_loop_t* loop = handle->loop;
-  int err;
-
-  if (!(handle->flags & UV_HANDLE_WRITABLE)) {
-    return UV_EPIPE;
-  }
-
-  err = ERROR_INVALID_PARAMETER;
-  switch (handle->type) {
-    case UV_TCP:
-      err = uv_tcp_write(loop, req, (uv_tcp_t*) handle, bufs, nbufs, cb);
-      break;
-    case UV_NAMED_PIPE:
-      err = uv__pipe_write(
-          loop, req, (uv_pipe_t*) handle, bufs, nbufs, NULL, cb);
-      break;
-    case UV_TTY:
-      err = uv_tty_write(loop, req, (uv_tty_t*) handle, bufs, nbufs, cb);
-      break;
-    default:
-      assert(0);
-  }
-
-  return uv_translate_sys_error(err);
-}
-
-
-int uv_write2(uv_write_t* req,
-              uv_stream_t* handle,
-              const uv_buf_t bufs[],
-              unsigned int nbufs,
-              uv_stream_t* send_handle,
-              uv_write_cb cb) {
-  uv_loop_t* loop = handle->loop;
-  int err;
-
-  if (send_handle == NULL) {
-    return uv_write(req, handle, bufs, nbufs, cb);
-  }
-
-  if (handle->type != UV_NAMED_PIPE || !((uv_pipe_t*) handle)->ipc) {
-    return UV_EINVAL;
-  } else if (!(handle->flags & UV_HANDLE_WRITABLE)) {
-    return UV_EPIPE;
-  }
-
-  err = uv__pipe_write(
-      loop, req, (uv_pipe_t*) handle, bufs, nbufs, send_handle, cb);
-  return uv_translate_sys_error(err);
-}
-
-
-int uv_try_write(uv_stream_t* stream,
-                 const uv_buf_t bufs[],
-                 unsigned int nbufs) {
-  if (stream->flags & UV_HANDLE_CLOSING)
-    return UV_EBADF;
-  if (!(stream->flags & UV_HANDLE_WRITABLE))
-    return UV_EPIPE;
-
-  switch (stream->type) {
-    case UV_TCP:
-      return uv__tcp_try_write((uv_tcp_t*) stream, bufs, nbufs);
-    case UV_TTY:
-      return uv__tty_try_write((uv_tty_t*) stream, bufs, nbufs);
-    case UV_NAMED_PIPE:
-      return UV_EAGAIN;
-    default:
-      assert(0);
-      return UV_ENOSYS;
-  }
-}
-
-
-int uv_shutdown(uv_shutdown_t* req, uv_stream_t* handle, uv_shutdown_cb cb) {
-  uv_loop_t* loop = handle->loop;
-
-  if (!(handle->flags & UV_HANDLE_WRITABLE)) {
-    return UV_EPIPE;
-  }
-
-  UV_REQ_INIT(req, UV_SHUTDOWN);
-  req->handle = handle;
-  req->cb = cb;
-
-  handle->flags &= ~UV_HANDLE_WRITABLE;
-  handle->stream.conn.shutdown_req = req;
-  handle->reqs_pending++;
-  REGISTER_HANDLE_REQ(loop, handle, req);
-
-  uv_want_endgame(loop, (uv_handle_t*)handle);
-
-  return 0;
-}
-
-
-int uv_is_readable(const uv_stream_t* handle) {
-  return !!(handle->flags & UV_HANDLE_READABLE);
-}
-
-
-int uv_is_writable(const uv_stream_t* handle) {
-  return !!(handle->flags & UV_HANDLE_WRITABLE);
-}
-
-
-int uv_stream_set_blocking(uv_stream_t* handle, int blocking) {
-  if (handle->type != UV_NAMED_PIPE)
-    return UV_EINVAL;
-
-  if (blocking != 0)
-    handle->flags |= UV_HANDLE_BLOCKING_WRITES;
-  else
-    handle->flags &= ~UV_HANDLE_BLOCKING_WRITES;
-
-  return 0;
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/tcp.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/tcp.cpp
deleted file mode 100644
index f2cb527..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/tcp.cpp
+++ /dev/null
@@ -1,1505 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include <assert.h>
-#include <stdlib.h>
-
-#include "uv.h"
-#include "internal.h"
-#include "handle-inl.h"
-#include "stream-inl.h"
-#include "req-inl.h"
-
-
-/*
- * Threshold of active tcp streams for which to preallocate tcp read buffers.
- * (Due to node slab allocator performing poorly under this pattern,
- *  the optimization is temporarily disabled (threshold=0).  This will be
- *  revisited once node allocator is improved.)
- */
-const unsigned int uv_active_tcp_streams_threshold = 0;
-
-/*
- * Number of simultaneous pending AcceptEx calls.
- */
-const unsigned int uv_simultaneous_server_accepts = 32;
-
-/* A zero-size buffer for use by uv_tcp_read */
-static char uv_zero_[] = "";
-
-static int uv__tcp_nodelay(uv_tcp_t* handle, SOCKET socket, int enable) {
-  if (setsockopt(socket,
-                 IPPROTO_TCP,
-                 TCP_NODELAY,
-                 (const char*)&enable,
-                 sizeof enable) == -1) {
-    return WSAGetLastError();
-  }
-  return 0;
-}
-
-
-static int uv__tcp_keepalive(uv_tcp_t* handle, SOCKET socket, int enable, unsigned int delay) {
-  if (setsockopt(socket,
-                 SOL_SOCKET,
-                 SO_KEEPALIVE,
-                 (const char*)&enable,
-                 sizeof enable) == -1) {
-    return WSAGetLastError();
-  }
-
-  if (enable && setsockopt(socket,
-                           IPPROTO_TCP,
-                           TCP_KEEPALIVE,
-                           (const char*)&delay,
-                           sizeof delay) == -1) {
-    return WSAGetLastError();
-  }
-
-  return 0;
-}
-
-
-static int uv_tcp_set_socket(uv_loop_t* loop,
-                             uv_tcp_t* handle,
-                             SOCKET socket,
-                             int family,
-                             int imported) {
-  DWORD yes = 1;
-  int non_ifs_lsp;
-  int err;
-
-  if (handle->socket != INVALID_SOCKET)
-    return UV_EBUSY;
-
-  /* Set the socket to nonblocking mode */
-  if (ioctlsocket(socket, FIONBIO, &yes) == SOCKET_ERROR) {
-    return WSAGetLastError();
-  }
-
-  /* Make the socket non-inheritable */
-  if (!SetHandleInformation((HANDLE) socket, HANDLE_FLAG_INHERIT, 0))
-    return GetLastError();
-
-  /* Associate it with the I/O completion port. Use uv_handle_t pointer as
-   * completion key. */
-  if (CreateIoCompletionPort((HANDLE)socket,
-                             loop->iocp,
-                             (ULONG_PTR)socket,
-                             0) == NULL) {
-    if (imported) {
-      handle->flags |= UV_HANDLE_EMULATE_IOCP;
-    } else {
-      return GetLastError();
-    }
-  }
-
-  if (family == AF_INET6) {
-    non_ifs_lsp = uv_tcp_non_ifs_lsp_ipv6;
-  } else {
-    non_ifs_lsp = uv_tcp_non_ifs_lsp_ipv4;
-  }
-
-  if (!(handle->flags & UV_HANDLE_EMULATE_IOCP) && !non_ifs_lsp) {
-    UCHAR sfcnm_flags =
-        FILE_SKIP_SET_EVENT_ON_HANDLE | FILE_SKIP_COMPLETION_PORT_ON_SUCCESS;
-    if (!SetFileCompletionNotificationModes((HANDLE) socket, sfcnm_flags))
-      return GetLastError();
-    handle->flags |= UV_HANDLE_SYNC_BYPASS_IOCP;
-  }
-
-  if (handle->flags & UV_HANDLE_TCP_NODELAY) {
-    err = uv__tcp_nodelay(handle, socket, 1);
-    if (err)
-      return err;
-  }
-
-  /* TODO: Use stored delay. */
-  if (handle->flags & UV_HANDLE_TCP_KEEPALIVE) {
-    err = uv__tcp_keepalive(handle, socket, 1, 60);
-    if (err)
-      return err;
-  }
-
-  handle->socket = socket;
-
-  if (family == AF_INET6) {
-    handle->flags |= UV_HANDLE_IPV6;
-  } else {
-    assert(!(handle->flags & UV_HANDLE_IPV6));
-  }
-
-  return 0;
-}
-
-
-int uv_tcp_init_ex(uv_loop_t* loop, uv_tcp_t* handle, unsigned int flags) {
-  int domain;
-
-  /* Use the lower 8 bits for the domain */
-  domain = flags & 0xFF;
-  if (domain != AF_INET && domain != AF_INET6 && domain != AF_UNSPEC)
-    return UV_EINVAL;
-
-  if (flags & ~0xFF)
-    return UV_EINVAL;
-
-  uv_stream_init(loop, (uv_stream_t*) handle, UV_TCP);
-  handle->tcp.serv.accept_reqs = NULL;
-  handle->tcp.serv.pending_accepts = NULL;
-  handle->socket = INVALID_SOCKET;
-  handle->reqs_pending = 0;
-  handle->tcp.serv.func_acceptex = NULL;
-  handle->tcp.conn.func_connectex = NULL;
-  handle->tcp.serv.processed_accepts = 0;
-  handle->delayed_error = 0;
-
-  /* If anything fails beyond this point we need to remove the handle from
-   * the handle queue, since it was added by uv__handle_init in uv_stream_init.
-   */
-
-  if (domain != AF_UNSPEC) {
-    SOCKET sock;
-    DWORD err;
-
-    sock = socket(domain, SOCK_STREAM, 0);
-    if (sock == INVALID_SOCKET) {
-      err = WSAGetLastError();
-      QUEUE_REMOVE(&handle->handle_queue);
-      return uv_translate_sys_error(err);
-    }
-
-    err = uv_tcp_set_socket(handle->loop, handle, sock, domain, 0);
-    if (err) {
-      closesocket(sock);
-      QUEUE_REMOVE(&handle->handle_queue);
-      return uv_translate_sys_error(err);
-    }
-
-  }
-
-  return 0;
-}
-
-
-int uv_tcp_init(uv_loop_t* loop, uv_tcp_t* handle) {
-  return uv_tcp_init_ex(loop, handle, AF_UNSPEC);
-}
-
-
-void uv_tcp_endgame(uv_loop_t* loop, uv_tcp_t* handle) {
-  int err;
-  unsigned int i;
-  uv_tcp_accept_t* req;
-
-  if (handle->flags & UV_HANDLE_CONNECTION &&
-      handle->stream.conn.shutdown_req != NULL &&
-      handle->stream.conn.write_reqs_pending == 0) {
-
-    UNREGISTER_HANDLE_REQ(loop, handle, handle->stream.conn.shutdown_req);
-
-    err = 0;
-    if (handle->flags & UV_HANDLE_CLOSING) {
-      err = ERROR_OPERATION_ABORTED;
-    } else if (shutdown(handle->socket, SD_SEND) == SOCKET_ERROR) {
-      err = WSAGetLastError();
-    }
-
-    if (handle->stream.conn.shutdown_req->cb) {
-      handle->stream.conn.shutdown_req->cb(handle->stream.conn.shutdown_req,
-                               uv_translate_sys_error(err));
-    }
-
-    handle->stream.conn.shutdown_req = NULL;
-    DECREASE_PENDING_REQ_COUNT(handle);
-    return;
-  }
-
-  if (handle->flags & UV_HANDLE_CLOSING &&
-      handle->reqs_pending == 0) {
-    assert(!(handle->flags & UV_HANDLE_CLOSED));
-
-    if (!(handle->flags & UV_HANDLE_TCP_SOCKET_CLOSED)) {
-      closesocket(handle->socket);
-      handle->socket = INVALID_SOCKET;
-      handle->flags |= UV_HANDLE_TCP_SOCKET_CLOSED;
-    }
-
-    if (!(handle->flags & UV_HANDLE_CONNECTION) && handle->tcp.serv.accept_reqs) {
-      if (handle->flags & UV_HANDLE_EMULATE_IOCP) {
-        for (i = 0; i < uv_simultaneous_server_accepts; i++) {
-          req = &handle->tcp.serv.accept_reqs[i];
-          if (req->wait_handle != INVALID_HANDLE_VALUE) {
-            UnregisterWait(req->wait_handle);
-            req->wait_handle = INVALID_HANDLE_VALUE;
-          }
-          if (req->event_handle) {
-            CloseHandle(req->event_handle);
-            req->event_handle = NULL;
-          }
-        }
-      }
-
-      uv__free(handle->tcp.serv.accept_reqs);
-      handle->tcp.serv.accept_reqs = NULL;
-    }
-
-    if (handle->flags & UV_HANDLE_CONNECTION &&
-        handle->flags & UV_HANDLE_EMULATE_IOCP) {
-      if (handle->read_req.wait_handle != INVALID_HANDLE_VALUE) {
-        UnregisterWait(handle->read_req.wait_handle);
-        handle->read_req.wait_handle = INVALID_HANDLE_VALUE;
-      }
-      if (handle->read_req.event_handle) {
-        CloseHandle(handle->read_req.event_handle);
-        handle->read_req.event_handle = NULL;
-      }
-    }
-
-    uv__handle_close(handle);
-    loop->active_tcp_streams--;
-  }
-}
-
-
-/* Unlike on Unix, here we don't set SO_REUSEADDR, because it doesn't just
- * allow binding to addresses that are in use by sockets in TIME_WAIT, it
- * effectively allows 'stealing' a port which is in use by another application.
- *
- * SO_EXCLUSIVEADDRUSE is also not good here because it does check all sockets,
- * regardless of state, so we'd get an error even if the port is in use by a
- * socket in TIME_WAIT state.
- *
- * See issue #1360.
- *
- */
-static int uv_tcp_try_bind(uv_tcp_t* handle,
-                           const struct sockaddr* addr,
-                           unsigned int addrlen,
-                           unsigned int flags) {
-  DWORD err;
-  int r;
-
-  if (handle->socket == INVALID_SOCKET) {
-    SOCKET sock;
-
-    /* Cannot set IPv6-only mode on non-IPv6 socket. */
-    if ((flags & UV_TCP_IPV6ONLY) && addr->sa_family != AF_INET6)
-      return ERROR_INVALID_PARAMETER;
-
-    sock = socket(addr->sa_family, SOCK_STREAM, 0);
-    if (sock == INVALID_SOCKET) {
-      return WSAGetLastError();
-    }
-
-    err = uv_tcp_set_socket(handle->loop, handle, sock, addr->sa_family, 0);
-    if (err) {
-      closesocket(sock);
-      return err;
-    }
-  }
-
-#ifdef IPV6_V6ONLY
-  if (addr->sa_family == AF_INET6) {
-    int on;
-
-    on = (flags & UV_TCP_IPV6ONLY) != 0;
-
-    /* TODO: how to handle errors? This may fail if there is no ipv4 stack
-     * available, or when run on XP/2003 which have no support for dualstack
-     * sockets. For now we're silently ignoring the error. */
-    setsockopt(handle->socket,
-               IPPROTO_IPV6,
-               IPV6_V6ONLY,
-               (const char*)&on,
-               sizeof on);
-  }
-#endif
-
-  r = bind(handle->socket, addr, addrlen);
-
-  if (r == SOCKET_ERROR) {
-    err = WSAGetLastError();
-    if (err == WSAEADDRINUSE) {
-      /* Some errors are not to be reported until connect() or listen() */
-      handle->delayed_error = err;
-    } else {
-      return err;
-    }
-  }
-
-  handle->flags |= UV_HANDLE_BOUND;
-
-  return 0;
-}
-
-
-static void CALLBACK post_completion(void* context, BOOLEAN timed_out) {
-  uv_req_t* req;
-  uv_tcp_t* handle;
-
-  req = (uv_req_t*) context;
-  assert(req != NULL);
-  handle = (uv_tcp_t*)req->data;
-  assert(handle != NULL);
-  assert(!timed_out);
-
-  if (!PostQueuedCompletionStatus(handle->loop->iocp,
-                                  req->u.io.overlapped.InternalHigh,
-                                  0,
-                                  &req->u.io.overlapped)) {
-    uv_fatal_error(GetLastError(), "PostQueuedCompletionStatus");
-  }
-}
-
-
-static void CALLBACK post_write_completion(void* context, BOOLEAN timed_out) {
-  uv_write_t* req;
-  uv_tcp_t* handle;
-
-  req = (uv_write_t*) context;
-  assert(req != NULL);
-  handle = (uv_tcp_t*)req->handle;
-  assert(handle != NULL);
-  assert(!timed_out);
-
-  if (!PostQueuedCompletionStatus(handle->loop->iocp,
-                                  req->u.io.overlapped.InternalHigh,
-                                  0,
-                                  &req->u.io.overlapped)) {
-    uv_fatal_error(GetLastError(), "PostQueuedCompletionStatus");
-  }
-}
-
-
-static void uv_tcp_queue_accept(uv_tcp_t* handle, uv_tcp_accept_t* req) {
-  uv_loop_t* loop = handle->loop;
-  BOOL success;
-  DWORD bytes;
-  SOCKET accept_socket;
-  short family;
-
-  assert(handle->flags & UV_HANDLE_LISTENING);
-  assert(req->accept_socket == INVALID_SOCKET);
-
-  /* choose family and extension function */
-  if (handle->flags & UV_HANDLE_IPV6) {
-    family = AF_INET6;
-  } else {
-    family = AF_INET;
-  }
-
-  /* Open a socket for the accepted connection. */
-  accept_socket = socket(family, SOCK_STREAM, 0);
-  if (accept_socket == INVALID_SOCKET) {
-    SET_REQ_ERROR(req, WSAGetLastError());
-    uv_insert_pending_req(loop, (uv_req_t*)req);
-    handle->reqs_pending++;
-    return;
-  }
-
-  /* Make the socket non-inheritable */
-  if (!SetHandleInformation((HANDLE) accept_socket, HANDLE_FLAG_INHERIT, 0)) {
-    SET_REQ_ERROR(req, GetLastError());
-    uv_insert_pending_req(loop, (uv_req_t*)req);
-    handle->reqs_pending++;
-    closesocket(accept_socket);
-    return;
-  }
-
-  /* Prepare the overlapped structure. */
-  memset(&(req->u.io.overlapped), 0, sizeof(req->u.io.overlapped));
-  if (handle->flags & UV_HANDLE_EMULATE_IOCP) {
-    req->u.io.overlapped.hEvent = (HANDLE) ((ULONG_PTR) req->event_handle | 1);
-  }
-
-  success = handle->tcp.serv.func_acceptex(handle->socket,
-                                          accept_socket,
-                                          (void*)req->accept_buffer,
-                                          0,
-                                          sizeof(struct sockaddr_storage),
-                                          sizeof(struct sockaddr_storage),
-                                          &bytes,
-                                          &req->u.io.overlapped);
-
-  if (UV_SUCCEEDED_WITHOUT_IOCP(success)) {
-    /* Process the req without IOCP. */
-    req->accept_socket = accept_socket;
-    handle->reqs_pending++;
-    uv_insert_pending_req(loop, (uv_req_t*)req);
-  } else if (UV_SUCCEEDED_WITH_IOCP(success)) {
-    /* The req will be processed with IOCP. */
-    req->accept_socket = accept_socket;
-    handle->reqs_pending++;
-    if (handle->flags & UV_HANDLE_EMULATE_IOCP &&
-        req->wait_handle == INVALID_HANDLE_VALUE &&
-        !RegisterWaitForSingleObject(&req->wait_handle,
-          req->event_handle, post_completion, (void*) req,
-          INFINITE, WT_EXECUTEINWAITTHREAD)) {
-      SET_REQ_ERROR(req, GetLastError());
-      uv_insert_pending_req(loop, (uv_req_t*)req);
-    }
-  } else {
-    /* Make this req pending reporting an error. */
-    SET_REQ_ERROR(req, WSAGetLastError());
-    uv_insert_pending_req(loop, (uv_req_t*)req);
-    handle->reqs_pending++;
-    /* Destroy the preallocated client socket. */
-    closesocket(accept_socket);
-    /* Destroy the event handle */
-    if (handle->flags & UV_HANDLE_EMULATE_IOCP) {
-      CloseHandle(req->u.io.overlapped.hEvent);
-      req->event_handle = NULL;
-    }
-  }
-}
-
-
-static void uv_tcp_queue_read(uv_loop_t* loop, uv_tcp_t* handle) {
-  uv_read_t* req;
-  uv_buf_t buf;
-  int result;
-  DWORD bytes, flags;
-
-  assert(handle->flags & UV_HANDLE_READING);
-  assert(!(handle->flags & UV_HANDLE_READ_PENDING));
-
-  req = &handle->read_req;
-  memset(&req->u.io.overlapped, 0, sizeof(req->u.io.overlapped));
-
-  /*
-   * Preallocate a read buffer if the number of active streams is below
-   * the threshold.
-  */
-  if (loop->active_tcp_streams < uv_active_tcp_streams_threshold) {
-    handle->flags &= ~UV_HANDLE_ZERO_READ;
-    handle->tcp.conn.read_buffer = uv_buf_init(NULL, 0);
-    handle->alloc_cb((uv_handle_t*) handle, 65536, &handle->tcp.conn.read_buffer);
-    if (handle->tcp.conn.read_buffer.base == NULL ||
-        handle->tcp.conn.read_buffer.len == 0) {
-      handle->read_cb((uv_stream_t*) handle, UV_ENOBUFS, &handle->tcp.conn.read_buffer);
-      return;
-    }
-    assert(handle->tcp.conn.read_buffer.base != NULL);
-    buf = handle->tcp.conn.read_buffer;
-  } else {
-    handle->flags |= UV_HANDLE_ZERO_READ;
-    buf.base = (char*) &uv_zero_;
-    buf.len = 0;
-  }
-
-  /* Prepare the overlapped structure. */
-  memset(&(req->u.io.overlapped), 0, sizeof(req->u.io.overlapped));
-  if (handle->flags & UV_HANDLE_EMULATE_IOCP) {
-    assert(req->event_handle);
-    req->u.io.overlapped.hEvent = (HANDLE) ((ULONG_PTR) req->event_handle | 1);
-  }
-
-  flags = 0;
-  result = WSARecv(handle->socket,
-                   (WSABUF*)&buf,
-                   1,
-                   &bytes,
-                   &flags,
-                   &req->u.io.overlapped,
-                   NULL);
-
-  if (UV_SUCCEEDED_WITHOUT_IOCP(result == 0)) {
-    /* Process the req without IOCP. */
-    handle->flags |= UV_HANDLE_READ_PENDING;
-    req->u.io.overlapped.InternalHigh = bytes;
-    handle->reqs_pending++;
-    uv_insert_pending_req(loop, (uv_req_t*)req);
-  } else if (UV_SUCCEEDED_WITH_IOCP(result == 0)) {
-    /* The req will be processed with IOCP. */
-    handle->flags |= UV_HANDLE_READ_PENDING;
-    handle->reqs_pending++;
-    if (handle->flags & UV_HANDLE_EMULATE_IOCP &&
-        req->wait_handle == INVALID_HANDLE_VALUE &&
-        !RegisterWaitForSingleObject(&req->wait_handle,
-          req->event_handle, post_completion, (void*) req,
-          INFINITE, WT_EXECUTEINWAITTHREAD)) {
-      SET_REQ_ERROR(req, GetLastError());
-      uv_insert_pending_req(loop, (uv_req_t*)req);
-    }
-  } else {
-    /* Make this req pending reporting an error. */
-    SET_REQ_ERROR(req, WSAGetLastError());
-    uv_insert_pending_req(loop, (uv_req_t*)req);
-    handle->reqs_pending++;
-  }
-}
-
-
-int uv_tcp_listen(uv_tcp_t* handle, int backlog, uv_connection_cb cb) {
-  unsigned int i, simultaneous_accepts;
-  uv_tcp_accept_t* req;
-  int err;
-
-  assert(backlog > 0);
-
-  if (handle->flags & UV_HANDLE_LISTENING) {
-    handle->stream.serv.connection_cb = cb;
-  }
-
-  if (handle->flags & UV_HANDLE_READING) {
-    return WSAEISCONN;
-  }
-
-  if (handle->delayed_error) {
-    return handle->delayed_error;
-  }
-
-  if (!(handle->flags & UV_HANDLE_BOUND)) {
-    err = uv_tcp_try_bind(handle,
-                          (const struct sockaddr*) &uv_addr_ip4_any_,
-                          sizeof(uv_addr_ip4_any_),
-                          0);
-    if (err)
-      return err;
-    if (handle->delayed_error)
-      return handle->delayed_error;
-  }
-
-  if (!handle->tcp.serv.func_acceptex) {
-    if (!uv_get_acceptex_function(handle->socket, &handle->tcp.serv.func_acceptex)) {
-      return WSAEAFNOSUPPORT;
-    }
-  }
-
-  if (!(handle->flags & UV_HANDLE_SHARED_TCP_SOCKET) &&
-      listen(handle->socket, backlog) == SOCKET_ERROR) {
-    return WSAGetLastError();
-  }
-
-  handle->flags |= UV_HANDLE_LISTENING;
-  handle->stream.serv.connection_cb = cb;
-  INCREASE_ACTIVE_COUNT(loop, handle);
-
-  simultaneous_accepts = handle->flags & UV_HANDLE_TCP_SINGLE_ACCEPT ? 1
-    : uv_simultaneous_server_accepts;
-
-  if(!handle->tcp.serv.accept_reqs) {
-    handle->tcp.serv.accept_reqs = (uv_tcp_accept_t*)
-      uv__malloc(uv_simultaneous_server_accepts * sizeof(uv_tcp_accept_t));
-    if (!handle->tcp.serv.accept_reqs) {
-      uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
-    }
-
-    for (i = 0; i < simultaneous_accepts; i++) {
-      req = &handle->tcp.serv.accept_reqs[i];
-      UV_REQ_INIT(req, UV_ACCEPT);
-      req->accept_socket = INVALID_SOCKET;
-      req->data = handle;
-
-      req->wait_handle = INVALID_HANDLE_VALUE;
-      if (handle->flags & UV_HANDLE_EMULATE_IOCP) {
-        req->event_handle = CreateEvent(NULL, 0, 0, NULL);
-        if (!req->event_handle) {
-          uv_fatal_error(GetLastError(), "CreateEvent");
-        }
-      } else {
-        req->event_handle = NULL;
-      }
-
-      uv_tcp_queue_accept(handle, req);
-    }
-
-    /* Initialize other unused requests too, because uv_tcp_endgame doesn't
-     * know how many requests were initialized, so it will try to clean up
-     * {uv_simultaneous_server_accepts} requests. */
-    for (i = simultaneous_accepts; i < uv_simultaneous_server_accepts; i++) {
-      req = &handle->tcp.serv.accept_reqs[i];
-      UV_REQ_INIT(req, UV_ACCEPT);
-      req->accept_socket = INVALID_SOCKET;
-      req->data = handle;
-      req->wait_handle = INVALID_HANDLE_VALUE;
-      req->event_handle = NULL;
-    }
-  }
-
-  return 0;
-}
-
-
-int uv_tcp_accept(uv_tcp_t* server, uv_tcp_t* client) {
-  uv_loop_t* loop = server->loop;
-  int err = 0;
-  int family;
-
-  uv_tcp_accept_t* req = server->tcp.serv.pending_accepts;
-
-  if (!req) {
-    /* No valid connections found, so we error out. */
-    return WSAEWOULDBLOCK;
-  }
-
-  if (req->accept_socket == INVALID_SOCKET) {
-    return WSAENOTCONN;
-  }
-
-  if (server->flags & UV_HANDLE_IPV6) {
-    family = AF_INET6;
-  } else {
-    family = AF_INET;
-  }
-
-  err = uv_tcp_set_socket(client->loop,
-                          client,
-                          req->accept_socket,
-                          family,
-                          0);
-  if (err) {
-    closesocket(req->accept_socket);
-  } else {
-    uv_connection_init((uv_stream_t*) client);
-    /* AcceptEx() implicitly binds the accepted socket. */
-    client->flags |= UV_HANDLE_BOUND | UV_HANDLE_READABLE | UV_HANDLE_WRITABLE;
-  }
-
-  /* Prepare the req to pick up a new connection */
-  server->tcp.serv.pending_accepts = req->next_pending;
-  req->next_pending = NULL;
-  req->accept_socket = INVALID_SOCKET;
-
-  if (!(server->flags & UV_HANDLE_CLOSING)) {
-    /* Check if we're in a middle of changing the number of pending accepts. */
-    if (!(server->flags & UV_HANDLE_TCP_ACCEPT_STATE_CHANGING)) {
-      uv_tcp_queue_accept(server, req);
-    } else {
-      /* We better be switching to a single pending accept. */
-      assert(server->flags & UV_HANDLE_TCP_SINGLE_ACCEPT);
-
-      server->tcp.serv.processed_accepts++;
-
-      if (server->tcp.serv.processed_accepts >= uv_simultaneous_server_accepts) {
-        server->tcp.serv.processed_accepts = 0;
-        /*
-         * All previously queued accept requests are now processed.
-         * We now switch to queueing just a single accept.
-         */
-        uv_tcp_queue_accept(server, &server->tcp.serv.accept_reqs[0]);
-        server->flags &= ~UV_HANDLE_TCP_ACCEPT_STATE_CHANGING;
-        server->flags |= UV_HANDLE_TCP_SINGLE_ACCEPT;
-      }
-    }
-  }
-
-  loop->active_tcp_streams++;
-
-  return err;
-}
-
-
-int uv_tcp_read_start(uv_tcp_t* handle, uv_alloc_cb alloc_cb,
-    uv_read_cb read_cb) {
-  uv_loop_t* loop = handle->loop;
-
-  handle->flags |= UV_HANDLE_READING;
-  handle->read_cb = read_cb;
-  handle->alloc_cb = alloc_cb;
-  INCREASE_ACTIVE_COUNT(loop, handle);
-
-  /* If reading was stopped and then started again, there could still be a read
-   * request pending. */
-  if (!(handle->flags & UV_HANDLE_READ_PENDING)) {
-    if (handle->flags & UV_HANDLE_EMULATE_IOCP &&
-        !handle->read_req.event_handle) {
-      handle->read_req.event_handle = CreateEvent(NULL, 0, 0, NULL);
-      if (!handle->read_req.event_handle) {
-        uv_fatal_error(GetLastError(), "CreateEvent");
-      }
-    }
-    uv_tcp_queue_read(loop, handle);
-  }
-
-  return 0;
-}
-
-
-static int uv_tcp_try_connect(uv_connect_t* req,
-                              uv_tcp_t* handle,
-                              const struct sockaddr* addr,
-                              unsigned int addrlen,
-                              uv_connect_cb cb) {
-  uv_loop_t* loop = handle->loop;
-  const struct sockaddr* bind_addr;
-  struct sockaddr_storage converted;
-  BOOL success;
-  DWORD bytes;
-  int err;
-
-  err = uv__convert_to_localhost_if_unspecified(addr, &converted);
-  if (err)
-    return err;
-
-  if (handle->delayed_error) {
-    return handle->delayed_error;
-  }
-
-  if (!(handle->flags & UV_HANDLE_BOUND)) {
-    if (addrlen == sizeof(uv_addr_ip4_any_)) {
-      bind_addr = (const struct sockaddr*) &uv_addr_ip4_any_;
-    } else if (addrlen == sizeof(uv_addr_ip6_any_)) {
-      bind_addr = (const struct sockaddr*) &uv_addr_ip6_any_;
-    } else {
-      abort();
-    }
-    err = uv_tcp_try_bind(handle, bind_addr, addrlen, 0);
-    if (err)
-      return err;
-    if (handle->delayed_error)
-      return handle->delayed_error;
-  }
-
-  if (!handle->tcp.conn.func_connectex) {
-    if (!uv_get_connectex_function(handle->socket, &handle->tcp.conn.func_connectex)) {
-      return WSAEAFNOSUPPORT;
-    }
-  }
-
-  UV_REQ_INIT(req, UV_CONNECT);
-  req->handle = (uv_stream_t*) handle;
-  req->cb = cb;
-  memset(&req->u.io.overlapped, 0, sizeof(req->u.io.overlapped));
-
-  success = handle->tcp.conn.func_connectex(handle->socket,
-                                            (const struct sockaddr*) &converted,
-                                            addrlen,
-                                            NULL,
-                                            0,
-                                            &bytes,
-                                            &req->u.io.overlapped);
-
-  if (UV_SUCCEEDED_WITHOUT_IOCP(success)) {
-    /* Process the req without IOCP. */
-    handle->reqs_pending++;
-    REGISTER_HANDLE_REQ(loop, handle, req);
-    uv_insert_pending_req(loop, (uv_req_t*)req);
-  } else if (UV_SUCCEEDED_WITH_IOCP(success)) {
-    /* The req will be processed with IOCP. */
-    handle->reqs_pending++;
-    REGISTER_HANDLE_REQ(loop, handle, req);
-  } else {
-    return WSAGetLastError();
-  }
-
-  return 0;
-}
-
-
-int uv_tcp_getsockname(const uv_tcp_t* handle,
-                       struct sockaddr* name,
-                       int* namelen) {
-
-  return uv__getsockpeername((const uv_handle_t*) handle,
-                             getsockname,
-                             name,
-                             namelen,
-                             handle->delayed_error);
-}
-
-
-int uv_tcp_getpeername(const uv_tcp_t* handle,
-                       struct sockaddr* name,
-                       int* namelen) {
-
-  return uv__getsockpeername((const uv_handle_t*) handle,
-                             getpeername,
-                             name,
-                             namelen,
-                             handle->delayed_error);
-}
-
-
-int uv_tcp_write(uv_loop_t* loop,
-                 uv_write_t* req,
-                 uv_tcp_t* handle,
-                 const uv_buf_t bufs[],
-                 unsigned int nbufs,
-                 uv_write_cb cb) {
-  int result;
-  DWORD bytes;
-
-  UV_REQ_INIT(req, UV_WRITE);
-  req->handle = (uv_stream_t*) handle;
-  req->cb = cb;
-
-  /* Prepare the overlapped structure. */
-  memset(&(req->u.io.overlapped), 0, sizeof(req->u.io.overlapped));
-  if (handle->flags & UV_HANDLE_EMULATE_IOCP) {
-    req->event_handle = CreateEvent(NULL, 0, 0, NULL);
-    if (!req->event_handle) {
-      uv_fatal_error(GetLastError(), "CreateEvent");
-    }
-    req->u.io.overlapped.hEvent = (HANDLE) ((ULONG_PTR) req->event_handle | 1);
-    req->wait_handle = INVALID_HANDLE_VALUE;
-  }
-
-  result = WSASend(handle->socket,
-                   (WSABUF*) bufs,
-                   nbufs,
-                   &bytes,
-                   0,
-                   &req->u.io.overlapped,
-                   NULL);
-
-  if (UV_SUCCEEDED_WITHOUT_IOCP(result == 0)) {
-    /* Request completed immediately. */
-    req->u.io.queued_bytes = 0;
-    handle->reqs_pending++;
-    handle->stream.conn.write_reqs_pending++;
-    REGISTER_HANDLE_REQ(loop, handle, req);
-    uv_insert_pending_req(loop, (uv_req_t*) req);
-  } else if (UV_SUCCEEDED_WITH_IOCP(result == 0)) {
-    /* Request queued by the kernel. */
-    req->u.io.queued_bytes = uv__count_bufs(bufs, nbufs);
-    handle->reqs_pending++;
-    handle->stream.conn.write_reqs_pending++;
-    REGISTER_HANDLE_REQ(loop, handle, req);
-    handle->write_queue_size += req->u.io.queued_bytes;
-    if (handle->flags & UV_HANDLE_EMULATE_IOCP &&
-        !RegisterWaitForSingleObject(&req->wait_handle,
-          req->event_handle, post_write_completion, (void*) req,
-          INFINITE, WT_EXECUTEINWAITTHREAD | WT_EXECUTEONLYONCE)) {
-      SET_REQ_ERROR(req, GetLastError());
-      uv_insert_pending_req(loop, (uv_req_t*)req);
-    }
-  } else {
-    /* Send failed due to an error, report it later */
-    req->u.io.queued_bytes = 0;
-    handle->reqs_pending++;
-    handle->stream.conn.write_reqs_pending++;
-    REGISTER_HANDLE_REQ(loop, handle, req);
-    SET_REQ_ERROR(req, WSAGetLastError());
-    uv_insert_pending_req(loop, (uv_req_t*) req);
-  }
-
-  return 0;
-}
-
-
-int uv__tcp_try_write(uv_tcp_t* handle,
-                     const uv_buf_t bufs[],
-                     unsigned int nbufs) {
-  int result;
-  DWORD bytes;
-
-  if (handle->stream.conn.write_reqs_pending > 0)
-    return UV_EAGAIN;
-
-  result = WSASend(handle->socket,
-                   (WSABUF*) bufs,
-                   nbufs,
-                   &bytes,
-                   0,
-                   NULL,
-                   NULL);
-
-  if (result == SOCKET_ERROR)
-    return uv_translate_sys_error(WSAGetLastError());
-  else
-    return bytes;
-}
-
-
-void uv_process_tcp_read_req(uv_loop_t* loop, uv_tcp_t* handle,
-    uv_req_t* req) {
-  DWORD bytes, flags, err;
-  uv_buf_t buf;
-  int count;
-
-  assert(handle->type == UV_TCP);
-
-  handle->flags &= ~UV_HANDLE_READ_PENDING;
-
-  if (!REQ_SUCCESS(req)) {
-    /* An error occurred doing the read. */
-    if ((handle->flags & UV_HANDLE_READING) ||
-        !(handle->flags & UV_HANDLE_ZERO_READ)) {
-      handle->flags &= ~UV_HANDLE_READING;
-      DECREASE_ACTIVE_COUNT(loop, handle);
-      buf = (handle->flags & UV_HANDLE_ZERO_READ) ?
-            uv_buf_init(NULL, 0) : handle->tcp.conn.read_buffer;
-
-      err = GET_REQ_SOCK_ERROR(req);
-
-      if (err == WSAECONNABORTED) {
-        /* Turn WSAECONNABORTED into UV_ECONNRESET to be consistent with Unix.
-         */
-        err = WSAECONNRESET;
-      }
-
-      handle->read_cb((uv_stream_t*)handle,
-                      uv_translate_sys_error(err),
-                      &buf);
-    }
-  } else {
-    if (!(handle->flags & UV_HANDLE_ZERO_READ)) {
-      /* The read was done with a non-zero buffer length. */
-      if (req->u.io.overlapped.InternalHigh > 0) {
-        /* Successful read */
-        handle->read_cb((uv_stream_t*)handle,
-                        req->u.io.overlapped.InternalHigh,
-                        &handle->tcp.conn.read_buffer);
-        /* Read again only if bytes == buf.len */
-        if (req->u.io.overlapped.InternalHigh < handle->tcp.conn.read_buffer.len) {
-          goto done;
-        }
-      } else {
-        /* Connection closed */
-        if (handle->flags & UV_HANDLE_READING) {
-          handle->flags &= ~UV_HANDLE_READING;
-          DECREASE_ACTIVE_COUNT(loop, handle);
-        }
-        handle->flags &= ~UV_HANDLE_READABLE;
-
-        buf.base = 0;
-        buf.len = 0;
-        handle->read_cb((uv_stream_t*)handle, UV_EOF, &handle->tcp.conn.read_buffer);
-        goto done;
-      }
-    }
-
-    /* Do nonblocking reads until the buffer is empty */
-    count = 32;
-    while ((handle->flags & UV_HANDLE_READING) && (count-- > 0)) {
-      buf = uv_buf_init(NULL, 0);
-      handle->alloc_cb((uv_handle_t*) handle, 65536, &buf);
-      if (buf.base == NULL || buf.len == 0) {
-        handle->read_cb((uv_stream_t*) handle, UV_ENOBUFS, &buf);
-        break;
-      }
-      assert(buf.base != NULL);
-
-      flags = 0;
-      if (WSARecv(handle->socket,
-                  (WSABUF*)&buf,
-                  1,
-                  &bytes,
-                  &flags,
-                  NULL,
-                  NULL) != SOCKET_ERROR) {
-        if (bytes > 0) {
-          /* Successful read */
-          handle->read_cb((uv_stream_t*)handle, bytes, &buf);
-          /* Read again only if bytes == buf.len */
-          if (bytes < buf.len) {
-            break;
-          }
-        } else {
-          /* Connection closed */
-          handle->flags &= ~(UV_HANDLE_READING | UV_HANDLE_READABLE);
-          DECREASE_ACTIVE_COUNT(loop, handle);
-
-          handle->read_cb((uv_stream_t*)handle, UV_EOF, &buf);
-          break;
-        }
-      } else {
-        err = WSAGetLastError();
-        if (err == WSAEWOULDBLOCK) {
-          /* Read buffer was completely empty, report a 0-byte read. */
-          handle->read_cb((uv_stream_t*)handle, 0, &buf);
-        } else {
-          /* Ouch! serious error. */
-          handle->flags &= ~UV_HANDLE_READING;
-          DECREASE_ACTIVE_COUNT(loop, handle);
-
-          if (err == WSAECONNABORTED) {
-            /* Turn WSAECONNABORTED into UV_ECONNRESET to be consistent with
-             * Unix. */
-            err = WSAECONNRESET;
-          }
-
-          handle->read_cb((uv_stream_t*)handle,
-                          uv_translate_sys_error(err),
-                          &buf);
-        }
-        break;
-      }
-    }
-
-done:
-    /* Post another read if still reading and not closing. */
-    if ((handle->flags & UV_HANDLE_READING) &&
-        !(handle->flags & UV_HANDLE_READ_PENDING)) {
-      uv_tcp_queue_read(loop, handle);
-    }
-  }
-
-  DECREASE_PENDING_REQ_COUNT(handle);
-}
-
-
-void uv_process_tcp_write_req(uv_loop_t* loop, uv_tcp_t* handle,
-    uv_write_t* req) {
-  int err;
-
-  assert(handle->type == UV_TCP);
-
-  assert(handle->write_queue_size >= req->u.io.queued_bytes);
-  handle->write_queue_size -= req->u.io.queued_bytes;
-
-  UNREGISTER_HANDLE_REQ(loop, handle, req);
-
-  if (handle->flags & UV_HANDLE_EMULATE_IOCP) {
-    if (req->wait_handle != INVALID_HANDLE_VALUE) {
-      UnregisterWait(req->wait_handle);
-      req->wait_handle = INVALID_HANDLE_VALUE;
-    }
-    if (req->event_handle) {
-      CloseHandle(req->event_handle);
-      req->event_handle = NULL;
-    }
-  }
-
-  if (req->cb) {
-    err = uv_translate_sys_error(GET_REQ_SOCK_ERROR(req));
-    if (err == UV_ECONNABORTED) {
-      /* use UV_ECANCELED for consistency with Unix */
-      err = UV_ECANCELED;
-    }
-    req->cb(req, err);
-  }
-
-  handle->stream.conn.write_reqs_pending--;
-  if (handle->stream.conn.shutdown_req != NULL &&
-      handle->stream.conn.write_reqs_pending == 0) {
-    uv_want_endgame(loop, (uv_handle_t*)handle);
-  }
-
-  DECREASE_PENDING_REQ_COUNT(handle);
-}
-
-
-void uv_process_tcp_accept_req(uv_loop_t* loop, uv_tcp_t* handle,
-    uv_req_t* raw_req) {
-  uv_tcp_accept_t* req = (uv_tcp_accept_t*) raw_req;
-  int err;
-
-  assert(handle->type == UV_TCP);
-
-  /* If handle->accepted_socket is not a valid socket, then uv_queue_accept
-   * must have failed. This is a serious error. We stop accepting connections
-   * and report this error to the connection callback. */
-  if (req->accept_socket == INVALID_SOCKET) {
-    if (handle->flags & UV_HANDLE_LISTENING) {
-      handle->flags &= ~UV_HANDLE_LISTENING;
-      DECREASE_ACTIVE_COUNT(loop, handle);
-      if (handle->stream.serv.connection_cb) {
-        err = GET_REQ_SOCK_ERROR(req);
-        handle->stream.serv.connection_cb((uv_stream_t*)handle,
-                                      uv_translate_sys_error(err));
-      }
-    }
-  } else if (REQ_SUCCESS(req) &&
-      setsockopt(req->accept_socket,
-                  SOL_SOCKET,
-                  SO_UPDATE_ACCEPT_CONTEXT,
-                  (char*)&handle->socket,
-                  sizeof(handle->socket)) == 0) {
-    req->next_pending = handle->tcp.serv.pending_accepts;
-    handle->tcp.serv.pending_accepts = req;
-
-    /* Accept and SO_UPDATE_ACCEPT_CONTEXT were successful. */
-    if (handle->stream.serv.connection_cb) {
-      handle->stream.serv.connection_cb((uv_stream_t*)handle, 0);
-    }
-  } else {
-    /* Error related to accepted socket is ignored because the server socket
-     * may still be healthy. If the server socket is broken uv_queue_accept
-     * will detect it. */
-    closesocket(req->accept_socket);
-    req->accept_socket = INVALID_SOCKET;
-    if (handle->flags & UV_HANDLE_LISTENING) {
-      uv_tcp_queue_accept(handle, req);
-    }
-  }
-
-  DECREASE_PENDING_REQ_COUNT(handle);
-}
-
-
-void uv_process_tcp_connect_req(uv_loop_t* loop, uv_tcp_t* handle,
-    uv_connect_t* req) {
-  int err;
-
-  assert(handle->type == UV_TCP);
-
-  UNREGISTER_HANDLE_REQ(loop, handle, req);
-
-  err = 0;
-  if (REQ_SUCCESS(req)) {
-    if (handle->flags & UV_HANDLE_CLOSING) {
-      /* use UV_ECANCELED for consistency with Unix */
-      err = ERROR_OPERATION_ABORTED;
-    } else if (setsockopt(handle->socket,
-                          SOL_SOCKET,
-                          SO_UPDATE_CONNECT_CONTEXT,
-                          NULL,
-                          0) == 0) {
-      uv_connection_init((uv_stream_t*)handle);
-      handle->flags |= UV_HANDLE_READABLE | UV_HANDLE_WRITABLE;
-      loop->active_tcp_streams++;
-    } else {
-      err = WSAGetLastError();
-    }
-  } else {
-    err = GET_REQ_SOCK_ERROR(req);
-  }
-  req->cb(req, uv_translate_sys_error(err));
-
-  DECREASE_PENDING_REQ_COUNT(handle);
-}
-
-
-int uv__tcp_xfer_export(uv_tcp_t* handle,
-                        int target_pid,
-                        uv__ipc_socket_xfer_type_t* xfer_type,
-                        uv__ipc_socket_xfer_info_t* xfer_info) {
-  if (handle->flags & UV_HANDLE_CONNECTION) {
-    *xfer_type = UV__IPC_SOCKET_XFER_TCP_CONNECTION;
-  } else {
-    *xfer_type = UV__IPC_SOCKET_XFER_TCP_SERVER;
-    /* We're about to share the socket with another process. Because this is a
-     * listening socket, we assume that the other process will be accepting
-     * connections on it. Thus, before sharing the socket with another process,
-     * we call listen here in the parent process. */
-    if (!(handle->flags & UV_HANDLE_LISTENING)) {
-      if (!(handle->flags & UV_HANDLE_BOUND)) {
-        return ERROR_NOT_SUPPORTED;
-      }
-      if (handle->delayed_error == 0 &&
-          listen(handle->socket, SOMAXCONN) == SOCKET_ERROR) {
-        handle->delayed_error = WSAGetLastError();
-      }
-    }
-  }
-
-  if (WSADuplicateSocketW(handle->socket, target_pid, &xfer_info->socket_info))
-    return WSAGetLastError();
-  xfer_info->delayed_error = handle->delayed_error;
-
-  /* Mark the local copy of the handle as 'shared' so we behave in a way that's
-   * friendly to the process(es) that we share the socket with. */
-  handle->flags |= UV_HANDLE_SHARED_TCP_SOCKET;
-
-  return 0;
-}
-
-
-int uv__tcp_xfer_import(uv_tcp_t* tcp,
-                        uv__ipc_socket_xfer_type_t xfer_type,
-                        uv__ipc_socket_xfer_info_t* xfer_info) {
-  int err;
-  SOCKET socket;
-
-  assert(xfer_type == UV__IPC_SOCKET_XFER_TCP_SERVER ||
-         xfer_type == UV__IPC_SOCKET_XFER_TCP_CONNECTION);
-
-  socket = WSASocketW(FROM_PROTOCOL_INFO,
-                      FROM_PROTOCOL_INFO,
-                      FROM_PROTOCOL_INFO,
-                      &xfer_info->socket_info,
-                      0,
-                      WSA_FLAG_OVERLAPPED);
-
-  if (socket == INVALID_SOCKET) {
-    return WSAGetLastError();
-  }
-
-  err = uv_tcp_set_socket(
-      tcp->loop, tcp, socket, xfer_info->socket_info.iAddressFamily, 1);
-  if (err) {
-    closesocket(socket);
-    return err;
-  }
-
-  tcp->delayed_error = xfer_info->delayed_error;
-  tcp->flags |= UV_HANDLE_BOUND | UV_HANDLE_SHARED_TCP_SOCKET;
-
-  if (xfer_type == UV__IPC_SOCKET_XFER_TCP_CONNECTION) {
-    uv_connection_init((uv_stream_t*)tcp);
-    tcp->flags |= UV_HANDLE_READABLE | UV_HANDLE_WRITABLE;
-  }
-
-  tcp->loop->active_tcp_streams++;
-  return 0;
-}
-
-
-int uv_tcp_nodelay(uv_tcp_t* handle, int enable) {
-  int err;
-
-  if (handle->socket != INVALID_SOCKET) {
-    err = uv__tcp_nodelay(handle, handle->socket, enable);
-    if (err)
-      return err;
-  }
-
-  if (enable) {
-    handle->flags |= UV_HANDLE_TCP_NODELAY;
-  } else {
-    handle->flags &= ~UV_HANDLE_TCP_NODELAY;
-  }
-
-  return 0;
-}
-
-
-int uv_tcp_keepalive(uv_tcp_t* handle, int enable, unsigned int delay) {
-  int err;
-
-  if (handle->socket != INVALID_SOCKET) {
-    err = uv__tcp_keepalive(handle, handle->socket, enable, delay);
-    if (err)
-      return err;
-  }
-
-  if (enable) {
-    handle->flags |= UV_HANDLE_TCP_KEEPALIVE;
-  } else {
-    handle->flags &= ~UV_HANDLE_TCP_KEEPALIVE;
-  }
-
-  /* TODO: Store delay if handle->socket isn't created yet. */
-
-  return 0;
-}
-
-
-int uv_tcp_simultaneous_accepts(uv_tcp_t* handle, int enable) {
-  if (handle->flags & UV_HANDLE_CONNECTION) {
-    return UV_EINVAL;
-  }
-
-  /* Check if we're already in the desired mode. */
-  if ((enable && !(handle->flags & UV_HANDLE_TCP_SINGLE_ACCEPT)) ||
-      (!enable && handle->flags & UV_HANDLE_TCP_SINGLE_ACCEPT)) {
-    return 0;
-  }
-
-  /* Don't allow switching from single pending accept to many. */
-  if (enable) {
-    return UV_ENOTSUP;
-  }
-
-  /* Check if we're in a middle of changing the number of pending accepts. */
-  if (handle->flags & UV_HANDLE_TCP_ACCEPT_STATE_CHANGING) {
-    return 0;
-  }
-
-  handle->flags |= UV_HANDLE_TCP_SINGLE_ACCEPT;
-
-  /* Flip the changing flag if we have already queued multiple accepts. */
-  if (handle->flags & UV_HANDLE_LISTENING) {
-    handle->flags |= UV_HANDLE_TCP_ACCEPT_STATE_CHANGING;
-  }
-
-  return 0;
-}
-
-
-static int uv_tcp_try_cancel_io(uv_tcp_t* tcp) {
-  SOCKET socket = tcp->socket;
-  int non_ifs_lsp;
-
-  /* Check if we have any non-IFS LSPs stacked on top of TCP */
-  non_ifs_lsp = (tcp->flags & UV_HANDLE_IPV6) ? uv_tcp_non_ifs_lsp_ipv6 :
-                                                uv_tcp_non_ifs_lsp_ipv4;
-
-  /* If there are non-ifs LSPs then try to obtain a base handle for the socket.
-   * This will always fail on Windows XP/3k. */
-  if (non_ifs_lsp) {
-    DWORD bytes;
-    if (WSAIoctl(socket,
-                 SIO_BASE_HANDLE,
-                 NULL,
-                 0,
-                 &socket,
-                 sizeof socket,
-                 &bytes,
-                 NULL,
-                 NULL) != 0) {
-      /* Failed. We can't do CancelIo. */
-      return -1;
-    }
-  }
-
-  assert(socket != 0 && socket != INVALID_SOCKET);
-
-  if (!CancelIo((HANDLE) socket)) {
-    return GetLastError();
-  }
-
-  /* It worked. */
-  return 0;
-}
-
-
-void uv_tcp_close(uv_loop_t* loop, uv_tcp_t* tcp) {
-  int close_socket = 1;
-
-  if (tcp->flags & UV_HANDLE_READ_PENDING) {
-    /* In order for winsock to do a graceful close there must not be any any
-     * pending reads, or the socket must be shut down for writing */
-    if (!(tcp->flags & UV_HANDLE_SHARED_TCP_SOCKET)) {
-      /* Just do shutdown on non-shared sockets, which ensures graceful close. */
-      shutdown(tcp->socket, SD_SEND);
-
-    } else if (uv_tcp_try_cancel_io(tcp) == 0) {
-      /* In case of a shared socket, we try to cancel all outstanding I/O,. If
-       * that works, don't close the socket yet - wait for the read req to
-       * return and close the socket in uv_tcp_endgame. */
-      close_socket = 0;
-
-    } else {
-      /* When cancelling isn't possible - which could happen when an LSP is
-       * present on an old Windows version, we will have to close the socket
-       * with a read pending. That is not nice because trailing sent bytes may
-       * not make it to the other side. */
-    }
-
-  } else if ((tcp->flags & UV_HANDLE_SHARED_TCP_SOCKET) &&
-             tcp->tcp.serv.accept_reqs != NULL) {
-    /* Under normal circumstances closesocket() will ensure that all pending
-     * accept reqs are canceled. However, when the socket is shared the
-     * presence of another reference to the socket in another process will keep
-     * the accept reqs going, so we have to ensure that these are canceled. */
-    if (uv_tcp_try_cancel_io(tcp) != 0) {
-      /* When cancellation is not possible, there is another option: we can
-       * close the incoming sockets, which will also cancel the accept
-       * operations. However this is not cool because we might inadvertently
-       * close a socket that just accepted a new connection, which will cause
-       * the connection to be aborted. */
-      unsigned int i;
-      for (i = 0; i < uv_simultaneous_server_accepts; i++) {
-        uv_tcp_accept_t* req = &tcp->tcp.serv.accept_reqs[i];
-        if (req->accept_socket != INVALID_SOCKET &&
-            !HasOverlappedIoCompleted(&req->u.io.overlapped)) {
-          closesocket(req->accept_socket);
-          req->accept_socket = INVALID_SOCKET;
-        }
-      }
-    }
-  }
-
-  if (tcp->flags & UV_HANDLE_READING) {
-    tcp->flags &= ~UV_HANDLE_READING;
-    DECREASE_ACTIVE_COUNT(loop, tcp);
-  }
-
-  if (tcp->flags & UV_HANDLE_LISTENING) {
-    tcp->flags &= ~UV_HANDLE_LISTENING;
-    DECREASE_ACTIVE_COUNT(loop, tcp);
-  }
-
-  if (close_socket) {
-    closesocket(tcp->socket);
-    tcp->socket = INVALID_SOCKET;
-    tcp->flags |= UV_HANDLE_TCP_SOCKET_CLOSED;
-  }
-
-  tcp->flags &= ~(UV_HANDLE_READABLE | UV_HANDLE_WRITABLE);
-  uv__handle_closing(tcp);
-
-  if (tcp->reqs_pending == 0) {
-    uv_want_endgame(tcp->loop, (uv_handle_t*)tcp);
-  }
-}
-
-
-int uv_tcp_open(uv_tcp_t* handle, uv_os_sock_t sock) {
-  WSAPROTOCOL_INFOW protocol_info;
-  int opt_len;
-  int err;
-  struct sockaddr_storage saddr;
-  int saddr_len;
-
-  /* Detect the address family of the socket. */
-  opt_len = (int) sizeof protocol_info;
-  if (getsockopt(sock,
-                 SOL_SOCKET,
-                 SO_PROTOCOL_INFOW,
-                 (char*) &protocol_info,
-                 &opt_len) == SOCKET_ERROR) {
-    return uv_translate_sys_error(GetLastError());
-  }
-
-  err = uv_tcp_set_socket(handle->loop,
-                          handle,
-                          sock,
-                          protocol_info.iAddressFamily,
-                          1);
-  if (err) {
-    return uv_translate_sys_error(err);
-  }
-
-  /* Support already active socket. */
-  saddr_len = sizeof(saddr);
-  if (!uv_tcp_getsockname(handle, (struct sockaddr*) &saddr, &saddr_len)) {
-    /* Socket is already bound. */
-    handle->flags |= UV_HANDLE_BOUND;
-    saddr_len = sizeof(saddr);
-    if (!uv_tcp_getpeername(handle, (struct sockaddr*) &saddr, &saddr_len)) {
-      /* Socket is already connected. */
-      uv_connection_init((uv_stream_t*) handle);
-      handle->flags |= UV_HANDLE_READABLE | UV_HANDLE_WRITABLE;
-    }
-  }
-
-  return 0;
-}
-
-
-/* This function is an egress point, i.e. it returns libuv errors rather than
- * system errors.
- */
-int uv__tcp_bind(uv_tcp_t* handle,
-                 const struct sockaddr* addr,
-                 unsigned int addrlen,
-                 unsigned int flags) {
-  int err;
-
-  err = uv_tcp_try_bind(handle, addr, addrlen, flags);
-  if (err)
-    return uv_translate_sys_error(err);
-
-  return 0;
-}
-
-
-/* This function is an egress point, i.e. it returns libuv errors rather than
- * system errors.
- */
-int uv__tcp_connect(uv_connect_t* req,
-                    uv_tcp_t* handle,
-                    const struct sockaddr* addr,
-                    unsigned int addrlen,
-                    uv_connect_cb cb) {
-  int err;
-
-  err = uv_tcp_try_connect(req, handle, addr, addrlen, cb);
-  if (err)
-    return uv_translate_sys_error(err);
-
-  return 0;
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/thread.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/thread.cpp
deleted file mode 100644
index 72af03c..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/thread.cpp
+++ /dev/null
@@ -1,520 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include <assert.h>
-#include <limits.h>
-#include <stdlib.h>
-
-#if defined(__MINGW64_VERSION_MAJOR)
-/* MemoryBarrier expands to __mm_mfence in some cases (x86+sse2), which may
- * require this header in some versions of mingw64. */
-#include <intrin.h>
-#endif
-
-#include "uv.h"
-#include "internal.h"
-
-static void uv__once_inner(uv_once_t* guard, void (*callback)(void)) {
-  DWORD result;
-  HANDLE existing_event, created_event;
-
-  created_event = CreateEvent(NULL, 1, 0, NULL);
-  if (created_event == 0) {
-    /* Could fail in a low-memory situation? */
-    uv_fatal_error(GetLastError(), "CreateEvent");
-  }
-
-  existing_event = InterlockedCompareExchangePointer(&guard->event,
-                                                     created_event,
-                                                     NULL);
-
-  if (existing_event == NULL) {
-    /* We won the race */
-    callback();
-
-    result = SetEvent(created_event);
-    assert(result);
-    guard->ran = 1;
-
-  } else {
-    /* We lost the race. Destroy the event we created and wait for the existing
-     * one to become signaled. */
-    CloseHandle(created_event);
-    result = WaitForSingleObject(existing_event, INFINITE);
-    assert(result == WAIT_OBJECT_0);
-  }
-}
-
-
-void uv_once(uv_once_t* guard, void (*callback)(void)) {
-  /* Fast case - avoid WaitForSingleObject. */
-  if (guard->ran) {
-    return;
-  }
-
-  uv__once_inner(guard, callback);
-}
-
-
-/* Verify that uv_thread_t can be stored in a TLS slot. */
-STATIC_ASSERT(sizeof(uv_thread_t) <= sizeof(void*));
-
-static uv_key_t uv__current_thread_key;
-static uv_once_t uv__current_thread_init_guard = UV_ONCE_INIT;
-
-
-static void uv__init_current_thread_key(void) {
-  if (uv_key_create(&uv__current_thread_key))
-    abort();
-}
-
-
-struct thread_ctx {
-  void (*entry)(void* arg);
-  void* arg;
-  uv_thread_t self;
-};
-
-
-static UINT __stdcall uv__thread_start(void* arg) {
-  struct thread_ctx *ctx_p;
-  struct thread_ctx ctx;
-
-  ctx_p = (struct thread_ctx*)arg;
-  ctx = *ctx_p;
-  uv__free(ctx_p);
-
-  uv_once(&uv__current_thread_init_guard, uv__init_current_thread_key);
-  uv_key_set(&uv__current_thread_key, (void*) ctx.self);
-
-  ctx.entry(ctx.arg);
-
-  return 0;
-}
-
-
-int uv_thread_create(uv_thread_t *tid, void (*entry)(void *arg), void *arg) {
-  uv_thread_options_t params;
-  params.flags = UV_THREAD_NO_FLAGS;
-  return uv_thread_create_ex(tid, &params, entry, arg);
-}
-
-int uv_thread_create_ex(uv_thread_t* tid,
-                        const uv_thread_options_t* params,
-                        void (*entry)(void *arg),
-                        void *arg) {
-  struct thread_ctx* ctx;
-  int err;
-  HANDLE thread;
-  SYSTEM_INFO sysinfo;
-  size_t stack_size;
-  size_t pagesize;
-
-  stack_size =
-      params->flags & UV_THREAD_HAS_STACK_SIZE ? params->stack_size : 0;
-
-  if (stack_size != 0) {
-    GetNativeSystemInfo(&sysinfo);
-    pagesize = (size_t)sysinfo.dwPageSize;
-    /* Round up to the nearest page boundary. */
-    stack_size = (stack_size + pagesize - 1) &~ (pagesize - 1);
-
-    if ((unsigned)stack_size != stack_size)
-      return UV_EINVAL;
-  }
-
-  ctx = (struct thread_ctx*)uv__malloc(sizeof(*ctx));
-  if (ctx == NULL)
-    return UV_ENOMEM;
-
-  ctx->entry = entry;
-  ctx->arg = arg;
-
-  /* Create the thread in suspended state so we have a chance to pass
-   * its own creation handle to it */
-  thread = (HANDLE) _beginthreadex(NULL,
-                                   (unsigned)stack_size,
-                                   uv__thread_start,
-                                   ctx,
-                                   CREATE_SUSPENDED,
-                                   NULL);
-  if (thread == NULL) {
-    err = errno;
-    uv__free(ctx);
-  } else {
-    err = 0;
-    *tid = thread;
-    ctx->self = thread;
-    ResumeThread(thread);
-  }
-
-  switch (err) {
-    case 0:
-      return 0;
-    case EACCES:
-      return UV_EACCES;
-    case EAGAIN:
-      return UV_EAGAIN;
-    case EINVAL:
-      return UV_EINVAL;
-  }
-
-  return UV_EIO;
-}
-
-
-uv_thread_t uv_thread_self(void) {
-  uv_once(&uv__current_thread_init_guard, uv__init_current_thread_key);
-  return (uv_thread_t) uv_key_get(&uv__current_thread_key);
-}
-
-
-int uv_thread_join(uv_thread_t *tid) {
-  if (WaitForSingleObject(*tid, INFINITE))
-    return uv_translate_sys_error(GetLastError());
-  else {
-    CloseHandle(*tid);
-    *tid = 0;
-    MemoryBarrier();  /* For feature parity with pthread_join(). */
-    return 0;
-  }
-}
-
-
-int uv_thread_equal(const uv_thread_t* t1, const uv_thread_t* t2) {
-  return *t1 == *t2;
-}
-
-
-int uv_mutex_init(uv_mutex_t* mutex) {
-  InitializeCriticalSection(mutex);
-  return 0;
-}
-
-
-int uv_mutex_init_recursive(uv_mutex_t* mutex) {
-  return uv_mutex_init(mutex);
-}
-
-
-void uv_mutex_destroy(uv_mutex_t* mutex) {
-  DeleteCriticalSection(mutex);
-}
-
-
-void uv_mutex_lock(uv_mutex_t* mutex) {
-  EnterCriticalSection(mutex);
-}
-
-
-int uv_mutex_trylock(uv_mutex_t* mutex) {
-  if (TryEnterCriticalSection(mutex))
-    return 0;
-  else
-    return UV_EBUSY;
-}
-
-
-void uv_mutex_unlock(uv_mutex_t* mutex) {
-  LeaveCriticalSection(mutex);
-}
-
-
-int uv_rwlock_init(uv_rwlock_t* rwlock) {
-  /* Initialize the semaphore that acts as the write lock. */
-  HANDLE handle = CreateSemaphoreW(NULL, 1, 1, NULL);
-  if (handle == NULL)
-    return uv_translate_sys_error(GetLastError());
-  rwlock->state_.write_semaphore_ = handle;
-
-  /* Initialize the critical section protecting the reader count. */
-  InitializeCriticalSection(&rwlock->state_.num_readers_lock_);
-
-  /* Initialize the reader count. */
-  rwlock->state_.num_readers_ = 0;
-
-  return 0;
-}
-
-
-void uv_rwlock_destroy(uv_rwlock_t* rwlock) {
-  DeleteCriticalSection(&rwlock->state_.num_readers_lock_);
-  CloseHandle(rwlock->state_.write_semaphore_);
-}
-
-
-void uv_rwlock_rdlock(uv_rwlock_t* rwlock) {
-  /* Acquire the lock that protects the reader count. */
-  EnterCriticalSection(&rwlock->state_.num_readers_lock_);
-
-  /* Increase the reader count, and lock for write if this is the first
-   * reader.
-   */
-  if (++rwlock->state_.num_readers_ == 1) {
-    DWORD r = WaitForSingleObject(rwlock->state_.write_semaphore_, INFINITE);
-    if (r != WAIT_OBJECT_0)
-      uv_fatal_error(GetLastError(), "WaitForSingleObject");
-  }
-
-  /* Release the lock that protects the reader count. */
-  LeaveCriticalSection(&rwlock->state_.num_readers_lock_);
-}
-
-
-int uv_rwlock_tryrdlock(uv_rwlock_t* rwlock) {
-  int err;
-
-  if (!TryEnterCriticalSection(&rwlock->state_.num_readers_lock_))
-    return UV_EBUSY;
-
-  err = 0;
-
-  if (rwlock->state_.num_readers_ == 0) {
-    /* Currently there are no other readers, which means that the write lock
-     * needs to be acquired.
-     */
-    DWORD r = WaitForSingleObject(rwlock->state_.write_semaphore_, 0);
-    if (r == WAIT_OBJECT_0)
-      rwlock->state_.num_readers_++;
-    else if (r == WAIT_TIMEOUT)
-      err = UV_EBUSY;
-    else if (r == WAIT_FAILED)
-      uv_fatal_error(GetLastError(), "WaitForSingleObject");
-
-  } else {
-    /* The write lock has already been acquired because there are other
-     * active readers.
-     */
-    rwlock->state_.num_readers_++;
-  }
-
-  LeaveCriticalSection(&rwlock->state_.num_readers_lock_);
-  return err;
-}
-
-
-void uv_rwlock_rdunlock(uv_rwlock_t* rwlock) {
-  EnterCriticalSection(&rwlock->state_.num_readers_lock_);
-
-  if (--rwlock->state_.num_readers_ == 0) {
-    if (!ReleaseSemaphore(rwlock->state_.write_semaphore_, 1, NULL))
-      uv_fatal_error(GetLastError(), "ReleaseSemaphore");
-  }
-
-  LeaveCriticalSection(&rwlock->state_.num_readers_lock_);
-}
-
-
-void uv_rwlock_wrlock(uv_rwlock_t* rwlock) {
-  DWORD r = WaitForSingleObject(rwlock->state_.write_semaphore_, INFINITE);
-  if (r != WAIT_OBJECT_0)
-    uv_fatal_error(GetLastError(), "WaitForSingleObject");
-}
-
-
-int uv_rwlock_trywrlock(uv_rwlock_t* rwlock) {
-  DWORD r = WaitForSingleObject(rwlock->state_.write_semaphore_, 0);
-  if (r == WAIT_OBJECT_0)
-    return 0;
-  else if (r == WAIT_TIMEOUT)
-    return UV_EBUSY;
-  else
-    uv_fatal_error(GetLastError(), "WaitForSingleObject");
-}
-
-
-void uv_rwlock_wrunlock(uv_rwlock_t* rwlock) {
-  if (!ReleaseSemaphore(rwlock->state_.write_semaphore_, 1, NULL))
-    uv_fatal_error(GetLastError(), "ReleaseSemaphore");
-}
-
-
-int uv_sem_init(uv_sem_t* sem, unsigned int value) {
-  *sem = CreateSemaphore(NULL, value, INT_MAX, NULL);
-  if (*sem == NULL)
-    return uv_translate_sys_error(GetLastError());
-  else
-    return 0;
-}
-
-
-void uv_sem_destroy(uv_sem_t* sem) {
-  if (!CloseHandle(*sem))
-    abort();
-}
-
-
-void uv_sem_post(uv_sem_t* sem) {
-  if (!ReleaseSemaphore(*sem, 1, NULL))
-    abort();
-}
-
-
-void uv_sem_wait(uv_sem_t* sem) {
-  if (WaitForSingleObject(*sem, INFINITE) != WAIT_OBJECT_0)
-    abort();
-}
-
-
-int uv_sem_trywait(uv_sem_t* sem) {
-  DWORD r = WaitForSingleObject(*sem, 0);
-
-  if (r == WAIT_OBJECT_0)
-    return 0;
-
-  if (r == WAIT_TIMEOUT)
-    return UV_EAGAIN;
-
-  abort();
-  return -1; /* Satisfy the compiler. */
-}
-
-
-int uv_cond_init(uv_cond_t* cond) {
-  InitializeConditionVariable(&cond->cond_var);
-  return 0;
-}
-
-
-void uv_cond_destroy(uv_cond_t* cond) {
-  /* nothing to do */
-  (void) &cond;
-}
-
-
-void uv_cond_signal(uv_cond_t* cond) {
-  WakeConditionVariable(&cond->cond_var);
-}
-
-
-void uv_cond_broadcast(uv_cond_t* cond) {
-  WakeAllConditionVariable(&cond->cond_var);
-}
-
-
-void uv_cond_wait(uv_cond_t* cond, uv_mutex_t* mutex) {
-  if (!SleepConditionVariableCS(&cond->cond_var, mutex, INFINITE))
-    abort();
-}
-
-int uv_cond_timedwait(uv_cond_t* cond, uv_mutex_t* mutex, uint64_t timeout) {
-  if (SleepConditionVariableCS(&cond->cond_var, mutex, (DWORD)(timeout / 1e6)))
-    return 0;
-  if (GetLastError() != ERROR_TIMEOUT)
-    abort();
-  return UV_ETIMEDOUT;
-}
-
-
-int uv_barrier_init(uv_barrier_t* barrier, unsigned int count) {
-  int err;
-
-  barrier->n = count;
-  barrier->count = 0;
-
-  err = uv_mutex_init(&barrier->mutex);
-  if (err)
-    return err;
-
-  err = uv_sem_init(&barrier->turnstile1, 0);
-  if (err)
-    goto error2;
-
-  err = uv_sem_init(&barrier->turnstile2, 1);
-  if (err)
-    goto error;
-
-  return 0;
-
-error:
-  uv_sem_destroy(&barrier->turnstile1);
-error2:
-  uv_mutex_destroy(&barrier->mutex);
-  return err;
-
-}
-
-
-void uv_barrier_destroy(uv_barrier_t* barrier) {
-  uv_sem_destroy(&barrier->turnstile2);
-  uv_sem_destroy(&barrier->turnstile1);
-  uv_mutex_destroy(&barrier->mutex);
-}
-
-
-int uv_barrier_wait(uv_barrier_t* barrier) {
-  int serial_thread;
-
-  uv_mutex_lock(&barrier->mutex);
-  if (++barrier->count == barrier->n) {
-    uv_sem_wait(&barrier->turnstile2);
-    uv_sem_post(&barrier->turnstile1);
-  }
-  uv_mutex_unlock(&barrier->mutex);
-
-  uv_sem_wait(&barrier->turnstile1);
-  uv_sem_post(&barrier->turnstile1);
-
-  uv_mutex_lock(&barrier->mutex);
-  serial_thread = (--barrier->count == 0);
-  if (serial_thread) {
-    uv_sem_wait(&barrier->turnstile1);
-    uv_sem_post(&barrier->turnstile2);
-  }
-  uv_mutex_unlock(&barrier->mutex);
-
-  uv_sem_wait(&barrier->turnstile2);
-  uv_sem_post(&barrier->turnstile2);
-  return serial_thread;
-}
-
-
-int uv_key_create(uv_key_t* key) {
-  key->tls_index = TlsAlloc();
-  if (key->tls_index == TLS_OUT_OF_INDEXES)
-    return UV_ENOMEM;
-  return 0;
-}
-
-
-void uv_key_delete(uv_key_t* key) {
-  if (TlsFree(key->tls_index) == FALSE)
-    abort();
-  key->tls_index = TLS_OUT_OF_INDEXES;
-}
-
-
-void* uv_key_get(uv_key_t* key) {
-  void* value;
-
-  value = TlsGetValue(key->tls_index);
-  if (value == NULL)
-    if (GetLastError() != ERROR_SUCCESS)
-      abort();
-
-  return value;
-}
-
-
-void uv_key_set(uv_key_t* key, void* value) {
-  if (TlsSetValue(key->tls_index, value) == FALSE)
-    abort();
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/tty.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/tty.cpp
deleted file mode 100644
index e4d7ac9..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/tty.cpp
+++ /dev/null
@@ -1,2335 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#define _CRT_NONSTDC_NO_WARNINGS
-
-#include <assert.h>
-#include <io.h>
-#include <string.h>
-#include <stdlib.h>
-
-#if defined(_MSC_VER) && _MSC_VER < 1600
-# include "uv/stdint-msvc2008.h"
-#else
-# include <stdint.h>
-#endif
-
-#ifndef COMMON_LVB_REVERSE_VIDEO
-# define COMMON_LVB_REVERSE_VIDEO 0x4000
-#endif
-
-#include "uv.h"
-#include "internal.h"
-#include "handle-inl.h"
-#include "stream-inl.h"
-#include "req-inl.h"
-
-#pragma comment(lib, "User32.lib")
-
-#ifndef InterlockedOr
-# define InterlockedOr _InterlockedOr
-#endif
-
-#define UNICODE_REPLACEMENT_CHARACTER (0xfffd)
-
-#define ANSI_NORMAL           0x00
-#define ANSI_ESCAPE_SEEN      0x02
-#define ANSI_CSI              0x04
-#define ANSI_ST_CONTROL       0x08
-#define ANSI_IGNORE           0x10
-#define ANSI_IN_ARG           0x20
-#define ANSI_IN_STRING        0x40
-#define ANSI_BACKSLASH_SEEN   0x80
-
-#define MAX_INPUT_BUFFER_LENGTH 8192
-#define MAX_CONSOLE_CHAR 8192
-
-#ifndef ENABLE_VIRTUAL_TERMINAL_PROCESSING
-#define ENABLE_VIRTUAL_TERMINAL_PROCESSING 0x0004
-#endif
-
-static void uv_tty_capture_initial_style(CONSOLE_SCREEN_BUFFER_INFO* info);
-static void uv_tty_update_virtual_window(CONSOLE_SCREEN_BUFFER_INFO* info);
-static int uv__cancel_read_console(uv_tty_t* handle);
-
-
-/* Null uv_buf_t */
-static const uv_buf_t uv_null_buf_ = { 0, NULL };
-
-enum uv__read_console_status_e {
-  NOT_STARTED,
-  IN_PROGRESS,
-  TRAP_REQUESTED,
-  COMPLETED
-};
-
-static volatile LONG uv__read_console_status = NOT_STARTED;
-static volatile LONG uv__restore_screen_state;
-static CONSOLE_SCREEN_BUFFER_INFO uv__saved_screen_state;
-
-
-/*
- * The console virtual window.
- *
- * Normally cursor movement in windows is relative to the console screen buffer,
- * e.g. the application is allowed to overwrite the 'history'. This is very
- * inconvenient, it makes absolute cursor movement pretty useless. There is
- * also the concept of 'client rect' which is defined by the actual size of
- * the console window and the scroll position of the screen buffer, but it's
- * very volatile because it changes when the user scrolls.
- *
- * To make cursor movement behave sensibly we define a virtual window to which
- * cursor movement is confined. The virtual window is always as wide as the
- * console screen buffer, but it's height is defined by the size of the
- * console window. The top of the virtual window aligns with the position
- * of the caret when the first stdout/err handle is created, unless that would
- * mean that it would extend beyond the bottom of the screen buffer -  in that
- * that case it's located as far down as possible.
- *
- * When the user writes a long text or many newlines, such that the output
- * reaches beyond the bottom of the virtual window, the virtual window is
- * shifted downwards, but not resized.
- *
- * Since all tty i/o happens on the same console, this window is shared
- * between all stdout/stderr handles.
- */
-
-static int uv_tty_virtual_offset = -1;
-static int uv_tty_virtual_height = -1;
-static int uv_tty_virtual_width = -1;
-
-/* The console window size
- * We keep this separate from uv_tty_virtual_*. We use those values to only
- * handle signalling SIGWINCH
- */
-
-static HANDLE uv__tty_console_handle = INVALID_HANDLE_VALUE;
-static int uv__tty_console_height = -1;
-static int uv__tty_console_width = -1;
-
-static DWORD WINAPI uv__tty_console_resize_message_loop_thread(void* param);
-static void CALLBACK uv__tty_console_resize_event(HWINEVENTHOOK hWinEventHook,
-                                                  DWORD event,
-                                                  HWND hwnd,
-                                                  LONG idObject,
-                                                  LONG idChild,
-                                                  DWORD dwEventThread,
-                                                  DWORD dwmsEventTime);
-
-/* We use a semaphore rather than a mutex or critical section because in some
-   cases (uv__cancel_read_console) we need take the lock in the main thread and
-   release it in another thread. Using a semaphore ensures that in such
-   scenario the main thread will still block when trying to acquire the lock. */
-static uv_sem_t uv_tty_output_lock;
-
-static WORD uv_tty_default_text_attributes =
-    FOREGROUND_RED | FOREGROUND_GREEN | FOREGROUND_BLUE;
-
-static char uv_tty_default_fg_color = 7;
-static char uv_tty_default_bg_color = 0;
-static char uv_tty_default_fg_bright = 0;
-static char uv_tty_default_bg_bright = 0;
-static char uv_tty_default_inverse = 0;
-
-typedef enum {
-  UV_SUPPORTED,
-  UV_UNCHECKED,
-  UV_UNSUPPORTED
-} uv_vtermstate_t;
-/* Determine whether or not ANSI support is enabled. */
-static uv_vtermstate_t uv__vterm_state = UV_UNCHECKED;
-static void uv__determine_vterm_state(HANDLE handle);
-
-void uv_console_init(void) {
-  if (uv_sem_init(&uv_tty_output_lock, 1))
-    abort();
-  uv__tty_console_handle = CreateFileW(L"CONOUT$",
-                                       GENERIC_READ | GENERIC_WRITE,
-                                       FILE_SHARE_WRITE,
-                                       0,
-                                       OPEN_EXISTING,
-                                       0,
-                                       0);
-  if (uv__tty_console_handle != INVALID_HANDLE_VALUE) {
-    QueueUserWorkItem(uv__tty_console_resize_message_loop_thread,
-                      NULL,
-                      WT_EXECUTELONGFUNCTION);
-  }
-}
-
-
-int uv_tty_init(uv_loop_t* loop, uv_tty_t* tty, uv_file fd, int unused) {
-  BOOL readable;
-  DWORD NumberOfEvents;
-  HANDLE handle;
-  CONSOLE_SCREEN_BUFFER_INFO screen_buffer_info;
-  (void)unused;
-
-  uv__once_init();
-  handle = (HANDLE) uv__get_osfhandle(fd);
-  if (handle == INVALID_HANDLE_VALUE)
-    return UV_EBADF;
-
-  if (fd <= 2) {
-    /* In order to avoid closing a stdio file descriptor 0-2, duplicate the
-     * underlying OS handle and forget about the original fd.
-     * We could also opt to use the original OS handle and just never close it,
-     * but then there would be no reliable way to cancel pending read operations
-     * upon close.
-     */
-    if (!DuplicateHandle(INVALID_HANDLE_VALUE,
-                         handle,
-                         INVALID_HANDLE_VALUE,
-                         &handle,
-                         0,
-                         FALSE,
-                         DUPLICATE_SAME_ACCESS))
-      return uv_translate_sys_error(GetLastError());
-    fd = -1;
-  }
-
-  readable = GetNumberOfConsoleInputEvents(handle, &NumberOfEvents);
-  if (!readable) {
-    /* Obtain the screen buffer info with the output handle. */
-    if (!GetConsoleScreenBufferInfo(handle, &screen_buffer_info)) {
-      return uv_translate_sys_error(GetLastError());
-    }
-
-    /* Obtain the tty_output_lock because the virtual window state is shared
-     * between all uv_tty_t handles. */
-    uv_sem_wait(&uv_tty_output_lock);
-
-    if (uv__vterm_state == UV_UNCHECKED)
-      uv__determine_vterm_state(handle);
-
-    /* Remember the original console text attributes. */
-    uv_tty_capture_initial_style(&screen_buffer_info);
-
-    uv_tty_update_virtual_window(&screen_buffer_info);
-
-    uv_sem_post(&uv_tty_output_lock);
-  }
-
-
-  uv_stream_init(loop, (uv_stream_t*) tty, UV_TTY);
-  uv_connection_init((uv_stream_t*) tty);
-
-  tty->handle = handle;
-  tty->u.fd = fd;
-  tty->reqs_pending = 0;
-  tty->flags |= UV_HANDLE_BOUND;
-
-  if (readable) {
-    /* Initialize TTY input specific fields. */
-    tty->flags |= UV_HANDLE_TTY_READABLE | UV_HANDLE_READABLE;
-    /* TODO: remove me in v2.x. */
-    tty->tty.rd.unused_ = NULL;
-    tty->tty.rd.read_line_buffer = uv_null_buf_;
-    tty->tty.rd.read_raw_wait = NULL;
-
-    /* Init keycode-to-vt100 mapper state. */
-    tty->tty.rd.last_key_len = 0;
-    tty->tty.rd.last_key_offset = 0;
-    tty->tty.rd.last_utf16_high_surrogate = 0;
-    memset(&tty->tty.rd.last_input_record, 0, sizeof tty->tty.rd.last_input_record);
-  } else {
-    /* TTY output specific fields. */
-    tty->flags |= UV_HANDLE_WRITABLE;
-
-    /* Init utf8-to-utf16 conversion state. */
-    tty->tty.wr.utf8_bytes_left = 0;
-    tty->tty.wr.utf8_codepoint = 0;
-
-    /* Initialize eol conversion state */
-    tty->tty.wr.previous_eol = 0;
-
-    /* Init ANSI parser state. */
-    tty->tty.wr.ansi_parser_state = ANSI_NORMAL;
-  }
-
-  return 0;
-}
-
-
-/* Set the default console text attributes based on how the console was
- * configured when libuv started.
- */
-static void uv_tty_capture_initial_style(CONSOLE_SCREEN_BUFFER_INFO* info) {
-  static int style_captured = 0;
-
-  /* Only do this once.
-     Assumption: Caller has acquired uv_tty_output_lock. */
-  if (style_captured)
-    return;
-
-  /* Save raw win32 attributes. */
-  uv_tty_default_text_attributes = info->wAttributes;
-
-  /* Convert black text on black background to use white text. */
-  if (uv_tty_default_text_attributes == 0)
-    uv_tty_default_text_attributes = 7;
-
-  /* Convert Win32 attributes to ANSI colors. */
-  uv_tty_default_fg_color = 0;
-  uv_tty_default_bg_color = 0;
-  uv_tty_default_fg_bright = 0;
-  uv_tty_default_bg_bright = 0;
-  uv_tty_default_inverse = 0;
-
-  if (uv_tty_default_text_attributes & FOREGROUND_RED)
-    uv_tty_default_fg_color |= 1;
-
-  if (uv_tty_default_text_attributes & FOREGROUND_GREEN)
-    uv_tty_default_fg_color |= 2;
-
-  if (uv_tty_default_text_attributes & FOREGROUND_BLUE)
-    uv_tty_default_fg_color |= 4;
-
-  if (uv_tty_default_text_attributes & BACKGROUND_RED)
-    uv_tty_default_bg_color |= 1;
-
-  if (uv_tty_default_text_attributes & BACKGROUND_GREEN)
-    uv_tty_default_bg_color |= 2;
-
-  if (uv_tty_default_text_attributes & BACKGROUND_BLUE)
-    uv_tty_default_bg_color |= 4;
-
-  if (uv_tty_default_text_attributes & FOREGROUND_INTENSITY)
-    uv_tty_default_fg_bright = 1;
-
-  if (uv_tty_default_text_attributes & BACKGROUND_INTENSITY)
-    uv_tty_default_bg_bright = 1;
-
-  if (uv_tty_default_text_attributes & COMMON_LVB_REVERSE_VIDEO)
-    uv_tty_default_inverse = 1;
-
-  style_captured = 1;
-}
-
-
-int uv_tty_set_mode(uv_tty_t* tty, uv_tty_mode_t mode) {
-  DWORD flags;
-  unsigned char was_reading;
-  uv_alloc_cb alloc_cb;
-  uv_read_cb read_cb;
-  int err;
-
-  if (!(tty->flags & UV_HANDLE_TTY_READABLE)) {
-    return UV_EINVAL;
-  }
-
-  if (!!mode == !!(tty->flags & UV_HANDLE_TTY_RAW)) {
-    return 0;
-  }
-
-  switch (mode) {
-    case UV_TTY_MODE_NORMAL:
-      flags = ENABLE_ECHO_INPUT | ENABLE_LINE_INPUT | ENABLE_PROCESSED_INPUT;
-      break;
-    case UV_TTY_MODE_RAW:
-      flags = ENABLE_WINDOW_INPUT;
-      break;
-    case UV_TTY_MODE_IO:
-      return UV_ENOTSUP;
-    default:
-      return UV_EINVAL;
-  }
-
-  /* If currently reading, stop, and restart reading. */
-  if (tty->flags & UV_HANDLE_READING) {
-    was_reading = 1;
-    alloc_cb = tty->alloc_cb;
-    read_cb = tty->read_cb;
-    err = uv_tty_read_stop(tty);
-    if (err) {
-      return uv_translate_sys_error(err);
-    }
-  } else {
-    was_reading = 0;
-    alloc_cb = NULL;
-    read_cb = NULL;
-  }
-
-  uv_sem_wait(&uv_tty_output_lock);
-  if (!SetConsoleMode(tty->handle, flags)) {
-    err = uv_translate_sys_error(GetLastError());
-    uv_sem_post(&uv_tty_output_lock);
-    return err;
-  }
-  uv_sem_post(&uv_tty_output_lock);
-
-  /* Update flag. */
-  tty->flags &= ~UV_HANDLE_TTY_RAW;
-  tty->flags |= mode ? UV_HANDLE_TTY_RAW : 0;
-
-  /* If we just stopped reading, restart. */
-  if (was_reading) {
-    err = uv_tty_read_start(tty, alloc_cb, read_cb);
-    if (err) {
-      return uv_translate_sys_error(err);
-    }
-  }
-
-  return 0;
-}
-
-
-int uv_tty_get_winsize(uv_tty_t* tty, int* width, int* height) {
-  CONSOLE_SCREEN_BUFFER_INFO info;
-
-  if (!GetConsoleScreenBufferInfo(tty->handle, &info)) {
-    return uv_translate_sys_error(GetLastError());
-  }
-
-  uv_sem_wait(&uv_tty_output_lock);
-  uv_tty_update_virtual_window(&info);
-  uv_sem_post(&uv_tty_output_lock);
-
-  *width = uv_tty_virtual_width;
-  *height = uv_tty_virtual_height;
-
-  return 0;
-}
-
-
-static void CALLBACK uv_tty_post_raw_read(void* data, BOOLEAN didTimeout) {
-  uv_loop_t* loop;
-  uv_tty_t* handle;
-  uv_req_t* req;
-
-  assert(data);
-  assert(!didTimeout);
-
-  req = (uv_req_t*) data;
-  handle = (uv_tty_t*) req->data;
-  loop = handle->loop;
-
-  UnregisterWait(handle->tty.rd.read_raw_wait);
-  handle->tty.rd.read_raw_wait = NULL;
-
-  SET_REQ_SUCCESS(req);
-  POST_COMPLETION_FOR_REQ(loop, req);
-}
-
-
-static void uv_tty_queue_read_raw(uv_loop_t* loop, uv_tty_t* handle) {
-  uv_read_t* req;
-  BOOL r;
-
-  assert(handle->flags & UV_HANDLE_READING);
-  assert(!(handle->flags & UV_HANDLE_READ_PENDING));
-
-  assert(handle->handle && handle->handle != INVALID_HANDLE_VALUE);
-
-  handle->tty.rd.read_line_buffer = uv_null_buf_;
-
-  req = &handle->read_req;
-  memset(&req->u.io.overlapped, 0, sizeof(req->u.io.overlapped));
-
-  r = RegisterWaitForSingleObject(&handle->tty.rd.read_raw_wait,
-                                  handle->handle,
-                                  uv_tty_post_raw_read,
-                                  (void*) req,
-                                  INFINITE,
-                                  WT_EXECUTEINWAITTHREAD | WT_EXECUTEONLYONCE);
-  if (!r) {
-    handle->tty.rd.read_raw_wait = NULL;
-    SET_REQ_ERROR(req, GetLastError());
-    uv_insert_pending_req(loop, (uv_req_t*)req);
-  }
-
-  handle->flags |= UV_HANDLE_READ_PENDING;
-  handle->reqs_pending++;
-}
-
-
-static DWORD CALLBACK uv_tty_line_read_thread(void* data) {
-  uv_loop_t* loop;
-  uv_tty_t* handle;
-  uv_req_t* req;
-  DWORD bytes, read_bytes;
-  WCHAR utf16[MAX_INPUT_BUFFER_LENGTH / 3];
-  DWORD chars, read_chars;
-  LONG status;
-  COORD pos;
-  BOOL read_console_success;
-
-  assert(data);
-
-  req = (uv_req_t*) data;
-  handle = (uv_tty_t*) req->data;
-  loop = handle->loop;
-
-  assert(handle->tty.rd.read_line_buffer.base != NULL);
-  assert(handle->tty.rd.read_line_buffer.len > 0);
-
-  /* ReadConsole can't handle big buffers. */
-  if (handle->tty.rd.read_line_buffer.len < MAX_INPUT_BUFFER_LENGTH) {
-    bytes = handle->tty.rd.read_line_buffer.len;
-  } else {
-    bytes = MAX_INPUT_BUFFER_LENGTH;
-  }
-
-  /* At last, unicode! One utf-16 codeunit never takes more than 3 utf-8
-   * codeunits to encode. */
-  chars = bytes / 3;
-
-  status = InterlockedExchange(&uv__read_console_status, IN_PROGRESS);
-  if (status == TRAP_REQUESTED) {
-    SET_REQ_SUCCESS(req);
-    req->u.io.overlapped.InternalHigh = 0;
-    POST_COMPLETION_FOR_REQ(loop, req);
-    return 0;
-  }
-
-  read_console_success = ReadConsoleW(handle->handle,
-                                      (void*) utf16,
-                                      chars,
-                                      &read_chars,
-                                      NULL);
-
-  if (read_console_success) {
-    read_bytes = WideCharToMultiByte(CP_UTF8,
-                                     0,
-                                     utf16,
-                                     read_chars,
-                                     handle->tty.rd.read_line_buffer.base,
-                                     bytes,
-                                     NULL,
-                                     NULL);
-    SET_REQ_SUCCESS(req);
-    req->u.io.overlapped.InternalHigh = read_bytes;
-  } else {
-    SET_REQ_ERROR(req, GetLastError());
-  }
-
-  status = InterlockedExchange(&uv__read_console_status, COMPLETED);
-
-  if (status ==  TRAP_REQUESTED) {
-    /* If we canceled the read by sending a VK_RETURN event, restore the
-       screen state to undo the visual effect of the VK_RETURN */
-    if (read_console_success && InterlockedOr(&uv__restore_screen_state, 0)) {
-      HANDLE active_screen_buffer;
-      active_screen_buffer = CreateFileA("conout$",
-                                         GENERIC_READ | GENERIC_WRITE,
-                                         FILE_SHARE_READ | FILE_SHARE_WRITE,
-                                         NULL,
-                                         OPEN_EXISTING,
-                                         FILE_ATTRIBUTE_NORMAL,
-                                         NULL);
-      if (active_screen_buffer != INVALID_HANDLE_VALUE) {
-        pos = uv__saved_screen_state.dwCursorPosition;
-
-        /* If the cursor was at the bottom line of the screen buffer, the
-           VK_RETURN would have caused the buffer contents to scroll up by one
-           line. The right position to reset the cursor to is therefore one line
-           higher */
-        if (pos.Y == uv__saved_screen_state.dwSize.Y - 1)
-          pos.Y--;
-
-        SetConsoleCursorPosition(active_screen_buffer, pos);
-        CloseHandle(active_screen_buffer);
-      }
-    }
-    uv_sem_post(&uv_tty_output_lock);
-  }
-  POST_COMPLETION_FOR_REQ(loop, req);
-  return 0;
-}
-
-
-static void uv_tty_queue_read_line(uv_loop_t* loop, uv_tty_t* handle) {
-  uv_read_t* req;
-  BOOL r;
-
-  assert(handle->flags & UV_HANDLE_READING);
-  assert(!(handle->flags & UV_HANDLE_READ_PENDING));
-  assert(handle->handle && handle->handle != INVALID_HANDLE_VALUE);
-
-  req = &handle->read_req;
-  memset(&req->u.io.overlapped, 0, sizeof(req->u.io.overlapped));
-
-  handle->tty.rd.read_line_buffer = uv_buf_init(NULL, 0);
-  handle->alloc_cb((uv_handle_t*) handle, 8192, &handle->tty.rd.read_line_buffer);
-  if (handle->tty.rd.read_line_buffer.base == NULL ||
-      handle->tty.rd.read_line_buffer.len == 0) {
-    handle->read_cb((uv_stream_t*) handle,
-                    UV_ENOBUFS,
-                    &handle->tty.rd.read_line_buffer);
-    return;
-  }
-  assert(handle->tty.rd.read_line_buffer.base != NULL);
-
-  /* Reset flags  No locking is required since there cannot be a line read
-     in progress. We are also relying on the memory barrier provided by
-     QueueUserWorkItem*/
-  uv__restore_screen_state = FALSE;
-  uv__read_console_status = NOT_STARTED;
-  r = QueueUserWorkItem(uv_tty_line_read_thread,
-                        (void*) req,
-                        WT_EXECUTELONGFUNCTION);
-  if (!r) {
-    SET_REQ_ERROR(req, GetLastError());
-    uv_insert_pending_req(loop, (uv_req_t*)req);
-  }
-
-  handle->flags |= UV_HANDLE_READ_PENDING;
-  handle->reqs_pending++;
-}
-
-
-static void uv_tty_queue_read(uv_loop_t* loop, uv_tty_t* handle) {
-  if (handle->flags & UV_HANDLE_TTY_RAW) {
-    uv_tty_queue_read_raw(loop, handle);
-  } else {
-    uv_tty_queue_read_line(loop, handle);
-  }
-}
-
-
-static const char* get_vt100_fn_key(DWORD code, char shift, char ctrl,
-    size_t* len) {
-#define VK_CASE(vk, normal_str, shift_str, ctrl_str, shift_ctrl_str)          \
-    case (vk):                                                                \
-      if (shift && ctrl) {                                                    \
-        *len = sizeof shift_ctrl_str;                                         \
-        return "\033" shift_ctrl_str;                                         \
-      } else if (shift) {                                                     \
-        *len = sizeof shift_str ;                                             \
-        return "\033" shift_str;                                              \
-      } else if (ctrl) {                                                      \
-        *len = sizeof ctrl_str;                                               \
-        return "\033" ctrl_str;                                               \
-      } else {                                                                \
-        *len = sizeof normal_str;                                             \
-        return "\033" normal_str;                                             \
-      }
-
-  switch (code) {
-    /* These mappings are the same as Cygwin's. Unmodified and alt-modified
-     * keypad keys comply with linux console, modifiers comply with xterm
-     * modifier usage. F1. f12 and shift-f1. f10 comply with linux console, f6.
-     * f12 with and without modifiers comply with rxvt. */
-    VK_CASE(VK_INSERT,  "[2~",  "[2;2~", "[2;5~", "[2;6~")
-    VK_CASE(VK_END,     "[4~",  "[4;2~", "[4;5~", "[4;6~")
-    VK_CASE(VK_DOWN,    "[B",   "[1;2B", "[1;5B", "[1;6B")
-    VK_CASE(VK_NEXT,    "[6~",  "[6;2~", "[6;5~", "[6;6~")
-    VK_CASE(VK_LEFT,    "[D",   "[1;2D", "[1;5D", "[1;6D")
-    VK_CASE(VK_CLEAR,   "[G",   "[1;2G", "[1;5G", "[1;6G")
-    VK_CASE(VK_RIGHT,   "[C",   "[1;2C", "[1;5C", "[1;6C")
-    VK_CASE(VK_UP,      "[A",   "[1;2A", "[1;5A", "[1;6A")
-    VK_CASE(VK_HOME,    "[1~",  "[1;2~", "[1;5~", "[1;6~")
-    VK_CASE(VK_PRIOR,   "[5~",  "[5;2~", "[5;5~", "[5;6~")
-    VK_CASE(VK_DELETE,  "[3~",  "[3;2~", "[3;5~", "[3;6~")
-    VK_CASE(VK_NUMPAD0, "[2~",  "[2;2~", "[2;5~", "[2;6~")
-    VK_CASE(VK_NUMPAD1, "[4~",  "[4;2~", "[4;5~", "[4;6~")
-    VK_CASE(VK_NUMPAD2, "[B",   "[1;2B", "[1;5B", "[1;6B")
-    VK_CASE(VK_NUMPAD3, "[6~",  "[6;2~", "[6;5~", "[6;6~")
-    VK_CASE(VK_NUMPAD4, "[D",   "[1;2D", "[1;5D", "[1;6D")
-    VK_CASE(VK_NUMPAD5, "[G",   "[1;2G", "[1;5G", "[1;6G")
-    VK_CASE(VK_NUMPAD6, "[C",   "[1;2C", "[1;5C", "[1;6C")
-    VK_CASE(VK_NUMPAD7, "[A",   "[1;2A", "[1;5A", "[1;6A")
-    VK_CASE(VK_NUMPAD8, "[1~",  "[1;2~", "[1;5~", "[1;6~")
-    VK_CASE(VK_NUMPAD9, "[5~",  "[5;2~", "[5;5~", "[5;6~")
-    VK_CASE(VK_DECIMAL, "[3~",  "[3;2~", "[3;5~", "[3;6~")
-    VK_CASE(VK_F1,      "[[A",  "[23~",  "[11^",  "[23^" )
-    VK_CASE(VK_F2,      "[[B",  "[24~",  "[12^",  "[24^" )
-    VK_CASE(VK_F3,      "[[C",  "[25~",  "[13^",  "[25^" )
-    VK_CASE(VK_F4,      "[[D",  "[26~",  "[14^",  "[26^" )
-    VK_CASE(VK_F5,      "[[E",  "[28~",  "[15^",  "[28^" )
-    VK_CASE(VK_F6,      "[17~", "[29~",  "[17^",  "[29^" )
-    VK_CASE(VK_F7,      "[18~", "[31~",  "[18^",  "[31^" )
-    VK_CASE(VK_F8,      "[19~", "[32~",  "[19^",  "[32^" )
-    VK_CASE(VK_F9,      "[20~", "[33~",  "[20^",  "[33^" )
-    VK_CASE(VK_F10,     "[21~", "[34~",  "[21^",  "[34^" )
-    VK_CASE(VK_F11,     "[23~", "[23$",  "[23^",  "[23@" )
-    VK_CASE(VK_F12,     "[24~", "[24$",  "[24^",  "[24@" )
-
-    default:
-      *len = 0;
-      return NULL;
-  }
-#undef VK_CASE
-}
-
-
-void uv_process_tty_read_raw_req(uv_loop_t* loop, uv_tty_t* handle,
-    uv_req_t* req) {
-  /* Shortcut for handle->tty.rd.last_input_record.Event.KeyEvent. */
-#define KEV handle->tty.rd.last_input_record.Event.KeyEvent
-
-  DWORD records_left, records_read;
-  uv_buf_t buf;
-  off_t buf_used;
-
-  assert(handle->type == UV_TTY);
-  assert(handle->flags & UV_HANDLE_TTY_READABLE);
-  handle->flags &= ~UV_HANDLE_READ_PENDING;
-
-  if (!(handle->flags & UV_HANDLE_READING) ||
-      !(handle->flags & UV_HANDLE_TTY_RAW)) {
-    goto out;
-  }
-
-  if (!REQ_SUCCESS(req)) {
-    /* An error occurred while waiting for the event. */
-    if ((handle->flags & UV_HANDLE_READING)) {
-      handle->flags &= ~UV_HANDLE_READING;
-      handle->read_cb((uv_stream_t*)handle,
-                      uv_translate_sys_error(GET_REQ_ERROR(req)),
-                      &uv_null_buf_);
-    }
-    goto out;
-  }
-
-  /* Fetch the number of events  */
-  if (!GetNumberOfConsoleInputEvents(handle->handle, &records_left)) {
-    handle->flags &= ~UV_HANDLE_READING;
-    DECREASE_ACTIVE_COUNT(loop, handle);
-    handle->read_cb((uv_stream_t*)handle,
-                    uv_translate_sys_error(GetLastError()),
-                    &uv_null_buf_);
-    goto out;
-  }
-
-  /* Windows sends a lot of events that we're not interested in, so buf will be
-   * allocated on demand, when there's actually something to emit. */
-  buf = uv_null_buf_;
-  buf_used = 0;
-
-  while ((records_left > 0 || handle->tty.rd.last_key_len > 0) &&
-         (handle->flags & UV_HANDLE_READING)) {
-    if (handle->tty.rd.last_key_len == 0) {
-      /* Read the next input record */
-      if (!ReadConsoleInputW(handle->handle,
-                             &handle->tty.rd.last_input_record,
-                             1,
-                             &records_read)) {
-        handle->flags &= ~UV_HANDLE_READING;
-        DECREASE_ACTIVE_COUNT(loop, handle);
-        handle->read_cb((uv_stream_t*) handle,
-                        uv_translate_sys_error(GetLastError()),
-                        &buf);
-        goto out;
-      }
-      records_left--;
-
-      /* Ignore other events that are not key events. */
-      if (handle->tty.rd.last_input_record.EventType != KEY_EVENT) {
-        continue;
-      }
-
-      /* Ignore keyup events, unless the left alt key was held and a valid
-       * unicode character was emitted. */
-      if (!KEV.bKeyDown &&
-          (KEV.wVirtualKeyCode != VK_MENU ||
-           KEV.uChar.UnicodeChar == 0)) {
-        continue;
-      }
-
-      /* Ignore keypresses to numpad number keys if the left alt is held
-       * because the user is composing a character, or windows simulating this.
-       */
-      if ((KEV.dwControlKeyState & LEFT_ALT_PRESSED) &&
-          !(KEV.dwControlKeyState & ENHANCED_KEY) &&
-          (KEV.wVirtualKeyCode == VK_INSERT ||
-          KEV.wVirtualKeyCode == VK_END ||
-          KEV.wVirtualKeyCode == VK_DOWN ||
-          KEV.wVirtualKeyCode == VK_NEXT ||
-          KEV.wVirtualKeyCode == VK_LEFT ||
-          KEV.wVirtualKeyCode == VK_CLEAR ||
-          KEV.wVirtualKeyCode == VK_RIGHT ||
-          KEV.wVirtualKeyCode == VK_HOME ||
-          KEV.wVirtualKeyCode == VK_UP ||
-          KEV.wVirtualKeyCode == VK_PRIOR ||
-          KEV.wVirtualKeyCode == VK_NUMPAD0 ||
-          KEV.wVirtualKeyCode == VK_NUMPAD1 ||
-          KEV.wVirtualKeyCode == VK_NUMPAD2 ||
-          KEV.wVirtualKeyCode == VK_NUMPAD3 ||
-          KEV.wVirtualKeyCode == VK_NUMPAD4 ||
-          KEV.wVirtualKeyCode == VK_NUMPAD5 ||
-          KEV.wVirtualKeyCode == VK_NUMPAD6 ||
-          KEV.wVirtualKeyCode == VK_NUMPAD7 ||
-          KEV.wVirtualKeyCode == VK_NUMPAD8 ||
-          KEV.wVirtualKeyCode == VK_NUMPAD9)) {
-        continue;
-      }
-
-      if (KEV.uChar.UnicodeChar != 0) {
-        int prefix_len, char_len;
-
-        /* Character key pressed */
-        if (KEV.uChar.UnicodeChar >= 0xD800 &&
-            KEV.uChar.UnicodeChar < 0xDC00) {
-          /* UTF-16 high surrogate */
-          handle->tty.rd.last_utf16_high_surrogate = KEV.uChar.UnicodeChar;
-          continue;
-        }
-
-        /* Prefix with \u033 if alt was held, but alt was not used as part a
-         * compose sequence. */
-        if ((KEV.dwControlKeyState & (LEFT_ALT_PRESSED | RIGHT_ALT_PRESSED))
-            && !(KEV.dwControlKeyState & (LEFT_CTRL_PRESSED |
-            RIGHT_CTRL_PRESSED)) && KEV.bKeyDown) {
-          handle->tty.rd.last_key[0] = '\033';
-          prefix_len = 1;
-        } else {
-          prefix_len = 0;
-        }
-
-        if (KEV.uChar.UnicodeChar >= 0xDC00 &&
-            KEV.uChar.UnicodeChar < 0xE000) {
-          /* UTF-16 surrogate pair */
-          WCHAR utf16_buffer[2];
-          utf16_buffer[0] = handle->tty.rd.last_utf16_high_surrogate;
-          utf16_buffer[1] = KEV.uChar.UnicodeChar;
-          char_len = WideCharToMultiByte(CP_UTF8,
-                                         0,
-                                         utf16_buffer,
-                                         2,
-                                         &handle->tty.rd.last_key[prefix_len],
-                                         sizeof handle->tty.rd.last_key,
-                                         NULL,
-                                         NULL);
-        } else {
-          /* Single UTF-16 character */
-          char_len = WideCharToMultiByte(CP_UTF8,
-                                         0,
-                                         &KEV.uChar.UnicodeChar,
-                                         1,
-                                         &handle->tty.rd.last_key[prefix_len],
-                                         sizeof handle->tty.rd.last_key,
-                                         NULL,
-                                         NULL);
-        }
-
-        /* Whatever happened, the last character wasn't a high surrogate. */
-        handle->tty.rd.last_utf16_high_surrogate = 0;
-
-        /* If the utf16 character(s) couldn't be converted something must be
-         * wrong. */
-        if (!char_len) {
-          handle->flags &= ~UV_HANDLE_READING;
-          DECREASE_ACTIVE_COUNT(loop, handle);
-          handle->read_cb((uv_stream_t*) handle,
-                          uv_translate_sys_error(GetLastError()),
-                          &buf);
-          goto out;
-        }
-
-        handle->tty.rd.last_key_len = (unsigned char) (prefix_len + char_len);
-        handle->tty.rd.last_key_offset = 0;
-        continue;
-
-      } else {
-        /* Function key pressed */
-        const char* vt100;
-        size_t prefix_len, vt100_len;
-
-        vt100 = get_vt100_fn_key(KEV.wVirtualKeyCode,
-                                  !!(KEV.dwControlKeyState & SHIFT_PRESSED),
-                                  !!(KEV.dwControlKeyState & (
-                                    LEFT_CTRL_PRESSED |
-                                    RIGHT_CTRL_PRESSED)),
-                                  &vt100_len);
-
-        /* If we were unable to map to a vt100 sequence, just ignore. */
-        if (!vt100) {
-          continue;
-        }
-
-        /* Prefix with \x033 when the alt key was held. */
-        if (KEV.dwControlKeyState & (LEFT_ALT_PRESSED | RIGHT_ALT_PRESSED)) {
-          handle->tty.rd.last_key[0] = '\033';
-          prefix_len = 1;
-        } else {
-          prefix_len = 0;
-        }
-
-        /* Copy the vt100 sequence to the handle buffer. */
-        assert(prefix_len + vt100_len < sizeof handle->tty.rd.last_key);
-        memcpy(&handle->tty.rd.last_key[prefix_len], vt100, vt100_len);
-
-        handle->tty.rd.last_key_len = (unsigned char) (prefix_len + vt100_len);
-        handle->tty.rd.last_key_offset = 0;
-        continue;
-      }
-    } else {
-      /* Copy any bytes left from the last keypress to the user buffer. */
-      if (handle->tty.rd.last_key_offset < handle->tty.rd.last_key_len) {
-        /* Allocate a buffer if needed */
-        if (buf_used == 0) {
-          buf = uv_buf_init(NULL, 0);
-          handle->alloc_cb((uv_handle_t*) handle, 1024, &buf);
-          if (buf.base == NULL || buf.len == 0) {
-            handle->read_cb((uv_stream_t*) handle, UV_ENOBUFS, &buf);
-            goto out;
-          }
-          assert(buf.base != NULL);
-        }
-
-        buf.base[buf_used++] = handle->tty.rd.last_key[handle->tty.rd.last_key_offset++];
-
-        /* If the buffer is full, emit it */
-        if ((size_t) buf_used == buf.len) {
-          handle->read_cb((uv_stream_t*) handle, buf_used, &buf);
-          buf = uv_null_buf_;
-          buf_used = 0;
-        }
-
-        continue;
-      }
-
-      /* Apply dwRepeat from the last input record. */
-      if (--KEV.wRepeatCount > 0) {
-        handle->tty.rd.last_key_offset = 0;
-        continue;
-      }
-
-      handle->tty.rd.last_key_len = 0;
-      continue;
-    }
-  }
-
-  /* Send the buffer back to the user */
-  if (buf_used > 0) {
-    handle->read_cb((uv_stream_t*) handle, buf_used, &buf);
-  }
-
- out:
-  /* Wait for more input events. */
-  if ((handle->flags & UV_HANDLE_READING) &&
-      !(handle->flags & UV_HANDLE_READ_PENDING)) {
-    uv_tty_queue_read(loop, handle);
-  }
-
-  DECREASE_PENDING_REQ_COUNT(handle);
-
-#undef KEV
-}
-
-
-
-void uv_process_tty_read_line_req(uv_loop_t* loop, uv_tty_t* handle,
-    uv_req_t* req) {
-  uv_buf_t buf;
-
-  assert(handle->type == UV_TTY);
-  assert(handle->flags & UV_HANDLE_TTY_READABLE);
-
-  buf = handle->tty.rd.read_line_buffer;
-
-  handle->flags &= ~UV_HANDLE_READ_PENDING;
-  handle->tty.rd.read_line_buffer = uv_null_buf_;
-
-  if (!REQ_SUCCESS(req)) {
-    /* Read was not successful */
-    if (handle->flags & UV_HANDLE_READING) {
-      /* Real error */
-      handle->flags &= ~UV_HANDLE_READING;
-      DECREASE_ACTIVE_COUNT(loop, handle);
-      handle->read_cb((uv_stream_t*) handle,
-                      uv_translate_sys_error(GET_REQ_ERROR(req)),
-                      &buf);
-    }
-  } else {
-    if (!(handle->flags & UV_HANDLE_CANCELLATION_PENDING) &&
-        req->u.io.overlapped.InternalHigh != 0) {
-      /* Read successful. TODO: read unicode, convert to utf-8 */
-      DWORD bytes = req->u.io.overlapped.InternalHigh;
-      handle->read_cb((uv_stream_t*) handle, bytes, &buf);
-    }
-    handle->flags &= ~UV_HANDLE_CANCELLATION_PENDING;
-  }
-
-  /* Wait for more input events. */
-  if ((handle->flags & UV_HANDLE_READING) &&
-      !(handle->flags & UV_HANDLE_READ_PENDING)) {
-    uv_tty_queue_read(loop, handle);
-  }
-
-  DECREASE_PENDING_REQ_COUNT(handle);
-}
-
-
-void uv_process_tty_read_req(uv_loop_t* loop, uv_tty_t* handle,
-    uv_req_t* req) {
-  assert(handle->type == UV_TTY);
-  assert(handle->flags & UV_HANDLE_TTY_READABLE);
-
-  /* If the read_line_buffer member is zero, it must have been an raw read.
-   * Otherwise it was a line-buffered read. FIXME: This is quite obscure. Use a
-   * flag or something. */
-  if (handle->tty.rd.read_line_buffer.len == 0) {
-    uv_process_tty_read_raw_req(loop, handle, req);
-  } else {
-    uv_process_tty_read_line_req(loop, handle, req);
-  }
-}
-
-
-int uv_tty_read_start(uv_tty_t* handle, uv_alloc_cb alloc_cb,
-    uv_read_cb read_cb) {
-  uv_loop_t* loop = handle->loop;
-
-  if (!(handle->flags & UV_HANDLE_TTY_READABLE)) {
-    return ERROR_INVALID_PARAMETER;
-  }
-
-  handle->flags |= UV_HANDLE_READING;
-  INCREASE_ACTIVE_COUNT(loop, handle);
-  handle->read_cb = read_cb;
-  handle->alloc_cb = alloc_cb;
-
-  /* If reading was stopped and then started again, there could still be a read
-   * request pending. */
-  if (handle->flags & UV_HANDLE_READ_PENDING) {
-    return 0;
-  }
-
-  /* Maybe the user stopped reading half-way while processing key events.
-   * Short-circuit if this could be the case. */
-  if (handle->tty.rd.last_key_len > 0) {
-    SET_REQ_SUCCESS(&handle->read_req);
-    uv_insert_pending_req(handle->loop, (uv_req_t*) &handle->read_req);
-    /* Make sure no attempt is made to insert it again until it's handled. */
-    handle->flags |= UV_HANDLE_READ_PENDING;
-    handle->reqs_pending++;
-    return 0;
-  }
-
-  uv_tty_queue_read(loop, handle);
-
-  return 0;
-}
-
-
-int uv_tty_read_stop(uv_tty_t* handle) {
-  INPUT_RECORD record;
-  DWORD written, err;
-
-  handle->flags &= ~UV_HANDLE_READING;
-  DECREASE_ACTIVE_COUNT(handle->loop, handle);
-
-  if (!(handle->flags & UV_HANDLE_READ_PENDING))
-    return 0;
-
-  if (handle->flags & UV_HANDLE_TTY_RAW) {
-    /* Cancel raw read. Write some bullshit event to force the console wait to
-     * return. */
-    memset(&record, 0, sizeof record);
-    record.EventType = FOCUS_EVENT;
-    if (!WriteConsoleInputW(handle->handle, &record, 1, &written)) {
-      return GetLastError();
-    }
-  } else if (!(handle->flags & UV_HANDLE_CANCELLATION_PENDING)) {
-    /* Cancel line-buffered read if not already pending */
-    err = uv__cancel_read_console(handle);
-    if (err)
-      return err;
-
-    handle->flags |= UV_HANDLE_CANCELLATION_PENDING;
-  }
-
-  return 0;
-}
-
-static int uv__cancel_read_console(uv_tty_t* handle) {
-  HANDLE active_screen_buffer = INVALID_HANDLE_VALUE;
-  INPUT_RECORD record;
-  DWORD written;
-  DWORD err = 0;
-  LONG status;
-
-  assert(!(handle->flags & UV_HANDLE_CANCELLATION_PENDING));
-
-  /* Hold the output lock during the cancellation, to ensure that further
-     writes don't interfere with the screen state. It will be the ReadConsole
-     thread's responsibility to release the lock. */
-  uv_sem_wait(&uv_tty_output_lock);
-  status = InterlockedExchange(&uv__read_console_status, TRAP_REQUESTED);
-  if (status != IN_PROGRESS) {
-    /* Either we have managed to set a trap for the other thread before
-       ReadConsole is called, or ReadConsole has returned because the user
-       has pressed ENTER. In either case, there is nothing else to do. */
-    uv_sem_post(&uv_tty_output_lock);
-    return 0;
-  }
-
-  /* Save screen state before sending the VK_RETURN event */
-  active_screen_buffer = CreateFileA("conout$",
-                                     GENERIC_READ | GENERIC_WRITE,
-                                     FILE_SHARE_READ | FILE_SHARE_WRITE,
-                                     NULL,
-                                     OPEN_EXISTING,
-                                     FILE_ATTRIBUTE_NORMAL,
-                                     NULL);
-
-  if (active_screen_buffer != INVALID_HANDLE_VALUE &&
-      GetConsoleScreenBufferInfo(active_screen_buffer,
-                                 &uv__saved_screen_state)) {
-    InterlockedOr(&uv__restore_screen_state, 1);
-  }
-
-  /* Write enter key event to force the console wait to return. */
-  record.EventType = KEY_EVENT;
-  record.Event.KeyEvent.bKeyDown = TRUE;
-  record.Event.KeyEvent.wRepeatCount = 1;
-  record.Event.KeyEvent.wVirtualKeyCode = VK_RETURN;
-  record.Event.KeyEvent.wVirtualScanCode =
-    MapVirtualKeyW(VK_RETURN, MAPVK_VK_TO_VSC);
-  record.Event.KeyEvent.uChar.UnicodeChar = L'\r';
-  record.Event.KeyEvent.dwControlKeyState = 0;
-  if (!WriteConsoleInputW(handle->handle, &record, 1, &written))
-    err = GetLastError();
-
-  if (active_screen_buffer != INVALID_HANDLE_VALUE)
-    CloseHandle(active_screen_buffer);
-
-  return err;
-}
-
-
-static void uv_tty_update_virtual_window(CONSOLE_SCREEN_BUFFER_INFO* info) {
-  uv_tty_virtual_width = info->dwSize.X;
-  uv_tty_virtual_height = info->srWindow.Bottom - info->srWindow.Top + 1;
-
-  /* Recompute virtual window offset row. */
-  if (uv_tty_virtual_offset == -1) {
-    uv_tty_virtual_offset = info->dwCursorPosition.Y;
-  } else if (uv_tty_virtual_offset < info->dwCursorPosition.Y -
-             uv_tty_virtual_height + 1) {
-    /* If suddenly find the cursor outside of the virtual window, it must have
-     * somehow scrolled. Update the virtual window offset. */
-    uv_tty_virtual_offset = info->dwCursorPosition.Y -
-                            uv_tty_virtual_height + 1;
-  }
-  if (uv_tty_virtual_offset + uv_tty_virtual_height > info->dwSize.Y) {
-    uv_tty_virtual_offset = info->dwSize.Y - uv_tty_virtual_height;
-  }
-  if (uv_tty_virtual_offset < 0) {
-    uv_tty_virtual_offset = 0;
-  }
-}
-
-
-static COORD uv_tty_make_real_coord(uv_tty_t* handle,
-    CONSOLE_SCREEN_BUFFER_INFO* info, int x, unsigned char x_relative, int y,
-    unsigned char y_relative) {
-  COORD result;
-
-  uv_tty_update_virtual_window(info);
-
-  /* Adjust y position */
-  if (y_relative) {
-    y = info->dwCursorPosition.Y + y;
-  } else {
-    y = uv_tty_virtual_offset + y;
-  }
-  /* Clip y to virtual client rectangle */
-  if (y < uv_tty_virtual_offset) {
-    y = uv_tty_virtual_offset;
-  } else if (y >= uv_tty_virtual_offset + uv_tty_virtual_height) {
-    y = uv_tty_virtual_offset + uv_tty_virtual_height - 1;
-  }
-
-  /* Adjust x */
-  if (x_relative) {
-    x = info->dwCursorPosition.X + x;
-  }
-  /* Clip x */
-  if (x < 0) {
-    x = 0;
-  } else if (x >= uv_tty_virtual_width) {
-    x = uv_tty_virtual_width - 1;
-  }
-
-  result.X = (unsigned short) x;
-  result.Y = (unsigned short) y;
-  return result;
-}
-
-
-static int uv_tty_emit_text(uv_tty_t* handle, WCHAR buffer[], DWORD length,
-    DWORD* error) {
-  DWORD written;
-
-  if (*error != ERROR_SUCCESS) {
-    return -1;
-  }
-
-  if (!WriteConsoleW(handle->handle,
-                     (void*) buffer,
-                     length,
-                     &written,
-                     NULL)) {
-    *error = GetLastError();
-    return -1;
-  }
-
-  return 0;
-}
-
-
-static int uv_tty_move_caret(uv_tty_t* handle, int x, unsigned char x_relative,
-    int y, unsigned char y_relative, DWORD* error) {
-  CONSOLE_SCREEN_BUFFER_INFO info;
-  COORD pos;
-
-  if (*error != ERROR_SUCCESS) {
-    return -1;
-  }
-
- retry:
-  if (!GetConsoleScreenBufferInfo(handle->handle, &info)) {
-    *error = GetLastError();
-  }
-
-  pos = uv_tty_make_real_coord(handle, &info, x, x_relative, y, y_relative);
-
-  if (!SetConsoleCursorPosition(handle->handle, pos)) {
-    if (GetLastError() == ERROR_INVALID_PARAMETER) {
-      /* The console may be resized - retry */
-      goto retry;
-    } else {
-      *error = GetLastError();
-      return -1;
-    }
-  }
-
-  return 0;
-}
-
-
-static int uv_tty_reset(uv_tty_t* handle, DWORD* error) {
-  const COORD origin = {0, 0};
-  const WORD char_attrs = uv_tty_default_text_attributes;
-  CONSOLE_SCREEN_BUFFER_INFO info;
-  DWORD count, written;
-
-  if (*error != ERROR_SUCCESS) {
-    return -1;
-  }
-
-  /* Reset original text attributes. */
-  if (!SetConsoleTextAttribute(handle->handle, char_attrs)) {
-    *error = GetLastError();
-    return -1;
-  }
-
-  /* Move the cursor position to (0, 0). */
-  if (!SetConsoleCursorPosition(handle->handle, origin)) {
-    *error = GetLastError();
-    return -1;
-  }
-
-  /* Clear the screen buffer. */
- retry:
-  if (!GetConsoleScreenBufferInfo(handle->handle, &info)) {
-    *error = GetLastError();
-    return -1;
-  }
-
-  count = info.dwSize.X * info.dwSize.Y;
-
-  if (!(FillConsoleOutputCharacterW(handle->handle,
-                                    L'\x20',
-                                    count,
-                                    origin,
-                                    &written) &&
-        FillConsoleOutputAttribute(handle->handle,
-                                   char_attrs,
-                                   written,
-                                   origin,
-                                   &written))) {
-    if (GetLastError() == ERROR_INVALID_PARAMETER) {
-      /* The console may be resized - retry */
-      goto retry;
-    } else {
-      *error = GetLastError();
-      return -1;
-    }
-  }
-
-  /* Move the virtual window up to the top. */
-  uv_tty_virtual_offset = 0;
-  uv_tty_update_virtual_window(&info);
-
-  return 0;
-}
-
-
-static int uv_tty_clear(uv_tty_t* handle, int dir, char entire_screen,
-    DWORD* error) {
-  CONSOLE_SCREEN_BUFFER_INFO info;
-  COORD start, end;
-  DWORD count, written;
-
-  int x1, x2, y1, y2;
-  int x1r, x2r, y1r, y2r;
-
-  if (*error != ERROR_SUCCESS) {
-    return -1;
-  }
-
-  if (dir == 0) {
-    /* Clear from current position */
-    x1 = 0;
-    x1r = 1;
-  } else {
-    /* Clear from column 0 */
-    x1 = 0;
-    x1r = 0;
-  }
-
-  if (dir == 1) {
-    /* Clear to current position */
-    x2 = 0;
-    x2r = 1;
-  } else {
-    /* Clear to end of row. We pretend the console is 65536 characters wide,
-     * uv_tty_make_real_coord will clip it to the actual console width. */
-    x2 = 0xffff;
-    x2r = 0;
-  }
-
-  if (!entire_screen) {
-    /* Stay on our own row */
-    y1 = y2 = 0;
-    y1r = y2r = 1;
-  } else {
-    /* Apply columns direction to row */
-    y1 = x1;
-    y1r = x1r;
-    y2 = x2;
-    y2r = x2r;
-  }
-
- retry:
-  if (!GetConsoleScreenBufferInfo(handle->handle, &info)) {
-    *error = GetLastError();
-    return -1;
-  }
-
-  start = uv_tty_make_real_coord(handle, &info, x1, x1r, y1, y1r);
-  end = uv_tty_make_real_coord(handle, &info, x2, x2r, y2, y2r);
-  count = (end.Y * info.dwSize.X + end.X) -
-          (start.Y * info.dwSize.X + start.X) + 1;
-
-  if (!(FillConsoleOutputCharacterW(handle->handle,
-                              L'\x20',
-                              count,
-                              start,
-                              &written) &&
-        FillConsoleOutputAttribute(handle->handle,
-                                   info.wAttributes,
-                                   written,
-                                   start,
-                                   &written))) {
-    if (GetLastError() == ERROR_INVALID_PARAMETER) {
-      /* The console may be resized - retry */
-      goto retry;
-    } else {
-      *error = GetLastError();
-      return -1;
-    }
-  }
-
-  return 0;
-}
-
-#define FLIP_FGBG                                                             \
-    do {                                                                      \
-      WORD fg = info.wAttributes & 0xF;                                       \
-      WORD bg = info.wAttributes & 0xF0;                                      \
-      info.wAttributes &= 0xFF00;                                             \
-      info.wAttributes |= fg << 4;                                            \
-      info.wAttributes |= bg >> 4;                                            \
-    } while (0)
-
-static int uv_tty_set_style(uv_tty_t* handle, DWORD* error) {
-  unsigned short argc = handle->tty.wr.ansi_csi_argc;
-  unsigned short* argv = handle->tty.wr.ansi_csi_argv;
-  int i;
-  CONSOLE_SCREEN_BUFFER_INFO info;
-
-  char fg_color = -1, bg_color = -1;
-  char fg_bright = -1, bg_bright = -1;
-  char inverse = -1;
-
-  if (argc == 0) {
-    /* Reset mode */
-    fg_color = uv_tty_default_fg_color;
-    bg_color = uv_tty_default_bg_color;
-    fg_bright = uv_tty_default_fg_bright;
-    bg_bright = uv_tty_default_bg_bright;
-    inverse = uv_tty_default_inverse;
-  }
-
-  for (i = 0; i < argc; i++) {
-    short arg = argv[i];
-
-    if (arg == 0) {
-      /* Reset mode */
-      fg_color = uv_tty_default_fg_color;
-      bg_color = uv_tty_default_bg_color;
-      fg_bright = uv_tty_default_fg_bright;
-      bg_bright = uv_tty_default_bg_bright;
-      inverse = uv_tty_default_inverse;
-
-    } else if (arg == 1) {
-      /* Foreground bright on */
-      fg_bright = 1;
-
-    } else if (arg == 2) {
-      /* Both bright off */
-      fg_bright = 0;
-      bg_bright = 0;
-
-    } else if (arg == 5) {
-      /* Background bright on */
-      bg_bright = 1;
-
-    } else if (arg == 7) {
-      /* Inverse: on */
-      inverse = 1;
-
-    } else if (arg == 21 || arg == 22) {
-      /* Foreground bright off */
-      fg_bright = 0;
-
-    } else if (arg == 25) {
-      /* Background bright off */
-      bg_bright = 0;
-
-    } else if (arg == 27) {
-      /* Inverse: off */
-      inverse = 0;
-
-    } else if (arg >= 30 && arg <= 37) {
-      /* Set foreground color */
-      fg_color = arg - 30;
-
-    } else if (arg == 39) {
-      /* Default text color */
-      fg_color = uv_tty_default_fg_color;
-      fg_bright = uv_tty_default_fg_bright;
-
-    } else if (arg >= 40 && arg <= 47) {
-      /* Set background color */
-      bg_color = arg - 40;
-
-    } else if (arg ==  49) {
-      /* Default background color */
-      bg_color = uv_tty_default_bg_color;
-      bg_bright = uv_tty_default_bg_bright;
-
-    } else if (arg >= 90 && arg <= 97) {
-      /* Set bold foreground color */
-      fg_bright = 1;
-      fg_color = arg - 90;
-
-    } else if (arg >= 100 && arg <= 107) {
-      /* Set bold background color */
-      bg_bright = 1;
-      bg_color = arg - 100;
-
-    }
-  }
-
-  if (fg_color == -1 && bg_color == -1 && fg_bright == -1 &&
-      bg_bright == -1 && inverse == -1) {
-    /* Nothing changed */
-    return 0;
-  }
-
-  if (!GetConsoleScreenBufferInfo(handle->handle, &info)) {
-    *error = GetLastError();
-    return -1;
-  }
-
-  if ((info.wAttributes & COMMON_LVB_REVERSE_VIDEO) > 0) {
-    FLIP_FGBG;
-  }
-
-  if (fg_color != -1) {
-    info.wAttributes &= ~(FOREGROUND_RED | FOREGROUND_GREEN | FOREGROUND_BLUE);
-    if (fg_color & 1) info.wAttributes |= FOREGROUND_RED;
-    if (fg_color & 2) info.wAttributes |= FOREGROUND_GREEN;
-    if (fg_color & 4) info.wAttributes |= FOREGROUND_BLUE;
-  }
-
-  if (fg_bright != -1) {
-    if (fg_bright) {
-      info.wAttributes |= FOREGROUND_INTENSITY;
-    } else {
-      info.wAttributes &= ~FOREGROUND_INTENSITY;
-    }
-  }
-
-  if (bg_color != -1) {
-    info.wAttributes &= ~(BACKGROUND_RED | BACKGROUND_GREEN | BACKGROUND_BLUE);
-    if (bg_color & 1) info.wAttributes |= BACKGROUND_RED;
-    if (bg_color & 2) info.wAttributes |= BACKGROUND_GREEN;
-    if (bg_color & 4) info.wAttributes |= BACKGROUND_BLUE;
-  }
-
-  if (bg_bright != -1) {
-    if (bg_bright) {
-      info.wAttributes |= BACKGROUND_INTENSITY;
-    } else {
-      info.wAttributes &= ~BACKGROUND_INTENSITY;
-    }
-  }
-
-  if (inverse != -1) {
-    if (inverse) {
-      info.wAttributes |= COMMON_LVB_REVERSE_VIDEO;
-    } else {
-      info.wAttributes &= ~COMMON_LVB_REVERSE_VIDEO;
-    }
-  }
-
-  if ((info.wAttributes & COMMON_LVB_REVERSE_VIDEO) > 0) {
-    FLIP_FGBG;
-  }
-
-  if (!SetConsoleTextAttribute(handle->handle, info.wAttributes)) {
-    *error = GetLastError();
-    return -1;
-  }
-
-  return 0;
-}
-
-
-static int uv_tty_save_state(uv_tty_t* handle, unsigned char save_attributes,
-    DWORD* error) {
-  CONSOLE_SCREEN_BUFFER_INFO info;
-
-  if (*error != ERROR_SUCCESS) {
-    return -1;
-  }
-
-  if (!GetConsoleScreenBufferInfo(handle->handle, &info)) {
-    *error = GetLastError();
-    return -1;
-  }
-
-  uv_tty_update_virtual_window(&info);
-
-  handle->tty.wr.saved_position.X = info.dwCursorPosition.X;
-  handle->tty.wr.saved_position.Y = info.dwCursorPosition.Y - uv_tty_virtual_offset;
-  handle->flags |= UV_HANDLE_TTY_SAVED_POSITION;
-
-  if (save_attributes) {
-    handle->tty.wr.saved_attributes = info.wAttributes &
-        (FOREGROUND_INTENSITY | BACKGROUND_INTENSITY);
-    handle->flags |= UV_HANDLE_TTY_SAVED_ATTRIBUTES;
-  }
-
-  return 0;
-}
-
-
-static int uv_tty_restore_state(uv_tty_t* handle,
-    unsigned char restore_attributes, DWORD* error) {
-  CONSOLE_SCREEN_BUFFER_INFO info;
-  WORD new_attributes;
-
-  if (*error != ERROR_SUCCESS) {
-    return -1;
-  }
-
-  if (handle->flags & UV_HANDLE_TTY_SAVED_POSITION) {
-    if (uv_tty_move_caret(handle,
-                          handle->tty.wr.saved_position.X,
-                          0,
-                          handle->tty.wr.saved_position.Y,
-                          0,
-                          error) != 0) {
-      return -1;
-    }
-  }
-
-  if (restore_attributes &&
-      (handle->flags & UV_HANDLE_TTY_SAVED_ATTRIBUTES)) {
-    if (!GetConsoleScreenBufferInfo(handle->handle, &info)) {
-      *error = GetLastError();
-      return -1;
-    }
-
-    new_attributes = info.wAttributes;
-    new_attributes &= ~(FOREGROUND_INTENSITY | BACKGROUND_INTENSITY);
-    new_attributes |= handle->tty.wr.saved_attributes;
-
-    if (!SetConsoleTextAttribute(handle->handle, new_attributes)) {
-      *error = GetLastError();
-      return -1;
-    }
-  }
-
-  return 0;
-}
-
-static int uv_tty_set_cursor_visibility(uv_tty_t* handle,
-                                        BOOL visible,
-                                        DWORD* error) {
-  CONSOLE_CURSOR_INFO cursor_info;
-
-  if (!GetConsoleCursorInfo(handle->handle, &cursor_info)) {
-    *error = GetLastError();
-    return -1;
-  }
-
-  cursor_info.bVisible = visible;
-
-  if (!SetConsoleCursorInfo(handle->handle, &cursor_info)) {
-    *error = GetLastError();
-    return -1;
-  }
-
-  return 0;
-}
-
-static int uv_tty_write_bufs(uv_tty_t* handle,
-                             const uv_buf_t bufs[],
-                             unsigned int nbufs,
-                             DWORD* error) {
-  /* We can only write 8k characters at a time. Windows can't handle much more
-   * characters in a single console write anyway. */
-  WCHAR utf16_buf[MAX_CONSOLE_CHAR];
-  WCHAR* utf16_buffer;
-  DWORD utf16_buf_used = 0;
-  unsigned int i, len, max_len, pos;
-  int allocate = 0;
-
-#define FLUSH_TEXT()                                                 \
-  do {                                                               \
-    pos = 0;                                                         \
-    do {                                                             \
-      len = utf16_buf_used - pos;                                    \
-      if (len > MAX_CONSOLE_CHAR)                                    \
-        len = MAX_CONSOLE_CHAR;                                      \
-      uv_tty_emit_text(handle, &utf16_buffer[pos], len, error);      \
-      pos += len;                                                    \
-    } while (pos < utf16_buf_used);                                  \
-    if (allocate) {                                                  \
-      uv__free(utf16_buffer);                                        \
-      allocate = 0;                                                  \
-      utf16_buffer = utf16_buf;                                      \
-    }                                                                \
-    utf16_buf_used = 0;                                              \
- } while (0)
-
-#define ENSURE_BUFFER_SPACE(wchars_needed)                          \
-  if (wchars_needed > ARRAY_SIZE(utf16_buf) - utf16_buf_used) {     \
-    FLUSH_TEXT();                                                   \
-  }
-
-  /* Cache for fast access */
-  unsigned char utf8_bytes_left = handle->tty.wr.utf8_bytes_left;
-  unsigned int utf8_codepoint = handle->tty.wr.utf8_codepoint;
-  unsigned char previous_eol = handle->tty.wr.previous_eol;
-  unsigned char ansi_parser_state = handle->tty.wr.ansi_parser_state;
-
-  /* Store the error here. If we encounter an error, stop trying to do i/o but
-   * keep parsing the buffer so we leave the parser in a consistent state. */
-  *error = ERROR_SUCCESS;
-
-  utf16_buffer = utf16_buf;
-
-  uv_sem_wait(&uv_tty_output_lock);
-
-  for (i = 0; i < nbufs; i++) {
-    uv_buf_t buf = bufs[i];
-    unsigned int j;
-
-    if (uv__vterm_state == UV_SUPPORTED && buf.len > 0) {
-      utf16_buf_used = MultiByteToWideChar(CP_UTF8,
-                                           0,
-                                           buf.base,
-                                           buf.len,
-                                           NULL,
-                                           0);
-
-      if (utf16_buf_used == 0) {
-        *error = GetLastError();
-        break;
-      }
-
-      max_len = (utf16_buf_used + 1) * sizeof(WCHAR);
-      allocate = max_len > MAX_CONSOLE_CHAR;
-      if (allocate)
-        utf16_buffer = (WCHAR*)uv__malloc(max_len);
-      if (!MultiByteToWideChar(CP_UTF8,
-                               0,
-                               buf.base,
-                               buf.len,
-                               utf16_buffer,
-                               utf16_buf_used)) {
-        if (allocate)
-          uv__free(utf16_buffer);
-        *error = GetLastError();
-        break;
-      }
-
-      FLUSH_TEXT();
-
-      continue;
-    }
-
-    for (j = 0; j < buf.len; j++) {
-      unsigned char c = buf.base[j];
-
-      /* Run the character through the utf8 decoder We happily accept non
-       * shortest form encodings and invalid code points - there's no real harm
-       * that can be done. */
-      if (utf8_bytes_left == 0) {
-        /* Read utf-8 start byte */
-        DWORD first_zero_bit;
-        unsigned char not_c = ~c;
-#ifdef _MSC_VER /* msvc */
-        if (_BitScanReverse(&first_zero_bit, not_c)) {
-#else /* assume gcc */
-        if (c != 0) {
-          first_zero_bit = (sizeof(int) * 8) - 1 - __builtin_clz(not_c);
-#endif
-          if (first_zero_bit == 7) {
-            /* Ascii - pass right through */
-            utf8_codepoint = (unsigned int) c;
-
-          } else if (first_zero_bit <= 5) {
-            /* Multibyte sequence */
-            utf8_codepoint = (0xff >> (8 - first_zero_bit)) & c;
-            utf8_bytes_left = (char) (6 - first_zero_bit);
-
-          } else {
-            /* Invalid continuation */
-            utf8_codepoint = UNICODE_REPLACEMENT_CHARACTER;
-          }
-
-        } else {
-          /* 0xff -- invalid */
-          utf8_codepoint = UNICODE_REPLACEMENT_CHARACTER;
-        }
-
-      } else if ((c & 0xc0) == 0x80) {
-        /* Valid continuation of utf-8 multibyte sequence */
-        utf8_bytes_left--;
-        utf8_codepoint <<= 6;
-        utf8_codepoint |= ((unsigned int) c & 0x3f);
-
-      } else {
-        /* Start byte where continuation was expected. */
-        utf8_bytes_left = 0;
-        utf8_codepoint = UNICODE_REPLACEMENT_CHARACTER;
-        /* Patch buf offset so this character will be parsed again as a start
-         * byte. */
-        j--;
-      }
-
-      /* Maybe we need to parse more bytes to find a character. */
-      if (utf8_bytes_left != 0) {
-        continue;
-      }
-
-      /* Parse vt100/ansi escape codes */
-      if (ansi_parser_state == ANSI_NORMAL) {
-        switch (utf8_codepoint) {
-          case '\033':
-            ansi_parser_state = ANSI_ESCAPE_SEEN;
-            continue;
-
-          case 0233:
-            ansi_parser_state = ANSI_CSI;
-            handle->tty.wr.ansi_csi_argc = 0;
-            continue;
-        }
-
-      } else if (ansi_parser_state == ANSI_ESCAPE_SEEN) {
-        switch (utf8_codepoint) {
-          case '[':
-            ansi_parser_state = ANSI_CSI;
-            handle->tty.wr.ansi_csi_argc = 0;
-            continue;
-
-          case '^':
-          case '_':
-          case 'P':
-          case ']':
-            /* Not supported, but we'll have to parse until we see a stop code,
-             * e. g. ESC \ or BEL. */
-            ansi_parser_state = ANSI_ST_CONTROL;
-            continue;
-
-          case '\033':
-            /* Ignore double escape. */
-            continue;
-
-          case 'c':
-            /* Full console reset. */
-            FLUSH_TEXT();
-            uv_tty_reset(handle, error);
-            ansi_parser_state = ANSI_NORMAL;
-            continue;
-
-          case '7':
-            /* Save the cursor position and text attributes. */
-            FLUSH_TEXT();
-            uv_tty_save_state(handle, 1, error);
-            ansi_parser_state = ANSI_NORMAL;
-            continue;
-
-           case '8':
-            /* Restore the cursor position and text attributes */
-            FLUSH_TEXT();
-            uv_tty_restore_state(handle, 1, error);
-            ansi_parser_state = ANSI_NORMAL;
-            continue;
-
-          default:
-            if (utf8_codepoint >= '@' && utf8_codepoint <= '_') {
-              /* Single-char control. */
-              ansi_parser_state = ANSI_NORMAL;
-              continue;
-            } else {
-              /* Invalid - proceed as normal, */
-              ansi_parser_state = ANSI_NORMAL;
-            }
-        }
-
-      } else if (ansi_parser_state & ANSI_CSI) {
-        if (!(ansi_parser_state & ANSI_IGNORE)) {
-          if (utf8_codepoint >= '0' && utf8_codepoint <= '9') {
-            /* Parsing a numerical argument */
-
-            if (!(ansi_parser_state & ANSI_IN_ARG)) {
-              /* We were not currently parsing a number */
-
-              /* Check for too many arguments */
-              if (handle->tty.wr.ansi_csi_argc >= ARRAY_SIZE(handle->tty.wr.ansi_csi_argv)) {
-                ansi_parser_state |= ANSI_IGNORE;
-                continue;
-              }
-
-              ansi_parser_state |= ANSI_IN_ARG;
-              handle->tty.wr.ansi_csi_argc++;
-              handle->tty.wr.ansi_csi_argv[handle->tty.wr.ansi_csi_argc - 1] =
-                  (unsigned short) utf8_codepoint - '0';
-              continue;
-            } else {
-              /* We were already parsing a number. Parse next digit. */
-              uint32_t value = 10 *
-                  handle->tty.wr.ansi_csi_argv[handle->tty.wr.ansi_csi_argc - 1];
-
-              /* Check for overflow. */
-              if (value > UINT16_MAX) {
-                ansi_parser_state |= ANSI_IGNORE;
-                continue;
-              }
-
-               handle->tty.wr.ansi_csi_argv[handle->tty.wr.ansi_csi_argc - 1] =
-                   (unsigned short) value + (utf8_codepoint - '0');
-               continue;
-            }
-
-          } else if (utf8_codepoint == ';') {
-            /* Denotes the end of an argument. */
-            if (ansi_parser_state & ANSI_IN_ARG) {
-              ansi_parser_state &= ~ANSI_IN_ARG;
-              continue;
-
-            } else {
-              /* If ANSI_IN_ARG is not set, add another argument and default it
-               * to 0. */
-
-              /* Check for too many arguments */
-              if (handle->tty.wr.ansi_csi_argc >= ARRAY_SIZE(handle->tty.wr.ansi_csi_argv)) {
-                ansi_parser_state |= ANSI_IGNORE;
-                continue;
-              }
-
-              handle->tty.wr.ansi_csi_argc++;
-              handle->tty.wr.ansi_csi_argv[handle->tty.wr.ansi_csi_argc - 1] = 0;
-              continue;
-            }
-
-          } else if (utf8_codepoint == '?' && !(ansi_parser_state & ANSI_IN_ARG) &&
-                     handle->tty.wr.ansi_csi_argc == 0) {
-            /* Ignores '?' if it is the first character after CSI[. This is an
-             * extension character from the VT100 codeset that is supported and
-             * used by most ANSI terminals today. */
-            continue;
-
-          } else if (utf8_codepoint >= '@' && utf8_codepoint <= '~' &&
-                     (handle->tty.wr.ansi_csi_argc > 0 || utf8_codepoint != '[')) {
-            int x, y, d;
-
-            /* Command byte */
-            switch (utf8_codepoint) {
-              case 'A':
-                /* cursor up */
-                FLUSH_TEXT();
-                y = -(handle->tty.wr.ansi_csi_argc ? handle->tty.wr.ansi_csi_argv[0] : 1);
-                uv_tty_move_caret(handle, 0, 1, y, 1, error);
-                break;
-
-              case 'B':
-                /* cursor down */
-                FLUSH_TEXT();
-                y = handle->tty.wr.ansi_csi_argc ? handle->tty.wr.ansi_csi_argv[0] : 1;
-                uv_tty_move_caret(handle, 0, 1, y, 1, error);
-                break;
-
-              case 'C':
-                /* cursor forward */
-                FLUSH_TEXT();
-                x = handle->tty.wr.ansi_csi_argc ? handle->tty.wr.ansi_csi_argv[0] : 1;
-                uv_tty_move_caret(handle, x, 1, 0, 1, error);
-                break;
-
-              case 'D':
-                /* cursor back */
-                FLUSH_TEXT();
-                x = -(handle->tty.wr.ansi_csi_argc ? handle->tty.wr.ansi_csi_argv[0] : 1);
-                uv_tty_move_caret(handle, x, 1, 0, 1, error);
-                break;
-
-              case 'E':
-                /* cursor next line */
-                FLUSH_TEXT();
-                y = handle->tty.wr.ansi_csi_argc ? handle->tty.wr.ansi_csi_argv[0] : 1;
-                uv_tty_move_caret(handle, 0, 0, y, 1, error);
-                break;
-
-              case 'F':
-                /* cursor previous line */
-                FLUSH_TEXT();
-                y = -(handle->tty.wr.ansi_csi_argc ? handle->tty.wr.ansi_csi_argv[0] : 1);
-                uv_tty_move_caret(handle, 0, 0, y, 1, error);
-                break;
-
-              case 'G':
-                /* cursor horizontal move absolute */
-                FLUSH_TEXT();
-                x = (handle->tty.wr.ansi_csi_argc >= 1 && handle->tty.wr.ansi_csi_argv[0])
-                  ? handle->tty.wr.ansi_csi_argv[0] - 1 : 0;
-                uv_tty_move_caret(handle, x, 0, 0, 1, error);
-                break;
-
-              case 'H':
-              case 'f':
-                /* cursor move absolute */
-                FLUSH_TEXT();
-                y = (handle->tty.wr.ansi_csi_argc >= 1 && handle->tty.wr.ansi_csi_argv[0])
-                  ? handle->tty.wr.ansi_csi_argv[0] - 1 : 0;
-                x = (handle->tty.wr.ansi_csi_argc >= 2 && handle->tty.wr.ansi_csi_argv[1])
-                  ? handle->tty.wr.ansi_csi_argv[1] - 1 : 0;
-                uv_tty_move_caret(handle, x, 0, y, 0, error);
-                break;
-
-              case 'J':
-                /* Erase screen */
-                FLUSH_TEXT();
-                d = handle->tty.wr.ansi_csi_argc ? handle->tty.wr.ansi_csi_argv[0] : 0;
-                if (d >= 0 && d <= 2) {
-                  uv_tty_clear(handle, d, 1, error);
-                }
-                break;
-
-              case 'K':
-                /* Erase line */
-                FLUSH_TEXT();
-                d = handle->tty.wr.ansi_csi_argc ? handle->tty.wr.ansi_csi_argv[0] : 0;
-                if (d >= 0 && d <= 2) {
-                  uv_tty_clear(handle, d, 0, error);
-                }
-                break;
-
-              case 'm':
-                /* Set style */
-                FLUSH_TEXT();
-                uv_tty_set_style(handle, error);
-                break;
-
-              case 's':
-                /* Save the cursor position. */
-                FLUSH_TEXT();
-                uv_tty_save_state(handle, 0, error);
-                break;
-
-              case 'u':
-                /* Restore the cursor position */
-                FLUSH_TEXT();
-                uv_tty_restore_state(handle, 0, error);
-                break;
-
-              case 'l':
-                /* Hide the cursor */
-                if (handle->tty.wr.ansi_csi_argc == 1 &&
-                    handle->tty.wr.ansi_csi_argv[0] == 25) {
-                  FLUSH_TEXT();
-                  uv_tty_set_cursor_visibility(handle, 0, error);
-                }
-                break;
-
-              case 'h':
-                /* Show the cursor */
-                if (handle->tty.wr.ansi_csi_argc == 1 &&
-                    handle->tty.wr.ansi_csi_argv[0] == 25) {
-                  FLUSH_TEXT();
-                  uv_tty_set_cursor_visibility(handle, 1, error);
-                }
-                break;
-            }
-
-            /* Sequence ended - go back to normal state. */
-            ansi_parser_state = ANSI_NORMAL;
-            continue;
-
-          } else {
-            /* We don't support commands that use private mode characters or
-             * intermediaries. Ignore the rest of the sequence. */
-            ansi_parser_state |= ANSI_IGNORE;
-            continue;
-          }
-        } else {
-          /* We're ignoring this command. Stop only on command character. */
-          if (utf8_codepoint >= '@' && utf8_codepoint <= '~') {
-            ansi_parser_state = ANSI_NORMAL;
-          }
-          continue;
-        }
-
-      } else if (ansi_parser_state & ANSI_ST_CONTROL) {
-        /* Unsupported control code.
-         * Ignore everything until we see `BEL` or `ESC \`. */
-        if (ansi_parser_state & ANSI_IN_STRING) {
-          if (!(ansi_parser_state & ANSI_BACKSLASH_SEEN)) {
-            if (utf8_codepoint == '"') {
-              ansi_parser_state &= ~ANSI_IN_STRING;
-            } else if (utf8_codepoint == '\\') {
-              ansi_parser_state |= ANSI_BACKSLASH_SEEN;
-            }
-          } else {
-            ansi_parser_state &= ~ANSI_BACKSLASH_SEEN;
-          }
-        } else {
-          if (utf8_codepoint == '\007' || (utf8_codepoint == '\\' &&
-              (ansi_parser_state & ANSI_ESCAPE_SEEN))) {
-            /* End of sequence */
-            ansi_parser_state = ANSI_NORMAL;
-          } else if (utf8_codepoint == '\033') {
-            /* Escape character */
-            ansi_parser_state |= ANSI_ESCAPE_SEEN;
-          } else if (utf8_codepoint == '"') {
-             /* String starting */
-            ansi_parser_state |= ANSI_IN_STRING;
-            ansi_parser_state &= ~ANSI_ESCAPE_SEEN;
-            ansi_parser_state &= ~ANSI_BACKSLASH_SEEN;
-          } else {
-            ansi_parser_state &= ~ANSI_ESCAPE_SEEN;
-          }
-        }
-        continue;
-      } else {
-        /* Inconsistent state */
-        abort();
-      }
-
-      /* We wouldn't mind emitting utf-16 surrogate pairs. Too bad, the windows
-       * console doesn't really support UTF-16, so just emit the replacement
-       * character. */
-      if (utf8_codepoint > 0xffff) {
-        utf8_codepoint = UNICODE_REPLACEMENT_CHARACTER;
-      }
-
-      if (utf8_codepoint == 0x0a || utf8_codepoint == 0x0d) {
-        /* EOL conversion - emit \r\n when we see \n. */
-
-        if (utf8_codepoint == 0x0a && previous_eol != 0x0d) {
-          /* \n was not preceded by \r; print \r\n. */
-          ENSURE_BUFFER_SPACE(2);
-          utf16_buf[utf16_buf_used++] = L'\r';
-          utf16_buf[utf16_buf_used++] = L'\n';
-        } else if (utf8_codepoint == 0x0d && previous_eol == 0x0a) {
-          /* \n was followed by \r; do not print the \r, since the source was
-           * either \r\n\r (so the second \r is redundant) or was \n\r (so the
-           * \n was processed by the last case and an \r automatically
-           * inserted). */
-        } else {
-          /* \r without \n; print \r as-is. */
-          ENSURE_BUFFER_SPACE(1);
-          utf16_buf[utf16_buf_used++] = (WCHAR) utf8_codepoint;
-        }
-
-        previous_eol = (char) utf8_codepoint;
-
-      } else if (utf8_codepoint <= 0xffff) {
-        /* Encode character into utf-16 buffer. */
-        ENSURE_BUFFER_SPACE(1);
-        utf16_buf[utf16_buf_used++] = (WCHAR) utf8_codepoint;
-        previous_eol = 0;
-      }
-    }
-  }
-
-  /* Flush remaining characters */
-  FLUSH_TEXT();
-
-  /* Copy cached values back to struct. */
-  handle->tty.wr.utf8_bytes_left = utf8_bytes_left;
-  handle->tty.wr.utf8_codepoint = utf8_codepoint;
-  handle->tty.wr.previous_eol = previous_eol;
-  handle->tty.wr.ansi_parser_state = ansi_parser_state;
-
-  uv_sem_post(&uv_tty_output_lock);
-
-  if (*error == STATUS_SUCCESS) {
-    return 0;
-  } else {
-    return -1;
-  }
-
-#undef FLUSH_TEXT
-}
-
-
-int uv_tty_write(uv_loop_t* loop,
-                 uv_write_t* req,
-                 uv_tty_t* handle,
-                 const uv_buf_t bufs[],
-                 unsigned int nbufs,
-                 uv_write_cb cb) {
-  DWORD error;
-
-  UV_REQ_INIT(req, UV_WRITE);
-  req->handle = (uv_stream_t*) handle;
-  req->cb = cb;
-
-  handle->reqs_pending++;
-  handle->stream.conn.write_reqs_pending++;
-  REGISTER_HANDLE_REQ(loop, handle, req);
-
-  req->u.io.queued_bytes = 0;
-
-  if (!uv_tty_write_bufs(handle, bufs, nbufs, &error)) {
-    SET_REQ_SUCCESS(req);
-  } else {
-    SET_REQ_ERROR(req, error);
-  }
-
-  uv_insert_pending_req(loop, (uv_req_t*) req);
-
-  return 0;
-}
-
-
-int uv__tty_try_write(uv_tty_t* handle,
-                      const uv_buf_t bufs[],
-                      unsigned int nbufs) {
-  DWORD error;
-
-  if (handle->stream.conn.write_reqs_pending > 0)
-    return UV_EAGAIN;
-
-  if (uv_tty_write_bufs(handle, bufs, nbufs, &error))
-    return uv_translate_sys_error(error);
-
-  return uv__count_bufs(bufs, nbufs);
-}
-
-
-void uv_process_tty_write_req(uv_loop_t* loop, uv_tty_t* handle,
-  uv_write_t* req) {
-  int err;
-
-  handle->write_queue_size -= req->u.io.queued_bytes;
-  UNREGISTER_HANDLE_REQ(loop, handle, req);
-
-  if (req->cb) {
-    err = GET_REQ_ERROR(req);
-    req->cb(req, uv_translate_sys_error(err));
-  }
-
-  handle->stream.conn.write_reqs_pending--;
-  if (handle->stream.conn.shutdown_req != NULL &&
-      handle->stream.conn.write_reqs_pending == 0) {
-    uv_want_endgame(loop, (uv_handle_t*)handle);
-  }
-
-  DECREASE_PENDING_REQ_COUNT(handle);
-}
-
-
-void uv_tty_close(uv_tty_t* handle) {
-  assert(handle->u.fd == -1 || handle->u.fd > 2);
-  if (handle->flags & UV_HANDLE_READING)
-    uv_tty_read_stop(handle);
-
-  if (handle->u.fd == -1)
-    CloseHandle(handle->handle);
-  else
-    close(handle->u.fd);
-
-  handle->u.fd = -1;
-  handle->handle = INVALID_HANDLE_VALUE;
-  handle->flags &= ~(UV_HANDLE_READABLE | UV_HANDLE_WRITABLE);
-  uv__handle_closing(handle);
-
-  if (handle->reqs_pending == 0) {
-    uv_want_endgame(handle->loop, (uv_handle_t*) handle);
-  }
-}
-
-
-void uv_tty_endgame(uv_loop_t* loop, uv_tty_t* handle) {
-  if (!(handle->flags & UV_HANDLE_TTY_READABLE) &&
-      handle->stream.conn.shutdown_req != NULL &&
-      handle->stream.conn.write_reqs_pending == 0) {
-    UNREGISTER_HANDLE_REQ(loop, handle, handle->stream.conn.shutdown_req);
-
-    /* TTY shutdown is really just a no-op */
-    if (handle->stream.conn.shutdown_req->cb) {
-      if (handle->flags & UV_HANDLE_CLOSING) {
-        handle->stream.conn.shutdown_req->cb(handle->stream.conn.shutdown_req, UV_ECANCELED);
-      } else {
-        handle->stream.conn.shutdown_req->cb(handle->stream.conn.shutdown_req, 0);
-      }
-    }
-
-    handle->stream.conn.shutdown_req = NULL;
-
-    DECREASE_PENDING_REQ_COUNT(handle);
-    return;
-  }
-
-  if (handle->flags & UV_HANDLE_CLOSING &&
-      handle->reqs_pending == 0) {
-    /* The wait handle used for raw reading should be unregistered when the
-     * wait callback runs. */
-    assert(!(handle->flags & UV_HANDLE_TTY_READABLE) ||
-           handle->tty.rd.read_raw_wait == NULL);
-
-    assert(!(handle->flags & UV_HANDLE_CLOSED));
-    uv__handle_close(handle);
-  }
-}
-
-
-/*
- * uv_process_tty_accept_req() is a stub to keep DELEGATE_STREAM_REQ working
- * TODO: find a way to remove it
- */
-void uv_process_tty_accept_req(uv_loop_t* loop, uv_tty_t* handle,
-    uv_req_t* raw_req) {
-  abort();
-}
-
-
-/*
- * uv_process_tty_connect_req() is a stub to keep DELEGATE_STREAM_REQ working
- * TODO: find a way to remove it
- */
-void uv_process_tty_connect_req(uv_loop_t* loop, uv_tty_t* handle,
-    uv_connect_t* req) {
-  abort();
-}
-
-
-int uv_tty_reset_mode(void) {
-  /* Not necessary to do anything. */
-  return 0;
-}
-
-/* Determine whether or not this version of windows supports
- * proper ANSI color codes. Should be supported as of windows
- * 10 version 1511, build number 10.0.10586.
- */
-static void uv__determine_vterm_state(HANDLE handle) {
-  DWORD dwMode = 0;
-
-  if (!GetConsoleMode(handle, &dwMode)) {
-    uv__vterm_state = UV_UNSUPPORTED;
-    return;
-  }
-
-  dwMode |= ENABLE_VIRTUAL_TERMINAL_PROCESSING;
-  if (!SetConsoleMode(handle, dwMode)) {
-    uv__vterm_state = UV_UNSUPPORTED;
-    return;
-  }
-
-  uv__vterm_state = UV_SUPPORTED;
-}
-
-static DWORD WINAPI uv__tty_console_resize_message_loop_thread(void* param) {
-  CONSOLE_SCREEN_BUFFER_INFO sb_info;
-  MSG msg;
-
-  if (!GetConsoleScreenBufferInfo(uv__tty_console_handle, &sb_info))
-    return 0;
-
-  uv__tty_console_width = sb_info.dwSize.X;
-  uv__tty_console_height = sb_info.srWindow.Bottom - sb_info.srWindow.Top + 1;
-
-  if (pSetWinEventHook == NULL)
-    return 0;
-
-  if (!pSetWinEventHook(EVENT_CONSOLE_LAYOUT,
-                        EVENT_CONSOLE_LAYOUT,
-                        NULL,
-                        uv__tty_console_resize_event,
-                        0,
-                        0,
-                        WINEVENT_OUTOFCONTEXT))
-    return 0;
-
-  while (GetMessage(&msg, NULL, 0, 0)) {
-    TranslateMessage(&msg);
-    DispatchMessage(&msg);
-  }
-  return 0;
-}
-
-static void CALLBACK uv__tty_console_resize_event(HWINEVENTHOOK hWinEventHook,
-                                                  DWORD event,
-                                                  HWND hwnd,
-                                                  LONG idObject,
-                                                  LONG idChild,
-                                                  DWORD dwEventThread,
-                                                  DWORD dwmsEventTime) {
-  CONSOLE_SCREEN_BUFFER_INFO sb_info;
-  int width, height;
-
-  if (!GetConsoleScreenBufferInfo(uv__tty_console_handle, &sb_info))
-    return;
-
-  width = sb_info.dwSize.X;
-  height = sb_info.srWindow.Bottom - sb_info.srWindow.Top + 1;
-
-  if (width != uv__tty_console_width || height != uv__tty_console_height) {
-    uv__tty_console_width = width;
-    uv__tty_console_height = height;
-    uv__signal_dispatch(SIGWINCH);
-  }
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/udp.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/udp.cpp
deleted file mode 100644
index 8aeeab3..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/udp.cpp
+++ /dev/null
@@ -1,1035 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include <assert.h>
-#include <stdlib.h>
-
-#include "uv.h"
-#include "internal.h"
-#include "handle-inl.h"
-#include "stream-inl.h"
-#include "req-inl.h"
-
-
-/*
- * Threshold of active udp streams for which to preallocate udp read buffers.
- */
-const unsigned int uv_active_udp_streams_threshold = 0;
-
-/* A zero-size buffer for use by uv_udp_read */
-static char uv_zero_[] = "";
-int uv_udp_getpeername(const uv_udp_t* handle,
-                       struct sockaddr* name,
-                       int* namelen) {
-
-  return uv__getsockpeername((const uv_handle_t*) handle,
-                             getpeername,
-                             name,
-                             namelen,
-                             0);
-}
-
-
-int uv_udp_getsockname(const uv_udp_t* handle,
-                       struct sockaddr* name,
-                       int* namelen) {
-
-  return uv__getsockpeername((const uv_handle_t*) handle,
-                             getsockname,
-                             name,
-                             namelen,
-                             0);
-}
-
-
-static int uv_udp_set_socket(uv_loop_t* loop, uv_udp_t* handle, SOCKET socket,
-    int family) {
-  DWORD yes = 1;
-  WSAPROTOCOL_INFOW info;
-  int opt_len;
-
-  if (handle->socket != INVALID_SOCKET)
-    return UV_EBUSY;
-
-  /* Set the socket to nonblocking mode */
-  if (ioctlsocket(socket, FIONBIO, &yes) == SOCKET_ERROR) {
-    return WSAGetLastError();
-  }
-
-  /* Make the socket non-inheritable */
-  if (!SetHandleInformation((HANDLE)socket, HANDLE_FLAG_INHERIT, 0)) {
-    return GetLastError();
-  }
-
-  /* Associate it with the I/O completion port. Use uv_handle_t pointer as
-   * completion key. */
-  if (CreateIoCompletionPort((HANDLE)socket,
-                             loop->iocp,
-                             (ULONG_PTR)socket,
-                             0) == NULL) {
-    return GetLastError();
-  }
-
-  /* All known Windows that support SetFileCompletionNotificationModes have a
-   * bug that makes it impossible to use this function in conjunction with
-   * datagram sockets. We can work around that but only if the user is using
-   * the default UDP driver (AFD) and has no other. LSPs stacked on top. Here
-   * we check whether that is the case. */
-  opt_len = (int) sizeof info;
-  if (getsockopt(
-          socket, SOL_SOCKET, SO_PROTOCOL_INFOW, (char*) &info, &opt_len) ==
-      SOCKET_ERROR) {
-    return GetLastError();
-  }
-
-  if (info.ProtocolChain.ChainLen == 1) {
-    if (SetFileCompletionNotificationModes(
-            (HANDLE) socket,
-            FILE_SKIP_SET_EVENT_ON_HANDLE |
-                FILE_SKIP_COMPLETION_PORT_ON_SUCCESS)) {
-      handle->flags |= UV_HANDLE_SYNC_BYPASS_IOCP;
-      handle->func_wsarecv = uv_wsarecv_workaround;
-      handle->func_wsarecvfrom = uv_wsarecvfrom_workaround;
-    } else if (GetLastError() != ERROR_INVALID_FUNCTION) {
-      return GetLastError();
-    }
-  }
-
-  handle->socket = socket;
-
-  if (family == AF_INET6) {
-    handle->flags |= UV_HANDLE_IPV6;
-  } else {
-    assert(!(handle->flags & UV_HANDLE_IPV6));
-  }
-
-  return 0;
-}
-
-
-int uv_udp_init_ex(uv_loop_t* loop, uv_udp_t* handle, unsigned int flags) {
-  int domain;
-
-  /* Use the lower 8 bits for the domain */
-  domain = flags & 0xFF;
-  if (domain != AF_INET && domain != AF_INET6 && domain != AF_UNSPEC)
-    return UV_EINVAL;
-
-  if (flags & ~0xFF)
-    return UV_EINVAL;
-
-  uv__handle_init(loop, (uv_handle_t*) handle, UV_UDP);
-  handle->socket = INVALID_SOCKET;
-  handle->reqs_pending = 0;
-  handle->activecnt = 0;
-  handle->func_wsarecv = WSARecv;
-  handle->func_wsarecvfrom = WSARecvFrom;
-  handle->send_queue_size = 0;
-  handle->send_queue_count = 0;
-  UV_REQ_INIT(&handle->recv_req, UV_UDP_RECV);
-  handle->recv_req.data = handle;
-
-  /* If anything fails beyond this point we need to remove the handle from
-   * the handle queue, since it was added by uv__handle_init.
-   */
-
-  if (domain != AF_UNSPEC) {
-    SOCKET sock;
-    DWORD err;
-
-    sock = socket(domain, SOCK_DGRAM, 0);
-    if (sock == INVALID_SOCKET) {
-      err = WSAGetLastError();
-      QUEUE_REMOVE(&handle->handle_queue);
-      return uv_translate_sys_error(err);
-    }
-
-    err = uv_udp_set_socket(handle->loop, handle, sock, domain);
-    if (err) {
-      closesocket(sock);
-      QUEUE_REMOVE(&handle->handle_queue);
-      return uv_translate_sys_error(err);
-    }
-  }
-
-  return 0;
-}
-
-
-int uv_udp_init(uv_loop_t* loop, uv_udp_t* handle) {
-  return uv_udp_init_ex(loop, handle, AF_UNSPEC);
-}
-
-
-void uv_udp_close(uv_loop_t* loop, uv_udp_t* handle) {
-  uv_udp_recv_stop(handle);
-  closesocket(handle->socket);
-  handle->socket = INVALID_SOCKET;
-
-  uv__handle_closing(handle);
-
-  if (handle->reqs_pending == 0) {
-    uv_want_endgame(loop, (uv_handle_t*) handle);
-  }
-}
-
-
-void uv_udp_endgame(uv_loop_t* loop, uv_udp_t* handle) {
-  if (handle->flags & UV_HANDLE_CLOSING &&
-      handle->reqs_pending == 0) {
-    assert(!(handle->flags & UV_HANDLE_CLOSED));
-    uv__handle_close(handle);
-  }
-}
-
-
-static int uv_udp_maybe_bind(uv_udp_t* handle,
-                             const struct sockaddr* addr,
-                             unsigned int addrlen,
-                             unsigned int flags) {
-  int r;
-  int err;
-  DWORD no = 0;
-
-  if (handle->flags & UV_HANDLE_BOUND)
-    return 0;
-
-  if ((flags & UV_UDP_IPV6ONLY) && addr->sa_family != AF_INET6) {
-    /* UV_UDP_IPV6ONLY is supported only for IPV6 sockets */
-    return ERROR_INVALID_PARAMETER;
-  }
-
-  if (handle->socket == INVALID_SOCKET) {
-    SOCKET sock = socket(addr->sa_family, SOCK_DGRAM, 0);
-    if (sock == INVALID_SOCKET) {
-      return WSAGetLastError();
-    }
-
-    err = uv_udp_set_socket(handle->loop, handle, sock, addr->sa_family);
-    if (err) {
-      closesocket(sock);
-      return err;
-    }
-  }
-
-  if (flags & UV_UDP_REUSEADDR) {
-    DWORD yes = 1;
-    /* Set SO_REUSEADDR on the socket. */
-    if (setsockopt(handle->socket,
-                   SOL_SOCKET,
-                   SO_REUSEADDR,
-                   (char*) &yes,
-                   sizeof yes) == SOCKET_ERROR) {
-      err = WSAGetLastError();
-      return err;
-    }
-  }
-
-  if (addr->sa_family == AF_INET6)
-    handle->flags |= UV_HANDLE_IPV6;
-
-  if (addr->sa_family == AF_INET6 && !(flags & UV_UDP_IPV6ONLY)) {
-    /* On windows IPV6ONLY is on by default. If the user doesn't specify it
-     * libuv turns it off. */
-
-    /* TODO: how to handle errors? This may fail if there is no ipv4 stack
-     * available, or when run on XP/2003 which have no support for dualstack
-     * sockets. For now we're silently ignoring the error. */
-    setsockopt(handle->socket,
-               IPPROTO_IPV6,
-               IPV6_V6ONLY,
-               (char*) &no,
-               sizeof no);
-  }
-
-  r = bind(handle->socket, addr, addrlen);
-  if (r == SOCKET_ERROR) {
-    return WSAGetLastError();
-  }
-
-  handle->flags |= UV_HANDLE_BOUND;
-
-  return 0;
-}
-
-
-static void uv_udp_queue_recv(uv_loop_t* loop, uv_udp_t* handle) {
-  uv_req_t* req;
-  uv_buf_t buf;
-  DWORD bytes, flags;
-  int result;
-
-  assert(handle->flags & UV_HANDLE_READING);
-  assert(!(handle->flags & UV_HANDLE_READ_PENDING));
-
-  req = &handle->recv_req;
-  memset(&req->u.io.overlapped, 0, sizeof(req->u.io.overlapped));
-
-  /*
-   * Preallocate a read buffer if the number of active streams is below
-   * the threshold.
-  */
-  if (loop->active_udp_streams < uv_active_udp_streams_threshold) {
-    handle->flags &= ~UV_HANDLE_ZERO_READ;
-
-    handle->recv_buffer = uv_buf_init(NULL, 0);
-    handle->alloc_cb((uv_handle_t*) handle, 65536, &handle->recv_buffer);
-    if (handle->recv_buffer.base == NULL || handle->recv_buffer.len == 0) {
-      handle->recv_cb(handle, UV_ENOBUFS, &handle->recv_buffer, NULL, 0);
-      return;
-    }
-    assert(handle->recv_buffer.base != NULL);
-
-    buf = handle->recv_buffer;
-    memset(&handle->recv_from, 0, sizeof handle->recv_from);
-    handle->recv_from_len = sizeof handle->recv_from;
-    flags = 0;
-
-    result = handle->func_wsarecvfrom(handle->socket,
-                                      (WSABUF*) &buf,
-                                      1,
-                                      &bytes,
-                                      &flags,
-                                      (struct sockaddr*) &handle->recv_from,
-                                      &handle->recv_from_len,
-                                      &req->u.io.overlapped,
-                                      NULL);
-
-    if (UV_SUCCEEDED_WITHOUT_IOCP(result == 0)) {
-      /* Process the req without IOCP. */
-      handle->flags |= UV_HANDLE_READ_PENDING;
-      req->u.io.overlapped.InternalHigh = bytes;
-      handle->reqs_pending++;
-      uv_insert_pending_req(loop, req);
-    } else if (UV_SUCCEEDED_WITH_IOCP(result == 0)) {
-      /* The req will be processed with IOCP. */
-      handle->flags |= UV_HANDLE_READ_PENDING;
-      handle->reqs_pending++;
-    } else {
-      /* Make this req pending reporting an error. */
-      SET_REQ_ERROR(req, WSAGetLastError());
-      uv_insert_pending_req(loop, req);
-      handle->reqs_pending++;
-    }
-
-  } else {
-    handle->flags |= UV_HANDLE_ZERO_READ;
-
-    buf.base = (char*) uv_zero_;
-    buf.len = 0;
-    flags = MSG_PEEK;
-
-    result = handle->func_wsarecv(handle->socket,
-                                  (WSABUF*) &buf,
-                                  1,
-                                  &bytes,
-                                  &flags,
-                                  &req->u.io.overlapped,
-                                  NULL);
-
-    if (UV_SUCCEEDED_WITHOUT_IOCP(result == 0)) {
-      /* Process the req without IOCP. */
-      handle->flags |= UV_HANDLE_READ_PENDING;
-      req->u.io.overlapped.InternalHigh = bytes;
-      handle->reqs_pending++;
-      uv_insert_pending_req(loop, req);
-    } else if (UV_SUCCEEDED_WITH_IOCP(result == 0)) {
-      /* The req will be processed with IOCP. */
-      handle->flags |= UV_HANDLE_READ_PENDING;
-      handle->reqs_pending++;
-    } else {
-      /* Make this req pending reporting an error. */
-      SET_REQ_ERROR(req, WSAGetLastError());
-      uv_insert_pending_req(loop, req);
-      handle->reqs_pending++;
-    }
-  }
-}
-
-
-int uv__udp_recv_start(uv_udp_t* handle, uv_alloc_cb alloc_cb,
-    uv_udp_recv_cb recv_cb) {
-  uv_loop_t* loop = handle->loop;
-  int err;
-
-  if (handle->flags & UV_HANDLE_READING) {
-    return UV_EALREADY;
-  }
-
-  err = uv_udp_maybe_bind(handle,
-                          (const struct sockaddr*) &uv_addr_ip4_any_,
-                          sizeof(uv_addr_ip4_any_),
-                          0);
-  if (err)
-    return uv_translate_sys_error(err);
-
-  handle->flags |= UV_HANDLE_READING;
-  INCREASE_ACTIVE_COUNT(loop, handle);
-  loop->active_udp_streams++;
-
-  handle->recv_cb = recv_cb;
-  handle->alloc_cb = alloc_cb;
-
-  /* If reading was stopped and then started again, there could still be a recv
-   * request pending. */
-  if (!(handle->flags & UV_HANDLE_READ_PENDING))
-    uv_udp_queue_recv(loop, handle);
-
-  return 0;
-}
-
-
-int uv__udp_recv_stop(uv_udp_t* handle) {
-  if (handle->flags & UV_HANDLE_READING) {
-    handle->flags &= ~UV_HANDLE_READING;
-    handle->loop->active_udp_streams--;
-    DECREASE_ACTIVE_COUNT(loop, handle);
-  }
-
-  return 0;
-}
-
-
-static int uv__send(uv_udp_send_t* req,
-                    uv_udp_t* handle,
-                    const uv_buf_t bufs[],
-                    unsigned int nbufs,
-                    const struct sockaddr* addr,
-                    unsigned int addrlen,
-                    uv_udp_send_cb cb) {
-  uv_loop_t* loop = handle->loop;
-  DWORD result, bytes;
-
-  UV_REQ_INIT(req, UV_UDP_SEND);
-  req->handle = handle;
-  req->cb = cb;
-  memset(&req->u.io.overlapped, 0, sizeof(req->u.io.overlapped));
-
-  result = WSASendTo(handle->socket,
-                     (WSABUF*)bufs,
-                     nbufs,
-                     &bytes,
-                     0,
-                     addr,
-                     addrlen,
-                     &req->u.io.overlapped,
-                     NULL);
-
-  if (UV_SUCCEEDED_WITHOUT_IOCP(result == 0)) {
-    /* Request completed immediately. */
-    req->u.io.queued_bytes = 0;
-    handle->reqs_pending++;
-    handle->send_queue_size += req->u.io.queued_bytes;
-    handle->send_queue_count++;
-    REGISTER_HANDLE_REQ(loop, handle, req);
-    uv_insert_pending_req(loop, (uv_req_t*)req);
-  } else if (UV_SUCCEEDED_WITH_IOCP(result == 0)) {
-    /* Request queued by the kernel. */
-    req->u.io.queued_bytes = uv__count_bufs(bufs, nbufs);
-    handle->reqs_pending++;
-    handle->send_queue_size += req->u.io.queued_bytes;
-    handle->send_queue_count++;
-    REGISTER_HANDLE_REQ(loop, handle, req);
-  } else {
-    /* Send failed due to an error. */
-    return WSAGetLastError();
-  }
-
-  return 0;
-}
-
-
-void uv_process_udp_recv_req(uv_loop_t* loop, uv_udp_t* handle,
-    uv_req_t* req) {
-  uv_buf_t buf;
-  int partial;
-
-  assert(handle->type == UV_UDP);
-
-  handle->flags &= ~UV_HANDLE_READ_PENDING;
-
-  if (!REQ_SUCCESS(req)) {
-    DWORD err = GET_REQ_SOCK_ERROR(req);
-    if (err == WSAEMSGSIZE) {
-      /* Not a real error, it just indicates that the received packet was
-       * bigger than the receive buffer. */
-    } else if (err == WSAECONNRESET || err == WSAENETRESET) {
-      /* A previous sendto operation failed; ignore this error. If zero-reading
-       * we need to call WSARecv/WSARecvFrom _without_ the. MSG_PEEK flag to
-       * clear out the error queue. For nonzero reads, immediately queue a new
-       * receive. */
-      if (!(handle->flags & UV_HANDLE_ZERO_READ)) {
-        goto done;
-      }
-    } else {
-      /* A real error occurred. Report the error to the user only if we're
-       * currently reading. */
-      if (handle->flags & UV_HANDLE_READING) {
-        uv_udp_recv_stop(handle);
-        buf = (handle->flags & UV_HANDLE_ZERO_READ) ?
-              uv_buf_init(NULL, 0) : handle->recv_buffer;
-        handle->recv_cb(handle, uv_translate_sys_error(err), &buf, NULL, 0);
-      }
-      goto done;
-    }
-  }
-
-  if (!(handle->flags & UV_HANDLE_ZERO_READ)) {
-    /* Successful read */
-    partial = !REQ_SUCCESS(req);
-    handle->recv_cb(handle,
-                    req->u.io.overlapped.InternalHigh,
-                    &handle->recv_buffer,
-                    (const struct sockaddr*) &handle->recv_from,
-                    partial ? UV_UDP_PARTIAL : 0);
-  } else if (handle->flags & UV_HANDLE_READING) {
-    DWORD bytes, err, flags;
-    struct sockaddr_storage from;
-    int from_len;
-
-    /* Do a nonblocking receive.
-     * TODO: try to read multiple datagrams at once. FIONREAD maybe? */
-    buf = uv_buf_init(NULL, 0);
-    handle->alloc_cb((uv_handle_t*) handle, 65536, &buf);
-    if (buf.base == NULL || buf.len == 0) {
-      handle->recv_cb(handle, UV_ENOBUFS, &buf, NULL, 0);
-      goto done;
-    }
-    assert(buf.base != NULL);
-
-    memset(&from, 0, sizeof from);
-    from_len = sizeof from;
-
-    flags = 0;
-
-    if (WSARecvFrom(handle->socket,
-                    (WSABUF*)&buf,
-                    1,
-                    &bytes,
-                    &flags,
-                    (struct sockaddr*) &from,
-                    &from_len,
-                    NULL,
-                    NULL) != SOCKET_ERROR) {
-
-      /* Message received */
-      handle->recv_cb(handle, bytes, &buf, (const struct sockaddr*) &from, 0);
-    } else {
-      err = WSAGetLastError();
-      if (err == WSAEMSGSIZE) {
-        /* Message truncated */
-        handle->recv_cb(handle,
-                        bytes,
-                        &buf,
-                        (const struct sockaddr*) &from,
-                        UV_UDP_PARTIAL);
-      } else if (err == WSAEWOULDBLOCK) {
-        /* Kernel buffer empty */
-        handle->recv_cb(handle, 0, &buf, NULL, 0);
-      } else if (err == WSAECONNRESET || err == WSAENETRESET) {
-        /* WSAECONNRESET/WSANETRESET is ignored because this just indicates
-         * that a previous sendto operation failed.
-         */
-        handle->recv_cb(handle, 0, &buf, NULL, 0);
-      } else {
-        /* Any other error that we want to report back to the user. */
-        uv_udp_recv_stop(handle);
-        handle->recv_cb(handle, uv_translate_sys_error(err), &buf, NULL, 0);
-      }
-    }
-  }
-
-done:
-  /* Post another read if still reading and not closing. */
-  if ((handle->flags & UV_HANDLE_READING) &&
-      !(handle->flags & UV_HANDLE_READ_PENDING)) {
-    uv_udp_queue_recv(loop, handle);
-  }
-
-  DECREASE_PENDING_REQ_COUNT(handle);
-}
-
-
-void uv_process_udp_send_req(uv_loop_t* loop, uv_udp_t* handle,
-    uv_udp_send_t* req) {
-  int err;
-
-  assert(handle->type == UV_UDP);
-
-  assert(handle->send_queue_size >= req->u.io.queued_bytes);
-  assert(handle->send_queue_count >= 1);
-  handle->send_queue_size -= req->u.io.queued_bytes;
-  handle->send_queue_count--;
-
-  UNREGISTER_HANDLE_REQ(loop, handle, req);
-
-  if (req->cb) {
-    err = 0;
-    if (!REQ_SUCCESS(req)) {
-      err = GET_REQ_SOCK_ERROR(req);
-    }
-    req->cb(req, uv_translate_sys_error(err));
-  }
-
-  DECREASE_PENDING_REQ_COUNT(handle);
-}
-
-
-static int uv__udp_set_membership4(uv_udp_t* handle,
-                                   const struct sockaddr_in* multicast_addr,
-                                   const char* interface_addr,
-                                   uv_membership membership) {
-  int err;
-  int optname;
-  struct ip_mreq mreq;
-
-  if (handle->flags & UV_HANDLE_IPV6)
-    return UV_EINVAL;
-
-  /* If the socket is unbound, bind to inaddr_any. */
-  err = uv_udp_maybe_bind(handle,
-                          (const struct sockaddr*) &uv_addr_ip4_any_,
-                          sizeof(uv_addr_ip4_any_),
-                          UV_UDP_REUSEADDR);
-  if (err)
-    return uv_translate_sys_error(err);
-
-  memset(&mreq, 0, sizeof mreq);
-
-  if (interface_addr) {
-    err = uv_inet_pton(AF_INET, interface_addr, &mreq.imr_interface.s_addr);
-    if (err)
-      return err;
-  } else {
-    mreq.imr_interface.s_addr = htonl(INADDR_ANY);
-  }
-
-  mreq.imr_multiaddr.s_addr = multicast_addr->sin_addr.s_addr;
-
-  switch (membership) {
-    case UV_JOIN_GROUP:
-      optname = IP_ADD_MEMBERSHIP;
-      break;
-    case UV_LEAVE_GROUP:
-      optname = IP_DROP_MEMBERSHIP;
-      break;
-    default:
-      return UV_EINVAL;
-  }
-
-  if (setsockopt(handle->socket,
-                 IPPROTO_IP,
-                 optname,
-                 (char*) &mreq,
-                 sizeof mreq) == SOCKET_ERROR) {
-    return uv_translate_sys_error(WSAGetLastError());
-  }
-
-  return 0;
-}
-
-
-int uv__udp_set_membership6(uv_udp_t* handle,
-                            const struct sockaddr_in6* multicast_addr,
-                            const char* interface_addr,
-                            uv_membership membership) {
-  int optname;
-  int err;
-  struct ipv6_mreq mreq;
-  struct sockaddr_in6 addr6;
-
-  if ((handle->flags & UV_HANDLE_BOUND) && !(handle->flags & UV_HANDLE_IPV6))
-    return UV_EINVAL;
-
-  err = uv_udp_maybe_bind(handle,
-                          (const struct sockaddr*) &uv_addr_ip6_any_,
-                          sizeof(uv_addr_ip6_any_),
-                          UV_UDP_REUSEADDR);
-
-  if (err)
-    return uv_translate_sys_error(err);
-
-  memset(&mreq, 0, sizeof(mreq));
-
-  if (interface_addr) {
-    if (uv_ip6_addr(interface_addr, 0, &addr6))
-      return UV_EINVAL;
-    mreq.ipv6mr_interface = addr6.sin6_scope_id;
-  } else {
-    mreq.ipv6mr_interface = 0;
-  }
-
-  mreq.ipv6mr_multiaddr = multicast_addr->sin6_addr;
-
-  switch (membership) {
-  case UV_JOIN_GROUP:
-    optname = IPV6_ADD_MEMBERSHIP;
-    break;
-  case UV_LEAVE_GROUP:
-    optname = IPV6_DROP_MEMBERSHIP;
-    break;
-  default:
-    return UV_EINVAL;
-  }
-
-  if (setsockopt(handle->socket,
-                 IPPROTO_IPV6,
-                 optname,
-                 (char*) &mreq,
-                 sizeof mreq) == SOCKET_ERROR) {
-    return uv_translate_sys_error(WSAGetLastError());
-  }
-
-  return 0;
-}
-
-
-int uv_udp_set_membership(uv_udp_t* handle,
-                          const char* multicast_addr,
-                          const char* interface_addr,
-                          uv_membership membership) {
-  struct sockaddr_in addr4;
-  struct sockaddr_in6 addr6;
-
-  if (uv_ip4_addr(multicast_addr, 0, &addr4) == 0)
-    return uv__udp_set_membership4(handle, &addr4, interface_addr, membership);
-  else if (uv_ip6_addr(multicast_addr, 0, &addr6) == 0)
-    return uv__udp_set_membership6(handle, &addr6, interface_addr, membership);
-  else
-    return UV_EINVAL;
-}
-
-
-int uv_udp_set_multicast_interface(uv_udp_t* handle, const char* interface_addr) {
-  struct sockaddr_storage addr_st;
-  struct sockaddr_in* addr4;
-  struct sockaddr_in6* addr6;
-
-  addr4 = (struct sockaddr_in*) &addr_st;
-  addr6 = (struct sockaddr_in6*) &addr_st;
-
-  if (!interface_addr) {
-    memset(&addr_st, 0, sizeof addr_st);
-    if (handle->flags & UV_HANDLE_IPV6) {
-      addr_st.ss_family = AF_INET6;
-      addr6->sin6_scope_id = 0;
-    } else {
-      addr_st.ss_family = AF_INET;
-      addr4->sin_addr.s_addr = htonl(INADDR_ANY);
-    }
-  } else if (uv_ip4_addr(interface_addr, 0, addr4) == 0) {
-    /* nothing, address was parsed */
-  } else if (uv_ip6_addr(interface_addr, 0, addr6) == 0) {
-    /* nothing, address was parsed */
-  } else {
-    return UV_EINVAL;
-  }
-
-  if (handle->socket == INVALID_SOCKET)
-    return UV_EBADF;
-
-  if (addr_st.ss_family == AF_INET) {
-    if (setsockopt(handle->socket,
-                   IPPROTO_IP,
-                   IP_MULTICAST_IF,
-                   (char*) &addr4->sin_addr,
-                   sizeof(addr4->sin_addr)) == SOCKET_ERROR) {
-      return uv_translate_sys_error(WSAGetLastError());
-    }
-  } else if (addr_st.ss_family == AF_INET6) {
-    if (setsockopt(handle->socket,
-                   IPPROTO_IPV6,
-                   IPV6_MULTICAST_IF,
-                   (char*) &addr6->sin6_scope_id,
-                   sizeof(addr6->sin6_scope_id)) == SOCKET_ERROR) {
-      return uv_translate_sys_error(WSAGetLastError());
-    }
-  } else {
-    assert(0 && "unexpected address family");
-    abort();
-  }
-
-  return 0;
-}
-
-
-int uv_udp_set_broadcast(uv_udp_t* handle, int value) {
-  BOOL optval = (BOOL) value;
-
-  if (handle->socket == INVALID_SOCKET)
-    return UV_EBADF;
-
-  if (setsockopt(handle->socket,
-                 SOL_SOCKET,
-                 SO_BROADCAST,
-                 (char*) &optval,
-                 sizeof optval)) {
-    return uv_translate_sys_error(WSAGetLastError());
-  }
-
-  return 0;
-}
-
-
-int uv__udp_is_bound(uv_udp_t* handle) {
-  struct sockaddr_storage addr;
-  int addrlen;
-
-  addrlen = sizeof(addr);
-  if (uv_udp_getsockname(handle, (struct sockaddr*) &addr, &addrlen) != 0)
-    return 0;
-
-  return addrlen > 0;
-}
-
-
-int uv_udp_open(uv_udp_t* handle, uv_os_sock_t sock) {
-  WSAPROTOCOL_INFOW protocol_info;
-  int opt_len;
-  int err;
-
-  /* Detect the address family of the socket. */
-  opt_len = (int) sizeof protocol_info;
-  if (getsockopt(sock,
-                 SOL_SOCKET,
-                 SO_PROTOCOL_INFOW,
-                 (char*) &protocol_info,
-                 &opt_len) == SOCKET_ERROR) {
-    return uv_translate_sys_error(GetLastError());
-  }
-
-  err = uv_udp_set_socket(handle->loop,
-                          handle,
-                          sock,
-                          protocol_info.iAddressFamily);
-  if (err)
-    return uv_translate_sys_error(err);
-
-  if (uv__udp_is_bound(handle))
-    handle->flags |= UV_HANDLE_BOUND;
-
-  if (uv__udp_is_connected(handle))
-    handle->flags |= UV_HANDLE_UDP_CONNECTED;
-
-  return 0;
-}
-
-
-#define SOCKOPT_SETTER(name, option4, option6, validate)                      \
-  int uv_udp_set_##name(uv_udp_t* handle, int value) {                        \
-    DWORD optval = (DWORD) value;                                             \
-                                                                              \
-    if (!(validate(value))) {                                                 \
-      return UV_EINVAL;                                                       \
-    }                                                                         \
-                                                                              \
-    if (handle->socket == INVALID_SOCKET)                                     \
-      return UV_EBADF;                                                        \
-                                                                              \
-    if (!(handle->flags & UV_HANDLE_IPV6)) {                                  \
-      /* Set IPv4 socket option */                                            \
-      if (setsockopt(handle->socket,                                          \
-                     IPPROTO_IP,                                              \
-                     option4,                                                 \
-                     (char*) &optval,                                         \
-                     sizeof optval)) {                                        \
-        return uv_translate_sys_error(WSAGetLastError());                     \
-      }                                                                       \
-    } else {                                                                  \
-      /* Set IPv6 socket option */                                            \
-      if (setsockopt(handle->socket,                                          \
-                     IPPROTO_IPV6,                                            \
-                     option6,                                                 \
-                     (char*) &optval,                                         \
-                     sizeof optval)) {                                        \
-        return uv_translate_sys_error(WSAGetLastError());                     \
-      }                                                                       \
-    }                                                                         \
-    return 0;                                                                 \
-  }
-
-#define VALIDATE_TTL(value) ((value) >= 1 && (value) <= 255)
-#define VALIDATE_MULTICAST_TTL(value) ((value) >= -1 && (value) <= 255)
-#define VALIDATE_MULTICAST_LOOP(value) (1)
-
-SOCKOPT_SETTER(ttl,
-               IP_TTL,
-               IPV6_HOPLIMIT,
-               VALIDATE_TTL)
-SOCKOPT_SETTER(multicast_ttl,
-               IP_MULTICAST_TTL,
-               IPV6_MULTICAST_HOPS,
-               VALIDATE_MULTICAST_TTL)
-SOCKOPT_SETTER(multicast_loop,
-               IP_MULTICAST_LOOP,
-               IPV6_MULTICAST_LOOP,
-               VALIDATE_MULTICAST_LOOP)
-
-#undef SOCKOPT_SETTER
-#undef VALIDATE_TTL
-#undef VALIDATE_MULTICAST_TTL
-#undef VALIDATE_MULTICAST_LOOP
-
-
-/* This function is an egress point, i.e. it returns libuv errors rather than
- * system errors.
- */
-int uv__udp_bind(uv_udp_t* handle,
-                 const struct sockaddr* addr,
-                 unsigned int addrlen,
-                 unsigned int flags) {
-  int err;
-
-  err = uv_udp_maybe_bind(handle, addr, addrlen, flags);
-  if (err)
-    return uv_translate_sys_error(err);
-
-  return 0;
-}
-
-
-int uv__udp_connect(uv_udp_t* handle,
-                    const struct sockaddr* addr,
-                    unsigned int addrlen) {
-  const struct sockaddr* bind_addr;
-  int err;
-
-  if (!(handle->flags & UV_HANDLE_BOUND)) {
-    if (addrlen == sizeof(uv_addr_ip4_any_))
-      bind_addr = (const struct sockaddr*) &uv_addr_ip4_any_;
-    else if (addrlen == sizeof(uv_addr_ip6_any_))
-      bind_addr = (const struct sockaddr*) &uv_addr_ip6_any_;
-    else
-      return UV_EINVAL;
-
-    err = uv_udp_maybe_bind(handle, bind_addr, addrlen, 0);
-    if (err)
-      return uv_translate_sys_error(err);
-  }
-
-  err = connect(handle->socket, addr, addrlen);
-  if (err)
-    return uv_translate_sys_error(err);
-
-  handle->flags |= UV_HANDLE_UDP_CONNECTED;
-
-  return 0;
-}
-
-
-int uv__udp_disconnect(uv_udp_t* handle) {
-    int err;
-    struct sockaddr addr;
-
-    memset(&addr, 0, sizeof(addr));
-
-    err = connect(handle->socket, &addr, sizeof(addr));
-    if (err)
-      return uv_translate_sys_error(err);
-
-    handle->flags &= ~UV_HANDLE_UDP_CONNECTED;
-    return 0;
-}
-
-
-/* This function is an egress point, i.e. it returns libuv errors rather than
- * system errors.
- */
-int uv__udp_send(uv_udp_send_t* req,
-                 uv_udp_t* handle,
-                 const uv_buf_t bufs[],
-                 unsigned int nbufs,
-                 const struct sockaddr* addr,
-                 unsigned int addrlen,
-                 uv_udp_send_cb send_cb) {
-  const struct sockaddr* bind_addr;
-  int err;
-
-  if (!(handle->flags & UV_HANDLE_BOUND)) {
-    if (addrlen == sizeof(uv_addr_ip4_any_))
-      bind_addr = (const struct sockaddr*) &uv_addr_ip4_any_;
-    else if (addrlen == sizeof(uv_addr_ip6_any_))
-      bind_addr = (const struct sockaddr*) &uv_addr_ip6_any_;
-    else
-      return UV_EINVAL;
-
-    err = uv_udp_maybe_bind(handle, bind_addr, addrlen, 0);
-    if (err)
-      return uv_translate_sys_error(err);
-  }
-
-  err = uv__send(req, handle, bufs, nbufs, addr, addrlen, send_cb);
-  if (err)
-    return uv_translate_sys_error(err);
-
-  return 0;
-}
-
-
-int uv__udp_try_send(uv_udp_t* handle,
-                     const uv_buf_t bufs[],
-                     unsigned int nbufs,
-                     const struct sockaddr* addr,
-                     unsigned int addrlen) {
-  DWORD bytes;
-  const struct sockaddr* bind_addr;
-  struct sockaddr_storage converted;
-  int err;
-
-  assert(nbufs > 0);
-
-  if (addr != NULL) {
-    err = uv__convert_to_localhost_if_unspecified(addr, &converted);
-    if (err)
-      return err;
-  }
-
-  /* Already sending a message.*/
-  if (handle->send_queue_count != 0)
-    return UV_EAGAIN;
-
-  if (!(handle->flags & UV_HANDLE_BOUND)) {
-    if (addrlen == sizeof(uv_addr_ip4_any_))
-      bind_addr = (const struct sockaddr*) &uv_addr_ip4_any_;
-    else if (addrlen == sizeof(uv_addr_ip6_any_))
-      bind_addr = (const struct sockaddr*) &uv_addr_ip6_any_;
-    else
-      return UV_EINVAL;
-    err = uv_udp_maybe_bind(handle, bind_addr, addrlen, 0);
-    if (err)
-      return uv_translate_sys_error(err);
-  }
-
-  err = WSASendTo(handle->socket,
-                  (WSABUF*)bufs,
-                  nbufs,
-                  &bytes,
-                  0,
-                  (const struct sockaddr*) &converted,
-                  addrlen,
-                  NULL,
-                  NULL);
-
-  if (err)
-    return uv_translate_sys_error(WSAGetLastError());
-
-  return bytes;
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/util.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/util.cpp
deleted file mode 100644
index b5afb1d..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/util.cpp
+++ /dev/null
@@ -1,1811 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include <assert.h>
-#include <direct.h>
-#include <limits.h>
-#include <stdio.h>
-#include <string.h>
-#include <time.h>
-#include <wchar.h>
-
-#include "uv.h"
-#include "internal.h"
-
-#include <winsock2.h>
-#include <winperf.h>
-#include <iphlpapi.h>
-#include <psapi.h>
-#include <tlhelp32.h>
-#include <windows.h>
-#include <userenv.h>
-#include <math.h>
-
-/*
- * Max title length; the only thing MSDN tells us about the maximum length
- * of the console title is that it is smaller than 64K. However in practice
- * it is much smaller, and there is no way to figure out what the exact length
- * of the title is or can be, at least not on XP. To make it even more
- * annoying, GetConsoleTitle fails when the buffer to be read into is bigger
- * than the actual maximum length. So we make a conservative guess here;
- * just don't put the novel you're writing in the title, unless the plot
- * survives truncation.
- */
-#define MAX_TITLE_LENGTH 8192
-
-/* The number of nanoseconds in one second. */
-#define UV__NANOSEC 1000000000
-
-/* Max user name length, from iphlpapi.h */
-#ifndef UNLEN
-# define UNLEN 256
-#endif
-
-
-/* Maximum environment variable size, including the terminating null */
-#define MAX_ENV_VAR_LENGTH 32767
-
-/* Cached copy of the process title, plus a mutex guarding it. */
-static char *process_title;
-static CRITICAL_SECTION process_title_lock;
-
-#pragma comment(lib, "Advapi32.lib")
-#pragma comment(lib, "IPHLPAPI.lib")
-#pragma comment(lib, "Psapi.lib")
-#pragma comment(lib, "Userenv.lib")
-#pragma comment(lib, "kernel32.lib")
-
-/* Interval (in seconds) of the high-resolution clock. */
-static double hrtime_interval_ = 0;
-
-
-/*
- * One-time initialization code for functionality defined in util.c.
- */
-void uv__util_init(void) {
-  LARGE_INTEGER perf_frequency;
-
-  /* Initialize process title access mutex. */
-  InitializeCriticalSection(&process_title_lock);
-
-  /* Retrieve high-resolution timer frequency
-   * and precompute its reciprocal.
-   */
-  if (QueryPerformanceFrequency(&perf_frequency)) {
-    hrtime_interval_ = 1.0 / perf_frequency.QuadPart;
-  } else {
-    hrtime_interval_= 0;
-  }
-}
-
-
-int uv_exepath(char* buffer, size_t* size_ptr) {
-  int utf8_len, utf16_buffer_len, utf16_len;
-  WCHAR* utf16_buffer;
-  int err;
-
-  if (buffer == NULL || size_ptr == NULL || *size_ptr == 0) {
-    return UV_EINVAL;
-  }
-
-  if (*size_ptr > 32768) {
-    /* Windows paths can never be longer than this. */
-    utf16_buffer_len = 32768;
-  } else {
-    utf16_buffer_len = (int) *size_ptr;
-  }
-
-  utf16_buffer = (WCHAR*) uv__malloc(sizeof(WCHAR) * utf16_buffer_len);
-  if (!utf16_buffer) {
-    return UV_ENOMEM;
-  }
-
-  /* Get the path as UTF-16. */
-  utf16_len = GetModuleFileNameW(NULL, utf16_buffer, utf16_buffer_len);
-  if (utf16_len <= 0) {
-    err = GetLastError();
-    goto error;
-  }
-
-  /* utf16_len contains the length, *not* including the terminating null. */
-  utf16_buffer[utf16_len] = L'\0';
-
-  /* Convert to UTF-8 */
-  utf8_len = WideCharToMultiByte(CP_UTF8,
-                                 0,
-                                 utf16_buffer,
-                                 -1,
-                                 buffer,
-                                 (int) *size_ptr,
-                                 NULL,
-                                 NULL);
-  if (utf8_len == 0) {
-    err = GetLastError();
-    goto error;
-  }
-
-  uv__free(utf16_buffer);
-
-  /* utf8_len *does* include the terminating null at this point, but the
-   * returned size shouldn't. */
-  *size_ptr = utf8_len - 1;
-  return 0;
-
- error:
-  uv__free(utf16_buffer);
-  return uv_translate_sys_error(err);
-}
-
-
-int uv_cwd(char* buffer, size_t* size) {
-  DWORD utf16_len;
-  WCHAR utf16_buffer[MAX_PATH];
-  int r;
-
-  if (buffer == NULL || size == NULL) {
-    return UV_EINVAL;
-  }
-
-  utf16_len = GetCurrentDirectoryW(MAX_PATH, utf16_buffer);
-  if (utf16_len == 0) {
-    return uv_translate_sys_error(GetLastError());
-  } else if (utf16_len > MAX_PATH) {
-    /* This should be impossible; however the CRT has a code path to deal with
-     * this scenario, so I added a check anyway. */
-    return UV_EIO;
-  }
-
-  /* utf16_len contains the length, *not* including the terminating null. */
-  utf16_buffer[utf16_len] = L'\0';
-
-  /* The returned directory should not have a trailing slash, unless it points
-   * at a drive root, like c:\. Remove it if needed. */
-  if (utf16_buffer[utf16_len - 1] == L'\\' &&
-      !(utf16_len == 3 && utf16_buffer[1] == L':')) {
-    utf16_len--;
-    utf16_buffer[utf16_len] = L'\0';
-  }
-
-  /* Check how much space we need */
-  r = WideCharToMultiByte(CP_UTF8,
-                          0,
-                          utf16_buffer,
-                          -1,
-                          NULL,
-                          0,
-                          NULL,
-                          NULL);
-  if (r == 0) {
-    return uv_translate_sys_error(GetLastError());
-  } else if (r > (int) *size) {
-    *size = r;
-    return UV_ENOBUFS;
-  }
-
-  /* Convert to UTF-8 */
-  r = WideCharToMultiByte(CP_UTF8,
-                          0,
-                          utf16_buffer,
-                          -1,
-                          buffer,
-                          *size > INT_MAX ? INT_MAX : (int) *size,
-                          NULL,
-                          NULL);
-  if (r == 0) {
-    return uv_translate_sys_error(GetLastError());
-  }
-
-  *size = r - 1;
-  return 0;
-}
-
-
-int uv_chdir(const char* dir) {
-  WCHAR utf16_buffer[MAX_PATH];
-  size_t utf16_len;
-  WCHAR drive_letter, env_var[4];
-
-  if (dir == NULL) {
-    return UV_EINVAL;
-  }
-
-  if (MultiByteToWideChar(CP_UTF8,
-                          0,
-                          dir,
-                          -1,
-                          utf16_buffer,
-                          MAX_PATH) == 0) {
-    DWORD error = GetLastError();
-    /* The maximum length of the current working directory is 260 chars,
-     * including terminating null. If it doesn't fit, the path name must be too
-     * long. */
-    if (error == ERROR_INSUFFICIENT_BUFFER) {
-      return UV_ENAMETOOLONG;
-    } else {
-      return uv_translate_sys_error(error);
-    }
-  }
-
-  if (!SetCurrentDirectoryW(utf16_buffer)) {
-    return uv_translate_sys_error(GetLastError());
-  }
-
-  /* Windows stores the drive-local path in an "hidden" environment variable,
-   * which has the form "=C:=C:\Windows". SetCurrentDirectory does not update
-   * this, so we'll have to do it. */
-  utf16_len = GetCurrentDirectoryW(MAX_PATH, utf16_buffer);
-  if (utf16_len == 0) {
-    return uv_translate_sys_error(GetLastError());
-  } else if (utf16_len > MAX_PATH) {
-    return UV_EIO;
-  }
-
-  /* The returned directory should not have a trailing slash, unless it points
-   * at a drive root, like c:\. Remove it if needed. */
-  if (utf16_buffer[utf16_len - 1] == L'\\' &&
-      !(utf16_len == 3 && utf16_buffer[1] == L':')) {
-    utf16_len--;
-    utf16_buffer[utf16_len] = L'\0';
-  }
-
-  if (utf16_len < 2 || utf16_buffer[1] != L':') {
-    /* Doesn't look like a drive letter could be there - probably an UNC path.
-     * TODO: Need to handle win32 namespaces like \\?\C:\ ? */
-    drive_letter = 0;
-  } else if (utf16_buffer[0] >= L'A' && utf16_buffer[0] <= L'Z') {
-    drive_letter = utf16_buffer[0];
-  } else if (utf16_buffer[0] >= L'a' && utf16_buffer[0] <= L'z') {
-    /* Convert to uppercase. */
-    drive_letter = utf16_buffer[0] - L'a' + L'A';
-  } else {
-    /* Not valid. */
-    drive_letter = 0;
-  }
-
-  if (drive_letter != 0) {
-    /* Construct the environment variable name and set it. */
-    env_var[0] = L'=';
-    env_var[1] = drive_letter;
-    env_var[2] = L':';
-    env_var[3] = L'\0';
-
-    if (!SetEnvironmentVariableW(env_var, utf16_buffer)) {
-      return uv_translate_sys_error(GetLastError());
-    }
-  }
-
-  return 0;
-}
-
-
-void uv_loadavg(double avg[3]) {
-  /* Can't be implemented */
-  avg[0] = avg[1] = avg[2] = 0;
-}
-
-
-uint64_t uv_get_free_memory(void) {
-  MEMORYSTATUSEX memory_status;
-  memory_status.dwLength = sizeof(memory_status);
-
-  if (!GlobalMemoryStatusEx(&memory_status)) {
-     return -1;
-  }
-
-  return (uint64_t)memory_status.ullAvailPhys;
-}
-
-
-uint64_t uv_get_total_memory(void) {
-  MEMORYSTATUSEX memory_status;
-  memory_status.dwLength = sizeof(memory_status);
-
-  if (!GlobalMemoryStatusEx(&memory_status)) {
-    return -1;
-  }
-
-  return (uint64_t)memory_status.ullTotalPhys;
-}
-
-
-uint64_t uv_get_constrained_memory(void) {
-  return 0;  /* Memory constraints are unknown. */
-}
-
-
-uv_pid_t uv_os_getpid(void) {
-  return GetCurrentProcessId();
-}
-
-
-uv_pid_t uv_os_getppid(void) {
-  int parent_pid = -1;
-  HANDLE handle;
-  PROCESSENTRY32 pe;
-  DWORD current_pid = GetCurrentProcessId();
-
-  pe.dwSize = sizeof(PROCESSENTRY32);
-  handle = CreateToolhelp32Snapshot(TH32CS_SNAPPROCESS, 0);
-
-  if (Process32First(handle, &pe)) {
-    do {
-      if (pe.th32ProcessID == current_pid) {
-        parent_pid = pe.th32ParentProcessID;
-        break;
-      }
-    } while( Process32Next(handle, &pe));
-  }
-
-  CloseHandle(handle);
-  return parent_pid;
-}
-
-
-char** uv_setup_args(int argc, char** argv) {
-  return argv;
-}
-
-
-int uv_set_process_title(const char* title) {
-  int err;
-  int length;
-  WCHAR* title_w = NULL;
-
-  uv__once_init();
-
-  /* Find out how big the buffer for the wide-char title must be */
-  length = MultiByteToWideChar(CP_UTF8, 0, title, -1, NULL, 0);
-  if (!length) {
-    err = GetLastError();
-    goto done;
-  }
-
-  /* Convert to wide-char string */
-  title_w = (WCHAR*)uv__malloc(sizeof(WCHAR) * length);
-  if (!title_w) {
-    uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
-  }
-
-  length = MultiByteToWideChar(CP_UTF8, 0, title, -1, title_w, length);
-  if (!length) {
-    err = GetLastError();
-    goto done;
-  }
-
-  /* If the title must be truncated insert a \0 terminator there */
-  if (length > MAX_TITLE_LENGTH) {
-    title_w[MAX_TITLE_LENGTH - 1] = L'\0';
-  }
-
-  if (!SetConsoleTitleW(title_w)) {
-    err = GetLastError();
-    goto done;
-  }
-
-  EnterCriticalSection(&process_title_lock);
-  uv__free(process_title);
-  process_title = uv__strdup(title);
-  LeaveCriticalSection(&process_title_lock);
-
-  err = 0;
-
-done:
-  uv__free(title_w);
-  return uv_translate_sys_error(err);
-}
-
-
-static int uv__get_process_title(void) {
-  WCHAR title_w[MAX_TITLE_LENGTH];
-
-  if (!GetConsoleTitleW(title_w, sizeof(title_w) / sizeof(WCHAR))) {
-    return -1;
-  }
-
-  if (uv__convert_utf16_to_utf8(title_w, -1, &process_title) != 0)
-    return -1;
-
-  return 0;
-}
-
-
-int uv_get_process_title(char* buffer, size_t size) {
-  size_t len;
-
-  if (buffer == NULL || size == 0)
-    return UV_EINVAL;
-
-  uv__once_init();
-
-  EnterCriticalSection(&process_title_lock);
-  /*
-   * If the process_title was never read before nor explicitly set,
-   * we must query it with getConsoleTitleW
-   */
-  if (!process_title && uv__get_process_title() == -1) {
-    LeaveCriticalSection(&process_title_lock);
-    return uv_translate_sys_error(GetLastError());
-  }
-
-  assert(process_title);
-  len = strlen(process_title) + 1;
-
-  if (size < len) {
-    LeaveCriticalSection(&process_title_lock);
-    return UV_ENOBUFS;
-  }
-
-  memcpy(buffer, process_title, len);
-  LeaveCriticalSection(&process_title_lock);
-
-  return 0;
-}
-
-
-uint64_t uv_hrtime(void) {
-  uv__once_init();
-  return uv__hrtime(UV__NANOSEC);
-}
-
-uint64_t uv__hrtime(double scale) {
-  LARGE_INTEGER counter;
-
-  /* If the performance interval is zero, there's no support. */
-  if (hrtime_interval_ == 0) {
-    return 0;
-  }
-
-  if (!QueryPerformanceCounter(&counter)) {
-    return 0;
-  }
-
-  /* Because we have no guarantee about the order of magnitude of the
-   * performance counter interval, integer math could cause this computation
-   * to overflow. Therefore we resort to floating point math.
-   */
-  return (uint64_t) ((double) counter.QuadPart * hrtime_interval_ * scale);
-}
-
-
-int uv_resident_set_memory(size_t* rss) {
-  HANDLE current_process;
-  PROCESS_MEMORY_COUNTERS pmc;
-
-  current_process = GetCurrentProcess();
-
-  if (!GetProcessMemoryInfo(current_process, &pmc, sizeof(pmc))) {
-    return uv_translate_sys_error(GetLastError());
-  }
-
-  *rss = pmc.WorkingSetSize;
-
-  return 0;
-}
-
-
-int uv_uptime(double* uptime) {
-  BYTE stack_buffer[4096];
-  BYTE* malloced_buffer = NULL;
-  BYTE* buffer = (BYTE*) stack_buffer;
-  size_t buffer_size = sizeof(stack_buffer);
-  DWORD data_size;
-
-  PERF_DATA_BLOCK* data_block;
-  PERF_OBJECT_TYPE* object_type;
-  PERF_COUNTER_DEFINITION* counter_definition;
-
-  DWORD i;
-
-  for (;;) {
-    LONG result;
-
-    data_size = (DWORD) buffer_size;
-    result = RegQueryValueExW(HKEY_PERFORMANCE_DATA,
-                              L"2",
-                              NULL,
-                              NULL,
-                              buffer,
-                              &data_size);
-    if (result == ERROR_SUCCESS) {
-      break;
-    } else if (result != ERROR_MORE_DATA) {
-      *uptime = 0;
-      return uv_translate_sys_error(result);
-    }
-
-    buffer_size *= 2;
-    /* Don't let the buffer grow infinitely. */
-    if (buffer_size > 1 << 20) {
-      goto internalError;
-    }
-
-    uv__free(malloced_buffer);
-
-    buffer = malloced_buffer = (BYTE*) uv__malloc(buffer_size);
-    if (malloced_buffer == NULL) {
-      *uptime = 0;
-      return UV_ENOMEM;
-    }
-  }
-
-  if (data_size < sizeof(*data_block))
-    goto internalError;
-
-  data_block = (PERF_DATA_BLOCK*) buffer;
-
-  if (wmemcmp(data_block->Signature, L"PERF", 4) != 0)
-    goto internalError;
-
-  if (data_size < data_block->HeaderLength + sizeof(*object_type))
-    goto internalError;
-
-  object_type = (PERF_OBJECT_TYPE*) (buffer + data_block->HeaderLength);
-
-  if (object_type->NumInstances != PERF_NO_INSTANCES)
-    goto internalError;
-
-  counter_definition = (PERF_COUNTER_DEFINITION*) (buffer +
-      data_block->HeaderLength + object_type->HeaderLength);
-  for (i = 0; i < object_type->NumCounters; i++) {
-    if ((BYTE*) counter_definition + sizeof(*counter_definition) >
-        buffer + data_size) {
-      break;
-    }
-
-    if (counter_definition->CounterNameTitleIndex == 674 &&
-        counter_definition->CounterSize == sizeof(uint64_t)) {
-      if (counter_definition->CounterOffset + sizeof(uint64_t) > data_size ||
-          !(counter_definition->CounterType & PERF_OBJECT_TIMER)) {
-        goto internalError;
-      } else {
-        BYTE* address = (BYTE*) object_type + object_type->DefinitionLength +
-                        counter_definition->CounterOffset;
-        uint64_t value = *((uint64_t*) address);
-        *uptime = floor((double) (object_type->PerfTime.QuadPart - value) /
-                        (double) object_type->PerfFreq.QuadPart);
-        uv__free(malloced_buffer);
-        return 0;
-      }
-    }
-
-    counter_definition = (PERF_COUNTER_DEFINITION*)
-        ((BYTE*) counter_definition + counter_definition->ByteLength);
-  }
-
-  /* If we get here, the uptime value was not found. */
-  uv__free(malloced_buffer);
-  *uptime = 0;
-  return UV_ENOSYS;
-
- internalError:
-  uv__free(malloced_buffer);
-  *uptime = 0;
-  return UV_EIO;
-}
-
-
-int uv_cpu_info(uv_cpu_info_t** cpu_infos_ptr, int* cpu_count_ptr) {
-  uv_cpu_info_t* cpu_infos;
-  SYSTEM_PROCESSOR_PERFORMANCE_INFORMATION* sppi;
-  DWORD sppi_size;
-  SYSTEM_INFO system_info;
-  DWORD cpu_count, i;
-  NTSTATUS status;
-  ULONG result_size;
-  int err;
-  uv_cpu_info_t* cpu_info;
-
-  cpu_infos = NULL;
-  cpu_count = 0;
-  sppi = NULL;
-
-  uv__once_init();
-
-  GetSystemInfo(&system_info);
-  cpu_count = system_info.dwNumberOfProcessors;
-
-  cpu_infos = (uv_cpu_info_t*)uv__calloc(cpu_count, sizeof *cpu_infos);
-  if (cpu_infos == NULL) {
-    err = ERROR_OUTOFMEMORY;
-    goto error;
-  }
-
-  sppi_size = cpu_count * sizeof(*sppi);
-  sppi = (SYSTEM_PROCESSOR_PERFORMANCE_INFORMATION*)uv__malloc(sppi_size);
-  if (sppi == NULL) {
-    err = ERROR_OUTOFMEMORY;
-    goto error;
-  }
-
-  status = pNtQuerySystemInformation(SystemProcessorPerformanceInformation,
-                                     sppi,
-                                     sppi_size,
-                                     &result_size);
-  if (!NT_SUCCESS(status)) {
-    err = pRtlNtStatusToDosError(status);
-    goto error;
-  }
-
-  assert(result_size == sppi_size);
-
-  for (i = 0; i < cpu_count; i++) {
-    WCHAR key_name[128];
-    HKEY processor_key;
-    DWORD cpu_speed;
-    DWORD cpu_speed_size = sizeof(cpu_speed);
-    WCHAR cpu_brand[256];
-    DWORD cpu_brand_size = sizeof(cpu_brand);
-    size_t len;
-
-    len = _snwprintf(key_name,
-                     ARRAY_SIZE(key_name),
-                     L"HARDWARE\\DESCRIPTION\\System\\CentralProcessor\\%d",
-                     i);
-
-    assert(len > 0 && len < ARRAY_SIZE(key_name));
-
-    err = RegOpenKeyExW(HKEY_LOCAL_MACHINE,
-                        key_name,
-                        0,
-                        KEY_QUERY_VALUE,
-                        &processor_key);
-    if (err != ERROR_SUCCESS) {
-      goto error;
-    }
-
-    err = RegQueryValueExW(processor_key,
-                           L"~MHz",
-                           NULL,
-                           NULL,
-                           (BYTE*)&cpu_speed,
-                           &cpu_speed_size);
-    if (err != ERROR_SUCCESS) {
-      RegCloseKey(processor_key);
-      goto error;
-    }
-
-    err = RegQueryValueExW(processor_key,
-                           L"ProcessorNameString",
-                           NULL,
-                           NULL,
-                           (BYTE*)&cpu_brand,
-                           &cpu_brand_size);
-    RegCloseKey(processor_key);
-    if (err != ERROR_SUCCESS)
-      goto error;
-
-    cpu_info = &cpu_infos[i];
-    cpu_info->speed = cpu_speed;
-    cpu_info->cpu_times.user = sppi[i].UserTime.QuadPart / 10000;
-    cpu_info->cpu_times.sys = (sppi[i].KernelTime.QuadPart -
-        sppi[i].IdleTime.QuadPart) / 10000;
-    cpu_info->cpu_times.idle = sppi[i].IdleTime.QuadPart / 10000;
-    cpu_info->cpu_times.irq = sppi[i].InterruptTime.QuadPart / 10000;
-    cpu_info->cpu_times.nice = 0;
-
-    uv__convert_utf16_to_utf8(cpu_brand,
-                              cpu_brand_size / sizeof(WCHAR),
-                              &(cpu_info->model));
-  }
-
-  uv__free(sppi);
-
-  *cpu_count_ptr = cpu_count;
-  *cpu_infos_ptr = cpu_infos;
-
-  return 0;
-
- error:
-  if (cpu_infos != NULL) {
-    /* This is safe because the cpu_infos array is zeroed on allocation. */
-    for (i = 0; i < cpu_count; i++)
-      uv__free(cpu_infos[i].model);
-  }
-
-  uv__free(cpu_infos);
-  uv__free(sppi);
-
-  return uv_translate_sys_error(err);
-}
-
-
-void uv_free_cpu_info(uv_cpu_info_t* cpu_infos, int count) {
-  int i;
-
-  for (i = 0; i < count; i++) {
-    uv__free(cpu_infos[i].model);
-  }
-
-  uv__free(cpu_infos);
-}
-
-
-static int is_windows_version_or_greater(DWORD os_major,
-                                         DWORD os_minor,
-                                         WORD service_pack_major,
-                                         WORD service_pack_minor) {
-  OSVERSIONINFOEX osvi;
-  DWORDLONG condition_mask = 0;
-  int op = VER_GREATER_EQUAL;
-
-  /* Initialize the OSVERSIONINFOEX structure. */
-  ZeroMemory(&osvi, sizeof(OSVERSIONINFOEX));
-  osvi.dwOSVersionInfoSize = sizeof(OSVERSIONINFOEX);
-  osvi.dwMajorVersion = os_major;
-  osvi.dwMinorVersion = os_minor;
-  osvi.wServicePackMajor = service_pack_major;
-  osvi.wServicePackMinor = service_pack_minor;
-
-  /* Initialize the condition mask. */
-  VER_SET_CONDITION(condition_mask, VER_MAJORVERSION, op);
-  VER_SET_CONDITION(condition_mask, VER_MINORVERSION, op);
-  VER_SET_CONDITION(condition_mask, VER_SERVICEPACKMAJOR, op);
-  VER_SET_CONDITION(condition_mask, VER_SERVICEPACKMINOR, op);
-
-  /* Perform the test. */
-  return (int) VerifyVersionInfo(
-    &osvi,
-    VER_MAJORVERSION | VER_MINORVERSION |
-    VER_SERVICEPACKMAJOR | VER_SERVICEPACKMINOR,
-    condition_mask);
-}
-
-
-static int address_prefix_match(int family,
-                                struct sockaddr* address,
-                                struct sockaddr* prefix_address,
-                                int prefix_len) {
-  uint8_t* address_data;
-  uint8_t* prefix_address_data;
-  int i;
-
-  assert(address->sa_family == family);
-  assert(prefix_address->sa_family == family);
-
-  if (family == AF_INET6) {
-    address_data = (uint8_t*) &(((struct sockaddr_in6 *) address)->sin6_addr);
-    prefix_address_data =
-      (uint8_t*) &(((struct sockaddr_in6 *) prefix_address)->sin6_addr);
-  } else {
-    address_data = (uint8_t*) &(((struct sockaddr_in *) address)->sin_addr);
-    prefix_address_data =
-      (uint8_t*) &(((struct sockaddr_in *) prefix_address)->sin_addr);
-  }
-
-  for (i = 0; i < prefix_len >> 3; i++) {
-    if (address_data[i] != prefix_address_data[i])
-      return 0;
-  }
-
-  if (prefix_len % 8)
-    return prefix_address_data[i] ==
-      (address_data[i] & (0xff << (8 - prefix_len % 8)));
-
-  return 1;
-}
-
-
-int uv_interface_addresses(uv_interface_address_t** addresses_ptr,
-    int* count_ptr) {
-  IP_ADAPTER_ADDRESSES* win_address_buf;
-  ULONG win_address_buf_size;
-  IP_ADAPTER_ADDRESSES* adapter;
-
-  uv_interface_address_t* uv_address_buf;
-  char* name_buf;
-  size_t uv_address_buf_size;
-  uv_interface_address_t* uv_address;
-
-  int count;
-
-  int is_vista_or_greater;
-  ULONG flags;
-
-  *addresses_ptr = NULL;
-  *count_ptr = 0;
-
-  is_vista_or_greater = is_windows_version_or_greater(6, 0, 0, 0);
-  if (is_vista_or_greater) {
-    flags = GAA_FLAG_SKIP_ANYCAST | GAA_FLAG_SKIP_MULTICAST |
-      GAA_FLAG_SKIP_DNS_SERVER;
-  } else {
-    /* We need at least XP SP1. */
-    if (!is_windows_version_or_greater(5, 1, 1, 0))
-      return UV_ENOTSUP;
-
-    flags = GAA_FLAG_SKIP_ANYCAST | GAA_FLAG_SKIP_MULTICAST |
-      GAA_FLAG_SKIP_DNS_SERVER | GAA_FLAG_INCLUDE_PREFIX;
-  }
-
-
-  /* Fetch the size of the adapters reported by windows, and then get the list
-   * itself. */
-  win_address_buf_size = 0;
-  win_address_buf = NULL;
-
-  for (;;) {
-    ULONG r;
-
-    /* If win_address_buf is 0, then GetAdaptersAddresses will fail with.
-     * ERROR_BUFFER_OVERFLOW, and the required buffer size will be stored in
-     * win_address_buf_size. */
-    r = GetAdaptersAddresses(AF_UNSPEC,
-                             flags,
-                             NULL,
-                             win_address_buf,
-                             &win_address_buf_size);
-
-    if (r == ERROR_SUCCESS)
-      break;
-
-    uv__free(win_address_buf);
-
-    switch (r) {
-      case ERROR_BUFFER_OVERFLOW:
-        /* This happens when win_address_buf is NULL or too small to hold all
-         * adapters. */
-        win_address_buf =
-            (IP_ADAPTER_ADDRESSES*)uv__malloc(win_address_buf_size);
-        if (win_address_buf == NULL)
-          return UV_ENOMEM;
-
-        continue;
-
-      case ERROR_NO_DATA: {
-        /* No adapters were found. */
-        uv_address_buf = (uv_interface_address_t*)uv__malloc(1);
-        if (uv_address_buf == NULL)
-          return UV_ENOMEM;
-
-        *count_ptr = 0;
-        *addresses_ptr = uv_address_buf;
-
-        return 0;
-      }
-
-      case ERROR_ADDRESS_NOT_ASSOCIATED:
-        return UV_EAGAIN;
-
-      case ERROR_INVALID_PARAMETER:
-        /* MSDN says:
-         *   "This error is returned for any of the following conditions: the
-         *   SizePointer parameter is NULL, the Address parameter is not
-         *   AF_INET, AF_INET6, or AF_UNSPEC, or the address information for
-         *   the parameters requested is greater than ULONG_MAX."
-         * Since the first two conditions are not met, it must be that the
-         * adapter data is too big.
-         */
-        return UV_ENOBUFS;
-
-      default:
-        /* Other (unspecified) errors can happen, but we don't have any special
-         * meaning for them. */
-        assert(r != ERROR_SUCCESS);
-        return uv_translate_sys_error(r);
-    }
-  }
-
-  /* Count the number of enabled interfaces and compute how much space is
-   * needed to store their info. */
-  count = 0;
-  uv_address_buf_size = 0;
-
-  for (adapter = win_address_buf;
-       adapter != NULL;
-       adapter = adapter->Next) {
-    IP_ADAPTER_UNICAST_ADDRESS* unicast_address;
-    int name_size;
-
-    /* Interfaces that are not 'up' should not be reported. Also skip
-     * interfaces that have no associated unicast address, as to avoid
-     * allocating space for the name for this interface. */
-    if (adapter->OperStatus != IfOperStatusUp ||
-        adapter->FirstUnicastAddress == NULL)
-      continue;
-
-    /* Compute the size of the interface name. */
-    name_size = WideCharToMultiByte(CP_UTF8,
-                                    0,
-                                    adapter->FriendlyName,
-                                    -1,
-                                    NULL,
-                                    0,
-                                    NULL,
-                                    FALSE);
-    if (name_size <= 0) {
-      uv__free(win_address_buf);
-      return uv_translate_sys_error(GetLastError());
-    }
-    uv_address_buf_size += name_size;
-
-    /* Count the number of addresses associated with this interface, and
-     * compute the size. */
-    for (unicast_address = (IP_ADAPTER_UNICAST_ADDRESS*)
-                           adapter->FirstUnicastAddress;
-         unicast_address != NULL;
-         unicast_address = unicast_address->Next) {
-      count++;
-      uv_address_buf_size += sizeof(uv_interface_address_t);
-    }
-  }
-
-  /* Allocate space to store interface data plus adapter names. */
-  uv_address_buf = (uv_interface_address_t*)uv__malloc(uv_address_buf_size);
-  if (uv_address_buf == NULL) {
-    uv__free(win_address_buf);
-    return UV_ENOMEM;
-  }
-
-  /* Compute the start of the uv_interface_address_t array, and the place in
-   * the buffer where the interface names will be stored. */
-  uv_address = uv_address_buf;
-  name_buf = (char*) (uv_address_buf + count);
-
-  /* Fill out the output buffer. */
-  for (adapter = win_address_buf;
-       adapter != NULL;
-       adapter = adapter->Next) {
-    IP_ADAPTER_UNICAST_ADDRESS* unicast_address;
-    int name_size;
-    size_t max_name_size;
-
-    if (adapter->OperStatus != IfOperStatusUp ||
-        adapter->FirstUnicastAddress == NULL)
-      continue;
-
-    /* Convert the interface name to UTF8. */
-    max_name_size = (char*) uv_address_buf + uv_address_buf_size - name_buf;
-    if (max_name_size > (size_t) INT_MAX)
-      max_name_size = INT_MAX;
-    name_size = WideCharToMultiByte(CP_UTF8,
-                                    0,
-                                    adapter->FriendlyName,
-                                    -1,
-                                    name_buf,
-                                    (int) max_name_size,
-                                    NULL,
-                                    FALSE);
-    if (name_size <= 0) {
-      uv__free(win_address_buf);
-      uv__free(uv_address_buf);
-      return uv_translate_sys_error(GetLastError());
-    }
-
-    /* Add an uv_interface_address_t element for every unicast address. */
-    for (unicast_address = (IP_ADAPTER_UNICAST_ADDRESS*)
-                           adapter->FirstUnicastAddress;
-         unicast_address != NULL;
-         unicast_address = unicast_address->Next) {
-      struct sockaddr* sa;
-      ULONG prefix_len;
-
-      sa = unicast_address->Address.lpSockaddr;
-
-      /* XP has no OnLinkPrefixLength field. */
-      if (is_vista_or_greater) {
-        prefix_len =
-          ((IP_ADAPTER_UNICAST_ADDRESS_LH*) unicast_address)->OnLinkPrefixLength;
-      } else {
-        /* Prior to Windows Vista the FirstPrefix pointed to the list with
-         * single prefix for each IP address assigned to the adapter.
-         * Order of FirstPrefix does not match order of FirstUnicastAddress,
-         * so we need to find corresponding prefix.
-         */
-        IP_ADAPTER_PREFIX* prefix;
-        prefix_len = 0;
-
-        for (prefix = adapter->FirstPrefix; prefix; prefix = prefix->Next) {
-          /* We want the longest matching prefix. */
-          if (prefix->Address.lpSockaddr->sa_family != sa->sa_family ||
-              prefix->PrefixLength <= prefix_len)
-            continue;
-
-          if (address_prefix_match(sa->sa_family, sa,
-              prefix->Address.lpSockaddr, prefix->PrefixLength)) {
-            prefix_len = prefix->PrefixLength;
-          }
-        }
-
-        /* If there is no matching prefix information, return a single-host
-         * subnet mask (e.g. 255.255.255.255 for IPv4).
-         */
-        if (!prefix_len)
-          prefix_len = (sa->sa_family == AF_INET6) ? 128 : 32;
-      }
-
-      memset(uv_address, 0, sizeof *uv_address);
-
-      uv_address->name = name_buf;
-
-      if (adapter->PhysicalAddressLength == sizeof(uv_address->phys_addr)) {
-        memcpy(uv_address->phys_addr,
-               adapter->PhysicalAddress,
-               sizeof(uv_address->phys_addr));
-      }
-
-      uv_address->is_internal =
-          (adapter->IfType == IF_TYPE_SOFTWARE_LOOPBACK);
-
-      if (sa->sa_family == AF_INET6) {
-        uv_address->address.address6 = *((struct sockaddr_in6 *) sa);
-
-        uv_address->netmask.netmask6.sin6_family = AF_INET6;
-        memset(uv_address->netmask.netmask6.sin6_addr.s6_addr, 0xff, prefix_len >> 3);
-        /* This check ensures that we don't write past the size of the data. */
-        if (prefix_len % 8) {
-          uv_address->netmask.netmask6.sin6_addr.s6_addr[prefix_len >> 3] =
-              0xff << (8 - prefix_len % 8);
-        }
-
-      } else {
-        uv_address->address.address4 = *((struct sockaddr_in *) sa);
-
-        uv_address->netmask.netmask4.sin_family = AF_INET;
-        uv_address->netmask.netmask4.sin_addr.s_addr = (prefix_len > 0) ?
-            htonl(0xffffffff << (32 - prefix_len)) : 0;
-      }
-
-      uv_address++;
-    }
-
-    name_buf += name_size;
-  }
-
-  uv__free(win_address_buf);
-
-  *addresses_ptr = uv_address_buf;
-  *count_ptr = count;
-
-  return 0;
-}
-
-
-void uv_free_interface_addresses(uv_interface_address_t* addresses,
-    int count) {
-  uv__free(addresses);
-}
-
-
-int uv_getrusage(uv_rusage_t *uv_rusage) {
-  FILETIME createTime, exitTime, kernelTime, userTime;
-  SYSTEMTIME kernelSystemTime, userSystemTime;
-  PROCESS_MEMORY_COUNTERS memCounters;
-  IO_COUNTERS ioCounters;
-  int ret;
-
-  ret = GetProcessTimes(GetCurrentProcess(), &createTime, &exitTime, &kernelTime, &userTime);
-  if (ret == 0) {
-    return uv_translate_sys_error(GetLastError());
-  }
-
-  ret = FileTimeToSystemTime(&kernelTime, &kernelSystemTime);
-  if (ret == 0) {
-    return uv_translate_sys_error(GetLastError());
-  }
-
-  ret = FileTimeToSystemTime(&userTime, &userSystemTime);
-  if (ret == 0) {
-    return uv_translate_sys_error(GetLastError());
-  }
-
-  ret = GetProcessMemoryInfo(GetCurrentProcess(),
-                             &memCounters,
-                             sizeof(memCounters));
-  if (ret == 0) {
-    return uv_translate_sys_error(GetLastError());
-  }
-
-  ret = GetProcessIoCounters(GetCurrentProcess(), &ioCounters);
-  if (ret == 0) {
-    return uv_translate_sys_error(GetLastError());
-  }
-
-  memset(uv_rusage, 0, sizeof(*uv_rusage));
-
-  uv_rusage->ru_utime.tv_sec = userSystemTime.wHour * 3600 +
-                               userSystemTime.wMinute * 60 +
-                               userSystemTime.wSecond;
-  uv_rusage->ru_utime.tv_usec = userSystemTime.wMilliseconds * 1000;
-
-  uv_rusage->ru_stime.tv_sec = kernelSystemTime.wHour * 3600 +
-                               kernelSystemTime.wMinute * 60 +
-                               kernelSystemTime.wSecond;
-  uv_rusage->ru_stime.tv_usec = kernelSystemTime.wMilliseconds * 1000;
-
-  uv_rusage->ru_majflt = (uint64_t) memCounters.PageFaultCount;
-  uv_rusage->ru_maxrss = (uint64_t) memCounters.PeakWorkingSetSize / 1024;
-
-  uv_rusage->ru_oublock = (uint64_t) ioCounters.WriteOperationCount;
-  uv_rusage->ru_inblock = (uint64_t) ioCounters.ReadOperationCount;
-
-  return 0;
-}
-
-
-int uv_os_homedir(char* buffer, size_t* size) {
-  uv_passwd_t pwd;
-  size_t len;
-  int r;
-
-  /* Check if the USERPROFILE environment variable is set first. The task of
-     performing input validation on buffer and size is taken care of by
-     uv_os_getenv(). */
-  r = uv_os_getenv("USERPROFILE", buffer, size);
-
-  /* Don't return an error if USERPROFILE was not found. */
-  if (r != UV_ENOENT)
-    return r;
-
-  /* USERPROFILE is not set, so call uv__getpwuid_r() */
-  r = uv__getpwuid_r(&pwd);
-
-  if (r != 0) {
-    return r;
-  }
-
-  len = strlen(pwd.homedir);
-
-  if (len >= *size) {
-    *size = len + 1;
-    uv_os_free_passwd(&pwd);
-    return UV_ENOBUFS;
-  }
-
-  memcpy(buffer, pwd.homedir, len + 1);
-  *size = len;
-  uv_os_free_passwd(&pwd);
-
-  return 0;
-}
-
-
-int uv_os_tmpdir(char* buffer, size_t* size) {
-  wchar_t path[MAX_PATH + 1];
-  DWORD bufsize;
-  size_t len;
-
-  if (buffer == NULL || size == NULL || *size == 0)
-    return UV_EINVAL;
-
-  len = GetTempPathW(MAX_PATH + 1, path);
-
-  if (len == 0) {
-    return uv_translate_sys_error(GetLastError());
-  } else if (len > MAX_PATH + 1) {
-    /* This should not be possible */
-    return UV_EIO;
-  }
-
-  /* The returned directory should not have a trailing slash, unless it points
-   * at a drive root, like c:\. Remove it if needed. */
-  if (path[len - 1] == L'\\' &&
-      !(len == 3 && path[1] == L':')) {
-    len--;
-    path[len] = L'\0';
-  }
-
-  /* Check how much space we need */
-  bufsize = WideCharToMultiByte(CP_UTF8, 0, path, -1, NULL, 0, NULL, NULL);
-
-  if (bufsize == 0) {
-    return uv_translate_sys_error(GetLastError());
-  } else if (bufsize > *size) {
-    *size = bufsize;
-    return UV_ENOBUFS;
-  }
-
-  /* Convert to UTF-8 */
-  bufsize = WideCharToMultiByte(CP_UTF8,
-                                0,
-                                path,
-                                -1,
-                                buffer,
-                                *size,
-                                NULL,
-                                NULL);
-
-  if (bufsize == 0)
-    return uv_translate_sys_error(GetLastError());
-
-  *size = bufsize - 1;
-  return 0;
-}
-
-
-void uv_os_free_passwd(uv_passwd_t* pwd) {
-  if (pwd == NULL)
-    return;
-
-  uv__free(pwd->username);
-  uv__free(pwd->homedir);
-  pwd->username = NULL;
-  pwd->homedir = NULL;
-}
-
-
-/*
- * Converts a UTF-16 string into a UTF-8 one. The resulting string is
- * null-terminated.
- *
- * If utf16 is null terminated, utf16len can be set to -1, otherwise it must
- * be specified.
- */
-int uv__convert_utf16_to_utf8(const WCHAR* utf16, int utf16len, char** utf8) {
-  DWORD bufsize;
-
-  if (utf16 == NULL)
-    return UV_EINVAL;
-
-  /* Check how much space we need */
-  bufsize = WideCharToMultiByte(CP_UTF8,
-                                0,
-                                utf16,
-                                utf16len,
-                                NULL,
-                                0,
-                                NULL,
-                                NULL);
-
-  if (bufsize == 0)
-    return uv_translate_sys_error(GetLastError());
-
-  /* Allocate the destination buffer adding an extra byte for the terminating
-   * NULL. If utf16len is not -1 WideCharToMultiByte will not add it, so
-   * we do it ourselves always, just in case. */
-  *utf8 = (char*)uv__malloc(bufsize + 1);
-
-  if (*utf8 == NULL)
-    return UV_ENOMEM;
-
-  /* Convert to UTF-8 */
-  bufsize = WideCharToMultiByte(CP_UTF8,
-                                0,
-                                utf16,
-                                utf16len,
-                                *utf8,
-                                bufsize,
-                                NULL,
-                                NULL);
-
-  if (bufsize == 0) {
-    uv__free(*utf8);
-    *utf8 = NULL;
-    return uv_translate_sys_error(GetLastError());
-  }
-
-  (*utf8)[bufsize] = '\0';
-  return 0;
-}
-
-
-/*
- * Converts a UTF-8 string into a UTF-16 one. The resulting string is
- * null-terminated.
- *
- * If utf8 is null terminated, utf8len can be set to -1, otherwise it must
- * be specified.
- */
-int uv__convert_utf8_to_utf16(const char* utf8, int utf8len, WCHAR** utf16) {
-  int bufsize;
-
-  if (utf8 == NULL)
-    return UV_EINVAL;
-
-  /* Check how much space we need */
-  bufsize = MultiByteToWideChar(CP_UTF8, 0, utf8, utf8len, NULL, 0);
-
-  if (bufsize == 0)
-    return uv_translate_sys_error(GetLastError());
-
-  /* Allocate the destination buffer adding an extra byte for the terminating
-   * NULL. If utf8len is not -1 MultiByteToWideChar will not add it, so
-   * we do it ourselves always, just in case. */
-  *utf16 = (WCHAR*)uv__malloc(sizeof(WCHAR) * (bufsize + 1));
-
-  if (*utf16 == NULL)
-    return UV_ENOMEM;
-
-  /* Convert to UTF-16 */
-  bufsize = MultiByteToWideChar(CP_UTF8, 0, utf8, utf8len, *utf16, bufsize);
-
-  if (bufsize == 0) {
-    uv__free(*utf16);
-    *utf16 = NULL;
-    return uv_translate_sys_error(GetLastError());
-  }
-
-  (*utf16)[bufsize] = '\0';
-  return 0;
-}
-
-
-int uv__getpwuid_r(uv_passwd_t* pwd) {
-  HANDLE token;
-  wchar_t username[UNLEN + 1];
-  wchar_t path[MAX_PATH];
-  DWORD bufsize;
-  int r;
-
-  if (pwd == NULL)
-    return UV_EINVAL;
-
-  /* Get the home directory using GetUserProfileDirectoryW() */
-  if (OpenProcessToken(GetCurrentProcess(), TOKEN_READ, &token) == 0)
-    return uv_translate_sys_error(GetLastError());
-
-  bufsize = ARRAY_SIZE(path);
-  if (!GetUserProfileDirectoryW(token, path, &bufsize)) {
-    r = GetLastError();
-    CloseHandle(token);
-
-    /* This should not be possible */
-    if (r == ERROR_INSUFFICIENT_BUFFER)
-      return UV_ENOMEM;
-
-    return uv_translate_sys_error(r);
-  }
-
-  CloseHandle(token);
-
-  /* Get the username using GetUserNameW() */
-  bufsize = ARRAY_SIZE(username);
-  if (!GetUserNameW(username, &bufsize)) {
-    r = GetLastError();
-
-    /* This should not be possible */
-    if (r == ERROR_INSUFFICIENT_BUFFER)
-      return UV_ENOMEM;
-
-    return uv_translate_sys_error(r);
-  }
-
-  pwd->homedir = NULL;
-  r = uv__convert_utf16_to_utf8(path, -1, &pwd->homedir);
-
-  if (r != 0)
-    return r;
-
-  pwd->username = NULL;
-  r = uv__convert_utf16_to_utf8(username, -1, &pwd->username);
-
-  if (r != 0) {
-    uv__free(pwd->homedir);
-    return r;
-  }
-
-  pwd->shell = NULL;
-  pwd->uid = -1;
-  pwd->gid = -1;
-
-  return 0;
-}
-
-
-int uv_os_get_passwd(uv_passwd_t* pwd) {
-  return uv__getpwuid_r(pwd);
-}
-
-
-int uv_os_getenv(const char* name, char* buffer, size_t* size) {
-  wchar_t var[MAX_ENV_VAR_LENGTH];
-  wchar_t* name_w;
-  DWORD bufsize;
-  size_t len;
-  int r;
-
-  if (name == NULL || buffer == NULL || size == NULL || *size == 0)
-    return UV_EINVAL;
-
-  r = uv__convert_utf8_to_utf16(name, -1, &name_w);
-
-  if (r != 0)
-    return r;
-
-  len = GetEnvironmentVariableW(name_w, var, MAX_ENV_VAR_LENGTH);
-  uv__free(name_w);
-  assert(len < MAX_ENV_VAR_LENGTH); /* len does not include the null */
-
-  if (len == 0) {
-    r = GetLastError();
-
-    if (r == ERROR_ENVVAR_NOT_FOUND)
-      return UV_ENOENT;
-
-    return uv_translate_sys_error(r);
-  }
-
-  /* Check how much space we need */
-  bufsize = WideCharToMultiByte(CP_UTF8, 0, var, -1, NULL, 0, NULL, NULL);
-
-  if (bufsize == 0) {
-    return uv_translate_sys_error(GetLastError());
-  } else if (bufsize > *size) {
-    *size = bufsize;
-    return UV_ENOBUFS;
-  }
-
-  /* Convert to UTF-8 */
-  bufsize = WideCharToMultiByte(CP_UTF8,
-                                0,
-                                var,
-                                -1,
-                                buffer,
-                                *size,
-                                NULL,
-                                NULL);
-
-  if (bufsize == 0)
-    return uv_translate_sys_error(GetLastError());
-
-  *size = bufsize - 1;
-  return 0;
-}
-
-
-int uv_os_setenv(const char* name, const char* value) {
-  wchar_t* name_w;
-  wchar_t* value_w;
-  int r;
-
-  if (name == NULL || value == NULL)
-    return UV_EINVAL;
-
-  r = uv__convert_utf8_to_utf16(name, -1, &name_w);
-
-  if (r != 0)
-    return r;
-
-  r = uv__convert_utf8_to_utf16(value, -1, &value_w);
-
-  if (r != 0) {
-    uv__free(name_w);
-    return r;
-  }
-
-  r = SetEnvironmentVariableW(name_w, value_w);
-  uv__free(name_w);
-  uv__free(value_w);
-
-  if (r == 0)
-    return uv_translate_sys_error(GetLastError());
-
-  return 0;
-}
-
-
-int uv_os_unsetenv(const char* name) {
-  wchar_t* name_w;
-  int r;
-
-  if (name == NULL)
-    return UV_EINVAL;
-
-  r = uv__convert_utf8_to_utf16(name, -1, &name_w);
-
-  if (r != 0)
-    return r;
-
-  r = SetEnvironmentVariableW(name_w, NULL);
-  uv__free(name_w);
-
-  if (r == 0)
-    return uv_translate_sys_error(GetLastError());
-
-  return 0;
-}
-
-
-int uv_os_gethostname(char* buffer, size_t* size) {
-  char buf[UV_MAXHOSTNAMESIZE];
-  size_t len;
-
-  if (buffer == NULL || size == NULL || *size == 0)
-    return UV_EINVAL;
-
-  uv__once_init(); /* Initialize winsock */
-
-  if (gethostname(buf, sizeof(buf)) != 0)
-    return uv_translate_sys_error(WSAGetLastError());
-
-  buf[sizeof(buf) - 1] = '\0'; /* Null terminate, just to be safe. */
-  len = strlen(buf);
-
-  if (len >= *size) {
-    *size = len + 1;
-    return UV_ENOBUFS;
-  }
-
-  memcpy(buffer, buf, len + 1);
-  *size = len;
-  return 0;
-}
-
-
-static int uv__get_handle(uv_pid_t pid, int access, HANDLE* handle) {
-  int r;
-
-  if (pid == 0)
-    *handle = GetCurrentProcess();
-  else
-    *handle = OpenProcess(access, FALSE, pid);
-
-  if (*handle == NULL) {
-    r = GetLastError();
-
-    if (r == ERROR_INVALID_PARAMETER)
-      return UV_ESRCH;
-    else
-      return uv_translate_sys_error(r);
-  }
-
-  return 0;
-}
-
-
-int uv_os_getpriority(uv_pid_t pid, int* priority) {
-  HANDLE handle;
-  int r;
-
-  if (priority == NULL)
-    return UV_EINVAL;
-
-  r = uv__get_handle(pid, PROCESS_QUERY_LIMITED_INFORMATION, &handle);
-
-  if (r != 0)
-    return r;
-
-  r = GetPriorityClass(handle);
-
-  if (r == 0) {
-    r = uv_translate_sys_error(GetLastError());
-  } else {
-    /* Map Windows priority classes to Unix nice values. */
-    if (r == REALTIME_PRIORITY_CLASS)
-      *priority = UV_PRIORITY_HIGHEST;
-    else if (r == HIGH_PRIORITY_CLASS)
-      *priority = UV_PRIORITY_HIGH;
-    else if (r == ABOVE_NORMAL_PRIORITY_CLASS)
-      *priority = UV_PRIORITY_ABOVE_NORMAL;
-    else if (r == NORMAL_PRIORITY_CLASS)
-      *priority = UV_PRIORITY_NORMAL;
-    else if (r == BELOW_NORMAL_PRIORITY_CLASS)
-      *priority = UV_PRIORITY_BELOW_NORMAL;
-    else  /* IDLE_PRIORITY_CLASS */
-      *priority = UV_PRIORITY_LOW;
-
-    r = 0;
-  }
-
-  CloseHandle(handle);
-  return r;
-}
-
-
-int uv_os_setpriority(uv_pid_t pid, int priority) {
-  HANDLE handle;
-  int priority_class;
-  int r;
-
-  /* Map Unix nice values to Windows priority classes. */
-  if (priority < UV_PRIORITY_HIGHEST || priority > UV_PRIORITY_LOW)
-    return UV_EINVAL;
-  else if (priority < UV_PRIORITY_HIGH)
-    priority_class = REALTIME_PRIORITY_CLASS;
-  else if (priority < UV_PRIORITY_ABOVE_NORMAL)
-    priority_class = HIGH_PRIORITY_CLASS;
-  else if (priority < UV_PRIORITY_NORMAL)
-    priority_class = ABOVE_NORMAL_PRIORITY_CLASS;
-  else if (priority < UV_PRIORITY_BELOW_NORMAL)
-    priority_class = NORMAL_PRIORITY_CLASS;
-  else if (priority < UV_PRIORITY_LOW)
-    priority_class = BELOW_NORMAL_PRIORITY_CLASS;
-  else
-    priority_class = IDLE_PRIORITY_CLASS;
-
-  r = uv__get_handle(pid, PROCESS_SET_INFORMATION, &handle);
-
-  if (r != 0)
-    return r;
-
-  if (SetPriorityClass(handle, priority_class) == 0)
-    r = uv_translate_sys_error(GetLastError());
-
-  CloseHandle(handle);
-  return r;
-}
-
-
-int uv_os_uname(uv_utsname_t* buffer) {
-  /* Implementation loosely based on
-     https://github.com/gagern/gnulib/blob/master/lib/uname.c */
-  OSVERSIONINFOW os_info;
-  SYSTEM_INFO system_info;
-  HKEY registry_key;
-  WCHAR product_name_w[256];
-  DWORD product_name_w_size;
-  int version_size;
-  int processor_level;
-  int r;
-
-  if (buffer == NULL)
-    return UV_EINVAL;
-
-  uv__once_init();
-  os_info.dwOSVersionInfoSize = sizeof(os_info);
-  os_info.szCSDVersion[0] = L'\0';
-
-  /* Try calling RtlGetVersion(), and fall back to the deprecated GetVersionEx()
-     if RtlGetVersion() is not available. */
-  if (pRtlGetVersion) {
-    pRtlGetVersion(&os_info);
-  } else {
-    /* Silence GetVersionEx() deprecation warning. */
-    #pragma warning(suppress : 4996)
-    if (GetVersionExW(&os_info) == 0) {
-      r = uv_translate_sys_error(GetLastError());
-      goto error;
-    }
-  }
-
-  /* Populate the version field. */
-  version_size = 0;
-  r = RegOpenKeyExW(HKEY_LOCAL_MACHINE,
-                    L"SOFTWARE\\Microsoft\\Windows NT\\CurrentVersion",
-                    0,
-                    KEY_QUERY_VALUE,
-                    &registry_key);
-
-  if (r == ERROR_SUCCESS) {
-    product_name_w_size = sizeof(product_name_w);
-    r = RegGetValueW(registry_key,
-                     NULL,
-                     L"ProductName",
-                     RRF_RT_REG_SZ,
-                     NULL,
-                     (PVOID) product_name_w,
-                     &product_name_w_size);
-    RegCloseKey(registry_key);
-
-    if (r == ERROR_SUCCESS) {
-      version_size = WideCharToMultiByte(CP_UTF8,
-                                         0,
-                                         product_name_w,
-                                         -1,
-                                         buffer->version,
-                                         sizeof(buffer->version),
-                                         NULL,
-                                         NULL);
-      if (version_size == 0) {
-        r = uv_translate_sys_error(GetLastError());
-        goto error;
-      }
-    }
-  }
-
-  /* Append service pack information to the version if present. */
-  if (os_info.szCSDVersion[0] != L'\0') {
-    if (version_size > 0)
-      buffer->version[version_size - 1] = ' ';
-
-    if (WideCharToMultiByte(CP_UTF8,
-                            0,
-                            os_info.szCSDVersion,
-                            -1,
-                            buffer->version + version_size,
-                            sizeof(buffer->version) - version_size,
-                            NULL,
-                            NULL) == 0) {
-      r = uv_translate_sys_error(GetLastError());
-      goto error;
-    }
-  }
-
-  /* Populate the sysname field. */
-#ifdef __MINGW32__
-  r = snprintf(buffer->sysname,
-               sizeof(buffer->sysname),
-               "MINGW32_NT-%u.%u",
-               (unsigned int) os_info.dwMajorVersion,
-               (unsigned int) os_info.dwMinorVersion);
-  assert(r < sizeof(buffer->sysname));
-#else
-  uv__strscpy(buffer->sysname, "Windows_NT", sizeof(buffer->sysname));
-#endif
-
-  /* Populate the release field. */
-  r = snprintf(buffer->release,
-               sizeof(buffer->release),
-               "%d.%d.%d",
-               (unsigned int) os_info.dwMajorVersion,
-               (unsigned int) os_info.dwMinorVersion,
-               (unsigned int) os_info.dwBuildNumber);
-  assert(r < sizeof(buffer->release));
-
-  /* Populate the machine field. */
-  GetSystemInfo(&system_info);
-
-  switch (system_info.wProcessorArchitecture) {
-    case PROCESSOR_ARCHITECTURE_AMD64:
-      uv__strscpy(buffer->machine, "x86_64", sizeof(buffer->machine));
-      break;
-    case PROCESSOR_ARCHITECTURE_IA64:
-      uv__strscpy(buffer->machine, "ia64", sizeof(buffer->machine));
-      break;
-    case PROCESSOR_ARCHITECTURE_INTEL:
-      uv__strscpy(buffer->machine, "i386", sizeof(buffer->machine));
-
-      if (system_info.wProcessorLevel > 3) {
-        processor_level = system_info.wProcessorLevel < 6 ?
-                          system_info.wProcessorLevel : 6;
-        buffer->machine[1] = '0' + processor_level;
-      }
-
-      break;
-    case PROCESSOR_ARCHITECTURE_IA32_ON_WIN64:
-      uv__strscpy(buffer->machine, "i686", sizeof(buffer->machine));
-      break;
-    case PROCESSOR_ARCHITECTURE_MIPS:
-      uv__strscpy(buffer->machine, "mips", sizeof(buffer->machine));
-      break;
-    case PROCESSOR_ARCHITECTURE_ALPHA:
-    case PROCESSOR_ARCHITECTURE_ALPHA64:
-      uv__strscpy(buffer->machine, "alpha", sizeof(buffer->machine));
-      break;
-    case PROCESSOR_ARCHITECTURE_PPC:
-      uv__strscpy(buffer->machine, "powerpc", sizeof(buffer->machine));
-      break;
-    case PROCESSOR_ARCHITECTURE_SHX:
-      uv__strscpy(buffer->machine, "sh", sizeof(buffer->machine));
-      break;
-    case PROCESSOR_ARCHITECTURE_ARM:
-      uv__strscpy(buffer->machine, "arm", sizeof(buffer->machine));
-      break;
-    default:
-      uv__strscpy(buffer->machine, "unknown", sizeof(buffer->machine));
-      break;
-  }
-
-  return 0;
-
-error:
-  buffer->sysname[0] = '\0';
-  buffer->release[0] = '\0';
-  buffer->version[0] = '\0';
-  buffer->machine[0] = '\0';
-  return r;
-}
-
-int uv_gettimeofday(uv_timeval64_t* tv) {
-  /* Based on https://doxygen.postgresql.org/gettimeofday_8c_source.html */
-  const uint64_t epoch = (uint64_t) 116444736000000000ULL;
-  FILETIME file_time;
-  ULARGE_INTEGER ularge;
-
-  if (tv == NULL)
-    return UV_EINVAL;
-
-  GetSystemTimeAsFileTime(&file_time);
-  ularge.LowPart = file_time.dwLowDateTime;
-  ularge.HighPart = file_time.dwHighDateTime;
-  tv->tv_sec = (int64_t) ((ularge.QuadPart - epoch) / 10000000L);
-  tv->tv_usec = (int32_t) (((ularge.QuadPart - epoch) % 10000000L) / 10);
-  return 0;
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/winapi.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/winapi.cpp
deleted file mode 100644
index fbbbcee..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/winapi.cpp
+++ /dev/null
@@ -1,130 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include <assert.h>
-
-#include "uv.h"
-#include "internal.h"
-
-
-/* Ntdll function pointers */
-sRtlGetVersion pRtlGetVersion;
-sRtlNtStatusToDosError pRtlNtStatusToDosError;
-sNtDeviceIoControlFile pNtDeviceIoControlFile;
-sNtQueryInformationFile pNtQueryInformationFile;
-sNtSetInformationFile pNtSetInformationFile;
-sNtQueryVolumeInformationFile pNtQueryVolumeInformationFile;
-sNtQueryDirectoryFile pNtQueryDirectoryFile;
-sNtQuerySystemInformation pNtQuerySystemInformation;
-
-/* Kernel32 function pointers */
-sGetQueuedCompletionStatusEx pGetQueuedCompletionStatusEx;
-
-/* Powrprof.dll function pointer */
-sPowerRegisterSuspendResumeNotification pPowerRegisterSuspendResumeNotification;
-
-/* User32.dll function pointer */
-sSetWinEventHook pSetWinEventHook;
-
-
-void uv_winapi_init(void) {
-  HMODULE ntdll_module;
-  HMODULE powrprof_module;
-  HMODULE user32_module;
-  HMODULE kernel32_module;
-
-  ntdll_module = GetModuleHandleA("ntdll.dll");
-  if (ntdll_module == NULL) {
-    uv_fatal_error(GetLastError(), "GetModuleHandleA");
-  }
-
-  pRtlGetVersion = (sRtlGetVersion) GetProcAddress(ntdll_module,
-                                                   "RtlGetVersion");
-
-  pRtlNtStatusToDosError = (sRtlNtStatusToDosError) GetProcAddress(
-      ntdll_module,
-      "RtlNtStatusToDosError");
-  if (pRtlNtStatusToDosError == NULL) {
-    uv_fatal_error(GetLastError(), "GetProcAddress");
-  }
-
-  pNtDeviceIoControlFile = (sNtDeviceIoControlFile) GetProcAddress(
-      ntdll_module,
-      "NtDeviceIoControlFile");
-  if (pNtDeviceIoControlFile == NULL) {
-    uv_fatal_error(GetLastError(), "GetProcAddress");
-  }
-
-  pNtQueryInformationFile = (sNtQueryInformationFile) GetProcAddress(
-      ntdll_module,
-      "NtQueryInformationFile");
-  if (pNtQueryInformationFile == NULL) {
-    uv_fatal_error(GetLastError(), "GetProcAddress");
-  }
-
-  pNtSetInformationFile = (sNtSetInformationFile) GetProcAddress(
-      ntdll_module,
-      "NtSetInformationFile");
-  if (pNtSetInformationFile == NULL) {
-    uv_fatal_error(GetLastError(), "GetProcAddress");
-  }
-
-  pNtQueryVolumeInformationFile = (sNtQueryVolumeInformationFile)
-      GetProcAddress(ntdll_module, "NtQueryVolumeInformationFile");
-  if (pNtQueryVolumeInformationFile == NULL) {
-    uv_fatal_error(GetLastError(), "GetProcAddress");
-  }
-
-  pNtQueryDirectoryFile = (sNtQueryDirectoryFile)
-      GetProcAddress(ntdll_module, "NtQueryDirectoryFile");
-  if (pNtQueryVolumeInformationFile == NULL) {
-    uv_fatal_error(GetLastError(), "GetProcAddress");
-  }
-
-  pNtQuerySystemInformation = (sNtQuerySystemInformation) GetProcAddress(
-      ntdll_module,
-      "NtQuerySystemInformation");
-  if (pNtQuerySystemInformation == NULL) {
-    uv_fatal_error(GetLastError(), "GetProcAddress");
-  }
-
-  kernel32_module = GetModuleHandleA("kernel32.dll");
-  if (kernel32_module == NULL) {
-    uv_fatal_error(GetLastError(), "GetModuleHandleA");
-  }
-
-  pGetQueuedCompletionStatusEx = (sGetQueuedCompletionStatusEx) GetProcAddress(
-      kernel32_module,
-      "GetQueuedCompletionStatusEx");
-
-  powrprof_module = LoadLibraryA("powrprof.dll");
-  if (powrprof_module != NULL) {
-    pPowerRegisterSuspendResumeNotification = (sPowerRegisterSuspendResumeNotification)
-      GetProcAddress(powrprof_module, "PowerRegisterSuspendResumeNotification");
-  }
-
-  user32_module = LoadLibraryA("user32.dll");
-  if (user32_module != NULL) {
-    pSetWinEventHook = (sSetWinEventHook)
-      GetProcAddress(user32_module, "SetWinEventHook");
-  }
-
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/winapi.h b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/winapi.h
deleted file mode 100644
index 82c5ed4..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/winapi.h
+++ /dev/null
@@ -1,4731 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#ifndef UV_WIN_WINAPI_H_
-#define UV_WIN_WINAPI_H_
-
-#include <windows.h>
-
-
-/*
- * Ntdll headers
- */
-#ifndef STATUS_SEVERITY_SUCCESS
-# define STATUS_SEVERITY_SUCCESS 0x0
-#endif
-
-#ifndef STATUS_SEVERITY_INFORMATIONAL
-# define STATUS_SEVERITY_INFORMATIONAL 0x1
-#endif
-
-#ifndef STATUS_SEVERITY_WARNING
-# define STATUS_SEVERITY_WARNING 0x2
-#endif
-
-#ifndef STATUS_SEVERITY_ERROR
-# define STATUS_SEVERITY_ERROR 0x3
-#endif
-
-#ifndef FACILITY_NTWIN32
-# define FACILITY_NTWIN32 0x7
-#endif
-
-#ifndef NT_SUCCESS
-# define NT_SUCCESS(status) (((NTSTATUS) (status)) >= 0)
-#endif
-
-#ifndef NT_INFORMATION
-# define NT_INFORMATION(status) ((((ULONG) (status)) >> 30) == 1)
-#endif
-
-#ifndef NT_WARNING
-# define NT_WARNING(status) ((((ULONG) (status)) >> 30) == 2)
-#endif
-
-#ifndef NT_ERROR
-# define NT_ERROR(status) ((((ULONG) (status)) >> 30) == 3)
-#endif
-
-#ifndef STATUS_SUCCESS
-# define STATUS_SUCCESS ((NTSTATUS) 0x00000000L)
-#endif
-
-#ifndef STATUS_WAIT_0
-# define STATUS_WAIT_0 ((NTSTATUS) 0x00000000L)
-#endif
-
-#ifndef STATUS_WAIT_1
-# define STATUS_WAIT_1 ((NTSTATUS) 0x00000001L)
-#endif
-
-#ifndef STATUS_WAIT_2
-# define STATUS_WAIT_2 ((NTSTATUS) 0x00000002L)
-#endif
-
-#ifndef STATUS_WAIT_3
-# define STATUS_WAIT_3 ((NTSTATUS) 0x00000003L)
-#endif
-
-#ifndef STATUS_WAIT_63
-# define STATUS_WAIT_63 ((NTSTATUS) 0x0000003FL)
-#endif
-
-#ifndef STATUS_ABANDONED
-# define STATUS_ABANDONED ((NTSTATUS) 0x00000080L)
-#endif
-
-#ifndef STATUS_ABANDONED_WAIT_0
-# define STATUS_ABANDONED_WAIT_0 ((NTSTATUS) 0x00000080L)
-#endif
-
-#ifndef STATUS_ABANDONED_WAIT_63
-# define STATUS_ABANDONED_WAIT_63 ((NTSTATUS) 0x000000BFL)
-#endif
-
-#ifndef STATUS_USER_APC
-# define STATUS_USER_APC ((NTSTATUS) 0x000000C0L)
-#endif
-
-#ifndef STATUS_KERNEL_APC
-# define STATUS_KERNEL_APC ((NTSTATUS) 0x00000100L)
-#endif
-
-#ifndef STATUS_ALERTED
-# define STATUS_ALERTED ((NTSTATUS) 0x00000101L)
-#endif
-
-#ifndef STATUS_TIMEOUT
-# define STATUS_TIMEOUT ((NTSTATUS) 0x00000102L)
-#endif
-
-#ifndef STATUS_PENDING
-# define STATUS_PENDING ((NTSTATUS) 0x00000103L)
-#endif
-
-#ifndef STATUS_REPARSE
-# define STATUS_REPARSE ((NTSTATUS) 0x00000104L)
-#endif
-
-#ifndef STATUS_MORE_ENTRIES
-# define STATUS_MORE_ENTRIES ((NTSTATUS) 0x00000105L)
-#endif
-
-#ifndef STATUS_NOT_ALL_ASSIGNED
-# define STATUS_NOT_ALL_ASSIGNED ((NTSTATUS) 0x00000106L)
-#endif
-
-#ifndef STATUS_SOME_NOT_MAPPED
-# define STATUS_SOME_NOT_MAPPED ((NTSTATUS) 0x00000107L)
-#endif
-
-#ifndef STATUS_OPLOCK_BREAK_IN_PROGRESS
-# define STATUS_OPLOCK_BREAK_IN_PROGRESS ((NTSTATUS) 0x00000108L)
-#endif
-
-#ifndef STATUS_VOLUME_MOUNTED
-# define STATUS_VOLUME_MOUNTED ((NTSTATUS) 0x00000109L)
-#endif
-
-#ifndef STATUS_RXACT_COMMITTED
-# define STATUS_RXACT_COMMITTED ((NTSTATUS) 0x0000010AL)
-#endif
-
-#ifndef STATUS_NOTIFY_CLEANUP
-# define STATUS_NOTIFY_CLEANUP ((NTSTATUS) 0x0000010BL)
-#endif
-
-#ifndef STATUS_NOTIFY_ENUM_DIR
-# define STATUS_NOTIFY_ENUM_DIR ((NTSTATUS) 0x0000010CL)
-#endif
-
-#ifndef STATUS_NO_QUOTAS_FOR_ACCOUNT
-# define STATUS_NO_QUOTAS_FOR_ACCOUNT ((NTSTATUS) 0x0000010DL)
-#endif
-
-#ifndef STATUS_PRIMARY_TRANSPORT_CONNECT_FAILED
-# define STATUS_PRIMARY_TRANSPORT_CONNECT_FAILED ((NTSTATUS) 0x0000010EL)
-#endif
-
-#ifndef STATUS_PAGE_FAULT_TRANSITION
-# define STATUS_PAGE_FAULT_TRANSITION ((NTSTATUS) 0x00000110L)
-#endif
-
-#ifndef STATUS_PAGE_FAULT_DEMAND_ZERO
-# define STATUS_PAGE_FAULT_DEMAND_ZERO ((NTSTATUS) 0x00000111L)
-#endif
-
-#ifndef STATUS_PAGE_FAULT_COPY_ON_WRITE
-# define STATUS_PAGE_FAULT_COPY_ON_WRITE ((NTSTATUS) 0x00000112L)
-#endif
-
-#ifndef STATUS_PAGE_FAULT_GUARD_PAGE
-# define STATUS_PAGE_FAULT_GUARD_PAGE ((NTSTATUS) 0x00000113L)
-#endif
-
-#ifndef STATUS_PAGE_FAULT_PAGING_FILE
-# define STATUS_PAGE_FAULT_PAGING_FILE ((NTSTATUS) 0x00000114L)
-#endif
-
-#ifndef STATUS_CACHE_PAGE_LOCKED
-# define STATUS_CACHE_PAGE_LOCKED ((NTSTATUS) 0x00000115L)
-#endif
-
-#ifndef STATUS_CRASH_DUMP
-# define STATUS_CRASH_DUMP ((NTSTATUS) 0x00000116L)
-#endif
-
-#ifndef STATUS_BUFFER_ALL_ZEROS
-# define STATUS_BUFFER_ALL_ZEROS ((NTSTATUS) 0x00000117L)
-#endif
-
-#ifndef STATUS_REPARSE_OBJECT
-# define STATUS_REPARSE_OBJECT ((NTSTATUS) 0x00000118L)
-#endif
-
-#ifndef STATUS_RESOURCE_REQUIREMENTS_CHANGED
-# define STATUS_RESOURCE_REQUIREMENTS_CHANGED ((NTSTATUS) 0x00000119L)
-#endif
-
-#ifndef STATUS_TRANSLATION_COMPLETE
-# define STATUS_TRANSLATION_COMPLETE ((NTSTATUS) 0x00000120L)
-#endif
-
-#ifndef STATUS_DS_MEMBERSHIP_EVALUATED_LOCALLY
-# define STATUS_DS_MEMBERSHIP_EVALUATED_LOCALLY ((NTSTATUS) 0x00000121L)
-#endif
-
-#ifndef STATUS_NOTHING_TO_TERMINATE
-# define STATUS_NOTHING_TO_TERMINATE ((NTSTATUS) 0x00000122L)
-#endif
-
-#ifndef STATUS_PROCESS_NOT_IN_JOB
-# define STATUS_PROCESS_NOT_IN_JOB ((NTSTATUS) 0x00000123L)
-#endif
-
-#ifndef STATUS_PROCESS_IN_JOB
-# define STATUS_PROCESS_IN_JOB ((NTSTATUS) 0x00000124L)
-#endif
-
-#ifndef STATUS_VOLSNAP_HIBERNATE_READY
-# define STATUS_VOLSNAP_HIBERNATE_READY ((NTSTATUS) 0x00000125L)
-#endif
-
-#ifndef STATUS_FSFILTER_OP_COMPLETED_SUCCESSFULLY
-# define STATUS_FSFILTER_OP_COMPLETED_SUCCESSFULLY ((NTSTATUS) 0x00000126L)
-#endif
-
-#ifndef STATUS_INTERRUPT_VECTOR_ALREADY_CONNECTED
-# define STATUS_INTERRUPT_VECTOR_ALREADY_CONNECTED ((NTSTATUS) 0x00000127L)
-#endif
-
-#ifndef STATUS_INTERRUPT_STILL_CONNECTED
-# define STATUS_INTERRUPT_STILL_CONNECTED ((NTSTATUS) 0x00000128L)
-#endif
-
-#ifndef STATUS_PROCESS_CLONED
-# define STATUS_PROCESS_CLONED ((NTSTATUS) 0x00000129L)
-#endif
-
-#ifndef STATUS_FILE_LOCKED_WITH_ONLY_READERS
-# define STATUS_FILE_LOCKED_WITH_ONLY_READERS ((NTSTATUS) 0x0000012AL)
-#endif
-
-#ifndef STATUS_FILE_LOCKED_WITH_WRITERS
-# define STATUS_FILE_LOCKED_WITH_WRITERS ((NTSTATUS) 0x0000012BL)
-#endif
-
-#ifndef STATUS_RESOURCEMANAGER_READ_ONLY
-# define STATUS_RESOURCEMANAGER_READ_ONLY ((NTSTATUS) 0x00000202L)
-#endif
-
-#ifndef STATUS_RING_PREVIOUSLY_EMPTY
-# define STATUS_RING_PREVIOUSLY_EMPTY ((NTSTATUS) 0x00000210L)
-#endif
-
-#ifndef STATUS_RING_PREVIOUSLY_FULL
-# define STATUS_RING_PREVIOUSLY_FULL ((NTSTATUS) 0x00000211L)
-#endif
-
-#ifndef STATUS_RING_PREVIOUSLY_ABOVE_QUOTA
-# define STATUS_RING_PREVIOUSLY_ABOVE_QUOTA ((NTSTATUS) 0x00000212L)
-#endif
-
-#ifndef STATUS_RING_NEWLY_EMPTY
-# define STATUS_RING_NEWLY_EMPTY ((NTSTATUS) 0x00000213L)
-#endif
-
-#ifndef STATUS_RING_SIGNAL_OPPOSITE_ENDPOINT
-# define STATUS_RING_SIGNAL_OPPOSITE_ENDPOINT ((NTSTATUS) 0x00000214L)
-#endif
-
-#ifndef STATUS_OPLOCK_SWITCHED_TO_NEW_HANDLE
-# define STATUS_OPLOCK_SWITCHED_TO_NEW_HANDLE ((NTSTATUS) 0x00000215L)
-#endif
-
-#ifndef STATUS_OPLOCK_HANDLE_CLOSED
-# define STATUS_OPLOCK_HANDLE_CLOSED ((NTSTATUS) 0x00000216L)
-#endif
-
-#ifndef STATUS_WAIT_FOR_OPLOCK
-# define STATUS_WAIT_FOR_OPLOCK ((NTSTATUS) 0x00000367L)
-#endif
-
-#ifndef STATUS_OBJECT_NAME_EXISTS
-# define STATUS_OBJECT_NAME_EXISTS ((NTSTATUS) 0x40000000L)
-#endif
-
-#ifndef STATUS_THREAD_WAS_SUSPENDED
-# define STATUS_THREAD_WAS_SUSPENDED ((NTSTATUS) 0x40000001L)
-#endif
-
-#ifndef STATUS_WORKING_SET_LIMIT_RANGE
-# define STATUS_WORKING_SET_LIMIT_RANGE ((NTSTATUS) 0x40000002L)
-#endif
-
-#ifndef STATUS_IMAGE_NOT_AT_BASE
-# define STATUS_IMAGE_NOT_AT_BASE ((NTSTATUS) 0x40000003L)
-#endif
-
-#ifndef STATUS_RXACT_STATE_CREATED
-# define STATUS_RXACT_STATE_CREATED ((NTSTATUS) 0x40000004L)
-#endif
-
-#ifndef STATUS_SEGMENT_NOTIFICATION
-# define STATUS_SEGMENT_NOTIFICATION ((NTSTATUS) 0x40000005L)
-#endif
-
-#ifndef STATUS_LOCAL_USER_SESSION_KEY
-# define STATUS_LOCAL_USER_SESSION_KEY ((NTSTATUS) 0x40000006L)
-#endif
-
-#ifndef STATUS_BAD_CURRENT_DIRECTORY
-# define STATUS_BAD_CURRENT_DIRECTORY ((NTSTATUS) 0x40000007L)
-#endif
-
-#ifndef STATUS_SERIAL_MORE_WRITES
-# define STATUS_SERIAL_MORE_WRITES ((NTSTATUS) 0x40000008L)
-#endif
-
-#ifndef STATUS_REGISTRY_RECOVERED
-# define STATUS_REGISTRY_RECOVERED ((NTSTATUS) 0x40000009L)
-#endif
-
-#ifndef STATUS_FT_READ_RECOVERY_FROM_BACKUP
-# define STATUS_FT_READ_RECOVERY_FROM_BACKUP ((NTSTATUS) 0x4000000AL)
-#endif
-
-#ifndef STATUS_FT_WRITE_RECOVERY
-# define STATUS_FT_WRITE_RECOVERY ((NTSTATUS) 0x4000000BL)
-#endif
-
-#ifndef STATUS_SERIAL_COUNTER_TIMEOUT
-# define STATUS_SERIAL_COUNTER_TIMEOUT ((NTSTATUS) 0x4000000CL)
-#endif
-
-#ifndef STATUS_NULL_LM_PASSWORD
-# define STATUS_NULL_LM_PASSWORD ((NTSTATUS) 0x4000000DL)
-#endif
-
-#ifndef STATUS_IMAGE_MACHINE_TYPE_MISMATCH
-# define STATUS_IMAGE_MACHINE_TYPE_MISMATCH ((NTSTATUS) 0x4000000EL)
-#endif
-
-#ifndef STATUS_RECEIVE_PARTIAL
-# define STATUS_RECEIVE_PARTIAL ((NTSTATUS) 0x4000000FL)
-#endif
-
-#ifndef STATUS_RECEIVE_EXPEDITED
-# define STATUS_RECEIVE_EXPEDITED ((NTSTATUS) 0x40000010L)
-#endif
-
-#ifndef STATUS_RECEIVE_PARTIAL_EXPEDITED
-# define STATUS_RECEIVE_PARTIAL_EXPEDITED ((NTSTATUS) 0x40000011L)
-#endif
-
-#ifndef STATUS_EVENT_DONE
-# define STATUS_EVENT_DONE ((NTSTATUS) 0x40000012L)
-#endif
-
-#ifndef STATUS_EVENT_PENDING
-# define STATUS_EVENT_PENDING ((NTSTATUS) 0x40000013L)
-#endif
-
-#ifndef STATUS_CHECKING_FILE_SYSTEM
-# define STATUS_CHECKING_FILE_SYSTEM ((NTSTATUS) 0x40000014L)
-#endif
-
-#ifndef STATUS_FATAL_APP_EXIT
-# define STATUS_FATAL_APP_EXIT ((NTSTATUS) 0x40000015L)
-#endif
-
-#ifndef STATUS_PREDEFINED_HANDLE
-# define STATUS_PREDEFINED_HANDLE ((NTSTATUS) 0x40000016L)
-#endif
-
-#ifndef STATUS_WAS_UNLOCKED
-# define STATUS_WAS_UNLOCKED ((NTSTATUS) 0x40000017L)
-#endif
-
-#ifndef STATUS_SERVICE_NOTIFICATION
-# define STATUS_SERVICE_NOTIFICATION ((NTSTATUS) 0x40000018L)
-#endif
-
-#ifndef STATUS_WAS_LOCKED
-# define STATUS_WAS_LOCKED ((NTSTATUS) 0x40000019L)
-#endif
-
-#ifndef STATUS_LOG_HARD_ERROR
-# define STATUS_LOG_HARD_ERROR ((NTSTATUS) 0x4000001AL)
-#endif
-
-#ifndef STATUS_ALREADY_WIN32
-# define STATUS_ALREADY_WIN32 ((NTSTATUS) 0x4000001BL)
-#endif
-
-#ifndef STATUS_WX86_UNSIMULATE
-# define STATUS_WX86_UNSIMULATE ((NTSTATUS) 0x4000001CL)
-#endif
-
-#ifndef STATUS_WX86_CONTINUE
-# define STATUS_WX86_CONTINUE ((NTSTATUS) 0x4000001DL)
-#endif
-
-#ifndef STATUS_WX86_SINGLE_STEP
-# define STATUS_WX86_SINGLE_STEP ((NTSTATUS) 0x4000001EL)
-#endif
-
-#ifndef STATUS_WX86_BREAKPOINT
-# define STATUS_WX86_BREAKPOINT ((NTSTATUS) 0x4000001FL)
-#endif
-
-#ifndef STATUS_WX86_EXCEPTION_CONTINUE
-# define STATUS_WX86_EXCEPTION_CONTINUE ((NTSTATUS) 0x40000020L)
-#endif
-
-#ifndef STATUS_WX86_EXCEPTION_LASTCHANCE
-# define STATUS_WX86_EXCEPTION_LASTCHANCE ((NTSTATUS) 0x40000021L)
-#endif
-
-#ifndef STATUS_WX86_EXCEPTION_CHAIN
-# define STATUS_WX86_EXCEPTION_CHAIN ((NTSTATUS) 0x40000022L)
-#endif
-
-#ifndef STATUS_IMAGE_MACHINE_TYPE_MISMATCH_EXE
-# define STATUS_IMAGE_MACHINE_TYPE_MISMATCH_EXE ((NTSTATUS) 0x40000023L)
-#endif
-
-#ifndef STATUS_NO_YIELD_PERFORMED
-# define STATUS_NO_YIELD_PERFORMED ((NTSTATUS) 0x40000024L)
-#endif
-
-#ifndef STATUS_TIMER_RESUME_IGNORED
-# define STATUS_TIMER_RESUME_IGNORED ((NTSTATUS) 0x40000025L)
-#endif
-
-#ifndef STATUS_ARBITRATION_UNHANDLED
-# define STATUS_ARBITRATION_UNHANDLED ((NTSTATUS) 0x40000026L)
-#endif
-
-#ifndef STATUS_CARDBUS_NOT_SUPPORTED
-# define STATUS_CARDBUS_NOT_SUPPORTED ((NTSTATUS) 0x40000027L)
-#endif
-
-#ifndef STATUS_WX86_CREATEWX86TIB
-# define STATUS_WX86_CREATEWX86TIB ((NTSTATUS) 0x40000028L)
-#endif
-
-#ifndef STATUS_MP_PROCESSOR_MISMATCH
-# define STATUS_MP_PROCESSOR_MISMATCH ((NTSTATUS) 0x40000029L)
-#endif
-
-#ifndef STATUS_HIBERNATED
-# define STATUS_HIBERNATED ((NTSTATUS) 0x4000002AL)
-#endif
-
-#ifndef STATUS_RESUME_HIBERNATION
-# define STATUS_RESUME_HIBERNATION ((NTSTATUS) 0x4000002BL)
-#endif
-
-#ifndef STATUS_FIRMWARE_UPDATED
-# define STATUS_FIRMWARE_UPDATED ((NTSTATUS) 0x4000002CL)
-#endif
-
-#ifndef STATUS_DRIVERS_LEAKING_LOCKED_PAGES
-# define STATUS_DRIVERS_LEAKING_LOCKED_PAGES ((NTSTATUS) 0x4000002DL)
-#endif
-
-#ifndef STATUS_MESSAGE_RETRIEVED
-# define STATUS_MESSAGE_RETRIEVED ((NTSTATUS) 0x4000002EL)
-#endif
-
-#ifndef STATUS_SYSTEM_POWERSTATE_TRANSITION
-# define STATUS_SYSTEM_POWERSTATE_TRANSITION ((NTSTATUS) 0x4000002FL)
-#endif
-
-#ifndef STATUS_ALPC_CHECK_COMPLETION_LIST
-# define STATUS_ALPC_CHECK_COMPLETION_LIST ((NTSTATUS) 0x40000030L)
-#endif
-
-#ifndef STATUS_SYSTEM_POWERSTATE_COMPLEX_TRANSITION
-# define STATUS_SYSTEM_POWERSTATE_COMPLEX_TRANSITION ((NTSTATUS) 0x40000031L)
-#endif
-
-#ifndef STATUS_ACCESS_AUDIT_BY_POLICY
-# define STATUS_ACCESS_AUDIT_BY_POLICY ((NTSTATUS) 0x40000032L)
-#endif
-
-#ifndef STATUS_ABANDON_HIBERFILE
-# define STATUS_ABANDON_HIBERFILE ((NTSTATUS) 0x40000033L)
-#endif
-
-#ifndef STATUS_BIZRULES_NOT_ENABLED
-# define STATUS_BIZRULES_NOT_ENABLED ((NTSTATUS) 0x40000034L)
-#endif
-
-#ifndef STATUS_GUARD_PAGE_VIOLATION
-# define STATUS_GUARD_PAGE_VIOLATION ((NTSTATUS) 0x80000001L)
-#endif
-
-#ifndef STATUS_DATATYPE_MISALIGNMENT
-# define STATUS_DATATYPE_MISALIGNMENT ((NTSTATUS) 0x80000002L)
-#endif
-
-#ifndef STATUS_BREAKPOINT
-# define STATUS_BREAKPOINT ((NTSTATUS) 0x80000003L)
-#endif
-
-#ifndef STATUS_SINGLE_STEP
-# define STATUS_SINGLE_STEP ((NTSTATUS) 0x80000004L)
-#endif
-
-#ifndef STATUS_BUFFER_OVERFLOW
-# define STATUS_BUFFER_OVERFLOW ((NTSTATUS) 0x80000005L)
-#endif
-
-#ifndef STATUS_NO_MORE_FILES
-# define STATUS_NO_MORE_FILES ((NTSTATUS) 0x80000006L)
-#endif
-
-#ifndef STATUS_WAKE_SYSTEM_DEBUGGER
-# define STATUS_WAKE_SYSTEM_DEBUGGER ((NTSTATUS) 0x80000007L)
-#endif
-
-#ifndef STATUS_HANDLES_CLOSED
-# define STATUS_HANDLES_CLOSED ((NTSTATUS) 0x8000000AL)
-#endif
-
-#ifndef STATUS_NO_INHERITANCE
-# define STATUS_NO_INHERITANCE ((NTSTATUS) 0x8000000BL)
-#endif
-
-#ifndef STATUS_GUID_SUBSTITUTION_MADE
-# define STATUS_GUID_SUBSTITUTION_MADE ((NTSTATUS) 0x8000000CL)
-#endif
-
-#ifndef STATUS_PARTIAL_COPY
-# define STATUS_PARTIAL_COPY ((NTSTATUS) 0x8000000DL)
-#endif
-
-#ifndef STATUS_DEVICE_PAPER_EMPTY
-# define STATUS_DEVICE_PAPER_EMPTY ((NTSTATUS) 0x8000000EL)
-#endif
-
-#ifndef STATUS_DEVICE_POWERED_OFF
-# define STATUS_DEVICE_POWERED_OFF ((NTSTATUS) 0x8000000FL)
-#endif
-
-#ifndef STATUS_DEVICE_OFF_LINE
-# define STATUS_DEVICE_OFF_LINE ((NTSTATUS) 0x80000010L)
-#endif
-
-#ifndef STATUS_DEVICE_BUSY
-# define STATUS_DEVICE_BUSY ((NTSTATUS) 0x80000011L)
-#endif
-
-#ifndef STATUS_NO_MORE_EAS
-# define STATUS_NO_MORE_EAS ((NTSTATUS) 0x80000012L)
-#endif
-
-#ifndef STATUS_INVALID_EA_NAME
-# define STATUS_INVALID_EA_NAME ((NTSTATUS) 0x80000013L)
-#endif
-
-#ifndef STATUS_EA_LIST_INCONSISTENT
-# define STATUS_EA_LIST_INCONSISTENT ((NTSTATUS) 0x80000014L)
-#endif
-
-#ifndef STATUS_INVALID_EA_FLAG
-# define STATUS_INVALID_EA_FLAG ((NTSTATUS) 0x80000015L)
-#endif
-
-#ifndef STATUS_VERIFY_REQUIRED
-# define STATUS_VERIFY_REQUIRED ((NTSTATUS) 0x80000016L)
-#endif
-
-#ifndef STATUS_EXTRANEOUS_INFORMATION
-# define STATUS_EXTRANEOUS_INFORMATION ((NTSTATUS) 0x80000017L)
-#endif
-
-#ifndef STATUS_RXACT_COMMIT_NECESSARY
-# define STATUS_RXACT_COMMIT_NECESSARY ((NTSTATUS) 0x80000018L)
-#endif
-
-#ifndef STATUS_NO_MORE_ENTRIES
-# define STATUS_NO_MORE_ENTRIES ((NTSTATUS) 0x8000001AL)
-#endif
-
-#ifndef STATUS_FILEMARK_DETECTED
-# define STATUS_FILEMARK_DETECTED ((NTSTATUS) 0x8000001BL)
-#endif
-
-#ifndef STATUS_MEDIA_CHANGED
-# define STATUS_MEDIA_CHANGED ((NTSTATUS) 0x8000001CL)
-#endif
-
-#ifndef STATUS_BUS_RESET
-# define STATUS_BUS_RESET ((NTSTATUS) 0x8000001DL)
-#endif
-
-#ifndef STATUS_END_OF_MEDIA
-# define STATUS_END_OF_MEDIA ((NTSTATUS) 0x8000001EL)
-#endif
-
-#ifndef STATUS_BEGINNING_OF_MEDIA
-# define STATUS_BEGINNING_OF_MEDIA ((NTSTATUS) 0x8000001FL)
-#endif
-
-#ifndef STATUS_MEDIA_CHECK
-# define STATUS_MEDIA_CHECK ((NTSTATUS) 0x80000020L)
-#endif
-
-#ifndef STATUS_SETMARK_DETECTED
-# define STATUS_SETMARK_DETECTED ((NTSTATUS) 0x80000021L)
-#endif
-
-#ifndef STATUS_NO_DATA_DETECTED
-# define STATUS_NO_DATA_DETECTED ((NTSTATUS) 0x80000022L)
-#endif
-
-#ifndef STATUS_REDIRECTOR_HAS_OPEN_HANDLES
-# define STATUS_REDIRECTOR_HAS_OPEN_HANDLES ((NTSTATUS) 0x80000023L)
-#endif
-
-#ifndef STATUS_SERVER_HAS_OPEN_HANDLES
-# define STATUS_SERVER_HAS_OPEN_HANDLES ((NTSTATUS) 0x80000024L)
-#endif
-
-#ifndef STATUS_ALREADY_DISCONNECTED
-# define STATUS_ALREADY_DISCONNECTED ((NTSTATUS) 0x80000025L)
-#endif
-
-#ifndef STATUS_LONGJUMP
-# define STATUS_LONGJUMP ((NTSTATUS) 0x80000026L)
-#endif
-
-#ifndef STATUS_CLEANER_CARTRIDGE_INSTALLED
-# define STATUS_CLEANER_CARTRIDGE_INSTALLED ((NTSTATUS) 0x80000027L)
-#endif
-
-#ifndef STATUS_PLUGPLAY_QUERY_VETOED
-# define STATUS_PLUGPLAY_QUERY_VETOED ((NTSTATUS) 0x80000028L)
-#endif
-
-#ifndef STATUS_UNWIND_CONSOLIDATE
-# define STATUS_UNWIND_CONSOLIDATE ((NTSTATUS) 0x80000029L)
-#endif
-
-#ifndef STATUS_REGISTRY_HIVE_RECOVERED
-# define STATUS_REGISTRY_HIVE_RECOVERED ((NTSTATUS) 0x8000002AL)
-#endif
-
-#ifndef STATUS_DLL_MIGHT_BE_INSECURE
-# define STATUS_DLL_MIGHT_BE_INSECURE ((NTSTATUS) 0x8000002BL)
-#endif
-
-#ifndef STATUS_DLL_MIGHT_BE_INCOMPATIBLE
-# define STATUS_DLL_MIGHT_BE_INCOMPATIBLE ((NTSTATUS) 0x8000002CL)
-#endif
-
-#ifndef STATUS_STOPPED_ON_SYMLINK
-# define STATUS_STOPPED_ON_SYMLINK ((NTSTATUS) 0x8000002DL)
-#endif
-
-#ifndef STATUS_CANNOT_GRANT_REQUESTED_OPLOCK
-# define STATUS_CANNOT_GRANT_REQUESTED_OPLOCK ((NTSTATUS) 0x8000002EL)
-#endif
-
-#ifndef STATUS_NO_ACE_CONDITION
-# define STATUS_NO_ACE_CONDITION ((NTSTATUS) 0x8000002FL)
-#endif
-
-#ifndef STATUS_UNSUCCESSFUL
-# define STATUS_UNSUCCESSFUL ((NTSTATUS) 0xC0000001L)
-#endif
-
-#ifndef STATUS_NOT_IMPLEMENTED
-# define STATUS_NOT_IMPLEMENTED ((NTSTATUS) 0xC0000002L)
-#endif
-
-#ifndef STATUS_INVALID_INFO_CLASS
-# define STATUS_INVALID_INFO_CLASS ((NTSTATUS) 0xC0000003L)
-#endif
-
-#ifndef STATUS_INFO_LENGTH_MISMATCH
-# define STATUS_INFO_LENGTH_MISMATCH ((NTSTATUS) 0xC0000004L)
-#endif
-
-#ifndef STATUS_ACCESS_VIOLATION
-# define STATUS_ACCESS_VIOLATION ((NTSTATUS) 0xC0000005L)
-#endif
-
-#ifndef STATUS_IN_PAGE_ERROR
-# define STATUS_IN_PAGE_ERROR ((NTSTATUS) 0xC0000006L)
-#endif
-
-#ifndef STATUS_PAGEFILE_QUOTA
-# define STATUS_PAGEFILE_QUOTA ((NTSTATUS) 0xC0000007L)
-#endif
-
-#ifndef STATUS_INVALID_HANDLE
-# define STATUS_INVALID_HANDLE ((NTSTATUS) 0xC0000008L)
-#endif
-
-#ifndef STATUS_BAD_INITIAL_STACK
-# define STATUS_BAD_INITIAL_STACK ((NTSTATUS) 0xC0000009L)
-#endif
-
-#ifndef STATUS_BAD_INITIAL_PC
-# define STATUS_BAD_INITIAL_PC ((NTSTATUS) 0xC000000AL)
-#endif
-
-#ifndef STATUS_INVALID_CID
-# define STATUS_INVALID_CID ((NTSTATUS) 0xC000000BL)
-#endif
-
-#ifndef STATUS_TIMER_NOT_CANCELED
-# define STATUS_TIMER_NOT_CANCELED ((NTSTATUS) 0xC000000CL)
-#endif
-
-#ifndef STATUS_INVALID_PARAMETER
-# define STATUS_INVALID_PARAMETER ((NTSTATUS) 0xC000000DL)
-#endif
-
-#ifndef STATUS_NO_SUCH_DEVICE
-# define STATUS_NO_SUCH_DEVICE ((NTSTATUS) 0xC000000EL)
-#endif
-
-#ifndef STATUS_NO_SUCH_FILE
-# define STATUS_NO_SUCH_FILE ((NTSTATUS) 0xC000000FL)
-#endif
-
-#ifndef STATUS_INVALID_DEVICE_REQUEST
-# define STATUS_INVALID_DEVICE_REQUEST ((NTSTATUS) 0xC0000010L)
-#endif
-
-#ifndef STATUS_END_OF_FILE
-# define STATUS_END_OF_FILE ((NTSTATUS) 0xC0000011L)
-#endif
-
-#ifndef STATUS_WRONG_VOLUME
-# define STATUS_WRONG_VOLUME ((NTSTATUS) 0xC0000012L)
-#endif
-
-#ifndef STATUS_NO_MEDIA_IN_DEVICE
-# define STATUS_NO_MEDIA_IN_DEVICE ((NTSTATUS) 0xC0000013L)
-#endif
-
-#ifndef STATUS_UNRECOGNIZED_MEDIA
-# define STATUS_UNRECOGNIZED_MEDIA ((NTSTATUS) 0xC0000014L)
-#endif
-
-#ifndef STATUS_NONEXISTENT_SECTOR
-# define STATUS_NONEXISTENT_SECTOR ((NTSTATUS) 0xC0000015L)
-#endif
-
-#ifndef STATUS_MORE_PROCESSING_REQUIRED
-# define STATUS_MORE_PROCESSING_REQUIRED ((NTSTATUS) 0xC0000016L)
-#endif
-
-#ifndef STATUS_NO_MEMORY
-# define STATUS_NO_MEMORY ((NTSTATUS) 0xC0000017L)
-#endif
-
-#ifndef STATUS_CONFLICTING_ADDRESSES
-# define STATUS_CONFLICTING_ADDRESSES ((NTSTATUS) 0xC0000018L)
-#endif
-
-#ifndef STATUS_NOT_MAPPED_VIEW
-# define STATUS_NOT_MAPPED_VIEW ((NTSTATUS) 0xC0000019L)
-#endif
-
-#ifndef STATUS_UNABLE_TO_FREE_VM
-# define STATUS_UNABLE_TO_FREE_VM ((NTSTATUS) 0xC000001AL)
-#endif
-
-#ifndef STATUS_UNABLE_TO_DELETE_SECTION
-# define STATUS_UNABLE_TO_DELETE_SECTION ((NTSTATUS) 0xC000001BL)
-#endif
-
-#ifndef STATUS_INVALID_SYSTEM_SERVICE
-# define STATUS_INVALID_SYSTEM_SERVICE ((NTSTATUS) 0xC000001CL)
-#endif
-
-#ifndef STATUS_ILLEGAL_INSTRUCTION
-# define STATUS_ILLEGAL_INSTRUCTION ((NTSTATUS) 0xC000001DL)
-#endif
-
-#ifndef STATUS_INVALID_LOCK_SEQUENCE
-# define STATUS_INVALID_LOCK_SEQUENCE ((NTSTATUS) 0xC000001EL)
-#endif
-
-#ifndef STATUS_INVALID_VIEW_SIZE
-# define STATUS_INVALID_VIEW_SIZE ((NTSTATUS) 0xC000001FL)
-#endif
-
-#ifndef STATUS_INVALID_FILE_FOR_SECTION
-# define STATUS_INVALID_FILE_FOR_SECTION ((NTSTATUS) 0xC0000020L)
-#endif
-
-#ifndef STATUS_ALREADY_COMMITTED
-# define STATUS_ALREADY_COMMITTED ((NTSTATUS) 0xC0000021L)
-#endif
-
-#ifndef STATUS_ACCESS_DENIED
-# define STATUS_ACCESS_DENIED ((NTSTATUS) 0xC0000022L)
-#endif
-
-#ifndef STATUS_BUFFER_TOO_SMALL
-# define STATUS_BUFFER_TOO_SMALL ((NTSTATUS) 0xC0000023L)
-#endif
-
-#ifndef STATUS_OBJECT_TYPE_MISMATCH
-# define STATUS_OBJECT_TYPE_MISMATCH ((NTSTATUS) 0xC0000024L)
-#endif
-
-#ifndef STATUS_NONCONTINUABLE_EXCEPTION
-# define STATUS_NONCONTINUABLE_EXCEPTION ((NTSTATUS) 0xC0000025L)
-#endif
-
-#ifndef STATUS_INVALID_DISPOSITION
-# define STATUS_INVALID_DISPOSITION ((NTSTATUS) 0xC0000026L)
-#endif
-
-#ifndef STATUS_UNWIND
-# define STATUS_UNWIND ((NTSTATUS) 0xC0000027L)
-#endif
-
-#ifndef STATUS_BAD_STACK
-# define STATUS_BAD_STACK ((NTSTATUS) 0xC0000028L)
-#endif
-
-#ifndef STATUS_INVALID_UNWIND_TARGET
-# define STATUS_INVALID_UNWIND_TARGET ((NTSTATUS) 0xC0000029L)
-#endif
-
-#ifndef STATUS_NOT_LOCKED
-# define STATUS_NOT_LOCKED ((NTSTATUS) 0xC000002AL)
-#endif
-
-#ifndef STATUS_PARITY_ERROR
-# define STATUS_PARITY_ERROR ((NTSTATUS) 0xC000002BL)
-#endif
-
-#ifndef STATUS_UNABLE_TO_DECOMMIT_VM
-# define STATUS_UNABLE_TO_DECOMMIT_VM ((NTSTATUS) 0xC000002CL)
-#endif
-
-#ifndef STATUS_NOT_COMMITTED
-# define STATUS_NOT_COMMITTED ((NTSTATUS) 0xC000002DL)
-#endif
-
-#ifndef STATUS_INVALID_PORT_ATTRIBUTES
-# define STATUS_INVALID_PORT_ATTRIBUTES ((NTSTATUS) 0xC000002EL)
-#endif
-
-#ifndef STATUS_PORT_MESSAGE_TOO_LONG
-# define STATUS_PORT_MESSAGE_TOO_LONG ((NTSTATUS) 0xC000002FL)
-#endif
-
-#ifndef STATUS_INVALID_PARAMETER_MIX
-# define STATUS_INVALID_PARAMETER_MIX ((NTSTATUS) 0xC0000030L)
-#endif
-
-#ifndef STATUS_INVALID_QUOTA_LOWER
-# define STATUS_INVALID_QUOTA_LOWER ((NTSTATUS) 0xC0000031L)
-#endif
-
-#ifndef STATUS_DISK_CORRUPT_ERROR
-# define STATUS_DISK_CORRUPT_ERROR ((NTSTATUS) 0xC0000032L)
-#endif
-
-#ifndef STATUS_OBJECT_NAME_INVALID
-# define STATUS_OBJECT_NAME_INVALID ((NTSTATUS) 0xC0000033L)
-#endif
-
-#ifndef STATUS_OBJECT_NAME_NOT_FOUND
-# define STATUS_OBJECT_NAME_NOT_FOUND ((NTSTATUS) 0xC0000034L)
-#endif
-
-#ifndef STATUS_OBJECT_NAME_COLLISION
-# define STATUS_OBJECT_NAME_COLLISION ((NTSTATUS) 0xC0000035L)
-#endif
-
-#ifndef STATUS_PORT_DISCONNECTED
-# define STATUS_PORT_DISCONNECTED ((NTSTATUS) 0xC0000037L)
-#endif
-
-#ifndef STATUS_DEVICE_ALREADY_ATTACHED
-# define STATUS_DEVICE_ALREADY_ATTACHED ((NTSTATUS) 0xC0000038L)
-#endif
-
-#ifndef STATUS_OBJECT_PATH_INVALID
-# define STATUS_OBJECT_PATH_INVALID ((NTSTATUS) 0xC0000039L)
-#endif
-
-#ifndef STATUS_OBJECT_PATH_NOT_FOUND
-# define STATUS_OBJECT_PATH_NOT_FOUND ((NTSTATUS) 0xC000003AL)
-#endif
-
-#ifndef STATUS_OBJECT_PATH_SYNTAX_BAD
-# define STATUS_OBJECT_PATH_SYNTAX_BAD ((NTSTATUS) 0xC000003BL)
-#endif
-
-#ifndef STATUS_DATA_OVERRUN
-# define STATUS_DATA_OVERRUN ((NTSTATUS) 0xC000003CL)
-#endif
-
-#ifndef STATUS_DATA_LATE_ERROR
-# define STATUS_DATA_LATE_ERROR ((NTSTATUS) 0xC000003DL)
-#endif
-
-#ifndef STATUS_DATA_ERROR
-# define STATUS_DATA_ERROR ((NTSTATUS) 0xC000003EL)
-#endif
-
-#ifndef STATUS_CRC_ERROR
-# define STATUS_CRC_ERROR ((NTSTATUS) 0xC000003FL)
-#endif
-
-#ifndef STATUS_SECTION_TOO_BIG
-# define STATUS_SECTION_TOO_BIG ((NTSTATUS) 0xC0000040L)
-#endif
-
-#ifndef STATUS_PORT_CONNECTION_REFUSED
-# define STATUS_PORT_CONNECTION_REFUSED ((NTSTATUS) 0xC0000041L)
-#endif
-
-#ifndef STATUS_INVALID_PORT_HANDLE
-# define STATUS_INVALID_PORT_HANDLE ((NTSTATUS) 0xC0000042L)
-#endif
-
-#ifndef STATUS_SHARING_VIOLATION
-# define STATUS_SHARING_VIOLATION ((NTSTATUS) 0xC0000043L)
-#endif
-
-#ifndef STATUS_QUOTA_EXCEEDED
-# define STATUS_QUOTA_EXCEEDED ((NTSTATUS) 0xC0000044L)
-#endif
-
-#ifndef STATUS_INVALID_PAGE_PROTECTION
-# define STATUS_INVALID_PAGE_PROTECTION ((NTSTATUS) 0xC0000045L)
-#endif
-
-#ifndef STATUS_MUTANT_NOT_OWNED
-# define STATUS_MUTANT_NOT_OWNED ((NTSTATUS) 0xC0000046L)
-#endif
-
-#ifndef STATUS_SEMAPHORE_LIMIT_EXCEEDED
-# define STATUS_SEMAPHORE_LIMIT_EXCEEDED ((NTSTATUS) 0xC0000047L)
-#endif
-
-#ifndef STATUS_PORT_ALREADY_SET
-# define STATUS_PORT_ALREADY_SET ((NTSTATUS) 0xC0000048L)
-#endif
-
-#ifndef STATUS_SECTION_NOT_IMAGE
-# define STATUS_SECTION_NOT_IMAGE ((NTSTATUS) 0xC0000049L)
-#endif
-
-#ifndef STATUS_SUSPEND_COUNT_EXCEEDED
-# define STATUS_SUSPEND_COUNT_EXCEEDED ((NTSTATUS) 0xC000004AL)
-#endif
-
-#ifndef STATUS_THREAD_IS_TERMINATING
-# define STATUS_THREAD_IS_TERMINATING ((NTSTATUS) 0xC000004BL)
-#endif
-
-#ifndef STATUS_BAD_WORKING_SET_LIMIT
-# define STATUS_BAD_WORKING_SET_LIMIT ((NTSTATUS) 0xC000004CL)
-#endif
-
-#ifndef STATUS_INCOMPATIBLE_FILE_MAP
-# define STATUS_INCOMPATIBLE_FILE_MAP ((NTSTATUS) 0xC000004DL)
-#endif
-
-#ifndef STATUS_SECTION_PROTECTION
-# define STATUS_SECTION_PROTECTION ((NTSTATUS) 0xC000004EL)
-#endif
-
-#ifndef STATUS_EAS_NOT_SUPPORTED
-# define STATUS_EAS_NOT_SUPPORTED ((NTSTATUS) 0xC000004FL)
-#endif
-
-#ifndef STATUS_EA_TOO_LARGE
-# define STATUS_EA_TOO_LARGE ((NTSTATUS) 0xC0000050L)
-#endif
-
-#ifndef STATUS_NONEXISTENT_EA_ENTRY
-# define STATUS_NONEXISTENT_EA_ENTRY ((NTSTATUS) 0xC0000051L)
-#endif
-
-#ifndef STATUS_NO_EAS_ON_FILE
-# define STATUS_NO_EAS_ON_FILE ((NTSTATUS) 0xC0000052L)
-#endif
-
-#ifndef STATUS_EA_CORRUPT_ERROR
-# define STATUS_EA_CORRUPT_ERROR ((NTSTATUS) 0xC0000053L)
-#endif
-
-#ifndef STATUS_FILE_LOCK_CONFLICT
-# define STATUS_FILE_LOCK_CONFLICT ((NTSTATUS) 0xC0000054L)
-#endif
-
-#ifndef STATUS_LOCK_NOT_GRANTED
-# define STATUS_LOCK_NOT_GRANTED ((NTSTATUS) 0xC0000055L)
-#endif
-
-#ifndef STATUS_DELETE_PENDING
-# define STATUS_DELETE_PENDING ((NTSTATUS) 0xC0000056L)
-#endif
-
-#ifndef STATUS_CTL_FILE_NOT_SUPPORTED
-# define STATUS_CTL_FILE_NOT_SUPPORTED ((NTSTATUS) 0xC0000057L)
-#endif
-
-#ifndef STATUS_UNKNOWN_REVISION
-# define STATUS_UNKNOWN_REVISION ((NTSTATUS) 0xC0000058L)
-#endif
-
-#ifndef STATUS_REVISION_MISMATCH
-# define STATUS_REVISION_MISMATCH ((NTSTATUS) 0xC0000059L)
-#endif
-
-#ifndef STATUS_INVALID_OWNER
-# define STATUS_INVALID_OWNER ((NTSTATUS) 0xC000005AL)
-#endif
-
-#ifndef STATUS_INVALID_PRIMARY_GROUP
-# define STATUS_INVALID_PRIMARY_GROUP ((NTSTATUS) 0xC000005BL)
-#endif
-
-#ifndef STATUS_NO_IMPERSONATION_TOKEN
-# define STATUS_NO_IMPERSONATION_TOKEN ((NTSTATUS) 0xC000005CL)
-#endif
-
-#ifndef STATUS_CANT_DISABLE_MANDATORY
-# define STATUS_CANT_DISABLE_MANDATORY ((NTSTATUS) 0xC000005DL)
-#endif
-
-#ifndef STATUS_NO_LOGON_SERVERS
-# define STATUS_NO_LOGON_SERVERS ((NTSTATUS) 0xC000005EL)
-#endif
-
-#ifndef STATUS_NO_SUCH_LOGON_SESSION
-# define STATUS_NO_SUCH_LOGON_SESSION ((NTSTATUS) 0xC000005FL)
-#endif
-
-#ifndef STATUS_NO_SUCH_PRIVILEGE
-# define STATUS_NO_SUCH_PRIVILEGE ((NTSTATUS) 0xC0000060L)
-#endif
-
-#ifndef STATUS_PRIVILEGE_NOT_HELD
-# define STATUS_PRIVILEGE_NOT_HELD ((NTSTATUS) 0xC0000061L)
-#endif
-
-#ifndef STATUS_INVALID_ACCOUNT_NAME
-# define STATUS_INVALID_ACCOUNT_NAME ((NTSTATUS) 0xC0000062L)
-#endif
-
-#ifndef STATUS_USER_EXISTS
-# define STATUS_USER_EXISTS ((NTSTATUS) 0xC0000063L)
-#endif
-
-#ifndef STATUS_NO_SUCH_USER
-# define STATUS_NO_SUCH_USER ((NTSTATUS) 0xC0000064L)
-#endif
-
-#ifndef STATUS_GROUP_EXISTS
-# define STATUS_GROUP_EXISTS ((NTSTATUS) 0xC0000065L)
-#endif
-
-#ifndef STATUS_NO_SUCH_GROUP
-# define STATUS_NO_SUCH_GROUP ((NTSTATUS) 0xC0000066L)
-#endif
-
-#ifndef STATUS_MEMBER_IN_GROUP
-# define STATUS_MEMBER_IN_GROUP ((NTSTATUS) 0xC0000067L)
-#endif
-
-#ifndef STATUS_MEMBER_NOT_IN_GROUP
-# define STATUS_MEMBER_NOT_IN_GROUP ((NTSTATUS) 0xC0000068L)
-#endif
-
-#ifndef STATUS_LAST_ADMIN
-# define STATUS_LAST_ADMIN ((NTSTATUS) 0xC0000069L)
-#endif
-
-#ifndef STATUS_WRONG_PASSWORD
-# define STATUS_WRONG_PASSWORD ((NTSTATUS) 0xC000006AL)
-#endif
-
-#ifndef STATUS_ILL_FORMED_PASSWORD
-# define STATUS_ILL_FORMED_PASSWORD ((NTSTATUS) 0xC000006BL)
-#endif
-
-#ifndef STATUS_PASSWORD_RESTRICTION
-# define STATUS_PASSWORD_RESTRICTION ((NTSTATUS) 0xC000006CL)
-#endif
-
-#ifndef STATUS_LOGON_FAILURE
-# define STATUS_LOGON_FAILURE ((NTSTATUS) 0xC000006DL)
-#endif
-
-#ifndef STATUS_ACCOUNT_RESTRICTION
-# define STATUS_ACCOUNT_RESTRICTION ((NTSTATUS) 0xC000006EL)
-#endif
-
-#ifndef STATUS_INVALID_LOGON_HOURS
-# define STATUS_INVALID_LOGON_HOURS ((NTSTATUS) 0xC000006FL)
-#endif
-
-#ifndef STATUS_INVALID_WORKSTATION
-# define STATUS_INVALID_WORKSTATION ((NTSTATUS) 0xC0000070L)
-#endif
-
-#ifndef STATUS_PASSWORD_EXPIRED
-# define STATUS_PASSWORD_EXPIRED ((NTSTATUS) 0xC0000071L)
-#endif
-
-#ifndef STATUS_ACCOUNT_DISABLED
-# define STATUS_ACCOUNT_DISABLED ((NTSTATUS) 0xC0000072L)
-#endif
-
-#ifndef STATUS_NONE_MAPPED
-# define STATUS_NONE_MAPPED ((NTSTATUS) 0xC0000073L)
-#endif
-
-#ifndef STATUS_TOO_MANY_LUIDS_REQUESTED
-# define STATUS_TOO_MANY_LUIDS_REQUESTED ((NTSTATUS) 0xC0000074L)
-#endif
-
-#ifndef STATUS_LUIDS_EXHAUSTED
-# define STATUS_LUIDS_EXHAUSTED ((NTSTATUS) 0xC0000075L)
-#endif
-
-#ifndef STATUS_INVALID_SUB_AUTHORITY
-# define STATUS_INVALID_SUB_AUTHORITY ((NTSTATUS) 0xC0000076L)
-#endif
-
-#ifndef STATUS_INVALID_ACL
-# define STATUS_INVALID_ACL ((NTSTATUS) 0xC0000077L)
-#endif
-
-#ifndef STATUS_INVALID_SID
-# define STATUS_INVALID_SID ((NTSTATUS) 0xC0000078L)
-#endif
-
-#ifndef STATUS_INVALID_SECURITY_DESCR
-# define STATUS_INVALID_SECURITY_DESCR ((NTSTATUS) 0xC0000079L)
-#endif
-
-#ifndef STATUS_PROCEDURE_NOT_FOUND
-# define STATUS_PROCEDURE_NOT_FOUND ((NTSTATUS) 0xC000007AL)
-#endif
-
-#ifndef STATUS_INVALID_IMAGE_FORMAT
-# define STATUS_INVALID_IMAGE_FORMAT ((NTSTATUS) 0xC000007BL)
-#endif
-
-#ifndef STATUS_NO_TOKEN
-# define STATUS_NO_TOKEN ((NTSTATUS) 0xC000007CL)
-#endif
-
-#ifndef STATUS_BAD_INHERITANCE_ACL
-# define STATUS_BAD_INHERITANCE_ACL ((NTSTATUS) 0xC000007DL)
-#endif
-
-#ifndef STATUS_RANGE_NOT_LOCKED
-# define STATUS_RANGE_NOT_LOCKED ((NTSTATUS) 0xC000007EL)
-#endif
-
-#ifndef STATUS_DISK_FULL
-# define STATUS_DISK_FULL ((NTSTATUS) 0xC000007FL)
-#endif
-
-#ifndef STATUS_SERVER_DISABLED
-# define STATUS_SERVER_DISABLED ((NTSTATUS) 0xC0000080L)
-#endif
-
-#ifndef STATUS_SERVER_NOT_DISABLED
-# define STATUS_SERVER_NOT_DISABLED ((NTSTATUS) 0xC0000081L)
-#endif
-
-#ifndef STATUS_TOO_MANY_GUIDS_REQUESTED
-# define STATUS_TOO_MANY_GUIDS_REQUESTED ((NTSTATUS) 0xC0000082L)
-#endif
-
-#ifndef STATUS_GUIDS_EXHAUSTED
-# define STATUS_GUIDS_EXHAUSTED ((NTSTATUS) 0xC0000083L)
-#endif
-
-#ifndef STATUS_INVALID_ID_AUTHORITY
-# define STATUS_INVALID_ID_AUTHORITY ((NTSTATUS) 0xC0000084L)
-#endif
-
-#ifndef STATUS_AGENTS_EXHAUSTED
-# define STATUS_AGENTS_EXHAUSTED ((NTSTATUS) 0xC0000085L)
-#endif
-
-#ifndef STATUS_INVALID_VOLUME_LABEL
-# define STATUS_INVALID_VOLUME_LABEL ((NTSTATUS) 0xC0000086L)
-#endif
-
-#ifndef STATUS_SECTION_NOT_EXTENDED
-# define STATUS_SECTION_NOT_EXTENDED ((NTSTATUS) 0xC0000087L)
-#endif
-
-#ifndef STATUS_NOT_MAPPED_DATA
-# define STATUS_NOT_MAPPED_DATA ((NTSTATUS) 0xC0000088L)
-#endif
-
-#ifndef STATUS_RESOURCE_DATA_NOT_FOUND
-# define STATUS_RESOURCE_DATA_NOT_FOUND ((NTSTATUS) 0xC0000089L)
-#endif
-
-#ifndef STATUS_RESOURCE_TYPE_NOT_FOUND
-# define STATUS_RESOURCE_TYPE_NOT_FOUND ((NTSTATUS) 0xC000008AL)
-#endif
-
-#ifndef STATUS_RESOURCE_NAME_NOT_FOUND
-# define STATUS_RESOURCE_NAME_NOT_FOUND ((NTSTATUS) 0xC000008BL)
-#endif
-
-#ifndef STATUS_ARRAY_BOUNDS_EXCEEDED
-# define STATUS_ARRAY_BOUNDS_EXCEEDED ((NTSTATUS) 0xC000008CL)
-#endif
-
-#ifndef STATUS_FLOAT_DENORMAL_OPERAND
-# define STATUS_FLOAT_DENORMAL_OPERAND ((NTSTATUS) 0xC000008DL)
-#endif
-
-#ifndef STATUS_FLOAT_DIVIDE_BY_ZERO
-# define STATUS_FLOAT_DIVIDE_BY_ZERO ((NTSTATUS) 0xC000008EL)
-#endif
-
-#ifndef STATUS_FLOAT_INEXACT_RESULT
-# define STATUS_FLOAT_INEXACT_RESULT ((NTSTATUS) 0xC000008FL)
-#endif
-
-#ifndef STATUS_FLOAT_INVALID_OPERATION
-# define STATUS_FLOAT_INVALID_OPERATION ((NTSTATUS) 0xC0000090L)
-#endif
-
-#ifndef STATUS_FLOAT_OVERFLOW
-# define STATUS_FLOAT_OVERFLOW ((NTSTATUS) 0xC0000091L)
-#endif
-
-#ifndef STATUS_FLOAT_STACK_CHECK
-# define STATUS_FLOAT_STACK_CHECK ((NTSTATUS) 0xC0000092L)
-#endif
-
-#ifndef STATUS_FLOAT_UNDERFLOW
-# define STATUS_FLOAT_UNDERFLOW ((NTSTATUS) 0xC0000093L)
-#endif
-
-#ifndef STATUS_INTEGER_DIVIDE_BY_ZERO
-# define STATUS_INTEGER_DIVIDE_BY_ZERO ((NTSTATUS) 0xC0000094L)
-#endif
-
-#ifndef STATUS_INTEGER_OVERFLOW
-# define STATUS_INTEGER_OVERFLOW ((NTSTATUS) 0xC0000095L)
-#endif
-
-#ifndef STATUS_PRIVILEGED_INSTRUCTION
-# define STATUS_PRIVILEGED_INSTRUCTION ((NTSTATUS) 0xC0000096L)
-#endif
-
-#ifndef STATUS_TOO_MANY_PAGING_FILES
-# define STATUS_TOO_MANY_PAGING_FILES ((NTSTATUS) 0xC0000097L)
-#endif
-
-#ifndef STATUS_FILE_INVALID
-# define STATUS_FILE_INVALID ((NTSTATUS) 0xC0000098L)
-#endif
-
-#ifndef STATUS_ALLOTTED_SPACE_EXCEEDED
-# define STATUS_ALLOTTED_SPACE_EXCEEDED ((NTSTATUS) 0xC0000099L)
-#endif
-
-#ifndef STATUS_INSUFFICIENT_RESOURCES
-# define STATUS_INSUFFICIENT_RESOURCES ((NTSTATUS) 0xC000009AL)
-#endif
-
-#ifndef STATUS_DFS_EXIT_PATH_FOUND
-# define STATUS_DFS_EXIT_PATH_FOUND ((NTSTATUS) 0xC000009BL)
-#endif
-
-#ifndef STATUS_DEVICE_DATA_ERROR
-# define STATUS_DEVICE_DATA_ERROR ((NTSTATUS) 0xC000009CL)
-#endif
-
-#ifndef STATUS_DEVICE_NOT_CONNECTED
-# define STATUS_DEVICE_NOT_CONNECTED ((NTSTATUS) 0xC000009DL)
-#endif
-
-#ifndef STATUS_DEVICE_POWER_FAILURE
-# define STATUS_DEVICE_POWER_FAILURE ((NTSTATUS) 0xC000009EL)
-#endif
-
-#ifndef STATUS_FREE_VM_NOT_AT_BASE
-# define STATUS_FREE_VM_NOT_AT_BASE ((NTSTATUS) 0xC000009FL)
-#endif
-
-#ifndef STATUS_MEMORY_NOT_ALLOCATED
-# define STATUS_MEMORY_NOT_ALLOCATED ((NTSTATUS) 0xC00000A0L)
-#endif
-
-#ifndef STATUS_WORKING_SET_QUOTA
-# define STATUS_WORKING_SET_QUOTA ((NTSTATUS) 0xC00000A1L)
-#endif
-
-#ifndef STATUS_MEDIA_WRITE_PROTECTED
-# define STATUS_MEDIA_WRITE_PROTECTED ((NTSTATUS) 0xC00000A2L)
-#endif
-
-#ifndef STATUS_DEVICE_NOT_READY
-# define STATUS_DEVICE_NOT_READY ((NTSTATUS) 0xC00000A3L)
-#endif
-
-#ifndef STATUS_INVALID_GROUP_ATTRIBUTES
-# define STATUS_INVALID_GROUP_ATTRIBUTES ((NTSTATUS) 0xC00000A4L)
-#endif
-
-#ifndef STATUS_BAD_IMPERSONATION_LEVEL
-# define STATUS_BAD_IMPERSONATION_LEVEL ((NTSTATUS) 0xC00000A5L)
-#endif
-
-#ifndef STATUS_CANT_OPEN_ANONYMOUS
-# define STATUS_CANT_OPEN_ANONYMOUS ((NTSTATUS) 0xC00000A6L)
-#endif
-
-#ifndef STATUS_BAD_VALIDATION_CLASS
-# define STATUS_BAD_VALIDATION_CLASS ((NTSTATUS) 0xC00000A7L)
-#endif
-
-#ifndef STATUS_BAD_TOKEN_TYPE
-# define STATUS_BAD_TOKEN_TYPE ((NTSTATUS) 0xC00000A8L)
-#endif
-
-#ifndef STATUS_BAD_MASTER_BOOT_RECORD
-# define STATUS_BAD_MASTER_BOOT_RECORD ((NTSTATUS) 0xC00000A9L)
-#endif
-
-#ifndef STATUS_INSTRUCTION_MISALIGNMENT
-# define STATUS_INSTRUCTION_MISALIGNMENT ((NTSTATUS) 0xC00000AAL)
-#endif
-
-#ifndef STATUS_INSTANCE_NOT_AVAILABLE
-# define STATUS_INSTANCE_NOT_AVAILABLE ((NTSTATUS) 0xC00000ABL)
-#endif
-
-#ifndef STATUS_PIPE_NOT_AVAILABLE
-# define STATUS_PIPE_NOT_AVAILABLE ((NTSTATUS) 0xC00000ACL)
-#endif
-
-#ifndef STATUS_INVALID_PIPE_STATE
-# define STATUS_INVALID_PIPE_STATE ((NTSTATUS) 0xC00000ADL)
-#endif
-
-#ifndef STATUS_PIPE_BUSY
-# define STATUS_PIPE_BUSY ((NTSTATUS) 0xC00000AEL)
-#endif
-
-#ifndef STATUS_ILLEGAL_FUNCTION
-# define STATUS_ILLEGAL_FUNCTION ((NTSTATUS) 0xC00000AFL)
-#endif
-
-#ifndef STATUS_PIPE_DISCONNECTED
-# define STATUS_PIPE_DISCONNECTED ((NTSTATUS) 0xC00000B0L)
-#endif
-
-#ifndef STATUS_PIPE_CLOSING
-# define STATUS_PIPE_CLOSING ((NTSTATUS) 0xC00000B1L)
-#endif
-
-#ifndef STATUS_PIPE_CONNECTED
-# define STATUS_PIPE_CONNECTED ((NTSTATUS) 0xC00000B2L)
-#endif
-
-#ifndef STATUS_PIPE_LISTENING
-# define STATUS_PIPE_LISTENING ((NTSTATUS) 0xC00000B3L)
-#endif
-
-#ifndef STATUS_INVALID_READ_MODE
-# define STATUS_INVALID_READ_MODE ((NTSTATUS) 0xC00000B4L)
-#endif
-
-#ifndef STATUS_IO_TIMEOUT
-# define STATUS_IO_TIMEOUT ((NTSTATUS) 0xC00000B5L)
-#endif
-
-#ifndef STATUS_FILE_FORCED_CLOSED
-# define STATUS_FILE_FORCED_CLOSED ((NTSTATUS) 0xC00000B6L)
-#endif
-
-#ifndef STATUS_PROFILING_NOT_STARTED
-# define STATUS_PROFILING_NOT_STARTED ((NTSTATUS) 0xC00000B7L)
-#endif
-
-#ifndef STATUS_PROFILING_NOT_STOPPED
-# define STATUS_PROFILING_NOT_STOPPED ((NTSTATUS) 0xC00000B8L)
-#endif
-
-#ifndef STATUS_COULD_NOT_INTERPRET
-# define STATUS_COULD_NOT_INTERPRET ((NTSTATUS) 0xC00000B9L)
-#endif
-
-#ifndef STATUS_FILE_IS_A_DIRECTORY
-# define STATUS_FILE_IS_A_DIRECTORY ((NTSTATUS) 0xC00000BAL)
-#endif
-
-#ifndef STATUS_NOT_SUPPORTED
-# define STATUS_NOT_SUPPORTED ((NTSTATUS) 0xC00000BBL)
-#endif
-
-#ifndef STATUS_REMOTE_NOT_LISTENING
-# define STATUS_REMOTE_NOT_LISTENING ((NTSTATUS) 0xC00000BCL)
-#endif
-
-#ifndef STATUS_DUPLICATE_NAME
-# define STATUS_DUPLICATE_NAME ((NTSTATUS) 0xC00000BDL)
-#endif
-
-#ifndef STATUS_BAD_NETWORK_PATH
-# define STATUS_BAD_NETWORK_PATH ((NTSTATUS) 0xC00000BEL)
-#endif
-
-#ifndef STATUS_NETWORK_BUSY
-# define STATUS_NETWORK_BUSY ((NTSTATUS) 0xC00000BFL)
-#endif
-
-#ifndef STATUS_DEVICE_DOES_NOT_EXIST
-# define STATUS_DEVICE_DOES_NOT_EXIST ((NTSTATUS) 0xC00000C0L)
-#endif
-
-#ifndef STATUS_TOO_MANY_COMMANDS
-# define STATUS_TOO_MANY_COMMANDS ((NTSTATUS) 0xC00000C1L)
-#endif
-
-#ifndef STATUS_ADAPTER_HARDWARE_ERROR
-# define STATUS_ADAPTER_HARDWARE_ERROR ((NTSTATUS) 0xC00000C2L)
-#endif
-
-#ifndef STATUS_INVALID_NETWORK_RESPONSE
-# define STATUS_INVALID_NETWORK_RESPONSE ((NTSTATUS) 0xC00000C3L)
-#endif
-
-#ifndef STATUS_UNEXPECTED_NETWORK_ERROR
-# define STATUS_UNEXPECTED_NETWORK_ERROR ((NTSTATUS) 0xC00000C4L)
-#endif
-
-#ifndef STATUS_BAD_REMOTE_ADAPTER
-# define STATUS_BAD_REMOTE_ADAPTER ((NTSTATUS) 0xC00000C5L)
-#endif
-
-#ifndef STATUS_PRINT_QUEUE_FULL
-# define STATUS_PRINT_QUEUE_FULL ((NTSTATUS) 0xC00000C6L)
-#endif
-
-#ifndef STATUS_NO_SPOOL_SPACE
-# define STATUS_NO_SPOOL_SPACE ((NTSTATUS) 0xC00000C7L)
-#endif
-
-#ifndef STATUS_PRINT_CANCELLED
-# define STATUS_PRINT_CANCELLED ((NTSTATUS) 0xC00000C8L)
-#endif
-
-#ifndef STATUS_NETWORK_NAME_DELETED
-# define STATUS_NETWORK_NAME_DELETED ((NTSTATUS) 0xC00000C9L)
-#endif
-
-#ifndef STATUS_NETWORK_ACCESS_DENIED
-# define STATUS_NETWORK_ACCESS_DENIED ((NTSTATUS) 0xC00000CAL)
-#endif
-
-#ifndef STATUS_BAD_DEVICE_TYPE
-# define STATUS_BAD_DEVICE_TYPE ((NTSTATUS) 0xC00000CBL)
-#endif
-
-#ifndef STATUS_BAD_NETWORK_NAME
-# define STATUS_BAD_NETWORK_NAME ((NTSTATUS) 0xC00000CCL)
-#endif
-
-#ifndef STATUS_TOO_MANY_NAMES
-# define STATUS_TOO_MANY_NAMES ((NTSTATUS) 0xC00000CDL)
-#endif
-
-#ifndef STATUS_TOO_MANY_SESSIONS
-# define STATUS_TOO_MANY_SESSIONS ((NTSTATUS) 0xC00000CEL)
-#endif
-
-#ifndef STATUS_SHARING_PAUSED
-# define STATUS_SHARING_PAUSED ((NTSTATUS) 0xC00000CFL)
-#endif
-
-#ifndef STATUS_REQUEST_NOT_ACCEPTED
-# define STATUS_REQUEST_NOT_ACCEPTED ((NTSTATUS) 0xC00000D0L)
-#endif
-
-#ifndef STATUS_REDIRECTOR_PAUSED
-# define STATUS_REDIRECTOR_PAUSED ((NTSTATUS) 0xC00000D1L)
-#endif
-
-#ifndef STATUS_NET_WRITE_FAULT
-# define STATUS_NET_WRITE_FAULT ((NTSTATUS) 0xC00000D2L)
-#endif
-
-#ifndef STATUS_PROFILING_AT_LIMIT
-# define STATUS_PROFILING_AT_LIMIT ((NTSTATUS) 0xC00000D3L)
-#endif
-
-#ifndef STATUS_NOT_SAME_DEVICE
-# define STATUS_NOT_SAME_DEVICE ((NTSTATUS) 0xC00000D4L)
-#endif
-
-#ifndef STATUS_FILE_RENAMED
-# define STATUS_FILE_RENAMED ((NTSTATUS) 0xC00000D5L)
-#endif
-
-#ifndef STATUS_VIRTUAL_CIRCUIT_CLOSED
-# define STATUS_VIRTUAL_CIRCUIT_CLOSED ((NTSTATUS) 0xC00000D6L)
-#endif
-
-#ifndef STATUS_NO_SECURITY_ON_OBJECT
-# define STATUS_NO_SECURITY_ON_OBJECT ((NTSTATUS) 0xC00000D7L)
-#endif
-
-#ifndef STATUS_CANT_WAIT
-# define STATUS_CANT_WAIT ((NTSTATUS) 0xC00000D8L)
-#endif
-
-#ifndef STATUS_PIPE_EMPTY
-# define STATUS_PIPE_EMPTY ((NTSTATUS) 0xC00000D9L)
-#endif
-
-#ifndef STATUS_CANT_ACCESS_DOMAIN_INFO
-# define STATUS_CANT_ACCESS_DOMAIN_INFO ((NTSTATUS) 0xC00000DAL)
-#endif
-
-#ifndef STATUS_CANT_TERMINATE_SELF
-# define STATUS_CANT_TERMINATE_SELF ((NTSTATUS) 0xC00000DBL)
-#endif
-
-#ifndef STATUS_INVALID_SERVER_STATE
-# define STATUS_INVALID_SERVER_STATE ((NTSTATUS) 0xC00000DCL)
-#endif
-
-#ifndef STATUS_INVALID_DOMAIN_STATE
-# define STATUS_INVALID_DOMAIN_STATE ((NTSTATUS) 0xC00000DDL)
-#endif
-
-#ifndef STATUS_INVALID_DOMAIN_ROLE
-# define STATUS_INVALID_DOMAIN_ROLE ((NTSTATUS) 0xC00000DEL)
-#endif
-
-#ifndef STATUS_NO_SUCH_DOMAIN
-# define STATUS_NO_SUCH_DOMAIN ((NTSTATUS) 0xC00000DFL)
-#endif
-
-#ifndef STATUS_DOMAIN_EXISTS
-# define STATUS_DOMAIN_EXISTS ((NTSTATUS) 0xC00000E0L)
-#endif
-
-#ifndef STATUS_DOMAIN_LIMIT_EXCEEDED
-# define STATUS_DOMAIN_LIMIT_EXCEEDED ((NTSTATUS) 0xC00000E1L)
-#endif
-
-#ifndef STATUS_OPLOCK_NOT_GRANTED
-# define STATUS_OPLOCK_NOT_GRANTED ((NTSTATUS) 0xC00000E2L)
-#endif
-
-#ifndef STATUS_INVALID_OPLOCK_PROTOCOL
-# define STATUS_INVALID_OPLOCK_PROTOCOL ((NTSTATUS) 0xC00000E3L)
-#endif
-
-#ifndef STATUS_INTERNAL_DB_CORRUPTION
-# define STATUS_INTERNAL_DB_CORRUPTION ((NTSTATUS) 0xC00000E4L)
-#endif
-
-#ifndef STATUS_INTERNAL_ERROR
-# define STATUS_INTERNAL_ERROR ((NTSTATUS) 0xC00000E5L)
-#endif
-
-#ifndef STATUS_GENERIC_NOT_MAPPED
-# define STATUS_GENERIC_NOT_MAPPED ((NTSTATUS) 0xC00000E6L)
-#endif
-
-#ifndef STATUS_BAD_DESCRIPTOR_FORMAT
-# define STATUS_BAD_DESCRIPTOR_FORMAT ((NTSTATUS) 0xC00000E7L)
-#endif
-
-#ifndef STATUS_INVALID_USER_BUFFER
-# define STATUS_INVALID_USER_BUFFER ((NTSTATUS) 0xC00000E8L)
-#endif
-
-#ifndef STATUS_UNEXPECTED_IO_ERROR
-# define STATUS_UNEXPECTED_IO_ERROR ((NTSTATUS) 0xC00000E9L)
-#endif
-
-#ifndef STATUS_UNEXPECTED_MM_CREATE_ERR
-# define STATUS_UNEXPECTED_MM_CREATE_ERR ((NTSTATUS) 0xC00000EAL)
-#endif
-
-#ifndef STATUS_UNEXPECTED_MM_MAP_ERROR
-# define STATUS_UNEXPECTED_MM_MAP_ERROR ((NTSTATUS) 0xC00000EBL)
-#endif
-
-#ifndef STATUS_UNEXPECTED_MM_EXTEND_ERR
-# define STATUS_UNEXPECTED_MM_EXTEND_ERR ((NTSTATUS) 0xC00000ECL)
-#endif
-
-#ifndef STATUS_NOT_LOGON_PROCESS
-# define STATUS_NOT_LOGON_PROCESS ((NTSTATUS) 0xC00000EDL)
-#endif
-
-#ifndef STATUS_LOGON_SESSION_EXISTS
-# define STATUS_LOGON_SESSION_EXISTS ((NTSTATUS) 0xC00000EEL)
-#endif
-
-#ifndef STATUS_INVALID_PARAMETER_1
-# define STATUS_INVALID_PARAMETER_1 ((NTSTATUS) 0xC00000EFL)
-#endif
-
-#ifndef STATUS_INVALID_PARAMETER_2
-# define STATUS_INVALID_PARAMETER_2 ((NTSTATUS) 0xC00000F0L)
-#endif
-
-#ifndef STATUS_INVALID_PARAMETER_3
-# define STATUS_INVALID_PARAMETER_3 ((NTSTATUS) 0xC00000F1L)
-#endif
-
-#ifndef STATUS_INVALID_PARAMETER_4
-# define STATUS_INVALID_PARAMETER_4 ((NTSTATUS) 0xC00000F2L)
-#endif
-
-#ifndef STATUS_INVALID_PARAMETER_5
-# define STATUS_INVALID_PARAMETER_5 ((NTSTATUS) 0xC00000F3L)
-#endif
-
-#ifndef STATUS_INVALID_PARAMETER_6
-# define STATUS_INVALID_PARAMETER_6 ((NTSTATUS) 0xC00000F4L)
-#endif
-
-#ifndef STATUS_INVALID_PARAMETER_7
-# define STATUS_INVALID_PARAMETER_7 ((NTSTATUS) 0xC00000F5L)
-#endif
-
-#ifndef STATUS_INVALID_PARAMETER_8
-# define STATUS_INVALID_PARAMETER_8 ((NTSTATUS) 0xC00000F6L)
-#endif
-
-#ifndef STATUS_INVALID_PARAMETER_9
-# define STATUS_INVALID_PARAMETER_9 ((NTSTATUS) 0xC00000F7L)
-#endif
-
-#ifndef STATUS_INVALID_PARAMETER_10
-# define STATUS_INVALID_PARAMETER_10 ((NTSTATUS) 0xC00000F8L)
-#endif
-
-#ifndef STATUS_INVALID_PARAMETER_11
-# define STATUS_INVALID_PARAMETER_11 ((NTSTATUS) 0xC00000F9L)
-#endif
-
-#ifndef STATUS_INVALID_PARAMETER_12
-# define STATUS_INVALID_PARAMETER_12 ((NTSTATUS) 0xC00000FAL)
-#endif
-
-#ifndef STATUS_REDIRECTOR_NOT_STARTED
-# define STATUS_REDIRECTOR_NOT_STARTED ((NTSTATUS) 0xC00000FBL)
-#endif
-
-#ifndef STATUS_REDIRECTOR_STARTED
-# define STATUS_REDIRECTOR_STARTED ((NTSTATUS) 0xC00000FCL)
-#endif
-
-#ifndef STATUS_STACK_OVERFLOW
-# define STATUS_STACK_OVERFLOW ((NTSTATUS) 0xC00000FDL)
-#endif
-
-#ifndef STATUS_NO_SUCH_PACKAGE
-# define STATUS_NO_SUCH_PACKAGE ((NTSTATUS) 0xC00000FEL)
-#endif
-
-#ifndef STATUS_BAD_FUNCTION_TABLE
-# define STATUS_BAD_FUNCTION_TABLE ((NTSTATUS) 0xC00000FFL)
-#endif
-
-#ifndef STATUS_VARIABLE_NOT_FOUND
-# define STATUS_VARIABLE_NOT_FOUND ((NTSTATUS) 0xC0000100L)
-#endif
-
-#ifndef STATUS_DIRECTORY_NOT_EMPTY
-# define STATUS_DIRECTORY_NOT_EMPTY ((NTSTATUS) 0xC0000101L)
-#endif
-
-#ifndef STATUS_FILE_CORRUPT_ERROR
-# define STATUS_FILE_CORRUPT_ERROR ((NTSTATUS) 0xC0000102L)
-#endif
-
-#ifndef STATUS_NOT_A_DIRECTORY
-# define STATUS_NOT_A_DIRECTORY ((NTSTATUS) 0xC0000103L)
-#endif
-
-#ifndef STATUS_BAD_LOGON_SESSION_STATE
-# define STATUS_BAD_LOGON_SESSION_STATE ((NTSTATUS) 0xC0000104L)
-#endif
-
-#ifndef STATUS_LOGON_SESSION_COLLISION
-# define STATUS_LOGON_SESSION_COLLISION ((NTSTATUS) 0xC0000105L)
-#endif
-
-#ifndef STATUS_NAME_TOO_LONG
-# define STATUS_NAME_TOO_LONG ((NTSTATUS) 0xC0000106L)
-#endif
-
-#ifndef STATUS_FILES_OPEN
-# define STATUS_FILES_OPEN ((NTSTATUS) 0xC0000107L)
-#endif
-
-#ifndef STATUS_CONNECTION_IN_USE
-# define STATUS_CONNECTION_IN_USE ((NTSTATUS) 0xC0000108L)
-#endif
-
-#ifndef STATUS_MESSAGE_NOT_FOUND
-# define STATUS_MESSAGE_NOT_FOUND ((NTSTATUS) 0xC0000109L)
-#endif
-
-#ifndef STATUS_PROCESS_IS_TERMINATING
-# define STATUS_PROCESS_IS_TERMINATING ((NTSTATUS) 0xC000010AL)
-#endif
-
-#ifndef STATUS_INVALID_LOGON_TYPE
-# define STATUS_INVALID_LOGON_TYPE ((NTSTATUS) 0xC000010BL)
-#endif
-
-#ifndef STATUS_NO_GUID_TRANSLATION
-# define STATUS_NO_GUID_TRANSLATION ((NTSTATUS) 0xC000010CL)
-#endif
-
-#ifndef STATUS_CANNOT_IMPERSONATE
-# define STATUS_CANNOT_IMPERSONATE ((NTSTATUS) 0xC000010DL)
-#endif
-
-#ifndef STATUS_IMAGE_ALREADY_LOADED
-# define STATUS_IMAGE_ALREADY_LOADED ((NTSTATUS) 0xC000010EL)
-#endif
-
-#ifndef STATUS_ABIOS_NOT_PRESENT
-# define STATUS_ABIOS_NOT_PRESENT ((NTSTATUS) 0xC000010FL)
-#endif
-
-#ifndef STATUS_ABIOS_LID_NOT_EXIST
-# define STATUS_ABIOS_LID_NOT_EXIST ((NTSTATUS) 0xC0000110L)
-#endif
-
-#ifndef STATUS_ABIOS_LID_ALREADY_OWNED
-# define STATUS_ABIOS_LID_ALREADY_OWNED ((NTSTATUS) 0xC0000111L)
-#endif
-
-#ifndef STATUS_ABIOS_NOT_LID_OWNER
-# define STATUS_ABIOS_NOT_LID_OWNER ((NTSTATUS) 0xC0000112L)
-#endif
-
-#ifndef STATUS_ABIOS_INVALID_COMMAND
-# define STATUS_ABIOS_INVALID_COMMAND ((NTSTATUS) 0xC0000113L)
-#endif
-
-#ifndef STATUS_ABIOS_INVALID_LID
-# define STATUS_ABIOS_INVALID_LID ((NTSTATUS) 0xC0000114L)
-#endif
-
-#ifndef STATUS_ABIOS_SELECTOR_NOT_AVAILABLE
-# define STATUS_ABIOS_SELECTOR_NOT_AVAILABLE ((NTSTATUS) 0xC0000115L)
-#endif
-
-#ifndef STATUS_ABIOS_INVALID_SELECTOR
-# define STATUS_ABIOS_INVALID_SELECTOR ((NTSTATUS) 0xC0000116L)
-#endif
-
-#ifndef STATUS_NO_LDT
-# define STATUS_NO_LDT ((NTSTATUS) 0xC0000117L)
-#endif
-
-#ifndef STATUS_INVALID_LDT_SIZE
-# define STATUS_INVALID_LDT_SIZE ((NTSTATUS) 0xC0000118L)
-#endif
-
-#ifndef STATUS_INVALID_LDT_OFFSET
-# define STATUS_INVALID_LDT_OFFSET ((NTSTATUS) 0xC0000119L)
-#endif
-
-#ifndef STATUS_INVALID_LDT_DESCRIPTOR
-# define STATUS_INVALID_LDT_DESCRIPTOR ((NTSTATUS) 0xC000011AL)
-#endif
-
-#ifndef STATUS_INVALID_IMAGE_NE_FORMAT
-# define STATUS_INVALID_IMAGE_NE_FORMAT ((NTSTATUS) 0xC000011BL)
-#endif
-
-#ifndef STATUS_RXACT_INVALID_STATE
-# define STATUS_RXACT_INVALID_STATE ((NTSTATUS) 0xC000011CL)
-#endif
-
-#ifndef STATUS_RXACT_COMMIT_FAILURE
-# define STATUS_RXACT_COMMIT_FAILURE ((NTSTATUS) 0xC000011DL)
-#endif
-
-#ifndef STATUS_MAPPED_FILE_SIZE_ZERO
-# define STATUS_MAPPED_FILE_SIZE_ZERO ((NTSTATUS) 0xC000011EL)
-#endif
-
-#ifndef STATUS_TOO_MANY_OPENED_FILES
-# define STATUS_TOO_MANY_OPENED_FILES ((NTSTATUS) 0xC000011FL)
-#endif
-
-#ifndef STATUS_CANCELLED
-# define STATUS_CANCELLED ((NTSTATUS) 0xC0000120L)
-#endif
-
-#ifndef STATUS_CANNOT_DELETE
-# define STATUS_CANNOT_DELETE ((NTSTATUS) 0xC0000121L)
-#endif
-
-#ifndef STATUS_INVALID_COMPUTER_NAME
-# define STATUS_INVALID_COMPUTER_NAME ((NTSTATUS) 0xC0000122L)
-#endif
-
-#ifndef STATUS_FILE_DELETED
-# define STATUS_FILE_DELETED ((NTSTATUS) 0xC0000123L)
-#endif
-
-#ifndef STATUS_SPECIAL_ACCOUNT
-# define STATUS_SPECIAL_ACCOUNT ((NTSTATUS) 0xC0000124L)
-#endif
-
-#ifndef STATUS_SPECIAL_GROUP
-# define STATUS_SPECIAL_GROUP ((NTSTATUS) 0xC0000125L)
-#endif
-
-#ifndef STATUS_SPECIAL_USER
-# define STATUS_SPECIAL_USER ((NTSTATUS) 0xC0000126L)
-#endif
-
-#ifndef STATUS_MEMBERS_PRIMARY_GROUP
-# define STATUS_MEMBERS_PRIMARY_GROUP ((NTSTATUS) 0xC0000127L)
-#endif
-
-#ifndef STATUS_FILE_CLOSED
-# define STATUS_FILE_CLOSED ((NTSTATUS) 0xC0000128L)
-#endif
-
-#ifndef STATUS_TOO_MANY_THREADS
-# define STATUS_TOO_MANY_THREADS ((NTSTATUS) 0xC0000129L)
-#endif
-
-#ifndef STATUS_THREAD_NOT_IN_PROCESS
-# define STATUS_THREAD_NOT_IN_PROCESS ((NTSTATUS) 0xC000012AL)
-#endif
-
-#ifndef STATUS_TOKEN_ALREADY_IN_USE
-# define STATUS_TOKEN_ALREADY_IN_USE ((NTSTATUS) 0xC000012BL)
-#endif
-
-#ifndef STATUS_PAGEFILE_QUOTA_EXCEEDED
-# define STATUS_PAGEFILE_QUOTA_EXCEEDED ((NTSTATUS) 0xC000012CL)
-#endif
-
-#ifndef STATUS_COMMITMENT_LIMIT
-# define STATUS_COMMITMENT_LIMIT ((NTSTATUS) 0xC000012DL)
-#endif
-
-#ifndef STATUS_INVALID_IMAGE_LE_FORMAT
-# define STATUS_INVALID_IMAGE_LE_FORMAT ((NTSTATUS) 0xC000012EL)
-#endif
-
-#ifndef STATUS_INVALID_IMAGE_NOT_MZ
-# define STATUS_INVALID_IMAGE_NOT_MZ ((NTSTATUS) 0xC000012FL)
-#endif
-
-#ifndef STATUS_INVALID_IMAGE_PROTECT
-# define STATUS_INVALID_IMAGE_PROTECT ((NTSTATUS) 0xC0000130L)
-#endif
-
-#ifndef STATUS_INVALID_IMAGE_WIN_16
-# define STATUS_INVALID_IMAGE_WIN_16 ((NTSTATUS) 0xC0000131L)
-#endif
-
-#ifndef STATUS_LOGON_SERVER_CONFLICT
-# define STATUS_LOGON_SERVER_CONFLICT ((NTSTATUS) 0xC0000132L)
-#endif
-
-#ifndef STATUS_TIME_DIFFERENCE_AT_DC
-# define STATUS_TIME_DIFFERENCE_AT_DC ((NTSTATUS) 0xC0000133L)
-#endif
-
-#ifndef STATUS_SYNCHRONIZATION_REQUIRED
-# define STATUS_SYNCHRONIZATION_REQUIRED ((NTSTATUS) 0xC0000134L)
-#endif
-
-#ifndef STATUS_DLL_NOT_FOUND
-# define STATUS_DLL_NOT_FOUND ((NTSTATUS) 0xC0000135L)
-#endif
-
-#ifndef STATUS_OPEN_FAILED
-# define STATUS_OPEN_FAILED ((NTSTATUS) 0xC0000136L)
-#endif
-
-#ifndef STATUS_IO_PRIVILEGE_FAILED
-# define STATUS_IO_PRIVILEGE_FAILED ((NTSTATUS) 0xC0000137L)
-#endif
-
-#ifndef STATUS_ORDINAL_NOT_FOUND
-# define STATUS_ORDINAL_NOT_FOUND ((NTSTATUS) 0xC0000138L)
-#endif
-
-#ifndef STATUS_ENTRYPOINT_NOT_FOUND
-# define STATUS_ENTRYPOINT_NOT_FOUND ((NTSTATUS) 0xC0000139L)
-#endif
-
-#ifndef STATUS_CONTROL_C_EXIT
-# define STATUS_CONTROL_C_EXIT ((NTSTATUS) 0xC000013AL)
-#endif
-
-#ifndef STATUS_LOCAL_DISCONNECT
-# define STATUS_LOCAL_DISCONNECT ((NTSTATUS) 0xC000013BL)
-#endif
-
-#ifndef STATUS_REMOTE_DISCONNECT
-# define STATUS_REMOTE_DISCONNECT ((NTSTATUS) 0xC000013CL)
-#endif
-
-#ifndef STATUS_REMOTE_RESOURCES
-# define STATUS_REMOTE_RESOURCES ((NTSTATUS) 0xC000013DL)
-#endif
-
-#ifndef STATUS_LINK_FAILED
-# define STATUS_LINK_FAILED ((NTSTATUS) 0xC000013EL)
-#endif
-
-#ifndef STATUS_LINK_TIMEOUT
-# define STATUS_LINK_TIMEOUT ((NTSTATUS) 0xC000013FL)
-#endif
-
-#ifndef STATUS_INVALID_CONNECTION
-# define STATUS_INVALID_CONNECTION ((NTSTATUS) 0xC0000140L)
-#endif
-
-#ifndef STATUS_INVALID_ADDRESS
-# define STATUS_INVALID_ADDRESS ((NTSTATUS) 0xC0000141L)
-#endif
-
-#ifndef STATUS_DLL_INIT_FAILED
-# define STATUS_DLL_INIT_FAILED ((NTSTATUS) 0xC0000142L)
-#endif
-
-#ifndef STATUS_MISSING_SYSTEMFILE
-# define STATUS_MISSING_SYSTEMFILE ((NTSTATUS) 0xC0000143L)
-#endif
-
-#ifndef STATUS_UNHANDLED_EXCEPTION
-# define STATUS_UNHANDLED_EXCEPTION ((NTSTATUS) 0xC0000144L)
-#endif
-
-#ifndef STATUS_APP_INIT_FAILURE
-# define STATUS_APP_INIT_FAILURE ((NTSTATUS) 0xC0000145L)
-#endif
-
-#ifndef STATUS_PAGEFILE_CREATE_FAILED
-# define STATUS_PAGEFILE_CREATE_FAILED ((NTSTATUS) 0xC0000146L)
-#endif
-
-#ifndef STATUS_NO_PAGEFILE
-# define STATUS_NO_PAGEFILE ((NTSTATUS) 0xC0000147L)
-#endif
-
-#ifndef STATUS_INVALID_LEVEL
-# define STATUS_INVALID_LEVEL ((NTSTATUS) 0xC0000148L)
-#endif
-
-#ifndef STATUS_WRONG_PASSWORD_CORE
-# define STATUS_WRONG_PASSWORD_CORE ((NTSTATUS) 0xC0000149L)
-#endif
-
-#ifndef STATUS_ILLEGAL_FLOAT_CONTEXT
-# define STATUS_ILLEGAL_FLOAT_CONTEXT ((NTSTATUS) 0xC000014AL)
-#endif
-
-#ifndef STATUS_PIPE_BROKEN
-# define STATUS_PIPE_BROKEN ((NTSTATUS) 0xC000014BL)
-#endif
-
-#ifndef STATUS_REGISTRY_CORRUPT
-# define STATUS_REGISTRY_CORRUPT ((NTSTATUS) 0xC000014CL)
-#endif
-
-#ifndef STATUS_REGISTRY_IO_FAILED
-# define STATUS_REGISTRY_IO_FAILED ((NTSTATUS) 0xC000014DL)
-#endif
-
-#ifndef STATUS_NO_EVENT_PAIR
-# define STATUS_NO_EVENT_PAIR ((NTSTATUS) 0xC000014EL)
-#endif
-
-#ifndef STATUS_UNRECOGNIZED_VOLUME
-# define STATUS_UNRECOGNIZED_VOLUME ((NTSTATUS) 0xC000014FL)
-#endif
-
-#ifndef STATUS_SERIAL_NO_DEVICE_INITED
-# define STATUS_SERIAL_NO_DEVICE_INITED ((NTSTATUS) 0xC0000150L)
-#endif
-
-#ifndef STATUS_NO_SUCH_ALIAS
-# define STATUS_NO_SUCH_ALIAS ((NTSTATUS) 0xC0000151L)
-#endif
-
-#ifndef STATUS_MEMBER_NOT_IN_ALIAS
-# define STATUS_MEMBER_NOT_IN_ALIAS ((NTSTATUS) 0xC0000152L)
-#endif
-
-#ifndef STATUS_MEMBER_IN_ALIAS
-# define STATUS_MEMBER_IN_ALIAS ((NTSTATUS) 0xC0000153L)
-#endif
-
-#ifndef STATUS_ALIAS_EXISTS
-# define STATUS_ALIAS_EXISTS ((NTSTATUS) 0xC0000154L)
-#endif
-
-#ifndef STATUS_LOGON_NOT_GRANTED
-# define STATUS_LOGON_NOT_GRANTED ((NTSTATUS) 0xC0000155L)
-#endif
-
-#ifndef STATUS_TOO_MANY_SECRETS
-# define STATUS_TOO_MANY_SECRETS ((NTSTATUS) 0xC0000156L)
-#endif
-
-#ifndef STATUS_SECRET_TOO_LONG
-# define STATUS_SECRET_TOO_LONG ((NTSTATUS) 0xC0000157L)
-#endif
-
-#ifndef STATUS_INTERNAL_DB_ERROR
-# define STATUS_INTERNAL_DB_ERROR ((NTSTATUS) 0xC0000158L)
-#endif
-
-#ifndef STATUS_FULLSCREEN_MODE
-# define STATUS_FULLSCREEN_MODE ((NTSTATUS) 0xC0000159L)
-#endif
-
-#ifndef STATUS_TOO_MANY_CONTEXT_IDS
-# define STATUS_TOO_MANY_CONTEXT_IDS ((NTSTATUS) 0xC000015AL)
-#endif
-
-#ifndef STATUS_LOGON_TYPE_NOT_GRANTED
-# define STATUS_LOGON_TYPE_NOT_GRANTED ((NTSTATUS) 0xC000015BL)
-#endif
-
-#ifndef STATUS_NOT_REGISTRY_FILE
-# define STATUS_NOT_REGISTRY_FILE ((NTSTATUS) 0xC000015CL)
-#endif
-
-#ifndef STATUS_NT_CROSS_ENCRYPTION_REQUIRED
-# define STATUS_NT_CROSS_ENCRYPTION_REQUIRED ((NTSTATUS) 0xC000015DL)
-#endif
-
-#ifndef STATUS_DOMAIN_CTRLR_CONFIG_ERROR
-# define STATUS_DOMAIN_CTRLR_CONFIG_ERROR ((NTSTATUS) 0xC000015EL)
-#endif
-
-#ifndef STATUS_FT_MISSING_MEMBER
-# define STATUS_FT_MISSING_MEMBER ((NTSTATUS) 0xC000015FL)
-#endif
-
-#ifndef STATUS_ILL_FORMED_SERVICE_ENTRY
-# define STATUS_ILL_FORMED_SERVICE_ENTRY ((NTSTATUS) 0xC0000160L)
-#endif
-
-#ifndef STATUS_ILLEGAL_CHARACTER
-# define STATUS_ILLEGAL_CHARACTER ((NTSTATUS) 0xC0000161L)
-#endif
-
-#ifndef STATUS_UNMAPPABLE_CHARACTER
-# define STATUS_UNMAPPABLE_CHARACTER ((NTSTATUS) 0xC0000162L)
-#endif
-
-#ifndef STATUS_UNDEFINED_CHARACTER
-# define STATUS_UNDEFINED_CHARACTER ((NTSTATUS) 0xC0000163L)
-#endif
-
-#ifndef STATUS_FLOPPY_VOLUME
-# define STATUS_FLOPPY_VOLUME ((NTSTATUS) 0xC0000164L)
-#endif
-
-#ifndef STATUS_FLOPPY_ID_MARK_NOT_FOUND
-# define STATUS_FLOPPY_ID_MARK_NOT_FOUND ((NTSTATUS) 0xC0000165L)
-#endif
-
-#ifndef STATUS_FLOPPY_WRONG_CYLINDER
-# define STATUS_FLOPPY_WRONG_CYLINDER ((NTSTATUS) 0xC0000166L)
-#endif
-
-#ifndef STATUS_FLOPPY_UNKNOWN_ERROR
-# define STATUS_FLOPPY_UNKNOWN_ERROR ((NTSTATUS) 0xC0000167L)
-#endif
-
-#ifndef STATUS_FLOPPY_BAD_REGISTERS
-# define STATUS_FLOPPY_BAD_REGISTERS ((NTSTATUS) 0xC0000168L)
-#endif
-
-#ifndef STATUS_DISK_RECALIBRATE_FAILED
-# define STATUS_DISK_RECALIBRATE_FAILED ((NTSTATUS) 0xC0000169L)
-#endif
-
-#ifndef STATUS_DISK_OPERATION_FAILED
-# define STATUS_DISK_OPERATION_FAILED ((NTSTATUS) 0xC000016AL)
-#endif
-
-#ifndef STATUS_DISK_RESET_FAILED
-# define STATUS_DISK_RESET_FAILED ((NTSTATUS) 0xC000016BL)
-#endif
-
-#ifndef STATUS_SHARED_IRQ_BUSY
-# define STATUS_SHARED_IRQ_BUSY ((NTSTATUS) 0xC000016CL)
-#endif
-
-#ifndef STATUS_FT_ORPHANING
-# define STATUS_FT_ORPHANING ((NTSTATUS) 0xC000016DL)
-#endif
-
-#ifndef STATUS_BIOS_FAILED_TO_CONNECT_INTERRUPT
-# define STATUS_BIOS_FAILED_TO_CONNECT_INTERRUPT ((NTSTATUS) 0xC000016EL)
-#endif
-
-#ifndef STATUS_PARTITION_FAILURE
-# define STATUS_PARTITION_FAILURE ((NTSTATUS) 0xC0000172L)
-#endif
-
-#ifndef STATUS_INVALID_BLOCK_LENGTH
-# define STATUS_INVALID_BLOCK_LENGTH ((NTSTATUS) 0xC0000173L)
-#endif
-
-#ifndef STATUS_DEVICE_NOT_PARTITIONED
-# define STATUS_DEVICE_NOT_PARTITIONED ((NTSTATUS) 0xC0000174L)
-#endif
-
-#ifndef STATUS_UNABLE_TO_LOCK_MEDIA
-# define STATUS_UNABLE_TO_LOCK_MEDIA ((NTSTATUS) 0xC0000175L)
-#endif
-
-#ifndef STATUS_UNABLE_TO_UNLOAD_MEDIA
-# define STATUS_UNABLE_TO_UNLOAD_MEDIA ((NTSTATUS) 0xC0000176L)
-#endif
-
-#ifndef STATUS_EOM_OVERFLOW
-# define STATUS_EOM_OVERFLOW ((NTSTATUS) 0xC0000177L)
-#endif
-
-#ifndef STATUS_NO_MEDIA
-# define STATUS_NO_MEDIA ((NTSTATUS) 0xC0000178L)
-#endif
-
-#ifndef STATUS_NO_SUCH_MEMBER
-# define STATUS_NO_SUCH_MEMBER ((NTSTATUS) 0xC000017AL)
-#endif
-
-#ifndef STATUS_INVALID_MEMBER
-# define STATUS_INVALID_MEMBER ((NTSTATUS) 0xC000017BL)
-#endif
-
-#ifndef STATUS_KEY_DELETED
-# define STATUS_KEY_DELETED ((NTSTATUS) 0xC000017CL)
-#endif
-
-#ifndef STATUS_NO_LOG_SPACE
-# define STATUS_NO_LOG_SPACE ((NTSTATUS) 0xC000017DL)
-#endif
-
-#ifndef STATUS_TOO_MANY_SIDS
-# define STATUS_TOO_MANY_SIDS ((NTSTATUS) 0xC000017EL)
-#endif
-
-#ifndef STATUS_LM_CROSS_ENCRYPTION_REQUIRED
-# define STATUS_LM_CROSS_ENCRYPTION_REQUIRED ((NTSTATUS) 0xC000017FL)
-#endif
-
-#ifndef STATUS_KEY_HAS_CHILDREN
-# define STATUS_KEY_HAS_CHILDREN ((NTSTATUS) 0xC0000180L)
-#endif
-
-#ifndef STATUS_CHILD_MUST_BE_VOLATILE
-# define STATUS_CHILD_MUST_BE_VOLATILE ((NTSTATUS) 0xC0000181L)
-#endif
-
-#ifndef STATUS_DEVICE_CONFIGURATION_ERROR
-# define STATUS_DEVICE_CONFIGURATION_ERROR ((NTSTATUS) 0xC0000182L)
-#endif
-
-#ifndef STATUS_DRIVER_INTERNAL_ERROR
-# define STATUS_DRIVER_INTERNAL_ERROR ((NTSTATUS) 0xC0000183L)
-#endif
-
-#ifndef STATUS_INVALID_DEVICE_STATE
-# define STATUS_INVALID_DEVICE_STATE ((NTSTATUS) 0xC0000184L)
-#endif
-
-#ifndef STATUS_IO_DEVICE_ERROR
-# define STATUS_IO_DEVICE_ERROR ((NTSTATUS) 0xC0000185L)
-#endif
-
-#ifndef STATUS_DEVICE_PROTOCOL_ERROR
-# define STATUS_DEVICE_PROTOCOL_ERROR ((NTSTATUS) 0xC0000186L)
-#endif
-
-#ifndef STATUS_BACKUP_CONTROLLER
-# define STATUS_BACKUP_CONTROLLER ((NTSTATUS) 0xC0000187L)
-#endif
-
-#ifndef STATUS_LOG_FILE_FULL
-# define STATUS_LOG_FILE_FULL ((NTSTATUS) 0xC0000188L)
-#endif
-
-#ifndef STATUS_TOO_LATE
-# define STATUS_TOO_LATE ((NTSTATUS) 0xC0000189L)
-#endif
-
-#ifndef STATUS_NO_TRUST_LSA_SECRET
-# define STATUS_NO_TRUST_LSA_SECRET ((NTSTATUS) 0xC000018AL)
-#endif
-
-#ifndef STATUS_NO_TRUST_SAM_ACCOUNT
-# define STATUS_NO_TRUST_SAM_ACCOUNT ((NTSTATUS) 0xC000018BL)
-#endif
-
-#ifndef STATUS_TRUSTED_DOMAIN_FAILURE
-# define STATUS_TRUSTED_DOMAIN_FAILURE ((NTSTATUS) 0xC000018CL)
-#endif
-
-#ifndef STATUS_TRUSTED_RELATIONSHIP_FAILURE
-# define STATUS_TRUSTED_RELATIONSHIP_FAILURE ((NTSTATUS) 0xC000018DL)
-#endif
-
-#ifndef STATUS_EVENTLOG_FILE_CORRUPT
-# define STATUS_EVENTLOG_FILE_CORRUPT ((NTSTATUS) 0xC000018EL)
-#endif
-
-#ifndef STATUS_EVENTLOG_CANT_START
-# define STATUS_EVENTLOG_CANT_START ((NTSTATUS) 0xC000018FL)
-#endif
-
-#ifndef STATUS_TRUST_FAILURE
-# define STATUS_TRUST_FAILURE ((NTSTATUS) 0xC0000190L)
-#endif
-
-#ifndef STATUS_MUTANT_LIMIT_EXCEEDED
-# define STATUS_MUTANT_LIMIT_EXCEEDED ((NTSTATUS) 0xC0000191L)
-#endif
-
-#ifndef STATUS_NETLOGON_NOT_STARTED
-# define STATUS_NETLOGON_NOT_STARTED ((NTSTATUS) 0xC0000192L)
-#endif
-
-#ifndef STATUS_ACCOUNT_EXPIRED
-# define STATUS_ACCOUNT_EXPIRED ((NTSTATUS) 0xC0000193L)
-#endif
-
-#ifndef STATUS_POSSIBLE_DEADLOCK
-# define STATUS_POSSIBLE_DEADLOCK ((NTSTATUS) 0xC0000194L)
-#endif
-
-#ifndef STATUS_NETWORK_CREDENTIAL_CONFLICT
-# define STATUS_NETWORK_CREDENTIAL_CONFLICT ((NTSTATUS) 0xC0000195L)
-#endif
-
-#ifndef STATUS_REMOTE_SESSION_LIMIT
-# define STATUS_REMOTE_SESSION_LIMIT ((NTSTATUS) 0xC0000196L)
-#endif
-
-#ifndef STATUS_EVENTLOG_FILE_CHANGED
-# define STATUS_EVENTLOG_FILE_CHANGED ((NTSTATUS) 0xC0000197L)
-#endif
-
-#ifndef STATUS_NOLOGON_INTERDOMAIN_TRUST_ACCOUNT
-# define STATUS_NOLOGON_INTERDOMAIN_TRUST_ACCOUNT ((NTSTATUS) 0xC0000198L)
-#endif
-
-#ifndef STATUS_NOLOGON_WORKSTATION_TRUST_ACCOUNT
-# define STATUS_NOLOGON_WORKSTATION_TRUST_ACCOUNT ((NTSTATUS) 0xC0000199L)
-#endif
-
-#ifndef STATUS_NOLOGON_SERVER_TRUST_ACCOUNT
-# define STATUS_NOLOGON_SERVER_TRUST_ACCOUNT ((NTSTATUS) 0xC000019AL)
-#endif
-
-#ifndef STATUS_DOMAIN_TRUST_INCONSISTENT
-# define STATUS_DOMAIN_TRUST_INCONSISTENT ((NTSTATUS) 0xC000019BL)
-#endif
-
-#ifndef STATUS_FS_DRIVER_REQUIRED
-# define STATUS_FS_DRIVER_REQUIRED ((NTSTATUS) 0xC000019CL)
-#endif
-
-#ifndef STATUS_IMAGE_ALREADY_LOADED_AS_DLL
-# define STATUS_IMAGE_ALREADY_LOADED_AS_DLL ((NTSTATUS) 0xC000019DL)
-#endif
-
-#ifndef STATUS_INCOMPATIBLE_WITH_GLOBAL_SHORT_NAME_REGISTRY_SETTING
-# define STATUS_INCOMPATIBLE_WITH_GLOBAL_SHORT_NAME_REGISTRY_SETTING ((NTSTATUS) 0xC000019EL)
-#endif
-
-#ifndef STATUS_SHORT_NAMES_NOT_ENABLED_ON_VOLUME
-# define STATUS_SHORT_NAMES_NOT_ENABLED_ON_VOLUME ((NTSTATUS) 0xC000019FL)
-#endif
-
-#ifndef STATUS_SECURITY_STREAM_IS_INCONSISTENT
-# define STATUS_SECURITY_STREAM_IS_INCONSISTENT ((NTSTATUS) 0xC00001A0L)
-#endif
-
-#ifndef STATUS_INVALID_LOCK_RANGE
-# define STATUS_INVALID_LOCK_RANGE ((NTSTATUS) 0xC00001A1L)
-#endif
-
-#ifndef STATUS_INVALID_ACE_CONDITION
-# define STATUS_INVALID_ACE_CONDITION ((NTSTATUS) 0xC00001A2L)
-#endif
-
-#ifndef STATUS_IMAGE_SUBSYSTEM_NOT_PRESENT
-# define STATUS_IMAGE_SUBSYSTEM_NOT_PRESENT ((NTSTATUS) 0xC00001A3L)
-#endif
-
-#ifndef STATUS_NOTIFICATION_GUID_ALREADY_DEFINED
-# define STATUS_NOTIFICATION_GUID_ALREADY_DEFINED ((NTSTATUS) 0xC00001A4L)
-#endif
-
-#ifndef STATUS_NETWORK_OPEN_RESTRICTION
-# define STATUS_NETWORK_OPEN_RESTRICTION ((NTSTATUS) 0xC0000201L)
-#endif
-
-#ifndef STATUS_NO_USER_SESSION_KEY
-# define STATUS_NO_USER_SESSION_KEY ((NTSTATUS) 0xC0000202L)
-#endif
-
-#ifndef STATUS_USER_SESSION_DELETED
-# define STATUS_USER_SESSION_DELETED ((NTSTATUS) 0xC0000203L)
-#endif
-
-#ifndef STATUS_RESOURCE_LANG_NOT_FOUND
-# define STATUS_RESOURCE_LANG_NOT_FOUND ((NTSTATUS) 0xC0000204L)
-#endif
-
-#ifndef STATUS_INSUFF_SERVER_RESOURCES
-# define STATUS_INSUFF_SERVER_RESOURCES ((NTSTATUS) 0xC0000205L)
-#endif
-
-#ifndef STATUS_INVALID_BUFFER_SIZE
-# define STATUS_INVALID_BUFFER_SIZE ((NTSTATUS) 0xC0000206L)
-#endif
-
-#ifndef STATUS_INVALID_ADDRESS_COMPONENT
-# define STATUS_INVALID_ADDRESS_COMPONENT ((NTSTATUS) 0xC0000207L)
-#endif
-
-#ifndef STATUS_INVALID_ADDRESS_WILDCARD
-# define STATUS_INVALID_ADDRESS_WILDCARD ((NTSTATUS) 0xC0000208L)
-#endif
-
-#ifndef STATUS_TOO_MANY_ADDRESSES
-# define STATUS_TOO_MANY_ADDRESSES ((NTSTATUS) 0xC0000209L)
-#endif
-
-#ifndef STATUS_ADDRESS_ALREADY_EXISTS
-# define STATUS_ADDRESS_ALREADY_EXISTS ((NTSTATUS) 0xC000020AL)
-#endif
-
-#ifndef STATUS_ADDRESS_CLOSED
-# define STATUS_ADDRESS_CLOSED ((NTSTATUS) 0xC000020BL)
-#endif
-
-#ifndef STATUS_CONNECTION_DISCONNECTED
-# define STATUS_CONNECTION_DISCONNECTED ((NTSTATUS) 0xC000020CL)
-#endif
-
-#ifndef STATUS_CONNECTION_RESET
-# define STATUS_CONNECTION_RESET ((NTSTATUS) 0xC000020DL)
-#endif
-
-#ifndef STATUS_TOO_MANY_NODES
-# define STATUS_TOO_MANY_NODES ((NTSTATUS) 0xC000020EL)
-#endif
-
-#ifndef STATUS_TRANSACTION_ABORTED
-# define STATUS_TRANSACTION_ABORTED ((NTSTATUS) 0xC000020FL)
-#endif
-
-#ifndef STATUS_TRANSACTION_TIMED_OUT
-# define STATUS_TRANSACTION_TIMED_OUT ((NTSTATUS) 0xC0000210L)
-#endif
-
-#ifndef STATUS_TRANSACTION_NO_RELEASE
-# define STATUS_TRANSACTION_NO_RELEASE ((NTSTATUS) 0xC0000211L)
-#endif
-
-#ifndef STATUS_TRANSACTION_NO_MATCH
-# define STATUS_TRANSACTION_NO_MATCH ((NTSTATUS) 0xC0000212L)
-#endif
-
-#ifndef STATUS_TRANSACTION_RESPONDED
-# define STATUS_TRANSACTION_RESPONDED ((NTSTATUS) 0xC0000213L)
-#endif
-
-#ifndef STATUS_TRANSACTION_INVALID_ID
-# define STATUS_TRANSACTION_INVALID_ID ((NTSTATUS) 0xC0000214L)
-#endif
-
-#ifndef STATUS_TRANSACTION_INVALID_TYPE
-# define STATUS_TRANSACTION_INVALID_TYPE ((NTSTATUS) 0xC0000215L)
-#endif
-
-#ifndef STATUS_NOT_SERVER_SESSION
-# define STATUS_NOT_SERVER_SESSION ((NTSTATUS) 0xC0000216L)
-#endif
-
-#ifndef STATUS_NOT_CLIENT_SESSION
-# define STATUS_NOT_CLIENT_SESSION ((NTSTATUS) 0xC0000217L)
-#endif
-
-#ifndef STATUS_CANNOT_LOAD_REGISTRY_FILE
-# define STATUS_CANNOT_LOAD_REGISTRY_FILE ((NTSTATUS) 0xC0000218L)
-#endif
-
-#ifndef STATUS_DEBUG_ATTACH_FAILED
-# define STATUS_DEBUG_ATTACH_FAILED ((NTSTATUS) 0xC0000219L)
-#endif
-
-#ifndef STATUS_SYSTEM_PROCESS_TERMINATED
-# define STATUS_SYSTEM_PROCESS_TERMINATED ((NTSTATUS) 0xC000021AL)
-#endif
-
-#ifndef STATUS_DATA_NOT_ACCEPTED
-# define STATUS_DATA_NOT_ACCEPTED ((NTSTATUS) 0xC000021BL)
-#endif
-
-#ifndef STATUS_NO_BROWSER_SERVERS_FOUND
-# define STATUS_NO_BROWSER_SERVERS_FOUND ((NTSTATUS) 0xC000021CL)
-#endif
-
-#ifndef STATUS_VDM_HARD_ERROR
-# define STATUS_VDM_HARD_ERROR ((NTSTATUS) 0xC000021DL)
-#endif
-
-#ifndef STATUS_DRIVER_CANCEL_TIMEOUT
-# define STATUS_DRIVER_CANCEL_TIMEOUT ((NTSTATUS) 0xC000021EL)
-#endif
-
-#ifndef STATUS_REPLY_MESSAGE_MISMATCH
-# define STATUS_REPLY_MESSAGE_MISMATCH ((NTSTATUS) 0xC000021FL)
-#endif
-
-#ifndef STATUS_MAPPED_ALIGNMENT
-# define STATUS_MAPPED_ALIGNMENT ((NTSTATUS) 0xC0000220L)
-#endif
-
-#ifndef STATUS_IMAGE_CHECKSUM_MISMATCH
-# define STATUS_IMAGE_CHECKSUM_MISMATCH ((NTSTATUS) 0xC0000221L)
-#endif
-
-#ifndef STATUS_LOST_WRITEBEHIND_DATA
-# define STATUS_LOST_WRITEBEHIND_DATA ((NTSTATUS) 0xC0000222L)
-#endif
-
-#ifndef STATUS_CLIENT_SERVER_PARAMETERS_INVALID
-# define STATUS_CLIENT_SERVER_PARAMETERS_INVALID ((NTSTATUS) 0xC0000223L)
-#endif
-
-#ifndef STATUS_PASSWORD_MUST_CHANGE
-# define STATUS_PASSWORD_MUST_CHANGE ((NTSTATUS) 0xC0000224L)
-#endif
-
-#ifndef STATUS_NOT_FOUND
-# define STATUS_NOT_FOUND ((NTSTATUS) 0xC0000225L)
-#endif
-
-#ifndef STATUS_NOT_TINY_STREAM
-# define STATUS_NOT_TINY_STREAM ((NTSTATUS) 0xC0000226L)
-#endif
-
-#ifndef STATUS_RECOVERY_FAILURE
-# define STATUS_RECOVERY_FAILURE ((NTSTATUS) 0xC0000227L)
-#endif
-
-#ifndef STATUS_STACK_OVERFLOW_READ
-# define STATUS_STACK_OVERFLOW_READ ((NTSTATUS) 0xC0000228L)
-#endif
-
-#ifndef STATUS_FAIL_CHECK
-# define STATUS_FAIL_CHECK ((NTSTATUS) 0xC0000229L)
-#endif
-
-#ifndef STATUS_DUPLICATE_OBJECTID
-# define STATUS_DUPLICATE_OBJECTID ((NTSTATUS) 0xC000022AL)
-#endif
-
-#ifndef STATUS_OBJECTID_EXISTS
-# define STATUS_OBJECTID_EXISTS ((NTSTATUS) 0xC000022BL)
-#endif
-
-#ifndef STATUS_CONVERT_TO_LARGE
-# define STATUS_CONVERT_TO_LARGE ((NTSTATUS) 0xC000022CL)
-#endif
-
-#ifndef STATUS_RETRY
-# define STATUS_RETRY ((NTSTATUS) 0xC000022DL)
-#endif
-
-#ifndef STATUS_FOUND_OUT_OF_SCOPE
-# define STATUS_FOUND_OUT_OF_SCOPE ((NTSTATUS) 0xC000022EL)
-#endif
-
-#ifndef STATUS_ALLOCATE_BUCKET
-# define STATUS_ALLOCATE_BUCKET ((NTSTATUS) 0xC000022FL)
-#endif
-
-#ifndef STATUS_PROPSET_NOT_FOUND
-# define STATUS_PROPSET_NOT_FOUND ((NTSTATUS) 0xC0000230L)
-#endif
-
-#ifndef STATUS_MARSHALL_OVERFLOW
-# define STATUS_MARSHALL_OVERFLOW ((NTSTATUS) 0xC0000231L)
-#endif
-
-#ifndef STATUS_INVALID_VARIANT
-# define STATUS_INVALID_VARIANT ((NTSTATUS) 0xC0000232L)
-#endif
-
-#ifndef STATUS_DOMAIN_CONTROLLER_NOT_FOUND
-# define STATUS_DOMAIN_CONTROLLER_NOT_FOUND ((NTSTATUS) 0xC0000233L)
-#endif
-
-#ifndef STATUS_ACCOUNT_LOCKED_OUT
-# define STATUS_ACCOUNT_LOCKED_OUT ((NTSTATUS) 0xC0000234L)
-#endif
-
-#ifndef STATUS_HANDLE_NOT_CLOSABLE
-# define STATUS_HANDLE_NOT_CLOSABLE ((NTSTATUS) 0xC0000235L)
-#endif
-
-#ifndef STATUS_CONNECTION_REFUSED
-# define STATUS_CONNECTION_REFUSED ((NTSTATUS) 0xC0000236L)
-#endif
-
-#ifndef STATUS_GRACEFUL_DISCONNECT
-# define STATUS_GRACEFUL_DISCONNECT ((NTSTATUS) 0xC0000237L)
-#endif
-
-#ifndef STATUS_ADDRESS_ALREADY_ASSOCIATED
-# define STATUS_ADDRESS_ALREADY_ASSOCIATED ((NTSTATUS) 0xC0000238L)
-#endif
-
-#ifndef STATUS_ADDRESS_NOT_ASSOCIATED
-# define STATUS_ADDRESS_NOT_ASSOCIATED ((NTSTATUS) 0xC0000239L)
-#endif
-
-#ifndef STATUS_CONNECTION_INVALID
-# define STATUS_CONNECTION_INVALID ((NTSTATUS) 0xC000023AL)
-#endif
-
-#ifndef STATUS_CONNECTION_ACTIVE
-# define STATUS_CONNECTION_ACTIVE ((NTSTATUS) 0xC000023BL)
-#endif
-
-#ifndef STATUS_NETWORK_UNREACHABLE
-# define STATUS_NETWORK_UNREACHABLE ((NTSTATUS) 0xC000023CL)
-#endif
-
-#ifndef STATUS_HOST_UNREACHABLE
-# define STATUS_HOST_UNREACHABLE ((NTSTATUS) 0xC000023DL)
-#endif
-
-#ifndef STATUS_PROTOCOL_UNREACHABLE
-# define STATUS_PROTOCOL_UNREACHABLE ((NTSTATUS) 0xC000023EL)
-#endif
-
-#ifndef STATUS_PORT_UNREACHABLE
-# define STATUS_PORT_UNREACHABLE ((NTSTATUS) 0xC000023FL)
-#endif
-
-#ifndef STATUS_REQUEST_ABORTED
-# define STATUS_REQUEST_ABORTED ((NTSTATUS) 0xC0000240L)
-#endif
-
-#ifndef STATUS_CONNECTION_ABORTED
-# define STATUS_CONNECTION_ABORTED ((NTSTATUS) 0xC0000241L)
-#endif
-
-#ifndef STATUS_BAD_COMPRESSION_BUFFER
-# define STATUS_BAD_COMPRESSION_BUFFER ((NTSTATUS) 0xC0000242L)
-#endif
-
-#ifndef STATUS_USER_MAPPED_FILE
-# define STATUS_USER_MAPPED_FILE ((NTSTATUS) 0xC0000243L)
-#endif
-
-#ifndef STATUS_AUDIT_FAILED
-# define STATUS_AUDIT_FAILED ((NTSTATUS) 0xC0000244L)
-#endif
-
-#ifndef STATUS_TIMER_RESOLUTION_NOT_SET
-# define STATUS_TIMER_RESOLUTION_NOT_SET ((NTSTATUS) 0xC0000245L)
-#endif
-
-#ifndef STATUS_CONNECTION_COUNT_LIMIT
-# define STATUS_CONNECTION_COUNT_LIMIT ((NTSTATUS) 0xC0000246L)
-#endif
-
-#ifndef STATUS_LOGIN_TIME_RESTRICTION
-# define STATUS_LOGIN_TIME_RESTRICTION ((NTSTATUS) 0xC0000247L)
-#endif
-
-#ifndef STATUS_LOGIN_WKSTA_RESTRICTION
-# define STATUS_LOGIN_WKSTA_RESTRICTION ((NTSTATUS) 0xC0000248L)
-#endif
-
-#ifndef STATUS_IMAGE_MP_UP_MISMATCH
-# define STATUS_IMAGE_MP_UP_MISMATCH ((NTSTATUS) 0xC0000249L)
-#endif
-
-#ifndef STATUS_INSUFFICIENT_LOGON_INFO
-# define STATUS_INSUFFICIENT_LOGON_INFO ((NTSTATUS) 0xC0000250L)
-#endif
-
-#ifndef STATUS_BAD_DLL_ENTRYPOINT
-# define STATUS_BAD_DLL_ENTRYPOINT ((NTSTATUS) 0xC0000251L)
-#endif
-
-#ifndef STATUS_BAD_SERVICE_ENTRYPOINT
-# define STATUS_BAD_SERVICE_ENTRYPOINT ((NTSTATUS) 0xC0000252L)
-#endif
-
-#ifndef STATUS_LPC_REPLY_LOST
-# define STATUS_LPC_REPLY_LOST ((NTSTATUS) 0xC0000253L)
-#endif
-
-#ifndef STATUS_IP_ADDRESS_CONFLICT1
-# define STATUS_IP_ADDRESS_CONFLICT1 ((NTSTATUS) 0xC0000254L)
-#endif
-
-#ifndef STATUS_IP_ADDRESS_CONFLICT2
-# define STATUS_IP_ADDRESS_CONFLICT2 ((NTSTATUS) 0xC0000255L)
-#endif
-
-#ifndef STATUS_REGISTRY_QUOTA_LIMIT
-# define STATUS_REGISTRY_QUOTA_LIMIT ((NTSTATUS) 0xC0000256L)
-#endif
-
-#ifndef STATUS_PATH_NOT_COVERED
-# define STATUS_PATH_NOT_COVERED ((NTSTATUS) 0xC0000257L)
-#endif
-
-#ifndef STATUS_NO_CALLBACK_ACTIVE
-# define STATUS_NO_CALLBACK_ACTIVE ((NTSTATUS) 0xC0000258L)
-#endif
-
-#ifndef STATUS_LICENSE_QUOTA_EXCEEDED
-# define STATUS_LICENSE_QUOTA_EXCEEDED ((NTSTATUS) 0xC0000259L)
-#endif
-
-#ifndef STATUS_PWD_TOO_SHORT
-# define STATUS_PWD_TOO_SHORT ((NTSTATUS) 0xC000025AL)
-#endif
-
-#ifndef STATUS_PWD_TOO_RECENT
-# define STATUS_PWD_TOO_RECENT ((NTSTATUS) 0xC000025BL)
-#endif
-
-#ifndef STATUS_PWD_HISTORY_CONFLICT
-# define STATUS_PWD_HISTORY_CONFLICT ((NTSTATUS) 0xC000025CL)
-#endif
-
-#ifndef STATUS_PLUGPLAY_NO_DEVICE
-# define STATUS_PLUGPLAY_NO_DEVICE ((NTSTATUS) 0xC000025EL)
-#endif
-
-#ifndef STATUS_UNSUPPORTED_COMPRESSION
-# define STATUS_UNSUPPORTED_COMPRESSION ((NTSTATUS) 0xC000025FL)
-#endif
-
-#ifndef STATUS_INVALID_HW_PROFILE
-# define STATUS_INVALID_HW_PROFILE ((NTSTATUS) 0xC0000260L)
-#endif
-
-#ifndef STATUS_INVALID_PLUGPLAY_DEVICE_PATH
-# define STATUS_INVALID_PLUGPLAY_DEVICE_PATH ((NTSTATUS) 0xC0000261L)
-#endif
-
-#ifndef STATUS_DRIVER_ORDINAL_NOT_FOUND
-# define STATUS_DRIVER_ORDINAL_NOT_FOUND ((NTSTATUS) 0xC0000262L)
-#endif
-
-#ifndef STATUS_DRIVER_ENTRYPOINT_NOT_FOUND
-# define STATUS_DRIVER_ENTRYPOINT_NOT_FOUND ((NTSTATUS) 0xC0000263L)
-#endif
-
-#ifndef STATUS_RESOURCE_NOT_OWNED
-# define STATUS_RESOURCE_NOT_OWNED ((NTSTATUS) 0xC0000264L)
-#endif
-
-#ifndef STATUS_TOO_MANY_LINKS
-# define STATUS_TOO_MANY_LINKS ((NTSTATUS) 0xC0000265L)
-#endif
-
-#ifndef STATUS_QUOTA_LIST_INCONSISTENT
-# define STATUS_QUOTA_LIST_INCONSISTENT ((NTSTATUS) 0xC0000266L)
-#endif
-
-#ifndef STATUS_FILE_IS_OFFLINE
-# define STATUS_FILE_IS_OFFLINE ((NTSTATUS) 0xC0000267L)
-#endif
-
-#ifndef STATUS_EVALUATION_EXPIRATION
-# define STATUS_EVALUATION_EXPIRATION ((NTSTATUS) 0xC0000268L)
-#endif
-
-#ifndef STATUS_ILLEGAL_DLL_RELOCATION
-# define STATUS_ILLEGAL_DLL_RELOCATION ((NTSTATUS) 0xC0000269L)
-#endif
-
-#ifndef STATUS_LICENSE_VIOLATION
-# define STATUS_LICENSE_VIOLATION ((NTSTATUS) 0xC000026AL)
-#endif
-
-#ifndef STATUS_DLL_INIT_FAILED_LOGOFF
-# define STATUS_DLL_INIT_FAILED_LOGOFF ((NTSTATUS) 0xC000026BL)
-#endif
-
-#ifndef STATUS_DRIVER_UNABLE_TO_LOAD
-# define STATUS_DRIVER_UNABLE_TO_LOAD ((NTSTATUS) 0xC000026CL)
-#endif
-
-#ifndef STATUS_DFS_UNAVAILABLE
-# define STATUS_DFS_UNAVAILABLE ((NTSTATUS) 0xC000026DL)
-#endif
-
-#ifndef STATUS_VOLUME_DISMOUNTED
-# define STATUS_VOLUME_DISMOUNTED ((NTSTATUS) 0xC000026EL)
-#endif
-
-#ifndef STATUS_WX86_INTERNAL_ERROR
-# define STATUS_WX86_INTERNAL_ERROR ((NTSTATUS) 0xC000026FL)
-#endif
-
-#ifndef STATUS_WX86_FLOAT_STACK_CHECK
-# define STATUS_WX86_FLOAT_STACK_CHECK ((NTSTATUS) 0xC0000270L)
-#endif
-
-#ifndef STATUS_VALIDATE_CONTINUE
-# define STATUS_VALIDATE_CONTINUE ((NTSTATUS) 0xC0000271L)
-#endif
-
-#ifndef STATUS_NO_MATCH
-# define STATUS_NO_MATCH ((NTSTATUS) 0xC0000272L)
-#endif
-
-#ifndef STATUS_NO_MORE_MATCHES
-# define STATUS_NO_MORE_MATCHES ((NTSTATUS) 0xC0000273L)
-#endif
-
-#ifndef STATUS_NOT_A_REPARSE_POINT
-# define STATUS_NOT_A_REPARSE_POINT ((NTSTATUS) 0xC0000275L)
-#endif
-
-#ifndef STATUS_IO_REPARSE_TAG_INVALID
-# define STATUS_IO_REPARSE_TAG_INVALID ((NTSTATUS) 0xC0000276L)
-#endif
-
-#ifndef STATUS_IO_REPARSE_TAG_MISMATCH
-# define STATUS_IO_REPARSE_TAG_MISMATCH ((NTSTATUS) 0xC0000277L)
-#endif
-
-#ifndef STATUS_IO_REPARSE_DATA_INVALID
-# define STATUS_IO_REPARSE_DATA_INVALID ((NTSTATUS) 0xC0000278L)
-#endif
-
-#ifndef STATUS_IO_REPARSE_TAG_NOT_HANDLED
-# define STATUS_IO_REPARSE_TAG_NOT_HANDLED ((NTSTATUS) 0xC0000279L)
-#endif
-
-#ifndef STATUS_REPARSE_POINT_NOT_RESOLVED
-# define STATUS_REPARSE_POINT_NOT_RESOLVED ((NTSTATUS) 0xC0000280L)
-#endif
-
-#ifndef STATUS_DIRECTORY_IS_A_REPARSE_POINT
-# define STATUS_DIRECTORY_IS_A_REPARSE_POINT ((NTSTATUS) 0xC0000281L)
-#endif
-
-#ifndef STATUS_RANGE_LIST_CONFLICT
-# define STATUS_RANGE_LIST_CONFLICT ((NTSTATUS) 0xC0000282L)
-#endif
-
-#ifndef STATUS_SOURCE_ELEMENT_EMPTY
-# define STATUS_SOURCE_ELEMENT_EMPTY ((NTSTATUS) 0xC0000283L)
-#endif
-
-#ifndef STATUS_DESTINATION_ELEMENT_FULL
-# define STATUS_DESTINATION_ELEMENT_FULL ((NTSTATUS) 0xC0000284L)
-#endif
-
-#ifndef STATUS_ILLEGAL_ELEMENT_ADDRESS
-# define STATUS_ILLEGAL_ELEMENT_ADDRESS ((NTSTATUS) 0xC0000285L)
-#endif
-
-#ifndef STATUS_MAGAZINE_NOT_PRESENT
-# define STATUS_MAGAZINE_NOT_PRESENT ((NTSTATUS) 0xC0000286L)
-#endif
-
-#ifndef STATUS_REINITIALIZATION_NEEDED
-# define STATUS_REINITIALIZATION_NEEDED ((NTSTATUS) 0xC0000287L)
-#endif
-
-#ifndef STATUS_DEVICE_REQUIRES_CLEANING
-# define STATUS_DEVICE_REQUIRES_CLEANING ((NTSTATUS) 0x80000288L)
-#endif
-
-#ifndef STATUS_DEVICE_DOOR_OPEN
-# define STATUS_DEVICE_DOOR_OPEN ((NTSTATUS) 0x80000289L)
-#endif
-
-#ifndef STATUS_ENCRYPTION_FAILED
-# define STATUS_ENCRYPTION_FAILED ((NTSTATUS) 0xC000028AL)
-#endif
-
-#ifndef STATUS_DECRYPTION_FAILED
-# define STATUS_DECRYPTION_FAILED ((NTSTATUS) 0xC000028BL)
-#endif
-
-#ifndef STATUS_RANGE_NOT_FOUND
-# define STATUS_RANGE_NOT_FOUND ((NTSTATUS) 0xC000028CL)
-#endif
-
-#ifndef STATUS_NO_RECOVERY_POLICY
-# define STATUS_NO_RECOVERY_POLICY ((NTSTATUS) 0xC000028DL)
-#endif
-
-#ifndef STATUS_NO_EFS
-# define STATUS_NO_EFS ((NTSTATUS) 0xC000028EL)
-#endif
-
-#ifndef STATUS_WRONG_EFS
-# define STATUS_WRONG_EFS ((NTSTATUS) 0xC000028FL)
-#endif
-
-#ifndef STATUS_NO_USER_KEYS
-# define STATUS_NO_USER_KEYS ((NTSTATUS) 0xC0000290L)
-#endif
-
-#ifndef STATUS_FILE_NOT_ENCRYPTED
-# define STATUS_FILE_NOT_ENCRYPTED ((NTSTATUS) 0xC0000291L)
-#endif
-
-#ifndef STATUS_NOT_EXPORT_FORMAT
-# define STATUS_NOT_EXPORT_FORMAT ((NTSTATUS) 0xC0000292L)
-#endif
-
-#ifndef STATUS_FILE_ENCRYPTED
-# define STATUS_FILE_ENCRYPTED ((NTSTATUS) 0xC0000293L)
-#endif
-
-#ifndef STATUS_WAKE_SYSTEM
-# define STATUS_WAKE_SYSTEM ((NTSTATUS) 0x40000294L)
-#endif
-
-#ifndef STATUS_WMI_GUID_NOT_FOUND
-# define STATUS_WMI_GUID_NOT_FOUND ((NTSTATUS) 0xC0000295L)
-#endif
-
-#ifndef STATUS_WMI_INSTANCE_NOT_FOUND
-# define STATUS_WMI_INSTANCE_NOT_FOUND ((NTSTATUS) 0xC0000296L)
-#endif
-
-#ifndef STATUS_WMI_ITEMID_NOT_FOUND
-# define STATUS_WMI_ITEMID_NOT_FOUND ((NTSTATUS) 0xC0000297L)
-#endif
-
-#ifndef STATUS_WMI_TRY_AGAIN
-# define STATUS_WMI_TRY_AGAIN ((NTSTATUS) 0xC0000298L)
-#endif
-
-#ifndef STATUS_SHARED_POLICY
-# define STATUS_SHARED_POLICY ((NTSTATUS) 0xC0000299L)
-#endif
-
-#ifndef STATUS_POLICY_OBJECT_NOT_FOUND
-# define STATUS_POLICY_OBJECT_NOT_FOUND ((NTSTATUS) 0xC000029AL)
-#endif
-
-#ifndef STATUS_POLICY_ONLY_IN_DS
-# define STATUS_POLICY_ONLY_IN_DS ((NTSTATUS) 0xC000029BL)
-#endif
-
-#ifndef STATUS_VOLUME_NOT_UPGRADED
-# define STATUS_VOLUME_NOT_UPGRADED ((NTSTATUS) 0xC000029CL)
-#endif
-
-#ifndef STATUS_REMOTE_STORAGE_NOT_ACTIVE
-# define STATUS_REMOTE_STORAGE_NOT_ACTIVE ((NTSTATUS) 0xC000029DL)
-#endif
-
-#ifndef STATUS_REMOTE_STORAGE_MEDIA_ERROR
-# define STATUS_REMOTE_STORAGE_MEDIA_ERROR ((NTSTATUS) 0xC000029EL)
-#endif
-
-#ifndef STATUS_NO_TRACKING_SERVICE
-# define STATUS_NO_TRACKING_SERVICE ((NTSTATUS) 0xC000029FL)
-#endif
-
-#ifndef STATUS_SERVER_SID_MISMATCH
-# define STATUS_SERVER_SID_MISMATCH ((NTSTATUS) 0xC00002A0L)
-#endif
-
-#ifndef STATUS_DS_NO_ATTRIBUTE_OR_VALUE
-# define STATUS_DS_NO_ATTRIBUTE_OR_VALUE ((NTSTATUS) 0xC00002A1L)
-#endif
-
-#ifndef STATUS_DS_INVALID_ATTRIBUTE_SYNTAX
-# define STATUS_DS_INVALID_ATTRIBUTE_SYNTAX ((NTSTATUS) 0xC00002A2L)
-#endif
-
-#ifndef STATUS_DS_ATTRIBUTE_TYPE_UNDEFINED
-# define STATUS_DS_ATTRIBUTE_TYPE_UNDEFINED ((NTSTATUS) 0xC00002A3L)
-#endif
-
-#ifndef STATUS_DS_ATTRIBUTE_OR_VALUE_EXISTS
-# define STATUS_DS_ATTRIBUTE_OR_VALUE_EXISTS ((NTSTATUS) 0xC00002A4L)
-#endif
-
-#ifndef STATUS_DS_BUSY
-# define STATUS_DS_BUSY ((NTSTATUS) 0xC00002A5L)
-#endif
-
-#ifndef STATUS_DS_UNAVAILABLE
-# define STATUS_DS_UNAVAILABLE ((NTSTATUS) 0xC00002A6L)
-#endif
-
-#ifndef STATUS_DS_NO_RIDS_ALLOCATED
-# define STATUS_DS_NO_RIDS_ALLOCATED ((NTSTATUS) 0xC00002A7L)
-#endif
-
-#ifndef STATUS_DS_NO_MORE_RIDS
-# define STATUS_DS_NO_MORE_RIDS ((NTSTATUS) 0xC00002A8L)
-#endif
-
-#ifndef STATUS_DS_INCORRECT_ROLE_OWNER
-# define STATUS_DS_INCORRECT_ROLE_OWNER ((NTSTATUS) 0xC00002A9L)
-#endif
-
-#ifndef STATUS_DS_RIDMGR_INIT_ERROR
-# define STATUS_DS_RIDMGR_INIT_ERROR ((NTSTATUS) 0xC00002AAL)
-#endif
-
-#ifndef STATUS_DS_OBJ_CLASS_VIOLATION
-# define STATUS_DS_OBJ_CLASS_VIOLATION ((NTSTATUS) 0xC00002ABL)
-#endif
-
-#ifndef STATUS_DS_CANT_ON_NON_LEAF
-# define STATUS_DS_CANT_ON_NON_LEAF ((NTSTATUS) 0xC00002ACL)
-#endif
-
-#ifndef STATUS_DS_CANT_ON_RDN
-# define STATUS_DS_CANT_ON_RDN ((NTSTATUS) 0xC00002ADL)
-#endif
-
-#ifndef STATUS_DS_CANT_MOD_OBJ_CLASS
-# define STATUS_DS_CANT_MOD_OBJ_CLASS ((NTSTATUS) 0xC00002AEL)
-#endif
-
-#ifndef STATUS_DS_CROSS_DOM_MOVE_FAILED
-# define STATUS_DS_CROSS_DOM_MOVE_FAILED ((NTSTATUS) 0xC00002AFL)
-#endif
-
-#ifndef STATUS_DS_GC_NOT_AVAILABLE
-# define STATUS_DS_GC_NOT_AVAILABLE ((NTSTATUS) 0xC00002B0L)
-#endif
-
-#ifndef STATUS_DIRECTORY_SERVICE_REQUIRED
-# define STATUS_DIRECTORY_SERVICE_REQUIRED ((NTSTATUS) 0xC00002B1L)
-#endif
-
-#ifndef STATUS_REPARSE_ATTRIBUTE_CONFLICT
-# define STATUS_REPARSE_ATTRIBUTE_CONFLICT ((NTSTATUS) 0xC00002B2L)
-#endif
-
-#ifndef STATUS_CANT_ENABLE_DENY_ONLY
-# define STATUS_CANT_ENABLE_DENY_ONLY ((NTSTATUS) 0xC00002B3L)
-#endif
-
-#ifndef STATUS_FLOAT_MULTIPLE_FAULTS
-# define STATUS_FLOAT_MULTIPLE_FAULTS ((NTSTATUS) 0xC00002B4L)
-#endif
-
-#ifndef STATUS_FLOAT_MULTIPLE_TRAPS
-# define STATUS_FLOAT_MULTIPLE_TRAPS ((NTSTATUS) 0xC00002B5L)
-#endif
-
-#ifndef STATUS_DEVICE_REMOVED
-# define STATUS_DEVICE_REMOVED ((NTSTATUS) 0xC00002B6L)
-#endif
-
-#ifndef STATUS_JOURNAL_DELETE_IN_PROGRESS
-# define STATUS_JOURNAL_DELETE_IN_PROGRESS ((NTSTATUS) 0xC00002B7L)
-#endif
-
-#ifndef STATUS_JOURNAL_NOT_ACTIVE
-# define STATUS_JOURNAL_NOT_ACTIVE ((NTSTATUS) 0xC00002B8L)
-#endif
-
-#ifndef STATUS_NOINTERFACE
-# define STATUS_NOINTERFACE ((NTSTATUS) 0xC00002B9L)
-#endif
-
-#ifndef STATUS_DS_ADMIN_LIMIT_EXCEEDED
-# define STATUS_DS_ADMIN_LIMIT_EXCEEDED ((NTSTATUS) 0xC00002C1L)
-#endif
-
-#ifndef STATUS_DRIVER_FAILED_SLEEP
-# define STATUS_DRIVER_FAILED_SLEEP ((NTSTATUS) 0xC00002C2L)
-#endif
-
-#ifndef STATUS_MUTUAL_AUTHENTICATION_FAILED
-# define STATUS_MUTUAL_AUTHENTICATION_FAILED ((NTSTATUS) 0xC00002C3L)
-#endif
-
-#ifndef STATUS_CORRUPT_SYSTEM_FILE
-# define STATUS_CORRUPT_SYSTEM_FILE ((NTSTATUS) 0xC00002C4L)
-#endif
-
-#ifndef STATUS_DATATYPE_MISALIGNMENT_ERROR
-# define STATUS_DATATYPE_MISALIGNMENT_ERROR ((NTSTATUS) 0xC00002C5L)
-#endif
-
-#ifndef STATUS_WMI_READ_ONLY
-# define STATUS_WMI_READ_ONLY ((NTSTATUS) 0xC00002C6L)
-#endif
-
-#ifndef STATUS_WMI_SET_FAILURE
-# define STATUS_WMI_SET_FAILURE ((NTSTATUS) 0xC00002C7L)
-#endif
-
-#ifndef STATUS_COMMITMENT_MINIMUM
-# define STATUS_COMMITMENT_MINIMUM ((NTSTATUS) 0xC00002C8L)
-#endif
-
-#ifndef STATUS_REG_NAT_CONSUMPTION
-# define STATUS_REG_NAT_CONSUMPTION ((NTSTATUS) 0xC00002C9L)
-#endif
-
-#ifndef STATUS_TRANSPORT_FULL
-# define STATUS_TRANSPORT_FULL ((NTSTATUS) 0xC00002CAL)
-#endif
-
-#ifndef STATUS_DS_SAM_INIT_FAILURE
-# define STATUS_DS_SAM_INIT_FAILURE ((NTSTATUS) 0xC00002CBL)
-#endif
-
-#ifndef STATUS_ONLY_IF_CONNECTED
-# define STATUS_ONLY_IF_CONNECTED ((NTSTATUS) 0xC00002CCL)
-#endif
-
-#ifndef STATUS_DS_SENSITIVE_GROUP_VIOLATION
-# define STATUS_DS_SENSITIVE_GROUP_VIOLATION ((NTSTATUS) 0xC00002CDL)
-#endif
-
-#ifndef STATUS_PNP_RESTART_ENUMERATION
-# define STATUS_PNP_RESTART_ENUMERATION ((NTSTATUS) 0xC00002CEL)
-#endif
-
-#ifndef STATUS_JOURNAL_ENTRY_DELETED
-# define STATUS_JOURNAL_ENTRY_DELETED ((NTSTATUS) 0xC00002CFL)
-#endif
-
-#ifndef STATUS_DS_CANT_MOD_PRIMARYGROUPID
-# define STATUS_DS_CANT_MOD_PRIMARYGROUPID ((NTSTATUS) 0xC00002D0L)
-#endif
-
-#ifndef STATUS_SYSTEM_IMAGE_BAD_SIGNATURE
-# define STATUS_SYSTEM_IMAGE_BAD_SIGNATURE ((NTSTATUS) 0xC00002D1L)
-#endif
-
-#ifndef STATUS_PNP_REBOOT_REQUIRED
-# define STATUS_PNP_REBOOT_REQUIRED ((NTSTATUS) 0xC00002D2L)
-#endif
-
-#ifndef STATUS_POWER_STATE_INVALID
-# define STATUS_POWER_STATE_INVALID ((NTSTATUS) 0xC00002D3L)
-#endif
-
-#ifndef STATUS_DS_INVALID_GROUP_TYPE
-# define STATUS_DS_INVALID_GROUP_TYPE ((NTSTATUS) 0xC00002D4L)
-#endif
-
-#ifndef STATUS_DS_NO_NEST_GLOBALGROUP_IN_MIXEDDOMAIN
-# define STATUS_DS_NO_NEST_GLOBALGROUP_IN_MIXEDDOMAIN ((NTSTATUS) 0xC00002D5L)
-#endif
-
-#ifndef STATUS_DS_NO_NEST_LOCALGROUP_IN_MIXEDDOMAIN
-# define STATUS_DS_NO_NEST_LOCALGROUP_IN_MIXEDDOMAIN ((NTSTATUS) 0xC00002D6L)
-#endif
-
-#ifndef STATUS_DS_GLOBAL_CANT_HAVE_LOCAL_MEMBER
-# define STATUS_DS_GLOBAL_CANT_HAVE_LOCAL_MEMBER ((NTSTATUS) 0xC00002D7L)
-#endif
-
-#ifndef STATUS_DS_GLOBAL_CANT_HAVE_UNIVERSAL_MEMBER
-# define STATUS_DS_GLOBAL_CANT_HAVE_UNIVERSAL_MEMBER ((NTSTATUS) 0xC00002D8L)
-#endif
-
-#ifndef STATUS_DS_UNIVERSAL_CANT_HAVE_LOCAL_MEMBER
-# define STATUS_DS_UNIVERSAL_CANT_HAVE_LOCAL_MEMBER ((NTSTATUS) 0xC00002D9L)
-#endif
-
-#ifndef STATUS_DS_GLOBAL_CANT_HAVE_CROSSDOMAIN_MEMBER
-# define STATUS_DS_GLOBAL_CANT_HAVE_CROSSDOMAIN_MEMBER ((NTSTATUS) 0xC00002DAL)
-#endif
-
-#ifndef STATUS_DS_LOCAL_CANT_HAVE_CROSSDOMAIN_LOCAL_MEMBER
-# define STATUS_DS_LOCAL_CANT_HAVE_CROSSDOMAIN_LOCAL_MEMBER ((NTSTATUS) 0xC00002DBL)
-#endif
-
-#ifndef STATUS_DS_HAVE_PRIMARY_MEMBERS
-# define STATUS_DS_HAVE_PRIMARY_MEMBERS ((NTSTATUS) 0xC00002DCL)
-#endif
-
-#ifndef STATUS_WMI_NOT_SUPPORTED
-# define STATUS_WMI_NOT_SUPPORTED ((NTSTATUS) 0xC00002DDL)
-#endif
-
-#ifndef STATUS_INSUFFICIENT_POWER
-# define STATUS_INSUFFICIENT_POWER ((NTSTATUS) 0xC00002DEL)
-#endif
-
-#ifndef STATUS_SAM_NEED_BOOTKEY_PASSWORD
-# define STATUS_SAM_NEED_BOOTKEY_PASSWORD ((NTSTATUS) 0xC00002DFL)
-#endif
-
-#ifndef STATUS_SAM_NEED_BOOTKEY_FLOPPY
-# define STATUS_SAM_NEED_BOOTKEY_FLOPPY ((NTSTATUS) 0xC00002E0L)
-#endif
-
-#ifndef STATUS_DS_CANT_START
-# define STATUS_DS_CANT_START ((NTSTATUS) 0xC00002E1L)
-#endif
-
-#ifndef STATUS_DS_INIT_FAILURE
-# define STATUS_DS_INIT_FAILURE ((NTSTATUS) 0xC00002E2L)
-#endif
-
-#ifndef STATUS_SAM_INIT_FAILURE
-# define STATUS_SAM_INIT_FAILURE ((NTSTATUS) 0xC00002E3L)
-#endif
-
-#ifndef STATUS_DS_GC_REQUIRED
-# define STATUS_DS_GC_REQUIRED ((NTSTATUS) 0xC00002E4L)
-#endif
-
-#ifndef STATUS_DS_LOCAL_MEMBER_OF_LOCAL_ONLY
-# define STATUS_DS_LOCAL_MEMBER_OF_LOCAL_ONLY ((NTSTATUS) 0xC00002E5L)
-#endif
-
-#ifndef STATUS_DS_NO_FPO_IN_UNIVERSAL_GROUPS
-# define STATUS_DS_NO_FPO_IN_UNIVERSAL_GROUPS ((NTSTATUS) 0xC00002E6L)
-#endif
-
-#ifndef STATUS_DS_MACHINE_ACCOUNT_QUOTA_EXCEEDED
-# define STATUS_DS_MACHINE_ACCOUNT_QUOTA_EXCEEDED ((NTSTATUS) 0xC00002E7L)
-#endif
-
-#ifndef STATUS_MULTIPLE_FAULT_VIOLATION
-# define STATUS_MULTIPLE_FAULT_VIOLATION ((NTSTATUS) 0xC00002E8L)
-#endif
-
-#ifndef STATUS_CURRENT_DOMAIN_NOT_ALLOWED
-# define STATUS_CURRENT_DOMAIN_NOT_ALLOWED ((NTSTATUS) 0xC00002E9L)
-#endif
-
-#ifndef STATUS_CANNOT_MAKE
-# define STATUS_CANNOT_MAKE ((NTSTATUS) 0xC00002EAL)
-#endif
-
-#ifndef STATUS_SYSTEM_SHUTDOWN
-# define STATUS_SYSTEM_SHUTDOWN ((NTSTATUS) 0xC00002EBL)
-#endif
-
-#ifndef STATUS_DS_INIT_FAILURE_CONSOLE
-# define STATUS_DS_INIT_FAILURE_CONSOLE ((NTSTATUS) 0xC00002ECL)
-#endif
-
-#ifndef STATUS_DS_SAM_INIT_FAILURE_CONSOLE
-# define STATUS_DS_SAM_INIT_FAILURE_CONSOLE ((NTSTATUS) 0xC00002EDL)
-#endif
-
-#ifndef STATUS_UNFINISHED_CONTEXT_DELETED
-# define STATUS_UNFINISHED_CONTEXT_DELETED ((NTSTATUS) 0xC00002EEL)
-#endif
-
-#ifndef STATUS_NO_TGT_REPLY
-# define STATUS_NO_TGT_REPLY ((NTSTATUS) 0xC00002EFL)
-#endif
-
-#ifndef STATUS_OBJECTID_NOT_FOUND
-# define STATUS_OBJECTID_NOT_FOUND ((NTSTATUS) 0xC00002F0L)
-#endif
-
-#ifndef STATUS_NO_IP_ADDRESSES
-# define STATUS_NO_IP_ADDRESSES ((NTSTATUS) 0xC00002F1L)
-#endif
-
-#ifndef STATUS_WRONG_CREDENTIAL_HANDLE
-# define STATUS_WRONG_CREDENTIAL_HANDLE ((NTSTATUS) 0xC00002F2L)
-#endif
-
-#ifndef STATUS_CRYPTO_SYSTEM_INVALID
-# define STATUS_CRYPTO_SYSTEM_INVALID ((NTSTATUS) 0xC00002F3L)
-#endif
-
-#ifndef STATUS_MAX_REFERRALS_EXCEEDED
-# define STATUS_MAX_REFERRALS_EXCEEDED ((NTSTATUS) 0xC00002F4L)
-#endif
-
-#ifndef STATUS_MUST_BE_KDC
-# define STATUS_MUST_BE_KDC ((NTSTATUS) 0xC00002F5L)
-#endif
-
-#ifndef STATUS_STRONG_CRYPTO_NOT_SUPPORTED
-# define STATUS_STRONG_CRYPTO_NOT_SUPPORTED ((NTSTATUS) 0xC00002F6L)
-#endif
-
-#ifndef STATUS_TOO_MANY_PRINCIPALS
-# define STATUS_TOO_MANY_PRINCIPALS ((NTSTATUS) 0xC00002F7L)
-#endif
-
-#ifndef STATUS_NO_PA_DATA
-# define STATUS_NO_PA_DATA ((NTSTATUS) 0xC00002F8L)
-#endif
-
-#ifndef STATUS_PKINIT_NAME_MISMATCH
-# define STATUS_PKINIT_NAME_MISMATCH ((NTSTATUS) 0xC00002F9L)
-#endif
-
-#ifndef STATUS_SMARTCARD_LOGON_REQUIRED
-# define STATUS_SMARTCARD_LOGON_REQUIRED ((NTSTATUS) 0xC00002FAL)
-#endif
-
-#ifndef STATUS_KDC_INVALID_REQUEST
-# define STATUS_KDC_INVALID_REQUEST ((NTSTATUS) 0xC00002FBL)
-#endif
-
-#ifndef STATUS_KDC_UNABLE_TO_REFER
-# define STATUS_KDC_UNABLE_TO_REFER ((NTSTATUS) 0xC00002FCL)
-#endif
-
-#ifndef STATUS_KDC_UNKNOWN_ETYPE
-# define STATUS_KDC_UNKNOWN_ETYPE ((NTSTATUS) 0xC00002FDL)
-#endif
-
-#ifndef STATUS_SHUTDOWN_IN_PROGRESS
-# define STATUS_SHUTDOWN_IN_PROGRESS ((NTSTATUS) 0xC00002FEL)
-#endif
-
-#ifndef STATUS_SERVER_SHUTDOWN_IN_PROGRESS
-# define STATUS_SERVER_SHUTDOWN_IN_PROGRESS ((NTSTATUS) 0xC00002FFL)
-#endif
-
-#ifndef STATUS_NOT_SUPPORTED_ON_SBS
-# define STATUS_NOT_SUPPORTED_ON_SBS ((NTSTATUS) 0xC0000300L)
-#endif
-
-#ifndef STATUS_WMI_GUID_DISCONNECTED
-# define STATUS_WMI_GUID_DISCONNECTED ((NTSTATUS) 0xC0000301L)
-#endif
-
-#ifndef STATUS_WMI_ALREADY_DISABLED
-# define STATUS_WMI_ALREADY_DISABLED ((NTSTATUS) 0xC0000302L)
-#endif
-
-#ifndef STATUS_WMI_ALREADY_ENABLED
-# define STATUS_WMI_ALREADY_ENABLED ((NTSTATUS) 0xC0000303L)
-#endif
-
-#ifndef STATUS_MFT_TOO_FRAGMENTED
-# define STATUS_MFT_TOO_FRAGMENTED ((NTSTATUS) 0xC0000304L)
-#endif
-
-#ifndef STATUS_COPY_PROTECTION_FAILURE
-# define STATUS_COPY_PROTECTION_FAILURE ((NTSTATUS) 0xC0000305L)
-#endif
-
-#ifndef STATUS_CSS_AUTHENTICATION_FAILURE
-# define STATUS_CSS_AUTHENTICATION_FAILURE ((NTSTATUS) 0xC0000306L)
-#endif
-
-#ifndef STATUS_CSS_KEY_NOT_PRESENT
-# define STATUS_CSS_KEY_NOT_PRESENT ((NTSTATUS) 0xC0000307L)
-#endif
-
-#ifndef STATUS_CSS_KEY_NOT_ESTABLISHED
-# define STATUS_CSS_KEY_NOT_ESTABLISHED ((NTSTATUS) 0xC0000308L)
-#endif
-
-#ifndef STATUS_CSS_SCRAMBLED_SECTOR
-# define STATUS_CSS_SCRAMBLED_SECTOR ((NTSTATUS) 0xC0000309L)
-#endif
-
-#ifndef STATUS_CSS_REGION_MISMATCH
-# define STATUS_CSS_REGION_MISMATCH ((NTSTATUS) 0xC000030AL)
-#endif
-
-#ifndef STATUS_CSS_RESETS_EXHAUSTED
-# define STATUS_CSS_RESETS_EXHAUSTED ((NTSTATUS) 0xC000030BL)
-#endif
-
-#ifndef STATUS_PKINIT_FAILURE
-# define STATUS_PKINIT_FAILURE ((NTSTATUS) 0xC0000320L)
-#endif
-
-#ifndef STATUS_SMARTCARD_SUBSYSTEM_FAILURE
-# define STATUS_SMARTCARD_SUBSYSTEM_FAILURE ((NTSTATUS) 0xC0000321L)
-#endif
-
-#ifndef STATUS_NO_KERB_KEY
-# define STATUS_NO_KERB_KEY ((NTSTATUS) 0xC0000322L)
-#endif
-
-#ifndef STATUS_HOST_DOWN
-# define STATUS_HOST_DOWN ((NTSTATUS) 0xC0000350L)
-#endif
-
-#ifndef STATUS_UNSUPPORTED_PREAUTH
-# define STATUS_UNSUPPORTED_PREAUTH ((NTSTATUS) 0xC0000351L)
-#endif
-
-#ifndef STATUS_EFS_ALG_BLOB_TOO_BIG
-# define STATUS_EFS_ALG_BLOB_TOO_BIG ((NTSTATUS) 0xC0000352L)
-#endif
-
-#ifndef STATUS_PORT_NOT_SET
-# define STATUS_PORT_NOT_SET ((NTSTATUS) 0xC0000353L)
-#endif
-
-#ifndef STATUS_DEBUGGER_INACTIVE
-# define STATUS_DEBUGGER_INACTIVE ((NTSTATUS) 0xC0000354L)
-#endif
-
-#ifndef STATUS_DS_VERSION_CHECK_FAILURE
-# define STATUS_DS_VERSION_CHECK_FAILURE ((NTSTATUS) 0xC0000355L)
-#endif
-
-#ifndef STATUS_AUDITING_DISABLED
-# define STATUS_AUDITING_DISABLED ((NTSTATUS) 0xC0000356L)
-#endif
-
-#ifndef STATUS_PRENT4_MACHINE_ACCOUNT
-# define STATUS_PRENT4_MACHINE_ACCOUNT ((NTSTATUS) 0xC0000357L)
-#endif
-
-#ifndef STATUS_DS_AG_CANT_HAVE_UNIVERSAL_MEMBER
-# define STATUS_DS_AG_CANT_HAVE_UNIVERSAL_MEMBER ((NTSTATUS) 0xC0000358L)
-#endif
-
-#ifndef STATUS_INVALID_IMAGE_WIN_32
-# define STATUS_INVALID_IMAGE_WIN_32 ((NTSTATUS) 0xC0000359L)
-#endif
-
-#ifndef STATUS_INVALID_IMAGE_WIN_64
-# define STATUS_INVALID_IMAGE_WIN_64 ((NTSTATUS) 0xC000035AL)
-#endif
-
-#ifndef STATUS_BAD_BINDINGS
-# define STATUS_BAD_BINDINGS ((NTSTATUS) 0xC000035BL)
-#endif
-
-#ifndef STATUS_NETWORK_SESSION_EXPIRED
-# define STATUS_NETWORK_SESSION_EXPIRED ((NTSTATUS) 0xC000035CL)
-#endif
-
-#ifndef STATUS_APPHELP_BLOCK
-# define STATUS_APPHELP_BLOCK ((NTSTATUS) 0xC000035DL)
-#endif
-
-#ifndef STATUS_ALL_SIDS_FILTERED
-# define STATUS_ALL_SIDS_FILTERED ((NTSTATUS) 0xC000035EL)
-#endif
-
-#ifndef STATUS_NOT_SAFE_MODE_DRIVER
-# define STATUS_NOT_SAFE_MODE_DRIVER ((NTSTATUS) 0xC000035FL)
-#endif
-
-#ifndef STATUS_ACCESS_DISABLED_BY_POLICY_DEFAULT
-# define STATUS_ACCESS_DISABLED_BY_POLICY_DEFAULT ((NTSTATUS) 0xC0000361L)
-#endif
-
-#ifndef STATUS_ACCESS_DISABLED_BY_POLICY_PATH
-# define STATUS_ACCESS_DISABLED_BY_POLICY_PATH ((NTSTATUS) 0xC0000362L)
-#endif
-
-#ifndef STATUS_ACCESS_DISABLED_BY_POLICY_PUBLISHER
-# define STATUS_ACCESS_DISABLED_BY_POLICY_PUBLISHER ((NTSTATUS) 0xC0000363L)
-#endif
-
-#ifndef STATUS_ACCESS_DISABLED_BY_POLICY_OTHER
-# define STATUS_ACCESS_DISABLED_BY_POLICY_OTHER ((NTSTATUS) 0xC0000364L)
-#endif
-
-#ifndef STATUS_FAILED_DRIVER_ENTRY
-# define STATUS_FAILED_DRIVER_ENTRY ((NTSTATUS) 0xC0000365L)
-#endif
-
-#ifndef STATUS_DEVICE_ENUMERATION_ERROR
-# define STATUS_DEVICE_ENUMERATION_ERROR ((NTSTATUS) 0xC0000366L)
-#endif
-
-#ifndef STATUS_MOUNT_POINT_NOT_RESOLVED
-# define STATUS_MOUNT_POINT_NOT_RESOLVED ((NTSTATUS) 0xC0000368L)
-#endif
-
-#ifndef STATUS_INVALID_DEVICE_OBJECT_PARAMETER
-# define STATUS_INVALID_DEVICE_OBJECT_PARAMETER ((NTSTATUS) 0xC0000369L)
-#endif
-
-#ifndef STATUS_MCA_OCCURED
-# define STATUS_MCA_OCCURED ((NTSTATUS) 0xC000036AL)
-#endif
-
-#ifndef STATUS_DRIVER_BLOCKED_CRITICAL
-# define STATUS_DRIVER_BLOCKED_CRITICAL ((NTSTATUS) 0xC000036BL)
-#endif
-
-#ifndef STATUS_DRIVER_BLOCKED
-# define STATUS_DRIVER_BLOCKED ((NTSTATUS) 0xC000036CL)
-#endif
-
-#ifndef STATUS_DRIVER_DATABASE_ERROR
-# define STATUS_DRIVER_DATABASE_ERROR ((NTSTATUS) 0xC000036DL)
-#endif
-
-#ifndef STATUS_SYSTEM_HIVE_TOO_LARGE
-# define STATUS_SYSTEM_HIVE_TOO_LARGE ((NTSTATUS) 0xC000036EL)
-#endif
-
-#ifndef STATUS_INVALID_IMPORT_OF_NON_DLL
-# define STATUS_INVALID_IMPORT_OF_NON_DLL ((NTSTATUS) 0xC000036FL)
-#endif
-
-#ifndef STATUS_DS_SHUTTING_DOWN
-# define STATUS_DS_SHUTTING_DOWN ((NTSTATUS) 0x40000370L)
-#endif
-
-#ifndef STATUS_NO_SECRETS
-# define STATUS_NO_SECRETS ((NTSTATUS) 0xC0000371L)
-#endif
-
-#ifndef STATUS_ACCESS_DISABLED_NO_SAFER_UI_BY_POLICY
-# define STATUS_ACCESS_DISABLED_NO_SAFER_UI_BY_POLICY ((NTSTATUS) 0xC0000372L)
-#endif
-
-#ifndef STATUS_FAILED_STACK_SWITCH
-# define STATUS_FAILED_STACK_SWITCH ((NTSTATUS) 0xC0000373L)
-#endif
-
-#ifndef STATUS_HEAP_CORRUPTION
-# define STATUS_HEAP_CORRUPTION ((NTSTATUS) 0xC0000374L)
-#endif
-
-#ifndef STATUS_SMARTCARD_WRONG_PIN
-# define STATUS_SMARTCARD_WRONG_PIN ((NTSTATUS) 0xC0000380L)
-#endif
-
-#ifndef STATUS_SMARTCARD_CARD_BLOCKED
-# define STATUS_SMARTCARD_CARD_BLOCKED ((NTSTATUS) 0xC0000381L)
-#endif
-
-#ifndef STATUS_SMARTCARD_CARD_NOT_AUTHENTICATED
-# define STATUS_SMARTCARD_CARD_NOT_AUTHENTICATED ((NTSTATUS) 0xC0000382L)
-#endif
-
-#ifndef STATUS_SMARTCARD_NO_CARD
-# define STATUS_SMARTCARD_NO_CARD ((NTSTATUS) 0xC0000383L)
-#endif
-
-#ifndef STATUS_SMARTCARD_NO_KEY_CONTAINER
-# define STATUS_SMARTCARD_NO_KEY_CONTAINER ((NTSTATUS) 0xC0000384L)
-#endif
-
-#ifndef STATUS_SMARTCARD_NO_CERTIFICATE
-# define STATUS_SMARTCARD_NO_CERTIFICATE ((NTSTATUS) 0xC0000385L)
-#endif
-
-#ifndef STATUS_SMARTCARD_NO_KEYSET
-# define STATUS_SMARTCARD_NO_KEYSET ((NTSTATUS) 0xC0000386L)
-#endif
-
-#ifndef STATUS_SMARTCARD_IO_ERROR
-# define STATUS_SMARTCARD_IO_ERROR ((NTSTATUS) 0xC0000387L)
-#endif
-
-#ifndef STATUS_DOWNGRADE_DETECTED
-# define STATUS_DOWNGRADE_DETECTED ((NTSTATUS) 0xC0000388L)
-#endif
-
-#ifndef STATUS_SMARTCARD_CERT_REVOKED
-# define STATUS_SMARTCARD_CERT_REVOKED ((NTSTATUS) 0xC0000389L)
-#endif
-
-#ifndef STATUS_ISSUING_CA_UNTRUSTED
-# define STATUS_ISSUING_CA_UNTRUSTED ((NTSTATUS) 0xC000038AL)
-#endif
-
-#ifndef STATUS_REVOCATION_OFFLINE_C
-# define STATUS_REVOCATION_OFFLINE_C ((NTSTATUS) 0xC000038BL)
-#endif
-
-#ifndef STATUS_PKINIT_CLIENT_FAILURE
-# define STATUS_PKINIT_CLIENT_FAILURE ((NTSTATUS) 0xC000038CL)
-#endif
-
-#ifndef STATUS_SMARTCARD_CERT_EXPIRED
-# define STATUS_SMARTCARD_CERT_EXPIRED ((NTSTATUS) 0xC000038DL)
-#endif
-
-#ifndef STATUS_DRIVER_FAILED_PRIOR_UNLOAD
-# define STATUS_DRIVER_FAILED_PRIOR_UNLOAD ((NTSTATUS) 0xC000038EL)
-#endif
-
-#ifndef STATUS_SMARTCARD_SILENT_CONTEXT
-# define STATUS_SMARTCARD_SILENT_CONTEXT ((NTSTATUS) 0xC000038FL)
-#endif
-
-#ifndef STATUS_PER_USER_TRUST_QUOTA_EXCEEDED
-# define STATUS_PER_USER_TRUST_QUOTA_EXCEEDED ((NTSTATUS) 0xC0000401L)
-#endif
-
-#ifndef STATUS_ALL_USER_TRUST_QUOTA_EXCEEDED
-# define STATUS_ALL_USER_TRUST_QUOTA_EXCEEDED ((NTSTATUS) 0xC0000402L)
-#endif
-
-#ifndef STATUS_USER_DELETE_TRUST_QUOTA_EXCEEDED
-# define STATUS_USER_DELETE_TRUST_QUOTA_EXCEEDED ((NTSTATUS) 0xC0000403L)
-#endif
-
-#ifndef STATUS_DS_NAME_NOT_UNIQUE
-# define STATUS_DS_NAME_NOT_UNIQUE ((NTSTATUS) 0xC0000404L)
-#endif
-
-#ifndef STATUS_DS_DUPLICATE_ID_FOUND
-# define STATUS_DS_DUPLICATE_ID_FOUND ((NTSTATUS) 0xC0000405L)
-#endif
-
-#ifndef STATUS_DS_GROUP_CONVERSION_ERROR
-# define STATUS_DS_GROUP_CONVERSION_ERROR ((NTSTATUS) 0xC0000406L)
-#endif
-
-#ifndef STATUS_VOLSNAP_PREPARE_HIBERNATE
-# define STATUS_VOLSNAP_PREPARE_HIBERNATE ((NTSTATUS) 0xC0000407L)
-#endif
-
-#ifndef STATUS_USER2USER_REQUIRED
-# define STATUS_USER2USER_REQUIRED ((NTSTATUS) 0xC0000408L)
-#endif
-
-#ifndef STATUS_STACK_BUFFER_OVERRUN
-# define STATUS_STACK_BUFFER_OVERRUN ((NTSTATUS) 0xC0000409L)
-#endif
-
-#ifndef STATUS_NO_S4U_PROT_SUPPORT
-# define STATUS_NO_S4U_PROT_SUPPORT ((NTSTATUS) 0xC000040AL)
-#endif
-
-#ifndef STATUS_CROSSREALM_DELEGATION_FAILURE
-# define STATUS_CROSSREALM_DELEGATION_FAILURE ((NTSTATUS) 0xC000040BL)
-#endif
-
-#ifndef STATUS_REVOCATION_OFFLINE_KDC
-# define STATUS_REVOCATION_OFFLINE_KDC ((NTSTATUS) 0xC000040CL)
-#endif
-
-#ifndef STATUS_ISSUING_CA_UNTRUSTED_KDC
-# define STATUS_ISSUING_CA_UNTRUSTED_KDC ((NTSTATUS) 0xC000040DL)
-#endif
-
-#ifndef STATUS_KDC_CERT_EXPIRED
-# define STATUS_KDC_CERT_EXPIRED ((NTSTATUS) 0xC000040EL)
-#endif
-
-#ifndef STATUS_KDC_CERT_REVOKED
-# define STATUS_KDC_CERT_REVOKED ((NTSTATUS) 0xC000040FL)
-#endif
-
-#ifndef STATUS_PARAMETER_QUOTA_EXCEEDED
-# define STATUS_PARAMETER_QUOTA_EXCEEDED ((NTSTATUS) 0xC0000410L)
-#endif
-
-#ifndef STATUS_HIBERNATION_FAILURE
-# define STATUS_HIBERNATION_FAILURE ((NTSTATUS) 0xC0000411L)
-#endif
-
-#ifndef STATUS_DELAY_LOAD_FAILED
-# define STATUS_DELAY_LOAD_FAILED ((NTSTATUS) 0xC0000412L)
-#endif
-
-#ifndef STATUS_AUTHENTICATION_FIREWALL_FAILED
-# define STATUS_AUTHENTICATION_FIREWALL_FAILED ((NTSTATUS) 0xC0000413L)
-#endif
-
-#ifndef STATUS_VDM_DISALLOWED
-# define STATUS_VDM_DISALLOWED ((NTSTATUS) 0xC0000414L)
-#endif
-
-#ifndef STATUS_HUNG_DISPLAY_DRIVER_THREAD
-# define STATUS_HUNG_DISPLAY_DRIVER_THREAD ((NTSTATUS) 0xC0000415L)
-#endif
-
-#ifndef STATUS_INSUFFICIENT_RESOURCE_FOR_SPECIFIED_SHARED_SECTION_SIZE
-# define STATUS_INSUFFICIENT_RESOURCE_FOR_SPECIFIED_SHARED_SECTION_SIZE ((NTSTATUS) 0xC0000416L)
-#endif
-
-#ifndef STATUS_INVALID_CRUNTIME_PARAMETER
-# define STATUS_INVALID_CRUNTIME_PARAMETER ((NTSTATUS) 0xC0000417L)
-#endif
-
-#ifndef STATUS_NTLM_BLOCKED
-# define STATUS_NTLM_BLOCKED ((NTSTATUS) 0xC0000418L)
-#endif
-
-#ifndef STATUS_DS_SRC_SID_EXISTS_IN_FOREST
-# define STATUS_DS_SRC_SID_EXISTS_IN_FOREST ((NTSTATUS) 0xC0000419L)
-#endif
-
-#ifndef STATUS_DS_DOMAIN_NAME_EXISTS_IN_FOREST
-# define STATUS_DS_DOMAIN_NAME_EXISTS_IN_FOREST ((NTSTATUS) 0xC000041AL)
-#endif
-
-#ifndef STATUS_DS_FLAT_NAME_EXISTS_IN_FOREST
-# define STATUS_DS_FLAT_NAME_EXISTS_IN_FOREST ((NTSTATUS) 0xC000041BL)
-#endif
-
-#ifndef STATUS_INVALID_USER_PRINCIPAL_NAME
-# define STATUS_INVALID_USER_PRINCIPAL_NAME ((NTSTATUS) 0xC000041CL)
-#endif
-
-#ifndef STATUS_FATAL_USER_CALLBACK_EXCEPTION
-# define STATUS_FATAL_USER_CALLBACK_EXCEPTION ((NTSTATUS) 0xC000041DL)
-#endif
-
-#ifndef STATUS_ASSERTION_FAILURE
-# define STATUS_ASSERTION_FAILURE ((NTSTATUS) 0xC0000420L)
-#endif
-
-#ifndef STATUS_VERIFIER_STOP
-# define STATUS_VERIFIER_STOP ((NTSTATUS) 0xC0000421L)
-#endif
-
-#ifndef STATUS_CALLBACK_POP_STACK
-# define STATUS_CALLBACK_POP_STACK ((NTSTATUS) 0xC0000423L)
-#endif
-
-#ifndef STATUS_INCOMPATIBLE_DRIVER_BLOCKED
-# define STATUS_INCOMPATIBLE_DRIVER_BLOCKED ((NTSTATUS) 0xC0000424L)
-#endif
-
-#ifndef STATUS_HIVE_UNLOADED
-# define STATUS_HIVE_UNLOADED ((NTSTATUS) 0xC0000425L)
-#endif
-
-#ifndef STATUS_COMPRESSION_DISABLED
-# define STATUS_COMPRESSION_DISABLED ((NTSTATUS) 0xC0000426L)
-#endif
-
-#ifndef STATUS_FILE_SYSTEM_LIMITATION
-# define STATUS_FILE_SYSTEM_LIMITATION ((NTSTATUS) 0xC0000427L)
-#endif
-
-#ifndef STATUS_INVALID_IMAGE_HASH
-# define STATUS_INVALID_IMAGE_HASH ((NTSTATUS) 0xC0000428L)
-#endif
-
-#ifndef STATUS_NOT_CAPABLE
-# define STATUS_NOT_CAPABLE ((NTSTATUS) 0xC0000429L)
-#endif
-
-#ifndef STATUS_REQUEST_OUT_OF_SEQUENCE
-# define STATUS_REQUEST_OUT_OF_SEQUENCE ((NTSTATUS) 0xC000042AL)
-#endif
-
-#ifndef STATUS_IMPLEMENTATION_LIMIT
-# define STATUS_IMPLEMENTATION_LIMIT ((NTSTATUS) 0xC000042BL)
-#endif
-
-#ifndef STATUS_ELEVATION_REQUIRED
-# define STATUS_ELEVATION_REQUIRED ((NTSTATUS) 0xC000042CL)
-#endif
-
-#ifndef STATUS_NO_SECURITY_CONTEXT
-# define STATUS_NO_SECURITY_CONTEXT ((NTSTATUS) 0xC000042DL)
-#endif
-
-#ifndef STATUS_PKU2U_CERT_FAILURE
-# define STATUS_PKU2U_CERT_FAILURE ((NTSTATUS) 0xC000042FL)
-#endif
-
-#ifndef STATUS_BEYOND_VDL
-# define STATUS_BEYOND_VDL ((NTSTATUS) 0xC0000432L)
-#endif
-
-#ifndef STATUS_ENCOUNTERED_WRITE_IN_PROGRESS
-# define STATUS_ENCOUNTERED_WRITE_IN_PROGRESS ((NTSTATUS) 0xC0000433L)
-#endif
-
-#ifndef STATUS_PTE_CHANGED
-# define STATUS_PTE_CHANGED ((NTSTATUS) 0xC0000434L)
-#endif
-
-#ifndef STATUS_PURGE_FAILED
-# define STATUS_PURGE_FAILED ((NTSTATUS) 0xC0000435L)
-#endif
-
-#ifndef STATUS_CRED_REQUIRES_CONFIRMATION
-# define STATUS_CRED_REQUIRES_CONFIRMATION ((NTSTATUS) 0xC0000440L)
-#endif
-
-#ifndef STATUS_CS_ENCRYPTION_INVALID_SERVER_RESPONSE
-# define STATUS_CS_ENCRYPTION_INVALID_SERVER_RESPONSE ((NTSTATUS) 0xC0000441L)
-#endif
-
-#ifndef STATUS_CS_ENCRYPTION_UNSUPPORTED_SERVER
-# define STATUS_CS_ENCRYPTION_UNSUPPORTED_SERVER ((NTSTATUS) 0xC0000442L)
-#endif
-
-#ifndef STATUS_CS_ENCRYPTION_EXISTING_ENCRYPTED_FILE
-# define STATUS_CS_ENCRYPTION_EXISTING_ENCRYPTED_FILE ((NTSTATUS) 0xC0000443L)
-#endif
-
-#ifndef STATUS_CS_ENCRYPTION_NEW_ENCRYPTED_FILE
-# define STATUS_CS_ENCRYPTION_NEW_ENCRYPTED_FILE ((NTSTATUS) 0xC0000444L)
-#endif
-
-#ifndef STATUS_CS_ENCRYPTION_FILE_NOT_CSE
-# define STATUS_CS_ENCRYPTION_FILE_NOT_CSE ((NTSTATUS) 0xC0000445L)
-#endif
-
-#ifndef STATUS_INVALID_LABEL
-# define STATUS_INVALID_LABEL ((NTSTATUS) 0xC0000446L)
-#endif
-
-#ifndef STATUS_DRIVER_PROCESS_TERMINATED
-# define STATUS_DRIVER_PROCESS_TERMINATED ((NTSTATUS) 0xC0000450L)
-#endif
-
-#ifndef STATUS_AMBIGUOUS_SYSTEM_DEVICE
-# define STATUS_AMBIGUOUS_SYSTEM_DEVICE ((NTSTATUS) 0xC0000451L)
-#endif
-
-#ifndef STATUS_SYSTEM_DEVICE_NOT_FOUND
-# define STATUS_SYSTEM_DEVICE_NOT_FOUND ((NTSTATUS) 0xC0000452L)
-#endif
-
-#ifndef STATUS_RESTART_BOOT_APPLICATION
-# define STATUS_RESTART_BOOT_APPLICATION ((NTSTATUS) 0xC0000453L)
-#endif
-
-#ifndef STATUS_INSUFFICIENT_NVRAM_RESOURCES
-# define STATUS_INSUFFICIENT_NVRAM_RESOURCES ((NTSTATUS) 0xC0000454L)
-#endif
-
-#ifndef STATUS_INVALID_TASK_NAME
-# define STATUS_INVALID_TASK_NAME ((NTSTATUS) 0xC0000500L)
-#endif
-
-#ifndef STATUS_INVALID_TASK_INDEX
-# define STATUS_INVALID_TASK_INDEX ((NTSTATUS) 0xC0000501L)
-#endif
-
-#ifndef STATUS_THREAD_ALREADY_IN_TASK
-# define STATUS_THREAD_ALREADY_IN_TASK ((NTSTATUS) 0xC0000502L)
-#endif
-
-#ifndef STATUS_CALLBACK_BYPASS
-# define STATUS_CALLBACK_BYPASS ((NTSTATUS) 0xC0000503L)
-#endif
-
-#ifndef STATUS_FAIL_FAST_EXCEPTION
-# define STATUS_FAIL_FAST_EXCEPTION ((NTSTATUS) 0xC0000602L)
-#endif
-
-#ifndef STATUS_IMAGE_CERT_REVOKED
-# define STATUS_IMAGE_CERT_REVOKED ((NTSTATUS) 0xC0000603L)
-#endif
-
-#ifndef STATUS_PORT_CLOSED
-# define STATUS_PORT_CLOSED ((NTSTATUS) 0xC0000700L)
-#endif
-
-#ifndef STATUS_MESSAGE_LOST
-# define STATUS_MESSAGE_LOST ((NTSTATUS) 0xC0000701L)
-#endif
-
-#ifndef STATUS_INVALID_MESSAGE
-# define STATUS_INVALID_MESSAGE ((NTSTATUS) 0xC0000702L)
-#endif
-
-#ifndef STATUS_REQUEST_CANCELED
-# define STATUS_REQUEST_CANCELED ((NTSTATUS) 0xC0000703L)
-#endif
-
-#ifndef STATUS_RECURSIVE_DISPATCH
-# define STATUS_RECURSIVE_DISPATCH ((NTSTATUS) 0xC0000704L)
-#endif
-
-#ifndef STATUS_LPC_RECEIVE_BUFFER_EXPECTED
-# define STATUS_LPC_RECEIVE_BUFFER_EXPECTED ((NTSTATUS) 0xC0000705L)
-#endif
-
-#ifndef STATUS_LPC_INVALID_CONNECTION_USAGE
-# define STATUS_LPC_INVALID_CONNECTION_USAGE ((NTSTATUS) 0xC0000706L)
-#endif
-
-#ifndef STATUS_LPC_REQUESTS_NOT_ALLOWED
-# define STATUS_LPC_REQUESTS_NOT_ALLOWED ((NTSTATUS) 0xC0000707L)
-#endif
-
-#ifndef STATUS_RESOURCE_IN_USE
-# define STATUS_RESOURCE_IN_USE ((NTSTATUS) 0xC0000708L)
-#endif
-
-#ifndef STATUS_HARDWARE_MEMORY_ERROR
-# define STATUS_HARDWARE_MEMORY_ERROR ((NTSTATUS) 0xC0000709L)
-#endif
-
-#ifndef STATUS_THREADPOOL_HANDLE_EXCEPTION
-# define STATUS_THREADPOOL_HANDLE_EXCEPTION ((NTSTATUS) 0xC000070AL)
-#endif
-
-#ifndef STATUS_THREADPOOL_SET_EVENT_ON_COMPLETION_FAILED
-# define STATUS_THREADPOOL_SET_EVENT_ON_COMPLETION_FAILED ((NTSTATUS) 0xC000070BL)
-#endif
-
-#ifndef STATUS_THREADPOOL_RELEASE_SEMAPHORE_ON_COMPLETION_FAILED
-# define STATUS_THREADPOOL_RELEASE_SEMAPHORE_ON_COMPLETION_FAILED ((NTSTATUS) 0xC000070CL)
-#endif
-
-#ifndef STATUS_THREADPOOL_RELEASE_MUTEX_ON_COMPLETION_FAILED
-# define STATUS_THREADPOOL_RELEASE_MUTEX_ON_COMPLETION_FAILED ((NTSTATUS) 0xC000070DL)
-#endif
-
-#ifndef STATUS_THREADPOOL_FREE_LIBRARY_ON_COMPLETION_FAILED
-# define STATUS_THREADPOOL_FREE_LIBRARY_ON_COMPLETION_FAILED ((NTSTATUS) 0xC000070EL)
-#endif
-
-#ifndef STATUS_THREADPOOL_RELEASED_DURING_OPERATION
-# define STATUS_THREADPOOL_RELEASED_DURING_OPERATION ((NTSTATUS) 0xC000070FL)
-#endif
-
-#ifndef STATUS_CALLBACK_RETURNED_WHILE_IMPERSONATING
-# define STATUS_CALLBACK_RETURNED_WHILE_IMPERSONATING ((NTSTATUS) 0xC0000710L)
-#endif
-
-#ifndef STATUS_APC_RETURNED_WHILE_IMPERSONATING
-# define STATUS_APC_RETURNED_WHILE_IMPERSONATING ((NTSTATUS) 0xC0000711L)
-#endif
-
-#ifndef STATUS_PROCESS_IS_PROTECTED
-# define STATUS_PROCESS_IS_PROTECTED ((NTSTATUS) 0xC0000712L)
-#endif
-
-#ifndef STATUS_MCA_EXCEPTION
-# define STATUS_MCA_EXCEPTION ((NTSTATUS) 0xC0000713L)
-#endif
-
-#ifndef STATUS_CERTIFICATE_MAPPING_NOT_UNIQUE
-# define STATUS_CERTIFICATE_MAPPING_NOT_UNIQUE ((NTSTATUS) 0xC0000714L)
-#endif
-
-#ifndef STATUS_SYMLINK_CLASS_DISABLED
-# define STATUS_SYMLINK_CLASS_DISABLED ((NTSTATUS) 0xC0000715L)
-#endif
-
-#ifndef STATUS_INVALID_IDN_NORMALIZATION
-# define STATUS_INVALID_IDN_NORMALIZATION ((NTSTATUS) 0xC0000716L)
-#endif
-
-#ifndef STATUS_NO_UNICODE_TRANSLATION
-# define STATUS_NO_UNICODE_TRANSLATION ((NTSTATUS) 0xC0000717L)
-#endif
-
-#ifndef STATUS_ALREADY_REGISTERED
-# define STATUS_ALREADY_REGISTERED ((NTSTATUS) 0xC0000718L)
-#endif
-
-#ifndef STATUS_CONTEXT_MISMATCH
-# define STATUS_CONTEXT_MISMATCH ((NTSTATUS) 0xC0000719L)
-#endif
-
-#ifndef STATUS_PORT_ALREADY_HAS_COMPLETION_LIST
-# define STATUS_PORT_ALREADY_HAS_COMPLETION_LIST ((NTSTATUS) 0xC000071AL)
-#endif
-
-#ifndef STATUS_CALLBACK_RETURNED_THREAD_PRIORITY
-# define STATUS_CALLBACK_RETURNED_THREAD_PRIORITY ((NTSTATUS) 0xC000071BL)
-#endif
-
-#ifndef STATUS_INVALID_THREAD
-# define STATUS_INVALID_THREAD ((NTSTATUS) 0xC000071CL)
-#endif
-
-#ifndef STATUS_CALLBACK_RETURNED_TRANSACTION
-# define STATUS_CALLBACK_RETURNED_TRANSACTION ((NTSTATUS) 0xC000071DL)
-#endif
-
-#ifndef STATUS_CALLBACK_RETURNED_LDR_LOCK
-# define STATUS_CALLBACK_RETURNED_LDR_LOCK ((NTSTATUS) 0xC000071EL)
-#endif
-
-#ifndef STATUS_CALLBACK_RETURNED_LANG
-# define STATUS_CALLBACK_RETURNED_LANG ((NTSTATUS) 0xC000071FL)
-#endif
-
-#ifndef STATUS_CALLBACK_RETURNED_PRI_BACK
-# define STATUS_CALLBACK_RETURNED_PRI_BACK ((NTSTATUS) 0xC0000720L)
-#endif
-
-#ifndef STATUS_CALLBACK_RETURNED_THREAD_AFFINITY
-# define STATUS_CALLBACK_RETURNED_THREAD_AFFINITY ((NTSTATUS) 0xC0000721L)
-#endif
-
-#ifndef STATUS_DISK_REPAIR_DISABLED
-# define STATUS_DISK_REPAIR_DISABLED ((NTSTATUS) 0xC0000800L)
-#endif
-
-#ifndef STATUS_DS_DOMAIN_RENAME_IN_PROGRESS
-# define STATUS_DS_DOMAIN_RENAME_IN_PROGRESS ((NTSTATUS) 0xC0000801L)
-#endif
-
-#ifndef STATUS_DISK_QUOTA_EXCEEDED
-# define STATUS_DISK_QUOTA_EXCEEDED ((NTSTATUS) 0xC0000802L)
-#endif
-
-#ifndef STATUS_DATA_LOST_REPAIR
-# define STATUS_DATA_LOST_REPAIR ((NTSTATUS) 0x80000803L)
-#endif
-
-#ifndef STATUS_CONTENT_BLOCKED
-# define STATUS_CONTENT_BLOCKED ((NTSTATUS) 0xC0000804L)
-#endif
-
-#ifndef STATUS_BAD_CLUSTERS
-# define STATUS_BAD_CLUSTERS ((NTSTATUS) 0xC0000805L)
-#endif
-
-#ifndef STATUS_VOLUME_DIRTY
-# define STATUS_VOLUME_DIRTY ((NTSTATUS) 0xC0000806L)
-#endif
-
-#ifndef STATUS_FILE_CHECKED_OUT
-# define STATUS_FILE_CHECKED_OUT ((NTSTATUS) 0xC0000901L)
-#endif
-
-#ifndef STATUS_CHECKOUT_REQUIRED
-# define STATUS_CHECKOUT_REQUIRED ((NTSTATUS) 0xC0000902L)
-#endif
-
-#ifndef STATUS_BAD_FILE_TYPE
-# define STATUS_BAD_FILE_TYPE ((NTSTATUS) 0xC0000903L)
-#endif
-
-#ifndef STATUS_FILE_TOO_LARGE
-# define STATUS_FILE_TOO_LARGE ((NTSTATUS) 0xC0000904L)
-#endif
-
-#ifndef STATUS_FORMS_AUTH_REQUIRED
-# define STATUS_FORMS_AUTH_REQUIRED ((NTSTATUS) 0xC0000905L)
-#endif
-
-#ifndef STATUS_VIRUS_INFECTED
-# define STATUS_VIRUS_INFECTED ((NTSTATUS) 0xC0000906L)
-#endif
-
-#ifndef STATUS_VIRUS_DELETED
-# define STATUS_VIRUS_DELETED ((NTSTATUS) 0xC0000907L)
-#endif
-
-#ifndef STATUS_BAD_MCFG_TABLE
-# define STATUS_BAD_MCFG_TABLE ((NTSTATUS) 0xC0000908L)
-#endif
-
-#ifndef STATUS_CANNOT_BREAK_OPLOCK
-# define STATUS_CANNOT_BREAK_OPLOCK ((NTSTATUS) 0xC0000909L)
-#endif
-
-#ifndef STATUS_WOW_ASSERTION
-# define STATUS_WOW_ASSERTION ((NTSTATUS) 0xC0009898L)
-#endif
-
-#ifndef STATUS_INVALID_SIGNATURE
-# define STATUS_INVALID_SIGNATURE ((NTSTATUS) 0xC000A000L)
-#endif
-
-#ifndef STATUS_HMAC_NOT_SUPPORTED
-# define STATUS_HMAC_NOT_SUPPORTED ((NTSTATUS) 0xC000A001L)
-#endif
-
-#ifndef STATUS_AUTH_TAG_MISMATCH
-# define STATUS_AUTH_TAG_MISMATCH ((NTSTATUS) 0xC000A002L)
-#endif
-
-#ifndef STATUS_IPSEC_QUEUE_OVERFLOW
-# define STATUS_IPSEC_QUEUE_OVERFLOW ((NTSTATUS) 0xC000A010L)
-#endif
-
-#ifndef STATUS_ND_QUEUE_OVERFLOW
-# define STATUS_ND_QUEUE_OVERFLOW ((NTSTATUS) 0xC000A011L)
-#endif
-
-#ifndef STATUS_HOPLIMIT_EXCEEDED
-# define STATUS_HOPLIMIT_EXCEEDED ((NTSTATUS) 0xC000A012L)
-#endif
-
-#ifndef STATUS_PROTOCOL_NOT_SUPPORTED
-# define STATUS_PROTOCOL_NOT_SUPPORTED ((NTSTATUS) 0xC000A013L)
-#endif
-
-#ifndef STATUS_FASTPATH_REJECTED
-# define STATUS_FASTPATH_REJECTED ((NTSTATUS) 0xC000A014L)
-#endif
-
-#ifndef STATUS_LOST_WRITEBEHIND_DATA_NETWORK_DISCONNECTED
-# define STATUS_LOST_WRITEBEHIND_DATA_NETWORK_DISCONNECTED ((NTSTATUS) 0xC000A080L)
-#endif
-
-#ifndef STATUS_LOST_WRITEBEHIND_DATA_NETWORK_SERVER_ERROR
-# define STATUS_LOST_WRITEBEHIND_DATA_NETWORK_SERVER_ERROR ((NTSTATUS) 0xC000A081L)
-#endif
-
-#ifndef STATUS_LOST_WRITEBEHIND_DATA_LOCAL_DISK_ERROR
-# define STATUS_LOST_WRITEBEHIND_DATA_LOCAL_DISK_ERROR ((NTSTATUS) 0xC000A082L)
-#endif
-
-#ifndef STATUS_XML_PARSE_ERROR
-# define STATUS_XML_PARSE_ERROR ((NTSTATUS) 0xC000A083L)
-#endif
-
-#ifndef STATUS_XMLDSIG_ERROR
-# define STATUS_XMLDSIG_ERROR ((NTSTATUS) 0xC000A084L)
-#endif
-
-#ifndef STATUS_WRONG_COMPARTMENT
-# define STATUS_WRONG_COMPARTMENT ((NTSTATUS) 0xC000A085L)
-#endif
-
-#ifndef STATUS_AUTHIP_FAILURE
-# define STATUS_AUTHIP_FAILURE ((NTSTATUS) 0xC000A086L)
-#endif
-
-#ifndef STATUS_DS_OID_MAPPED_GROUP_CANT_HAVE_MEMBERS
-# define STATUS_DS_OID_MAPPED_GROUP_CANT_HAVE_MEMBERS ((NTSTATUS) 0xC000A087L)
-#endif
-
-#ifndef STATUS_DS_OID_NOT_FOUND
-# define STATUS_DS_OID_NOT_FOUND ((NTSTATUS) 0xC000A088L)
-#endif
-
-#ifndef STATUS_HASH_NOT_SUPPORTED
-# define STATUS_HASH_NOT_SUPPORTED ((NTSTATUS) 0xC000A100L)
-#endif
-
-#ifndef STATUS_HASH_NOT_PRESENT
-# define STATUS_HASH_NOT_PRESENT ((NTSTATUS) 0xC000A101L)
-#endif
-
-/* This is not the NTSTATUS_FROM_WIN32 that the DDK provides, because the DDK
- * got it wrong! */
-#ifdef NTSTATUS_FROM_WIN32
-# undef NTSTATUS_FROM_WIN32
-#endif
-#define NTSTATUS_FROM_WIN32(error) ((NTSTATUS) (error) <= 0 ? \
-        ((NTSTATUS) (error)) : ((NTSTATUS) (((error) & 0x0000FFFF) | \
-        (FACILITY_NTWIN32 << 16) | ERROR_SEVERITY_WARNING)))
-
-#ifndef JOB_OBJECT_LIMIT_PROCESS_MEMORY
-# define JOB_OBJECT_LIMIT_PROCESS_MEMORY             0x00000100
-#endif
-#ifndef JOB_OBJECT_LIMIT_JOB_MEMORY
-# define JOB_OBJECT_LIMIT_JOB_MEMORY                 0x00000200
-#endif
-#ifndef JOB_OBJECT_LIMIT_DIE_ON_UNHANDLED_EXCEPTION
-# define JOB_OBJECT_LIMIT_DIE_ON_UNHANDLED_EXCEPTION 0x00000400
-#endif
-#ifndef JOB_OBJECT_LIMIT_BREAKAWAY_OK
-# define JOB_OBJECT_LIMIT_BREAKAWAY_OK               0x00000800
-#endif
-#ifndef JOB_OBJECT_LIMIT_SILENT_BREAKAWAY_OK
-# define JOB_OBJECT_LIMIT_SILENT_BREAKAWAY_OK        0x00001000
-#endif
-#ifndef JOB_OBJECT_LIMIT_KILL_ON_JOB_CLOSE
-# define JOB_OBJECT_LIMIT_KILL_ON_JOB_CLOSE          0x00002000
-#endif
-
-#ifndef SYMBOLIC_LINK_FLAG_ALLOW_UNPRIVILEGED_CREATE
-# define SYMBOLIC_LINK_FLAG_ALLOW_UNPRIVILEGED_CREATE 0x00000002
-#endif
-
-/* from winternl.h */
-#if !defined(__UNICODE_STRING_DEFINED) && defined(__MINGW32_)
-#define __UNICODE_STRING_DEFINED
-#endif
-typedef struct _UNICODE_STRING {
-  USHORT Length;
-  USHORT MaximumLength;
-  PWSTR  Buffer;
-} UNICODE_STRING, *PUNICODE_STRING;
-
-typedef const UNICODE_STRING *PCUNICODE_STRING;
-
-/* from ntifs.h */
-#ifndef DEVICE_TYPE
-# define DEVICE_TYPE DWORD
-#endif
-
-/* MinGW already has a definition for REPARSE_DATA_BUFFER, but mingw-w64 does
- * not.
- */
-#if defined(_MSC_VER) || defined(__MINGW64_VERSION_MAJOR)
-  typedef struct _REPARSE_DATA_BUFFER {
-    ULONG  ReparseTag;
-    USHORT ReparseDataLength;
-    USHORT Reserved;
-    union {
-      struct {
-        USHORT SubstituteNameOffset;
-        USHORT SubstituteNameLength;
-        USHORT PrintNameOffset;
-        USHORT PrintNameLength;
-        ULONG Flags;
-        WCHAR PathBuffer[1];
-      } SymbolicLinkReparseBuffer;
-      struct {
-        USHORT SubstituteNameOffset;
-        USHORT SubstituteNameLength;
-        USHORT PrintNameOffset;
-        USHORT PrintNameLength;
-        WCHAR PathBuffer[1];
-      } MountPointReparseBuffer;
-      struct {
-        UCHAR  DataBuffer[1];
-      } GenericReparseBuffer;
-    };
-  } REPARSE_DATA_BUFFER, *PREPARSE_DATA_BUFFER;
-#endif
-
-typedef struct _IO_STATUS_BLOCK {
-  union {
-    NTSTATUS Status;
-    PVOID Pointer;
-  };
-  ULONG_PTR Information;
-} IO_STATUS_BLOCK, *PIO_STATUS_BLOCK;
-
-typedef enum _FILE_INFORMATION_CLASS {
-  FileDirectoryInformation = 1,
-  FileFullDirectoryInformation,
-  FileBothDirectoryInformation,
-  FileBasicInformation,
-  FileStandardInformation,
-  FileInternalInformation,
-  FileEaInformation,
-  FileAccessInformation,
-  FileNameInformation,
-  FileRenameInformation,
-  FileLinkInformation,
-  FileNamesInformation,
-  FileDispositionInformation,
-  FilePositionInformation,
-  FileFullEaInformation,
-  FileModeInformation,
-  FileAlignmentInformation,
-  FileAllInformation,
-  FileAllocationInformation,
-  FileEndOfFileInformation,
-  FileAlternateNameInformation,
-  FileStreamInformation,
-  FilePipeInformation,
-  FilePipeLocalInformation,
-  FilePipeRemoteInformation,
-  FileMailslotQueryInformation,
-  FileMailslotSetInformation,
-  FileCompressionInformation,
-  FileObjectIdInformation,
-  FileCompletionInformation,
-  FileMoveClusterInformation,
-  FileQuotaInformation,
-  FileReparsePointInformation,
-  FileNetworkOpenInformation,
-  FileAttributeTagInformation,
-  FileTrackingInformation,
-  FileIdBothDirectoryInformation,
-  FileIdFullDirectoryInformation,
-  FileValidDataLengthInformation,
-  FileShortNameInformation,
-  FileIoCompletionNotificationInformation,
-  FileIoStatusBlockRangeInformation,
-  FileIoPriorityHintInformation,
-  FileSfioReserveInformation,
-  FileSfioVolumeInformation,
-  FileHardLinkInformation,
-  FileProcessIdsUsingFileInformation,
-  FileNormalizedNameInformation,
-  FileNetworkPhysicalNameInformation,
-  FileIdGlobalTxDirectoryInformation,
-  FileIsRemoteDeviceInformation,
-  FileAttributeCacheInformation,
-  FileNumaNodeInformation,
-  FileStandardLinkInformation,
-  FileRemoteProtocolInformation,
-  FileMaximumInformation
-} FILE_INFORMATION_CLASS, *PFILE_INFORMATION_CLASS;
-
-typedef struct _FILE_DIRECTORY_INFORMATION {
-  ULONG NextEntryOffset;
-  ULONG FileIndex;
-  LARGE_INTEGER CreationTime;
-  LARGE_INTEGER LastAccessTime;
-  LARGE_INTEGER LastWriteTime;
-  LARGE_INTEGER ChangeTime;
-  LARGE_INTEGER EndOfFile;
-  LARGE_INTEGER AllocationSize;
-  ULONG FileAttributes;
-  ULONG FileNameLength;
-  WCHAR FileName[1];
-} FILE_DIRECTORY_INFORMATION, *PFILE_DIRECTORY_INFORMATION;
-
-typedef struct _FILE_BOTH_DIR_INFORMATION {
-  ULONG NextEntryOffset;
-  ULONG FileIndex;
-  LARGE_INTEGER CreationTime;
-  LARGE_INTEGER LastAccessTime;
-  LARGE_INTEGER LastWriteTime;
-  LARGE_INTEGER ChangeTime;
-  LARGE_INTEGER EndOfFile;
-  LARGE_INTEGER AllocationSize;
-  ULONG FileAttributes;
-  ULONG FileNameLength;
-  ULONG EaSize;
-  CCHAR ShortNameLength;
-  WCHAR ShortName[12];
-  WCHAR FileName[1];
-} FILE_BOTH_DIR_INFORMATION, *PFILE_BOTH_DIR_INFORMATION;
-
-typedef struct _FILE_BASIC_INFORMATION {
-  LARGE_INTEGER CreationTime;
-  LARGE_INTEGER LastAccessTime;
-  LARGE_INTEGER LastWriteTime;
-  LARGE_INTEGER ChangeTime;
-  DWORD FileAttributes;
-} FILE_BASIC_INFORMATION, *PFILE_BASIC_INFORMATION;
-
-typedef struct _FILE_STANDARD_INFORMATION {
-  LARGE_INTEGER AllocationSize;
-  LARGE_INTEGER EndOfFile;
-  ULONG         NumberOfLinks;
-  BOOLEAN       DeletePending;
-  BOOLEAN       Directory;
-} FILE_STANDARD_INFORMATION, *PFILE_STANDARD_INFORMATION;
-
-typedef struct _FILE_INTERNAL_INFORMATION {
-  LARGE_INTEGER IndexNumber;
-} FILE_INTERNAL_INFORMATION, *PFILE_INTERNAL_INFORMATION;
-
-typedef struct _FILE_EA_INFORMATION {
-  ULONG EaSize;
-} FILE_EA_INFORMATION, *PFILE_EA_INFORMATION;
-
-typedef struct _FILE_ACCESS_INFORMATION {
-  ACCESS_MASK AccessFlags;
-} FILE_ACCESS_INFORMATION, *PFILE_ACCESS_INFORMATION;
-
-typedef struct _FILE_POSITION_INFORMATION {
-  LARGE_INTEGER CurrentByteOffset;
-} FILE_POSITION_INFORMATION, *PFILE_POSITION_INFORMATION;
-
-typedef struct _FILE_MODE_INFORMATION {
-  ULONG Mode;
-} FILE_MODE_INFORMATION, *PFILE_MODE_INFORMATION;
-
-typedef struct _FILE_ALIGNMENT_INFORMATION {
-  ULONG AlignmentRequirement;
-} FILE_ALIGNMENT_INFORMATION, *PFILE_ALIGNMENT_INFORMATION;
-
-typedef struct _FILE_NAME_INFORMATION {
-  ULONG FileNameLength;
-  WCHAR FileName[1];
-} FILE_NAME_INFORMATION, *PFILE_NAME_INFORMATION;
-
-typedef struct _FILE_END_OF_FILE_INFORMATION {
-  LARGE_INTEGER  EndOfFile;
-} FILE_END_OF_FILE_INFORMATION, *PFILE_END_OF_FILE_INFORMATION;
-
-typedef struct _FILE_ALL_INFORMATION {
-  FILE_BASIC_INFORMATION     BasicInformation;
-  FILE_STANDARD_INFORMATION  StandardInformation;
-  FILE_INTERNAL_INFORMATION  InternalInformation;
-  FILE_EA_INFORMATION        EaInformation;
-  FILE_ACCESS_INFORMATION    AccessInformation;
-  FILE_POSITION_INFORMATION  PositionInformation;
-  FILE_MODE_INFORMATION      ModeInformation;
-  FILE_ALIGNMENT_INFORMATION AlignmentInformation;
-  FILE_NAME_INFORMATION      NameInformation;
-} FILE_ALL_INFORMATION, *PFILE_ALL_INFORMATION;
-
-typedef struct _FILE_DISPOSITION_INFORMATION {
-  BOOLEAN DeleteFile;
-} FILE_DISPOSITION_INFORMATION, *PFILE_DISPOSITION_INFORMATION;
-
-typedef struct _FILE_PIPE_LOCAL_INFORMATION {
-  ULONG NamedPipeType;
-  ULONG NamedPipeConfiguration;
-  ULONG MaximumInstances;
-  ULONG CurrentInstances;
-  ULONG InboundQuota;
-  ULONG ReadDataAvailable;
-  ULONG OutboundQuota;
-  ULONG WriteQuotaAvailable;
-  ULONG NamedPipeState;
-  ULONG NamedPipeEnd;
-} FILE_PIPE_LOCAL_INFORMATION, *PFILE_PIPE_LOCAL_INFORMATION;
-
-#define FILE_SYNCHRONOUS_IO_ALERT               0x00000010
-#define FILE_SYNCHRONOUS_IO_NONALERT            0x00000020
-
-typedef enum _FS_INFORMATION_CLASS {
-  FileFsVolumeInformation       = 1,
-  FileFsLabelInformation        = 2,
-  FileFsSizeInformation         = 3,
-  FileFsDeviceInformation       = 4,
-  FileFsAttributeInformation    = 5,
-  FileFsControlInformation      = 6,
-  FileFsFullSizeInformation     = 7,
-  FileFsObjectIdInformation     = 8,
-  FileFsDriverPathInformation   = 9,
-  FileFsVolumeFlagsInformation  = 10,
-  FileFsSectorSizeInformation   = 11
-} FS_INFORMATION_CLASS, *PFS_INFORMATION_CLASS;
-
-typedef struct _FILE_FS_VOLUME_INFORMATION {
-  LARGE_INTEGER VolumeCreationTime;
-  ULONG         VolumeSerialNumber;
-  ULONG         VolumeLabelLength;
-  BOOLEAN       SupportsObjects;
-  WCHAR         VolumeLabel[1];
-} FILE_FS_VOLUME_INFORMATION, *PFILE_FS_VOLUME_INFORMATION;
-
-typedef struct _FILE_FS_LABEL_INFORMATION {
-  ULONG VolumeLabelLength;
-  WCHAR VolumeLabel[1];
-} FILE_FS_LABEL_INFORMATION, *PFILE_FS_LABEL_INFORMATION;
-
-typedef struct _FILE_FS_SIZE_INFORMATION {
-  LARGE_INTEGER TotalAllocationUnits;
-  LARGE_INTEGER AvailableAllocationUnits;
-  ULONG         SectorsPerAllocationUnit;
-  ULONG         BytesPerSector;
-} FILE_FS_SIZE_INFORMATION, *PFILE_FS_SIZE_INFORMATION;
-
-typedef struct _FILE_FS_DEVICE_INFORMATION {
-  DEVICE_TYPE DeviceType;
-  ULONG       Characteristics;
-} FILE_FS_DEVICE_INFORMATION, *PFILE_FS_DEVICE_INFORMATION;
-
-typedef struct _FILE_FS_ATTRIBUTE_INFORMATION {
-  ULONG FileSystemAttributes;
-  LONG  MaximumComponentNameLength;
-  ULONG FileSystemNameLength;
-  WCHAR FileSystemName[1];
-} FILE_FS_ATTRIBUTE_INFORMATION, *PFILE_FS_ATTRIBUTE_INFORMATION;
-
-typedef struct _FILE_FS_CONTROL_INFORMATION {
-  LARGE_INTEGER FreeSpaceStartFiltering;
-  LARGE_INTEGER FreeSpaceThreshold;
-  LARGE_INTEGER FreeSpaceStopFiltering;
-  LARGE_INTEGER DefaultQuotaThreshold;
-  LARGE_INTEGER DefaultQuotaLimit;
-  ULONG         FileSystemControlFlags;
-} FILE_FS_CONTROL_INFORMATION, *PFILE_FS_CONTROL_INFORMATION;
-
-typedef struct _FILE_FS_FULL_SIZE_INFORMATION {
-  LARGE_INTEGER TotalAllocationUnits;
-  LARGE_INTEGER CallerAvailableAllocationUnits;
-  LARGE_INTEGER ActualAvailableAllocationUnits;
-  ULONG         SectorsPerAllocationUnit;
-  ULONG         BytesPerSector;
-} FILE_FS_FULL_SIZE_INFORMATION, *PFILE_FS_FULL_SIZE_INFORMATION;
-
-typedef struct _FILE_FS_OBJECTID_INFORMATION {
-  UCHAR ObjectId[16];
-  UCHAR ExtendedInfo[48];
-} FILE_FS_OBJECTID_INFORMATION, *PFILE_FS_OBJECTID_INFORMATION;
-
-typedef struct _FILE_FS_DRIVER_PATH_INFORMATION {
-  BOOLEAN DriverInPath;
-  ULONG   DriverNameLength;
-  WCHAR   DriverName[1];
-} FILE_FS_DRIVER_PATH_INFORMATION, *PFILE_FS_DRIVER_PATH_INFORMATION;
-
-typedef struct _FILE_FS_VOLUME_FLAGS_INFORMATION {
-  ULONG Flags;
-} FILE_FS_VOLUME_FLAGS_INFORMATION, *PFILE_FS_VOLUME_FLAGS_INFORMATION;
-
-typedef struct _FILE_FS_SECTOR_SIZE_INFORMATION {
-  ULONG LogicalBytesPerSector;
-  ULONG PhysicalBytesPerSectorForAtomicity;
-  ULONG PhysicalBytesPerSectorForPerformance;
-  ULONG FileSystemEffectivePhysicalBytesPerSectorForAtomicity;
-  ULONG Flags;
-  ULONG ByteOffsetForSectorAlignment;
-  ULONG ByteOffsetForPartitionAlignment;
-} FILE_FS_SECTOR_SIZE_INFORMATION, *PFILE_FS_SECTOR_SIZE_INFORMATION;
-
-typedef struct _SYSTEM_PROCESSOR_PERFORMANCE_INFORMATION {
-    LARGE_INTEGER IdleTime;
-    LARGE_INTEGER KernelTime;
-    LARGE_INTEGER UserTime;
-    LARGE_INTEGER DpcTime;
-    LARGE_INTEGER InterruptTime;
-    ULONG InterruptCount;
-} SYSTEM_PROCESSOR_PERFORMANCE_INFORMATION, *PSYSTEM_PROCESSOR_PERFORMANCE_INFORMATION;
-
-#ifndef SystemProcessorPerformanceInformation
-# define SystemProcessorPerformanceInformation 8
-#endif
-
-#ifndef FILE_DEVICE_FILE_SYSTEM
-# define FILE_DEVICE_FILE_SYSTEM 0x00000009
-#endif
-
-#ifndef FILE_DEVICE_NETWORK
-# define FILE_DEVICE_NETWORK 0x00000012
-#endif
-
-#ifndef METHOD_BUFFERED
-# define METHOD_BUFFERED 0
-#endif
-
-#ifndef METHOD_IN_DIRECT
-# define METHOD_IN_DIRECT 1
-#endif
-
-#ifndef METHOD_OUT_DIRECT
-# define METHOD_OUT_DIRECT 2
-#endif
-
-#ifndef METHOD_NEITHER
-#define METHOD_NEITHER 3
-#endif
-
-#ifndef METHOD_DIRECT_TO_HARDWARE
-# define METHOD_DIRECT_TO_HARDWARE METHOD_IN_DIRECT
-#endif
-
-#ifndef METHOD_DIRECT_FROM_HARDWARE
-# define METHOD_DIRECT_FROM_HARDWARE METHOD_OUT_DIRECT
-#endif
-
-#ifndef FILE_ANY_ACCESS
-# define FILE_ANY_ACCESS 0
-#endif
-
-#ifndef FILE_SPECIAL_ACCESS
-# define FILE_SPECIAL_ACCESS (FILE_ANY_ACCESS)
-#endif
-
-#ifndef FILE_READ_ACCESS
-# define FILE_READ_ACCESS 0x0001
-#endif
-
-#ifndef FILE_WRITE_ACCESS
-# define FILE_WRITE_ACCESS 0x0002
-#endif
-
-#ifndef CTL_CODE
-# define CTL_CODE(device_type, function, method, access)                      \
-    (((device_type) << 16) | ((access) << 14) | ((function) << 2) | (method))
-#endif
-
-#ifndef FSCTL_SET_REPARSE_POINT
-# define FSCTL_SET_REPARSE_POINT CTL_CODE(FILE_DEVICE_FILE_SYSTEM,            \
-                                          41,                                 \
-                                          METHOD_BUFFERED,                    \
-                                          FILE_SPECIAL_ACCESS)
-#endif
-
-#ifndef FSCTL_GET_REPARSE_POINT
-# define FSCTL_GET_REPARSE_POINT CTL_CODE(FILE_DEVICE_FILE_SYSTEM,            \
-                                          42,                                 \
-                                          METHOD_BUFFERED,                    \
-                                          FILE_ANY_ACCESS)
-#endif
-
-#ifndef FSCTL_DELETE_REPARSE_POINT
-# define FSCTL_DELETE_REPARSE_POINT CTL_CODE(FILE_DEVICE_FILE_SYSTEM,         \
-                                             43,                              \
-                                             METHOD_BUFFERED,                 \
-                                             FILE_SPECIAL_ACCESS)
-#endif
-
-#ifndef IO_REPARSE_TAG_SYMLINK
-# define IO_REPARSE_TAG_SYMLINK (0xA000000CL)
-#endif
-
-typedef VOID (NTAPI *PIO_APC_ROUTINE)
-             (PVOID ApcContext,
-              PIO_STATUS_BLOCK IoStatusBlock,
-              ULONG Reserved);
-
-typedef NTSTATUS (NTAPI *sRtlGetVersion)
-                 (PRTL_OSVERSIONINFOW lpVersionInformation);
-
-typedef ULONG (NTAPI *sRtlNtStatusToDosError)
-              (NTSTATUS Status);
-
-typedef NTSTATUS (NTAPI *sNtDeviceIoControlFile)
-                 (HANDLE FileHandle,
-                  HANDLE Event,
-                  PIO_APC_ROUTINE ApcRoutine,
-                  PVOID ApcContext,
-                  PIO_STATUS_BLOCK IoStatusBlock,
-                  ULONG IoControlCode,
-                  PVOID InputBuffer,
-                  ULONG InputBufferLength,
-                  PVOID OutputBuffer,
-                  ULONG OutputBufferLength);
-
-typedef NTSTATUS (NTAPI *sNtQueryInformationFile)
-                 (HANDLE FileHandle,
-                  PIO_STATUS_BLOCK IoStatusBlock,
-                  PVOID FileInformation,
-                  ULONG Length,
-                  FILE_INFORMATION_CLASS FileInformationClass);
-
-typedef NTSTATUS (NTAPI *sNtSetInformationFile)
-                 (HANDLE FileHandle,
-                  PIO_STATUS_BLOCK IoStatusBlock,
-                  PVOID FileInformation,
-                  ULONG Length,
-                  FILE_INFORMATION_CLASS FileInformationClass);
-
-typedef NTSTATUS (NTAPI *sNtQueryVolumeInformationFile)
-                 (HANDLE FileHandle,
-                  PIO_STATUS_BLOCK IoStatusBlock,
-                  PVOID FsInformation,
-                  ULONG Length,
-                  FS_INFORMATION_CLASS FsInformationClass);
-
-typedef NTSTATUS (NTAPI *sNtQuerySystemInformation)
-                 (UINT SystemInformationClass,
-                  PVOID SystemInformation,
-                  ULONG SystemInformationLength,
-                  PULONG ReturnLength);
-
-typedef NTSTATUS (NTAPI *sNtQueryDirectoryFile)
-                 (HANDLE FileHandle,
-                  HANDLE Event,
-                  PIO_APC_ROUTINE ApcRoutine,
-                  PVOID ApcContext,
-                  PIO_STATUS_BLOCK IoStatusBlock,
-                  PVOID FileInformation,
-                  ULONG Length,
-                  FILE_INFORMATION_CLASS FileInformationClass,
-                  BOOLEAN ReturnSingleEntry,
-                  PUNICODE_STRING FileName,
-                  BOOLEAN RestartScan
-                );
-
-/*
- * Kernel32 headers
- */
-#ifndef FILE_SKIP_COMPLETION_PORT_ON_SUCCESS
-# define FILE_SKIP_COMPLETION_PORT_ON_SUCCESS 0x1
-#endif
-
-#ifndef FILE_SKIP_SET_EVENT_ON_HANDLE
-# define FILE_SKIP_SET_EVENT_ON_HANDLE 0x2
-#endif
-
-#ifndef SYMBOLIC_LINK_FLAG_DIRECTORY
-# define SYMBOLIC_LINK_FLAG_DIRECTORY 0x1
-#endif
-
-#if defined(__MINGW32__) && !defined(__MINGW64_VERSION_MAJOR)
-  typedef struct _OVERLAPPED_ENTRY {
-      ULONG_PTR lpCompletionKey;
-      LPOVERLAPPED lpOverlapped;
-      ULONG_PTR Internal;
-      DWORD dwNumberOfBytesTransferred;
-  } OVERLAPPED_ENTRY, *LPOVERLAPPED_ENTRY;
-#endif
-
-/* from wincon.h */
-#ifndef ENABLE_INSERT_MODE
-# define ENABLE_INSERT_MODE 0x20
-#endif
-
-#ifndef ENABLE_QUICK_EDIT_MODE
-# define ENABLE_QUICK_EDIT_MODE 0x40
-#endif
-
-#ifndef ENABLE_EXTENDED_FLAGS
-# define ENABLE_EXTENDED_FLAGS 0x80
-#endif
-
-/* from winerror.h */
-#ifndef ERROR_ELEVATION_REQUIRED
-# define ERROR_ELEVATION_REQUIRED 740
-#endif
-
-#ifndef ERROR_SYMLINK_NOT_SUPPORTED
-# define ERROR_SYMLINK_NOT_SUPPORTED 1464
-#endif
-
-#ifndef ERROR_MUI_FILE_NOT_FOUND
-# define ERROR_MUI_FILE_NOT_FOUND 15100
-#endif
-
-#ifndef ERROR_MUI_INVALID_FILE
-# define ERROR_MUI_INVALID_FILE 15101
-#endif
-
-#ifndef ERROR_MUI_INVALID_RC_CONFIG
-# define ERROR_MUI_INVALID_RC_CONFIG 15102
-#endif
-
-#ifndef ERROR_MUI_INVALID_LOCALE_NAME
-# define ERROR_MUI_INVALID_LOCALE_NAME 15103
-#endif
-
-#ifndef ERROR_MUI_INVALID_ULTIMATEFALLBACK_NAME
-# define ERROR_MUI_INVALID_ULTIMATEFALLBACK_NAME 15104
-#endif
-
-#ifndef ERROR_MUI_FILE_NOT_LOADED
-# define ERROR_MUI_FILE_NOT_LOADED 15105
-#endif
-
-typedef BOOL (WINAPI *sGetQueuedCompletionStatusEx)
-             (HANDLE CompletionPort,
-              LPOVERLAPPED_ENTRY lpCompletionPortEntries,
-              ULONG ulCount,
-              PULONG ulNumEntriesRemoved,
-              DWORD dwMilliseconds,
-              BOOL fAlertable);
-
-/* from powerbase.h */
-#ifndef DEVICE_NOTIFY_CALLBACK
-# define DEVICE_NOTIFY_CALLBACK 2
-#endif
-
-#ifndef PBT_APMRESUMEAUTOMATIC
-# define PBT_APMRESUMEAUTOMATIC 18
-#endif
-
-#ifndef PBT_APMRESUMESUSPEND
-# define PBT_APMRESUMESUSPEND 7
-#endif
-
-typedef ULONG CALLBACK _DEVICE_NOTIFY_CALLBACK_ROUTINE(
-  PVOID Context,
-  ULONG Type,
-  PVOID Setting
-);
-typedef _DEVICE_NOTIFY_CALLBACK_ROUTINE* _PDEVICE_NOTIFY_CALLBACK_ROUTINE;
-
-typedef struct _DEVICE_NOTIFY_SUBSCRIBE_PARAMETERS {
-  _PDEVICE_NOTIFY_CALLBACK_ROUTINE Callback;
-  PVOID Context;
-} _DEVICE_NOTIFY_SUBSCRIBE_PARAMETERS, *_PDEVICE_NOTIFY_SUBSCRIBE_PARAMETERS;
-
-typedef PVOID _HPOWERNOTIFY;
-typedef _HPOWERNOTIFY *_PHPOWERNOTIFY;
-
-typedef DWORD (WINAPI *sPowerRegisterSuspendResumeNotification)
-              (DWORD         Flags,
-               HANDLE        Recipient,
-               _PHPOWERNOTIFY RegistrationHandle);
-
-/* from Winuser.h */
-typedef VOID (CALLBACK* WINEVENTPROC)
-             (HWINEVENTHOOK hWinEventHook,
-              DWORD         event,
-              HWND          hwnd,
-              LONG          idObject,
-              LONG          idChild,
-              DWORD         idEventThread,
-              DWORD         dwmsEventTime);
-
-typedef HWINEVENTHOOK (WINAPI *sSetWinEventHook)
-                      (UINT         eventMin,
-                       UINT         eventMax,
-                       HMODULE      hmodWinEventProc,
-                       WINEVENTPROC lpfnWinEventProc,
-                       DWORD        idProcess,
-                       DWORD        idThread,
-                       UINT         dwflags);
-
-
-/* Ntdll function pointers */
-extern sRtlGetVersion pRtlGetVersion;
-extern sRtlNtStatusToDosError pRtlNtStatusToDosError;
-extern sNtDeviceIoControlFile pNtDeviceIoControlFile;
-extern sNtQueryInformationFile pNtQueryInformationFile;
-extern sNtSetInformationFile pNtSetInformationFile;
-extern sNtQueryVolumeInformationFile pNtQueryVolumeInformationFile;
-extern sNtQueryDirectoryFile pNtQueryDirectoryFile;
-extern sNtQuerySystemInformation pNtQuerySystemInformation;
-
-/* Kernel32 function pointers */
-extern sGetQueuedCompletionStatusEx pGetQueuedCompletionStatusEx;
-
-/* Powrprof.dll function pointer */
-extern sPowerRegisterSuspendResumeNotification pPowerRegisterSuspendResumeNotification;
-
-/* User32.dll function pointer */
-extern sSetWinEventHook pSetWinEventHook;
-
-#endif /* UV_WIN_WINAPI_H_ */
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/winsock.cpp b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/winsock.cpp
deleted file mode 100644
index 668e3b6..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/winsock.cpp
+++ /dev/null
@@ -1,596 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include <assert.h>
-#include <stdlib.h>
-
-#include "uv.h"
-#include "internal.h"
-
-
-#pragma comment(lib, "Ws2_32.lib")
-
-/* Whether there are any non-IFS LSPs stacked on TCP */
-int uv_tcp_non_ifs_lsp_ipv4;
-int uv_tcp_non_ifs_lsp_ipv6;
-
-/* Ip address used to bind to any port at any interface */
-struct sockaddr_in uv_addr_ip4_any_;
-struct sockaddr_in6 uv_addr_ip6_any_;
-
-
-/*
- * Retrieves the pointer to a winsock extension function.
- */
-static BOOL uv_get_extension_function(SOCKET socket, GUID guid,
-    void **target) {
-  int result;
-  DWORD bytes;
-
-  result = WSAIoctl(socket,
-                    SIO_GET_EXTENSION_FUNCTION_POINTER,
-                    &guid,
-                    sizeof(guid),
-                    (void*)target,
-                    sizeof(*target),
-                    &bytes,
-                    NULL,
-                    NULL);
-
-  if (result == SOCKET_ERROR) {
-    *target = NULL;
-    return FALSE;
-  } else {
-    return TRUE;
-  }
-}
-
-
-BOOL uv_get_acceptex_function(SOCKET socket, LPFN_ACCEPTEX* target) {
-  const GUID wsaid_acceptex = WSAID_ACCEPTEX;
-  return uv_get_extension_function(socket, wsaid_acceptex, (void**)target);
-}
-
-
-BOOL uv_get_connectex_function(SOCKET socket, LPFN_CONNECTEX* target) {
-  const GUID wsaid_connectex = WSAID_CONNECTEX;
-  return uv_get_extension_function(socket, wsaid_connectex, (void**)target);
-}
-
-
-static int error_means_no_support(DWORD error) {
-  return error == WSAEPROTONOSUPPORT || error == WSAESOCKTNOSUPPORT ||
-         error == WSAEPFNOSUPPORT || error == WSAEAFNOSUPPORT;
-}
-
-
-void uv_winsock_init(void) {
-  WSADATA wsa_data;
-  int errorno;
-  SOCKET dummy;
-  WSAPROTOCOL_INFOW protocol_info;
-  int opt_len;
-
-  /* Set implicit binding address used by connectEx */
-  if (uv_ip4_addr("0.0.0.0", 0, &uv_addr_ip4_any_)) {
-    abort();
-  }
-
-  if (uv_ip6_addr("::", 0, &uv_addr_ip6_any_)) {
-    abort();
-  }
-
-  /* Skip initialization in safe mode without network support */
-  if (1 == GetSystemMetrics(SM_CLEANBOOT)) return;
-
-  /* Initialize winsock */
-  errorno = WSAStartup(MAKEWORD(2, 2), &wsa_data);
-  if (errorno != 0) {
-    uv_fatal_error(errorno, "WSAStartup");
-  }
-
-  /* Detect non-IFS LSPs */
-  dummy = socket(AF_INET, SOCK_STREAM, IPPROTO_IP);
-
-  if (dummy != INVALID_SOCKET) {
-    opt_len = (int) sizeof protocol_info;
-    if (getsockopt(dummy,
-                   SOL_SOCKET,
-                   SO_PROTOCOL_INFOW,
-                   (char*) &protocol_info,
-                   &opt_len) == SOCKET_ERROR)
-      uv_fatal_error(WSAGetLastError(), "getsockopt");
-
-    if (!(protocol_info.dwServiceFlags1 & XP1_IFS_HANDLES))
-      uv_tcp_non_ifs_lsp_ipv4 = 1;
-
-    if (closesocket(dummy) == SOCKET_ERROR)
-      uv_fatal_error(WSAGetLastError(), "closesocket");
-
-  } else if (!error_means_no_support(WSAGetLastError())) {
-    /* Any error other than "socket type not supported" is fatal. */
-    uv_fatal_error(WSAGetLastError(), "socket");
-  }
-
-  /* Detect IPV6 support and non-IFS LSPs */
-  dummy = socket(AF_INET6, SOCK_STREAM, IPPROTO_IP);
-
-  if (dummy != INVALID_SOCKET) {
-    opt_len = (int) sizeof protocol_info;
-    if (getsockopt(dummy,
-                   SOL_SOCKET,
-                   SO_PROTOCOL_INFOW,
-                   (char*) &protocol_info,
-                   &opt_len) == SOCKET_ERROR)
-      uv_fatal_error(WSAGetLastError(), "getsockopt");
-
-    if (!(protocol_info.dwServiceFlags1 & XP1_IFS_HANDLES))
-      uv_tcp_non_ifs_lsp_ipv6 = 1;
-
-    if (closesocket(dummy) == SOCKET_ERROR)
-      uv_fatal_error(WSAGetLastError(), "closesocket");
-
-  } else if (!error_means_no_support(WSAGetLastError())) {
-    /* Any error other than "socket type not supported" is fatal. */
-    uv_fatal_error(WSAGetLastError(), "socket");
-  }
-}
-
-
-int uv_ntstatus_to_winsock_error(NTSTATUS status) {
-  switch (status) {
-    case STATUS_SUCCESS:
-      return ERROR_SUCCESS;
-
-    case STATUS_PENDING:
-      return ERROR_IO_PENDING;
-
-    case STATUS_INVALID_HANDLE:
-    case STATUS_OBJECT_TYPE_MISMATCH:
-      return WSAENOTSOCK;
-
-    case STATUS_INSUFFICIENT_RESOURCES:
-    case STATUS_PAGEFILE_QUOTA:
-    case STATUS_COMMITMENT_LIMIT:
-    case STATUS_WORKING_SET_QUOTA:
-    case STATUS_NO_MEMORY:
-    case STATUS_QUOTA_EXCEEDED:
-    case STATUS_TOO_MANY_PAGING_FILES:
-    case STATUS_REMOTE_RESOURCES:
-      return WSAENOBUFS;
-
-    case STATUS_TOO_MANY_ADDRESSES:
-    case STATUS_SHARING_VIOLATION:
-    case STATUS_ADDRESS_ALREADY_EXISTS:
-      return WSAEADDRINUSE;
-
-    case STATUS_LINK_TIMEOUT:
-    case STATUS_IO_TIMEOUT:
-    case STATUS_TIMEOUT:
-      return WSAETIMEDOUT;
-
-    case STATUS_GRACEFUL_DISCONNECT:
-      return WSAEDISCON;
-
-    case STATUS_REMOTE_DISCONNECT:
-    case STATUS_CONNECTION_RESET:
-    case STATUS_LINK_FAILED:
-    case STATUS_CONNECTION_DISCONNECTED:
-    case STATUS_PORT_UNREACHABLE:
-    case STATUS_HOPLIMIT_EXCEEDED:
-      return WSAECONNRESET;
-
-    case STATUS_LOCAL_DISCONNECT:
-    case STATUS_TRANSACTION_ABORTED:
-    case STATUS_CONNECTION_ABORTED:
-      return WSAECONNABORTED;
-
-    case STATUS_BAD_NETWORK_PATH:
-    case STATUS_NETWORK_UNREACHABLE:
-    case STATUS_PROTOCOL_UNREACHABLE:
-      return WSAENETUNREACH;
-
-    case STATUS_HOST_UNREACHABLE:
-      return WSAEHOSTUNREACH;
-
-    case STATUS_CANCELLED:
-    case STATUS_REQUEST_ABORTED:
-      return WSAEINTR;
-
-    case STATUS_BUFFER_OVERFLOW:
-    case STATUS_INVALID_BUFFER_SIZE:
-      return WSAEMSGSIZE;
-
-    case STATUS_BUFFER_TOO_SMALL:
-    case STATUS_ACCESS_VIOLATION:
-      return WSAEFAULT;
-
-    case STATUS_DEVICE_NOT_READY:
-    case STATUS_REQUEST_NOT_ACCEPTED:
-      return WSAEWOULDBLOCK;
-
-    case STATUS_INVALID_NETWORK_RESPONSE:
-    case STATUS_NETWORK_BUSY:
-    case STATUS_NO_SUCH_DEVICE:
-    case STATUS_NO_SUCH_FILE:
-    case STATUS_OBJECT_PATH_NOT_FOUND:
-    case STATUS_OBJECT_NAME_NOT_FOUND:
-    case STATUS_UNEXPECTED_NETWORK_ERROR:
-      return WSAENETDOWN;
-
-    case STATUS_INVALID_CONNECTION:
-      return WSAENOTCONN;
-
-    case STATUS_REMOTE_NOT_LISTENING:
-    case STATUS_CONNECTION_REFUSED:
-      return WSAECONNREFUSED;
-
-    case STATUS_PIPE_DISCONNECTED:
-      return WSAESHUTDOWN;
-
-    case STATUS_CONFLICTING_ADDRESSES:
-    case STATUS_INVALID_ADDRESS:
-    case STATUS_INVALID_ADDRESS_COMPONENT:
-      return WSAEADDRNOTAVAIL;
-
-    case STATUS_NOT_SUPPORTED:
-    case STATUS_NOT_IMPLEMENTED:
-      return WSAEOPNOTSUPP;
-
-    case STATUS_ACCESS_DENIED:
-      return WSAEACCES;
-
-    default:
-      if ((status & (FACILITY_NTWIN32 << 16)) == (FACILITY_NTWIN32 << 16) &&
-          (status & (ERROR_SEVERITY_ERROR | ERROR_SEVERITY_WARNING))) {
-        /* It's a windows error that has been previously mapped to an ntstatus
-         * code. */
-        return (DWORD) (status & 0xffff);
-      } else {
-        /* The default fallback for unmappable ntstatus codes. */
-        return WSAEINVAL;
-      }
-  }
-}
-
-
-/*
- * This function provides a workaround for a bug in the winsock implementation
- * of WSARecv. The problem is that when SetFileCompletionNotificationModes is
- * used to avoid IOCP notifications of completed reads, WSARecv does not
- * reliably indicate whether we can expect a completion package to be posted
- * when the receive buffer is smaller than the received datagram.
- *
- * However it is desirable to use SetFileCompletionNotificationModes because
- * it yields a massive performance increase.
- *
- * This function provides a workaround for that bug, but it only works for the
- * specific case that we need it for. E.g. it assumes that the "avoid iocp"
- * bit has been set, and supports only overlapped operation. It also requires
- * the user to use the default msafd driver, doesn't work when other LSPs are
- * stacked on top of it.
- */
-int WSAAPI uv_wsarecv_workaround(SOCKET socket, WSABUF* buffers,
-    DWORD buffer_count, DWORD* bytes, DWORD* flags, WSAOVERLAPPED *overlapped,
-    LPWSAOVERLAPPED_COMPLETION_ROUTINE completion_routine) {
-  NTSTATUS status;
-  void* apc_context;
-  IO_STATUS_BLOCK* iosb = (IO_STATUS_BLOCK*) &overlapped->Internal;
-  AFD_RECV_INFO info;
-  DWORD error;
-
-  if (overlapped == NULL || completion_routine != NULL) {
-    WSASetLastError(WSAEINVAL);
-    return SOCKET_ERROR;
-  }
-
-  info.BufferArray = buffers;
-  info.BufferCount = buffer_count;
-  info.AfdFlags = AFD_OVERLAPPED;
-  info.TdiFlags = TDI_RECEIVE_NORMAL;
-
-  if (*flags & MSG_PEEK) {
-    info.TdiFlags |= TDI_RECEIVE_PEEK;
-  }
-
-  if (*flags & MSG_PARTIAL) {
-    info.TdiFlags |= TDI_RECEIVE_PARTIAL;
-  }
-
-  if (!((intptr_t) overlapped->hEvent & 1)) {
-    apc_context = (void*) overlapped;
-  } else {
-    apc_context = NULL;
-  }
-
-  iosb->Status = STATUS_PENDING;
-  iosb->Pointer = 0;
-
-  status = pNtDeviceIoControlFile((HANDLE) socket,
-                                  overlapped->hEvent,
-                                  NULL,
-                                  apc_context,
-                                  iosb,
-                                  IOCTL_AFD_RECEIVE,
-                                  &info,
-                                  sizeof(info),
-                                  NULL,
-                                  0);
-
-  *flags = 0;
-  *bytes = (DWORD) iosb->Information;
-
-  switch (status) {
-    case STATUS_SUCCESS:
-      error = ERROR_SUCCESS;
-      break;
-
-    case STATUS_PENDING:
-      error = WSA_IO_PENDING;
-      break;
-
-    case STATUS_BUFFER_OVERFLOW:
-      error = WSAEMSGSIZE;
-      break;
-
-    case STATUS_RECEIVE_EXPEDITED:
-      error = ERROR_SUCCESS;
-      *flags = MSG_OOB;
-      break;
-
-    case STATUS_RECEIVE_PARTIAL_EXPEDITED:
-      error = ERROR_SUCCESS;
-      *flags = MSG_PARTIAL | MSG_OOB;
-      break;
-
-    case STATUS_RECEIVE_PARTIAL:
-      error = ERROR_SUCCESS;
-      *flags = MSG_PARTIAL;
-      break;
-
-    default:
-      error = uv_ntstatus_to_winsock_error(status);
-      break;
-  }
-
-  WSASetLastError(error);
-
-  if (error == ERROR_SUCCESS) {
-    return 0;
-  } else {
-    return SOCKET_ERROR;
-  }
-}
-
-
-/* See description of uv_wsarecv_workaround. */
-int WSAAPI uv_wsarecvfrom_workaround(SOCKET socket, WSABUF* buffers,
-    DWORD buffer_count, DWORD* bytes, DWORD* flags, struct sockaddr* addr,
-    int* addr_len, WSAOVERLAPPED *overlapped,
-    LPWSAOVERLAPPED_COMPLETION_ROUTINE completion_routine) {
-  NTSTATUS status;
-  void* apc_context;
-  IO_STATUS_BLOCK* iosb = (IO_STATUS_BLOCK*) &overlapped->Internal;
-  AFD_RECV_DATAGRAM_INFO info;
-  DWORD error;
-
-  if (overlapped == NULL || addr == NULL || addr_len == NULL ||
-      completion_routine != NULL) {
-    WSASetLastError(WSAEINVAL);
-    return SOCKET_ERROR;
-  }
-
-  info.BufferArray = buffers;
-  info.BufferCount = buffer_count;
-  info.AfdFlags = AFD_OVERLAPPED;
-  info.TdiFlags = TDI_RECEIVE_NORMAL;
-  info.Address = addr;
-  info.AddressLength = addr_len;
-
-  if (*flags & MSG_PEEK) {
-    info.TdiFlags |= TDI_RECEIVE_PEEK;
-  }
-
-  if (*flags & MSG_PARTIAL) {
-    info.TdiFlags |= TDI_RECEIVE_PARTIAL;
-  }
-
-  if (!((intptr_t) overlapped->hEvent & 1)) {
-    apc_context = (void*) overlapped;
-  } else {
-    apc_context = NULL;
-  }
-
-  iosb->Status = STATUS_PENDING;
-  iosb->Pointer = 0;
-
-  status = pNtDeviceIoControlFile((HANDLE) socket,
-                                  overlapped->hEvent,
-                                  NULL,
-                                  apc_context,
-                                  iosb,
-                                  IOCTL_AFD_RECEIVE_DATAGRAM,
-                                  &info,
-                                  sizeof(info),
-                                  NULL,
-                                  0);
-
-  *flags = 0;
-  *bytes = (DWORD) iosb->Information;
-
-  switch (status) {
-    case STATUS_SUCCESS:
-      error = ERROR_SUCCESS;
-      break;
-
-    case STATUS_PENDING:
-      error = WSA_IO_PENDING;
-      break;
-
-    case STATUS_BUFFER_OVERFLOW:
-      error = WSAEMSGSIZE;
-      break;
-
-    case STATUS_RECEIVE_EXPEDITED:
-      error = ERROR_SUCCESS;
-      *flags = MSG_OOB;
-      break;
-
-    case STATUS_RECEIVE_PARTIAL_EXPEDITED:
-      error = ERROR_SUCCESS;
-      *flags = MSG_PARTIAL | MSG_OOB;
-      break;
-
-    case STATUS_RECEIVE_PARTIAL:
-      error = ERROR_SUCCESS;
-      *flags = MSG_PARTIAL;
-      break;
-
-    default:
-      error = uv_ntstatus_to_winsock_error(status);
-      break;
-  }
-
-  WSASetLastError(error);
-
-  if (error == ERROR_SUCCESS) {
-    return 0;
-  } else {
-    return SOCKET_ERROR;
-  }
-}
-
-
-int WSAAPI uv_msafd_poll(SOCKET socket, AFD_POLL_INFO* info_in,
-    AFD_POLL_INFO* info_out, OVERLAPPED* overlapped) {
-  IO_STATUS_BLOCK iosb;
-  IO_STATUS_BLOCK* iosb_ptr;
-  HANDLE event = NULL;
-  void* apc_context;
-  NTSTATUS status;
-  DWORD error;
-
-  if (overlapped != NULL) {
-    /* Overlapped operation. */
-    iosb_ptr = (IO_STATUS_BLOCK*) &overlapped->Internal;
-    event = overlapped->hEvent;
-
-    /* Do not report iocp completion if hEvent is tagged. */
-    if ((uintptr_t) event & 1) {
-      event = (HANDLE)((uintptr_t) event & ~(uintptr_t) 1);
-      apc_context = NULL;
-    } else {
-      apc_context = overlapped;
-    }
-
-  } else {
-    /* Blocking operation. */
-    iosb_ptr = &iosb;
-    event = CreateEvent(NULL, FALSE, FALSE, NULL);
-    if (event == NULL) {
-      return SOCKET_ERROR;
-    }
-    apc_context = NULL;
-  }
-
-  iosb_ptr->Status = STATUS_PENDING;
-  status = pNtDeviceIoControlFile((HANDLE) socket,
-                                  event,
-                                  NULL,
-                                  apc_context,
-                                  iosb_ptr,
-                                  IOCTL_AFD_POLL,
-                                  info_in,
-                                  sizeof *info_in,
-                                  info_out,
-                                  sizeof *info_out);
-
-  if (overlapped == NULL) {
-    /* If this is a blocking operation, wait for the event to become signaled,
-     * and then grab the real status from the io status block. */
-    if (status == STATUS_PENDING) {
-      DWORD r = WaitForSingleObject(event, INFINITE);
-
-      if (r == WAIT_FAILED) {
-        DWORD saved_error = GetLastError();
-        CloseHandle(event);
-        WSASetLastError(saved_error);
-        return SOCKET_ERROR;
-      }
-
-      status = iosb.Status;
-    }
-
-    CloseHandle(event);
-  }
-
-  switch (status) {
-    case STATUS_SUCCESS:
-      error = ERROR_SUCCESS;
-      break;
-
-    case STATUS_PENDING:
-      error = WSA_IO_PENDING;
-      break;
-
-    default:
-      error = uv_ntstatus_to_winsock_error(status);
-      break;
-  }
-
-  WSASetLastError(error);
-
-  if (error == ERROR_SUCCESS) {
-    return 0;
-  } else {
-    return SOCKET_ERROR;
-  }
-}
-
-int uv__convert_to_localhost_if_unspecified(const struct sockaddr* addr,
-                                            struct sockaddr_storage* storage) {
-  struct sockaddr_in* dest4;
-  struct sockaddr_in6* dest6;
-
-  if (addr == NULL)
-    return UV_EINVAL;
-
-  switch (addr->sa_family) {
-  case AF_INET:
-    dest4 = (struct sockaddr_in*) storage;
-    memcpy(dest4, addr, sizeof(*dest4));
-    if (dest4->sin_addr.s_addr == 0)
-      dest4->sin_addr.s_addr = htonl(INADDR_LOOPBACK);
-    return 0;
-  case AF_INET6:
-    dest6 = (struct sockaddr_in6*) storage;
-    memcpy(dest6, addr, sizeof(*dest6));
-    if (memcmp(&dest6->sin6_addr,
-               &uv_addr_ip6_any_.sin6_addr,
-               sizeof(uv_addr_ip6_any_.sin6_addr)) == 0) {
-      struct in6_addr init_sin6_addr = IN6ADDR_LOOPBACK_INIT;
-      dest6->sin6_addr = init_sin6_addr;
-    }
-    return 0;
-  default:
-    return UV_EINVAL;
-  }
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/winsock.h b/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/winsock.h
deleted file mode 100644
index 7ecb755..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/libuv/src/win/winsock.h
+++ /dev/null
@@ -1,193 +0,0 @@
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#ifndef UV_WIN_WINSOCK_H_
-#define UV_WIN_WINSOCK_H_
-
-#include <winsock2.h>
-#include <iptypes.h>
-#include <mswsock.h>
-#include <ws2tcpip.h>
-#include <windows.h>
-
-#include "winapi.h"
-
-
-/*
- * MinGW is missing these too
- */
-#ifndef SO_UPDATE_CONNECT_CONTEXT
-# define SO_UPDATE_CONNECT_CONTEXT 0x7010
-#endif
-
-#ifndef TCP_KEEPALIVE
-# define TCP_KEEPALIVE 3
-#endif
-
-#ifndef IPV6_V6ONLY
-# define IPV6_V6ONLY 27
-#endif
-
-#ifndef IPV6_HOPLIMIT
-# define IPV6_HOPLIMIT 21
-#endif
-
-#ifndef SIO_BASE_HANDLE
-# define SIO_BASE_HANDLE 0x48000022
-#endif
-
-/*
- * TDI defines that are only in the DDK.
- * We only need receive flags so far.
- */
-#ifndef TDI_RECEIVE_NORMAL
-  #define TDI_RECEIVE_BROADCAST           0x00000004
-  #define TDI_RECEIVE_MULTICAST           0x00000008
-  #define TDI_RECEIVE_PARTIAL             0x00000010
-  #define TDI_RECEIVE_NORMAL              0x00000020
-  #define TDI_RECEIVE_EXPEDITED           0x00000040
-  #define TDI_RECEIVE_PEEK                0x00000080
-  #define TDI_RECEIVE_NO_RESPONSE_EXP     0x00000100
-  #define TDI_RECEIVE_COPY_LOOKAHEAD      0x00000200
-  #define TDI_RECEIVE_ENTIRE_MESSAGE      0x00000400
-  #define TDI_RECEIVE_AT_DISPATCH_LEVEL   0x00000800
-  #define TDI_RECEIVE_CONTROL_INFO        0x00001000
-  #define TDI_RECEIVE_FORCE_INDICATION    0x00002000
-  #define TDI_RECEIVE_NO_PUSH             0x00004000
-#endif
-
-/*
- * The "Auxiliary Function Driver" is the windows kernel-mode driver that does
- * TCP, UDP etc. Winsock is just a layer that dispatches requests to it.
- * Having these definitions allows us to bypass winsock and make an AFD kernel
- * call directly, avoiding a bug in winsock's recvfrom implementation.
- */
-
-#define AFD_NO_FAST_IO   0x00000001
-#define AFD_OVERLAPPED   0x00000002
-#define AFD_IMMEDIATE    0x00000004
-
-#define AFD_POLL_RECEIVE_BIT            0
-#define AFD_POLL_RECEIVE                (1 << AFD_POLL_RECEIVE_BIT)
-#define AFD_POLL_RECEIVE_EXPEDITED_BIT  1
-#define AFD_POLL_RECEIVE_EXPEDITED      (1 << AFD_POLL_RECEIVE_EXPEDITED_BIT)
-#define AFD_POLL_SEND_BIT               2
-#define AFD_POLL_SEND                   (1 << AFD_POLL_SEND_BIT)
-#define AFD_POLL_DISCONNECT_BIT         3
-#define AFD_POLL_DISCONNECT             (1 << AFD_POLL_DISCONNECT_BIT)
-#define AFD_POLL_ABORT_BIT              4
-#define AFD_POLL_ABORT                  (1 << AFD_POLL_ABORT_BIT)
-#define AFD_POLL_LOCAL_CLOSE_BIT        5
-#define AFD_POLL_LOCAL_CLOSE            (1 << AFD_POLL_LOCAL_CLOSE_BIT)
-#define AFD_POLL_CONNECT_BIT            6
-#define AFD_POLL_CONNECT                (1 << AFD_POLL_CONNECT_BIT)
-#define AFD_POLL_ACCEPT_BIT             7
-#define AFD_POLL_ACCEPT                 (1 << AFD_POLL_ACCEPT_BIT)
-#define AFD_POLL_CONNECT_FAIL_BIT       8
-#define AFD_POLL_CONNECT_FAIL           (1 << AFD_POLL_CONNECT_FAIL_BIT)
-#define AFD_POLL_QOS_BIT                9
-#define AFD_POLL_QOS                    (1 << AFD_POLL_QOS_BIT)
-#define AFD_POLL_GROUP_QOS_BIT          10
-#define AFD_POLL_GROUP_QOS              (1 << AFD_POLL_GROUP_QOS_BIT)
-
-#define AFD_NUM_POLL_EVENTS             11
-#define AFD_POLL_ALL                    ((1 << AFD_NUM_POLL_EVENTS) - 1)
-
-typedef struct _AFD_RECV_DATAGRAM_INFO {
-    LPWSABUF BufferArray;
-    ULONG BufferCount;
-    ULONG AfdFlags;
-    ULONG TdiFlags;
-    struct sockaddr* Address;
-    int* AddressLength;
-} AFD_RECV_DATAGRAM_INFO, *PAFD_RECV_DATAGRAM_INFO;
-
-typedef struct _AFD_RECV_INFO {
-    LPWSABUF BufferArray;
-    ULONG BufferCount;
-    ULONG AfdFlags;
-    ULONG TdiFlags;
-} AFD_RECV_INFO, *PAFD_RECV_INFO;
-
-
-#define _AFD_CONTROL_CODE(operation, method) \
-    ((FSCTL_AFD_BASE) << 12 | (operation << 2) | method)
-
-#define FSCTL_AFD_BASE FILE_DEVICE_NETWORK
-
-#define AFD_RECEIVE            5
-#define AFD_RECEIVE_DATAGRAM   6
-#define AFD_POLL               9
-
-#define IOCTL_AFD_RECEIVE \
-    _AFD_CONTROL_CODE(AFD_RECEIVE, METHOD_NEITHER)
-
-#define IOCTL_AFD_RECEIVE_DATAGRAM \
-    _AFD_CONTROL_CODE(AFD_RECEIVE_DATAGRAM, METHOD_NEITHER)
-
-#define IOCTL_AFD_POLL \
-    _AFD_CONTROL_CODE(AFD_POLL, METHOD_BUFFERED)
-
-#if defined(__MINGW32__) && !defined(__MINGW64_VERSION_MAJOR)
-typedef struct _IP_ADAPTER_UNICAST_ADDRESS_XP {
-  /* FIXME: __C89_NAMELESS was removed */
-  /* __C89_NAMELESS */ union {
-    ULONGLONG Alignment;
-    /* __C89_NAMELESS */ struct {
-      ULONG Length;
-      DWORD Flags;
-    };
-  };
-  struct _IP_ADAPTER_UNICAST_ADDRESS_XP *Next;
-  SOCKET_ADDRESS Address;
-  IP_PREFIX_ORIGIN PrefixOrigin;
-  IP_SUFFIX_ORIGIN SuffixOrigin;
-  IP_DAD_STATE DadState;
-  ULONG ValidLifetime;
-  ULONG PreferredLifetime;
-  ULONG LeaseLifetime;
-} IP_ADAPTER_UNICAST_ADDRESS_XP,*PIP_ADAPTER_UNICAST_ADDRESS_XP;
-
-typedef struct _IP_ADAPTER_UNICAST_ADDRESS_LH {
-  union {
-    ULONGLONG Alignment;
-    struct {
-      ULONG Length;
-      DWORD Flags;
-    };
-  };
-  struct _IP_ADAPTER_UNICAST_ADDRESS_LH *Next;
-  SOCKET_ADDRESS Address;
-  IP_PREFIX_ORIGIN PrefixOrigin;
-  IP_SUFFIX_ORIGIN SuffixOrigin;
-  IP_DAD_STATE DadState;
-  ULONG ValidLifetime;
-  ULONG PreferredLifetime;
-  ULONG LeaseLifetime;
-  UINT8 OnLinkPrefixLength;
-} IP_ADAPTER_UNICAST_ADDRESS_LH,*PIP_ADAPTER_UNICAST_ADDRESS_LH;
-
-#endif
-
-int uv__convert_to_localhost_if_unspecified(const struct sockaddr* addr,
-                                            struct sockaddr_storage* storage);
-
-#endif /* UV_WIN_WINSOCK_H_ */
diff --git a/third_party/allwpilib/wpiutil/src/main/native/linux/AvahiClient.cpp b/third_party/allwpilib/wpiutil/src/main/native/linux/AvahiClient.cpp
deleted file mode 100644
index 6a17ea0..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/linux/AvahiClient.cpp
+++ /dev/null
@@ -1,118 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "AvahiClient.h"
-
-#include <wpi/mutex.h>
-
-#include <thread>
-
-#include "dlfcn.h"
-
-using namespace wpi;
-
-#define AvahiFunctionLoad(snake_name)                                          \
-  do {                                                                         \
-    snake_name =                                                               \
-        reinterpret_cast<snake_name##_func>(dlsym(lib, "avahi_" #snake_name)); \
-    if (!snake_name) {                                                         \
-      return;                                                                  \
-    }                                                                          \
-  } while (false)
-
-AvahiFunctionTable::AvahiFunctionTable() {
-  void* lib = dlopen("libavahi-common.so.3", RTLD_LAZY);
-
-  valid = false;
-
-  if (lib == nullptr) {
-    return;
-  }
-
-  AvahiFunctionLoad(threaded_poll_new);
-  AvahiFunctionLoad(threaded_poll_free);
-  AvahiFunctionLoad(threaded_poll_get);
-  AvahiFunctionLoad(threaded_poll_start);
-  AvahiFunctionLoad(threaded_poll_stop);
-  AvahiFunctionLoad(threaded_poll_lock);
-  AvahiFunctionLoad(threaded_poll_unlock);
-  AvahiFunctionLoad(string_list_new_from_array);
-  AvahiFunctionLoad(string_list_free);
-  AvahiFunctionLoad(unescape_label);
-  AvahiFunctionLoad(alternative_service_name);
-  AvahiFunctionLoad(free);
-
-  lib = dlopen("libavahi-client.so.3", RTLD_LAZY);
-
-  if (lib == nullptr) {
-    return;
-  }
-
-  AvahiFunctionLoad(client_new);
-  AvahiFunctionLoad(client_free);
-  AvahiFunctionLoad(service_browser_new);
-  AvahiFunctionLoad(service_browser_get_client);
-  AvahiFunctionLoad(service_browser_free);
-  AvahiFunctionLoad(service_resolver_new);
-  AvahiFunctionLoad(service_resolver_free);
-  AvahiFunctionLoad(entry_group_new);
-  AvahiFunctionLoad(entry_group_free);
-  AvahiFunctionLoad(entry_group_add_service_strlst);
-  AvahiFunctionLoad(entry_group_reset);
-  AvahiFunctionLoad(entry_group_is_empty);
-  AvahiFunctionLoad(entry_group_commit);
-  AvahiFunctionLoad(entry_group_get_client);
-
-  valid = true;
-}
-
-AvahiFunctionTable& AvahiFunctionTable::Get() {
-  static AvahiFunctionTable table;
-  return table;
-}
-
-static wpi::mutex ThreadLoopLock;
-static std::weak_ptr<AvahiThread> ThreadLoop;
-
-std::shared_ptr<AvahiThread> AvahiThread::Get() {
-  std::scoped_lock lock{ThreadLoopLock};
-  auto locked = ThreadLoop.lock();
-  if (!locked) {
-    locked = std::make_unique<AvahiThread>(private_init{});
-    ThreadLoop = locked;
-  }
-  return locked;
-}
-
-AvahiThread::AvahiThread(const private_init&) {
-  if (!table.IsValid()) {
-    return;
-  }
-
-  threadedPoll = table.threaded_poll_new();
-  table.threaded_poll_start(threadedPoll);
-}
-
-AvahiThread::~AvahiThread() noexcept {
-  if (!table.IsValid()) {
-    return;
-  }
-
-  if (threadedPoll) {
-    table.threaded_poll_stop(threadedPoll);
-    table.threaded_poll_free(threadedPoll);
-  }
-}
-
-void AvahiThread::lock() {
-  table.threaded_poll_lock(threadedPoll);
-}
-
-void AvahiThread::unlock() {
-  table.threaded_poll_unlock(threadedPoll);
-}
-
-const AvahiPoll* AvahiThread::GetPoll() const {
-  return table.threaded_poll_get(threadedPoll);
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/linux/AvahiClient.h b/third_party/allwpilib/wpiutil/src/main/native/linux/AvahiClient.h
deleted file mode 100644
index ca679bb..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/linux/AvahiClient.h
+++ /dev/null
@@ -1,316 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <stdint.h>
-
-#include <memory>
-
-/***
-  This file is part of avahi.
-  avahi is free software; you can redistribute it and/or modify it
-  under the terms of the GNU Lesser General Public License as
-  published by the Free Software Foundation; either version 2.1 of the
-  License, or (at your option) any later version.
-  avahi is distributed in the hope that it will be useful, but WITHOUT
-  ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
-  or FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General
-  Public License for more details.
-  You should have received a copy of the GNU Lesser General Public
-  License along with avahi; if not, write to the Free Software
-  Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307
-  USA.
-***/
-
-typedef struct AvahiPoll AvahiPoll;
-
-typedef enum {
-  AVAHI_SERVER_INVALID,
-  AVAHI_SERVER_REGISTERING,
-  AVAHI_SERVER_RUNNING,
-  AVAHI_SERVER_COLLISION,
-  AVAHI_SERVER_FAILURE
-} AvahiServerState;
-
-typedef struct AvahiClient AvahiClient;
-
-typedef enum {
-  AVAHI_CLIENT_S_REGISTERING = AVAHI_SERVER_REGISTERING,
-  AVAHI_CLIENT_S_RUNNING = AVAHI_SERVER_RUNNING,
-  AVAHI_CLIENT_S_COLLISION = AVAHI_SERVER_COLLISION,
-  AVAHI_CLIENT_FAILURE = 100,
-  AVAHI_CLIENT_CONNECTING = 101
-} AvahiClientState;
-
-typedef enum {
-  AVAHI_CLIENT_IGNORE_USER_CONFIG = 1,
-  AVAHI_CLIENT_NO_FAIL = 2
-} AvahiClientFlags;
-
-typedef void (*AvahiClientCallback)(AvahiClient* s, AvahiClientState state,
-                                    void* userdata);
-
-typedef struct AvahiServiceBrowser AvahiServiceBrowser;
-
-typedef int AvahiProtocol;
-
-typedef int AvahiIfIndex;
-
-typedef enum {
-  AVAHI_BROWSER_NEW,
-  AVAHI_BROWSER_REMOVE,
-  AVAHI_BROWSER_CACHE_EXHAUSTED,
-  AVAHI_BROWSER_ALL_FOR_NOW,
-  AVAHI_BROWSER_FAILURE
-} AvahiBrowserEvent;
-
-typedef enum {
-  AVAHI_LOOKUP_RESULT_CACHED = 1,
-  AVAHI_LOOKUP_RESULT_WIDE_AREA = 2,
-  AVAHI_LOOKUP_RESULT_MULTICAST = 4,
-  AVAHI_LOOKUP_RESULT_LOCAL = 8,
-  AVAHI_LOOKUP_RESULT_OUR_OWN = 16,
-  AVAHI_LOOKUP_RESULT_STATIC = 32
-} AvahiLookupResultFlags;
-
-typedef void (*AvahiServiceBrowserCallback)(
-    AvahiServiceBrowser* b, AvahiIfIndex interface, AvahiProtocol protocol,
-    AvahiBrowserEvent event, const char* name, const char* type,
-    const char* domain, AvahiLookupResultFlags flags, void* userdata);
-
-typedef enum {
-  AVAHI_LOOKUP_USE_WIDE_AREA = 1,
-  AVAHI_LOOKUP_USE_MULTICAST = 2,
-
-  AVAHI_LOOKUP_NO_TXT = 4,
-  AVAHI_LOOKUP_NO_ADDRESS = 8
-} AvahiLookupFlags;
-
-typedef struct AvahiServiceResolver AvahiServiceResolver;
-
-typedef enum {
-  AVAHI_RESOLVER_FOUND,
-  AVAHI_RESOLVER_FAILURE
-} AvahiResolverEvent;
-
-typedef struct AvahiIPv4Address {
-  uint32_t address;
-} AvahiIPv4Address;
-
-typedef struct AvahiIPv6Address {
-  uint8_t address[16];
-} AvahiIPv6Address;
-
-typedef struct AvahiAddress {
-  AvahiProtocol proto;
-
-  union {
-    AvahiIPv6Address ipv6;
-    AvahiIPv4Address ipv4;
-    uint8_t data[1];
-  } data;
-} AvahiAddress;
-
-typedef struct AvahiStringList {
-  struct AvahiStringList* next;
-  size_t size;
-  uint8_t text[1];
-} AvahiStringList;
-
-typedef void (*AvahiServiceResolverCallback)(
-    AvahiServiceResolver* r, AvahiIfIndex interface, AvahiProtocol protocol,
-    AvahiResolverEvent event, const char* name, const char* type,
-    const char* domain, const char* host_name, const AvahiAddress* a,
-    uint16_t port, AvahiStringList* txt, AvahiLookupResultFlags flags,
-    void* userdata);
-
-typedef struct AvahiThreadedPoll AvahiThreadedPoll;
-
-typedef struct AvahiEntryGroup AvahiEntryGroup;
-
-typedef enum {
-  AVAHI_ENTRY_GROUP_UNCOMMITED,
-  AVAHI_ENTRY_GROUP_REGISTERING,
-  AVAHI_ENTRY_GROUP_ESTABLISHED,
-  AVAHI_ENTRY_GROUP_COLLISION,
-  AVAHI_ENTRY_GROUP_FAILURE
-} AvahiEntryGroupState;
-
-typedef void (*AvahiEntryGroupCallback)(AvahiEntryGroup* g,
-                                        AvahiEntryGroupState state,
-                                        void* userdata);
-
-typedef enum {
-  AVAHI_PUBLISH_UNIQUE = 1,
-  AVAHI_PUBLISH_NO_PROBE = 2,
-  AVAHI_PUBLISH_NO_ANNOUNCE = 4,
-  AVAHI_PUBLISH_ALLOW_MULTIPLE = 8,
-
-  AVAHI_PUBLISH_NO_REVERSE = 16,
-  AVAHI_PUBLISH_NO_COOKIE = 32,
-  AVAHI_PUBLISH_UPDATE = 64,
-  AVAHI_PUBLISH_USE_WIDE_AREA = 128,
-  AVAHI_PUBLISH_USE_MULTICAST = 256
-} AvahiPublishFlags;
-
-enum { AVAHI_IF_UNSPEC = -1 };
-
-enum { AVAHI_PROTO_INET = 0, AVAHI_PROTO_INET6 = 1, AVAHI_PROTO_UNSPEC = -1 };
-
-enum {
-  AVAHI_OK = 0,
-  AVAHI_ERR_FAILURE = -1,
-  AVAHI_ERR_BAD_STATE = -2,
-  AVAHI_ERR_INVALID_HOST_NAME = -3,
-  AVAHI_ERR_INVALID_DOMAIN_NAME = -4,
-  AVAHI_ERR_NO_NETWORK = -5,
-  AVAHI_ERR_INVALID_TTL = -6,
-  AVAHI_ERR_IS_PATTERN = -7,
-  AVAHI_ERR_COLLISION = -8,
-  AVAHI_ERR_INVALID_RECORD = -9,
-
-  AVAHI_ERR_INVALID_SERVICE_NAME = -10,
-  AVAHI_ERR_INVALID_SERVICE_TYPE = -11,
-  AVAHI_ERR_INVALID_PORT = -12,
-  AVAHI_ERR_INVALID_KEY = -13,
-  AVAHI_ERR_INVALID_ADDRESS = -14,
-  AVAHI_ERR_TIMEOUT = -15,
-  AVAHI_ERR_TOO_MANY_CLIENTS = -16,
-  AVAHI_ERR_TOO_MANY_OBJECTS = -17,
-  AVAHI_ERR_TOO_MANY_ENTRIES = -18,
-  AVAHI_ERR_OS = -19,
-
-  AVAHI_ERR_ACCESS_DENIED = -20,
-  AVAHI_ERR_INVALID_OPERATION = -21,
-  AVAHI_ERR_DBUS_ERROR = -22,
-  AVAHI_ERR_DISCONNECTED = -23,
-  AVAHI_ERR_NO_MEMORY = -24,
-  AVAHI_ERR_INVALID_OBJECT = -25,
-  AVAHI_ERR_NO_DAEMON = -26,
-  AVAHI_ERR_INVALID_INTERFACE = -27,
-  AVAHI_ERR_INVALID_PROTOCOL = -28,
-  AVAHI_ERR_INVALID_FLAGS = -29,
-
-  AVAHI_ERR_NOT_FOUND = -30,
-  AVAHI_ERR_INVALID_CONFIG = -31,
-  AVAHI_ERR_VERSION_MISMATCH = -32,
-  AVAHI_ERR_INVALID_SERVICE_SUBTYPE = -33,
-  AVAHI_ERR_INVALID_PACKET = -34,
-  AVAHI_ERR_INVALID_DNS_ERROR = -35,
-  AVAHI_ERR_DNS_FORMERR = -36,
-  AVAHI_ERR_DNS_SERVFAIL = -37,
-  AVAHI_ERR_DNS_NXDOMAIN = -38,
-  AVAHI_ERR_DNS_NOTIMP = -39,
-
-  AVAHI_ERR_DNS_REFUSED = -40,
-  AVAHI_ERR_DNS_YXDOMAIN = -41,
-  AVAHI_ERR_DNS_YXRRSET = -42,
-  AVAHI_ERR_DNS_NXRRSET = -43,
-  AVAHI_ERR_DNS_NOTAUTH = -44,
-  AVAHI_ERR_DNS_NOTZONE = -45,
-  AVAHI_ERR_INVALID_RDATA = -46,
-  AVAHI_ERR_INVALID_DNS_CLASS = -47,
-  AVAHI_ERR_INVALID_DNS_TYPE = -48,
-  AVAHI_ERR_NOT_SUPPORTED = -49,
-
-  AVAHI_ERR_NOT_PERMITTED = -50,
-  AVAHI_ERR_INVALID_ARGUMENT = -51,
-  AVAHI_ERR_IS_EMPTY = -52,
-  AVAHI_ERR_NO_CHANGE = -53,
-
-  AVAHI_ERR_MAX = -54
-};
-
-namespace wpi {
-class AvahiFunctionTable {
- public:
-#define AvahiFunction(CapName, RetType, Parameters) \
-  using CapName##_func = RetType(*) Parameters;     \
-  CapName##_func CapName = nullptr
-
-  AvahiFunction(threaded_poll_new, AvahiThreadedPoll*, (void));
-  AvahiFunction(threaded_poll_free, void, (AvahiThreadedPoll*));
-  AvahiFunction(threaded_poll_get, const AvahiPoll*, (AvahiThreadedPoll*));
-  AvahiFunction(threaded_poll_start, int, (AvahiThreadedPoll*));
-  AvahiFunction(threaded_poll_stop, int, (AvahiThreadedPoll*));
-  AvahiFunction(threaded_poll_lock, int, (AvahiThreadedPoll*));
-  AvahiFunction(threaded_poll_unlock, int, (AvahiThreadedPoll*));
-
-  AvahiFunction(client_new, AvahiClient*,
-                (const AvahiPoll* poll_api, AvahiClientFlags flags,
-                 AvahiClientCallback callback, void* userdata, int* error));
-  AvahiFunction(client_free, void, (AvahiClient*));
-
-  AvahiFunction(service_browser_new, AvahiServiceBrowser*,
-                (AvahiClient * client, AvahiIfIndex interface,
-                 AvahiProtocol protocol, const char* type, const char* domain,
-                 AvahiLookupFlags flags, AvahiServiceBrowserCallback callback,
-                 void* userdata));
-
-  AvahiFunction(service_browser_free, int, (AvahiServiceBrowser*));
-
-  AvahiFunction(service_resolver_new, AvahiServiceResolver*,
-                (AvahiClient * client, AvahiIfIndex interface,
-                 AvahiProtocol protocol, const char* name, const char* type,
-                 const char* domain, AvahiProtocol aprotocol,
-                 AvahiLookupFlags flags, AvahiServiceResolverCallback callback,
-                 void* userdata));
-  AvahiFunction(service_resolver_free, int, (AvahiServiceResolver*));
-
-  AvahiFunction(entry_group_new, AvahiEntryGroup*,
-                (AvahiClient*, AvahiEntryGroupCallback, void*));
-  AvahiFunction(entry_group_free, int, (AvahiEntryGroup*));
-
-  AvahiFunction(entry_group_add_service_strlst, int,
-                (AvahiEntryGroup * group, AvahiIfIndex interface,
-                 AvahiProtocol protocol, AvahiPublishFlags flags,
-                 const char* name, const char* type, const char* domain,
-                 const char* host, uint16_t port, AvahiStringList*));
-
-  AvahiFunction(entry_group_reset, int, (AvahiEntryGroup*));
-  AvahiFunction(entry_group_is_empty, int, (AvahiEntryGroup*));
-  AvahiFunction(entry_group_commit, int, (AvahiEntryGroup*));
-  AvahiFunction(entry_group_get_client, AvahiClient*, (AvahiEntryGroup*));
-
-  AvahiFunction(string_list_new_from_array, AvahiStringList*,
-                (const char** array, int len));
-  AvahiFunction(string_list_free, void, (AvahiStringList*));
-
-  AvahiFunction(service_browser_get_client, AvahiClient*,
-                (AvahiServiceBrowser*));
-
-  AvahiFunction(unescape_label, char*, (const char**, char*, size_t));
-  AvahiFunction(alternative_service_name, char*, (const char*));
-  AvahiFunction(free, void, (void*));
-
-  bool IsValid() const { return valid; }
-
-  static AvahiFunctionTable& Get();
-
- private:
-  AvahiFunctionTable();
-  bool valid;
-};
-
-class AvahiThread {
- private:
-  struct private_init {};
-
- public:
-  explicit AvahiThread(const private_init&);
-  ~AvahiThread() noexcept;
-
-  void lock();
-  const AvahiPoll* GetPoll() const;
-  void unlock();
-
-  static std::shared_ptr<AvahiThread> Get();
-
- private:
-  AvahiThreadedPoll* threadedPoll;
-  AvahiFunctionTable& table = AvahiFunctionTable::Get();
-};
-
-}  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/main/native/linux/MulticastServiceAnnouncer.cpp b/third_party/allwpilib/wpiutil/src/main/native/linux/MulticastServiceAnnouncer.cpp
deleted file mode 100644
index 1a7af39..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/linux/MulticastServiceAnnouncer.cpp
+++ /dev/null
@@ -1,169 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/MulticastServiceAnnouncer.h"
-
-#include <vector>
-
-#include "AvahiClient.h"
-#include "fmt/format.h"
-#include "wpi/mutex.h"
-
-using namespace wpi;
-
-struct MulticastServiceAnnouncer::Impl {
-  AvahiFunctionTable& table = AvahiFunctionTable::Get();
-  std::shared_ptr<AvahiThread> thread = AvahiThread::Get();
-  AvahiClient* client;
-  AvahiEntryGroup* group = nullptr;
-  std::string serviceName;
-  std::string serviceType;
-  int port;
-  AvahiStringList* stringList = nullptr;
-
-  ~Impl() noexcept {
-    if (stringList != nullptr && table.IsValid()) {
-      table.string_list_free(stringList);
-    }
-  }
-
-  template <typename T>
-  Impl(std::string_view serviceName, std::string_view serviceType, int port,
-       wpi::span<const std::pair<T, T>> txt);
-};
-
-template <typename T>
-MulticastServiceAnnouncer::Impl::Impl(std::string_view serviceName,
-                                      std::string_view serviceType, int port,
-                                      wpi::span<const std::pair<T, T>> txt) {
-  if (!this->table.IsValid()) {
-    return;
-  }
-
-  this->serviceName = serviceName;
-  this->serviceType = serviceType;
-  this->port = port;
-
-  std::vector<std::string> txts;
-  for (auto&& i : txt) {
-    txts.push_back(fmt::format("{}={}", i.first, i.second));
-  }
-
-  std::vector<const char*> txtArr;
-  for (auto&& i : txts) {
-    txtArr.push_back(i.c_str());
-  }
-
-  this->stringList =
-      this->table.string_list_new_from_array(txtArr.data(), txtArr.size());
-}
-
-static void RegisterService(AvahiClient* client,
-                            MulticastServiceAnnouncer::Impl* impl);
-
-static void EntryGroupCallback(AvahiEntryGroup* group,
-                               AvahiEntryGroupState state, void* userdata) {
-  if (state == AVAHI_ENTRY_GROUP_COLLISION) {
-    // Remote collision
-    MulticastServiceAnnouncer::Impl* impl =
-        reinterpret_cast<MulticastServiceAnnouncer::Impl*>(userdata);
-    char* newName =
-        impl->table.alternative_service_name(impl->serviceName.c_str());
-    impl->serviceName = newName;
-    impl->table.free(newName);
-    RegisterService(impl->table.entry_group_get_client(group), impl);
-  }
-}
-
-static void RegisterService(AvahiClient* client,
-                            MulticastServiceAnnouncer::Impl* impl) {
-  if (impl->group == nullptr) {
-    impl->group = impl->table.entry_group_new(client, EntryGroupCallback, impl);
-  }
-
-  while (true) {
-    if (impl->table.entry_group_is_empty(impl->group)) {
-      auto ret = impl->table.entry_group_add_service_strlst(
-          impl->group, AVAHI_IF_UNSPEC, AVAHI_PROTO_UNSPEC,
-          AVAHI_PUBLISH_USE_MULTICAST, impl->serviceName.c_str(),
-          impl->serviceType.c_str(), "local", nullptr, impl->port,
-          impl->stringList);
-      if (ret == AVAHI_ERR_COLLISION) {
-        // Local collision
-        char* newName =
-            impl->table.alternative_service_name(impl->serviceName.c_str());
-        impl->serviceName = newName;
-        impl->table.free(newName);
-        continue;
-      } else if (ret != AVAHI_OK) {
-        break;
-      }
-      impl->table.entry_group_commit(impl->group);
-      break;
-    }
-  }
-}
-
-static void ClientCallback(AvahiClient* client, AvahiClientState state,
-                           void* userdata) {
-  MulticastServiceAnnouncer::Impl* impl =
-      reinterpret_cast<MulticastServiceAnnouncer::Impl*>(userdata);
-
-  if (state == AVAHI_CLIENT_S_RUNNING) {
-    RegisterService(client, impl);
-  } else if (state == AVAHI_CLIENT_S_COLLISION ||
-             state == AVAHI_CLIENT_S_REGISTERING) {
-    if (impl->group) {
-      impl->table.entry_group_reset(impl->group);
-    }
-  }
-}
-
-MulticastServiceAnnouncer::MulticastServiceAnnouncer(
-    std::string_view serviceName, std::string_view serviceType, int port,
-    wpi::span<const std::pair<std::string, std::string>> txt) {
-  pImpl = std::make_unique<Impl>(serviceName, serviceType, port, txt);
-}
-
-MulticastServiceAnnouncer::MulticastServiceAnnouncer(
-    std::string_view serviceName, std::string_view serviceType, int port,
-    wpi::span<const std::pair<std::string_view, std::string_view>> txt) {
-  pImpl = std::make_unique<Impl>(serviceName, serviceType, port, txt);
-}
-
-MulticastServiceAnnouncer::~MulticastServiceAnnouncer() noexcept {
-  Stop();
-}
-
-bool MulticastServiceAnnouncer::HasImplementation() const {
-  return pImpl->table.IsValid();
-}
-
-void MulticastServiceAnnouncer::Start() {
-  if (!pImpl->table.IsValid()) {
-    return;
-  }
-  std::scoped_lock lock{*pImpl->thread};
-  if (pImpl->client) {
-    return;
-  }
-  pImpl->client =
-      pImpl->table.client_new(pImpl->thread->GetPoll(), AVAHI_CLIENT_NO_FAIL,
-                              ClientCallback, pImpl.get(), nullptr);
-}
-
-void MulticastServiceAnnouncer::Stop() {
-  if (!pImpl->table.IsValid()) {
-    return;
-  }
-  std::scoped_lock lock{*pImpl->thread};
-  if (pImpl->client) {
-    if (pImpl->group) {
-      pImpl->table.entry_group_free(pImpl->group);
-      pImpl->group = nullptr;
-    }
-    pImpl->table.client_free(pImpl->client);
-    pImpl->client = nullptr;
-  }
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/linux/MulticastServiceResolver.cpp b/third_party/allwpilib/wpiutil/src/main/native/linux/MulticastServiceResolver.cpp
deleted file mode 100644
index 6585443..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/linux/MulticastServiceResolver.cpp
+++ /dev/null
@@ -1,149 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/MulticastServiceResolver.h"
-
-#include "AvahiClient.h"
-#include "wpi/SmallString.h"
-#include "wpi/StringExtras.h"
-#include "wpi/mutex.h"
-
-using namespace wpi;
-
-struct MulticastServiceResolver::Impl {
-  AvahiFunctionTable& table = AvahiFunctionTable::Get();
-  std::shared_ptr<AvahiThread> thread = AvahiThread::Get();
-  AvahiClient* client;
-  AvahiServiceBrowser* browser;
-  std::string serviceType;
-  MulticastServiceResolver* resolver;
-
-  void onFound(ServiceData&& data) {
-    resolver->PushData(std::forward<ServiceData>(data));
-  }
-};
-
-MulticastServiceResolver::MulticastServiceResolver(
-    std::string_view serviceType) {
-  pImpl = std::make_unique<Impl>();
-  pImpl->serviceType = serviceType;
-  pImpl->resolver = this;
-}
-
-MulticastServiceResolver::~MulticastServiceResolver() noexcept {
-  Stop();
-}
-
-bool MulticastServiceResolver::HasImplementation() const {
-  return pImpl->table.IsValid();
-}
-
-static void ResolveCallback(AvahiServiceResolver* r, AvahiIfIndex interface,
-                            AvahiProtocol protocol, AvahiResolverEvent event,
-                            const char* name, const char* type,
-                            const char* domain, const char* host_name,
-                            const AvahiAddress* address, uint16_t port,
-                            AvahiStringList* txt, AvahiLookupResultFlags flags,
-                            void* userdata) {
-  MulticastServiceResolver::Impl* impl =
-      reinterpret_cast<MulticastServiceResolver::Impl*>(userdata);
-
-  if (event == AVAHI_RESOLVER_FOUND) {
-    if (address->proto == AVAHI_PROTO_INET) {
-      AvahiStringList* strLst = txt;
-      MulticastServiceResolver::ServiceData data;
-      while (strLst != nullptr) {
-        std::string_view value{reinterpret_cast<const char*>(strLst->text),
-                               strLst->size};
-        strLst = strLst->next;
-        size_t splitIndex = value.find('=');
-        if (splitIndex == value.npos) {
-          // Todo make this just do key
-          continue;
-        }
-        std::string_view key = wpi::substr(value, 0, splitIndex);
-        value =
-            wpi::substr(value, splitIndex + 1, value.size() - splitIndex - 1);
-        data.txt.emplace_back(std::pair<std::string, std::string>{key, value});
-      }
-      wpi::SmallString<256> outputHostName;
-      char label[256];
-      do {
-        impl->table.unescape_label(&host_name, label, sizeof(label));
-        if (label[0] == '\0') {
-          break;
-        }
-        outputHostName.append(label);
-        outputHostName.append(".");
-      } while (true);
-
-      data.ipv4Address = address->data.ipv4.address;
-      data.port = port;
-      data.serviceName = name;
-      data.hostName = outputHostName.string();
-
-      impl->onFound(std::move(data));
-    }
-  }
-
-  impl->table.service_resolver_free(r);
-}
-
-static void BrowseCallback(AvahiServiceBrowser* b, AvahiIfIndex interface,
-                           AvahiProtocol protocol, AvahiBrowserEvent event,
-                           const char* name, const char* type,
-                           const char* domain, AvahiLookupResultFlags flags,
-                           void* userdata) {
-  MulticastServiceResolver::Impl* impl =
-      reinterpret_cast<MulticastServiceResolver::Impl*>(userdata);
-
-  if (event == AVAHI_BROWSER_NEW) {
-    impl->table.service_resolver_new(
-        impl->table.service_browser_get_client(b), interface, protocol, name,
-        type, domain, AVAHI_PROTO_UNSPEC, AVAHI_LOOKUP_USE_MULTICAST,
-        ResolveCallback, userdata);
-  }
-}
-
-static void ClientCallback(AvahiClient* client, AvahiClientState state,
-                           void* userdata) {
-  MulticastServiceResolver::Impl* impl =
-      reinterpret_cast<MulticastServiceResolver::Impl*>(userdata);
-
-  if (state == AVAHI_CLIENT_S_RUNNING) {
-    impl->browser = impl->table.service_browser_new(
-        client, AVAHI_IF_UNSPEC, AVAHI_PROTO_UNSPEC, impl->serviceType.c_str(),
-        "local", AvahiLookupFlags::AVAHI_LOOKUP_USE_MULTICAST, BrowseCallback,
-        userdata);
-  }
-}
-
-void MulticastServiceResolver::Start() {
-  if (!pImpl->table.IsValid()) {
-    return;
-  }
-  std::scoped_lock lock{*pImpl->thread};
-  if (pImpl->client) {
-    return;
-  }
-
-  pImpl->client =
-      pImpl->table.client_new(pImpl->thread->GetPoll(), AVAHI_CLIENT_NO_FAIL,
-                              ClientCallback, pImpl.get(), nullptr);
-}
-
-void MulticastServiceResolver::Stop() {
-  if (!pImpl->table.IsValid()) {
-    return;
-  }
-  std::scoped_lock lock{*pImpl->thread};
-  if (pImpl->client) {
-    if (pImpl->browser) {
-      pImpl->table.service_browser_free(pImpl->browser);
-      pImpl->browser = nullptr;
-    }
-    pImpl->table.client_free(pImpl->client);
-    pImpl->client = nullptr;
-  }
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/macOS/MulticastServiceAnnouncer.cpp b/third_party/allwpilib/wpiutil/src/main/native/macOS/MulticastServiceAnnouncer.cpp
deleted file mode 100644
index ad2ff48..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/macOS/MulticastServiceAnnouncer.cpp
+++ /dev/null
@@ -1,86 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/MulticastServiceAnnouncer.h"
-
-#include <wpi/SmallString.h>
-
-#include "dns_sd.h"
-
-using namespace wpi;
-
-struct MulticastServiceAnnouncer::Impl {
-  std::string serviceName;
-  std::string serviceType;
-  int port;
-  DNSServiceRef serviceRef{nullptr};
-  TXTRecordRef txtRecord;
-
-  Impl() { TXTRecordCreate(&txtRecord, 0, nullptr); }
-
-  ~Impl() noexcept { TXTRecordDeallocate(&txtRecord); }
-};
-
-MulticastServiceAnnouncer::MulticastServiceAnnouncer(
-    std::string_view serviceName, std::string_view serviceType, int port,
-    wpi::span<const std::pair<std::string, std::string>> txt) {
-  pImpl = std::make_unique<Impl>();
-  pImpl->serviceName = serviceName;
-  pImpl->serviceType = serviceType;
-  pImpl->port = port;
-
-  for (auto&& i : txt) {
-    TXTRecordSetValue(&pImpl->txtRecord, i.first.c_str(), i.second.length(),
-                      i.second.c_str());
-  }
-}
-
-MulticastServiceAnnouncer::MulticastServiceAnnouncer(
-    std::string_view serviceName, std::string_view serviceType, int port,
-    wpi::span<const std::pair<std::string_view, std::string_view>> txt) {
-  pImpl = std::make_unique<Impl>();
-  pImpl->serviceName = serviceName;
-  pImpl->serviceType = serviceType;
-  pImpl->port = port;
-
-  wpi::SmallString<64> key;
-
-  for (auto&& i : txt) {
-    key.clear();
-    key.append(i.first);
-    key.emplace_back('\0');
-
-    TXTRecordSetValue(&pImpl->txtRecord, key.data(), i.second.length(),
-                      i.second.data());
-  }
-}
-
-MulticastServiceAnnouncer::~MulticastServiceAnnouncer() noexcept {
-  Stop();
-}
-
-bool MulticastServiceAnnouncer::HasImplementation() const {
-  return true;
-}
-
-void MulticastServiceAnnouncer::Start() {
-  if (pImpl->serviceRef) {
-    return;
-  }
-
-  uint16_t len = TXTRecordGetLength(&pImpl->txtRecord);
-  const void* ptr = TXTRecordGetBytesPtr(&pImpl->txtRecord);
-
-  (void)DNSServiceRegister(&pImpl->serviceRef, 0, 0, pImpl->serviceName.c_str(),
-                           pImpl->serviceType.c_str(), "local", nullptr,
-                           htons(pImpl->port), len, ptr, nullptr, nullptr);
-}
-
-void MulticastServiceAnnouncer::Stop() {
-  if (!pImpl->serviceRef) {
-    return;
-  }
-  DNSServiceRefDeallocate(pImpl->serviceRef);
-  pImpl->serviceRef = nullptr;
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/macOS/MulticastServiceResolver.cpp b/third_party/allwpilib/wpiutil/src/main/native/macOS/MulticastServiceResolver.cpp
deleted file mode 100644
index 4af8cad..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/macOS/MulticastServiceResolver.cpp
+++ /dev/null
@@ -1,213 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/MulticastServiceResolver.h"
-
-#include <netinet/in.h>
-#include <poll.h>
-
-#include <atomic>
-#include <thread>
-#include <vector>
-
-#include "ResolverThread.h"
-#include "dns_sd.h"
-#include "wpi/SmallVector.h"
-
-using namespace wpi;
-
-struct DnsResolveState {
-  DnsResolveState(MulticastServiceResolver::Impl* impl,
-                  std::string_view serviceNameView)
-      : pImpl{impl} {
-    data.serviceName = serviceNameView;
-  }
-
-  DNSServiceRef ResolveRef = nullptr;
-  MulticastServiceResolver::Impl* pImpl;
-
-  MulticastServiceResolver::ServiceData data;
-};
-
-struct MulticastServiceResolver::Impl {
-  std::string serviceType;
-  MulticastServiceResolver* resolver;
-  std::shared_ptr<ResolverThread> thread = ResolverThread::Get();
-  std::vector<std::unique_ptr<DnsResolveState>> ResolveStates;
-  DNSServiceRef serviceRef = nullptr;
-
-  void onFound(ServiceData&& data) {
-    resolver->PushData(std::forward<ServiceData>(data));
-  }
-};
-
-MulticastServiceResolver::MulticastServiceResolver(
-    std::string_view serviceType) {
-  pImpl = std::make_unique<Impl>();
-  pImpl->serviceType = serviceType;
-  pImpl->resolver = this;
-}
-
-MulticastServiceResolver::~MulticastServiceResolver() noexcept {
-  Stop();
-}
-
-void ServiceGetAddrInfoReply(DNSServiceRef sdRef, DNSServiceFlags flags,
-                             uint32_t interfaceIndex,
-                             DNSServiceErrorType errorCode,
-                             const char* hostname,
-                             const struct sockaddr* address, uint32_t ttl,
-                             void* context) {
-  if (errorCode != kDNSServiceErr_NoError) {
-    return;
-  }
-
-  DnsResolveState* resolveState = static_cast<DnsResolveState*>(context);
-
-  resolveState->data.hostName = hostname;
-  resolveState->data.ipv4Address =
-      reinterpret_cast<const struct sockaddr_in*>(address)->sin_addr.s_addr;
-
-  resolveState->pImpl->onFound(std::move(resolveState->data));
-
-  resolveState->pImpl->thread->RemoveServiceRefInThread(
-      resolveState->ResolveRef);
-
-  resolveState->pImpl->ResolveStates.erase(std::find_if(
-      resolveState->pImpl->ResolveStates.begin(),
-      resolveState->pImpl->ResolveStates.end(),
-      [resolveState](auto& a) { return a.get() == resolveState; }));
-}
-
-void ServiceResolveReply(DNSServiceRef sdRef, DNSServiceFlags flags,
-                         uint32_t interfaceIndex, DNSServiceErrorType errorCode,
-                         const char* fullname, const char* hosttarget,
-                         uint16_t port, /* In network byte order */
-                         uint16_t txtLen, const unsigned char* txtRecord,
-                         void* context) {
-  if (errorCode != kDNSServiceErr_NoError) {
-    return;
-  }
-
-  DnsResolveState* resolveState = static_cast<DnsResolveState*>(context);
-  resolveState->pImpl->thread->RemoveServiceRefInThread(
-      resolveState->ResolveRef);
-  DNSServiceRefDeallocate(resolveState->ResolveRef);
-  resolveState->ResolveRef = nullptr;
-  resolveState->data.port = ntohs(port);
-
-  int txtCount = TXTRecordGetCount(txtLen, txtRecord);
-  char keyBuf[256];
-  uint8_t valueLen;
-  const void* value;
-
-  for (int i = 0; i < txtCount; i++) {
-    errorCode = TXTRecordGetItemAtIndex(txtLen, txtRecord, i, sizeof(keyBuf),
-                                        keyBuf, &valueLen, &value);
-    if (errorCode == kDNSServiceErr_NoError) {
-      if (valueLen == 0) {
-        // No value
-        resolveState->data.txt.emplace_back(
-            std::pair<std::string, std::string>{std::string{keyBuf}, {}});
-      } else {
-        resolveState->data.txt.emplace_back(std::pair<std::string, std::string>{
-            std::string{keyBuf},
-            std::string{reinterpret_cast<const char*>(value), valueLen}});
-      }
-    }
-  }
-
-  errorCode = DNSServiceGetAddrInfo(
-      &resolveState->ResolveRef, flags, interfaceIndex,
-      kDNSServiceProtocol_IPv4, hosttarget, ServiceGetAddrInfoReply, context);
-
-  if (errorCode == kDNSServiceErr_NoError) {
-    dnssd_sock_t socket = DNSServiceRefSockFD(resolveState->ResolveRef);
-    resolveState->pImpl->thread->AddServiceRef(resolveState->ResolveRef,
-                                               socket);
-  } else {
-    resolveState->pImpl->thread->RemoveServiceRefInThread(
-        resolveState->ResolveRef);
-    resolveState->pImpl->ResolveStates.erase(std::find_if(
-        resolveState->pImpl->ResolveStates.begin(),
-        resolveState->pImpl->ResolveStates.end(),
-        [resolveState](auto& a) { return a.get() == resolveState; }));
-  }
-}
-
-static void DnsCompletion(DNSServiceRef sdRef, DNSServiceFlags flags,
-                          uint32_t interfaceIndex,
-                          DNSServiceErrorType errorCode,
-                          const char* serviceName, const char* regtype,
-                          const char* replyDomain, void* context) {
-  if (errorCode != kDNSServiceErr_NoError) {
-    return;
-  }
-  if (!(flags & kDNSServiceFlagsAdd)) {
-    return;
-  }
-
-  MulticastServiceResolver::Impl* impl =
-      static_cast<MulticastServiceResolver::Impl*>(context);
-  auto& resolveState = impl->ResolveStates.emplace_back(
-      std::make_unique<DnsResolveState>(impl, serviceName));
-
-  errorCode = DNSServiceResolve(&resolveState->ResolveRef, 0, interfaceIndex,
-                                serviceName, regtype, replyDomain,
-                                ServiceResolveReply, resolveState.get());
-
-  if (errorCode == kDNSServiceErr_NoError) {
-    dnssd_sock_t socket = DNSServiceRefSockFD(resolveState->ResolveRef);
-    resolveState->pImpl->thread->AddServiceRef(resolveState->ResolveRef,
-                                               socket);
-  } else {
-    resolveState->pImpl->ResolveStates.erase(std::find_if(
-        resolveState->pImpl->ResolveStates.begin(),
-        resolveState->pImpl->ResolveStates.end(),
-        [r = resolveState.get()](auto& a) { return a.get() == r; }));
-  }
-}
-
-bool MulticastServiceResolver::HasImplementation() const {
-  return true;
-}
-
-void MulticastServiceResolver::Start() {
-  if (pImpl->serviceRef) {
-    return;
-  }
-
-  DNSServiceErrorType status =
-      DNSServiceBrowse(&pImpl->serviceRef, 0, 0, pImpl->serviceType.c_str(),
-                       "local", DnsCompletion, pImpl.get());
-  if (status == kDNSServiceErr_NoError) {
-    dnssd_sock_t socket = DNSServiceRefSockFD(pImpl->serviceRef);
-    pImpl->thread->AddServiceRef(pImpl->serviceRef, socket);
-  }
-}
-
-void MulticastServiceResolver::Stop() {
-  if (!pImpl->serviceRef) {
-    return;
-  }
-  wpi::SmallVector<WPI_EventHandle, 8> cleanupEvents;
-  for (auto&& i : pImpl->ResolveStates) {
-    cleanupEvents.push_back(
-        pImpl->thread->RemoveServiceRefOutsideThread(i->ResolveRef));
-  }
-  cleanupEvents.push_back(
-      pImpl->thread->RemoveServiceRefOutsideThread(pImpl->serviceRef));
-  wpi::SmallVector<WPI_Handle, 8> signaledBuf;
-  signaledBuf.resize(cleanupEvents.size());
-  while (!cleanupEvents.empty()) {
-    auto signaled = wpi::WaitForObjects(cleanupEvents, signaledBuf);
-    for (auto&& s : signaled) {
-      cleanupEvents.erase(
-          std::find(cleanupEvents.begin(), cleanupEvents.end(), s));
-    }
-  }
-
-  pImpl->ResolveStates.clear();
-  pImpl->serviceRef = nullptr;
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/macOS/ResolverThread.cpp b/third_party/allwpilib/wpiutil/src/main/native/macOS/ResolverThread.cpp
deleted file mode 100644
index b91d6b6..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/macOS/ResolverThread.cpp
+++ /dev/null
@@ -1,109 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "ResolverThread.h"
-
-#include "wpi/mutex.h"
-
-using namespace wpi;
-
-ResolverThread::ResolverThread(const private_init&) {}
-
-ResolverThread::~ResolverThread() noexcept {
-  running = false;
-  if (thread.joinable()) {
-    thread.join();
-  }
-}
-
-void ResolverThread::AddServiceRef(DNSServiceRef serviceRef,
-                                   dnssd_sock_t socket) {
-  std::scoped_lock lock{serviceRefMutex};
-  serviceRefs.emplace_back(
-      std::pair<DNSServiceRef, dnssd_sock_t>{serviceRef, socket});
-  if (serviceRefs.size() == 1) {
-    running = false;
-    if (thread.joinable()) {
-      thread.join();
-    }
-    running = true;
-    thread = std::thread([=] { ThreadMain(); });
-  }
-}
-
-void ResolverThread::RemoveServiceRefInThread(DNSServiceRef serviceRef) {
-  std::scoped_lock lock{serviceRefMutex};
-  serviceRefs.erase(
-      std::find_if(serviceRefs.begin(), serviceRefs.end(),
-                   [=](auto& a) { return a.first == serviceRef; }));
-  DNSServiceRefDeallocate(serviceRef);
-}
-
-WPI_EventHandle ResolverThread::RemoveServiceRefOutsideThread(
-    DNSServiceRef serviceRef) {
-  std::scoped_lock lock{serviceRefMutex};
-  WPI_EventHandle handle = CreateEvent(true);
-  serviceRefsToRemove.push_back({serviceRef, handle});
-  return handle;
-}
-
-bool ResolverThread::CleanupRefs() {
-  std::scoped_lock lock{serviceRefMutex};
-  for (auto&& r : serviceRefsToRemove) {
-    serviceRefs.erase(
-        std::find_if(serviceRefs.begin(), serviceRefs.end(),
-                     [=](auto& a) { return a.first == r.first; }));
-    DNSServiceRefDeallocate(r.first);
-    wpi::SetEvent(r.second);
-  }
-  serviceRefsToRemove.clear();
-  return serviceRefs.empty();
-}
-
-void ResolverThread::ThreadMain() {
-  std::vector<pollfd> readSockets;
-  std::vector<DNSServiceRef> serviceRefs;
-
-  while (running) {
-    readSockets.clear();
-    serviceRefs.clear();
-
-    for (auto&& i : this->serviceRefs) {
-      readSockets.emplace_back(pollfd{i.second, POLLIN, 0});
-      serviceRefs.emplace_back(i.first);
-    }
-
-    int res = poll(readSockets.begin().base(), readSockets.size(), 100);
-
-    if (res > 0) {
-      for (size_t i = 0; i < readSockets.size(); i++) {
-        if (readSockets[i].revents == POLLIN) {
-          DNSServiceProcessResult(serviceRefs[i]);
-        }
-      }
-    } else if (res == 0) {
-      if (!running) {
-        CleanupRefs();
-        break;
-      }
-    }
-
-    if (CleanupRefs()) {
-      break;
-    }
-  }
-}
-
-static wpi::mutex ThreadLoopLock;
-static std::weak_ptr<ResolverThread> ThreadLoop;
-
-std::shared_ptr<ResolverThread> ResolverThread::Get() {
-  std::scoped_lock lock{ThreadLoopLock};
-  auto locked = ThreadLoop.lock();
-  if (!locked) {
-    locked = std::make_unique<ResolverThread>(private_init{});
-    ThreadLoop = locked;
-  }
-  return locked;
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/macOS/ResolverThread.h b/third_party/allwpilib/wpiutil/src/main/native/macOS/ResolverThread.h
deleted file mode 100644
index 0162de5..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/macOS/ResolverThread.h
+++ /dev/null
@@ -1,45 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <netinet/in.h>
-#include <poll.h>
-
-#include <atomic>
-#include <memory>
-#include <thread>
-#include <utility>
-#include <vector>
-
-#include "dns_sd.h"
-#include "wpi/Synchronization.h"
-#include "wpi/mutex.h"
-
-namespace wpi {
-class ResolverThread {
- private:
-  struct private_init {};
-
- public:
-  explicit ResolverThread(const private_init&);
-  ~ResolverThread() noexcept;
-
-  void AddServiceRef(DNSServiceRef serviceRef, dnssd_sock_t socket);
-  void RemoveServiceRefInThread(DNSServiceRef serviceRef);
-  WPI_EventHandle RemoveServiceRefOutsideThread(DNSServiceRef serviceRef);
-
-  static std::shared_ptr<ResolverThread> Get();
-
- private:
-  void ThreadMain();
-  bool CleanupRefs();
-
-  wpi::mutex serviceRefMutex;
-  std::vector<std::pair<DNSServiceRef, WPI_EventHandle>> serviceRefsToRemove;
-  std::vector<std::pair<DNSServiceRef, dnssd_sock_t>> serviceRefs;
-  std::thread thread;
-  std::atomic_bool running;
-};
-}  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/args.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/args.h
new file mode 100644
index 0000000..a3966d1
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/args.h
@@ -0,0 +1,234 @@
+// Formatting library for C++ - dynamic format arguments
+//
+// Copyright (c) 2012 - present, Victor Zverovich
+// All rights reserved.
+//
+// For the license information refer to format.h.
+
+#ifndef FMT_ARGS_H_
+#define FMT_ARGS_H_
+
+#include <functional>  // std::reference_wrapper
+#include <memory>      // std::unique_ptr
+#include <vector>
+
+#include "core.h"
+
+FMT_BEGIN_NAMESPACE
+
+namespace detail {
+
+template <typename T> struct is_reference_wrapper : std::false_type {};
+template <typename T>
+struct is_reference_wrapper<std::reference_wrapper<T>> : std::true_type {};
+
+template <typename T> const T& unwrap(const T& v) { return v; }
+template <typename T> const T& unwrap(const std::reference_wrapper<T>& v) {
+  return static_cast<const T&>(v);
+}
+
+class dynamic_arg_list {
+  // Workaround for clang's -Wweak-vtables. Unlike for regular classes, for
+  // templates it doesn't complain about inability to deduce single translation
+  // unit for placing vtable. So storage_node_base is made a fake template.
+  template <typename = void> struct node {
+    virtual ~node() = default;
+    std::unique_ptr<node<>> next;
+  };
+
+  template <typename T> struct typed_node : node<> {
+    T value;
+
+    template <typename Arg>
+    FMT_CONSTEXPR typed_node(const Arg& arg) : value(arg) {}
+
+    template <typename Char>
+    FMT_CONSTEXPR typed_node(const basic_string_view<Char>& arg)
+        : value(arg.data(), arg.size()) {}
+  };
+
+  std::unique_ptr<node<>> head_;
+
+ public:
+  template <typename T, typename Arg> const T& push(const Arg& arg) {
+    auto new_node = std::unique_ptr<typed_node<T>>(new typed_node<T>(arg));
+    auto& value = new_node->value;
+    new_node->next = std::move(head_);
+    head_ = std::move(new_node);
+    return value;
+  }
+};
+}  // namespace detail
+
+/**
+  \rst
+  A dynamic version of `fmt::format_arg_store`.
+  It's equipped with a storage to potentially temporary objects which lifetimes
+  could be shorter than the format arguments object.
+
+  It can be implicitly converted into `~fmt::basic_format_args` for passing
+  into type-erased formatting functions such as `~fmt::vformat`.
+  \endrst
+ */
+template <typename Context>
+class dynamic_format_arg_store
+#if FMT_GCC_VERSION && FMT_GCC_VERSION < 409
+    // Workaround a GCC template argument substitution bug.
+    : public basic_format_args<Context>
+#endif
+{
+ private:
+  using char_type = typename Context::char_type;
+
+  template <typename T> struct need_copy {
+    static constexpr detail::type mapped_type =
+        detail::mapped_type_constant<T, Context>::value;
+
+    enum {
+      value = !(detail::is_reference_wrapper<T>::value ||
+                std::is_same<T, basic_string_view<char_type>>::value ||
+                std::is_same<T, detail::std_string_view<char_type>>::value ||
+                (mapped_type != detail::type::cstring_type &&
+                 mapped_type != detail::type::string_type &&
+                 mapped_type != detail::type::custom_type))
+    };
+  };
+
+  template <typename T>
+  using stored_type = conditional_t<
+      std::is_convertible<T, std::basic_string<char_type>>::value &&
+          !detail::is_reference_wrapper<T>::value,
+      std::basic_string<char_type>, T>;
+
+  // Storage of basic_format_arg must be contiguous.
+  std::vector<basic_format_arg<Context>> data_;
+  std::vector<detail::named_arg_info<char_type>> named_info_;
+
+  // Storage of arguments not fitting into basic_format_arg must grow
+  // without relocation because items in data_ refer to it.
+  detail::dynamic_arg_list dynamic_args_;
+
+  friend class basic_format_args<Context>;
+
+  unsigned long long get_types() const {
+    return detail::is_unpacked_bit | data_.size() |
+           (named_info_.empty()
+                ? 0ULL
+                : static_cast<unsigned long long>(detail::has_named_args_bit));
+  }
+
+  const basic_format_arg<Context>* data() const {
+    return named_info_.empty() ? data_.data() : data_.data() + 1;
+  }
+
+  template <typename T> void emplace_arg(const T& arg) {
+    data_.emplace_back(detail::make_arg<Context>(arg));
+  }
+
+  template <typename T>
+  void emplace_arg(const detail::named_arg<char_type, T>& arg) {
+    if (named_info_.empty()) {
+      constexpr const detail::named_arg_info<char_type>* zero_ptr{nullptr};
+      data_.insert(data_.begin(), {zero_ptr, 0});
+    }
+    data_.emplace_back(detail::make_arg<Context>(detail::unwrap(arg.value)));
+    auto pop_one = [](std::vector<basic_format_arg<Context>>* data) {
+      data->pop_back();
+    };
+    std::unique_ptr<std::vector<basic_format_arg<Context>>, decltype(pop_one)>
+        guard{&data_, pop_one};
+    named_info_.push_back({arg.name, static_cast<int>(data_.size() - 2u)});
+    data_[0].value_.named_args = {named_info_.data(), named_info_.size()};
+    guard.release();
+  }
+
+ public:
+  constexpr dynamic_format_arg_store() = default;
+
+  /**
+    \rst
+    Adds an argument into the dynamic store for later passing to a formatting
+    function.
+
+    Note that custom types and string types (but not string views) are copied
+    into the store dynamically allocating memory if necessary.
+
+    **Example**::
+
+      fmt::dynamic_format_arg_store<fmt::format_context> store;
+      store.push_back(42);
+      store.push_back("abc");
+      store.push_back(1.5f);
+      std::string result = fmt::vformat("{} and {} and {}", store);
+    \endrst
+  */
+  template <typename T> void push_back(const T& arg) {
+    if (detail::const_check(need_copy<T>::value))
+      emplace_arg(dynamic_args_.push<stored_type<T>>(arg));
+    else
+      emplace_arg(detail::unwrap(arg));
+  }
+
+  /**
+    \rst
+    Adds a reference to the argument into the dynamic store for later passing to
+    a formatting function.
+
+    **Example**::
+
+      fmt::dynamic_format_arg_store<fmt::format_context> store;
+      char band[] = "Rolling Stones";
+      store.push_back(std::cref(band));
+      band[9] = 'c'; // Changing str affects the output.
+      std::string result = fmt::vformat("{}", store);
+      // result == "Rolling Scones"
+    \endrst
+  */
+  template <typename T> void push_back(std::reference_wrapper<T> arg) {
+    static_assert(
+        need_copy<T>::value,
+        "objects of built-in types and string views are always copied");
+    emplace_arg(arg.get());
+  }
+
+  /**
+    Adds named argument into the dynamic store for later passing to a formatting
+    function. ``std::reference_wrapper`` is supported to avoid copying of the
+    argument. The name is always copied into the store.
+  */
+  template <typename T>
+  void push_back(const detail::named_arg<char_type, T>& arg) {
+    const char_type* arg_name =
+        dynamic_args_.push<std::basic_string<char_type>>(arg.name).c_str();
+    if (detail::const_check(need_copy<T>::value)) {
+      emplace_arg(
+          fmt::arg(arg_name, dynamic_args_.push<stored_type<T>>(arg.value)));
+    } else {
+      emplace_arg(fmt::arg(arg_name, arg.value));
+    }
+  }
+
+  /** Erase all elements from the store */
+  void clear() {
+    data_.clear();
+    named_info_.clear();
+    dynamic_args_ = detail::dynamic_arg_list();
+  }
+
+  /**
+    \rst
+    Reserves space to store at least *new_cap* arguments including
+    *new_cap_named* named arguments.
+    \endrst
+  */
+  void reserve(size_t new_cap, size_t new_cap_named) {
+    FMT_ASSERT(new_cap >= new_cap_named,
+               "Set of arguments includes set of named arguments");
+    data_.reserve(new_cap);
+    named_info_.reserve(new_cap_named);
+  }
+};
+
+FMT_END_NAMESPACE
+
+#endif  // FMT_ARGS_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/chrono.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/chrono.h
new file mode 100644
index 0000000..b112f76
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/chrono.h
@@ -0,0 +1,2069 @@
+// Formatting library for C++ - chrono support
+//
+// Copyright (c) 2012 - present, Victor Zverovich
+// All rights reserved.
+//
+// For the license information refer to format.h.
+
+#ifndef FMT_CHRONO_H_
+#define FMT_CHRONO_H_
+
+#include <algorithm>
+#include <chrono>
+#include <cmath>    // std::isfinite
+#include <cstring>  // std::memcpy
+#include <ctime>
+#include <iterator>
+#include <locale>
+#include <ostream>
+#include <type_traits>
+
+#include "format.h"
+
+FMT_BEGIN_NAMESPACE
+
+// Enable tzset.
+#ifndef FMT_USE_TZSET
+// UWP doesn't provide _tzset.
+#  if FMT_HAS_INCLUDE("winapifamily.h")
+#    include <winapifamily.h>
+#  endif
+#  if defined(_WIN32) && (!defined(WINAPI_FAMILY) || \
+                          (WINAPI_FAMILY == WINAPI_FAMILY_DESKTOP_APP))
+#    define FMT_USE_TZSET 1
+#  else
+#    define FMT_USE_TZSET 0
+#  endif
+#endif
+
+// Enable safe chrono durations, unless explicitly disabled.
+#ifndef FMT_SAFE_DURATION_CAST
+#  define FMT_SAFE_DURATION_CAST 1
+#endif
+#if FMT_SAFE_DURATION_CAST
+
+// For conversion between std::chrono::durations without undefined
+// behaviour or erroneous results.
+// This is a stripped down version of duration_cast, for inclusion in fmt.
+// See https://github.com/pauldreik/safe_duration_cast
+//
+// Copyright Paul Dreik 2019
+namespace safe_duration_cast {
+
+template <typename To, typename From,
+          FMT_ENABLE_IF(!std::is_same<From, To>::value &&
+                        std::numeric_limits<From>::is_signed ==
+                            std::numeric_limits<To>::is_signed)>
+FMT_CONSTEXPR To lossless_integral_conversion(const From from, int& ec) {
+  ec = 0;
+  using F = std::numeric_limits<From>;
+  using T = std::numeric_limits<To>;
+  static_assert(F::is_integer, "From must be integral");
+  static_assert(T::is_integer, "To must be integral");
+
+  // A and B are both signed, or both unsigned.
+  if (detail::const_check(F::digits <= T::digits)) {
+    // From fits in To without any problem.
+  } else {
+    // From does not always fit in To, resort to a dynamic check.
+    if (from < (T::min)() || from > (T::max)()) {
+      // outside range.
+      ec = 1;
+      return {};
+    }
+  }
+  return static_cast<To>(from);
+}
+
+/**
+ * converts From to To, without loss. If the dynamic value of from
+ * can't be converted to To without loss, ec is set.
+ */
+template <typename To, typename From,
+          FMT_ENABLE_IF(!std::is_same<From, To>::value &&
+                        std::numeric_limits<From>::is_signed !=
+                            std::numeric_limits<To>::is_signed)>
+FMT_CONSTEXPR To lossless_integral_conversion(const From from, int& ec) {
+  ec = 0;
+  using F = std::numeric_limits<From>;
+  using T = std::numeric_limits<To>;
+  static_assert(F::is_integer, "From must be integral");
+  static_assert(T::is_integer, "To must be integral");
+
+  if (detail::const_check(F::is_signed && !T::is_signed)) {
+    // From may be negative, not allowed!
+    if (fmt::detail::is_negative(from)) {
+      ec = 1;
+      return {};
+    }
+    // From is positive. Can it always fit in To?
+    if (detail::const_check(F::digits > T::digits) &&
+        from > static_cast<From>(detail::max_value<To>())) {
+      ec = 1;
+      return {};
+    }
+  }
+
+  if (detail::const_check(!F::is_signed && T::is_signed &&
+                          F::digits >= T::digits) &&
+      from > static_cast<From>(detail::max_value<To>())) {
+    ec = 1;
+    return {};
+  }
+  return static_cast<To>(from);  // Lossless conversion.
+}
+
+template <typename To, typename From,
+          FMT_ENABLE_IF(std::is_same<From, To>::value)>
+FMT_CONSTEXPR To lossless_integral_conversion(const From from, int& ec) {
+  ec = 0;
+  return from;
+}  // function
+
+// clang-format off
+/**
+ * converts From to To if possible, otherwise ec is set.
+ *
+ * input                            |    output
+ * ---------------------------------|---------------
+ * NaN                              | NaN
+ * Inf                              | Inf
+ * normal, fits in output           | converted (possibly lossy)
+ * normal, does not fit in output   | ec is set
+ * subnormal                        | best effort
+ * -Inf                             | -Inf
+ */
+// clang-format on
+template <typename To, typename From,
+          FMT_ENABLE_IF(!std::is_same<From, To>::value)>
+FMT_CONSTEXPR To safe_float_conversion(const From from, int& ec) {
+  ec = 0;
+  using T = std::numeric_limits<To>;
+  static_assert(std::is_floating_point<From>::value, "From must be floating");
+  static_assert(std::is_floating_point<To>::value, "To must be floating");
+
+  // catch the only happy case
+  if (std::isfinite(from)) {
+    if (from >= T::lowest() && from <= (T::max)()) {
+      return static_cast<To>(from);
+    }
+    // not within range.
+    ec = 1;
+    return {};
+  }
+
+  // nan and inf will be preserved
+  return static_cast<To>(from);
+}  // function
+
+template <typename To, typename From,
+          FMT_ENABLE_IF(std::is_same<From, To>::value)>
+FMT_CONSTEXPR To safe_float_conversion(const From from, int& ec) {
+  ec = 0;
+  static_assert(std::is_floating_point<From>::value, "From must be floating");
+  return from;
+}
+
+/**
+ * safe duration cast between integral durations
+ */
+template <typename To, typename FromRep, typename FromPeriod,
+          FMT_ENABLE_IF(std::is_integral<FromRep>::value),
+          FMT_ENABLE_IF(std::is_integral<typename To::rep>::value)>
+To safe_duration_cast(std::chrono::duration<FromRep, FromPeriod> from,
+                      int& ec) {
+  using From = std::chrono::duration<FromRep, FromPeriod>;
+  ec = 0;
+  // the basic idea is that we need to convert from count() in the from type
+  // to count() in the To type, by multiplying it with this:
+  struct Factor
+      : std::ratio_divide<typename From::period, typename To::period> {};
+
+  static_assert(Factor::num > 0, "num must be positive");
+  static_assert(Factor::den > 0, "den must be positive");
+
+  // the conversion is like this: multiply from.count() with Factor::num
+  // /Factor::den and convert it to To::rep, all this without
+  // overflow/underflow. let's start by finding a suitable type that can hold
+  // both To, From and Factor::num
+  using IntermediateRep =
+      typename std::common_type<typename From::rep, typename To::rep,
+                                decltype(Factor::num)>::type;
+
+  // safe conversion to IntermediateRep
+  IntermediateRep count =
+      lossless_integral_conversion<IntermediateRep>(from.count(), ec);
+  if (ec) return {};
+  // multiply with Factor::num without overflow or underflow
+  if (detail::const_check(Factor::num != 1)) {
+    const auto max1 = detail::max_value<IntermediateRep>() / Factor::num;
+    if (count > max1) {
+      ec = 1;
+      return {};
+    }
+    const auto min1 =
+        (std::numeric_limits<IntermediateRep>::min)() / Factor::num;
+    if (!std::is_unsigned<IntermediateRep>::value && count < min1) {
+      ec = 1;
+      return {};
+    }
+    count *= Factor::num;
+  }
+
+  if (detail::const_check(Factor::den != 1)) count /= Factor::den;
+  auto tocount = lossless_integral_conversion<typename To::rep>(count, ec);
+  return ec ? To() : To(tocount);
+}
+
+/**
+ * safe duration_cast between floating point durations
+ */
+template <typename To, typename FromRep, typename FromPeriod,
+          FMT_ENABLE_IF(std::is_floating_point<FromRep>::value),
+          FMT_ENABLE_IF(std::is_floating_point<typename To::rep>::value)>
+To safe_duration_cast(std::chrono::duration<FromRep, FromPeriod> from,
+                      int& ec) {
+  using From = std::chrono::duration<FromRep, FromPeriod>;
+  ec = 0;
+  if (std::isnan(from.count())) {
+    // nan in, gives nan out. easy.
+    return To{std::numeric_limits<typename To::rep>::quiet_NaN()};
+  }
+  // maybe we should also check if from is denormal, and decide what to do about
+  // it.
+
+  // +-inf should be preserved.
+  if (std::isinf(from.count())) {
+    return To{from.count()};
+  }
+
+  // the basic idea is that we need to convert from count() in the from type
+  // to count() in the To type, by multiplying it with this:
+  struct Factor
+      : std::ratio_divide<typename From::period, typename To::period> {};
+
+  static_assert(Factor::num > 0, "num must be positive");
+  static_assert(Factor::den > 0, "den must be positive");
+
+  // the conversion is like this: multiply from.count() with Factor::num
+  // /Factor::den and convert it to To::rep, all this without
+  // overflow/underflow. let's start by finding a suitable type that can hold
+  // both To, From and Factor::num
+  using IntermediateRep =
+      typename std::common_type<typename From::rep, typename To::rep,
+                                decltype(Factor::num)>::type;
+
+  // force conversion of From::rep -> IntermediateRep to be safe,
+  // even if it will never happen be narrowing in this context.
+  IntermediateRep count =
+      safe_float_conversion<IntermediateRep>(from.count(), ec);
+  if (ec) {
+    return {};
+  }
+
+  // multiply with Factor::num without overflow or underflow
+  if (detail::const_check(Factor::num != 1)) {
+    constexpr auto max1 = detail::max_value<IntermediateRep>() /
+                          static_cast<IntermediateRep>(Factor::num);
+    if (count > max1) {
+      ec = 1;
+      return {};
+    }
+    constexpr auto min1 = std::numeric_limits<IntermediateRep>::lowest() /
+                          static_cast<IntermediateRep>(Factor::num);
+    if (count < min1) {
+      ec = 1;
+      return {};
+    }
+    count *= static_cast<IntermediateRep>(Factor::num);
+  }
+
+  // this can't go wrong, right? den>0 is checked earlier.
+  if (detail::const_check(Factor::den != 1)) {
+    using common_t = typename std::common_type<IntermediateRep, intmax_t>::type;
+    count /= static_cast<common_t>(Factor::den);
+  }
+
+  // convert to the to type, safely
+  using ToRep = typename To::rep;
+
+  const ToRep tocount = safe_float_conversion<ToRep>(count, ec);
+  if (ec) {
+    return {};
+  }
+  return To{tocount};
+}
+}  // namespace safe_duration_cast
+#endif
+
+// Prevents expansion of a preceding token as a function-style macro.
+// Usage: f FMT_NOMACRO()
+#define FMT_NOMACRO
+
+namespace detail {
+template <typename T = void> struct null {};
+inline null<> localtime_r FMT_NOMACRO(...) { return null<>(); }
+inline null<> localtime_s(...) { return null<>(); }
+inline null<> gmtime_r(...) { return null<>(); }
+inline null<> gmtime_s(...) { return null<>(); }
+
+inline const std::locale& get_classic_locale() {
+  static const auto& locale = std::locale::classic();
+  return locale;
+}
+
+template <typename CodeUnit> struct codecvt_result {
+  static constexpr const size_t max_size = 32;
+  CodeUnit buf[max_size];
+  CodeUnit* end;
+};
+template <typename CodeUnit>
+constexpr const size_t codecvt_result<CodeUnit>::max_size;
+
+template <typename CodeUnit>
+void write_codecvt(codecvt_result<CodeUnit>& out, string_view in_buf,
+                   const std::locale& loc) {
+#if FMT_CLANG_VERSION
+#  pragma clang diagnostic push
+#  pragma clang diagnostic ignored "-Wdeprecated"
+  auto& f = std::use_facet<std::codecvt<CodeUnit, char, std::mbstate_t>>(loc);
+#  pragma clang diagnostic pop
+#else
+  auto& f = std::use_facet<std::codecvt<CodeUnit, char, std::mbstate_t>>(loc);
+#endif
+  auto mb = std::mbstate_t();
+  const char* from_next = nullptr;
+  auto result = f.in(mb, in_buf.begin(), in_buf.end(), from_next,
+                     std::begin(out.buf), std::end(out.buf), out.end);
+  if (result != std::codecvt_base::ok)
+    FMT_THROW(format_error("failed to format time"));
+}
+
+template <typename OutputIt>
+auto write_encoded_tm_str(OutputIt out, string_view in, const std::locale& loc)
+    -> OutputIt {
+  if (detail::is_utf8() && loc != get_classic_locale()) {
+    // char16_t and char32_t codecvts are broken in MSVC (linkage errors) and
+    // gcc-4.
+#if FMT_MSC_VERSION != 0 || \
+    (defined(__GLIBCXX__) && !defined(_GLIBCXX_USE_DUAL_ABI))
+    // The _GLIBCXX_USE_DUAL_ABI macro is always defined in libstdc++ from gcc-5
+    // and newer.
+    using code_unit = wchar_t;
+#else
+    using code_unit = char32_t;
+#endif
+
+    using unit_t = codecvt_result<code_unit>;
+    unit_t unit;
+    write_codecvt(unit, in, loc);
+    // In UTF-8 is used one to four one-byte code units.
+    auto&& buf = basic_memory_buffer<char, unit_t::max_size * 4>();
+    for (code_unit* p = unit.buf; p != unit.end; ++p) {
+      uint32_t c = static_cast<uint32_t>(*p);
+      if (sizeof(code_unit) == 2 && c >= 0xd800 && c <= 0xdfff) {
+        // surrogate pair
+        ++p;
+        if (p == unit.end || (c & 0xfc00) != 0xd800 ||
+            (*p & 0xfc00) != 0xdc00) {
+          FMT_THROW(format_error("failed to format time"));
+        }
+        c = (c << 10) + static_cast<uint32_t>(*p) - 0x35fdc00;
+      }
+      if (c < 0x80) {
+        buf.push_back(static_cast<char>(c));
+      } else if (c < 0x800) {
+        buf.push_back(static_cast<char>(0xc0 | (c >> 6)));
+        buf.push_back(static_cast<char>(0x80 | (c & 0x3f)));
+      } else if ((c >= 0x800 && c <= 0xd7ff) || (c >= 0xe000 && c <= 0xffff)) {
+        buf.push_back(static_cast<char>(0xe0 | (c >> 12)));
+        buf.push_back(static_cast<char>(0x80 | ((c & 0xfff) >> 6)));
+        buf.push_back(static_cast<char>(0x80 | (c & 0x3f)));
+      } else if (c >= 0x10000 && c <= 0x10ffff) {
+        buf.push_back(static_cast<char>(0xf0 | (c >> 18)));
+        buf.push_back(static_cast<char>(0x80 | ((c & 0x3ffff) >> 12)));
+        buf.push_back(static_cast<char>(0x80 | ((c & 0xfff) >> 6)));
+        buf.push_back(static_cast<char>(0x80 | (c & 0x3f)));
+      } else {
+        FMT_THROW(format_error("failed to format time"));
+      }
+    }
+    return copy_str<char>(buf.data(), buf.data() + buf.size(), out);
+  }
+  return copy_str<char>(in.data(), in.data() + in.size(), out);
+}
+
+template <typename Char, typename OutputIt,
+          FMT_ENABLE_IF(!std::is_same<Char, char>::value)>
+auto write_tm_str(OutputIt out, string_view sv, const std::locale& loc)
+    -> OutputIt {
+  codecvt_result<Char> unit;
+  write_codecvt(unit, sv, loc);
+  return copy_str<Char>(unit.buf, unit.end, out);
+}
+
+template <typename Char, typename OutputIt,
+          FMT_ENABLE_IF(std::is_same<Char, char>::value)>
+auto write_tm_str(OutputIt out, string_view sv, const std::locale& loc)
+    -> OutputIt {
+  return write_encoded_tm_str(out, sv, loc);
+}
+
+template <typename Char>
+inline void do_write(buffer<Char>& buf, const std::tm& time,
+                     const std::locale& loc, char format, char modifier) {
+  auto&& format_buf = formatbuf<std::basic_streambuf<Char>>(buf);
+  auto&& os = std::basic_ostream<Char>(&format_buf);
+  os.imbue(loc);
+  using iterator = std::ostreambuf_iterator<Char>;
+  const auto& facet = std::use_facet<std::time_put<Char, iterator>>(loc);
+  auto end = facet.put(os, os, Char(' '), &time, format, modifier);
+  if (end.failed()) FMT_THROW(format_error("failed to format time"));
+}
+
+template <typename Char, typename OutputIt,
+          FMT_ENABLE_IF(!std::is_same<Char, char>::value)>
+auto write(OutputIt out, const std::tm& time, const std::locale& loc,
+           char format, char modifier = 0) -> OutputIt {
+  auto&& buf = get_buffer<Char>(out);
+  do_write<Char>(buf, time, loc, format, modifier);
+  return buf.out();
+}
+
+template <typename Char, typename OutputIt,
+          FMT_ENABLE_IF(std::is_same<Char, char>::value)>
+auto write(OutputIt out, const std::tm& time, const std::locale& loc,
+           char format, char modifier = 0) -> OutputIt {
+  auto&& buf = basic_memory_buffer<Char>();
+  do_write<char>(buf, time, loc, format, modifier);
+  return write_encoded_tm_str(out, string_view(buf.data(), buf.size()), loc);
+}
+
+}  // namespace detail
+
+FMT_MODULE_EXPORT_BEGIN
+
+/**
+  Converts given time since epoch as ``std::time_t`` value into calendar time,
+  expressed in local time. Unlike ``std::localtime``, this function is
+  thread-safe on most platforms.
+ */
+inline std::tm localtime(std::time_t time) {
+  struct dispatcher {
+    std::time_t time_;
+    std::tm tm_;
+
+    dispatcher(std::time_t t) : time_(t) {}
+
+    bool run() {
+      using namespace fmt::detail;
+      return handle(localtime_r(&time_, &tm_));
+    }
+
+    bool handle(std::tm* tm) { return tm != nullptr; }
+
+    bool handle(detail::null<>) {
+      using namespace fmt::detail;
+      return fallback(localtime_s(&tm_, &time_));
+    }
+
+    bool fallback(int res) { return res == 0; }
+
+#if !FMT_MSC_VERSION
+    bool fallback(detail::null<>) {
+      using namespace fmt::detail;
+      std::tm* tm = std::localtime(&time_);
+      if (tm) tm_ = *tm;
+      return tm != nullptr;
+    }
+#endif
+  };
+  dispatcher lt(time);
+  // Too big time values may be unsupported.
+  if (!lt.run()) FMT_THROW(format_error("time_t value out of range"));
+  return lt.tm_;
+}
+
+inline std::tm localtime(
+    std::chrono::time_point<std::chrono::system_clock> time_point) {
+  return localtime(std::chrono::system_clock::to_time_t(time_point));
+}
+
+/**
+  Converts given time since epoch as ``std::time_t`` value into calendar time,
+  expressed in Coordinated Universal Time (UTC). Unlike ``std::gmtime``, this
+  function is thread-safe on most platforms.
+ */
+inline std::tm gmtime(std::time_t time) {
+  struct dispatcher {
+    std::time_t time_;
+    std::tm tm_;
+
+    dispatcher(std::time_t t) : time_(t) {}
+
+    bool run() {
+      using namespace fmt::detail;
+      return handle(gmtime_r(&time_, &tm_));
+    }
+
+    bool handle(std::tm* tm) { return tm != nullptr; }
+
+    bool handle(detail::null<>) {
+      using namespace fmt::detail;
+      return fallback(gmtime_s(&tm_, &time_));
+    }
+
+    bool fallback(int res) { return res == 0; }
+
+#if !FMT_MSC_VERSION
+    bool fallback(detail::null<>) {
+      std::tm* tm = std::gmtime(&time_);
+      if (tm) tm_ = *tm;
+      return tm != nullptr;
+    }
+#endif
+  };
+  dispatcher gt(time);
+  // Too big time values may be unsupported.
+  if (!gt.run()) FMT_THROW(format_error("time_t value out of range"));
+  return gt.tm_;
+}
+
+inline std::tm gmtime(
+    std::chrono::time_point<std::chrono::system_clock> time_point) {
+  return gmtime(std::chrono::system_clock::to_time_t(time_point));
+}
+
+FMT_BEGIN_DETAIL_NAMESPACE
+
+// Writes two-digit numbers a, b and c separated by sep to buf.
+// The method by Pavel Novikov based on
+// https://johnnylee-sde.github.io/Fast-unsigned-integer-to-time-string/.
+inline void write_digit2_separated(char* buf, unsigned a, unsigned b,
+                                   unsigned c, char sep) {
+  unsigned long long digits =
+      a | (b << 24) | (static_cast<unsigned long long>(c) << 48);
+  // Convert each value to BCD.
+  // We have x = a * 10 + b and we want to convert it to BCD y = a * 16 + b.
+  // The difference is
+  //   y - x = a * 6
+  // a can be found from x:
+  //   a = floor(x / 10)
+  // then
+  //   y = x + a * 6 = x + floor(x / 10) * 6
+  // floor(x / 10) is (x * 205) >> 11 (needs 16 bits).
+  digits += (((digits * 205) >> 11) & 0x000f00000f00000f) * 6;
+  // Put low nibbles to high bytes and high nibbles to low bytes.
+  digits = ((digits & 0x00f00000f00000f0) >> 4) |
+           ((digits & 0x000f00000f00000f) << 8);
+  auto usep = static_cast<unsigned long long>(sep);
+  // Add ASCII '0' to each digit byte and insert separators.
+  digits |= 0x3030003030003030 | (usep << 16) | (usep << 40);
+
+  constexpr const size_t len = 8;
+  if (const_check(is_big_endian())) {
+    char tmp[len];
+    std::memcpy(tmp, &digits, len);
+    std::reverse_copy(tmp, tmp + len, buf);
+  } else {
+    std::memcpy(buf, &digits, len);
+  }
+}
+
+template <typename Period> FMT_CONSTEXPR inline const char* get_units() {
+  if (std::is_same<Period, std::atto>::value) return "as";
+  if (std::is_same<Period, std::femto>::value) return "fs";
+  if (std::is_same<Period, std::pico>::value) return "ps";
+  if (std::is_same<Period, std::nano>::value) return "ns";
+  if (std::is_same<Period, std::micro>::value) return "µs";
+  if (std::is_same<Period, std::milli>::value) return "ms";
+  if (std::is_same<Period, std::centi>::value) return "cs";
+  if (std::is_same<Period, std::deci>::value) return "ds";
+  if (std::is_same<Period, std::ratio<1>>::value) return "s";
+  if (std::is_same<Period, std::deca>::value) return "das";
+  if (std::is_same<Period, std::hecto>::value) return "hs";
+  if (std::is_same<Period, std::kilo>::value) return "ks";
+  if (std::is_same<Period, std::mega>::value) return "Ms";
+  if (std::is_same<Period, std::giga>::value) return "Gs";
+  if (std::is_same<Period, std::tera>::value) return "Ts";
+  if (std::is_same<Period, std::peta>::value) return "Ps";
+  if (std::is_same<Period, std::exa>::value) return "Es";
+  if (std::is_same<Period, std::ratio<60>>::value) return "m";
+  if (std::is_same<Period, std::ratio<3600>>::value) return "h";
+  return nullptr;
+}
+
+enum class numeric_system {
+  standard,
+  // Alternative numeric system, e.g. 十二 instead of 12 in ja_JP locale.
+  alternative
+};
+
+// Parses a put_time-like format string and invokes handler actions.
+template <typename Char, typename Handler>
+FMT_CONSTEXPR const Char* parse_chrono_format(const Char* begin,
+                                              const Char* end,
+                                              Handler&& handler) {
+  auto ptr = begin;
+  while (ptr != end) {
+    auto c = *ptr;
+    if (c == '}') break;
+    if (c != '%') {
+      ++ptr;
+      continue;
+    }
+    if (begin != ptr) handler.on_text(begin, ptr);
+    ++ptr;  // consume '%'
+    if (ptr == end) FMT_THROW(format_error("invalid format"));
+    c = *ptr++;
+    switch (c) {
+    case '%':
+      handler.on_text(ptr - 1, ptr);
+      break;
+    case 'n': {
+      const Char newline[] = {'\n'};
+      handler.on_text(newline, newline + 1);
+      break;
+    }
+    case 't': {
+      const Char tab[] = {'\t'};
+      handler.on_text(tab, tab + 1);
+      break;
+    }
+    // Year:
+    case 'Y':
+      handler.on_year(numeric_system::standard);
+      break;
+    case 'y':
+      handler.on_short_year(numeric_system::standard);
+      break;
+    case 'C':
+      handler.on_century(numeric_system::standard);
+      break;
+    case 'G':
+      handler.on_iso_week_based_year();
+      break;
+    case 'g':
+      handler.on_iso_week_based_short_year();
+      break;
+    // Day of the week:
+    case 'a':
+      handler.on_abbr_weekday();
+      break;
+    case 'A':
+      handler.on_full_weekday();
+      break;
+    case 'w':
+      handler.on_dec0_weekday(numeric_system::standard);
+      break;
+    case 'u':
+      handler.on_dec1_weekday(numeric_system::standard);
+      break;
+    // Month:
+    case 'b':
+    case 'h':
+      handler.on_abbr_month();
+      break;
+    case 'B':
+      handler.on_full_month();
+      break;
+    case 'm':
+      handler.on_dec_month(numeric_system::standard);
+      break;
+    // Day of the year/month:
+    case 'U':
+      handler.on_dec0_week_of_year(numeric_system::standard);
+      break;
+    case 'W':
+      handler.on_dec1_week_of_year(numeric_system::standard);
+      break;
+    case 'V':
+      handler.on_iso_week_of_year(numeric_system::standard);
+      break;
+    case 'j':
+      handler.on_day_of_year();
+      break;
+    case 'd':
+      handler.on_day_of_month(numeric_system::standard);
+      break;
+    case 'e':
+      handler.on_day_of_month_space(numeric_system::standard);
+      break;
+    // Hour, minute, second:
+    case 'H':
+      handler.on_24_hour(numeric_system::standard);
+      break;
+    case 'I':
+      handler.on_12_hour(numeric_system::standard);
+      break;
+    case 'M':
+      handler.on_minute(numeric_system::standard);
+      break;
+    case 'S':
+      handler.on_second(numeric_system::standard);
+      break;
+    // Other:
+    case 'c':
+      handler.on_datetime(numeric_system::standard);
+      break;
+    case 'x':
+      handler.on_loc_date(numeric_system::standard);
+      break;
+    case 'X':
+      handler.on_loc_time(numeric_system::standard);
+      break;
+    case 'D':
+      handler.on_us_date();
+      break;
+    case 'F':
+      handler.on_iso_date();
+      break;
+    case 'r':
+      handler.on_12_hour_time();
+      break;
+    case 'R':
+      handler.on_24_hour_time();
+      break;
+    case 'T':
+      handler.on_iso_time();
+      break;
+    case 'p':
+      handler.on_am_pm();
+      break;
+    case 'Q':
+      handler.on_duration_value();
+      break;
+    case 'q':
+      handler.on_duration_unit();
+      break;
+    case 'z':
+      handler.on_utc_offset();
+      break;
+    case 'Z':
+      handler.on_tz_name();
+      break;
+    // Alternative representation:
+    case 'E': {
+      if (ptr == end) FMT_THROW(format_error("invalid format"));
+      c = *ptr++;
+      switch (c) {
+      case 'Y':
+        handler.on_year(numeric_system::alternative);
+        break;
+      case 'y':
+        handler.on_offset_year();
+        break;
+      case 'C':
+        handler.on_century(numeric_system::alternative);
+        break;
+      case 'c':
+        handler.on_datetime(numeric_system::alternative);
+        break;
+      case 'x':
+        handler.on_loc_date(numeric_system::alternative);
+        break;
+      case 'X':
+        handler.on_loc_time(numeric_system::alternative);
+        break;
+      default:
+        FMT_THROW(format_error("invalid format"));
+      }
+      break;
+    }
+    case 'O':
+      if (ptr == end) FMT_THROW(format_error("invalid format"));
+      c = *ptr++;
+      switch (c) {
+      case 'y':
+        handler.on_short_year(numeric_system::alternative);
+        break;
+      case 'm':
+        handler.on_dec_month(numeric_system::alternative);
+        break;
+      case 'U':
+        handler.on_dec0_week_of_year(numeric_system::alternative);
+        break;
+      case 'W':
+        handler.on_dec1_week_of_year(numeric_system::alternative);
+        break;
+      case 'V':
+        handler.on_iso_week_of_year(numeric_system::alternative);
+        break;
+      case 'd':
+        handler.on_day_of_month(numeric_system::alternative);
+        break;
+      case 'e':
+        handler.on_day_of_month_space(numeric_system::alternative);
+        break;
+      case 'w':
+        handler.on_dec0_weekday(numeric_system::alternative);
+        break;
+      case 'u':
+        handler.on_dec1_weekday(numeric_system::alternative);
+        break;
+      case 'H':
+        handler.on_24_hour(numeric_system::alternative);
+        break;
+      case 'I':
+        handler.on_12_hour(numeric_system::alternative);
+        break;
+      case 'M':
+        handler.on_minute(numeric_system::alternative);
+        break;
+      case 'S':
+        handler.on_second(numeric_system::alternative);
+        break;
+      default:
+        FMT_THROW(format_error("invalid format"));
+      }
+      break;
+    default:
+      FMT_THROW(format_error("invalid format"));
+    }
+    begin = ptr;
+  }
+  if (begin != ptr) handler.on_text(begin, ptr);
+  return ptr;
+}
+
+template <typename Derived> struct null_chrono_spec_handler {
+  FMT_CONSTEXPR void unsupported() {
+    static_cast<Derived*>(this)->unsupported();
+  }
+  FMT_CONSTEXPR void on_year(numeric_system) { unsupported(); }
+  FMT_CONSTEXPR void on_short_year(numeric_system) { unsupported(); }
+  FMT_CONSTEXPR void on_offset_year() { unsupported(); }
+  FMT_CONSTEXPR void on_century(numeric_system) { unsupported(); }
+  FMT_CONSTEXPR void on_iso_week_based_year() { unsupported(); }
+  FMT_CONSTEXPR void on_iso_week_based_short_year() { unsupported(); }
+  FMT_CONSTEXPR void on_abbr_weekday() { unsupported(); }
+  FMT_CONSTEXPR void on_full_weekday() { unsupported(); }
+  FMT_CONSTEXPR void on_dec0_weekday(numeric_system) { unsupported(); }
+  FMT_CONSTEXPR void on_dec1_weekday(numeric_system) { unsupported(); }
+  FMT_CONSTEXPR void on_abbr_month() { unsupported(); }
+  FMT_CONSTEXPR void on_full_month() { unsupported(); }
+  FMT_CONSTEXPR void on_dec_month(numeric_system) { unsupported(); }
+  FMT_CONSTEXPR void on_dec0_week_of_year(numeric_system) { unsupported(); }
+  FMT_CONSTEXPR void on_dec1_week_of_year(numeric_system) { unsupported(); }
+  FMT_CONSTEXPR void on_iso_week_of_year(numeric_system) { unsupported(); }
+  FMT_CONSTEXPR void on_day_of_year() { unsupported(); }
+  FMT_CONSTEXPR void on_day_of_month(numeric_system) { unsupported(); }
+  FMT_CONSTEXPR void on_day_of_month_space(numeric_system) { unsupported(); }
+  FMT_CONSTEXPR void on_24_hour(numeric_system) { unsupported(); }
+  FMT_CONSTEXPR void on_12_hour(numeric_system) { unsupported(); }
+  FMT_CONSTEXPR void on_minute(numeric_system) { unsupported(); }
+  FMT_CONSTEXPR void on_second(numeric_system) { unsupported(); }
+  FMT_CONSTEXPR void on_datetime(numeric_system) { unsupported(); }
+  FMT_CONSTEXPR void on_loc_date(numeric_system) { unsupported(); }
+  FMT_CONSTEXPR void on_loc_time(numeric_system) { unsupported(); }
+  FMT_CONSTEXPR void on_us_date() { unsupported(); }
+  FMT_CONSTEXPR void on_iso_date() { unsupported(); }
+  FMT_CONSTEXPR void on_12_hour_time() { unsupported(); }
+  FMT_CONSTEXPR void on_24_hour_time() { unsupported(); }
+  FMT_CONSTEXPR void on_iso_time() { unsupported(); }
+  FMT_CONSTEXPR void on_am_pm() { unsupported(); }
+  FMT_CONSTEXPR void on_duration_value() { unsupported(); }
+  FMT_CONSTEXPR void on_duration_unit() { unsupported(); }
+  FMT_CONSTEXPR void on_utc_offset() { unsupported(); }
+  FMT_CONSTEXPR void on_tz_name() { unsupported(); }
+};
+
+struct tm_format_checker : null_chrono_spec_handler<tm_format_checker> {
+  FMT_NORETURN void unsupported() { FMT_THROW(format_error("no format")); }
+
+  template <typename Char>
+  FMT_CONSTEXPR void on_text(const Char*, const Char*) {}
+  FMT_CONSTEXPR void on_year(numeric_system) {}
+  FMT_CONSTEXPR void on_short_year(numeric_system) {}
+  FMT_CONSTEXPR void on_offset_year() {}
+  FMT_CONSTEXPR void on_century(numeric_system) {}
+  FMT_CONSTEXPR void on_iso_week_based_year() {}
+  FMT_CONSTEXPR void on_iso_week_based_short_year() {}
+  FMT_CONSTEXPR void on_abbr_weekday() {}
+  FMT_CONSTEXPR void on_full_weekday() {}
+  FMT_CONSTEXPR void on_dec0_weekday(numeric_system) {}
+  FMT_CONSTEXPR void on_dec1_weekday(numeric_system) {}
+  FMT_CONSTEXPR void on_abbr_month() {}
+  FMT_CONSTEXPR void on_full_month() {}
+  FMT_CONSTEXPR void on_dec_month(numeric_system) {}
+  FMT_CONSTEXPR void on_dec0_week_of_year(numeric_system) {}
+  FMT_CONSTEXPR void on_dec1_week_of_year(numeric_system) {}
+  FMT_CONSTEXPR void on_iso_week_of_year(numeric_system) {}
+  FMT_CONSTEXPR void on_day_of_year() {}
+  FMT_CONSTEXPR void on_day_of_month(numeric_system) {}
+  FMT_CONSTEXPR void on_day_of_month_space(numeric_system) {}
+  FMT_CONSTEXPR void on_24_hour(numeric_system) {}
+  FMT_CONSTEXPR void on_12_hour(numeric_system) {}
+  FMT_CONSTEXPR void on_minute(numeric_system) {}
+  FMT_CONSTEXPR void on_second(numeric_system) {}
+  FMT_CONSTEXPR void on_datetime(numeric_system) {}
+  FMT_CONSTEXPR void on_loc_date(numeric_system) {}
+  FMT_CONSTEXPR void on_loc_time(numeric_system) {}
+  FMT_CONSTEXPR void on_us_date() {}
+  FMT_CONSTEXPR void on_iso_date() {}
+  FMT_CONSTEXPR void on_12_hour_time() {}
+  FMT_CONSTEXPR void on_24_hour_time() {}
+  FMT_CONSTEXPR void on_iso_time() {}
+  FMT_CONSTEXPR void on_am_pm() {}
+  FMT_CONSTEXPR void on_utc_offset() {}
+  FMT_CONSTEXPR void on_tz_name() {}
+};
+
+inline const char* tm_wday_full_name(int wday) {
+  static constexpr const char* full_name_list[] = {
+      "Sunday",   "Monday", "Tuesday", "Wednesday",
+      "Thursday", "Friday", "Saturday"};
+  return wday >= 0 && wday <= 6 ? full_name_list[wday] : "?";
+}
+inline const char* tm_wday_short_name(int wday) {
+  static constexpr const char* short_name_list[] = {"Sun", "Mon", "Tue", "Wed",
+                                                    "Thu", "Fri", "Sat"};
+  return wday >= 0 && wday <= 6 ? short_name_list[wday] : "???";
+}
+
+inline const char* tm_mon_full_name(int mon) {
+  static constexpr const char* full_name_list[] = {
+      "January", "February", "March",     "April",   "May",      "June",
+      "July",    "August",   "September", "October", "November", "December"};
+  return mon >= 0 && mon <= 11 ? full_name_list[mon] : "?";
+}
+inline const char* tm_mon_short_name(int mon) {
+  static constexpr const char* short_name_list[] = {
+      "Jan", "Feb", "Mar", "Apr", "May", "Jun",
+      "Jul", "Aug", "Sep", "Oct", "Nov", "Dec",
+  };
+  return mon >= 0 && mon <= 11 ? short_name_list[mon] : "???";
+}
+
+template <typename T, typename = void>
+struct has_member_data_tm_gmtoff : std::false_type {};
+template <typename T>
+struct has_member_data_tm_gmtoff<T, void_t<decltype(T::tm_gmtoff)>>
+    : std::true_type {};
+
+template <typename T, typename = void>
+struct has_member_data_tm_zone : std::false_type {};
+template <typename T>
+struct has_member_data_tm_zone<T, void_t<decltype(T::tm_zone)>>
+    : std::true_type {};
+
+#if FMT_USE_TZSET
+inline void tzset_once() {
+  static bool init = []() -> bool {
+    _tzset();
+    return true;
+  }();
+  ignore_unused(init);
+}
+#endif
+
+template <typename OutputIt, typename Char> class tm_writer {
+ private:
+  static constexpr int days_per_week = 7;
+
+  const std::locale& loc_;
+  const bool is_classic_;
+  OutputIt out_;
+  const std::tm& tm_;
+
+  auto tm_sec() const noexcept -> int {
+    FMT_ASSERT(tm_.tm_sec >= 0 && tm_.tm_sec <= 61, "");
+    return tm_.tm_sec;
+  }
+  auto tm_min() const noexcept -> int {
+    FMT_ASSERT(tm_.tm_min >= 0 && tm_.tm_min <= 59, "");
+    return tm_.tm_min;
+  }
+  auto tm_hour() const noexcept -> int {
+    FMT_ASSERT(tm_.tm_hour >= 0 && tm_.tm_hour <= 23, "");
+    return tm_.tm_hour;
+  }
+  auto tm_mday() const noexcept -> int {
+    FMT_ASSERT(tm_.tm_mday >= 1 && tm_.tm_mday <= 31, "");
+    return tm_.tm_mday;
+  }
+  auto tm_mon() const noexcept -> int {
+    FMT_ASSERT(tm_.tm_mon >= 0 && tm_.tm_mon <= 11, "");
+    return tm_.tm_mon;
+  }
+  auto tm_year() const noexcept -> long long { return 1900ll + tm_.tm_year; }
+  auto tm_wday() const noexcept -> int {
+    FMT_ASSERT(tm_.tm_wday >= 0 && tm_.tm_wday <= 6, "");
+    return tm_.tm_wday;
+  }
+  auto tm_yday() const noexcept -> int {
+    FMT_ASSERT(tm_.tm_yday >= 0 && tm_.tm_yday <= 365, "");
+    return tm_.tm_yday;
+  }
+
+  auto tm_hour12() const noexcept -> int {
+    const auto h = tm_hour();
+    const auto z = h < 12 ? h : h - 12;
+    return z == 0 ? 12 : z;
+  }
+
+  // POSIX and the C Standard are unclear or inconsistent about what %C and %y
+  // do if the year is negative or exceeds 9999. Use the convention that %C
+  // concatenated with %y yields the same output as %Y, and that %Y contains at
+  // least 4 characters, with more only if necessary.
+  auto split_year_lower(long long year) const noexcept -> int {
+    auto l = year % 100;
+    if (l < 0) l = -l;  // l in [0, 99]
+    return static_cast<int>(l);
+  }
+
+  // Algorithm:
+  // https://en.wikipedia.org/wiki/ISO_week_date#Calculating_the_week_number_from_a_month_and_day_of_the_month_or_ordinal_date
+  auto iso_year_weeks(long long curr_year) const noexcept -> int {
+    const auto prev_year = curr_year - 1;
+    const auto curr_p =
+        (curr_year + curr_year / 4 - curr_year / 100 + curr_year / 400) %
+        days_per_week;
+    const auto prev_p =
+        (prev_year + prev_year / 4 - prev_year / 100 + prev_year / 400) %
+        days_per_week;
+    return 52 + ((curr_p == 4 || prev_p == 3) ? 1 : 0);
+  }
+  auto iso_week_num(int tm_yday, int tm_wday) const noexcept -> int {
+    return (tm_yday + 11 - (tm_wday == 0 ? days_per_week : tm_wday)) /
+           days_per_week;
+  }
+  auto tm_iso_week_year() const noexcept -> long long {
+    const auto year = tm_year();
+    const auto w = iso_week_num(tm_yday(), tm_wday());
+    if (w < 1) return year - 1;
+    if (w > iso_year_weeks(year)) return year + 1;
+    return year;
+  }
+  auto tm_iso_week_of_year() const noexcept -> int {
+    const auto year = tm_year();
+    const auto w = iso_week_num(tm_yday(), tm_wday());
+    if (w < 1) return iso_year_weeks(year - 1);
+    if (w > iso_year_weeks(year)) return 1;
+    return w;
+  }
+
+  void write1(int value) {
+    *out_++ = static_cast<char>('0' + to_unsigned(value) % 10);
+  }
+  void write2(int value) {
+    const char* d = digits2(to_unsigned(value) % 100);
+    *out_++ = *d++;
+    *out_++ = *d;
+  }
+
+  void write_year_extended(long long year) {
+    // At least 4 characters.
+    int width = 4;
+    if (year < 0) {
+      *out_++ = '-';
+      year = 0 - year;
+      --width;
+    }
+    uint32_or_64_or_128_t<long long> n = to_unsigned(year);
+    const int num_digits = count_digits(n);
+    if (width > num_digits) out_ = std::fill_n(out_, width - num_digits, '0');
+    out_ = format_decimal<Char>(out_, n, num_digits).end;
+  }
+  void write_year(long long year) {
+    if (year >= 0 && year < 10000) {
+      write2(static_cast<int>(year / 100));
+      write2(static_cast<int>(year % 100));
+    } else {
+      write_year_extended(year);
+    }
+  }
+
+  void write_utc_offset(long offset) {
+    if (offset < 0) {
+      *out_++ = '-';
+      offset = -offset;
+    } else {
+      *out_++ = '+';
+    }
+    offset /= 60;
+    write2(static_cast<int>(offset / 60));
+    write2(static_cast<int>(offset % 60));
+  }
+  template <typename T, FMT_ENABLE_IF(has_member_data_tm_gmtoff<T>::value)>
+  void format_utc_offset_impl(const T& tm) {
+    write_utc_offset(tm.tm_gmtoff);
+  }
+  template <typename T, FMT_ENABLE_IF(!has_member_data_tm_gmtoff<T>::value)>
+  void format_utc_offset_impl(const T& tm) {
+#if defined(_WIN32) && defined(_UCRT)
+#  if FMT_USE_TZSET
+    tzset_once();
+#  endif
+    long offset = 0;
+    _get_timezone(&offset);
+    if (tm.tm_isdst) {
+      long dstbias = 0;
+      _get_dstbias(&dstbias);
+      offset += dstbias;
+    }
+    write_utc_offset(-offset);
+#else
+    ignore_unused(tm);
+    format_localized('z');
+#endif
+  }
+
+  template <typename T, FMT_ENABLE_IF(has_member_data_tm_zone<T>::value)>
+  void format_tz_name_impl(const T& tm) {
+    if (is_classic_)
+      out_ = write_tm_str<Char>(out_, tm.tm_zone, loc_);
+    else
+      format_localized('Z');
+  }
+  template <typename T, FMT_ENABLE_IF(!has_member_data_tm_zone<T>::value)>
+  void format_tz_name_impl(const T&) {
+    format_localized('Z');
+  }
+
+  void format_localized(char format, char modifier = 0) {
+    out_ = write<Char>(out_, tm_, loc_, format, modifier);
+  }
+
+ public:
+  tm_writer(const std::locale& loc, OutputIt out, const std::tm& tm)
+      : loc_(loc),
+        is_classic_(loc_ == get_classic_locale()),
+        out_(out),
+        tm_(tm) {}
+
+  OutputIt out() const { return out_; }
+
+  FMT_CONSTEXPR void on_text(const Char* begin, const Char* end) {
+    out_ = copy_str<Char>(begin, end, out_);
+  }
+
+  void on_abbr_weekday() {
+    if (is_classic_)
+      out_ = write(out_, tm_wday_short_name(tm_wday()));
+    else
+      format_localized('a');
+  }
+  void on_full_weekday() {
+    if (is_classic_)
+      out_ = write(out_, tm_wday_full_name(tm_wday()));
+    else
+      format_localized('A');
+  }
+  void on_dec0_weekday(numeric_system ns) {
+    if (is_classic_ || ns == numeric_system::standard) return write1(tm_wday());
+    format_localized('w', 'O');
+  }
+  void on_dec1_weekday(numeric_system ns) {
+    if (is_classic_ || ns == numeric_system::standard) {
+      auto wday = tm_wday();
+      write1(wday == 0 ? days_per_week : wday);
+    } else {
+      format_localized('u', 'O');
+    }
+  }
+
+  void on_abbr_month() {
+    if (is_classic_)
+      out_ = write(out_, tm_mon_short_name(tm_mon()));
+    else
+      format_localized('b');
+  }
+  void on_full_month() {
+    if (is_classic_)
+      out_ = write(out_, tm_mon_full_name(tm_mon()));
+    else
+      format_localized('B');
+  }
+
+  void on_datetime(numeric_system ns) {
+    if (is_classic_) {
+      on_abbr_weekday();
+      *out_++ = ' ';
+      on_abbr_month();
+      *out_++ = ' ';
+      on_day_of_month_space(numeric_system::standard);
+      *out_++ = ' ';
+      on_iso_time();
+      *out_++ = ' ';
+      on_year(numeric_system::standard);
+    } else {
+      format_localized('c', ns == numeric_system::standard ? '\0' : 'E');
+    }
+  }
+  void on_loc_date(numeric_system ns) {
+    if (is_classic_)
+      on_us_date();
+    else
+      format_localized('x', ns == numeric_system::standard ? '\0' : 'E');
+  }
+  void on_loc_time(numeric_system ns) {
+    if (is_classic_)
+      on_iso_time();
+    else
+      format_localized('X', ns == numeric_system::standard ? '\0' : 'E');
+  }
+  void on_us_date() {
+    char buf[8];
+    write_digit2_separated(buf, to_unsigned(tm_mon() + 1),
+                           to_unsigned(tm_mday()),
+                           to_unsigned(split_year_lower(tm_year())), '/');
+    out_ = copy_str<Char>(std::begin(buf), std::end(buf), out_);
+  }
+  void on_iso_date() {
+    auto year = tm_year();
+    char buf[10];
+    size_t offset = 0;
+    if (year >= 0 && year < 10000) {
+      copy2(buf, digits2(static_cast<size_t>(year / 100)));
+    } else {
+      offset = 4;
+      write_year_extended(year);
+      year = 0;
+    }
+    write_digit2_separated(buf + 2, static_cast<unsigned>(year % 100),
+                           to_unsigned(tm_mon() + 1), to_unsigned(tm_mday()),
+                           '-');
+    out_ = copy_str<Char>(std::begin(buf) + offset, std::end(buf), out_);
+  }
+
+  void on_utc_offset() { format_utc_offset_impl(tm_); }
+  void on_tz_name() { format_tz_name_impl(tm_); }
+
+  void on_year(numeric_system ns) {
+    if (is_classic_ || ns == numeric_system::standard)
+      return write_year(tm_year());
+    format_localized('Y', 'E');
+  }
+  void on_short_year(numeric_system ns) {
+    if (is_classic_ || ns == numeric_system::standard)
+      return write2(split_year_lower(tm_year()));
+    format_localized('y', 'O');
+  }
+  void on_offset_year() {
+    if (is_classic_) return write2(split_year_lower(tm_year()));
+    format_localized('y', 'E');
+  }
+
+  void on_century(numeric_system ns) {
+    if (is_classic_ || ns == numeric_system::standard) {
+      auto year = tm_year();
+      auto upper = year / 100;
+      if (year >= -99 && year < 0) {
+        // Zero upper on negative year.
+        *out_++ = '-';
+        *out_++ = '0';
+      } else if (upper >= 0 && upper < 100) {
+        write2(static_cast<int>(upper));
+      } else {
+        out_ = write<Char>(out_, upper);
+      }
+    } else {
+      format_localized('C', 'E');
+    }
+  }
+
+  void on_dec_month(numeric_system ns) {
+    if (is_classic_ || ns == numeric_system::standard)
+      return write2(tm_mon() + 1);
+    format_localized('m', 'O');
+  }
+
+  void on_dec0_week_of_year(numeric_system ns) {
+    if (is_classic_ || ns == numeric_system::standard)
+      return write2((tm_yday() + days_per_week - tm_wday()) / days_per_week);
+    format_localized('U', 'O');
+  }
+  void on_dec1_week_of_year(numeric_system ns) {
+    if (is_classic_ || ns == numeric_system::standard) {
+      auto wday = tm_wday();
+      write2((tm_yday() + days_per_week -
+              (wday == 0 ? (days_per_week - 1) : (wday - 1))) /
+             days_per_week);
+    } else {
+      format_localized('W', 'O');
+    }
+  }
+  void on_iso_week_of_year(numeric_system ns) {
+    if (is_classic_ || ns == numeric_system::standard)
+      return write2(tm_iso_week_of_year());
+    format_localized('V', 'O');
+  }
+
+  void on_iso_week_based_year() { write_year(tm_iso_week_year()); }
+  void on_iso_week_based_short_year() {
+    write2(split_year_lower(tm_iso_week_year()));
+  }
+
+  void on_day_of_year() {
+    auto yday = tm_yday() + 1;
+    write1(yday / 100);
+    write2(yday % 100);
+  }
+  void on_day_of_month(numeric_system ns) {
+    if (is_classic_ || ns == numeric_system::standard) return write2(tm_mday());
+    format_localized('d', 'O');
+  }
+  void on_day_of_month_space(numeric_system ns) {
+    if (is_classic_ || ns == numeric_system::standard) {
+      auto mday = to_unsigned(tm_mday()) % 100;
+      const char* d2 = digits2(mday);
+      *out_++ = mday < 10 ? ' ' : d2[0];
+      *out_++ = d2[1];
+    } else {
+      format_localized('e', 'O');
+    }
+  }
+
+  void on_24_hour(numeric_system ns) {
+    if (is_classic_ || ns == numeric_system::standard) return write2(tm_hour());
+    format_localized('H', 'O');
+  }
+  void on_12_hour(numeric_system ns) {
+    if (is_classic_ || ns == numeric_system::standard)
+      return write2(tm_hour12());
+    format_localized('I', 'O');
+  }
+  void on_minute(numeric_system ns) {
+    if (is_classic_ || ns == numeric_system::standard) return write2(tm_min());
+    format_localized('M', 'O');
+  }
+  void on_second(numeric_system ns) {
+    if (is_classic_ || ns == numeric_system::standard) return write2(tm_sec());
+    format_localized('S', 'O');
+  }
+
+  void on_12_hour_time() {
+    if (is_classic_) {
+      char buf[8];
+      write_digit2_separated(buf, to_unsigned(tm_hour12()),
+                             to_unsigned(tm_min()), to_unsigned(tm_sec()), ':');
+      out_ = copy_str<Char>(std::begin(buf), std::end(buf), out_);
+      *out_++ = ' ';
+      on_am_pm();
+    } else {
+      format_localized('r');
+    }
+  }
+  void on_24_hour_time() {
+    write2(tm_hour());
+    *out_++ = ':';
+    write2(tm_min());
+  }
+  void on_iso_time() {
+    char buf[8];
+    write_digit2_separated(buf, to_unsigned(tm_hour()), to_unsigned(tm_min()),
+                           to_unsigned(tm_sec()), ':');
+    out_ = copy_str<Char>(std::begin(buf), std::end(buf), out_);
+  }
+
+  void on_am_pm() {
+    if (is_classic_) {
+      *out_++ = tm_hour() < 12 ? 'A' : 'P';
+      *out_++ = 'M';
+    } else {
+      format_localized('p');
+    }
+  }
+
+  // These apply to chrono durations but not tm.
+  void on_duration_value() {}
+  void on_duration_unit() {}
+};
+
+struct chrono_format_checker : null_chrono_spec_handler<chrono_format_checker> {
+  FMT_NORETURN void unsupported() { FMT_THROW(format_error("no date")); }
+
+  template <typename Char>
+  FMT_CONSTEXPR void on_text(const Char*, const Char*) {}
+  FMT_CONSTEXPR void on_24_hour(numeric_system) {}
+  FMT_CONSTEXPR void on_12_hour(numeric_system) {}
+  FMT_CONSTEXPR void on_minute(numeric_system) {}
+  FMT_CONSTEXPR void on_second(numeric_system) {}
+  FMT_CONSTEXPR void on_12_hour_time() {}
+  FMT_CONSTEXPR void on_24_hour_time() {}
+  FMT_CONSTEXPR void on_iso_time() {}
+  FMT_CONSTEXPR void on_am_pm() {}
+  FMT_CONSTEXPR void on_duration_value() {}
+  FMT_CONSTEXPR void on_duration_unit() {}
+};
+
+template <typename T, FMT_ENABLE_IF(std::is_integral<T>::value)>
+inline bool isfinite(T) {
+  return true;
+}
+
+// Converts value to Int and checks that it's in the range [0, upper).
+template <typename T, typename Int, FMT_ENABLE_IF(std::is_integral<T>::value)>
+inline Int to_nonnegative_int(T value, Int upper) {
+  FMT_ASSERT(std::is_unsigned<Int>::value ||
+             (value >= 0 && to_unsigned(value) <= to_unsigned(upper)),
+             "invalid value");
+  (void)upper;
+  return static_cast<Int>(value);
+}
+template <typename T, typename Int, FMT_ENABLE_IF(!std::is_integral<T>::value)>
+inline Int to_nonnegative_int(T value, Int upper) {
+  if (value < 0 || value > static_cast<T>(upper))
+    FMT_THROW(format_error("invalid value"));
+  return static_cast<Int>(value);
+}
+
+template <typename T, FMT_ENABLE_IF(std::is_integral<T>::value)>
+inline T mod(T x, int y) {
+  return x % static_cast<T>(y);
+}
+template <typename T, FMT_ENABLE_IF(std::is_floating_point<T>::value)>
+inline T mod(T x, int y) {
+  return std::fmod(x, static_cast<T>(y));
+}
+
+// If T is an integral type, maps T to its unsigned counterpart, otherwise
+// leaves it unchanged (unlike std::make_unsigned).
+template <typename T, bool INTEGRAL = std::is_integral<T>::value>
+struct make_unsigned_or_unchanged {
+  using type = T;
+};
+
+template <typename T> struct make_unsigned_or_unchanged<T, true> {
+  using type = typename std::make_unsigned<T>::type;
+};
+
+#if FMT_SAFE_DURATION_CAST
+// throwing version of safe_duration_cast
+template <typename To, typename FromRep, typename FromPeriod>
+To fmt_safe_duration_cast(std::chrono::duration<FromRep, FromPeriod> from) {
+  int ec;
+  To to = safe_duration_cast::safe_duration_cast<To>(from, ec);
+  if (ec) FMT_THROW(format_error("cannot format duration"));
+  return to;
+}
+#endif
+
+template <typename Rep, typename Period,
+          FMT_ENABLE_IF(std::is_integral<Rep>::value)>
+inline std::chrono::duration<Rep, std::milli> get_milliseconds(
+    std::chrono::duration<Rep, Period> d) {
+  // this may overflow and/or the result may not fit in the
+  // target type.
+#if FMT_SAFE_DURATION_CAST
+  using CommonSecondsType =
+      typename std::common_type<decltype(d), std::chrono::seconds>::type;
+  const auto d_as_common = fmt_safe_duration_cast<CommonSecondsType>(d);
+  const auto d_as_whole_seconds =
+      fmt_safe_duration_cast<std::chrono::seconds>(d_as_common);
+  // this conversion should be nonproblematic
+  const auto diff = d_as_common - d_as_whole_seconds;
+  const auto ms =
+      fmt_safe_duration_cast<std::chrono::duration<Rep, std::milli>>(diff);
+  return ms;
+#else
+  auto s = std::chrono::duration_cast<std::chrono::seconds>(d);
+  return std::chrono::duration_cast<std::chrono::milliseconds>(d - s);
+#endif
+}
+
+// Counts the number of fractional digits in the range [0, 18] according to the
+// C++20 spec. If more than 18 fractional digits are required then returns 6 for
+// microseconds precision.
+template <long long Num, long long Den, int N = 0,
+          bool Enabled = (N < 19) && (Num <= max_value<long long>() / 10)>
+struct count_fractional_digits {
+  static constexpr int value =
+      Num % Den == 0 ? N : count_fractional_digits<Num * 10, Den, N + 1>::value;
+};
+
+// Base case that doesn't instantiate any more templates
+// in order to avoid overflow.
+template <long long Num, long long Den, int N>
+struct count_fractional_digits<Num, Den, N, false> {
+  static constexpr int value = (Num % Den == 0) ? N : 6;
+};
+
+constexpr long long pow10(std::uint32_t n) {
+  return n == 0 ? 1 : 10 * pow10(n - 1);
+}
+
+template <class Rep, class Period,
+          FMT_ENABLE_IF(std::numeric_limits<Rep>::is_signed)>
+constexpr std::chrono::duration<Rep, Period> abs(
+    std::chrono::duration<Rep, Period> d) {
+  // We need to compare the duration using the count() method directly
+  // due to a compiler bug in clang-11 regarding the spaceship operator,
+  // when -Wzero-as-null-pointer-constant is enabled.
+  // In clang-12 the bug has been fixed. See
+  // https://bugs.llvm.org/show_bug.cgi?id=46235 and the reproducible example:
+  // https://www.godbolt.org/z/Knbb5joYx.
+  return d.count() >= d.zero().count() ? d : -d;
+}
+
+template <class Rep, class Period,
+          FMT_ENABLE_IF(!std::numeric_limits<Rep>::is_signed)>
+constexpr std::chrono::duration<Rep, Period> abs(
+    std::chrono::duration<Rep, Period> d) {
+  return d;
+}
+
+template <typename Char, typename Rep, typename OutputIt,
+          FMT_ENABLE_IF(std::is_integral<Rep>::value)>
+OutputIt format_duration_value(OutputIt out, Rep val, int) {
+  return write<Char>(out, val);
+}
+
+template <typename Char, typename Rep, typename OutputIt,
+          FMT_ENABLE_IF(std::is_floating_point<Rep>::value)>
+OutputIt format_duration_value(OutputIt out, Rep val, int precision) {
+  auto specs = basic_format_specs<Char>();
+  specs.precision = precision;
+  specs.type = precision >= 0 ? presentation_type::fixed_lower
+                              : presentation_type::general_lower;
+  return write<Char>(out, val, specs);
+}
+
+template <typename Char, typename OutputIt>
+OutputIt copy_unit(string_view unit, OutputIt out, Char) {
+  return std::copy(unit.begin(), unit.end(), out);
+}
+
+template <typename OutputIt>
+OutputIt copy_unit(string_view unit, OutputIt out, wchar_t) {
+  // This works when wchar_t is UTF-32 because units only contain characters
+  // that have the same representation in UTF-16 and UTF-32.
+  utf8_to_utf16 u(unit);
+  return std::copy(u.c_str(), u.c_str() + u.size(), out);
+}
+
+template <typename Char, typename Period, typename OutputIt>
+OutputIt format_duration_unit(OutputIt out) {
+  if (const char* unit = get_units<Period>())
+    return copy_unit(string_view(unit), out, Char());
+  *out++ = '[';
+  out = write<Char>(out, Period::num);
+  if (const_check(Period::den != 1)) {
+    *out++ = '/';
+    out = write<Char>(out, Period::den);
+  }
+  *out++ = ']';
+  *out++ = 's';
+  return out;
+}
+
+class get_locale {
+ private:
+  union {
+    std::locale locale_;
+  };
+  bool has_locale_ = false;
+
+ public:
+  get_locale(bool localized, locale_ref loc) : has_locale_(localized) {
+    if (localized)
+      ::new (&locale_) std::locale(loc.template get<std::locale>());
+  }
+  ~get_locale() {
+    if (has_locale_) locale_.~locale();
+  }
+  operator const std::locale&() const {
+    return has_locale_ ? locale_ : get_classic_locale();
+  }
+};
+
+template <typename FormatContext, typename OutputIt, typename Rep,
+          typename Period>
+struct chrono_formatter {
+  FormatContext& context;
+  OutputIt out;
+  int precision;
+  bool localized = false;
+  // rep is unsigned to avoid overflow.
+  using rep =
+      conditional_t<std::is_integral<Rep>::value && sizeof(Rep) < sizeof(int),
+                    unsigned, typename make_unsigned_or_unchanged<Rep>::type>;
+  rep val;
+  using seconds = std::chrono::duration<rep>;
+  seconds s;
+  using milliseconds = std::chrono::duration<rep, std::milli>;
+  bool negative;
+
+  using char_type = typename FormatContext::char_type;
+  using tm_writer_type = tm_writer<OutputIt, char_type>;
+
+  chrono_formatter(FormatContext& ctx, OutputIt o,
+                   std::chrono::duration<Rep, Period> d)
+      : context(ctx),
+        out(o),
+        val(static_cast<rep>(d.count())),
+        negative(false) {
+    if (d.count() < 0) {
+      val = 0 - val;
+      negative = true;
+    }
+
+    // this may overflow and/or the result may not fit in the
+    // target type.
+#if FMT_SAFE_DURATION_CAST
+    // might need checked conversion (rep!=Rep)
+    auto tmpval = std::chrono::duration<rep, Period>(val);
+    s = fmt_safe_duration_cast<seconds>(tmpval);
+#else
+    s = std::chrono::duration_cast<seconds>(
+        std::chrono::duration<rep, Period>(val));
+#endif
+  }
+
+  // returns true if nan or inf, writes to out.
+  bool handle_nan_inf() {
+    if (isfinite(val)) {
+      return false;
+    }
+    if (isnan(val)) {
+      write_nan();
+      return true;
+    }
+    // must be +-inf
+    if (val > 0) {
+      write_pinf();
+    } else {
+      write_ninf();
+    }
+    return true;
+  }
+
+  Rep hour() const { return static_cast<Rep>(mod((s.count() / 3600), 24)); }
+
+  Rep hour12() const {
+    Rep hour = static_cast<Rep>(mod((s.count() / 3600), 12));
+    return hour <= 0 ? 12 : hour;
+  }
+
+  Rep minute() const { return static_cast<Rep>(mod((s.count() / 60), 60)); }
+  Rep second() const { return static_cast<Rep>(mod(s.count(), 60)); }
+
+  std::tm time() const {
+    auto time = std::tm();
+    time.tm_hour = to_nonnegative_int(hour(), 24);
+    time.tm_min = to_nonnegative_int(minute(), 60);
+    time.tm_sec = to_nonnegative_int(second(), 60);
+    return time;
+  }
+
+  void write_sign() {
+    if (negative) {
+      *out++ = '-';
+      negative = false;
+    }
+  }
+
+  void write(Rep value, int width) {
+    write_sign();
+    if (isnan(value)) return write_nan();
+    uint32_or_64_or_128_t<int> n =
+        to_unsigned(to_nonnegative_int(value, max_value<int>()));
+    int num_digits = detail::count_digits(n);
+    if (width > num_digits) out = std::fill_n(out, width - num_digits, '0');
+    out = format_decimal<char_type>(out, n, num_digits).end;
+  }
+
+  template <typename Duration> void write_fractional_seconds(Duration d) {
+    FMT_ASSERT(!std::is_floating_point<typename Duration::rep>::value, "");
+    constexpr auto num_fractional_digits =
+        count_fractional_digits<Duration::period::num,
+                                Duration::period::den>::value;
+
+    using subsecond_precision = std::chrono::duration<
+        typename std::common_type<typename Duration::rep,
+                                  std::chrono::seconds::rep>::type,
+        std::ratio<1, detail::pow10(num_fractional_digits)>>;
+    if (std::ratio_less<typename subsecond_precision::period,
+                        std::chrono::seconds::period>::value) {
+      *out++ = '.';
+      auto fractional =
+          detail::abs(d) - std::chrono::duration_cast<std::chrono::seconds>(d);
+      auto subseconds =
+          std::chrono::treat_as_floating_point<
+              typename subsecond_precision::rep>::value
+              ? fractional.count()
+              : std::chrono::duration_cast<subsecond_precision>(fractional)
+                    .count();
+      uint32_or_64_or_128_t<long long> n =
+          to_unsigned(to_nonnegative_int(subseconds, max_value<long long>()));
+      int num_digits = detail::count_digits(n);
+      if (num_fractional_digits > num_digits)
+        out = std::fill_n(out, num_fractional_digits - num_digits, '0');
+      out = format_decimal<char_type>(out, n, num_digits).end;
+    }
+  }
+
+  void write_nan() { std::copy_n("nan", 3, out); }
+  void write_pinf() { std::copy_n("inf", 3, out); }
+  void write_ninf() { std::copy_n("-inf", 4, out); }
+
+  template <typename Callback, typename... Args>
+  void format_tm(const tm& time, Callback cb, Args... args) {
+    if (isnan(val)) return write_nan();
+    get_locale loc(localized, context.locale());
+    auto w = tm_writer_type(loc, out, time);
+    (w.*cb)(args...);
+    out = w.out();
+  }
+
+  void on_text(const char_type* begin, const char_type* end) {
+    std::copy(begin, end, out);
+  }
+
+  // These are not implemented because durations don't have date information.
+  void on_abbr_weekday() {}
+  void on_full_weekday() {}
+  void on_dec0_weekday(numeric_system) {}
+  void on_dec1_weekday(numeric_system) {}
+  void on_abbr_month() {}
+  void on_full_month() {}
+  void on_datetime(numeric_system) {}
+  void on_loc_date(numeric_system) {}
+  void on_loc_time(numeric_system) {}
+  void on_us_date() {}
+  void on_iso_date() {}
+  void on_utc_offset() {}
+  void on_tz_name() {}
+  void on_year(numeric_system) {}
+  void on_short_year(numeric_system) {}
+  void on_offset_year() {}
+  void on_century(numeric_system) {}
+  void on_iso_week_based_year() {}
+  void on_iso_week_based_short_year() {}
+  void on_dec_month(numeric_system) {}
+  void on_dec0_week_of_year(numeric_system) {}
+  void on_dec1_week_of_year(numeric_system) {}
+  void on_iso_week_of_year(numeric_system) {}
+  void on_day_of_year() {}
+  void on_day_of_month(numeric_system) {}
+  void on_day_of_month_space(numeric_system) {}
+
+  void on_24_hour(numeric_system ns) {
+    if (handle_nan_inf()) return;
+
+    if (ns == numeric_system::standard) return write(hour(), 2);
+    auto time = tm();
+    time.tm_hour = to_nonnegative_int(hour(), 24);
+    format_tm(time, &tm_writer_type::on_24_hour, ns);
+  }
+
+  void on_12_hour(numeric_system ns) {
+    if (handle_nan_inf()) return;
+
+    if (ns == numeric_system::standard) return write(hour12(), 2);
+    auto time = tm();
+    time.tm_hour = to_nonnegative_int(hour12(), 12);
+    format_tm(time, &tm_writer_type::on_12_hour, ns);
+  }
+
+  void on_minute(numeric_system ns) {
+    if (handle_nan_inf()) return;
+
+    if (ns == numeric_system::standard) return write(minute(), 2);
+    auto time = tm();
+    time.tm_min = to_nonnegative_int(minute(), 60);
+    format_tm(time, &tm_writer_type::on_minute, ns);
+  }
+
+  void on_second(numeric_system ns) {
+    if (handle_nan_inf()) return;
+
+    if (ns == numeric_system::standard) {
+      if (std::is_floating_point<rep>::value) {
+        constexpr auto num_fractional_digits =
+            count_fractional_digits<Period::num, Period::den>::value;
+        auto buf = memory_buffer();
+        format_to(std::back_inserter(buf), runtime("{:.{}f}"),
+                  std::fmod(val * static_cast<rep>(Period::num) /
+                                static_cast<rep>(Period::den),
+                            static_cast<rep>(60)),
+                  num_fractional_digits);
+        if (negative) *out++ = '-';
+        if (buf.size() < 2 || buf[1] == '.') *out++ = '0';
+        out = std::copy(buf.begin(), buf.end(), out);
+      } else {
+        write(second(), 2);
+        write_fractional_seconds(std::chrono::duration<rep, Period>(val));
+      }
+      return;
+    }
+    auto time = tm();
+    time.tm_sec = to_nonnegative_int(second(), 60);
+    format_tm(time, &tm_writer_type::on_second, ns);
+  }
+
+  void on_12_hour_time() {
+    if (handle_nan_inf()) return;
+    format_tm(time(), &tm_writer_type::on_12_hour_time);
+  }
+
+  void on_24_hour_time() {
+    if (handle_nan_inf()) {
+      *out++ = ':';
+      handle_nan_inf();
+      return;
+    }
+
+    write(hour(), 2);
+    *out++ = ':';
+    write(minute(), 2);
+  }
+
+  void on_iso_time() {
+    on_24_hour_time();
+    *out++ = ':';
+    if (handle_nan_inf()) return;
+    on_second(numeric_system::standard);
+  }
+
+  void on_am_pm() {
+    if (handle_nan_inf()) return;
+    format_tm(time(), &tm_writer_type::on_am_pm);
+  }
+
+  void on_duration_value() {
+    if (handle_nan_inf()) return;
+    write_sign();
+    out = format_duration_value<char_type>(out, val, precision);
+  }
+
+  void on_duration_unit() {
+    out = format_duration_unit<char_type, Period>(out);
+  }
+};
+
+FMT_END_DETAIL_NAMESPACE
+
+#if defined(__cpp_lib_chrono) && __cpp_lib_chrono >= 201907
+using weekday = std::chrono::weekday;
+#else
+// A fallback version of weekday.
+class weekday {
+ private:
+  unsigned char value;
+
+ public:
+  weekday() = default;
+  explicit constexpr weekday(unsigned wd) noexcept
+      : value(static_cast<unsigned char>(wd != 7 ? wd : 0)) {}
+  constexpr unsigned c_encoding() const noexcept { return value; }
+};
+
+class year_month_day {};
+#endif
+
+// A rudimentary weekday formatter.
+template <typename Char> struct formatter<weekday, Char> {
+ private:
+  bool localized = false;
+
+ public:
+  FMT_CONSTEXPR auto parse(basic_format_parse_context<Char>& ctx)
+      -> decltype(ctx.begin()) {
+    auto begin = ctx.begin(), end = ctx.end();
+    if (begin != end && *begin == 'L') {
+      ++begin;
+      localized = true;
+    }
+    return begin;
+  }
+
+  template <typename FormatContext>
+  auto format(weekday wd, FormatContext& ctx) const -> decltype(ctx.out()) {
+    auto time = std::tm();
+    time.tm_wday = static_cast<int>(wd.c_encoding());
+    detail::get_locale loc(localized, ctx.locale());
+    auto w = detail::tm_writer<decltype(ctx.out()), Char>(loc, ctx.out(), time);
+    w.on_abbr_weekday();
+    return w.out();
+  }
+};
+
+template <typename Rep, typename Period, typename Char>
+struct formatter<std::chrono::duration<Rep, Period>, Char> {
+ private:
+  basic_format_specs<Char> specs;
+  int precision = -1;
+  using arg_ref_type = detail::arg_ref<Char>;
+  arg_ref_type width_ref;
+  arg_ref_type precision_ref;
+  bool localized = false;
+  basic_string_view<Char> format_str;
+  using duration = std::chrono::duration<Rep, Period>;
+
+  struct spec_handler {
+    formatter& f;
+    basic_format_parse_context<Char>& context;
+    basic_string_view<Char> format_str;
+
+    template <typename Id> FMT_CONSTEXPR arg_ref_type make_arg_ref(Id arg_id) {
+      context.check_arg_id(arg_id);
+      return arg_ref_type(arg_id);
+    }
+
+    FMT_CONSTEXPR arg_ref_type make_arg_ref(basic_string_view<Char> arg_id) {
+      context.check_arg_id(arg_id);
+      return arg_ref_type(arg_id);
+    }
+
+    FMT_CONSTEXPR arg_ref_type make_arg_ref(detail::auto_id) {
+      return arg_ref_type(context.next_arg_id());
+    }
+
+    void on_error(const char* msg) { FMT_THROW(format_error(msg)); }
+    FMT_CONSTEXPR void on_fill(basic_string_view<Char> fill) {
+      f.specs.fill = fill;
+    }
+    FMT_CONSTEXPR void on_align(align_t align) { f.specs.align = align; }
+    FMT_CONSTEXPR void on_width(int width) { f.specs.width = width; }
+    FMT_CONSTEXPR void on_precision(int _precision) {
+      f.precision = _precision;
+    }
+    FMT_CONSTEXPR void end_precision() {}
+
+    template <typename Id> FMT_CONSTEXPR void on_dynamic_width(Id arg_id) {
+      f.width_ref = make_arg_ref(arg_id);
+    }
+
+    template <typename Id> FMT_CONSTEXPR void on_dynamic_precision(Id arg_id) {
+      f.precision_ref = make_arg_ref(arg_id);
+    }
+  };
+
+  using iterator = typename basic_format_parse_context<Char>::iterator;
+  struct parse_range {
+    iterator begin;
+    iterator end;
+  };
+
+  FMT_CONSTEXPR parse_range do_parse(basic_format_parse_context<Char>& ctx) {
+    auto begin = ctx.begin(), end = ctx.end();
+    if (begin == end || *begin == '}') return {begin, begin};
+    spec_handler handler{*this, ctx, format_str};
+    begin = detail::parse_align(begin, end, handler);
+    if (begin == end) return {begin, begin};
+    begin = detail::parse_width(begin, end, handler);
+    if (begin == end) return {begin, begin};
+    if (*begin == '.') {
+      if (std::is_floating_point<Rep>::value)
+        begin = detail::parse_precision(begin, end, handler);
+      else
+        handler.on_error("precision not allowed for this argument type");
+    }
+    if (begin != end && *begin == 'L') {
+      ++begin;
+      localized = true;
+    }
+    end = detail::parse_chrono_format(begin, end,
+                                      detail::chrono_format_checker());
+    return {begin, end};
+  }
+
+ public:
+  FMT_CONSTEXPR auto parse(basic_format_parse_context<Char>& ctx)
+      -> decltype(ctx.begin()) {
+    auto range = do_parse(ctx);
+    format_str = basic_string_view<Char>(
+        &*range.begin, detail::to_unsigned(range.end - range.begin));
+    return range.end;
+  }
+
+  template <typename FormatContext>
+  auto format(const duration& d, FormatContext& ctx) const
+      -> decltype(ctx.out()) {
+    auto specs_copy = specs;
+    auto precision_copy = precision;
+    auto begin = format_str.begin(), end = format_str.end();
+    // As a possible future optimization, we could avoid extra copying if width
+    // is not specified.
+    basic_memory_buffer<Char> buf;
+    auto out = std::back_inserter(buf);
+    detail::handle_dynamic_spec<detail::width_checker>(specs_copy.width,
+                                                       width_ref, ctx);
+    detail::handle_dynamic_spec<detail::precision_checker>(precision_copy,
+                                                           precision_ref, ctx);
+    if (begin == end || *begin == '}') {
+      out = detail::format_duration_value<Char>(out, d.count(), precision_copy);
+      detail::format_duration_unit<Char, Period>(out);
+    } else {
+      detail::chrono_formatter<FormatContext, decltype(out), Rep, Period> f(
+          ctx, out, d);
+      f.precision = precision_copy;
+      f.localized = localized;
+      detail::parse_chrono_format(begin, end, f);
+    }
+    return detail::write(
+        ctx.out(), basic_string_view<Char>(buf.data(), buf.size()), specs_copy);
+  }
+};
+
+template <typename Char, typename Duration>
+struct formatter<std::chrono::time_point<std::chrono::system_clock, Duration>,
+                 Char> : formatter<std::tm, Char> {
+  FMT_CONSTEXPR formatter() {
+    basic_string_view<Char> default_specs =
+        detail::string_literal<Char, '%', 'F', ' ', '%', 'T'>{};
+    this->do_parse(default_specs.begin(), default_specs.end());
+  }
+
+  template <typename FormatContext>
+  auto format(std::chrono::time_point<std::chrono::system_clock> val,
+              FormatContext& ctx) const -> decltype(ctx.out()) {
+    return formatter<std::tm, Char>::format(localtime(val), ctx);
+  }
+};
+
+template <typename Char> struct formatter<std::tm, Char> {
+ private:
+  enum class spec {
+    unknown,
+    year_month_day,
+    hh_mm_ss,
+  };
+  spec spec_ = spec::unknown;
+  basic_string_view<Char> specs;
+
+ protected:
+  template <typename It> FMT_CONSTEXPR auto do_parse(It begin, It end) -> It {
+    if (begin != end && *begin == ':') ++begin;
+    end = detail::parse_chrono_format(begin, end, detail::tm_format_checker());
+    // Replace default spec only if the new spec is not empty.
+    if (end != begin) specs = {begin, detail::to_unsigned(end - begin)};
+    return end;
+  }
+
+ public:
+  FMT_CONSTEXPR auto parse(basic_format_parse_context<Char>& ctx)
+      -> decltype(ctx.begin()) {
+    auto end = this->do_parse(ctx.begin(), ctx.end());
+    // basic_string_view<>::compare isn't constexpr before C++17.
+    if (specs.size() == 2 && specs[0] == Char('%')) {
+      if (specs[1] == Char('F'))
+        spec_ = spec::year_month_day;
+      else if (specs[1] == Char('T'))
+        spec_ = spec::hh_mm_ss;
+    }
+    return end;
+  }
+
+  template <typename FormatContext>
+  auto format(const std::tm& tm, FormatContext& ctx) const
+      -> decltype(ctx.out()) {
+    const auto loc_ref = ctx.locale();
+    detail::get_locale loc(static_cast<bool>(loc_ref), loc_ref);
+    auto w = detail::tm_writer<decltype(ctx.out()), Char>(loc, ctx.out(), tm);
+    if (spec_ == spec::year_month_day)
+      w.on_iso_date();
+    else if (spec_ == spec::hh_mm_ss)
+      w.on_iso_time();
+    else
+      detail::parse_chrono_format(specs.begin(), specs.end(), w);
+    return w.out();
+  }
+};
+
+FMT_MODULE_EXPORT_END
+FMT_END_NAMESPACE
+
+#endif  // FMT_CHRONO_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/color.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/color.h
new file mode 100644
index 0000000..4c16327
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/color.h
@@ -0,0 +1,651 @@
+// Formatting library for C++ - color support
+//
+// Copyright (c) 2018 - present, Victor Zverovich and fmt contributors
+// All rights reserved.
+//
+// For the license information refer to format.h.
+
+#ifndef FMT_COLOR_H_
+#define FMT_COLOR_H_
+
+#include "format.h"
+
+FMT_BEGIN_NAMESPACE
+FMT_MODULE_EXPORT_BEGIN
+
+enum class color : uint32_t {
+  alice_blue = 0xF0F8FF,               // rgb(240,248,255)
+  antique_white = 0xFAEBD7,            // rgb(250,235,215)
+  aqua = 0x00FFFF,                     // rgb(0,255,255)
+  aquamarine = 0x7FFFD4,               // rgb(127,255,212)
+  azure = 0xF0FFFF,                    // rgb(240,255,255)
+  beige = 0xF5F5DC,                    // rgb(245,245,220)
+  bisque = 0xFFE4C4,                   // rgb(255,228,196)
+  black = 0x000000,                    // rgb(0,0,0)
+  blanched_almond = 0xFFEBCD,          // rgb(255,235,205)
+  blue = 0x0000FF,                     // rgb(0,0,255)
+  blue_violet = 0x8A2BE2,              // rgb(138,43,226)
+  brown = 0xA52A2A,                    // rgb(165,42,42)
+  burly_wood = 0xDEB887,               // rgb(222,184,135)
+  cadet_blue = 0x5F9EA0,               // rgb(95,158,160)
+  chartreuse = 0x7FFF00,               // rgb(127,255,0)
+  chocolate = 0xD2691E,                // rgb(210,105,30)
+  coral = 0xFF7F50,                    // rgb(255,127,80)
+  cornflower_blue = 0x6495ED,          // rgb(100,149,237)
+  cornsilk = 0xFFF8DC,                 // rgb(255,248,220)
+  crimson = 0xDC143C,                  // rgb(220,20,60)
+  cyan = 0x00FFFF,                     // rgb(0,255,255)
+  dark_blue = 0x00008B,                // rgb(0,0,139)
+  dark_cyan = 0x008B8B,                // rgb(0,139,139)
+  dark_golden_rod = 0xB8860B,          // rgb(184,134,11)
+  dark_gray = 0xA9A9A9,                // rgb(169,169,169)
+  dark_green = 0x006400,               // rgb(0,100,0)
+  dark_khaki = 0xBDB76B,               // rgb(189,183,107)
+  dark_magenta = 0x8B008B,             // rgb(139,0,139)
+  dark_olive_green = 0x556B2F,         // rgb(85,107,47)
+  dark_orange = 0xFF8C00,              // rgb(255,140,0)
+  dark_orchid = 0x9932CC,              // rgb(153,50,204)
+  dark_red = 0x8B0000,                 // rgb(139,0,0)
+  dark_salmon = 0xE9967A,              // rgb(233,150,122)
+  dark_sea_green = 0x8FBC8F,           // rgb(143,188,143)
+  dark_slate_blue = 0x483D8B,          // rgb(72,61,139)
+  dark_slate_gray = 0x2F4F4F,          // rgb(47,79,79)
+  dark_turquoise = 0x00CED1,           // rgb(0,206,209)
+  dark_violet = 0x9400D3,              // rgb(148,0,211)
+  deep_pink = 0xFF1493,                // rgb(255,20,147)
+  deep_sky_blue = 0x00BFFF,            // rgb(0,191,255)
+  dim_gray = 0x696969,                 // rgb(105,105,105)
+  dodger_blue = 0x1E90FF,              // rgb(30,144,255)
+  fire_brick = 0xB22222,               // rgb(178,34,34)
+  floral_white = 0xFFFAF0,             // rgb(255,250,240)
+  forest_green = 0x228B22,             // rgb(34,139,34)
+  fuchsia = 0xFF00FF,                  // rgb(255,0,255)
+  gainsboro = 0xDCDCDC,                // rgb(220,220,220)
+  ghost_white = 0xF8F8FF,              // rgb(248,248,255)
+  gold = 0xFFD700,                     // rgb(255,215,0)
+  golden_rod = 0xDAA520,               // rgb(218,165,32)
+  gray = 0x808080,                     // rgb(128,128,128)
+  green = 0x008000,                    // rgb(0,128,0)
+  green_yellow = 0xADFF2F,             // rgb(173,255,47)
+  honey_dew = 0xF0FFF0,                // rgb(240,255,240)
+  hot_pink = 0xFF69B4,                 // rgb(255,105,180)
+  indian_red = 0xCD5C5C,               // rgb(205,92,92)
+  indigo = 0x4B0082,                   // rgb(75,0,130)
+  ivory = 0xFFFFF0,                    // rgb(255,255,240)
+  khaki = 0xF0E68C,                    // rgb(240,230,140)
+  lavender = 0xE6E6FA,                 // rgb(230,230,250)
+  lavender_blush = 0xFFF0F5,           // rgb(255,240,245)
+  lawn_green = 0x7CFC00,               // rgb(124,252,0)
+  lemon_chiffon = 0xFFFACD,            // rgb(255,250,205)
+  light_blue = 0xADD8E6,               // rgb(173,216,230)
+  light_coral = 0xF08080,              // rgb(240,128,128)
+  light_cyan = 0xE0FFFF,               // rgb(224,255,255)
+  light_golden_rod_yellow = 0xFAFAD2,  // rgb(250,250,210)
+  light_gray = 0xD3D3D3,               // rgb(211,211,211)
+  light_green = 0x90EE90,              // rgb(144,238,144)
+  light_pink = 0xFFB6C1,               // rgb(255,182,193)
+  light_salmon = 0xFFA07A,             // rgb(255,160,122)
+  light_sea_green = 0x20B2AA,          // rgb(32,178,170)
+  light_sky_blue = 0x87CEFA,           // rgb(135,206,250)
+  light_slate_gray = 0x778899,         // rgb(119,136,153)
+  light_steel_blue = 0xB0C4DE,         // rgb(176,196,222)
+  light_yellow = 0xFFFFE0,             // rgb(255,255,224)
+  lime = 0x00FF00,                     // rgb(0,255,0)
+  lime_green = 0x32CD32,               // rgb(50,205,50)
+  linen = 0xFAF0E6,                    // rgb(250,240,230)
+  magenta = 0xFF00FF,                  // rgb(255,0,255)
+  maroon = 0x800000,                   // rgb(128,0,0)
+  medium_aquamarine = 0x66CDAA,        // rgb(102,205,170)
+  medium_blue = 0x0000CD,              // rgb(0,0,205)
+  medium_orchid = 0xBA55D3,            // rgb(186,85,211)
+  medium_purple = 0x9370DB,            // rgb(147,112,219)
+  medium_sea_green = 0x3CB371,         // rgb(60,179,113)
+  medium_slate_blue = 0x7B68EE,        // rgb(123,104,238)
+  medium_spring_green = 0x00FA9A,      // rgb(0,250,154)
+  medium_turquoise = 0x48D1CC,         // rgb(72,209,204)
+  medium_violet_red = 0xC71585,        // rgb(199,21,133)
+  midnight_blue = 0x191970,            // rgb(25,25,112)
+  mint_cream = 0xF5FFFA,               // rgb(245,255,250)
+  misty_rose = 0xFFE4E1,               // rgb(255,228,225)
+  moccasin = 0xFFE4B5,                 // rgb(255,228,181)
+  navajo_white = 0xFFDEAD,             // rgb(255,222,173)
+  navy = 0x000080,                     // rgb(0,0,128)
+  old_lace = 0xFDF5E6,                 // rgb(253,245,230)
+  olive = 0x808000,                    // rgb(128,128,0)
+  olive_drab = 0x6B8E23,               // rgb(107,142,35)
+  orange = 0xFFA500,                   // rgb(255,165,0)
+  orange_red = 0xFF4500,               // rgb(255,69,0)
+  orchid = 0xDA70D6,                   // rgb(218,112,214)
+  pale_golden_rod = 0xEEE8AA,          // rgb(238,232,170)
+  pale_green = 0x98FB98,               // rgb(152,251,152)
+  pale_turquoise = 0xAFEEEE,           // rgb(175,238,238)
+  pale_violet_red = 0xDB7093,          // rgb(219,112,147)
+  papaya_whip = 0xFFEFD5,              // rgb(255,239,213)
+  peach_puff = 0xFFDAB9,               // rgb(255,218,185)
+  peru = 0xCD853F,                     // rgb(205,133,63)
+  pink = 0xFFC0CB,                     // rgb(255,192,203)
+  plum = 0xDDA0DD,                     // rgb(221,160,221)
+  powder_blue = 0xB0E0E6,              // rgb(176,224,230)
+  purple = 0x800080,                   // rgb(128,0,128)
+  rebecca_purple = 0x663399,           // rgb(102,51,153)
+  red = 0xFF0000,                      // rgb(255,0,0)
+  rosy_brown = 0xBC8F8F,               // rgb(188,143,143)
+  royal_blue = 0x4169E1,               // rgb(65,105,225)
+  saddle_brown = 0x8B4513,             // rgb(139,69,19)
+  salmon = 0xFA8072,                   // rgb(250,128,114)
+  sandy_brown = 0xF4A460,              // rgb(244,164,96)
+  sea_green = 0x2E8B57,                // rgb(46,139,87)
+  sea_shell = 0xFFF5EE,                // rgb(255,245,238)
+  sienna = 0xA0522D,                   // rgb(160,82,45)
+  silver = 0xC0C0C0,                   // rgb(192,192,192)
+  sky_blue = 0x87CEEB,                 // rgb(135,206,235)
+  slate_blue = 0x6A5ACD,               // rgb(106,90,205)
+  slate_gray = 0x708090,               // rgb(112,128,144)
+  snow = 0xFFFAFA,                     // rgb(255,250,250)
+  spring_green = 0x00FF7F,             // rgb(0,255,127)
+  steel_blue = 0x4682B4,               // rgb(70,130,180)
+  tan = 0xD2B48C,                      // rgb(210,180,140)
+  teal = 0x008080,                     // rgb(0,128,128)
+  thistle = 0xD8BFD8,                  // rgb(216,191,216)
+  tomato = 0xFF6347,                   // rgb(255,99,71)
+  turquoise = 0x40E0D0,                // rgb(64,224,208)
+  violet = 0xEE82EE,                   // rgb(238,130,238)
+  wheat = 0xF5DEB3,                    // rgb(245,222,179)
+  white = 0xFFFFFF,                    // rgb(255,255,255)
+  white_smoke = 0xF5F5F5,              // rgb(245,245,245)
+  yellow = 0xFFFF00,                   // rgb(255,255,0)
+  yellow_green = 0x9ACD32              // rgb(154,205,50)
+};                                     // enum class color
+
+enum class terminal_color : uint8_t {
+  black = 30,
+  red,
+  green,
+  yellow,
+  blue,
+  magenta,
+  cyan,
+  white,
+  bright_black = 90,
+  bright_red,
+  bright_green,
+  bright_yellow,
+  bright_blue,
+  bright_magenta,
+  bright_cyan,
+  bright_white
+};
+
+enum class emphasis : uint8_t {
+  bold = 1,
+  faint = 1 << 1,
+  italic = 1 << 2,
+  underline = 1 << 3,
+  blink = 1 << 4,
+  reverse = 1 << 5,
+  conceal = 1 << 6,
+  strikethrough = 1 << 7,
+};
+
+// rgb is a struct for red, green and blue colors.
+// Using the name "rgb" makes some editors show the color in a tooltip.
+struct rgb {
+  FMT_CONSTEXPR rgb() : r(0), g(0), b(0) {}
+  FMT_CONSTEXPR rgb(uint8_t r_, uint8_t g_, uint8_t b_) : r(r_), g(g_), b(b_) {}
+  FMT_CONSTEXPR rgb(uint32_t hex)
+      : r((hex >> 16) & 0xFF), g((hex >> 8) & 0xFF), b(hex & 0xFF) {}
+  FMT_CONSTEXPR rgb(color hex)
+      : r((uint32_t(hex) >> 16) & 0xFF),
+        g((uint32_t(hex) >> 8) & 0xFF),
+        b(uint32_t(hex) & 0xFF) {}
+  uint8_t r;
+  uint8_t g;
+  uint8_t b;
+};
+
+FMT_BEGIN_DETAIL_NAMESPACE
+
+// color is a struct of either a rgb color or a terminal color.
+struct color_type {
+  FMT_CONSTEXPR color_type() noexcept : is_rgb(), value{} {}
+  FMT_CONSTEXPR color_type(color rgb_color) noexcept : is_rgb(true), value{} {
+    value.rgb_color = static_cast<uint32_t>(rgb_color);
+  }
+  FMT_CONSTEXPR color_type(rgb rgb_color) noexcept : is_rgb(true), value{} {
+    value.rgb_color = (static_cast<uint32_t>(rgb_color.r) << 16) |
+                      (static_cast<uint32_t>(rgb_color.g) << 8) | rgb_color.b;
+  }
+  FMT_CONSTEXPR color_type(terminal_color term_color) noexcept
+      : is_rgb(), value{} {
+    value.term_color = static_cast<uint8_t>(term_color);
+  }
+  bool is_rgb;
+  union color_union {
+    uint8_t term_color;
+    uint32_t rgb_color;
+  } value;
+};
+
+FMT_END_DETAIL_NAMESPACE
+
+/** A text style consisting of foreground and background colors and emphasis. */
+class text_style {
+ public:
+  FMT_CONSTEXPR text_style(emphasis em = emphasis()) noexcept
+      : set_foreground_color(), set_background_color(), ems(em) {}
+
+  FMT_CONSTEXPR text_style& operator|=(const text_style& rhs) {
+    if (!set_foreground_color) {
+      set_foreground_color = rhs.set_foreground_color;
+      foreground_color = rhs.foreground_color;
+    } else if (rhs.set_foreground_color) {
+      if (!foreground_color.is_rgb || !rhs.foreground_color.is_rgb)
+        FMT_THROW(format_error("can't OR a terminal color"));
+      foreground_color.value.rgb_color |= rhs.foreground_color.value.rgb_color;
+    }
+
+    if (!set_background_color) {
+      set_background_color = rhs.set_background_color;
+      background_color = rhs.background_color;
+    } else if (rhs.set_background_color) {
+      if (!background_color.is_rgb || !rhs.background_color.is_rgb)
+        FMT_THROW(format_error("can't OR a terminal color"));
+      background_color.value.rgb_color |= rhs.background_color.value.rgb_color;
+    }
+
+    ems = static_cast<emphasis>(static_cast<uint8_t>(ems) |
+                                static_cast<uint8_t>(rhs.ems));
+    return *this;
+  }
+
+  friend FMT_CONSTEXPR text_style operator|(text_style lhs,
+                                            const text_style& rhs) {
+    return lhs |= rhs;
+  }
+
+  FMT_CONSTEXPR bool has_foreground() const noexcept {
+    return set_foreground_color;
+  }
+  FMT_CONSTEXPR bool has_background() const noexcept {
+    return set_background_color;
+  }
+  FMT_CONSTEXPR bool has_emphasis() const noexcept {
+    return static_cast<uint8_t>(ems) != 0;
+  }
+  FMT_CONSTEXPR detail::color_type get_foreground() const noexcept {
+    FMT_ASSERT(has_foreground(), "no foreground specified for this style");
+    return foreground_color;
+  }
+  FMT_CONSTEXPR detail::color_type get_background() const noexcept {
+    FMT_ASSERT(has_background(), "no background specified for this style");
+    return background_color;
+  }
+  FMT_CONSTEXPR emphasis get_emphasis() const noexcept {
+    FMT_ASSERT(has_emphasis(), "no emphasis specified for this style");
+    return ems;
+  }
+
+ private:
+  FMT_CONSTEXPR text_style(bool is_foreground,
+                           detail::color_type text_color) noexcept
+      : set_foreground_color(), set_background_color(), ems() {
+    if (is_foreground) {
+      foreground_color = text_color;
+      set_foreground_color = true;
+    } else {
+      background_color = text_color;
+      set_background_color = true;
+    }
+  }
+
+  friend FMT_CONSTEXPR text_style fg(detail::color_type foreground) noexcept;
+
+  friend FMT_CONSTEXPR text_style bg(detail::color_type background) noexcept;
+
+  detail::color_type foreground_color;
+  detail::color_type background_color;
+  bool set_foreground_color;
+  bool set_background_color;
+  emphasis ems;
+};
+
+/** Creates a text style from the foreground (text) color. */
+FMT_CONSTEXPR inline text_style fg(detail::color_type foreground) noexcept {
+  return text_style(true, foreground);
+}
+
+/** Creates a text style from the background color. */
+FMT_CONSTEXPR inline text_style bg(detail::color_type background) noexcept {
+  return text_style(false, background);
+}
+
+FMT_CONSTEXPR inline text_style operator|(emphasis lhs, emphasis rhs) noexcept {
+  return text_style(lhs) | rhs;
+}
+
+FMT_BEGIN_DETAIL_NAMESPACE
+
+template <typename Char> struct ansi_color_escape {
+  FMT_CONSTEXPR ansi_color_escape(detail::color_type text_color,
+                                  const char* esc) noexcept {
+    // If we have a terminal color, we need to output another escape code
+    // sequence.
+    if (!text_color.is_rgb) {
+      bool is_background = esc == string_view("\x1b[48;2;");
+      uint32_t value = text_color.value.term_color;
+      // Background ASCII codes are the same as the foreground ones but with
+      // 10 more.
+      if (is_background) value += 10u;
+
+      size_t index = 0;
+      buffer[index++] = static_cast<Char>('\x1b');
+      buffer[index++] = static_cast<Char>('[');
+
+      if (value >= 100u) {
+        buffer[index++] = static_cast<Char>('1');
+        value %= 100u;
+      }
+      buffer[index++] = static_cast<Char>('0' + value / 10u);
+      buffer[index++] = static_cast<Char>('0' + value % 10u);
+
+      buffer[index++] = static_cast<Char>('m');
+      buffer[index++] = static_cast<Char>('\0');
+      return;
+    }
+
+    for (int i = 0; i < 7; i++) {
+      buffer[i] = static_cast<Char>(esc[i]);
+    }
+    rgb color(text_color.value.rgb_color);
+    to_esc(color.r, buffer + 7, ';');
+    to_esc(color.g, buffer + 11, ';');
+    to_esc(color.b, buffer + 15, 'm');
+    buffer[19] = static_cast<Char>(0);
+  }
+  FMT_CONSTEXPR ansi_color_escape(emphasis em) noexcept {
+    uint8_t em_codes[num_emphases] = {};
+    if (has_emphasis(em, emphasis::bold)) em_codes[0] = 1;
+    if (has_emphasis(em, emphasis::faint)) em_codes[1] = 2;
+    if (has_emphasis(em, emphasis::italic)) em_codes[2] = 3;
+    if (has_emphasis(em, emphasis::underline)) em_codes[3] = 4;
+    if (has_emphasis(em, emphasis::blink)) em_codes[4] = 5;
+    if (has_emphasis(em, emphasis::reverse)) em_codes[5] = 7;
+    if (has_emphasis(em, emphasis::conceal)) em_codes[6] = 8;
+    if (has_emphasis(em, emphasis::strikethrough)) em_codes[7] = 9;
+
+    size_t index = 0;
+    for (size_t i = 0; i < num_emphases; ++i) {
+      if (!em_codes[i]) continue;
+      buffer[index++] = static_cast<Char>('\x1b');
+      buffer[index++] = static_cast<Char>('[');
+      buffer[index++] = static_cast<Char>('0' + em_codes[i]);
+      buffer[index++] = static_cast<Char>('m');
+    }
+    buffer[index++] = static_cast<Char>(0);
+  }
+  FMT_CONSTEXPR operator const Char*() const noexcept { return buffer; }
+
+  FMT_CONSTEXPR const Char* begin() const noexcept { return buffer; }
+  FMT_CONSTEXPR_CHAR_TRAITS const Char* end() const noexcept {
+    return buffer + std::char_traits<Char>::length(buffer);
+  }
+
+ private:
+  static constexpr size_t num_emphases = 8;
+  Char buffer[7u + 3u * num_emphases + 1u];
+
+  static FMT_CONSTEXPR void to_esc(uint8_t c, Char* out,
+                                   char delimiter) noexcept {
+    out[0] = static_cast<Char>('0' + c / 100);
+    out[1] = static_cast<Char>('0' + c / 10 % 10);
+    out[2] = static_cast<Char>('0' + c % 10);
+    out[3] = static_cast<Char>(delimiter);
+  }
+  static FMT_CONSTEXPR bool has_emphasis(emphasis em, emphasis mask) noexcept {
+    return static_cast<uint8_t>(em) & static_cast<uint8_t>(mask);
+  }
+};
+
+template <typename Char>
+FMT_CONSTEXPR ansi_color_escape<Char> make_foreground_color(
+    detail::color_type foreground) noexcept {
+  return ansi_color_escape<Char>(foreground, "\x1b[38;2;");
+}
+
+template <typename Char>
+FMT_CONSTEXPR ansi_color_escape<Char> make_background_color(
+    detail::color_type background) noexcept {
+  return ansi_color_escape<Char>(background, "\x1b[48;2;");
+}
+
+template <typename Char>
+FMT_CONSTEXPR ansi_color_escape<Char> make_emphasis(emphasis em) noexcept {
+  return ansi_color_escape<Char>(em);
+}
+
+template <typename Char> inline void fputs(const Char* chars, FILE* stream) {
+  int result = std::fputs(chars, stream);
+  if (result < 0)
+    FMT_THROW(system_error(errno, FMT_STRING("cannot write to file")));
+}
+
+template <> inline void fputs<wchar_t>(const wchar_t* chars, FILE* stream) {
+  int result = std::fputws(chars, stream);
+  if (result < 0)
+    FMT_THROW(system_error(errno, FMT_STRING("cannot write to file")));
+}
+
+template <typename Char> inline void reset_color(FILE* stream) {
+  fputs("\x1b[0m", stream);
+}
+
+template <> inline void reset_color<wchar_t>(FILE* stream) {
+  fputs(L"\x1b[0m", stream);
+}
+
+template <typename Char> inline void reset_color(buffer<Char>& buffer) {
+  auto reset_color = string_view("\x1b[0m");
+  buffer.append(reset_color.begin(), reset_color.end());
+}
+
+template <typename T> struct styled_arg {
+  const T& value;
+  text_style style;
+};
+
+template <typename Char>
+void vformat_to(buffer<Char>& buf, const text_style& ts,
+                basic_string_view<Char> format_str,
+                basic_format_args<buffer_context<type_identity_t<Char>>> args) {
+  bool has_style = false;
+  if (ts.has_emphasis()) {
+    has_style = true;
+    auto emphasis = detail::make_emphasis<Char>(ts.get_emphasis());
+    buf.append(emphasis.begin(), emphasis.end());
+  }
+  if (ts.has_foreground()) {
+    has_style = true;
+    auto foreground = detail::make_foreground_color<Char>(ts.get_foreground());
+    buf.append(foreground.begin(), foreground.end());
+  }
+  if (ts.has_background()) {
+    has_style = true;
+    auto background = detail::make_background_color<Char>(ts.get_background());
+    buf.append(background.begin(), background.end());
+  }
+  detail::vformat_to(buf, format_str, args, {});
+  if (has_style) detail::reset_color<Char>(buf);
+}
+
+FMT_END_DETAIL_NAMESPACE
+
+template <typename S, typename Char = char_t<S>>
+void vprint(std::FILE* f, const text_style& ts, const S& format,
+            basic_format_args<buffer_context<type_identity_t<Char>>> args) {
+  basic_memory_buffer<Char> buf;
+  detail::vformat_to(buf, ts, detail::to_string_view(format), args);
+  if (detail::is_utf8()) {
+    detail::print(f, basic_string_view<Char>(buf.begin(), buf.size()));
+  } else {
+    buf.push_back(Char(0));
+    detail::fputs(buf.data(), f);
+  }
+}
+
+/**
+  \rst
+  Formats a string and prints it to the specified file stream using ANSI
+  escape sequences to specify text formatting.
+
+  **Example**::
+
+    fmt::print(fmt::emphasis::bold | fg(fmt::color::red),
+               "Elapsed time: {0:.2f} seconds", 1.23);
+  \endrst
+ */
+template <typename S, typename... Args,
+          FMT_ENABLE_IF(detail::is_string<S>::value)>
+void print(std::FILE* f, const text_style& ts, const S& format_str,
+           const Args&... args) {
+  vprint(f, ts, format_str,
+         fmt::make_format_args<buffer_context<char_t<S>>>(args...));
+}
+
+/**
+  \rst
+  Formats a string and prints it to stdout using ANSI escape sequences to
+  specify text formatting.
+
+  **Example**::
+
+    fmt::print(fmt::emphasis::bold | fg(fmt::color::red),
+               "Elapsed time: {0:.2f} seconds", 1.23);
+  \endrst
+ */
+template <typename S, typename... Args,
+          FMT_ENABLE_IF(detail::is_string<S>::value)>
+void print(const text_style& ts, const S& format_str, const Args&... args) {
+  return print(stdout, ts, format_str, args...);
+}
+
+template <typename S, typename Char = char_t<S>>
+inline std::basic_string<Char> vformat(
+    const text_style& ts, const S& format_str,
+    basic_format_args<buffer_context<type_identity_t<Char>>> args) {
+  basic_memory_buffer<Char> buf;
+  detail::vformat_to(buf, ts, detail::to_string_view(format_str), args);
+  return fmt::to_string(buf);
+}
+
+/**
+  \rst
+  Formats arguments and returns the result as a string using ANSI
+  escape sequences to specify text formatting.
+
+  **Example**::
+
+    #include <fmt/color.h>
+    std::string message = fmt::format(fmt::emphasis::bold | fg(fmt::color::red),
+                                      "The answer is {}", 42);
+  \endrst
+*/
+template <typename S, typename... Args, typename Char = char_t<S>>
+inline std::basic_string<Char> format(const text_style& ts, const S& format_str,
+                                      const Args&... args) {
+  return fmt::vformat(ts, detail::to_string_view(format_str),
+                      fmt::make_format_args<buffer_context<Char>>(args...));
+}
+
+/**
+  Formats a string with the given text_style and writes the output to ``out``.
+ */
+template <typename OutputIt, typename Char,
+          FMT_ENABLE_IF(detail::is_output_iterator<OutputIt, Char>::value)>
+OutputIt vformat_to(
+    OutputIt out, const text_style& ts, basic_string_view<Char> format_str,
+    basic_format_args<buffer_context<type_identity_t<Char>>> args) {
+  auto&& buf = detail::get_buffer<Char>(out);
+  detail::vformat_to(buf, ts, format_str, args);
+  return detail::get_iterator(buf);
+}
+
+/**
+  \rst
+  Formats arguments with the given text_style, writes the result to the output
+  iterator ``out`` and returns the iterator past the end of the output range.
+
+  **Example**::
+
+    std::vector<char> out;
+    fmt::format_to(std::back_inserter(out),
+                   fmt::emphasis::bold | fg(fmt::color::red), "{}", 42);
+  \endrst
+*/
+template <typename OutputIt, typename S, typename... Args,
+          bool enable = detail::is_output_iterator<OutputIt, char_t<S>>::value&&
+              detail::is_string<S>::value>
+inline auto format_to(OutputIt out, const text_style& ts, const S& format_str,
+                      Args&&... args) ->
+    typename std::enable_if<enable, OutputIt>::type {
+  return vformat_to(out, ts, detail::to_string_view(format_str),
+                    fmt::make_format_args<buffer_context<char_t<S>>>(args...));
+}
+
+template <typename T, typename Char>
+struct formatter<detail::styled_arg<T>, Char> : formatter<T, Char> {
+  template <typename FormatContext>
+  auto format(const detail::styled_arg<T>& arg, FormatContext& ctx) const
+      -> decltype(ctx.out()) {
+    const auto& ts = arg.style;
+    const auto& value = arg.value;
+    auto out = ctx.out();
+
+    bool has_style = false;
+    if (ts.has_emphasis()) {
+      has_style = true;
+      auto emphasis = detail::make_emphasis<Char>(ts.get_emphasis());
+      out = std::copy(emphasis.begin(), emphasis.end(), out);
+    }
+    if (ts.has_foreground()) {
+      has_style = true;
+      auto foreground =
+          detail::make_foreground_color<Char>(ts.get_foreground());
+      out = std::copy(foreground.begin(), foreground.end(), out);
+    }
+    if (ts.has_background()) {
+      has_style = true;
+      auto background =
+          detail::make_background_color<Char>(ts.get_background());
+      out = std::copy(background.begin(), background.end(), out);
+    }
+    out = formatter<T, Char>::format(value, ctx);
+    if (has_style) {
+      auto reset_color = string_view("\x1b[0m");
+      out = std::copy(reset_color.begin(), reset_color.end(), out);
+    }
+    return out;
+  }
+};
+
+/**
+  \rst
+  Returns an argument that will be formatted using ANSI escape sequences,
+  to be used in a formatting function.
+
+  **Example**::
+
+    fmt::print("Elapsed time: {0:.2f} seconds",
+               fmt::styled(1.23, fmt::fg(fmt::color::green) |
+                                 fmt::bg(fmt::color::blue)));
+  \endrst
+ */
+template <typename T>
+FMT_CONSTEXPR auto styled(const T& value, text_style ts)
+    -> detail::styled_arg<remove_cvref_t<T>> {
+  return detail::styled_arg<remove_cvref_t<T>>{value, ts};
+}
+
+FMT_MODULE_EXPORT_END
+FMT_END_NAMESPACE
+
+#endif  // FMT_COLOR_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/compile.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/compile.h
new file mode 100644
index 0000000..933668c
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/compile.h
@@ -0,0 +1,611 @@
+// Formatting library for C++ - experimental format string compilation
+//
+// Copyright (c) 2012 - present, Victor Zverovich and fmt contributors
+// All rights reserved.
+//
+// For the license information refer to format.h.
+
+#ifndef FMT_COMPILE_H_
+#define FMT_COMPILE_H_
+
+#include "format.h"
+
+FMT_BEGIN_NAMESPACE
+namespace detail {
+
+template <typename Char, typename InputIt>
+FMT_CONSTEXPR inline counting_iterator copy_str(InputIt begin, InputIt end,
+                                                counting_iterator it) {
+  return it + (end - begin);
+}
+
+template <typename OutputIt> class truncating_iterator_base {
+ protected:
+  OutputIt out_;
+  size_t limit_;
+  size_t count_ = 0;
+
+  truncating_iterator_base() : out_(), limit_(0) {}
+
+  truncating_iterator_base(OutputIt out, size_t limit)
+      : out_(out), limit_(limit) {}
+
+ public:
+  using iterator_category = std::output_iterator_tag;
+  using value_type = typename std::iterator_traits<OutputIt>::value_type;
+  using difference_type = std::ptrdiff_t;
+  using pointer = void;
+  using reference = void;
+  FMT_UNCHECKED_ITERATOR(truncating_iterator_base);
+
+  OutputIt base() const { return out_; }
+  size_t count() const { return count_; }
+};
+
+// An output iterator that truncates the output and counts the number of objects
+// written to it.
+template <typename OutputIt,
+          typename Enable = typename std::is_void<
+              typename std::iterator_traits<OutputIt>::value_type>::type>
+class truncating_iterator;
+
+template <typename OutputIt>
+class truncating_iterator<OutputIt, std::false_type>
+    : public truncating_iterator_base<OutputIt> {
+  mutable typename truncating_iterator_base<OutputIt>::value_type blackhole_;
+
+ public:
+  using value_type = typename truncating_iterator_base<OutputIt>::value_type;
+
+  truncating_iterator() = default;
+
+  truncating_iterator(OutputIt out, size_t limit)
+      : truncating_iterator_base<OutputIt>(out, limit) {}
+
+  truncating_iterator& operator++() {
+    if (this->count_++ < this->limit_) ++this->out_;
+    return *this;
+  }
+
+  truncating_iterator operator++(int) {
+    auto it = *this;
+    ++*this;
+    return it;
+  }
+
+  value_type& operator*() const {
+    return this->count_ < this->limit_ ? *this->out_ : blackhole_;
+  }
+};
+
+template <typename OutputIt>
+class truncating_iterator<OutputIt, std::true_type>
+    : public truncating_iterator_base<OutputIt> {
+ public:
+  truncating_iterator() = default;
+
+  truncating_iterator(OutputIt out, size_t limit)
+      : truncating_iterator_base<OutputIt>(out, limit) {}
+
+  template <typename T> truncating_iterator& operator=(T val) {
+    if (this->count_++ < this->limit_) *this->out_++ = val;
+    return *this;
+  }
+
+  truncating_iterator& operator++() { return *this; }
+  truncating_iterator& operator++(int) { return *this; }
+  truncating_iterator& operator*() { return *this; }
+};
+
+// A compile-time string which is compiled into fast formatting code.
+class compiled_string {};
+
+template <typename S>
+struct is_compiled_string : std::is_base_of<compiled_string, S> {};
+
+/**
+  \rst
+  Converts a string literal *s* into a format string that will be parsed at
+  compile time and converted into efficient formatting code. Requires C++17
+  ``constexpr if`` compiler support.
+
+  **Example**::
+
+    // Converts 42 into std::string using the most efficient method and no
+    // runtime format string processing.
+    std::string s = fmt::format(FMT_COMPILE("{}"), 42);
+  \endrst
+ */
+#if defined(__cpp_if_constexpr) && defined(__cpp_return_type_deduction)
+#  define FMT_COMPILE(s) \
+    FMT_STRING_IMPL(s, fmt::detail::compiled_string, explicit)
+#else
+#  define FMT_COMPILE(s) FMT_STRING(s)
+#endif
+
+#if FMT_USE_NONTYPE_TEMPLATE_ARGS
+template <typename Char, size_t N,
+          fmt::detail_exported::fixed_string<Char, N> Str>
+struct udl_compiled_string : compiled_string {
+  using char_type = Char;
+  explicit constexpr operator basic_string_view<char_type>() const {
+    return {Str.data, N - 1};
+  }
+};
+#endif
+
+template <typename T, typename... Tail>
+const T& first(const T& value, const Tail&...) {
+  return value;
+}
+
+#if defined(__cpp_if_constexpr) && defined(__cpp_return_type_deduction)
+template <typename... Args> struct type_list {};
+
+// Returns a reference to the argument at index N from [first, rest...].
+template <int N, typename T, typename... Args>
+constexpr const auto& get([[maybe_unused]] const T& first,
+                          [[maybe_unused]] const Args&... rest) {
+  static_assert(N < 1 + sizeof...(Args), "index is out of bounds");
+  if constexpr (N == 0)
+    return first;
+  else
+    return detail::get<N - 1>(rest...);
+}
+
+template <typename Char, typename... Args>
+constexpr int get_arg_index_by_name(basic_string_view<Char> name,
+                                    type_list<Args...>) {
+  return get_arg_index_by_name<Args...>(name);
+}
+
+template <int N, typename> struct get_type_impl;
+
+template <int N, typename... Args> struct get_type_impl<N, type_list<Args...>> {
+  using type =
+      remove_cvref_t<decltype(detail::get<N>(std::declval<Args>()...))>;
+};
+
+template <int N, typename T>
+using get_type = typename get_type_impl<N, T>::type;
+
+template <typename T> struct is_compiled_format : std::false_type {};
+
+template <typename Char> struct text {
+  basic_string_view<Char> data;
+  using char_type = Char;
+
+  template <typename OutputIt, typename... Args>
+  constexpr OutputIt format(OutputIt out, const Args&...) const {
+    return write<Char>(out, data);
+  }
+};
+
+template <typename Char>
+struct is_compiled_format<text<Char>> : std::true_type {};
+
+template <typename Char>
+constexpr text<Char> make_text(basic_string_view<Char> s, size_t pos,
+                               size_t size) {
+  return {{&s[pos], size}};
+}
+
+template <typename Char> struct code_unit {
+  Char value;
+  using char_type = Char;
+
+  template <typename OutputIt, typename... Args>
+  constexpr OutputIt format(OutputIt out, const Args&...) const {
+    return write<Char>(out, value);
+  }
+};
+
+// This ensures that the argument type is convertible to `const T&`.
+template <typename T, int N, typename... Args>
+constexpr const T& get_arg_checked(const Args&... args) {
+  const auto& arg = detail::get<N>(args...);
+  if constexpr (detail::is_named_arg<remove_cvref_t<decltype(arg)>>()) {
+    return arg.value;
+  } else {
+    return arg;
+  }
+}
+
+template <typename Char>
+struct is_compiled_format<code_unit<Char>> : std::true_type {};
+
+// A replacement field that refers to argument N.
+template <typename Char, typename T, int N> struct field {
+  using char_type = Char;
+
+  template <typename OutputIt, typename... Args>
+  constexpr OutputIt format(OutputIt out, const Args&... args) const {
+    return write<Char>(out, get_arg_checked<T, N>(args...));
+  }
+};
+
+template <typename Char, typename T, int N>
+struct is_compiled_format<field<Char, T, N>> : std::true_type {};
+
+// A replacement field that refers to argument with name.
+template <typename Char> struct runtime_named_field {
+  using char_type = Char;
+  basic_string_view<Char> name;
+
+  template <typename OutputIt, typename T>
+  constexpr static bool try_format_argument(
+      OutputIt& out,
+      // [[maybe_unused]] due to unused-but-set-parameter warning in GCC 7,8,9
+      [[maybe_unused]] basic_string_view<Char> arg_name, const T& arg) {
+    if constexpr (is_named_arg<typename std::remove_cv<T>::type>::value) {
+      if (arg_name == arg.name) {
+        out = write<Char>(out, arg.value);
+        return true;
+      }
+    }
+    return false;
+  }
+
+  template <typename OutputIt, typename... Args>
+  constexpr OutputIt format(OutputIt out, const Args&... args) const {
+    bool found = (try_format_argument(out, name, args) || ...);
+    if (!found) {
+      FMT_THROW(format_error("argument with specified name is not found"));
+    }
+    return out;
+  }
+};
+
+template <typename Char>
+struct is_compiled_format<runtime_named_field<Char>> : std::true_type {};
+
+// A replacement field that refers to argument N and has format specifiers.
+template <typename Char, typename T, int N> struct spec_field {
+  using char_type = Char;
+  formatter<T, Char> fmt;
+
+  template <typename OutputIt, typename... Args>
+  constexpr FMT_INLINE OutputIt format(OutputIt out,
+                                       const Args&... args) const {
+    const auto& vargs =
+        fmt::make_format_args<basic_format_context<OutputIt, Char>>(args...);
+    basic_format_context<OutputIt, Char> ctx(out, vargs);
+    return fmt.format(get_arg_checked<T, N>(args...), ctx);
+  }
+};
+
+template <typename Char, typename T, int N>
+struct is_compiled_format<spec_field<Char, T, N>> : std::true_type {};
+
+template <typename L, typename R> struct concat {
+  L lhs;
+  R rhs;
+  using char_type = typename L::char_type;
+
+  template <typename OutputIt, typename... Args>
+  constexpr OutputIt format(OutputIt out, const Args&... args) const {
+    out = lhs.format(out, args...);
+    return rhs.format(out, args...);
+  }
+};
+
+template <typename L, typename R>
+struct is_compiled_format<concat<L, R>> : std::true_type {};
+
+template <typename L, typename R>
+constexpr concat<L, R> make_concat(L lhs, R rhs) {
+  return {lhs, rhs};
+}
+
+struct unknown_format {};
+
+template <typename Char>
+constexpr size_t parse_text(basic_string_view<Char> str, size_t pos) {
+  for (size_t size = str.size(); pos != size; ++pos) {
+    if (str[pos] == '{' || str[pos] == '}') break;
+  }
+  return pos;
+}
+
+template <typename Args, size_t POS, int ID, typename S>
+constexpr auto compile_format_string(S format_str);
+
+template <typename Args, size_t POS, int ID, typename T, typename S>
+constexpr auto parse_tail(T head, S format_str) {
+  if constexpr (POS !=
+                basic_string_view<typename S::char_type>(format_str).size()) {
+    constexpr auto tail = compile_format_string<Args, POS, ID>(format_str);
+    if constexpr (std::is_same<remove_cvref_t<decltype(tail)>,
+                               unknown_format>())
+      return tail;
+    else
+      return make_concat(head, tail);
+  } else {
+    return head;
+  }
+}
+
+template <typename T, typename Char> struct parse_specs_result {
+  formatter<T, Char> fmt;
+  size_t end;
+  int next_arg_id;
+};
+
+constexpr int manual_indexing_id = -1;
+
+template <typename T, typename Char>
+constexpr parse_specs_result<T, Char> parse_specs(basic_string_view<Char> str,
+                                                  size_t pos, int next_arg_id) {
+  str.remove_prefix(pos);
+  auto ctx = compile_parse_context<Char>(str, max_value<int>(), nullptr, {},
+                                         next_arg_id);
+  auto f = formatter<T, Char>();
+  auto end = f.parse(ctx);
+  return {f, pos + fmt::detail::to_unsigned(end - str.data()),
+          next_arg_id == 0 ? manual_indexing_id : ctx.next_arg_id()};
+}
+
+template <typename Char> struct arg_id_handler {
+  arg_ref<Char> arg_id;
+
+  constexpr int operator()() {
+    FMT_ASSERT(false, "handler cannot be used with automatic indexing");
+    return 0;
+  }
+  constexpr int operator()(int id) {
+    arg_id = arg_ref<Char>(id);
+    return 0;
+  }
+  constexpr int operator()(basic_string_view<Char> id) {
+    arg_id = arg_ref<Char>(id);
+    return 0;
+  }
+
+  constexpr void on_error(const char* message) {
+    FMT_THROW(format_error(message));
+  }
+};
+
+template <typename Char> struct parse_arg_id_result {
+  arg_ref<Char> arg_id;
+  const Char* arg_id_end;
+};
+
+template <int ID, typename Char>
+constexpr auto parse_arg_id(const Char* begin, const Char* end) {
+  auto handler = arg_id_handler<Char>{arg_ref<Char>{}};
+  auto arg_id_end = parse_arg_id(begin, end, handler);
+  return parse_arg_id_result<Char>{handler.arg_id, arg_id_end};
+}
+
+template <typename T, typename Enable = void> struct field_type {
+  using type = remove_cvref_t<T>;
+};
+
+template <typename T>
+struct field_type<T, enable_if_t<detail::is_named_arg<T>::value>> {
+  using type = remove_cvref_t<decltype(T::value)>;
+};
+
+template <typename T, typename Args, size_t END_POS, int ARG_INDEX, int NEXT_ID,
+          typename S>
+constexpr auto parse_replacement_field_then_tail(S format_str) {
+  using char_type = typename S::char_type;
+  constexpr auto str = basic_string_view<char_type>(format_str);
+  constexpr char_type c = END_POS != str.size() ? str[END_POS] : char_type();
+  if constexpr (c == '}') {
+    return parse_tail<Args, END_POS + 1, NEXT_ID>(
+        field<char_type, typename field_type<T>::type, ARG_INDEX>(),
+        format_str);
+  } else if constexpr (c != ':') {
+    FMT_THROW(format_error("expected ':'"));
+  } else {
+    constexpr auto result = parse_specs<typename field_type<T>::type>(
+        str, END_POS + 1, NEXT_ID == manual_indexing_id ? 0 : NEXT_ID);
+    if constexpr (result.end >= str.size() || str[result.end] != '}') {
+      FMT_THROW(format_error("expected '}'"));
+      return 0;
+    } else {
+      return parse_tail<Args, result.end + 1, result.next_arg_id>(
+          spec_field<char_type, typename field_type<T>::type, ARG_INDEX>{
+              result.fmt},
+          format_str);
+    }
+  }
+}
+
+// Compiles a non-empty format string and returns the compiled representation
+// or unknown_format() on unrecognized input.
+template <typename Args, size_t POS, int ID, typename S>
+constexpr auto compile_format_string(S format_str) {
+  using char_type = typename S::char_type;
+  constexpr auto str = basic_string_view<char_type>(format_str);
+  if constexpr (str[POS] == '{') {
+    if constexpr (POS + 1 == str.size())
+      FMT_THROW(format_error("unmatched '{' in format string"));
+    if constexpr (str[POS + 1] == '{') {
+      return parse_tail<Args, POS + 2, ID>(make_text(str, POS, 1), format_str);
+    } else if constexpr (str[POS + 1] == '}' || str[POS + 1] == ':') {
+      static_assert(ID != manual_indexing_id,
+                    "cannot switch from manual to automatic argument indexing");
+      constexpr auto next_id =
+          ID != manual_indexing_id ? ID + 1 : manual_indexing_id;
+      return parse_replacement_field_then_tail<get_type<ID, Args>, Args,
+                                               POS + 1, ID, next_id>(
+          format_str);
+    } else {
+      constexpr auto arg_id_result =
+          parse_arg_id<ID>(str.data() + POS + 1, str.data() + str.size());
+      constexpr auto arg_id_end_pos = arg_id_result.arg_id_end - str.data();
+      constexpr char_type c =
+          arg_id_end_pos != str.size() ? str[arg_id_end_pos] : char_type();
+      static_assert(c == '}' || c == ':', "missing '}' in format string");
+      if constexpr (arg_id_result.arg_id.kind == arg_id_kind::index) {
+        static_assert(
+            ID == manual_indexing_id || ID == 0,
+            "cannot switch from automatic to manual argument indexing");
+        constexpr auto arg_index = arg_id_result.arg_id.val.index;
+        return parse_replacement_field_then_tail<get_type<arg_index, Args>,
+                                                 Args, arg_id_end_pos,
+                                                 arg_index, manual_indexing_id>(
+            format_str);
+      } else if constexpr (arg_id_result.arg_id.kind == arg_id_kind::name) {
+        constexpr auto arg_index =
+            get_arg_index_by_name(arg_id_result.arg_id.val.name, Args{});
+        if constexpr (arg_index != invalid_arg_index) {
+          constexpr auto next_id =
+              ID != manual_indexing_id ? ID + 1 : manual_indexing_id;
+          return parse_replacement_field_then_tail<
+              decltype(get_type<arg_index, Args>::value), Args, arg_id_end_pos,
+              arg_index, next_id>(format_str);
+        } else {
+          if constexpr (c == '}') {
+            return parse_tail<Args, arg_id_end_pos + 1, ID>(
+                runtime_named_field<char_type>{arg_id_result.arg_id.val.name},
+                format_str);
+          } else if constexpr (c == ':') {
+            return unknown_format();  // no type info for specs parsing
+          }
+        }
+      }
+    }
+  } else if constexpr (str[POS] == '}') {
+    if constexpr (POS + 1 == str.size())
+      FMT_THROW(format_error("unmatched '}' in format string"));
+    return parse_tail<Args, POS + 2, ID>(make_text(str, POS, 1), format_str);
+  } else {
+    constexpr auto end = parse_text(str, POS + 1);
+    if constexpr (end - POS > 1) {
+      return parse_tail<Args, end, ID>(make_text(str, POS, end - POS),
+                                       format_str);
+    } else {
+      return parse_tail<Args, end, ID>(code_unit<char_type>{str[POS]},
+                                       format_str);
+    }
+  }
+}
+
+template <typename... Args, typename S,
+          FMT_ENABLE_IF(detail::is_compiled_string<S>::value)>
+constexpr auto compile(S format_str) {
+  constexpr auto str = basic_string_view<typename S::char_type>(format_str);
+  if constexpr (str.size() == 0) {
+    return detail::make_text(str, 0, 0);
+  } else {
+    constexpr auto result =
+        detail::compile_format_string<detail::type_list<Args...>, 0, 0>(
+            format_str);
+    return result;
+  }
+}
+#endif  // defined(__cpp_if_constexpr) && defined(__cpp_return_type_deduction)
+}  // namespace detail
+
+FMT_MODULE_EXPORT_BEGIN
+
+#if defined(__cpp_if_constexpr) && defined(__cpp_return_type_deduction)
+
+template <typename CompiledFormat, typename... Args,
+          typename Char = typename CompiledFormat::char_type,
+          FMT_ENABLE_IF(detail::is_compiled_format<CompiledFormat>::value)>
+FMT_INLINE std::basic_string<Char> format(const CompiledFormat& cf,
+                                          const Args&... args) {
+  auto s = std::basic_string<Char>();
+  cf.format(std::back_inserter(s), args...);
+  return s;
+}
+
+template <typename OutputIt, typename CompiledFormat, typename... Args,
+          FMT_ENABLE_IF(detail::is_compiled_format<CompiledFormat>::value)>
+constexpr FMT_INLINE OutputIt format_to(OutputIt out, const CompiledFormat& cf,
+                                        const Args&... args) {
+  return cf.format(out, args...);
+}
+
+template <typename S, typename... Args,
+          FMT_ENABLE_IF(detail::is_compiled_string<S>::value)>
+FMT_INLINE std::basic_string<typename S::char_type> format(const S&,
+                                                           Args&&... args) {
+  if constexpr (std::is_same<typename S::char_type, char>::value) {
+    constexpr auto str = basic_string_view<typename S::char_type>(S());
+    if constexpr (str.size() == 2 && str[0] == '{' && str[1] == '}') {
+      const auto& first = detail::first(args...);
+      if constexpr (detail::is_named_arg<
+                        remove_cvref_t<decltype(first)>>::value) {
+        return fmt::to_string(first.value);
+      } else {
+        return fmt::to_string(first);
+      }
+    }
+  }
+  constexpr auto compiled = detail::compile<Args...>(S());
+  if constexpr (std::is_same<remove_cvref_t<decltype(compiled)>,
+                             detail::unknown_format>()) {
+    return fmt::format(
+        static_cast<basic_string_view<typename S::char_type>>(S()),
+        std::forward<Args>(args)...);
+  } else {
+    return fmt::format(compiled, std::forward<Args>(args)...);
+  }
+}
+
+template <typename OutputIt, typename S, typename... Args,
+          FMT_ENABLE_IF(detail::is_compiled_string<S>::value)>
+FMT_CONSTEXPR OutputIt format_to(OutputIt out, const S&, Args&&... args) {
+  constexpr auto compiled = detail::compile<Args...>(S());
+  if constexpr (std::is_same<remove_cvref_t<decltype(compiled)>,
+                             detail::unknown_format>()) {
+    return fmt::format_to(
+        out, static_cast<basic_string_view<typename S::char_type>>(S()),
+        std::forward<Args>(args)...);
+  } else {
+    return fmt::format_to(out, compiled, std::forward<Args>(args)...);
+  }
+}
+#endif
+
+template <typename OutputIt, typename S, typename... Args,
+          FMT_ENABLE_IF(detail::is_compiled_string<S>::value)>
+format_to_n_result<OutputIt> format_to_n(OutputIt out, size_t n,
+                                         const S& format_str, Args&&... args) {
+  auto it = fmt::format_to(detail::truncating_iterator<OutputIt>(out, n),
+                           format_str, std::forward<Args>(args)...);
+  return {it.base(), it.count()};
+}
+
+template <typename S, typename... Args,
+          FMT_ENABLE_IF(detail::is_compiled_string<S>::value)>
+FMT_CONSTEXPR20 size_t formatted_size(const S& format_str,
+                                      const Args&... args) {
+  return fmt::format_to(detail::counting_iterator(), format_str, args...)
+      .count();
+}
+
+template <typename S, typename... Args,
+          FMT_ENABLE_IF(detail::is_compiled_string<S>::value)>
+void print(std::FILE* f, const S& format_str, const Args&... args) {
+  memory_buffer buffer;
+  fmt::format_to(std::back_inserter(buffer), format_str, args...);
+  detail::print(f, {buffer.data(), buffer.size()});
+}
+
+template <typename S, typename... Args,
+          FMT_ENABLE_IF(detail::is_compiled_string<S>::value)>
+void print(const S& format_str, const Args&... args) {
+  print(stdout, format_str, args...);
+}
+
+#if FMT_USE_NONTYPE_TEMPLATE_ARGS
+inline namespace literals {
+template <detail_exported::fixed_string Str> constexpr auto operator""_cf() {
+  using char_t = remove_cvref_t<decltype(Str.data[0])>;
+  return detail::udl_compiled_string<char_t, sizeof(Str.data) / sizeof(char_t),
+                                     Str>();
+}
+}  // namespace literals
+#endif
+
+FMT_MODULE_EXPORT_END
+FMT_END_NAMESPACE
+
+#endif  // FMT_COMPILE_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/core.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/core.h
new file mode 100644
index 0000000..5c210bc
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/core.h
@@ -0,0 +1,3323 @@
+// Formatting library for C++ - the core API for char/UTF-8
+//
+// Copyright (c) 2012 - present, Victor Zverovich
+// All rights reserved.
+//
+// For the license information refer to format.h.
+
+#ifndef FMT_CORE_H_
+#define FMT_CORE_H_
+
+#include <cstddef>  // std::byte
+#include <cstdio>   // std::FILE
+#include <cstring>  // std::strlen
+#include <iterator>
+#include <limits>
+#include <string>
+#include <type_traits>
+
+// The fmt library version in the form major * 10000 + minor * 100 + patch.
+#define FMT_VERSION 90100
+
+#if defined(__clang__) && !defined(__ibmxl__)
+#  define FMT_CLANG_VERSION (__clang_major__ * 100 + __clang_minor__)
+#else
+#  define FMT_CLANG_VERSION 0
+#endif
+
+#if defined(__GNUC__) && !defined(__clang__) && !defined(__INTEL_COMPILER) && \
+    !defined(__NVCOMPILER)
+#  define FMT_GCC_VERSION (__GNUC__ * 100 + __GNUC_MINOR__)
+#else
+#  define FMT_GCC_VERSION 0
+#endif
+
+#ifndef FMT_GCC_PRAGMA
+// Workaround _Pragma bug https://gcc.gnu.org/bugzilla/show_bug.cgi?id=59884.
+#  if FMT_GCC_VERSION >= 504
+#    define FMT_GCC_PRAGMA(arg) _Pragma(arg)
+#  else
+#    define FMT_GCC_PRAGMA(arg)
+#  endif
+#endif
+
+#ifdef __ICL
+#  define FMT_ICC_VERSION __ICL
+#elif defined(__INTEL_COMPILER)
+#  define FMT_ICC_VERSION __INTEL_COMPILER
+#else
+#  define FMT_ICC_VERSION 0
+#endif
+
+#ifdef _MSC_VER
+#  define FMT_MSC_VERSION _MSC_VER
+#  define FMT_MSC_WARNING(...) __pragma(warning(__VA_ARGS__))
+#else
+#  define FMT_MSC_VERSION 0
+#  define FMT_MSC_WARNING(...)
+#endif
+
+#ifdef _MSVC_LANG
+#  define FMT_CPLUSPLUS _MSVC_LANG
+#else
+#  define FMT_CPLUSPLUS __cplusplus
+#endif
+
+#ifdef __has_feature
+#  define FMT_HAS_FEATURE(x) __has_feature(x)
+#else
+#  define FMT_HAS_FEATURE(x) 0
+#endif
+
+#if (defined(__has_include) || FMT_ICC_VERSION >= 1600 || \
+     FMT_MSC_VERSION > 1900) &&                           \
+    !defined(__INTELLISENSE__)
+#  define FMT_HAS_INCLUDE(x) __has_include(x)
+#else
+#  define FMT_HAS_INCLUDE(x) 0
+#endif
+
+#ifdef __has_cpp_attribute
+#  define FMT_HAS_CPP_ATTRIBUTE(x) __has_cpp_attribute(x)
+#else
+#  define FMT_HAS_CPP_ATTRIBUTE(x) 0
+#endif
+
+#define FMT_HAS_CPP14_ATTRIBUTE(attribute) \
+  (FMT_CPLUSPLUS >= 201402L && FMT_HAS_CPP_ATTRIBUTE(attribute))
+
+#define FMT_HAS_CPP17_ATTRIBUTE(attribute) \
+  (FMT_CPLUSPLUS >= 201703L && FMT_HAS_CPP_ATTRIBUTE(attribute))
+
+// Check if relaxed C++14 constexpr is supported.
+// GCC doesn't allow throw in constexpr until version 6 (bug 67371).
+#ifndef FMT_USE_CONSTEXPR
+#  if (FMT_HAS_FEATURE(cxx_relaxed_constexpr) || FMT_MSC_VERSION >= 1912 || \
+       (FMT_GCC_VERSION >= 600 && FMT_CPLUSPLUS >= 201402L)) &&             \
+      !FMT_ICC_VERSION && !defined(__NVCC__)
+#    define FMT_USE_CONSTEXPR 1
+#  else
+#    define FMT_USE_CONSTEXPR 0
+#  endif
+#endif
+#if FMT_USE_CONSTEXPR
+#  define FMT_CONSTEXPR constexpr
+#else
+#  define FMT_CONSTEXPR
+#endif
+
+#if ((FMT_CPLUSPLUS >= 202002L) &&                            \
+     (!defined(_GLIBCXX_RELEASE) || _GLIBCXX_RELEASE > 9)) || \
+    (FMT_CPLUSPLUS >= 201709L && FMT_GCC_VERSION >= 1002)
+#  define FMT_CONSTEXPR20 constexpr
+#else
+#  define FMT_CONSTEXPR20
+#endif
+
+// Check if constexpr std::char_traits<>::{compare,length} are supported.
+#if defined(__GLIBCXX__)
+#  if FMT_CPLUSPLUS >= 201703L && defined(_GLIBCXX_RELEASE) && \
+      _GLIBCXX_RELEASE >= 7  // GCC 7+ libstdc++ has _GLIBCXX_RELEASE.
+#    define FMT_CONSTEXPR_CHAR_TRAITS constexpr
+#  endif
+#elif defined(_LIBCPP_VERSION) && FMT_CPLUSPLUS >= 201703L && \
+    _LIBCPP_VERSION >= 4000
+#  define FMT_CONSTEXPR_CHAR_TRAITS constexpr
+#elif FMT_MSC_VERSION >= 1914 && FMT_CPLUSPLUS >= 201703L
+#  define FMT_CONSTEXPR_CHAR_TRAITS constexpr
+#endif
+#ifndef FMT_CONSTEXPR_CHAR_TRAITS
+#  define FMT_CONSTEXPR_CHAR_TRAITS
+#endif
+
+// Check if exceptions are disabled.
+#ifndef FMT_EXCEPTIONS
+#  if (defined(__GNUC__) && !defined(__EXCEPTIONS)) || \
+      (FMT_MSC_VERSION && !_HAS_EXCEPTIONS)
+#    define FMT_EXCEPTIONS 0
+#  else
+#    define FMT_EXCEPTIONS 1
+#  endif
+#endif
+
+#ifndef FMT_DEPRECATED
+#  if FMT_HAS_CPP14_ATTRIBUTE(deprecated) || FMT_MSC_VERSION >= 1900
+#    define FMT_DEPRECATED [[deprecated]]
+#  else
+#    if (defined(__GNUC__) && !defined(__LCC__)) || defined(__clang__)
+#      define FMT_DEPRECATED __attribute__((deprecated))
+#    elif FMT_MSC_VERSION
+#      define FMT_DEPRECATED __declspec(deprecated)
+#    else
+#      define FMT_DEPRECATED /* deprecated */
+#    endif
+#  endif
+#endif
+
+// [[noreturn]] is disabled on MSVC and NVCC because of bogus unreachable code
+// warnings.
+#if FMT_EXCEPTIONS && FMT_HAS_CPP_ATTRIBUTE(noreturn) && !FMT_MSC_VERSION && \
+    !defined(__NVCC__)
+#  define FMT_NORETURN [[noreturn]]
+#else
+#  define FMT_NORETURN
+#endif
+
+#if FMT_HAS_CPP17_ATTRIBUTE(fallthrough)
+#  define FMT_FALLTHROUGH [[fallthrough]]
+#elif defined(__clang__)
+#  define FMT_FALLTHROUGH [[clang::fallthrough]]
+#elif FMT_GCC_VERSION >= 700 && \
+    (!defined(__EDG_VERSION__) || __EDG_VERSION__ >= 520)
+#  define FMT_FALLTHROUGH [[gnu::fallthrough]]
+#else
+#  define FMT_FALLTHROUGH
+#endif
+
+#ifndef FMT_NODISCARD
+#  if FMT_HAS_CPP17_ATTRIBUTE(nodiscard)
+#    define FMT_NODISCARD [[nodiscard]]
+#  else
+#    define FMT_NODISCARD
+#  endif
+#endif
+
+#ifndef FMT_USE_FLOAT
+#  define FMT_USE_FLOAT 1
+#endif
+#ifndef FMT_USE_DOUBLE
+#  define FMT_USE_DOUBLE 1
+#endif
+#ifndef FMT_USE_LONG_DOUBLE
+#  define FMT_USE_LONG_DOUBLE 1
+#endif
+
+#ifndef FMT_INLINE
+#  if FMT_GCC_VERSION || FMT_CLANG_VERSION
+#    define FMT_INLINE inline __attribute__((always_inline))
+#  else
+#    define FMT_INLINE inline
+#  endif
+#endif
+
+// An inline std::forward replacement.
+#define FMT_FORWARD(...) static_cast<decltype(__VA_ARGS__)&&>(__VA_ARGS__)
+
+#ifdef _MSC_VER
+#  define FMT_UNCHECKED_ITERATOR(It) \
+    using _Unchecked_type = It  // Mark iterator as checked.
+#else
+#  define FMT_UNCHECKED_ITERATOR(It) using unchecked_type = It
+#endif
+
+#ifndef FMT_BEGIN_NAMESPACE
+#  define FMT_BEGIN_NAMESPACE \
+    namespace fmt {           \
+    inline namespace v9 {
+#  define FMT_END_NAMESPACE \
+    }                       \
+    }
+#endif
+
+#ifndef FMT_MODULE_EXPORT
+#  define FMT_MODULE_EXPORT
+#  define FMT_MODULE_EXPORT_BEGIN
+#  define FMT_MODULE_EXPORT_END
+#  define FMT_BEGIN_DETAIL_NAMESPACE namespace detail {
+#  define FMT_END_DETAIL_NAMESPACE }
+#endif
+
+#if !defined(FMT_HEADER_ONLY) && defined(_WIN32)
+#  define FMT_CLASS_API FMT_MSC_WARNING(suppress : 4275)
+#  ifdef FMT_EXPORT
+#    define FMT_API __declspec(dllexport)
+#  elif defined(FMT_SHARED)
+#    define FMT_API __declspec(dllimport)
+#  endif
+#else
+#  define FMT_CLASS_API
+#  if defined(FMT_EXPORT) || defined(FMT_SHARED)
+#    if defined(__GNUC__) || defined(__clang__)
+#      define FMT_API __attribute__((visibility("default")))
+#    endif
+#  endif
+#endif
+#ifndef FMT_API
+#  define FMT_API
+#endif
+
+// libc++ supports string_view in pre-c++17.
+#if FMT_HAS_INCLUDE(<string_view>) && \
+    (FMT_CPLUSPLUS >= 201703L || defined(_LIBCPP_VERSION))
+#  include <string_view>
+#  define FMT_USE_STRING_VIEW
+#elif FMT_HAS_INCLUDE("experimental/string_view") && FMT_CPLUSPLUS >= 201402L
+#  include <experimental/string_view>
+#  define FMT_USE_EXPERIMENTAL_STRING_VIEW
+#endif
+
+#ifndef FMT_UNICODE
+#  define FMT_UNICODE !FMT_MSC_VERSION
+#endif
+
+#ifndef FMT_CONSTEVAL
+#  if ((FMT_GCC_VERSION >= 1000 || FMT_CLANG_VERSION >= 1101) &&         \
+       FMT_CPLUSPLUS >= 202002L && !defined(__apple_build_version__)) || \
+      (defined(__cpp_consteval) &&                                       \
+       (!FMT_MSC_VERSION || _MSC_FULL_VER >= 193030704))
+// consteval is broken in MSVC before VS2022 and Apple clang 13.
+#    define FMT_CONSTEVAL consteval
+#    define FMT_HAS_CONSTEVAL
+#  else
+#    define FMT_CONSTEVAL
+#  endif
+#endif
+
+#ifndef FMT_USE_NONTYPE_TEMPLATE_ARGS
+#  if defined(__cpp_nontype_template_args) &&                  \
+      ((FMT_GCC_VERSION >= 903 && FMT_CPLUSPLUS >= 201709L) || \
+       __cpp_nontype_template_args >= 201911L) &&              \
+      !defined(__NVCOMPILER)
+#    define FMT_USE_NONTYPE_TEMPLATE_ARGS 1
+#  else
+#    define FMT_USE_NONTYPE_TEMPLATE_ARGS 0
+#  endif
+#endif
+
+// Enable minimal optimizations for more compact code in debug mode.
+FMT_GCC_PRAGMA("GCC push_options")
+#if !defined(__OPTIMIZE__) && !defined(__NVCOMPILER)
+FMT_GCC_PRAGMA("GCC optimize(\"Og\")")
+#endif
+
+FMT_BEGIN_NAMESPACE
+FMT_MODULE_EXPORT_BEGIN
+
+// Implementations of enable_if_t and other metafunctions for older systems.
+template <bool B, typename T = void>
+using enable_if_t = typename std::enable_if<B, T>::type;
+template <bool B, typename T, typename F>
+using conditional_t = typename std::conditional<B, T, F>::type;
+template <bool B> using bool_constant = std::integral_constant<bool, B>;
+template <typename T>
+using remove_reference_t = typename std::remove_reference<T>::type;
+template <typename T>
+using remove_const_t = typename std::remove_const<T>::type;
+template <typename T>
+using remove_cvref_t = typename std::remove_cv<remove_reference_t<T>>::type;
+template <typename T> struct type_identity { using type = T; };
+template <typename T> using type_identity_t = typename type_identity<T>::type;
+template <typename T>
+using underlying_t = typename std::underlying_type<T>::type;
+
+template <typename...> struct disjunction : std::false_type {};
+template <typename P> struct disjunction<P> : P {};
+template <typename P1, typename... Pn>
+struct disjunction<P1, Pn...>
+    : conditional_t<bool(P1::value), P1, disjunction<Pn...>> {};
+
+template <typename...> struct conjunction : std::true_type {};
+template <typename P> struct conjunction<P> : P {};
+template <typename P1, typename... Pn>
+struct conjunction<P1, Pn...>
+    : conditional_t<bool(P1::value), conjunction<Pn...>, P1> {};
+
+struct monostate {
+  constexpr monostate() {}
+};
+
+// An enable_if helper to be used in template parameters which results in much
+// shorter symbols: https://godbolt.org/z/sWw4vP. Extra parentheses are needed
+// to workaround a bug in MSVC 2019 (see #1140 and #1186).
+#ifdef FMT_DOC
+#  define FMT_ENABLE_IF(...)
+#else
+#  define FMT_ENABLE_IF(...) enable_if_t<(__VA_ARGS__), int> = 0
+#endif
+
+FMT_BEGIN_DETAIL_NAMESPACE
+
+// Suppresses "unused variable" warnings with the method described in
+// https://herbsutter.com/2009/10/18/mailbag-shutting-up-compiler-warnings/.
+// (void)var does not work on many Intel compilers.
+template <typename... T> FMT_CONSTEXPR void ignore_unused(const T&...) {}
+
+constexpr FMT_INLINE auto is_constant_evaluated(
+    bool default_value = false) noexcept -> bool {
+#ifdef __cpp_lib_is_constant_evaluated
+  ignore_unused(default_value);
+  return std::is_constant_evaluated();
+#else
+  return default_value;
+#endif
+}
+
+// Suppresses "conditional expression is constant" warnings.
+template <typename T> constexpr FMT_INLINE auto const_check(T value) -> T {
+  return value;
+}
+
+FMT_NORETURN FMT_API void assert_fail(const char* file, int line,
+                                      const char* message);
+
+#ifndef FMT_ASSERT
+#  ifdef NDEBUG
+// FMT_ASSERT is not empty to avoid -Wempty-body.
+#    define FMT_ASSERT(condition, message) \
+      ::fmt::detail::ignore_unused((condition), (message))
+#  else
+#    define FMT_ASSERT(condition, message)                                    \
+      ((condition) /* void() fails with -Winvalid-constexpr on clang 4.0.1 */ \
+           ? (void)0                                                          \
+           : ::fmt::detail::assert_fail(__FILE__, __LINE__, (message)))
+#  endif
+#endif
+
+#if defined(FMT_USE_STRING_VIEW)
+template <typename Char> using std_string_view = std::basic_string_view<Char>;
+#elif defined(FMT_USE_EXPERIMENTAL_STRING_VIEW)
+template <typename Char>
+using std_string_view = std::experimental::basic_string_view<Char>;
+#else
+template <typename T> struct std_string_view {};
+#endif
+
+#ifdef FMT_USE_INT128
+// Do nothing.
+#elif defined(__SIZEOF_INT128__) && !defined(__NVCC__) && \
+    !(FMT_CLANG_VERSION && FMT_MSC_VERSION)
+#  define FMT_USE_INT128 1
+using int128_opt = __int128_t;  // An optional native 128-bit integer.
+using uint128_opt = __uint128_t;
+template <typename T> inline auto convert_for_visit(T value) -> T {
+  return value;
+}
+#else
+#  define FMT_USE_INT128 0
+#endif
+#if !FMT_USE_INT128
+enum class int128_opt {};
+enum class uint128_opt {};
+// Reduce template instantiations.
+template <typename T> auto convert_for_visit(T) -> monostate { return {}; }
+#endif
+
+// Casts a nonnegative integer to unsigned.
+template <typename Int>
+FMT_CONSTEXPR auto to_unsigned(Int value) ->
+    typename std::make_unsigned<Int>::type {
+  FMT_ASSERT(std::is_unsigned<Int>::value || value >= 0, "negative value");
+  return static_cast<typename std::make_unsigned<Int>::type>(value);
+}
+
+FMT_MSC_WARNING(suppress : 4566) constexpr unsigned char micro[] = "\u00B5";
+
+constexpr auto is_utf8() -> bool {
+  // Avoid buggy sign extensions in MSVC's constant evaluation mode (#2297).
+  using uchar = unsigned char;
+  return FMT_UNICODE || (sizeof(micro) == 3 && uchar(micro[0]) == 0xC2 &&
+                         uchar(micro[1]) == 0xB5);
+}
+FMT_END_DETAIL_NAMESPACE
+
+/**
+  An implementation of ``std::basic_string_view`` for pre-C++17. It provides a
+  subset of the API. ``fmt::basic_string_view`` is used for format strings even
+  if ``std::string_view`` is available to prevent issues when a library is
+  compiled with a different ``-std`` option than the client code (which is not
+  recommended).
+ */
+template <typename Char> class basic_string_view {
+ private:
+  const Char* data_;
+  size_t size_;
+
+ public:
+  using value_type = Char;
+  using iterator = const Char*;
+
+  constexpr basic_string_view() noexcept : data_(nullptr), size_(0) {}
+
+  /** Constructs a string reference object from a C string and a size. */
+  constexpr basic_string_view(const Char* s, size_t count) noexcept
+      : data_(s), size_(count) {}
+
+  /**
+    \rst
+    Constructs a string reference object from a C string computing
+    the size with ``std::char_traits<Char>::length``.
+    \endrst
+   */
+  FMT_CONSTEXPR_CHAR_TRAITS
+  FMT_INLINE
+  basic_string_view(const Char* s)
+      : data_(s),
+        size_(detail::const_check(std::is_same<Char, char>::value &&
+                                  !detail::is_constant_evaluated(true))
+                  ? std::strlen(reinterpret_cast<const char*>(s))
+                  : std::char_traits<Char>::length(s)) {}
+
+  /** Constructs a string reference from a ``std::basic_string`` object. */
+  template <typename Traits, typename Alloc>
+  FMT_CONSTEXPR basic_string_view(
+      const std::basic_string<Char, Traits, Alloc>& s) noexcept
+      : data_(s.data()), size_(s.size()) {}
+
+  template <typename S, FMT_ENABLE_IF(std::is_same<
+                                      S, detail::std_string_view<Char>>::value)>
+  FMT_CONSTEXPR basic_string_view(S s) noexcept
+      : data_(s.data()), size_(s.size()) {}
+
+  /** Returns a pointer to the string data. */
+  constexpr auto data() const noexcept -> const Char* { return data_; }
+
+  /** Returns the string size. */
+  constexpr auto size() const noexcept -> size_t { return size_; }
+
+  constexpr auto begin() const noexcept -> iterator { return data_; }
+  constexpr auto end() const noexcept -> iterator { return data_ + size_; }
+
+  constexpr auto operator[](size_t pos) const noexcept -> const Char& {
+    return data_[pos];
+  }
+
+  FMT_CONSTEXPR void remove_prefix(size_t n) noexcept {
+    data_ += n;
+    size_ -= n;
+  }
+
+  // Lexicographically compare this string reference to other.
+  FMT_CONSTEXPR_CHAR_TRAITS auto compare(basic_string_view other) const -> int {
+    size_t str_size = size_ < other.size_ ? size_ : other.size_;
+    int result = std::char_traits<Char>::compare(data_, other.data_, str_size);
+    if (result == 0)
+      result = size_ == other.size_ ? 0 : (size_ < other.size_ ? -1 : 1);
+    return result;
+  }
+
+  FMT_CONSTEXPR_CHAR_TRAITS friend auto operator==(basic_string_view lhs,
+                                                   basic_string_view rhs)
+      -> bool {
+    return lhs.compare(rhs) == 0;
+  }
+  friend auto operator!=(basic_string_view lhs, basic_string_view rhs) -> bool {
+    return lhs.compare(rhs) != 0;
+  }
+  friend auto operator<(basic_string_view lhs, basic_string_view rhs) -> bool {
+    return lhs.compare(rhs) < 0;
+  }
+  friend auto operator<=(basic_string_view lhs, basic_string_view rhs) -> bool {
+    return lhs.compare(rhs) <= 0;
+  }
+  friend auto operator>(basic_string_view lhs, basic_string_view rhs) -> bool {
+    return lhs.compare(rhs) > 0;
+  }
+  friend auto operator>=(basic_string_view lhs, basic_string_view rhs) -> bool {
+    return lhs.compare(rhs) >= 0;
+  }
+};
+
+using string_view = basic_string_view<char>;
+
+/** Specifies if ``T`` is a character type. Can be specialized by users. */
+template <typename T> struct is_char : std::false_type {};
+template <> struct is_char<char> : std::true_type {};
+
+FMT_BEGIN_DETAIL_NAMESPACE
+
+// A base class for compile-time strings.
+struct compile_string {};
+
+template <typename S>
+struct is_compile_string : std::is_base_of<compile_string, S> {};
+
+// Returns a string view of `s`.
+template <typename Char, FMT_ENABLE_IF(is_char<Char>::value)>
+FMT_INLINE auto to_string_view(const Char* s) -> basic_string_view<Char> {
+  return s;
+}
+template <typename Char, typename Traits, typename Alloc>
+inline auto to_string_view(const std::basic_string<Char, Traits, Alloc>& s)
+    -> basic_string_view<Char> {
+  return s;
+}
+template <typename Char>
+constexpr auto to_string_view(basic_string_view<Char> s)
+    -> basic_string_view<Char> {
+  return s;
+}
+template <typename Char,
+          FMT_ENABLE_IF(!std::is_empty<std_string_view<Char>>::value)>
+inline auto to_string_view(std_string_view<Char> s) -> basic_string_view<Char> {
+  return s;
+}
+template <typename S, FMT_ENABLE_IF(is_compile_string<S>::value)>
+constexpr auto to_string_view(const S& s)
+    -> basic_string_view<typename S::char_type> {
+  return basic_string_view<typename S::char_type>(s);
+}
+void to_string_view(...);
+
+// Specifies whether S is a string type convertible to fmt::basic_string_view.
+// It should be a constexpr function but MSVC 2017 fails to compile it in
+// enable_if and MSVC 2015 fails to compile it as an alias template.
+// ADL invocation of to_string_view is DEPRECATED!
+template <typename S>
+struct is_string : std::is_class<decltype(to_string_view(std::declval<S>()))> {
+};
+
+template <typename S, typename = void> struct char_t_impl {};
+template <typename S> struct char_t_impl<S, enable_if_t<is_string<S>::value>> {
+  using result = decltype(to_string_view(std::declval<S>()));
+  using type = typename result::value_type;
+};
+
+enum class type {
+  none_type,
+  // Integer types should go first,
+  int_type,
+  uint_type,
+  long_long_type,
+  ulong_long_type,
+  int128_type,
+  uint128_type,
+  bool_type,
+  char_type,
+  last_integer_type = char_type,
+  // followed by floating-point types.
+  float_type,
+  double_type,
+  long_double_type,
+  last_numeric_type = long_double_type,
+  cstring_type,
+  string_type,
+  pointer_type,
+  custom_type
+};
+
+// Maps core type T to the corresponding type enum constant.
+template <typename T, typename Char>
+struct type_constant : std::integral_constant<type, type::custom_type> {};
+
+#define FMT_TYPE_CONSTANT(Type, constant) \
+  template <typename Char>                \
+  struct type_constant<Type, Char>        \
+      : std::integral_constant<type, type::constant> {}
+
+FMT_TYPE_CONSTANT(int, int_type);
+FMT_TYPE_CONSTANT(unsigned, uint_type);
+FMT_TYPE_CONSTANT(long long, long_long_type);
+FMT_TYPE_CONSTANT(unsigned long long, ulong_long_type);
+FMT_TYPE_CONSTANT(int128_opt, int128_type);
+FMT_TYPE_CONSTANT(uint128_opt, uint128_type);
+FMT_TYPE_CONSTANT(bool, bool_type);
+FMT_TYPE_CONSTANT(Char, char_type);
+FMT_TYPE_CONSTANT(float, float_type);
+FMT_TYPE_CONSTANT(double, double_type);
+FMT_TYPE_CONSTANT(long double, long_double_type);
+FMT_TYPE_CONSTANT(const Char*, cstring_type);
+FMT_TYPE_CONSTANT(basic_string_view<Char>, string_type);
+FMT_TYPE_CONSTANT(const void*, pointer_type);
+
+constexpr bool is_integral_type(type t) {
+  return t > type::none_type && t <= type::last_integer_type;
+}
+
+constexpr bool is_arithmetic_type(type t) {
+  return t > type::none_type && t <= type::last_numeric_type;
+}
+
+FMT_NORETURN FMT_API void throw_format_error(const char* message);
+
+struct error_handler {
+  constexpr error_handler() = default;
+  constexpr error_handler(const error_handler&) = default;
+
+  // This function is intentionally not constexpr to give a compile-time error.
+  FMT_NORETURN void on_error(const char* message) {
+    throw_format_error(message);
+  }
+};
+FMT_END_DETAIL_NAMESPACE
+
+/** String's character type. */
+template <typename S> using char_t = typename detail::char_t_impl<S>::type;
+
+/**
+  \rst
+  Parsing context consisting of a format string range being parsed and an
+  argument counter for automatic indexing.
+  You can use the ``format_parse_context`` type alias for ``char`` instead.
+  \endrst
+ */
+template <typename Char, typename ErrorHandler = detail::error_handler>
+class basic_format_parse_context : private ErrorHandler {
+ private:
+  basic_string_view<Char> format_str_;
+  int next_arg_id_;
+
+  FMT_CONSTEXPR void do_check_arg_id(int id);
+
+ public:
+  using char_type = Char;
+  using iterator = typename basic_string_view<Char>::iterator;
+
+  explicit constexpr basic_format_parse_context(
+      basic_string_view<Char> format_str, ErrorHandler eh = {},
+      int next_arg_id = 0)
+      : ErrorHandler(eh), format_str_(format_str), next_arg_id_(next_arg_id) {}
+
+  /**
+    Returns an iterator to the beginning of the format string range being
+    parsed.
+   */
+  constexpr auto begin() const noexcept -> iterator {
+    return format_str_.begin();
+  }
+
+  /**
+    Returns an iterator past the end of the format string range being parsed.
+   */
+  constexpr auto end() const noexcept -> iterator { return format_str_.end(); }
+
+  /** Advances the begin iterator to ``it``. */
+  FMT_CONSTEXPR void advance_to(iterator it) {
+    format_str_.remove_prefix(detail::to_unsigned(it - begin()));
+  }
+
+  /**
+    Reports an error if using the manual argument indexing; otherwise returns
+    the next argument index and switches to the automatic indexing.
+   */
+  FMT_CONSTEXPR auto next_arg_id() -> int {
+    if (next_arg_id_ < 0) {
+      on_error("cannot switch from manual to automatic argument indexing");
+      return 0;
+    }
+    int id = next_arg_id_++;
+    do_check_arg_id(id);
+    return id;
+  }
+
+  /**
+    Reports an error if using the automatic argument indexing; otherwise
+    switches to the manual indexing.
+   */
+  FMT_CONSTEXPR void check_arg_id(int id) {
+    if (next_arg_id_ > 0) {
+      on_error("cannot switch from automatic to manual argument indexing");
+      return;
+    }
+    next_arg_id_ = -1;
+    do_check_arg_id(id);
+  }
+  FMT_CONSTEXPR void check_arg_id(basic_string_view<Char>) {}
+  FMT_CONSTEXPR void check_dynamic_spec(int arg_id);
+
+  FMT_CONSTEXPR void on_error(const char* message) {
+    ErrorHandler::on_error(message);
+  }
+
+  constexpr auto error_handler() const -> ErrorHandler { return *this; }
+};
+
+using format_parse_context = basic_format_parse_context<char>;
+
+FMT_BEGIN_DETAIL_NAMESPACE
+// A parse context with extra data used only in compile-time checks.
+template <typename Char, typename ErrorHandler = detail::error_handler>
+class compile_parse_context
+    : public basic_format_parse_context<Char, ErrorHandler> {
+ private:
+  int num_args_;
+  const type* types_;
+  using base = basic_format_parse_context<Char, ErrorHandler>;
+
+ public:
+  explicit FMT_CONSTEXPR compile_parse_context(
+      basic_string_view<Char> format_str, int num_args, const type* types,
+      ErrorHandler eh = {}, int next_arg_id = 0)
+      : base(format_str, eh, next_arg_id), num_args_(num_args), types_(types) {}
+
+  constexpr auto num_args() const -> int { return num_args_; }
+  constexpr auto arg_type(int id) const -> type { return types_[id]; }
+
+  FMT_CONSTEXPR auto next_arg_id() -> int {
+    int id = base::next_arg_id();
+    if (id >= num_args_) this->on_error("argument not found");
+    return id;
+  }
+
+  FMT_CONSTEXPR void check_arg_id(int id) {
+    base::check_arg_id(id);
+    if (id >= num_args_) this->on_error("argument not found");
+  }
+  using base::check_arg_id;
+
+  FMT_CONSTEXPR void check_dynamic_spec(int arg_id) {
+    if (arg_id < num_args_ && types_ && !is_integral_type(types_[arg_id]))
+      this->on_error("width/precision is not integer");
+  }
+};
+FMT_END_DETAIL_NAMESPACE
+
+template <typename Char, typename ErrorHandler>
+FMT_CONSTEXPR void
+basic_format_parse_context<Char, ErrorHandler>::do_check_arg_id(int id) {
+  // Argument id is only checked at compile-time during parsing because
+  // formatting has its own validation.
+  if (detail::is_constant_evaluated() && FMT_GCC_VERSION >= 1200) {
+    using context = detail::compile_parse_context<Char, ErrorHandler>;
+    if (id >= static_cast<context*>(this)->num_args())
+      on_error("argument not found");
+  }
+}
+
+template <typename Char, typename ErrorHandler>
+FMT_CONSTEXPR void
+basic_format_parse_context<Char, ErrorHandler>::check_dynamic_spec(int arg_id) {
+  if (detail::is_constant_evaluated()) {
+    using context = detail::compile_parse_context<Char, ErrorHandler>;
+    static_cast<context*>(this)->check_dynamic_spec(arg_id);
+  }
+}
+
+template <typename Context> class basic_format_arg;
+template <typename Context> class basic_format_args;
+template <typename Context> class dynamic_format_arg_store;
+
+// A formatter for objects of type T.
+template <typename T, typename Char = char, typename Enable = void>
+struct formatter {
+  // A deleted default constructor indicates a disabled formatter.
+  formatter() = delete;
+};
+
+// Specifies if T has an enabled formatter specialization. A type can be
+// formattable even if it doesn't have a formatter e.g. via a conversion.
+template <typename T, typename Context>
+using has_formatter =
+    std::is_constructible<typename Context::template formatter_type<T>>;
+
+// Checks whether T is a container with contiguous storage.
+template <typename T> struct is_contiguous : std::false_type {};
+template <typename Char>
+struct is_contiguous<std::basic_string<Char>> : std::true_type {};
+
+class appender;
+
+FMT_BEGIN_DETAIL_NAMESPACE
+
+template <typename Context, typename T>
+constexpr auto has_const_formatter_impl(T*)
+    -> decltype(typename Context::template formatter_type<T>().format(
+                    std::declval<const T&>(), std::declval<Context&>()),
+                true) {
+  return true;
+}
+template <typename Context>
+constexpr auto has_const_formatter_impl(...) -> bool {
+  return false;
+}
+template <typename T, typename Context>
+constexpr auto has_const_formatter() -> bool {
+  return has_const_formatter_impl<Context>(static_cast<T*>(nullptr));
+}
+
+// Extracts a reference to the container from back_insert_iterator.
+template <typename Container>
+inline auto get_container(std::back_insert_iterator<Container> it)
+    -> Container& {
+  using base = std::back_insert_iterator<Container>;
+  struct accessor : base {
+    accessor(base b) : base(b) {}
+    using base::container;
+  };
+  return *accessor(it).container;
+}
+
+template <typename Char, typename InputIt, typename OutputIt>
+FMT_CONSTEXPR auto copy_str(InputIt begin, InputIt end, OutputIt out)
+    -> OutputIt {
+  while (begin != end) *out++ = static_cast<Char>(*begin++);
+  return out;
+}
+
+template <typename Char, typename T, typename U,
+          FMT_ENABLE_IF(
+              std::is_same<remove_const_t<T>, U>::value&& is_char<U>::value)>
+FMT_CONSTEXPR auto copy_str(T* begin, T* end, U* out) -> U* {
+  if (is_constant_evaluated()) return copy_str<Char, T*, U*>(begin, end, out);
+  auto size = to_unsigned(end - begin);
+  memcpy(out, begin, size * sizeof(U));
+  return out + size;
+}
+
+/**
+  \rst
+  A contiguous memory buffer with an optional growing ability. It is an internal
+  class and shouldn't be used directly, only via `~fmt::basic_memory_buffer`.
+  \endrst
+ */
+template <typename T> class buffer {
+ private:
+  T* ptr_;
+  size_t size_;
+  size_t capacity_;
+
+ protected:
+  // Don't initialize ptr_ since it is not accessed to save a few cycles.
+  FMT_MSC_WARNING(suppress : 26495)
+  buffer(size_t sz) noexcept : size_(sz), capacity_(sz) {}
+
+  FMT_CONSTEXPR20 buffer(T* p = nullptr, size_t sz = 0, size_t cap = 0) noexcept
+      : ptr_(p), size_(sz), capacity_(cap) {}
+
+  FMT_CONSTEXPR20 ~buffer() = default;
+  buffer(buffer&&) = default;
+
+  /** Sets the buffer data and capacity. */
+  FMT_CONSTEXPR void set(T* buf_data, size_t buf_capacity) noexcept {
+    ptr_ = buf_data;
+    capacity_ = buf_capacity;
+  }
+
+  /** Increases the buffer capacity to hold at least *capacity* elements. */
+  virtual FMT_CONSTEXPR20 void grow(size_t capacity) = 0;
+
+ public:
+  using value_type = T;
+  using const_reference = const T&;
+
+  buffer(const buffer&) = delete;
+  void operator=(const buffer&) = delete;
+
+  auto begin() noexcept -> T* { return ptr_; }
+  auto end() noexcept -> T* { return ptr_ + size_; }
+
+  auto begin() const noexcept -> const T* { return ptr_; }
+  auto end() const noexcept -> const T* { return ptr_ + size_; }
+
+  /** Returns the size of this buffer. */
+  constexpr auto size() const noexcept -> size_t { return size_; }
+
+  /** Returns the capacity of this buffer. */
+  constexpr auto capacity() const noexcept -> size_t { return capacity_; }
+
+  /** Returns a pointer to the buffer data. */
+  FMT_CONSTEXPR auto data() noexcept -> T* { return ptr_; }
+
+  /** Returns a pointer to the buffer data. */
+  FMT_CONSTEXPR auto data() const noexcept -> const T* { return ptr_; }
+
+  /** Clears this buffer. */
+  void clear() { size_ = 0; }
+
+  // Tries resizing the buffer to contain *count* elements. If T is a POD type
+  // the new elements may not be initialized.
+  FMT_CONSTEXPR20 void try_resize(size_t count) {
+    try_reserve(count);
+    size_ = count <= capacity_ ? count : capacity_;
+  }
+
+  // Tries increasing the buffer capacity to *new_capacity*. It can increase the
+  // capacity by a smaller amount than requested but guarantees there is space
+  // for at least one additional element either by increasing the capacity or by
+  // flushing the buffer if it is full.
+  FMT_CONSTEXPR20 void try_reserve(size_t new_capacity) {
+    if (new_capacity > capacity_) grow(new_capacity);
+  }
+
+  FMT_CONSTEXPR20 void push_back(const T& value) {
+    try_reserve(size_ + 1);
+    ptr_[size_++] = value;
+  }
+
+  /** Appends data to the end of the buffer. */
+  template <typename U> void append(const U* begin, const U* end);
+
+  template <typename Idx> FMT_CONSTEXPR auto operator[](Idx index) -> T& {
+    return ptr_[index];
+  }
+  template <typename Idx>
+  FMT_CONSTEXPR auto operator[](Idx index) const -> const T& {
+    return ptr_[index];
+  }
+};
+
+struct buffer_traits {
+  explicit buffer_traits(size_t) {}
+  auto count() const -> size_t { return 0; }
+  auto limit(size_t size) -> size_t { return size; }
+};
+
+class fixed_buffer_traits {
+ private:
+  size_t count_ = 0;
+  size_t limit_;
+
+ public:
+  explicit fixed_buffer_traits(size_t limit) : limit_(limit) {}
+  auto count() const -> size_t { return count_; }
+  auto limit(size_t size) -> size_t {
+    size_t n = limit_ > count_ ? limit_ - count_ : 0;
+    count_ += size;
+    return size < n ? size : n;
+  }
+};
+
+// A buffer that writes to an output iterator when flushed.
+template <typename OutputIt, typename T, typename Traits = buffer_traits>
+class iterator_buffer final : public Traits, public buffer<T> {
+ private:
+  OutputIt out_;
+  enum { buffer_size = 256 };
+  T data_[buffer_size];
+
+ protected:
+  FMT_CONSTEXPR20 void grow(size_t) override {
+    if (this->size() == buffer_size) flush();
+  }
+
+  void flush() {
+    auto size = this->size();
+    this->clear();
+    out_ = copy_str<T>(data_, data_ + this->limit(size), out_);
+  }
+
+ public:
+  explicit iterator_buffer(OutputIt out, size_t n = buffer_size)
+      : Traits(n), buffer<T>(data_, 0, buffer_size), out_(out) {}
+  iterator_buffer(iterator_buffer&& other)
+      : Traits(other), buffer<T>(data_, 0, buffer_size), out_(other.out_) {}
+  ~iterator_buffer() { flush(); }
+
+  auto out() -> OutputIt {
+    flush();
+    return out_;
+  }
+  auto count() const -> size_t { return Traits::count() + this->size(); }
+};
+
+template <typename T>
+class iterator_buffer<T*, T, fixed_buffer_traits> final
+    : public fixed_buffer_traits,
+      public buffer<T> {
+ private:
+  T* out_;
+  enum { buffer_size = 256 };
+  T data_[buffer_size];
+
+ protected:
+  FMT_CONSTEXPR20 void grow(size_t) override {
+    if (this->size() == this->capacity()) flush();
+  }
+
+  void flush() {
+    size_t n = this->limit(this->size());
+    if (this->data() == out_) {
+      out_ += n;
+      this->set(data_, buffer_size);
+    }
+    this->clear();
+  }
+
+ public:
+  explicit iterator_buffer(T* out, size_t n = buffer_size)
+      : fixed_buffer_traits(n), buffer<T>(out, 0, n), out_(out) {}
+  iterator_buffer(iterator_buffer&& other)
+      : fixed_buffer_traits(other),
+        buffer<T>(std::move(other)),
+        out_(other.out_) {
+    if (this->data() != out_) {
+      this->set(data_, buffer_size);
+      this->clear();
+    }
+  }
+  ~iterator_buffer() { flush(); }
+
+  auto out() -> T* {
+    flush();
+    return out_;
+  }
+  auto count() const -> size_t {
+    return fixed_buffer_traits::count() + this->size();
+  }
+};
+
+template <typename T> class iterator_buffer<T*, T> final : public buffer<T> {
+ protected:
+  FMT_CONSTEXPR20 void grow(size_t) override {}
+
+ public:
+  explicit iterator_buffer(T* out, size_t = 0) : buffer<T>(out, 0, ~size_t()) {}
+
+  auto out() -> T* { return &*this->end(); }
+};
+
+// A buffer that writes to a container with the contiguous storage.
+template <typename Container>
+class iterator_buffer<std::back_insert_iterator<Container>,
+                      enable_if_t<is_contiguous<Container>::value,
+                                  typename Container::value_type>>
+    final : public buffer<typename Container::value_type> {
+ private:
+  Container& container_;
+
+ protected:
+  FMT_CONSTEXPR20 void grow(size_t capacity) override {
+    container_.resize(capacity);
+    this->set(&container_[0], capacity);
+  }
+
+ public:
+  explicit iterator_buffer(Container& c)
+      : buffer<typename Container::value_type>(c.size()), container_(c) {}
+  explicit iterator_buffer(std::back_insert_iterator<Container> out, size_t = 0)
+      : iterator_buffer(get_container(out)) {}
+
+  auto out() -> std::back_insert_iterator<Container> {
+    return std::back_inserter(container_);
+  }
+};
+
+// A buffer that counts the number of code units written discarding the output.
+template <typename T = char> class counting_buffer final : public buffer<T> {
+ private:
+  enum { buffer_size = 256 };
+  T data_[buffer_size];
+  size_t count_ = 0;
+
+ protected:
+  FMT_CONSTEXPR20 void grow(size_t) override {
+    if (this->size() != buffer_size) return;
+    count_ += this->size();
+    this->clear();
+  }
+
+ public:
+  counting_buffer() : buffer<T>(data_, 0, buffer_size) {}
+
+  auto count() -> size_t { return count_ + this->size(); }
+};
+
+template <typename T>
+using buffer_appender = conditional_t<std::is_same<T, char>::value, appender,
+                                      std::back_insert_iterator<buffer<T>>>;
+
+// Maps an output iterator to a buffer.
+template <typename T, typename OutputIt>
+auto get_buffer(OutputIt out) -> iterator_buffer<OutputIt, T> {
+  return iterator_buffer<OutputIt, T>(out);
+}
+
+template <typename Buffer>
+auto get_iterator(Buffer& buf) -> decltype(buf.out()) {
+  return buf.out();
+}
+template <typename T> auto get_iterator(buffer<T>& buf) -> buffer_appender<T> {
+  return buffer_appender<T>(buf);
+}
+
+template <typename T, typename Char = char, typename Enable = void>
+struct fallback_formatter {
+  fallback_formatter() = delete;
+};
+
+// Specifies if T has an enabled fallback_formatter specialization.
+template <typename T, typename Char>
+using has_fallback_formatter =
+#ifdef FMT_DEPRECATED_OSTREAM
+    std::is_constructible<fallback_formatter<T, Char>>;
+#else
+    std::false_type;
+#endif
+
+struct view {};
+
+template <typename Char, typename T> struct named_arg : view {
+  const Char* name;
+  const T& value;
+  named_arg(const Char* n, const T& v) : name(n), value(v) {}
+};
+
+template <typename Char> struct named_arg_info {
+  const Char* name;
+  int id;
+};
+
+template <typename T, typename Char, size_t NUM_ARGS, size_t NUM_NAMED_ARGS>
+struct arg_data {
+  // args_[0].named_args points to named_args_ to avoid bloating format_args.
+  // +1 to workaround a bug in gcc 7.5 that causes duplicated-branches warning.
+  T args_[1 + (NUM_ARGS != 0 ? NUM_ARGS : +1)];
+  named_arg_info<Char> named_args_[NUM_NAMED_ARGS];
+
+  template <typename... U>
+  arg_data(const U&... init) : args_{T(named_args_, NUM_NAMED_ARGS), init...} {}
+  arg_data(const arg_data& other) = delete;
+  auto args() const -> const T* { return args_ + 1; }
+  auto named_args() -> named_arg_info<Char>* { return named_args_; }
+};
+
+template <typename T, typename Char, size_t NUM_ARGS>
+struct arg_data<T, Char, NUM_ARGS, 0> {
+  // +1 to workaround a bug in gcc 7.5 that causes duplicated-branches warning.
+  T args_[NUM_ARGS != 0 ? NUM_ARGS : +1];
+
+  template <typename... U>
+  FMT_CONSTEXPR FMT_INLINE arg_data(const U&... init) : args_{init...} {}
+  FMT_CONSTEXPR FMT_INLINE auto args() const -> const T* { return args_; }
+  FMT_CONSTEXPR FMT_INLINE auto named_args() -> std::nullptr_t {
+    return nullptr;
+  }
+};
+
+template <typename Char>
+inline void init_named_args(named_arg_info<Char>*, int, int) {}
+
+template <typename T> struct is_named_arg : std::false_type {};
+template <typename T> struct is_statically_named_arg : std::false_type {};
+
+template <typename T, typename Char>
+struct is_named_arg<named_arg<Char, T>> : std::true_type {};
+
+template <typename Char, typename T, typename... Tail,
+          FMT_ENABLE_IF(!is_named_arg<T>::value)>
+void init_named_args(named_arg_info<Char>* named_args, int arg_count,
+                     int named_arg_count, const T&, const Tail&... args) {
+  init_named_args(named_args, arg_count + 1, named_arg_count, args...);
+}
+
+template <typename Char, typename T, typename... Tail,
+          FMT_ENABLE_IF(is_named_arg<T>::value)>
+void init_named_args(named_arg_info<Char>* named_args, int arg_count,
+                     int named_arg_count, const T& arg, const Tail&... args) {
+  named_args[named_arg_count++] = {arg.name, arg_count};
+  init_named_args(named_args, arg_count + 1, named_arg_count, args...);
+}
+
+template <typename... Args>
+FMT_CONSTEXPR FMT_INLINE void init_named_args(std::nullptr_t, int, int,
+                                              const Args&...) {}
+
+template <bool B = false> constexpr auto count() -> size_t { return B ? 1 : 0; }
+template <bool B1, bool B2, bool... Tail> constexpr auto count() -> size_t {
+  return (B1 ? 1 : 0) + count<B2, Tail...>();
+}
+
+template <typename... Args> constexpr auto count_named_args() -> size_t {
+  return count<is_named_arg<Args>::value...>();
+}
+
+template <typename... Args>
+constexpr auto count_statically_named_args() -> size_t {
+  return count<is_statically_named_arg<Args>::value...>();
+}
+
+struct unformattable {};
+struct unformattable_char : unformattable {};
+struct unformattable_const : unformattable {};
+struct unformattable_pointer : unformattable {};
+
+template <typename Char> struct string_value {
+  const Char* data;
+  size_t size;
+};
+
+template <typename Char> struct named_arg_value {
+  const named_arg_info<Char>* data;
+  size_t size;
+};
+
+template <typename Context> struct custom_value {
+  using parse_context = typename Context::parse_context_type;
+  void* value;
+  void (*format)(void* arg, parse_context& parse_ctx, Context& ctx);
+};
+
+// A formatting argument value.
+template <typename Context> class value {
+ public:
+  using char_type = typename Context::char_type;
+
+  union {
+    monostate no_value;
+    int int_value;
+    unsigned uint_value;
+    long long long_long_value;
+    unsigned long long ulong_long_value;
+    int128_opt int128_value;
+    uint128_opt uint128_value;
+    bool bool_value;
+    char_type char_value;
+    float float_value;
+    double double_value;
+    long double long_double_value;
+    const void* pointer;
+    string_value<char_type> string;
+    custom_value<Context> custom;
+    named_arg_value<char_type> named_args;
+  };
+
+  constexpr FMT_INLINE value() : no_value() {}
+  constexpr FMT_INLINE value(int val) : int_value(val) {}
+  constexpr FMT_INLINE value(unsigned val) : uint_value(val) {}
+  constexpr FMT_INLINE value(long long val) : long_long_value(val) {}
+  constexpr FMT_INLINE value(unsigned long long val) : ulong_long_value(val) {}
+  FMT_INLINE value(int128_opt val) : int128_value(val) {}
+  FMT_INLINE value(uint128_opt val) : uint128_value(val) {}
+  constexpr FMT_INLINE value(float val) : float_value(val) {}
+  constexpr FMT_INLINE value(double val) : double_value(val) {}
+  FMT_INLINE value(long double val) : long_double_value(val) {}
+  constexpr FMT_INLINE value(bool val) : bool_value(val) {}
+  constexpr FMT_INLINE value(char_type val) : char_value(val) {}
+  FMT_CONSTEXPR FMT_INLINE value(const char_type* val) {
+    string.data = val;
+    if (is_constant_evaluated()) string.size = {};
+  }
+  FMT_CONSTEXPR FMT_INLINE value(basic_string_view<char_type> val) {
+    string.data = val.data();
+    string.size = val.size();
+  }
+  FMT_INLINE value(const void* val) : pointer(val) {}
+  FMT_INLINE value(const named_arg_info<char_type>* args, size_t size)
+      : named_args{args, size} {}
+
+  template <typename T> FMT_CONSTEXPR FMT_INLINE value(T& val) {
+    using value_type = remove_cvref_t<T>;
+    custom.value = const_cast<value_type*>(&val);
+    // Get the formatter type through the context to allow different contexts
+    // have different extension points, e.g. `formatter<T>` for `format` and
+    // `printf_formatter<T>` for `printf`.
+    custom.format = format_custom_arg<
+        value_type,
+        conditional_t<has_formatter<value_type, Context>::value,
+                      typename Context::template formatter_type<value_type>,
+                      fallback_formatter<value_type, char_type>>>;
+  }
+  value(unformattable);
+  value(unformattable_char);
+  value(unformattable_const);
+  value(unformattable_pointer);
+
+ private:
+  // Formats an argument of a custom type, such as a user-defined class.
+  template <typename T, typename Formatter>
+  static void format_custom_arg(void* arg,
+                                typename Context::parse_context_type& parse_ctx,
+                                Context& ctx) {
+    auto f = Formatter();
+    parse_ctx.advance_to(f.parse(parse_ctx));
+    using qualified_type =
+        conditional_t<has_const_formatter<T, Context>(), const T, T>;
+    ctx.advance_to(f.format(*static_cast<qualified_type*>(arg), ctx));
+  }
+};
+
+template <typename Context, typename T>
+FMT_CONSTEXPR auto make_arg(T&& value) -> basic_format_arg<Context>;
+
+// To minimize the number of types we need to deal with, long is translated
+// either to int or to long long depending on its size.
+enum { long_short = sizeof(long) == sizeof(int) };
+using long_type = conditional_t<long_short, int, long long>;
+using ulong_type = conditional_t<long_short, unsigned, unsigned long long>;
+
+#ifdef __cpp_lib_byte
+inline auto format_as(std::byte b) -> unsigned char {
+  return static_cast<unsigned char>(b);
+}
+#endif
+
+template <typename T> struct has_format_as {
+  template <typename U, typename V = decltype(format_as(U())),
+            FMT_ENABLE_IF(std::is_enum<U>::value&& std::is_integral<V>::value)>
+  static auto check(U*) -> std::true_type;
+  static auto check(...) -> std::false_type;
+
+  enum { value = decltype(check(static_cast<T*>(nullptr)))::value };
+};
+
+// Maps formatting arguments to core types.
+// arg_mapper reports errors by returning unformattable instead of using
+// static_assert because it's used in the is_formattable trait.
+template <typename Context> struct arg_mapper {
+  using char_type = typename Context::char_type;
+
+  FMT_CONSTEXPR FMT_INLINE auto map(signed char val) -> int { return val; }
+  FMT_CONSTEXPR FMT_INLINE auto map(unsigned char val) -> unsigned {
+    return val;
+  }
+  FMT_CONSTEXPR FMT_INLINE auto map(short val) -> int { return val; }
+  FMT_CONSTEXPR FMT_INLINE auto map(unsigned short val) -> unsigned {
+    return val;
+  }
+  FMT_CONSTEXPR FMT_INLINE auto map(int val) -> int { return val; }
+  FMT_CONSTEXPR FMT_INLINE auto map(unsigned val) -> unsigned { return val; }
+  FMT_CONSTEXPR FMT_INLINE auto map(long val) -> long_type { return val; }
+  FMT_CONSTEXPR FMT_INLINE auto map(unsigned long val) -> ulong_type {
+    return val;
+  }
+  FMT_CONSTEXPR FMT_INLINE auto map(long long val) -> long long { return val; }
+  FMT_CONSTEXPR FMT_INLINE auto map(unsigned long long val)
+      -> unsigned long long {
+    return val;
+  }
+  FMT_CONSTEXPR FMT_INLINE auto map(int128_opt val) -> int128_opt {
+    return val;
+  }
+  FMT_CONSTEXPR FMT_INLINE auto map(uint128_opt val) -> uint128_opt {
+    return val;
+  }
+  FMT_CONSTEXPR FMT_INLINE auto map(bool val) -> bool { return val; }
+
+  template <typename T, FMT_ENABLE_IF(std::is_same<T, char>::value ||
+                                      std::is_same<T, char_type>::value)>
+  FMT_CONSTEXPR FMT_INLINE auto map(T val) -> char_type {
+    return val;
+  }
+  template <typename T, enable_if_t<(std::is_same<T, wchar_t>::value ||
+#ifdef __cpp_char8_t
+                                     std::is_same<T, char8_t>::value ||
+#endif
+                                     std::is_same<T, char16_t>::value ||
+                                     std::is_same<T, char32_t>::value) &&
+                                        !std::is_same<T, char_type>::value,
+                                    int> = 0>
+  FMT_CONSTEXPR FMT_INLINE auto map(T) -> unformattable_char {
+    return {};
+  }
+
+  FMT_CONSTEXPR FMT_INLINE auto map(float val) -> float { return val; }
+  FMT_CONSTEXPR FMT_INLINE auto map(double val) -> double { return val; }
+  FMT_CONSTEXPR FMT_INLINE auto map(long double val) -> long double {
+    return val;
+  }
+
+  FMT_CONSTEXPR FMT_INLINE auto map(char_type* val) -> const char_type* {
+    return val;
+  }
+  FMT_CONSTEXPR FMT_INLINE auto map(const char_type* val) -> const char_type* {
+    return val;
+  }
+  template <typename T,
+            FMT_ENABLE_IF(is_string<T>::value && !std::is_pointer<T>::value &&
+                          std::is_same<char_type, char_t<T>>::value)>
+  FMT_CONSTEXPR FMT_INLINE auto map(const T& val)
+      -> basic_string_view<char_type> {
+    return to_string_view(val);
+  }
+  template <typename T,
+            FMT_ENABLE_IF(is_string<T>::value && !std::is_pointer<T>::value &&
+                          !std::is_same<char_type, char_t<T>>::value)>
+  FMT_CONSTEXPR FMT_INLINE auto map(const T&) -> unformattable_char {
+    return {};
+  }
+  template <typename T,
+            FMT_ENABLE_IF(
+                std::is_convertible<T, basic_string_view<char_type>>::value &&
+                !is_string<T>::value && !has_formatter<T, Context>::value &&
+                !has_fallback_formatter<T, char_type>::value)>
+  FMT_CONSTEXPR FMT_INLINE auto map(const T& val)
+      -> basic_string_view<char_type> {
+    return basic_string_view<char_type>(val);
+  }
+  template <typename T,
+            FMT_ENABLE_IF(
+                std::is_convertible<T, std_string_view<char_type>>::value &&
+                !std::is_convertible<T, basic_string_view<char_type>>::value &&
+                !is_string<T>::value && !has_formatter<T, Context>::value &&
+                !has_fallback_formatter<T, char_type>::value)>
+  FMT_CONSTEXPR FMT_INLINE auto map(const T& val)
+      -> basic_string_view<char_type> {
+    return std_string_view<char_type>(val);
+  }
+
+  FMT_CONSTEXPR FMT_INLINE auto map(void* val) -> const void* { return val; }
+  FMT_CONSTEXPR FMT_INLINE auto map(const void* val) -> const void* {
+    return val;
+  }
+  FMT_CONSTEXPR FMT_INLINE auto map(std::nullptr_t val) -> const void* {
+    return val;
+  }
+
+  // We use SFINAE instead of a const T* parameter to avoid conflicting with
+  // the C array overload.
+  template <
+      typename T,
+      FMT_ENABLE_IF(
+          std::is_pointer<T>::value || std::is_member_pointer<T>::value ||
+          std::is_function<typename std::remove_pointer<T>::type>::value ||
+          (std::is_convertible<const T&, const void*>::value &&
+           !std::is_convertible<const T&, const char_type*>::value &&
+           !has_formatter<T, Context>::value))>
+  FMT_CONSTEXPR auto map(const T&) -> unformattable_pointer {
+    return {};
+  }
+
+  template <typename T, std::size_t N,
+            FMT_ENABLE_IF(!std::is_same<T, wchar_t>::value)>
+  FMT_CONSTEXPR FMT_INLINE auto map(const T (&values)[N]) -> const T (&)[N] {
+    return values;
+  }
+
+  template <typename T,
+            FMT_ENABLE_IF(
+                std::is_enum<T>::value&& std::is_convertible<T, int>::value &&
+                !has_format_as<T>::value && !has_formatter<T, Context>::value &&
+                !has_fallback_formatter<T, char_type>::value)>
+  FMT_DEPRECATED FMT_CONSTEXPR FMT_INLINE auto map(const T& val)
+      -> decltype(std::declval<arg_mapper>().map(
+          static_cast<underlying_t<T>>(val))) {
+    return map(static_cast<underlying_t<T>>(val));
+  }
+
+  template <typename T, FMT_ENABLE_IF(has_format_as<T>::value &&
+                                      !has_formatter<T, Context>::value)>
+  FMT_CONSTEXPR FMT_INLINE auto map(const T& val)
+      -> decltype(std::declval<arg_mapper>().map(format_as(T()))) {
+    return map(format_as(val));
+  }
+
+  template <typename T, typename U = remove_cvref_t<T>>
+  struct formattable
+      : bool_constant<has_const_formatter<U, Context>() ||
+                      !std::is_const<remove_reference_t<T>>::value ||
+                      has_fallback_formatter<U, char_type>::value> {};
+
+#if (FMT_MSC_VERSION != 0 && FMT_MSC_VERSION < 1910) || \
+    FMT_ICC_VERSION != 0 || defined(__NVCC__)
+  // Workaround a bug in MSVC and Intel (Issue 2746).
+  template <typename T> FMT_CONSTEXPR FMT_INLINE auto do_map(T&& val) -> T& {
+    return val;
+  }
+#else
+  template <typename T, FMT_ENABLE_IF(formattable<T>::value)>
+  FMT_CONSTEXPR FMT_INLINE auto do_map(T&& val) -> T& {
+    return val;
+  }
+  template <typename T, FMT_ENABLE_IF(!formattable<T>::value)>
+  FMT_CONSTEXPR FMT_INLINE auto do_map(T&&) -> unformattable_const {
+    return {};
+  }
+#endif
+
+  template <typename T, typename U = remove_cvref_t<T>,
+            FMT_ENABLE_IF(!is_string<U>::value && !is_char<U>::value &&
+                          !std::is_array<U>::value &&
+                          !std::is_pointer<U>::value &&
+                          !has_format_as<U>::value &&
+                          (has_formatter<U, Context>::value ||
+                           has_fallback_formatter<U, char_type>::value))>
+  FMT_CONSTEXPR FMT_INLINE auto map(T&& val)
+      -> decltype(this->do_map(std::forward<T>(val))) {
+    return do_map(std::forward<T>(val));
+  }
+
+  template <typename T, FMT_ENABLE_IF(is_named_arg<T>::value)>
+  FMT_CONSTEXPR FMT_INLINE auto map(const T& named_arg)
+      -> decltype(std::declval<arg_mapper>().map(named_arg.value)) {
+    return map(named_arg.value);
+  }
+
+  auto map(...) -> unformattable { return {}; }
+};
+
+// A type constant after applying arg_mapper<Context>.
+template <typename T, typename Context>
+using mapped_type_constant =
+    type_constant<decltype(arg_mapper<Context>().map(std::declval<const T&>())),
+                  typename Context::char_type>;
+
+enum { packed_arg_bits = 4 };
+// Maximum number of arguments with packed types.
+enum { max_packed_args = 62 / packed_arg_bits };
+enum : unsigned long long { is_unpacked_bit = 1ULL << 63 };
+enum : unsigned long long { has_named_args_bit = 1ULL << 62 };
+
+FMT_END_DETAIL_NAMESPACE
+
+// An output iterator that appends to a buffer.
+// It is used to reduce symbol sizes for the common case.
+class appender : public std::back_insert_iterator<detail::buffer<char>> {
+  using base = std::back_insert_iterator<detail::buffer<char>>;
+
+  template <typename T>
+  friend auto get_buffer(appender out) -> detail::buffer<char>& {
+    return detail::get_container(out);
+  }
+
+ public:
+  using std::back_insert_iterator<detail::buffer<char>>::back_insert_iterator;
+  appender(base it) noexcept : base(it) {}
+  FMT_UNCHECKED_ITERATOR(appender);
+
+  auto operator++() noexcept -> appender& { return *this; }
+  auto operator++(int) noexcept -> appender { return *this; }
+};
+
+// A formatting argument. It is a trivially copyable/constructible type to
+// allow storage in basic_memory_buffer.
+template <typename Context> class basic_format_arg {
+ private:
+  detail::value<Context> value_;
+  detail::type type_;
+
+  template <typename ContextType, typename T>
+  friend FMT_CONSTEXPR auto detail::make_arg(T&& value)
+      -> basic_format_arg<ContextType>;
+
+  template <typename Visitor, typename Ctx>
+  friend FMT_CONSTEXPR auto visit_format_arg(Visitor&& vis,
+                                             const basic_format_arg<Ctx>& arg)
+      -> decltype(vis(0));
+
+  friend class basic_format_args<Context>;
+  friend class dynamic_format_arg_store<Context>;
+
+  using char_type = typename Context::char_type;
+
+  template <typename T, typename Char, size_t NUM_ARGS, size_t NUM_NAMED_ARGS>
+  friend struct detail::arg_data;
+
+  basic_format_arg(const detail::named_arg_info<char_type>* args, size_t size)
+      : value_(args, size) {}
+
+ public:
+  class handle {
+   public:
+    explicit handle(detail::custom_value<Context> custom) : custom_(custom) {}
+
+    void format(typename Context::parse_context_type& parse_ctx,
+                Context& ctx) const {
+      custom_.format(custom_.value, parse_ctx, ctx);
+    }
+
+   private:
+    detail::custom_value<Context> custom_;
+  };
+
+  constexpr basic_format_arg() : type_(detail::type::none_type) {}
+
+  constexpr explicit operator bool() const noexcept {
+    return type_ != detail::type::none_type;
+  }
+
+  auto type() const -> detail::type { return type_; }
+
+  auto is_integral() const -> bool { return detail::is_integral_type(type_); }
+  auto is_arithmetic() const -> bool {
+    return detail::is_arithmetic_type(type_);
+  }
+};
+
+/**
+  \rst
+  Visits an argument dispatching to the appropriate visit method based on
+  the argument type. For example, if the argument type is ``double`` then
+  ``vis(value)`` will be called with the value of type ``double``.
+  \endrst
+ */
+template <typename Visitor, typename Context>
+FMT_CONSTEXPR FMT_INLINE auto visit_format_arg(
+    Visitor&& vis, const basic_format_arg<Context>& arg) -> decltype(vis(0)) {
+  switch (arg.type_) {
+  case detail::type::none_type:
+    break;
+  case detail::type::int_type:
+    return vis(arg.value_.int_value);
+  case detail::type::uint_type:
+    return vis(arg.value_.uint_value);
+  case detail::type::long_long_type:
+    return vis(arg.value_.long_long_value);
+  case detail::type::ulong_long_type:
+    return vis(arg.value_.ulong_long_value);
+  case detail::type::int128_type:
+    return vis(detail::convert_for_visit(arg.value_.int128_value));
+  case detail::type::uint128_type:
+    return vis(detail::convert_for_visit(arg.value_.uint128_value));
+  case detail::type::bool_type:
+    return vis(arg.value_.bool_value);
+  case detail::type::char_type:
+    return vis(arg.value_.char_value);
+  case detail::type::float_type:
+    return vis(arg.value_.float_value);
+  case detail::type::double_type:
+    return vis(arg.value_.double_value);
+  case detail::type::long_double_type:
+    return vis(arg.value_.long_double_value);
+  case detail::type::cstring_type:
+    return vis(arg.value_.string.data);
+  case detail::type::string_type:
+    using sv = basic_string_view<typename Context::char_type>;
+    return vis(sv(arg.value_.string.data, arg.value_.string.size));
+  case detail::type::pointer_type:
+    return vis(arg.value_.pointer);
+  case detail::type::custom_type:
+    return vis(typename basic_format_arg<Context>::handle(arg.value_.custom));
+  }
+  return vis(monostate());
+}
+
+FMT_BEGIN_DETAIL_NAMESPACE
+
+template <typename Char, typename InputIt>
+auto copy_str(InputIt begin, InputIt end, appender out) -> appender {
+  get_container(out).append(begin, end);
+  return out;
+}
+
+template <typename Char, typename R, typename OutputIt>
+FMT_CONSTEXPR auto copy_str(R&& rng, OutputIt out) -> OutputIt {
+  return detail::copy_str<Char>(rng.begin(), rng.end(), out);
+}
+
+#if FMT_GCC_VERSION && FMT_GCC_VERSION < 500
+// A workaround for gcc 4.8 to make void_t work in a SFINAE context.
+template <typename... Ts> struct void_t_impl { using type = void; };
+template <typename... Ts>
+using void_t = typename detail::void_t_impl<Ts...>::type;
+#else
+template <typename...> using void_t = void;
+#endif
+
+template <typename It, typename T, typename Enable = void>
+struct is_output_iterator : std::false_type {};
+
+template <typename It, typename T>
+struct is_output_iterator<
+    It, T,
+    void_t<typename std::iterator_traits<It>::iterator_category,
+           decltype(*std::declval<It>() = std::declval<T>())>>
+    : std::true_type {};
+
+template <typename OutputIt>
+struct is_back_insert_iterator : std::false_type {};
+template <typename Container>
+struct is_back_insert_iterator<std::back_insert_iterator<Container>>
+    : std::true_type {};
+
+template <typename OutputIt>
+struct is_contiguous_back_insert_iterator : std::false_type {};
+template <typename Container>
+struct is_contiguous_back_insert_iterator<std::back_insert_iterator<Container>>
+    : is_contiguous<Container> {};
+template <>
+struct is_contiguous_back_insert_iterator<appender> : std::true_type {};
+
+// A type-erased reference to an std::locale to avoid a heavy <locale> include.
+class locale_ref {
+ private:
+  const void* locale_;  // A type-erased pointer to std::locale.
+
+ public:
+  constexpr locale_ref() : locale_(nullptr) {}
+  template <typename Locale> explicit locale_ref(const Locale& loc);
+
+  explicit operator bool() const noexcept { return locale_ != nullptr; }
+
+  template <typename Locale> auto get() const -> Locale;
+};
+
+template <typename> constexpr auto encode_types() -> unsigned long long {
+  return 0;
+}
+
+template <typename Context, typename Arg, typename... Args>
+constexpr auto encode_types() -> unsigned long long {
+  return static_cast<unsigned>(mapped_type_constant<Arg, Context>::value) |
+         (encode_types<Context, Args...>() << packed_arg_bits);
+}
+
+template <typename Context, typename T>
+FMT_CONSTEXPR FMT_INLINE auto make_value(T&& val) -> value<Context> {
+  const auto& arg = arg_mapper<Context>().map(FMT_FORWARD(val));
+
+  constexpr bool formattable_char =
+      !std::is_same<decltype(arg), const unformattable_char&>::value;
+  static_assert(formattable_char, "Mixing character types is disallowed.");
+
+  constexpr bool formattable_const =
+      !std::is_same<decltype(arg), const unformattable_const&>::value;
+  static_assert(formattable_const, "Cannot format a const argument.");
+
+  // Formatting of arbitrary pointers is disallowed. If you want to output
+  // a pointer cast it to "void *" or "const void *". In particular, this
+  // forbids formatting of "[const] volatile char *" which is printed as bool
+  // by iostreams.
+  constexpr bool formattable_pointer =
+      !std::is_same<decltype(arg), const unformattable_pointer&>::value;
+  static_assert(formattable_pointer,
+                "Formatting of non-void pointers is disallowed.");
+
+  constexpr bool formattable =
+      !std::is_same<decltype(arg), const unformattable&>::value;
+  static_assert(
+      formattable,
+      "Cannot format an argument. To make type T formattable provide a "
+      "formatter<T> specialization: https://fmt.dev/latest/api.html#udt");
+  return {arg};
+}
+
+template <typename Context, typename T>
+FMT_CONSTEXPR auto make_arg(T&& value) -> basic_format_arg<Context> {
+  basic_format_arg<Context> arg;
+  arg.type_ = mapped_type_constant<T, Context>::value;
+  arg.value_ = make_value<Context>(value);
+  return arg;
+}
+
+// The type template parameter is there to avoid an ODR violation when using
+// a fallback formatter in one translation unit and an implicit conversion in
+// another (not recommended).
+template <bool IS_PACKED, typename Context, type, typename T,
+          FMT_ENABLE_IF(IS_PACKED)>
+FMT_CONSTEXPR FMT_INLINE auto make_arg(T&& val) -> value<Context> {
+  return make_value<Context>(val);
+}
+
+template <bool IS_PACKED, typename Context, type, typename T,
+          FMT_ENABLE_IF(!IS_PACKED)>
+FMT_CONSTEXPR inline auto make_arg(T&& value) -> basic_format_arg<Context> {
+  return make_arg<Context>(value);
+}
+FMT_END_DETAIL_NAMESPACE
+
+// Formatting context.
+template <typename OutputIt, typename Char> class basic_format_context {
+ public:
+  /** The character type for the output. */
+  using char_type = Char;
+
+ private:
+  OutputIt out_;
+  basic_format_args<basic_format_context> args_;
+  detail::locale_ref loc_;
+
+ public:
+  using iterator = OutputIt;
+  using format_arg = basic_format_arg<basic_format_context>;
+  using parse_context_type = basic_format_parse_context<Char>;
+  template <typename T> using formatter_type = formatter<T, char_type>;
+
+  basic_format_context(basic_format_context&&) = default;
+  basic_format_context(const basic_format_context&) = delete;
+  void operator=(const basic_format_context&) = delete;
+  /**
+   Constructs a ``basic_format_context`` object. References to the arguments are
+   stored in the object so make sure they have appropriate lifetimes.
+   */
+  constexpr basic_format_context(
+      OutputIt out, basic_format_args<basic_format_context> ctx_args,
+      detail::locale_ref loc = detail::locale_ref())
+      : out_(out), args_(ctx_args), loc_(loc) {}
+
+  constexpr auto arg(int id) const -> format_arg { return args_.get(id); }
+  FMT_CONSTEXPR auto arg(basic_string_view<char_type> name) -> format_arg {
+    return args_.get(name);
+  }
+  FMT_CONSTEXPR auto arg_id(basic_string_view<char_type> name) -> int {
+    return args_.get_id(name);
+  }
+  auto args() const -> const basic_format_args<basic_format_context>& {
+    return args_;
+  }
+
+  FMT_CONSTEXPR auto error_handler() -> detail::error_handler { return {}; }
+  void on_error(const char* message) { error_handler().on_error(message); }
+
+  // Returns an iterator to the beginning of the output range.
+  FMT_CONSTEXPR auto out() -> iterator { return out_; }
+
+  // Advances the begin iterator to ``it``.
+  void advance_to(iterator it) {
+    if (!detail::is_back_insert_iterator<iterator>()) out_ = it;
+  }
+
+  FMT_CONSTEXPR auto locale() -> detail::locale_ref { return loc_; }
+};
+
+template <typename Char>
+using buffer_context =
+    basic_format_context<detail::buffer_appender<Char>, Char>;
+using format_context = buffer_context<char>;
+
+// Workaround an alias issue: https://stackoverflow.com/q/62767544/471164.
+#define FMT_BUFFER_CONTEXT(Char) \
+  basic_format_context<detail::buffer_appender<Char>, Char>
+
+template <typename T, typename Char = char>
+using is_formattable = bool_constant<
+    !std::is_base_of<detail::unformattable,
+                     decltype(detail::arg_mapper<buffer_context<Char>>().map(
+                         std::declval<T>()))>::value &&
+    !detail::has_fallback_formatter<T, Char>::value>;
+
+/**
+  \rst
+  An array of references to arguments. It can be implicitly converted into
+  `~fmt::basic_format_args` for passing into type-erased formatting functions
+  such as `~fmt::vformat`.
+  \endrst
+ */
+template <typename Context, typename... Args>
+class format_arg_store
+#if FMT_GCC_VERSION && FMT_GCC_VERSION < 409
+    // Workaround a GCC template argument substitution bug.
+    : public basic_format_args<Context>
+#endif
+{
+ private:
+  static const size_t num_args = sizeof...(Args);
+  static const size_t num_named_args = detail::count_named_args<Args...>();
+  static const bool is_packed = num_args <= detail::max_packed_args;
+
+  using value_type = conditional_t<is_packed, detail::value<Context>,
+                                   basic_format_arg<Context>>;
+
+  detail::arg_data<value_type, typename Context::char_type, num_args,
+                   num_named_args>
+      data_;
+
+  friend class basic_format_args<Context>;
+
+  static constexpr unsigned long long desc =
+      (is_packed ? detail::encode_types<Context, Args...>()
+                 : detail::is_unpacked_bit | num_args) |
+      (num_named_args != 0
+           ? static_cast<unsigned long long>(detail::has_named_args_bit)
+           : 0);
+
+ public:
+  template <typename... T>
+  FMT_CONSTEXPR FMT_INLINE format_arg_store(T&&... args)
+      :
+#if FMT_GCC_VERSION && FMT_GCC_VERSION < 409
+        basic_format_args<Context>(*this),
+#endif
+        data_{detail::make_arg<
+            is_packed, Context,
+            detail::mapped_type_constant<remove_cvref_t<T>, Context>::value>(
+            FMT_FORWARD(args))...} {
+    detail::init_named_args(data_.named_args(), 0, 0, args...);
+  }
+};
+
+/**
+  \rst
+  Constructs a `~fmt::format_arg_store` object that contains references to
+  arguments and can be implicitly converted to `~fmt::format_args`. `Context`
+  can be omitted in which case it defaults to `~fmt::context`.
+  See `~fmt::arg` for lifetime considerations.
+  \endrst
+ */
+template <typename Context = format_context, typename... Args>
+constexpr auto make_format_args(Args&&... args)
+    -> format_arg_store<Context, remove_cvref_t<Args>...> {
+  return {FMT_FORWARD(args)...};
+}
+
+/**
+  \rst
+  Returns a named argument to be used in a formatting function.
+  It should only be used in a call to a formatting function or
+  `dynamic_format_arg_store::push_back`.
+
+  **Example**::
+
+    fmt::print("Elapsed time: {s:.2f} seconds", fmt::arg("s", 1.23));
+  \endrst
+ */
+template <typename Char, typename T>
+inline auto arg(const Char* name, const T& arg) -> detail::named_arg<Char, T> {
+  static_assert(!detail::is_named_arg<T>(), "nested named arguments");
+  return {name, arg};
+}
+
+/**
+  \rst
+  A view of a collection of formatting arguments. To avoid lifetime issues it
+  should only be used as a parameter type in type-erased functions such as
+  ``vformat``::
+
+    void vlog(string_view format_str, format_args args);  // OK
+    format_args args = make_format_args(42);  // Error: dangling reference
+  \endrst
+ */
+template <typename Context> class basic_format_args {
+ public:
+  using size_type = int;
+  using format_arg = basic_format_arg<Context>;
+
+ private:
+  // A descriptor that contains information about formatting arguments.
+  // If the number of arguments is less or equal to max_packed_args then
+  // argument types are passed in the descriptor. This reduces binary code size
+  // per formatting function call.
+  unsigned long long desc_;
+  union {
+    // If is_packed() returns true then argument values are stored in values_;
+    // otherwise they are stored in args_. This is done to improve cache
+    // locality and reduce compiled code size since storing larger objects
+    // may require more code (at least on x86-64) even if the same amount of
+    // data is actually copied to stack. It saves ~10% on the bloat test.
+    const detail::value<Context>* values_;
+    const format_arg* args_;
+  };
+
+  constexpr auto is_packed() const -> bool {
+    return (desc_ & detail::is_unpacked_bit) == 0;
+  }
+  auto has_named_args() const -> bool {
+    return (desc_ & detail::has_named_args_bit) != 0;
+  }
+
+  FMT_CONSTEXPR auto type(int index) const -> detail::type {
+    int shift = index * detail::packed_arg_bits;
+    unsigned int mask = (1 << detail::packed_arg_bits) - 1;
+    return static_cast<detail::type>((desc_ >> shift) & mask);
+  }
+
+  constexpr FMT_INLINE basic_format_args(unsigned long long desc,
+                                         const detail::value<Context>* values)
+      : desc_(desc), values_(values) {}
+  constexpr basic_format_args(unsigned long long desc, const format_arg* args)
+      : desc_(desc), args_(args) {}
+
+ public:
+  constexpr basic_format_args() : desc_(0), args_(nullptr) {}
+
+  /**
+   \rst
+   Constructs a `basic_format_args` object from `~fmt::format_arg_store`.
+   \endrst
+   */
+  template <typename... Args>
+  constexpr FMT_INLINE basic_format_args(
+      const format_arg_store<Context, Args...>& store)
+      : basic_format_args(format_arg_store<Context, Args...>::desc,
+                          store.data_.args()) {}
+
+  /**
+   \rst
+   Constructs a `basic_format_args` object from
+   `~fmt::dynamic_format_arg_store`.
+   \endrst
+   */
+  constexpr FMT_INLINE basic_format_args(
+      const dynamic_format_arg_store<Context>& store)
+      : basic_format_args(store.get_types(), store.data()) {}
+
+  /**
+   \rst
+   Constructs a `basic_format_args` object from a dynamic set of arguments.
+   \endrst
+   */
+  constexpr basic_format_args(const format_arg* args, int count)
+      : basic_format_args(detail::is_unpacked_bit | detail::to_unsigned(count),
+                          args) {}
+
+  /** Returns the argument with the specified id. */
+  FMT_CONSTEXPR auto get(int id) const -> format_arg {
+    format_arg arg;
+    if (!is_packed()) {
+      if (id < max_size()) arg = args_[id];
+      return arg;
+    }
+    if (id >= detail::max_packed_args) return arg;
+    arg.type_ = type(id);
+    if (arg.type_ == detail::type::none_type) return arg;
+    arg.value_ = values_[id];
+    return arg;
+  }
+
+  template <typename Char>
+  auto get(basic_string_view<Char> name) const -> format_arg {
+    int id = get_id(name);
+    return id >= 0 ? get(id) : format_arg();
+  }
+
+  template <typename Char>
+  auto get_id(basic_string_view<Char> name) const -> int {
+    if (!has_named_args()) return -1;
+    const auto& named_args =
+        (is_packed() ? values_[-1] : args_[-1].value_).named_args;
+    for (size_t i = 0; i < named_args.size; ++i) {
+      if (named_args.data[i].name == name) return named_args.data[i].id;
+    }
+    return -1;
+  }
+
+  auto max_size() const -> int {
+    unsigned long long max_packed = detail::max_packed_args;
+    return static_cast<int>(is_packed() ? max_packed
+                                        : desc_ & ~detail::is_unpacked_bit);
+  }
+};
+
+/** An alias to ``basic_format_args<format_context>``. */
+// A separate type would result in shorter symbols but break ABI compatibility
+// between clang and gcc on ARM (#1919).
+using format_args = basic_format_args<format_context>;
+
+// We cannot use enum classes as bit fields because of a gcc bug, so we put them
+// in namespaces instead (https://gcc.gnu.org/bugzilla/show_bug.cgi?id=61414).
+// Additionally, if an underlying type is specified, older gcc incorrectly warns
+// that the type is too small. Both bugs are fixed in gcc 9.3.
+#if FMT_GCC_VERSION && FMT_GCC_VERSION < 903
+#  define FMT_ENUM_UNDERLYING_TYPE(type)
+#else
+#  define FMT_ENUM_UNDERLYING_TYPE(type) : type
+#endif
+namespace align {
+enum type FMT_ENUM_UNDERLYING_TYPE(unsigned char){none, left, right, center,
+                                                  numeric};
+}
+using align_t = align::type;
+namespace sign {
+enum type FMT_ENUM_UNDERLYING_TYPE(unsigned char){none, minus, plus, space};
+}
+using sign_t = sign::type;
+
+FMT_BEGIN_DETAIL_NAMESPACE
+
+// Workaround an array initialization issue in gcc 4.8.
+template <typename Char> struct fill_t {
+ private:
+  enum { max_size = 4 };
+  Char data_[max_size] = {Char(' '), Char(0), Char(0), Char(0)};
+  unsigned char size_ = 1;
+
+ public:
+  FMT_CONSTEXPR void operator=(basic_string_view<Char> s) {
+    auto size = s.size();
+    if (size > max_size) return throw_format_error("invalid fill");
+    for (size_t i = 0; i < size; ++i) data_[i] = s[i];
+    size_ = static_cast<unsigned char>(size);
+  }
+
+  constexpr auto size() const -> size_t { return size_; }
+  constexpr auto data() const -> const Char* { return data_; }
+
+  FMT_CONSTEXPR auto operator[](size_t index) -> Char& { return data_[index]; }
+  FMT_CONSTEXPR auto operator[](size_t index) const -> const Char& {
+    return data_[index];
+  }
+};
+FMT_END_DETAIL_NAMESPACE
+
+enum class presentation_type : unsigned char {
+  none,
+  // Integer types should go first,
+  dec,             // 'd'
+  oct,             // 'o'
+  hex_lower,       // 'x'
+  hex_upper,       // 'X'
+  bin_lower,       // 'b'
+  bin_upper,       // 'B'
+  hexfloat_lower,  // 'a'
+  hexfloat_upper,  // 'A'
+  exp_lower,       // 'e'
+  exp_upper,       // 'E'
+  fixed_lower,     // 'f'
+  fixed_upper,     // 'F'
+  general_lower,   // 'g'
+  general_upper,   // 'G'
+  chr,             // 'c'
+  string,          // 's'
+  pointer,         // 'p'
+  debug            // '?'
+};
+
+// Format specifiers for built-in and string types.
+template <typename Char> struct basic_format_specs {
+  int width;
+  int precision;
+  presentation_type type;
+  align_t align : 4;
+  sign_t sign : 3;
+  bool alt : 1;  // Alternate form ('#').
+  bool localized : 1;
+  detail::fill_t<Char> fill;
+
+  constexpr basic_format_specs()
+      : width(0),
+        precision(-1),
+        type(presentation_type::none),
+        align(align::none),
+        sign(sign::none),
+        alt(false),
+        localized(false) {}
+};
+
+using format_specs = basic_format_specs<char>;
+
+FMT_BEGIN_DETAIL_NAMESPACE
+
+enum class arg_id_kind { none, index, name };
+
+// An argument reference.
+template <typename Char> struct arg_ref {
+  FMT_CONSTEXPR arg_ref() : kind(arg_id_kind::none), val() {}
+
+  FMT_CONSTEXPR explicit arg_ref(int index)
+      : kind(arg_id_kind::index), val(index) {}
+  FMT_CONSTEXPR explicit arg_ref(basic_string_view<Char> name)
+      : kind(arg_id_kind::name), val(name) {}
+
+  FMT_CONSTEXPR auto operator=(int idx) -> arg_ref& {
+    kind = arg_id_kind::index;
+    val.index = idx;
+    return *this;
+  }
+
+  arg_id_kind kind;
+  union value {
+    FMT_CONSTEXPR value(int id = 0) : index{id} {}
+    FMT_CONSTEXPR value(basic_string_view<Char> n) : name(n) {}
+
+    int index;
+    basic_string_view<Char> name;
+  } val;
+};
+
+// Format specifiers with width and precision resolved at formatting rather
+// than parsing time to allow re-using the same parsed specifiers with
+// different sets of arguments (precompilation of format strings).
+template <typename Char>
+struct dynamic_format_specs : basic_format_specs<Char> {
+  arg_ref<Char> width_ref;
+  arg_ref<Char> precision_ref;
+};
+
+struct auto_id {};
+
+// A format specifier handler that sets fields in basic_format_specs.
+template <typename Char> class specs_setter {
+ protected:
+  basic_format_specs<Char>& specs_;
+
+ public:
+  explicit FMT_CONSTEXPR specs_setter(basic_format_specs<Char>& specs)
+      : specs_(specs) {}
+
+  FMT_CONSTEXPR specs_setter(const specs_setter& other)
+      : specs_(other.specs_) {}
+
+  FMT_CONSTEXPR void on_align(align_t align) { specs_.align = align; }
+  FMT_CONSTEXPR void on_fill(basic_string_view<Char> fill) {
+    specs_.fill = fill;
+  }
+  FMT_CONSTEXPR void on_sign(sign_t s) { specs_.sign = s; }
+  FMT_CONSTEXPR void on_hash() { specs_.alt = true; }
+  FMT_CONSTEXPR void on_localized() { specs_.localized = true; }
+
+  FMT_CONSTEXPR void on_zero() {
+    if (specs_.align == align::none) specs_.align = align::numeric;
+    specs_.fill[0] = Char('0');
+  }
+
+  FMT_CONSTEXPR void on_width(int width) { specs_.width = width; }
+  FMT_CONSTEXPR void on_precision(int precision) {
+    specs_.precision = precision;
+  }
+  FMT_CONSTEXPR void end_precision() {}
+
+  FMT_CONSTEXPR void on_type(presentation_type type) { specs_.type = type; }
+};
+
+// Format spec handler that saves references to arguments representing dynamic
+// width and precision to be resolved at formatting time.
+template <typename ParseContext>
+class dynamic_specs_handler
+    : public specs_setter<typename ParseContext::char_type> {
+ public:
+  using char_type = typename ParseContext::char_type;
+
+  FMT_CONSTEXPR dynamic_specs_handler(dynamic_format_specs<char_type>& specs,
+                                      ParseContext& ctx)
+      : specs_setter<char_type>(specs), specs_(specs), context_(ctx) {}
+
+  FMT_CONSTEXPR dynamic_specs_handler(const dynamic_specs_handler& other)
+      : specs_setter<char_type>(other),
+        specs_(other.specs_),
+        context_(other.context_) {}
+
+  template <typename Id> FMT_CONSTEXPR void on_dynamic_width(Id arg_id) {
+    specs_.width_ref = make_arg_ref(arg_id);
+  }
+
+  template <typename Id> FMT_CONSTEXPR void on_dynamic_precision(Id arg_id) {
+    specs_.precision_ref = make_arg_ref(arg_id);
+  }
+
+  FMT_CONSTEXPR void on_error(const char* message) {
+    context_.on_error(message);
+  }
+
+ private:
+  dynamic_format_specs<char_type>& specs_;
+  ParseContext& context_;
+
+  using arg_ref_type = arg_ref<char_type>;
+
+  FMT_CONSTEXPR auto make_arg_ref(int arg_id) -> arg_ref_type {
+    context_.check_arg_id(arg_id);
+    context_.check_dynamic_spec(arg_id);
+    return arg_ref_type(arg_id);
+  }
+
+  FMT_CONSTEXPR auto make_arg_ref(auto_id) -> arg_ref_type {
+    int arg_id = context_.next_arg_id();
+    context_.check_dynamic_spec(arg_id);
+    return arg_ref_type(arg_id);
+  }
+
+  FMT_CONSTEXPR auto make_arg_ref(basic_string_view<char_type> arg_id)
+      -> arg_ref_type {
+    context_.check_arg_id(arg_id);
+    basic_string_view<char_type> format_str(
+        context_.begin(), to_unsigned(context_.end() - context_.begin()));
+    return arg_ref_type(arg_id);
+  }
+};
+
+template <typename Char> constexpr bool is_ascii_letter(Char c) {
+  return (c >= 'a' && c <= 'z') || (c >= 'A' && c <= 'Z');
+}
+
+// Converts a character to ASCII. Returns a number > 127 on conversion failure.
+template <typename Char, FMT_ENABLE_IF(std::is_integral<Char>::value)>
+constexpr auto to_ascii(Char c) -> Char {
+  return c;
+}
+template <typename Char, FMT_ENABLE_IF(std::is_enum<Char>::value)>
+constexpr auto to_ascii(Char c) -> underlying_t<Char> {
+  return c;
+}
+
+FMT_CONSTEXPR inline auto code_point_length_impl(char c) -> int {
+  return "\1\1\1\1\1\1\1\1\1\1\1\1\1\1\1\1\0\0\0\0\0\0\0\0\2\2\2\2\3\3\4"
+      [static_cast<unsigned char>(c) >> 3];
+}
+
+template <typename Char>
+FMT_CONSTEXPR auto code_point_length(const Char* begin) -> int {
+  if (const_check(sizeof(Char) != 1)) return 1;
+  int len = code_point_length_impl(static_cast<char>(*begin));
+
+  // Compute the pointer to the next character early so that the next
+  // iteration can start working on the next character. Neither Clang
+  // nor GCC figure out this reordering on their own.
+  return len + !len;
+}
+
+// Return the result via the out param to workaround gcc bug 77539.
+template <bool IS_CONSTEXPR, typename T, typename Ptr = const T*>
+FMT_CONSTEXPR auto find(Ptr first, Ptr last, T value, Ptr& out) -> bool {
+  for (out = first; out != last; ++out) {
+    if (*out == value) return true;
+  }
+  return false;
+}
+
+template <>
+inline auto find<false, char>(const char* first, const char* last, char value,
+                              const char*& out) -> bool {
+  out = static_cast<const char*>(
+      std::memchr(first, value, to_unsigned(last - first)));
+  return out != nullptr;
+}
+
+// Parses the range [begin, end) as an unsigned integer. This function assumes
+// that the range is non-empty and the first character is a digit.
+template <typename Char>
+FMT_CONSTEXPR auto parse_nonnegative_int(const Char*& begin, const Char* end,
+                                         int error_value) noexcept -> int {
+  FMT_ASSERT(begin != end && '0' <= *begin && *begin <= '9', "");
+  unsigned value = 0, prev = 0;
+  auto p = begin;
+  do {
+    prev = value;
+    value = value * 10 + unsigned(*p - '0');
+    ++p;
+  } while (p != end && '0' <= *p && *p <= '9');
+  auto num_digits = p - begin;
+  begin = p;
+  if (num_digits <= std::numeric_limits<int>::digits10)
+    return static_cast<int>(value);
+  // Check for overflow.
+  const unsigned max = to_unsigned((std::numeric_limits<int>::max)());
+  return num_digits == std::numeric_limits<int>::digits10 + 1 &&
+                 prev * 10ull + unsigned(p[-1] - '0') <= max
+             ? static_cast<int>(value)
+             : error_value;
+}
+
+// Parses fill and alignment.
+template <typename Char, typename Handler>
+FMT_CONSTEXPR auto parse_align(const Char* begin, const Char* end,
+                               Handler&& handler) -> const Char* {
+  FMT_ASSERT(begin != end, "");
+  auto align = align::none;
+  auto p = begin + code_point_length(begin);
+  if (end - p <= 0) p = begin;
+  for (;;) {
+    switch (to_ascii(*p)) {
+    case '<':
+      align = align::left;
+      break;
+    case '>':
+      align = align::right;
+      break;
+    case '^':
+      align = align::center;
+      break;
+    default:
+      break;
+    }
+    if (align != align::none) {
+      if (p != begin) {
+        auto c = *begin;
+        if (c == '{')
+          return handler.on_error("invalid fill character '{'"), begin;
+        handler.on_fill(basic_string_view<Char>(begin, to_unsigned(p - begin)));
+        begin = p + 1;
+      } else
+        ++begin;
+      handler.on_align(align);
+      break;
+    } else if (p == begin) {
+      break;
+    }
+    p = begin;
+  }
+  return begin;
+}
+
+template <typename Char> FMT_CONSTEXPR bool is_name_start(Char c) {
+  return ('a' <= c && c <= 'z') || ('A' <= c && c <= 'Z') || '_' == c;
+}
+
+template <typename Char, typename IDHandler>
+FMT_CONSTEXPR auto do_parse_arg_id(const Char* begin, const Char* end,
+                                   IDHandler&& handler) -> const Char* {
+  FMT_ASSERT(begin != end, "");
+  Char c = *begin;
+  if (c >= '0' && c <= '9') {
+    int index = 0;
+    if (c != '0')
+      index =
+          parse_nonnegative_int(begin, end, (std::numeric_limits<int>::max)());
+    else
+      ++begin;
+    if (begin == end || (*begin != '}' && *begin != ':'))
+      handler.on_error("invalid format string");
+    else
+      handler(index);
+    return begin;
+  }
+  if (!is_name_start(c)) {
+    handler.on_error("invalid format string");
+    return begin;
+  }
+  auto it = begin;
+  do {
+    ++it;
+  } while (it != end && (is_name_start(c = *it) || ('0' <= c && c <= '9')));
+  handler(basic_string_view<Char>(begin, to_unsigned(it - begin)));
+  return it;
+}
+
+template <typename Char, typename IDHandler>
+FMT_CONSTEXPR FMT_INLINE auto parse_arg_id(const Char* begin, const Char* end,
+                                           IDHandler&& handler) -> const Char* {
+  Char c = *begin;
+  if (c != '}' && c != ':') return do_parse_arg_id(begin, end, handler);
+  handler();
+  return begin;
+}
+
+template <typename Char, typename Handler>
+FMT_CONSTEXPR auto parse_width(const Char* begin, const Char* end,
+                               Handler&& handler) -> const Char* {
+  using detail::auto_id;
+  struct width_adapter {
+    Handler& handler;
+
+    FMT_CONSTEXPR void operator()() { handler.on_dynamic_width(auto_id()); }
+    FMT_CONSTEXPR void operator()(int id) { handler.on_dynamic_width(id); }
+    FMT_CONSTEXPR void operator()(basic_string_view<Char> id) {
+      handler.on_dynamic_width(id);
+    }
+    FMT_CONSTEXPR void on_error(const char* message) {
+      if (message) handler.on_error(message);
+    }
+  };
+
+  FMT_ASSERT(begin != end, "");
+  if ('0' <= *begin && *begin <= '9') {
+    int width = parse_nonnegative_int(begin, end, -1);
+    if (width != -1)
+      handler.on_width(width);
+    else
+      handler.on_error("number is too big");
+  } else if (*begin == '{') {
+    ++begin;
+    if (begin != end) begin = parse_arg_id(begin, end, width_adapter{handler});
+    if (begin == end || *begin != '}')
+      return handler.on_error("invalid format string"), begin;
+    ++begin;
+  }
+  return begin;
+}
+
+template <typename Char, typename Handler>
+FMT_CONSTEXPR auto parse_precision(const Char* begin, const Char* end,
+                                   Handler&& handler) -> const Char* {
+  using detail::auto_id;
+  struct precision_adapter {
+    Handler& handler;
+
+    FMT_CONSTEXPR void operator()() { handler.on_dynamic_precision(auto_id()); }
+    FMT_CONSTEXPR void operator()(int id) { handler.on_dynamic_precision(id); }
+    FMT_CONSTEXPR void operator()(basic_string_view<Char> id) {
+      handler.on_dynamic_precision(id);
+    }
+    FMT_CONSTEXPR void on_error(const char* message) {
+      if (message) handler.on_error(message);
+    }
+  };
+
+  ++begin;
+  auto c = begin != end ? *begin : Char();
+  if ('0' <= c && c <= '9') {
+    auto precision = parse_nonnegative_int(begin, end, -1);
+    if (precision != -1)
+      handler.on_precision(precision);
+    else
+      handler.on_error("number is too big");
+  } else if (c == '{') {
+    ++begin;
+    if (begin != end)
+      begin = parse_arg_id(begin, end, precision_adapter{handler});
+    if (begin == end || *begin++ != '}')
+      return handler.on_error("invalid format string"), begin;
+  } else {
+    return handler.on_error("missing precision specifier"), begin;
+  }
+  handler.end_precision();
+  return begin;
+}
+
+template <typename Char>
+FMT_CONSTEXPR auto parse_presentation_type(Char type) -> presentation_type {
+  switch (to_ascii(type)) {
+  case 'd':
+    return presentation_type::dec;
+  case 'o':
+    return presentation_type::oct;
+  case 'x':
+    return presentation_type::hex_lower;
+  case 'X':
+    return presentation_type::hex_upper;
+  case 'b':
+    return presentation_type::bin_lower;
+  case 'B':
+    return presentation_type::bin_upper;
+  case 'a':
+    return presentation_type::hexfloat_lower;
+  case 'A':
+    return presentation_type::hexfloat_upper;
+  case 'e':
+    return presentation_type::exp_lower;
+  case 'E':
+    return presentation_type::exp_upper;
+  case 'f':
+    return presentation_type::fixed_lower;
+  case 'F':
+    return presentation_type::fixed_upper;
+  case 'g':
+    return presentation_type::general_lower;
+  case 'G':
+    return presentation_type::general_upper;
+  case 'c':
+    return presentation_type::chr;
+  case 's':
+    return presentation_type::string;
+  case 'p':
+    return presentation_type::pointer;
+  case '?':
+    return presentation_type::debug;
+  default:
+    return presentation_type::none;
+  }
+}
+
+// Parses standard format specifiers and sends notifications about parsed
+// components to handler.
+template <typename Char, typename SpecHandler>
+FMT_CONSTEXPR FMT_INLINE auto parse_format_specs(const Char* begin,
+                                                 const Char* end,
+                                                 SpecHandler&& handler)
+    -> const Char* {
+  if (1 < end - begin && begin[1] == '}' && is_ascii_letter(*begin) &&
+      *begin != 'L') {
+    presentation_type type = parse_presentation_type(*begin++);
+    if (type == presentation_type::none)
+      handler.on_error("invalid type specifier");
+    handler.on_type(type);
+    return begin;
+  }
+
+  if (begin == end) return begin;
+
+  begin = parse_align(begin, end, handler);
+  if (begin == end) return begin;
+
+  // Parse sign.
+  switch (to_ascii(*begin)) {
+  case '+':
+    handler.on_sign(sign::plus);
+    ++begin;
+    break;
+  case '-':
+    handler.on_sign(sign::minus);
+    ++begin;
+    break;
+  case ' ':
+    handler.on_sign(sign::space);
+    ++begin;
+    break;
+  default:
+    break;
+  }
+  if (begin == end) return begin;
+
+  if (*begin == '#') {
+    handler.on_hash();
+    if (++begin == end) return begin;
+  }
+
+  // Parse zero flag.
+  if (*begin == '0') {
+    handler.on_zero();
+    if (++begin == end) return begin;
+  }
+
+  begin = parse_width(begin, end, handler);
+  if (begin == end) return begin;
+
+  // Parse precision.
+  if (*begin == '.') {
+    begin = parse_precision(begin, end, handler);
+    if (begin == end) return begin;
+  }
+
+  if (*begin == 'L') {
+    handler.on_localized();
+    ++begin;
+  }
+
+  // Parse type.
+  if (begin != end && *begin != '}') {
+    presentation_type type = parse_presentation_type(*begin++);
+    if (type == presentation_type::none)
+      handler.on_error("invalid type specifier");
+    handler.on_type(type);
+  }
+  return begin;
+}
+
+template <typename Char, typename Handler>
+FMT_CONSTEXPR auto parse_replacement_field(const Char* begin, const Char* end,
+                                           Handler&& handler) -> const Char* {
+  struct id_adapter {
+    Handler& handler;
+    int arg_id;
+
+    FMT_CONSTEXPR void operator()() { arg_id = handler.on_arg_id(); }
+    FMT_CONSTEXPR void operator()(int id) { arg_id = handler.on_arg_id(id); }
+    FMT_CONSTEXPR void operator()(basic_string_view<Char> id) {
+      arg_id = handler.on_arg_id(id);
+    }
+    FMT_CONSTEXPR void on_error(const char* message) {
+      if (message) handler.on_error(message);
+    }
+  };
+
+  ++begin;
+  if (begin == end) return handler.on_error("invalid format string"), end;
+  if (*begin == '}') {
+    handler.on_replacement_field(handler.on_arg_id(), begin);
+  } else if (*begin == '{') {
+    handler.on_text(begin, begin + 1);
+  } else {
+    auto adapter = id_adapter{handler, 0};
+    begin = parse_arg_id(begin, end, adapter);
+    Char c = begin != end ? *begin : Char();
+    if (c == '}') {
+      handler.on_replacement_field(adapter.arg_id, begin);
+    } else if (c == ':') {
+      begin = handler.on_format_specs(adapter.arg_id, begin + 1, end);
+      if (begin == end || *begin != '}')
+        return handler.on_error("unknown format specifier"), end;
+    } else {
+      return handler.on_error("missing '}' in format string"), end;
+    }
+  }
+  return begin + 1;
+}
+
+template <bool IS_CONSTEXPR, typename Char, typename Handler>
+FMT_CONSTEXPR FMT_INLINE void parse_format_string(
+    basic_string_view<Char> format_str, Handler&& handler) {
+  // Workaround a name-lookup bug in MSVC's modules implementation.
+  using detail::find;
+
+  auto begin = format_str.data();
+  auto end = begin + format_str.size();
+  if (end - begin < 32) {
+    // Use a simple loop instead of memchr for small strings.
+    const Char* p = begin;
+    while (p != end) {
+      auto c = *p++;
+      if (c == '{') {
+        handler.on_text(begin, p - 1);
+        begin = p = parse_replacement_field(p - 1, end, handler);
+      } else if (c == '}') {
+        if (p == end || *p != '}')
+          return handler.on_error("unmatched '}' in format string");
+        handler.on_text(begin, p);
+        begin = ++p;
+      }
+    }
+    handler.on_text(begin, end);
+    return;
+  }
+  struct writer {
+    FMT_CONSTEXPR void operator()(const Char* from, const Char* to) {
+      if (from == to) return;
+      for (;;) {
+        const Char* p = nullptr;
+        if (!find<IS_CONSTEXPR>(from, to, Char('}'), p))
+          return handler_.on_text(from, to);
+        ++p;
+        if (p == to || *p != '}')
+          return handler_.on_error("unmatched '}' in format string");
+        handler_.on_text(from, p);
+        from = p + 1;
+      }
+    }
+    Handler& handler_;
+  } write = {handler};
+  while (begin != end) {
+    // Doing two passes with memchr (one for '{' and another for '}') is up to
+    // 2.5x faster than the naive one-pass implementation on big format strings.
+    const Char* p = begin;
+    if (*begin != '{' && !find<IS_CONSTEXPR>(begin + 1, end, Char('{'), p))
+      return write(begin, end);
+    write(begin, p);
+    begin = parse_replacement_field(p, end, handler);
+  }
+}
+
+template <typename T, bool = is_named_arg<T>::value> struct strip_named_arg {
+  using type = T;
+};
+template <typename T> struct strip_named_arg<T, true> {
+  using type = remove_cvref_t<decltype(T::value)>;
+};
+
+template <typename T, typename ParseContext>
+FMT_CONSTEXPR auto parse_format_specs(ParseContext& ctx)
+    -> decltype(ctx.begin()) {
+  using char_type = typename ParseContext::char_type;
+  using context = buffer_context<char_type>;
+  using stripped_type = typename strip_named_arg<T>::type;
+  using mapped_type = conditional_t<
+      mapped_type_constant<T, context>::value != type::custom_type,
+      decltype(arg_mapper<context>().map(std::declval<const T&>())),
+      stripped_type>;
+  auto f = conditional_t<has_formatter<mapped_type, context>::value,
+                         formatter<mapped_type, char_type>,
+                         fallback_formatter<stripped_type, char_type>>();
+  return f.parse(ctx);
+}
+
+template <typename ErrorHandler>
+FMT_CONSTEXPR void check_int_type_spec(presentation_type type,
+                                       ErrorHandler&& eh) {
+  if (type > presentation_type::bin_upper && type != presentation_type::chr)
+    eh.on_error("invalid type specifier");
+}
+
+// Checks char specs and returns true if the type spec is char (and not int).
+template <typename Char, typename ErrorHandler = error_handler>
+FMT_CONSTEXPR auto check_char_specs(const basic_format_specs<Char>& specs,
+                                    ErrorHandler&& eh = {}) -> bool {
+  if (specs.type != presentation_type::none &&
+      specs.type != presentation_type::chr &&
+      specs.type != presentation_type::debug) {
+    check_int_type_spec(specs.type, eh);
+    return false;
+  }
+  if (specs.align == align::numeric || specs.sign != sign::none || specs.alt)
+    eh.on_error("invalid format specifier for char");
+  return true;
+}
+
+// A floating-point presentation format.
+enum class float_format : unsigned char {
+  general,  // General: exponent notation or fixed point based on magnitude.
+  exp,      // Exponent notation with the default precision of 6, e.g. 1.2e-3.
+  fixed,    // Fixed point with the default precision of 6, e.g. 0.0012.
+  hex
+};
+
+struct float_specs {
+  int precision;
+  float_format format : 8;
+  sign_t sign : 8;
+  bool upper : 1;
+  bool locale : 1;
+  bool binary32 : 1;
+  bool showpoint : 1;
+};
+
+template <typename ErrorHandler = error_handler, typename Char>
+FMT_CONSTEXPR auto parse_float_type_spec(const basic_format_specs<Char>& specs,
+                                         ErrorHandler&& eh = {})
+    -> float_specs {
+  auto result = float_specs();
+  result.showpoint = specs.alt;
+  result.locale = specs.localized;
+  switch (specs.type) {
+  case presentation_type::none:
+    result.format = float_format::general;
+    break;
+  case presentation_type::general_upper:
+    result.upper = true;
+    FMT_FALLTHROUGH;
+  case presentation_type::general_lower:
+    result.format = float_format::general;
+    break;
+  case presentation_type::exp_upper:
+    result.upper = true;
+    FMT_FALLTHROUGH;
+  case presentation_type::exp_lower:
+    result.format = float_format::exp;
+    result.showpoint |= specs.precision != 0;
+    break;
+  case presentation_type::fixed_upper:
+    result.upper = true;
+    FMT_FALLTHROUGH;
+  case presentation_type::fixed_lower:
+    result.format = float_format::fixed;
+    result.showpoint |= specs.precision != 0;
+    break;
+  case presentation_type::hexfloat_upper:
+    result.upper = true;
+    FMT_FALLTHROUGH;
+  case presentation_type::hexfloat_lower:
+    result.format = float_format::hex;
+    break;
+  default:
+    eh.on_error("invalid type specifier");
+    break;
+  }
+  return result;
+}
+
+template <typename ErrorHandler = error_handler>
+FMT_CONSTEXPR auto check_cstring_type_spec(presentation_type type,
+                                           ErrorHandler&& eh = {}) -> bool {
+  if (type == presentation_type::none || type == presentation_type::string ||
+      type == presentation_type::debug)
+    return true;
+  if (type != presentation_type::pointer) eh.on_error("invalid type specifier");
+  return false;
+}
+
+template <typename ErrorHandler = error_handler>
+FMT_CONSTEXPR void check_string_type_spec(presentation_type type,
+                                          ErrorHandler&& eh = {}) {
+  if (type != presentation_type::none && type != presentation_type::string &&
+      type != presentation_type::debug)
+    eh.on_error("invalid type specifier");
+}
+
+template <typename ErrorHandler>
+FMT_CONSTEXPR void check_pointer_type_spec(presentation_type type,
+                                           ErrorHandler&& eh) {
+  if (type != presentation_type::none && type != presentation_type::pointer)
+    eh.on_error("invalid type specifier");
+}
+
+// A parse_format_specs handler that checks if specifiers are consistent with
+// the argument type.
+template <typename Handler> class specs_checker : public Handler {
+ private:
+  detail::type arg_type_;
+
+  FMT_CONSTEXPR void require_numeric_argument() {
+    if (!is_arithmetic_type(arg_type_))
+      this->on_error("format specifier requires numeric argument");
+  }
+
+ public:
+  FMT_CONSTEXPR specs_checker(const Handler& handler, detail::type arg_type)
+      : Handler(handler), arg_type_(arg_type) {}
+
+  FMT_CONSTEXPR void on_align(align_t align) {
+    if (align == align::numeric) require_numeric_argument();
+    Handler::on_align(align);
+  }
+
+  FMT_CONSTEXPR void on_sign(sign_t s) {
+    require_numeric_argument();
+    if (is_integral_type(arg_type_) && arg_type_ != type::int_type &&
+        arg_type_ != type::long_long_type && arg_type_ != type::int128_type &&
+        arg_type_ != type::char_type) {
+      this->on_error("format specifier requires signed argument");
+    }
+    Handler::on_sign(s);
+  }
+
+  FMT_CONSTEXPR void on_hash() {
+    require_numeric_argument();
+    Handler::on_hash();
+  }
+
+  FMT_CONSTEXPR void on_localized() {
+    require_numeric_argument();
+    Handler::on_localized();
+  }
+
+  FMT_CONSTEXPR void on_zero() {
+    require_numeric_argument();
+    Handler::on_zero();
+  }
+
+  FMT_CONSTEXPR void end_precision() {
+    if (is_integral_type(arg_type_) || arg_type_ == type::pointer_type)
+      this->on_error("precision not allowed for this argument type");
+  }
+};
+
+constexpr int invalid_arg_index = -1;
+
+#if FMT_USE_NONTYPE_TEMPLATE_ARGS
+template <int N, typename T, typename... Args, typename Char>
+constexpr auto get_arg_index_by_name(basic_string_view<Char> name) -> int {
+  if constexpr (detail::is_statically_named_arg<T>()) {
+    if (name == T::name) return N;
+  }
+  if constexpr (sizeof...(Args) > 0)
+    return get_arg_index_by_name<N + 1, Args...>(name);
+  (void)name;  // Workaround an MSVC bug about "unused" parameter.
+  return invalid_arg_index;
+}
+#endif
+
+template <typename... Args, typename Char>
+FMT_CONSTEXPR auto get_arg_index_by_name(basic_string_view<Char> name) -> int {
+#if FMT_USE_NONTYPE_TEMPLATE_ARGS
+  if constexpr (sizeof...(Args) > 0)
+    return get_arg_index_by_name<0, Args...>(name);
+#endif
+  (void)name;
+  return invalid_arg_index;
+}
+
+template <typename Char, typename ErrorHandler, typename... Args>
+class format_string_checker {
+ private:
+  // In the future basic_format_parse_context will replace compile_parse_context
+  // here and will use is_constant_evaluated and downcasting to access the data
+  // needed for compile-time checks: https://godbolt.org/z/GvWzcTjh1.
+  using parse_context_type = compile_parse_context<Char, ErrorHandler>;
+  static constexpr int num_args = sizeof...(Args);
+
+  // Format specifier parsing function.
+  using parse_func = const Char* (*)(parse_context_type&);
+
+  parse_context_type context_;
+  parse_func parse_funcs_[num_args > 0 ? static_cast<size_t>(num_args) : 1];
+  type types_[num_args > 0 ? static_cast<size_t>(num_args) : 1];
+
+ public:
+  explicit FMT_CONSTEXPR format_string_checker(
+      basic_string_view<Char> format_str, ErrorHandler eh)
+      : context_(format_str, num_args, types_, eh),
+        parse_funcs_{&parse_format_specs<Args, parse_context_type>...},
+        types_{  // NOLINT(clang-analyzer-optin.cplusplus.UninitializedObject)
+            mapped_type_constant<Args,
+                                 basic_format_context<Char*, Char>>::value...} {
+  }
+
+  FMT_CONSTEXPR void on_text(const Char*, const Char*) {}
+
+  FMT_CONSTEXPR auto on_arg_id() -> int { return context_.next_arg_id(); }
+  FMT_CONSTEXPR auto on_arg_id(int id) -> int {
+    return context_.check_arg_id(id), id;
+  }
+  FMT_CONSTEXPR auto on_arg_id(basic_string_view<Char> id) -> int {
+#if FMT_USE_NONTYPE_TEMPLATE_ARGS
+    auto index = get_arg_index_by_name<Args...>(id);
+    if (index == invalid_arg_index) on_error("named argument is not found");
+    return context_.check_arg_id(index), index;
+#else
+    (void)id;
+    on_error("compile-time checks for named arguments require C++20 support");
+    return 0;
+#endif
+  }
+
+  FMT_CONSTEXPR void on_replacement_field(int, const Char*) {}
+
+  FMT_CONSTEXPR auto on_format_specs(int id, const Char* begin, const Char*)
+      -> const Char* {
+    context_.advance_to(context_.begin() + (begin - &*context_.begin()));
+    // id >= 0 check is a workaround for gcc 10 bug (#2065).
+    return id >= 0 && id < num_args ? parse_funcs_[id](context_) : begin;
+  }
+
+  FMT_CONSTEXPR void on_error(const char* message) {
+    context_.on_error(message);
+  }
+};
+
+// Reports a compile-time error if S is not a valid format string.
+template <typename..., typename S, FMT_ENABLE_IF(!is_compile_string<S>::value)>
+FMT_INLINE void check_format_string(const S&) {
+#ifdef FMT_ENFORCE_COMPILE_STRING
+  static_assert(is_compile_string<S>::value,
+                "FMT_ENFORCE_COMPILE_STRING requires all format strings to use "
+                "FMT_STRING.");
+#endif
+}
+template <typename... Args, typename S,
+          FMT_ENABLE_IF(is_compile_string<S>::value)>
+void check_format_string(S format_str) {
+  FMT_CONSTEXPR auto s = basic_string_view<typename S::char_type>(format_str);
+  using checker = format_string_checker<typename S::char_type, error_handler,
+                                        remove_cvref_t<Args>...>;
+  FMT_CONSTEXPR bool invalid_format =
+      (parse_format_string<true>(s, checker(s, {})), true);
+  ignore_unused(invalid_format);
+}
+
+template <typename Char>
+void vformat_to(
+    buffer<Char>& buf, basic_string_view<Char> fmt,
+    basic_format_args<FMT_BUFFER_CONTEXT(type_identity_t<Char>)> args,
+    locale_ref loc = {});
+
+FMT_API void vprint_mojibake(std::FILE*, string_view, format_args);
+#ifndef _WIN32
+inline void vprint_mojibake(std::FILE*, string_view, format_args) {}
+#endif
+FMT_END_DETAIL_NAMESPACE
+
+// A formatter specialization for the core types corresponding to detail::type
+// constants.
+template <typename T, typename Char>
+struct formatter<T, Char,
+                 enable_if_t<detail::type_constant<T, Char>::value !=
+                             detail::type::custom_type>> {
+ private:
+  detail::dynamic_format_specs<Char> specs_;
+
+ public:
+  // Parses format specifiers stopping either at the end of the range or at the
+  // terminating '}'.
+  template <typename ParseContext>
+  FMT_CONSTEXPR auto parse(ParseContext& ctx) -> decltype(ctx.begin()) {
+    auto begin = ctx.begin(), end = ctx.end();
+    if (begin == end) return begin;
+    using handler_type = detail::dynamic_specs_handler<ParseContext>;
+    auto type = detail::type_constant<T, Char>::value;
+    auto checker =
+        detail::specs_checker<handler_type>(handler_type(specs_, ctx), type);
+    auto it = detail::parse_format_specs(begin, end, checker);
+    auto eh = ctx.error_handler();
+    switch (type) {
+    case detail::type::none_type:
+      FMT_ASSERT(false, "invalid argument type");
+      break;
+    case detail::type::bool_type:
+      if (specs_.type == presentation_type::none ||
+          specs_.type == presentation_type::string) {
+        break;
+      }
+      FMT_FALLTHROUGH;
+    case detail::type::int_type:
+    case detail::type::uint_type:
+    case detail::type::long_long_type:
+    case detail::type::ulong_long_type:
+    case detail::type::int128_type:
+    case detail::type::uint128_type:
+      detail::check_int_type_spec(specs_.type, eh);
+      break;
+    case detail::type::char_type:
+      detail::check_char_specs(specs_, eh);
+      break;
+    case detail::type::float_type:
+      if (detail::const_check(FMT_USE_FLOAT))
+        detail::parse_float_type_spec(specs_, eh);
+      else
+        FMT_ASSERT(false, "float support disabled");
+      break;
+    case detail::type::double_type:
+      if (detail::const_check(FMT_USE_DOUBLE))
+        detail::parse_float_type_spec(specs_, eh);
+      else
+        FMT_ASSERT(false, "double support disabled");
+      break;
+    case detail::type::long_double_type:
+      if (detail::const_check(FMT_USE_LONG_DOUBLE))
+        detail::parse_float_type_spec(specs_, eh);
+      else
+        FMT_ASSERT(false, "long double support disabled");
+      break;
+    case detail::type::cstring_type:
+      detail::check_cstring_type_spec(specs_.type, eh);
+      break;
+    case detail::type::string_type:
+      detail::check_string_type_spec(specs_.type, eh);
+      break;
+    case detail::type::pointer_type:
+      detail::check_pointer_type_spec(specs_.type, eh);
+      break;
+    case detail::type::custom_type:
+      // Custom format specifiers are checked in parse functions of
+      // formatter specializations.
+      break;
+    }
+    return it;
+  }
+
+  template <detail::type U = detail::type_constant<T, Char>::value,
+            enable_if_t<(U == detail::type::string_type ||
+                         U == detail::type::cstring_type ||
+                         U == detail::type::char_type),
+                        int> = 0>
+  FMT_CONSTEXPR void set_debug_format() {
+    specs_.type = presentation_type::debug;
+  }
+
+  template <typename FormatContext>
+  FMT_CONSTEXPR auto format(const T& val, FormatContext& ctx) const
+      -> decltype(ctx.out());
+};
+
+#define FMT_FORMAT_AS(Type, Base)                                        \
+  template <typename Char>                                               \
+  struct formatter<Type, Char> : formatter<Base, Char> {                 \
+    template <typename FormatContext>                                    \
+    auto format(Type const& val, FormatContext& ctx) const               \
+        -> decltype(ctx.out()) {                                         \
+      return formatter<Base, Char>::format(static_cast<Base>(val), ctx); \
+    }                                                                    \
+  }
+
+FMT_FORMAT_AS(signed char, int);
+FMT_FORMAT_AS(unsigned char, unsigned);
+FMT_FORMAT_AS(short, int);
+FMT_FORMAT_AS(unsigned short, unsigned);
+FMT_FORMAT_AS(long, long long);
+FMT_FORMAT_AS(unsigned long, unsigned long long);
+FMT_FORMAT_AS(Char*, const Char*);
+FMT_FORMAT_AS(std::basic_string<Char>, basic_string_view<Char>);
+FMT_FORMAT_AS(std::nullptr_t, const void*);
+FMT_FORMAT_AS(detail::std_string_view<Char>, basic_string_view<Char>);
+
+template <typename Char> struct basic_runtime { basic_string_view<Char> str; };
+
+/** A compile-time format string. */
+template <typename Char, typename... Args> class basic_format_string {
+ private:
+  basic_string_view<Char> str_;
+
+ public:
+  template <typename S,
+            FMT_ENABLE_IF(
+                std::is_convertible<const S&, basic_string_view<Char>>::value)>
+  FMT_CONSTEVAL FMT_INLINE basic_format_string(const S& s) : str_(s) {
+    static_assert(
+        detail::count<
+            (std::is_base_of<detail::view, remove_reference_t<Args>>::value &&
+             std::is_reference<Args>::value)...>() == 0,
+        "passing views as lvalues is disallowed");
+#ifdef FMT_HAS_CONSTEVAL
+    if constexpr (detail::count_named_args<Args...>() ==
+                  detail::count_statically_named_args<Args...>()) {
+      using checker = detail::format_string_checker<Char, detail::error_handler,
+                                                    remove_cvref_t<Args>...>;
+      detail::parse_format_string<true>(str_, checker(s, {}));
+    }
+#else
+    detail::check_format_string<Args...>(s);
+#endif
+  }
+  basic_format_string(basic_runtime<Char> r) : str_(r.str) {}
+
+  FMT_INLINE operator basic_string_view<Char>() const { return str_; }
+};
+
+#if FMT_GCC_VERSION && FMT_GCC_VERSION < 409
+// Workaround broken conversion on older gcc.
+template <typename...> using format_string = string_view;
+inline auto runtime(string_view s) -> string_view { return s; }
+#else
+template <typename... Args>
+using format_string = basic_format_string<char, type_identity_t<Args>...>;
+/**
+  \rst
+  Creates a runtime format string.
+
+  **Example**::
+
+    // Check format string at runtime instead of compile-time.
+    fmt::print(fmt::runtime("{:d}"), "I am not a number");
+  \endrst
+ */
+inline auto runtime(string_view s) -> basic_runtime<char> { return {{s}}; }
+#endif
+
+FMT_API auto vformat(string_view fmt, format_args args) -> std::string;
+
+/**
+  \rst
+  Formats ``args`` according to specifications in ``fmt`` and returns the result
+  as a string.
+
+  **Example**::
+
+    #include <fmt/core.h>
+    std::string message = fmt::format("The answer is {}.", 42);
+  \endrst
+*/
+template <typename... T>
+FMT_NODISCARD FMT_INLINE auto format(format_string<T...> fmt, T&&... args)
+    -> std::string {
+  return vformat(fmt, fmt::make_format_args(args...));
+}
+
+/** Formats a string and writes the output to ``out``. */
+template <typename OutputIt,
+          FMT_ENABLE_IF(detail::is_output_iterator<OutputIt, char>::value)>
+auto vformat_to(OutputIt out, string_view fmt, format_args args) -> OutputIt {
+  using detail::get_buffer;
+  auto&& buf = get_buffer<char>(out);
+  detail::vformat_to(buf, fmt, args, {});
+  return detail::get_iterator(buf);
+}
+
+/**
+ \rst
+ Formats ``args`` according to specifications in ``fmt``, writes the result to
+ the output iterator ``out`` and returns the iterator past the end of the output
+ range. `format_to` does not append a terminating null character.
+
+ **Example**::
+
+   auto out = std::vector<char>();
+   fmt::format_to(std::back_inserter(out), "{}", 42);
+ \endrst
+ */
+template <typename OutputIt, typename... T,
+          FMT_ENABLE_IF(detail::is_output_iterator<OutputIt, char>::value)>
+FMT_INLINE auto format_to(OutputIt out, format_string<T...> fmt, T&&... args)
+    -> OutputIt {
+  return vformat_to(out, fmt, fmt::make_format_args(args...));
+}
+
+template <typename OutputIt> struct format_to_n_result {
+  /** Iterator past the end of the output range. */
+  OutputIt out;
+  /** Total (not truncated) output size. */
+  size_t size;
+};
+
+template <typename OutputIt, typename... T,
+          FMT_ENABLE_IF(detail::is_output_iterator<OutputIt, char>::value)>
+auto vformat_to_n(OutputIt out, size_t n, string_view fmt, format_args args)
+    -> format_to_n_result<OutputIt> {
+  using traits = detail::fixed_buffer_traits;
+  auto buf = detail::iterator_buffer<OutputIt, char, traits>(out, n);
+  detail::vformat_to(buf, fmt, args, {});
+  return {buf.out(), buf.count()};
+}
+
+/**
+  \rst
+  Formats ``args`` according to specifications in ``fmt``, writes up to ``n``
+  characters of the result to the output iterator ``out`` and returns the total
+  (not truncated) output size and the iterator past the end of the output range.
+  `format_to_n` does not append a terminating null character.
+  \endrst
+ */
+template <typename OutputIt, typename... T,
+          FMT_ENABLE_IF(detail::is_output_iterator<OutputIt, char>::value)>
+FMT_INLINE auto format_to_n(OutputIt out, size_t n, format_string<T...> fmt,
+                            T&&... args) -> format_to_n_result<OutputIt> {
+  return vformat_to_n(out, n, fmt, fmt::make_format_args(args...));
+}
+
+/** Returns the number of chars in the output of ``format(fmt, args...)``. */
+template <typename... T>
+FMT_NODISCARD FMT_INLINE auto formatted_size(format_string<T...> fmt,
+                                             T&&... args) -> size_t {
+  auto buf = detail::counting_buffer<>();
+  detail::vformat_to(buf, string_view(fmt), fmt::make_format_args(args...), {});
+  return buf.count();
+}
+
+FMT_API void vprint(string_view fmt, format_args args);
+FMT_API void vprint(std::FILE* f, string_view fmt, format_args args);
+
+/**
+  \rst
+  Formats ``args`` according to specifications in ``fmt`` and writes the output
+  to ``stdout``.
+
+  **Example**::
+
+    fmt::print("Elapsed time: {0:.2f} seconds", 1.23);
+  \endrst
+ */
+template <typename... T>
+FMT_INLINE void print(format_string<T...> fmt, T&&... args) {
+  const auto& vargs = fmt::make_format_args(args...);
+  return detail::is_utf8() ? vprint(fmt, vargs)
+                           : detail::vprint_mojibake(stdout, fmt, vargs);
+}
+
+/**
+  \rst
+  Formats ``args`` according to specifications in ``fmt`` and writes the
+  output to the file ``f``.
+
+  **Example**::
+
+    fmt::print(stderr, "Don't {}!", "panic");
+  \endrst
+ */
+template <typename... T>
+FMT_INLINE void print(std::FILE* f, format_string<T...> fmt, T&&... args) {
+  const auto& vargs = fmt::make_format_args(args...);
+  return detail::is_utf8() ? vprint(f, fmt, vargs)
+                           : detail::vprint_mojibake(f, fmt, vargs);
+}
+
+FMT_MODULE_EXPORT_END
+FMT_GCC_PRAGMA("GCC pop_options")
+FMT_END_NAMESPACE
+
+#ifdef FMT_HEADER_ONLY
+#  include "format.h"
+#endif
+#endif  // FMT_CORE_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/format-inl.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/format-inl.h
new file mode 100644
index 0000000..abe4ff1
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/format-inl.h
@@ -0,0 +1,1721 @@
+// Formatting library for C++ - implementation
+//
+// Copyright (c) 2012 - 2016, Victor Zverovich
+// All rights reserved.
+//
+// For the license information refer to format.h.
+
+#ifndef FMT_FORMAT_INL_H_
+#define FMT_FORMAT_INL_H_
+
+#include <algorithm>
+#include <cctype>
+#include <cerrno>  // errno
+#include <climits>
+#include <cmath>
+#include <cstdarg>
+#include <cstring>  // std::memmove
+#include <cwchar>
+#include <exception>
+
+#ifndef FMT_STATIC_THOUSANDS_SEPARATOR
+#  include <locale>
+#endif
+
+#ifdef _WIN32
+#  include <io.h>  // _isatty
+#endif
+
+#include "format.h"
+
+FMT_BEGIN_NAMESPACE
+namespace detail {
+
+FMT_FUNC void assert_fail(const char* file, int line, const char* message) {
+  // Use unchecked std::fprintf to avoid triggering another assertion when
+  // writing to stderr fails
+  std::fprintf(stderr, "%s:%d: assertion failed: %s", file, line, message);
+  // Chosen instead of std::abort to satisfy Clang in CUDA mode during device
+  // code pass.
+  std::terminate();
+}
+
+FMT_FUNC void throw_format_error(const char* message) {
+  FMT_THROW(format_error(message));
+}
+
+FMT_FUNC void format_error_code(detail::buffer<char>& out, int error_code,
+                                string_view message) noexcept {
+  // Report error code making sure that the output fits into
+  // inline_buffer_size to avoid dynamic memory allocation and potential
+  // bad_alloc.
+  out.try_resize(0);
+  static const char SEP[] = ": ";
+  static const char ERROR_STR[] = "error ";
+  // Subtract 2 to account for terminating null characters in SEP and ERROR_STR.
+  size_t error_code_size = sizeof(SEP) + sizeof(ERROR_STR) - 2;
+  auto abs_value = static_cast<uint32_or_64_or_128_t<int>>(error_code);
+  if (detail::is_negative(error_code)) {
+    abs_value = 0 - abs_value;
+    ++error_code_size;
+  }
+  error_code_size += detail::to_unsigned(detail::count_digits(abs_value));
+  auto it = buffer_appender<char>(out);
+  if (message.size() <= inline_buffer_size - error_code_size)
+    format_to(it, FMT_STRING("{}{}"), message, SEP);
+  format_to(it, FMT_STRING("{}{}"), ERROR_STR, error_code);
+  FMT_ASSERT(out.size() <= inline_buffer_size, "");
+}
+
+FMT_FUNC void report_error(format_func func, int error_code,
+                           const char* message) noexcept {
+  memory_buffer full_message;
+  func(full_message, error_code, message);
+  // Don't use fwrite_fully because the latter may throw.
+  if (std::fwrite(full_message.data(), full_message.size(), 1, stderr) > 0)
+    std::fputc('\n', stderr);
+}
+
+// A wrapper around fwrite that throws on error.
+inline void fwrite_fully(const void* ptr, size_t size, size_t count,
+                         FILE* stream) {
+  std::fwrite(ptr, size, count, stream);
+}
+
+#ifndef FMT_STATIC_THOUSANDS_SEPARATOR
+template <typename Locale>
+locale_ref::locale_ref(const Locale& loc) : locale_(&loc) {
+  static_assert(std::is_same<Locale, std::locale>::value, "");
+}
+
+template <typename Locale> Locale locale_ref::get() const {
+  static_assert(std::is_same<Locale, std::locale>::value, "");
+  return locale_ ? *static_cast<const std::locale*>(locale_) : std::locale();
+}
+
+template <typename Char>
+FMT_FUNC auto thousands_sep_impl(locale_ref loc) -> thousands_sep_result<Char> {
+  auto& facet = std::use_facet<std::numpunct<Char>>(loc.get<std::locale>());
+  auto grouping = facet.grouping();
+  auto thousands_sep = grouping.empty() ? Char() : facet.thousands_sep();
+  return {std::move(grouping), thousands_sep};
+}
+template <typename Char> FMT_FUNC Char decimal_point_impl(locale_ref loc) {
+  return std::use_facet<std::numpunct<Char>>(loc.get<std::locale>())
+      .decimal_point();
+}
+#else
+template <typename Char>
+FMT_FUNC auto thousands_sep_impl(locale_ref) -> thousands_sep_result<Char> {
+  return {"\03", FMT_STATIC_THOUSANDS_SEPARATOR};
+}
+template <typename Char> FMT_FUNC Char decimal_point_impl(locale_ref) {
+  return '.';
+}
+#endif
+}  // namespace detail
+
+#if !FMT_MSC_VERSION
+FMT_API FMT_FUNC format_error::~format_error() noexcept = default;
+#endif
+
+FMT_FUNC std::system_error vsystem_error(int error_code, string_view format_str,
+                                         format_args args) {
+  auto ec = std::error_code(error_code, std::generic_category());
+  return std::system_error(ec, vformat(format_str, args));
+}
+
+namespace detail {
+
+template <typename F> inline bool operator==(basic_fp<F> x, basic_fp<F> y) {
+  return x.f == y.f && x.e == y.e;
+}
+
+// Compilers should be able to optimize this into the ror instruction.
+FMT_CONSTEXPR inline uint32_t rotr(uint32_t n, uint32_t r) noexcept {
+  r &= 31;
+  return (n >> r) | (n << (32 - r));
+}
+FMT_CONSTEXPR inline uint64_t rotr(uint64_t n, uint32_t r) noexcept {
+  r &= 63;
+  return (n >> r) | (n << (64 - r));
+}
+
+// Computes 128-bit result of multiplication of two 64-bit unsigned integers.
+inline uint128_fallback umul128(uint64_t x, uint64_t y) noexcept {
+#if FMT_USE_INT128
+  auto p = static_cast<uint128_opt>(x) * static_cast<uint128_opt>(y);
+  return {static_cast<uint64_t>(p >> 64), static_cast<uint64_t>(p)};
+#elif defined(_MSC_VER) && defined(_M_X64)
+  auto result = uint128_fallback();
+  result.lo_ = _umul128(x, y, &result.hi_);
+  return result;
+#else
+  const uint64_t mask = static_cast<uint64_t>(max_value<uint32_t>());
+
+  uint64_t a = x >> 32;
+  uint64_t b = x & mask;
+  uint64_t c = y >> 32;
+  uint64_t d = y & mask;
+
+  uint64_t ac = a * c;
+  uint64_t bc = b * c;
+  uint64_t ad = a * d;
+  uint64_t bd = b * d;
+
+  uint64_t intermediate = (bd >> 32) + (ad & mask) + (bc & mask);
+
+  return {ac + (intermediate >> 32) + (ad >> 32) + (bc >> 32),
+          (intermediate << 32) + (bd & mask)};
+#endif
+}
+
+// Implementation of Dragonbox algorithm: https://github.com/jk-jeon/dragonbox.
+namespace dragonbox {
+// Computes upper 64 bits of multiplication of two 64-bit unsigned integers.
+inline uint64_t umul128_upper64(uint64_t x, uint64_t y) noexcept {
+#if FMT_USE_INT128
+  auto p = static_cast<uint128_opt>(x) * static_cast<uint128_opt>(y);
+  return static_cast<uint64_t>(p >> 64);
+#elif defined(_MSC_VER) && defined(_M_X64)
+  return __umulh(x, y);
+#else
+  return umul128(x, y).high();
+#endif
+}
+
+// Computes upper 128 bits of multiplication of a 64-bit unsigned integer and a
+// 128-bit unsigned integer.
+inline uint128_fallback umul192_upper128(uint64_t x,
+                                         uint128_fallback y) noexcept {
+  uint128_fallback r = umul128(x, y.high());
+  r += umul128_upper64(x, y.low());
+  return r;
+}
+
+// Computes upper 64 bits of multiplication of a 32-bit unsigned integer and a
+// 64-bit unsigned integer.
+inline uint64_t umul96_upper64(uint32_t x, uint64_t y) noexcept {
+  return umul128_upper64(static_cast<uint64_t>(x) << 32, y);
+}
+
+// Computes lower 128 bits of multiplication of a 64-bit unsigned integer and a
+// 128-bit unsigned integer.
+inline uint128_fallback umul192_lower128(uint64_t x,
+                                         uint128_fallback y) noexcept {
+  uint64_t high = x * y.high();
+  uint128_fallback high_low = umul128(x, y.low());
+  return {high + high_low.high(), high_low.low()};
+}
+
+// Computes lower 64 bits of multiplication of a 32-bit unsigned integer and a
+// 64-bit unsigned integer.
+inline uint64_t umul96_lower64(uint32_t x, uint64_t y) noexcept {
+  return x * y;
+}
+
+// Computes floor(log10(pow(2, e))) for e in [-2620, 2620] using the method from
+// https://fmt.dev/papers/Dragonbox.pdf#page=28, section 6.1.
+inline int floor_log10_pow2(int e) noexcept {
+  FMT_ASSERT(e <= 2620 && e >= -2620, "too large exponent");
+  static_assert((-1 >> 1) == -1, "right shift is not arithmetic");
+  return (e * 315653) >> 20;
+}
+
+// Various fast log computations.
+inline int floor_log2_pow10(int e) noexcept {
+  FMT_ASSERT(e <= 1233 && e >= -1233, "too large exponent");
+  return (e * 1741647) >> 19;
+}
+inline int floor_log10_pow2_minus_log10_4_over_3(int e) noexcept {
+  FMT_ASSERT(e <= 2936 && e >= -2985, "too large exponent");
+  return (e * 631305 - 261663) >> 21;
+}
+
+static constexpr struct {
+  uint32_t divisor;
+  int shift_amount;
+} div_small_pow10_infos[] = {{10, 16}, {100, 16}};
+
+// Replaces n by floor(n / pow(10, N)) returning true if and only if n is
+// divisible by pow(10, N).
+// Precondition: n <= pow(10, N + 1).
+template <int N>
+bool check_divisibility_and_divide_by_pow10(uint32_t& n) noexcept {
+  // The numbers below are chosen such that:
+  //   1. floor(n/d) = floor(nm / 2^k) where d=10 or d=100,
+  //   2. nm mod 2^k < m if and only if n is divisible by d,
+  // where m is magic_number, k is shift_amount
+  // and d is divisor.
+  //
+  // Item 1 is a common technique of replacing division by a constant with
+  // multiplication, see e.g. "Division by Invariant Integers Using
+  // Multiplication" by Granlund and Montgomery (1994). magic_number (m) is set
+  // to ceil(2^k/d) for large enough k.
+  // The idea for item 2 originates from Schubfach.
+  constexpr auto info = div_small_pow10_infos[N - 1];
+  FMT_ASSERT(n <= info.divisor * 10, "n is too large");
+  constexpr uint32_t magic_number =
+      (1u << info.shift_amount) / info.divisor + 1;
+  n *= magic_number;
+  const uint32_t comparison_mask = (1u << info.shift_amount) - 1;
+  bool result = (n & comparison_mask) < magic_number;
+  n >>= info.shift_amount;
+  return result;
+}
+
+// Computes floor(n / pow(10, N)) for small n and N.
+// Precondition: n <= pow(10, N + 1).
+template <int N> uint32_t small_division_by_pow10(uint32_t n) noexcept {
+  constexpr auto info = div_small_pow10_infos[N - 1];
+  FMT_ASSERT(n <= info.divisor * 10, "n is too large");
+  constexpr uint32_t magic_number =
+      (1u << info.shift_amount) / info.divisor + 1;
+  return (n * magic_number) >> info.shift_amount;
+}
+
+// Computes floor(n / 10^(kappa + 1)) (float)
+inline uint32_t divide_by_10_to_kappa_plus_1(uint32_t n) noexcept {
+  // 1374389535 = ceil(2^37/100)
+  return static_cast<uint32_t>((static_cast<uint64_t>(n) * 1374389535) >> 37);
+}
+// Computes floor(n / 10^(kappa + 1)) (double)
+inline uint64_t divide_by_10_to_kappa_plus_1(uint64_t n) noexcept {
+  // 2361183241434822607 = ceil(2^(64+7)/1000)
+  return umul128_upper64(n, 2361183241434822607ull) >> 7;
+}
+
+// Various subroutines using pow10 cache
+template <class T> struct cache_accessor;
+
+template <> struct cache_accessor<float> {
+  using carrier_uint = float_info<float>::carrier_uint;
+  using cache_entry_type = uint64_t;
+
+  static uint64_t get_cached_power(int k) noexcept {
+    FMT_ASSERT(k >= float_info<float>::min_k && k <= float_info<float>::max_k,
+               "k is out of range");
+    static constexpr const uint64_t pow10_significands[] = {
+        0x81ceb32c4b43fcf5, 0xa2425ff75e14fc32, 0xcad2f7f5359a3b3f,
+        0xfd87b5f28300ca0e, 0x9e74d1b791e07e49, 0xc612062576589ddb,
+        0xf79687aed3eec552, 0x9abe14cd44753b53, 0xc16d9a0095928a28,
+        0xf1c90080baf72cb2, 0x971da05074da7bef, 0xbce5086492111aeb,
+        0xec1e4a7db69561a6, 0x9392ee8e921d5d08, 0xb877aa3236a4b44a,
+        0xe69594bec44de15c, 0x901d7cf73ab0acda, 0xb424dc35095cd810,
+        0xe12e13424bb40e14, 0x8cbccc096f5088cc, 0xafebff0bcb24aaff,
+        0xdbe6fecebdedd5bf, 0x89705f4136b4a598, 0xabcc77118461cefd,
+        0xd6bf94d5e57a42bd, 0x8637bd05af6c69b6, 0xa7c5ac471b478424,
+        0xd1b71758e219652c, 0x83126e978d4fdf3c, 0xa3d70a3d70a3d70b,
+        0xcccccccccccccccd, 0x8000000000000000, 0xa000000000000000,
+        0xc800000000000000, 0xfa00000000000000, 0x9c40000000000000,
+        0xc350000000000000, 0xf424000000000000, 0x9896800000000000,
+        0xbebc200000000000, 0xee6b280000000000, 0x9502f90000000000,
+        0xba43b74000000000, 0xe8d4a51000000000, 0x9184e72a00000000,
+        0xb5e620f480000000, 0xe35fa931a0000000, 0x8e1bc9bf04000000,
+        0xb1a2bc2ec5000000, 0xde0b6b3a76400000, 0x8ac7230489e80000,
+        0xad78ebc5ac620000, 0xd8d726b7177a8000, 0x878678326eac9000,
+        0xa968163f0a57b400, 0xd3c21bcecceda100, 0x84595161401484a0,
+        0xa56fa5b99019a5c8, 0xcecb8f27f4200f3a, 0x813f3978f8940985,
+        0xa18f07d736b90be6, 0xc9f2c9cd04674edf, 0xfc6f7c4045812297,
+        0x9dc5ada82b70b59e, 0xc5371912364ce306, 0xf684df56c3e01bc7,
+        0x9a130b963a6c115d, 0xc097ce7bc90715b4, 0xf0bdc21abb48db21,
+        0x96769950b50d88f5, 0xbc143fa4e250eb32, 0xeb194f8e1ae525fe,
+        0x92efd1b8d0cf37bf, 0xb7abc627050305ae, 0xe596b7b0c643c71a,
+        0x8f7e32ce7bea5c70, 0xb35dbf821ae4f38c, 0xe0352f62a19e306f};
+    return pow10_significands[k - float_info<float>::min_k];
+  }
+
+  struct compute_mul_result {
+    carrier_uint result;
+    bool is_integer;
+  };
+  struct compute_mul_parity_result {
+    bool parity;
+    bool is_integer;
+  };
+
+  static compute_mul_result compute_mul(
+      carrier_uint u, const cache_entry_type& cache) noexcept {
+    auto r = umul96_upper64(u, cache);
+    return {static_cast<carrier_uint>(r >> 32),
+            static_cast<carrier_uint>(r) == 0};
+  }
+
+  static uint32_t compute_delta(const cache_entry_type& cache,
+                                int beta) noexcept {
+    return static_cast<uint32_t>(cache >> (64 - 1 - beta));
+  }
+
+  static compute_mul_parity_result compute_mul_parity(
+      carrier_uint two_f, const cache_entry_type& cache, int beta) noexcept {
+    FMT_ASSERT(beta >= 1, "");
+    FMT_ASSERT(beta < 64, "");
+
+    auto r = umul96_lower64(two_f, cache);
+    return {((r >> (64 - beta)) & 1) != 0,
+            static_cast<uint32_t>(r >> (32 - beta)) == 0};
+  }
+
+  static carrier_uint compute_left_endpoint_for_shorter_interval_case(
+      const cache_entry_type& cache, int beta) noexcept {
+    return static_cast<carrier_uint>(
+        (cache - (cache >> (num_significand_bits<float>() + 2))) >>
+        (64 - num_significand_bits<float>() - 1 - beta));
+  }
+
+  static carrier_uint compute_right_endpoint_for_shorter_interval_case(
+      const cache_entry_type& cache, int beta) noexcept {
+    return static_cast<carrier_uint>(
+        (cache + (cache >> (num_significand_bits<float>() + 1))) >>
+        (64 - num_significand_bits<float>() - 1 - beta));
+  }
+
+  static carrier_uint compute_round_up_for_shorter_interval_case(
+      const cache_entry_type& cache, int beta) noexcept {
+    return (static_cast<carrier_uint>(
+                cache >> (64 - num_significand_bits<float>() - 2 - beta)) +
+            1) /
+           2;
+  }
+};
+
+template <> struct cache_accessor<double> {
+  using carrier_uint = float_info<double>::carrier_uint;
+  using cache_entry_type = uint128_fallback;
+
+  static uint128_fallback get_cached_power(int k) noexcept {
+    FMT_ASSERT(k >= float_info<double>::min_k && k <= float_info<double>::max_k,
+               "k is out of range");
+
+    static constexpr const uint128_fallback pow10_significands[] = {
+#if FMT_USE_FULL_CACHE_DRAGONBOX
+      {0xff77b1fcbebcdc4f, 0x25e8e89c13bb0f7b},
+      {0x9faacf3df73609b1, 0x77b191618c54e9ad},
+      {0xc795830d75038c1d, 0xd59df5b9ef6a2418},
+      {0xf97ae3d0d2446f25, 0x4b0573286b44ad1e},
+      {0x9becce62836ac577, 0x4ee367f9430aec33},
+      {0xc2e801fb244576d5, 0x229c41f793cda740},
+      {0xf3a20279ed56d48a, 0x6b43527578c11110},
+      {0x9845418c345644d6, 0x830a13896b78aaaa},
+      {0xbe5691ef416bd60c, 0x23cc986bc656d554},
+      {0xedec366b11c6cb8f, 0x2cbfbe86b7ec8aa9},
+      {0x94b3a202eb1c3f39, 0x7bf7d71432f3d6aa},
+      {0xb9e08a83a5e34f07, 0xdaf5ccd93fb0cc54},
+      {0xe858ad248f5c22c9, 0xd1b3400f8f9cff69},
+      {0x91376c36d99995be, 0x23100809b9c21fa2},
+      {0xb58547448ffffb2d, 0xabd40a0c2832a78b},
+      {0xe2e69915b3fff9f9, 0x16c90c8f323f516d},
+      {0x8dd01fad907ffc3b, 0xae3da7d97f6792e4},
+      {0xb1442798f49ffb4a, 0x99cd11cfdf41779d},
+      {0xdd95317f31c7fa1d, 0x40405643d711d584},
+      {0x8a7d3eef7f1cfc52, 0x482835ea666b2573},
+      {0xad1c8eab5ee43b66, 0xda3243650005eed0},
+      {0xd863b256369d4a40, 0x90bed43e40076a83},
+      {0x873e4f75e2224e68, 0x5a7744a6e804a292},
+      {0xa90de3535aaae202, 0x711515d0a205cb37},
+      {0xd3515c2831559a83, 0x0d5a5b44ca873e04},
+      {0x8412d9991ed58091, 0xe858790afe9486c3},
+      {0xa5178fff668ae0b6, 0x626e974dbe39a873},
+      {0xce5d73ff402d98e3, 0xfb0a3d212dc81290},
+      {0x80fa687f881c7f8e, 0x7ce66634bc9d0b9a},
+      {0xa139029f6a239f72, 0x1c1fffc1ebc44e81},
+      {0xc987434744ac874e, 0xa327ffb266b56221},
+      {0xfbe9141915d7a922, 0x4bf1ff9f0062baa9},
+      {0x9d71ac8fada6c9b5, 0x6f773fc3603db4aa},
+      {0xc4ce17b399107c22, 0xcb550fb4384d21d4},
+      {0xf6019da07f549b2b, 0x7e2a53a146606a49},
+      {0x99c102844f94e0fb, 0x2eda7444cbfc426e},
+      {0xc0314325637a1939, 0xfa911155fefb5309},
+      {0xf03d93eebc589f88, 0x793555ab7eba27cb},
+      {0x96267c7535b763b5, 0x4bc1558b2f3458df},
+      {0xbbb01b9283253ca2, 0x9eb1aaedfb016f17},
+      {0xea9c227723ee8bcb, 0x465e15a979c1cadd},
+      {0x92a1958a7675175f, 0x0bfacd89ec191eca},
+      {0xb749faed14125d36, 0xcef980ec671f667c},
+      {0xe51c79a85916f484, 0x82b7e12780e7401b},
+      {0x8f31cc0937ae58d2, 0xd1b2ecb8b0908811},
+      {0xb2fe3f0b8599ef07, 0x861fa7e6dcb4aa16},
+      {0xdfbdcece67006ac9, 0x67a791e093e1d49b},
+      {0x8bd6a141006042bd, 0xe0c8bb2c5c6d24e1},
+      {0xaecc49914078536d, 0x58fae9f773886e19},
+      {0xda7f5bf590966848, 0xaf39a475506a899f},
+      {0x888f99797a5e012d, 0x6d8406c952429604},
+      {0xaab37fd7d8f58178, 0xc8e5087ba6d33b84},
+      {0xd5605fcdcf32e1d6, 0xfb1e4a9a90880a65},
+      {0x855c3be0a17fcd26, 0x5cf2eea09a550680},
+      {0xa6b34ad8c9dfc06f, 0xf42faa48c0ea481f},
+      {0xd0601d8efc57b08b, 0xf13b94daf124da27},
+      {0x823c12795db6ce57, 0x76c53d08d6b70859},
+      {0xa2cb1717b52481ed, 0x54768c4b0c64ca6f},
+      {0xcb7ddcdda26da268, 0xa9942f5dcf7dfd0a},
+      {0xfe5d54150b090b02, 0xd3f93b35435d7c4d},
+      {0x9efa548d26e5a6e1, 0xc47bc5014a1a6db0},
+      {0xc6b8e9b0709f109a, 0x359ab6419ca1091c},
+      {0xf867241c8cc6d4c0, 0xc30163d203c94b63},
+      {0x9b407691d7fc44f8, 0x79e0de63425dcf1e},
+      {0xc21094364dfb5636, 0x985915fc12f542e5},
+      {0xf294b943e17a2bc4, 0x3e6f5b7b17b2939e},
+      {0x979cf3ca6cec5b5a, 0xa705992ceecf9c43},
+      {0xbd8430bd08277231, 0x50c6ff782a838354},
+      {0xece53cec4a314ebd, 0xa4f8bf5635246429},
+      {0x940f4613ae5ed136, 0x871b7795e136be9a},
+      {0xb913179899f68584, 0x28e2557b59846e40},
+      {0xe757dd7ec07426e5, 0x331aeada2fe589d0},
+      {0x9096ea6f3848984f, 0x3ff0d2c85def7622},
+      {0xb4bca50b065abe63, 0x0fed077a756b53aa},
+      {0xe1ebce4dc7f16dfb, 0xd3e8495912c62895},
+      {0x8d3360f09cf6e4bd, 0x64712dd7abbbd95d},
+      {0xb080392cc4349dec, 0xbd8d794d96aacfb4},
+      {0xdca04777f541c567, 0xecf0d7a0fc5583a1},
+      {0x89e42caaf9491b60, 0xf41686c49db57245},
+      {0xac5d37d5b79b6239, 0x311c2875c522ced6},
+      {0xd77485cb25823ac7, 0x7d633293366b828c},
+      {0x86a8d39ef77164bc, 0xae5dff9c02033198},
+      {0xa8530886b54dbdeb, 0xd9f57f830283fdfd},
+      {0xd267caa862a12d66, 0xd072df63c324fd7c},
+      {0x8380dea93da4bc60, 0x4247cb9e59f71e6e},
+      {0xa46116538d0deb78, 0x52d9be85f074e609},
+      {0xcd795be870516656, 0x67902e276c921f8c},
+      {0x806bd9714632dff6, 0x00ba1cd8a3db53b7},
+      {0xa086cfcd97bf97f3, 0x80e8a40eccd228a5},
+      {0xc8a883c0fdaf7df0, 0x6122cd128006b2ce},
+      {0xfad2a4b13d1b5d6c, 0x796b805720085f82},
+      {0x9cc3a6eec6311a63, 0xcbe3303674053bb1},
+      {0xc3f490aa77bd60fc, 0xbedbfc4411068a9d},
+      {0xf4f1b4d515acb93b, 0xee92fb5515482d45},
+      {0x991711052d8bf3c5, 0x751bdd152d4d1c4b},
+      {0xbf5cd54678eef0b6, 0xd262d45a78a0635e},
+      {0xef340a98172aace4, 0x86fb897116c87c35},
+      {0x9580869f0e7aac0e, 0xd45d35e6ae3d4da1},
+      {0xbae0a846d2195712, 0x8974836059cca10a},
+      {0xe998d258869facd7, 0x2bd1a438703fc94c},
+      {0x91ff83775423cc06, 0x7b6306a34627ddd0},
+      {0xb67f6455292cbf08, 0x1a3bc84c17b1d543},
+      {0xe41f3d6a7377eeca, 0x20caba5f1d9e4a94},
+      {0x8e938662882af53e, 0x547eb47b7282ee9d},
+      {0xb23867fb2a35b28d, 0xe99e619a4f23aa44},
+      {0xdec681f9f4c31f31, 0x6405fa00e2ec94d5},
+      {0x8b3c113c38f9f37e, 0xde83bc408dd3dd05},
+      {0xae0b158b4738705e, 0x9624ab50b148d446},
+      {0xd98ddaee19068c76, 0x3badd624dd9b0958},
+      {0x87f8a8d4cfa417c9, 0xe54ca5d70a80e5d7},
+      {0xa9f6d30a038d1dbc, 0x5e9fcf4ccd211f4d},
+      {0xd47487cc8470652b, 0x7647c32000696720},
+      {0x84c8d4dfd2c63f3b, 0x29ecd9f40041e074},
+      {0xa5fb0a17c777cf09, 0xf468107100525891},
+      {0xcf79cc9db955c2cc, 0x7182148d4066eeb5},
+      {0x81ac1fe293d599bf, 0xc6f14cd848405531},
+      {0xa21727db38cb002f, 0xb8ada00e5a506a7d},
+      {0xca9cf1d206fdc03b, 0xa6d90811f0e4851d},
+      {0xfd442e4688bd304a, 0x908f4a166d1da664},
+      {0x9e4a9cec15763e2e, 0x9a598e4e043287ff},
+      {0xc5dd44271ad3cdba, 0x40eff1e1853f29fe},
+      {0xf7549530e188c128, 0xd12bee59e68ef47d},
+      {0x9a94dd3e8cf578b9, 0x82bb74f8301958cf},
+      {0xc13a148e3032d6e7, 0xe36a52363c1faf02},
+      {0xf18899b1bc3f8ca1, 0xdc44e6c3cb279ac2},
+      {0x96f5600f15a7b7e5, 0x29ab103a5ef8c0ba},
+      {0xbcb2b812db11a5de, 0x7415d448f6b6f0e8},
+      {0xebdf661791d60f56, 0x111b495b3464ad22},
+      {0x936b9fcebb25c995, 0xcab10dd900beec35},
+      {0xb84687c269ef3bfb, 0x3d5d514f40eea743},
+      {0xe65829b3046b0afa, 0x0cb4a5a3112a5113},
+      {0x8ff71a0fe2c2e6dc, 0x47f0e785eaba72ac},
+      {0xb3f4e093db73a093, 0x59ed216765690f57},
+      {0xe0f218b8d25088b8, 0x306869c13ec3532d},
+      {0x8c974f7383725573, 0x1e414218c73a13fc},
+      {0xafbd2350644eeacf, 0xe5d1929ef90898fb},
+      {0xdbac6c247d62a583, 0xdf45f746b74abf3a},
+      {0x894bc396ce5da772, 0x6b8bba8c328eb784},
+      {0xab9eb47c81f5114f, 0x066ea92f3f326565},
+      {0xd686619ba27255a2, 0xc80a537b0efefebe},
+      {0x8613fd0145877585, 0xbd06742ce95f5f37},
+      {0xa798fc4196e952e7, 0x2c48113823b73705},
+      {0xd17f3b51fca3a7a0, 0xf75a15862ca504c6},
+      {0x82ef85133de648c4, 0x9a984d73dbe722fc},
+      {0xa3ab66580d5fdaf5, 0xc13e60d0d2e0ebbb},
+      {0xcc963fee10b7d1b3, 0x318df905079926a9},
+      {0xffbbcfe994e5c61f, 0xfdf17746497f7053},
+      {0x9fd561f1fd0f9bd3, 0xfeb6ea8bedefa634},
+      {0xc7caba6e7c5382c8, 0xfe64a52ee96b8fc1},
+      {0xf9bd690a1b68637b, 0x3dfdce7aa3c673b1},
+      {0x9c1661a651213e2d, 0x06bea10ca65c084f},
+      {0xc31bfa0fe5698db8, 0x486e494fcff30a63},
+      {0xf3e2f893dec3f126, 0x5a89dba3c3efccfb},
+      {0x986ddb5c6b3a76b7, 0xf89629465a75e01d},
+      {0xbe89523386091465, 0xf6bbb397f1135824},
+      {0xee2ba6c0678b597f, 0x746aa07ded582e2d},
+      {0x94db483840b717ef, 0xa8c2a44eb4571cdd},
+      {0xba121a4650e4ddeb, 0x92f34d62616ce414},
+      {0xe896a0d7e51e1566, 0x77b020baf9c81d18},
+      {0x915e2486ef32cd60, 0x0ace1474dc1d122f},
+      {0xb5b5ada8aaff80b8, 0x0d819992132456bb},
+      {0xe3231912d5bf60e6, 0x10e1fff697ed6c6a},
+      {0x8df5efabc5979c8f, 0xca8d3ffa1ef463c2},
+      {0xb1736b96b6fd83b3, 0xbd308ff8a6b17cb3},
+      {0xddd0467c64bce4a0, 0xac7cb3f6d05ddbdf},
+      {0x8aa22c0dbef60ee4, 0x6bcdf07a423aa96c},
+      {0xad4ab7112eb3929d, 0x86c16c98d2c953c7},
+      {0xd89d64d57a607744, 0xe871c7bf077ba8b8},
+      {0x87625f056c7c4a8b, 0x11471cd764ad4973},
+      {0xa93af6c6c79b5d2d, 0xd598e40d3dd89bd0},
+      {0xd389b47879823479, 0x4aff1d108d4ec2c4},
+      {0x843610cb4bf160cb, 0xcedf722a585139bb},
+      {0xa54394fe1eedb8fe, 0xc2974eb4ee658829},
+      {0xce947a3da6a9273e, 0x733d226229feea33},
+      {0x811ccc668829b887, 0x0806357d5a3f5260},
+      {0xa163ff802a3426a8, 0xca07c2dcb0cf26f8},
+      {0xc9bcff6034c13052, 0xfc89b393dd02f0b6},
+      {0xfc2c3f3841f17c67, 0xbbac2078d443ace3},
+      {0x9d9ba7832936edc0, 0xd54b944b84aa4c0e},
+      {0xc5029163f384a931, 0x0a9e795e65d4df12},
+      {0xf64335bcf065d37d, 0x4d4617b5ff4a16d6},
+      {0x99ea0196163fa42e, 0x504bced1bf8e4e46},
+      {0xc06481fb9bcf8d39, 0xe45ec2862f71e1d7},
+      {0xf07da27a82c37088, 0x5d767327bb4e5a4d},
+      {0x964e858c91ba2655, 0x3a6a07f8d510f870},
+      {0xbbe226efb628afea, 0x890489f70a55368c},
+      {0xeadab0aba3b2dbe5, 0x2b45ac74ccea842f},
+      {0x92c8ae6b464fc96f, 0x3b0b8bc90012929e},
+      {0xb77ada0617e3bbcb, 0x09ce6ebb40173745},
+      {0xe55990879ddcaabd, 0xcc420a6a101d0516},
+      {0x8f57fa54c2a9eab6, 0x9fa946824a12232e},
+      {0xb32df8e9f3546564, 0x47939822dc96abfa},
+      {0xdff9772470297ebd, 0x59787e2b93bc56f8},
+      {0x8bfbea76c619ef36, 0x57eb4edb3c55b65b},
+      {0xaefae51477a06b03, 0xede622920b6b23f2},
+      {0xdab99e59958885c4, 0xe95fab368e45ecee},
+      {0x88b402f7fd75539b, 0x11dbcb0218ebb415},
+      {0xaae103b5fcd2a881, 0xd652bdc29f26a11a},
+      {0xd59944a37c0752a2, 0x4be76d3346f04960},
+      {0x857fcae62d8493a5, 0x6f70a4400c562ddc},
+      {0xa6dfbd9fb8e5b88e, 0xcb4ccd500f6bb953},
+      {0xd097ad07a71f26b2, 0x7e2000a41346a7a8},
+      {0x825ecc24c873782f, 0x8ed400668c0c28c9},
+      {0xa2f67f2dfa90563b, 0x728900802f0f32fb},
+      {0xcbb41ef979346bca, 0x4f2b40a03ad2ffba},
+      {0xfea126b7d78186bc, 0xe2f610c84987bfa9},
+      {0x9f24b832e6b0f436, 0x0dd9ca7d2df4d7ca},
+      {0xc6ede63fa05d3143, 0x91503d1c79720dbc},
+      {0xf8a95fcf88747d94, 0x75a44c6397ce912b},
+      {0x9b69dbe1b548ce7c, 0xc986afbe3ee11abb},
+      {0xc24452da229b021b, 0xfbe85badce996169},
+      {0xf2d56790ab41c2a2, 0xfae27299423fb9c4},
+      {0x97c560ba6b0919a5, 0xdccd879fc967d41b},
+      {0xbdb6b8e905cb600f, 0x5400e987bbc1c921},
+      {0xed246723473e3813, 0x290123e9aab23b69},
+      {0x9436c0760c86e30b, 0xf9a0b6720aaf6522},
+      {0xb94470938fa89bce, 0xf808e40e8d5b3e6a},
+      {0xe7958cb87392c2c2, 0xb60b1d1230b20e05},
+      {0x90bd77f3483bb9b9, 0xb1c6f22b5e6f48c3},
+      {0xb4ecd5f01a4aa828, 0x1e38aeb6360b1af4},
+      {0xe2280b6c20dd5232, 0x25c6da63c38de1b1},
+      {0x8d590723948a535f, 0x579c487e5a38ad0f},
+      {0xb0af48ec79ace837, 0x2d835a9df0c6d852},
+      {0xdcdb1b2798182244, 0xf8e431456cf88e66},
+      {0x8a08f0f8bf0f156b, 0x1b8e9ecb641b5900},
+      {0xac8b2d36eed2dac5, 0xe272467e3d222f40},
+      {0xd7adf884aa879177, 0x5b0ed81dcc6abb10},
+      {0x86ccbb52ea94baea, 0x98e947129fc2b4ea},
+      {0xa87fea27a539e9a5, 0x3f2398d747b36225},
+      {0xd29fe4b18e88640e, 0x8eec7f0d19a03aae},
+      {0x83a3eeeef9153e89, 0x1953cf68300424ad},
+      {0xa48ceaaab75a8e2b, 0x5fa8c3423c052dd8},
+      {0xcdb02555653131b6, 0x3792f412cb06794e},
+      {0x808e17555f3ebf11, 0xe2bbd88bbee40bd1},
+      {0xa0b19d2ab70e6ed6, 0x5b6aceaeae9d0ec5},
+      {0xc8de047564d20a8b, 0xf245825a5a445276},
+      {0xfb158592be068d2e, 0xeed6e2f0f0d56713},
+      {0x9ced737bb6c4183d, 0x55464dd69685606c},
+      {0xc428d05aa4751e4c, 0xaa97e14c3c26b887},
+      {0xf53304714d9265df, 0xd53dd99f4b3066a9},
+      {0x993fe2c6d07b7fab, 0xe546a8038efe402a},
+      {0xbf8fdb78849a5f96, 0xde98520472bdd034},
+      {0xef73d256a5c0f77c, 0x963e66858f6d4441},
+      {0x95a8637627989aad, 0xdde7001379a44aa9},
+      {0xbb127c53b17ec159, 0x5560c018580d5d53},
+      {0xe9d71b689dde71af, 0xaab8f01e6e10b4a7},
+      {0x9226712162ab070d, 0xcab3961304ca70e9},
+      {0xb6b00d69bb55c8d1, 0x3d607b97c5fd0d23},
+      {0xe45c10c42a2b3b05, 0x8cb89a7db77c506b},
+      {0x8eb98a7a9a5b04e3, 0x77f3608e92adb243},
+      {0xb267ed1940f1c61c, 0x55f038b237591ed4},
+      {0xdf01e85f912e37a3, 0x6b6c46dec52f6689},
+      {0x8b61313bbabce2c6, 0x2323ac4b3b3da016},
+      {0xae397d8aa96c1b77, 0xabec975e0a0d081b},
+      {0xd9c7dced53c72255, 0x96e7bd358c904a22},
+      {0x881cea14545c7575, 0x7e50d64177da2e55},
+      {0xaa242499697392d2, 0xdde50bd1d5d0b9ea},
+      {0xd4ad2dbfc3d07787, 0x955e4ec64b44e865},
+      {0x84ec3c97da624ab4, 0xbd5af13bef0b113f},
+      {0xa6274bbdd0fadd61, 0xecb1ad8aeacdd58f},
+      {0xcfb11ead453994ba, 0x67de18eda5814af3},
+      {0x81ceb32c4b43fcf4, 0x80eacf948770ced8},
+      {0xa2425ff75e14fc31, 0xa1258379a94d028e},
+      {0xcad2f7f5359a3b3e, 0x096ee45813a04331},
+      {0xfd87b5f28300ca0d, 0x8bca9d6e188853fd},
+      {0x9e74d1b791e07e48, 0x775ea264cf55347e},
+      {0xc612062576589dda, 0x95364afe032a819e},
+      {0xf79687aed3eec551, 0x3a83ddbd83f52205},
+      {0x9abe14cd44753b52, 0xc4926a9672793543},
+      {0xc16d9a0095928a27, 0x75b7053c0f178294},
+      {0xf1c90080baf72cb1, 0x5324c68b12dd6339},
+      {0x971da05074da7bee, 0xd3f6fc16ebca5e04},
+      {0xbce5086492111aea, 0x88f4bb1ca6bcf585},
+      {0xec1e4a7db69561a5, 0x2b31e9e3d06c32e6},
+      {0x9392ee8e921d5d07, 0x3aff322e62439fd0},
+      {0xb877aa3236a4b449, 0x09befeb9fad487c3},
+      {0xe69594bec44de15b, 0x4c2ebe687989a9b4},
+      {0x901d7cf73ab0acd9, 0x0f9d37014bf60a11},
+      {0xb424dc35095cd80f, 0x538484c19ef38c95},
+      {0xe12e13424bb40e13, 0x2865a5f206b06fba},
+      {0x8cbccc096f5088cb, 0xf93f87b7442e45d4},
+      {0xafebff0bcb24aafe, 0xf78f69a51539d749},
+      {0xdbe6fecebdedd5be, 0xb573440e5a884d1c},
+      {0x89705f4136b4a597, 0x31680a88f8953031},
+      {0xabcc77118461cefc, 0xfdc20d2b36ba7c3e},
+      {0xd6bf94d5e57a42bc, 0x3d32907604691b4d},
+      {0x8637bd05af6c69b5, 0xa63f9a49c2c1b110},
+      {0xa7c5ac471b478423, 0x0fcf80dc33721d54},
+      {0xd1b71758e219652b, 0xd3c36113404ea4a9},
+      {0x83126e978d4fdf3b, 0x645a1cac083126ea},
+      {0xa3d70a3d70a3d70a, 0x3d70a3d70a3d70a4},
+      {0xcccccccccccccccc, 0xcccccccccccccccd},
+      {0x8000000000000000, 0x0000000000000000},
+      {0xa000000000000000, 0x0000000000000000},
+      {0xc800000000000000, 0x0000000000000000},
+      {0xfa00000000000000, 0x0000000000000000},
+      {0x9c40000000000000, 0x0000000000000000},
+      {0xc350000000000000, 0x0000000000000000},
+      {0xf424000000000000, 0x0000000000000000},
+      {0x9896800000000000, 0x0000000000000000},
+      {0xbebc200000000000, 0x0000000000000000},
+      {0xee6b280000000000, 0x0000000000000000},
+      {0x9502f90000000000, 0x0000000000000000},
+      {0xba43b74000000000, 0x0000000000000000},
+      {0xe8d4a51000000000, 0x0000000000000000},
+      {0x9184e72a00000000, 0x0000000000000000},
+      {0xb5e620f480000000, 0x0000000000000000},
+      {0xe35fa931a0000000, 0x0000000000000000},
+      {0x8e1bc9bf04000000, 0x0000000000000000},
+      {0xb1a2bc2ec5000000, 0x0000000000000000},
+      {0xde0b6b3a76400000, 0x0000000000000000},
+      {0x8ac7230489e80000, 0x0000000000000000},
+      {0xad78ebc5ac620000, 0x0000000000000000},
+      {0xd8d726b7177a8000, 0x0000000000000000},
+      {0x878678326eac9000, 0x0000000000000000},
+      {0xa968163f0a57b400, 0x0000000000000000},
+      {0xd3c21bcecceda100, 0x0000000000000000},
+      {0x84595161401484a0, 0x0000000000000000},
+      {0xa56fa5b99019a5c8, 0x0000000000000000},
+      {0xcecb8f27f4200f3a, 0x0000000000000000},
+      {0x813f3978f8940984, 0x4000000000000000},
+      {0xa18f07d736b90be5, 0x5000000000000000},
+      {0xc9f2c9cd04674ede, 0xa400000000000000},
+      {0xfc6f7c4045812296, 0x4d00000000000000},
+      {0x9dc5ada82b70b59d, 0xf020000000000000},
+      {0xc5371912364ce305, 0x6c28000000000000},
+      {0xf684df56c3e01bc6, 0xc732000000000000},
+      {0x9a130b963a6c115c, 0x3c7f400000000000},
+      {0xc097ce7bc90715b3, 0x4b9f100000000000},
+      {0xf0bdc21abb48db20, 0x1e86d40000000000},
+      {0x96769950b50d88f4, 0x1314448000000000},
+      {0xbc143fa4e250eb31, 0x17d955a000000000},
+      {0xeb194f8e1ae525fd, 0x5dcfab0800000000},
+      {0x92efd1b8d0cf37be, 0x5aa1cae500000000},
+      {0xb7abc627050305ad, 0xf14a3d9e40000000},
+      {0xe596b7b0c643c719, 0x6d9ccd05d0000000},
+      {0x8f7e32ce7bea5c6f, 0xe4820023a2000000},
+      {0xb35dbf821ae4f38b, 0xdda2802c8a800000},
+      {0xe0352f62a19e306e, 0xd50b2037ad200000},
+      {0x8c213d9da502de45, 0x4526f422cc340000},
+      {0xaf298d050e4395d6, 0x9670b12b7f410000},
+      {0xdaf3f04651d47b4c, 0x3c0cdd765f114000},
+      {0x88d8762bf324cd0f, 0xa5880a69fb6ac800},
+      {0xab0e93b6efee0053, 0x8eea0d047a457a00},
+      {0xd5d238a4abe98068, 0x72a4904598d6d880},
+      {0x85a36366eb71f041, 0x47a6da2b7f864750},
+      {0xa70c3c40a64e6c51, 0x999090b65f67d924},
+      {0xd0cf4b50cfe20765, 0xfff4b4e3f741cf6d},
+      {0x82818f1281ed449f, 0xbff8f10e7a8921a5},
+      {0xa321f2d7226895c7, 0xaff72d52192b6a0e},
+      {0xcbea6f8ceb02bb39, 0x9bf4f8a69f764491},
+      {0xfee50b7025c36a08, 0x02f236d04753d5b5},
+      {0x9f4f2726179a2245, 0x01d762422c946591},
+      {0xc722f0ef9d80aad6, 0x424d3ad2b7b97ef6},
+      {0xf8ebad2b84e0d58b, 0xd2e0898765a7deb3},
+      {0x9b934c3b330c8577, 0x63cc55f49f88eb30},
+      {0xc2781f49ffcfa6d5, 0x3cbf6b71c76b25fc},
+      {0xf316271c7fc3908a, 0x8bef464e3945ef7b},
+      {0x97edd871cfda3a56, 0x97758bf0e3cbb5ad},
+      {0xbde94e8e43d0c8ec, 0x3d52eeed1cbea318},
+      {0xed63a231d4c4fb27, 0x4ca7aaa863ee4bde},
+      {0x945e455f24fb1cf8, 0x8fe8caa93e74ef6b},
+      {0xb975d6b6ee39e436, 0xb3e2fd538e122b45},
+      {0xe7d34c64a9c85d44, 0x60dbbca87196b617},
+      {0x90e40fbeea1d3a4a, 0xbc8955e946fe31ce},
+      {0xb51d13aea4a488dd, 0x6babab6398bdbe42},
+      {0xe264589a4dcdab14, 0xc696963c7eed2dd2},
+      {0x8d7eb76070a08aec, 0xfc1e1de5cf543ca3},
+      {0xb0de65388cc8ada8, 0x3b25a55f43294bcc},
+      {0xdd15fe86affad912, 0x49ef0eb713f39ebf},
+      {0x8a2dbf142dfcc7ab, 0x6e3569326c784338},
+      {0xacb92ed9397bf996, 0x49c2c37f07965405},
+      {0xd7e77a8f87daf7fb, 0xdc33745ec97be907},
+      {0x86f0ac99b4e8dafd, 0x69a028bb3ded71a4},
+      {0xa8acd7c0222311bc, 0xc40832ea0d68ce0d},
+      {0xd2d80db02aabd62b, 0xf50a3fa490c30191},
+      {0x83c7088e1aab65db, 0x792667c6da79e0fb},
+      {0xa4b8cab1a1563f52, 0x577001b891185939},
+      {0xcde6fd5e09abcf26, 0xed4c0226b55e6f87},
+      {0x80b05e5ac60b6178, 0x544f8158315b05b5},
+      {0xa0dc75f1778e39d6, 0x696361ae3db1c722},
+      {0xc913936dd571c84c, 0x03bc3a19cd1e38ea},
+      {0xfb5878494ace3a5f, 0x04ab48a04065c724},
+      {0x9d174b2dcec0e47b, 0x62eb0d64283f9c77},
+      {0xc45d1df942711d9a, 0x3ba5d0bd324f8395},
+      {0xf5746577930d6500, 0xca8f44ec7ee3647a},
+      {0x9968bf6abbe85f20, 0x7e998b13cf4e1ecc},
+      {0xbfc2ef456ae276e8, 0x9e3fedd8c321a67f},
+      {0xefb3ab16c59b14a2, 0xc5cfe94ef3ea101f},
+      {0x95d04aee3b80ece5, 0xbba1f1d158724a13},
+      {0xbb445da9ca61281f, 0x2a8a6e45ae8edc98},
+      {0xea1575143cf97226, 0xf52d09d71a3293be},
+      {0x924d692ca61be758, 0x593c2626705f9c57},
+      {0xb6e0c377cfa2e12e, 0x6f8b2fb00c77836d},
+      {0xe498f455c38b997a, 0x0b6dfb9c0f956448},
+      {0x8edf98b59a373fec, 0x4724bd4189bd5ead},
+      {0xb2977ee300c50fe7, 0x58edec91ec2cb658},
+      {0xdf3d5e9bc0f653e1, 0x2f2967b66737e3ee},
+      {0x8b865b215899f46c, 0xbd79e0d20082ee75},
+      {0xae67f1e9aec07187, 0xecd8590680a3aa12},
+      {0xda01ee641a708de9, 0xe80e6f4820cc9496},
+      {0x884134fe908658b2, 0x3109058d147fdcde},
+      {0xaa51823e34a7eede, 0xbd4b46f0599fd416},
+      {0xd4e5e2cdc1d1ea96, 0x6c9e18ac7007c91b},
+      {0x850fadc09923329e, 0x03e2cf6bc604ddb1},
+      {0xa6539930bf6bff45, 0x84db8346b786151d},
+      {0xcfe87f7cef46ff16, 0xe612641865679a64},
+      {0x81f14fae158c5f6e, 0x4fcb7e8f3f60c07f},
+      {0xa26da3999aef7749, 0xe3be5e330f38f09e},
+      {0xcb090c8001ab551c, 0x5cadf5bfd3072cc6},
+      {0xfdcb4fa002162a63, 0x73d9732fc7c8f7f7},
+      {0x9e9f11c4014dda7e, 0x2867e7fddcdd9afb},
+      {0xc646d63501a1511d, 0xb281e1fd541501b9},
+      {0xf7d88bc24209a565, 0x1f225a7ca91a4227},
+      {0x9ae757596946075f, 0x3375788de9b06959},
+      {0xc1a12d2fc3978937, 0x0052d6b1641c83af},
+      {0xf209787bb47d6b84, 0xc0678c5dbd23a49b},
+      {0x9745eb4d50ce6332, 0xf840b7ba963646e1},
+      {0xbd176620a501fbff, 0xb650e5a93bc3d899},
+      {0xec5d3fa8ce427aff, 0xa3e51f138ab4cebf},
+      {0x93ba47c980e98cdf, 0xc66f336c36b10138},
+      {0xb8a8d9bbe123f017, 0xb80b0047445d4185},
+      {0xe6d3102ad96cec1d, 0xa60dc059157491e6},
+      {0x9043ea1ac7e41392, 0x87c89837ad68db30},
+      {0xb454e4a179dd1877, 0x29babe4598c311fc},
+      {0xe16a1dc9d8545e94, 0xf4296dd6fef3d67b},
+      {0x8ce2529e2734bb1d, 0x1899e4a65f58660d},
+      {0xb01ae745b101e9e4, 0x5ec05dcff72e7f90},
+      {0xdc21a1171d42645d, 0x76707543f4fa1f74},
+      {0x899504ae72497eba, 0x6a06494a791c53a9},
+      {0xabfa45da0edbde69, 0x0487db9d17636893},
+      {0xd6f8d7509292d603, 0x45a9d2845d3c42b7},
+      {0x865b86925b9bc5c2, 0x0b8a2392ba45a9b3},
+      {0xa7f26836f282b732, 0x8e6cac7768d7141f},
+      {0xd1ef0244af2364ff, 0x3207d795430cd927},
+      {0x8335616aed761f1f, 0x7f44e6bd49e807b9},
+      {0xa402b9c5a8d3a6e7, 0x5f16206c9c6209a7},
+      {0xcd036837130890a1, 0x36dba887c37a8c10},
+      {0x802221226be55a64, 0xc2494954da2c978a},
+      {0xa02aa96b06deb0fd, 0xf2db9baa10b7bd6d},
+      {0xc83553c5c8965d3d, 0x6f92829494e5acc8},
+      {0xfa42a8b73abbf48c, 0xcb772339ba1f17fa},
+      {0x9c69a97284b578d7, 0xff2a760414536efc},
+      {0xc38413cf25e2d70d, 0xfef5138519684abb},
+      {0xf46518c2ef5b8cd1, 0x7eb258665fc25d6a},
+      {0x98bf2f79d5993802, 0xef2f773ffbd97a62},
+      {0xbeeefb584aff8603, 0xaafb550ffacfd8fb},
+      {0xeeaaba2e5dbf6784, 0x95ba2a53f983cf39},
+      {0x952ab45cfa97a0b2, 0xdd945a747bf26184},
+      {0xba756174393d88df, 0x94f971119aeef9e5},
+      {0xe912b9d1478ceb17, 0x7a37cd5601aab85e},
+      {0x91abb422ccb812ee, 0xac62e055c10ab33b},
+      {0xb616a12b7fe617aa, 0x577b986b314d600a},
+      {0xe39c49765fdf9d94, 0xed5a7e85fda0b80c},
+      {0x8e41ade9fbebc27d, 0x14588f13be847308},
+      {0xb1d219647ae6b31c, 0x596eb2d8ae258fc9},
+      {0xde469fbd99a05fe3, 0x6fca5f8ed9aef3bc},
+      {0x8aec23d680043bee, 0x25de7bb9480d5855},
+      {0xada72ccc20054ae9, 0xaf561aa79a10ae6b},
+      {0xd910f7ff28069da4, 0x1b2ba1518094da05},
+      {0x87aa9aff79042286, 0x90fb44d2f05d0843},
+      {0xa99541bf57452b28, 0x353a1607ac744a54},
+      {0xd3fa922f2d1675f2, 0x42889b8997915ce9},
+      {0x847c9b5d7c2e09b7, 0x69956135febada12},
+      {0xa59bc234db398c25, 0x43fab9837e699096},
+      {0xcf02b2c21207ef2e, 0x94f967e45e03f4bc},
+      {0x8161afb94b44f57d, 0x1d1be0eebac278f6},
+      {0xa1ba1ba79e1632dc, 0x6462d92a69731733},
+      {0xca28a291859bbf93, 0x7d7b8f7503cfdcff},
+      {0xfcb2cb35e702af78, 0x5cda735244c3d43f},
+      {0x9defbf01b061adab, 0x3a0888136afa64a8},
+      {0xc56baec21c7a1916, 0x088aaa1845b8fdd1},
+      {0xf6c69a72a3989f5b, 0x8aad549e57273d46},
+      {0x9a3c2087a63f6399, 0x36ac54e2f678864c},
+      {0xc0cb28a98fcf3c7f, 0x84576a1bb416a7de},
+      {0xf0fdf2d3f3c30b9f, 0x656d44a2a11c51d6},
+      {0x969eb7c47859e743, 0x9f644ae5a4b1b326},
+      {0xbc4665b596706114, 0x873d5d9f0dde1fef},
+      {0xeb57ff22fc0c7959, 0xa90cb506d155a7eb},
+      {0x9316ff75dd87cbd8, 0x09a7f12442d588f3},
+      {0xb7dcbf5354e9bece, 0x0c11ed6d538aeb30},
+      {0xe5d3ef282a242e81, 0x8f1668c8a86da5fb},
+      {0x8fa475791a569d10, 0xf96e017d694487bd},
+      {0xb38d92d760ec4455, 0x37c981dcc395a9ad},
+      {0xe070f78d3927556a, 0x85bbe253f47b1418},
+      {0x8c469ab843b89562, 0x93956d7478ccec8f},
+      {0xaf58416654a6babb, 0x387ac8d1970027b3},
+      {0xdb2e51bfe9d0696a, 0x06997b05fcc0319f},
+      {0x88fcf317f22241e2, 0x441fece3bdf81f04},
+      {0xab3c2fddeeaad25a, 0xd527e81cad7626c4},
+      {0xd60b3bd56a5586f1, 0x8a71e223d8d3b075},
+      {0x85c7056562757456, 0xf6872d5667844e4a},
+      {0xa738c6bebb12d16c, 0xb428f8ac016561dc},
+      {0xd106f86e69d785c7, 0xe13336d701beba53},
+      {0x82a45b450226b39c, 0xecc0024661173474},
+      {0xa34d721642b06084, 0x27f002d7f95d0191},
+      {0xcc20ce9bd35c78a5, 0x31ec038df7b441f5},
+      {0xff290242c83396ce, 0x7e67047175a15272},
+      {0x9f79a169bd203e41, 0x0f0062c6e984d387},
+      {0xc75809c42c684dd1, 0x52c07b78a3e60869},
+      {0xf92e0c3537826145, 0xa7709a56ccdf8a83},
+      {0x9bbcc7a142b17ccb, 0x88a66076400bb692},
+      {0xc2abf989935ddbfe, 0x6acff893d00ea436},
+      {0xf356f7ebf83552fe, 0x0583f6b8c4124d44},
+      {0x98165af37b2153de, 0xc3727a337a8b704b},
+      {0xbe1bf1b059e9a8d6, 0x744f18c0592e4c5d},
+      {0xeda2ee1c7064130c, 0x1162def06f79df74},
+      {0x9485d4d1c63e8be7, 0x8addcb5645ac2ba9},
+      {0xb9a74a0637ce2ee1, 0x6d953e2bd7173693},
+      {0xe8111c87c5c1ba99, 0xc8fa8db6ccdd0438},
+      {0x910ab1d4db9914a0, 0x1d9c9892400a22a3},
+      {0xb54d5e4a127f59c8, 0x2503beb6d00cab4c},
+      {0xe2a0b5dc971f303a, 0x2e44ae64840fd61e},
+      {0x8da471a9de737e24, 0x5ceaecfed289e5d3},
+      {0xb10d8e1456105dad, 0x7425a83e872c5f48},
+      {0xdd50f1996b947518, 0xd12f124e28f7771a},
+      {0x8a5296ffe33cc92f, 0x82bd6b70d99aaa70},
+      {0xace73cbfdc0bfb7b, 0x636cc64d1001550c},
+      {0xd8210befd30efa5a, 0x3c47f7e05401aa4f},
+      {0x8714a775e3e95c78, 0x65acfaec34810a72},
+      {0xa8d9d1535ce3b396, 0x7f1839a741a14d0e},
+      {0xd31045a8341ca07c, 0x1ede48111209a051},
+      {0x83ea2b892091e44d, 0x934aed0aab460433},
+      {0xa4e4b66b68b65d60, 0xf81da84d56178540},
+      {0xce1de40642e3f4b9, 0x36251260ab9d668f},
+      {0x80d2ae83e9ce78f3, 0xc1d72b7c6b42601a},
+      {0xa1075a24e4421730, 0xb24cf65b8612f820},
+      {0xc94930ae1d529cfc, 0xdee033f26797b628},
+      {0xfb9b7cd9a4a7443c, 0x169840ef017da3b2},
+      {0x9d412e0806e88aa5, 0x8e1f289560ee864f},
+      {0xc491798a08a2ad4e, 0xf1a6f2bab92a27e3},
+      {0xf5b5d7ec8acb58a2, 0xae10af696774b1dc},
+      {0x9991a6f3d6bf1765, 0xacca6da1e0a8ef2a},
+      {0xbff610b0cc6edd3f, 0x17fd090a58d32af4},
+      {0xeff394dcff8a948e, 0xddfc4b4cef07f5b1},
+      {0x95f83d0a1fb69cd9, 0x4abdaf101564f98f},
+      {0xbb764c4ca7a4440f, 0x9d6d1ad41abe37f2},
+      {0xea53df5fd18d5513, 0x84c86189216dc5ee},
+      {0x92746b9be2f8552c, 0x32fd3cf5b4e49bb5},
+      {0xb7118682dbb66a77, 0x3fbc8c33221dc2a2},
+      {0xe4d5e82392a40515, 0x0fabaf3feaa5334b},
+      {0x8f05b1163ba6832d, 0x29cb4d87f2a7400f},
+      {0xb2c71d5bca9023f8, 0x743e20e9ef511013},
+      {0xdf78e4b2bd342cf6, 0x914da9246b255417},
+      {0x8bab8eefb6409c1a, 0x1ad089b6c2f7548f},
+      {0xae9672aba3d0c320, 0xa184ac2473b529b2},
+      {0xda3c0f568cc4f3e8, 0xc9e5d72d90a2741f},
+      {0x8865899617fb1871, 0x7e2fa67c7a658893},
+      {0xaa7eebfb9df9de8d, 0xddbb901b98feeab8},
+      {0xd51ea6fa85785631, 0x552a74227f3ea566},
+      {0x8533285c936b35de, 0xd53a88958f872760},
+      {0xa67ff273b8460356, 0x8a892abaf368f138},
+      {0xd01fef10a657842c, 0x2d2b7569b0432d86},
+      {0x8213f56a67f6b29b, 0x9c3b29620e29fc74},
+      {0xa298f2c501f45f42, 0x8349f3ba91b47b90},
+      {0xcb3f2f7642717713, 0x241c70a936219a74},
+      {0xfe0efb53d30dd4d7, 0xed238cd383aa0111},
+      {0x9ec95d1463e8a506, 0xf4363804324a40ab},
+      {0xc67bb4597ce2ce48, 0xb143c6053edcd0d6},
+      {0xf81aa16fdc1b81da, 0xdd94b7868e94050b},
+      {0x9b10a4e5e9913128, 0xca7cf2b4191c8327},
+      {0xc1d4ce1f63f57d72, 0xfd1c2f611f63a3f1},
+      {0xf24a01a73cf2dccf, 0xbc633b39673c8ced},
+      {0x976e41088617ca01, 0xd5be0503e085d814},
+      {0xbd49d14aa79dbc82, 0x4b2d8644d8a74e19},
+      {0xec9c459d51852ba2, 0xddf8e7d60ed1219f},
+      {0x93e1ab8252f33b45, 0xcabb90e5c942b504},
+      {0xb8da1662e7b00a17, 0x3d6a751f3b936244},
+      {0xe7109bfba19c0c9d, 0x0cc512670a783ad5},
+      {0x906a617d450187e2, 0x27fb2b80668b24c6},
+      {0xb484f9dc9641e9da, 0xb1f9f660802dedf7},
+      {0xe1a63853bbd26451, 0x5e7873f8a0396974},
+      {0x8d07e33455637eb2, 0xdb0b487b6423e1e9},
+      {0xb049dc016abc5e5f, 0x91ce1a9a3d2cda63},
+      {0xdc5c5301c56b75f7, 0x7641a140cc7810fc},
+      {0x89b9b3e11b6329ba, 0xa9e904c87fcb0a9e},
+      {0xac2820d9623bf429, 0x546345fa9fbdcd45},
+      {0xd732290fbacaf133, 0xa97c177947ad4096},
+      {0x867f59a9d4bed6c0, 0x49ed8eabcccc485e},
+      {0xa81f301449ee8c70, 0x5c68f256bfff5a75},
+      {0xd226fc195c6a2f8c, 0x73832eec6fff3112},
+      {0x83585d8fd9c25db7, 0xc831fd53c5ff7eac},
+      {0xa42e74f3d032f525, 0xba3e7ca8b77f5e56},
+      {0xcd3a1230c43fb26f, 0x28ce1bd2e55f35ec},
+      {0x80444b5e7aa7cf85, 0x7980d163cf5b81b4},
+      {0xa0555e361951c366, 0xd7e105bcc3326220},
+      {0xc86ab5c39fa63440, 0x8dd9472bf3fefaa8},
+      {0xfa856334878fc150, 0xb14f98f6f0feb952},
+      {0x9c935e00d4b9d8d2, 0x6ed1bf9a569f33d4},
+      {0xc3b8358109e84f07, 0x0a862f80ec4700c9},
+      {0xf4a642e14c6262c8, 0xcd27bb612758c0fb},
+      {0x98e7e9cccfbd7dbd, 0x8038d51cb897789d},
+      {0xbf21e44003acdd2c, 0xe0470a63e6bd56c4},
+      {0xeeea5d5004981478, 0x1858ccfce06cac75},
+      {0x95527a5202df0ccb, 0x0f37801e0c43ebc9},
+      {0xbaa718e68396cffd, 0xd30560258f54e6bb},
+      {0xe950df20247c83fd, 0x47c6b82ef32a206a},
+      {0x91d28b7416cdd27e, 0x4cdc331d57fa5442},
+      {0xb6472e511c81471d, 0xe0133fe4adf8e953},
+      {0xe3d8f9e563a198e5, 0x58180fddd97723a7},
+      {0x8e679c2f5e44ff8f, 0x570f09eaa7ea7649},
+      {0xb201833b35d63f73, 0x2cd2cc6551e513db},
+      {0xde81e40a034bcf4f, 0xf8077f7ea65e58d2},
+      {0x8b112e86420f6191, 0xfb04afaf27faf783},
+      {0xadd57a27d29339f6, 0x79c5db9af1f9b564},
+      {0xd94ad8b1c7380874, 0x18375281ae7822bd},
+      {0x87cec76f1c830548, 0x8f2293910d0b15b6},
+      {0xa9c2794ae3a3c69a, 0xb2eb3875504ddb23},
+      {0xd433179d9c8cb841, 0x5fa60692a46151ec},
+      {0x849feec281d7f328, 0xdbc7c41ba6bcd334},
+      {0xa5c7ea73224deff3, 0x12b9b522906c0801},
+      {0xcf39e50feae16bef, 0xd768226b34870a01},
+      {0x81842f29f2cce375, 0xe6a1158300d46641},
+      {0xa1e53af46f801c53, 0x60495ae3c1097fd1},
+      {0xca5e89b18b602368, 0x385bb19cb14bdfc5},
+      {0xfcf62c1dee382c42, 0x46729e03dd9ed7b6},
+      {0x9e19db92b4e31ba9, 0x6c07a2c26a8346d2},
+      {0xc5a05277621be293, 0xc7098b7305241886},
+      { 0xf70867153aa2db38,
+        0xb8cbee4fc66d1ea8 }
+#else
+      {0xff77b1fcbebcdc4f, 0x25e8e89c13bb0f7b},
+      {0xce5d73ff402d98e3, 0xfb0a3d212dc81290},
+      {0xa6b34ad8c9dfc06f, 0xf42faa48c0ea481f},
+      {0x86a8d39ef77164bc, 0xae5dff9c02033198},
+      {0xd98ddaee19068c76, 0x3badd624dd9b0958},
+      {0xafbd2350644eeacf, 0xe5d1929ef90898fb},
+      {0x8df5efabc5979c8f, 0xca8d3ffa1ef463c2},
+      {0xe55990879ddcaabd, 0xcc420a6a101d0516},
+      {0xb94470938fa89bce, 0xf808e40e8d5b3e6a},
+      {0x95a8637627989aad, 0xdde7001379a44aa9},
+      {0xf1c90080baf72cb1, 0x5324c68b12dd6339},
+      {0xc350000000000000, 0x0000000000000000},
+      {0x9dc5ada82b70b59d, 0xf020000000000000},
+      {0xfee50b7025c36a08, 0x02f236d04753d5b5},
+      {0xcde6fd5e09abcf26, 0xed4c0226b55e6f87},
+      {0xa6539930bf6bff45, 0x84db8346b786151d},
+      {0x865b86925b9bc5c2, 0x0b8a2392ba45a9b3},
+      {0xd910f7ff28069da4, 0x1b2ba1518094da05},
+      {0xaf58416654a6babb, 0x387ac8d1970027b3},
+      {0x8da471a9de737e24, 0x5ceaecfed289e5d3},
+      {0xe4d5e82392a40515, 0x0fabaf3feaa5334b},
+      {0xb8da1662e7b00a17, 0x3d6a751f3b936244},
+      { 0x95527a5202df0ccb,
+        0x0f37801e0c43ebc9 }
+#endif
+    };
+
+#if FMT_USE_FULL_CACHE_DRAGONBOX
+    return pow10_significands[k - float_info<double>::min_k];
+#else
+    static constexpr const uint64_t powers_of_5_64[] = {
+        0x0000000000000001, 0x0000000000000005, 0x0000000000000019,
+        0x000000000000007d, 0x0000000000000271, 0x0000000000000c35,
+        0x0000000000003d09, 0x000000000001312d, 0x000000000005f5e1,
+        0x00000000001dcd65, 0x00000000009502f9, 0x0000000002e90edd,
+        0x000000000e8d4a51, 0x0000000048c27395, 0x000000016bcc41e9,
+        0x000000071afd498d, 0x0000002386f26fc1, 0x000000b1a2bc2ec5,
+        0x000003782dace9d9, 0x00001158e460913d, 0x000056bc75e2d631,
+        0x0001b1ae4d6e2ef5, 0x000878678326eac9, 0x002a5a058fc295ed,
+        0x00d3c21bcecceda1, 0x0422ca8b0a00a425, 0x14adf4b7320334b9};
+
+    static const int compression_ratio = 27;
+
+    // Compute base index.
+    int cache_index = (k - float_info<double>::min_k) / compression_ratio;
+    int kb = cache_index * compression_ratio + float_info<double>::min_k;
+    int offset = k - kb;
+
+    // Get base cache.
+    uint128_fallback base_cache = pow10_significands[cache_index];
+    if (offset == 0) return base_cache;
+
+    // Compute the required amount of bit-shift.
+    int alpha = floor_log2_pow10(kb + offset) - floor_log2_pow10(kb) - offset;
+    FMT_ASSERT(alpha > 0 && alpha < 64, "shifting error detected");
+
+    // Try to recover the real cache.
+    uint64_t pow5 = powers_of_5_64[offset];
+    uint128_fallback recovered_cache = umul128(base_cache.high(), pow5);
+    uint128_fallback middle_low = umul128(base_cache.low(), pow5);
+
+    recovered_cache += middle_low.high();
+
+    uint64_t high_to_middle = recovered_cache.high() << (64 - alpha);
+    uint64_t middle_to_low = recovered_cache.low() << (64 - alpha);
+
+    recovered_cache =
+        uint128_fallback{(recovered_cache.low() >> alpha) | high_to_middle,
+                         ((middle_low.low() >> alpha) | middle_to_low)};
+    FMT_ASSERT(recovered_cache.low() + 1 != 0, "");
+    return {recovered_cache.high(), recovered_cache.low() + 1};
+#endif
+  }
+
+  struct compute_mul_result {
+    carrier_uint result;
+    bool is_integer;
+  };
+  struct compute_mul_parity_result {
+    bool parity;
+    bool is_integer;
+  };
+
+  static compute_mul_result compute_mul(
+      carrier_uint u, const cache_entry_type& cache) noexcept {
+    auto r = umul192_upper128(u, cache);
+    return {r.high(), r.low() == 0};
+  }
+
+  static uint32_t compute_delta(cache_entry_type const& cache,
+                                int beta) noexcept {
+    return static_cast<uint32_t>(cache.high() >> (64 - 1 - beta));
+  }
+
+  static compute_mul_parity_result compute_mul_parity(
+      carrier_uint two_f, const cache_entry_type& cache, int beta) noexcept {
+    FMT_ASSERT(beta >= 1, "");
+    FMT_ASSERT(beta < 64, "");
+
+    auto r = umul192_lower128(two_f, cache);
+    return {((r.high() >> (64 - beta)) & 1) != 0,
+            ((r.high() << beta) | (r.low() >> (64 - beta))) == 0};
+  }
+
+  static carrier_uint compute_left_endpoint_for_shorter_interval_case(
+      const cache_entry_type& cache, int beta) noexcept {
+    return (cache.high() -
+            (cache.high() >> (num_significand_bits<double>() + 2))) >>
+           (64 - num_significand_bits<double>() - 1 - beta);
+  }
+
+  static carrier_uint compute_right_endpoint_for_shorter_interval_case(
+      const cache_entry_type& cache, int beta) noexcept {
+    return (cache.high() +
+            (cache.high() >> (num_significand_bits<double>() + 1))) >>
+           (64 - num_significand_bits<double>() - 1 - beta);
+  }
+
+  static carrier_uint compute_round_up_for_shorter_interval_case(
+      const cache_entry_type& cache, int beta) noexcept {
+    return ((cache.high() >> (64 - num_significand_bits<double>() - 2 - beta)) +
+            1) /
+           2;
+  }
+};
+
+// Various integer checks
+template <class T>
+bool is_left_endpoint_integer_shorter_interval(int exponent) noexcept {
+  const int case_shorter_interval_left_endpoint_lower_threshold = 2;
+  const int case_shorter_interval_left_endpoint_upper_threshold = 3;
+  return exponent >= case_shorter_interval_left_endpoint_lower_threshold &&
+         exponent <= case_shorter_interval_left_endpoint_upper_threshold;
+}
+
+// Remove trailing zeros from n and return the number of zeros removed (float)
+FMT_INLINE int remove_trailing_zeros(uint32_t& n) noexcept {
+  FMT_ASSERT(n != 0, "");
+  const uint32_t mod_inv_5 = 0xcccccccd;
+  const uint32_t mod_inv_25 = mod_inv_5 * mod_inv_5;
+
+  int s = 0;
+  while (true) {
+    auto q = rotr(n * mod_inv_25, 2);
+    if (q > max_value<uint32_t>() / 100) break;
+    n = q;
+    s += 2;
+  }
+  auto q = rotr(n * mod_inv_5, 1);
+  if (q <= max_value<uint32_t>() / 10) {
+    n = q;
+    s |= 1;
+  }
+
+  return s;
+}
+
+// Removes trailing zeros and returns the number of zeros removed (double)
+FMT_INLINE int remove_trailing_zeros(uint64_t& n) noexcept {
+  FMT_ASSERT(n != 0, "");
+
+  // This magic number is ceil(2^90 / 10^8).
+  constexpr uint64_t magic_number = 12379400392853802749ull;
+  auto nm = umul128(n, magic_number);
+
+  // Is n is divisible by 10^8?
+  if ((nm.high() & ((1ull << (90 - 64)) - 1)) == 0 && nm.low() < magic_number) {
+    // If yes, work with the quotient.
+    auto n32 = static_cast<uint32_t>(nm.high() >> (90 - 64));
+
+    const uint32_t mod_inv_5 = 0xcccccccd;
+    const uint32_t mod_inv_25 = mod_inv_5 * mod_inv_5;
+
+    int s = 8;
+    while (true) {
+      auto q = rotr(n32 * mod_inv_25, 2);
+      if (q > max_value<uint32_t>() / 100) break;
+      n32 = q;
+      s += 2;
+    }
+    auto q = rotr(n32 * mod_inv_5, 1);
+    if (q <= max_value<uint32_t>() / 10) {
+      n32 = q;
+      s |= 1;
+    }
+
+    n = n32;
+    return s;
+  }
+
+  // If n is not divisible by 10^8, work with n itself.
+  const uint64_t mod_inv_5 = 0xcccccccccccccccd;
+  const uint64_t mod_inv_25 = mod_inv_5 * mod_inv_5;
+
+  int s = 0;
+  while (true) {
+    auto q = rotr(n * mod_inv_25, 2);
+    if (q > max_value<uint64_t>() / 100) break;
+    n = q;
+    s += 2;
+  }
+  auto q = rotr(n * mod_inv_5, 1);
+  if (q <= max_value<uint64_t>() / 10) {
+    n = q;
+    s |= 1;
+  }
+
+  return s;
+}
+
+// The main algorithm for shorter interval case
+template <class T>
+FMT_INLINE decimal_fp<T> shorter_interval_case(int exponent) noexcept {
+  decimal_fp<T> ret_value;
+  // Compute k and beta
+  const int minus_k = floor_log10_pow2_minus_log10_4_over_3(exponent);
+  const int beta = exponent + floor_log2_pow10(-minus_k);
+
+  // Compute xi and zi
+  using cache_entry_type = typename cache_accessor<T>::cache_entry_type;
+  const cache_entry_type cache = cache_accessor<T>::get_cached_power(-minus_k);
+
+  auto xi = cache_accessor<T>::compute_left_endpoint_for_shorter_interval_case(
+      cache, beta);
+  auto zi = cache_accessor<T>::compute_right_endpoint_for_shorter_interval_case(
+      cache, beta);
+
+  // If the left endpoint is not an integer, increase it
+  if (!is_left_endpoint_integer_shorter_interval<T>(exponent)) ++xi;
+
+  // Try bigger divisor
+  ret_value.significand = zi / 10;
+
+  // If succeed, remove trailing zeros if necessary and return
+  if (ret_value.significand * 10 >= xi) {
+    ret_value.exponent = minus_k + 1;
+    ret_value.exponent += remove_trailing_zeros(ret_value.significand);
+    return ret_value;
+  }
+
+  // Otherwise, compute the round-up of y
+  ret_value.significand =
+      cache_accessor<T>::compute_round_up_for_shorter_interval_case(cache,
+                                                                    beta);
+  ret_value.exponent = minus_k;
+
+  // When tie occurs, choose one of them according to the rule
+  if (exponent >= float_info<T>::shorter_interval_tie_lower_threshold &&
+      exponent <= float_info<T>::shorter_interval_tie_upper_threshold) {
+    ret_value.significand = ret_value.significand % 2 == 0
+                                ? ret_value.significand
+                                : ret_value.significand - 1;
+  } else if (ret_value.significand < xi) {
+    ++ret_value.significand;
+  }
+  return ret_value;
+}
+
+template <typename T> decimal_fp<T> to_decimal(T x) noexcept {
+  // Step 1: integer promotion & Schubfach multiplier calculation.
+
+  using carrier_uint = typename float_info<T>::carrier_uint;
+  using cache_entry_type = typename cache_accessor<T>::cache_entry_type;
+  auto br = bit_cast<carrier_uint>(x);
+
+  // Extract significand bits and exponent bits.
+  const carrier_uint significand_mask =
+      (static_cast<carrier_uint>(1) << num_significand_bits<T>()) - 1;
+  carrier_uint significand = (br & significand_mask);
+  int exponent =
+      static_cast<int>((br & exponent_mask<T>()) >> num_significand_bits<T>());
+
+  if (exponent != 0) {  // Check if normal.
+    exponent -= exponent_bias<T>() + num_significand_bits<T>();
+
+    // Shorter interval case; proceed like Schubfach.
+    // In fact, when exponent == 1 and significand == 0, the interval is
+    // regular. However, it can be shown that the end-results are anyway same.
+    if (significand == 0) return shorter_interval_case<T>(exponent);
+
+    significand |= (static_cast<carrier_uint>(1) << num_significand_bits<T>());
+  } else {
+    // Subnormal case; the interval is always regular.
+    if (significand == 0) return {0, 0};
+    exponent =
+        std::numeric_limits<T>::min_exponent - num_significand_bits<T>() - 1;
+  }
+
+  const bool include_left_endpoint = (significand % 2 == 0);
+  const bool include_right_endpoint = include_left_endpoint;
+
+  // Compute k and beta.
+  const int minus_k = floor_log10_pow2(exponent) - float_info<T>::kappa;
+  const cache_entry_type cache = cache_accessor<T>::get_cached_power(-minus_k);
+  const int beta = exponent + floor_log2_pow10(-minus_k);
+
+  // Compute zi and deltai.
+  // 10^kappa <= deltai < 10^(kappa + 1)
+  const uint32_t deltai = cache_accessor<T>::compute_delta(cache, beta);
+  const carrier_uint two_fc = significand << 1;
+
+  // For the case of binary32, the result of integer check is not correct for
+  // 29711844 * 2^-82
+  // = 6.1442653300000000008655037797566933477355632930994033813476... * 10^-18
+  // and 29711844 * 2^-81
+  // = 1.2288530660000000001731007559513386695471126586198806762695... * 10^-17,
+  // and they are the unique counterexamples. However, since 29711844 is even,
+  // this does not cause any problem for the endpoints calculations; it can only
+  // cause a problem when we need to perform integer check for the center.
+  // Fortunately, with these inputs, that branch is never executed, so we are
+  // fine.
+  const typename cache_accessor<T>::compute_mul_result z_mul =
+      cache_accessor<T>::compute_mul((two_fc | 1) << beta, cache);
+
+  // Step 2: Try larger divisor; remove trailing zeros if necessary.
+
+  // Using an upper bound on zi, we might be able to optimize the division
+  // better than the compiler; we are computing zi / big_divisor here.
+  decimal_fp<T> ret_value;
+  ret_value.significand = divide_by_10_to_kappa_plus_1(z_mul.result);
+  uint32_t r = static_cast<uint32_t>(z_mul.result - float_info<T>::big_divisor *
+                                                        ret_value.significand);
+
+  if (r < deltai) {
+    // Exclude the right endpoint if necessary.
+    if (r == 0 && (z_mul.is_integer & !include_right_endpoint)) {
+      --ret_value.significand;
+      r = float_info<T>::big_divisor;
+      goto small_divisor_case_label;
+    }
+  } else if (r > deltai) {
+    goto small_divisor_case_label;
+  } else {
+    // r == deltai; compare fractional parts.
+    const typename cache_accessor<T>::compute_mul_parity_result x_mul =
+        cache_accessor<T>::compute_mul_parity(two_fc - 1, cache, beta);
+
+    if (!(x_mul.parity | (x_mul.is_integer & include_left_endpoint)))
+      goto small_divisor_case_label;
+  }
+  ret_value.exponent = minus_k + float_info<T>::kappa + 1;
+
+  // We may need to remove trailing zeros.
+  ret_value.exponent += remove_trailing_zeros(ret_value.significand);
+  return ret_value;
+
+  // Step 3: Find the significand with the smaller divisor.
+
+small_divisor_case_label:
+  ret_value.significand *= 10;
+  ret_value.exponent = minus_k + float_info<T>::kappa;
+
+  uint32_t dist = r - (deltai / 2) + (float_info<T>::small_divisor / 2);
+  const bool approx_y_parity =
+      ((dist ^ (float_info<T>::small_divisor / 2)) & 1) != 0;
+
+  // Is dist divisible by 10^kappa?
+  const bool divisible_by_small_divisor =
+      check_divisibility_and_divide_by_pow10<float_info<T>::kappa>(dist);
+
+  // Add dist / 10^kappa to the significand.
+  ret_value.significand += dist;
+
+  if (!divisible_by_small_divisor) return ret_value;
+
+  // Check z^(f) >= epsilon^(f).
+  // We have either yi == zi - epsiloni or yi == (zi - epsiloni) - 1,
+  // where yi == zi - epsiloni if and only if z^(f) >= epsilon^(f).
+  // Since there are only 2 possibilities, we only need to care about the
+  // parity. Also, zi and r should have the same parity since the divisor
+  // is an even number.
+  const auto y_mul = cache_accessor<T>::compute_mul_parity(two_fc, cache, beta);
+
+  // If z^(f) >= epsilon^(f), we might have a tie when z^(f) == epsilon^(f),
+  // or equivalently, when y is an integer.
+  if (y_mul.parity != approx_y_parity)
+    --ret_value.significand;
+  else if (y_mul.is_integer & (ret_value.significand % 2 != 0))
+    --ret_value.significand;
+  return ret_value;
+}
+}  // namespace dragonbox
+
+#ifdef _MSC_VER
+FMT_FUNC auto fmt_snprintf(char* buf, size_t size, const char* fmt, ...)
+    -> int {
+  auto args = va_list();
+  va_start(args, fmt);
+  int result = vsnprintf_s(buf, size, _TRUNCATE, fmt, args);
+  va_end(args);
+  return result;
+}
+#endif
+}  // namespace detail
+
+template <> struct formatter<detail::bigint> {
+  FMT_CONSTEXPR auto parse(format_parse_context& ctx)
+      -> format_parse_context::iterator {
+    return ctx.begin();
+  }
+
+  template <typename FormatContext>
+  auto format(const detail::bigint& n, FormatContext& ctx) const ->
+      typename FormatContext::iterator {
+    auto out = ctx.out();
+    bool first = true;
+    for (auto i = n.bigits_.size(); i > 0; --i) {
+      auto value = n.bigits_[i - 1u];
+      if (first) {
+        out = format_to(out, FMT_STRING("{:x}"), value);
+        first = false;
+        continue;
+      }
+      out = format_to(out, FMT_STRING("{:08x}"), value);
+    }
+    if (n.exp_ > 0)
+      out = format_to(out, FMT_STRING("p{}"),
+                      n.exp_ * detail::bigint::bigit_bits);
+    return out;
+  }
+};
+
+FMT_FUNC detail::utf8_to_utf16::utf8_to_utf16(string_view s) {
+  for_each_codepoint(s, [this](uint32_t cp, string_view) {
+    if (cp == invalid_code_point) FMT_THROW(std::runtime_error("invalid utf8"));
+    if (cp <= 0xFFFF) {
+      buffer_.push_back(static_cast<wchar_t>(cp));
+    } else {
+      cp -= 0x10000;
+      buffer_.push_back(static_cast<wchar_t>(0xD800 + (cp >> 10)));
+      buffer_.push_back(static_cast<wchar_t>(0xDC00 + (cp & 0x3FF)));
+    }
+    return true;
+  });
+  buffer_.push_back(0);
+}
+
+FMT_FUNC void format_system_error(detail::buffer<char>& out, int error_code,
+                                  const char* message) noexcept {
+  FMT_TRY {
+    auto ec = std::error_code(error_code, std::generic_category());
+    write(std::back_inserter(out), std::system_error(ec, message).what());
+    return;
+  }
+  FMT_CATCH(...) {}
+  format_error_code(out, error_code, message);
+}
+
+FMT_FUNC void report_system_error(int error_code,
+                                  const char* message) noexcept {
+  report_error(format_system_error, error_code, message);
+}
+
+FMT_FUNC std::string vformat(string_view fmt, format_args args) {
+  // Don't optimize the "{}" case to keep the binary size small and because it
+  // can be better optimized in fmt::format anyway.
+  auto buffer = memory_buffer();
+  detail::vformat_to(buffer, fmt, args);
+  return to_string(buffer);
+}
+
+namespace detail {
+#ifdef _WIN32
+using dword = conditional_t<sizeof(long) == 4, unsigned long, unsigned>;
+extern "C" __declspec(dllimport) int __stdcall WriteConsoleW(  //
+    void*, const void*, dword, dword*, void*);
+
+FMT_FUNC bool write_console(std::FILE* f, string_view text) {
+  auto fd = _fileno(f);
+  if (_isatty(fd)) {
+    detail::utf8_to_utf16 u16(string_view(text.data(), text.size()));
+    auto written = detail::dword();
+    if (detail::WriteConsoleW(reinterpret_cast<void*>(_get_osfhandle(fd)),
+                              u16.c_str(), static_cast<uint32_t>(u16.size()),
+                              &written, nullptr)) {
+      return true;
+    }
+  }
+  // We return false if the file descriptor was not TTY, or it was but
+  // SetConsoleW failed which can happen if the output has been redirected to
+  // NUL. In both cases when we return false, we should attempt to do regular
+  // write via fwrite or std::ostream::write.
+  return false;
+}
+#endif
+
+FMT_FUNC void print(std::FILE* f, string_view text) {
+#ifdef _WIN32
+  if (write_console(f, text)) return;
+#endif
+  detail::fwrite_fully(text.data(), 1, text.size(), f);
+}
+}  // namespace detail
+
+FMT_FUNC void vprint(std::FILE* f, string_view format_str, format_args args) {
+  memory_buffer buffer;
+  detail::vformat_to(buffer, format_str, args);
+  detail::print(f, {buffer.data(), buffer.size()});
+}
+
+#ifdef _WIN32
+// Print assuming legacy (non-Unicode) encoding.
+FMT_FUNC void detail::vprint_mojibake(std::FILE* f, string_view format_str,
+                                      format_args args) {
+  memory_buffer buffer;
+  detail::vformat_to(buffer, format_str,
+                     basic_format_args<buffer_context<char>>(args));
+  fwrite_fully(buffer.data(), 1, buffer.size(), f);
+}
+#endif
+
+FMT_FUNC void vprint(string_view format_str, format_args args) {
+  vprint(stdout, format_str, args);
+}
+
+namespace detail {
+
+struct singleton {
+  unsigned char upper;
+  unsigned char lower_count;
+};
+
+inline auto is_printable(uint16_t x, const singleton* singletons,
+                         size_t singletons_size,
+                         const unsigned char* singleton_lowers,
+                         const unsigned char* normal, size_t normal_size)
+    -> bool {
+  auto upper = x >> 8;
+  auto lower_start = 0;
+  for (size_t i = 0; i < singletons_size; ++i) {
+    auto s = singletons[i];
+    auto lower_end = lower_start + s.lower_count;
+    if (upper < s.upper) break;
+    if (upper == s.upper) {
+      for (auto j = lower_start; j < lower_end; ++j) {
+        if (singleton_lowers[j] == (x & 0xff)) return false;
+      }
+    }
+    lower_start = lower_end;
+  }
+
+  auto xsigned = static_cast<int>(x);
+  auto current = true;
+  for (size_t i = 0; i < normal_size; ++i) {
+    auto v = static_cast<int>(normal[i]);
+    auto len = (v & 0x80) != 0 ? (v & 0x7f) << 8 | normal[++i] : v;
+    xsigned -= len;
+    if (xsigned < 0) break;
+    current = !current;
+  }
+  return current;
+}
+
+// This code is generated by support/printable.py.
+FMT_FUNC auto is_printable(uint32_t cp) -> bool {
+  static constexpr singleton singletons0[] = {
+      {0x00, 1},  {0x03, 5},  {0x05, 6},  {0x06, 3},  {0x07, 6},  {0x08, 8},
+      {0x09, 17}, {0x0a, 28}, {0x0b, 25}, {0x0c, 20}, {0x0d, 16}, {0x0e, 13},
+      {0x0f, 4},  {0x10, 3},  {0x12, 18}, {0x13, 9},  {0x16, 1},  {0x17, 5},
+      {0x18, 2},  {0x19, 3},  {0x1a, 7},  {0x1c, 2},  {0x1d, 1},  {0x1f, 22},
+      {0x20, 3},  {0x2b, 3},  {0x2c, 2},  {0x2d, 11}, {0x2e, 1},  {0x30, 3},
+      {0x31, 2},  {0x32, 1},  {0xa7, 2},  {0xa9, 2},  {0xaa, 4},  {0xab, 8},
+      {0xfa, 2},  {0xfb, 5},  {0xfd, 4},  {0xfe, 3},  {0xff, 9},
+  };
+  static constexpr unsigned char singletons0_lower[] = {
+      0xad, 0x78, 0x79, 0x8b, 0x8d, 0xa2, 0x30, 0x57, 0x58, 0x8b, 0x8c, 0x90,
+      0x1c, 0x1d, 0xdd, 0x0e, 0x0f, 0x4b, 0x4c, 0xfb, 0xfc, 0x2e, 0x2f, 0x3f,
+      0x5c, 0x5d, 0x5f, 0xb5, 0xe2, 0x84, 0x8d, 0x8e, 0x91, 0x92, 0xa9, 0xb1,
+      0xba, 0xbb, 0xc5, 0xc6, 0xc9, 0xca, 0xde, 0xe4, 0xe5, 0xff, 0x00, 0x04,
+      0x11, 0x12, 0x29, 0x31, 0x34, 0x37, 0x3a, 0x3b, 0x3d, 0x49, 0x4a, 0x5d,
+      0x84, 0x8e, 0x92, 0xa9, 0xb1, 0xb4, 0xba, 0xbb, 0xc6, 0xca, 0xce, 0xcf,
+      0xe4, 0xe5, 0x00, 0x04, 0x0d, 0x0e, 0x11, 0x12, 0x29, 0x31, 0x34, 0x3a,
+      0x3b, 0x45, 0x46, 0x49, 0x4a, 0x5e, 0x64, 0x65, 0x84, 0x91, 0x9b, 0x9d,
+      0xc9, 0xce, 0xcf, 0x0d, 0x11, 0x29, 0x45, 0x49, 0x57, 0x64, 0x65, 0x8d,
+      0x91, 0xa9, 0xb4, 0xba, 0xbb, 0xc5, 0xc9, 0xdf, 0xe4, 0xe5, 0xf0, 0x0d,
+      0x11, 0x45, 0x49, 0x64, 0x65, 0x80, 0x84, 0xb2, 0xbc, 0xbe, 0xbf, 0xd5,
+      0xd7, 0xf0, 0xf1, 0x83, 0x85, 0x8b, 0xa4, 0xa6, 0xbe, 0xbf, 0xc5, 0xc7,
+      0xce, 0xcf, 0xda, 0xdb, 0x48, 0x98, 0xbd, 0xcd, 0xc6, 0xce, 0xcf, 0x49,
+      0x4e, 0x4f, 0x57, 0x59, 0x5e, 0x5f, 0x89, 0x8e, 0x8f, 0xb1, 0xb6, 0xb7,
+      0xbf, 0xc1, 0xc6, 0xc7, 0xd7, 0x11, 0x16, 0x17, 0x5b, 0x5c, 0xf6, 0xf7,
+      0xfe, 0xff, 0x80, 0x0d, 0x6d, 0x71, 0xde, 0xdf, 0x0e, 0x0f, 0x1f, 0x6e,
+      0x6f, 0x1c, 0x1d, 0x5f, 0x7d, 0x7e, 0xae, 0xaf, 0xbb, 0xbc, 0xfa, 0x16,
+      0x17, 0x1e, 0x1f, 0x46, 0x47, 0x4e, 0x4f, 0x58, 0x5a, 0x5c, 0x5e, 0x7e,
+      0x7f, 0xb5, 0xc5, 0xd4, 0xd5, 0xdc, 0xf0, 0xf1, 0xf5, 0x72, 0x73, 0x8f,
+      0x74, 0x75, 0x96, 0x2f, 0x5f, 0x26, 0x2e, 0x2f, 0xa7, 0xaf, 0xb7, 0xbf,
+      0xc7, 0xcf, 0xd7, 0xdf, 0x9a, 0x40, 0x97, 0x98, 0x30, 0x8f, 0x1f, 0xc0,
+      0xc1, 0xce, 0xff, 0x4e, 0x4f, 0x5a, 0x5b, 0x07, 0x08, 0x0f, 0x10, 0x27,
+      0x2f, 0xee, 0xef, 0x6e, 0x6f, 0x37, 0x3d, 0x3f, 0x42, 0x45, 0x90, 0x91,
+      0xfe, 0xff, 0x53, 0x67, 0x75, 0xc8, 0xc9, 0xd0, 0xd1, 0xd8, 0xd9, 0xe7,
+      0xfe, 0xff,
+  };
+  static constexpr singleton singletons1[] = {
+      {0x00, 6},  {0x01, 1}, {0x03, 1},  {0x04, 2}, {0x08, 8},  {0x09, 2},
+      {0x0a, 5},  {0x0b, 2}, {0x0e, 4},  {0x10, 1}, {0x11, 2},  {0x12, 5},
+      {0x13, 17}, {0x14, 1}, {0x15, 2},  {0x17, 2}, {0x19, 13}, {0x1c, 5},
+      {0x1d, 8},  {0x24, 1}, {0x6a, 3},  {0x6b, 2}, {0xbc, 2},  {0xd1, 2},
+      {0xd4, 12}, {0xd5, 9}, {0xd6, 2},  {0xd7, 2}, {0xda, 1},  {0xe0, 5},
+      {0xe1, 2},  {0xe8, 2}, {0xee, 32}, {0xf0, 4}, {0xf8, 2},  {0xf9, 2},
+      {0xfa, 2},  {0xfb, 1},
+  };
+  static constexpr unsigned char singletons1_lower[] = {
+      0x0c, 0x27, 0x3b, 0x3e, 0x4e, 0x4f, 0x8f, 0x9e, 0x9e, 0x9f, 0x06, 0x07,
+      0x09, 0x36, 0x3d, 0x3e, 0x56, 0xf3, 0xd0, 0xd1, 0x04, 0x14, 0x18, 0x36,
+      0x37, 0x56, 0x57, 0x7f, 0xaa, 0xae, 0xaf, 0xbd, 0x35, 0xe0, 0x12, 0x87,
+      0x89, 0x8e, 0x9e, 0x04, 0x0d, 0x0e, 0x11, 0x12, 0x29, 0x31, 0x34, 0x3a,
+      0x45, 0x46, 0x49, 0x4a, 0x4e, 0x4f, 0x64, 0x65, 0x5c, 0xb6, 0xb7, 0x1b,
+      0x1c, 0x07, 0x08, 0x0a, 0x0b, 0x14, 0x17, 0x36, 0x39, 0x3a, 0xa8, 0xa9,
+      0xd8, 0xd9, 0x09, 0x37, 0x90, 0x91, 0xa8, 0x07, 0x0a, 0x3b, 0x3e, 0x66,
+      0x69, 0x8f, 0x92, 0x6f, 0x5f, 0xee, 0xef, 0x5a, 0x62, 0x9a, 0x9b, 0x27,
+      0x28, 0x55, 0x9d, 0xa0, 0xa1, 0xa3, 0xa4, 0xa7, 0xa8, 0xad, 0xba, 0xbc,
+      0xc4, 0x06, 0x0b, 0x0c, 0x15, 0x1d, 0x3a, 0x3f, 0x45, 0x51, 0xa6, 0xa7,
+      0xcc, 0xcd, 0xa0, 0x07, 0x19, 0x1a, 0x22, 0x25, 0x3e, 0x3f, 0xc5, 0xc6,
+      0x04, 0x20, 0x23, 0x25, 0x26, 0x28, 0x33, 0x38, 0x3a, 0x48, 0x4a, 0x4c,
+      0x50, 0x53, 0x55, 0x56, 0x58, 0x5a, 0x5c, 0x5e, 0x60, 0x63, 0x65, 0x66,
+      0x6b, 0x73, 0x78, 0x7d, 0x7f, 0x8a, 0xa4, 0xaa, 0xaf, 0xb0, 0xc0, 0xd0,
+      0xae, 0xaf, 0x79, 0xcc, 0x6e, 0x6f, 0x93,
+  };
+  static constexpr unsigned char normal0[] = {
+      0x00, 0x20, 0x5f, 0x22, 0x82, 0xdf, 0x04, 0x82, 0x44, 0x08, 0x1b, 0x04,
+      0x06, 0x11, 0x81, 0xac, 0x0e, 0x80, 0xab, 0x35, 0x28, 0x0b, 0x80, 0xe0,
+      0x03, 0x19, 0x08, 0x01, 0x04, 0x2f, 0x04, 0x34, 0x04, 0x07, 0x03, 0x01,
+      0x07, 0x06, 0x07, 0x11, 0x0a, 0x50, 0x0f, 0x12, 0x07, 0x55, 0x07, 0x03,
+      0x04, 0x1c, 0x0a, 0x09, 0x03, 0x08, 0x03, 0x07, 0x03, 0x02, 0x03, 0x03,
+      0x03, 0x0c, 0x04, 0x05, 0x03, 0x0b, 0x06, 0x01, 0x0e, 0x15, 0x05, 0x3a,
+      0x03, 0x11, 0x07, 0x06, 0x05, 0x10, 0x07, 0x57, 0x07, 0x02, 0x07, 0x15,
+      0x0d, 0x50, 0x04, 0x43, 0x03, 0x2d, 0x03, 0x01, 0x04, 0x11, 0x06, 0x0f,
+      0x0c, 0x3a, 0x04, 0x1d, 0x25, 0x5f, 0x20, 0x6d, 0x04, 0x6a, 0x25, 0x80,
+      0xc8, 0x05, 0x82, 0xb0, 0x03, 0x1a, 0x06, 0x82, 0xfd, 0x03, 0x59, 0x07,
+      0x15, 0x0b, 0x17, 0x09, 0x14, 0x0c, 0x14, 0x0c, 0x6a, 0x06, 0x0a, 0x06,
+      0x1a, 0x06, 0x59, 0x07, 0x2b, 0x05, 0x46, 0x0a, 0x2c, 0x04, 0x0c, 0x04,
+      0x01, 0x03, 0x31, 0x0b, 0x2c, 0x04, 0x1a, 0x06, 0x0b, 0x03, 0x80, 0xac,
+      0x06, 0x0a, 0x06, 0x21, 0x3f, 0x4c, 0x04, 0x2d, 0x03, 0x74, 0x08, 0x3c,
+      0x03, 0x0f, 0x03, 0x3c, 0x07, 0x38, 0x08, 0x2b, 0x05, 0x82, 0xff, 0x11,
+      0x18, 0x08, 0x2f, 0x11, 0x2d, 0x03, 0x20, 0x10, 0x21, 0x0f, 0x80, 0x8c,
+      0x04, 0x82, 0x97, 0x19, 0x0b, 0x15, 0x88, 0x94, 0x05, 0x2f, 0x05, 0x3b,
+      0x07, 0x02, 0x0e, 0x18, 0x09, 0x80, 0xb3, 0x2d, 0x74, 0x0c, 0x80, 0xd6,
+      0x1a, 0x0c, 0x05, 0x80, 0xff, 0x05, 0x80, 0xdf, 0x0c, 0xee, 0x0d, 0x03,
+      0x84, 0x8d, 0x03, 0x37, 0x09, 0x81, 0x5c, 0x14, 0x80, 0xb8, 0x08, 0x80,
+      0xcb, 0x2a, 0x38, 0x03, 0x0a, 0x06, 0x38, 0x08, 0x46, 0x08, 0x0c, 0x06,
+      0x74, 0x0b, 0x1e, 0x03, 0x5a, 0x04, 0x59, 0x09, 0x80, 0x83, 0x18, 0x1c,
+      0x0a, 0x16, 0x09, 0x4c, 0x04, 0x80, 0x8a, 0x06, 0xab, 0xa4, 0x0c, 0x17,
+      0x04, 0x31, 0xa1, 0x04, 0x81, 0xda, 0x26, 0x07, 0x0c, 0x05, 0x05, 0x80,
+      0xa5, 0x11, 0x81, 0x6d, 0x10, 0x78, 0x28, 0x2a, 0x06, 0x4c, 0x04, 0x80,
+      0x8d, 0x04, 0x80, 0xbe, 0x03, 0x1b, 0x03, 0x0f, 0x0d,
+  };
+  static constexpr unsigned char normal1[] = {
+      0x5e, 0x22, 0x7b, 0x05, 0x03, 0x04, 0x2d, 0x03, 0x66, 0x03, 0x01, 0x2f,
+      0x2e, 0x80, 0x82, 0x1d, 0x03, 0x31, 0x0f, 0x1c, 0x04, 0x24, 0x09, 0x1e,
+      0x05, 0x2b, 0x05, 0x44, 0x04, 0x0e, 0x2a, 0x80, 0xaa, 0x06, 0x24, 0x04,
+      0x24, 0x04, 0x28, 0x08, 0x34, 0x0b, 0x01, 0x80, 0x90, 0x81, 0x37, 0x09,
+      0x16, 0x0a, 0x08, 0x80, 0x98, 0x39, 0x03, 0x63, 0x08, 0x09, 0x30, 0x16,
+      0x05, 0x21, 0x03, 0x1b, 0x05, 0x01, 0x40, 0x38, 0x04, 0x4b, 0x05, 0x2f,
+      0x04, 0x0a, 0x07, 0x09, 0x07, 0x40, 0x20, 0x27, 0x04, 0x0c, 0x09, 0x36,
+      0x03, 0x3a, 0x05, 0x1a, 0x07, 0x04, 0x0c, 0x07, 0x50, 0x49, 0x37, 0x33,
+      0x0d, 0x33, 0x07, 0x2e, 0x08, 0x0a, 0x81, 0x26, 0x52, 0x4e, 0x28, 0x08,
+      0x2a, 0x56, 0x1c, 0x14, 0x17, 0x09, 0x4e, 0x04, 0x1e, 0x0f, 0x43, 0x0e,
+      0x19, 0x07, 0x0a, 0x06, 0x48, 0x08, 0x27, 0x09, 0x75, 0x0b, 0x3f, 0x41,
+      0x2a, 0x06, 0x3b, 0x05, 0x0a, 0x06, 0x51, 0x06, 0x01, 0x05, 0x10, 0x03,
+      0x05, 0x80, 0x8b, 0x62, 0x1e, 0x48, 0x08, 0x0a, 0x80, 0xa6, 0x5e, 0x22,
+      0x45, 0x0b, 0x0a, 0x06, 0x0d, 0x13, 0x39, 0x07, 0x0a, 0x36, 0x2c, 0x04,
+      0x10, 0x80, 0xc0, 0x3c, 0x64, 0x53, 0x0c, 0x48, 0x09, 0x0a, 0x46, 0x45,
+      0x1b, 0x48, 0x08, 0x53, 0x1d, 0x39, 0x81, 0x07, 0x46, 0x0a, 0x1d, 0x03,
+      0x47, 0x49, 0x37, 0x03, 0x0e, 0x08, 0x0a, 0x06, 0x39, 0x07, 0x0a, 0x81,
+      0x36, 0x19, 0x80, 0xb7, 0x01, 0x0f, 0x32, 0x0d, 0x83, 0x9b, 0x66, 0x75,
+      0x0b, 0x80, 0xc4, 0x8a, 0xbc, 0x84, 0x2f, 0x8f, 0xd1, 0x82, 0x47, 0xa1,
+      0xb9, 0x82, 0x39, 0x07, 0x2a, 0x04, 0x02, 0x60, 0x26, 0x0a, 0x46, 0x0a,
+      0x28, 0x05, 0x13, 0x82, 0xb0, 0x5b, 0x65, 0x4b, 0x04, 0x39, 0x07, 0x11,
+      0x40, 0x05, 0x0b, 0x02, 0x0e, 0x97, 0xf8, 0x08, 0x84, 0xd6, 0x2a, 0x09,
+      0xa2, 0xf7, 0x81, 0x1f, 0x31, 0x03, 0x11, 0x04, 0x08, 0x81, 0x8c, 0x89,
+      0x04, 0x6b, 0x05, 0x0d, 0x03, 0x09, 0x07, 0x10, 0x93, 0x60, 0x80, 0xf6,
+      0x0a, 0x73, 0x08, 0x6e, 0x17, 0x46, 0x80, 0x9a, 0x14, 0x0c, 0x57, 0x09,
+      0x19, 0x80, 0x87, 0x81, 0x47, 0x03, 0x85, 0x42, 0x0f, 0x15, 0x85, 0x50,
+      0x2b, 0x80, 0xd5, 0x2d, 0x03, 0x1a, 0x04, 0x02, 0x81, 0x70, 0x3a, 0x05,
+      0x01, 0x85, 0x00, 0x80, 0xd7, 0x29, 0x4c, 0x04, 0x0a, 0x04, 0x02, 0x83,
+      0x11, 0x44, 0x4c, 0x3d, 0x80, 0xc2, 0x3c, 0x06, 0x01, 0x04, 0x55, 0x05,
+      0x1b, 0x34, 0x02, 0x81, 0x0e, 0x2c, 0x04, 0x64, 0x0c, 0x56, 0x0a, 0x80,
+      0xae, 0x38, 0x1d, 0x0d, 0x2c, 0x04, 0x09, 0x07, 0x02, 0x0e, 0x06, 0x80,
+      0x9a, 0x83, 0xd8, 0x08, 0x0d, 0x03, 0x0d, 0x03, 0x74, 0x0c, 0x59, 0x07,
+      0x0c, 0x14, 0x0c, 0x04, 0x38, 0x08, 0x0a, 0x06, 0x28, 0x08, 0x22, 0x4e,
+      0x81, 0x54, 0x0c, 0x15, 0x03, 0x03, 0x05, 0x07, 0x09, 0x19, 0x07, 0x07,
+      0x09, 0x03, 0x0d, 0x07, 0x29, 0x80, 0xcb, 0x25, 0x0a, 0x84, 0x06,
+  };
+  auto lower = static_cast<uint16_t>(cp);
+  if (cp < 0x10000) {
+    return is_printable(lower, singletons0,
+                        sizeof(singletons0) / sizeof(*singletons0),
+                        singletons0_lower, normal0, sizeof(normal0));
+  }
+  if (cp < 0x20000) {
+    return is_printable(lower, singletons1,
+                        sizeof(singletons1) / sizeof(*singletons1),
+                        singletons1_lower, normal1, sizeof(normal1));
+  }
+  if (0x2a6de <= cp && cp < 0x2a700) return false;
+  if (0x2b735 <= cp && cp < 0x2b740) return false;
+  if (0x2b81e <= cp && cp < 0x2b820) return false;
+  if (0x2cea2 <= cp && cp < 0x2ceb0) return false;
+  if (0x2ebe1 <= cp && cp < 0x2f800) return false;
+  if (0x2fa1e <= cp && cp < 0x30000) return false;
+  if (0x3134b <= cp && cp < 0xe0100) return false;
+  if (0xe01f0 <= cp && cp < 0x110000) return false;
+  return cp < 0x110000;
+}
+
+}  // namespace detail
+
+FMT_END_NAMESPACE
+
+#endif  // FMT_FORMAT_INL_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/format.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/format.h
new file mode 100644
index 0000000..7c607db
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/format.h
@@ -0,0 +1,4217 @@
+/*
+  Formatting library for C++
+
+  Copyright (c) 2012 - present, Victor Zverovich
+
+  Permission is hereby granted, free of charge, to any person obtaining
+  a copy of this software and associated documentation files (the
+  "Software"), to deal in the Software without restriction, including
+  without limitation the rights to use, copy, modify, merge, publish,
+  distribute, sublicense, and/or sell copies of the Software, and to
+  permit persons to whom the Software is furnished to do so, subject to
+  the following conditions:
+
+  The above copyright notice and this permission notice shall be
+  included in all copies or substantial portions of the Software.
+
+  THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
+  EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
+  MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
+  NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE
+  LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION
+  OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION
+  WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
+
+  --- Optional exception to the license ---
+
+  As an exception, if, as a result of your compiling your source code, portions
+  of this Software are embedded into a machine-executable object form of such
+  source code, you may redistribute such embedded portions in such object form
+  without including the above copyright and permission notices.
+ */
+
+#ifndef FMT_FORMAT_H_
+#define FMT_FORMAT_H_
+
+#include <cmath>         // std::signbit
+#include <cstdint>       // uint32_t
+#include <cstring>       // std::memcpy
+#include <limits>        // std::numeric_limits
+#include <memory>        // std::uninitialized_copy
+#include <stdexcept>     // std::runtime_error
+#include <system_error>  // std::system_error
+
+#ifdef __cpp_lib_bit_cast
+#  include <bit>  // std::bitcast
+#endif
+
+#include "core.h"
+
+#if FMT_GCC_VERSION
+#  define FMT_GCC_VISIBILITY_HIDDEN __attribute__((visibility("hidden")))
+#else
+#  define FMT_GCC_VISIBILITY_HIDDEN
+#endif
+
+#ifdef __NVCC__
+#  define FMT_CUDA_VERSION (__CUDACC_VER_MAJOR__ * 100 + __CUDACC_VER_MINOR__)
+#else
+#  define FMT_CUDA_VERSION 0
+#endif
+
+#ifdef __has_builtin
+#  define FMT_HAS_BUILTIN(x) __has_builtin(x)
+#else
+#  define FMT_HAS_BUILTIN(x) 0
+#endif
+
+#if FMT_GCC_VERSION || FMT_CLANG_VERSION
+#  define FMT_NOINLINE __attribute__((noinline))
+#else
+#  define FMT_NOINLINE
+#endif
+
+#if FMT_MSC_VERSION
+#  define FMT_MSC_DEFAULT = default
+#else
+#  define FMT_MSC_DEFAULT
+#endif
+
+#ifndef FMT_THROW
+#  if FMT_EXCEPTIONS
+#    if FMT_MSC_VERSION || defined(__NVCC__)
+FMT_BEGIN_NAMESPACE
+namespace detail {
+template <typename Exception> inline void do_throw(const Exception& x) {
+  // Silence unreachable code warnings in MSVC and NVCC because these
+  // are nearly impossible to fix in a generic code.
+  volatile bool b = true;
+  if (b) throw x;
+}
+}  // namespace detail
+FMT_END_NAMESPACE
+#      define FMT_THROW(x) detail::do_throw(x)
+#    else
+#      define FMT_THROW(x) throw x
+#    endif
+#  else
+#    define FMT_THROW(x)               \
+      do {                             \
+        FMT_ASSERT(false, (x).what()); \
+      } while (false)
+#  endif
+#endif
+
+#if FMT_EXCEPTIONS
+#  define FMT_TRY try
+#  define FMT_CATCH(x) catch (x)
+#else
+#  define FMT_TRY if (true)
+#  define FMT_CATCH(x) if (false)
+#endif
+
+#ifndef FMT_MAYBE_UNUSED
+#  if FMT_HAS_CPP17_ATTRIBUTE(maybe_unused)
+#    define FMT_MAYBE_UNUSED [[maybe_unused]]
+#  else
+#    define FMT_MAYBE_UNUSED
+#  endif
+#endif
+
+#ifndef FMT_USE_USER_DEFINED_LITERALS
+// EDG based compilers (Intel, NVIDIA, Elbrus, etc), GCC and MSVC support UDLs.
+#  if (FMT_HAS_FEATURE(cxx_user_literals) || FMT_GCC_VERSION >= 407 || \
+       FMT_MSC_VERSION >= 1900) &&                                     \
+      (!defined(__EDG_VERSION__) || __EDG_VERSION__ >= /* UDL feature */ 480)
+#    define FMT_USE_USER_DEFINED_LITERALS 1
+#  else
+#    define FMT_USE_USER_DEFINED_LITERALS 0
+#  endif
+#endif
+
+// Defining FMT_REDUCE_INT_INSTANTIATIONS to 1, will reduce the number of
+// integer formatter template instantiations to just one by only using the
+// largest integer type. This results in a reduction in binary size but will
+// cause a decrease in integer formatting performance.
+#if !defined(FMT_REDUCE_INT_INSTANTIATIONS)
+#  define FMT_REDUCE_INT_INSTANTIATIONS 0
+#endif
+
+// __builtin_clz is broken in clang with Microsoft CodeGen:
+// https://github.com/fmtlib/fmt/issues/519.
+#if !FMT_MSC_VERSION
+#  if FMT_HAS_BUILTIN(__builtin_clz) || FMT_GCC_VERSION || FMT_ICC_VERSION
+#    define FMT_BUILTIN_CLZ(n) __builtin_clz(n)
+#  endif
+#  if FMT_HAS_BUILTIN(__builtin_clzll) || FMT_GCC_VERSION || FMT_ICC_VERSION
+#    define FMT_BUILTIN_CLZLL(n) __builtin_clzll(n)
+#  endif
+#endif
+
+// __builtin_ctz is broken in Intel Compiler Classic on Windows:
+// https://github.com/fmtlib/fmt/issues/2510.
+#ifndef __ICL
+#  if FMT_HAS_BUILTIN(__builtin_ctz) || FMT_GCC_VERSION || FMT_ICC_VERSION || \
+      defined(__NVCOMPILER)
+#    define FMT_BUILTIN_CTZ(n) __builtin_ctz(n)
+#  endif
+#  if FMT_HAS_BUILTIN(__builtin_ctzll) || FMT_GCC_VERSION || \
+      FMT_ICC_VERSION || defined(__NVCOMPILER)
+#    define FMT_BUILTIN_CTZLL(n) __builtin_ctzll(n)
+#  endif
+#endif
+
+#if FMT_MSC_VERSION
+#  include <intrin.h>  // _BitScanReverse[64], _BitScanForward[64], _umul128
+#endif
+
+// Some compilers masquerade as both MSVC and GCC-likes or otherwise support
+// __builtin_clz and __builtin_clzll, so only define FMT_BUILTIN_CLZ using the
+// MSVC intrinsics if the clz and clzll builtins are not available.
+#if FMT_MSC_VERSION && !defined(FMT_BUILTIN_CLZLL) && \
+    !defined(FMT_BUILTIN_CTZLL)
+FMT_BEGIN_NAMESPACE
+namespace detail {
+// Avoid Clang with Microsoft CodeGen's -Wunknown-pragmas warning.
+#  if !defined(__clang__)
+#    pragma intrinsic(_BitScanForward)
+#    pragma intrinsic(_BitScanReverse)
+#    if defined(_WIN64)
+#      pragma intrinsic(_BitScanForward64)
+#      pragma intrinsic(_BitScanReverse64)
+#    endif
+#  endif
+
+inline auto clz(uint32_t x) -> int {
+  unsigned long r = 0;
+  _BitScanReverse(&r, x);
+  FMT_ASSERT(x != 0, "");
+  // Static analysis complains about using uninitialized data
+  // "r", but the only way that can happen is if "x" is 0,
+  // which the callers guarantee to not happen.
+  FMT_MSC_WARNING(suppress : 6102)
+  return 31 ^ static_cast<int>(r);
+}
+#  define FMT_BUILTIN_CLZ(n) detail::clz(n)
+
+inline auto clzll(uint64_t x) -> int {
+  unsigned long r = 0;
+#  ifdef _WIN64
+  _BitScanReverse64(&r, x);
+#  else
+  // Scan the high 32 bits.
+  if (_BitScanReverse(&r, static_cast<uint32_t>(x >> 32))) return 63 ^ (r + 32);
+  // Scan the low 32 bits.
+  _BitScanReverse(&r, static_cast<uint32_t>(x));
+#  endif
+  FMT_ASSERT(x != 0, "");
+  FMT_MSC_WARNING(suppress : 6102)  // Suppress a bogus static analysis warning.
+  return 63 ^ static_cast<int>(r);
+}
+#  define FMT_BUILTIN_CLZLL(n) detail::clzll(n)
+
+inline auto ctz(uint32_t x) -> int {
+  unsigned long r = 0;
+  _BitScanForward(&r, x);
+  FMT_ASSERT(x != 0, "");
+  FMT_MSC_WARNING(suppress : 6102)  // Suppress a bogus static analysis warning.
+  return static_cast<int>(r);
+}
+#  define FMT_BUILTIN_CTZ(n) detail::ctz(n)
+
+inline auto ctzll(uint64_t x) -> int {
+  unsigned long r = 0;
+  FMT_ASSERT(x != 0, "");
+  FMT_MSC_WARNING(suppress : 6102)  // Suppress a bogus static analysis warning.
+#  ifdef _WIN64
+  _BitScanForward64(&r, x);
+#  else
+  // Scan the low 32 bits.
+  if (_BitScanForward(&r, static_cast<uint32_t>(x))) return static_cast<int>(r);
+  // Scan the high 32 bits.
+  _BitScanForward(&r, static_cast<uint32_t>(x >> 32));
+  r += 32;
+#  endif
+  return static_cast<int>(r);
+}
+#  define FMT_BUILTIN_CTZLL(n) detail::ctzll(n)
+}  // namespace detail
+FMT_END_NAMESPACE
+#endif
+
+FMT_BEGIN_NAMESPACE
+namespace detail {
+
+FMT_CONSTEXPR inline void abort_fuzzing_if(bool condition) {
+  ignore_unused(condition);
+#ifdef FMT_FUZZ
+  if (condition) throw std::runtime_error("fuzzing limit reached");
+#endif
+}
+
+template <typename CharT, CharT... C> struct string_literal {
+  static constexpr CharT value[sizeof...(C)] = {C...};
+  constexpr operator basic_string_view<CharT>() const {
+    return {value, sizeof...(C)};
+  }
+};
+
+#if FMT_CPLUSPLUS < 201703L
+template <typename CharT, CharT... C>
+constexpr CharT string_literal<CharT, C...>::value[sizeof...(C)];
+#endif
+
+template <typename Streambuf> class formatbuf : public Streambuf {
+ private:
+  using char_type = typename Streambuf::char_type;
+  using streamsize = decltype(std::declval<Streambuf>().sputn(nullptr, 0));
+  using int_type = typename Streambuf::int_type;
+  using traits_type = typename Streambuf::traits_type;
+
+  buffer<char_type>& buffer_;
+
+ public:
+  explicit formatbuf(buffer<char_type>& buf) : buffer_(buf) {}
+
+ protected:
+  // The put area is always empty. This makes the implementation simpler and has
+  // the advantage that the streambuf and the buffer are always in sync and
+  // sputc never writes into uninitialized memory. A disadvantage is that each
+  // call to sputc always results in a (virtual) call to overflow. There is no
+  // disadvantage here for sputn since this always results in a call to xsputn.
+
+  auto overflow(int_type ch) -> int_type override {
+    if (!traits_type::eq_int_type(ch, traits_type::eof()))
+      buffer_.push_back(static_cast<char_type>(ch));
+    return ch;
+  }
+
+  auto xsputn(const char_type* s, streamsize count) -> streamsize override {
+    buffer_.append(s, s + count);
+    return count;
+  }
+};
+
+// Implementation of std::bit_cast for pre-C++20.
+template <typename To, typename From, FMT_ENABLE_IF(sizeof(To) == sizeof(From))>
+FMT_CONSTEXPR20 auto bit_cast(const From& from) -> To {
+#ifdef __cpp_lib_bit_cast
+  if (is_constant_evaluated()) return std::bit_cast<To>(from);
+#endif
+  auto to = To();
+  // The cast suppresses a bogus -Wclass-memaccess on GCC.
+  std::memcpy(static_cast<void*>(&to), &from, sizeof(to));
+  return to;
+}
+
+inline auto is_big_endian() -> bool {
+#ifdef _WIN32
+  return false;
+#elif defined(__BIG_ENDIAN__)
+  return true;
+#elif defined(__BYTE_ORDER__) && defined(__ORDER_BIG_ENDIAN__)
+  return __BYTE_ORDER__ == __ORDER_BIG_ENDIAN__;
+#else
+  struct bytes {
+    char data[sizeof(int)];
+  };
+  return bit_cast<bytes>(1).data[0] == 0;
+#endif
+}
+
+class uint128_fallback {
+ private:
+  uint64_t lo_, hi_;
+
+  friend uint128_fallback umul128(uint64_t x, uint64_t y) noexcept;
+
+ public:
+  constexpr uint128_fallback(uint64_t hi, uint64_t lo) : lo_(lo), hi_(hi) {}
+  constexpr uint128_fallback(uint64_t value = 0) : lo_(value), hi_(0) {}
+
+  constexpr uint64_t high() const noexcept { return hi_; }
+  constexpr uint64_t low() const noexcept { return lo_; }
+
+  template <typename T, FMT_ENABLE_IF(std::is_integral<T>::value)>
+  constexpr explicit operator T() const {
+    return static_cast<T>(lo_);
+  }
+
+  friend constexpr auto operator==(const uint128_fallback& lhs,
+                                   const uint128_fallback& rhs) -> bool {
+    return lhs.hi_ == rhs.hi_ && lhs.lo_ == rhs.lo_;
+  }
+  friend constexpr auto operator!=(const uint128_fallback& lhs,
+                                   const uint128_fallback& rhs) -> bool {
+    return !(lhs == rhs);
+  }
+  friend constexpr auto operator>(const uint128_fallback& lhs,
+                                  const uint128_fallback& rhs) -> bool {
+    return lhs.hi_ != rhs.hi_ ? lhs.hi_ > rhs.hi_ : lhs.lo_ > rhs.lo_;
+  }
+  friend constexpr auto operator|(const uint128_fallback& lhs,
+                                  const uint128_fallback& rhs)
+      -> uint128_fallback {
+    return {lhs.hi_ | rhs.hi_, lhs.lo_ | rhs.lo_};
+  }
+  friend constexpr auto operator&(const uint128_fallback& lhs,
+                                  const uint128_fallback& rhs)
+      -> uint128_fallback {
+    return {lhs.hi_ & rhs.hi_, lhs.lo_ & rhs.lo_};
+  }
+  friend auto operator+(const uint128_fallback& lhs,
+                        const uint128_fallback& rhs) -> uint128_fallback {
+    auto result = uint128_fallback(lhs);
+    result += rhs;
+    return result;
+  }
+  friend auto operator*(const uint128_fallback& lhs, uint32_t rhs)
+      -> uint128_fallback {
+    FMT_ASSERT(lhs.hi_ == 0, "");
+    uint64_t hi = (lhs.lo_ >> 32) * rhs;
+    uint64_t lo = (lhs.lo_ & ~uint32_t()) * rhs;
+    uint64_t new_lo = (hi << 32) + lo;
+    return {(hi >> 32) + (new_lo < lo ? 1 : 0), new_lo};
+  }
+  friend auto operator-(const uint128_fallback& lhs, uint64_t rhs)
+      -> uint128_fallback {
+    return {lhs.hi_ - (lhs.lo_ < rhs ? 1 : 0), lhs.lo_ - rhs};
+  }
+  FMT_CONSTEXPR auto operator>>(int shift) const -> uint128_fallback {
+    if (shift == 64) return {0, hi_};
+    if (shift > 64) return uint128_fallback(0, hi_) >> (shift - 64);
+    return {hi_ >> shift, (hi_ << (64 - shift)) | (lo_ >> shift)};
+  }
+  FMT_CONSTEXPR auto operator<<(int shift) const -> uint128_fallback {
+    if (shift == 64) return {lo_, 0};
+    if (shift > 64) return uint128_fallback(lo_, 0) << (shift - 64);
+    return {hi_ << shift | (lo_ >> (64 - shift)), (lo_ << shift)};
+  }
+  FMT_CONSTEXPR auto operator>>=(int shift) -> uint128_fallback& {
+    return *this = *this >> shift;
+  }
+  FMT_CONSTEXPR void operator+=(uint128_fallback n) {
+    uint64_t new_lo = lo_ + n.lo_;
+    uint64_t new_hi = hi_ + n.hi_ + (new_lo < lo_ ? 1 : 0);
+    FMT_ASSERT(new_hi >= hi_, "");
+    lo_ = new_lo;
+    hi_ = new_hi;
+  }
+
+  FMT_CONSTEXPR20 uint128_fallback& operator+=(uint64_t n) noexcept {
+    if (is_constant_evaluated()) {
+      lo_ += n;
+      hi_ += (lo_ < n ? 1 : 0);
+      return *this;
+    }
+#if FMT_HAS_BUILTIN(__builtin_addcll) && !defined(__ibmxl__)
+    unsigned long long carry;
+    lo_ = __builtin_addcll(lo_, n, 0, &carry);
+    hi_ += carry;
+#elif FMT_HAS_BUILTIN(__builtin_ia32_addcarryx_u64) && !defined(__ibmxl__)
+    unsigned long long result;
+    auto carry = __builtin_ia32_addcarryx_u64(0, lo_, n, &result);
+    lo_ = result;
+    hi_ += carry;
+#elif defined(_MSC_VER) && defined(_M_X64)
+    auto carry = _addcarry_u64(0, lo_, n, &lo_);
+    _addcarry_u64(carry, hi_, 0, &hi_);
+#else
+    lo_ += n;
+    hi_ += (lo_ < n ? 1 : 0);
+#endif
+    return *this;
+  }
+};
+
+using uint128_t = conditional_t<FMT_USE_INT128, uint128_opt, uint128_fallback>;
+
+#ifdef UINTPTR_MAX
+using uintptr_t = ::uintptr_t;
+#else
+using uintptr_t = uint128_t;
+#endif
+
+// Returns the largest possible value for type T. Same as
+// std::numeric_limits<T>::max() but shorter and not affected by the max macro.
+template <typename T> constexpr auto max_value() -> T {
+  return (std::numeric_limits<T>::max)();
+}
+template <typename T> constexpr auto num_bits() -> int {
+  return std::numeric_limits<T>::digits;
+}
+// std::numeric_limits<T>::digits may return 0 for 128-bit ints.
+template <> constexpr auto num_bits<int128_opt>() -> int { return 128; }
+template <> constexpr auto num_bits<uint128_t>() -> int { return 128; }
+
+// A heterogeneous bit_cast used for converting 96-bit long double to uint128_t
+// and 128-bit pointers to uint128_fallback.
+template <typename To, typename From, FMT_ENABLE_IF(sizeof(To) > sizeof(From))>
+inline auto bit_cast(const From& from) -> To {
+  constexpr auto size = static_cast<int>(sizeof(From) / sizeof(unsigned));
+  struct data_t {
+    unsigned value[static_cast<unsigned>(size)];
+  } data = bit_cast<data_t>(from);
+  auto result = To();
+  if (const_check(is_big_endian())) {
+    for (int i = 0; i < size; ++i)
+      result = (result << num_bits<unsigned>()) | data.value[i];
+  } else {
+    for (int i = size - 1; i >= 0; --i)
+      result = (result << num_bits<unsigned>()) | data.value[i];
+  }
+  return result;
+}
+
+FMT_INLINE void assume(bool condition) {
+  (void)condition;
+#if FMT_HAS_BUILTIN(__builtin_assume) && !FMT_ICC_VERSION
+  __builtin_assume(condition);
+#endif
+}
+
+// An approximation of iterator_t for pre-C++20 systems.
+template <typename T>
+using iterator_t = decltype(std::begin(std::declval<T&>()));
+template <typename T> using sentinel_t = decltype(std::end(std::declval<T&>()));
+
+// A workaround for std::string not having mutable data() until C++17.
+template <typename Char>
+inline auto get_data(std::basic_string<Char>& s) -> Char* {
+  return &s[0];
+}
+template <typename Container>
+inline auto get_data(Container& c) -> typename Container::value_type* {
+  return c.data();
+}
+
+#if defined(_SECURE_SCL) && _SECURE_SCL
+// Make a checked iterator to avoid MSVC warnings.
+template <typename T> using checked_ptr = stdext::checked_array_iterator<T*>;
+template <typename T>
+constexpr auto make_checked(T* p, size_t size) -> checked_ptr<T> {
+  return {p, size};
+}
+#else
+template <typename T> using checked_ptr = T*;
+template <typename T> constexpr auto make_checked(T* p, size_t) -> T* {
+  return p;
+}
+#endif
+
+// Attempts to reserve space for n extra characters in the output range.
+// Returns a pointer to the reserved range or a reference to it.
+template <typename Container, FMT_ENABLE_IF(is_contiguous<Container>::value)>
+#if FMT_CLANG_VERSION >= 307 && !FMT_ICC_VERSION
+__attribute__((no_sanitize("undefined")))
+#endif
+inline auto
+reserve(std::back_insert_iterator<Container> it, size_t n)
+    -> checked_ptr<typename Container::value_type> {
+  Container& c = get_container(it);
+  size_t size = c.size();
+  c.resize(size + n);
+  return make_checked(get_data(c) + size, n);
+}
+
+template <typename T>
+inline auto reserve(buffer_appender<T> it, size_t n) -> buffer_appender<T> {
+  buffer<T>& buf = get_container(it);
+  buf.try_reserve(buf.size() + n);
+  return it;
+}
+
+template <typename Iterator>
+constexpr auto reserve(Iterator& it, size_t) -> Iterator& {
+  return it;
+}
+
+template <typename OutputIt>
+using reserve_iterator =
+    remove_reference_t<decltype(reserve(std::declval<OutputIt&>(), 0))>;
+
+template <typename T, typename OutputIt>
+constexpr auto to_pointer(OutputIt, size_t) -> T* {
+  return nullptr;
+}
+template <typename T> auto to_pointer(buffer_appender<T> it, size_t n) -> T* {
+  buffer<T>& buf = get_container(it);
+  auto size = buf.size();
+  if (buf.capacity() < size + n) return nullptr;
+  buf.try_resize(size + n);
+  return buf.data() + size;
+}
+
+template <typename Container, FMT_ENABLE_IF(is_contiguous<Container>::value)>
+inline auto base_iterator(std::back_insert_iterator<Container>& it,
+                          checked_ptr<typename Container::value_type>)
+    -> std::back_insert_iterator<Container> {
+  return it;
+}
+
+template <typename Iterator>
+constexpr auto base_iterator(Iterator, Iterator it) -> Iterator {
+  return it;
+}
+
+// <algorithm> is spectacularly slow to compile in C++20 so use a simple fill_n
+// instead (#1998).
+template <typename OutputIt, typename Size, typename T>
+FMT_CONSTEXPR auto fill_n(OutputIt out, Size count, const T& value)
+    -> OutputIt {
+  for (Size i = 0; i < count; ++i) *out++ = value;
+  return out;
+}
+template <typename T, typename Size>
+FMT_CONSTEXPR20 auto fill_n(T* out, Size count, char value) -> T* {
+  if (is_constant_evaluated()) {
+    return fill_n<T*, Size, T>(out, count, value);
+  }
+  std::memset(out, value, to_unsigned(count));
+  return out + count;
+}
+
+#ifdef __cpp_char8_t
+using char8_type = char8_t;
+#else
+enum char8_type : unsigned char {};
+#endif
+
+template <typename OutChar, typename InputIt, typename OutputIt>
+FMT_CONSTEXPR FMT_NOINLINE auto copy_str_noinline(InputIt begin, InputIt end,
+                                                  OutputIt out) -> OutputIt {
+  return copy_str<OutChar>(begin, end, out);
+}
+
+// A public domain branchless UTF-8 decoder by Christopher Wellons:
+// https://github.com/skeeto/branchless-utf8
+/* Decode the next character, c, from s, reporting errors in e.
+ *
+ * Since this is a branchless decoder, four bytes will be read from the
+ * buffer regardless of the actual length of the next character. This
+ * means the buffer _must_ have at least three bytes of zero padding
+ * following the end of the data stream.
+ *
+ * Errors are reported in e, which will be non-zero if the parsed
+ * character was somehow invalid: invalid byte sequence, non-canonical
+ * encoding, or a surrogate half.
+ *
+ * The function returns a pointer to the next character. When an error
+ * occurs, this pointer will be a guess that depends on the particular
+ * error, but it will always advance at least one byte.
+ */
+FMT_CONSTEXPR inline auto utf8_decode(const char* s, uint32_t* c, int* e)
+    -> const char* {
+  constexpr const int masks[] = {0x00, 0x7f, 0x1f, 0x0f, 0x07};
+  constexpr const uint32_t mins[] = {4194304, 0, 128, 2048, 65536};
+  constexpr const int shiftc[] = {0, 18, 12, 6, 0};
+  constexpr const int shifte[] = {0, 6, 4, 2, 0};
+
+  int len = code_point_length_impl(*s);
+  // Compute the pointer to the next character early so that the next
+  // iteration can start working on the next character. Neither Clang
+  // nor GCC figure out this reordering on their own.
+  const char* next = s + len + !len;
+
+  using uchar = unsigned char;
+
+  // Assume a four-byte character and load four bytes. Unused bits are
+  // shifted out.
+  *c = uint32_t(uchar(s[0]) & masks[len]) << 18;
+  *c |= uint32_t(uchar(s[1]) & 0x3f) << 12;
+  *c |= uint32_t(uchar(s[2]) & 0x3f) << 6;
+  *c |= uint32_t(uchar(s[3]) & 0x3f) << 0;
+  *c >>= shiftc[len];
+
+  // Accumulate the various error conditions.
+  *e = (*c < mins[len]) << 6;       // non-canonical encoding
+  *e |= ((*c >> 11) == 0x1b) << 7;  // surrogate half?
+  *e |= (*c > 0x10FFFF) << 8;       // out of range?
+  *e |= (uchar(s[1]) & 0xc0) >> 2;
+  *e |= (uchar(s[2]) & 0xc0) >> 4;
+  *e |= uchar(s[3]) >> 6;
+  *e ^= 0x2a;  // top two bits of each tail byte correct?
+  *e >>= shifte[len];
+
+  return next;
+}
+
+constexpr uint32_t invalid_code_point = ~uint32_t();
+
+// Invokes f(cp, sv) for every code point cp in s with sv being the string view
+// corresponding to the code point. cp is invalid_code_point on error.
+template <typename F>
+FMT_CONSTEXPR void for_each_codepoint(string_view s, F f) {
+  auto decode = [f](const char* buf_ptr, const char* ptr) {
+    auto cp = uint32_t();
+    auto error = 0;
+    auto end = utf8_decode(buf_ptr, &cp, &error);
+    bool result = f(error ? invalid_code_point : cp,
+                    string_view(ptr, error ? 1 : to_unsigned(end - buf_ptr)));
+    return result ? (error ? buf_ptr + 1 : end) : nullptr;
+  };
+  auto p = s.data();
+  const size_t block_size = 4;  // utf8_decode always reads blocks of 4 chars.
+  if (s.size() >= block_size) {
+    for (auto end = p + s.size() - block_size + 1; p < end;) {
+      p = decode(p, p);
+      if (!p) return;
+    }
+  }
+  if (auto num_chars_left = s.data() + s.size() - p) {
+    char buf[2 * block_size - 1] = {};
+    copy_str<char>(p, p + num_chars_left, buf);
+    const char* buf_ptr = buf;
+    do {
+      auto end = decode(buf_ptr, p);
+      if (!end) return;
+      p += end - buf_ptr;
+      buf_ptr = end;
+    } while (buf_ptr - buf < num_chars_left);
+  }
+}
+
+template <typename Char>
+inline auto compute_width(basic_string_view<Char> s) -> size_t {
+  return s.size();
+}
+
+// Computes approximate display width of a UTF-8 string.
+FMT_CONSTEXPR inline size_t compute_width(string_view s) {
+  size_t num_code_points = 0;
+  // It is not a lambda for compatibility with C++14.
+  struct count_code_points {
+    size_t* count;
+    FMT_CONSTEXPR auto operator()(uint32_t cp, string_view) const -> bool {
+      *count += detail::to_unsigned(
+          1 +
+          (cp >= 0x1100 &&
+           (cp <= 0x115f ||  // Hangul Jamo init. consonants
+            cp == 0x2329 ||  // LEFT-POINTING ANGLE BRACKET
+            cp == 0x232a ||  // RIGHT-POINTING ANGLE BRACKET
+            // CJK ... Yi except IDEOGRAPHIC HALF FILL SPACE:
+            (cp >= 0x2e80 && cp <= 0xa4cf && cp != 0x303f) ||
+            (cp >= 0xac00 && cp <= 0xd7a3) ||    // Hangul Syllables
+            (cp >= 0xf900 && cp <= 0xfaff) ||    // CJK Compatibility Ideographs
+            (cp >= 0xfe10 && cp <= 0xfe19) ||    // Vertical Forms
+            (cp >= 0xfe30 && cp <= 0xfe6f) ||    // CJK Compatibility Forms
+            (cp >= 0xff00 && cp <= 0xff60) ||    // Fullwidth Forms
+            (cp >= 0xffe0 && cp <= 0xffe6) ||    // Fullwidth Forms
+            (cp >= 0x20000 && cp <= 0x2fffd) ||  // CJK
+            (cp >= 0x30000 && cp <= 0x3fffd) ||
+            // Miscellaneous Symbols and Pictographs + Emoticons:
+            (cp >= 0x1f300 && cp <= 0x1f64f) ||
+            // Supplemental Symbols and Pictographs:
+            (cp >= 0x1f900 && cp <= 0x1f9ff))));
+      return true;
+    }
+  };
+  for_each_codepoint(s, count_code_points{&num_code_points});
+  return num_code_points;
+}
+
+inline auto compute_width(basic_string_view<char8_type> s) -> size_t {
+  return compute_width(
+      string_view(reinterpret_cast<const char*>(s.data()), s.size()));
+}
+
+template <typename Char>
+inline auto code_point_index(basic_string_view<Char> s, size_t n) -> size_t {
+  size_t size = s.size();
+  return n < size ? n : size;
+}
+
+// Calculates the index of the nth code point in a UTF-8 string.
+inline auto code_point_index(string_view s, size_t n) -> size_t {
+  const char* data = s.data();
+  size_t num_code_points = 0;
+  for (size_t i = 0, size = s.size(); i != size; ++i) {
+    if ((data[i] & 0xc0) != 0x80 && ++num_code_points > n) return i;
+  }
+  return s.size();
+}
+
+inline auto code_point_index(basic_string_view<char8_type> s, size_t n)
+    -> size_t {
+  return code_point_index(
+      string_view(reinterpret_cast<const char*>(s.data()), s.size()), n);
+}
+
+#ifndef FMT_USE_FLOAT128
+#  ifdef __SIZEOF_FLOAT128__
+#    define FMT_USE_FLOAT128 1
+#  else
+#    define FMT_USE_FLOAT128 0
+#  endif
+#endif
+#if FMT_USE_FLOAT128
+using float128 = __float128;
+#else
+using float128 = void;
+#endif
+template <typename T> using is_float128 = std::is_same<T, float128>;
+
+template <typename T>
+using is_floating_point =
+    bool_constant<std::is_floating_point<T>::value || is_float128<T>::value>;
+
+template <typename T, bool = std::is_floating_point<T>::value>
+struct is_fast_float : bool_constant<std::numeric_limits<T>::is_iec559 &&
+                                     sizeof(T) <= sizeof(double)> {};
+template <typename T> struct is_fast_float<T, false> : std::false_type {};
+
+template <typename T>
+using is_double_double = bool_constant<std::numeric_limits<T>::digits == 106>;
+
+#ifndef FMT_USE_FULL_CACHE_DRAGONBOX
+#  define FMT_USE_FULL_CACHE_DRAGONBOX 0
+#endif
+
+template <typename T>
+template <typename U>
+void buffer<T>::append(const U* begin, const U* end) {
+  while (begin != end) {
+    auto count = to_unsigned(end - begin);
+    try_reserve(size_ + count);
+    auto free_cap = capacity_ - size_;
+    if (free_cap < count) count = free_cap;
+    std::uninitialized_copy_n(begin, count, make_checked(ptr_ + size_, count));
+    size_ += count;
+    begin += count;
+  }
+}
+
+template <typename T, typename Enable = void>
+struct is_locale : std::false_type {};
+template <typename T>
+struct is_locale<T, void_t<decltype(T::classic())>> : std::true_type {};
+}  // namespace detail
+
+FMT_MODULE_EXPORT_BEGIN
+
+// The number of characters to store in the basic_memory_buffer object itself
+// to avoid dynamic memory allocation.
+enum { inline_buffer_size = 500 };
+
+/**
+  \rst
+  A dynamically growing memory buffer for trivially copyable/constructible types
+  with the first ``SIZE`` elements stored in the object itself.
+
+  You can use the ``memory_buffer`` type alias for ``char`` instead.
+
+  **Example**::
+
+     auto out = fmt::memory_buffer();
+     format_to(std::back_inserter(out), "The answer is {}.", 42);
+
+  This will append the following output to the ``out`` object:
+
+  .. code-block:: none
+
+     The answer is 42.
+
+  The output can be converted to an ``std::string`` with ``to_string(out)``.
+  \endrst
+ */
+template <typename T, size_t SIZE = inline_buffer_size,
+          typename Allocator = std::allocator<T>>
+class basic_memory_buffer final : public detail::buffer<T> {
+ private:
+  T store_[SIZE];
+
+  // Don't inherit from Allocator avoid generating type_info for it.
+  Allocator alloc_;
+
+  // Deallocate memory allocated by the buffer.
+  FMT_CONSTEXPR20 void deallocate() {
+    T* data = this->data();
+    if (data != store_) alloc_.deallocate(data, this->capacity());
+  }
+
+ protected:
+  FMT_CONSTEXPR20 void grow(size_t size) override;
+
+ public:
+  using value_type = T;
+  using const_reference = const T&;
+
+  FMT_CONSTEXPR20 explicit basic_memory_buffer(
+      const Allocator& alloc = Allocator())
+      : alloc_(alloc) {
+    this->set(store_, SIZE);
+    if (detail::is_constant_evaluated()) detail::fill_n(store_, SIZE, T());
+  }
+  FMT_CONSTEXPR20 ~basic_memory_buffer() { deallocate(); }
+
+ private:
+  // Move data from other to this buffer.
+  FMT_CONSTEXPR20 void move(basic_memory_buffer& other) {
+    alloc_ = std::move(other.alloc_);
+    T* data = other.data();
+    size_t size = other.size(), capacity = other.capacity();
+    if (data == other.store_) {
+      this->set(store_, capacity);
+      detail::copy_str<T>(other.store_, other.store_ + size,
+                          detail::make_checked(store_, capacity));
+    } else {
+      this->set(data, capacity);
+      // Set pointer to the inline array so that delete is not called
+      // when deallocating.
+      other.set(other.store_, 0);
+      other.clear();
+    }
+    this->resize(size);
+  }
+
+ public:
+  /**
+    \rst
+    Constructs a :class:`fmt::basic_memory_buffer` object moving the content
+    of the other object to it.
+    \endrst
+   */
+  FMT_CONSTEXPR20 basic_memory_buffer(basic_memory_buffer&& other) noexcept {
+    move(other);
+  }
+
+  /**
+    \rst
+    Moves the content of the other ``basic_memory_buffer`` object to this one.
+    \endrst
+   */
+  auto operator=(basic_memory_buffer&& other) noexcept -> basic_memory_buffer& {
+    FMT_ASSERT(this != &other, "");
+    deallocate();
+    move(other);
+    return *this;
+  }
+
+  // Returns a copy of the allocator associated with this buffer.
+  auto get_allocator() const -> Allocator { return alloc_; }
+
+  /**
+    Resizes the buffer to contain *count* elements. If T is a POD type new
+    elements may not be initialized.
+   */
+  FMT_CONSTEXPR20 void resize(size_t count) { this->try_resize(count); }
+
+  /** Increases the buffer capacity to *new_capacity*. */
+  void reserve(size_t new_capacity) { this->try_reserve(new_capacity); }
+
+  // Directly append data into the buffer
+  using detail::buffer<T>::append;
+  template <typename ContiguousRange>
+  void append(const ContiguousRange& range) {
+    append(range.data(), range.data() + range.size());
+  }
+};
+
+template <typename T, size_t SIZE, typename Allocator>
+FMT_CONSTEXPR20 void basic_memory_buffer<T, SIZE, Allocator>::grow(
+    size_t size) {
+  detail::abort_fuzzing_if(size > 5000);
+  const size_t max_size = std::allocator_traits<Allocator>::max_size(alloc_);
+  size_t old_capacity = this->capacity();
+  size_t new_capacity = old_capacity + old_capacity / 2;
+  if (size > new_capacity)
+    new_capacity = size;
+  else if (new_capacity > max_size)
+    new_capacity = size > max_size ? size : max_size;
+  T* old_data = this->data();
+  T* new_data =
+      std::allocator_traits<Allocator>::allocate(alloc_, new_capacity);
+  // The following code doesn't throw, so the raw pointer above doesn't leak.
+  std::uninitialized_copy(old_data, old_data + this->size(),
+                          detail::make_checked(new_data, new_capacity));
+  this->set(new_data, new_capacity);
+  // deallocate must not throw according to the standard, but even if it does,
+  // the buffer already uses the new storage and will deallocate it in
+  // destructor.
+  if (old_data != store_) alloc_.deallocate(old_data, old_capacity);
+}
+
+using memory_buffer = basic_memory_buffer<char>;
+
+template <typename T, size_t SIZE, typename Allocator>
+struct is_contiguous<basic_memory_buffer<T, SIZE, Allocator>> : std::true_type {
+};
+
+namespace detail {
+#ifdef _WIN32
+FMT_API bool write_console(std::FILE* f, string_view text);
+#endif
+FMT_API void print(std::FILE*, string_view);
+}  // namespace detail
+
+/** A formatting error such as invalid format string. */
+FMT_CLASS_API
+class FMT_API format_error : public std::runtime_error {
+ public:
+  explicit format_error(const char* message) : std::runtime_error(message) {}
+  explicit format_error(const std::string& message)
+      : std::runtime_error(message) {}
+  format_error(const format_error&) = default;
+  format_error& operator=(const format_error&) = default;
+  format_error(format_error&&) = default;
+  format_error& operator=(format_error&&) = default;
+  ~format_error() noexcept override FMT_MSC_DEFAULT;
+};
+
+namespace detail_exported {
+#if FMT_USE_NONTYPE_TEMPLATE_ARGS
+template <typename Char, size_t N> struct fixed_string {
+  constexpr fixed_string(const Char (&str)[N]) {
+    detail::copy_str<Char, const Char*, Char*>(static_cast<const Char*>(str),
+                                               str + N, data);
+  }
+  Char data[N] = {};
+};
+#endif
+
+// Converts a compile-time string to basic_string_view.
+template <typename Char, size_t N>
+constexpr auto compile_string_to_view(const Char (&s)[N])
+    -> basic_string_view<Char> {
+  // Remove trailing NUL character if needed. Won't be present if this is used
+  // with a raw character array (i.e. not defined as a string).
+  return {s, N - (std::char_traits<Char>::to_int_type(s[N - 1]) == 0 ? 1 : 0)};
+}
+template <typename Char>
+constexpr auto compile_string_to_view(detail::std_string_view<Char> s)
+    -> basic_string_view<Char> {
+  return {s.data(), s.size()};
+}
+}  // namespace detail_exported
+
+FMT_BEGIN_DETAIL_NAMESPACE
+
+template <typename T> struct is_integral : std::is_integral<T> {};
+template <> struct is_integral<int128_opt> : std::true_type {};
+template <> struct is_integral<uint128_t> : std::true_type {};
+
+template <typename T>
+using is_signed =
+    std::integral_constant<bool, std::numeric_limits<T>::is_signed ||
+                                     std::is_same<T, int128_opt>::value>;
+
+// Returns true if value is negative, false otherwise.
+// Same as `value < 0` but doesn't produce warnings if T is an unsigned type.
+template <typename T, FMT_ENABLE_IF(is_signed<T>::value)>
+constexpr auto is_negative(T value) -> bool {
+  return value < 0;
+}
+template <typename T, FMT_ENABLE_IF(!is_signed<T>::value)>
+constexpr auto is_negative(T) -> bool {
+  return false;
+}
+
+template <typename T>
+FMT_CONSTEXPR auto is_supported_floating_point(T) -> bool {
+  if (std::is_same<T, float>()) return FMT_USE_FLOAT;
+  if (std::is_same<T, double>()) return FMT_USE_DOUBLE;
+  if (std::is_same<T, long double>()) return FMT_USE_LONG_DOUBLE;
+  return true;
+}
+
+// Smallest of uint32_t, uint64_t, uint128_t that is large enough to
+// represent all values of an integral type T.
+template <typename T>
+using uint32_or_64_or_128_t =
+    conditional_t<num_bits<T>() <= 32 && !FMT_REDUCE_INT_INSTANTIATIONS,
+                  uint32_t,
+                  conditional_t<num_bits<T>() <= 64, uint64_t, uint128_t>>;
+template <typename T>
+using uint64_or_128_t = conditional_t<num_bits<T>() <= 64, uint64_t, uint128_t>;
+
+#define FMT_POWERS_OF_10(factor)                                             \
+  factor * 10, (factor)*100, (factor)*1000, (factor)*10000, (factor)*100000, \
+      (factor)*1000000, (factor)*10000000, (factor)*100000000,               \
+      (factor)*1000000000
+
+// Converts value in the range [0, 100) to a string.
+constexpr const char* digits2(size_t value) {
+  // GCC generates slightly better code when value is pointer-size.
+  return &"0001020304050607080910111213141516171819"
+         "2021222324252627282930313233343536373839"
+         "4041424344454647484950515253545556575859"
+         "6061626364656667686970717273747576777879"
+         "8081828384858687888990919293949596979899"[value * 2];
+}
+
+// Sign is a template parameter to workaround a bug in gcc 4.8.
+template <typename Char, typename Sign> constexpr Char sign(Sign s) {
+#if !FMT_GCC_VERSION || FMT_GCC_VERSION >= 604
+  static_assert(std::is_same<Sign, sign_t>::value, "");
+#endif
+  return static_cast<Char>("\0-+ "[s]);
+}
+
+template <typename T> FMT_CONSTEXPR auto count_digits_fallback(T n) -> int {
+  int count = 1;
+  for (;;) {
+    // Integer division is slow so do it for a group of four digits instead
+    // of for every digit. The idea comes from the talk by Alexandrescu
+    // "Three Optimization Tips for C++". See speed-test for a comparison.
+    if (n < 10) return count;
+    if (n < 100) return count + 1;
+    if (n < 1000) return count + 2;
+    if (n < 10000) return count + 3;
+    n /= 10000u;
+    count += 4;
+  }
+}
+#if FMT_USE_INT128
+FMT_CONSTEXPR inline auto count_digits(uint128_opt n) -> int {
+  return count_digits_fallback(n);
+}
+#endif
+
+#ifdef FMT_BUILTIN_CLZLL
+// It is a separate function rather than a part of count_digits to workaround
+// the lack of static constexpr in constexpr functions.
+inline auto do_count_digits(uint64_t n) -> int {
+  // This has comparable performance to the version by Kendall Willets
+  // (https://github.com/fmtlib/format-benchmark/blob/master/digits10)
+  // but uses smaller tables.
+  // Maps bsr(n) to ceil(log10(pow(2, bsr(n) + 1) - 1)).
+  static constexpr uint8_t bsr2log10[] = {
+      1,  1,  1,  2,  2,  2,  3,  3,  3,  4,  4,  4,  4,  5,  5,  5,
+      6,  6,  6,  7,  7,  7,  7,  8,  8,  8,  9,  9,  9,  10, 10, 10,
+      10, 11, 11, 11, 12, 12, 12, 13, 13, 13, 13, 14, 14, 14, 15, 15,
+      15, 16, 16, 16, 16, 17, 17, 17, 18, 18, 18, 19, 19, 19, 19, 20};
+  auto t = bsr2log10[FMT_BUILTIN_CLZLL(n | 1) ^ 63];
+  static constexpr const uint64_t zero_or_powers_of_10[] = {
+      0, 0, FMT_POWERS_OF_10(1U), FMT_POWERS_OF_10(1000000000ULL),
+      10000000000000000000ULL};
+  return t - (n < zero_or_powers_of_10[t]);
+}
+#endif
+
+// Returns the number of decimal digits in n. Leading zeros are not counted
+// except for n == 0 in which case count_digits returns 1.
+FMT_CONSTEXPR20 inline auto count_digits(uint64_t n) -> int {
+#ifdef FMT_BUILTIN_CLZLL
+  if (!is_constant_evaluated()) {
+    return do_count_digits(n);
+  }
+#endif
+  return count_digits_fallback(n);
+}
+
+// Counts the number of digits in n. BITS = log2(radix).
+template <int BITS, typename UInt>
+FMT_CONSTEXPR auto count_digits(UInt n) -> int {
+#ifdef FMT_BUILTIN_CLZ
+  if (!is_constant_evaluated() && num_bits<UInt>() == 32)
+    return (FMT_BUILTIN_CLZ(static_cast<uint32_t>(n) | 1) ^ 31) / BITS + 1;
+#endif
+  // Lambda avoids unreachable code warnings from NVHPC.
+  return [](UInt m) {
+    int num_digits = 0;
+    do {
+      ++num_digits;
+    } while ((m >>= BITS) != 0);
+    return num_digits;
+  }(n);
+}
+
+#ifdef FMT_BUILTIN_CLZ
+// It is a separate function rather than a part of count_digits to workaround
+// the lack of static constexpr in constexpr functions.
+FMT_INLINE auto do_count_digits(uint32_t n) -> int {
+// An optimization by Kendall Willets from https://bit.ly/3uOIQrB.
+// This increments the upper 32 bits (log10(T) - 1) when >= T is added.
+#  define FMT_INC(T) (((sizeof(#  T) - 1ull) << 32) - T)
+  static constexpr uint64_t table[] = {
+      FMT_INC(0),          FMT_INC(0),          FMT_INC(0),           // 8
+      FMT_INC(10),         FMT_INC(10),         FMT_INC(10),          // 64
+      FMT_INC(100),        FMT_INC(100),        FMT_INC(100),         // 512
+      FMT_INC(1000),       FMT_INC(1000),       FMT_INC(1000),        // 4096
+      FMT_INC(10000),      FMT_INC(10000),      FMT_INC(10000),       // 32k
+      FMT_INC(100000),     FMT_INC(100000),     FMT_INC(100000),      // 256k
+      FMT_INC(1000000),    FMT_INC(1000000),    FMT_INC(1000000),     // 2048k
+      FMT_INC(10000000),   FMT_INC(10000000),   FMT_INC(10000000),    // 16M
+      FMT_INC(100000000),  FMT_INC(100000000),  FMT_INC(100000000),   // 128M
+      FMT_INC(1000000000), FMT_INC(1000000000), FMT_INC(1000000000),  // 1024M
+      FMT_INC(1000000000), FMT_INC(1000000000)                        // 4B
+  };
+  auto inc = table[FMT_BUILTIN_CLZ(n | 1) ^ 31];
+  return static_cast<int>((n + inc) >> 32);
+}
+#endif
+
+// Optional version of count_digits for better performance on 32-bit platforms.
+FMT_CONSTEXPR20 inline auto count_digits(uint32_t n) -> int {
+#ifdef FMT_BUILTIN_CLZ
+  if (!is_constant_evaluated()) {
+    return do_count_digits(n);
+  }
+#endif
+  return count_digits_fallback(n);
+}
+
+template <typename Int> constexpr auto digits10() noexcept -> int {
+  return std::numeric_limits<Int>::digits10;
+}
+template <> constexpr auto digits10<int128_opt>() noexcept -> int { return 38; }
+template <> constexpr auto digits10<uint128_t>() noexcept -> int { return 38; }
+
+template <typename Char> struct thousands_sep_result {
+  std::string grouping;
+  Char thousands_sep;
+};
+
+template <typename Char>
+FMT_API auto thousands_sep_impl(locale_ref loc) -> thousands_sep_result<Char>;
+template <typename Char>
+inline auto thousands_sep(locale_ref loc) -> thousands_sep_result<Char> {
+  auto result = thousands_sep_impl<char>(loc);
+  return {result.grouping, Char(result.thousands_sep)};
+}
+template <>
+inline auto thousands_sep(locale_ref loc) -> thousands_sep_result<wchar_t> {
+  return thousands_sep_impl<wchar_t>(loc);
+}
+
+template <typename Char>
+FMT_API auto decimal_point_impl(locale_ref loc) -> Char;
+template <typename Char> inline auto decimal_point(locale_ref loc) -> Char {
+  return Char(decimal_point_impl<char>(loc));
+}
+template <> inline auto decimal_point(locale_ref loc) -> wchar_t {
+  return decimal_point_impl<wchar_t>(loc);
+}
+
+// Compares two characters for equality.
+template <typename Char> auto equal2(const Char* lhs, const char* rhs) -> bool {
+  return lhs[0] == Char(rhs[0]) && lhs[1] == Char(rhs[1]);
+}
+inline auto equal2(const char* lhs, const char* rhs) -> bool {
+  return memcmp(lhs, rhs, 2) == 0;
+}
+
+// Copies two characters from src to dst.
+template <typename Char>
+FMT_CONSTEXPR20 FMT_INLINE void copy2(Char* dst, const char* src) {
+  if (!is_constant_evaluated() && sizeof(Char) == sizeof(char)) {
+    memcpy(dst, src, 2);
+    return;
+  }
+  *dst++ = static_cast<Char>(*src++);
+  *dst = static_cast<Char>(*src);
+}
+
+template <typename Iterator> struct format_decimal_result {
+  Iterator begin;
+  Iterator end;
+};
+
+// Formats a decimal unsigned integer value writing into out pointing to a
+// buffer of specified size. The caller must ensure that the buffer is large
+// enough.
+template <typename Char, typename UInt>
+FMT_CONSTEXPR20 auto format_decimal(Char* out, UInt value, int size)
+    -> format_decimal_result<Char*> {
+  FMT_ASSERT(size >= count_digits(value), "invalid digit count");
+  out += size;
+  Char* end = out;
+  while (value >= 100) {
+    // Integer division is slow so do it for a group of two digits instead
+    // of for every digit. The idea comes from the talk by Alexandrescu
+    // "Three Optimization Tips for C++". See speed-test for a comparison.
+    out -= 2;
+    copy2(out, digits2(static_cast<size_t>(value % 100)));
+    value /= 100;
+  }
+  if (value < 10) {
+    *--out = static_cast<Char>('0' + value);
+    return {out, end};
+  }
+  out -= 2;
+  copy2(out, digits2(static_cast<size_t>(value)));
+  return {out, end};
+}
+
+template <typename Char, typename UInt, typename Iterator,
+          FMT_ENABLE_IF(!std::is_pointer<remove_cvref_t<Iterator>>::value)>
+FMT_CONSTEXPR inline auto format_decimal(Iterator out, UInt value, int size)
+    -> format_decimal_result<Iterator> {
+  // Buffer is large enough to hold all digits (digits10 + 1).
+  Char buffer[digits10<UInt>() + 1];
+  auto end = format_decimal(buffer, value, size).end;
+  return {out, detail::copy_str_noinline<Char>(buffer, end, out)};
+}
+
+template <unsigned BASE_BITS, typename Char, typename UInt>
+FMT_CONSTEXPR auto format_uint(Char* buffer, UInt value, int num_digits,
+                               bool upper = false) -> Char* {
+  buffer += num_digits;
+  Char* end = buffer;
+  do {
+    const char* digits = upper ? "0123456789ABCDEF" : "0123456789abcdef";
+    unsigned digit = static_cast<unsigned>(value & ((1 << BASE_BITS) - 1));
+    *--buffer = static_cast<Char>(BASE_BITS < 4 ? static_cast<char>('0' + digit)
+                                                : digits[digit]);
+  } while ((value >>= BASE_BITS) != 0);
+  return end;
+}
+
+template <unsigned BASE_BITS, typename Char, typename It, typename UInt>
+inline auto format_uint(It out, UInt value, int num_digits, bool upper = false)
+    -> It {
+  if (auto ptr = to_pointer<Char>(out, to_unsigned(num_digits))) {
+    format_uint<BASE_BITS>(ptr, value, num_digits, upper);
+    return out;
+  }
+  // Buffer should be large enough to hold all digits (digits / BASE_BITS + 1).
+  char buffer[num_bits<UInt>() / BASE_BITS + 1];
+  format_uint<BASE_BITS>(buffer, value, num_digits, upper);
+  return detail::copy_str_noinline<Char>(buffer, buffer + num_digits, out);
+}
+
+// A converter from UTF-8 to UTF-16.
+class utf8_to_utf16 {
+ private:
+  basic_memory_buffer<wchar_t> buffer_;
+
+ public:
+  FMT_API explicit utf8_to_utf16(string_view s);
+  operator basic_string_view<wchar_t>() const { return {&buffer_[0], size()}; }
+  auto size() const -> size_t { return buffer_.size() - 1; }
+  auto c_str() const -> const wchar_t* { return &buffer_[0]; }
+  auto str() const -> std::wstring { return {&buffer_[0], size()}; }
+};
+
+namespace dragonbox {
+
+// Type-specific information that Dragonbox uses.
+template <typename T, typename Enable = void> struct float_info;
+
+template <> struct float_info<float> {
+  using carrier_uint = uint32_t;
+  static const int exponent_bits = 8;
+  static const int kappa = 1;
+  static const int big_divisor = 100;
+  static const int small_divisor = 10;
+  static const int min_k = -31;
+  static const int max_k = 46;
+  static const int shorter_interval_tie_lower_threshold = -35;
+  static const int shorter_interval_tie_upper_threshold = -35;
+};
+
+template <> struct float_info<double> {
+  using carrier_uint = uint64_t;
+  static const int exponent_bits = 11;
+  static const int kappa = 2;
+  static const int big_divisor = 1000;
+  static const int small_divisor = 100;
+  static const int min_k = -292;
+  static const int max_k = 326;
+  static const int shorter_interval_tie_lower_threshold = -77;
+  static const int shorter_interval_tie_upper_threshold = -77;
+};
+
+// An 80- or 128-bit floating point number.
+template <typename T>
+struct float_info<T, enable_if_t<std::numeric_limits<T>::digits == 64 ||
+                                 std::numeric_limits<T>::digits == 113 ||
+                                 is_float128<T>::value>> {
+  using carrier_uint = detail::uint128_t;
+  static const int exponent_bits = 15;
+};
+
+// A double-double floating point number.
+template <typename T>
+struct float_info<T, enable_if_t<is_double_double<T>::value>> {
+  using carrier_uint = detail::uint128_t;
+};
+
+template <typename T> struct decimal_fp {
+  using significand_type = typename float_info<T>::carrier_uint;
+  significand_type significand;
+  int exponent;
+};
+
+template <typename T> FMT_API auto to_decimal(T x) noexcept -> decimal_fp<T>;
+}  // namespace dragonbox
+
+// Returns true iff Float has the implicit bit which is not stored.
+template <typename Float> constexpr bool has_implicit_bit() {
+  // An 80-bit FP number has a 64-bit significand an no implicit bit.
+  return std::numeric_limits<Float>::digits != 64;
+}
+
+// Returns the number of significand bits stored in Float. The implicit bit is
+// not counted since it is not stored.
+template <typename Float> constexpr int num_significand_bits() {
+  // std::numeric_limits may not support __float128.
+  return is_float128<Float>() ? 112
+                              : (std::numeric_limits<Float>::digits -
+                                 (has_implicit_bit<Float>() ? 1 : 0));
+}
+
+template <typename Float>
+constexpr auto exponent_mask() ->
+    typename dragonbox::float_info<Float>::carrier_uint {
+  using uint = typename dragonbox::float_info<Float>::carrier_uint;
+  return ((uint(1) << dragonbox::float_info<Float>::exponent_bits) - 1)
+         << num_significand_bits<Float>();
+}
+template <typename Float> constexpr auto exponent_bias() -> int {
+  // std::numeric_limits may not support __float128.
+  return is_float128<Float>() ? 16383
+                              : std::numeric_limits<Float>::max_exponent - 1;
+}
+
+// Writes the exponent exp in the form "[+-]d{2,3}" to buffer.
+template <typename Char, typename It>
+FMT_CONSTEXPR auto write_exponent(int exp, It it) -> It {
+  FMT_ASSERT(-10000 < exp && exp < 10000, "exponent out of range");
+  if (exp < 0) {
+    *it++ = static_cast<Char>('-');
+    exp = -exp;
+  } else {
+    *it++ = static_cast<Char>('+');
+  }
+  if (exp >= 100) {
+    const char* top = digits2(to_unsigned(exp / 100));
+    if (exp >= 1000) *it++ = static_cast<Char>(top[0]);
+    *it++ = static_cast<Char>(top[1]);
+    exp %= 100;
+  }
+  const char* d = digits2(to_unsigned(exp));
+  *it++ = static_cast<Char>(d[0]);
+  *it++ = static_cast<Char>(d[1]);
+  return it;
+}
+
+// A floating-point number f * pow(2, e) where F is an unsigned type.
+template <typename F> struct basic_fp {
+  F f;
+  int e;
+
+  static constexpr const int num_significand_bits =
+      static_cast<int>(sizeof(F) * num_bits<unsigned char>());
+
+  constexpr basic_fp() : f(0), e(0) {}
+  constexpr basic_fp(uint64_t f_val, int e_val) : f(f_val), e(e_val) {}
+
+  // Constructs fp from an IEEE754 floating-point number.
+  template <typename Float> FMT_CONSTEXPR basic_fp(Float n) { assign(n); }
+
+  // Assigns n to this and return true iff predecessor is closer than successor.
+  template <typename Float, FMT_ENABLE_IF(!is_double_double<Float>::value)>
+  FMT_CONSTEXPR auto assign(Float n) -> bool {
+    static_assert(std::numeric_limits<Float>::digits <= 113, "unsupported FP");
+    // Assume Float is in the format [sign][exponent][significand].
+    using carrier_uint = typename dragonbox::float_info<Float>::carrier_uint;
+    const auto num_float_significand_bits =
+        detail::num_significand_bits<Float>();
+    const auto implicit_bit = carrier_uint(1) << num_float_significand_bits;
+    const auto significand_mask = implicit_bit - 1;
+    auto u = bit_cast<carrier_uint>(n);
+    f = static_cast<F>(u & significand_mask);
+    auto biased_e = static_cast<int>((u & exponent_mask<Float>()) >>
+                                     num_float_significand_bits);
+    // The predecessor is closer if n is a normalized power of 2 (f == 0)
+    // other than the smallest normalized number (biased_e > 1).
+    auto is_predecessor_closer = f == 0 && biased_e > 1;
+    if (biased_e == 0)
+      biased_e = 1;  // Subnormals use biased exponent 1 (min exponent).
+    else if (has_implicit_bit<Float>())
+      f += static_cast<F>(implicit_bit);
+    e = biased_e - exponent_bias<Float>() - num_float_significand_bits;
+    if (!has_implicit_bit<Float>()) ++e;
+    return is_predecessor_closer;
+  }
+
+  template <typename Float, FMT_ENABLE_IF(is_double_double<Float>::value)>
+  FMT_CONSTEXPR auto assign(Float n) -> bool {
+    static_assert(std::numeric_limits<double>::is_iec559, "unsupported FP");
+    return assign(static_cast<double>(n));
+  }
+};
+
+using fp = basic_fp<unsigned long long>;
+
+// Normalizes the value converted from double and multiplied by (1 << SHIFT).
+template <int SHIFT = 0, typename F>
+FMT_CONSTEXPR basic_fp<F> normalize(basic_fp<F> value) {
+  // Handle subnormals.
+  const auto implicit_bit = F(1) << num_significand_bits<double>();
+  const auto shifted_implicit_bit = implicit_bit << SHIFT;
+  while ((value.f & shifted_implicit_bit) == 0) {
+    value.f <<= 1;
+    --value.e;
+  }
+  // Subtract 1 to account for hidden bit.
+  const auto offset = basic_fp<F>::num_significand_bits -
+                      num_significand_bits<double>() - SHIFT - 1;
+  value.f <<= offset;
+  value.e -= offset;
+  return value;
+}
+
+// Computes lhs * rhs / pow(2, 64) rounded to nearest with half-up tie breaking.
+FMT_CONSTEXPR inline uint64_t multiply(uint64_t lhs, uint64_t rhs) {
+#if FMT_USE_INT128
+  auto product = static_cast<__uint128_t>(lhs) * rhs;
+  auto f = static_cast<uint64_t>(product >> 64);
+  return (static_cast<uint64_t>(product) & (1ULL << 63)) != 0 ? f + 1 : f;
+#else
+  // Multiply 32-bit parts of significands.
+  uint64_t mask = (1ULL << 32) - 1;
+  uint64_t a = lhs >> 32, b = lhs & mask;
+  uint64_t c = rhs >> 32, d = rhs & mask;
+  uint64_t ac = a * c, bc = b * c, ad = a * d, bd = b * d;
+  // Compute mid 64-bit of result and round.
+  uint64_t mid = (bd >> 32) + (ad & mask) + (bc & mask) + (1U << 31);
+  return ac + (ad >> 32) + (bc >> 32) + (mid >> 32);
+#endif
+}
+
+FMT_CONSTEXPR inline fp operator*(fp x, fp y) {
+  return {multiply(x.f, y.f), x.e + y.e + 64};
+}
+
+template <typename T = void> struct basic_data {
+  // Normalized 64-bit significands of pow(10, k), for k = -348, -340, ..., 340.
+  // These are generated by support/compute-powers.py.
+  static constexpr uint64_t pow10_significands[87] = {
+      0xfa8fd5a0081c0288, 0xbaaee17fa23ebf76, 0x8b16fb203055ac76,
+      0xcf42894a5dce35ea, 0x9a6bb0aa55653b2d, 0xe61acf033d1a45df,
+      0xab70fe17c79ac6ca, 0xff77b1fcbebcdc4f, 0xbe5691ef416bd60c,
+      0x8dd01fad907ffc3c, 0xd3515c2831559a83, 0x9d71ac8fada6c9b5,
+      0xea9c227723ee8bcb, 0xaecc49914078536d, 0x823c12795db6ce57,
+      0xc21094364dfb5637, 0x9096ea6f3848984f, 0xd77485cb25823ac7,
+      0xa086cfcd97bf97f4, 0xef340a98172aace5, 0xb23867fb2a35b28e,
+      0x84c8d4dfd2c63f3b, 0xc5dd44271ad3cdba, 0x936b9fcebb25c996,
+      0xdbac6c247d62a584, 0xa3ab66580d5fdaf6, 0xf3e2f893dec3f126,
+      0xb5b5ada8aaff80b8, 0x87625f056c7c4a8b, 0xc9bcff6034c13053,
+      0x964e858c91ba2655, 0xdff9772470297ebd, 0xa6dfbd9fb8e5b88f,
+      0xf8a95fcf88747d94, 0xb94470938fa89bcf, 0x8a08f0f8bf0f156b,
+      0xcdb02555653131b6, 0x993fe2c6d07b7fac, 0xe45c10c42a2b3b06,
+      0xaa242499697392d3, 0xfd87b5f28300ca0e, 0xbce5086492111aeb,
+      0x8cbccc096f5088cc, 0xd1b71758e219652c, 0x9c40000000000000,
+      0xe8d4a51000000000, 0xad78ebc5ac620000, 0x813f3978f8940984,
+      0xc097ce7bc90715b3, 0x8f7e32ce7bea5c70, 0xd5d238a4abe98068,
+      0x9f4f2726179a2245, 0xed63a231d4c4fb27, 0xb0de65388cc8ada8,
+      0x83c7088e1aab65db, 0xc45d1df942711d9a, 0x924d692ca61be758,
+      0xda01ee641a708dea, 0xa26da3999aef774a, 0xf209787bb47d6b85,
+      0xb454e4a179dd1877, 0x865b86925b9bc5c2, 0xc83553c5c8965d3d,
+      0x952ab45cfa97a0b3, 0xde469fbd99a05fe3, 0xa59bc234db398c25,
+      0xf6c69a72a3989f5c, 0xb7dcbf5354e9bece, 0x88fcf317f22241e2,
+      0xcc20ce9bd35c78a5, 0x98165af37b2153df, 0xe2a0b5dc971f303a,
+      0xa8d9d1535ce3b396, 0xfb9b7cd9a4a7443c, 0xbb764c4ca7a44410,
+      0x8bab8eefb6409c1a, 0xd01fef10a657842c, 0x9b10a4e5e9913129,
+      0xe7109bfba19c0c9d, 0xac2820d9623bf429, 0x80444b5e7aa7cf85,
+      0xbf21e44003acdd2d, 0x8e679c2f5e44ff8f, 0xd433179d9c8cb841,
+      0x9e19db92b4e31ba9, 0xeb96bf6ebadf77d9, 0xaf87023b9bf0ee6b,
+  };
+
+#if FMT_GCC_VERSION && FMT_GCC_VERSION < 409
+#  pragma GCC diagnostic push
+#  pragma GCC diagnostic ignored "-Wnarrowing"
+#endif
+  // Binary exponents of pow(10, k), for k = -348, -340, ..., 340, corresponding
+  // to significands above.
+  static constexpr int16_t pow10_exponents[87] = {
+      -1220, -1193, -1166, -1140, -1113, -1087, -1060, -1034, -1007, -980, -954,
+      -927,  -901,  -874,  -847,  -821,  -794,  -768,  -741,  -715,  -688, -661,
+      -635,  -608,  -582,  -555,  -529,  -502,  -475,  -449,  -422,  -396, -369,
+      -343,  -316,  -289,  -263,  -236,  -210,  -183,  -157,  -130,  -103, -77,
+      -50,   -24,   3,     30,    56,    83,    109,   136,   162,   189,  216,
+      242,   269,   295,   322,   348,   375,   402,   428,   455,   481,  508,
+      534,   561,   588,   614,   641,   667,   694,   720,   747,   774,  800,
+      827,   853,   880,   907,   933,   960,   986,   1013,  1039,  1066};
+#if FMT_GCC_VERSION && FMT_GCC_VERSION < 409
+#  pragma GCC diagnostic pop
+#endif
+
+  static constexpr uint64_t power_of_10_64[20] = {
+      1, FMT_POWERS_OF_10(1ULL), FMT_POWERS_OF_10(1000000000ULL),
+      10000000000000000000ULL};
+};
+
+#if FMT_CPLUSPLUS < 201703L
+template <typename T> constexpr uint64_t basic_data<T>::pow10_significands[];
+template <typename T> constexpr int16_t basic_data<T>::pow10_exponents[];
+template <typename T> constexpr uint64_t basic_data<T>::power_of_10_64[];
+#endif
+
+// This is a struct rather than an alias to avoid shadowing warnings in gcc.
+struct data : basic_data<> {};
+
+// Returns a cached power of 10 `c_k = c_k.f * pow(2, c_k.e)` such that its
+// (binary) exponent satisfies `min_exponent <= c_k.e <= min_exponent + 28`.
+FMT_CONSTEXPR inline fp get_cached_power(int min_exponent,
+                                         int& pow10_exponent) {
+  const int shift = 32;
+  // log10(2) = 0x0.4d104d427de7fbcc...
+  const int64_t significand = 0x4d104d427de7fbcc;
+  int index = static_cast<int>(
+      ((min_exponent + fp::num_significand_bits - 1) * (significand >> shift) +
+       ((int64_t(1) << shift) - 1))  // ceil
+      >> 32                          // arithmetic shift
+  );
+  // Decimal exponent of the first (smallest) cached power of 10.
+  const int first_dec_exp = -348;
+  // Difference between 2 consecutive decimal exponents in cached powers of 10.
+  const int dec_exp_step = 8;
+  index = (index - first_dec_exp - 1) / dec_exp_step + 1;
+  pow10_exponent = first_dec_exp + index * dec_exp_step;
+  // Using *(x + index) instead of x[index] avoids an issue with some compilers
+  // using the EDG frontend (e.g. nvhpc/22.3 in C++17 mode).
+  return {*(data::pow10_significands + index),
+          *(data::pow10_exponents + index)};
+}
+
+#ifndef _MSC_VER
+#  define FMT_SNPRINTF snprintf
+#else
+FMT_API auto fmt_snprintf(char* buf, size_t size, const char* fmt, ...) -> int;
+#  define FMT_SNPRINTF fmt_snprintf
+#endif  // _MSC_VER
+
+// Formats a floating-point number with snprintf using the hexfloat format.
+template <typename T>
+auto snprintf_float(T value, int precision, float_specs specs,
+                    buffer<char>& buf) -> int {
+  // Buffer capacity must be non-zero, otherwise MSVC's vsnprintf_s will fail.
+  FMT_ASSERT(buf.capacity() > buf.size(), "empty buffer");
+  FMT_ASSERT(specs.format == float_format::hex, "");
+  static_assert(!std::is_same<T, float>::value, "");
+
+  // Build the format string.
+  char format[7];  // The longest format is "%#.*Le".
+  char* format_ptr = format;
+  *format_ptr++ = '%';
+  if (specs.showpoint) *format_ptr++ = '#';
+  if (precision >= 0) {
+    *format_ptr++ = '.';
+    *format_ptr++ = '*';
+  }
+  if (std::is_same<T, long double>()) *format_ptr++ = 'L';
+  *format_ptr++ = specs.upper ? 'A' : 'a';
+  *format_ptr = '\0';
+
+  // Format using snprintf.
+  auto offset = buf.size();
+  for (;;) {
+    auto begin = buf.data() + offset;
+    auto capacity = buf.capacity() - offset;
+    abort_fuzzing_if(precision > 100000);
+    // Suppress the warning about a nonliteral format string.
+    // Cannot use auto because of a bug in MinGW (#1532).
+    int (*snprintf_ptr)(char*, size_t, const char*, ...) = FMT_SNPRINTF;
+    int result = precision >= 0
+                     ? snprintf_ptr(begin, capacity, format, precision, value)
+                     : snprintf_ptr(begin, capacity, format, value);
+    if (result < 0) {
+      // The buffer will grow exponentially.
+      buf.try_reserve(buf.capacity() + 1);
+      continue;
+    }
+    auto size = to_unsigned(result);
+    // Size equal to capacity means that the last character was truncated.
+    if (size < capacity) {
+      buf.try_resize(size + offset);
+      return 0;
+    }
+    buf.try_reserve(size + offset + 1);  // Add 1 for the terminating '\0'.
+  }
+}
+
+template <typename T>
+using convert_float_result =
+    conditional_t<std::is_same<T, float>::value || sizeof(T) == sizeof(double),
+                  double, T>;
+
+template <typename T>
+constexpr auto convert_float(T value) -> convert_float_result<T> {
+  return static_cast<convert_float_result<T>>(value);
+}
+
+template <typename OutputIt, typename Char>
+FMT_NOINLINE FMT_CONSTEXPR auto fill(OutputIt it, size_t n,
+                                     const fill_t<Char>& fill) -> OutputIt {
+  auto fill_size = fill.size();
+  if (fill_size == 1) return detail::fill_n(it, n, fill[0]);
+  auto data = fill.data();
+  for (size_t i = 0; i < n; ++i)
+    it = copy_str<Char>(data, data + fill_size, it);
+  return it;
+}
+
+// Writes the output of f, padded according to format specifications in specs.
+// size: output size in code units.
+// width: output display width in (terminal) column positions.
+template <align::type align = align::left, typename OutputIt, typename Char,
+          typename F>
+FMT_CONSTEXPR auto write_padded(OutputIt out,
+                                const basic_format_specs<Char>& specs,
+                                size_t size, size_t width, F&& f) -> OutputIt {
+  static_assert(align == align::left || align == align::right, "");
+  unsigned spec_width = to_unsigned(specs.width);
+  size_t padding = spec_width > width ? spec_width - width : 0;
+  // Shifts are encoded as string literals because static constexpr is not
+  // supported in constexpr functions.
+  auto* shifts = align == align::left ? "\x1f\x1f\x00\x01" : "\x00\x1f\x00\x01";
+  size_t left_padding = padding >> shifts[specs.align];
+  size_t right_padding = padding - left_padding;
+  auto it = reserve(out, size + padding * specs.fill.size());
+  if (left_padding != 0) it = fill(it, left_padding, specs.fill);
+  it = f(it);
+  if (right_padding != 0) it = fill(it, right_padding, specs.fill);
+  return base_iterator(out, it);
+}
+
+template <align::type align = align::left, typename OutputIt, typename Char,
+          typename F>
+constexpr auto write_padded(OutputIt out, const basic_format_specs<Char>& specs,
+                            size_t size, F&& f) -> OutputIt {
+  return write_padded<align>(out, specs, size, size, f);
+}
+
+template <align::type align = align::left, typename Char, typename OutputIt>
+FMT_CONSTEXPR auto write_bytes(OutputIt out, string_view bytes,
+                               const basic_format_specs<Char>& specs)
+    -> OutputIt {
+  return write_padded<align>(
+      out, specs, bytes.size(), [bytes](reserve_iterator<OutputIt> it) {
+        const char* data = bytes.data();
+        return copy_str<Char>(data, data + bytes.size(), it);
+      });
+}
+
+template <typename Char, typename OutputIt, typename UIntPtr>
+auto write_ptr(OutputIt out, UIntPtr value,
+               const basic_format_specs<Char>* specs) -> OutputIt {
+  int num_digits = count_digits<4>(value);
+  auto size = to_unsigned(num_digits) + size_t(2);
+  auto write = [=](reserve_iterator<OutputIt> it) {
+    *it++ = static_cast<Char>('0');
+    *it++ = static_cast<Char>('x');
+    return format_uint<4, Char>(it, value, num_digits);
+  };
+  return specs ? write_padded<align::right>(out, *specs, size, write)
+               : base_iterator(out, write(reserve(out, size)));
+}
+
+// Returns true iff the code point cp is printable.
+FMT_API auto is_printable(uint32_t cp) -> bool;
+
+inline auto needs_escape(uint32_t cp) -> bool {
+  return cp < 0x20 || cp == 0x7f || cp == '"' || cp == '\\' ||
+         !is_printable(cp);
+}
+
+template <typename Char> struct find_escape_result {
+  const Char* begin;
+  const Char* end;
+  uint32_t cp;
+};
+
+template <typename Char>
+using make_unsigned_char =
+    typename conditional_t<std::is_integral<Char>::value,
+                           std::make_unsigned<Char>,
+                           type_identity<uint32_t>>::type;
+
+template <typename Char>
+auto find_escape(const Char* begin, const Char* end)
+    -> find_escape_result<Char> {
+  for (; begin != end; ++begin) {
+    uint32_t cp = static_cast<make_unsigned_char<Char>>(*begin);
+    if (const_check(sizeof(Char) == 1) && cp >= 0x80) continue;
+    if (needs_escape(cp)) return {begin, begin + 1, cp};
+  }
+  return {begin, nullptr, 0};
+}
+
+inline auto find_escape(const char* begin, const char* end)
+    -> find_escape_result<char> {
+  if (!is_utf8()) return find_escape<char>(begin, end);
+  auto result = find_escape_result<char>{end, nullptr, 0};
+  for_each_codepoint(string_view(begin, to_unsigned(end - begin)),
+                     [&](uint32_t cp, string_view sv) {
+                       if (needs_escape(cp)) {
+                         result = {sv.begin(), sv.end(), cp};
+                         return false;
+                       }
+                       return true;
+                     });
+  return result;
+}
+
+#define FMT_STRING_IMPL(s, base, explicit)                                    \
+  [] {                                                                        \
+    /* Use the hidden visibility as a workaround for a GCC bug (#1973). */    \
+    /* Use a macro-like name to avoid shadowing warnings. */                  \
+    struct FMT_GCC_VISIBILITY_HIDDEN FMT_COMPILE_STRING : base {              \
+      using char_type FMT_MAYBE_UNUSED = fmt::remove_cvref_t<decltype(s[0])>; \
+      FMT_MAYBE_UNUSED FMT_CONSTEXPR explicit                                 \
+      operator fmt::basic_string_view<char_type>() const {                    \
+        return fmt::detail_exported::compile_string_to_view<char_type>(s);    \
+      }                                                                       \
+    };                                                                        \
+    return FMT_COMPILE_STRING();                                              \
+  }()
+
+/**
+  \rst
+  Constructs a compile-time format string from a string literal *s*.
+
+  **Example**::
+
+    // A compile-time error because 'd' is an invalid specifier for strings.
+    std::string s = fmt::format(FMT_STRING("{:d}"), "foo");
+  \endrst
+ */
+#define FMT_STRING(s) FMT_STRING_IMPL(s, fmt::detail::compile_string, )
+
+template <size_t width, typename Char, typename OutputIt>
+auto write_codepoint(OutputIt out, char prefix, uint32_t cp) -> OutputIt {
+  *out++ = static_cast<Char>('\\');
+  *out++ = static_cast<Char>(prefix);
+  Char buf[width];
+  fill_n(buf, width, static_cast<Char>('0'));
+  format_uint<4>(buf, cp, width);
+  return copy_str<Char>(buf, buf + width, out);
+}
+
+template <typename OutputIt, typename Char>
+auto write_escaped_cp(OutputIt out, const find_escape_result<Char>& escape)
+    -> OutputIt {
+  auto c = static_cast<Char>(escape.cp);
+  switch (escape.cp) {
+  case '\n':
+    *out++ = static_cast<Char>('\\');
+    c = static_cast<Char>('n');
+    break;
+  case '\r':
+    *out++ = static_cast<Char>('\\');
+    c = static_cast<Char>('r');
+    break;
+  case '\t':
+    *out++ = static_cast<Char>('\\');
+    c = static_cast<Char>('t');
+    break;
+  case '"':
+    FMT_FALLTHROUGH;
+  case '\'':
+    FMT_FALLTHROUGH;
+  case '\\':
+    *out++ = static_cast<Char>('\\');
+    break;
+  default:
+    if (is_utf8()) {
+      if (escape.cp < 0x100) {
+        return write_codepoint<2, Char>(out, 'x', escape.cp);
+      }
+      if (escape.cp < 0x10000) {
+        return write_codepoint<4, Char>(out, 'u', escape.cp);
+      }
+      if (escape.cp < 0x110000) {
+        return write_codepoint<8, Char>(out, 'U', escape.cp);
+      }
+    }
+    for (Char escape_char : basic_string_view<Char>(
+             escape.begin, to_unsigned(escape.end - escape.begin))) {
+      out = write_codepoint<2, Char>(out, 'x',
+                                     static_cast<uint32_t>(escape_char) & 0xFF);
+    }
+    return out;
+  }
+  *out++ = c;
+  return out;
+}
+
+template <typename Char, typename OutputIt>
+auto write_escaped_string(OutputIt out, basic_string_view<Char> str)
+    -> OutputIt {
+  *out++ = static_cast<Char>('"');
+  auto begin = str.begin(), end = str.end();
+  do {
+    auto escape = find_escape(begin, end);
+    out = copy_str<Char>(begin, escape.begin, out);
+    begin = escape.end;
+    if (!begin) break;
+    out = write_escaped_cp<OutputIt, Char>(out, escape);
+  } while (begin != end);
+  *out++ = static_cast<Char>('"');
+  return out;
+}
+
+template <typename Char, typename OutputIt>
+auto write_escaped_char(OutputIt out, Char v) -> OutputIt {
+  *out++ = static_cast<Char>('\'');
+  if ((needs_escape(static_cast<uint32_t>(v)) && v != static_cast<Char>('"')) ||
+      v == static_cast<Char>('\'')) {
+    out = write_escaped_cp(
+        out, find_escape_result<Char>{&v, &v + 1, static_cast<uint32_t>(v)});
+  } else {
+    *out++ = v;
+  }
+  *out++ = static_cast<Char>('\'');
+  return out;
+}
+
+template <typename Char, typename OutputIt>
+FMT_CONSTEXPR auto write_char(OutputIt out, Char value,
+                              const basic_format_specs<Char>& specs)
+    -> OutputIt {
+  bool is_debug = specs.type == presentation_type::debug;
+  return write_padded(out, specs, 1, [=](reserve_iterator<OutputIt> it) {
+    if (is_debug) return write_escaped_char(it, value);
+    *it++ = value;
+    return it;
+  });
+}
+template <typename Char, typename OutputIt>
+FMT_CONSTEXPR auto write(OutputIt out, Char value,
+                         const basic_format_specs<Char>& specs,
+                         locale_ref loc = {}) -> OutputIt {
+  return check_char_specs(specs)
+             ? write_char(out, value, specs)
+             : write(out, static_cast<int>(value), specs, loc);
+}
+
+// Data for write_int that doesn't depend on output iterator type. It is used to
+// avoid template code bloat.
+template <typename Char> struct write_int_data {
+  size_t size;
+  size_t padding;
+
+  FMT_CONSTEXPR write_int_data(int num_digits, unsigned prefix,
+                               const basic_format_specs<Char>& specs)
+      : size((prefix >> 24) + to_unsigned(num_digits)), padding(0) {
+    if (specs.align == align::numeric) {
+      auto width = to_unsigned(specs.width);
+      if (width > size) {
+        padding = width - size;
+        size = width;
+      }
+    } else if (specs.precision > num_digits) {
+      size = (prefix >> 24) + to_unsigned(specs.precision);
+      padding = to_unsigned(specs.precision - num_digits);
+    }
+  }
+};
+
+// Writes an integer in the format
+//   <left-padding><prefix><numeric-padding><digits><right-padding>
+// where <digits> are written by write_digits(it).
+// prefix contains chars in three lower bytes and the size in the fourth byte.
+template <typename OutputIt, typename Char, typename W>
+FMT_CONSTEXPR FMT_INLINE auto write_int(OutputIt out, int num_digits,
+                                        unsigned prefix,
+                                        const basic_format_specs<Char>& specs,
+                                        W write_digits) -> OutputIt {
+  // Slightly faster check for specs.width == 0 && specs.precision == -1.
+  if ((specs.width | (specs.precision + 1)) == 0) {
+    auto it = reserve(out, to_unsigned(num_digits) + (prefix >> 24));
+    if (prefix != 0) {
+      for (unsigned p = prefix & 0xffffff; p != 0; p >>= 8)
+        *it++ = static_cast<Char>(p & 0xff);
+    }
+    return base_iterator(out, write_digits(it));
+  }
+  auto data = write_int_data<Char>(num_digits, prefix, specs);
+  return write_padded<align::right>(
+      out, specs, data.size, [=](reserve_iterator<OutputIt> it) {
+        for (unsigned p = prefix & 0xffffff; p != 0; p >>= 8)
+          *it++ = static_cast<Char>(p & 0xff);
+        it = detail::fill_n(it, data.padding, static_cast<Char>('0'));
+        return write_digits(it);
+      });
+}
+
+template <typename Char> class digit_grouping {
+ private:
+  thousands_sep_result<Char> sep_;
+
+  struct next_state {
+    std::string::const_iterator group;
+    int pos;
+  };
+  next_state initial_state() const { return {sep_.grouping.begin(), 0}; }
+
+  // Returns the next digit group separator position.
+  int next(next_state& state) const {
+    if (!sep_.thousands_sep) return max_value<int>();
+    if (state.group == sep_.grouping.end())
+      return state.pos += sep_.grouping.back();
+    if (*state.group <= 0 || *state.group == max_value<char>())
+      return max_value<int>();
+    state.pos += *state.group++;
+    return state.pos;
+  }
+
+ public:
+  explicit digit_grouping(locale_ref loc, bool localized = true) {
+    if (localized)
+      sep_ = thousands_sep<Char>(loc);
+    else
+      sep_.thousands_sep = Char();
+  }
+  explicit digit_grouping(thousands_sep_result<Char> sep) : sep_(sep) {}
+
+  Char separator() const { return sep_.thousands_sep; }
+
+  int count_separators(int num_digits) const {
+    int count = 0;
+    auto state = initial_state();
+    while (num_digits > next(state)) ++count;
+    return count;
+  }
+
+  // Applies grouping to digits and write the output to out.
+  template <typename Out, typename C>
+  Out apply(Out out, basic_string_view<C> digits) const {
+    auto num_digits = static_cast<int>(digits.size());
+    auto separators = basic_memory_buffer<int>();
+    separators.push_back(0);
+    auto state = initial_state();
+    while (int i = next(state)) {
+      if (i >= num_digits) break;
+      separators.push_back(i);
+    }
+    for (int i = 0, sep_index = static_cast<int>(separators.size() - 1);
+         i < num_digits; ++i) {
+      if (num_digits - i == separators[sep_index]) {
+        *out++ = separator();
+        --sep_index;
+      }
+      *out++ = static_cast<Char>(digits[to_unsigned(i)]);
+    }
+    return out;
+  }
+};
+
+template <typename OutputIt, typename UInt, typename Char>
+auto write_int_localized(OutputIt out, UInt value, unsigned prefix,
+                         const basic_format_specs<Char>& specs,
+                         const digit_grouping<Char>& grouping) -> OutputIt {
+  static_assert(std::is_same<uint64_or_128_t<UInt>, UInt>::value, "");
+  int num_digits = count_digits(value);
+  char digits[40];
+  format_decimal(digits, value, num_digits);
+  unsigned size = to_unsigned((prefix != 0 ? 1 : 0) + num_digits +
+                              grouping.count_separators(num_digits));
+  return write_padded<align::right>(
+      out, specs, size, size, [&](reserve_iterator<OutputIt> it) {
+        if (prefix != 0) {
+          char sign = static_cast<char>(prefix);
+          *it++ = static_cast<Char>(sign);
+        }
+        return grouping.apply(it, string_view(digits, to_unsigned(num_digits)));
+      });
+}
+
+template <typename OutputIt, typename UInt, typename Char>
+auto write_int_localized(OutputIt& out, UInt value, unsigned prefix,
+                         const basic_format_specs<Char>& specs, locale_ref loc)
+    -> bool {
+  auto grouping = digit_grouping<Char>(loc);
+  out = write_int_localized(out, value, prefix, specs, grouping);
+  return true;
+}
+
+FMT_CONSTEXPR inline void prefix_append(unsigned& prefix, unsigned value) {
+  prefix |= prefix != 0 ? value << 8 : value;
+  prefix += (1u + (value > 0xff ? 1 : 0)) << 24;
+}
+
+template <typename UInt> struct write_int_arg {
+  UInt abs_value;
+  unsigned prefix;
+};
+
+template <typename T>
+FMT_CONSTEXPR auto make_write_int_arg(T value, sign_t sign)
+    -> write_int_arg<uint32_or_64_or_128_t<T>> {
+  auto prefix = 0u;
+  auto abs_value = static_cast<uint32_or_64_or_128_t<T>>(value);
+  if (is_negative(value)) {
+    prefix = 0x01000000 | '-';
+    abs_value = 0 - abs_value;
+  } else {
+    constexpr const unsigned prefixes[4] = {0, 0, 0x1000000u | '+',
+                                            0x1000000u | ' '};
+    prefix = prefixes[sign];
+  }
+  return {abs_value, prefix};
+}
+
+template <typename Char, typename OutputIt, typename T>
+FMT_CONSTEXPR FMT_INLINE auto write_int(OutputIt out, write_int_arg<T> arg,
+                                        const basic_format_specs<Char>& specs,
+                                        locale_ref loc) -> OutputIt {
+  static_assert(std::is_same<T, uint32_or_64_or_128_t<T>>::value, "");
+  auto abs_value = arg.abs_value;
+  auto prefix = arg.prefix;
+  switch (specs.type) {
+  case presentation_type::none:
+  case presentation_type::dec: {
+    if (specs.localized &&
+        write_int_localized(out, static_cast<uint64_or_128_t<T>>(abs_value),
+                            prefix, specs, loc)) {
+      return out;
+    }
+    auto num_digits = count_digits(abs_value);
+    return write_int(
+        out, num_digits, prefix, specs, [=](reserve_iterator<OutputIt> it) {
+          return format_decimal<Char>(it, abs_value, num_digits).end;
+        });
+  }
+  case presentation_type::hex_lower:
+  case presentation_type::hex_upper: {
+    bool upper = specs.type == presentation_type::hex_upper;
+    if (specs.alt)
+      prefix_append(prefix, unsigned(upper ? 'X' : 'x') << 8 | '0');
+    int num_digits = count_digits<4>(abs_value);
+    return write_int(
+        out, num_digits, prefix, specs, [=](reserve_iterator<OutputIt> it) {
+          return format_uint<4, Char>(it, abs_value, num_digits, upper);
+        });
+  }
+  case presentation_type::bin_lower:
+  case presentation_type::bin_upper: {
+    bool upper = specs.type == presentation_type::bin_upper;
+    if (specs.alt)
+      prefix_append(prefix, unsigned(upper ? 'B' : 'b') << 8 | '0');
+    int num_digits = count_digits<1>(abs_value);
+    return write_int(out, num_digits, prefix, specs,
+                     [=](reserve_iterator<OutputIt> it) {
+                       return format_uint<1, Char>(it, abs_value, num_digits);
+                     });
+  }
+  case presentation_type::oct: {
+    int num_digits = count_digits<3>(abs_value);
+    // Octal prefix '0' is counted as a digit, so only add it if precision
+    // is not greater than the number of digits.
+    if (specs.alt && specs.precision <= num_digits && abs_value != 0)
+      prefix_append(prefix, '0');
+    return write_int(out, num_digits, prefix, specs,
+                     [=](reserve_iterator<OutputIt> it) {
+                       return format_uint<3, Char>(it, abs_value, num_digits);
+                     });
+  }
+  case presentation_type::chr:
+    return write_char(out, static_cast<Char>(abs_value), specs);
+  default:
+    throw_format_error("invalid type specifier");
+  }
+  return out;
+}
+template <typename Char, typename OutputIt, typename T>
+FMT_CONSTEXPR FMT_NOINLINE auto write_int_noinline(
+    OutputIt out, write_int_arg<T> arg, const basic_format_specs<Char>& specs,
+    locale_ref loc) -> OutputIt {
+  return write_int(out, arg, specs, loc);
+}
+template <typename Char, typename OutputIt, typename T,
+          FMT_ENABLE_IF(is_integral<T>::value &&
+                        !std::is_same<T, bool>::value &&
+                        std::is_same<OutputIt, buffer_appender<Char>>::value)>
+FMT_CONSTEXPR FMT_INLINE auto write(OutputIt out, T value,
+                                    const basic_format_specs<Char>& specs,
+                                    locale_ref loc) -> OutputIt {
+  return write_int_noinline(out, make_write_int_arg(value, specs.sign), specs,
+                            loc);
+}
+// An inlined version of write used in format string compilation.
+template <typename Char, typename OutputIt, typename T,
+          FMT_ENABLE_IF(is_integral<T>::value &&
+                        !std::is_same<T, bool>::value &&
+                        !std::is_same<OutputIt, buffer_appender<Char>>::value)>
+FMT_CONSTEXPR FMT_INLINE auto write(OutputIt out, T value,
+                                    const basic_format_specs<Char>& specs,
+                                    locale_ref loc) -> OutputIt {
+  return write_int(out, make_write_int_arg(value, specs.sign), specs, loc);
+}
+
+// An output iterator that counts the number of objects written to it and
+// discards them.
+class counting_iterator {
+ private:
+  size_t count_;
+
+ public:
+  using iterator_category = std::output_iterator_tag;
+  using difference_type = std::ptrdiff_t;
+  using pointer = void;
+  using reference = void;
+  FMT_UNCHECKED_ITERATOR(counting_iterator);
+
+  struct value_type {
+    template <typename T> FMT_CONSTEXPR void operator=(const T&) {}
+  };
+
+  FMT_CONSTEXPR counting_iterator() : count_(0) {}
+
+  FMT_CONSTEXPR size_t count() const { return count_; }
+
+  FMT_CONSTEXPR counting_iterator& operator++() {
+    ++count_;
+    return *this;
+  }
+  FMT_CONSTEXPR counting_iterator operator++(int) {
+    auto it = *this;
+    ++*this;
+    return it;
+  }
+
+  FMT_CONSTEXPR friend counting_iterator operator+(counting_iterator it,
+                                                   difference_type n) {
+    it.count_ += static_cast<size_t>(n);
+    return it;
+  }
+
+  FMT_CONSTEXPR value_type operator*() const { return {}; }
+};
+
+template <typename Char, typename OutputIt>
+FMT_CONSTEXPR auto write(OutputIt out, basic_string_view<Char> s,
+                         const basic_format_specs<Char>& specs) -> OutputIt {
+  auto data = s.data();
+  auto size = s.size();
+  if (specs.precision >= 0 && to_unsigned(specs.precision) < size)
+    size = code_point_index(s, to_unsigned(specs.precision));
+  bool is_debug = specs.type == presentation_type::debug;
+  size_t width = 0;
+  if (specs.width != 0) {
+    if (is_debug)
+      width = write_escaped_string(counting_iterator{}, s).count();
+    else
+      width = compute_width(basic_string_view<Char>(data, size));
+  }
+  return write_padded(out, specs, size, width,
+                      [=](reserve_iterator<OutputIt> it) {
+                        if (is_debug) return write_escaped_string(it, s);
+                        return copy_str<Char>(data, data + size, it);
+                      });
+}
+template <typename Char, typename OutputIt>
+FMT_CONSTEXPR auto write(OutputIt out,
+                         basic_string_view<type_identity_t<Char>> s,
+                         const basic_format_specs<Char>& specs, locale_ref)
+    -> OutputIt {
+  check_string_type_spec(specs.type);
+  return write(out, s, specs);
+}
+template <typename Char, typename OutputIt>
+FMT_CONSTEXPR auto write(OutputIt out, const Char* s,
+                         const basic_format_specs<Char>& specs, locale_ref)
+    -> OutputIt {
+  return check_cstring_type_spec(specs.type)
+             ? write(out, basic_string_view<Char>(s), specs, {})
+             : write_ptr<Char>(out, bit_cast<uintptr_t>(s), &specs);
+}
+
+template <typename Char, typename OutputIt, typename T,
+          FMT_ENABLE_IF(is_integral<T>::value &&
+                        !std::is_same<T, bool>::value &&
+                        !std::is_same<T, Char>::value)>
+FMT_CONSTEXPR auto write(OutputIt out, T value) -> OutputIt {
+  auto abs_value = static_cast<uint32_or_64_or_128_t<T>>(value);
+  bool negative = is_negative(value);
+  // Don't do -abs_value since it trips unsigned-integer-overflow sanitizer.
+  if (negative) abs_value = ~abs_value + 1;
+  int num_digits = count_digits(abs_value);
+  auto size = (negative ? 1 : 0) + static_cast<size_t>(num_digits);
+  auto it = reserve(out, size);
+  if (auto ptr = to_pointer<Char>(it, size)) {
+    if (negative) *ptr++ = static_cast<Char>('-');
+    format_decimal<Char>(ptr, abs_value, num_digits);
+    return out;
+  }
+  if (negative) *it++ = static_cast<Char>('-');
+  it = format_decimal<Char>(it, abs_value, num_digits).end;
+  return base_iterator(out, it);
+}
+
+template <typename Char, typename OutputIt>
+FMT_CONSTEXPR20 auto write_nonfinite(OutputIt out, bool isnan,
+                                     basic_format_specs<Char> specs,
+                                     const float_specs& fspecs) -> OutputIt {
+  auto str =
+      isnan ? (fspecs.upper ? "NAN" : "nan") : (fspecs.upper ? "INF" : "inf");
+  constexpr size_t str_size = 3;
+  auto sign = fspecs.sign;
+  auto size = str_size + (sign ? 1 : 0);
+  // Replace '0'-padding with space for non-finite values.
+  const bool is_zero_fill =
+      specs.fill.size() == 1 && *specs.fill.data() == static_cast<Char>('0');
+  if (is_zero_fill) specs.fill[0] = static_cast<Char>(' ');
+  return write_padded(out, specs, size, [=](reserve_iterator<OutputIt> it) {
+    if (sign) *it++ = detail::sign<Char>(sign);
+    return copy_str<Char>(str, str + str_size, it);
+  });
+}
+
+// A decimal floating-point number significand * pow(10, exp).
+struct big_decimal_fp {
+  const char* significand;
+  int significand_size;
+  int exponent;
+};
+
+constexpr auto get_significand_size(const big_decimal_fp& f) -> int {
+  return f.significand_size;
+}
+template <typename T>
+inline auto get_significand_size(const dragonbox::decimal_fp<T>& f) -> int {
+  return count_digits(f.significand);
+}
+
+template <typename Char, typename OutputIt>
+constexpr auto write_significand(OutputIt out, const char* significand,
+                                 int significand_size) -> OutputIt {
+  return copy_str<Char>(significand, significand + significand_size, out);
+}
+template <typename Char, typename OutputIt, typename UInt>
+inline auto write_significand(OutputIt out, UInt significand,
+                              int significand_size) -> OutputIt {
+  return format_decimal<Char>(out, significand, significand_size).end;
+}
+template <typename Char, typename OutputIt, typename T, typename Grouping>
+FMT_CONSTEXPR20 auto write_significand(OutputIt out, T significand,
+                                       int significand_size, int exponent,
+                                       const Grouping& grouping) -> OutputIt {
+  if (!grouping.separator()) {
+    out = write_significand<Char>(out, significand, significand_size);
+    return detail::fill_n(out, exponent, static_cast<Char>('0'));
+  }
+  auto buffer = memory_buffer();
+  write_significand<char>(appender(buffer), significand, significand_size);
+  detail::fill_n(appender(buffer), exponent, '0');
+  return grouping.apply(out, string_view(buffer.data(), buffer.size()));
+}
+
+template <typename Char, typename UInt,
+          FMT_ENABLE_IF(std::is_integral<UInt>::value)>
+inline auto write_significand(Char* out, UInt significand, int significand_size,
+                              int integral_size, Char decimal_point) -> Char* {
+  if (!decimal_point)
+    return format_decimal(out, significand, significand_size).end;
+  out += significand_size + 1;
+  Char* end = out;
+  int floating_size = significand_size - integral_size;
+  for (int i = floating_size / 2; i > 0; --i) {
+    out -= 2;
+    copy2(out, digits2(static_cast<std::size_t>(significand % 100)));
+    significand /= 100;
+  }
+  if (floating_size % 2 != 0) {
+    *--out = static_cast<Char>('0' + significand % 10);
+    significand /= 10;
+  }
+  *--out = decimal_point;
+  format_decimal(out - integral_size, significand, integral_size);
+  return end;
+}
+
+template <typename OutputIt, typename UInt, typename Char,
+          FMT_ENABLE_IF(!std::is_pointer<remove_cvref_t<OutputIt>>::value)>
+inline auto write_significand(OutputIt out, UInt significand,
+                              int significand_size, int integral_size,
+                              Char decimal_point) -> OutputIt {
+  // Buffer is large enough to hold digits (digits10 + 1) and a decimal point.
+  Char buffer[digits10<UInt>() + 2];
+  auto end = write_significand(buffer, significand, significand_size,
+                               integral_size, decimal_point);
+  return detail::copy_str_noinline<Char>(buffer, end, out);
+}
+
+template <typename OutputIt, typename Char>
+FMT_CONSTEXPR auto write_significand(OutputIt out, const char* significand,
+                                     int significand_size, int integral_size,
+                                     Char decimal_point) -> OutputIt {
+  out = detail::copy_str_noinline<Char>(significand,
+                                        significand + integral_size, out);
+  if (!decimal_point) return out;
+  *out++ = decimal_point;
+  return detail::copy_str_noinline<Char>(significand + integral_size,
+                                         significand + significand_size, out);
+}
+
+template <typename OutputIt, typename Char, typename T, typename Grouping>
+FMT_CONSTEXPR20 auto write_significand(OutputIt out, T significand,
+                                       int significand_size, int integral_size,
+                                       Char decimal_point,
+                                       const Grouping& grouping) -> OutputIt {
+  if (!grouping.separator()) {
+    return write_significand(out, significand, significand_size, integral_size,
+                             decimal_point);
+  }
+  auto buffer = basic_memory_buffer<Char>();
+  write_significand(buffer_appender<Char>(buffer), significand,
+                    significand_size, integral_size, decimal_point);
+  grouping.apply(
+      out, basic_string_view<Char>(buffer.data(), to_unsigned(integral_size)));
+  return detail::copy_str_noinline<Char>(buffer.data() + integral_size,
+                                         buffer.end(), out);
+}
+
+template <typename OutputIt, typename DecimalFP, typename Char,
+          typename Grouping = digit_grouping<Char>>
+FMT_CONSTEXPR20 auto do_write_float(OutputIt out, const DecimalFP& f,
+                                    const basic_format_specs<Char>& specs,
+                                    float_specs fspecs, locale_ref loc)
+    -> OutputIt {
+  auto significand = f.significand;
+  int significand_size = get_significand_size(f);
+  const Char zero = static_cast<Char>('0');
+  auto sign = fspecs.sign;
+  size_t size = to_unsigned(significand_size) + (sign ? 1 : 0);
+  using iterator = reserve_iterator<OutputIt>;
+
+  Char decimal_point =
+      fspecs.locale ? detail::decimal_point<Char>(loc) : static_cast<Char>('.');
+
+  int output_exp = f.exponent + significand_size - 1;
+  auto use_exp_format = [=]() {
+    if (fspecs.format == float_format::exp) return true;
+    if (fspecs.format != float_format::general) return false;
+    // Use the fixed notation if the exponent is in [exp_lower, exp_upper),
+    // e.g. 0.0001 instead of 1e-04. Otherwise use the exponent notation.
+    const int exp_lower = -4, exp_upper = 16;
+    return output_exp < exp_lower ||
+           output_exp >= (fspecs.precision > 0 ? fspecs.precision : exp_upper);
+  };
+  if (use_exp_format()) {
+    int num_zeros = 0;
+    if (fspecs.showpoint) {
+      num_zeros = fspecs.precision - significand_size;
+      if (num_zeros < 0) num_zeros = 0;
+      size += to_unsigned(num_zeros);
+    } else if (significand_size == 1) {
+      decimal_point = Char();
+    }
+    auto abs_output_exp = output_exp >= 0 ? output_exp : -output_exp;
+    int exp_digits = 2;
+    if (abs_output_exp >= 100) exp_digits = abs_output_exp >= 1000 ? 4 : 3;
+
+    size += to_unsigned((decimal_point ? 1 : 0) + 2 + exp_digits);
+    char exp_char = fspecs.upper ? 'E' : 'e';
+    auto write = [=](iterator it) {
+      if (sign) *it++ = detail::sign<Char>(sign);
+      // Insert a decimal point after the first digit and add an exponent.
+      it = write_significand(it, significand, significand_size, 1,
+                             decimal_point);
+      if (num_zeros > 0) it = detail::fill_n(it, num_zeros, zero);
+      *it++ = static_cast<Char>(exp_char);
+      return write_exponent<Char>(output_exp, it);
+    };
+    return specs.width > 0 ? write_padded<align::right>(out, specs, size, write)
+                           : base_iterator(out, write(reserve(out, size)));
+  }
+
+  int exp = f.exponent + significand_size;
+  if (f.exponent >= 0) {
+    // 1234e5 -> 123400000[.0+]
+    size += to_unsigned(f.exponent);
+    int num_zeros = fspecs.precision - exp;
+    abort_fuzzing_if(num_zeros > 5000);
+    if (fspecs.showpoint) {
+      ++size;
+      if (num_zeros <= 0 && fspecs.format != float_format::fixed) num_zeros = 1;
+      if (num_zeros > 0) size += to_unsigned(num_zeros);
+    }
+    auto grouping = Grouping(loc, fspecs.locale);
+    size += to_unsigned(grouping.count_separators(exp));
+    return write_padded<align::right>(out, specs, size, [&](iterator it) {
+      if (sign) *it++ = detail::sign<Char>(sign);
+      it = write_significand<Char>(it, significand, significand_size,
+                                   f.exponent, grouping);
+      if (!fspecs.showpoint) return it;
+      *it++ = decimal_point;
+      return num_zeros > 0 ? detail::fill_n(it, num_zeros, zero) : it;
+    });
+  } else if (exp > 0) {
+    // 1234e-2 -> 12.34[0+]
+    int num_zeros = fspecs.showpoint ? fspecs.precision - significand_size : 0;
+    size += 1 + to_unsigned(num_zeros > 0 ? num_zeros : 0);
+    auto grouping = Grouping(loc, fspecs.locale);
+    size += to_unsigned(grouping.count_separators(significand_size));
+    return write_padded<align::right>(out, specs, size, [&](iterator it) {
+      if (sign) *it++ = detail::sign<Char>(sign);
+      it = write_significand(it, significand, significand_size, exp,
+                             decimal_point, grouping);
+      return num_zeros > 0 ? detail::fill_n(it, num_zeros, zero) : it;
+    });
+  }
+  // 1234e-6 -> 0.001234
+  int num_zeros = -exp;
+  if (significand_size == 0 && fspecs.precision >= 0 &&
+      fspecs.precision < num_zeros) {
+    num_zeros = fspecs.precision;
+  }
+  bool pointy = num_zeros != 0 || significand_size != 0 || fspecs.showpoint;
+  size += 1 + (pointy ? 1 : 0) + to_unsigned(num_zeros);
+  return write_padded<align::right>(out, specs, size, [&](iterator it) {
+    if (sign) *it++ = detail::sign<Char>(sign);
+    *it++ = zero;
+    if (!pointy) return it;
+    *it++ = decimal_point;
+    it = detail::fill_n(it, num_zeros, zero);
+    return write_significand<Char>(it, significand, significand_size);
+  });
+}
+
+template <typename Char> class fallback_digit_grouping {
+ public:
+  constexpr fallback_digit_grouping(locale_ref, bool) {}
+
+  constexpr Char separator() const { return Char(); }
+
+  constexpr int count_separators(int) const { return 0; }
+
+  template <typename Out, typename C>
+  constexpr Out apply(Out out, basic_string_view<C>) const {
+    return out;
+  }
+};
+
+template <typename OutputIt, typename DecimalFP, typename Char>
+FMT_CONSTEXPR20 auto write_float(OutputIt out, const DecimalFP& f,
+                                 const basic_format_specs<Char>& specs,
+                                 float_specs fspecs, locale_ref loc)
+    -> OutputIt {
+  if (is_constant_evaluated()) {
+    return do_write_float<OutputIt, DecimalFP, Char,
+                          fallback_digit_grouping<Char>>(out, f, specs, fspecs,
+                                                         loc);
+  } else {
+    return do_write_float(out, f, specs, fspecs, loc);
+  }
+}
+
+template <typename T> constexpr bool isnan(T value) {
+  return !(value >= value);  // std::isnan doesn't support __float128.
+}
+
+template <typename T, typename Enable = void>
+struct has_isfinite : std::false_type {};
+
+template <typename T>
+struct has_isfinite<T, enable_if_t<sizeof(std::isfinite(T())) != 0>>
+    : std::true_type {};
+
+template <typename T, FMT_ENABLE_IF(std::is_floating_point<T>::value&&
+                                        has_isfinite<T>::value)>
+FMT_CONSTEXPR20 bool isfinite(T value) {
+  constexpr T inf = T(std::numeric_limits<double>::infinity());
+  if (is_constant_evaluated())
+    return !detail::isnan(value) && value != inf && value != -inf;
+  return std::isfinite(value);
+}
+template <typename T, FMT_ENABLE_IF(!has_isfinite<T>::value)>
+FMT_CONSTEXPR bool isfinite(T value) {
+  T inf = T(std::numeric_limits<double>::infinity());
+  // std::isfinite doesn't support __float128.
+  return !detail::isnan(value) && value != inf && value != -inf;
+}
+
+template <typename T, FMT_ENABLE_IF(is_floating_point<T>::value)>
+FMT_INLINE FMT_CONSTEXPR bool signbit(T value) {
+  if (is_constant_evaluated()) {
+#ifdef __cpp_if_constexpr
+    if constexpr (std::numeric_limits<double>::is_iec559) {
+      auto bits = detail::bit_cast<uint64_t>(static_cast<double>(value));
+      return (bits >> (num_bits<uint64_t>() - 1)) != 0;
+    }
+#endif
+  }
+  return std::signbit(static_cast<double>(value));
+}
+
+enum class round_direction { unknown, up, down };
+
+// Given the divisor (normally a power of 10), the remainder = v % divisor for
+// some number v and the error, returns whether v should be rounded up, down, or
+// whether the rounding direction can't be determined due to error.
+// error should be less than divisor / 2.
+FMT_CONSTEXPR inline round_direction get_round_direction(uint64_t divisor,
+                                                         uint64_t remainder,
+                                                         uint64_t error) {
+  FMT_ASSERT(remainder < divisor, "");  // divisor - remainder won't overflow.
+  FMT_ASSERT(error < divisor, "");      // divisor - error won't overflow.
+  FMT_ASSERT(error < divisor - error, "");  // error * 2 won't overflow.
+  // Round down if (remainder + error) * 2 <= divisor.
+  if (remainder <= divisor - remainder && error * 2 <= divisor - remainder * 2)
+    return round_direction::down;
+  // Round up if (remainder - error) * 2 >= divisor.
+  if (remainder >= error &&
+      remainder - error >= divisor - (remainder - error)) {
+    return round_direction::up;
+  }
+  return round_direction::unknown;
+}
+
+namespace digits {
+enum result {
+  more,  // Generate more digits.
+  done,  // Done generating digits.
+  error  // Digit generation cancelled due to an error.
+};
+}
+
+struct gen_digits_handler {
+  char* buf;
+  int size;
+  int precision;
+  int exp10;
+  bool fixed;
+
+  FMT_CONSTEXPR digits::result on_digit(char digit, uint64_t divisor,
+                                        uint64_t remainder, uint64_t error,
+                                        bool integral) {
+    FMT_ASSERT(remainder < divisor, "");
+    buf[size++] = digit;
+    if (!integral && error >= remainder) return digits::error;
+    if (size < precision) return digits::more;
+    if (!integral) {
+      // Check if error * 2 < divisor with overflow prevention.
+      // The check is not needed for the integral part because error = 1
+      // and divisor > (1 << 32) there.
+      if (error >= divisor || error >= divisor - error) return digits::error;
+    } else {
+      FMT_ASSERT(error == 1 && divisor > 2, "");
+    }
+    auto dir = get_round_direction(divisor, remainder, error);
+    if (dir != round_direction::up)
+      return dir == round_direction::down ? digits::done : digits::error;
+    ++buf[size - 1];
+    for (int i = size - 1; i > 0 && buf[i] > '9'; --i) {
+      buf[i] = '0';
+      ++buf[i - 1];
+    }
+    if (buf[0] > '9') {
+      buf[0] = '1';
+      if (fixed)
+        buf[size++] = '0';
+      else
+        ++exp10;
+    }
+    return digits::done;
+  }
+};
+
+inline FMT_CONSTEXPR20 void adjust_precision(int& precision, int exp10) {
+  // Adjust fixed precision by exponent because it is relative to decimal
+  // point.
+  if (exp10 > 0 && precision > max_value<int>() - exp10)
+    FMT_THROW(format_error("number is too big"));
+  precision += exp10;
+}
+
+// Generates output using the Grisu digit-gen algorithm.
+// error: the size of the region (lower, upper) outside of which numbers
+// definitely do not round to value (Delta in Grisu3).
+FMT_INLINE FMT_CONSTEXPR20 auto grisu_gen_digits(fp value, uint64_t error,
+                                                 int& exp,
+                                                 gen_digits_handler& handler)
+    -> digits::result {
+  const fp one(1ULL << -value.e, value.e);
+  // The integral part of scaled value (p1 in Grisu) = value / one. It cannot be
+  // zero because it contains a product of two 64-bit numbers with MSB set (due
+  // to normalization) - 1, shifted right by at most 60 bits.
+  auto integral = static_cast<uint32_t>(value.f >> -one.e);
+  FMT_ASSERT(integral != 0, "");
+  FMT_ASSERT(integral == value.f >> -one.e, "");
+  // The fractional part of scaled value (p2 in Grisu) c = value % one.
+  uint64_t fractional = value.f & (one.f - 1);
+  exp = count_digits(integral);  // kappa in Grisu.
+  // Non-fixed formats require at least one digit and no precision adjustment.
+  if (handler.fixed) {
+    adjust_precision(handler.precision, exp + handler.exp10);
+    // Check if precision is satisfied just by leading zeros, e.g.
+    // format("{:.2f}", 0.001) gives "0.00" without generating any digits.
+    if (handler.precision <= 0) {
+      if (handler.precision < 0) return digits::done;
+      // Divide by 10 to prevent overflow.
+      uint64_t divisor = data::power_of_10_64[exp - 1] << -one.e;
+      auto dir = get_round_direction(divisor, value.f / 10, error * 10);
+      if (dir == round_direction::unknown) return digits::error;
+      handler.buf[handler.size++] = dir == round_direction::up ? '1' : '0';
+      return digits::done;
+    }
+  }
+  // Generate digits for the integral part. This can produce up to 10 digits.
+  do {
+    uint32_t digit = 0;
+    auto divmod_integral = [&](uint32_t divisor) {
+      digit = integral / divisor;
+      integral %= divisor;
+    };
+    // This optimization by Milo Yip reduces the number of integer divisions by
+    // one per iteration.
+    switch (exp) {
+    case 10:
+      divmod_integral(1000000000);
+      break;
+    case 9:
+      divmod_integral(100000000);
+      break;
+    case 8:
+      divmod_integral(10000000);
+      break;
+    case 7:
+      divmod_integral(1000000);
+      break;
+    case 6:
+      divmod_integral(100000);
+      break;
+    case 5:
+      divmod_integral(10000);
+      break;
+    case 4:
+      divmod_integral(1000);
+      break;
+    case 3:
+      divmod_integral(100);
+      break;
+    case 2:
+      divmod_integral(10);
+      break;
+    case 1:
+      digit = integral;
+      integral = 0;
+      break;
+    default:
+      FMT_ASSERT(false, "invalid number of digits");
+    }
+    --exp;
+    auto remainder = (static_cast<uint64_t>(integral) << -one.e) + fractional;
+    auto result = handler.on_digit(static_cast<char>('0' + digit),
+                                   data::power_of_10_64[exp] << -one.e,
+                                   remainder, error, true);
+    if (result != digits::more) return result;
+  } while (exp > 0);
+  // Generate digits for the fractional part.
+  for (;;) {
+    fractional *= 10;
+    error *= 10;
+    char digit = static_cast<char>('0' + (fractional >> -one.e));
+    fractional &= one.f - 1;
+    --exp;
+    auto result = handler.on_digit(digit, one.f, fractional, error, false);
+    if (result != digits::more) return result;
+  }
+}
+
+class bigint {
+ private:
+  // A bigint is stored as an array of bigits (big digits), with bigit at index
+  // 0 being the least significant one.
+  using bigit = uint32_t;
+  using double_bigit = uint64_t;
+  enum { bigits_capacity = 32 };
+  basic_memory_buffer<bigit, bigits_capacity> bigits_;
+  int exp_;
+
+  FMT_CONSTEXPR20 bigit operator[](int index) const {
+    return bigits_[to_unsigned(index)];
+  }
+  FMT_CONSTEXPR20 bigit& operator[](int index) {
+    return bigits_[to_unsigned(index)];
+  }
+
+  static constexpr const int bigit_bits = num_bits<bigit>();
+
+  friend struct formatter<bigint>;
+
+  FMT_CONSTEXPR20 void subtract_bigits(int index, bigit other, bigit& borrow) {
+    auto result = static_cast<double_bigit>((*this)[index]) - other - borrow;
+    (*this)[index] = static_cast<bigit>(result);
+    borrow = static_cast<bigit>(result >> (bigit_bits * 2 - 1));
+  }
+
+  FMT_CONSTEXPR20 void remove_leading_zeros() {
+    int num_bigits = static_cast<int>(bigits_.size()) - 1;
+    while (num_bigits > 0 && (*this)[num_bigits] == 0) --num_bigits;
+    bigits_.resize(to_unsigned(num_bigits + 1));
+  }
+
+  // Computes *this -= other assuming aligned bigints and *this >= other.
+  FMT_CONSTEXPR20 void subtract_aligned(const bigint& other) {
+    FMT_ASSERT(other.exp_ >= exp_, "unaligned bigints");
+    FMT_ASSERT(compare(*this, other) >= 0, "");
+    bigit borrow = 0;
+    int i = other.exp_ - exp_;
+    for (size_t j = 0, n = other.bigits_.size(); j != n; ++i, ++j)
+      subtract_bigits(i, other.bigits_[j], borrow);
+    while (borrow > 0) subtract_bigits(i, 0, borrow);
+    remove_leading_zeros();
+  }
+
+  FMT_CONSTEXPR20 void multiply(uint32_t value) {
+    const double_bigit wide_value = value;
+    bigit carry = 0;
+    for (size_t i = 0, n = bigits_.size(); i < n; ++i) {
+      double_bigit result = bigits_[i] * wide_value + carry;
+      bigits_[i] = static_cast<bigit>(result);
+      carry = static_cast<bigit>(result >> bigit_bits);
+    }
+    if (carry != 0) bigits_.push_back(carry);
+  }
+
+  template <typename UInt, FMT_ENABLE_IF(std::is_same<UInt, uint64_t>::value ||
+                                         std::is_same<UInt, uint128_t>::value)>
+  FMT_CONSTEXPR20 void multiply(UInt value) {
+    using half_uint =
+        conditional_t<std::is_same<UInt, uint128_t>::value, uint64_t, uint32_t>;
+    const int shift = num_bits<half_uint>() - bigit_bits;
+    const UInt lower = static_cast<half_uint>(value);
+    const UInt upper = value >> num_bits<half_uint>();
+    UInt carry = 0;
+    for (size_t i = 0, n = bigits_.size(); i < n; ++i) {
+      UInt result = lower * bigits_[i] + static_cast<bigit>(carry);
+      carry = (upper * bigits_[i] << shift) + (result >> bigit_bits) +
+              (carry >> bigit_bits);
+      bigits_[i] = static_cast<bigit>(result);
+    }
+    while (carry != 0) {
+      bigits_.push_back(static_cast<bigit>(carry));
+      carry >>= bigit_bits;
+    }
+  }
+
+  template <typename UInt, FMT_ENABLE_IF(std::is_same<UInt, uint64_t>::value ||
+                                         std::is_same<UInt, uint128_t>::value)>
+  FMT_CONSTEXPR20 void assign(UInt n) {
+    size_t num_bigits = 0;
+    do {
+      bigits_[num_bigits++] = static_cast<bigit>(n);
+      n >>= bigit_bits;
+    } while (n != 0);
+    bigits_.resize(num_bigits);
+    exp_ = 0;
+  }
+
+ public:
+  FMT_CONSTEXPR20 bigint() : exp_(0) {}
+  explicit bigint(uint64_t n) { assign(n); }
+
+  bigint(const bigint&) = delete;
+  void operator=(const bigint&) = delete;
+
+  FMT_CONSTEXPR20 void assign(const bigint& other) {
+    auto size = other.bigits_.size();
+    bigits_.resize(size);
+    auto data = other.bigits_.data();
+    std::copy(data, data + size, make_checked(bigits_.data(), size));
+    exp_ = other.exp_;
+  }
+
+  template <typename Int> FMT_CONSTEXPR20 void operator=(Int n) {
+    FMT_ASSERT(n > 0, "");
+    assign(uint64_or_128_t<Int>(n));
+  }
+
+  FMT_CONSTEXPR20 int num_bigits() const {
+    return static_cast<int>(bigits_.size()) + exp_;
+  }
+
+  FMT_NOINLINE FMT_CONSTEXPR20 bigint& operator<<=(int shift) {
+    FMT_ASSERT(shift >= 0, "");
+    exp_ += shift / bigit_bits;
+    shift %= bigit_bits;
+    if (shift == 0) return *this;
+    bigit carry = 0;
+    for (size_t i = 0, n = bigits_.size(); i < n; ++i) {
+      bigit c = bigits_[i] >> (bigit_bits - shift);
+      bigits_[i] = (bigits_[i] << shift) + carry;
+      carry = c;
+    }
+    if (carry != 0) bigits_.push_back(carry);
+    return *this;
+  }
+
+  template <typename Int> FMT_CONSTEXPR20 bigint& operator*=(Int value) {
+    FMT_ASSERT(value > 0, "");
+    multiply(uint32_or_64_or_128_t<Int>(value));
+    return *this;
+  }
+
+  friend FMT_CONSTEXPR20 int compare(const bigint& lhs, const bigint& rhs) {
+    int num_lhs_bigits = lhs.num_bigits(), num_rhs_bigits = rhs.num_bigits();
+    if (num_lhs_bigits != num_rhs_bigits)
+      return num_lhs_bigits > num_rhs_bigits ? 1 : -1;
+    int i = static_cast<int>(lhs.bigits_.size()) - 1;
+    int j = static_cast<int>(rhs.bigits_.size()) - 1;
+    int end = i - j;
+    if (end < 0) end = 0;
+    for (; i >= end; --i, --j) {
+      bigit lhs_bigit = lhs[i], rhs_bigit = rhs[j];
+      if (lhs_bigit != rhs_bigit) return lhs_bigit > rhs_bigit ? 1 : -1;
+    }
+    if (i != j) return i > j ? 1 : -1;
+    return 0;
+  }
+
+  // Returns compare(lhs1 + lhs2, rhs).
+  friend FMT_CONSTEXPR20 int add_compare(const bigint& lhs1, const bigint& lhs2,
+                                         const bigint& rhs) {
+    auto minimum = [](int a, int b) { return a < b ? a : b; };
+    auto maximum = [](int a, int b) { return a > b ? a : b; };
+    int max_lhs_bigits = maximum(lhs1.num_bigits(), lhs2.num_bigits());
+    int num_rhs_bigits = rhs.num_bigits();
+    if (max_lhs_bigits + 1 < num_rhs_bigits) return -1;
+    if (max_lhs_bigits > num_rhs_bigits) return 1;
+    auto get_bigit = [](const bigint& n, int i) -> bigit {
+      return i >= n.exp_ && i < n.num_bigits() ? n[i - n.exp_] : 0;
+    };
+    double_bigit borrow = 0;
+    int min_exp = minimum(minimum(lhs1.exp_, lhs2.exp_), rhs.exp_);
+    for (int i = num_rhs_bigits - 1; i >= min_exp; --i) {
+      double_bigit sum =
+          static_cast<double_bigit>(get_bigit(lhs1, i)) + get_bigit(lhs2, i);
+      bigit rhs_bigit = get_bigit(rhs, i);
+      if (sum > rhs_bigit + borrow) return 1;
+      borrow = rhs_bigit + borrow - sum;
+      if (borrow > 1) return -1;
+      borrow <<= bigit_bits;
+    }
+    return borrow != 0 ? -1 : 0;
+  }
+
+  // Assigns pow(10, exp) to this bigint.
+  FMT_CONSTEXPR20 void assign_pow10(int exp) {
+    FMT_ASSERT(exp >= 0, "");
+    if (exp == 0) return *this = 1;
+    // Find the top bit.
+    int bitmask = 1;
+    while (exp >= bitmask) bitmask <<= 1;
+    bitmask >>= 1;
+    // pow(10, exp) = pow(5, exp) * pow(2, exp). First compute pow(5, exp) by
+    // repeated squaring and multiplication.
+    *this = 5;
+    bitmask >>= 1;
+    while (bitmask != 0) {
+      square();
+      if ((exp & bitmask) != 0) *this *= 5;
+      bitmask >>= 1;
+    }
+    *this <<= exp;  // Multiply by pow(2, exp) by shifting.
+  }
+
+  FMT_CONSTEXPR20 void square() {
+    int num_bigits = static_cast<int>(bigits_.size());
+    int num_result_bigits = 2 * num_bigits;
+    basic_memory_buffer<bigit, bigits_capacity> n(std::move(bigits_));
+    bigits_.resize(to_unsigned(num_result_bigits));
+    auto sum = uint128_t();
+    for (int bigit_index = 0; bigit_index < num_bigits; ++bigit_index) {
+      // Compute bigit at position bigit_index of the result by adding
+      // cross-product terms n[i] * n[j] such that i + j == bigit_index.
+      for (int i = 0, j = bigit_index; j >= 0; ++i, --j) {
+        // Most terms are multiplied twice which can be optimized in the future.
+        sum += static_cast<double_bigit>(n[i]) * n[j];
+      }
+      (*this)[bigit_index] = static_cast<bigit>(sum);
+      sum >>= num_bits<bigit>();  // Compute the carry.
+    }
+    // Do the same for the top half.
+    for (int bigit_index = num_bigits; bigit_index < num_result_bigits;
+         ++bigit_index) {
+      for (int j = num_bigits - 1, i = bigit_index - j; i < num_bigits;)
+        sum += static_cast<double_bigit>(n[i++]) * n[j--];
+      (*this)[bigit_index] = static_cast<bigit>(sum);
+      sum >>= num_bits<bigit>();
+    }
+    remove_leading_zeros();
+    exp_ *= 2;
+  }
+
+  // If this bigint has a bigger exponent than other, adds trailing zero to make
+  // exponents equal. This simplifies some operations such as subtraction.
+  FMT_CONSTEXPR20 void align(const bigint& other) {
+    int exp_difference = exp_ - other.exp_;
+    if (exp_difference <= 0) return;
+    int num_bigits = static_cast<int>(bigits_.size());
+    bigits_.resize(to_unsigned(num_bigits + exp_difference));
+    for (int i = num_bigits - 1, j = i + exp_difference; i >= 0; --i, --j)
+      bigits_[j] = bigits_[i];
+    std::uninitialized_fill_n(bigits_.data(), exp_difference, 0);
+    exp_ -= exp_difference;
+  }
+
+  // Divides this bignum by divisor, assigning the remainder to this and
+  // returning the quotient.
+  FMT_CONSTEXPR20 int divmod_assign(const bigint& divisor) {
+    FMT_ASSERT(this != &divisor, "");
+    if (compare(*this, divisor) < 0) return 0;
+    FMT_ASSERT(divisor.bigits_[divisor.bigits_.size() - 1u] != 0, "");
+    align(divisor);
+    int quotient = 0;
+    do {
+      subtract_aligned(divisor);
+      ++quotient;
+    } while (compare(*this, divisor) >= 0);
+    return quotient;
+  }
+};
+
+// format_dragon flags.
+enum dragon {
+  predecessor_closer = 1,
+  fixup = 2,  // Run fixup to correct exp10 which can be off by one.
+  fixed = 4,
+};
+
+// Formats a floating-point number using a variation of the Fixed-Precision
+// Positive Floating-Point Printout ((FPP)^2) algorithm by Steele & White:
+// https://fmt.dev/papers/p372-steele.pdf.
+FMT_CONSTEXPR20 inline void format_dragon(basic_fp<uint128_t> value,
+                                          unsigned flags, int num_digits,
+                                          buffer<char>& buf, int& exp10) {
+  bigint numerator;    // 2 * R in (FPP)^2.
+  bigint denominator;  // 2 * S in (FPP)^2.
+  // lower and upper are differences between value and corresponding boundaries.
+  bigint lower;             // (M^- in (FPP)^2).
+  bigint upper_store;       // upper's value if different from lower.
+  bigint* upper = nullptr;  // (M^+ in (FPP)^2).
+  // Shift numerator and denominator by an extra bit or two (if lower boundary
+  // is closer) to make lower and upper integers. This eliminates multiplication
+  // by 2 during later computations.
+  bool is_predecessor_closer = (flags & dragon::predecessor_closer) != 0;
+  int shift = is_predecessor_closer ? 2 : 1;
+  if (value.e >= 0) {
+    numerator = value.f;
+    numerator <<= value.e + shift;
+    lower = 1;
+    lower <<= value.e;
+    if (is_predecessor_closer) {
+      upper_store = 1;
+      upper_store <<= value.e + 1;
+      upper = &upper_store;
+    }
+    denominator.assign_pow10(exp10);
+    denominator <<= shift;
+  } else if (exp10 < 0) {
+    numerator.assign_pow10(-exp10);
+    lower.assign(numerator);
+    if (is_predecessor_closer) {
+      upper_store.assign(numerator);
+      upper_store <<= 1;
+      upper = &upper_store;
+    }
+    numerator *= value.f;
+    numerator <<= shift;
+    denominator = 1;
+    denominator <<= shift - value.e;
+  } else {
+    numerator = value.f;
+    numerator <<= shift;
+    denominator.assign_pow10(exp10);
+    denominator <<= shift - value.e;
+    lower = 1;
+    if (is_predecessor_closer) {
+      upper_store = 1ULL << 1;
+      upper = &upper_store;
+    }
+  }
+  int even = static_cast<int>((value.f & 1) == 0);
+  if (!upper) upper = &lower;
+  if ((flags & dragon::fixup) != 0) {
+    if (add_compare(numerator, *upper, denominator) + even <= 0) {
+      --exp10;
+      numerator *= 10;
+      if (num_digits < 0) {
+        lower *= 10;
+        if (upper != &lower) *upper *= 10;
+      }
+    }
+    if ((flags & dragon::fixed) != 0) adjust_precision(num_digits, exp10 + 1);
+  }
+  // Invariant: value == (numerator / denominator) * pow(10, exp10).
+  if (num_digits < 0) {
+    // Generate the shortest representation.
+    num_digits = 0;
+    char* data = buf.data();
+    for (;;) {
+      int digit = numerator.divmod_assign(denominator);
+      bool low = compare(numerator, lower) - even < 0;  // numerator <[=] lower.
+      // numerator + upper >[=] pow10:
+      bool high = add_compare(numerator, *upper, denominator) + even > 0;
+      data[num_digits++] = static_cast<char>('0' + digit);
+      if (low || high) {
+        if (!low) {
+          ++data[num_digits - 1];
+        } else if (high) {
+          int result = add_compare(numerator, numerator, denominator);
+          // Round half to even.
+          if (result > 0 || (result == 0 && (digit % 2) != 0))
+            ++data[num_digits - 1];
+        }
+        buf.try_resize(to_unsigned(num_digits));
+        exp10 -= num_digits - 1;
+        return;
+      }
+      numerator *= 10;
+      lower *= 10;
+      if (upper != &lower) *upper *= 10;
+    }
+  }
+  // Generate the given number of digits.
+  exp10 -= num_digits - 1;
+  if (num_digits == 0) {
+    denominator *= 10;
+    auto digit = add_compare(numerator, numerator, denominator) > 0 ? '1' : '0';
+    buf.push_back(digit);
+    return;
+  }
+  buf.try_resize(to_unsigned(num_digits));
+  for (int i = 0; i < num_digits - 1; ++i) {
+    int digit = numerator.divmod_assign(denominator);
+    buf[i] = static_cast<char>('0' + digit);
+    numerator *= 10;
+  }
+  int digit = numerator.divmod_assign(denominator);
+  auto result = add_compare(numerator, numerator, denominator);
+  if (result > 0 || (result == 0 && (digit % 2) != 0)) {
+    if (digit == 9) {
+      const auto overflow = '0' + 10;
+      buf[num_digits - 1] = overflow;
+      // Propagate the carry.
+      for (int i = num_digits - 1; i > 0 && buf[i] == overflow; --i) {
+        buf[i] = '0';
+        ++buf[i - 1];
+      }
+      if (buf[0] == overflow) {
+        buf[0] = '1';
+        ++exp10;
+      }
+      return;
+    }
+    ++digit;
+  }
+  buf[num_digits - 1] = static_cast<char>('0' + digit);
+}
+
+template <typename Float>
+FMT_CONSTEXPR20 auto format_float(Float value, int precision, float_specs specs,
+                                  buffer<char>& buf) -> int {
+  // float is passed as double to reduce the number of instantiations.
+  static_assert(!std::is_same<Float, float>::value, "");
+  FMT_ASSERT(value >= 0, "value is negative");
+  auto converted_value = convert_float(value);
+
+  const bool fixed = specs.format == float_format::fixed;
+  if (value <= 0) {  // <= instead of == to silence a warning.
+    if (precision <= 0 || !fixed) {
+      buf.push_back('0');
+      return 0;
+    }
+    buf.try_resize(to_unsigned(precision));
+    fill_n(buf.data(), precision, '0');
+    return -precision;
+  }
+
+  int exp = 0;
+  bool use_dragon = true;
+  unsigned dragon_flags = 0;
+  if (!is_fast_float<Float>()) {
+    const auto inv_log2_10 = 0.3010299956639812;  // 1 / log2(10)
+    using info = dragonbox::float_info<decltype(converted_value)>;
+    const auto f = basic_fp<typename info::carrier_uint>(converted_value);
+    // Compute exp, an approximate power of 10, such that
+    //   10^(exp - 1) <= value < 10^exp or 10^exp <= value < 10^(exp + 1).
+    // This is based on log10(value) == log2(value) / log2(10) and approximation
+    // of log2(value) by e + num_fraction_bits idea from double-conversion.
+    exp = static_cast<int>(
+        std::ceil((f.e + count_digits<1>(f.f) - 1) * inv_log2_10 - 1e-10));
+    dragon_flags = dragon::fixup;
+  } else if (!is_constant_evaluated() && precision < 0) {
+    // Use Dragonbox for the shortest format.
+    if (specs.binary32) {
+      auto dec = dragonbox::to_decimal(static_cast<float>(value));
+      write<char>(buffer_appender<char>(buf), dec.significand);
+      return dec.exponent;
+    }
+    auto dec = dragonbox::to_decimal(static_cast<double>(value));
+    write<char>(buffer_appender<char>(buf), dec.significand);
+    return dec.exponent;
+  } else {
+    // Use Grisu + Dragon4 for the given precision:
+    // https://www.cs.tufts.edu/~nr/cs257/archive/florian-loitsch/printf.pdf.
+    const int min_exp = -60;  // alpha in Grisu.
+    int cached_exp10 = 0;     // K in Grisu.
+    fp normalized = normalize(fp(converted_value));
+    const auto cached_pow = get_cached_power(
+        min_exp - (normalized.e + fp::num_significand_bits), cached_exp10);
+    normalized = normalized * cached_pow;
+    gen_digits_handler handler{buf.data(), 0, precision, -cached_exp10, fixed};
+    if (grisu_gen_digits(normalized, 1, exp, handler) != digits::error &&
+        !is_constant_evaluated()) {
+      exp += handler.exp10;
+      buf.try_resize(to_unsigned(handler.size));
+      use_dragon = false;
+    } else {
+      exp += handler.size - cached_exp10 - 1;
+      precision = handler.precision;
+    }
+  }
+  if (use_dragon) {
+    auto f = basic_fp<uint128_t>();
+    bool is_predecessor_closer = specs.binary32
+                                     ? f.assign(static_cast<float>(value))
+                                     : f.assign(converted_value);
+    if (is_predecessor_closer) dragon_flags |= dragon::predecessor_closer;
+    if (fixed) dragon_flags |= dragon::fixed;
+    // Limit precision to the maximum possible number of significant digits in
+    // an IEEE754 double because we don't need to generate zeros.
+    const int max_double_digits = 767;
+    if (precision > max_double_digits) precision = max_double_digits;
+    format_dragon(f, dragon_flags, precision, buf, exp);
+  }
+  if (!fixed && !specs.showpoint) {
+    // Remove trailing zeros.
+    auto num_digits = buf.size();
+    while (num_digits > 0 && buf[num_digits - 1] == '0') {
+      --num_digits;
+      ++exp;
+    }
+    buf.try_resize(num_digits);
+  }
+  return exp;
+}
+
+template <typename Char, typename OutputIt, typename T,
+          FMT_ENABLE_IF(is_floating_point<T>::value)>
+FMT_CONSTEXPR20 auto write(OutputIt out, T value,
+                           basic_format_specs<Char> specs, locale_ref loc = {})
+    -> OutputIt {
+  if (const_check(!is_supported_floating_point(value))) return out;
+  float_specs fspecs = parse_float_type_spec(specs);
+  fspecs.sign = specs.sign;
+  if (detail::signbit(value)) {  // value < 0 is false for NaN so use signbit.
+    fspecs.sign = sign::minus;
+    value = -value;
+  } else if (fspecs.sign == sign::minus) {
+    fspecs.sign = sign::none;
+  }
+
+  if (!detail::isfinite(value))
+    return write_nonfinite(out, detail::isnan(value), specs, fspecs);
+
+  if (specs.align == align::numeric && fspecs.sign) {
+    auto it = reserve(out, 1);
+    *it++ = detail::sign<Char>(fspecs.sign);
+    out = base_iterator(out, it);
+    fspecs.sign = sign::none;
+    if (specs.width != 0) --specs.width;
+  }
+
+  memory_buffer buffer;
+  if (fspecs.format == float_format::hex) {
+    if (fspecs.sign) buffer.push_back(detail::sign<char>(fspecs.sign));
+    snprintf_float(convert_float(value), specs.precision, fspecs, buffer);
+    return write_bytes<align::right>(out, {buffer.data(), buffer.size()},
+                                     specs);
+  }
+  int precision = specs.precision >= 0 || specs.type == presentation_type::none
+                      ? specs.precision
+                      : 6;
+  if (fspecs.format == float_format::exp) {
+    if (precision == max_value<int>())
+      throw_format_error("number is too big");
+    else
+      ++precision;
+  } else if (fspecs.format != float_format::fixed && precision == 0) {
+    precision = 1;
+  }
+  if (const_check(std::is_same<T, float>())) fspecs.binary32 = true;
+  int exp = format_float(convert_float(value), precision, fspecs, buffer);
+  fspecs.precision = precision;
+  auto f = big_decimal_fp{buffer.data(), static_cast<int>(buffer.size()), exp};
+  return write_float(out, f, specs, fspecs, loc);
+}
+
+template <typename Char, typename OutputIt, typename T,
+          FMT_ENABLE_IF(is_fast_float<T>::value)>
+FMT_CONSTEXPR20 auto write(OutputIt out, T value) -> OutputIt {
+  if (is_constant_evaluated())
+    return write(out, value, basic_format_specs<Char>());
+  if (const_check(!is_supported_floating_point(value))) return out;
+
+  auto fspecs = float_specs();
+  if (detail::signbit(value)) {
+    fspecs.sign = sign::minus;
+    value = -value;
+  }
+
+  constexpr auto specs = basic_format_specs<Char>();
+  using floaty = conditional_t<std::is_same<T, long double>::value, double, T>;
+  using uint = typename dragonbox::float_info<floaty>::carrier_uint;
+  uint mask = exponent_mask<floaty>();
+  if ((bit_cast<uint>(value) & mask) == mask)
+    return write_nonfinite(out, std::isnan(value), specs, fspecs);
+
+  auto dec = dragonbox::to_decimal(static_cast<floaty>(value));
+  return write_float(out, dec, specs, fspecs, {});
+}
+
+template <typename Char, typename OutputIt, typename T,
+          FMT_ENABLE_IF(is_floating_point<T>::value &&
+                        !is_fast_float<T>::value)>
+inline auto write(OutputIt out, T value) -> OutputIt {
+  return write(out, value, basic_format_specs<Char>());
+}
+
+template <typename Char, typename OutputIt>
+auto write(OutputIt out, monostate, basic_format_specs<Char> = {},
+           locale_ref = {}) -> OutputIt {
+  FMT_ASSERT(false, "");
+  return out;
+}
+
+template <typename Char, typename OutputIt>
+FMT_CONSTEXPR auto write(OutputIt out, basic_string_view<Char> value)
+    -> OutputIt {
+  auto it = reserve(out, value.size());
+  it = copy_str_noinline<Char>(value.begin(), value.end(), it);
+  return base_iterator(out, it);
+}
+
+template <typename Char, typename OutputIt, typename T,
+          FMT_ENABLE_IF(is_string<T>::value)>
+constexpr auto write(OutputIt out, const T& value) -> OutputIt {
+  return write<Char>(out, to_string_view(value));
+}
+
+// FMT_ENABLE_IF() condition separated to workaround an MSVC bug.
+template <
+    typename Char, typename OutputIt, typename T,
+    bool check =
+        std::is_enum<T>::value && !std::is_same<T, Char>::value &&
+        mapped_type_constant<T, basic_format_context<OutputIt, Char>>::value !=
+            type::custom_type,
+    FMT_ENABLE_IF(check)>
+FMT_CONSTEXPR auto write(OutputIt out, T value) -> OutputIt {
+  return write<Char>(out, static_cast<underlying_t<T>>(value));
+}
+
+template <typename Char, typename OutputIt, typename T,
+          FMT_ENABLE_IF(std::is_same<T, bool>::value)>
+FMT_CONSTEXPR auto write(OutputIt out, T value,
+                         const basic_format_specs<Char>& specs = {},
+                         locale_ref = {}) -> OutputIt {
+  return specs.type != presentation_type::none &&
+                 specs.type != presentation_type::string
+             ? write(out, value ? 1 : 0, specs, {})
+             : write_bytes(out, value ? "true" : "false", specs);
+}
+
+template <typename Char, typename OutputIt>
+FMT_CONSTEXPR auto write(OutputIt out, Char value) -> OutputIt {
+  auto it = reserve(out, 1);
+  *it++ = value;
+  return base_iterator(out, it);
+}
+
+template <typename Char, typename OutputIt>
+FMT_CONSTEXPR_CHAR_TRAITS auto write(OutputIt out, const Char* value)
+    -> OutputIt {
+  if (!value) {
+    throw_format_error("string pointer is null");
+  } else {
+    out = write(out, basic_string_view<Char>(value));
+  }
+  return out;
+}
+
+template <typename Char, typename OutputIt, typename T,
+          FMT_ENABLE_IF(std::is_same<T, void>::value)>
+auto write(OutputIt out, const T* value,
+           const basic_format_specs<Char>& specs = {}, locale_ref = {})
+    -> OutputIt {
+  check_pointer_type_spec(specs.type, error_handler());
+  return write_ptr<Char>(out, bit_cast<uintptr_t>(value), &specs);
+}
+
+// A write overload that handles implicit conversions.
+template <typename Char, typename OutputIt, typename T,
+          typename Context = basic_format_context<OutputIt, Char>>
+FMT_CONSTEXPR auto write(OutputIt out, const T& value) -> enable_if_t<
+    std::is_class<T>::value && !is_string<T>::value &&
+        !is_floating_point<T>::value && !std::is_same<T, Char>::value &&
+        !std::is_same<const T&,
+                      decltype(arg_mapper<Context>().map(value))>::value,
+    OutputIt> {
+  return write<Char>(out, arg_mapper<Context>().map(value));
+}
+
+template <typename Char, typename OutputIt, typename T,
+          typename Context = basic_format_context<OutputIt, Char>>
+FMT_CONSTEXPR auto write(OutputIt out, const T& value)
+    -> enable_if_t<mapped_type_constant<T, Context>::value == type::custom_type,
+                   OutputIt> {
+  using formatter_type =
+      conditional_t<has_formatter<T, Context>::value,
+                    typename Context::template formatter_type<T>,
+                    fallback_formatter<T, Char>>;
+  auto ctx = Context(out, {}, {});
+  return formatter_type().format(value, ctx);
+}
+
+// An argument visitor that formats the argument and writes it via the output
+// iterator. It's a class and not a generic lambda for compatibility with C++11.
+template <typename Char> struct default_arg_formatter {
+  using iterator = buffer_appender<Char>;
+  using context = buffer_context<Char>;
+
+  iterator out;
+  basic_format_args<context> args;
+  locale_ref loc;
+
+  template <typename T> auto operator()(T value) -> iterator {
+    return write<Char>(out, value);
+  }
+  auto operator()(typename basic_format_arg<context>::handle h) -> iterator {
+    basic_format_parse_context<Char> parse_ctx({});
+    context format_ctx(out, args, loc);
+    h.format(parse_ctx, format_ctx);
+    return format_ctx.out();
+  }
+};
+
+template <typename Char> struct arg_formatter {
+  using iterator = buffer_appender<Char>;
+  using context = buffer_context<Char>;
+
+  iterator out;
+  const basic_format_specs<Char>& specs;
+  locale_ref locale;
+
+  template <typename T>
+  FMT_CONSTEXPR FMT_INLINE auto operator()(T value) -> iterator {
+    return detail::write(out, value, specs, locale);
+  }
+  auto operator()(typename basic_format_arg<context>::handle) -> iterator {
+    // User-defined types are handled separately because they require access
+    // to the parse context.
+    return out;
+  }
+};
+
+template <typename Char> struct custom_formatter {
+  basic_format_parse_context<Char>& parse_ctx;
+  buffer_context<Char>& ctx;
+
+  void operator()(
+      typename basic_format_arg<buffer_context<Char>>::handle h) const {
+    h.format(parse_ctx, ctx);
+  }
+  template <typename T> void operator()(T) const {}
+};
+
+template <typename T>
+using is_integer =
+    bool_constant<is_integral<T>::value && !std::is_same<T, bool>::value &&
+                  !std::is_same<T, char>::value &&
+                  !std::is_same<T, wchar_t>::value>;
+
+template <typename ErrorHandler> class width_checker {
+ public:
+  explicit FMT_CONSTEXPR width_checker(ErrorHandler& eh) : handler_(eh) {}
+
+  template <typename T, FMT_ENABLE_IF(is_integer<T>::value)>
+  FMT_CONSTEXPR auto operator()(T value) -> unsigned long long {
+    if (is_negative(value)) handler_.on_error("negative width");
+    return static_cast<unsigned long long>(value);
+  }
+
+  template <typename T, FMT_ENABLE_IF(!is_integer<T>::value)>
+  FMT_CONSTEXPR auto operator()(T) -> unsigned long long {
+    handler_.on_error("width is not integer");
+    return 0;
+  }
+
+ private:
+  ErrorHandler& handler_;
+};
+
+template <typename ErrorHandler> class precision_checker {
+ public:
+  explicit FMT_CONSTEXPR precision_checker(ErrorHandler& eh) : handler_(eh) {}
+
+  template <typename T, FMT_ENABLE_IF(is_integer<T>::value)>
+  FMT_CONSTEXPR auto operator()(T value) -> unsigned long long {
+    if (is_negative(value)) handler_.on_error("negative precision");
+    return static_cast<unsigned long long>(value);
+  }
+
+  template <typename T, FMT_ENABLE_IF(!is_integer<T>::value)>
+  FMT_CONSTEXPR auto operator()(T) -> unsigned long long {
+    handler_.on_error("precision is not integer");
+    return 0;
+  }
+
+ private:
+  ErrorHandler& handler_;
+};
+
+template <template <typename> class Handler, typename FormatArg,
+          typename ErrorHandler>
+FMT_CONSTEXPR auto get_dynamic_spec(FormatArg arg, ErrorHandler eh) -> int {
+  unsigned long long value = visit_format_arg(Handler<ErrorHandler>(eh), arg);
+  if (value > to_unsigned(max_value<int>())) eh.on_error("number is too big");
+  return static_cast<int>(value);
+}
+
+template <typename Context, typename ID>
+FMT_CONSTEXPR auto get_arg(Context& ctx, ID id) ->
+    typename Context::format_arg {
+  auto arg = ctx.arg(id);
+  if (!arg) ctx.on_error("argument not found");
+  return arg;
+}
+
+// The standard format specifier handler with checking.
+template <typename Char> class specs_handler : public specs_setter<Char> {
+ private:
+  basic_format_parse_context<Char>& parse_context_;
+  buffer_context<Char>& context_;
+
+  // This is only needed for compatibility with gcc 4.4.
+  using format_arg = basic_format_arg<buffer_context<Char>>;
+
+  FMT_CONSTEXPR auto get_arg(auto_id) -> format_arg {
+    return detail::get_arg(context_, parse_context_.next_arg_id());
+  }
+
+  FMT_CONSTEXPR auto get_arg(int arg_id) -> format_arg {
+    parse_context_.check_arg_id(arg_id);
+    return detail::get_arg(context_, arg_id);
+  }
+
+  FMT_CONSTEXPR auto get_arg(basic_string_view<Char> arg_id) -> format_arg {
+    parse_context_.check_arg_id(arg_id);
+    return detail::get_arg(context_, arg_id);
+  }
+
+ public:
+  FMT_CONSTEXPR specs_handler(basic_format_specs<Char>& specs,
+                              basic_format_parse_context<Char>& parse_ctx,
+                              buffer_context<Char>& ctx)
+      : specs_setter<Char>(specs), parse_context_(parse_ctx), context_(ctx) {}
+
+  template <typename Id> FMT_CONSTEXPR void on_dynamic_width(Id arg_id) {
+    this->specs_.width = get_dynamic_spec<width_checker>(
+        get_arg(arg_id), context_.error_handler());
+  }
+
+  template <typename Id> FMT_CONSTEXPR void on_dynamic_precision(Id arg_id) {
+    this->specs_.precision = get_dynamic_spec<precision_checker>(
+        get_arg(arg_id), context_.error_handler());
+  }
+
+  void on_error(const char* message) { context_.on_error(message); }
+};
+
+template <template <typename> class Handler, typename Context>
+FMT_CONSTEXPR void handle_dynamic_spec(int& value,
+                                       arg_ref<typename Context::char_type> ref,
+                                       Context& ctx) {
+  switch (ref.kind) {
+  case arg_id_kind::none:
+    break;
+  case arg_id_kind::index:
+    value = detail::get_dynamic_spec<Handler>(ctx.arg(ref.val.index),
+                                              ctx.error_handler());
+    break;
+  case arg_id_kind::name:
+    value = detail::get_dynamic_spec<Handler>(ctx.arg(ref.val.name),
+                                              ctx.error_handler());
+    break;
+  }
+}
+
+#if FMT_USE_USER_DEFINED_LITERALS
+template <typename Char> struct udl_formatter {
+  basic_string_view<Char> str;
+
+  template <typename... T>
+  auto operator()(T&&... args) const -> std::basic_string<Char> {
+    return vformat(str, fmt::make_format_args<buffer_context<Char>>(args...));
+  }
+};
+
+#  if FMT_USE_NONTYPE_TEMPLATE_ARGS
+template <typename T, typename Char, size_t N,
+          fmt::detail_exported::fixed_string<Char, N> Str>
+struct statically_named_arg : view {
+  static constexpr auto name = Str.data;
+
+  const T& value;
+  statically_named_arg(const T& v) : value(v) {}
+};
+
+template <typename T, typename Char, size_t N,
+          fmt::detail_exported::fixed_string<Char, N> Str>
+struct is_named_arg<statically_named_arg<T, Char, N, Str>> : std::true_type {};
+
+template <typename T, typename Char, size_t N,
+          fmt::detail_exported::fixed_string<Char, N> Str>
+struct is_statically_named_arg<statically_named_arg<T, Char, N, Str>>
+    : std::true_type {};
+
+template <typename Char, size_t N,
+          fmt::detail_exported::fixed_string<Char, N> Str>
+struct udl_arg {
+  template <typename T> auto operator=(T&& value) const {
+    return statically_named_arg<T, Char, N, Str>(std::forward<T>(value));
+  }
+};
+#  else
+template <typename Char> struct udl_arg {
+  const Char* str;
+
+  template <typename T> auto operator=(T&& value) const -> named_arg<Char, T> {
+    return {str, std::forward<T>(value)};
+  }
+};
+#  endif
+#endif  // FMT_USE_USER_DEFINED_LITERALS
+
+template <typename Locale, typename Char>
+auto vformat(const Locale& loc, basic_string_view<Char> format_str,
+             basic_format_args<buffer_context<type_identity_t<Char>>> args)
+    -> std::basic_string<Char> {
+  basic_memory_buffer<Char> buffer;
+  detail::vformat_to(buffer, format_str, args, detail::locale_ref(loc));
+  return {buffer.data(), buffer.size()};
+}
+
+using format_func = void (*)(detail::buffer<char>&, int, const char*);
+
+FMT_API void format_error_code(buffer<char>& out, int error_code,
+                               string_view message) noexcept;
+
+FMT_API void report_error(format_func func, int error_code,
+                          const char* message) noexcept;
+FMT_END_DETAIL_NAMESPACE
+
+FMT_API auto vsystem_error(int error_code, string_view format_str,
+                           format_args args) -> std::system_error;
+
+/**
+ \rst
+ Constructs :class:`std::system_error` with a message formatted with
+ ``fmt::format(fmt, args...)``.
+  *error_code* is a system error code as given by ``errno``.
+
+ **Example**::
+
+   // This throws std::system_error with the description
+   //   cannot open file 'madeup': No such file or directory
+   // or similar (system message may vary).
+   const char* filename = "madeup";
+   std::FILE* file = std::fopen(filename, "r");
+   if (!file)
+     throw fmt::system_error(errno, "cannot open file '{}'", filename);
+ \endrst
+*/
+template <typename... T>
+auto system_error(int error_code, format_string<T...> fmt, T&&... args)
+    -> std::system_error {
+  return vsystem_error(error_code, fmt, fmt::make_format_args(args...));
+}
+
+/**
+  \rst
+  Formats an error message for an error returned by an operating system or a
+  language runtime, for example a file opening error, and writes it to *out*.
+  The format is the same as the one used by ``std::system_error(ec, message)``
+  where ``ec`` is ``std::error_code(error_code, std::generic_category()})``.
+  It is implementation-defined but normally looks like:
+
+  .. parsed-literal::
+     *<message>*: *<system-message>*
+
+  where *<message>* is the passed message and *<system-message>* is the system
+  message corresponding to the error code.
+  *error_code* is a system error code as given by ``errno``.
+  \endrst
+ */
+FMT_API void format_system_error(detail::buffer<char>& out, int error_code,
+                                 const char* message) noexcept;
+
+// Reports a system error without throwing an exception.
+// Can be used to report errors from destructors.
+FMT_API void report_system_error(int error_code, const char* message) noexcept;
+
+/** Fast integer formatter. */
+class format_int {
+ private:
+  // Buffer should be large enough to hold all digits (digits10 + 1),
+  // a sign and a null character.
+  enum { buffer_size = std::numeric_limits<unsigned long long>::digits10 + 3 };
+  mutable char buffer_[buffer_size];
+  char* str_;
+
+  template <typename UInt> auto format_unsigned(UInt value) -> char* {
+    auto n = static_cast<detail::uint32_or_64_or_128_t<UInt>>(value);
+    return detail::format_decimal(buffer_, n, buffer_size - 1).begin;
+  }
+
+  template <typename Int> auto format_signed(Int value) -> char* {
+    auto abs_value = static_cast<detail::uint32_or_64_or_128_t<Int>>(value);
+    bool negative = value < 0;
+    if (negative) abs_value = 0 - abs_value;
+    auto begin = format_unsigned(abs_value);
+    if (negative) *--begin = '-';
+    return begin;
+  }
+
+ public:
+  explicit format_int(int value) : str_(format_signed(value)) {}
+  explicit format_int(long value) : str_(format_signed(value)) {}
+  explicit format_int(long long value) : str_(format_signed(value)) {}
+  explicit format_int(unsigned value) : str_(format_unsigned(value)) {}
+  explicit format_int(unsigned long value) : str_(format_unsigned(value)) {}
+  explicit format_int(unsigned long long value)
+      : str_(format_unsigned(value)) {}
+
+  /** Returns the number of characters written to the output buffer. */
+  auto size() const -> size_t {
+    return detail::to_unsigned(buffer_ - str_ + buffer_size - 1);
+  }
+
+  /**
+    Returns a pointer to the output buffer content. No terminating null
+    character is appended.
+   */
+  auto data() const -> const char* { return str_; }
+
+  /**
+    Returns a pointer to the output buffer content with terminating null
+    character appended.
+   */
+  auto c_str() const -> const char* {
+    buffer_[buffer_size - 1] = '\0';
+    return str_;
+  }
+
+  /**
+    \rst
+    Returns the content of the output buffer as an ``std::string``.
+    \endrst
+   */
+  auto str() const -> std::string { return std::string(str_, size()); }
+};
+
+template <typename T, typename Char>
+template <typename FormatContext>
+FMT_CONSTEXPR FMT_INLINE auto
+formatter<T, Char,
+          enable_if_t<detail::type_constant<T, Char>::value !=
+                      detail::type::custom_type>>::format(const T& val,
+                                                          FormatContext& ctx)
+    const -> decltype(ctx.out()) {
+  if (specs_.width_ref.kind != detail::arg_id_kind::none ||
+      specs_.precision_ref.kind != detail::arg_id_kind::none) {
+    auto specs = specs_;
+    detail::handle_dynamic_spec<detail::width_checker>(specs.width,
+                                                       specs.width_ref, ctx);
+    detail::handle_dynamic_spec<detail::precision_checker>(
+        specs.precision, specs.precision_ref, ctx);
+    return detail::write<Char>(ctx.out(), val, specs, ctx.locale());
+  }
+  return detail::write<Char>(ctx.out(), val, specs_, ctx.locale());
+}
+
+template <typename Char>
+struct formatter<void*, Char> : formatter<const void*, Char> {
+  template <typename FormatContext>
+  auto format(void* val, FormatContext& ctx) const -> decltype(ctx.out()) {
+    return formatter<const void*, Char>::format(val, ctx);
+  }
+};
+
+template <typename Char, size_t N>
+struct formatter<Char[N], Char> : formatter<basic_string_view<Char>, Char> {
+  template <typename FormatContext>
+  FMT_CONSTEXPR auto format(const Char* val, FormatContext& ctx) const
+      -> decltype(ctx.out()) {
+    return formatter<basic_string_view<Char>, Char>::format(val, ctx);
+  }
+};
+
+// A formatter for types known only at run time such as variant alternatives.
+//
+// Usage:
+//   using variant = std::variant<int, std::string>;
+//   template <>
+//   struct formatter<variant>: dynamic_formatter<> {
+//     auto format(const variant& v, format_context& ctx) {
+//       return visit([&](const auto& val) {
+//           return dynamic_formatter<>::format(val, ctx);
+//       }, v);
+//     }
+//   };
+template <typename Char = char> class dynamic_formatter {
+ private:
+  detail::dynamic_format_specs<Char> specs_;
+  const Char* format_str_;
+
+  struct null_handler : detail::error_handler {
+    void on_align(align_t) {}
+    void on_sign(sign_t) {}
+    void on_hash() {}
+  };
+
+  template <typename Context> void handle_specs(Context& ctx) {
+    detail::handle_dynamic_spec<detail::width_checker>(specs_.width,
+                                                       specs_.width_ref, ctx);
+    detail::handle_dynamic_spec<detail::precision_checker>(
+        specs_.precision, specs_.precision_ref, ctx);
+  }
+
+ public:
+  template <typename ParseContext>
+  FMT_CONSTEXPR auto parse(ParseContext& ctx) -> decltype(ctx.begin()) {
+    format_str_ = ctx.begin();
+    // Checks are deferred to formatting time when the argument type is known.
+    detail::dynamic_specs_handler<ParseContext> handler(specs_, ctx);
+    return detail::parse_format_specs(ctx.begin(), ctx.end(), handler);
+  }
+
+  template <typename T, typename FormatContext>
+  auto format(const T& val, FormatContext& ctx) -> decltype(ctx.out()) {
+    handle_specs(ctx);
+    detail::specs_checker<null_handler> checker(
+        null_handler(), detail::mapped_type_constant<T, FormatContext>::value);
+    checker.on_align(specs_.align);
+    if (specs_.sign != sign::none) checker.on_sign(specs_.sign);
+    if (specs_.alt) checker.on_hash();
+    if (specs_.precision >= 0) checker.end_precision();
+    return detail::write<Char>(ctx.out(), val, specs_, ctx.locale());
+  }
+};
+
+/**
+  \rst
+  Converts ``p`` to ``const void*`` for pointer formatting.
+
+  **Example**::
+
+    auto s = fmt::format("{}", fmt::ptr(p));
+  \endrst
+ */
+template <typename T> auto ptr(T p) -> const void* {
+  static_assert(std::is_pointer<T>::value, "");
+  return detail::bit_cast<const void*>(p);
+}
+template <typename T> auto ptr(const std::unique_ptr<T>& p) -> const void* {
+  return p.get();
+}
+template <typename T> auto ptr(const std::shared_ptr<T>& p) -> const void* {
+  return p.get();
+}
+
+/**
+  \rst
+  Converts ``e`` to the underlying type.
+
+  **Example**::
+
+    enum class color { red, green, blue };
+    auto s = fmt::format("{}", fmt::underlying(color::red));
+  \endrst
+ */
+template <typename Enum>
+constexpr auto underlying(Enum e) noexcept -> underlying_t<Enum> {
+  return static_cast<underlying_t<Enum>>(e);
+}
+
+namespace enums {
+template <typename Enum, FMT_ENABLE_IF(std::is_enum<Enum>::value)>
+constexpr auto format_as(Enum e) noexcept -> underlying_t<Enum> {
+  return static_cast<underlying_t<Enum>>(e);
+}
+}  // namespace enums
+
+class bytes {
+ private:
+  string_view data_;
+  friend struct formatter<bytes>;
+
+ public:
+  explicit bytes(string_view data) : data_(data) {}
+};
+
+template <> struct formatter<bytes> {
+ private:
+  detail::dynamic_format_specs<char> specs_;
+
+ public:
+  template <typename ParseContext>
+  FMT_CONSTEXPR auto parse(ParseContext& ctx) -> decltype(ctx.begin()) {
+    using handler_type = detail::dynamic_specs_handler<ParseContext>;
+    detail::specs_checker<handler_type> handler(handler_type(specs_, ctx),
+                                                detail::type::string_type);
+    auto it = parse_format_specs(ctx.begin(), ctx.end(), handler);
+    detail::check_string_type_spec(specs_.type, ctx.error_handler());
+    return it;
+  }
+
+  template <typename FormatContext>
+  auto format(bytes b, FormatContext& ctx) -> decltype(ctx.out()) {
+    detail::handle_dynamic_spec<detail::width_checker>(specs_.width,
+                                                       specs_.width_ref, ctx);
+    detail::handle_dynamic_spec<detail::precision_checker>(
+        specs_.precision, specs_.precision_ref, ctx);
+    return detail::write_bytes(ctx.out(), b.data_, specs_);
+  }
+};
+
+// group_digits_view is not derived from view because it copies the argument.
+template <typename T> struct group_digits_view { T value; };
+
+/**
+  \rst
+  Returns a view that formats an integer value using ',' as a locale-independent
+  thousands separator.
+
+  **Example**::
+
+    fmt::print("{}", fmt::group_digits(12345));
+    // Output: "12,345"
+  \endrst
+ */
+template <typename T> auto group_digits(T value) -> group_digits_view<T> {
+  return {value};
+}
+
+template <typename T> struct formatter<group_digits_view<T>> : formatter<T> {
+ private:
+  detail::dynamic_format_specs<char> specs_;
+
+ public:
+  template <typename ParseContext>
+  FMT_CONSTEXPR auto parse(ParseContext& ctx) -> decltype(ctx.begin()) {
+    using handler_type = detail::dynamic_specs_handler<ParseContext>;
+    detail::specs_checker<handler_type> handler(handler_type(specs_, ctx),
+                                                detail::type::int_type);
+    auto it = parse_format_specs(ctx.begin(), ctx.end(), handler);
+    detail::check_string_type_spec(specs_.type, ctx.error_handler());
+    return it;
+  }
+
+  template <typename FormatContext>
+  auto format(group_digits_view<T> t, FormatContext& ctx)
+      -> decltype(ctx.out()) {
+    detail::handle_dynamic_spec<detail::width_checker>(specs_.width,
+                                                       specs_.width_ref, ctx);
+    detail::handle_dynamic_spec<detail::precision_checker>(
+        specs_.precision, specs_.precision_ref, ctx);
+    return detail::write_int_localized(
+        ctx.out(), static_cast<detail::uint64_or_128_t<T>>(t.value), 0, specs_,
+        detail::digit_grouping<char>({"\3", ','}));
+  }
+};
+
+template <typename It, typename Sentinel, typename Char = char>
+struct join_view : detail::view {
+  It begin;
+  Sentinel end;
+  basic_string_view<Char> sep;
+
+  join_view(It b, Sentinel e, basic_string_view<Char> s)
+      : begin(b), end(e), sep(s) {}
+};
+
+template <typename It, typename Sentinel, typename Char>
+struct formatter<join_view<It, Sentinel, Char>, Char> {
+ private:
+  using value_type =
+#ifdef __cpp_lib_ranges
+      std::iter_value_t<It>;
+#else
+      typename std::iterator_traits<It>::value_type;
+#endif
+  using context = buffer_context<Char>;
+  using mapper = detail::arg_mapper<context>;
+
+  template <typename T, FMT_ENABLE_IF(has_formatter<T, context>::value)>
+  static auto map(const T& value) -> const T& {
+    return value;
+  }
+  template <typename T, FMT_ENABLE_IF(!has_formatter<T, context>::value)>
+  static auto map(const T& value) -> decltype(mapper().map(value)) {
+    return mapper().map(value);
+  }
+
+  using formatter_type =
+      conditional_t<is_formattable<value_type, Char>::value,
+                    formatter<remove_cvref_t<decltype(map(
+                                  std::declval<const value_type&>()))>,
+                              Char>,
+                    detail::fallback_formatter<value_type, Char>>;
+
+  formatter_type value_formatter_;
+
+ public:
+  template <typename ParseContext>
+  FMT_CONSTEXPR auto parse(ParseContext& ctx) -> decltype(ctx.begin()) {
+    return value_formatter_.parse(ctx);
+  }
+
+  template <typename FormatContext>
+  auto format(const join_view<It, Sentinel, Char>& value,
+              FormatContext& ctx) const -> decltype(ctx.out()) {
+    auto it = value.begin;
+    auto out = ctx.out();
+    if (it != value.end) {
+      out = value_formatter_.format(map(*it), ctx);
+      ++it;
+      while (it != value.end) {
+        out = detail::copy_str<Char>(value.sep.begin(), value.sep.end(), out);
+        ctx.advance_to(out);
+        out = value_formatter_.format(map(*it), ctx);
+        ++it;
+      }
+    }
+    return out;
+  }
+};
+
+/**
+  Returns a view that formats the iterator range `[begin, end)` with elements
+  separated by `sep`.
+ */
+template <typename It, typename Sentinel>
+auto join(It begin, Sentinel end, string_view sep) -> join_view<It, Sentinel> {
+  return {begin, end, sep};
+}
+
+/**
+  \rst
+  Returns a view that formats `range` with elements separated by `sep`.
+
+  **Example**::
+
+    std::vector<int> v = {1, 2, 3};
+    fmt::print("{}", fmt::join(v, ", "));
+    // Output: "1, 2, 3"
+
+  ``fmt::join`` applies passed format specifiers to the range elements::
+
+    fmt::print("{:02}", fmt::join(v, ", "));
+    // Output: "01, 02, 03"
+  \endrst
+ */
+template <typename Range>
+auto join(Range&& range, string_view sep)
+    -> join_view<detail::iterator_t<Range>, detail::sentinel_t<Range>> {
+  return join(std::begin(range), std::end(range), sep);
+}
+
+/**
+  \rst
+  Converts *value* to ``std::string`` using the default format for type *T*.
+
+  **Example**::
+
+    #include <fmt/format.h>
+
+    std::string answer = fmt::to_string(42);
+  \endrst
+ */
+template <typename T, FMT_ENABLE_IF(!std::is_integral<T>::value)>
+inline auto to_string(const T& value) -> std::string {
+  auto result = std::string();
+  detail::write<char>(std::back_inserter(result), value);
+  return result;
+}
+
+template <typename T, FMT_ENABLE_IF(std::is_integral<T>::value)>
+FMT_NODISCARD inline auto to_string(T value) -> std::string {
+  // The buffer should be large enough to store the number including the sign
+  // or "false" for bool.
+  constexpr int max_size = detail::digits10<T>() + 2;
+  char buffer[max_size > 5 ? static_cast<unsigned>(max_size) : 5];
+  char* begin = buffer;
+  return std::string(begin, detail::write<char>(begin, value));
+}
+
+template <typename Char, size_t SIZE>
+FMT_NODISCARD auto to_string(const basic_memory_buffer<Char, SIZE>& buf)
+    -> std::basic_string<Char> {
+  auto size = buf.size();
+  detail::assume(size < std::basic_string<Char>().max_size());
+  return std::basic_string<Char>(buf.data(), size);
+}
+
+FMT_BEGIN_DETAIL_NAMESPACE
+
+template <typename Char>
+void vformat_to(
+    buffer<Char>& buf, basic_string_view<Char> fmt,
+    basic_format_args<FMT_BUFFER_CONTEXT(type_identity_t<Char>)> args,
+    locale_ref loc) {
+  // workaround for msvc bug regarding name-lookup in module
+  // link names into function scope
+  using detail::arg_formatter;
+  using detail::buffer_appender;
+  using detail::custom_formatter;
+  using detail::default_arg_formatter;
+  using detail::get_arg;
+  using detail::locale_ref;
+  using detail::parse_format_specs;
+  using detail::specs_checker;
+  using detail::specs_handler;
+  using detail::to_unsigned;
+  using detail::type;
+  using detail::write;
+  auto out = buffer_appender<Char>(buf);
+  if (fmt.size() == 2 && equal2(fmt.data(), "{}")) {
+    auto arg = args.get(0);
+    if (!arg) error_handler().on_error("argument not found");
+    visit_format_arg(default_arg_formatter<Char>{out, args, loc}, arg);
+    return;
+  }
+
+  struct format_handler : error_handler {
+    basic_format_parse_context<Char> parse_context;
+    buffer_context<Char> context;
+
+    format_handler(buffer_appender<Char> p_out, basic_string_view<Char> str,
+                   basic_format_args<buffer_context<Char>> p_args,
+                   locale_ref p_loc)
+        : parse_context(str), context(p_out, p_args, p_loc) {}
+
+    void on_text(const Char* begin, const Char* end) {
+      auto text = basic_string_view<Char>(begin, to_unsigned(end - begin));
+      context.advance_to(write<Char>(context.out(), text));
+    }
+
+    FMT_CONSTEXPR auto on_arg_id() -> int {
+      return parse_context.next_arg_id();
+    }
+    FMT_CONSTEXPR auto on_arg_id(int id) -> int {
+      return parse_context.check_arg_id(id), id;
+    }
+    FMT_CONSTEXPR auto on_arg_id(basic_string_view<Char> id) -> int {
+      int arg_id = context.arg_id(id);
+      if (arg_id < 0) on_error("argument not found");
+      return arg_id;
+    }
+
+    FMT_INLINE void on_replacement_field(int id, const Char*) {
+      auto arg = get_arg(context, id);
+      context.advance_to(visit_format_arg(
+          default_arg_formatter<Char>{context.out(), context.args(),
+                                      context.locale()},
+          arg));
+    }
+
+    auto on_format_specs(int id, const Char* begin, const Char* end)
+        -> const Char* {
+      auto arg = get_arg(context, id);
+      if (arg.type() == type::custom_type) {
+        parse_context.advance_to(parse_context.begin() +
+                                 (begin - &*parse_context.begin()));
+        visit_format_arg(custom_formatter<Char>{parse_context, context}, arg);
+        return parse_context.begin();
+      }
+      auto specs = basic_format_specs<Char>();
+      specs_checker<specs_handler<Char>> handler(
+          specs_handler<Char>(specs, parse_context, context), arg.type());
+      begin = parse_format_specs(begin, end, handler);
+      if (begin == end || *begin != '}')
+        on_error("missing '}' in format string");
+      auto f = arg_formatter<Char>{context.out(), specs, context.locale()};
+      context.advance_to(visit_format_arg(f, arg));
+      return begin;
+    }
+  };
+  detail::parse_format_string<false>(fmt, format_handler(out, fmt, args, loc));
+}
+
+#ifndef FMT_HEADER_ONLY
+extern template FMT_API auto thousands_sep_impl<char>(locale_ref)
+    -> thousands_sep_result<char>;
+extern template FMT_API auto thousands_sep_impl<wchar_t>(locale_ref)
+    -> thousands_sep_result<wchar_t>;
+extern template FMT_API auto decimal_point_impl(locale_ref) -> char;
+extern template FMT_API auto decimal_point_impl(locale_ref) -> wchar_t;
+#endif  // FMT_HEADER_ONLY
+
+FMT_END_DETAIL_NAMESPACE
+
+#if FMT_USE_USER_DEFINED_LITERALS
+inline namespace literals {
+/**
+  \rst
+  User-defined literal equivalent of :func:`fmt::arg`.
+
+  **Example**::
+
+    using namespace fmt::literals;
+    fmt::print("Elapsed time: {s:.2f} seconds", "s"_a=1.23);
+  \endrst
+ */
+#  if FMT_USE_NONTYPE_TEMPLATE_ARGS
+template <detail_exported::fixed_string Str> constexpr auto operator""_a() {
+  using char_t = remove_cvref_t<decltype(Str.data[0])>;
+  return detail::udl_arg<char_t, sizeof(Str.data) / sizeof(char_t), Str>();
+}
+#  else
+constexpr auto operator"" _a(const char* s, size_t) -> detail::udl_arg<char> {
+  return {s};
+}
+#  endif
+}  // namespace literals
+#endif  // FMT_USE_USER_DEFINED_LITERALS
+
+template <typename Locale, FMT_ENABLE_IF(detail::is_locale<Locale>::value)>
+inline auto vformat(const Locale& loc, string_view fmt, format_args args)
+    -> std::string {
+  return detail::vformat(loc, fmt, args);
+}
+
+template <typename Locale, typename... T,
+          FMT_ENABLE_IF(detail::is_locale<Locale>::value)>
+inline auto format(const Locale& loc, format_string<T...> fmt, T&&... args)
+    -> std::string {
+  return vformat(loc, string_view(fmt), fmt::make_format_args(args...));
+}
+
+template <typename OutputIt, typename Locale,
+          FMT_ENABLE_IF(detail::is_output_iterator<OutputIt, char>::value&&
+                            detail::is_locale<Locale>::value)>
+auto vformat_to(OutputIt out, const Locale& loc, string_view fmt,
+                format_args args) -> OutputIt {
+  using detail::get_buffer;
+  auto&& buf = get_buffer<char>(out);
+  detail::vformat_to(buf, fmt, args, detail::locale_ref(loc));
+  return detail::get_iterator(buf);
+}
+
+template <typename OutputIt, typename Locale, typename... T,
+          FMT_ENABLE_IF(detail::is_output_iterator<OutputIt, char>::value&&
+                            detail::is_locale<Locale>::value)>
+FMT_INLINE auto format_to(OutputIt out, const Locale& loc,
+                          format_string<T...> fmt, T&&... args) -> OutputIt {
+  return vformat_to(out, loc, fmt, fmt::make_format_args(args...));
+}
+
+FMT_MODULE_EXPORT_END
+FMT_END_NAMESPACE
+
+#ifdef FMT_HEADER_ONLY
+#  define FMT_FUNC inline
+#  include "format-inl.h"
+#else
+#  define FMT_FUNC
+#endif
+
+#endif  // FMT_FORMAT_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/os.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/os.h
new file mode 100644
index 0000000..d82be11
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/os.h
@@ -0,0 +1,478 @@
+// Formatting library for C++ - optional OS-specific functionality
+//
+// Copyright (c) 2012 - present, Victor Zverovich
+// All rights reserved.
+//
+// For the license information refer to format.h.
+
+#ifndef FMT_OS_H_
+#define FMT_OS_H_
+
+#include <cerrno>
+#include <cstddef>
+#include <cstdio>
+#include <system_error>  // std::system_error
+
+#if defined __APPLE__ || defined(__FreeBSD__)
+#  include <xlocale.h>  // for LC_NUMERIC_MASK on OS X
+#endif
+
+#include "format.h"
+
+#ifndef FMT_USE_FCNTL
+// UWP doesn't provide _pipe.
+#  if FMT_HAS_INCLUDE("winapifamily.h")
+#    include <winapifamily.h>
+#  endif
+#  if (FMT_HAS_INCLUDE(<fcntl.h>) || defined(__APPLE__) || \
+       defined(__linux__)) &&                              \
+      (!defined(WINAPI_FAMILY) ||                          \
+       (WINAPI_FAMILY == WINAPI_FAMILY_DESKTOP_APP))
+#    include <fcntl.h>  // for O_RDONLY
+#    define FMT_USE_FCNTL 1
+#  else
+#    define FMT_USE_FCNTL 0
+#  endif
+#endif
+
+#ifndef FMT_POSIX
+#  if defined(_WIN32) && !defined(__MINGW32__)
+// Fix warnings about deprecated symbols.
+#    define FMT_POSIX(call) _##call
+#  else
+#    define FMT_POSIX(call) call
+#  endif
+#endif
+
+// Calls to system functions are wrapped in FMT_SYSTEM for testability.
+#ifdef FMT_SYSTEM
+#  define FMT_POSIX_CALL(call) FMT_SYSTEM(call)
+#else
+#  define FMT_SYSTEM(call) ::call
+#  ifdef _WIN32
+// Fix warnings about deprecated symbols.
+#    define FMT_POSIX_CALL(call) ::_##call
+#  else
+#    define FMT_POSIX_CALL(call) ::call
+#  endif
+#endif
+
+// Retries the expression while it evaluates to error_result and errno
+// equals to EINTR.
+#ifndef _WIN32
+#  define FMT_RETRY_VAL(result, expression, error_result) \
+    do {                                                  \
+      (result) = (expression);                            \
+    } while ((result) == (error_result) && errno == EINTR)
+#else
+#  define FMT_RETRY_VAL(result, expression, error_result) result = (expression)
+#endif
+
+#define FMT_RETRY(result, expression) FMT_RETRY_VAL(result, expression, -1)
+
+FMT_BEGIN_NAMESPACE
+FMT_MODULE_EXPORT_BEGIN
+
+/**
+  \rst
+  A reference to a null-terminated string. It can be constructed from a C
+  string or ``std::string``.
+
+  You can use one of the following type aliases for common character types:
+
+  +---------------+-----------------------------+
+  | Type          | Definition                  |
+  +===============+=============================+
+  | cstring_view  | basic_cstring_view<char>    |
+  +---------------+-----------------------------+
+  | wcstring_view | basic_cstring_view<wchar_t> |
+  +---------------+-----------------------------+
+
+  This class is most useful as a parameter type to allow passing
+  different types of strings to a function, for example::
+
+    template <typename... Args>
+    std::string format(cstring_view format_str, const Args & ... args);
+
+    format("{}", 42);
+    format(std::string("{}"), 42);
+  \endrst
+ */
+template <typename Char> class basic_cstring_view {
+ private:
+  const Char* data_;
+
+ public:
+  /** Constructs a string reference object from a C string. */
+  basic_cstring_view(const Char* s) : data_(s) {}
+
+  /**
+    \rst
+    Constructs a string reference from an ``std::string`` object.
+    \endrst
+   */
+  basic_cstring_view(const std::basic_string<Char>& s) : data_(s.c_str()) {}
+
+  /** Returns the pointer to a C string. */
+  const Char* c_str() const { return data_; }
+};
+
+using cstring_view = basic_cstring_view<char>;
+using wcstring_view = basic_cstring_view<wchar_t>;
+
+template <typename Char> struct formatter<std::error_code, Char> {
+  template <typename ParseContext>
+  FMT_CONSTEXPR auto parse(ParseContext& ctx) -> decltype(ctx.begin()) {
+    return ctx.begin();
+  }
+
+  template <typename FormatContext>
+  FMT_CONSTEXPR auto format(const std::error_code& ec, FormatContext& ctx) const
+      -> decltype(ctx.out()) {
+    auto out = ctx.out();
+    out = detail::write_bytes(out, ec.category().name(),
+                              basic_format_specs<Char>());
+    out = detail::write<Char>(out, Char(':'));
+    out = detail::write<Char>(out, ec.value());
+    return out;
+  }
+};
+
+#ifdef _WIN32
+FMT_API const std::error_category& system_category() noexcept;
+
+FMT_BEGIN_DETAIL_NAMESPACE
+// A converter from UTF-16 to UTF-8.
+// It is only provided for Windows since other systems support UTF-8 natively.
+class utf16_to_utf8 {
+ private:
+  memory_buffer buffer_;
+
+ public:
+  utf16_to_utf8() {}
+  FMT_API explicit utf16_to_utf8(basic_string_view<wchar_t> s);
+  operator string_view() const { return string_view(&buffer_[0], size()); }
+  size_t size() const { return buffer_.size() - 1; }
+  const char* c_str() const { return &buffer_[0]; }
+  std::string str() const { return std::string(&buffer_[0], size()); }
+
+  // Performs conversion returning a system error code instead of
+  // throwing exception on conversion error. This method may still throw
+  // in case of memory allocation error.
+  FMT_API int convert(basic_string_view<wchar_t> s);
+};
+
+FMT_API void format_windows_error(buffer<char>& out, int error_code,
+                                  const char* message) noexcept;
+FMT_END_DETAIL_NAMESPACE
+
+FMT_API std::system_error vwindows_error(int error_code, string_view format_str,
+                                         format_args args);
+
+/**
+ \rst
+ Constructs a :class:`std::system_error` object with the description
+ of the form
+
+ .. parsed-literal::
+   *<message>*: *<system-message>*
+
+ where *<message>* is the formatted message and *<system-message>* is the
+ system message corresponding to the error code.
+ *error_code* is a Windows error code as given by ``GetLastError``.
+ If *error_code* is not a valid error code such as -1, the system message
+ will look like "error -1".
+
+ **Example**::
+
+   // This throws a system_error with the description
+   //   cannot open file 'madeup': The system cannot find the file specified.
+   // or similar (system message may vary).
+   const char *filename = "madeup";
+   LPOFSTRUCT of = LPOFSTRUCT();
+   HFILE file = OpenFile(filename, &of, OF_READ);
+   if (file == HFILE_ERROR) {
+     throw fmt::windows_error(GetLastError(),
+                              "cannot open file '{}'", filename);
+   }
+ \endrst
+*/
+template <typename... Args>
+std::system_error windows_error(int error_code, string_view message,
+                                const Args&... args) {
+  return vwindows_error(error_code, message, fmt::make_format_args(args...));
+}
+
+// Reports a Windows error without throwing an exception.
+// Can be used to report errors from destructors.
+FMT_API void report_windows_error(int error_code, const char* message) noexcept;
+#else
+inline const std::error_category& system_category() noexcept {
+  return std::system_category();
+}
+#endif  // _WIN32
+
+// std::system is not available on some platforms such as iOS (#2248).
+#ifdef __OSX__
+template <typename S, typename... Args, typename Char = char_t<S>>
+void say(const S& format_str, Args&&... args) {
+  std::system(format("say \"{}\"", format(format_str, args...)).c_str());
+}
+#endif
+
+// A buffered file.
+class buffered_file {
+ private:
+  FILE* file_;
+
+  friend class file;
+
+  explicit buffered_file(FILE* f) : file_(f) {}
+
+ public:
+  buffered_file(const buffered_file&) = delete;
+  void operator=(const buffered_file&) = delete;
+
+  // Constructs a buffered_file object which doesn't represent any file.
+  buffered_file() noexcept : file_(nullptr) {}
+
+  // Destroys the object closing the file it represents if any.
+  FMT_API ~buffered_file() noexcept;
+
+ public:
+  buffered_file(buffered_file&& other) noexcept : file_(other.file_) {
+    other.file_ = nullptr;
+  }
+
+  buffered_file& operator=(buffered_file&& other) {
+    close();
+    file_ = other.file_;
+    other.file_ = nullptr;
+    return *this;
+  }
+
+  // Opens a file.
+  FMT_API buffered_file(cstring_view filename, cstring_view mode);
+
+  // Closes the file.
+  FMT_API void close();
+
+  // Returns the pointer to a FILE object representing this file.
+  FILE* get() const noexcept { return file_; }
+
+  FMT_API int descriptor() const;
+
+  void vprint(string_view format_str, format_args args) {
+    fmt::vprint(file_, format_str, args);
+  }
+
+  template <typename... Args>
+  inline void print(string_view format_str, const Args&... args) {
+    vprint(format_str, fmt::make_format_args(args...));
+  }
+};
+
+#if FMT_USE_FCNTL
+// A file. Closed file is represented by a file object with descriptor -1.
+// Methods that are not declared with noexcept may throw
+// fmt::system_error in case of failure. Note that some errors such as
+// closing the file multiple times will cause a crash on Windows rather
+// than an exception. You can get standard behavior by overriding the
+// invalid parameter handler with _set_invalid_parameter_handler.
+class FMT_API file {
+ private:
+  int fd_;  // File descriptor.
+
+  // Constructs a file object with a given descriptor.
+  explicit file(int fd) : fd_(fd) {}
+
+ public:
+  // Possible values for the oflag argument to the constructor.
+  enum {
+    RDONLY = FMT_POSIX(O_RDONLY),  // Open for reading only.
+    WRONLY = FMT_POSIX(O_WRONLY),  // Open for writing only.
+    RDWR = FMT_POSIX(O_RDWR),      // Open for reading and writing.
+    CREATE = FMT_POSIX(O_CREAT),   // Create if the file doesn't exist.
+    APPEND = FMT_POSIX(O_APPEND),  // Open in append mode.
+    TRUNC = FMT_POSIX(O_TRUNC)     // Truncate the content of the file.
+  };
+
+  // Constructs a file object which doesn't represent any file.
+  file() noexcept : fd_(-1) {}
+
+  // Opens a file and constructs a file object representing this file.
+  file(cstring_view path, int oflag);
+
+ public:
+  file(const file&) = delete;
+  void operator=(const file&) = delete;
+
+  file(file&& other) noexcept : fd_(other.fd_) { other.fd_ = -1; }
+
+  // Move assignment is not noexcept because close may throw.
+  file& operator=(file&& other) {
+    close();
+    fd_ = other.fd_;
+    other.fd_ = -1;
+    return *this;
+  }
+
+  // Destroys the object closing the file it represents if any.
+  ~file() noexcept;
+
+  // Returns the file descriptor.
+  int descriptor() const noexcept { return fd_; }
+
+  // Closes the file.
+  void close();
+
+  // Returns the file size. The size has signed type for consistency with
+  // stat::st_size.
+  long long size() const;
+
+  // Attempts to read count bytes from the file into the specified buffer.
+  size_t read(void* buffer, size_t count);
+
+  // Attempts to write count bytes from the specified buffer to the file.
+  size_t write(const void* buffer, size_t count);
+
+  // Duplicates a file descriptor with the dup function and returns
+  // the duplicate as a file object.
+  static file dup(int fd);
+
+  // Makes fd be the copy of this file descriptor, closing fd first if
+  // necessary.
+  void dup2(int fd);
+
+  // Makes fd be the copy of this file descriptor, closing fd first if
+  // necessary.
+  void dup2(int fd, std::error_code& ec) noexcept;
+
+  // Creates a pipe setting up read_end and write_end file objects for reading
+  // and writing respectively.
+  static void pipe(file& read_end, file& write_end);
+
+  // Creates a buffered_file object associated with this file and detaches
+  // this file object from the file.
+  buffered_file fdopen(const char* mode);
+};
+
+// Returns the memory page size.
+long getpagesize();
+
+FMT_BEGIN_DETAIL_NAMESPACE
+
+struct buffer_size {
+  buffer_size() = default;
+  size_t value = 0;
+  buffer_size operator=(size_t val) const {
+    auto bs = buffer_size();
+    bs.value = val;
+    return bs;
+  }
+};
+
+struct ostream_params {
+  int oflag = file::WRONLY | file::CREATE | file::TRUNC;
+  size_t buffer_size = BUFSIZ > 32768 ? BUFSIZ : 32768;
+
+  ostream_params() {}
+
+  template <typename... T>
+  ostream_params(T... params, int new_oflag) : ostream_params(params...) {
+    oflag = new_oflag;
+  }
+
+  template <typename... T>
+  ostream_params(T... params, detail::buffer_size bs)
+      : ostream_params(params...) {
+    this->buffer_size = bs.value;
+  }
+
+// Intel has a bug that results in failure to deduce a constructor
+// for empty parameter packs.
+#  if defined(__INTEL_COMPILER) && __INTEL_COMPILER < 2000
+  ostream_params(int new_oflag) : oflag(new_oflag) {}
+  ostream_params(detail::buffer_size bs) : buffer_size(bs.value) {}
+#  endif
+};
+
+FMT_END_DETAIL_NAMESPACE
+
+// Added {} below to work around default constructor error known to
+// occur in Xcode versions 7.2.1 and 8.2.1.
+constexpr detail::buffer_size buffer_size{};
+
+/** A fast output stream which is not thread-safe. */
+class FMT_API ostream final : private detail::buffer<char> {
+ private:
+  file file_;
+
+  void grow(size_t) override;
+
+  ostream(cstring_view path, const detail::ostream_params& params)
+      : file_(path, params.oflag) {
+    set(new char[params.buffer_size], params.buffer_size);
+  }
+
+ public:
+  ostream(ostream&& other)
+      : detail::buffer<char>(other.data(), other.size(), other.capacity()),
+        file_(std::move(other.file_)) {
+    other.clear();
+    other.set(nullptr, 0);
+  }
+  ~ostream() {
+    flush();
+    delete[] data();
+  }
+
+  void flush() {
+    if (size() == 0) return;
+    file_.write(data(), size());
+    clear();
+  }
+
+  template <typename... T>
+  friend ostream output_file(cstring_view path, T... params);
+
+  void close() {
+    flush();
+    file_.close();
+  }
+
+  /**
+    Formats ``args`` according to specifications in ``fmt`` and writes the
+    output to the file.
+   */
+  template <typename... T> void print(format_string<T...> fmt, T&&... args) {
+    vformat_to(detail::buffer_appender<char>(*this), fmt,
+               fmt::make_format_args(args...));
+  }
+};
+
+/**
+  \rst
+  Opens a file for writing. Supported parameters passed in *params*:
+
+  * ``<integer>``: Flags passed to `open
+    <https://pubs.opengroup.org/onlinepubs/007904875/functions/open.html>`_
+    (``file::WRONLY | file::CREATE | file::TRUNC`` by default)
+  * ``buffer_size=<integer>``: Output buffer size
+
+  **Example**::
+
+    auto out = fmt::output_file("guide.txt");
+    out.print("Don't {}", "Panic");
+  \endrst
+ */
+template <typename... T>
+inline ostream output_file(cstring_view path, T... params) {
+  return {path, detail::ostream_params(params...)};
+}
+#endif  // FMT_USE_FCNTL
+
+FMT_MODULE_EXPORT_END
+FMT_END_NAMESPACE
+
+#endif  // FMT_OS_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/ostream.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/ostream.h
new file mode 100644
index 0000000..c3cdd4a
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/ostream.h
@@ -0,0 +1,237 @@
+// Formatting library for C++ - std::ostream support
+//
+// Copyright (c) 2012 - present, Victor Zverovich
+// All rights reserved.
+//
+// For the license information refer to format.h.
+
+#ifndef FMT_OSTREAM_H_
+#define FMT_OSTREAM_H_
+
+#include <fstream>
+#include <ostream>
+#if defined(_WIN32) && defined(__GLIBCXX__)
+#  include <ext/stdio_filebuf.h>
+#  include <ext/stdio_sync_filebuf.h>
+#elif defined(_WIN32) && defined(_LIBCPP_VERSION)
+#  include <__std_stream>
+#endif
+
+#include "format.h"
+
+FMT_BEGIN_NAMESPACE
+
+template <typename OutputIt, typename Char> class basic_printf_context;
+
+namespace detail {
+
+// Checks if T has a user-defined operator<<.
+template <typename T, typename Char, typename Enable = void>
+class is_streamable {
+ private:
+  template <typename U>
+  static auto test(int)
+      -> bool_constant<sizeof(std::declval<std::basic_ostream<Char>&>()
+                              << std::declval<U>()) != 0>;
+
+  template <typename> static auto test(...) -> std::false_type;
+
+  using result = decltype(test<T>(0));
+
+ public:
+  is_streamable() = default;
+
+  static const bool value = result::value;
+};
+
+// Formatting of built-in types and arrays is intentionally disabled because
+// it's handled by standard (non-ostream) formatters.
+template <typename T, typename Char>
+struct is_streamable<
+    T, Char,
+    enable_if_t<
+        std::is_arithmetic<T>::value || std::is_array<T>::value ||
+        std::is_pointer<T>::value || std::is_same<T, char8_type>::value ||
+        std::is_convertible<T, fmt::basic_string_view<Char>>::value ||
+        std::is_same<T, std_string_view<Char>>::value ||
+        (std::is_convertible<T, int>::value && !std::is_enum<T>::value)>>
+    : std::false_type {};
+
+// Generate a unique explicit instantion in every translation unit using a tag
+// type in an anonymous namespace.
+namespace {
+struct file_access_tag {};
+}  // namespace
+template <class Tag, class BufType, FILE* BufType::*FileMemberPtr>
+class file_access {
+  friend auto get_file(BufType& obj) -> FILE* { return obj.*FileMemberPtr; }
+};
+
+#if FMT_MSC_VERSION
+template class file_access<file_access_tag, std::filebuf,
+                           &std::filebuf::_Myfile>;
+auto get_file(std::filebuf&) -> FILE*;
+#elif defined(_WIN32) && defined(_LIBCPP_VERSION)
+template class file_access<file_access_tag, std::__stdoutbuf<char>,
+                           &std::__stdoutbuf<char>::__file_>;
+auto get_file(std::__stdoutbuf<char>&) -> FILE*;
+#endif
+
+inline bool write_ostream_unicode(std::ostream& os, fmt::string_view data) {
+#if FMT_MSC_VERSION
+  if (auto* buf = dynamic_cast<std::filebuf*>(os.rdbuf()))
+    if (FILE* f = get_file(*buf)) return write_console(f, data);
+#elif defined(_WIN32) && defined(__GLIBCXX__)
+  auto* rdbuf = os.rdbuf();
+  FILE* c_file;
+  if (auto* fbuf = dynamic_cast<__gnu_cxx::stdio_sync_filebuf<char>*>(rdbuf))
+    c_file = fbuf->file();
+  else if (auto* fbuf = dynamic_cast<__gnu_cxx::stdio_filebuf<char>*>(rdbuf))
+    c_file = fbuf->file();
+  else
+    return false;
+  if (c_file) return write_console(c_file, data);
+#elif defined(_WIN32) && defined(_LIBCPP_VERSION)
+  if (auto* buf = dynamic_cast<std::__stdoutbuf<char>*>(os.rdbuf()))
+    if (FILE* f = get_file(*buf)) return write_console(f, data);
+#else
+  ignore_unused(os, data);
+#endif
+  return false;
+}
+inline bool write_ostream_unicode(std::wostream&,
+                                  fmt::basic_string_view<wchar_t>) {
+  return false;
+}
+
+// Write the content of buf to os.
+// It is a separate function rather than a part of vprint to simplify testing.
+template <typename Char>
+void write_buffer(std::basic_ostream<Char>& os, buffer<Char>& buf) {
+  const Char* buf_data = buf.data();
+  using unsigned_streamsize = std::make_unsigned<std::streamsize>::type;
+  unsigned_streamsize size = buf.size();
+  unsigned_streamsize max_size = to_unsigned(max_value<std::streamsize>());
+  do {
+    unsigned_streamsize n = size <= max_size ? size : max_size;
+    os.write(buf_data, static_cast<std::streamsize>(n));
+    buf_data += n;
+    size -= n;
+  } while (size != 0);
+}
+
+template <typename Char, typename T>
+void format_value(buffer<Char>& buf, const T& value,
+                  locale_ref loc = locale_ref()) {
+  auto&& format_buf = formatbuf<std::basic_streambuf<Char>>(buf);
+  auto&& output = std::basic_ostream<Char>(&format_buf);
+#if !defined(FMT_STATIC_THOUSANDS_SEPARATOR)
+  if (loc) output.imbue(loc.get<std::locale>());
+#endif
+  output << value;
+  output.exceptions(std::ios_base::failbit | std::ios_base::badbit);
+}
+
+template <typename T> struct streamed_view { const T& value; };
+
+}  // namespace detail
+
+// Formats an object of type T that has an overloaded ostream operator<<.
+template <typename Char>
+struct basic_ostream_formatter : formatter<basic_string_view<Char>, Char> {
+  void set_debug_format() = delete;
+
+  template <typename T, typename OutputIt>
+  auto format(const T& value, basic_format_context<OutputIt, Char>& ctx) const
+      -> OutputIt {
+    auto buffer = basic_memory_buffer<Char>();
+    format_value(buffer, value, ctx.locale());
+    return formatter<basic_string_view<Char>, Char>::format(
+        {buffer.data(), buffer.size()}, ctx);
+  }
+};
+
+using ostream_formatter = basic_ostream_formatter<char>;
+
+template <typename T, typename Char>
+struct formatter<detail::streamed_view<T>, Char>
+    : basic_ostream_formatter<Char> {
+  template <typename OutputIt>
+  auto format(detail::streamed_view<T> view,
+              basic_format_context<OutputIt, Char>& ctx) const -> OutputIt {
+    return basic_ostream_formatter<Char>::format(view.value, ctx);
+  }
+};
+
+/**
+  \rst
+  Returns a view that formats `value` via an ostream ``operator<<``.
+
+  **Example**::
+
+    fmt::print("Current thread id: {}\n",
+               fmt::streamed(std::this_thread::get_id()));
+  \endrst
+ */
+template <typename T>
+auto streamed(const T& value) -> detail::streamed_view<T> {
+  return {value};
+}
+
+namespace detail {
+
+// Formats an object of type T that has an overloaded ostream operator<<.
+template <typename T, typename Char>
+struct fallback_formatter<T, Char, enable_if_t<is_streamable<T, Char>::value>>
+    : basic_ostream_formatter<Char> {
+  using basic_ostream_formatter<Char>::format;
+};
+
+inline void vprint_directly(std::ostream& os, string_view format_str,
+                            format_args args) {
+  auto buffer = memory_buffer();
+  detail::vformat_to(buffer, format_str, args);
+  detail::write_buffer(os, buffer);
+}
+
+}  // namespace detail
+
+FMT_MODULE_EXPORT template <typename Char>
+void vprint(std::basic_ostream<Char>& os,
+            basic_string_view<type_identity_t<Char>> format_str,
+            basic_format_args<buffer_context<type_identity_t<Char>>> args) {
+  auto buffer = basic_memory_buffer<Char>();
+  detail::vformat_to(buffer, format_str, args);
+  if (detail::write_ostream_unicode(os, {buffer.data(), buffer.size()})) return;
+  detail::write_buffer(os, buffer);
+}
+
+/**
+  \rst
+  Prints formatted data to the stream *os*.
+
+  **Example**::
+
+    fmt::print(cerr, "Don't {}!", "panic");
+  \endrst
+ */
+FMT_MODULE_EXPORT template <typename... T>
+void print(std::ostream& os, format_string<T...> fmt, T&&... args) {
+  const auto& vargs = fmt::make_format_args(args...);
+  if (detail::is_utf8())
+    vprint(os, fmt, vargs);
+  else
+    detail::vprint_directly(os, fmt, vargs);
+}
+
+FMT_MODULE_EXPORT
+template <typename... Args>
+void print(std::wostream& os,
+           basic_format_string<wchar_t, type_identity_t<Args>...> fmt,
+           Args&&... args) {
+  vprint(os, fmt, fmt::make_format_args<buffer_context<wchar_t>>(args...));
+}
+
+FMT_END_NAMESPACE
+
+#endif  // FMT_OSTREAM_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/printf.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/printf.h
new file mode 100644
index 0000000..70a592d
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/printf.h
@@ -0,0 +1,640 @@
+// Formatting library for C++ - legacy printf implementation
+//
+// Copyright (c) 2012 - 2016, Victor Zverovich
+// All rights reserved.
+//
+// For the license information refer to format.h.
+
+#ifndef FMT_PRINTF_H_
+#define FMT_PRINTF_H_
+
+#include <algorithm>  // std::max
+#include <limits>     // std::numeric_limits
+
+#include "format.h"
+
+FMT_BEGIN_NAMESPACE
+FMT_MODULE_EXPORT_BEGIN
+
+template <typename T> struct printf_formatter { printf_formatter() = delete; };
+
+template <typename Char>
+class basic_printf_parse_context : public basic_format_parse_context<Char> {
+  using basic_format_parse_context<Char>::basic_format_parse_context;
+};
+
+template <typename OutputIt, typename Char> class basic_printf_context {
+ private:
+  OutputIt out_;
+  basic_format_args<basic_printf_context> args_;
+
+ public:
+  using char_type = Char;
+  using format_arg = basic_format_arg<basic_printf_context>;
+  using parse_context_type = basic_printf_parse_context<Char>;
+  template <typename T> using formatter_type = printf_formatter<T>;
+
+  /**
+    \rst
+    Constructs a ``printf_context`` object. References to the arguments are
+    stored in the context object so make sure they have appropriate lifetimes.
+    \endrst
+   */
+  basic_printf_context(OutputIt out,
+                       basic_format_args<basic_printf_context> args)
+      : out_(out), args_(args) {}
+
+  OutputIt out() { return out_; }
+  void advance_to(OutputIt it) { out_ = it; }
+
+  detail::locale_ref locale() { return {}; }
+
+  format_arg arg(int id) const { return args_.get(id); }
+
+  FMT_CONSTEXPR void on_error(const char* message) {
+    detail::error_handler().on_error(message);
+  }
+};
+
+FMT_BEGIN_DETAIL_NAMESPACE
+
+// Checks if a value fits in int - used to avoid warnings about comparing
+// signed and unsigned integers.
+template <bool IsSigned> struct int_checker {
+  template <typename T> static bool fits_in_int(T value) {
+    unsigned max = max_value<int>();
+    return value <= max;
+  }
+  static bool fits_in_int(bool) { return true; }
+};
+
+template <> struct int_checker<true> {
+  template <typename T> static bool fits_in_int(T value) {
+    return value >= (std::numeric_limits<int>::min)() &&
+           value <= max_value<int>();
+  }
+  static bool fits_in_int(int) { return true; }
+};
+
+class printf_precision_handler {
+ public:
+  template <typename T, FMT_ENABLE_IF(std::is_integral<T>::value)>
+  int operator()(T value) {
+    if (!int_checker<std::numeric_limits<T>::is_signed>::fits_in_int(value))
+      FMT_THROW(format_error("number is too big"));
+    return (std::max)(static_cast<int>(value), 0);
+  }
+
+  template <typename T, FMT_ENABLE_IF(!std::is_integral<T>::value)>
+  int operator()(T) {
+    FMT_THROW(format_error("precision is not integer"));
+    return 0;
+  }
+};
+
+// An argument visitor that returns true iff arg is a zero integer.
+class is_zero_int {
+ public:
+  template <typename T, FMT_ENABLE_IF(std::is_integral<T>::value)>
+  bool operator()(T value) {
+    return value == 0;
+  }
+
+  template <typename T, FMT_ENABLE_IF(!std::is_integral<T>::value)>
+  bool operator()(T) {
+    return false;
+  }
+};
+
+template <typename T> struct make_unsigned_or_bool : std::make_unsigned<T> {};
+
+template <> struct make_unsigned_or_bool<bool> { using type = bool; };
+
+template <typename T, typename Context> class arg_converter {
+ private:
+  using char_type = typename Context::char_type;
+
+  basic_format_arg<Context>& arg_;
+  char_type type_;
+
+ public:
+  arg_converter(basic_format_arg<Context>& arg, char_type type)
+      : arg_(arg), type_(type) {}
+
+  void operator()(bool value) {
+    if (type_ != 's') operator()<bool>(value);
+  }
+
+  template <typename U, FMT_ENABLE_IF(std::is_integral<U>::value)>
+  void operator()(U value) {
+    bool is_signed = type_ == 'd' || type_ == 'i';
+    using target_type = conditional_t<std::is_same<T, void>::value, U, T>;
+    if (const_check(sizeof(target_type) <= sizeof(int))) {
+      // Extra casts are used to silence warnings.
+      if (is_signed) {
+        arg_ = detail::make_arg<Context>(
+            static_cast<int>(static_cast<target_type>(value)));
+      } else {
+        using unsigned_type = typename make_unsigned_or_bool<target_type>::type;
+        arg_ = detail::make_arg<Context>(
+            static_cast<unsigned>(static_cast<unsigned_type>(value)));
+      }
+    } else {
+      if (is_signed) {
+        // glibc's printf doesn't sign extend arguments of smaller types:
+        //   std::printf("%lld", -42);  // prints "4294967254"
+        // but we don't have to do the same because it's a UB.
+        arg_ = detail::make_arg<Context>(static_cast<long long>(value));
+      } else {
+        arg_ = detail::make_arg<Context>(
+            static_cast<typename make_unsigned_or_bool<U>::type>(value));
+      }
+    }
+  }
+
+  template <typename U, FMT_ENABLE_IF(!std::is_integral<U>::value)>
+  void operator()(U) {}  // No conversion needed for non-integral types.
+};
+
+// Converts an integer argument to T for printf, if T is an integral type.
+// If T is void, the argument is converted to corresponding signed or unsigned
+// type depending on the type specifier: 'd' and 'i' - signed, other -
+// unsigned).
+template <typename T, typename Context, typename Char>
+void convert_arg(basic_format_arg<Context>& arg, Char type) {
+  visit_format_arg(arg_converter<T, Context>(arg, type), arg);
+}
+
+// Converts an integer argument to char for printf.
+template <typename Context> class char_converter {
+ private:
+  basic_format_arg<Context>& arg_;
+
+ public:
+  explicit char_converter(basic_format_arg<Context>& arg) : arg_(arg) {}
+
+  template <typename T, FMT_ENABLE_IF(std::is_integral<T>::value)>
+  void operator()(T value) {
+    arg_ = detail::make_arg<Context>(
+        static_cast<typename Context::char_type>(value));
+  }
+
+  template <typename T, FMT_ENABLE_IF(!std::is_integral<T>::value)>
+  void operator()(T) {}  // No conversion needed for non-integral types.
+};
+
+// An argument visitor that return a pointer to a C string if argument is a
+// string or null otherwise.
+template <typename Char> struct get_cstring {
+  template <typename T> const Char* operator()(T) { return nullptr; }
+  const Char* operator()(const Char* s) { return s; }
+};
+
+// Checks if an argument is a valid printf width specifier and sets
+// left alignment if it is negative.
+template <typename Char> class printf_width_handler {
+ private:
+  using format_specs = basic_format_specs<Char>;
+
+  format_specs& specs_;
+
+ public:
+  explicit printf_width_handler(format_specs& specs) : specs_(specs) {}
+
+  template <typename T, FMT_ENABLE_IF(std::is_integral<T>::value)>
+  unsigned operator()(T value) {
+    auto width = static_cast<uint32_or_64_or_128_t<T>>(value);
+    if (detail::is_negative(value)) {
+      specs_.align = align::left;
+      width = 0 - width;
+    }
+    unsigned int_max = max_value<int>();
+    if (width > int_max) FMT_THROW(format_error("number is too big"));
+    return static_cast<unsigned>(width);
+  }
+
+  template <typename T, FMT_ENABLE_IF(!std::is_integral<T>::value)>
+  unsigned operator()(T) {
+    FMT_THROW(format_error("width is not integer"));
+    return 0;
+  }
+};
+
+// The ``printf`` argument formatter.
+template <typename OutputIt, typename Char>
+class printf_arg_formatter : public arg_formatter<Char> {
+ private:
+  using base = arg_formatter<Char>;
+  using context_type = basic_printf_context<OutputIt, Char>;
+  using format_specs = basic_format_specs<Char>;
+
+  context_type& context_;
+
+  OutputIt write_null_pointer(bool is_string = false) {
+    auto s = this->specs;
+    s.type = presentation_type::none;
+    return write_bytes(this->out, is_string ? "(null)" : "(nil)", s);
+  }
+
+ public:
+  printf_arg_formatter(OutputIt iter, format_specs& s, context_type& ctx)
+      : base{iter, s, locale_ref()}, context_(ctx) {}
+
+  OutputIt operator()(monostate value) { return base::operator()(value); }
+
+  template <typename T, FMT_ENABLE_IF(detail::is_integral<T>::value)>
+  OutputIt operator()(T value) {
+    // MSVC2013 fails to compile separate overloads for bool and Char so use
+    // std::is_same instead.
+    if (std::is_same<T, Char>::value) {
+      format_specs fmt_specs = this->specs;
+      if (fmt_specs.type != presentation_type::none &&
+          fmt_specs.type != presentation_type::chr) {
+        return (*this)(static_cast<int>(value));
+      }
+      fmt_specs.sign = sign::none;
+      fmt_specs.alt = false;
+      fmt_specs.fill[0] = ' ';  // Ignore '0' flag for char types.
+      // align::numeric needs to be overwritten here since the '0' flag is
+      // ignored for non-numeric types
+      if (fmt_specs.align == align::none || fmt_specs.align == align::numeric)
+        fmt_specs.align = align::right;
+      return write<Char>(this->out, static_cast<Char>(value), fmt_specs);
+    }
+    return base::operator()(value);
+  }
+
+  template <typename T, FMT_ENABLE_IF(std::is_floating_point<T>::value)>
+  OutputIt operator()(T value) {
+    return base::operator()(value);
+  }
+
+  /** Formats a null-terminated C string. */
+  OutputIt operator()(const char* value) {
+    if (value) return base::operator()(value);
+    return write_null_pointer(this->specs.type != presentation_type::pointer);
+  }
+
+  /** Formats a null-terminated wide C string. */
+  OutputIt operator()(const wchar_t* value) {
+    if (value) return base::operator()(value);
+    return write_null_pointer(this->specs.type != presentation_type::pointer);
+  }
+
+  OutputIt operator()(basic_string_view<Char> value) {
+    return base::operator()(value);
+  }
+
+  /** Formats a pointer. */
+  OutputIt operator()(const void* value) {
+    return value ? base::operator()(value) : write_null_pointer();
+  }
+
+  /** Formats an argument of a custom (user-defined) type. */
+  OutputIt operator()(typename basic_format_arg<context_type>::handle handle) {
+    auto parse_ctx =
+        basic_printf_parse_context<Char>(basic_string_view<Char>());
+    handle.format(parse_ctx, context_);
+    return this->out;
+  }
+};
+
+template <typename Char>
+void parse_flags(basic_format_specs<Char>& specs, const Char*& it,
+                 const Char* end) {
+  for (; it != end; ++it) {
+    switch (*it) {
+    case '-':
+      specs.align = align::left;
+      break;
+    case '+':
+      specs.sign = sign::plus;
+      break;
+    case '0':
+      specs.fill[0] = '0';
+      break;
+    case ' ':
+      if (specs.sign != sign::plus) {
+        specs.sign = sign::space;
+      }
+      break;
+    case '#':
+      specs.alt = true;
+      break;
+    default:
+      return;
+    }
+  }
+}
+
+template <typename Char, typename GetArg>
+int parse_header(const Char*& it, const Char* end,
+                 basic_format_specs<Char>& specs, GetArg get_arg) {
+  int arg_index = -1;
+  Char c = *it;
+  if (c >= '0' && c <= '9') {
+    // Parse an argument index (if followed by '$') or a width possibly
+    // preceded with '0' flag(s).
+    int value = parse_nonnegative_int(it, end, -1);
+    if (it != end && *it == '$') {  // value is an argument index
+      ++it;
+      arg_index = value != -1 ? value : max_value<int>();
+    } else {
+      if (c == '0') specs.fill[0] = '0';
+      if (value != 0) {
+        // Nonzero value means that we parsed width and don't need to
+        // parse it or flags again, so return now.
+        if (value == -1) FMT_THROW(format_error("number is too big"));
+        specs.width = value;
+        return arg_index;
+      }
+    }
+  }
+  parse_flags(specs, it, end);
+  // Parse width.
+  if (it != end) {
+    if (*it >= '0' && *it <= '9') {
+      specs.width = parse_nonnegative_int(it, end, -1);
+      if (specs.width == -1) FMT_THROW(format_error("number is too big"));
+    } else if (*it == '*') {
+      ++it;
+      specs.width = static_cast<int>(visit_format_arg(
+          detail::printf_width_handler<Char>(specs), get_arg(-1)));
+    }
+  }
+  return arg_index;
+}
+
+template <typename Char, typename Context>
+void vprintf(buffer<Char>& buf, basic_string_view<Char> format,
+             basic_format_args<Context> args) {
+  using OutputIt = buffer_appender<Char>;
+  auto out = OutputIt(buf);
+  auto context = basic_printf_context<OutputIt, Char>(out, args);
+  auto parse_ctx = basic_printf_parse_context<Char>(format);
+
+  // Returns the argument with specified index or, if arg_index is -1, the next
+  // argument.
+  auto get_arg = [&](int arg_index) {
+    if (arg_index < 0)
+      arg_index = parse_ctx.next_arg_id();
+    else
+      parse_ctx.check_arg_id(--arg_index);
+    return detail::get_arg(context, arg_index);
+  };
+
+  const Char* start = parse_ctx.begin();
+  const Char* end = parse_ctx.end();
+  auto it = start;
+  while (it != end) {
+    if (!detail::find<false, Char>(it, end, '%', it)) {
+      it = end;  // detail::find leaves it == nullptr if it doesn't find '%'
+      break;
+    }
+    Char c = *it++;
+    if (it != end && *it == c) {
+      out = detail::write(
+          out, basic_string_view<Char>(start, detail::to_unsigned(it - start)));
+      start = ++it;
+      continue;
+    }
+    out = detail::write(out, basic_string_view<Char>(
+                                 start, detail::to_unsigned(it - 1 - start)));
+
+    basic_format_specs<Char> specs;
+    specs.align = align::right;
+
+    // Parse argument index, flags and width.
+    int arg_index = parse_header(it, end, specs, get_arg);
+    if (arg_index == 0) parse_ctx.on_error("argument not found");
+
+    // Parse precision.
+    if (it != end && *it == '.') {
+      ++it;
+      c = it != end ? *it : 0;
+      if ('0' <= c && c <= '9') {
+        specs.precision = parse_nonnegative_int(it, end, 0);
+      } else if (c == '*') {
+        ++it;
+        specs.precision = static_cast<int>(
+            visit_format_arg(detail::printf_precision_handler(), get_arg(-1)));
+      } else {
+        specs.precision = 0;
+      }
+    }
+
+    auto arg = get_arg(arg_index);
+    // For d, i, o, u, x, and X conversion specifiers, if a precision is
+    // specified, the '0' flag is ignored
+    if (specs.precision >= 0 && arg.is_integral())
+      specs.fill[0] =
+          ' ';  // Ignore '0' flag for non-numeric types or if '-' present.
+    if (specs.precision >= 0 && arg.type() == detail::type::cstring_type) {
+      auto str = visit_format_arg(detail::get_cstring<Char>(), arg);
+      auto str_end = str + specs.precision;
+      auto nul = std::find(str, str_end, Char());
+      arg = detail::make_arg<basic_printf_context<OutputIt, Char>>(
+          basic_string_view<Char>(
+              str, detail::to_unsigned(nul != str_end ? nul - str
+                                                      : specs.precision)));
+    }
+    if (specs.alt && visit_format_arg(detail::is_zero_int(), arg))
+      specs.alt = false;
+    if (specs.fill[0] == '0') {
+      if (arg.is_arithmetic() && specs.align != align::left)
+        specs.align = align::numeric;
+      else
+        specs.fill[0] = ' ';  // Ignore '0' flag for non-numeric types or if '-'
+                              // flag is also present.
+    }
+
+    // Parse length and convert the argument to the required type.
+    c = it != end ? *it++ : 0;
+    Char t = it != end ? *it : 0;
+    using detail::convert_arg;
+    switch (c) {
+    case 'h':
+      if (t == 'h') {
+        ++it;
+        t = it != end ? *it : 0;
+        convert_arg<signed char>(arg, t);
+      } else {
+        convert_arg<short>(arg, t);
+      }
+      break;
+    case 'l':
+      if (t == 'l') {
+        ++it;
+        t = it != end ? *it : 0;
+        convert_arg<long long>(arg, t);
+      } else {
+        convert_arg<long>(arg, t);
+      }
+      break;
+    case 'j':
+      convert_arg<intmax_t>(arg, t);
+      break;
+    case 'z':
+      convert_arg<size_t>(arg, t);
+      break;
+    case 't':
+      convert_arg<std::ptrdiff_t>(arg, t);
+      break;
+    case 'L':
+      // printf produces garbage when 'L' is omitted for long double, no
+      // need to do the same.
+      break;
+    default:
+      --it;
+      convert_arg<void>(arg, c);
+    }
+
+    // Parse type.
+    if (it == end) FMT_THROW(format_error("invalid format string"));
+    char type = static_cast<char>(*it++);
+    if (arg.is_integral()) {
+      // Normalize type.
+      switch (type) {
+      case 'i':
+      case 'u':
+        type = 'd';
+        break;
+      case 'c':
+        visit_format_arg(
+            detail::char_converter<basic_printf_context<OutputIt, Char>>(arg),
+            arg);
+        break;
+      }
+    }
+    specs.type = parse_presentation_type(type);
+    if (specs.type == presentation_type::none)
+      parse_ctx.on_error("invalid type specifier");
+
+    start = it;
+
+    // Format argument.
+    out = visit_format_arg(
+        detail::printf_arg_formatter<OutputIt, Char>(out, specs, context), arg);
+  }
+  detail::write(out, basic_string_view<Char>(start, to_unsigned(it - start)));
+}
+FMT_END_DETAIL_NAMESPACE
+
+template <typename Char>
+using basic_printf_context_t =
+    basic_printf_context<detail::buffer_appender<Char>, Char>;
+
+using printf_context = basic_printf_context_t<char>;
+using wprintf_context = basic_printf_context_t<wchar_t>;
+
+using printf_args = basic_format_args<printf_context>;
+using wprintf_args = basic_format_args<wprintf_context>;
+
+/**
+  \rst
+  Constructs an `~fmt::format_arg_store` object that contains references to
+  arguments and can be implicitly converted to `~fmt::printf_args`.
+  \endrst
+ */
+template <typename... T>
+inline auto make_printf_args(const T&... args)
+    -> format_arg_store<printf_context, T...> {
+  return {args...};
+}
+
+/**
+  \rst
+  Constructs an `~fmt::format_arg_store` object that contains references to
+  arguments and can be implicitly converted to `~fmt::wprintf_args`.
+  \endrst
+ */
+template <typename... T>
+inline auto make_wprintf_args(const T&... args)
+    -> format_arg_store<wprintf_context, T...> {
+  return {args...};
+}
+
+template <typename S, typename Char = char_t<S>>
+inline auto vsprintf(
+    const S& fmt,
+    basic_format_args<basic_printf_context_t<type_identity_t<Char>>> args)
+    -> std::basic_string<Char> {
+  basic_memory_buffer<Char> buffer;
+  vprintf(buffer, detail::to_string_view(fmt), args);
+  return to_string(buffer);
+}
+
+/**
+  \rst
+  Formats arguments and returns the result as a string.
+
+  **Example**::
+
+    std::string message = fmt::sprintf("The answer is %d", 42);
+  \endrst
+*/
+template <typename S, typename... T,
+          typename Char = enable_if_t<detail::is_string<S>::value, char_t<S>>>
+inline auto sprintf(const S& fmt, const T&... args) -> std::basic_string<Char> {
+  using context = basic_printf_context_t<Char>;
+  return vsprintf(detail::to_string_view(fmt),
+                  fmt::make_format_args<context>(args...));
+}
+
+template <typename S, typename Char = char_t<S>>
+inline auto vfprintf(
+    std::FILE* f, const S& fmt,
+    basic_format_args<basic_printf_context_t<type_identity_t<Char>>> args)
+    -> int {
+  basic_memory_buffer<Char> buffer;
+  vprintf(buffer, detail::to_string_view(fmt), args);
+  size_t size = buffer.size();
+  return std::fwrite(buffer.data(), sizeof(Char), size, f) < size
+             ? -1
+             : static_cast<int>(size);
+}
+
+/**
+  \rst
+  Prints formatted data to the file *f*.
+
+  **Example**::
+
+    fmt::fprintf(stderr, "Don't %s!", "panic");
+  \endrst
+ */
+template <typename S, typename... T, typename Char = char_t<S>>
+inline auto fprintf(std::FILE* f, const S& fmt, const T&... args) -> int {
+  using context = basic_printf_context_t<Char>;
+  return vfprintf(f, detail::to_string_view(fmt),
+                  fmt::make_format_args<context>(args...));
+}
+
+template <typename S, typename Char = char_t<S>>
+inline auto vprintf(
+    const S& fmt,
+    basic_format_args<basic_printf_context_t<type_identity_t<Char>>> args)
+    -> int {
+  return vfprintf(stdout, detail::to_string_view(fmt), args);
+}
+
+/**
+  \rst
+  Prints formatted data to ``stdout``.
+
+  **Example**::
+
+    fmt::printf("Elapsed time: %.2f seconds", 1.23);
+  \endrst
+ */
+template <typename S, typename... T, FMT_ENABLE_IF(detail::is_string<S>::value)>
+inline auto printf(const S& fmt, const T&... args) -> int {
+  return vprintf(
+      detail::to_string_view(fmt),
+      fmt::make_format_args<basic_printf_context_t<char_t<S>>>(args...));
+}
+
+FMT_MODULE_EXPORT_END
+FMT_END_NAMESPACE
+
+#endif  // FMT_PRINTF_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/ranges.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/ranges.h
new file mode 100644
index 0000000..dea7d60
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/ranges.h
@@ -0,0 +1,722 @@
+// Formatting library for C++ - experimental range support
+//
+// Copyright (c) 2012 - present, Victor Zverovich
+// All rights reserved.
+//
+// For the license information refer to format.h.
+//
+// Copyright (c) 2018 - present, Remotion (Igor Schulz)
+// All Rights Reserved
+// {fmt} support for ranges, containers and types tuple interface.
+
+#ifndef FMT_RANGES_H_
+#define FMT_RANGES_H_
+
+#include <initializer_list>
+#include <tuple>
+#include <type_traits>
+
+#include "format.h"
+
+FMT_BEGIN_NAMESPACE
+
+namespace detail {
+
+template <typename RangeT, typename OutputIterator>
+OutputIterator copy(const RangeT& range, OutputIterator out) {
+  for (auto it = range.begin(), end = range.end(); it != end; ++it)
+    *out++ = *it;
+  return out;
+}
+
+template <typename OutputIterator>
+OutputIterator copy(const char* str, OutputIterator out) {
+  while (*str) *out++ = *str++;
+  return out;
+}
+
+template <typename OutputIterator>
+OutputIterator copy(char ch, OutputIterator out) {
+  *out++ = ch;
+  return out;
+}
+
+template <typename OutputIterator>
+OutputIterator copy(wchar_t ch, OutputIterator out) {
+  *out++ = ch;
+  return out;
+}
+
+// Returns true if T has a std::string-like interface, like std::string_view.
+template <typename T> class is_std_string_like {
+  template <typename U>
+  static auto check(U* p)
+      -> decltype((void)p->find('a'), p->length(), (void)p->data(), int());
+  template <typename> static void check(...);
+
+ public:
+  static constexpr const bool value =
+      is_string<T>::value ||
+      std::is_convertible<T, std_string_view<char>>::value ||
+      !std::is_void<decltype(check<T>(nullptr))>::value;
+};
+
+template <typename Char>
+struct is_std_string_like<fmt::basic_string_view<Char>> : std::true_type {};
+
+template <typename T> class is_map {
+  template <typename U> static auto check(U*) -> typename U::mapped_type;
+  template <typename> static void check(...);
+
+ public:
+#ifdef FMT_FORMAT_MAP_AS_LIST
+  static constexpr const bool value = false;
+#else
+  static constexpr const bool value =
+      !std::is_void<decltype(check<T>(nullptr))>::value;
+#endif
+};
+
+template <typename T> class is_set {
+  template <typename U> static auto check(U*) -> typename U::key_type;
+  template <typename> static void check(...);
+
+ public:
+#ifdef FMT_FORMAT_SET_AS_LIST
+  static constexpr const bool value = false;
+#else
+  static constexpr const bool value =
+      !std::is_void<decltype(check<T>(nullptr))>::value && !is_map<T>::value;
+#endif
+};
+
+template <typename... Ts> struct conditional_helper {};
+
+template <typename T, typename _ = void> struct is_range_ : std::false_type {};
+
+#if !FMT_MSC_VERSION || FMT_MSC_VERSION > 1800
+
+#  define FMT_DECLTYPE_RETURN(val)  \
+    ->decltype(val) { return val; } \
+    static_assert(                  \
+        true, "")  // This makes it so that a semicolon is required after the
+                   // macro, which helps clang-format handle the formatting.
+
+// C array overload
+template <typename T, std::size_t N>
+auto range_begin(const T (&arr)[N]) -> const T* {
+  return arr;
+}
+template <typename T, std::size_t N>
+auto range_end(const T (&arr)[N]) -> const T* {
+  return arr + N;
+}
+
+template <typename T, typename Enable = void>
+struct has_member_fn_begin_end_t : std::false_type {};
+
+template <typename T>
+struct has_member_fn_begin_end_t<T, void_t<decltype(std::declval<T>().begin()),
+                                           decltype(std::declval<T>().end())>>
+    : std::true_type {};
+
+// Member function overload
+template <typename T>
+auto range_begin(T&& rng) FMT_DECLTYPE_RETURN(static_cast<T&&>(rng).begin());
+template <typename T>
+auto range_end(T&& rng) FMT_DECLTYPE_RETURN(static_cast<T&&>(rng).end());
+
+// ADL overload. Only participates in overload resolution if member functions
+// are not found.
+template <typename T>
+auto range_begin(T&& rng)
+    -> enable_if_t<!has_member_fn_begin_end_t<T&&>::value,
+                   decltype(begin(static_cast<T&&>(rng)))> {
+  return begin(static_cast<T&&>(rng));
+}
+template <typename T>
+auto range_end(T&& rng) -> enable_if_t<!has_member_fn_begin_end_t<T&&>::value,
+                                       decltype(end(static_cast<T&&>(rng)))> {
+  return end(static_cast<T&&>(rng));
+}
+
+template <typename T, typename Enable = void>
+struct has_const_begin_end : std::false_type {};
+template <typename T, typename Enable = void>
+struct has_mutable_begin_end : std::false_type {};
+
+template <typename T>
+struct has_const_begin_end<
+    T,
+    void_t<
+        decltype(detail::range_begin(std::declval<const remove_cvref_t<T>&>())),
+        decltype(detail::range_end(std::declval<const remove_cvref_t<T>&>()))>>
+    : std::true_type {};
+
+template <typename T>
+struct has_mutable_begin_end<
+    T, void_t<decltype(detail::range_begin(std::declval<T>())),
+              decltype(detail::range_end(std::declval<T>())),
+              enable_if_t<std::is_copy_constructible<T>::value>>>
+    : std::true_type {};
+
+template <typename T>
+struct is_range_<T, void>
+    : std::integral_constant<bool, (has_const_begin_end<T>::value ||
+                                    has_mutable_begin_end<T>::value)> {};
+#  undef FMT_DECLTYPE_RETURN
+#endif
+
+// tuple_size and tuple_element check.
+template <typename T> class is_tuple_like_ {
+  template <typename U>
+  static auto check(U* p) -> decltype(std::tuple_size<U>::value, int());
+  template <typename> static void check(...);
+
+ public:
+  static constexpr const bool value =
+      !std::is_void<decltype(check<T>(nullptr))>::value;
+};
+
+// Check for integer_sequence
+#if defined(__cpp_lib_integer_sequence) || FMT_MSC_VERSION >= 1900
+template <typename T, T... N>
+using integer_sequence = std::integer_sequence<T, N...>;
+template <size_t... N> using index_sequence = std::index_sequence<N...>;
+template <size_t N> using make_index_sequence = std::make_index_sequence<N>;
+#else
+template <typename T, T... N> struct integer_sequence {
+  using value_type = T;
+
+  static FMT_CONSTEXPR size_t size() { return sizeof...(N); }
+};
+
+template <size_t... N> using index_sequence = integer_sequence<size_t, N...>;
+
+template <typename T, size_t N, T... Ns>
+struct make_integer_sequence : make_integer_sequence<T, N - 1, N - 1, Ns...> {};
+template <typename T, T... Ns>
+struct make_integer_sequence<T, 0, Ns...> : integer_sequence<T, Ns...> {};
+
+template <size_t N>
+using make_index_sequence = make_integer_sequence<size_t, N>;
+#endif
+
+template <typename T>
+using tuple_index_sequence = make_index_sequence<std::tuple_size<T>::value>;
+
+template <typename T, typename C, bool = is_tuple_like_<T>::value>
+class is_tuple_formattable_ {
+ public:
+  static constexpr const bool value = false;
+};
+template <typename T, typename C> class is_tuple_formattable_<T, C, true> {
+  template <std::size_t... I>
+  static std::true_type check2(index_sequence<I...>,
+                               integer_sequence<bool, (I == I)...>);
+  static std::false_type check2(...);
+  template <std::size_t... I>
+  static decltype(check2(
+      index_sequence<I...>{},
+      integer_sequence<
+          bool, (is_formattable<typename std::tuple_element<I, T>::type,
+                                C>::value)...>{})) check(index_sequence<I...>);
+
+ public:
+  static constexpr const bool value =
+      decltype(check(tuple_index_sequence<T>{}))::value;
+};
+
+template <class Tuple, class F, size_t... Is>
+void for_each(index_sequence<Is...>, Tuple&& tup, F&& f) noexcept {
+  using std::get;
+  // using free function get<I>(T) now.
+  const int _[] = {0, ((void)f(get<Is>(tup)), 0)...};
+  (void)_;  // blocks warnings
+}
+
+template <class T>
+FMT_CONSTEXPR make_index_sequence<std::tuple_size<T>::value> get_indexes(
+    T const&) {
+  return {};
+}
+
+template <class Tuple, class F> void for_each(Tuple&& tup, F&& f) {
+  const auto indexes = get_indexes(tup);
+  for_each(indexes, std::forward<Tuple>(tup), std::forward<F>(f));
+}
+
+#if FMT_MSC_VERSION && FMT_MSC_VERSION < 1920
+// Older MSVC doesn't get the reference type correctly for arrays.
+template <typename R> struct range_reference_type_impl {
+  using type = decltype(*detail::range_begin(std::declval<R&>()));
+};
+
+template <typename T, std::size_t N> struct range_reference_type_impl<T[N]> {
+  using type = T&;
+};
+
+template <typename T>
+using range_reference_type = typename range_reference_type_impl<T>::type;
+#else
+template <typename Range>
+using range_reference_type =
+    decltype(*detail::range_begin(std::declval<Range&>()));
+#endif
+
+// We don't use the Range's value_type for anything, but we do need the Range's
+// reference type, with cv-ref stripped.
+template <typename Range>
+using uncvref_type = remove_cvref_t<range_reference_type<Range>>;
+
+template <typename Range>
+using uncvref_first_type =
+    remove_cvref_t<decltype(std::declval<range_reference_type<Range>>().first)>;
+
+template <typename Range>
+using uncvref_second_type = remove_cvref_t<
+    decltype(std::declval<range_reference_type<Range>>().second)>;
+
+template <typename OutputIt> OutputIt write_delimiter(OutputIt out) {
+  *out++ = ',';
+  *out++ = ' ';
+  return out;
+}
+
+template <typename Char, typename OutputIt>
+auto write_range_entry(OutputIt out, basic_string_view<Char> str) -> OutputIt {
+  return write_escaped_string(out, str);
+}
+
+template <typename Char, typename OutputIt, typename T,
+          FMT_ENABLE_IF(std::is_convertible<T, std_string_view<char>>::value)>
+inline auto write_range_entry(OutputIt out, const T& str) -> OutputIt {
+  auto sv = std_string_view<Char>(str);
+  return write_range_entry<Char>(out, basic_string_view<Char>(sv));
+}
+
+template <typename Char, typename OutputIt, typename Arg,
+          FMT_ENABLE_IF(std::is_same<Arg, Char>::value)>
+OutputIt write_range_entry(OutputIt out, const Arg v) {
+  return write_escaped_char(out, v);
+}
+
+template <
+    typename Char, typename OutputIt, typename Arg,
+    FMT_ENABLE_IF(!is_std_string_like<typename std::decay<Arg>::type>::value &&
+                  !std::is_same<Arg, Char>::value)>
+OutputIt write_range_entry(OutputIt out, const Arg& v) {
+  return write<Char>(out, v);
+}
+
+}  // namespace detail
+
+template <typename T> struct is_tuple_like {
+  static constexpr const bool value =
+      detail::is_tuple_like_<T>::value && !detail::is_range_<T>::value;
+};
+
+template <typename T, typename C> struct is_tuple_formattable {
+  static constexpr const bool value =
+      detail::is_tuple_formattable_<T, C>::value;
+};
+
+template <typename TupleT, typename Char>
+struct formatter<TupleT, Char,
+                 enable_if_t<fmt::is_tuple_like<TupleT>::value &&
+                             fmt::is_tuple_formattable<TupleT, Char>::value>> {
+ private:
+  basic_string_view<Char> separator_ = detail::string_literal<Char, ',', ' '>{};
+  basic_string_view<Char> opening_bracket_ =
+      detail::string_literal<Char, '('>{};
+  basic_string_view<Char> closing_bracket_ =
+      detail::string_literal<Char, ')'>{};
+
+  // C++11 generic lambda for format().
+  template <typename FormatContext> struct format_each {
+    template <typename T> void operator()(const T& v) {
+      if (i > 0) out = detail::copy_str<Char>(separator, out);
+      out = detail::write_range_entry<Char>(out, v);
+      ++i;
+    }
+    int i;
+    typename FormatContext::iterator& out;
+    basic_string_view<Char> separator;
+  };
+
+ public:
+  FMT_CONSTEXPR formatter() {}
+
+  FMT_CONSTEXPR void set_separator(basic_string_view<Char> sep) {
+    separator_ = sep;
+  }
+
+  FMT_CONSTEXPR void set_brackets(basic_string_view<Char> open,
+                                  basic_string_view<Char> close) {
+    opening_bracket_ = open;
+    closing_bracket_ = close;
+  }
+
+  template <typename ParseContext>
+  FMT_CONSTEXPR auto parse(ParseContext& ctx) -> decltype(ctx.begin()) {
+    return ctx.begin();
+  }
+
+  template <typename FormatContext = format_context>
+  auto format(const TupleT& values, FormatContext& ctx) const
+      -> decltype(ctx.out()) {
+    auto out = ctx.out();
+    out = detail::copy_str<Char>(opening_bracket_, out);
+    detail::for_each(values, format_each<FormatContext>{0, out, separator_});
+    out = detail::copy_str<Char>(closing_bracket_, out);
+    return out;
+  }
+};
+
+template <typename T, typename Char> struct is_range {
+  static constexpr const bool value =
+      detail::is_range_<T>::value && !detail::is_std_string_like<T>::value &&
+      !std::is_convertible<T, std::basic_string<Char>>::value &&
+      !std::is_convertible<T, detail::std_string_view<Char>>::value;
+};
+
+namespace detail {
+template <typename Context> struct range_mapper {
+  using mapper = arg_mapper<Context>;
+
+  template <typename T,
+            FMT_ENABLE_IF(has_formatter<remove_cvref_t<T>, Context>::value)>
+  static auto map(T&& value) -> T&& {
+    return static_cast<T&&>(value);
+  }
+  template <typename T,
+            FMT_ENABLE_IF(!has_formatter<remove_cvref_t<T>, Context>::value)>
+  static auto map(T&& value)
+      -> decltype(mapper().map(static_cast<T&&>(value))) {
+    return mapper().map(static_cast<T&&>(value));
+  }
+};
+
+template <typename Char, typename Element>
+using range_formatter_type = conditional_t<
+    is_formattable<Element, Char>::value,
+    formatter<remove_cvref_t<decltype(range_mapper<buffer_context<Char>>{}.map(
+                  std::declval<Element>()))>,
+              Char>,
+    fallback_formatter<Element, Char>>;
+
+template <typename R>
+using maybe_const_range =
+    conditional_t<has_const_begin_end<R>::value, const R, R>;
+
+// Workaround a bug in MSVC 2015 and earlier.
+#if !FMT_MSC_VERSION || FMT_MSC_VERSION >= 1910
+template <typename R, typename Char>
+struct is_formattable_delayed
+    : disjunction<
+          is_formattable<uncvref_type<maybe_const_range<R>>, Char>,
+          has_fallback_formatter<uncvref_type<maybe_const_range<R>>, Char>> {};
+#endif
+
+}  // namespace detail
+
+template <typename T, typename Char, typename Enable = void>
+struct range_formatter;
+
+template <typename T, typename Char>
+struct range_formatter<
+    T, Char,
+    enable_if_t<conjunction<
+        std::is_same<T, remove_cvref_t<T>>,
+        disjunction<is_formattable<T, Char>,
+                    detail::has_fallback_formatter<T, Char>>>::value>> {
+ private:
+  detail::range_formatter_type<Char, T> underlying_;
+  bool custom_specs_ = false;
+  basic_string_view<Char> separator_ = detail::string_literal<Char, ',', ' '>{};
+  basic_string_view<Char> opening_bracket_ =
+      detail::string_literal<Char, '['>{};
+  basic_string_view<Char> closing_bracket_ =
+      detail::string_literal<Char, ']'>{};
+
+  template <class U>
+  FMT_CONSTEXPR static auto maybe_set_debug_format(U& u, int)
+      -> decltype(u.set_debug_format()) {
+    u.set_debug_format();
+  }
+
+  template <class U>
+  FMT_CONSTEXPR static void maybe_set_debug_format(U&, ...) {}
+
+  FMT_CONSTEXPR void maybe_set_debug_format() {
+    maybe_set_debug_format(underlying_, 0);
+  }
+
+ public:
+  FMT_CONSTEXPR range_formatter() {}
+
+  FMT_CONSTEXPR auto underlying() -> detail::range_formatter_type<Char, T>& {
+    return underlying_;
+  }
+
+  FMT_CONSTEXPR void set_separator(basic_string_view<Char> sep) {
+    separator_ = sep;
+  }
+
+  FMT_CONSTEXPR void set_brackets(basic_string_view<Char> open,
+                                  basic_string_view<Char> close) {
+    opening_bracket_ = open;
+    closing_bracket_ = close;
+  }
+
+  template <typename ParseContext>
+  FMT_CONSTEXPR auto parse(ParseContext& ctx) -> decltype(ctx.begin()) {
+    auto it = ctx.begin();
+    auto end = ctx.end();
+    if (it == end || *it == '}') {
+      maybe_set_debug_format();
+      return it;
+    }
+
+    if (*it == 'n') {
+      set_brackets({}, {});
+      ++it;
+    }
+
+    if (*it == '}') {
+      maybe_set_debug_format();
+      return it;
+    }
+
+    if (*it != ':')
+      FMT_THROW(format_error("no other top-level range formatters supported"));
+
+    custom_specs_ = true;
+    ++it;
+    ctx.advance_to(it);
+    return underlying_.parse(ctx);
+  }
+
+  template <typename R, class FormatContext>
+  auto format(R&& range, FormatContext& ctx) const -> decltype(ctx.out()) {
+    detail::range_mapper<buffer_context<Char>> mapper;
+    auto out = ctx.out();
+    out = detail::copy_str<Char>(opening_bracket_, out);
+    int i = 0;
+    auto it = detail::range_begin(range);
+    auto end = detail::range_end(range);
+    for (; it != end; ++it) {
+      if (i > 0) out = detail::copy_str<Char>(separator_, out);
+      ;
+      ctx.advance_to(out);
+      out = underlying_.format(mapper.map(*it), ctx);
+      ++i;
+    }
+    out = detail::copy_str<Char>(closing_bracket_, out);
+    return out;
+  }
+};
+
+enum class range_format { disabled, map, set, sequence, string, debug_string };
+
+namespace detail {
+template <typename T> struct range_format_kind_ {
+  static constexpr auto value = std::is_same<range_reference_type<T>, T>::value
+                                    ? range_format::disabled
+                                : is_map<T>::value ? range_format::map
+                                : is_set<T>::value ? range_format::set
+                                                   : range_format::sequence;
+};
+
+template <range_format K, typename R, typename Char, typename Enable = void>
+struct range_default_formatter;
+
+template <range_format K>
+using range_format_constant = std::integral_constant<range_format, K>;
+
+template <range_format K, typename R, typename Char>
+struct range_default_formatter<
+    K, R, Char,
+    enable_if_t<(K == range_format::sequence || K == range_format::map ||
+                 K == range_format::set)>> {
+  using range_type = detail::maybe_const_range<R>;
+  range_formatter<detail::uncvref_type<range_type>, Char> underlying_;
+
+  FMT_CONSTEXPR range_default_formatter() { init(range_format_constant<K>()); }
+
+  FMT_CONSTEXPR void init(range_format_constant<range_format::set>) {
+    underlying_.set_brackets(detail::string_literal<Char, '{'>{},
+                             detail::string_literal<Char, '}'>{});
+  }
+
+  FMT_CONSTEXPR void init(range_format_constant<range_format::map>) {
+    underlying_.set_brackets(detail::string_literal<Char, '{'>{},
+                             detail::string_literal<Char, '}'>{});
+    underlying_.underlying().set_brackets({}, {});
+    underlying_.underlying().set_separator(
+        detail::string_literal<Char, ':', ' '>{});
+  }
+
+  FMT_CONSTEXPR void init(range_format_constant<range_format::sequence>) {}
+
+  template <typename ParseContext>
+  FMT_CONSTEXPR auto parse(ParseContext& ctx) -> decltype(ctx.begin()) {
+    return underlying_.parse(ctx);
+  }
+
+  template <typename FormatContext>
+  auto format(range_type& range, FormatContext& ctx) const
+      -> decltype(ctx.out()) {
+    return underlying_.format(range, ctx);
+  }
+};
+}  // namespace detail
+
+template <typename T, typename Char, typename Enable = void>
+struct range_format_kind
+    : conditional_t<
+          is_range<T, Char>::value, detail::range_format_kind_<T>,
+          std::integral_constant<range_format, range_format::disabled>> {};
+
+template <typename R, typename Char>
+struct formatter<
+    R, Char,
+    enable_if_t<conjunction<bool_constant<range_format_kind<R, Char>::value !=
+                                          range_format::disabled>
+// Workaround a bug in MSVC 2015 and earlier.
+#if !FMT_MSC_VERSION || FMT_MSC_VERSION >= 1910
+                            ,
+                            detail::is_formattable_delayed<R, Char>
+#endif
+                            >::value>>
+    : detail::range_default_formatter<range_format_kind<R, Char>::value, R,
+                                      Char> {
+};
+
+template <typename Char, typename... T> struct tuple_join_view : detail::view {
+  const std::tuple<T...>& tuple;
+  basic_string_view<Char> sep;
+
+  tuple_join_view(const std::tuple<T...>& t, basic_string_view<Char> s)
+      : tuple(t), sep{s} {}
+};
+
+template <typename Char, typename... T>
+using tuple_arg_join = tuple_join_view<Char, T...>;
+
+// Define FMT_TUPLE_JOIN_SPECIFIERS to enable experimental format specifiers
+// support in tuple_join. It is disabled by default because of issues with
+// the dynamic width and precision.
+#ifndef FMT_TUPLE_JOIN_SPECIFIERS
+#  define FMT_TUPLE_JOIN_SPECIFIERS 0
+#endif
+
+template <typename Char, typename... T>
+struct formatter<tuple_join_view<Char, T...>, Char> {
+  template <typename ParseContext>
+  FMT_CONSTEXPR auto parse(ParseContext& ctx) -> decltype(ctx.begin()) {
+    return do_parse(ctx, std::integral_constant<size_t, sizeof...(T)>());
+  }
+
+  template <typename FormatContext>
+  auto format(const tuple_join_view<Char, T...>& value,
+              FormatContext& ctx) const -> typename FormatContext::iterator {
+    return do_format(value, ctx,
+                     std::integral_constant<size_t, sizeof...(T)>());
+  }
+
+ private:
+  std::tuple<formatter<typename std::decay<T>::type, Char>...> formatters_;
+
+  template <typename ParseContext>
+  FMT_CONSTEXPR auto do_parse(ParseContext& ctx,
+                              std::integral_constant<size_t, 0>)
+      -> decltype(ctx.begin()) {
+    return ctx.begin();
+  }
+
+  template <typename ParseContext, size_t N>
+  FMT_CONSTEXPR auto do_parse(ParseContext& ctx,
+                              std::integral_constant<size_t, N>)
+      -> decltype(ctx.begin()) {
+    auto end = ctx.begin();
+#if FMT_TUPLE_JOIN_SPECIFIERS
+    end = std::get<sizeof...(T) - N>(formatters_).parse(ctx);
+    if (N > 1) {
+      auto end1 = do_parse(ctx, std::integral_constant<size_t, N - 1>());
+      if (end != end1)
+        FMT_THROW(format_error("incompatible format specs for tuple elements"));
+    }
+#endif
+    return end;
+  }
+
+  template <typename FormatContext>
+  auto do_format(const tuple_join_view<Char, T...>&, FormatContext& ctx,
+                 std::integral_constant<size_t, 0>) const ->
+      typename FormatContext::iterator {
+    return ctx.out();
+  }
+
+  template <typename FormatContext, size_t N>
+  auto do_format(const tuple_join_view<Char, T...>& value, FormatContext& ctx,
+                 std::integral_constant<size_t, N>) const ->
+      typename FormatContext::iterator {
+    auto out = std::get<sizeof...(T) - N>(formatters_)
+                   .format(std::get<sizeof...(T) - N>(value.tuple), ctx);
+    if (N > 1) {
+      out = std::copy(value.sep.begin(), value.sep.end(), out);
+      ctx.advance_to(out);
+      return do_format(value, ctx, std::integral_constant<size_t, N - 1>());
+    }
+    return out;
+  }
+};
+
+FMT_MODULE_EXPORT_BEGIN
+
+/**
+  \rst
+  Returns an object that formats `tuple` with elements separated by `sep`.
+
+  **Example**::
+
+    std::tuple<int, char> t = {1, 'a'};
+    fmt::print("{}", fmt::join(t, ", "));
+    // Output: "1, a"
+  \endrst
+ */
+template <typename... T>
+FMT_CONSTEXPR auto join(const std::tuple<T...>& tuple, string_view sep)
+    -> tuple_join_view<char, T...> {
+  return {tuple, sep};
+}
+
+template <typename... T>
+FMT_CONSTEXPR auto join(const std::tuple<T...>& tuple,
+                        basic_string_view<wchar_t> sep)
+    -> tuple_join_view<wchar_t, T...> {
+  return {tuple, sep};
+}
+
+/**
+  \rst
+  Returns an object that formats `initializer_list` with elements separated by
+  `sep`.
+
+  **Example**::
+
+    fmt::print("{}", fmt::join({1, 2, 3}, ", "));
+    // Output: "1, 2, 3"
+  \endrst
+ */
+template <typename T>
+auto join(std::initializer_list<T> list, string_view sep)
+    -> join_view<const T*, const T*> {
+  return join(std::begin(list), std::end(list), sep);
+}
+
+FMT_MODULE_EXPORT_END
+FMT_END_NAMESPACE
+
+#endif  // FMT_RANGES_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/std.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/std.h
new file mode 100644
index 0000000..41d2b28
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/std.h
@@ -0,0 +1,171 @@
+// Formatting library for C++ - formatters for standard library types
+//
+// Copyright (c) 2012 - present, Victor Zverovich
+// All rights reserved.
+//
+// For the license information refer to format.h.
+
+#ifndef FMT_STD_H_
+#define FMT_STD_H_
+
+#include <thread>
+#include <type_traits>
+#include <utility>
+
+#include "ostream.h"
+
+#if FMT_HAS_INCLUDE(<version>)
+#  include <version>
+#endif
+// Checking FMT_CPLUSPLUS for warning suppression in MSVC.
+#if FMT_CPLUSPLUS >= 201703L
+#  if FMT_HAS_INCLUDE(<filesystem>)
+#    include <filesystem>
+#  endif
+#  if FMT_HAS_INCLUDE(<variant>)
+#    include <variant>
+#  endif
+#endif
+
+#ifdef __cpp_lib_filesystem
+FMT_BEGIN_NAMESPACE
+
+namespace detail {
+
+template <typename Char>
+void write_escaped_path(basic_memory_buffer<Char>& quoted,
+                        const std::filesystem::path& p) {
+  write_escaped_string<Char>(std::back_inserter(quoted), p.string<Char>());
+}
+#  ifdef _WIN32
+template <>
+inline void write_escaped_path<char>(basic_memory_buffer<char>& quoted,
+                                     const std::filesystem::path& p) {
+  auto s = p.u8string();
+  write_escaped_string<char>(
+      std::back_inserter(quoted),
+      string_view(reinterpret_cast<const char*>(s.c_str()), s.size()));
+}
+#  endif
+template <>
+inline void write_escaped_path<std::filesystem::path::value_type>(
+    basic_memory_buffer<std::filesystem::path::value_type>& quoted,
+    const std::filesystem::path& p) {
+  write_escaped_string<std::filesystem::path::value_type>(
+      std::back_inserter(quoted), p.native());
+}
+
+}  // namespace detail
+
+template <typename Char>
+struct formatter<std::filesystem::path, Char>
+    : formatter<basic_string_view<Char>> {
+  template <typename FormatContext>
+  auto format(const std::filesystem::path& p, FormatContext& ctx) const ->
+      typename FormatContext::iterator {
+    basic_memory_buffer<Char> quoted;
+    detail::write_escaped_path(quoted, p);
+    return formatter<basic_string_view<Char>>::format(
+        basic_string_view<Char>(quoted.data(), quoted.size()), ctx);
+  }
+};
+FMT_END_NAMESPACE
+#endif
+
+FMT_BEGIN_NAMESPACE
+template <typename Char>
+struct formatter<std::thread::id, Char> : basic_ostream_formatter<Char> {};
+FMT_END_NAMESPACE
+
+#ifdef __cpp_lib_variant
+FMT_BEGIN_NAMESPACE
+template <typename Char> struct formatter<std::monostate, Char> {
+  template <typename ParseContext>
+  FMT_CONSTEXPR auto parse(ParseContext& ctx) -> decltype(ctx.begin()) {
+    return ctx.begin();
+  }
+
+  template <typename FormatContext>
+  auto format(const std::monostate&, FormatContext& ctx) const
+      -> decltype(ctx.out()) {
+    auto out = ctx.out();
+    out = detail::write<Char>(out, "monostate");
+    return out;
+  }
+};
+
+namespace detail {
+
+template <typename T>
+using variant_index_sequence =
+    std::make_index_sequence<std::variant_size<T>::value>;
+
+// variant_size and variant_alternative check.
+template <typename T, typename U = void>
+struct is_variant_like_ : std::false_type {};
+template <typename T>
+struct is_variant_like_<T, std::void_t<decltype(std::variant_size<T>::value)>>
+    : std::true_type {};
+
+// formattable element check
+template <typename T, typename C> class is_variant_formattable_ {
+  template <std::size_t... I>
+  static std::conjunction<
+      is_formattable<std::variant_alternative_t<I, T>, C>...>
+      check(std::index_sequence<I...>);
+
+ public:
+  static constexpr const bool value =
+      decltype(check(variant_index_sequence<T>{}))::value;
+};
+
+template <typename Char, typename OutputIt, typename T>
+auto write_variant_alternative(OutputIt out, const T& v) -> OutputIt {
+  if constexpr (is_string<T>::value)
+    return write_escaped_string<Char>(out, detail::to_string_view(v));
+  else if constexpr (std::is_same_v<T, Char>)
+    return write_escaped_char(out, v);
+  else
+    return write<Char>(out, v);
+}
+
+}  // namespace detail
+
+template <typename T> struct is_variant_like {
+  static constexpr const bool value = detail::is_variant_like_<T>::value;
+};
+
+template <typename T, typename C> struct is_variant_formattable {
+  static constexpr const bool value =
+      detail::is_variant_formattable_<T, C>::value;
+};
+
+template <typename Variant, typename Char>
+struct formatter<
+    Variant, Char,
+    std::enable_if_t<std::conjunction_v<
+        is_variant_like<Variant>, is_variant_formattable<Variant, Char>>>> {
+  template <typename ParseContext>
+  FMT_CONSTEXPR auto parse(ParseContext& ctx) -> decltype(ctx.begin()) {
+    return ctx.begin();
+  }
+
+  template <typename FormatContext>
+  auto format(const Variant& value, FormatContext& ctx) const
+      -> decltype(ctx.out()) {
+    auto out = ctx.out();
+
+    out = detail::write<Char>(out, "variant(");
+    std::visit(
+        [&](const auto& v) {
+          out = detail::write_variant_alternative<Char>(out, v);
+        },
+        value);
+    *out++ = ')';
+    return out;
+  }
+};
+FMT_END_NAMESPACE
+#endif
+
+#endif  // FMT_STD_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/xchar.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/xchar.h
new file mode 100644
index 0000000..fc3c67f
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/xchar.h
@@ -0,0 +1,228 @@
+// Formatting library for C++ - optional wchar_t and exotic character support
+//
+// Copyright (c) 2012 - present, Victor Zverovich
+// All rights reserved.
+//
+// For the license information refer to format.h.
+
+#ifndef FMT_XCHAR_H_
+#define FMT_XCHAR_H_
+
+#include <cwchar>
+
+#include "format.h"
+
+FMT_BEGIN_NAMESPACE
+namespace detail {
+template <typename T>
+using is_exotic_char = bool_constant<!std::is_same<T, char>::value>;
+}
+
+FMT_MODULE_EXPORT_BEGIN
+
+using wstring_view = basic_string_view<wchar_t>;
+using wformat_parse_context = basic_format_parse_context<wchar_t>;
+using wformat_context = buffer_context<wchar_t>;
+using wformat_args = basic_format_args<wformat_context>;
+using wmemory_buffer = basic_memory_buffer<wchar_t>;
+
+#if FMT_GCC_VERSION && FMT_GCC_VERSION < 409
+// Workaround broken conversion on older gcc.
+template <typename... Args> using wformat_string = wstring_view;
+inline auto runtime(wstring_view s) -> wstring_view { return s; }
+#else
+template <typename... Args>
+using wformat_string = basic_format_string<wchar_t, type_identity_t<Args>...>;
+inline auto runtime(wstring_view s) -> basic_runtime<wchar_t> { return {{s}}; }
+#endif
+
+template <> struct is_char<wchar_t> : std::true_type {};
+template <> struct is_char<detail::char8_type> : std::true_type {};
+template <> struct is_char<char16_t> : std::true_type {};
+template <> struct is_char<char32_t> : std::true_type {};
+
+template <typename... Args>
+constexpr format_arg_store<wformat_context, Args...> make_wformat_args(
+    const Args&... args) {
+  return {args...};
+}
+
+inline namespace literals {
+#if FMT_USE_USER_DEFINED_LITERALS && !FMT_USE_NONTYPE_TEMPLATE_ARGS
+constexpr detail::udl_arg<wchar_t> operator"" _a(const wchar_t* s, size_t) {
+  return {s};
+}
+#endif
+}  // namespace literals
+
+template <typename It, typename Sentinel>
+auto join(It begin, Sentinel end, wstring_view sep)
+    -> join_view<It, Sentinel, wchar_t> {
+  return {begin, end, sep};
+}
+
+template <typename Range>
+auto join(Range&& range, wstring_view sep)
+    -> join_view<detail::iterator_t<Range>, detail::sentinel_t<Range>,
+                 wchar_t> {
+  return join(std::begin(range), std::end(range), sep);
+}
+
+template <typename T>
+auto join(std::initializer_list<T> list, wstring_view sep)
+    -> join_view<const T*, const T*, wchar_t> {
+  return join(std::begin(list), std::end(list), sep);
+}
+
+template <typename Char, FMT_ENABLE_IF(!std::is_same<Char, char>::value)>
+auto vformat(basic_string_view<Char> format_str,
+             basic_format_args<buffer_context<type_identity_t<Char>>> args)
+    -> std::basic_string<Char> {
+  basic_memory_buffer<Char> buffer;
+  detail::vformat_to(buffer, format_str, args);
+  return to_string(buffer);
+}
+
+template <typename... T>
+auto format(wformat_string<T...> fmt, T&&... args) -> std::wstring {
+  return vformat(fmt::wstring_view(fmt), fmt::make_wformat_args(args...));
+}
+
+// Pass char_t as a default template parameter instead of using
+// std::basic_string<char_t<S>> to reduce the symbol size.
+template <typename S, typename... Args, typename Char = char_t<S>,
+          FMT_ENABLE_IF(!std::is_same<Char, char>::value &&
+                        !std::is_same<Char, wchar_t>::value)>
+auto format(const S& format_str, Args&&... args) -> std::basic_string<Char> {
+  return vformat(detail::to_string_view(format_str),
+                 fmt::make_format_args<buffer_context<Char>>(args...));
+}
+
+template <typename Locale, typename S, typename Char = char_t<S>,
+          FMT_ENABLE_IF(detail::is_locale<Locale>::value&&
+                            detail::is_exotic_char<Char>::value)>
+inline auto vformat(
+    const Locale& loc, const S& format_str,
+    basic_format_args<buffer_context<type_identity_t<Char>>> args)
+    -> std::basic_string<Char> {
+  return detail::vformat(loc, detail::to_string_view(format_str), args);
+}
+
+template <typename Locale, typename S, typename... Args,
+          typename Char = char_t<S>,
+          FMT_ENABLE_IF(detail::is_locale<Locale>::value&&
+                            detail::is_exotic_char<Char>::value)>
+inline auto format(const Locale& loc, const S& format_str, Args&&... args)
+    -> std::basic_string<Char> {
+  return detail::vformat(loc, detail::to_string_view(format_str),
+                         fmt::make_format_args<buffer_context<Char>>(args...));
+}
+
+template <typename OutputIt, typename S, typename Char = char_t<S>,
+          FMT_ENABLE_IF(detail::is_output_iterator<OutputIt, Char>::value&&
+                            detail::is_exotic_char<Char>::value)>
+auto vformat_to(OutputIt out, const S& format_str,
+                basic_format_args<buffer_context<type_identity_t<Char>>> args)
+    -> OutputIt {
+  auto&& buf = detail::get_buffer<Char>(out);
+  detail::vformat_to(buf, detail::to_string_view(format_str), args);
+  return detail::get_iterator(buf);
+}
+
+template <typename OutputIt, typename S, typename... Args,
+          typename Char = char_t<S>,
+          FMT_ENABLE_IF(detail::is_output_iterator<OutputIt, Char>::value&&
+                            detail::is_exotic_char<Char>::value)>
+inline auto format_to(OutputIt out, const S& fmt, Args&&... args) -> OutputIt {
+  return vformat_to(out, detail::to_string_view(fmt),
+                    fmt::make_format_args<buffer_context<Char>>(args...));
+}
+
+template <typename Locale, typename S, typename OutputIt, typename... Args,
+          typename Char = char_t<S>,
+          FMT_ENABLE_IF(detail::is_output_iterator<OutputIt, Char>::value&&
+                            detail::is_locale<Locale>::value&&
+                                detail::is_exotic_char<Char>::value)>
+inline auto vformat_to(
+    OutputIt out, const Locale& loc, const S& format_str,
+    basic_format_args<buffer_context<type_identity_t<Char>>> args) -> OutputIt {
+  auto&& buf = detail::get_buffer<Char>(out);
+  vformat_to(buf, detail::to_string_view(format_str), args,
+             detail::locale_ref(loc));
+  return detail::get_iterator(buf);
+}
+
+template <
+    typename OutputIt, typename Locale, typename S, typename... Args,
+    typename Char = char_t<S>,
+    bool enable = detail::is_output_iterator<OutputIt, Char>::value&&
+        detail::is_locale<Locale>::value&& detail::is_exotic_char<Char>::value>
+inline auto format_to(OutputIt out, const Locale& loc, const S& format_str,
+                      Args&&... args) ->
+    typename std::enable_if<enable, OutputIt>::type {
+  return vformat_to(out, loc, to_string_view(format_str),
+                    fmt::make_format_args<buffer_context<Char>>(args...));
+}
+
+template <typename OutputIt, typename Char, typename... Args,
+          FMT_ENABLE_IF(detail::is_output_iterator<OutputIt, Char>::value&&
+                            detail::is_exotic_char<Char>::value)>
+inline auto vformat_to_n(
+    OutputIt out, size_t n, basic_string_view<Char> format_str,
+    basic_format_args<buffer_context<type_identity_t<Char>>> args)
+    -> format_to_n_result<OutputIt> {
+  detail::iterator_buffer<OutputIt, Char, detail::fixed_buffer_traits> buf(out,
+                                                                           n);
+  detail::vformat_to(buf, format_str, args);
+  return {buf.out(), buf.count()};
+}
+
+template <typename OutputIt, typename S, typename... Args,
+          typename Char = char_t<S>,
+          FMT_ENABLE_IF(detail::is_output_iterator<OutputIt, Char>::value&&
+                            detail::is_exotic_char<Char>::value)>
+inline auto format_to_n(OutputIt out, size_t n, const S& fmt,
+                        const Args&... args) -> format_to_n_result<OutputIt> {
+  return vformat_to_n(out, n, detail::to_string_view(fmt),
+                      fmt::make_format_args<buffer_context<Char>>(args...));
+}
+
+template <typename S, typename... Args, typename Char = char_t<S>,
+          FMT_ENABLE_IF(detail::is_exotic_char<Char>::value)>
+inline auto formatted_size(const S& fmt, Args&&... args) -> size_t {
+  detail::counting_buffer<Char> buf;
+  detail::vformat_to(buf, detail::to_string_view(fmt),
+                     fmt::make_format_args<buffer_context<Char>>(args...));
+  return buf.count();
+}
+
+inline void vprint(std::FILE* f, wstring_view fmt, wformat_args args) {
+  wmemory_buffer buffer;
+  detail::vformat_to(buffer, fmt, args);
+  buffer.push_back(L'\0');
+  std::fputws(buffer.data(), f);
+}
+
+inline void vprint(wstring_view fmt, wformat_args args) {
+  vprint(stdout, fmt, args);
+}
+
+template <typename... T>
+void print(std::FILE* f, wformat_string<T...> fmt, T&&... args) {
+  return vprint(f, wstring_view(fmt), fmt::make_wformat_args(args...));
+}
+
+template <typename... T> void print(wformat_string<T...> fmt, T&&... args) {
+  return vprint(wstring_view(fmt), fmt::make_wformat_args(args...));
+}
+
+/**
+  Converts *value* to ``std::wstring`` using the default format for type *T*.
+ */
+template <typename T> inline auto to_wstring(const T& value) -> std::wstring {
+  return format(FMT_STRING(L"{}"), value);
+}
+FMT_MODULE_EXPORT_END
+FMT_END_NAMESPACE
+
+#endif  // FMT_XCHAR_H_
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/src/format.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/src/format.cpp
new file mode 100644
index 0000000..99b7e9d
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/src/format.cpp
@@ -0,0 +1,47 @@
+// Formatting library for C++
+//
+// Copyright (c) 2012 - 2016, Victor Zverovich
+// All rights reserved.
+//
+// For the license information refer to format.h.
+
+#include "fmt/format-inl.h"
+
+FMT_BEGIN_NAMESPACE
+namespace detail {
+
+template FMT_API auto dragonbox::to_decimal(float x) noexcept
+    -> dragonbox::decimal_fp<float>;
+template FMT_API auto dragonbox::to_decimal(double x) noexcept
+    -> dragonbox::decimal_fp<double>;
+
+#ifndef FMT_STATIC_THOUSANDS_SEPARATOR
+template FMT_API locale_ref::locale_ref(const std::locale& loc);
+template FMT_API auto locale_ref::get<std::locale>() const -> std::locale;
+#endif
+
+// Explicit instantiations for char.
+
+template FMT_API auto thousands_sep_impl(locale_ref)
+    -> thousands_sep_result<char>;
+template FMT_API auto decimal_point_impl(locale_ref) -> char;
+
+template FMT_API void buffer<char>::append(const char*, const char*);
+
+// DEPRECATED!
+// There is no correspondent extern template in format.h because of
+// incompatibility between clang and gcc (#2377).
+template FMT_API void vformat_to(buffer<char>&, string_view,
+                                 basic_format_args<FMT_BUFFER_CONTEXT(char)>,
+                                 locale_ref);
+
+// Explicit instantiations for wchar_t.
+
+template FMT_API auto thousands_sep_impl(locale_ref)
+    -> thousands_sep_result<wchar_t>;
+template FMT_API auto decimal_point_impl(locale_ref) -> wchar_t;
+
+template FMT_API void buffer<wchar_t>::append(const wchar_t*, const wchar_t*);
+
+}  // namespace detail
+FMT_END_NAMESPACE
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/src/os.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/src/os.cpp
new file mode 100644
index 0000000..2c49951
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/fmtlib/src/os.cpp
@@ -0,0 +1,360 @@
+// Formatting library for C++ - optional OS-specific functionality
+//
+// Copyright (c) 2012 - 2016, Victor Zverovich
+// All rights reserved.
+//
+// For the license information refer to format.h.
+
+// Disable bogus MSVC warnings.
+#if !defined(_CRT_SECURE_NO_WARNINGS) && defined(_MSC_VER)
+#  define _CRT_SECURE_NO_WARNINGS
+#endif
+
+#include "fmt/os.h"
+
+#include <climits>
+
+#if FMT_USE_FCNTL
+#  include <sys/stat.h>
+#  include <sys/types.h>
+
+#  ifndef _WIN32
+#    include <unistd.h>
+#  else
+#    ifndef WIN32_LEAN_AND_MEAN
+#      define WIN32_LEAN_AND_MEAN
+#    endif
+#    include <io.h>
+
+#    ifndef S_IRUSR
+#      define S_IRUSR _S_IREAD
+#    endif
+#    ifndef S_IWUSR
+#      define S_IWUSR _S_IWRITE
+#    endif
+#    ifndef S_IRGRP
+#      define S_IRGRP 0
+#    endif
+#    ifndef S_IWGRP
+#      define S_IWGRP 0
+#    endif
+#    ifndef S_IROTH
+#      define S_IROTH 0
+#    endif
+#    ifndef S_IWOTH
+#      define S_IWOTH 0
+#    endif
+#  endif  // _WIN32
+#endif    // FMT_USE_FCNTL
+
+#ifdef _WIN32
+#  include <windows.h>
+#endif
+
+namespace {
+#ifdef _WIN32
+// Return type of read and write functions.
+using rwresult = int;
+
+// On Windows the count argument to read and write is unsigned, so convert
+// it from size_t preventing integer overflow.
+inline unsigned convert_rwcount(std::size_t count) {
+  return count <= UINT_MAX ? static_cast<unsigned>(count) : UINT_MAX;
+}
+#elif FMT_USE_FCNTL
+// Return type of read and write functions.
+using rwresult = ssize_t;
+
+inline std::size_t convert_rwcount(std::size_t count) { return count; }
+#endif
+}  // namespace
+
+FMT_BEGIN_NAMESPACE
+
+#ifdef _WIN32
+detail::utf16_to_utf8::utf16_to_utf8(basic_string_view<wchar_t> s) {
+  if (int error_code = convert(s)) {
+    FMT_THROW(windows_error(error_code,
+                            "cannot convert string from UTF-16 to UTF-8"));
+  }
+}
+
+int detail::utf16_to_utf8::convert(basic_string_view<wchar_t> s) {
+  if (s.size() > INT_MAX) return ERROR_INVALID_PARAMETER;
+  int s_size = static_cast<int>(s.size());
+  if (s_size == 0) {
+    // WideCharToMultiByte does not support zero length, handle separately.
+    buffer_.resize(1);
+    buffer_[0] = 0;
+    return 0;
+  }
+
+  int length = WideCharToMultiByte(CP_UTF8, 0, s.data(), s_size, nullptr, 0,
+                                   nullptr, nullptr);
+  if (length == 0) return GetLastError();
+  buffer_.resize(length + 1);
+  length = WideCharToMultiByte(CP_UTF8, 0, s.data(), s_size, &buffer_[0],
+                               length, nullptr, nullptr);
+  if (length == 0) return GetLastError();
+  buffer_[length] = 0;
+  return 0;
+}
+
+namespace detail {
+
+class system_message {
+  system_message(const system_message&) = delete;
+  void operator=(const system_message&) = delete;
+
+  unsigned long result_;
+  wchar_t* message_;
+
+  static bool is_whitespace(wchar_t c) noexcept {
+    return c == L' ' || c == L'\n' || c == L'\r' || c == L'\t' || c == L'\0';
+  }
+
+ public:
+  explicit system_message(unsigned long error_code)
+      : result_(0), message_(nullptr) {
+    result_ = FormatMessageW(
+        FORMAT_MESSAGE_ALLOCATE_BUFFER | FORMAT_MESSAGE_FROM_SYSTEM |
+            FORMAT_MESSAGE_IGNORE_INSERTS,
+        nullptr, error_code, MAKELANGID(LANG_NEUTRAL, SUBLANG_DEFAULT),
+        reinterpret_cast<wchar_t*>(&message_), 0, nullptr);
+    if (result_ != 0) {
+      while (result_ != 0 && is_whitespace(message_[result_ - 1])) {
+        --result_;
+      }
+    }
+  }
+  ~system_message() { LocalFree(message_); }
+  explicit operator bool() const noexcept { return result_ != 0; }
+  operator basic_string_view<wchar_t>() const noexcept {
+    return basic_string_view<wchar_t>(message_, result_);
+  }
+};
+
+class utf8_system_category final : public std::error_category {
+ public:
+  const char* name() const noexcept override { return "system"; }
+  std::string message(int error_code) const override {
+    system_message msg(error_code);
+    if (msg) {
+      utf16_to_utf8 utf8_message;
+      if (utf8_message.convert(msg) == ERROR_SUCCESS) {
+        return utf8_message.str();
+      }
+    }
+    return "unknown error";
+  }
+};
+
+}  // namespace detail
+
+FMT_API const std::error_category& system_category() noexcept {
+  static const detail::utf8_system_category category;
+  return category;
+}
+
+std::system_error vwindows_error(int err_code, string_view format_str,
+                                 format_args args) {
+  auto ec = std::error_code(err_code, system_category());
+  return std::system_error(ec, vformat(format_str, args));
+}
+
+void detail::format_windows_error(detail::buffer<char>& out, int error_code,
+                                  const char* message) noexcept {
+  FMT_TRY {
+    system_message msg(error_code);
+    if (msg) {
+      utf16_to_utf8 utf8_message;
+      if (utf8_message.convert(msg) == ERROR_SUCCESS) {
+        fmt::format_to(buffer_appender<char>(out), "{}: {}", message, utf8_message);
+        return;
+      }
+    }
+  }
+  FMT_CATCH(...) {}
+  format_error_code(out, error_code, message);
+}
+
+void report_windows_error(int error_code, const char* message) noexcept {
+  report_error(detail::format_windows_error, error_code, message);
+}
+#endif  // _WIN32
+
+buffered_file::~buffered_file() noexcept {
+  if (file_ && FMT_SYSTEM(fclose(file_)) != 0)
+    report_system_error(errno, "cannot close file");
+}
+
+buffered_file::buffered_file(cstring_view filename, cstring_view mode) {
+  FMT_RETRY_VAL(file_, FMT_SYSTEM(fopen(filename.c_str(), mode.c_str())),
+                nullptr);
+  if (!file_)
+    FMT_THROW(system_error(errno, "cannot open file {}", filename.c_str()));
+}
+
+void buffered_file::close() {
+  if (!file_) return;
+  int result = FMT_SYSTEM(fclose(file_));
+  file_ = nullptr;
+  if (result != 0) FMT_THROW(system_error(errno, "cannot close file"));
+}
+
+int buffered_file::descriptor() const {
+  int fd = FMT_POSIX_CALL(fileno(file_));
+  if (fd == -1) FMT_THROW(system_error(errno, "cannot get file descriptor"));
+  return fd;
+}
+
+#if FMT_USE_FCNTL
+file::file(cstring_view path, int oflag) {
+#  ifdef _WIN32
+  using mode_t = int;
+#  endif
+  constexpr mode_t mode =
+      S_IRUSR | S_IWUSR | S_IRGRP | S_IWGRP | S_IROTH | S_IWOTH;
+#  if defined(_WIN32) && !defined(__MINGW32__)
+  fd_ = -1;
+  FMT_POSIX_CALL(sopen_s(&fd_, path.c_str(), oflag, _SH_DENYNO, mode));
+#  else
+  FMT_RETRY(fd_, FMT_POSIX_CALL(open(path.c_str(), oflag, mode)));
+#  endif
+  if (fd_ == -1)
+    FMT_THROW(system_error(errno, "cannot open file {}", path.c_str()));
+}
+
+file::~file() noexcept {
+  // Don't retry close in case of EINTR!
+  // See http://linux.derkeiler.com/Mailing-Lists/Kernel/2005-09/3000.html
+  if (fd_ != -1 && FMT_POSIX_CALL(close(fd_)) != 0)
+    report_system_error(errno, "cannot close file");
+}
+
+void file::close() {
+  if (fd_ == -1) return;
+  // Don't retry close in case of EINTR!
+  // See http://linux.derkeiler.com/Mailing-Lists/Kernel/2005-09/3000.html
+  int result = FMT_POSIX_CALL(close(fd_));
+  fd_ = -1;
+  if (result != 0) FMT_THROW(system_error(errno, "cannot close file"));
+}
+
+long long file::size() const {
+#  ifdef _WIN32
+  // Use GetFileSize instead of GetFileSizeEx for the case when _WIN32_WINNT
+  // is less than 0x0500 as is the case with some default MinGW builds.
+  // Both functions support large file sizes.
+  DWORD size_upper = 0;
+  HANDLE handle = reinterpret_cast<HANDLE>(_get_osfhandle(fd_));
+  DWORD size_lower = FMT_SYSTEM(GetFileSize(handle, &size_upper));
+  if (size_lower == INVALID_FILE_SIZE) {
+    DWORD error = GetLastError();
+    if (error != NO_ERROR)
+      FMT_THROW(windows_error(GetLastError(), "cannot get file size"));
+  }
+  unsigned long long long_size = size_upper;
+  return (long_size << sizeof(DWORD) * CHAR_BIT) | size_lower;
+#  else
+  using Stat = struct stat;
+  Stat file_stat = Stat();
+  if (FMT_POSIX_CALL(fstat(fd_, &file_stat)) == -1)
+    FMT_THROW(system_error(errno, "cannot get file attributes"));
+  static_assert(sizeof(long long) >= sizeof(file_stat.st_size),
+                "return type of file::size is not large enough");
+  return file_stat.st_size;
+#  endif
+}
+
+std::size_t file::read(void* buffer, std::size_t count) {
+  rwresult result = 0;
+  FMT_RETRY(result, FMT_POSIX_CALL(read(fd_, buffer, convert_rwcount(count))));
+  if (result < 0) FMT_THROW(system_error(errno, "cannot read from file"));
+  return detail::to_unsigned(result);
+}
+
+std::size_t file::write(const void* buffer, std::size_t count) {
+  rwresult result = 0;
+  FMT_RETRY(result, FMT_POSIX_CALL(write(fd_, buffer, convert_rwcount(count))));
+  return count;
+}
+
+file file::dup(int fd) {
+  // Don't retry as dup doesn't return EINTR.
+  // http://pubs.opengroup.org/onlinepubs/009695399/functions/dup.html
+  int new_fd = FMT_POSIX_CALL(dup(fd));
+  if (new_fd == -1)
+    FMT_THROW(system_error(errno, "cannot duplicate file descriptor {}", fd));
+  return file(new_fd);
+}
+
+void file::dup2(int fd) {
+  int result = 0;
+  FMT_RETRY(result, FMT_POSIX_CALL(dup2(fd_, fd)));
+  if (result == -1) {
+    FMT_THROW(system_error(errno, "cannot duplicate file descriptor {} to {}",
+                           fd_, fd));
+  }
+}
+
+void file::dup2(int fd, std::error_code& ec) noexcept {
+  int result = 0;
+  FMT_RETRY(result, FMT_POSIX_CALL(dup2(fd_, fd)));
+  if (result == -1) ec = std::error_code(errno, std::generic_category());
+}
+
+void file::pipe(file& read_end, file& write_end) {
+  // Close the descriptors first to make sure that assignments don't throw
+  // and there are no leaks.
+  read_end.close();
+  write_end.close();
+  int fds[2] = {};
+#  ifdef _WIN32
+  // Make the default pipe capacity same as on Linux 2.6.11+.
+  enum { DEFAULT_CAPACITY = 65536 };
+  int result = FMT_POSIX_CALL(pipe(fds, DEFAULT_CAPACITY, _O_BINARY));
+#  else
+  // Don't retry as the pipe function doesn't return EINTR.
+  // http://pubs.opengroup.org/onlinepubs/009696799/functions/pipe.html
+  int result = FMT_POSIX_CALL(pipe(fds));
+#  endif
+  if (result != 0) FMT_THROW(system_error(errno, "cannot create pipe"));
+  // The following assignments don't throw because read_fd and write_fd
+  // are closed.
+  read_end = file(fds[0]);
+  write_end = file(fds[1]);
+}
+
+buffered_file file::fdopen(const char* mode) {
+// Don't retry as fdopen doesn't return EINTR.
+#  if defined(__MINGW32__) && defined(_POSIX_)
+  FILE* f = ::fdopen(fd_, mode);
+#  else
+  FILE* f = FMT_POSIX_CALL(fdopen(fd_, mode));
+#  endif
+  if (!f)
+    FMT_THROW(
+        system_error(errno, "cannot associate stream with file descriptor"));
+  buffered_file bf(f);
+  fd_ = -1;
+  return bf;
+}
+
+long getpagesize() {
+#  ifdef _WIN32
+  SYSTEM_INFO si;
+  GetSystemInfo(&si);
+  return si.dwPageSize;
+#  else
+  long size = FMT_POSIX_CALL(sysconf(_SC_PAGESIZE));
+  if (size < 0) FMT_THROW(system_error(errno, "cannot get memory page size"));
+  return size;
+#  endif
+}
+
+FMT_API void ostream::grow(size_t) {
+  if (this->size() == this->capacity()) flush();
+}
+#endif  // FMT_USE_FCNTL
+FMT_END_NAMESPACE
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/ghc/filesystem.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/ghc/include/wpi/ghc/filesystem.hpp
similarity index 100%
rename from third_party/allwpilib/wpiutil/src/main/native/include/wpi/ghc/filesystem.hpp
rename to third_party/allwpilib/wpiutil/src/main/native/thirdparty/ghc/include/wpi/ghc/filesystem.hpp
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/json.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/json/cpp/json.cpp
similarity index 100%
rename from third_party/allwpilib/wpiutil/src/main/native/cpp/json.cpp
rename to third_party/allwpilib/wpiutil/src/main/native/thirdparty/json/cpp/json.cpp
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/json/cpp/json_binary_reader.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/json/cpp/json_binary_reader.cpp
new file mode 100644
index 0000000..2081359
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/json/cpp/json_binary_reader.cpp
@@ -0,0 +1,1415 @@
+/*----------------------------------------------------------------------------*/
+/* Modifications Copyright (c) 2017-2018 FIRST. All Rights Reserved.          */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+/*
+    __ _____ _____ _____
+ __|  |   __|     |   | |  JSON for Modern C++
+|  |  |__   |  |  | | | |  version 3.1.2
+|_____|_____|_____|_|___|  https://github.com/nlohmann/json
+
+Licensed under the MIT License <http://opensource.org/licenses/MIT>.
+Copyright (c) 2013-2018 Niels Lohmann <http://nlohmann.me>.
+
+Permission is hereby  granted, free of charge, to any  person obtaining a copy
+of this software and associated  documentation files (the "Software"), to deal
+in the Software  without restriction, including without  limitation the rights
+to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
+copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
+IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
+FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
+AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
+LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+*/
+#define WPI_JSON_IMPLEMENTATION
+#include "wpi/json.h"
+
+#include <cmath>  // ldexp
+
+#include "fmt/format.h"
+#include "wpi/raw_istream.h"
+
+namespace wpi {
+
+/*!
+@brief deserialization of CBOR and MessagePack values
+*/
+class json::binary_reader
+{
+  public:
+    /*!
+    @brief create a binary reader
+
+    @param[in] adapter  input adapter to read from
+    */
+    explicit binary_reader(raw_istream& s) : is(s)
+    {
+    }
+
+    /*!
+    @brief create a JSON value from CBOR input
+
+    @param[in] strict  whether to expect the input to be consumed completed
+    @return JSON value created from CBOR input
+
+    @throw parse_error.110 if input ended unexpectedly or the end of file was
+                           not reached when @a strict was set to true
+    @throw parse_error.112 if unsupported byte was read
+    */
+    json parse_cbor(const bool strict)
+    {
+        const auto res = parse_cbor_internal();
+        if (strict)
+        {
+            get();
+            expect_eof();
+        }
+        return res;
+    }
+
+    /*!
+    @brief create a JSON value from MessagePack input
+
+    @param[in] strict  whether to expect the input to be consumed completed
+    @return JSON value created from MessagePack input
+
+    @throw parse_error.110 if input ended unexpectedly or the end of file was
+                           not reached when @a strict was set to true
+    @throw parse_error.112 if unsupported byte was read
+    */
+    json parse_msgpack(const bool strict)
+    {
+        const auto res = parse_msgpack_internal();
+        if (strict)
+        {
+            get();
+            expect_eof();
+        }
+        return res;
+    }
+
+    /*!
+    @brief create a JSON value from UBJSON input
+
+    @param[in] strict  whether to expect the input to be consumed completed
+    @return JSON value created from UBJSON input
+
+    @throw parse_error.110 if input ended unexpectedly or the end of file was
+                           not reached when @a strict was set to true
+    @throw parse_error.112 if unsupported byte was read
+    */
+    json parse_ubjson(const bool strict)
+    {
+        const auto res = parse_ubjson_internal();
+        if (strict)
+        {
+            get_ignore_noop();
+            expect_eof();
+        }
+        return res;
+    }
+
+    /*!
+    @brief determine system byte order
+
+    @return true if and only if system's byte order is little endian
+
+    @note from http://stackoverflow.com/a/1001328/266378
+    */
+    static bool little_endianess(int num = 1) noexcept
+    {
+        return (*reinterpret_cast<char*>(&num) == 1);
+    }
+
+  private:
+    /*!
+    @param[in] get_char  whether a new character should be retrieved from the
+                         input (true, default) or whether the last read
+                         character should be considered instead
+    */
+    json parse_cbor_internal(const bool get_char = true);
+
+    json parse_msgpack_internal();
+
+    /*!
+    @param[in] get_char  whether a new character should be retrieved from the
+                         input (true, default) or whether the last read
+                         character should be considered instead
+    */
+    json parse_ubjson_internal(const bool get_char = true)
+    {
+        return get_ubjson_value(get_char ? get_ignore_noop() : current);
+    }
+
+    /*!
+    @brief get next character from the input
+
+    This function provides the interface to the used input adapter. It does
+    not throw in case the input reached EOF, but returns a -'ve valued
+    `std::char_traits<char>::eof()` in that case.
+
+    @return character read from the input
+    */
+    int get()
+    {
+        ++chars_read;
+        unsigned char c;
+        is.read(c);
+        if (is.has_error())
+        {
+            current = std::char_traits<char>::eof();
+        }
+        else
+        {
+            current = c;
+        }
+        return current;
+    }
+
+    /*!
+    @return character read from the input after ignoring all 'N' entries
+    */
+    int get_ignore_noop()
+    {
+        do
+        {
+            get();
+        }
+        while (current == 'N');
+
+        return current;
+    }
+
+    /*
+    @brief read a number from the input
+
+    @tparam NumberType the type of the number
+
+    @return number of type @a NumberType
+
+    @note This function needs to respect the system's endianess, because
+          bytes in CBOR and MessagePack are stored in network order (big
+          endian) and therefore need reordering on little endian systems.
+
+    @throw parse_error.110 if input has less than `sizeof(NumberType)` bytes
+    */
+    template<typename NumberType> NumberType get_number()
+    {
+        // step 1: read input into array with system's byte order
+        std::array<uint8_t, sizeof(NumberType)> vec;
+        for (std::size_t i = 0; i < sizeof(NumberType); ++i)
+        {
+            get();
+            unexpect_eof();
+
+            // reverse byte order prior to conversion if necessary
+            if (is_little_endian)
+            {
+                vec[sizeof(NumberType) - i - 1] = static_cast<uint8_t>(current);
+            }
+            else
+            {
+                vec[i] = static_cast<uint8_t>(current); // LCOV_EXCL_LINE
+            }
+        }
+
+        // step 2: convert array into number of type T and return
+        NumberType result;
+        std::memcpy(&result, vec.data(), sizeof(NumberType));
+        return result;
+    }
+
+    /*!
+    @brief create a string by reading characters from the input
+
+    @param[in] len number of bytes to read
+
+    @note We can not reserve @a len bytes for the result, because @a len
+          may be too large. Usually, @ref unexpect_eof() detects the end of
+          the input before we run out of string memory.
+
+    @return string created by reading @a len bytes
+
+    @throw parse_error.110 if input has less than @a len bytes
+    */
+    template<typename NumberType>
+    std::string get_string(const NumberType len)
+    {
+        std::string result;
+        std::generate_n(std::back_inserter(result), len, [this]()
+        {
+            get();
+            unexpect_eof();
+            return static_cast<char>(current);
+        });
+        return result;
+    }
+
+    /*!
+    @brief reads a CBOR string
+
+    This function first reads starting bytes to determine the expected
+    string length and then copies this number of bytes into a string.
+    Additionally, CBOR's strings with indefinite lengths are supported.
+
+    @return string
+
+    @throw parse_error.110 if input ended
+    @throw parse_error.113 if an unexpected byte is read
+    */
+    std::string get_cbor_string();
+
+    template<typename NumberType>
+    json get_cbor_array(const NumberType len)
+    {
+        json result = value_t::array;
+        std::generate_n(std::back_inserter(*result.m_value.array), len, [this]()
+        {
+            return parse_cbor_internal();
+        });
+        return result;
+    }
+
+    template<typename NumberType>
+    json get_cbor_object(const NumberType len)
+    {
+        json result = value_t::object;
+        for (NumberType i = 0; i < len; ++i)
+        {
+            get();
+            auto key = get_cbor_string();
+            (*result.m_value.object)[key] = parse_cbor_internal();
+        }
+        return result;
+    }
+
+    /*!
+    @brief reads a MessagePack string
+
+    This function first reads starting bytes to determine the expected
+    string length and then copies this number of bytes into a string.
+
+    @return string
+
+    @throw parse_error.110 if input ended
+    @throw parse_error.113 if an unexpected byte is read
+    */
+    std::string get_msgpack_string();
+
+    template<typename NumberType>
+    json get_msgpack_array(const NumberType len)
+    {
+        json result = value_t::array;
+        std::generate_n(std::back_inserter(*result.m_value.array), len, [this]()
+        {
+            return parse_msgpack_internal();
+        });
+        return result;
+    }
+
+    template<typename NumberType>
+    json get_msgpack_object(const NumberType len)
+    {
+        json result = value_t::object;
+        for (NumberType i = 0; i < len; ++i)
+        {
+            get();
+            auto key = get_msgpack_string();
+            (*result.m_value.object)[key] = parse_msgpack_internal();
+        }
+        return result;
+    }
+
+    /*!
+    @brief reads a UBJSON string
+
+    This function is either called after reading the 'S' byte explicitly
+    indicating a string, or in case of an object key where the 'S' byte can be
+    left out.
+
+    @param[in] get_char  whether a new character should be retrieved from the
+                         input (true, default) or whether the last read
+                         character should be considered instead
+
+    @return string
+
+    @throw parse_error.110 if input ended
+    @throw parse_error.113 if an unexpected byte is read
+    */
+    std::string get_ubjson_string(const bool get_char = true);
+
+    /*!
+    @brief determine the type and size for a container
+
+    In the optimized UBJSON format, a type and a size can be provided to allow
+    for a more compact representation.
+
+    @return pair of the size and the type
+    */
+    std::pair<std::size_t, int> get_ubjson_size_type();
+
+    json get_ubjson_value(const int prefix);
+
+    json get_ubjson_array();
+
+    json get_ubjson_object();
+
+    /*!
+    @brief throw if end of input is not reached
+    @throw parse_error.110 if input not ended
+    */
+    void expect_eof() const
+    {
+        if (JSON_UNLIKELY(current != std::char_traits<char>::eof()))
+        {
+            JSON_THROW(parse_error::create(110, chars_read, "expected end of input"));
+        }
+    }
+
+    /*!
+    @briefthrow if end of input is reached
+    @throw parse_error.110 if input ended
+    */
+    void unexpect_eof() const
+    {
+        if (JSON_UNLIKELY(current == std::char_traits<char>::eof()))
+        {
+            JSON_THROW(parse_error::create(110, chars_read, "unexpected end of input"));
+        }
+    }
+
+  private:
+    /// input adapter
+    raw_istream& is;
+
+    /// the current character
+    int current = std::char_traits<char>::eof();
+
+    /// the number of characters read
+    std::size_t chars_read = 0;
+
+    /// whether we can assume little endianess
+    const bool is_little_endian = little_endianess();
+};
+
+json json::binary_reader::parse_cbor_internal(const bool get_char)
+{
+    switch (get_char ? get() : current)
+    {
+        // EOF
+        case std::char_traits<char>::eof():
+            JSON_THROW(parse_error::create(110, chars_read, "unexpected end of input"));
+
+        // Integer 0x00..0x17 (0..23)
+        case 0x00:
+        case 0x01:
+        case 0x02:
+        case 0x03:
+        case 0x04:
+        case 0x05:
+        case 0x06:
+        case 0x07:
+        case 0x08:
+        case 0x09:
+        case 0x0A:
+        case 0x0B:
+        case 0x0C:
+        case 0x0D:
+        case 0x0E:
+        case 0x0F:
+        case 0x10:
+        case 0x11:
+        case 0x12:
+        case 0x13:
+        case 0x14:
+        case 0x15:
+        case 0x16:
+        case 0x17:
+            return static_cast<uint64_t>(current);
+
+        case 0x18: // Unsigned integer (one-byte uint8_t follows)
+            return get_number<uint8_t>();
+
+        case 0x19: // Unsigned integer (two-byte uint16_t follows)
+            return get_number<uint16_t>();
+
+        case 0x1A: // Unsigned integer (four-byte uint32_t follows)
+            return get_number<uint32_t>();
+
+        case 0x1B: // Unsigned integer (eight-byte uint64_t follows)
+            return get_number<uint64_t>();
+
+        // Negative integer -1-0x00..-1-0x17 (-1..-24)
+        case 0x20:
+        case 0x21:
+        case 0x22:
+        case 0x23:
+        case 0x24:
+        case 0x25:
+        case 0x26:
+        case 0x27:
+        case 0x28:
+        case 0x29:
+        case 0x2A:
+        case 0x2B:
+        case 0x2C:
+        case 0x2D:
+        case 0x2E:
+        case 0x2F:
+        case 0x30:
+        case 0x31:
+        case 0x32:
+        case 0x33:
+        case 0x34:
+        case 0x35:
+        case 0x36:
+        case 0x37:
+            return static_cast<int8_t>(0x20 - 1 - current);
+
+        case 0x38: // Negative integer (one-byte uint8_t follows)
+        {
+            return static_cast<int64_t>(-1) - get_number<uint8_t>();
+        }
+
+        case 0x39: // Negative integer -1-n (two-byte uint16_t follows)
+        {
+            return static_cast<int64_t>(-1) - get_number<uint16_t>();
+        }
+
+        case 0x3A: // Negative integer -1-n (four-byte uint32_t follows)
+        {
+            return static_cast<int64_t>(-1) - get_number<uint32_t>();
+        }
+
+        case 0x3B: // Negative integer -1-n (eight-byte uint64_t follows)
+        {
+            return static_cast<int64_t>(-1) -
+                   static_cast<int64_t>(get_number<uint64_t>());
+        }
+
+        // UTF-8 string (0x00..0x17 bytes follow)
+        case 0x60:
+        case 0x61:
+        case 0x62:
+        case 0x63:
+        case 0x64:
+        case 0x65:
+        case 0x66:
+        case 0x67:
+        case 0x68:
+        case 0x69:
+        case 0x6A:
+        case 0x6B:
+        case 0x6C:
+        case 0x6D:
+        case 0x6E:
+        case 0x6F:
+        case 0x70:
+        case 0x71:
+        case 0x72:
+        case 0x73:
+        case 0x74:
+        case 0x75:
+        case 0x76:
+        case 0x77:
+        case 0x78: // UTF-8 string (one-byte uint8_t for n follows)
+        case 0x79: // UTF-8 string (two-byte uint16_t for n follow)
+        case 0x7A: // UTF-8 string (four-byte uint32_t for n follow)
+        case 0x7B: // UTF-8 string (eight-byte uint64_t for n follow)
+        case 0x7F: // UTF-8 string (indefinite length)
+        {
+            return get_cbor_string();
+        }
+
+        // array (0x00..0x17 data items follow)
+        case 0x80:
+        case 0x81:
+        case 0x82:
+        case 0x83:
+        case 0x84:
+        case 0x85:
+        case 0x86:
+        case 0x87:
+        case 0x88:
+        case 0x89:
+        case 0x8A:
+        case 0x8B:
+        case 0x8C:
+        case 0x8D:
+        case 0x8E:
+        case 0x8F:
+        case 0x90:
+        case 0x91:
+        case 0x92:
+        case 0x93:
+        case 0x94:
+        case 0x95:
+        case 0x96:
+        case 0x97:
+        {
+            return get_cbor_array(current & 0x1F);
+        }
+
+        case 0x98: // array (one-byte uint8_t for n follows)
+        {
+            return get_cbor_array(get_number<uint8_t>());
+        }
+
+        case 0x99: // array (two-byte uint16_t for n follow)
+        {
+            return get_cbor_array(get_number<uint16_t>());
+        }
+
+        case 0x9A: // array (four-byte uint32_t for n follow)
+        {
+            return get_cbor_array(get_number<uint32_t>());
+        }
+
+        case 0x9B: // array (eight-byte uint64_t for n follow)
+        {
+            return get_cbor_array(get_number<uint64_t>());
+        }
+
+        case 0x9F: // array (indefinite length)
+        {
+            json result = value_t::array;
+            while (get() != 0xFF)
+            {
+                result.push_back(parse_cbor_internal(false));
+            }
+            return result;
+        }
+
+        // map (0x00..0x17 pairs of data items follow)
+        case 0xA0:
+        case 0xA1:
+        case 0xA2:
+        case 0xA3:
+        case 0xA4:
+        case 0xA5:
+        case 0xA6:
+        case 0xA7:
+        case 0xA8:
+        case 0xA9:
+        case 0xAA:
+        case 0xAB:
+        case 0xAC:
+        case 0xAD:
+        case 0xAE:
+        case 0xAF:
+        case 0xB0:
+        case 0xB1:
+        case 0xB2:
+        case 0xB3:
+        case 0xB4:
+        case 0xB5:
+        case 0xB6:
+        case 0xB7:
+        {
+            return get_cbor_object(current & 0x1F);
+        }
+
+        case 0xB8: // map (one-byte uint8_t for n follows)
+        {
+            return get_cbor_object(get_number<uint8_t>());
+        }
+
+        case 0xB9: // map (two-byte uint16_t for n follow)
+        {
+            return get_cbor_object(get_number<uint16_t>());
+        }
+
+        case 0xBA: // map (four-byte uint32_t for n follow)
+        {
+            return get_cbor_object(get_number<uint32_t>());
+        }
+
+        case 0xBB: // map (eight-byte uint64_t for n follow)
+        {
+            return get_cbor_object(get_number<uint64_t>());
+        }
+
+        case 0xBF: // map (indefinite length)
+        {
+            json result = value_t::object;
+            while (get() != 0xFF)
+            {
+                auto key = get_cbor_string();
+                result[key] = parse_cbor_internal();
+            }
+            return result;
+        }
+
+        case 0xF4: // false
+        {
+            return false;
+        }
+
+        case 0xF5: // true
+        {
+            return true;
+        }
+
+        case 0xF6: // null
+        {
+            return value_t::null;
+        }
+
+        case 0xF9: // Half-Precision Float (two-byte IEEE 754)
+        {
+            const int byte1 = get();
+            unexpect_eof();
+            const int byte2 = get();
+            unexpect_eof();
+
+            // code from RFC 7049, Appendix D, Figure 3:
+            // As half-precision floating-point numbers were only added
+            // to IEEE 754 in 2008, today's programming platforms often
+            // still only have limited support for them. It is very
+            // easy to include at least decoding support for them even
+            // without such support. An example of a small decoder for
+            // half-precision floating-point numbers in the C language
+            // is shown in Fig. 3.
+            const int half = (byte1 << 8) + byte2;
+            const int exp = (half >> 10) & 0x1F;
+            const int mant = half & 0x3FF;
+            double val;
+            if (exp == 0)
+            {
+                val = std::ldexp(mant, -24);
+            }
+            else if (exp != 31)
+            {
+                val = std::ldexp(mant + 1024, exp - 25);
+            }
+            else
+            {
+                val = (mant == 0) ? std::numeric_limits<double>::infinity()
+                      : std::numeric_limits<double>::quiet_NaN();
+            }
+            return (half & 0x8000) != 0 ? -val : val;
+        }
+
+        case 0xFA: // Single-Precision Float (four-byte IEEE 754)
+        {
+            return get_number<float>();
+        }
+
+        case 0xFB: // Double-Precision Float (eight-byte IEEE 754)
+        {
+            return get_number<double>();
+        }
+
+        default: // anything else (0xFF is handled inside the other types)
+        {
+            JSON_THROW(parse_error::create(112, chars_read, fmt::format("error reading CBOR; last byte: {:#02x}", current)));
+        }
+    }
+}
+
+json json::binary_reader::parse_msgpack_internal()
+{
+    switch (get())
+    {
+        // EOF
+        case std::char_traits<char>::eof():
+            JSON_THROW(parse_error::create(110, chars_read, "unexpected end of input"));
+
+        // positive fixint
+        case 0x00:
+        case 0x01:
+        case 0x02:
+        case 0x03:
+        case 0x04:
+        case 0x05:
+        case 0x06:
+        case 0x07:
+        case 0x08:
+        case 0x09:
+        case 0x0A:
+        case 0x0B:
+        case 0x0C:
+        case 0x0D:
+        case 0x0E:
+        case 0x0F:
+        case 0x10:
+        case 0x11:
+        case 0x12:
+        case 0x13:
+        case 0x14:
+        case 0x15:
+        case 0x16:
+        case 0x17:
+        case 0x18:
+        case 0x19:
+        case 0x1A:
+        case 0x1B:
+        case 0x1C:
+        case 0x1D:
+        case 0x1E:
+        case 0x1F:
+        case 0x20:
+        case 0x21:
+        case 0x22:
+        case 0x23:
+        case 0x24:
+        case 0x25:
+        case 0x26:
+        case 0x27:
+        case 0x28:
+        case 0x29:
+        case 0x2A:
+        case 0x2B:
+        case 0x2C:
+        case 0x2D:
+        case 0x2E:
+        case 0x2F:
+        case 0x30:
+        case 0x31:
+        case 0x32:
+        case 0x33:
+        case 0x34:
+        case 0x35:
+        case 0x36:
+        case 0x37:
+        case 0x38:
+        case 0x39:
+        case 0x3A:
+        case 0x3B:
+        case 0x3C:
+        case 0x3D:
+        case 0x3E:
+        case 0x3F:
+        case 0x40:
+        case 0x41:
+        case 0x42:
+        case 0x43:
+        case 0x44:
+        case 0x45:
+        case 0x46:
+        case 0x47:
+        case 0x48:
+        case 0x49:
+        case 0x4A:
+        case 0x4B:
+        case 0x4C:
+        case 0x4D:
+        case 0x4E:
+        case 0x4F:
+        case 0x50:
+        case 0x51:
+        case 0x52:
+        case 0x53:
+        case 0x54:
+        case 0x55:
+        case 0x56:
+        case 0x57:
+        case 0x58:
+        case 0x59:
+        case 0x5A:
+        case 0x5B:
+        case 0x5C:
+        case 0x5D:
+        case 0x5E:
+        case 0x5F:
+        case 0x60:
+        case 0x61:
+        case 0x62:
+        case 0x63:
+        case 0x64:
+        case 0x65:
+        case 0x66:
+        case 0x67:
+        case 0x68:
+        case 0x69:
+        case 0x6A:
+        case 0x6B:
+        case 0x6C:
+        case 0x6D:
+        case 0x6E:
+        case 0x6F:
+        case 0x70:
+        case 0x71:
+        case 0x72:
+        case 0x73:
+        case 0x74:
+        case 0x75:
+        case 0x76:
+        case 0x77:
+        case 0x78:
+        case 0x79:
+        case 0x7A:
+        case 0x7B:
+        case 0x7C:
+        case 0x7D:
+        case 0x7E:
+        case 0x7F:
+            return static_cast<uint64_t>(current);
+
+        // fixmap
+        case 0x80:
+        case 0x81:
+        case 0x82:
+        case 0x83:
+        case 0x84:
+        case 0x85:
+        case 0x86:
+        case 0x87:
+        case 0x88:
+        case 0x89:
+        case 0x8A:
+        case 0x8B:
+        case 0x8C:
+        case 0x8D:
+        case 0x8E:
+        case 0x8F:
+        {
+            return get_msgpack_object(current & 0x0F);
+        }
+
+        // fixarray
+        case 0x90:
+        case 0x91:
+        case 0x92:
+        case 0x93:
+        case 0x94:
+        case 0x95:
+        case 0x96:
+        case 0x97:
+        case 0x98:
+        case 0x99:
+        case 0x9A:
+        case 0x9B:
+        case 0x9C:
+        case 0x9D:
+        case 0x9E:
+        case 0x9F:
+        {
+            return get_msgpack_array(current & 0x0F);
+        }
+
+        // fixstr
+        case 0xA0:
+        case 0xA1:
+        case 0xA2:
+        case 0xA3:
+        case 0xA4:
+        case 0xA5:
+        case 0xA6:
+        case 0xA7:
+        case 0xA8:
+        case 0xA9:
+        case 0xAA:
+        case 0xAB:
+        case 0xAC:
+        case 0xAD:
+        case 0xAE:
+        case 0xAF:
+        case 0xB0:
+        case 0xB1:
+        case 0xB2:
+        case 0xB3:
+        case 0xB4:
+        case 0xB5:
+        case 0xB6:
+        case 0xB7:
+        case 0xB8:
+        case 0xB9:
+        case 0xBA:
+        case 0xBB:
+        case 0xBC:
+        case 0xBD:
+        case 0xBE:
+        case 0xBF:
+            return get_msgpack_string();
+
+        case 0xC0: // nil
+            return value_t::null;
+
+        case 0xC2: // false
+            return false;
+
+        case 0xC3: // true
+            return true;
+
+        case 0xCA: // float 32
+            return get_number<float>();
+
+        case 0xCB: // float 64
+            return get_number<double>();
+
+        case 0xCC: // uint 8
+            return get_number<uint8_t>();
+
+        case 0xCD: // uint 16
+            return get_number<uint16_t>();
+
+        case 0xCE: // uint 32
+            return get_number<uint32_t>();
+
+        case 0xCF: // uint 64
+            return get_number<uint64_t>();
+
+        case 0xD0: // int 8
+            return get_number<int8_t>();
+
+        case 0xD1: // int 16
+            return get_number<int16_t>();
+
+        case 0xD2: // int 32
+            return get_number<int32_t>();
+
+        case 0xD3: // int 64
+            return get_number<int64_t>();
+
+        case 0xD9: // str 8
+        case 0xDA: // str 16
+        case 0xDB: // str 32
+            return get_msgpack_string();
+
+        case 0xDC: // array 16
+        {
+            return get_msgpack_array(get_number<uint16_t>());
+        }
+
+        case 0xDD: // array 32
+        {
+            return get_msgpack_array(get_number<uint32_t>());
+        }
+
+        case 0xDE: // map 16
+        {
+            return get_msgpack_object(get_number<uint16_t>());
+        }
+
+        case 0xDF: // map 32
+        {
+            return get_msgpack_object(get_number<uint32_t>());
+        }
+
+        // positive fixint
+        case 0xE0:
+        case 0xE1:
+        case 0xE2:
+        case 0xE3:
+        case 0xE4:
+        case 0xE5:
+        case 0xE6:
+        case 0xE7:
+        case 0xE8:
+        case 0xE9:
+        case 0xEA:
+        case 0xEB:
+        case 0xEC:
+        case 0xED:
+        case 0xEE:
+        case 0xEF:
+        case 0xF0:
+        case 0xF1:
+        case 0xF2:
+        case 0xF3:
+        case 0xF4:
+        case 0xF5:
+        case 0xF6:
+        case 0xF7:
+        case 0xF8:
+        case 0xF9:
+        case 0xFA:
+        case 0xFB:
+        case 0xFC:
+        case 0xFD:
+        case 0xFE:
+        case 0xFF:
+            return static_cast<int8_t>(current);
+
+        default: // anything else
+        {
+            JSON_THROW(parse_error::create(112, chars_read,
+                fmt::format("error reading MessagePack; last byte: {:#02x}", current)));
+        }
+    }
+}
+
+std::string json::binary_reader::get_cbor_string()
+{
+    unexpect_eof();
+
+    switch (current)
+    {
+        // UTF-8 string (0x00..0x17 bytes follow)
+        case 0x60:
+        case 0x61:
+        case 0x62:
+        case 0x63:
+        case 0x64:
+        case 0x65:
+        case 0x66:
+        case 0x67:
+        case 0x68:
+        case 0x69:
+        case 0x6A:
+        case 0x6B:
+        case 0x6C:
+        case 0x6D:
+        case 0x6E:
+        case 0x6F:
+        case 0x70:
+        case 0x71:
+        case 0x72:
+        case 0x73:
+        case 0x74:
+        case 0x75:
+        case 0x76:
+        case 0x77:
+        {
+            return get_string(current & 0x1F);
+        }
+
+        case 0x78: // UTF-8 string (one-byte uint8_t for n follows)
+        {
+            return get_string(get_number<uint8_t>());
+        }
+
+        case 0x79: // UTF-8 string (two-byte uint16_t for n follow)
+        {
+            return get_string(get_number<uint16_t>());
+        }
+
+        case 0x7A: // UTF-8 string (four-byte uint32_t for n follow)
+        {
+            return get_string(get_number<uint32_t>());
+        }
+
+        case 0x7B: // UTF-8 string (eight-byte uint64_t for n follow)
+        {
+            return get_string(get_number<uint64_t>());
+        }
+
+        case 0x7F: // UTF-8 string (indefinite length)
+        {
+            std::string result;
+            while (get() != 0xFF)
+            {
+                result.append(get_cbor_string());
+            }
+            return result;
+        }
+
+        default:
+        {
+            JSON_THROW(parse_error::create(113, chars_read,
+                fmt::format("expected a CBOR string; last byte: {:#02x}", current)));
+        }
+    }
+}
+
+std::string json::binary_reader::get_msgpack_string()
+{
+    unexpect_eof();
+
+    switch (current)
+    {
+        // fixstr
+        case 0xA0:
+        case 0xA1:
+        case 0xA2:
+        case 0xA3:
+        case 0xA4:
+        case 0xA5:
+        case 0xA6:
+        case 0xA7:
+        case 0xA8:
+        case 0xA9:
+        case 0xAA:
+        case 0xAB:
+        case 0xAC:
+        case 0xAD:
+        case 0xAE:
+        case 0xAF:
+        case 0xB0:
+        case 0xB1:
+        case 0xB2:
+        case 0xB3:
+        case 0xB4:
+        case 0xB5:
+        case 0xB6:
+        case 0xB7:
+        case 0xB8:
+        case 0xB9:
+        case 0xBA:
+        case 0xBB:
+        case 0xBC:
+        case 0xBD:
+        case 0xBE:
+        case 0xBF:
+        {
+            return get_string(current & 0x1F);
+        }
+
+        case 0xD9: // str 8
+        {
+            return get_string(get_number<uint8_t>());
+        }
+
+        case 0xDA: // str 16
+        {
+            return get_string(get_number<uint16_t>());
+        }
+
+        case 0xDB: // str 32
+        {
+            return get_string(get_number<uint32_t>());
+        }
+
+        default:
+        {
+            JSON_THROW(parse_error::create(113, chars_read,
+                fmt::format("expected a MessagePack string; last byte: {:#02x}", current)));
+        }
+    }
+}
+
+std::string json::binary_reader::get_ubjson_string(const bool get_char)
+{
+    if (get_char)
+    {
+        get();  // TODO: may we ignore N here?
+    }
+
+    unexpect_eof();
+
+    switch (current)
+    {
+        case 'U':
+            return get_string(get_number<uint8_t>());
+        case 'i':
+            return get_string(get_number<int8_t>());
+        case 'I':
+            return get_string(get_number<int16_t>());
+        case 'l':
+            return get_string(get_number<int32_t>());
+        case 'L':
+            return get_string(get_number<int64_t>());
+        default:
+            JSON_THROW(parse_error::create(113, chars_read,
+                fmt::format("expected a UBJSON string; last byte: {:#02x}", current)));
+    }
+}
+
+std::pair<std::size_t, int> json::binary_reader::get_ubjson_size_type()
+{
+    std::size_t sz = std::string::npos;
+    int tc = 0;
+
+    get_ignore_noop();
+
+    if (current == '$')
+    {
+        tc = get();  // must not ignore 'N', because 'N' maybe the type
+        unexpect_eof();
+
+        get_ignore_noop();
+        if (current != '#')
+        {
+            JSON_THROW(parse_error::create(112, chars_read,
+                fmt::format("expected '#' after UBJSON type information; last byte: {:#02x}", current)));
+        }
+        sz = parse_ubjson_internal();
+    }
+    else if (current == '#')
+    {
+        sz = parse_ubjson_internal();
+    }
+
+    return std::make_pair(sz, tc);
+}
+
+json json::binary_reader::get_ubjson_value(const int prefix)
+{
+    switch (prefix)
+    {
+        case std::char_traits<char>::eof():  // EOF
+            JSON_THROW(parse_error::create(110, chars_read, "unexpected end of input"));
+
+        case 'T':  // true
+            return true;
+        case 'F':  // false
+            return false;
+
+        case 'Z':  // null
+            return nullptr;
+
+        case 'U':
+            return get_number<uint8_t>();
+        case 'i':
+            return get_number<int8_t>();
+        case 'I':
+            return get_number<int16_t>();
+        case 'l':
+            return get_number<int32_t>();
+        case 'L':
+            return get_number<int64_t>();
+        case 'd':
+            return get_number<float>();
+        case 'D':
+            return get_number<double>();
+
+        case 'C':  // char
+        {
+            get();
+            unexpect_eof();
+            if (JSON_UNLIKELY(current > 127))
+            {
+                JSON_THROW(parse_error::create(113, chars_read,
+                    fmt::format("byte after 'C' must be in range 0x00..0x7F; last byte: {:#02x}", current)));
+            }
+            return std::string(1, static_cast<char>(current));
+        }
+
+        case 'S':  // string
+            return get_ubjson_string();
+
+        case '[':  // array
+            return get_ubjson_array();
+
+        case '{':  // object
+            return get_ubjson_object();
+
+        default: // anything else
+            JSON_THROW(parse_error::create(112, chars_read,
+                fmt::format("error reading UBJSON; last byte: {:#02x}", current)));
+    }
+}
+
+json json::binary_reader::get_ubjson_array()
+{
+    json result = value_t::array;
+    const auto size_and_type = get_ubjson_size_type();
+
+    if (size_and_type.first != std::string::npos)
+    {
+        if (JSON_UNLIKELY(size_and_type.first > result.max_size()))
+        {
+            JSON_THROW(out_of_range::create(408,
+                fmt::format("excessive array size: {}", size_and_type.first)));
+        }
+
+        if (size_and_type.second != 0)
+        {
+            if (size_and_type.second != 'N')
+            {
+                std::generate_n(std::back_inserter(*result.m_value.array),
+                                size_and_type.first, [this, size_and_type]()
+                {
+                    return get_ubjson_value(size_and_type.second);
+                });
+            }
+        }
+        else
+        {
+            std::generate_n(std::back_inserter(*result.m_value.array),
+                            size_and_type.first, [this]()
+            {
+                return parse_ubjson_internal();
+            });
+        }
+    }
+    else
+    {
+        while (current != ']')
+        {
+            result.push_back(parse_ubjson_internal(false));
+            get_ignore_noop();
+        }
+    }
+
+    return result;
+}
+
+json json::binary_reader::get_ubjson_object()
+{
+    json result = value_t::object;
+    const auto size_and_type = get_ubjson_size_type();
+
+    if (size_and_type.first != std::string::npos)
+    {
+        if (JSON_UNLIKELY(size_and_type.first > result.max_size()))
+        {
+            JSON_THROW(out_of_range::create(408,
+                fmt::format("excessive object size: {}", size_and_type.first)));
+        }
+
+        if (size_and_type.second != 0)
+        {
+            for (size_t i = 0; i < size_and_type.first; ++i)
+            {
+                auto key = get_ubjson_string();
+                (*result.m_value.object)[key] = get_ubjson_value(size_and_type.second);
+            }
+        }
+        else
+        {
+            for (size_t i = 0; i < size_and_type.first; ++i)
+            {
+                auto key = get_ubjson_string();
+                (*result.m_value.object)[key] = parse_ubjson_internal();
+            }
+        }
+    }
+    else
+    {
+        while (current != '}')
+        {
+            auto key = get_ubjson_string(false);
+            result[std::move(key)] = parse_ubjson_internal();
+            get_ignore_noop();
+        }
+    }
+
+    return result;
+}
+
+json json::from_cbor(raw_istream& is, const bool strict)
+{
+    return binary_reader(is).parse_cbor(strict);
+}
+
+json json::from_cbor(std::span<const uint8_t> arr, const bool strict)
+{
+    raw_mem_istream is(arr);
+    return from_cbor(is, strict);
+}
+
+json json::from_msgpack(raw_istream& is, const bool strict)
+{
+    return binary_reader(is).parse_msgpack(strict);
+}
+
+json json::from_msgpack(std::span<const uint8_t> arr, const bool strict)
+{
+    raw_mem_istream is(arr);
+    return from_msgpack(is, strict);
+}
+
+json json::from_ubjson(raw_istream& is, const bool strict)
+{
+    return binary_reader(is).parse_ubjson(strict);
+}
+
+json json::from_ubjson(std::span<const uint8_t> arr, const bool strict)
+{
+    raw_mem_istream is(arr);
+    return from_ubjson(is, strict);
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/json/cpp/json_binary_writer.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/json/cpp/json_binary_writer.cpp
new file mode 100644
index 0000000..e25d478
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/json/cpp/json_binary_writer.cpp
@@ -0,0 +1,1091 @@
+/*----------------------------------------------------------------------------*/
+/* Modifications Copyright (c) 2017-2018 FIRST. All Rights Reserved.          */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+/*
+    __ _____ _____ _____
+ __|  |   __|     |   | |  JSON for Modern C++
+|  |  |__   |  |  | | | |  version 3.1.2
+|_____|_____|_____|_|___|  https://github.com/nlohmann/json
+
+Licensed under the MIT License <http://opensource.org/licenses/MIT>.
+Copyright (c) 2013-2018 Niels Lohmann <http://nlohmann.me>.
+
+Permission is hereby  granted, free of charge, to any  person obtaining a copy
+of this software and associated  documentation files (the "Software"), to deal
+in the Software  without restriction, including without  limitation the rights
+to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
+copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
+IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
+FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
+AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
+LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+*/
+#define WPI_JSON_IMPLEMENTATION
+#include "wpi/json.h"
+
+#include "fmt/format.h"
+#include "wpi/raw_ostream.h"
+
+namespace wpi {
+
+/*!
+@brief serialization to CBOR and MessagePack values
+*/
+class json::binary_writer
+{
+    using CharType = unsigned char;
+
+  public:
+    /*!
+    @brief create a binary writer
+
+    @param[in] adapter  output adapter to write to
+    */
+    explicit binary_writer(raw_ostream& s) : o(s)
+    {
+    }
+
+    /*!
+    @brief[in] j  JSON value to serialize
+    */
+    void write_cbor(const json& j);
+
+    /*!
+    @brief[in] j  JSON value to serialize
+    */
+    void write_msgpack(const json& j);
+
+    /*!
+    @param[in] j  JSON value to serialize
+    @param[in] use_count   whether to use '#' prefixes (optimized format)
+    @param[in] use_type    whether to use '$' prefixes (optimized format)
+    @param[in] add_prefix  whether prefixes need to be used for this value
+    */
+    void write_ubjson(const json& j, const bool use_count,
+                      const bool use_type, const bool add_prefix = true);
+
+  private:
+    void write_cbor_string(std::string_view str);
+
+    void write_msgpack_string(std::string_view str);
+
+    /*
+    @brief write a number to output input
+
+    @param[in] n number of type @a NumberType
+    @tparam NumberType the type of the number
+
+    @note This function needs to respect the system's endianess, because bytes
+          in CBOR, MessagePack, and UBJSON are stored in network order (big
+          endian) and therefore need reordering on little endian systems.
+    */
+    template<typename NumberType>
+    void write_number(const NumberType n);
+
+    // UBJSON: write number (floating point)
+    template<typename NumberType, typename std::enable_if<
+                 std::is_floating_point<NumberType>::value, int>::type = 0>
+    void write_number_with_ubjson_prefix(const NumberType n,
+                                         const bool add_prefix)
+    {
+        if (add_prefix)
+        {
+            o << get_ubjson_float_prefix(n);
+        }
+        write_number(n);
+    }
+
+    // UBJSON: write number (unsigned integer)
+    template<typename NumberType, typename std::enable_if<
+                 std::is_unsigned<NumberType>::value, int>::type = 0>
+    void write_number_with_ubjson_prefix(const NumberType n,
+                                         const bool add_prefix);
+
+    // UBJSON: write number (signed integer)
+    template<typename NumberType, typename std::enable_if<
+                 std::is_signed<NumberType>::value and
+                 not std::is_floating_point<NumberType>::value, int>::type = 0>
+    void write_number_with_ubjson_prefix(const NumberType n,
+                                         const bool add_prefix);
+
+    /*!
+    @brief determine the type prefix of container values
+
+    @note This function does not need to be 100% accurate when it comes to
+          integer limits. In case a number exceeds the limits of int64_t,
+          this will be detected by a later call to function
+          write_number_with_ubjson_prefix. Therefore, we return 'L' for any
+          value that does not fit the previous limits.
+    */
+    CharType ubjson_prefix(const json& j) const noexcept;
+
+    static constexpr CharType get_cbor_float_prefix(float)
+    {
+        return static_cast<CharType>(0xFA);  // Single-Precision Float
+    }
+
+    static constexpr CharType get_cbor_float_prefix(double)
+    {
+        return static_cast<CharType>(0xFB);  // Double-Precision Float
+    }
+
+    static constexpr CharType get_msgpack_float_prefix(float)
+    {
+        return static_cast<CharType>(0xCA);  // float 32
+    }
+
+    static constexpr CharType get_msgpack_float_prefix(double)
+    {
+        return static_cast<CharType>(0xCB);  // float 64
+    }
+
+    static constexpr CharType get_ubjson_float_prefix(float)
+    {
+        return 'd';  // float 32
+    }
+
+    static constexpr CharType get_ubjson_float_prefix(double)
+    {
+        return 'D';  // float 64
+    }
+
+  private:
+    static bool little_endianess(int num = 1) noexcept
+    {
+        return (*reinterpret_cast<char*>(&num) == 1);
+    }
+
+    /// whether we can assume little endianess
+    const bool is_little_endian = little_endianess();
+
+    /// the output
+    raw_ostream& o;
+};
+
+void json::binary_writer::write_cbor(const json& j)
+{
+    switch (j.type())
+    {
+        case value_t::null:
+        {
+            o << static_cast<CharType>(0xF6);
+            break;
+        }
+
+        case value_t::boolean:
+        {
+            o << static_cast<CharType>(j.m_value.boolean ? 0xF5 : 0xF4);
+            break;
+        }
+
+        case value_t::number_integer:
+        {
+            if (j.m_value.number_integer >= 0)
+            {
+                // CBOR does not differentiate between positive signed
+                // integers and unsigned integers. Therefore, we used the
+                // code from the value_t::number_unsigned case here.
+                if (j.m_value.number_integer <= 0x17)
+                {
+                    write_number(static_cast<uint8_t>(j.m_value.number_integer));
+                }
+                else if (j.m_value.number_integer <= (std::numeric_limits<uint8_t>::max)())
+                {
+                    o << static_cast<CharType>(0x18);
+                    write_number(static_cast<uint8_t>(j.m_value.number_integer));
+                }
+                else if (j.m_value.number_integer <= (std::numeric_limits<uint16_t>::max)())
+                {
+                    o << static_cast<CharType>(0x19);
+                    write_number(static_cast<uint16_t>(j.m_value.number_integer));
+                }
+                else if (j.m_value.number_integer <= (std::numeric_limits<uint32_t>::max)())
+                {
+                    o << static_cast<CharType>(0x1A);
+                    write_number(static_cast<uint32_t>(j.m_value.number_integer));
+                }
+                else
+                {
+                    o << static_cast<CharType>(0x1B);
+                    write_number(static_cast<uint64_t>(j.m_value.number_integer));
+                }
+            }
+            else
+            {
+                // The conversions below encode the sign in the first
+                // byte, and the value is converted to a positive number.
+                const auto positive_number = -1 - j.m_value.number_integer;
+                if (j.m_value.number_integer >= -24)
+                {
+                    write_number(static_cast<uint8_t>(0x20 + positive_number));
+                }
+                else if (positive_number <= (std::numeric_limits<uint8_t>::max)())
+                {
+                    o << static_cast<CharType>(0x38);
+                    write_number(static_cast<uint8_t>(positive_number));
+                }
+                else if (positive_number <= (std::numeric_limits<uint16_t>::max)())
+                {
+                    o << static_cast<CharType>(0x39);
+                    write_number(static_cast<uint16_t>(positive_number));
+                }
+                else if (positive_number <= (std::numeric_limits<uint32_t>::max)())
+                {
+                    o << static_cast<CharType>(0x3A);
+                    write_number(static_cast<uint32_t>(positive_number));
+                }
+                else
+                {
+                    o << static_cast<CharType>(0x3B);
+                    write_number(static_cast<uint64_t>(positive_number));
+                }
+            }
+            break;
+        }
+
+        case value_t::number_unsigned:
+        {
+            if (j.m_value.number_unsigned <= 0x17)
+            {
+                write_number(static_cast<uint8_t>(j.m_value.number_unsigned));
+            }
+            else if (j.m_value.number_unsigned <= (std::numeric_limits<uint8_t>::max)())
+            {
+                o << static_cast<CharType>(0x18);
+                write_number(static_cast<uint8_t>(j.m_value.number_unsigned));
+            }
+            else if (j.m_value.number_unsigned <= (std::numeric_limits<uint16_t>::max)())
+            {
+                o << static_cast<CharType>(0x19);
+                write_number(static_cast<uint16_t>(j.m_value.number_unsigned));
+            }
+            else if (j.m_value.number_unsigned <= (std::numeric_limits<uint32_t>::max)())
+            {
+                o << static_cast<CharType>(0x1A);
+                write_number(static_cast<uint32_t>(j.m_value.number_unsigned));
+            }
+            else
+            {
+                o << static_cast<CharType>(0x1B);
+                write_number(static_cast<uint64_t>(j.m_value.number_unsigned));
+            }
+            break;
+        }
+
+        case value_t::number_float:
+        {
+            o << get_cbor_float_prefix(j.m_value.number_float);
+            write_number(j.m_value.number_float);
+            break;
+        }
+
+        case value_t::string:
+        {
+            write_cbor_string(*j.m_value.string);
+            break;
+        }
+
+        case value_t::array:
+        {
+            // step 1: write control byte and the array size
+            const auto N = j.m_value.array->size();
+            if (N <= 0x17)
+            {
+                write_number(static_cast<uint8_t>(0x80 + N));
+            }
+            else if (N <= (std::numeric_limits<uint8_t>::max)())
+            {
+                o << static_cast<CharType>(0x98);
+                write_number(static_cast<uint8_t>(N));
+            }
+            else if (N <= (std::numeric_limits<uint16_t>::max)())
+            {
+                o << static_cast<CharType>(0x99);
+                write_number(static_cast<uint16_t>(N));
+            }
+            else if (N <= (std::numeric_limits<uint32_t>::max)())
+            {
+                o << static_cast<CharType>(0x9A);
+                write_number(static_cast<uint32_t>(N));
+            }
+            // LCOV_EXCL_START
+            else if (N <= (std::numeric_limits<uint64_t>::max)())
+            {
+                o << static_cast<CharType>(0x9B);
+                write_number(static_cast<uint64_t>(N));
+            }
+            // LCOV_EXCL_STOP
+
+            // step 2: write each element
+            for (const auto& el : *j.m_value.array)
+            {
+                write_cbor(el);
+            }
+            break;
+        }
+
+        case value_t::object:
+        {
+            // step 1: write control byte and the object size
+            const auto N = j.m_value.object->size();
+            if (N <= 0x17)
+            {
+                write_number(static_cast<uint8_t>(0xA0 + N));
+            }
+            else if (N <= (std::numeric_limits<uint8_t>::max)())
+            {
+                o << static_cast<CharType>(0xB8);
+                write_number(static_cast<uint8_t>(N));
+            }
+            else if (N <= (std::numeric_limits<uint16_t>::max)())
+            {
+                o << static_cast<CharType>(0xB9);
+                write_number(static_cast<uint16_t>(N));
+            }
+            else if (N <= (std::numeric_limits<uint32_t>::max)())
+            {
+                o << static_cast<CharType>(0xBA);
+                write_number(static_cast<uint32_t>(N));
+            }
+            // LCOV_EXCL_START
+            else /*if (N <= (std::numeric_limits<uint64_t>::max)())*/
+            {
+                o << static_cast<CharType>(0xBB);
+                write_number(static_cast<uint64_t>(N));
+            }
+            // LCOV_EXCL_STOP
+
+            // step 2: write each element
+            for (const auto& el : *j.m_value.object)
+            {
+                write_cbor_string(el.first());
+                write_cbor(el.second);
+            }
+            break;
+        }
+
+        default:
+            break;
+    }
+}
+
+void json::binary_writer::write_msgpack(const json& j)
+{
+    switch (j.type())
+    {
+        case value_t::null: // nil
+        {
+            o << static_cast<CharType>(0xC0);
+            break;
+        }
+
+        case value_t::boolean: // true and false
+        {
+            o << static_cast<CharType>(j.m_value.boolean ? 0xC3 : 0xC2);
+            break;
+        }
+
+        case value_t::number_integer:
+        {
+            if (j.m_value.number_integer >= 0)
+            {
+                // MessagePack does not differentiate between positive
+                // signed integers and unsigned integers. Therefore, we used
+                // the code from the value_t::number_unsigned case here.
+                if (j.m_value.number_unsigned < 128)
+                {
+                    // positive fixnum
+                    write_number(static_cast<uint8_t>(j.m_value.number_integer));
+                }
+                else if (j.m_value.number_unsigned <= (std::numeric_limits<uint8_t>::max)())
+                {
+                    // uint 8
+                    o << static_cast<CharType>(0xCC);
+                    write_number(static_cast<uint8_t>(j.m_value.number_integer));
+                }
+                else if (j.m_value.number_unsigned <= (std::numeric_limits<uint16_t>::max)())
+                {
+                    // uint 16
+                    o << static_cast<CharType>(0xCD);
+                    write_number(static_cast<uint16_t>(j.m_value.number_integer));
+                }
+                else if (j.m_value.number_unsigned <= (std::numeric_limits<uint32_t>::max)())
+                {
+                    // uint 32
+                    o << static_cast<CharType>(0xCE);
+                    write_number(static_cast<uint32_t>(j.m_value.number_integer));
+                }
+                else if (j.m_value.number_unsigned <= (std::numeric_limits<uint64_t>::max)())
+                {
+                    // uint 64
+                    o << static_cast<CharType>(0xCF);
+                    write_number(static_cast<uint64_t>(j.m_value.number_integer));
+                }
+            }
+            else
+            {
+                if (j.m_value.number_integer >= -32)
+                {
+                    // negative fixnum
+                    write_number(static_cast<int8_t>(j.m_value.number_integer));
+                }
+                else if (j.m_value.number_integer >= (std::numeric_limits<int8_t>::min)() and
+                         j.m_value.number_integer <= (std::numeric_limits<int8_t>::max)())
+                {
+                    // int 8
+                    o << static_cast<CharType>(0xD0);
+                    write_number(static_cast<int8_t>(j.m_value.number_integer));
+                }
+                else if (j.m_value.number_integer >= (std::numeric_limits<int16_t>::min)() and
+                         j.m_value.number_integer <= (std::numeric_limits<int16_t>::max)())
+                {
+                    // int 16
+                    o << static_cast<CharType>(0xD1);
+                    write_number(static_cast<int16_t>(j.m_value.number_integer));
+                }
+                else if (j.m_value.number_integer >= (std::numeric_limits<int32_t>::min)() and
+                         j.m_value.number_integer <= (std::numeric_limits<int32_t>::max)())
+                {
+                    // int 32
+                    o << static_cast<CharType>(0xD2);
+                    write_number(static_cast<int32_t>(j.m_value.number_integer));
+                }
+                else if (j.m_value.number_integer >= (std::numeric_limits<int64_t>::min)() and
+                         j.m_value.number_integer <= (std::numeric_limits<int64_t>::max)())
+                {
+                    // int 64
+                    o << static_cast<CharType>(0xD3);
+                    write_number(static_cast<int64_t>(j.m_value.number_integer));
+                }
+            }
+            break;
+        }
+
+        case value_t::number_unsigned:
+        {
+            if (j.m_value.number_unsigned < 128)
+            {
+                // positive fixnum
+                write_number(static_cast<uint8_t>(j.m_value.number_integer));
+            }
+            else if (j.m_value.number_unsigned <= (std::numeric_limits<uint8_t>::max)())
+            {
+                // uint 8
+                o << static_cast<CharType>(0xCC);
+                write_number(static_cast<uint8_t>(j.m_value.number_integer));
+            }
+            else if (j.m_value.number_unsigned <= (std::numeric_limits<uint16_t>::max)())
+            {
+                // uint 16
+                o << static_cast<CharType>(0xCD);
+                write_number(static_cast<uint16_t>(j.m_value.number_integer));
+            }
+            else if (j.m_value.number_unsigned <= (std::numeric_limits<uint32_t>::max)())
+            {
+                // uint 32
+                o << static_cast<CharType>(0xCE);
+                write_number(static_cast<uint32_t>(j.m_value.number_integer));
+            }
+            else if (j.m_value.number_unsigned <= (std::numeric_limits<uint64_t>::max)())
+            {
+                // uint 64
+                o << static_cast<CharType>(0xCF);
+                write_number(static_cast<uint64_t>(j.m_value.number_integer));
+            }
+            break;
+        }
+
+        case value_t::number_float:
+        {
+            o << get_msgpack_float_prefix(j.m_value.number_float);
+            write_number(j.m_value.number_float);
+            break;
+        }
+
+        case value_t::string:
+        {
+            write_msgpack_string(*j.m_value.string);
+            break;
+        }
+
+        case value_t::array:
+        {
+            // step 1: write control byte and the array size
+            const auto N = j.m_value.array->size();
+            if (N <= 15)
+            {
+                // fixarray
+                write_number(static_cast<uint8_t>(0x90 | N));
+            }
+            else if (N <= (std::numeric_limits<uint16_t>::max)())
+            {
+                // array 16
+                o << static_cast<CharType>(0xDC);
+                write_number(static_cast<uint16_t>(N));
+            }
+            else if (N <= (std::numeric_limits<uint32_t>::max)())
+            {
+                // array 32
+                o << static_cast<CharType>(0xDD);
+                write_number(static_cast<uint32_t>(N));
+            }
+
+            // step 2: write each element
+            for (const auto& el : *j.m_value.array)
+            {
+                write_msgpack(el);
+            }
+            break;
+        }
+
+        case value_t::object:
+        {
+            // step 1: write control byte and the object size
+            const auto N = j.m_value.object->size();
+            if (N <= 15)
+            {
+                // fixmap
+                write_number(static_cast<uint8_t>(0x80 | (N & 0xF)));
+            }
+            else if (N <= (std::numeric_limits<uint16_t>::max)())
+            {
+                // map 16
+                o << static_cast<CharType>(0xDE);
+                write_number(static_cast<uint16_t>(N));
+            }
+            else if (N <= (std::numeric_limits<uint32_t>::max)())
+            {
+                // map 32
+                o << static_cast<CharType>(0xDF);
+                write_number(static_cast<uint32_t>(N));
+            }
+
+            // step 2: write each element
+            for (const auto& el : *j.m_value.object)
+            {
+                write_msgpack_string(el.first());
+                write_msgpack(el.second);
+            }
+            break;
+        }
+
+        default:
+            break;
+    }
+}
+
+void json::binary_writer::write_ubjson(const json& j, const bool use_count,
+                  const bool use_type, const bool add_prefix)
+{
+    switch (j.type())
+    {
+        case value_t::null:
+        {
+            if (add_prefix)
+            {
+                o << static_cast<CharType>('Z');
+            }
+            break;
+        }
+
+        case value_t::boolean:
+        {
+            if (add_prefix)
+                o << static_cast<CharType>(j.m_value.boolean ? 'T' : 'F');
+            break;
+        }
+
+        case value_t::number_integer:
+        {
+            write_number_with_ubjson_prefix(j.m_value.number_integer, add_prefix);
+            break;
+        }
+
+        case value_t::number_unsigned:
+        {
+            write_number_with_ubjson_prefix(j.m_value.number_unsigned, add_prefix);
+            break;
+        }
+
+        case value_t::number_float:
+        {
+            write_number_with_ubjson_prefix(j.m_value.number_float, add_prefix);
+            break;
+        }
+
+        case value_t::string:
+        {
+            if (add_prefix)
+            {
+                o << static_cast<CharType>('S');
+            }
+            write_number_with_ubjson_prefix(j.m_value.string->size(), true);
+            o << *j.m_value.string;
+            break;
+        }
+
+        case value_t::array:
+        {
+            if (add_prefix)
+            {
+                o << static_cast<CharType>('[');
+            }
+
+            bool prefix_required = true;
+            if (use_type and not j.m_value.array->empty())
+            {
+                assert(use_count);
+                const CharType first_prefix = ubjson_prefix(j.front());
+                const bool same_prefix = std::all_of(j.begin() + 1, j.end(),
+                                                     [this, first_prefix](const json & v)
+                {
+                    return ubjson_prefix(v) == first_prefix;
+                });
+
+                if (same_prefix)
+                {
+                    prefix_required = false;
+                    o << static_cast<CharType>('$');
+                    o << first_prefix;
+                }
+            }
+
+            if (use_count)
+            {
+                o << static_cast<CharType>('#');
+                write_number_with_ubjson_prefix(j.m_value.array->size(), true);
+            }
+
+            for (const auto& el : *j.m_value.array)
+            {
+                write_ubjson(el, use_count, use_type, prefix_required);
+            }
+
+            if (not use_count)
+            {
+                o << static_cast<CharType>(']');
+            }
+
+            break;
+        }
+
+        case value_t::object:
+        {
+            if (add_prefix)
+            {
+                o << static_cast<CharType>('{');
+            }
+
+            bool prefix_required = true;
+            if (use_type and not j.m_value.object->empty())
+            {
+                assert(use_count);
+                const CharType first_prefix = ubjson_prefix(j.front());
+                const bool same_prefix = std::all_of(j.begin(), j.end(),
+                                                     [this, first_prefix](const json & v)
+                {
+                    return ubjson_prefix(v) == first_prefix;
+                });
+
+                if (same_prefix)
+                {
+                    prefix_required = false;
+                    o << static_cast<CharType>('$');
+                    o << first_prefix;
+                }
+            }
+
+            if (use_count)
+            {
+                o << static_cast<CharType>('#');
+                write_number_with_ubjson_prefix(j.m_value.object->size(), true);
+            }
+
+            for (const auto& el : *j.m_value.object)
+            {
+                write_number_with_ubjson_prefix(el.first().size(), true);
+                o << el.first();
+                write_ubjson(el.second, use_count, use_type, prefix_required);
+            }
+
+            if (not use_count)
+            {
+                o << static_cast<CharType>('}');
+            }
+
+            break;
+        }
+
+        default:
+            break;
+    }
+}
+
+void json::binary_writer::write_cbor_string(std::string_view str)
+{
+    // step 1: write control byte and the string length
+    const auto N = str.size();
+    if (N <= 0x17)
+    {
+        write_number(static_cast<uint8_t>(0x60 + N));
+    }
+    else if (N <= (std::numeric_limits<uint8_t>::max)())
+    {
+        o << static_cast<CharType>(0x78);
+        write_number(static_cast<uint8_t>(N));
+    }
+    else if (N <= (std::numeric_limits<uint16_t>::max)())
+    {
+        o << static_cast<CharType>(0x79);
+        write_number(static_cast<uint16_t>(N));
+    }
+    else if (N <= (std::numeric_limits<uint32_t>::max)())
+    {
+        o << static_cast<CharType>(0x7A);
+        write_number(static_cast<uint32_t>(N));
+    }
+    // LCOV_EXCL_START
+    else if (N <= (std::numeric_limits<uint64_t>::max)())
+    {
+        o << static_cast<CharType>(0x7B);
+        write_number(static_cast<uint64_t>(N));
+    }
+    // LCOV_EXCL_STOP
+
+    // step 2: write the string
+    o << str;
+}
+
+void json::binary_writer::write_msgpack_string(std::string_view str)
+{
+    // step 1: write control byte and the string length
+    const auto N = str.size();
+    if (N <= 31)
+    {
+        // fixstr
+        write_number(static_cast<uint8_t>(0xA0 | N));
+    }
+    else if (N <= (std::numeric_limits<uint8_t>::max)())
+    {
+        // str 8
+        o << static_cast<CharType>(0xD9);
+        write_number(static_cast<uint8_t>(N));
+    }
+    else if (N <= (std::numeric_limits<uint16_t>::max)())
+    {
+        // str 16
+        o << static_cast<CharType>(0xDA);
+        write_number(static_cast<uint16_t>(N));
+    }
+    else if (N <= (std::numeric_limits<uint32_t>::max)())
+    {
+        // str 32
+        o << static_cast<CharType>(0xDB);
+        write_number(static_cast<uint32_t>(N));
+    }
+
+    // step 2: write the string
+    o << str;
+}
+
+template<typename NumberType>
+void json::binary_writer::write_number(const NumberType n)
+{
+    // step 1: write number to array of length NumberType
+    std::array<uint8_t, sizeof(NumberType)> vec;
+    std::memcpy(vec.data(), &n, sizeof(NumberType));
+
+    // step 2: write array to output (with possible reordering)
+    if (is_little_endian)
+    {
+        // reverse byte order prior to conversion if necessary
+        std::reverse(vec.begin(), vec.end());
+    }
+
+    o << std::span{vec.data(), sizeof(NumberType)};
+}
+
+template<typename NumberType, typename std::enable_if<
+             std::is_unsigned<NumberType>::value, int>::type>
+void json::binary_writer::write_number_with_ubjson_prefix(const NumberType n,
+                                     const bool add_prefix)
+{
+    if (n <= static_cast<uint64_t>((std::numeric_limits<int8_t>::max)()))
+    {
+        if (add_prefix)
+        {
+            o << static_cast<CharType>('i');  // int8
+        }
+        write_number(static_cast<uint8_t>(n));
+    }
+    else if (n <= (std::numeric_limits<uint8_t>::max)())
+    {
+        if (add_prefix)
+        {
+            o << static_cast<CharType>('U');  // uint8
+        }
+        write_number(static_cast<uint8_t>(n));
+    }
+    else if (n <= static_cast<uint64_t>((std::numeric_limits<int16_t>::max)()))
+    {
+        if (add_prefix)
+        {
+            o << static_cast<CharType>('I');  // int16
+        }
+        write_number(static_cast<int16_t>(n));
+    }
+    else if (n <= static_cast<uint64_t>((std::numeric_limits<int32_t>::max)()))
+    {
+        if (add_prefix)
+        {
+            o << static_cast<CharType>('l');  // int32
+        }
+        write_number(static_cast<int32_t>(n));
+    }
+    else if (n <= static_cast<uint64_t>((std::numeric_limits<int64_t>::max)()))
+    {
+        if (add_prefix)
+        {
+            o << static_cast<CharType>('L');  // int64
+        }
+        write_number(static_cast<int64_t>(n));
+    }
+    else
+    {
+        JSON_THROW(out_of_range::create(407, fmt::format("number overflow serializing {}", n)));
+    }
+}
+
+template<typename NumberType, typename std::enable_if<
+             std::is_signed<NumberType>::value and
+             not std::is_floating_point<NumberType>::value, int>::type>
+void json::binary_writer::write_number_with_ubjson_prefix(const NumberType n,
+                                     const bool add_prefix)
+{
+    if ((std::numeric_limits<int8_t>::min)() <= n and n <= (std::numeric_limits<int8_t>::max)())
+    {
+        if (add_prefix)
+        {
+            o << static_cast<CharType>('i');  // int8
+        }
+        write_number(static_cast<int8_t>(n));
+    }
+    else if (static_cast<int64_t>((std::numeric_limits<uint8_t>::min)()) <= n and n <= static_cast<int64_t>((std::numeric_limits<uint8_t>::max)()))
+    {
+        if (add_prefix)
+        {
+            o << static_cast<CharType>('U');  // uint8
+        }
+        write_number(static_cast<uint8_t>(n));
+    }
+    else if ((std::numeric_limits<int16_t>::min)() <= n and n <= (std::numeric_limits<int16_t>::max)())
+    {
+        if (add_prefix)
+        {
+            o << static_cast<CharType>('I');  // int16
+        }
+        write_number(static_cast<int16_t>(n));
+    }
+    else if ((std::numeric_limits<int32_t>::min)() <= n and n <= (std::numeric_limits<int32_t>::max)())
+    {
+        if (add_prefix)
+        {
+            o << static_cast<CharType>('l');  // int32
+        }
+        write_number(static_cast<int32_t>(n));
+    }
+    else if ((std::numeric_limits<int64_t>::min)() <= n and n <= (std::numeric_limits<int64_t>::max)())
+    {
+        if (add_prefix)
+        {
+            o << static_cast<CharType>('L');  // int64
+        }
+        write_number(static_cast<int64_t>(n));
+    }
+    // LCOV_EXCL_START
+    else
+    {
+        JSON_THROW(out_of_range::create(407, fmt::format("number overflow serializing {}", n)));
+    }
+    // LCOV_EXCL_STOP
+}
+
+json::binary_writer::CharType json::binary_writer::ubjson_prefix(const json& j) const noexcept
+{
+    switch (j.type())
+    {
+        case value_t::null:
+            return 'Z';
+
+        case value_t::boolean:
+            return j.m_value.boolean ? 'T' : 'F';
+
+        case value_t::number_integer:
+        {
+            if ((std::numeric_limits<int8_t>::min)() <= j.m_value.number_integer and j.m_value.number_integer <= (std::numeric_limits<int8_t>::max)())
+            {
+                return 'i';
+            }
+            else if ((std::numeric_limits<uint8_t>::min)() <= j.m_value.number_integer and j.m_value.number_integer <= (std::numeric_limits<uint8_t>::max)())
+            {
+                return 'U';
+            }
+            else if ((std::numeric_limits<int16_t>::min)() <= j.m_value.number_integer and j.m_value.number_integer <= (std::numeric_limits<int16_t>::max)())
+            {
+                return 'I';
+            }
+            else if ((std::numeric_limits<int32_t>::min)() <= j.m_value.number_integer and j.m_value.number_integer <= (std::numeric_limits<int32_t>::max)())
+            {
+                return 'l';
+            }
+            else  // no check and assume int64_t (see note above)
+            {
+                return 'L';
+            }
+        }
+
+        case value_t::number_unsigned:
+        {
+            if (j.m_value.number_unsigned <= static_cast<uint64_t>((std::numeric_limits<int8_t>::max)()))
+            {
+                return 'i';
+            }
+            else if (j.m_value.number_unsigned <= (std::numeric_limits<uint8_t>::max)())
+            {
+                return 'U';
+            }
+            else if (j.m_value.number_unsigned <= static_cast<uint64_t>((std::numeric_limits<int16_t>::max)()))
+            {
+                return 'I';
+            }
+            else if (j.m_value.number_unsigned <= static_cast<uint64_t>((std::numeric_limits<int32_t>::max)()))
+            {
+                return 'l';
+            }
+            else  // no check and assume int64_t (see note above)
+            {
+                return 'L';
+            }
+        }
+
+        case value_t::number_float:
+            return get_ubjson_float_prefix(j.m_value.number_float);
+
+        case value_t::string:
+            return 'S';
+
+        case value_t::array:
+            return '[';
+
+        case value_t::object:
+            return '{';
+
+        default:  // discarded values
+            return 'N';
+    }
+}
+
+std::vector<uint8_t> json::to_cbor(const json& j)
+{
+    std::vector<uint8_t> result;
+    raw_uvector_ostream os(result);
+    to_cbor(os, j);
+    return result;
+}
+
+std::span<uint8_t> json::to_cbor(const json& j, std::vector<uint8_t>& buf)
+{
+    buf.clear();
+    raw_uvector_ostream os(buf);
+    to_cbor(os, j);
+    return os.array();
+}
+
+std::span<uint8_t> json::to_cbor(const json& j, SmallVectorImpl<uint8_t>& buf)
+{
+    buf.clear();
+    raw_usvector_ostream os(buf);
+    to_cbor(os, j);
+    return os.array();
+}
+
+void json::to_cbor(raw_ostream& os, const json& j)
+{
+    binary_writer(os).write_cbor(j);
+}
+
+std::vector<uint8_t> json::to_msgpack(const json& j)
+{
+    std::vector<uint8_t> result;
+    raw_uvector_ostream os(result);
+    to_msgpack(os, j);
+    return result;
+}
+
+std::span<uint8_t> json::to_msgpack(const json& j, std::vector<uint8_t>& buf)
+{
+    buf.clear();
+    raw_uvector_ostream os(buf);
+    to_msgpack(os, j);
+    return os.array();
+}
+
+std::span<uint8_t> json::to_msgpack(const json& j, SmallVectorImpl<uint8_t>& buf)
+{
+    buf.clear();
+    raw_usvector_ostream os(buf);
+    to_msgpack(os, j);
+    return os.array();
+}
+
+void json::to_msgpack(raw_ostream& os, const json& j)
+{
+    binary_writer(os).write_msgpack(j);
+}
+
+std::vector<uint8_t> json::to_ubjson(const json& j,
+                                     const bool use_size,
+                                     const bool use_type)
+{
+    std::vector<uint8_t> result;
+    raw_uvector_ostream os(result);
+    to_ubjson(os, j, use_size, use_type);
+    return result;
+}
+
+std::span<uint8_t> json::to_ubjson(const json& j, std::vector<uint8_t>& buf,
+                              const bool use_size, const bool use_type)
+{
+    buf.clear();
+    raw_uvector_ostream os(buf);
+    to_ubjson(os, j, use_size, use_type);
+    return os.array();
+}
+
+std::span<uint8_t> json::to_ubjson(const json& j, SmallVectorImpl<uint8_t>& buf,
+                              const bool use_size, const bool use_type)
+{
+    buf.clear();
+    raw_usvector_ostream os(buf);
+    to_ubjson(os, j, use_size, use_type);
+    return os.array();
+}
+
+void json::to_ubjson(raw_ostream& os, const json& j,
+                     const bool use_size, const bool use_type)
+{
+    binary_writer(os).write_ubjson(j, use_size, use_type);
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/json/cpp/json_parser.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/json/cpp/json_parser.cpp
new file mode 100644
index 0000000..3c29489
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/json/cpp/json_parser.cpp
@@ -0,0 +1,1968 @@
+/*----------------------------------------------------------------------------*/
+/* Modifications Copyright (c) 2017-2018 FIRST. All Rights Reserved.          */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+/*
+    __ _____ _____ _____
+ __|  |   __|     |   | |  JSON for Modern C++
+|  |  |__   |  |  | | | |  version 3.1.2
+|_____|_____|_____|_|___|  https://github.com/nlohmann/json
+
+Licensed under the MIT License <http://opensource.org/licenses/MIT>.
+Copyright (c) 2013-2018 Niels Lohmann <http://nlohmann.me>.
+
+Permission is hereby  granted, free of charge, to any  person obtaining a copy
+of this software and associated  documentation files (the "Software"), to deal
+in the Software  without restriction, including without  limitation the rights
+to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
+copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
+IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
+FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
+AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
+LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+*/
+#define WPI_JSON_IMPLEMENTATION
+#include "wpi/json.h"
+
+#include <clocale>
+#include <cmath>
+#include <cstdlib>
+
+#include "fmt/format.h"
+#include "wpi/SmallString.h"
+#include "wpi/raw_istream.h"
+#include "wpi/raw_ostream.h"
+
+namespace wpi {
+
+/*!
+@brief lexical analysis
+
+This class organizes the lexical analysis during JSON deserialization.
+*/
+class json::lexer
+{
+  public:
+    /// token types for the parser
+    enum class token_type
+    {
+        uninitialized,    ///< indicating the scanner is uninitialized
+        literal_true,     ///< the `true` literal
+        literal_false,    ///< the `false` literal
+        literal_null,     ///< the `null` literal
+        value_string,     ///< a string -- use get_string() for actual value
+        value_unsigned,   ///< an unsigned integer -- use get_number_unsigned() for actual value
+        value_integer,    ///< a signed integer -- use get_number_integer() for actual value
+        value_float,      ///< an floating point number -- use get_number_float() for actual value
+        begin_array,      ///< the character for array begin `[`
+        begin_object,     ///< the character for object begin `{`
+        end_array,        ///< the character for array end `]`
+        end_object,       ///< the character for object end `}`
+        name_separator,   ///< the name separator `:`
+        value_separator,  ///< the value separator `,`
+        parse_error,      ///< indicating a parse error
+        end_of_input,     ///< indicating the end of the input buffer
+        literal_or_value  ///< a literal or the begin of a value (only for diagnostics)
+    };
+
+    /// return name of values of type token_type (only used for errors)
+    static const char* token_type_name(const token_type t) noexcept;
+
+    explicit lexer(raw_istream& s);
+
+    // delete because of pointer members
+    lexer(const lexer&) = delete;
+    lexer& operator=(lexer&) = delete;
+
+  private:
+    /////////////////////
+    // locales
+    /////////////////////
+
+    /// return the locale-dependent decimal point
+    static char get_decimal_point() noexcept
+    {
+        const auto loc = localeconv();
+        assert(loc != nullptr);
+        return (loc->decimal_point == nullptr) ? '.' : *(loc->decimal_point);
+    }
+
+    /////////////////////
+    // scan functions
+    /////////////////////
+
+    /*!
+    @brief get codepoint from 4 hex characters following `\u`
+
+    For input "\u c1 c2 c3 c4" the codepoint is:
+      (c1 * 0x1000) + (c2 * 0x0100) + (c3 * 0x0010) + c4
+    = (c1 << 12) + (c2 << 8) + (c3 << 4) + (c4 << 0)
+
+    Furthermore, the possible characters '0'..'9', 'A'..'F', and 'a'..'f'
+    must be converted to the integers 0x0..0x9, 0xA..0xF, 0xA..0xF, resp. The
+    conversion is done by subtracting the offset (0x30, 0x37, and 0x57)
+    between the ASCII value of the character and the desired integer value.
+
+    @return codepoint (0x0000..0xFFFF) or -1 in case of an error (e.g. EOF or
+            non-hex character)
+    */
+    int get_codepoint();
+
+    /*!
+    @brief check if the next byte(s) are inside a given range
+
+    Adds the current byte and, for each passed range, reads a new byte and
+    checks if it is inside the range. If a violation was detected, set up an
+    error message and return false. Otherwise, return true.
+
+    @param[in] ranges  list of integers; interpreted as list of pairs of
+                       inclusive lower and upper bound, respectively
+
+    @pre The passed list @a ranges must have 2, 4, or 6 elements; that is,
+         1, 2, or 3 pairs. This precondition is enforced by an assertion.
+
+    @return true if and only if no range violation was detected
+    */
+    bool next_byte_in_range(std::initializer_list<int> ranges)
+    {
+        assert(ranges.size() == 2 or ranges.size() == 4 or ranges.size() == 6);
+        add(current);
+
+        for (auto range = ranges.begin(); range != ranges.end(); ++range)
+        {
+            get();
+            if (JSON_LIKELY(*range <= current and current <= *(++range)))
+            {
+                add(current);
+            }
+            else
+            {
+                error_message = "invalid string: ill-formed UTF-8 byte";
+                return false;
+            }
+        }
+
+        return true;
+    }
+
+    /*!
+    @brief scan a string literal
+
+    This function scans a string according to Sect. 7 of RFC 7159. While
+    scanning, bytes are escaped and copied into buffer token_buffer. Then the
+    function returns successfully, token_buffer is *not* null-terminated (as it
+    may contain \0 bytes), and token_buffer.size() is the number of bytes in the
+    string.
+
+    @return token_type::value_string if string could be successfully scanned,
+            token_type::parse_error otherwise
+
+    @note In case of errors, variable error_message contains a textual
+          description.
+    */
+    token_type scan_string();
+
+    static void strtof(float& f, const char* str, char** endptr) noexcept
+    {
+        f = std::strtof(str, endptr);
+    }
+
+    static void strtof(double& f, const char* str, char** endptr) noexcept
+    {
+        f = std::strtod(str, endptr);
+    }
+
+    static void strtof(long double& f, const char* str, char** endptr) noexcept
+    {
+        f = std::strtold(str, endptr);
+    }
+
+    /*!
+    @brief scan a number literal
+
+    This function scans a string according to Sect. 6 of RFC 7159.
+
+    The function is realized with a deterministic finite state machine derived
+    from the grammar described in RFC 7159. Starting in state "init", the
+    input is read and used to determined the next state. Only state "done"
+    accepts the number. State "error" is a trap state to model errors. In the
+    table below, "anything" means any character but the ones listed before.
+
+    state    | 0        | 1-9      | e E      | +       | -       | .        | anything
+    ---------|----------|----------|----------|---------|---------|----------|-----------
+    init     | zero     | any1     | [error]  | [error] | minus   | [error]  | [error]
+    minus    | zero     | any1     | [error]  | [error] | [error] | [error]  | [error]
+    zero     | done     | done     | exponent | done    | done    | decimal1 | done
+    any1     | any1     | any1     | exponent | done    | done    | decimal1 | done
+    decimal1 | decimal2 | [error]  | [error]  | [error] | [error] | [error]  | [error]
+    decimal2 | decimal2 | decimal2 | exponent | done    | done    | done     | done
+    exponent | any2     | any2     | [error]  | sign    | sign    | [error]  | [error]
+    sign     | any2     | any2     | [error]  | [error] | [error] | [error]  | [error]
+    any2     | any2     | any2     | done     | done    | done    | done     | done
+
+    The state machine is realized with one label per state (prefixed with
+    "scan_number_") and `goto` statements between them. The state machine
+    contains cycles, but any cycle can be left when EOF is read. Therefore,
+    the function is guaranteed to terminate.
+
+    During scanning, the read bytes are stored in token_buffer. This string is
+    then converted to a signed integer, an unsigned integer, or a
+    floating-point number.
+
+    @return token_type::value_unsigned, token_type::value_integer, or
+            token_type::value_float if number could be successfully scanned,
+            token_type::parse_error otherwise
+
+    @note The scanner is independent of the current locale. Internally, the
+          locale's decimal point is used instead of `.` to work with the
+          locale-dependent converters.
+    */
+    token_type scan_number();
+
+    /*!
+    @param[in] literal_text  the literal text to expect
+    @param[in] length        the length of the passed literal text
+    @param[in] return_type   the token type to return on success
+    */
+    token_type scan_literal(const char* literal_text, const std::size_t length,
+                            token_type return_type);
+
+    /////////////////////
+    // input management
+    /////////////////////
+
+    /// reset token_buffer; current character is beginning of token
+    void reset() noexcept
+    {
+        token_buffer.clear();
+        token_string.clear();
+        token_string.push_back(std::char_traits<char>::to_char_type(current));
+    }
+
+    /*
+    @brief get next character from the input
+
+    This function provides the interface to the used input adapter. It does
+    not throw in case the input reached EOF, but returns a
+    `std::char_traits<char>::eof()` in that case.  Stores the scanned characters
+    for use in error messages.
+
+    @return character read from the input
+    */
+    std::char_traits<char>::int_type get()
+    {
+        ++chars_read;
+        if (JSON_UNLIKELY(!unget_chars.empty()))
+        {
+            current = unget_chars.back();
+            unget_chars.pop_back();
+            token_string.push_back(current);
+            return current;
+        }
+        char c;
+        is.read(c);
+        if (JSON_UNLIKELY(is.has_error()))
+        {
+            current = std::char_traits<char>::eof();
+        }
+        else
+        {
+            current = std::char_traits<char>::to_int_type(c);
+            token_string.push_back(c);
+        }
+        return current;
+    }
+
+    /// unget current character (return it again on next get)
+    void unget()
+    {
+        --chars_read;
+        if (JSON_LIKELY(current != std::char_traits<char>::eof()))
+        {
+            unget_chars.emplace_back(current);
+            assert(token_string.size() != 0);
+            token_string.pop_back();
+            if (!token_string.empty())
+            {
+                current = token_string.back();
+            }
+        }
+    }
+
+    /// put back character (returned on next get)
+    void putback(std::char_traits<char>::int_type c)
+    {
+        --chars_read;
+        unget_chars.emplace_back(c);
+    }
+
+    /// add a character to token_buffer
+    void add(int c)
+    {
+        token_buffer.push_back(std::char_traits<char>::to_char_type(c));
+    }
+
+  public:
+    /////////////////////
+    // value getters
+    /////////////////////
+
+    /// return integer value
+    int64_t get_number_integer() const noexcept
+    {
+        return value_integer;
+    }
+
+    /// return unsigned integer value
+    uint64_t get_number_unsigned() const noexcept
+    {
+        return value_unsigned;
+    }
+
+    /// return floating-point value
+    double get_number_float() const noexcept
+    {
+        return value_float;
+    }
+
+    /// return current string value
+    std::string_view get_string()
+    {
+        return token_buffer;
+    }
+
+    /////////////////////
+    // diagnostics
+    /////////////////////
+
+    /// return position of last read token
+    std::size_t get_position() const noexcept
+    {
+        return chars_read;
+    }
+
+    /// return the last read token (for errors only).  Will never contain EOF
+    /// (an arbitrary value that is not a valid char value, often -1), because
+    /// 255 may legitimately occur.  May contain NUL, which should be escaped.
+    std::string get_token_string() const;
+
+    /// return syntax error message
+    const char* get_error_message() const noexcept
+    {
+        return error_message;
+    }
+
+    /////////////////////
+    // actual scanner
+    /////////////////////
+
+    token_type scan();
+
+  private:
+    /// input adapter
+    raw_istream& is;
+
+    /// the current character
+    std::char_traits<char>::int_type current = std::char_traits<char>::eof();
+
+    /// unget characters
+    SmallVector<std::char_traits<char>::int_type, 4> unget_chars;
+
+    /// the number of characters read
+    std::size_t chars_read = 0;
+
+    /// raw input token string (for error messages)
+    SmallString<128> token_string {};
+
+    /// buffer for variable-length tokens (numbers, strings)
+    SmallString<128> token_buffer {};
+
+    /// a description of occurred lexer errors
+    const char* error_message = "";
+
+    // number values
+    int64_t value_integer = 0;
+    uint64_t value_unsigned = 0;
+    double value_float = 0;
+
+    /// the decimal point
+    const char decimal_point_char = '.';
+};
+
+////////////
+// parser //
+////////////
+
+/*!
+@brief syntax analysis
+
+This class implements a recursive decent parser.
+*/
+class json::parser
+{
+    using lexer_t = json::lexer;
+    using token_type = typename lexer_t::token_type;
+
+  public:
+    /// a parser reading from an input adapter
+    explicit parser(raw_istream& s,
+                    const parser_callback_t cb = nullptr,
+                    const bool allow_exceptions_ = true)
+        : callback(cb), m_lexer(s), allow_exceptions(allow_exceptions_)
+    {}
+
+    /*!
+    @brief public parser interface
+
+    @param[in] strict      whether to expect the last token to be EOF
+    @param[in,out] result  parsed JSON value
+
+    @throw parse_error.101 in case of an unexpected token
+    @throw parse_error.102 if to_unicode fails or surrogate error
+    @throw parse_error.103 if to_unicode fails
+    */
+    void parse(const bool strict, json& result);
+
+    /*!
+    @brief public accept interface
+
+    @param[in] strict  whether to expect the last token to be EOF
+    @return whether the input is a proper JSON text
+    */
+    bool accept(const bool strict = true)
+    {
+        // read first token
+        get_token();
+
+        if (not accept_internal())
+        {
+            return false;
+        }
+
+        // strict => last token must be EOF
+        return not strict or (get_token() == token_type::end_of_input);
+    }
+
+  private:
+    /*!
+    @brief the actual parser
+    @throw parse_error.101 in case of an unexpected token
+    @throw parse_error.102 if to_unicode fails or surrogate error
+    @throw parse_error.103 if to_unicode fails
+    */
+    void parse_internal(bool keep, json& result);
+
+    /*!
+    @brief the actual acceptor
+
+    @invariant 1. The last token is not yet processed. Therefore, the caller
+                  of this function must make sure a token has been read.
+               2. When this function returns, the last token is processed.
+                  That is, the last read character was already considered.
+
+    This invariant makes sure that no token needs to be "unput".
+    */
+    bool accept_internal();
+
+    /// get next token from lexer
+    token_type get_token()
+    {
+        return (last_token = m_lexer.scan());
+    }
+
+    /*!
+    @throw parse_error.101 if expected token did not occur
+    */
+    bool expect(token_type t)
+    {
+        if (JSON_UNLIKELY(t != last_token))
+        {
+            errored = true;
+            expected = t;
+            if (allow_exceptions)
+            {
+                throw_exception();
+            }
+            else
+            {
+                return false;
+            }
+        }
+
+        return true;
+    }
+
+    [[noreturn]] void throw_exception() const;
+
+  private:
+    /// current level of recursion
+    int depth = 0;
+    /// callback function
+    const parser_callback_t callback = nullptr;
+    /// the type of the last read token
+    token_type last_token = token_type::uninitialized;
+    /// the lexer
+    lexer_t m_lexer;
+    /// whether a syntax error occurred
+    bool errored = false;
+    /// possible reason for the syntax error
+    token_type expected = token_type::uninitialized;
+    /// whether to throw exceptions in case of errors
+    const bool allow_exceptions = true;
+};
+
+const char* json::lexer::token_type_name(const token_type t) noexcept
+{
+    switch (t)
+    {
+        case token_type::uninitialized:
+            return "<uninitialized>";
+        case token_type::literal_true:
+            return "true literal";
+        case token_type::literal_false:
+            return "false literal";
+        case token_type::literal_null:
+            return "null literal";
+        case token_type::value_string:
+            return "string literal";
+        case lexer::token_type::value_unsigned:
+        case lexer::token_type::value_integer:
+        case lexer::token_type::value_float:
+            return "number literal";
+        case token_type::begin_array:
+            return "'['";
+        case token_type::begin_object:
+            return "'{'";
+        case token_type::end_array:
+            return "']'";
+        case token_type::end_object:
+            return "'}'";
+        case token_type::name_separator:
+            return "':'";
+        case token_type::value_separator:
+            return "','";
+        case token_type::parse_error:
+            return "<parse error>";
+        case token_type::end_of_input:
+            return "end of input";
+        case token_type::literal_or_value:
+            return "'[', '{', or a literal";
+        default: // catch non-enum values
+            return "unknown token"; // LCOV_EXCL_LINE
+    }
+}
+
+json::lexer::lexer(raw_istream& s)
+    : is(s), decimal_point_char(get_decimal_point())
+{
+    // skip byte order mark
+    std::char_traits<char>::int_type c;
+    if ((c = get()) == 0xEF)
+    {
+        if ((c = get()) == 0xBB)
+        {
+            if ((c = get()) == 0xBF)
+            {
+                chars_read = 0;
+                return; // Ignore BOM
+            }
+            else if (c != std::char_traits<char>::eof())
+            {
+                unget();
+            }
+            putback('\xBB');
+        }
+        else if (c != std::char_traits<char>::eof())
+        {
+            unget();
+        }
+        putback('\xEF');
+    }
+    unget(); // no byte order mark; process as usual
+}
+
+int json::lexer::get_codepoint()
+{
+    // this function only makes sense after reading `\u`
+    assert(current == 'u');
+    int codepoint = 0;
+
+    const auto factors = { 12, 8, 4, 0 };
+    for (const auto factor : factors)
+    {
+        get();
+
+        if (current >= '0' and current <= '9')
+        {
+            codepoint += ((current - 0x30) << factor);
+        }
+        else if (current >= 'A' and current <= 'F')
+        {
+            codepoint += ((current - 0x37) << factor);
+        }
+        else if (current >= 'a' and current <= 'f')
+        {
+            codepoint += ((current - 0x57) << factor);
+        }
+        else
+        {
+            return -1;
+        }
+    }
+
+    assert(0x0000 <= codepoint and codepoint <= 0xFFFF);
+    return codepoint;
+}
+
+json::lexer::token_type json::lexer::scan_string()
+{
+    // reset token_buffer (ignore opening quote)
+    reset();
+
+    // we entered the function by reading an open quote
+    assert(current == '\"');
+
+    while (true)
+    {
+        // get next character
+        switch (get())
+        {
+            // end of file while parsing string
+            case std::char_traits<char>::eof():
+            {
+                error_message = "invalid string: missing closing quote";
+                return token_type::parse_error;
+            }
+
+            // closing quote
+            case '\"':
+            {
+                return token_type::value_string;
+            }
+
+            // escapes
+            case '\\':
+            {
+                switch (get())
+                {
+                    // quotation mark
+                    case '\"':
+                        add('\"');
+                        break;
+                    // reverse solidus
+                    case '\\':
+                        add('\\');
+                        break;
+                    // solidus
+                    case '/':
+                        add('/');
+                        break;
+                    // backspace
+                    case 'b':
+                        add('\b');
+                        break;
+                    // form feed
+                    case 'f':
+                        add('\f');
+                        break;
+                    // line feed
+                    case 'n':
+                        add('\n');
+                        break;
+                    // carriage return
+                    case 'r':
+                        add('\r');
+                        break;
+                    // tab
+                    case 't':
+                        add('\t');
+                        break;
+
+                    // unicode escapes
+                    case 'u':
+                    {
+                        const int codepoint1 = get_codepoint();
+                        int codepoint = codepoint1; // start with codepoint1
+
+                        if (JSON_UNLIKELY(codepoint1 == -1))
+                        {
+                            error_message = "invalid string: '\\u' must be followed by 4 hex digits";
+                            return token_type::parse_error;
+                        }
+
+                        // check if code point is a high surrogate
+                        if (0xD800 <= codepoint1 and codepoint1 <= 0xDBFF)
+                        {
+                            // expect next \uxxxx entry
+                            if (JSON_LIKELY(get() == '\\' and get() == 'u'))
+                            {
+                                const int codepoint2 = get_codepoint();
+
+                                if (JSON_UNLIKELY(codepoint2 == -1))
+                                {
+                                    error_message = "invalid string: '\\u' must be followed by 4 hex digits";
+                                    return token_type::parse_error;
+                                }
+
+                                // check if codepoint2 is a low surrogate
+                                if (JSON_LIKELY(0xDC00 <= codepoint2 and codepoint2 <= 0xDFFF))
+                                {
+                                    // overwrite codepoint
+                                    codepoint =
+                                        // high surrogate occupies the most significant 22 bits
+                                        (codepoint1 << 10)
+                                        // low surrogate occupies the least significant 15 bits
+                                        + codepoint2
+                                        // there is still the 0xD800, 0xDC00 and 0x10000 noise
+                                        // in the result so we have to subtract with:
+                                        // (0xD800 << 10) + DC00 - 0x10000 = 0x35FDC00
+                                        - 0x35FDC00;
+                                }
+                                else
+                                {
+                                    error_message = "invalid string: surrogate U+DC00..U+DFFF must be followed by U+DC00..U+DFFF";
+                                    return token_type::parse_error;
+                                }
+                            }
+                            else
+                            {
+                                error_message = "invalid string: surrogate U+DC00..U+DFFF must be followed by U+DC00..U+DFFF";
+                                return token_type::parse_error;
+                            }
+                        }
+                        else
+                        {
+                            if (JSON_UNLIKELY(0xDC00 <= codepoint1 and codepoint1 <= 0xDFFF))
+                            {
+                                error_message = "invalid string: surrogate U+DC00..U+DFFF must follow U+D800..U+DBFF";
+                                return token_type::parse_error;
+                            }
+                        }
+
+                        // result of the above calculation yields a proper codepoint
+                        assert(0x00 <= codepoint and codepoint <= 0x10FFFF);
+
+                        // translate codepoint into bytes
+                        if (codepoint < 0x80)
+                        {
+                            // 1-byte characters: 0xxxxxxx (ASCII)
+                            add(codepoint);
+                        }
+                        else if (codepoint <= 0x7FF)
+                        {
+                            // 2-byte characters: 110xxxxx 10xxxxxx
+                            add(0xC0 | (codepoint >> 6));
+                            add(0x80 | (codepoint & 0x3F));
+                        }
+                        else if (codepoint <= 0xFFFF)
+                        {
+                            // 3-byte characters: 1110xxxx 10xxxxxx 10xxxxxx
+                            add(0xE0 | (codepoint >> 12));
+                            add(0x80 | ((codepoint >> 6) & 0x3F));
+                            add(0x80 | (codepoint & 0x3F));
+                        }
+                        else
+                        {
+                            // 4-byte characters: 11110xxx 10xxxxxx 10xxxxxx 10xxxxxx
+                            add(0xF0 | (codepoint >> 18));
+                            add(0x80 | ((codepoint >> 12) & 0x3F));
+                            add(0x80 | ((codepoint >> 6) & 0x3F));
+                            add(0x80 | (codepoint & 0x3F));
+                        }
+
+                        break;
+                    }
+
+                    // other characters after escape
+                    default:
+                        error_message = "invalid string: forbidden character after backslash";
+                        return token_type::parse_error;
+                }
+
+                break;
+            }
+
+            // invalid control characters
+            case 0x00:
+            case 0x01:
+            case 0x02:
+            case 0x03:
+            case 0x04:
+            case 0x05:
+            case 0x06:
+            case 0x07:
+            case 0x08:
+            case 0x09:
+            case 0x0A:
+            case 0x0B:
+            case 0x0C:
+            case 0x0D:
+            case 0x0E:
+            case 0x0F:
+            case 0x10:
+            case 0x11:
+            case 0x12:
+            case 0x13:
+            case 0x14:
+            case 0x15:
+            case 0x16:
+            case 0x17:
+            case 0x18:
+            case 0x19:
+            case 0x1A:
+            case 0x1B:
+            case 0x1C:
+            case 0x1D:
+            case 0x1E:
+            case 0x1F:
+            {
+                error_message = "invalid string: control character must be escaped";
+                return token_type::parse_error;
+            }
+
+            // U+0020..U+007F (except U+0022 (quote) and U+005C (backspace))
+            case 0x20:
+            case 0x21:
+            case 0x23:
+            case 0x24:
+            case 0x25:
+            case 0x26:
+            case 0x27:
+            case 0x28:
+            case 0x29:
+            case 0x2A:
+            case 0x2B:
+            case 0x2C:
+            case 0x2D:
+            case 0x2E:
+            case 0x2F:
+            case 0x30:
+            case 0x31:
+            case 0x32:
+            case 0x33:
+            case 0x34:
+            case 0x35:
+            case 0x36:
+            case 0x37:
+            case 0x38:
+            case 0x39:
+            case 0x3A:
+            case 0x3B:
+            case 0x3C:
+            case 0x3D:
+            case 0x3E:
+            case 0x3F:
+            case 0x40:
+            case 0x41:
+            case 0x42:
+            case 0x43:
+            case 0x44:
+            case 0x45:
+            case 0x46:
+            case 0x47:
+            case 0x48:
+            case 0x49:
+            case 0x4A:
+            case 0x4B:
+            case 0x4C:
+            case 0x4D:
+            case 0x4E:
+            case 0x4F:
+            case 0x50:
+            case 0x51:
+            case 0x52:
+            case 0x53:
+            case 0x54:
+            case 0x55:
+            case 0x56:
+            case 0x57:
+            case 0x58:
+            case 0x59:
+            case 0x5A:
+            case 0x5B:
+            case 0x5D:
+            case 0x5E:
+            case 0x5F:
+            case 0x60:
+            case 0x61:
+            case 0x62:
+            case 0x63:
+            case 0x64:
+            case 0x65:
+            case 0x66:
+            case 0x67:
+            case 0x68:
+            case 0x69:
+            case 0x6A:
+            case 0x6B:
+            case 0x6C:
+            case 0x6D:
+            case 0x6E:
+            case 0x6F:
+            case 0x70:
+            case 0x71:
+            case 0x72:
+            case 0x73:
+            case 0x74:
+            case 0x75:
+            case 0x76:
+            case 0x77:
+            case 0x78:
+            case 0x79:
+            case 0x7A:
+            case 0x7B:
+            case 0x7C:
+            case 0x7D:
+            case 0x7E:
+            case 0x7F:
+            {
+                add(current);
+                break;
+            }
+
+            // U+0080..U+07FF: bytes C2..DF 80..BF
+            case 0xC2:
+            case 0xC3:
+            case 0xC4:
+            case 0xC5:
+            case 0xC6:
+            case 0xC7:
+            case 0xC8:
+            case 0xC9:
+            case 0xCA:
+            case 0xCB:
+            case 0xCC:
+            case 0xCD:
+            case 0xCE:
+            case 0xCF:
+            case 0xD0:
+            case 0xD1:
+            case 0xD2:
+            case 0xD3:
+            case 0xD4:
+            case 0xD5:
+            case 0xD6:
+            case 0xD7:
+            case 0xD8:
+            case 0xD9:
+            case 0xDA:
+            case 0xDB:
+            case 0xDC:
+            case 0xDD:
+            case 0xDE:
+            case 0xDF:
+            {
+                if (JSON_UNLIKELY(not next_byte_in_range({0x80, 0xBF})))
+                {
+                    return token_type::parse_error;
+                }
+                break;
+            }
+
+            // U+0800..U+0FFF: bytes E0 A0..BF 80..BF
+            case 0xE0:
+            {
+                if (JSON_UNLIKELY(not (next_byte_in_range({0xA0, 0xBF, 0x80, 0xBF}))))
+                {
+                    return token_type::parse_error;
+                }
+                break;
+            }
+
+            // U+1000..U+CFFF: bytes E1..EC 80..BF 80..BF
+            // U+E000..U+FFFF: bytes EE..EF 80..BF 80..BF
+            case 0xE1:
+            case 0xE2:
+            case 0xE3:
+            case 0xE4:
+            case 0xE5:
+            case 0xE6:
+            case 0xE7:
+            case 0xE8:
+            case 0xE9:
+            case 0xEA:
+            case 0xEB:
+            case 0xEC:
+            case 0xEE:
+            case 0xEF:
+            {
+                if (JSON_UNLIKELY(not (next_byte_in_range({0x80, 0xBF, 0x80, 0xBF}))))
+                {
+                    return token_type::parse_error;
+                }
+                break;
+            }
+
+            // U+D000..U+D7FF: bytes ED 80..9F 80..BF
+            case 0xED:
+            {
+                if (JSON_UNLIKELY(not (next_byte_in_range({0x80, 0x9F, 0x80, 0xBF}))))
+                {
+                    return token_type::parse_error;
+                }
+                break;
+            }
+
+            // U+10000..U+3FFFF F0 90..BF 80..BF 80..BF
+            case 0xF0:
+            {
+                if (JSON_UNLIKELY(not (next_byte_in_range({0x90, 0xBF, 0x80, 0xBF, 0x80, 0xBF}))))
+                {
+                    return token_type::parse_error;
+                }
+                break;
+            }
+
+            // U+40000..U+FFFFF F1..F3 80..BF 80..BF 80..BF
+            case 0xF1:
+            case 0xF2:
+            case 0xF3:
+            {
+                if (JSON_UNLIKELY(not (next_byte_in_range({0x80, 0xBF, 0x80, 0xBF, 0x80, 0xBF}))))
+                {
+                    return token_type::parse_error;
+                }
+                break;
+            }
+
+            // U+100000..U+10FFFF F4 80..8F 80..BF 80..BF
+            case 0xF4:
+            {
+                if (JSON_UNLIKELY(not (next_byte_in_range({0x80, 0x8F, 0x80, 0xBF, 0x80, 0xBF}))))
+                {
+                    return token_type::parse_error;
+                }
+                break;
+            }
+
+            // remaining bytes (80..C1 and F5..FF) are ill-formed
+            default:
+            {
+                error_message = "invalid string: ill-formed UTF-8 byte";
+                return token_type::parse_error;
+            }
+        }
+    }
+}
+
+json::lexer::token_type json::lexer::scan_number()
+{
+    // reset token_buffer to store the number's bytes
+    reset();
+
+    // the type of the parsed number; initially set to unsigned; will be
+    // changed if minus sign, decimal point or exponent is read
+    token_type number_type = token_type::value_unsigned;
+
+    // state (init): we just found out we need to scan a number
+    switch (current)
+    {
+        case '-':
+        {
+            add(current);
+            goto scan_number_minus;
+        }
+
+        case '0':
+        {
+            add(current);
+            goto scan_number_zero;
+        }
+
+        case '1':
+        case '2':
+        case '3':
+        case '4':
+        case '5':
+        case '6':
+        case '7':
+        case '8':
+        case '9':
+        {
+            add(current);
+            goto scan_number_any1;
+        }
+
+        default:
+        {
+            // all other characters are rejected outside scan_number()
+            assert(false); // LCOV_EXCL_LINE
+        }
+    }
+
+scan_number_minus:
+    // state: we just parsed a leading minus sign
+    number_type = token_type::value_integer;
+    switch (get())
+    {
+        case '0':
+        {
+            add(current);
+            goto scan_number_zero;
+        }
+
+        case '1':
+        case '2':
+        case '3':
+        case '4':
+        case '5':
+        case '6':
+        case '7':
+        case '8':
+        case '9':
+        {
+            add(current);
+            goto scan_number_any1;
+        }
+
+        default:
+        {
+            error_message = "invalid number; expected digit after '-'";
+            return token_type::parse_error;
+        }
+    }
+
+scan_number_zero:
+    // state: we just parse a zero (maybe with a leading minus sign)
+    switch (get())
+    {
+        case '.':
+        {
+            add(decimal_point_char);
+            goto scan_number_decimal1;
+        }
+
+        case 'e':
+        case 'E':
+        {
+            add(current);
+            goto scan_number_exponent;
+        }
+
+        default:
+            goto scan_number_done;
+    }
+
+scan_number_any1:
+    // state: we just parsed a number 0-9 (maybe with a leading minus sign)
+    switch (get())
+    {
+        case '0':
+        case '1':
+        case '2':
+        case '3':
+        case '4':
+        case '5':
+        case '6':
+        case '7':
+        case '8':
+        case '9':
+        {
+            add(current);
+            goto scan_number_any1;
+        }
+
+        case '.':
+        {
+            add(decimal_point_char);
+            goto scan_number_decimal1;
+        }
+
+        case 'e':
+        case 'E':
+        {
+            add(current);
+            goto scan_number_exponent;
+        }
+
+        default:
+            goto scan_number_done;
+    }
+
+scan_number_decimal1:
+    // state: we just parsed a decimal point
+    number_type = token_type::value_float;
+    switch (get())
+    {
+        case '0':
+        case '1':
+        case '2':
+        case '3':
+        case '4':
+        case '5':
+        case '6':
+        case '7':
+        case '8':
+        case '9':
+        {
+            add(current);
+            goto scan_number_decimal2;
+        }
+
+        default:
+        {
+            error_message = "invalid number; expected digit after '.'";
+            return token_type::parse_error;
+        }
+    }
+
+scan_number_decimal2:
+    // we just parsed at least one number after a decimal point
+    switch (get())
+    {
+        case '0':
+        case '1':
+        case '2':
+        case '3':
+        case '4':
+        case '5':
+        case '6':
+        case '7':
+        case '8':
+        case '9':
+        {
+            add(current);
+            goto scan_number_decimal2;
+        }
+
+        case 'e':
+        case 'E':
+        {
+            add(current);
+            goto scan_number_exponent;
+        }
+
+        default:
+            goto scan_number_done;
+    }
+
+scan_number_exponent:
+    // we just parsed an exponent
+    number_type = token_type::value_float;
+    switch (get())
+    {
+        case '+':
+        case '-':
+        {
+            add(current);
+            goto scan_number_sign;
+        }
+
+        case '0':
+        case '1':
+        case '2':
+        case '3':
+        case '4':
+        case '5':
+        case '6':
+        case '7':
+        case '8':
+        case '9':
+        {
+            add(current);
+            goto scan_number_any2;
+        }
+
+        default:
+        {
+            error_message =
+                "invalid number; expected '+', '-', or digit after exponent";
+            return token_type::parse_error;
+        }
+    }
+
+scan_number_sign:
+    // we just parsed an exponent sign
+    switch (get())
+    {
+        case '0':
+        case '1':
+        case '2':
+        case '3':
+        case '4':
+        case '5':
+        case '6':
+        case '7':
+        case '8':
+        case '9':
+        {
+            add(current);
+            goto scan_number_any2;
+        }
+
+        default:
+        {
+            error_message = "invalid number; expected digit after exponent sign";
+            return token_type::parse_error;
+        }
+    }
+
+scan_number_any2:
+    // we just parsed a number after the exponent or exponent sign
+    switch (get())
+    {
+        case '0':
+        case '1':
+        case '2':
+        case '3':
+        case '4':
+        case '5':
+        case '6':
+        case '7':
+        case '8':
+        case '9':
+        {
+            add(current);
+            goto scan_number_any2;
+        }
+
+        default:
+            goto scan_number_done;
+    }
+
+scan_number_done:
+    // unget the character after the number (we only read it to know that
+    // we are done scanning a number)
+    unget();
+
+    char* endptr = nullptr;
+    errno = 0;
+
+    // try to parse integers first and fall back to floats
+    if (number_type == token_type::value_unsigned)
+    {
+        const auto x = std::strtoull(token_buffer.c_str(), &endptr, 10);
+
+        // we checked the number format before
+        assert(endptr == token_buffer.data() + token_buffer.size());
+
+        if (errno == 0)
+        {
+            value_unsigned = static_cast<uint64_t>(x);
+            if (value_unsigned == x)
+            {
+                return token_type::value_unsigned;
+            }
+        }
+    }
+    else if (number_type == token_type::value_integer)
+    {
+        const auto x = std::strtoll(token_buffer.c_str(), &endptr, 10);
+
+        // we checked the number format before
+        assert(endptr == token_buffer.data() + token_buffer.size());
+
+        if (errno == 0)
+        {
+            value_integer = static_cast<int64_t>(x);
+            if (value_integer == x)
+            {
+                return token_type::value_integer;
+            }
+        }
+    }
+
+    // this code is reached if we parse a floating-point number or if an
+    // integer conversion above failed
+    strtof(value_float, token_buffer.c_str(), &endptr);
+
+    // we checked the number format before
+    assert(endptr == token_buffer.data() + token_buffer.size());
+
+    return token_type::value_float;
+}
+
+json::lexer::token_type json::lexer::scan_literal(const char* literal_text, const std::size_t length,
+                        token_type return_type)
+{
+    assert(current == literal_text[0]);
+    for (std::size_t i = 1; i < length; ++i)
+    {
+        if (JSON_UNLIKELY(get() != literal_text[i]))
+        {
+            error_message = "invalid literal";
+            return token_type::parse_error;
+        }
+    }
+    return return_type;
+}
+
+std::string json::lexer::get_token_string() const
+{
+    // escape control characters
+    std::string result;
+    raw_string_ostream ss(result);
+    for (const unsigned char c : token_string)
+    {
+        if (c <= '\x1F')
+        {
+            // escape control characters
+            ss << fmt::format("<U+{:04X}>", c);
+        }
+        else
+        {
+            // add character as is
+            ss << c;
+        }
+    }
+
+    ss.flush();
+    return result;
+}
+
+json::lexer::token_type json::lexer::scan()
+{
+    // read next character and ignore whitespace
+    do
+    {
+        get();
+    }
+    while (current == ' ' or current == '\t' or current == '\n' or current == '\r');
+
+    switch (current)
+    {
+        // structural characters
+        case '[':
+            return token_type::begin_array;
+        case ']':
+            return token_type::end_array;
+        case '{':
+            return token_type::begin_object;
+        case '}':
+            return token_type::end_object;
+        case ':':
+            return token_type::name_separator;
+        case ',':
+            return token_type::value_separator;
+
+        // literals
+        case 't':
+            return scan_literal("true", 4, token_type::literal_true);
+        case 'f':
+            return scan_literal("false", 5, token_type::literal_false);
+        case 'n':
+            return scan_literal("null", 4, token_type::literal_null);
+
+        // string
+        case '\"':
+            return scan_string();
+
+        // number
+        case '-':
+        case '0':
+        case '1':
+        case '2':
+        case '3':
+        case '4':
+        case '5':
+        case '6':
+        case '7':
+        case '8':
+        case '9':
+            return scan_number();
+
+        // end of input (the null byte is needed when parsing from
+        // string literals)
+        case '\0':
+        case std::char_traits<char>::eof():
+            return token_type::end_of_input;
+
+        // error
+        default:
+            error_message = "invalid literal";
+            return token_type::parse_error;
+    }
+}
+
+void json::parser::parse(const bool strict, json& result)
+{
+    // read first token
+    get_token();
+
+    parse_internal(true, result);
+    result.assert_invariant();
+
+    // in strict mode, input must be completely read
+    if (strict)
+    {
+        get_token();
+        expect(token_type::end_of_input);
+    }
+
+    // in case of an error, return discarded value
+    if (errored)
+    {
+        result = value_t::discarded;
+        return;
+    }
+
+    // set top-level value to null if it was discarded by the callback
+    // function
+    if (result.is_discarded())
+    {
+        result = nullptr;
+    }
+}
+
+void json::parser::parse_internal(bool keep, json& result)
+{
+    // never parse after a parse error was detected
+    assert(not errored);
+
+    // start with a discarded value
+    if (not result.is_discarded())
+    {
+        result.m_value.destroy(result.m_type);
+        result.m_type = value_t::discarded;
+    }
+
+    switch (last_token)
+    {
+        case token_type::begin_object:
+        {
+            if (keep)
+            {
+                if (callback)
+                {
+                    keep = callback(depth++, parse_event_t::object_start, result);
+                }
+
+                if (not callback or keep)
+                {
+                    // explicitly set result to object to cope with {}
+                    result.m_type = value_t::object;
+                    result.m_value = value_t::object;
+                }
+            }
+
+            // read next token
+            get_token();
+
+            // closing } -> we are done
+            if (last_token == token_type::end_object)
+            {
+                if (keep and callback and not callback(--depth, parse_event_t::object_end, result))
+                {
+                    result.m_value.destroy(result.m_type);
+                    result.m_type = value_t::discarded;
+                }
+                break;
+            }
+
+            // parse values
+            SmallString<128> key;
+            json value;
+            while (true)
+            {
+                // store key
+                if (not expect(token_type::value_string))
+                {
+                    return;
+                }
+                key = m_lexer.get_string();
+
+                bool keep_tag = false;
+                if (keep)
+                {
+                    if (callback)
+                    {
+                        json k(key);
+                        keep_tag = callback(depth, parse_event_t::key, k);
+                    }
+                    else
+                    {
+                        keep_tag = true;
+                    }
+                }
+
+                // parse separator (:)
+                get_token();
+                if (not expect(token_type::name_separator))
+                {
+                    return;
+                }
+
+                // parse and add value
+                get_token();
+                value.m_value.destroy(value.m_type);
+                value.m_type = value_t::discarded;
+                parse_internal(keep, value);
+
+                if (JSON_UNLIKELY(errored))
+                {
+                    return;
+                }
+
+                if (keep and keep_tag and not value.is_discarded())
+                {
+                    result.m_value.object->try_emplace(std::string_view(key.data(), key.size()), std::move(value));
+                }
+
+                // comma -> next value
+                get_token();
+                if (last_token == token_type::value_separator)
+                {
+                    get_token();
+                    continue;
+                }
+
+                // closing }
+                if (not expect(token_type::end_object))
+                {
+                    return;
+                }
+                break;
+            }
+
+            if (keep and callback and not callback(--depth, parse_event_t::object_end, result))
+            {
+                result.m_value.destroy(result.m_type);
+                result.m_type = value_t::discarded;
+            }
+            break;
+        }
+
+        case token_type::begin_array:
+        {
+            if (keep)
+            {
+                if (callback)
+                {
+                    keep = callback(depth++, parse_event_t::array_start, result);
+                }
+
+                if (not callback or keep)
+                {
+                    // explicitly set result to array to cope with []
+                    result.m_type = value_t::array;
+                    result.m_value = value_t::array;
+                }
+            }
+
+            // read next token
+            get_token();
+
+            // closing ] -> we are done
+            if (last_token == token_type::end_array)
+            {
+                if (callback and not callback(--depth, parse_event_t::array_end, result))
+                {
+                    result.m_value.destroy(result.m_type);
+                    result.m_type = value_t::discarded;
+                }
+                break;
+            }
+
+            // parse values
+            json value;
+            while (true)
+            {
+                // parse value
+                value.m_value.destroy(value.m_type);
+                value.m_type = value_t::discarded;
+                parse_internal(keep, value);
+
+                if (JSON_UNLIKELY(errored))
+                {
+                    return;
+                }
+
+                if (keep and not value.is_discarded())
+                {
+                    result.m_value.array->push_back(std::move(value));
+                }
+
+                // comma -> next value
+                get_token();
+                if (last_token == token_type::value_separator)
+                {
+                    get_token();
+                    continue;
+                }
+
+                // closing ]
+                if (not expect(token_type::end_array))
+                {
+                    return;
+                }
+                break;
+            }
+
+            if (keep and callback and not callback(--depth, parse_event_t::array_end, result))
+            {
+                result.m_value.destroy(result.m_type);
+                result.m_type = value_t::discarded;
+            }
+            break;
+        }
+
+        case token_type::literal_null:
+        {
+            result.m_type = value_t::null;
+            break;
+        }
+
+        case token_type::value_string:
+        {
+            result.m_type = value_t::string;
+            result.m_value = m_lexer.get_string();
+            break;
+        }
+
+        case token_type::literal_true:
+        {
+            result.m_type = value_t::boolean;
+            result.m_value = true;
+            break;
+        }
+
+        case token_type::literal_false:
+        {
+            result.m_type = value_t::boolean;
+            result.m_value = false;
+            break;
+        }
+
+        case token_type::value_unsigned:
+        {
+            result.m_type = value_t::number_unsigned;
+            result.m_value = m_lexer.get_number_unsigned();
+            break;
+        }
+
+        case token_type::value_integer:
+        {
+            result.m_type = value_t::number_integer;
+            result.m_value = m_lexer.get_number_integer();
+            break;
+        }
+
+        case token_type::value_float:
+        {
+            result.m_type = value_t::number_float;
+            result.m_value = m_lexer.get_number_float();
+
+            // throw in case of infinity or NAN
+            if (JSON_UNLIKELY(not std::isfinite(result.m_value.number_float)))
+            {
+                if (allow_exceptions)
+                {
+                    JSON_THROW(out_of_range::create(406,
+                        fmt::format("number overflow parsing '{}'", m_lexer.get_token_string())));
+                }
+                expect(token_type::uninitialized);
+            }
+            break;
+        }
+
+        case token_type::parse_error:
+        {
+            // using "uninitialized" to avoid "expected" message
+            if (not expect(token_type::uninitialized))
+            {
+                return;
+            }
+            break; // LCOV_EXCL_LINE
+        }
+
+        default:
+        {
+            // the last token was unexpected; we expected a value
+            if (not expect(token_type::literal_or_value))
+            {
+                return;
+            }
+            break; // LCOV_EXCL_LINE
+        }
+    }
+
+    if (keep and callback and not callback(depth, parse_event_t::value, result))
+    {
+        result.m_value.destroy(result.m_type);
+        result.m_type = value_t::discarded;
+    }
+}
+
+bool json::parser::accept_internal()
+{
+    switch (last_token)
+    {
+        case token_type::begin_object:
+        {
+            // read next token
+            get_token();
+
+            // closing } -> we are done
+            if (last_token == token_type::end_object)
+            {
+                return true;
+            }
+
+            // parse values
+            while (true)
+            {
+                // parse key
+                if (last_token != token_type::value_string)
+                {
+                    return false;
+                }
+
+                // parse separator (:)
+                get_token();
+                if (last_token != token_type::name_separator)
+                {
+                    return false;
+                }
+
+                // parse value
+                get_token();
+                if (not accept_internal())
+                {
+                    return false;
+                }
+
+                // comma -> next value
+                get_token();
+                if (last_token == token_type::value_separator)
+                {
+                    get_token();
+                    continue;
+                }
+
+                // closing }
+                return (last_token == token_type::end_object);
+            }
+        }
+
+        case token_type::begin_array:
+        {
+            // read next token
+            get_token();
+
+            // closing ] -> we are done
+            if (last_token == token_type::end_array)
+            {
+                return true;
+            }
+
+            // parse values
+            while (true)
+            {
+                // parse value
+                if (not accept_internal())
+                {
+                    return false;
+                }
+
+                // comma -> next value
+                get_token();
+                if (last_token == token_type::value_separator)
+                {
+                    get_token();
+                    continue;
+                }
+
+                // closing ]
+                return (last_token == token_type::end_array);
+            }
+        }
+
+        case token_type::value_float:
+        {
+            // reject infinity or NAN
+            return std::isfinite(m_lexer.get_number_float());
+        }
+
+        case token_type::literal_false:
+        case token_type::literal_null:
+        case token_type::literal_true:
+        case token_type::value_integer:
+        case token_type::value_string:
+        case token_type::value_unsigned:
+            return true;
+
+        default: // the last token was unexpected
+            return false;
+    }
+}
+
+void json::parser::throw_exception() const
+{
+    std::string error_msg = "syntax error - ";
+    if (last_token == token_type::parse_error)
+    {
+        error_msg += std::string(m_lexer.get_error_message()) + "; last read: '" +
+                     m_lexer.get_token_string() + "'";
+    }
+    else
+    {
+        error_msg += "unexpected " + std::string(lexer_t::token_type_name(last_token));
+    }
+
+    if (expected != token_type::uninitialized)
+    {
+        error_msg += "; expected " + std::string(lexer_t::token_type_name(expected));
+    }
+
+    JSON_THROW(parse_error::create(101, m_lexer.get_position(), error_msg));
+}
+
+json json::parse(std::string_view s,
+                        const parser_callback_t cb,
+                        const bool allow_exceptions)
+{
+    raw_mem_istream is(std::span<const char>(s.data(), s.size()));
+    return parse(is, cb, allow_exceptions);
+}
+
+json json::parse(std::span<const uint8_t> arr,
+                        const parser_callback_t cb,
+                        const bool allow_exceptions)
+{
+    raw_mem_istream is(arr);
+    return parse(is, cb, allow_exceptions);
+}
+
+json json::parse(raw_istream& i,
+                        const parser_callback_t cb,
+                        const bool allow_exceptions)
+{
+    json result;
+    parser(i, cb, allow_exceptions).parse(true, result);
+    return result;
+}
+
+bool json::accept(std::string_view s)
+{
+    raw_mem_istream is(std::span<const char>(s.data(), s.size()));
+    return parser(is).accept(true);
+}
+
+bool json::accept(std::span<const uint8_t> arr)
+{
+    raw_mem_istream is(arr);
+    return parser(is).accept(true);
+}
+
+bool json::accept(raw_istream& i)
+{
+    return parser(i).accept(true);
+}
+
+raw_istream& operator>>(raw_istream& i, json& j)
+{
+    json::parser(i).parse(false, j);
+    return i;
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/json_pointer.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/json/cpp/json_pointer.cpp
similarity index 100%
rename from third_party/allwpilib/wpiutil/src/main/native/cpp/json_pointer.cpp
rename to third_party/allwpilib/wpiutil/src/main/native/thirdparty/json/cpp/json_pointer.cpp
diff --git a/third_party/allwpilib/wpiutil/src/main/native/cpp/json_serializer.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/json/cpp/json_serializer.cpp
similarity index 100%
rename from third_party/allwpilib/wpiutil/src/main/native/cpp/json_serializer.cpp
rename to third_party/allwpilib/wpiutil/src/main/native/thirdparty/json/cpp/json_serializer.cpp
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/json/include/wpi/json.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/json/include/wpi/json.h
new file mode 100644
index 0000000..1c07deb
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/json/include/wpi/json.h
@@ -0,0 +1,8119 @@
+/*----------------------------------------------------------------------------*/
+/* Modifications Copyright (c) 2017-2019 FIRST. All Rights Reserved.          */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+/*
+    __ _____ _____ _____
+ __|  |   __|     |   | |  JSON for Modern C++
+|  |  |__   |  |  | | | |  version 3.1.2
+|_____|_____|_____|_|___|  https://github.com/nlohmann/json
+
+Licensed under the MIT License <http://opensource.org/licenses/MIT>.
+Copyright (c) 2013-2018 Niels Lohmann <http://nlohmann.me>.
+
+Permission is hereby  granted, free of charge, to any  person obtaining a copy
+of this software and associated  documentation files (the "Software"), to deal
+in the Software  without restriction, including without  limitation the rights
+to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
+copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
+IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
+FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
+AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
+LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+*/
+
+#ifndef WPIUTIL_JSON_H
+#define WPIUTIL_JSON_H
+
+#define NLOHMANN_JSON_VERSION_MAJOR 3
+#define NLOHMANN_JSON_VERSION_MINOR 1
+#define NLOHMANN_JSON_VERSION_PATCH 2
+
+
+#include <algorithm> // all_of, copy, find, for_each, generate_n, min, reverse, remove, fill, none_of, transform
+#include <array> // array
+#include <cassert> // assert
+#include <cstddef> // nullptr_t, ptrdiff_t, size_t
+#include <cstdint> // uint8_t, uint16_t, uint32_t, uint64_t
+#include <exception> // exception
+#include <functional> // function, hash, less
+#include <initializer_list> // initializer_list
+#include <iterator>
+#include <limits> // numeric_limits
+#include <memory> // allocator, shared_ptr, make_shared, addressof
+#include <span>
+#include <stdexcept> // runtime_error
+#include <string> // string, char_traits, stoi, to_string
+#include <string_view>
+#include <tuple> // tuple, get, make_tuple
+#include <type_traits>
+#include <utility>
+#include <vector> // vector
+
+#include "wpi/StringMap.h"
+
+namespace wpi
+{
+
+class raw_istream;
+class raw_ostream;
+
+class JsonTest;
+
+/*!
+@brief default JSONSerializer template argument
+
+This serializer ignores the template arguments and uses ADL
+([argument-dependent lookup](http://en.cppreference.com/w/cpp/language/adl))
+for serialization.
+*/
+template<typename = void, typename = void>
+struct adl_serializer;
+
+/*!
+@brief JSON Pointer
+
+A JSON pointer defines a string syntax for identifying a specific value
+within a JSON document. It can be used with functions `at` and
+`operator[]`. Furthermore, JSON pointers are the base for JSON patches.
+
+@sa [RFC 6901](https://tools.ietf.org/html/rfc6901)
+
+@since version 2.0.0
+*/
+class json_pointer;
+
+/*!
+@brief default JSON class
+
+This type is the default specialization of the @ref json class which
+uses the standard template types.
+
+@since version 1.0.0
+*/
+class json;
+}
+
+// exclude unsupported compilers
+#if defined(__clang__)
+    #if (__clang_major__ * 10000 + __clang_minor__ * 100 + __clang_patchlevel__) < 30400
+        #error "unsupported Clang version - see https://github.com/nlohmann/json#supported-compilers"
+    #endif
+#elif defined(__GNUC__) && !(defined(__ICC) || defined(__INTEL_COMPILER))
+    #if (__GNUC__ * 10000 + __GNUC_MINOR__ * 100 + __GNUC_PATCHLEVEL__) < 40900
+        #error "unsupported GCC version - see https://github.com/nlohmann/json#supported-compilers"
+    #endif
+#endif
+
+// disable float-equal warnings on GCC/clang
+#if defined(__clang__) || defined(__GNUC__) || defined(__GNUG__)
+    #pragma GCC diagnostic push
+    #pragma GCC diagnostic ignored "-Wfloat-equal"
+#endif
+
+// disable documentation warnings on clang
+#if defined(__clang__)
+    #pragma GCC diagnostic push
+    #pragma GCC diagnostic ignored "-Wdocumentation"
+#endif
+
+// allow to disable exceptions
+#if (defined(__cpp_exceptions) || defined(__EXCEPTIONS) || defined(_CPPUNWIND)) && !defined(JSON_NOEXCEPTION)
+    #define JSON_THROW(exception) throw exception
+    #define JSON_TRY try
+    #define JSON_CATCH(exception) catch(exception)
+#else
+    #define JSON_THROW(exception) std::abort()
+    #define JSON_TRY if(true)
+    #define JSON_CATCH(exception) if(false)
+#endif
+
+// override exception macros
+#if defined(JSON_THROW_USER)
+    #undef JSON_THROW
+    #define JSON_THROW JSON_THROW_USER
+#endif
+#if defined(JSON_TRY_USER)
+    #undef JSON_TRY
+    #define JSON_TRY JSON_TRY_USER
+#endif
+#if defined(JSON_CATCH_USER)
+    #undef JSON_CATCH
+    #define JSON_CATCH JSON_CATCH_USER
+#endif
+
+// manual branch prediction
+#if defined(__clang__) || defined(__GNUC__) || defined(__GNUG__)
+    #define JSON_LIKELY(x)      __builtin_expect(!!(x), 1)
+    #define JSON_UNLIKELY(x)    __builtin_expect(!!(x), 0)
+#else
+    #define JSON_LIKELY(x)      x
+    #define JSON_UNLIKELY(x)    x
+#endif
+
+/*!
+@brief Helper to determine whether there's a key_type for T.
+
+This helper is used to tell associative containers apart from other containers
+such as sequence containers. For instance, `std::map` passes the test as it
+contains a `mapped_type`, whereas `std::vector` fails the test.
+
+@sa http://stackoverflow.com/a/7728728/266378
+@since version 1.0.0, overworked in version 2.0.6
+*/
+#define NLOHMANN_JSON_HAS_HELPER(type)                                        \
+    template<typename T> struct has_##type {                                  \
+    private:                                                                  \
+        template<typename U, typename = typename U::type>                     \
+        static int detect(U &&);                                              \
+        static void detect(...);                                              \
+    public:                                                                   \
+        static constexpr bool value =                                         \
+                std::is_integral<decltype(detect(std::declval<T>()))>::value; \
+    }
+
+namespace wpi
+{
+/*!
+@brief detail namespace with internal helper functions
+
+This namespace collects functions that should not be exposed,
+implementations of some @ref json methods, and meta-programming helpers.
+
+@since version 2.1.0
+*/
+namespace detail
+{
+/////////////
+// helpers //
+/////////////
+
+template<typename> struct is_json : std::false_type {};
+
+template<> struct is_json<json> : std::true_type {};
+
+// alias templates to reduce boilerplate
+template<bool B, typename T = void>
+using enable_if_t = typename std::enable_if<B, T>::type;
+
+template<typename T>
+using uncvref_t = typename std::remove_cv<typename std::remove_reference<T>::type>::type;
+
+// dispatch utility (taken from ranges-v3)
+template<unsigned N> struct priority_tag : priority_tag < N - 1 > {};
+template<> struct priority_tag<0> {};
+
+////////////////////////
+// has_/is_ functions //
+////////////////////////
+
+// source: https://stackoverflow.com/a/37193089/4116453
+
+template <typename T, typename = void>
+struct is_complete_type : std::false_type {};
+
+template <typename T>
+struct is_complete_type<T, decltype(void(sizeof(T)))> : std::true_type {};
+
+NLOHMANN_JSON_HAS_HELPER(mapped_type);
+NLOHMANN_JSON_HAS_HELPER(key_type);
+NLOHMANN_JSON_HAS_HELPER(value_type);
+NLOHMANN_JSON_HAS_HELPER(iterator);
+
+template<bool B, class RealType, class CompatibleObjectType>
+struct is_compatible_object_type_impl : std::false_type {};
+
+template<class RealType, class CompatibleObjectType>
+struct is_compatible_object_type_impl<true, RealType, CompatibleObjectType>
+{
+    static constexpr auto value =
+        std::is_constructible<std::string_view, typename CompatibleObjectType::key_type>::value and
+        std::is_constructible<typename RealType::mapped_type, typename CompatibleObjectType::mapped_type>::value;
+};
+
+template<class BasicJsonType, class CompatibleObjectType>
+struct is_compatible_object_type
+{
+    static auto constexpr value = is_compatible_object_type_impl <
+                                  std::conjunction<std::negation<std::is_same<void, CompatibleObjectType>>,
+                                  has_mapped_type<CompatibleObjectType>,
+                                  has_key_type<CompatibleObjectType>>::value,
+                                  typename BasicJsonType::object_t, CompatibleObjectType >::value;
+};
+
+template<typename BasicJsonType, typename T>
+struct is_json_nested_type
+{
+    static auto constexpr value = std::is_same<T, typename BasicJsonType::iterator>::value or
+                                  std::is_same<T, typename BasicJsonType::const_iterator>::value or
+                                  std::is_same<T, typename BasicJsonType::reverse_iterator>::value or
+                                  std::is_same<T, typename BasicJsonType::const_reverse_iterator>::value;
+};
+
+template<class BasicJsonType, class CompatibleArrayType>
+struct is_compatible_array_type
+{
+    static auto constexpr value =
+        std::conjunction<std::negation<std::is_same<void, CompatibleArrayType>>,
+        std::negation<is_compatible_object_type<
+        BasicJsonType, CompatibleArrayType>>,
+        std::negation<std::is_constructible<std::string_view,
+        CompatibleArrayType>>,
+        std::negation<is_json_nested_type<BasicJsonType, CompatibleArrayType>>,
+        has_value_type<CompatibleArrayType>,
+        has_iterator<CompatibleArrayType>>::value;
+};
+
+template<bool, typename, typename>
+struct is_compatible_integer_type_impl : std::false_type {};
+
+template<typename RealIntegerType, typename CompatibleNumberIntegerType>
+struct is_compatible_integer_type_impl<true, RealIntegerType, CompatibleNumberIntegerType>
+{
+    // is there an assert somewhere on overflows?
+    using RealLimits = std::numeric_limits<RealIntegerType>;
+    using CompatibleLimits = std::numeric_limits<CompatibleNumberIntegerType>;
+
+    static constexpr auto value =
+        std::is_constructible<RealIntegerType, CompatibleNumberIntegerType>::value and
+        CompatibleLimits::is_integer and
+        RealLimits::is_signed == CompatibleLimits::is_signed;
+};
+
+template<typename RealIntegerType, typename CompatibleNumberIntegerType>
+struct is_compatible_integer_type
+{
+    static constexpr auto value =
+        is_compatible_integer_type_impl <
+        std::is_integral<CompatibleNumberIntegerType>::value and
+        not std::is_same<bool, CompatibleNumberIntegerType>::value,
+        RealIntegerType, CompatibleNumberIntegerType > ::value;
+};
+
+// trait checking if JSONSerializer<T>::from_json(json const&, udt&) exists
+template<typename BasicJsonType, typename T>
+struct has_from_json
+{
+  private:
+    // also check the return type of from_json
+    template<typename U, typename = enable_if_t<std::is_same<void, decltype(uncvref_t<U>::from_json(
+                 std::declval<BasicJsonType>(), std::declval<T&>()))>::value>>
+    static int detect(U&&);
+    static void detect(...);
+
+  public:
+    static constexpr bool value = std::is_integral<decltype(
+                                      detect(std::declval<typename BasicJsonType::template json_serializer<T, void>>()))>::value;
+};
+
+// This trait checks if JSONSerializer<T>::from_json(json const&) exists
+// this overload is used for non-default-constructible user-defined-types
+template<typename BasicJsonType, typename T>
+struct has_non_default_from_json
+{
+  private:
+    template <
+        typename U,
+        typename = enable_if_t<std::is_same<
+                                   T, decltype(uncvref_t<U>::from_json(std::declval<BasicJsonType>()))>::value >>
+    static int detect(U&&);
+    static void detect(...);
+
+  public:
+    static constexpr bool value = std::is_integral<decltype(detect(
+                                      std::declval<typename BasicJsonType::template json_serializer<T, void>>()))>::value;
+};
+
+// This trait checks if BasicJsonType::json_serializer<T>::to_json exists
+template<typename BasicJsonType, typename T>
+struct has_to_json
+{
+  private:
+    template<typename U, typename = decltype(uncvref_t<U>::to_json(
+                 std::declval<BasicJsonType&>(), std::declval<T>()))>
+    static int detect(U&&);
+    static void detect(...);
+
+  public:
+    static constexpr bool value = std::is_integral<decltype(detect(
+                                      std::declval<typename BasicJsonType::template json_serializer<T, void>>()))>::value;
+};
+
+template <typename BasicJsonType, typename CompatibleCompleteType>
+struct is_compatible_complete_type
+{
+    static constexpr bool value =
+        not std::is_base_of<std::istream, CompatibleCompleteType>::value and
+        not is_json<CompatibleCompleteType>::value and
+        not is_json_nested_type<BasicJsonType, CompatibleCompleteType>::value and
+        has_to_json<BasicJsonType, CompatibleCompleteType>::value;
+};
+
+template <typename BasicJsonType, typename CompatibleType>
+struct is_compatible_type
+    : std::conjunction<is_complete_type<CompatibleType>,
+      is_compatible_complete_type<BasicJsonType, CompatibleType>>
+{
+};
+
+// taken from ranges-v3
+template<typename T>
+struct static_const
+{
+    static constexpr T value{};
+};
+
+template<typename T>
+constexpr T static_const<T>::value;
+
+////////////////
+// exceptions //
+////////////////
+
+/*!
+@brief general exception of the @ref json class
+
+This class is an extension of `std::exception` objects with a member @a id for
+exception ids. It is used as the base class for all exceptions thrown by the
+@ref json class. This class can hence be used as "wildcard" to catch
+exceptions.
+
+Subclasses:
+- @ref parse_error for exceptions indicating a parse error
+- @ref invalid_iterator for exceptions indicating errors with iterators
+- @ref type_error for exceptions indicating executing a member function with
+                  a wrong type
+- @ref out_of_range for exceptions indicating access out of the defined range
+- @ref other_error for exceptions indicating other library errors
+
+@internal
+@note To have nothrow-copy-constructible exceptions, we internally use
+      `std::runtime_error` which can cope with arbitrary-length error messages.
+      Intermediate strings are built with static functions and then passed to
+      the actual constructor.
+@endinternal
+
+@liveexample{The following code shows how arbitrary library exceptions can be
+caught.,exception}
+
+@since version 3.0.0
+*/
+class exception : public std::exception
+{
+  public:
+    /// returns the explanatory string
+    const char* what() const noexcept override
+    {
+        return m.what();
+    }
+
+    /// the id of the exception
+    const int id;
+
+  protected:
+    exception(int id_, std::string_view what_arg);
+
+  private:
+    /// an exception object as storage for error messages
+    std::runtime_error m;
+};
+
+/*!
+@brief exception indicating a parse error
+
+This exception is thrown by the library when a parse error occurs. Parse errors
+can occur during the deserialization of JSON text, CBOR, MessagePack, as well
+as when using JSON Patch.
+
+Member @a byte holds the byte index of the last read character in the input
+file.
+
+Exceptions have ids 1xx.
+
+name / id                      | example message | description
+------------------------------ | --------------- | -------------------------
+json.exception.parse_error.101 | parse error at 2: unexpected end of input; expected string literal | This error indicates a syntax error while deserializing a JSON text. The error message describes that an unexpected token (character) was encountered, and the member @a byte indicates the error position.
+json.exception.parse_error.102 | parse error at 14: missing or wrong low surrogate | JSON uses the `\uxxxx` format to describe Unicode characters. Code points above above 0xFFFF are split into two `\uxxxx` entries ("surrogate pairs"). This error indicates that the surrogate pair is incomplete or contains an invalid code point.
+json.exception.parse_error.103 | parse error: code points above 0x10FFFF are invalid | Unicode supports code points up to 0x10FFFF. Code points above 0x10FFFF are invalid.
+json.exception.parse_error.104 | parse error: JSON patch must be an array of objects | [RFC 6902](https://tools.ietf.org/html/rfc6902) requires a JSON Patch document to be a JSON document that represents an array of objects.
+json.exception.parse_error.105 | parse error: operation must have string member 'op' | An operation of a JSON Patch document must contain exactly one "op" member, whose value indicates the operation to perform. Its value must be one of "add", "remove", "replace", "move", "copy", or "test"; other values are errors.
+json.exception.parse_error.106 | parse error: array index '01' must not begin with '0' | An array index in a JSON Pointer ([RFC 6901](https://tools.ietf.org/html/rfc6901)) may be `0` or any number without a leading `0`.
+json.exception.parse_error.107 | parse error: JSON pointer must be empty or begin with '/' - was: 'foo' | A JSON Pointer must be a Unicode string containing a sequence of zero or more reference tokens, each prefixed by a `/` character.
+json.exception.parse_error.108 | parse error: escape character '~' must be followed with '0' or '1' | In a JSON Pointer, only `~0` and `~1` are valid escape sequences.
+json.exception.parse_error.109 | parse error: array index 'one' is not a number | A JSON Pointer array index must be a number.
+json.exception.parse_error.110 | parse error at 1: cannot read 2 bytes from vector | When parsing CBOR or MessagePack, the byte vector ends before the complete value has been read.
+json.exception.parse_error.112 | parse error at 1: error reading CBOR; last byte: 0xF8 | Not all types of CBOR or MessagePack are supported. This exception occurs if an unsupported byte was read.
+json.exception.parse_error.113 | parse error at 2: expected a CBOR string; last byte: 0x98 | While parsing a map key, a value that is not a string has been read.
+
+@note For an input with n bytes, 1 is the index of the first character and n+1
+      is the index of the terminating null byte or the end of file. This also
+      holds true when reading a byte vector (CBOR or MessagePack).
+
+@liveexample{The following code shows how a `parse_error` exception can be
+caught.,parse_error}
+
+@sa @ref exception for the base class of the library exceptions
+@sa @ref invalid_iterator for exceptions indicating errors with iterators
+@sa @ref type_error for exceptions indicating executing a member function with
+                    a wrong type
+@sa @ref out_of_range for exceptions indicating access out of the defined range
+@sa @ref other_error for exceptions indicating other library errors
+
+@since version 3.0.0
+*/
+class parse_error : public exception
+{
+  public:
+    /*!
+    @brief create a parse error exception
+    @param[in] id_       the id of the exception
+    @param[in] byte_     the byte index where the error occurred (or 0 if the
+                         position cannot be determined)
+    @param[in] what_arg  the explanatory string
+    @return parse_error object
+    */
+    static parse_error create(int id_, std::size_t byte_, std::string_view what_arg);
+
+    /*!
+    @brief byte index of the parse error
+
+    The byte index of the last read character in the input file.
+
+    @note For an input with n bytes, 1 is the index of the first character and
+          n+1 is the index of the terminating null byte or the end of file.
+          This also holds true when reading a byte vector (CBOR or MessagePack).
+    */
+    const std::size_t byte;
+
+  private:
+    parse_error(int id_, std::size_t byte_, std::string_view what_arg)
+        : exception(id_, what_arg), byte(byte_) {}
+};
+
+/*!
+@brief exception indicating errors with iterators
+
+This exception is thrown if iterators passed to a library function do not match
+the expected semantics.
+
+Exceptions have ids 2xx.
+
+name / id                           | example message | description
+----------------------------------- | --------------- | -------------------------
+json.exception.invalid_iterator.201 | iterators are not compatible | The iterators passed to constructor @ref json(InputIT first, InputIT last) are not compatible, meaning they do not belong to the same container. Therefore, the range (@a first, @a last) is invalid.
+json.exception.invalid_iterator.202 | iterator does not fit current value | In an erase or insert function, the passed iterator @a pos does not belong to the JSON value for which the function was called. It hence does not define a valid position for the deletion/insertion.
+json.exception.invalid_iterator.203 | iterators do not fit current value | Either iterator passed to function @ref erase(IteratorType first, IteratorType last) does not belong to the JSON value from which values shall be erased. It hence does not define a valid range to delete values from.
+json.exception.invalid_iterator.204 | iterators out of range | When an iterator range for a primitive type (number, boolean, or string) is passed to a constructor or an erase function, this range has to be exactly (@ref begin(), @ref end()), because this is the only way the single stored value is expressed. All other ranges are invalid.
+json.exception.invalid_iterator.205 | iterator out of range | When an iterator for a primitive type (number, boolean, or string) is passed to an erase function, the iterator has to be the @ref begin() iterator, because it is the only way to address the stored value. All other iterators are invalid.
+json.exception.invalid_iterator.206 | cannot construct with iterators from null | The iterators passed to constructor @ref json(InputIT first, InputIT last) belong to a JSON null value and hence to not define a valid range.
+json.exception.invalid_iterator.207 | cannot use key() for non-object iterators | The key() member function can only be used on iterators belonging to a JSON object, because other types do not have a concept of a key.
+json.exception.invalid_iterator.208 | cannot use operator[] for object iterators | The operator[] to specify a concrete offset cannot be used on iterators belonging to a JSON object, because JSON objects are unordered.
+json.exception.invalid_iterator.209 | cannot use offsets with object iterators | The offset operators (+, -, +=, -=) cannot be used on iterators belonging to a JSON object, because JSON objects are unordered.
+json.exception.invalid_iterator.210 | iterators do not fit | The iterator range passed to the insert function are not compatible, meaning they do not belong to the same container. Therefore, the range (@a first, @a last) is invalid.
+json.exception.invalid_iterator.211 | passed iterators may not belong to container | The iterator range passed to the insert function must not be a subrange of the container to insert to.
+json.exception.invalid_iterator.212 | cannot compare iterators of different containers | When two iterators are compared, they must belong to the same container.
+json.exception.invalid_iterator.213 | cannot compare order of object iterators | The order of object iterators cannot be compared, because JSON objects are unordered.
+json.exception.invalid_iterator.214 | cannot get value | Cannot get value for iterator: Either the iterator belongs to a null value or it is an iterator to a primitive type (number, boolean, or string), but the iterator is different to @ref begin().
+
+@liveexample{The following code shows how an `invalid_iterator` exception can be
+caught.,invalid_iterator}
+
+@sa @ref exception for the base class of the library exceptions
+@sa @ref parse_error for exceptions indicating a parse error
+@sa @ref type_error for exceptions indicating executing a member function with
+                    a wrong type
+@sa @ref out_of_range for exceptions indicating access out of the defined range
+@sa @ref other_error for exceptions indicating other library errors
+
+@since version 3.0.0
+*/
+class invalid_iterator : public exception
+{
+  public:
+    static invalid_iterator create(int id_, std::string_view what_arg);
+    static invalid_iterator create(int id_, std::string_view what_arg, std::string_view type_info);
+
+  private:
+    invalid_iterator(int id_, std::string_view what_arg)
+        : exception(id_, what_arg) {}
+};
+
+/*!
+@brief exception indicating executing a member function with a wrong type
+
+This exception is thrown in case of a type error; that is, a library function is
+executed on a JSON value whose type does not match the expected semantics.
+
+Exceptions have ids 3xx.
+
+name / id                     | example message | description
+----------------------------- | --------------- | -------------------------
+json.exception.type_error.301 | cannot create object from initializer list | To create an object from an initializer list, the initializer list must consist only of a list of pairs whose first element is a string. When this constraint is violated, an array is created instead.
+json.exception.type_error.302 | type must be object, but is array | During implicit or explicit value conversion, the JSON type must be compatible to the target type. For instance, a JSON string can only be converted into string types, but not into numbers or boolean types.
+json.exception.type_error.303 | incompatible ReferenceType for get_ref, actual type is object | To retrieve a reference to a value stored in a @ref json object with @ref get_ref, the type of the reference must match the value type. For instance, for a JSON array, the @a ReferenceType must be @ref array_t&.
+json.exception.type_error.304 | cannot use at() with string | The @ref at() member functions can only be executed for certain JSON types.
+json.exception.type_error.305 | cannot use operator[] with string | The @ref operator[] member functions can only be executed for certain JSON types.
+json.exception.type_error.306 | cannot use value() with string | The @ref value() member functions can only be executed for certain JSON types.
+json.exception.type_error.307 | cannot use erase() with string | The @ref erase() member functions can only be executed for certain JSON types.
+json.exception.type_error.308 | cannot use push_back() with string | The @ref push_back() and @ref operator+= member functions can only be executed for certain JSON types.
+json.exception.type_error.309 | cannot use insert() with | The @ref insert() member functions can only be executed for certain JSON types.
+json.exception.type_error.310 | cannot use swap() with number | The @ref swap() member functions can only be executed for certain JSON types.
+json.exception.type_error.311 | cannot use emplace_back() with string | The @ref emplace_back() member function can only be executed for certain JSON types.
+json.exception.type_error.312 | cannot use update() with string | The @ref update() member functions can only be executed for certain JSON types.
+json.exception.type_error.313 | invalid value to unflatten | The @ref unflatten function converts an object whose keys are JSON Pointers back into an arbitrary nested JSON value. The JSON Pointers must not overlap, because then the resulting value would not be well defined.
+json.exception.type_error.314 | only objects can be unflattened | The @ref unflatten function only works for an object whose keys are JSON Pointers.
+json.exception.type_error.315 | values in object must be primitive | The @ref unflatten function only works for an object whose keys are JSON Pointers and whose values are primitive.
+json.exception.type_error.316 | invalid UTF-8 byte at index 10: 0x7E | The @ref dump function only works with UTF-8 encoded strings; that is, if you assign a `std::string` to a JSON value, make sure it is UTF-8 encoded. |
+
+@liveexample{The following code shows how a `type_error` exception can be
+caught.,type_error}
+
+@sa @ref exception for the base class of the library exceptions
+@sa @ref parse_error for exceptions indicating a parse error
+@sa @ref invalid_iterator for exceptions indicating errors with iterators
+@sa @ref out_of_range for exceptions indicating access out of the defined range
+@sa @ref other_error for exceptions indicating other library errors
+
+@since version 3.0.0
+*/
+class type_error : public exception
+{
+  public:
+    static type_error create(int id_, std::string_view what_arg);
+    static type_error create(int id_, std::string_view what_arg, std::string_view type_info);
+
+  private:
+    type_error(int id_, std::string_view what_arg) : exception(id_, what_arg) {}
+};
+
+/*!
+@brief exception indicating access out of the defined range
+
+This exception is thrown in case a library function is called on an input
+parameter that exceeds the expected range, for instance in case of array
+indices or nonexisting object keys.
+
+Exceptions have ids 4xx.
+
+name / id                       | example message | description
+------------------------------- | --------------- | -------------------------
+json.exception.out_of_range.401 | array index 3 is out of range | The provided array index @a i is larger than @a size-1.
+json.exception.out_of_range.402 | array index '-' (3) is out of range | The special array index `-` in a JSON Pointer never describes a valid element of the array, but the index past the end. That is, it can only be used to add elements at this position, but not to read it.
+json.exception.out_of_range.403 | key 'foo' not found | The provided key was not found in the JSON object.
+json.exception.out_of_range.404 | unresolved reference token 'foo' | A reference token in a JSON Pointer could not be resolved.
+json.exception.out_of_range.405 | JSON pointer has no parent | The JSON Patch operations 'remove' and 'add' can not be applied to the root element of the JSON value.
+json.exception.out_of_range.406 | number overflow parsing '10E1000' | A parsed number could not be stored as without changing it to NaN or INF.
+json.exception.out_of_range.407 | number overflow serializing '9223372036854775808' | UBJSON only supports integers numbers up to 9223372036854775807. |
+json.exception.out_of_range.408 | excessive array size: 8658170730974374167 | The size (following `#`) of an UBJSON array or object exceeds the maximal capacity. |
+
+@liveexample{The following code shows how an `out_of_range` exception can be
+caught.,out_of_range}
+
+@sa @ref exception for the base class of the library exceptions
+@sa @ref parse_error for exceptions indicating a parse error
+@sa @ref invalid_iterator for exceptions indicating errors with iterators
+@sa @ref type_error for exceptions indicating executing a member function with
+                    a wrong type
+@sa @ref other_error for exceptions indicating other library errors
+
+@since version 3.0.0
+*/
+class out_of_range : public exception
+{
+  public:
+    static out_of_range create(int id_, std::string_view what_arg);
+
+  private:
+    out_of_range(int id_, std::string_view what_arg) : exception(id_, what_arg) {}
+};
+
+/*!
+@brief exception indicating other library errors
+
+This exception is thrown in case of errors that cannot be classified with the
+other exception types.
+
+Exceptions have ids 5xx.
+
+name / id                      | example message | description
+------------------------------ | --------------- | -------------------------
+json.exception.other_error.501 | unsuccessful: {"op":"test","path":"/baz", "value":"bar"} | A JSON Patch operation 'test' failed. The unsuccessful operation is also printed.
+
+@sa @ref exception for the base class of the library exceptions
+@sa @ref parse_error for exceptions indicating a parse error
+@sa @ref invalid_iterator for exceptions indicating errors with iterators
+@sa @ref type_error for exceptions indicating executing a member function with
+                    a wrong type
+@sa @ref out_of_range for exceptions indicating access out of the defined range
+
+@liveexample{The following code shows how an `other_error` exception can be
+caught.,other_error}
+
+@since version 3.0.0
+*/
+class other_error : public exception
+{
+  public:
+    static other_error create(int id_, std::string_view what_arg);
+
+  private:
+    other_error(int id_, std::string_view what_arg) : exception(id_, what_arg) {}
+};
+
+///////////////////////////
+// JSON type enumeration //
+///////////////////////////
+
+/*!
+@brief the JSON type enumeration
+
+This enumeration collects the different JSON types. It is internally used to
+distinguish the stored values, and the functions @ref json::is_null(),
+@ref json::is_object(), @ref json::is_array(),
+@ref json::is_string(), @ref json::is_boolean(),
+@ref json::is_number() (with @ref json::is_number_integer(),
+@ref json::is_number_unsigned(), and @ref json::is_number_float()),
+@ref json::is_discarded(), @ref json::is_primitive(), and
+@ref json::is_structured() rely on it.
+
+@note There are three enumeration entries (number_integer, number_unsigned, and
+number_float), because the library distinguishes these three types for numbers:
+uint64_t is used for unsigned integers,
+int64_t is used for signed integers, and
+double is used for floating-point numbers or to
+approximate integers which do not fit in the limits of their respective type.
+
+@sa @ref json::json(const value_t value_type) -- create a JSON
+value with the default value for a given type
+
+@since version 1.0.0
+*/
+enum class value_t : std::uint8_t
+{
+    null,             ///< null value
+    object,           ///< object (unordered set of name/value pairs)
+    array,            ///< array (ordered collection of values)
+    string,           ///< string value
+    boolean,          ///< boolean value
+    number_integer,   ///< number value (signed integer)
+    number_unsigned,  ///< number value (unsigned integer)
+    number_float,     ///< number value (floating-point)
+    discarded         ///< discarded by the the parser callback function
+};
+
+/*!
+@brief comparison operator for JSON types
+
+Returns an ordering that is similar to Python:
+- order: null < boolean < number < object < array < string
+- furthermore, each type is not smaller than itself
+- discarded values are not comparable
+
+@since version 1.0.0
+*/
+inline bool operator<(const value_t lhs, const value_t rhs) noexcept
+{
+    static constexpr std::array<std::uint8_t, 8> order = {{
+            0 /* null */, 3 /* object */, 4 /* array */, 5 /* string */,
+            1 /* boolean */, 2 /* integer */, 2 /* unsigned */, 2 /* float */
+        }
+    };
+
+    const auto l_index = static_cast<std::size_t>(lhs);
+    const auto r_index = static_cast<std::size_t>(rhs);
+    return l_index < order.size() and r_index < order.size() and order[l_index] < order[r_index];
+}
+
+// overloads for json template parameters
+template<typename BasicJsonType, typename ArithmeticType,
+         enable_if_t<std::is_arithmetic<ArithmeticType>::value and
+                     not std::is_same<ArithmeticType, bool>::value,
+                     int> = 0>
+void get_arithmetic_value(const BasicJsonType& j, ArithmeticType& val)
+{
+    switch (static_cast<value_t>(j))
+    {
+        case value_t::number_unsigned:
+        {
+            val = static_cast<ArithmeticType>(*j.template get_ptr<const uint64_t*>());
+            break;
+        }
+        case value_t::number_integer:
+        {
+            val = static_cast<ArithmeticType>(*j.template get_ptr<const int64_t*>());
+            break;
+        }
+        case value_t::number_float:
+        {
+            val = static_cast<ArithmeticType>(*j.template get_ptr<const double*>());
+            break;
+        }
+
+        default:
+            JSON_THROW(type_error::create(302, "type must be number, but is", j.type_name()));
+    }
+}
+
+template<typename BasicJsonType>
+void from_json(const BasicJsonType& j, bool& b)
+{
+    if (JSON_UNLIKELY(not j.is_boolean()))
+    {
+        JSON_THROW(type_error::create(302, "type must be boolean, but is", j.type_name()));
+    }
+    b = *j.template get_ptr<const bool*>();
+}
+
+template<typename BasicJsonType>
+void from_json(const BasicJsonType& j, std::string& s)
+{
+    if (JSON_UNLIKELY(not j.is_string()))
+    {
+        JSON_THROW(type_error::create(302, "type must be string, but is", j.type_name()));
+    }
+    s = *j.template get_ptr<const std::string*>();
+}
+
+template<typename BasicJsonType>
+void from_json(const BasicJsonType& j, double& val)
+{
+    get_arithmetic_value(j, val);
+}
+
+template<typename BasicJsonType>
+void from_json(const BasicJsonType& j, uint64_t& val)
+{
+    get_arithmetic_value(j, val);
+}
+
+template<typename BasicJsonType>
+void from_json(const BasicJsonType& j, int64_t& val)
+{
+    get_arithmetic_value(j, val);
+}
+
+template<typename BasicJsonType, typename EnumType,
+         enable_if_t<std::is_enum<EnumType>::value, int> = 0>
+void from_json(const BasicJsonType& j, EnumType& e)
+{
+    typename std::underlying_type<EnumType>::type val;
+    get_arithmetic_value(j, val);
+    e = static_cast<EnumType>(val);
+}
+
+template<typename BasicJsonType>
+void from_json(const BasicJsonType& j, typename BasicJsonType::array_t& arr)
+{
+    if (JSON_UNLIKELY(not j.is_array()))
+    {
+        JSON_THROW(type_error::create(302, "type must be array, but is", j.type_name()));
+    }
+    arr = *j.template get_ptr<const typename BasicJsonType::array_t*>();
+}
+
+template<typename BasicJsonType, typename CompatibleArrayType>
+void from_json_array_impl(const BasicJsonType& j, CompatibleArrayType& arr, priority_tag<0> /*unused*/)
+{
+    using std::end;
+
+    std::transform(j.begin(), j.end(),
+                   std::inserter(arr, end(arr)), [](const BasicJsonType & i)
+    {
+        // get<BasicJsonType>() returns *this, this won't call a from_json
+        // method when value_type is BasicJsonType
+        return i.template get<typename CompatibleArrayType::value_type>();
+    });
+}
+
+template<typename BasicJsonType, typename CompatibleArrayType>
+auto from_json_array_impl(const BasicJsonType& j, CompatibleArrayType& arr, priority_tag<1> /*unused*/)
+-> decltype(
+    arr.reserve(std::declval<typename CompatibleArrayType::size_type>()),
+    void())
+{
+    using std::end;
+
+    arr.reserve(j.size());
+    std::transform(j.begin(), j.end(),
+                   std::inserter(arr, end(arr)), [](const BasicJsonType & i)
+    {
+        // get<BasicJsonType>() returns *this, this won't call a from_json
+        // method when value_type is BasicJsonType
+        return i.template get<typename CompatibleArrayType::value_type>();
+    });
+}
+
+template<typename BasicJsonType, typename T, std::size_t N>
+void from_json_array_impl(const BasicJsonType& j, std::array<T, N>& arr, priority_tag<2> /*unused*/)
+{
+    for (std::size_t i = 0; i < N; ++i)
+    {
+        arr[i] = j.at(i).template get<T>();
+    }
+}
+
+template <
+    typename BasicJsonType, typename CompatibleArrayType,
+    enable_if_t <
+        is_compatible_array_type<BasicJsonType, CompatibleArrayType>::value and
+        not std::is_same<typename BasicJsonType::array_t,
+                         CompatibleArrayType>::value and
+        std::is_constructible <
+            BasicJsonType, typename CompatibleArrayType::value_type >::value,
+        int > = 0 >
+void from_json(const BasicJsonType& j, CompatibleArrayType& arr)
+{
+    if (JSON_UNLIKELY(not j.is_array()))
+    {
+        JSON_THROW(type_error::create(302, "type must be array, but is", j.type_name()));
+    }
+
+    from_json_array_impl(j, arr, priority_tag<2> {});
+}
+
+template<typename BasicJsonType>
+inline
+void from_json(const BasicJsonType& j, typename BasicJsonType::object_t& obj)
+{
+    if (!j.is_object())
+    {
+        JSON_THROW(type_error::create(302, "type must be object, but is", j.type_name()));
+    }
+
+    auto inner_object = j.template get_ptr<const typename BasicJsonType::object_t*>();
+    for (const auto& i : *inner_object) {
+        obj.try_emplace(i.first(), i.second);
+    }
+}
+
+template<typename BasicJsonType, typename CompatibleObjectType,
+         enable_if_t<is_compatible_object_type<BasicJsonType, CompatibleObjectType>::value and
+                     not std::is_same<typename BasicJsonType::object_t, CompatibleObjectType>::value, int> = 0>
+void from_json(const BasicJsonType& j, CompatibleObjectType& obj)
+{
+    if (JSON_UNLIKELY(not j.is_object()))
+    {
+        JSON_THROW(type_error::create(302, "type must be object, but is", j.type_name()));
+    }
+
+    auto inner_object = j.template get_ptr<const typename BasicJsonType::object_t*>();
+    using std::begin;
+    using std::end;
+    using value_type = typename CompatibleObjectType::value_type;
+    std::vector<value_type> v;
+    v.reserve(j.size());
+    for (const auto& p : *inner_object)
+    {
+        v.emplace_back(
+            p.first(),
+            p.second
+            .template get<typename CompatibleObjectType::mapped_type>());
+    }
+    // we could avoid the assignment, but this might require a for loop, which
+    // might be less efficient than the container constructor for some
+    // containers (would it?)
+    obj = CompatibleObjectType(std::make_move_iterator(begin(v)),
+                               std::make_move_iterator(end(v)));
+}
+
+// overload for arithmetic types, not chosen for json template arguments
+// (BooleanType, etc..); note: Is it really necessary to provide explicit
+// overloads for bool etc. in case of a custom BooleanType which is not
+// an arithmetic type?
+template<typename BasicJsonType, typename ArithmeticType,
+         enable_if_t <
+             std::is_arithmetic<ArithmeticType>::value and
+             not std::is_same<ArithmeticType, uint64_t>::value and
+             not std::is_same<ArithmeticType, int64_t>::value and
+             not std::is_same<ArithmeticType, double>::value and
+             not std::is_same<ArithmeticType, bool>::value,
+             int> = 0>
+void from_json(const BasicJsonType& j, ArithmeticType& val)
+{
+    switch (static_cast<value_t>(j))
+    {
+        case value_t::number_unsigned:
+        {
+            val = static_cast<ArithmeticType>(*j.template get_ptr<const uint64_t*>());
+            break;
+        }
+        case value_t::number_integer:
+        {
+            val = static_cast<ArithmeticType>(*j.template get_ptr<const int64_t*>());
+            break;
+        }
+        case value_t::number_float:
+        {
+            val = static_cast<ArithmeticType>(*j.template get_ptr<const double*>());
+            break;
+        }
+        case value_t::boolean:
+        {
+            val = static_cast<ArithmeticType>(*j.template get_ptr<const bool*>());
+            break;
+        }
+
+        default:
+            JSON_THROW(type_error::create(302, "type must be number, but is", j.type_name()));
+    }
+}
+
+template<typename BasicJsonType, typename A1, typename A2>
+void from_json(const BasicJsonType& j, std::pair<A1, A2>& p)
+{
+    p = {j.at(0).template get<A1>(), j.at(1).template get<A2>()};
+}
+
+template<typename BasicJsonType, typename Tuple, std::size_t... Idx>
+void from_json_tuple_impl(const BasicJsonType& j, Tuple& t, std::index_sequence<Idx...>)
+{
+    t = std::make_tuple(j.at(Idx).template get<typename std::tuple_element<Idx, Tuple>::type>()...);
+}
+
+template<typename BasicJsonType, typename... Args>
+void from_json(const BasicJsonType& j, std::tuple<Args...>& t)
+{
+    from_json_tuple_impl(j, t, std::index_sequence_for<Args...> {});
+}
+
+struct from_json_fn
+{
+  private:
+    template<typename BasicJsonType, typename T>
+    auto call(const BasicJsonType& j, T& val, priority_tag<1> /*unused*/) const
+    noexcept(noexcept(from_json(j, val)))
+    -> decltype(from_json(j, val), void())
+    {
+        return from_json(j, val);
+    }
+
+    template<typename BasicJsonType, typename T>
+    void call(const BasicJsonType& /*unused*/, T& /*unused*/, priority_tag<0> /*unused*/) const noexcept
+    {
+        static_assert(sizeof(BasicJsonType) == 0,
+                      "could not find from_json() method in T's namespace");
+#ifdef _MSC_VER
+        // MSVC does not show a stacktrace for the above assert
+        using decayed = uncvref_t<T>;
+        static_assert(sizeof(typename decayed::force_msvc_stacktrace) == 0,
+                      "forcing MSVC stacktrace to show which T we're talking about.");
+#endif
+    }
+
+  public:
+    template<typename BasicJsonType, typename T>
+    void operator()(const BasicJsonType& j, T& val) const
+    noexcept(noexcept(std::declval<from_json_fn>().call(j, val, priority_tag<1> {})))
+    {
+        return call(j, val, priority_tag<1> {});
+    }
+};
+}
+
+// namespace to hold default `from_json` function
+// to see why this is required:
+// http://www.open-std.org/jtc1/sc22/wg21/docs/papers/2015/n4381.html
+namespace
+{
+constexpr const auto& from_json = detail::static_const<detail::from_json_fn>::value;
+}
+
+namespace detail
+{
+//////////////////
+// constructors //
+//////////////////
+
+template<value_t> struct external_constructor;
+
+template<>
+struct external_constructor<value_t::boolean>
+{
+    template<typename BasicJsonType>
+    static void construct(BasicJsonType& j, bool b) noexcept
+    {
+        j.m_type = value_t::boolean;
+        j.m_value = b;
+        j.assert_invariant();
+    }
+};
+
+template<>
+struct external_constructor<value_t::string>
+{
+    template<typename BasicJsonType>
+    static void construct(BasicJsonType& j, std::string_view s)
+    {
+        j.m_type = value_t::string;
+        j.m_value = s;
+        j.assert_invariant();
+    }
+
+    template<typename BasicJsonType, typename T,
+             enable_if_t<std::is_same<std::string, T>::value, int> = 0>
+    static void construct(BasicJsonType& j, T&& s)
+    {
+        j.m_type = value_t::string;
+        j.m_value = std::move(s);
+        j.assert_invariant();
+    }
+};
+
+template<>
+struct external_constructor<value_t::number_float>
+{
+    template<typename BasicJsonType>
+    static void construct(BasicJsonType& j, double val) noexcept
+    {
+        j.m_type = value_t::number_float;
+        j.m_value = val;
+        j.assert_invariant();
+    }
+};
+
+template<>
+struct external_constructor<value_t::number_unsigned>
+{
+    template<typename BasicJsonType>
+    static void construct(BasicJsonType& j, uint64_t val) noexcept
+    {
+        j.m_type = value_t::number_unsigned;
+        j.m_value = val;
+        j.assert_invariant();
+    }
+};
+
+template<>
+struct external_constructor<value_t::number_integer>
+{
+    template<typename BasicJsonType>
+    static void construct(BasicJsonType& j, int64_t val) noexcept
+    {
+        j.m_type = value_t::number_integer;
+        j.m_value = val;
+        j.assert_invariant();
+    }
+};
+
+template<>
+struct external_constructor<value_t::array>
+{
+    template<typename BasicJsonType>
+    static void construct(BasicJsonType& j, const typename BasicJsonType::array_t& arr)
+    {
+        j.m_type = value_t::array;
+        j.m_value = arr;
+        j.assert_invariant();
+    }
+
+    template<typename BasicJsonType>
+    static void construct(BasicJsonType& j, typename BasicJsonType::array_t&& arr)
+    {
+        j.m_type = value_t::array;
+        j.m_value = std::move(arr);
+        j.assert_invariant();
+    }
+
+    template<typename BasicJsonType, typename T>
+    static void construct(BasicJsonType& j, std::span<T> arr)
+    {
+        using std::begin;
+        using std::end;
+        j.m_type = value_t::array;
+        j.m_value.array = j.template create<typename BasicJsonType::array_t>(begin(arr), end(arr));
+        j.assert_invariant();
+    }
+
+    template<typename BasicJsonType, typename CompatibleArrayType,
+             enable_if_t<not std::is_same<CompatibleArrayType, typename BasicJsonType::array_t>::value,
+                         int> = 0>
+    static void construct(BasicJsonType& j, const CompatibleArrayType& arr)
+    {
+        using std::begin;
+        using std::end;
+        j.m_type = value_t::array;
+        j.m_value.array = j.template create<typename BasicJsonType::array_t>(begin(arr), end(arr));
+        j.assert_invariant();
+    }
+
+    template<typename BasicJsonType>
+    static void construct(BasicJsonType& j, const std::vector<bool>& arr)
+    {
+        j.m_type = value_t::array;
+        j.m_value = value_t::array;
+        j.m_value.array->reserve(arr.size());
+        for (const bool x : arr)
+        {
+            j.m_value.array->push_back(x);
+        }
+        j.assert_invariant();
+    }
+};
+
+template<>
+struct external_constructor<value_t::object>
+{
+    template<typename BasicJsonType>
+    static void construct(BasicJsonType& j, const typename BasicJsonType::object_t& obj)
+    {
+        j.m_type = value_t::object;
+        j.m_value = obj;
+        j.assert_invariant();
+    }
+
+    template<typename BasicJsonType>
+    static void construct(BasicJsonType& j, typename BasicJsonType::object_t&& obj)
+    {
+        j.m_type = value_t::object;
+        j.m_value = std::move(obj);
+        j.assert_invariant();
+    }
+
+    template<typename BasicJsonType, typename CompatibleObjectType,
+             enable_if_t<not std::is_same<CompatibleObjectType, typename BasicJsonType::object_t>::value, int> = 0>
+    static void construct(BasicJsonType& j, const CompatibleObjectType& obj)
+    {
+        j.m_type = value_t::object;
+        j.m_value = value_t::object;
+        for (const auto& x : obj)
+        {
+            j.m_value.object->try_emplace(x.first, x.second);
+        }
+        j.assert_invariant();
+    }
+};
+
+/////////////
+// to_json //
+/////////////
+
+template<typename BasicJsonType, typename T,
+         enable_if_t<std::is_same<T, bool>::value, int> = 0>
+void to_json(BasicJsonType& j, T b) noexcept
+{
+    external_constructor<value_t::boolean>::construct(j, b);
+}
+
+template<typename BasicJsonType, typename CompatibleString,
+         enable_if_t<std::is_constructible<std::string_view, CompatibleString>::value, int> = 0>
+void to_json(BasicJsonType& j, const CompatibleString& s)
+{
+    external_constructor<value_t::string>::construct(j, s);
+}
+
+template<typename BasicJsonType, typename T,
+         enable_if_t<std::is_same<std::string, T>::value, int> = 0>
+void to_json(BasicJsonType& j, T&& s)
+{
+    external_constructor<value_t::string>::construct(j, std::move(s));
+}
+
+template<typename BasicJsonType, typename FloatType,
+         enable_if_t<std::is_floating_point<FloatType>::value, int> = 0>
+void to_json(BasicJsonType& j, FloatType val) noexcept
+{
+    external_constructor<value_t::number_float>::construct(j, static_cast<double>(val));
+}
+
+template<typename BasicJsonType, typename CompatibleNumberUnsignedType,
+         enable_if_t<is_compatible_integer_type<uint64_t, CompatibleNumberUnsignedType>::value, int> = 0>
+void to_json(BasicJsonType& j, CompatibleNumberUnsignedType val) noexcept
+{
+    external_constructor<value_t::number_unsigned>::construct(j, static_cast<uint64_t>(val));
+}
+
+template<typename BasicJsonType, typename CompatibleNumberIntegerType,
+         enable_if_t<is_compatible_integer_type<int64_t, CompatibleNumberIntegerType>::value, int> = 0>
+void to_json(BasicJsonType& j, CompatibleNumberIntegerType val) noexcept
+{
+    external_constructor<value_t::number_integer>::construct(j, static_cast<int64_t>(val));
+}
+
+template<typename BasicJsonType, typename EnumType,
+         enable_if_t<std::is_enum<EnumType>::value, int> = 0>
+void to_json(BasicJsonType& j, EnumType e) noexcept
+{
+    using underlying_type = typename std::underlying_type<EnumType>::type;
+    external_constructor<value_t::number_integer>::construct(j, static_cast<underlying_type>(e));
+}
+
+template<typename BasicJsonType>
+void to_json(BasicJsonType& j, const std::vector<bool>& e)
+{
+    external_constructor<value_t::array>::construct(j, e);
+}
+
+template<typename BasicJsonType, typename CompatibleArrayType,
+         enable_if_t<is_compatible_array_type<BasicJsonType, CompatibleArrayType>::value or
+                     std::is_same<typename BasicJsonType::array_t, CompatibleArrayType>::value,
+                     int> = 0>
+void to_json(BasicJsonType& j, const CompatibleArrayType& arr)
+{
+    external_constructor<value_t::array>::construct(j, arr);
+}
+
+template<typename BasicJsonType>
+void to_json(BasicJsonType& j, typename BasicJsonType::array_t&& arr)
+{
+    external_constructor<value_t::array>::construct(j, std::move(arr));
+}
+
+template<typename BasicJsonType, typename CompatibleObjectType,
+         enable_if_t<is_compatible_object_type<BasicJsonType, CompatibleObjectType>::value, int> = 0>
+void to_json(BasicJsonType& j, const CompatibleObjectType& obj)
+{
+    external_constructor<value_t::object>::construct(j, obj);
+}
+
+template<typename BasicJsonType>
+void to_json(BasicJsonType& j, typename BasicJsonType::object_t&& obj)
+{
+    external_constructor<value_t::object>::construct(j, std::move(obj));
+}
+
+template<typename BasicJsonType, typename T, std::size_t N,
+         enable_if_t<not std::is_constructible<std::string_view, T (&)[N]>::value, int> = 0>
+void to_json(BasicJsonType& j, T (&arr)[N])
+{
+    external_constructor<value_t::array>::construct(j, arr);
+}
+
+template<typename BasicJsonType, typename... Args>
+void to_json(BasicJsonType& j, const std::pair<Args...>& p)
+{
+    j = {p.first, p.second};
+}
+
+template<typename BasicJsonType, typename Tuple, std::size_t... Idx>
+void to_json_tuple_impl(BasicJsonType& j, const Tuple& t, std::index_sequence<Idx...>)
+{
+    j = {std::get<Idx>(t)...};
+}
+
+template<typename BasicJsonType, typename... Args>
+void to_json(BasicJsonType& j, const std::tuple<Args...>& t)
+{
+    to_json_tuple_impl(j, t, std::index_sequence_for<Args...> {});
+}
+
+struct to_json_fn
+{
+  private:
+    template<typename BasicJsonType, typename T>
+    auto call(BasicJsonType& j, T&& val, priority_tag<1> /*unused*/) const noexcept(noexcept(to_json(j, std::forward<T>(val))))
+    -> decltype(to_json(j, std::forward<T>(val)), void())
+    {
+        return to_json(j, std::forward<T>(val));
+    }
+
+    template<typename BasicJsonType, typename T>
+    void call(BasicJsonType& /*unused*/, T&& /*unused*/, priority_tag<0> /*unused*/) const noexcept
+    {
+        static_assert(sizeof(BasicJsonType) == 0,
+                      "could not find to_json() method in T's namespace");
+
+#ifdef _MSC_VER
+        // MSVC does not show a stacktrace for the above assert
+        using decayed = uncvref_t<T>;
+        static_assert(sizeof(typename decayed::force_msvc_stacktrace) == 0,
+                      "forcing MSVC stacktrace to show which T we're talking about.");
+#endif
+    }
+
+  public:
+    template<typename BasicJsonType, typename T>
+    void operator()(BasicJsonType& j, T&& val) const
+    noexcept(noexcept(std::declval<to_json_fn>().call(j, std::forward<T>(val), priority_tag<1> {})))
+    {
+        return call(j, std::forward<T>(val), priority_tag<1> {});
+    }
+};
+}
+
+// namespace to hold default `to_json` function
+namespace
+{
+constexpr const auto& to_json = detail::static_const<detail::to_json_fn>::value;
+}
+
+namespace detail
+{
+/*
+@brief an iterator for primitive JSON types
+
+This class models an iterator for primitive JSON types (boolean, number,
+string). It's only purpose is to allow the iterator/const_iterator classes
+to "iterate" over primitive values. Internally, the iterator is modeled by
+a `difference_type` variable. Value begin_value (`0`) models the begin,
+end_value (`1`) models past the end.
+*/
+class primitive_iterator_t
+{
+  private:
+    using difference_type = std::ptrdiff_t;
+    static constexpr difference_type begin_value = 0;
+    static constexpr difference_type end_value = begin_value + 1;
+
+    /// iterator as signed integer type
+    difference_type m_it = (std::numeric_limits<std::ptrdiff_t>::min)();
+
+  public:
+    constexpr difference_type get_value() const noexcept
+    {
+        return m_it;
+    }
+
+    /// set iterator to a defined beginning
+    void set_begin() noexcept
+    {
+        m_it = begin_value;
+    }
+
+    /// set iterator to a defined past the end
+    void set_end() noexcept
+    {
+        m_it = end_value;
+    }
+
+    /// return whether the iterator can be dereferenced
+    constexpr bool is_begin() const noexcept
+    {
+        return m_it == begin_value;
+    }
+
+    /// return whether the iterator is at end
+    constexpr bool is_end() const noexcept
+    {
+        return m_it == end_value;
+    }
+
+    friend constexpr bool operator==(primitive_iterator_t lhs, primitive_iterator_t rhs) noexcept
+    {
+        return lhs.m_it == rhs.m_it;
+    }
+
+    friend constexpr bool operator<(primitive_iterator_t lhs, primitive_iterator_t rhs) noexcept
+    {
+        return lhs.m_it < rhs.m_it;
+    }
+
+    primitive_iterator_t operator+(difference_type n) noexcept
+    {
+        auto result = *this;
+        result += n;
+        return result;
+    }
+
+    friend constexpr difference_type operator-(primitive_iterator_t lhs, primitive_iterator_t rhs) noexcept
+    {
+        return lhs.m_it - rhs.m_it;
+    }
+
+    primitive_iterator_t& operator++() noexcept
+    {
+        ++m_it;
+        return *this;
+    }
+
+    primitive_iterator_t const operator++(int) noexcept
+    {
+        auto result = *this;
+        m_it++;
+        return result;
+    }
+
+    primitive_iterator_t& operator--() noexcept
+    {
+        --m_it;
+        return *this;
+    }
+
+    primitive_iterator_t const operator--(int) noexcept
+    {
+        auto result = *this;
+        m_it--;
+        return result;
+    }
+
+    primitive_iterator_t& operator+=(difference_type n) noexcept
+    {
+        m_it += n;
+        return *this;
+    }
+
+    primitive_iterator_t& operator-=(difference_type n) noexcept
+    {
+        m_it -= n;
+        return *this;
+    }
+};
+
+/*!
+@brief an iterator value
+
+@note This structure could easily be a union, but MSVC currently does not allow
+unions members with complex constructors, see https://github.com/nlohmann/json/pull/105.
+*/
+template<typename BasicJsonType> struct internal_iterator
+{
+    /// iterator for JSON objects
+    typename BasicJsonType::object_t::iterator object_iterator {};
+    /// iterator for JSON arrays
+    typename BasicJsonType::array_t::iterator array_iterator {};
+    /// generic iterator for all other types
+    primitive_iterator_t primitive_iterator {};
+};
+
+// forward declare, to be able to friend it later on
+template<typename IteratorType> class iteration_proxy;
+
+/*!
+@brief a template for a bidirectional iterator for the @ref json class
+
+This class implements a both iterators (iterator and const_iterator) for the
+@ref json class.
+
+@note An iterator is called *initialized* when a pointer to a JSON value has
+      been set (e.g., by a constructor or a copy assignment). If the iterator is
+      default-constructed, it is *uninitialized* and most methods are undefined.
+      **The library uses assertions to detect calls on uninitialized iterators.**
+
+@requirement The class satisfies the following concept requirements:
+-
+[BidirectionalIterator](http://en.cppreference.com/w/cpp/concept/BidirectionalIterator):
+  The iterator that can be moved can be moved in both directions (i.e.
+  incremented and decremented).
+
+@since version 1.0.0, simplified in version 2.0.9, change to bidirectional
+       iterators in version 3.0.0 (see https://github.com/nlohmann/json/issues/593)
+*/
+template<typename BasicJsonType>
+class iter_impl
+{
+    /// allow json to access private members
+    friend iter_impl<typename std::conditional<std::is_const<BasicJsonType>::value, typename std::remove_const<BasicJsonType>::type, const BasicJsonType>::type>;
+    friend BasicJsonType;
+    friend iteration_proxy<iter_impl>;
+    friend class ::wpi::JsonTest;
+
+    using object_t = typename BasicJsonType::object_t;
+    using array_t = typename BasicJsonType::array_t;
+    // make sure BasicJsonType is json or const json
+    static_assert(is_json<typename std::remove_const<BasicJsonType>::type>::value,
+                  "iter_impl only accepts (const) json");
+
+  public:
+
+    /// The std::iterator class template (used as a base class to provide typedefs) is deprecated in C++17.
+    /// The C++ Standard has never required user-defined iterators to derive from std::iterator.
+    /// A user-defined iterator should provide publicly accessible typedefs named
+    /// iterator_category, value_type, difference_type, pointer, and reference.
+    /// Note that value_type is required to be non-const, even for constant iterators.
+    using iterator_category = std::bidirectional_iterator_tag;
+
+    /// the type of the values when the iterator is dereferenced
+    using value_type = typename BasicJsonType::value_type;
+    /// a type to represent differences between iterators
+    using difference_type = typename BasicJsonType::difference_type;
+    /// defines a pointer to the type iterated over (value_type)
+    using pointer = typename std::conditional<std::is_const<BasicJsonType>::value,
+          typename BasicJsonType::const_pointer,
+          typename BasicJsonType::pointer>::type;
+    /// defines a reference to the type iterated over (value_type)
+    using reference =
+        typename std::conditional<std::is_const<BasicJsonType>::value,
+        typename BasicJsonType::const_reference,
+        typename BasicJsonType::reference>::type;
+
+    /// default constructor
+    iter_impl() = default;
+
+    /*!
+    @brief constructor for a given JSON instance
+    @param[in] object  pointer to a JSON object for this iterator
+    @pre object != nullptr
+    @post The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    explicit iter_impl(pointer object) noexcept : m_object(object)
+    {
+        assert(m_object != nullptr);
+
+        switch (m_object->m_type)
+        {
+            case value_t::object:
+            {
+                m_it.object_iterator = typename object_t::iterator();
+                break;
+            }
+
+            case value_t::array:
+            {
+                m_it.array_iterator = typename array_t::iterator();
+                break;
+            }
+
+            default:
+            {
+                m_it.primitive_iterator = primitive_iterator_t();
+                break;
+            }
+        }
+    }
+
+    /*!
+    @note The conventional copy constructor and copy assignment are implicitly
+          defined. Combined with the following converting constructor and
+          assignment, they support: (1) copy from iterator to iterator, (2)
+          copy from const iterator to const iterator, and (3) conversion from
+          iterator to const iterator. However conversion from const iterator
+          to iterator is not defined.
+    */
+
+    /*!
+    @brief converting constructor
+    @param[in] other  non-const iterator to copy from
+    @note It is not checked whether @a other is initialized.
+    */
+    iter_impl(const iter_impl<typename std::remove_const<BasicJsonType>::type>& other) noexcept
+        : m_object(other.m_object), m_it(other.m_it) {}
+
+    /*!
+    @brief converting assignment
+    @param[in,out] other  non-const iterator to copy from
+    @return const/non-const iterator
+    @note It is not checked whether @a other is initialized.
+    */
+    iter_impl& operator=(const iter_impl<typename std::remove_const<BasicJsonType>::type>& other) noexcept
+    {
+        m_object = other.m_object;
+        m_it = other.m_it;
+        return *this;
+    }
+
+  private:
+    /*!
+    @brief set the iterator to the first value
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    void set_begin() noexcept
+    {
+        assert(m_object != nullptr);
+
+        switch (m_object->m_type)
+        {
+            case value_t::object:
+            {
+                m_it.object_iterator = m_object->m_value.object->begin();
+                break;
+            }
+
+            case value_t::array:
+            {
+                m_it.array_iterator = m_object->m_value.array->begin();
+                break;
+            }
+
+            case value_t::null:
+            {
+                // set to end so begin()==end() is true: null is empty
+                m_it.primitive_iterator.set_end();
+                break;
+            }
+
+            default:
+            {
+                m_it.primitive_iterator.set_begin();
+                break;
+            }
+        }
+    }
+
+    /*!
+    @brief set the iterator past the last value
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    void set_end() noexcept
+    {
+        assert(m_object != nullptr);
+
+        switch (m_object->m_type)
+        {
+            case value_t::object:
+            {
+                m_it.object_iterator = m_object->m_value.object->end();
+                break;
+            }
+
+            case value_t::array:
+            {
+                m_it.array_iterator = m_object->m_value.array->end();
+                break;
+            }
+
+            default:
+            {
+                m_it.primitive_iterator.set_end();
+                break;
+            }
+        }
+    }
+
+  public:
+    /*!
+    @brief return a reference to the value pointed to by the iterator
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    reference operator*() const
+    {
+        assert(m_object != nullptr);
+
+        switch (m_object->m_type)
+        {
+            case value_t::object:
+            {
+                assert(m_it.object_iterator != m_object->m_value.object->end());
+                return m_it.object_iterator->second;
+            }
+
+            case value_t::array:
+            {
+                assert(m_it.array_iterator != m_object->m_value.array->end());
+                return *m_it.array_iterator;
+            }
+
+            case value_t::null:
+                JSON_THROW(invalid_iterator::create(214, "cannot get value"));
+
+            default:
+            {
+                if (JSON_LIKELY(m_it.primitive_iterator.is_begin()))
+                {
+                    return *m_object;
+                }
+
+                JSON_THROW(invalid_iterator::create(214, "cannot get value"));
+            }
+        }
+    }
+
+    /*!
+    @brief dereference the iterator
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    pointer operator->() const
+    {
+        assert(m_object != nullptr);
+
+        switch (m_object->m_type)
+        {
+            case value_t::object:
+            {
+                assert(m_it.object_iterator != m_object->m_value.object->end());
+                return &(m_it.object_iterator->second);
+            }
+
+            case value_t::array:
+            {
+                assert(m_it.array_iterator != m_object->m_value.array->end());
+                return &*m_it.array_iterator;
+            }
+
+            default:
+            {
+                if (JSON_LIKELY(m_it.primitive_iterator.is_begin()))
+                {
+                    return m_object;
+                }
+
+                JSON_THROW(invalid_iterator::create(214, "cannot get value"));
+            }
+        }
+    }
+
+    /*!
+    @brief post-increment (it++)
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    iter_impl const operator++(int)
+    {
+        auto result = *this;
+        ++(*this);
+        return result;
+    }
+
+    /*!
+    @brief pre-increment (++it)
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    iter_impl& operator++()
+    {
+        assert(m_object != nullptr);
+
+        switch (m_object->m_type)
+        {
+            case value_t::object:
+            {
+                ++m_it.object_iterator;
+                break;
+            }
+
+            case value_t::array:
+            {
+                std::advance(m_it.array_iterator, 1);
+                break;
+            }
+
+            default:
+            {
+                ++m_it.primitive_iterator;
+                break;
+            }
+        }
+
+        return *this;
+    }
+
+    /*!
+    @brief post-decrement (it--)
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    iter_impl const operator--(int)
+    {
+        auto result = *this;
+        --(*this);
+        return result;
+    }
+
+    /*!
+    @brief pre-decrement (--it)
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    iter_impl& operator--()
+    {
+        assert(m_object != nullptr);
+
+        switch (m_object->m_type)
+        {
+            case value_t::object:
+            {
+                --m_it.object_iterator;
+                break;
+            }
+
+            case value_t::array:
+            {
+                std::advance(m_it.array_iterator, -1);
+                break;
+            }
+
+            default:
+            {
+                --m_it.primitive_iterator;
+                break;
+            }
+        }
+
+        return *this;
+    }
+
+    /*!
+    @brief  comparison: equal
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    bool operator==(const iter_impl& other) const
+    {
+        // if objects are not the same, the comparison is undefined
+        if (JSON_UNLIKELY(m_object != other.m_object))
+        {
+            JSON_THROW(invalid_iterator::create(212, "cannot compare iterators of different containers"));
+        }
+
+        assert(m_object != nullptr);
+
+        switch (m_object->m_type)
+        {
+            case value_t::object:
+                return (m_it.object_iterator == other.m_it.object_iterator);
+
+            case value_t::array:
+                return (m_it.array_iterator == other.m_it.array_iterator);
+
+            default:
+                return (m_it.primitive_iterator == other.m_it.primitive_iterator);
+        }
+    }
+
+    /*!
+    @brief  comparison: not equal
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    bool operator!=(const iter_impl& other) const
+    {
+        return not operator==(other);
+    }
+
+    /*!
+    @brief  comparison: smaller
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    bool operator<(const iter_impl& other) const
+    {
+        // if objects are not the same, the comparison is undefined
+        if (JSON_UNLIKELY(m_object != other.m_object))
+        {
+            JSON_THROW(invalid_iterator::create(212, "cannot compare iterators of different containers"));
+        }
+
+        assert(m_object != nullptr);
+
+        switch (m_object->m_type)
+        {
+            case value_t::object:
+                JSON_THROW(invalid_iterator::create(213, "cannot compare order of object iterators"));
+
+            case value_t::array:
+                return (m_it.array_iterator < other.m_it.array_iterator);
+
+            default:
+                return (m_it.primitive_iterator < other.m_it.primitive_iterator);
+        }
+    }
+
+    /*!
+    @brief  comparison: less than or equal
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    bool operator<=(const iter_impl& other) const
+    {
+        return not other.operator < (*this);
+    }
+
+    /*!
+    @brief  comparison: greater than
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    bool operator>(const iter_impl& other) const
+    {
+        return not operator<=(other);
+    }
+
+    /*!
+    @brief  comparison: greater than or equal
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    bool operator>=(const iter_impl& other) const
+    {
+        return not operator<(other);
+    }
+
+    /*!
+    @brief  add to iterator
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    iter_impl& operator+=(difference_type i)
+    {
+        assert(m_object != nullptr);
+
+        switch (m_object->m_type)
+        {
+            case value_t::object:
+                JSON_THROW(invalid_iterator::create(209, "cannot use offsets with object iterators"));
+
+            case value_t::array:
+            {
+                std::advance(m_it.array_iterator, i);
+                break;
+            }
+
+            default:
+            {
+                m_it.primitive_iterator += i;
+                break;
+            }
+        }
+
+        return *this;
+    }
+
+    /*!
+    @brief  subtract from iterator
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    iter_impl& operator-=(difference_type i)
+    {
+        return operator+=(-i);
+    }
+
+    /*!
+    @brief  add to iterator
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    iter_impl operator+(difference_type i) const
+    {
+        auto result = *this;
+        result += i;
+        return result;
+    }
+
+    /*!
+    @brief  addition of distance and iterator
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    friend iter_impl operator+(difference_type i, const iter_impl& it)
+    {
+        auto result = it;
+        result += i;
+        return result;
+    }
+
+    /*!
+    @brief  subtract from iterator
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    iter_impl operator-(difference_type i) const
+    {
+        auto result = *this;
+        result -= i;
+        return result;
+    }
+
+    /*!
+    @brief  return difference
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    difference_type operator-(const iter_impl& other) const
+    {
+        assert(m_object != nullptr);
+
+        switch (m_object->m_type)
+        {
+            case value_t::object:
+                JSON_THROW(invalid_iterator::create(209, "cannot use offsets with object iterators"));
+
+            case value_t::array:
+                return m_it.array_iterator - other.m_it.array_iterator;
+
+            default:
+                return m_it.primitive_iterator - other.m_it.primitive_iterator;
+        }
+    }
+
+    /*!
+    @brief  access to successor
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    reference operator[](difference_type n) const
+    {
+        assert(m_object != nullptr);
+
+        switch (m_object->m_type)
+        {
+            case value_t::object:
+                JSON_THROW(invalid_iterator::create(208, "cannot use operator[] for object iterators"));
+
+            case value_t::array:
+                return *std::next(m_it.array_iterator, n);
+
+            case value_t::null:
+                JSON_THROW(invalid_iterator::create(214, "cannot get value"));
+
+            default:
+            {
+                if (JSON_LIKELY(m_it.primitive_iterator.get_value() == -n))
+                {
+                    return *m_object;
+                }
+
+                JSON_THROW(invalid_iterator::create(214, "cannot get value"));
+            }
+        }
+    }
+
+    /*!
+    @brief  return the key of an object iterator
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    std::string_view key() const
+    {
+        assert(m_object != nullptr);
+
+        if (JSON_LIKELY(m_object->is_object()))
+        {
+            return m_it.object_iterator->first();
+        }
+
+        JSON_THROW(invalid_iterator::create(207, "cannot use key() for non-object iterators"));
+    }
+
+    /*!
+    @brief  return the value of an iterator
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    reference value() const
+    {
+        return operator*();
+    }
+
+  private:
+    /// associated JSON instance
+    pointer m_object = nullptr;
+    /// the actual iterator of the associated instance
+    internal_iterator<typename std::remove_const<BasicJsonType>::type> m_it;
+};
+
+/// proxy class for the items() function
+template<typename IteratorType> class iteration_proxy
+{
+  private:
+    /// helper class for iteration
+    class iteration_proxy_internal
+    {
+      private:
+        /// the iterator
+        IteratorType anchor;
+        /// an index for arrays (used to create key names)
+        std::size_t array_index = 0;
+
+      public:
+        explicit iteration_proxy_internal(IteratorType it) noexcept : anchor(it) {}
+
+        /// dereference operator (needed for range-based for)
+        iteration_proxy_internal& operator*()
+        {
+            return *this;
+        }
+
+        /// increment operator (needed for range-based for)
+        iteration_proxy_internal& operator++()
+        {
+            ++anchor;
+            ++array_index;
+
+            return *this;
+        }
+
+        /// inequality operator (needed for range-based for)
+        bool operator!=(const iteration_proxy_internal& o) const noexcept
+        {
+            return anchor != o.anchor;
+        }
+
+        /// return key of the iterator
+        std::string key() const
+        {
+            assert(anchor.m_object != nullptr);
+
+            switch (anchor.m_object->type())
+            {
+                // use integer array index as key
+                case value_t::array:
+                    return std::to_string(array_index);
+
+                // use key from the object
+                case value_t::object:
+                    return std::string{anchor.key()};
+
+                // use an empty key for all primitive types
+                default:
+                    return "";
+            }
+        }
+
+        /// return value of the iterator
+        typename IteratorType::reference value() const
+        {
+            return anchor.value();
+        }
+    };
+
+    /// the container to iterate
+    typename IteratorType::reference container;
+
+  public:
+    /// construct iteration proxy from a container
+    explicit iteration_proxy(typename IteratorType::reference cont) noexcept
+        : container(cont) {}
+
+    /// return iterator begin (needed for range-based for)
+    iteration_proxy_internal begin() noexcept
+    {
+        return iteration_proxy_internal(container.begin());
+    }
+
+    /// return iterator end (needed for range-based for)
+    iteration_proxy_internal end() noexcept
+    {
+        return iteration_proxy_internal(container.end());
+    }
+};
+
+//////////////////////
+// reverse_iterator //
+//////////////////////
+
+/*!
+@brief a template for a reverse iterator class
+
+@tparam Base the base iterator type to reverse. Valid types are @ref
+iterator (to create @ref reverse_iterator) and @ref const_iterator (to
+create @ref const_reverse_iterator).
+
+@requirement The class satisfies the following concept requirements:
+-
+[BidirectionalIterator](http://en.cppreference.com/w/cpp/concept/BidirectionalIterator):
+  The iterator that can be moved can be moved in both directions (i.e.
+  incremented and decremented).
+- [OutputIterator](http://en.cppreference.com/w/cpp/concept/OutputIterator):
+  It is possible to write to the pointed-to element (only if @a Base is
+  @ref iterator).
+
+@since version 1.0.0
+*/
+template<typename Base>
+class json_reverse_iterator : public std::reverse_iterator<Base>
+{
+  public:
+    using difference_type = std::ptrdiff_t;
+    /// shortcut to the reverse iterator adapter
+    using base_iterator = std::reverse_iterator<Base>;
+    /// the reference type for the pointed-to element
+    using reference = typename Base::reference;
+
+    /// create reverse iterator from iterator
+    json_reverse_iterator(const typename base_iterator::iterator_type& it) noexcept
+        : base_iterator(it) {}
+
+    /// create reverse iterator from base class
+    json_reverse_iterator(const base_iterator& it) noexcept : base_iterator(it) {}
+
+    /// post-increment (it++)
+    json_reverse_iterator const operator++(int)
+    {
+        return static_cast<json_reverse_iterator>(base_iterator::operator++(1));
+    }
+
+    /// pre-increment (++it)
+    json_reverse_iterator& operator++()
+    {
+        return static_cast<json_reverse_iterator&>(base_iterator::operator++());
+    }
+
+    /// post-decrement (it--)
+    json_reverse_iterator const operator--(int)
+    {
+        return static_cast<json_reverse_iterator>(base_iterator::operator--(1));
+    }
+
+    /// pre-decrement (--it)
+    json_reverse_iterator& operator--()
+    {
+        return static_cast<json_reverse_iterator&>(base_iterator::operator--());
+    }
+
+    /// add to iterator
+    json_reverse_iterator& operator+=(difference_type i)
+    {
+        return static_cast<json_reverse_iterator&>(base_iterator::operator+=(i));
+    }
+
+    /// add to iterator
+    json_reverse_iterator operator+(difference_type i) const
+    {
+        return static_cast<json_reverse_iterator>(base_iterator::operator+(i));
+    }
+
+    /// subtract from iterator
+    json_reverse_iterator operator-(difference_type i) const
+    {
+        return static_cast<json_reverse_iterator>(base_iterator::operator-(i));
+    }
+
+    /// return difference
+    difference_type operator-(const json_reverse_iterator& other) const
+    {
+        return base_iterator(*this) - base_iterator(other);
+    }
+
+    /// access to successor
+    reference operator[](difference_type n) const
+    {
+        return *(this->operator+(n));
+    }
+
+    /// return the key of an object iterator
+    auto key() const -> decltype(std::declval<Base>().key())
+    {
+        auto it = --this->base();
+        return it.key();
+    }
+
+    /// return the value of an iterator
+    reference value() const
+    {
+        auto it = --this->base();
+        return it.operator * ();
+    }
+};
+
+template<typename BasicJsonType>
+class json_ref
+{
+  public:
+    using value_type = BasicJsonType;
+
+    json_ref(value_type&& value)
+        : owned_value(std::move(value)), value_ref(&owned_value), is_rvalue(true)
+    {}
+
+    json_ref(const value_type& value)
+        : value_ref(const_cast<value_type*>(&value)), is_rvalue(false)
+    {}
+
+    json_ref(std::initializer_list<json_ref> init)
+        : owned_value(init), value_ref(&owned_value), is_rvalue(true)
+    {}
+
+    template<class... Args>
+    json_ref(Args&& ... args)
+        : owned_value(std::forward<Args>(args)...), value_ref(&owned_value), is_rvalue(true)
+    {}
+
+    // class should be movable only
+    json_ref(json_ref&&) = default;
+    json_ref(const json_ref&) = delete;
+    json_ref& operator=(const json_ref&) = delete;
+
+    value_type moved_or_copied() const
+    {
+        if (is_rvalue)
+        {
+            return std::move(*value_ref);
+        }
+        return *value_ref;
+    }
+
+    value_type const& operator*() const
+    {
+        return *static_cast<value_type const*>(value_ref);
+    }
+
+    value_type const* operator->() const
+    {
+        return static_cast<value_type const*>(value_ref);
+    }
+
+  private:
+    mutable value_type owned_value = nullptr;
+    value_type* value_ref = nullptr;
+    const bool is_rvalue;
+};
+}  // namespace detail
+
+class json_pointer
+{
+    // allow json to access private members
+    friend class json;
+    friend class JsonTest;
+
+  public:
+    /*!
+    @brief create JSON pointer
+
+    Create a JSON pointer according to the syntax described in
+    [Section 3 of RFC6901](https://tools.ietf.org/html/rfc6901#section-3).
+
+    @param[in] s  string representing the JSON pointer; if omitted, the empty
+                  string is assumed which references the whole JSON value
+
+    @throw parse_error.107 if the given JSON pointer @a s is nonempty and does
+                           not begin with a slash (`/`); see example below
+
+    @throw parse_error.108 if a tilde (`~`) in the given JSON pointer @a s is
+    not followed by `0` (representing `~`) or `1` (representing `/`); see
+    example below
+
+    @liveexample{The example shows the construction several valid JSON pointers
+    as well as the exceptional behavior.,json_pointer}
+
+    @since version 2.0.0
+    */
+    explicit json_pointer(std::string_view s = {})
+        : reference_tokens(split(s))
+    {}
+
+    /*!
+    @brief return a string representation of the JSON pointer
+
+    @invariant For each JSON pointer `ptr`, it holds:
+    @code {.cpp}
+    ptr == json_pointer(ptr.to_string());
+    @endcode
+
+    @return a string representation of the JSON pointer
+
+    @liveexample{The example shows the result of `to_string`.,
+    json_pointer__to_string}
+
+    @since version 2.0.0
+    */
+    std::string to_string() const noexcept;
+
+    /// @copydoc to_string()
+    operator std::string() const
+    {
+        return to_string();
+    }
+
+    /*!
+    @param[in] s  reference token to be converted into an array index
+
+    @return integer representation of @a s
+
+    @throw out_of_range.404 if string @a s could not be converted to an integer
+    */
+    static int array_index(std::string_view s);
+
+  private:
+    /*!
+    @brief remove and return last reference pointer
+    @throw out_of_range.405 if JSON pointer has no parent
+    */
+    std::string pop_back()
+    {
+        if (JSON_UNLIKELY(is_root()))
+        {
+            JSON_THROW(detail::out_of_range::create(405, "JSON pointer has no parent"));
+        }
+
+        auto last = reference_tokens.back();
+        reference_tokens.pop_back();
+        return last;
+    }
+
+    /// return whether pointer points to the root document
+    bool is_root() const
+    {
+        return reference_tokens.empty();
+    }
+
+    json_pointer top() const
+    {
+        if (JSON_UNLIKELY(is_root()))
+        {
+            JSON_THROW(detail::out_of_range::create(405, "JSON pointer has no parent"));
+        }
+
+        json_pointer result = *this;
+        result.reference_tokens = {reference_tokens[0]};
+        return result;
+    }
+
+    /*!
+    @brief create and return a reference to the pointed to value
+
+    @complexity Linear in the number of reference tokens.
+
+    @throw parse_error.109 if array index is not a number
+    @throw type_error.313 if value cannot be unflattened
+    */
+    json& get_and_create(json& j) const;
+
+    /*!
+    @brief return a reference to the pointed to value
+
+    @note This version does not throw if a value is not present, but tries to
+          create nested values instead. For instance, calling this function
+          with pointer `"/this/that"` on a null value is equivalent to calling
+          `operator[]("this").operator[]("that")` on that value, effectively
+          changing the null value to an object.
+
+    @param[in] ptr  a JSON value
+
+    @return reference to the JSON value pointed to by the JSON pointer
+
+    @complexity Linear in the length of the JSON pointer.
+
+    @throw parse_error.106   if an array index begins with '0'
+    @throw parse_error.109   if an array index was not a number
+    @throw out_of_range.404  if the JSON pointer can not be resolved
+    */
+    json& get_unchecked(json* ptr) const;
+
+    /*!
+    @throw parse_error.106   if an array index begins with '0'
+    @throw parse_error.109   if an array index was not a number
+    @throw out_of_range.402  if the array index '-' is used
+    @throw out_of_range.404  if the JSON pointer can not be resolved
+    */
+    json& get_checked(json* ptr) const;
+
+    /*!
+    @brief return a const reference to the pointed to value
+
+    @param[in] ptr  a JSON value
+
+    @return const reference to the JSON value pointed to by the JSON
+    pointer
+
+    @throw parse_error.106   if an array index begins with '0'
+    @throw parse_error.109   if an array index was not a number
+    @throw out_of_range.402  if the array index '-' is used
+    @throw out_of_range.404  if the JSON pointer can not be resolved
+    */
+    const json& get_unchecked(const json* ptr) const;
+
+    /*!
+    @throw parse_error.106   if an array index begins with '0'
+    @throw parse_error.109   if an array index was not a number
+    @throw out_of_range.402  if the array index '-' is used
+    @throw out_of_range.404  if the JSON pointer can not be resolved
+    */
+    const json& get_checked(const json* ptr) const;
+
+    /*!
+    @brief split the string input to reference tokens
+
+    @note This function is only called by the json_pointer constructor.
+          All exceptions below are documented there.
+
+    @throw parse_error.107  if the pointer is not empty or begins with '/'
+    @throw parse_error.108  if character '~' is not followed by '0' or '1'
+    */
+    static std::vector<std::string> split(std::string_view reference_string);
+
+    /*!
+    @brief replace all occurrences of a substring by another string
+
+    @param[in,out] s  the string to manipulate; changed so that all
+                   occurrences of @a f are replaced with @a t
+    @param[in]     f  the substring to replace with @a t
+    @param[in]     t  the string to replace @a f
+
+    @pre The search string @a f must not be empty. **This precondition is
+    enforced with an assertion.**
+
+    @since version 2.0.0
+    */
+    static void replace_substring(std::string& s, const std::string& f,
+                                  const std::string& t);
+
+    /// escape "~"" to "~0" and "/" to "~1"
+    static std::string escape(std::string s);
+
+    /// unescape "~1" to tilde and "~0" to slash (order is important!)
+    static void unescape(std::string& s);
+
+    /*!
+    @param[in] reference_string  the reference string to the current value
+    @param[in] value             the value to consider
+    @param[in,out] result        the result object to insert values to
+
+    @note Empty objects or arrays are flattened to `null`.
+    */
+    static void flatten(std::string_view reference_string,
+                        const json& value,
+                        json& result);
+
+    /*!
+    @param[in] value  flattened JSON
+
+    @return unflattened JSON
+
+    @throw parse_error.109 if array index is not a number
+    @throw type_error.314  if value is not an object
+    @throw type_error.315  if object values are not primitive
+    @throw type_error.313  if value cannot be unflattened
+    */
+    static json
+    unflatten(const json& value);
+
+    friend bool operator==(json_pointer const& lhs,
+                           json_pointer const& rhs) noexcept
+    {
+        return (lhs.reference_tokens == rhs.reference_tokens);
+    }
+
+    friend bool operator!=(json_pointer const& lhs,
+                           json_pointer const& rhs) noexcept
+    {
+        return not (lhs == rhs);
+    }
+
+    /// the reference tokens
+    std::vector<std::string> reference_tokens;
+};
+
+template<typename, typename>
+struct adl_serializer
+{
+    /*!
+    @brief convert a JSON value to any value type
+
+    This function is usually called by the `get()` function of the
+    @ref json class (either explicit or via conversion operators).
+
+    @param[in] j         JSON value to read from
+    @param[in,out] val  value to write to
+    */
+    template<typename BasicJsonType, typename ValueType>
+    static void from_json(BasicJsonType&& j, ValueType& val) noexcept(
+        noexcept(::wpi::from_json(std::forward<BasicJsonType>(j), val)))
+    {
+        ::wpi::from_json(std::forward<BasicJsonType>(j), val);
+    }
+
+    /*!
+    @brief convert any value type to a JSON value
+
+    This function is usually called by the constructors of the @ref json
+    class.
+
+    @param[in,out] j  JSON value to write to
+    @param[in] val     value to read from
+    */
+    template<typename BasicJsonType, typename ValueType>
+    static void to_json(BasicJsonType& j, ValueType&& val) noexcept(
+        noexcept(::wpi::to_json(j, std::forward<ValueType>(val))))
+    {
+        ::wpi::to_json(j, std::forward<ValueType>(val));
+    }
+};
+
+/*!
+@brief a class to store JSON values
+
+@requirement The class satisfies the following concept requirements:
+- Basic
+ - [DefaultConstructible](http://en.cppreference.com/w/cpp/concept/DefaultConstructible):
+   JSON values can be default constructed. The result will be a JSON null
+   value.
+ - [MoveConstructible](http://en.cppreference.com/w/cpp/concept/MoveConstructible):
+   A JSON value can be constructed from an rvalue argument.
+ - [CopyConstructible](http://en.cppreference.com/w/cpp/concept/CopyConstructible):
+   A JSON value can be copy-constructed from an lvalue expression.
+ - [MoveAssignable](http://en.cppreference.com/w/cpp/concept/MoveAssignable):
+   A JSON value van be assigned from an rvalue argument.
+ - [CopyAssignable](http://en.cppreference.com/w/cpp/concept/CopyAssignable):
+   A JSON value can be copy-assigned from an lvalue expression.
+ - [Destructible](http://en.cppreference.com/w/cpp/concept/Destructible):
+   JSON values can be destructed.
+- Layout
+ - [StandardLayoutType](http://en.cppreference.com/w/cpp/concept/StandardLayoutType):
+   JSON values have
+   [standard layout](http://en.cppreference.com/w/cpp/language/data_members#Standard_layout):
+   All non-static data members are private and standard layout types, the
+   class has no virtual functions or (virtual) base classes.
+- Library-wide
+ - [EqualityComparable](http://en.cppreference.com/w/cpp/concept/EqualityComparable):
+   JSON values can be compared with `==`, see @ref
+   operator==(const_reference,const_reference).
+ - [LessThanComparable](http://en.cppreference.com/w/cpp/concept/LessThanComparable):
+   JSON values can be compared with `<`, see @ref
+   operator<(const_reference,const_reference).
+ - [Swappable](http://en.cppreference.com/w/cpp/concept/Swappable):
+   Any JSON lvalue or rvalue of can be swapped with any lvalue or rvalue of
+   other compatible types, using unqualified function call @ref swap().
+ - [NullablePointer](http://en.cppreference.com/w/cpp/concept/NullablePointer):
+   JSON values can be compared against `std::nullptr_t` objects which are used
+   to model the `null` value.
+- Container
+ - [Container](http://en.cppreference.com/w/cpp/concept/Container):
+   JSON values can be used like STL containers and provide iterator access.
+ - [ReversibleContainer](http://en.cppreference.com/w/cpp/concept/ReversibleContainer);
+   JSON values can be used like STL containers and provide reverse iterator
+   access.
+
+@invariant The member variables @a m_value and @a m_type have the following
+relationship:
+- If `m_type == value_t::object`, then `m_value.object != nullptr`.
+- If `m_type == value_t::array`, then `m_value.array != nullptr`.
+- If `m_type == value_t::string`, then `m_value.string != nullptr`.
+The invariants are checked by member function assert_invariant().
+
+@internal
+@note ObjectType trick from http://stackoverflow.com/a/9860911
+@endinternal
+
+@see [RFC 7159: The JavaScript Object Notation (JSON) Data Interchange
+Format](http://rfc7159.net/rfc7159)
+
+@since version 1.0.0
+
+@nosubgrouping
+*/
+class json
+{
+  private:
+    template<detail::value_t> friend struct detail::external_constructor;
+    friend ::wpi::json_pointer;
+    template<typename BasicJsonType>
+    friend class ::wpi::detail::iter_impl;
+    friend class JsonTest;
+
+    /// workaround type for MSVC
+    using json_t = json;
+
+    // convenience aliases for types residing in namespace detail;
+    using primitive_iterator_t = ::wpi::detail::primitive_iterator_t;
+    template<typename BasicJsonType>
+    using internal_iterator = ::wpi::detail::internal_iterator<BasicJsonType>;
+    template<typename BasicJsonType>
+    using iter_impl = ::wpi::detail::iter_impl<BasicJsonType>;
+    template<typename Iterator>
+    using iteration_proxy = ::wpi::detail::iteration_proxy<Iterator>;
+    template<typename Base> using json_reverse_iterator = ::wpi::detail::json_reverse_iterator<Base>;
+
+    class binary_reader;
+    class binary_writer;
+    class lexer;
+    class parser;
+
+  public:
+    class serializer;
+
+    using value_t = detail::value_t;
+    /// @copydoc wpi::json_pointer
+    using json_pointer = ::wpi::json_pointer;
+    template<typename T, typename SFINAE>
+    using json_serializer = adl_serializer<T, SFINAE>;
+    /// helper type for initializer lists of json values
+    using initializer_list_t = std::initializer_list<detail::json_ref<json>>;
+
+    ////////////////
+    // exceptions //
+    ////////////////
+
+    /// @name exceptions
+    /// Classes to implement user-defined exceptions.
+    /// @{
+
+    /// @copydoc detail::exception
+    using exception = detail::exception;
+    /// @copydoc detail::parse_error
+    using parse_error = detail::parse_error;
+    /// @copydoc detail::invalid_iterator
+    using invalid_iterator = detail::invalid_iterator;
+    /// @copydoc detail::type_error
+    using type_error = detail::type_error;
+    /// @copydoc detail::out_of_range
+    using out_of_range = detail::out_of_range;
+    /// @copydoc detail::other_error
+    using other_error = detail::other_error;
+
+    /// @}
+
+
+    /////////////////////
+    // container types //
+    /////////////////////
+
+    /// @name container types
+    /// The canonic container types to use @ref json like any other STL
+    /// container.
+    /// @{
+
+    /// the type of elements in a json container
+    using value_type = json;
+
+    /// the type of an element reference
+    using reference = value_type&;
+    /// the type of an element const reference
+    using const_reference = const value_type&;
+
+    /// a type to represent differences between iterators
+    using difference_type = std::ptrdiff_t;
+    /// a type to represent container sizes
+    using size_type = std::size_t;
+
+    /// the allocator type
+    using allocator_type = std::allocator<json>;
+
+    /// the type of an element pointer
+    using pointer = json*;
+    /// the type of an element const pointer
+    using const_pointer = const json*;
+
+    /// an iterator for a json container
+    using iterator = iter_impl<json>;
+    /// a const iterator for a json container
+    using const_iterator = iter_impl<const json>;
+    /// a reverse iterator for a json container
+    using reverse_iterator = json_reverse_iterator<typename json::iterator>;
+    /// a const reverse iterator for a json container
+    using const_reverse_iterator = json_reverse_iterator<typename json::const_iterator>;
+
+    /// @}
+
+
+    /*!
+    @brief returns the allocator associated with the container
+    */
+    static allocator_type get_allocator()
+    {
+        return allocator_type();
+    }
+
+    /*!
+    @brief returns version information on the library
+
+    This function returns a JSON object with information about the library,
+    including the version number and information on the platform and compiler.
+
+    @return JSON object holding version information
+    key         | description
+    ----------- | ---------------
+    `compiler`  | Information on the used compiler. It is an object with the following keys: `c++` (the used C++ standard), `family` (the compiler family; possible values are `clang`, `icc`, `gcc`, `ilecpp`, `msvc`, `pgcpp`, `sunpro`, and `unknown`), and `version` (the compiler version).
+    `copyright` | The copyright line for the library as string.
+    `name`      | The name of the library as string.
+    `platform`  | The used platform as string. Possible values are `win32`, `linux`, `apple`, `unix`, and `unknown`.
+    `url`       | The URL of the project as string.
+    `version`   | The version of the library. It is an object with the following keys: `major`, `minor`, and `patch` as defined by [Semantic Versioning](http://semver.org), and `string` (the version string).
+
+    @liveexample{The following code shows an example output of the `meta()`
+    function.,meta}
+
+    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
+    changes to any JSON value.
+
+    @complexity Constant.
+
+    @since 2.1.0
+    */
+    static json meta();
+
+
+    ///////////////////////////
+    // JSON value data types //
+    ///////////////////////////
+
+    /// @name JSON value data types
+    /// The data types to store a JSON value. These types are derived from
+    /// the template arguments passed to class @ref json.
+    /// @{
+
+    // Use transparent comparator if possible, combined with perfect forwarding
+    // on find() and count() calls prevents unnecessary string construction.
+    using object_comparator_t = std::less<>;
+
+    /*!
+    @brief a type for an object
+
+    [RFC 7159](http://rfc7159.net/rfc7159) describes JSON objects as follows:
+    > An object is an unordered collection of zero or more name/value pairs,
+    > where a name is a string and a value is a string, number, boolean, null,
+    > object, or array.
+
+    #### Behavior
+
+    The choice of @a object_t influences the behavior of the JSON class. With
+    the default type, objects have the following behavior:
+
+    - When all names are unique, objects will be interoperable in the sense
+      that all software implementations receiving that object will agree on
+      the name-value mappings.
+    - When the names within an object are not unique, it is unspecified which
+      one of the values for a given key will be chosen. For instance,
+      `{"key": 2, "key": 1}` could be equal to either `{"key": 1}` or
+      `{"key": 2}`.
+    - Internally, name/value pairs are stored in lexicographical order of the
+      names. Objects will also be serialized (see @ref dump) in this order.
+      For instance, `{"b": 1, "a": 2}` and `{"a": 2, "b": 1}` will be stored
+      and serialized as `{"a": 2, "b": 1}`.
+    - When comparing objects, the order of the name/value pairs is irrelevant.
+      This makes objects interoperable in the sense that they will not be
+      affected by these differences. For instance, `{"b": 1, "a": 2}` and
+      `{"a": 2, "b": 1}` will be treated as equal.
+
+    #### Limits
+
+    [RFC 7159](http://rfc7159.net/rfc7159) specifies:
+    > An implementation may set limits on the maximum depth of nesting.
+
+    In this class, the object's limit of nesting is not explicitly constrained.
+    However, a maximum depth of nesting may be introduced by the compiler or
+    runtime environment. A theoretical limit can be queried by calling the
+    @ref max_size function of a JSON object.
+
+    #### Storage
+
+    Objects are stored as pointers in a @ref json type. That is, for any
+    access to object values, a pointer of type `object_t*` must be
+    dereferenced.
+
+    @since version 1.0.0
+
+    @note The order name/value pairs are added to the object is *not*
+    preserved by the library. Therefore, iterating an object may return
+    name/value pairs in a different order than they were originally stored. In
+    fact, keys will be traversed in alphabetical order as `std::map` with
+    `std::less` is used by default. Please note this behavior conforms to [RFC
+    7159](http://rfc7159.net/rfc7159), because any order implements the
+    specified "unordered" nature of JSON objects.
+    */
+    using object_t = StringMap<json>;
+
+    /*!
+    @brief a type for an array
+
+    [RFC 7159](http://rfc7159.net/rfc7159) describes JSON arrays as follows:
+    > An array is an ordered sequence of zero or more values.
+
+    #### Limits
+
+    [RFC 7159](http://rfc7159.net/rfc7159) specifies:
+    > An implementation may set limits on the maximum depth of nesting.
+
+    In this class, the array's limit of nesting is not explicitly constrained.
+    However, a maximum depth of nesting may be introduced by the compiler or
+    runtime environment. A theoretical limit can be queried by calling the
+    @ref max_size function of a JSON array.
+
+    #### Storage
+
+    Arrays are stored as pointers in a @ref json type. That is, for any
+    access to array values, a pointer of type `array_t*` must be dereferenced.
+
+    @sa @ref object_t -- type for an object value
+
+    @since version 1.0.0
+    */
+    using array_t = std::vector<json>;
+
+    /// @}
+
+  private:
+
+    /// helper for exception-safe object creation
+    template<typename T, typename... Args>
+    static T* create(Args&& ... args)
+    {
+        std::allocator<T> alloc;
+
+		using AllocatorTraits = std::allocator_traits<std::allocator<T>>;
+
+		auto deleter = [&](T * object)
+		{
+			AllocatorTraits::deallocate(alloc, object, 1);
+		};
+		std::unique_ptr<T, decltype(deleter)> object(AllocatorTraits::allocate(alloc, 1), deleter);
+		AllocatorTraits::construct(alloc, object.get(), std::forward<Args>(args)...);
+        assert(object != nullptr);
+        return object.release();
+    }
+
+    ////////////////////////
+    // JSON value storage //
+    ////////////////////////
+
+    /*!
+    @brief a JSON value
+
+    The actual storage for a JSON value of the @ref json class. This
+    union combines the different storage types for the JSON value types
+    defined in @ref value_t.
+
+    JSON type | value_t type    | used type
+    --------- | --------------- | ------------------------
+    object    | object          | pointer to @ref object_t
+    array     | array           | pointer to @ref array_t
+    string    | string          | pointer to std::string
+    boolean   | boolean         | bool
+    number    | number_integer  | int64_t
+    number    | number_unsigned | uint64_t
+    number    | number_float    | double
+    null      | null            | *no value is stored*
+
+    @note Variable-length types (objects, arrays, and strings) are stored as
+    pointers. The size of the union should not exceed 64 bits if the default
+    value types are used.
+
+    @since version 1.0.0
+    */
+    union json_value
+    {
+        /// object (stored with pointer to save storage)
+        object_t* object;
+        /// array (stored with pointer to save storage)
+        array_t* array;
+        /// string (stored with pointer to save storage)
+        std::string* string;
+        /// boolean
+        bool boolean;
+        /// number (integer)
+        int64_t number_integer;
+        /// number (unsigned integer)
+        uint64_t number_unsigned;
+        /// number (floating-point)
+        double number_float;
+
+        /// default constructor (for null values)
+        json_value() = default;
+        /// constructor for booleans
+        json_value(bool v) noexcept : boolean(v) {}
+        /// constructor for numbers (integer)
+        json_value(int64_t v) noexcept : number_integer(v) {}
+        /// constructor for numbers (unsigned)
+        json_value(uint64_t v) noexcept : number_unsigned(v) {}
+        /// constructor for numbers (floating-point)
+        json_value(double v) noexcept : number_float(v) {}
+        /// constructor for empty values of a given type
+        json_value(value_t t);
+
+        /// constructor for strings
+        json_value(std::string_view value)
+        {
+            string = create<std::string>(value);
+        }
+
+        /// constructor for strings
+        json_value(const std::string& value)
+        {
+            string = create<std::string>(value);
+        }
+
+        /// constructor for rvalue strings
+        json_value(std::string&& value)
+        {
+            string = create<std::string>(std::move(value));
+        }
+
+        /// constructor for objects
+        json_value(const object_t& value)
+        {
+            object = create<object_t>(value);
+        }
+
+        /// constructor for rvalue objects
+        json_value(object_t&& value)
+        {
+            object = create<object_t>(std::move(value));
+        }
+
+        /// constructor for arrays
+        json_value(const array_t& value)
+        {
+            array = create<array_t>(value);
+        }
+
+        /// constructor for rvalue arrays
+        json_value(array_t&& value)
+        {
+            array = create<array_t>(std::move(value));
+        }
+
+        void destroy(value_t t) noexcept;
+    };
+
+    /*!
+    @brief checks the class invariants
+
+    This function asserts the class invariants. It needs to be called at the
+    end of every constructor to make sure that created objects respect the
+    invariant. Furthermore, it has to be called each time the type of a JSON
+    value is changed, because the invariant expresses a relationship between
+    @a m_type and @a m_value.
+    */
+    void assert_invariant() const noexcept
+    {
+        assert(m_type != value_t::object or m_value.object != nullptr);
+        assert(m_type != value_t::array or m_value.array != nullptr);
+        assert(m_type != value_t::string or m_value.string != nullptr);
+    }
+
+  public:
+    //////////////////////////
+    // JSON parser callback //
+    //////////////////////////
+
+    /*!
+    @brief parser event types
+
+    The parser callback distinguishes the following events:
+    - `object_start`: the parser read `{` and started to process a JSON object
+    - `key`: the parser read a key of a value in an object
+    - `object_end`: the parser read `}` and finished processing a JSON object
+    - `array_start`: the parser read `[` and started to process a JSON array
+    - `array_end`: the parser read `]` and finished processing a JSON array
+    - `value`: the parser finished reading a JSON value
+
+    @image html callback_events.png "Example when certain parse events are triggered"
+
+    @sa @ref parser_callback_t for more information and examples
+    */
+    enum class parse_event_t : uint8_t
+    {
+        /// the parser read `{` and started to process a JSON object
+        object_start,
+        /// the parser read `}` and finished processing a JSON object
+        object_end,
+        /// the parser read `[` and started to process a JSON array
+        array_start,
+        /// the parser read `]` and finished processing a JSON array
+        array_end,
+        /// the parser read a key of a value in an object
+        key,
+        /// the parser finished reading a JSON value
+        value
+    };
+
+    /*!
+    @brief per-element parser callback type
+
+    With a parser callback function, the result of parsing a JSON text can be
+    influenced. When passed to @ref parse, it is called on certain events
+    (passed as @ref parse_event_t via parameter @a event) with a set recursion
+    depth @a depth and context JSON value @a parsed. The return value of the
+    callback function is a boolean indicating whether the element that emitted
+    the callback shall be kept or not.
+
+    We distinguish six scenarios (determined by the event type) in which the
+    callback function can be called. The following table describes the values
+    of the parameters @a depth, @a event, and @a parsed.
+
+    parameter @a event | description | parameter @a depth | parameter @a parsed
+    ------------------ | ----------- | ------------------ | -------------------
+    parse_event_t::object_start | the parser read `{` and started to process a JSON object | depth of the parent of the JSON object | a JSON value with type discarded
+    parse_event_t::key | the parser read a key of a value in an object | depth of the currently parsed JSON object | a JSON string containing the key
+    parse_event_t::object_end | the parser read `}` and finished processing a JSON object | depth of the parent of the JSON object | the parsed JSON object
+    parse_event_t::array_start | the parser read `[` and started to process a JSON array | depth of the parent of the JSON array | a JSON value with type discarded
+    parse_event_t::array_end | the parser read `]` and finished processing a JSON array | depth of the parent of the JSON array | the parsed JSON array
+    parse_event_t::value | the parser finished reading a JSON value | depth of the value | the parsed JSON value
+
+    @image html callback_events.png "Example when certain parse events are triggered"
+
+    Discarding a value (i.e., returning `false`) has different effects
+    depending on the context in which function was called:
+
+    - Discarded values in structured types are skipped. That is, the parser
+      will behave as if the discarded value was never read.
+    - In case a value outside a structured type is skipped, it is replaced
+      with `null`. This case happens if the top-level element is skipped.
+
+    @param[in] depth  the depth of the recursion during parsing
+
+    @param[in] event  an event of type parse_event_t indicating the context in
+    the callback function has been called
+
+    @param[in,out] parsed  the current intermediate parse result; note that
+    writing to this value has no effect for parse_event_t::key events
+
+    @return Whether the JSON value which called the function during parsing
+    should be kept (`true`) or not (`false`). In the latter case, it is either
+    skipped completely or replaced by an empty discarded object.
+
+    @sa @ref parse for examples
+
+    @since version 1.0.0
+    */
+    using parser_callback_t =
+        std::function<bool(int depth, parse_event_t event, json& parsed)>;
+
+
+    //////////////////
+    // constructors //
+    //////////////////
+
+    /// @name constructors and destructors
+    /// Constructors of class @ref json, copy/move constructor, copy
+    /// assignment, static functions creating objects, and the destructor.
+    /// @{
+
+    /*!
+    @brief create an empty value with a given type
+
+    Create an empty JSON value with a given type. The value will be default
+    initialized with an empty value which depends on the type:
+
+    Value type  | initial value
+    ----------- | -------------
+    null        | `null`
+    boolean     | `false`
+    string      | `""`
+    number      | `0`
+    object      | `{}`
+    array       | `[]`
+
+    @param[in] v  the type of the value to create
+
+    @complexity Constant.
+
+    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
+    changes to any JSON value.
+
+    @liveexample{The following code shows the constructor for different @ref
+    value_t values,json__value_t}
+
+    @sa @ref clear() -- restores the postcondition of this constructor
+
+    @since version 1.0.0
+    */
+    json(const value_t v)
+        : m_type(v), m_value(v)
+    {
+        assert_invariant();
+    }
+
+    /*!
+    @brief create a null object
+
+    Create a `null` JSON value. It either takes a null pointer as parameter
+    (explicitly creating `null`) or no parameter (implicitly creating `null`).
+    The passed null pointer itself is not read -- it is only used to choose
+    the right constructor.
+
+    @complexity Constant.
+
+    @exceptionsafety No-throw guarantee: this constructor never throws
+    exceptions.
+
+    @liveexample{The following code shows the constructor with and without a
+    null pointer parameter.,json__nullptr_t}
+
+    @since version 1.0.0
+    */
+    json(std::nullptr_t = nullptr) noexcept
+        : json(value_t::null)
+    {
+        assert_invariant();
+    }
+
+    /*!
+    @brief create a JSON value
+
+    This is a "catch all" constructor for all compatible JSON types; that is,
+    types for which a `to_json()` method exists. The constructor forwards the
+    parameter @a val to that method (to `json_serializer<U>::to_json` method
+    with `U = uncvref_t<CompatibleType>`, to be exact).
+
+    Template type @a CompatibleType includes, but is not limited to, the
+    following types:
+    - **arrays**: @ref array_t and all kinds of compatible containers such as
+      `std::vector`, `std::deque`, `std::list`,
+      `std::array`, `std::set`, `std::unordered_set`,
+      `std::multiset`, and `std::unordered_multiset` with a `value_type` from
+      which a @ref json value can be constructed.
+    - **objects**: @ref object_t and all kinds of compatible associative
+      containers such as `std::map`, `std::unordered_map`, `std::multimap`,
+      and `std::unordered_multimap` with a `key_type` compatible to
+      `std::string` and a `value_type` from which a @ref json value can
+      be constructed.
+    - **strings**: `std::string`, string literals, and all compatible string
+      containers can be used.
+    - **numbers**: int64_t, uint64_t,
+      double, and all convertible number types such as `int`,
+      `size_t`, `int64_t`, `float` or `double` can be used.
+    - **boolean**: `bool` can be used.
+
+    See the examples below.
+
+    @tparam CompatibleType a type such that:
+    - @a CompatibleType is not derived from `std::istream`,
+    - @a CompatibleType is not @ref json (to avoid hijacking copy/move
+         constructors),
+    - @a CompatibleType is not a different @ref json type (i.e. with different template arguments)
+    - @a CompatibleType is not a @ref json nested type (e.g.,
+         @ref json_pointer, @ref iterator, etc ...)
+    - @ref @ref json_serializer<U> has a
+         `to_json(json_t&, CompatibleType&&)` method
+
+    @tparam U = `uncvref_t<CompatibleType>`
+
+    @param[in] val the value to be forwarded to the respective constructor
+
+    @complexity Usually linear in the size of the passed @a val, also
+                depending on the implementation of the called `to_json()`
+                method.
+
+    @exceptionsafety Depends on the called constructor. For types directly
+    supported by the library (i.e., all types for which no `to_json()` function
+    was provided), strong guarantee holds: if an exception is thrown, there are
+    no changes to any JSON value.
+
+    @liveexample{The following code shows the constructor with several
+    compatible types.,json__CompatibleType}
+
+    @since version 2.1.0
+    */
+    template <typename CompatibleType,
+              typename U = detail::uncvref_t<CompatibleType>,
+              detail::enable_if_t<
+                  detail::is_compatible_type<json_t, U>::value, int> = 0>
+    json(CompatibleType && val) noexcept(noexcept(
+                adl_serializer<U, void>::to_json(std::declval<json_t&>(),
+                                           std::forward<CompatibleType>(val))))
+    {
+        adl_serializer<U, void>::to_json(*this, std::forward<CompatibleType>(val));
+        assert_invariant();
+    }
+
+    /*!
+    @brief create a container (array or object) from an initializer list
+
+    Creates a JSON value of type array or object from the passed initializer
+    list @a init. In case @a type_deduction is `true` (default), the type of
+    the JSON value to be created is deducted from the initializer list @a init
+    according to the following rules:
+
+    1. If the list is empty, an empty JSON object value `{}` is created.
+    2. If the list consists of pairs whose first element is a string, a JSON
+       object value is created where the first elements of the pairs are
+       treated as keys and the second elements are as values.
+    3. In all other cases, an array is created.
+
+    The rules aim to create the best fit between a C++ initializer list and
+    JSON values. The rationale is as follows:
+
+    1. The empty initializer list is written as `{}` which is exactly an empty
+       JSON object.
+    2. C++ has no way of describing mapped types other than to list a list of
+       pairs. As JSON requires that keys must be of type string, rule 2 is the
+       weakest constraint one can pose on initializer lists to interpret them
+       as an object.
+    3. In all other cases, the initializer list could not be interpreted as
+       JSON object type, so interpreting it as JSON array type is safe.
+
+    With the rules described above, the following JSON values cannot be
+    expressed by an initializer list:
+
+    - the empty array (`[]`): use @ref array(initializer_list_t)
+      with an empty initializer list in this case
+    - arrays whose elements satisfy rule 2: use @ref
+      array(initializer_list_t) with the same initializer list
+      in this case
+
+    @note When used without parentheses around an empty initializer list, @ref
+    json() is called instead of this function, yielding the JSON null
+    value.
+
+    @param[in] init  initializer list with JSON values
+
+    @param[in] type_deduction internal parameter; when set to `true`, the type
+    of the JSON value is deducted from the initializer list @a init; when set
+    to `false`, the type provided via @a manual_type is forced. This mode is
+    used by the functions @ref array(initializer_list_t) and
+    @ref object(initializer_list_t).
+
+    @param[in] manual_type internal parameter; when @a type_deduction is set
+    to `false`, the created JSON value will use the provided type (only @ref
+    value_t::array and @ref value_t::object are valid); when @a type_deduction
+    is set to `true`, this parameter has no effect
+
+    @throw type_error.301 if @a type_deduction is `false`, @a manual_type is
+    `value_t::object`, but @a init contains an element which is not a pair
+    whose first element is a string. In this case, the constructor could not
+    create an object. If @a type_deduction would have be `true`, an array
+    would have been created. See @ref object(initializer_list_t)
+    for an example.
+
+    @complexity Linear in the size of the initializer list @a init.
+
+    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
+    changes to any JSON value.
+
+    @liveexample{The example below shows how JSON values are created from
+    initializer lists.,json__list_init_t}
+
+    @sa @ref array(initializer_list_t) -- create a JSON array
+    value from an initializer list
+    @sa @ref object(initializer_list_t) -- create a JSON object
+    value from an initializer list
+
+    @since version 1.0.0
+    */
+    json(initializer_list_t init,
+               bool type_deduction = true,
+               value_t manual_type = value_t::array);
+
+    /*!
+    @brief explicitly create an array from an initializer list
+
+    Creates a JSON array value from a given initializer list. That is, given a
+    list of values `a, b, c`, creates the JSON value `[a, b, c]`. If the
+    initializer list is empty, the empty array `[]` is created.
+
+    @note This function is only needed to express two edge cases that cannot
+    be realized with the initializer list constructor (@ref
+    json(initializer_list_t, bool, value_t)). These cases
+    are:
+    1. creating an array whose elements are all pairs whose first element is a
+    string -- in this case, the initializer list constructor would create an
+    object, taking the first elements as keys
+    2. creating an empty array -- passing the empty initializer list to the
+    initializer list constructor yields an empty object
+
+    @param[in] init  initializer list with JSON values to create an array from
+    (optional)
+
+    @return JSON array value
+
+    @complexity Linear in the size of @a init.
+
+    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
+    changes to any JSON value.
+
+    @liveexample{The following code shows an example for the `array`
+    function.,array}
+
+    @sa @ref json(initializer_list_t, bool, value_t) --
+    create a JSON value from an initializer list
+    @sa @ref object(initializer_list_t) -- create a JSON object
+    value from an initializer list
+
+    @since version 1.0.0
+    */
+    static json array(initializer_list_t init = {})
+    {
+        return json(init, false, value_t::array);
+    }
+
+    /*!
+    @brief explicitly create an object from an initializer list
+
+    Creates a JSON object value from a given initializer list. The initializer
+    lists elements must be pairs, and their first elements must be strings. If
+    the initializer list is empty, the empty object `{}` is created.
+
+    @note This function is only added for symmetry reasons. In contrast to the
+    related function @ref array(initializer_list_t), there are
+    no cases which can only be expressed by this function. That is, any
+    initializer list @a init can also be passed to the initializer list
+    constructor @ref json(initializer_list_t, bool, value_t).
+
+    @param[in] init  initializer list to create an object from (optional)
+
+    @return JSON object value
+
+    @throw type_error.301 if @a init is not a list of pairs whose first
+    elements are strings. In this case, no object can be created. When such a
+    value is passed to @ref json(initializer_list_t, bool, value_t),
+    an array would have been created from the passed initializer list @a init.
+    See example below.
+
+    @complexity Linear in the size of @a init.
+
+    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
+    changes to any JSON value.
+
+    @liveexample{The following code shows an example for the `object`
+    function.,object}
+
+    @sa @ref json(initializer_list_t, bool, value_t) --
+    create a JSON value from an initializer list
+    @sa @ref array(initializer_list_t) -- create a JSON array
+    value from an initializer list
+
+    @since version 1.0.0
+    */
+    static json object(initializer_list_t init = {})
+    {
+        return json(init, false, value_t::object);
+    }
+
+    /*!
+    @brief construct an array with count copies of given value
+
+    Constructs a JSON array value by creating @a cnt copies of a passed value.
+    In case @a cnt is `0`, an empty array is created.
+
+    @param[in] cnt  the number of JSON copies of @a val to create
+    @param[in] val  the JSON value to copy
+
+    @post `std::distance(begin(),end()) == cnt` holds.
+
+    @complexity Linear in @a cnt.
+
+    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
+    changes to any JSON value.
+
+    @liveexample{The following code shows examples for the @ref
+    json(size_type\, const json&)
+    constructor.,json__size_type_json}
+
+    @since version 1.0.0
+    */
+    json(size_type cnt, const json& val);
+
+    /*!
+    @brief construct a JSON container given an iterator range
+
+    Constructs the JSON value with the contents of the range `[first, last)`.
+    The semantics depends on the different types a JSON value can have:
+    - In case of a null type, invalid_iterator.206 is thrown.
+    - In case of other primitive types (number, boolean, or string), @a first
+      must be `begin()` and @a last must be `end()`. In this case, the value is
+      copied. Otherwise, invalid_iterator.204 is thrown.
+    - In case of structured types (array, object), the constructor behaves as
+      similar versions for `std::vector` or `std::map`; that is, a JSON array
+      or object is constructed from the values in the range.
+
+    @tparam InputIT an input iterator type (@ref iterator or @ref
+    const_iterator)
+
+    @param[in] first begin of the range to copy from (included)
+    @param[in] last end of the range to copy from (excluded)
+
+    @pre Iterators @a first and @a last must be initialized. **This
+         precondition is enforced with an assertion (see warning).** If
+         assertions are switched off, a violation of this precondition yields
+         undefined behavior.
+
+    @pre Range `[first, last)` is valid. Usually, this precondition cannot be
+         checked efficiently. Only certain edge cases are detected; see the
+         description of the exceptions below. A violation of this precondition
+         yields undefined behavior.
+
+    @warning A precondition is enforced with a runtime assertion that will
+             result in calling `std::abort` if this precondition is not met.
+             Assertions can be disabled by defining `NDEBUG` at compile time.
+             See http://en.cppreference.com/w/cpp/error/assert for more
+             information.
+
+    @throw invalid_iterator.201 if iterators @a first and @a last are not
+    compatible (i.e., do not belong to the same JSON value). In this case,
+    the range `[first, last)` is undefined.
+    @throw invalid_iterator.204 if iterators @a first and @a last belong to a
+    primitive type (number, boolean, or string), but @a first does not point
+    to the first element any more. In this case, the range `[first, last)` is
+    undefined. See example code below.
+    @throw invalid_iterator.206 if iterators @a first and @a last belong to a
+    null value. In this case, the range `[first, last)` is undefined.
+
+    @complexity Linear in distance between @a first and @a last.
+
+    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
+    changes to any JSON value.
+
+    @liveexample{The example below shows several ways to create JSON values by
+    specifying a subrange with iterators.,json__InputIt_InputIt}
+
+    @since version 1.0.0
+    */
+    template<class InputIT, typename std::enable_if<
+                 std::is_same<InputIT, typename json_t::iterator>::value or
+                 std::is_same<InputIT, typename json_t::const_iterator>::value, int>::type = 0>
+    json(InputIT first, InputIT last)
+    {
+        assert(first.m_object != nullptr);
+        assert(last.m_object != nullptr);
+
+        // make sure iterator fits the current value
+        if (JSON_UNLIKELY(first.m_object != last.m_object))
+        {
+            JSON_THROW(invalid_iterator::create(201, "iterators are not compatible"));
+        }
+
+        // copy type from first iterator
+        m_type = first.m_object->m_type;
+
+        // check if iterator range is complete for primitive values
+        switch (m_type)
+        {
+            case value_t::boolean:
+            case value_t::number_float:
+            case value_t::number_integer:
+            case value_t::number_unsigned:
+            case value_t::string:
+            {
+                if (JSON_UNLIKELY(not first.m_it.primitive_iterator.is_begin()
+                                  or not last.m_it.primitive_iterator.is_end()))
+                {
+                    JSON_THROW(invalid_iterator::create(204, "iterators out of range"));
+                }
+                break;
+            }
+
+            default:
+                break;
+        }
+
+        switch (m_type)
+        {
+            case value_t::number_integer:
+            {
+                m_value.number_integer = first.m_object->m_value.number_integer;
+                break;
+            }
+
+            case value_t::number_unsigned:
+            {
+                m_value.number_unsigned = first.m_object->m_value.number_unsigned;
+                break;
+            }
+
+            case value_t::number_float:
+            {
+                m_value.number_float = first.m_object->m_value.number_float;
+                break;
+            }
+
+            case value_t::boolean:
+            {
+                m_value.boolean = first.m_object->m_value.boolean;
+                break;
+            }
+
+            case value_t::string:
+            {
+                m_value = *first.m_object->m_value.string;
+                break;
+            }
+
+            case value_t::array:
+            {
+                m_value.array = create<array_t>(first.m_it.array_iterator,
+                                                last.m_it.array_iterator);
+                break;
+            }
+
+            default:
+                JSON_THROW(invalid_iterator::create(206, "cannot construct with iterators from", first.m_object->type_name()));
+        }
+
+        assert_invariant();
+    }
+
+
+    ///////////////////////////////////////
+    // other constructors and destructor //
+    ///////////////////////////////////////
+
+    /// @private
+    json(const detail::json_ref<json>& ref)
+        : json(ref.moved_or_copied())
+    {}
+
+    /*!
+    @brief copy constructor
+
+    Creates a copy of a given JSON value.
+
+    @param[in] other  the JSON value to copy
+
+    @post `*this == other`
+
+    @complexity Linear in the size of @a other.
+
+    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
+    changes to any JSON value.
+
+    @requirement This function helps `json` satisfying the
+    [Container](http://en.cppreference.com/w/cpp/concept/Container)
+    requirements:
+    - The complexity is linear.
+    - As postcondition, it holds: `other == json(other)`.
+
+    @liveexample{The following code shows an example for the copy
+    constructor.,json__json}
+
+    @since version 1.0.0
+    */
+    json(const json& other);
+
+    /*!
+    @brief move constructor
+
+    Move constructor. Constructs a JSON value with the contents of the given
+    value @a other using move semantics. It "steals" the resources from @a
+    other and leaves it as JSON null value.
+
+    @param[in,out] other  value to move to this object
+
+    @post `*this` has the same value as @a other before the call.
+    @post @a other is a JSON null value.
+
+    @complexity Constant.
+
+    @exceptionsafety No-throw guarantee: this constructor never throws
+    exceptions.
+
+    @requirement This function helps `json` satisfying the
+    [MoveConstructible](http://en.cppreference.com/w/cpp/concept/MoveConstructible)
+    requirements.
+
+    @liveexample{The code below shows the move constructor explicitly called
+    via std::move.,json__moveconstructor}
+
+    @since version 1.0.0
+    */
+    json(json&& other) noexcept
+        : m_type(std::move(other.m_type)),
+          m_value(std::move(other.m_value))
+    {
+        // check that passed value is valid
+        other.assert_invariant();
+
+        // invalidate payload
+        other.m_type = value_t::null;
+        other.m_value = {};
+
+        assert_invariant();
+    }
+
+    /*!
+    @brief copy assignment
+
+    Copy assignment operator. Copies a JSON value via the "copy and swap"
+    strategy: It is expressed in terms of the copy constructor, destructor,
+    and the `swap()` member function.
+
+    @param[in] other  value to copy from
+
+    @complexity Linear.
+
+    @requirement This function helps `json` satisfying the
+    [Container](http://en.cppreference.com/w/cpp/concept/Container)
+    requirements:
+    - The complexity is linear.
+
+    @liveexample{The code below shows and example for the copy assignment. It
+    creates a copy of value `a` which is then swapped with `b`. Finally\, the
+    copy of `a` (which is the null value after the swap) is
+    destroyed.,json__copyassignment}
+
+    @since version 1.0.0
+    */
+    reference& operator=(json other) noexcept (
+        std::is_nothrow_move_constructible<value_t>::value and
+        std::is_nothrow_move_assignable<value_t>::value and
+        std::is_nothrow_move_constructible<json_value>::value and
+        std::is_nothrow_move_assignable<json_value>::value
+    )
+    {
+        // check that passed value is valid
+        other.assert_invariant();
+
+        using std::swap;
+        swap(m_type, other.m_type);
+        swap(m_value, other.m_value);
+
+        assert_invariant();
+        return *this;
+    }
+
+    /*!
+    @brief destructor
+
+    Destroys the JSON value and frees all allocated memory.
+
+    @complexity Linear.
+
+    @requirement This function helps `json` satisfying the
+    [Container](http://en.cppreference.com/w/cpp/concept/Container)
+    requirements:
+    - The complexity is linear.
+    - All stored elements are destroyed and all memory is freed.
+
+    @since version 1.0.0
+    */
+    ~json() noexcept
+    {
+        assert_invariant();
+        m_value.destroy(m_type);
+    }
+
+    /// @}
+
+  public:
+    ///////////////////////
+    // object inspection //
+    ///////////////////////
+
+    /// @name object inspection
+    /// Functions to inspect the type of a JSON value.
+    /// @{
+
+    /*!
+    @brief serialization
+
+    Serialization function for JSON values. The function tries to mimic
+    Python's `json.dumps()` function, and currently supports its @a indent
+    and @a ensure_ascii parameters.
+
+    @param[in] indent If indent is nonnegative, then array elements and object
+    members will be pretty-printed with that indent level. An indent level of
+    `0` will only insert newlines. `-1` (the default) selects the most compact
+    representation.
+    @param[in] indent_char The character to use for indentation if @a indent is
+    greater than `0`. The default is ` ` (space).
+    @param[in] ensure_ascii If @a ensure_ascii is true, all non-ASCII characters
+    in the output are escaped with `\uXXXX` sequences, and the result consists
+    of ASCII characters only.
+
+    @return string containing the serialization of the JSON value
+
+    @throw type_error.316 if a string stored inside the JSON value is not
+                          UTF-8 encoded
+
+    @complexity Linear.
+
+    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
+    changes in the JSON value.
+
+    @liveexample{The following example shows the effect of different @a indent\,
+    @a indent_char\, and @a ensure_ascii parameters to the result of the
+    serialization.,dump}
+
+    @see https://docs.python.org/2/library/json.html#json.dump
+
+    @since version 1.0.0; indentation character @a indent_char, option
+           @a ensure_ascii and exceptions added in version 3.0.0
+    */
+    std::string dump(const int indent = -1, const char indent_char = ' ',
+                     const bool ensure_ascii = false) const;
+
+    void dump(raw_ostream& os, int indent = -1, const char indent_char = ' ',
+              const bool ensure_ascii = false) const;
+
+    /*!
+    @brief return the type of the JSON value (explicit)
+
+    Return the type of the JSON value as a value from the @ref value_t
+    enumeration.
+
+    @return the type of the JSON value
+            Value type                | return value
+            ------------------------- | -------------------------
+            null                      | value_t::null
+            boolean                   | value_t::boolean
+            string                    | value_t::string
+            number (integer)          | value_t::number_integer
+            number (unsigned integer) | value_t::number_unsigned
+            number (floating-point)   | value_t::number_float
+            object                    | value_t::object
+            array                     | value_t::array
+            discarded                 | value_t::discarded
+
+    @complexity Constant.
+
+    @exceptionsafety No-throw guarantee: this member function never throws
+    exceptions.
+
+    @liveexample{The following code exemplifies `type()` for all JSON
+    types.,type}
+
+    @sa @ref operator value_t() -- return the type of the JSON value (implicit)
+    @sa @ref type_name() -- return the type as string
+
+    @since version 1.0.0
+    */
+    value_t type() const noexcept
+    {
+        return m_type;
+    }
+
+    /*!
+    @brief return whether type is primitive
+
+    This function returns true if and only if the JSON type is primitive
+    (string, number, boolean, or null).
+
+    @return `true` if type is primitive (string, number, boolean, or null),
+    `false` otherwise.
+
+    @complexity Constant.
+
+    @exceptionsafety No-throw guarantee: this member function never throws
+    exceptions.
+
+    @liveexample{The following code exemplifies `is_primitive()` for all JSON
+    types.,is_primitive}
+
+    @sa @ref is_structured() -- returns whether JSON value is structured
+    @sa @ref is_null() -- returns whether JSON value is `null`
+    @sa @ref is_string() -- returns whether JSON value is a string
+    @sa @ref is_boolean() -- returns whether JSON value is a boolean
+    @sa @ref is_number() -- returns whether JSON value is a number
+
+    @since version 1.0.0
+    */
+    bool is_primitive() const noexcept
+    {
+        return is_null() or is_string() or is_boolean() or is_number();
+    }
+
+    /*!
+    @brief return whether type is structured
+
+    This function returns true if and only if the JSON type is structured
+    (array or object).
+
+    @return `true` if type is structured (array or object), `false` otherwise.
+
+    @complexity Constant.
+
+    @exceptionsafety No-throw guarantee: this member function never throws
+    exceptions.
+
+    @liveexample{The following code exemplifies `is_structured()` for all JSON
+    types.,is_structured}
+
+    @sa @ref is_primitive() -- returns whether value is primitive
+    @sa @ref is_array() -- returns whether value is an array
+    @sa @ref is_object() -- returns whether value is an object
+
+    @since version 1.0.0
+    */
+    bool is_structured() const noexcept
+    {
+        return is_array() or is_object();
+    }
+
+    /*!
+    @brief return whether value is null
+
+    This function returns true if and only if the JSON value is null.
+
+    @return `true` if type is null, `false` otherwise.
+
+    @complexity Constant.
+
+    @exceptionsafety No-throw guarantee: this member function never throws
+    exceptions.
+
+    @liveexample{The following code exemplifies `is_null()` for all JSON
+    types.,is_null}
+
+    @since version 1.0.0
+    */
+    bool is_null() const noexcept
+    {
+        return (m_type == value_t::null);
+    }
+
+    /*!
+    @brief return whether value is a boolean
+
+    This function returns true if and only if the JSON value is a boolean.
+
+    @return `true` if type is boolean, `false` otherwise.
+
+    @complexity Constant.
+
+    @exceptionsafety No-throw guarantee: this member function never throws
+    exceptions.
+
+    @liveexample{The following code exemplifies `is_boolean()` for all JSON
+    types.,is_boolean}
+
+    @since version 1.0.0
+    */
+    bool is_boolean() const noexcept
+    {
+        return (m_type == value_t::boolean);
+    }
+
+    /*!
+    @brief return whether value is a number
+
+    This function returns true if and only if the JSON value is a number. This
+    includes both integer (signed and unsigned) and floating-point values.
+
+    @return `true` if type is number (regardless whether integer, unsigned
+    integer or floating-type), `false` otherwise.
+
+    @complexity Constant.
+
+    @exceptionsafety No-throw guarantee: this member function never throws
+    exceptions.
+
+    @liveexample{The following code exemplifies `is_number()` for all JSON
+    types.,is_number}
+
+    @sa @ref is_number_integer() -- check if value is an integer or unsigned
+    integer number
+    @sa @ref is_number_unsigned() -- check if value is an unsigned integer
+    number
+    @sa @ref is_number_float() -- check if value is a floating-point number
+
+    @since version 1.0.0
+    */
+    bool is_number() const noexcept
+    {
+        return is_number_integer() or is_number_float();
+    }
+
+    /*!
+    @brief return whether value is an integer number
+
+    This function returns true if and only if the JSON value is a signed or
+    unsigned integer number. This excludes floating-point values.
+
+    @return `true` if type is an integer or unsigned integer number, `false`
+    otherwise.
+
+    @complexity Constant.
+
+    @exceptionsafety No-throw guarantee: this member function never throws
+    exceptions.
+
+    @liveexample{The following code exemplifies `is_number_integer()` for all
+    JSON types.,is_number_integer}
+
+    @sa @ref is_number() -- check if value is a number
+    @sa @ref is_number_unsigned() -- check if value is an unsigned integer
+    number
+    @sa @ref is_number_float() -- check if value is a floating-point number
+
+    @since version 1.0.0
+    */
+    bool is_number_integer() const noexcept
+    {
+        return (m_type == value_t::number_integer or m_type == value_t::number_unsigned);
+    }
+
+    /*!
+    @brief return whether value is an unsigned integer number
+
+    This function returns true if and only if the JSON value is an unsigned
+    integer number. This excludes floating-point and signed integer values.
+
+    @return `true` if type is an unsigned integer number, `false` otherwise.
+
+    @complexity Constant.
+
+    @exceptionsafety No-throw guarantee: this member function never throws
+    exceptions.
+
+    @liveexample{The following code exemplifies `is_number_unsigned()` for all
+    JSON types.,is_number_unsigned}
+
+    @sa @ref is_number() -- check if value is a number
+    @sa @ref is_number_integer() -- check if value is an integer or unsigned
+    integer number
+    @sa @ref is_number_float() -- check if value is a floating-point number
+
+    @since version 2.0.0
+    */
+    bool is_number_unsigned() const noexcept
+    {
+        return (m_type == value_t::number_unsigned);
+    }
+
+    /*!
+    @brief return whether value is a floating-point number
+
+    This function returns true if and only if the JSON value is a
+    floating-point number. This excludes signed and unsigned integer values.
+
+    @return `true` if type is a floating-point number, `false` otherwise.
+
+    @complexity Constant.
+
+    @exceptionsafety No-throw guarantee: this member function never throws
+    exceptions.
+
+    @liveexample{The following code exemplifies `is_number_float()` for all
+    JSON types.,is_number_float}
+
+    @sa @ref is_number() -- check if value is number
+    @sa @ref is_number_integer() -- check if value is an integer number
+    @sa @ref is_number_unsigned() -- check if value is an unsigned integer
+    number
+
+    @since version 1.0.0
+    */
+    bool is_number_float() const noexcept
+    {
+        return (m_type == value_t::number_float);
+    }
+
+    /*!
+    @brief return whether value is an object
+
+    This function returns true if and only if the JSON value is an object.
+
+    @return `true` if type is object, `false` otherwise.
+
+    @complexity Constant.
+
+    @exceptionsafety No-throw guarantee: this member function never throws
+    exceptions.
+
+    @liveexample{The following code exemplifies `is_object()` for all JSON
+    types.,is_object}
+
+    @since version 1.0.0
+    */
+    bool is_object() const noexcept
+    {
+        return (m_type == value_t::object);
+    }
+
+    /*!
+    @brief return whether value is an array
+
+    This function returns true if and only if the JSON value is an array.
+
+    @return `true` if type is array, `false` otherwise.
+
+    @complexity Constant.
+
+    @exceptionsafety No-throw guarantee: this member function never throws
+    exceptions.
+
+    @liveexample{The following code exemplifies `is_array()` for all JSON
+    types.,is_array}
+
+    @since version 1.0.0
+    */
+    bool is_array() const noexcept
+    {
+        return (m_type == value_t::array);
+    }
+
+    /*!
+    @brief return whether value is a string
+
+    This function returns true if and only if the JSON value is a string.
+
+    @return `true` if type is string, `false` otherwise.
+
+    @complexity Constant.
+
+    @exceptionsafety No-throw guarantee: this member function never throws
+    exceptions.
+
+    @liveexample{The following code exemplifies `is_string()` for all JSON
+    types.,is_string}
+
+    @since version 1.0.0
+    */
+    bool is_string() const noexcept
+    {
+        return (m_type == value_t::string);
+    }
+
+    /*!
+    @brief return whether value is discarded
+
+    This function returns true if and only if the JSON value was discarded
+    during parsing with a callback function (see @ref parser_callback_t).
+
+    @note This function will always be `false` for JSON values after parsing.
+    That is, discarded values can only occur during parsing, but will be
+    removed when inside a structured value or replaced by null in other cases.
+
+    @return `true` if type is discarded, `false` otherwise.
+
+    @complexity Constant.
+
+    @exceptionsafety No-throw guarantee: this member function never throws
+    exceptions.
+
+    @liveexample{The following code exemplifies `is_discarded()` for all JSON
+    types.,is_discarded}
+
+    @since version 1.0.0
+    */
+    bool is_discarded() const noexcept
+    {
+        return (m_type == value_t::discarded);
+    }
+
+    /*!
+    @brief return the type of the JSON value (implicit)
+
+    Implicitly return the type of the JSON value as a value from the @ref
+    value_t enumeration.
+
+    @return the type of the JSON value
+
+    @complexity Constant.
+
+    @exceptionsafety No-throw guarantee: this member function never throws
+    exceptions.
+
+    @liveexample{The following code exemplifies the @ref value_t operator for
+    all JSON types.,operator__value_t}
+
+    @sa @ref type() -- return the type of the JSON value (explicit)
+    @sa @ref type_name() -- return the type as string
+
+    @since version 1.0.0
+    */
+    operator value_t() const noexcept
+    {
+        return m_type;
+    }
+
+    /// @}
+
+  private:
+    //////////////////
+    // value access //
+    //////////////////
+
+    /// get a boolean (explicit)
+    bool get_impl(bool* /*unused*/) const
+    {
+        if (JSON_LIKELY(is_boolean()))
+        {
+            return m_value.boolean;
+        }
+
+        JSON_THROW(type_error::create(302, "type must be boolean, but is", type_name()));
+    }
+
+    /// get a pointer to the value (object)
+    object_t* get_impl_ptr(object_t* /*unused*/) noexcept
+    {
+        return is_object() ? m_value.object : nullptr;
+    }
+
+    /// get a pointer to the value (object)
+    const object_t* get_impl_ptr(const object_t* /*unused*/) const noexcept
+    {
+        return is_object() ? m_value.object : nullptr;
+    }
+
+    /// get a pointer to the value (array)
+    array_t* get_impl_ptr(array_t* /*unused*/) noexcept
+    {
+        return is_array() ? m_value.array : nullptr;
+    }
+
+    /// get a pointer to the value (array)
+    const array_t* get_impl_ptr(const array_t* /*unused*/) const noexcept
+    {
+        return is_array() ? m_value.array : nullptr;
+    }
+
+    /// get a pointer to the value (string)
+    std::string* get_impl_ptr(std::string* /*unused*/) noexcept
+    {
+        return is_string() ? m_value.string : nullptr;
+    }
+
+    /// get a pointer to the value (string)
+    const std::string* get_impl_ptr(const std::string* /*unused*/) const noexcept
+    {
+        return is_string() ? m_value.string : nullptr;
+    }
+
+    /// get a pointer to the value (boolean)
+    bool* get_impl_ptr(bool* /*unused*/) noexcept
+    {
+        return is_boolean() ? &m_value.boolean : nullptr;
+    }
+
+    /// get a pointer to the value (boolean)
+    const bool* get_impl_ptr(const bool* /*unused*/) const noexcept
+    {
+        return is_boolean() ? &m_value.boolean : nullptr;
+    }
+
+    /// get a pointer to the value (integer number)
+    int64_t* get_impl_ptr(int64_t* /*unused*/) noexcept
+    {
+        return is_number_integer() ? &m_value.number_integer : nullptr;
+    }
+
+    /// get a pointer to the value (integer number)
+    const int64_t* get_impl_ptr(const int64_t* /*unused*/) const noexcept
+    {
+        return is_number_integer() ? &m_value.number_integer : nullptr;
+    }
+
+    /// get a pointer to the value (unsigned number)
+    uint64_t* get_impl_ptr(uint64_t* /*unused*/) noexcept
+    {
+        return is_number_unsigned() ? &m_value.number_unsigned : nullptr;
+    }
+
+    /// get a pointer to the value (unsigned number)
+    const uint64_t* get_impl_ptr(const uint64_t* /*unused*/) const noexcept
+    {
+        return is_number_unsigned() ? &m_value.number_unsigned : nullptr;
+    }
+
+    /// get a pointer to the value (floating-point number)
+    double* get_impl_ptr(double* /*unused*/) noexcept
+    {
+        return is_number_float() ? &m_value.number_float : nullptr;
+    }
+
+    /// get a pointer to the value (floating-point number)
+    const double* get_impl_ptr(const double* /*unused*/) const noexcept
+    {
+        return is_number_float() ? &m_value.number_float : nullptr;
+    }
+
+    /*!
+    @brief helper function to implement get_ref()
+
+    This function helps to implement get_ref() without code duplication for
+    const and non-const overloads
+
+    @tparam ThisType will be deduced as `json` or `const json`
+
+    @throw type_error.303 if ReferenceType does not match underlying value
+    type of the current JSON
+    */
+    template<typename ReferenceType, typename ThisType>
+    static ReferenceType get_ref_impl(ThisType& obj)
+    {
+        // delegate the call to get_ptr<>()
+        auto ptr = obj.template get_ptr<typename std::add_pointer<ReferenceType>::type>();
+
+        if (JSON_LIKELY(ptr != nullptr))
+        {
+            return *ptr;
+        }
+
+        JSON_THROW(type_error::create(303, "incompatible ReferenceType for get_ref, actual type is", obj.type_name()));
+    }
+
+  public:
+    /// @name value access
+    /// Direct access to the stored value of a JSON value.
+    /// @{
+
+    /*!
+    @brief get special-case overload
+
+    This overloads avoids a lot of template boilerplate, it can be seen as the
+    identity method
+
+    @tparam BasicJsonType == @ref json
+
+    @return a copy of *this
+
+    @complexity Constant.
+
+    @since version 2.1.0
+    */
+    template<typename BasicJsonType, detail::enable_if_t<
+                 std::is_same<typename std::remove_const<BasicJsonType>::type, json_t>::value,
+                 int> = 0>
+    json get() const
+    {
+        return *this;
+    }
+
+    /*!
+    @brief get a value (explicit)
+
+    Explicit type conversion between the JSON value and a compatible value
+    which is [CopyConstructible](http://en.cppreference.com/w/cpp/concept/CopyConstructible)
+    and [DefaultConstructible](http://en.cppreference.com/w/cpp/concept/DefaultConstructible).
+    The value is converted by calling the @ref json_serializer<ValueType>
+    `from_json()` method.
+
+    The function is equivalent to executing
+    @code {.cpp}
+    ValueType ret;
+    adl_serializer<ValueType, void>::from_json(*this, ret);
+    return ret;
+    @endcode
+
+    This overloads is chosen if:
+    - @a ValueType is not @ref json,
+    - @ref json_serializer<ValueType> has a `from_json()` method of the form
+      `void from_json(const json&, ValueType&)`, and
+    - @ref json_serializer<ValueType> does not have a `from_json()` method of
+      the form `ValueType from_json(const json&)`
+
+    @tparam ValueTypeCV the provided value type
+    @tparam ValueType the returned value type
+
+    @return copy of the JSON value, converted to @a ValueType
+
+    @throw what @ref json_serializer<ValueType> `from_json()` method throws
+
+    @liveexample{The example below shows several conversions from JSON values
+    to other types. There a few things to note: (1) Floating-point numbers can
+    be converted to integers\, (2) A JSON array can be converted to a standard
+    `std::vector<short>`\, (3) A JSON object can be converted to C++
+    associative containers such as `std::unordered_map<std::string\,
+    json>`.,get__ValueType_const}
+
+    @since version 2.1.0
+    */
+    template<typename ValueTypeCV, typename ValueType = detail::uncvref_t<ValueTypeCV>,
+             detail::enable_if_t <
+                 not detail::is_json<ValueType>::value and
+                 detail::has_from_json<json_t, ValueType>::value and
+                 not detail::has_non_default_from_json<json_t, ValueType>::value,
+                 int> = 0>
+    ValueType get() const noexcept(noexcept(
+                                       adl_serializer<ValueType, void>::from_json(std::declval<const json_t&>(), std::declval<ValueType&>())))
+    {
+        // we cannot static_assert on ValueTypeCV being non-const, because
+        // there is support for get<const json_t>(), which is why we
+        // still need the uncvref
+        static_assert(not std::is_reference<ValueTypeCV>::value,
+                      "get() cannot be used with reference types, you might want to use get_ref()");
+        static_assert(std::is_default_constructible<ValueType>::value,
+                      "types must be DefaultConstructible when used with get()");
+
+        ValueType ret;
+        adl_serializer<ValueType, void>::from_json(*this, ret);
+        return ret;
+    }
+
+    /*!
+    @brief get a value (explicit); special case
+
+    Explicit type conversion between the JSON value and a compatible value
+    which is **not** [CopyConstructible](http://en.cppreference.com/w/cpp/concept/CopyConstructible)
+    and **not** [DefaultConstructible](http://en.cppreference.com/w/cpp/concept/DefaultConstructible).
+    The value is converted by calling the @ref json_serializer<ValueType>
+    `from_json()` method.
+
+    The function is equivalent to executing
+    @code {.cpp}
+    return adl_serializer<ValueTypeCV, void>::from_json(*this);
+    @endcode
+
+    This overloads is chosen if:
+    - @a ValueType is not @ref json and
+    - @ref json_serializer<ValueType> has a `from_json()` method of the form
+      `ValueType from_json(const json&)`
+
+    @note If @ref json_serializer<ValueType> has both overloads of
+    `from_json()`, this one is chosen.
+
+    @tparam ValueTypeCV the provided value type
+    @tparam ValueType the returned value type
+
+    @return copy of the JSON value, converted to @a ValueType
+
+    @throw what @ref json_serializer<ValueType> `from_json()` method throws
+
+    @since version 2.1.0
+    */
+    template<typename ValueTypeCV, typename ValueType = detail::uncvref_t<ValueTypeCV>,
+             detail::enable_if_t<not std::is_same<json_t, ValueType>::value and
+                                 detail::has_non_default_from_json<json_t, ValueType>::value,
+                                 int> = 0>
+    ValueType get() const noexcept(noexcept(
+                                       adl_serializer<ValueTypeCV, void>::from_json(std::declval<const json_t&>())))
+    {
+        static_assert(not std::is_reference<ValueTypeCV>::value,
+                      "get() cannot be used with reference types, you might want to use get_ref()");
+        return adl_serializer<ValueTypeCV, void>::from_json(*this);
+    }
+
+    /*!
+    @brief get a pointer value (explicit)
+
+    Explicit pointer access to the internally stored JSON value. No copies are
+    made.
+
+    @warning The pointer becomes invalid if the underlying JSON object
+    changes.
+
+    @tparam PointerType pointer type; must be a pointer to @ref array_t, @ref
+    object_t, `std::string`, bool, int64_t, uint64_t, or double.
+
+    @return pointer to the internally stored JSON value if the requested
+    pointer type @a PointerType fits to the JSON value; `nullptr` otherwise
+
+    @complexity Constant.
+
+    @liveexample{The example below shows how pointers to internal values of a
+    JSON value can be requested. Note that no type conversions are made and a
+    `nullptr` is returned if the value and the requested pointer type does not
+    match.,get__PointerType}
+
+    @sa @ref get_ptr() for explicit pointer-member access
+
+    @since version 1.0.0
+    */
+    template<typename PointerType, typename std::enable_if<
+                 std::is_pointer<PointerType>::value, int>::type = 0>
+    PointerType get() noexcept
+    {
+        // delegate the call to get_ptr
+        return get_ptr<PointerType>();
+    }
+
+    /*!
+    @brief get a pointer value (explicit)
+    @copydoc get()
+    */
+    template<typename PointerType, typename std::enable_if<
+                 std::is_pointer<PointerType>::value, int>::type = 0>
+    const PointerType get() const noexcept
+    {
+        // delegate the call to get_ptr
+        return get_ptr<PointerType>();
+    }
+
+    /*!
+    @brief get a pointer value (implicit)
+
+    Implicit pointer access to the internally stored JSON value. No copies are
+    made.
+
+    @warning Writing data to the pointee of the result yields an undefined
+    state.
+
+    @tparam PointerType pointer type; must be a pointer to @ref array_t, @ref
+    object_t, `std::string`, bool, int64_t,
+    uint64_t, or double. Enforced by a static assertion.
+
+    @return pointer to the internally stored JSON value if the requested
+    pointer type @a PointerType fits to the JSON value; `nullptr` otherwise
+
+    @complexity Constant.
+
+    @liveexample{The example below shows how pointers to internal values of a
+    JSON value can be requested. Note that no type conversions are made and a
+    `nullptr` is returned if the value and the requested pointer type does not
+    match.,get_ptr}
+
+    @since version 1.0.0
+    */
+    template<typename PointerType, typename std::enable_if<
+                 std::is_pointer<PointerType>::value, int>::type = 0>
+    PointerType get_ptr() noexcept
+    {
+        // get the type of the PointerType (remove pointer and const)
+        using pointee_t = typename std::remove_const<typename
+                          std::remove_pointer<typename
+                          std::remove_const<PointerType>::type>::type>::type;
+        // make sure the type matches the allowed types
+        static_assert(
+            std::is_same<object_t, pointee_t>::value
+            or std::is_same<array_t, pointee_t>::value
+            or std::is_same<std::string, pointee_t>::value
+            or std::is_same<bool, pointee_t>::value
+            or std::is_same<int64_t, pointee_t>::value
+            or std::is_same<uint64_t, pointee_t>::value
+            or std::is_same<double, pointee_t>::value
+            , "incompatible pointer type");
+
+        // delegate the call to get_impl_ptr<>()
+        return get_impl_ptr(static_cast<PointerType>(nullptr));
+    }
+
+    /*!
+    @brief get a pointer value (implicit)
+    @copydoc get_ptr()
+    */
+    template<typename PointerType, typename std::enable_if<
+                 std::is_pointer<PointerType>::value and
+                 std::is_const<typename std::remove_pointer<PointerType>::type>::value, int>::type = 0>
+    const PointerType get_ptr() const noexcept
+    {
+        // get the type of the PointerType (remove pointer and const)
+        using pointee_t = typename std::remove_const<typename
+                          std::remove_pointer<typename
+                          std::remove_const<PointerType>::type>::type>::type;
+        // make sure the type matches the allowed types
+        static_assert(
+            std::is_same<object_t, pointee_t>::value
+            or std::is_same<array_t, pointee_t>::value
+            or std::is_same<std::string, pointee_t>::value
+            or std::is_same<bool, pointee_t>::value
+            or std::is_same<int64_t, pointee_t>::value
+            or std::is_same<uint64_t, pointee_t>::value
+            or std::is_same<double, pointee_t>::value
+            , "incompatible pointer type");
+
+        // delegate the call to get_impl_ptr<>() const
+        return get_impl_ptr(static_cast<PointerType>(nullptr));
+    }
+
+    /*!
+    @brief get a reference value (implicit)
+
+    Implicit reference access to the internally stored JSON value. No copies
+    are made.
+
+    @warning Writing data to the referee of the result yields an undefined
+    state.
+
+    @tparam ReferenceType reference type; must be a reference to @ref array_t,
+    @ref object_t, std::string, bool, int64_t, or
+    double. Enforced by static assertion.
+
+    @return reference to the internally stored JSON value if the requested
+    reference type @a ReferenceType fits to the JSON value; throws
+    type_error.303 otherwise
+
+    @throw type_error.303 in case passed type @a ReferenceType is incompatible
+    with the stored JSON value; see example below
+
+    @complexity Constant.
+
+    @liveexample{The example shows several calls to `get_ref()`.,get_ref}
+
+    @since version 1.1.0
+    */
+    template<typename ReferenceType, typename std::enable_if<
+                 std::is_reference<ReferenceType>::value, int>::type = 0>
+    ReferenceType get_ref()
+    {
+        // delegate call to get_ref_impl
+        return get_ref_impl<ReferenceType>(*this);
+    }
+
+    /*!
+    @brief get a reference value (implicit)
+    @copydoc get_ref()
+    */
+    template<typename ReferenceType, typename std::enable_if<
+                 std::is_reference<ReferenceType>::value and
+                 std::is_const<typename std::remove_reference<ReferenceType>::type>::value, int>::type = 0>
+    ReferenceType get_ref() const
+    {
+        // delegate call to get_ref_impl
+        return get_ref_impl<ReferenceType>(*this);
+    }
+
+    /*!
+    @brief get a value (implicit)
+
+    Implicit type conversion between the JSON value and a compatible value.
+    The call is realized by calling @ref get() const.
+
+    @tparam ValueType non-pointer type compatible to the JSON value, for
+    instance `int` for JSON integer numbers, `bool` for JSON booleans, or
+    `std::vector` types for JSON arrays. The character type of `std::string`
+    as well as an initializer list of this type is excluded to avoid
+    ambiguities as these types implicitly convert to `std::string`.
+
+    @return copy of the JSON value, converted to type @a ValueType
+
+    @throw type_error.302 in case passed type @a ValueType is incompatible
+    to the JSON value type (e.g., the JSON value is of type boolean, but a
+    string is requested); see example below
+
+    @complexity Linear in the size of the JSON value.
+
+    @liveexample{The example below shows several conversions from JSON values
+    to other types. There a few things to note: (1) Floating-point numbers can
+    be converted to integers\, (2) A JSON array can be converted to a standard
+    `std::vector<short>`\, (3) A JSON object can be converted to C++
+    associative containers such as `std::unordered_map<std::string\,
+    json>`.,operator__ValueType}
+
+    @since version 1.0.0
+    */
+    template < typename ValueType, typename std::enable_if <
+                   not std::is_pointer<ValueType>::value and
+                   not std::is_same<ValueType, detail::json_ref<json>>::value and
+                   not std::is_same<ValueType, std::string::value_type>::value and
+                   not detail::is_json<ValueType>::value
+#ifndef _MSC_VER  // fix for issue #167 operator<< ambiguity under VS2015
+                   and not std::is_same<ValueType, std::initializer_list<std::string::value_type>>::value
+#endif
+                   and not std::is_same<ValueType, typename std::string_view>::value
+                   , int >::type = 0 >
+    operator ValueType() const
+    {
+        // delegate the call to get<>() const
+        return get<ValueType>();
+    }
+
+    /// @}
+
+
+    ////////////////////
+    // element access //
+    ////////////////////
+
+    /// @name element access
+    /// Access to the JSON value.
+    /// @{
+
+    /*!
+    @brief access specified array element with bounds checking
+
+    Returns a reference to the element at specified location @a idx, with
+    bounds checking.
+
+    @param[in] idx  index of the element to access
+
+    @return reference to the element at index @a idx
+
+    @throw type_error.304 if the JSON value is not an array; in this case,
+    calling `at` with an index makes no sense. See example below.
+    @throw out_of_range.401 if the index @a idx is out of range of the array;
+    that is, `idx >= size()`. See example below.
+
+    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
+    changes in the JSON value.
+
+    @complexity Constant.
+
+    @since version 1.0.0
+
+    @liveexample{The example below shows how array elements can be read and
+    written using `at()`. It also demonstrates the different exceptions that
+    can be thrown.,at__size_type}
+    */
+    reference at(size_type idx);
+
+    /*!
+    @brief access specified array element with bounds checking
+
+    Returns a const reference to the element at specified location @a idx,
+    with bounds checking.
+
+    @param[in] idx  index of the element to access
+
+    @return const reference to the element at index @a idx
+
+    @throw type_error.304 if the JSON value is not an array; in this case,
+    calling `at` with an index makes no sense. See example below.
+    @throw out_of_range.401 if the index @a idx is out of range of the array;
+    that is, `idx >= size()`. See example below.
+
+    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
+    changes in the JSON value.
+
+    @complexity Constant.
+
+    @since version 1.0.0
+
+    @liveexample{The example below shows how array elements can be read using
+    `at()`. It also demonstrates the different exceptions that can be thrown.,
+    at__size_type_const}
+    */
+    const_reference at(size_type idx) const;
+
+    /*!
+    @brief access specified object element with bounds checking
+
+    Returns a reference to the element at with specified key @a key, with
+    bounds checking.
+
+    @param[in] key  key of the element to access
+
+    @return reference to the element at key @a key
+
+    @throw type_error.304 if the JSON value is not an object; in this case,
+    calling `at` with a key makes no sense. See example below.
+    @throw out_of_range.403 if the key @a key is is not stored in the object;
+    that is, `find(key) == end()`. See example below.
+
+    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
+    changes in the JSON value.
+
+    @complexity Logarithmic in the size of the container.
+
+    @sa @ref operator[](const typename object_t::key_type&) for unchecked
+    access by reference
+    @sa @ref value() for access by value with a default value
+
+    @since version 1.0.0
+
+    @liveexample{The example below shows how object elements can be read and
+    written using `at()`. It also demonstrates the different exceptions that
+    can be thrown.,at__object_t_key_type}
+    */
+    reference at(std::string_view key);
+
+    /*!
+    @brief access specified object element with bounds checking
+
+    Returns a const reference to the element at with specified key @a key,
+    with bounds checking.
+
+    @param[in] key  key of the element to access
+
+    @return const reference to the element at key @a key
+
+    @throw type_error.304 if the JSON value is not an object; in this case,
+    calling `at` with a key makes no sense. See example below.
+    @throw out_of_range.403 if the key @a key is is not stored in the object;
+    that is, `find(key) == end()`. See example below.
+
+    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
+    changes in the JSON value.
+
+    @complexity Logarithmic in the size of the container.
+
+    @sa @ref operator[](const typename object_t::key_type&) for unchecked
+    access by reference
+    @sa @ref value() for access by value with a default value
+
+    @since version 1.0.0
+
+    @liveexample{The example below shows how object elements can be read using
+    `at()`. It also demonstrates the different exceptions that can be thrown.,
+    at__object_t_key_type_const}
+    */
+    const_reference at(std::string_view key) const;
+
+    /*!
+    @brief access specified array element
+
+    Returns a reference to the element at specified location @a idx.
+
+    @note If @a idx is beyond the range of the array (i.e., `idx >= size()`),
+    then the array is silently filled up with `null` values to make `idx` a
+    valid reference to the last stored element.
+
+    @param[in] idx  index of the element to access
+
+    @return reference to the element at index @a idx
+
+    @throw type_error.305 if the JSON value is not an array or null; in that
+    cases, using the [] operator with an index makes no sense.
+
+    @complexity Constant if @a idx is in the range of the array. Otherwise
+    linear in `idx - size()`.
+
+    @liveexample{The example below shows how array elements can be read and
+    written using `[]` operator. Note the addition of `null`
+    values.,operatorarray__size_type}
+
+    @since version 1.0.0
+    */
+    reference operator[](size_type idx);
+
+    /*!
+    @brief access specified array element
+
+    Returns a const reference to the element at specified location @a idx.
+
+    @param[in] idx  index of the element to access
+
+    @return const reference to the element at index @a idx
+
+    @throw type_error.305 if the JSON value is not an array; in that case,
+    using the [] operator with an index makes no sense.
+
+    @complexity Constant.
+
+    @liveexample{The example below shows how array elements can be read using
+    the `[]` operator.,operatorarray__size_type_const}
+
+    @since version 1.0.0
+    */
+    const_reference operator[](size_type idx) const;
+
+    /*!
+    @brief access specified object element
+
+    Returns a reference to the element at with specified key @a key.
+
+    @note If @a key is not found in the object, then it is silently added to
+    the object and filled with a `null` value to make `key` a valid reference.
+    In case the value was `null` before, it is converted to an object.
+
+    @param[in] key  key of the element to access
+
+    @return reference to the element at key @a key
+
+    @throw type_error.305 if the JSON value is not an object or null; in that
+    cases, using the [] operator with a key makes no sense.
+
+    @complexity Logarithmic in the size of the container.
+
+    @liveexample{The example below shows how object elements can be read and
+    written using the `[]` operator.,operatorarray__key_type}
+
+    @sa @ref at(const typename object_t::key_type&) for access by reference
+    with range checking
+    @sa @ref value() for access by value with a default value
+
+    @since version 1.0.0
+    */
+    reference operator[](std::string_view key);
+
+    /*!
+    @brief read-only access specified object element
+
+    Returns a const reference to the element at with specified key @a key. No
+    bounds checking is performed.
+
+    @warning If the element with key @a key does not exist, the behavior is
+    undefined.
+
+    @param[in] key  key of the element to access
+
+    @return const reference to the element at key @a key
+
+    @pre The element with key @a key must exist. **This precondition is
+         enforced with an assertion.**
+
+    @throw type_error.305 if the JSON value is not an object; in that case,
+    using the [] operator with a key makes no sense.
+
+    @complexity Logarithmic in the size of the container.
+
+    @liveexample{The example below shows how object elements can be read using
+    the `[]` operator.,operatorarray__key_type_const}
+
+    @sa @ref at(const typename object_t::key_type&) for access by reference
+    with range checking
+    @sa @ref value() for access by value with a default value
+
+    @since version 1.0.0
+    */
+    const_reference operator[](std::string_view key) const;
+
+    /*!
+    @brief access specified object element
+
+    Returns a reference to the element at with specified key @a key.
+
+    @note If @a key is not found in the object, then it is silently added to
+    the object and filled with a `null` value to make `key` a valid reference.
+    In case the value was `null` before, it is converted to an object.
+
+    @param[in] key  key of the element to access
+
+    @return reference to the element at key @a key
+
+    @throw type_error.305 if the JSON value is not an object or null; in that
+    cases, using the [] operator with a key makes no sense.
+
+    @complexity Logarithmic in the size of the container.
+
+    @liveexample{The example below shows how object elements can be read and
+    written using the `[]` operator.,operatorarray__key_type}
+
+    @sa @ref at(const typename object_t::key_type&) for access by reference
+    with range checking
+    @sa @ref value() for access by value with a default value
+
+    @since version 1.1.0
+    */
+    template<typename T>
+    reference operator[](T* key)
+    {
+        // implicitly convert null to object
+        if (is_null())
+        {
+            m_type = value_t::object;
+            m_value = value_t::object;
+            assert_invariant();
+        }
+
+        // at only works for objects
+        if (JSON_LIKELY(is_object()))
+        {
+            return m_value.object->operator[](key);
+        }
+
+        JSON_THROW(type_error::create(305, "cannot use operator[] with", type_name()));
+    }
+
+    /*!
+    @brief read-only access specified object element
+
+    Returns a const reference to the element at with specified key @a key. No
+    bounds checking is performed.
+
+    @warning If the element with key @a key does not exist, the behavior is
+    undefined.
+
+    @param[in] key  key of the element to access
+
+    @return const reference to the element at key @a key
+
+    @pre The element with key @a key must exist. **This precondition is
+         enforced with an assertion.**
+
+    @throw type_error.305 if the JSON value is not an object; in that case,
+    using the [] operator with a key makes no sense.
+
+    @complexity Logarithmic in the size of the container.
+
+    @liveexample{The example below shows how object elements can be read using
+    the `[]` operator.,operatorarray__key_type_const}
+
+    @sa @ref at(const typename object_t::key_type&) for access by reference
+    with range checking
+    @sa @ref value() for access by value with a default value
+
+    @since version 1.1.0
+    */
+    template<typename T>
+    const_reference operator[](T* key) const
+    {
+        // at only works for objects
+        if (JSON_LIKELY(is_object()))
+        {
+            assert(m_value.object->find(key) != m_value.object->end());
+            return m_value.object->find(key)->second;
+        }
+
+        JSON_THROW(type_error::create(305, "cannot use operator[] with", type_name()));
+    }
+
+    /*!
+    @brief access specified object element with default value
+
+    Returns either a copy of an object's element at the specified key @a key
+    or a given default value if no element with key @a key exists.
+
+    The function is basically equivalent to executing
+    @code {.cpp}
+    try {
+        return at(key);
+    } catch(out_of_range) {
+        return default_value;
+    }
+    @endcode
+
+    @note Unlike @ref at(const typename object_t::key_type&), this function
+    does not throw if the given key @a key was not found.
+
+    @note Unlike @ref operator[](const typename object_t::key_type& key), this
+    function does not implicitly add an element to the position defined by @a
+    key. This function is furthermore also applicable to const objects.
+
+    @param[in] key  key of the element to access
+    @param[in] default_value  the value to return if @a key is not found
+
+    @tparam ValueType type compatible to JSON values, for instance `int` for
+    JSON integer numbers, `bool` for JSON booleans, or `std::vector` types for
+    JSON arrays. Note the type of the expected value at @a key and the default
+    value @a default_value must be compatible.
+
+    @return copy of the element at key @a key or @a default_value if @a key
+    is not found
+
+    @throw type_error.306 if the JSON value is not an object; in that case,
+    using `value()` with a key makes no sense.
+
+    @complexity Logarithmic in the size of the container.
+
+    @liveexample{The example below shows how object elements can be queried
+    with a default value.,json__value}
+
+    @sa @ref at(const typename object_t::key_type&) for access by reference
+    with range checking
+    @sa @ref operator[](const typename object_t::key_type&) for unchecked
+    access by reference
+
+    @since version 1.0.0
+    */
+    template<class ValueType, typename std::enable_if<
+                 std::is_convertible<json_t, ValueType>::value, int>::type = 0>
+    ValueType value(std::string_view key, const ValueType& default_value) const
+    {
+        // at only works for objects
+        if (JSON_LIKELY(is_object()))
+        {
+            // if key is found, return value and given default value otherwise
+            const auto it = find(key);
+            if (it != end())
+            {
+                return *it;
+            }
+
+            return default_value;
+        }
+
+        JSON_THROW(type_error::create(306, "cannot use value() with", type_name()));
+    }
+
+    /*!
+    @brief overload for a default value of type const char*
+    @copydoc json::value(const typename object_t::key_type&, ValueType) const
+    */
+    std::string value(std::string_view key, const char* default_value) const
+    {
+        return value(key, std::string(default_value));
+    }
+
+    /*!
+    @brief access specified object element via JSON Pointer with default value
+
+    Returns either a copy of an object's element at the specified key @a key
+    or a given default value if no element with key @a key exists.
+
+    The function is basically equivalent to executing
+    @code {.cpp}
+    try {
+        return at(ptr);
+    } catch(out_of_range) {
+        return default_value;
+    }
+    @endcode
+
+    @note Unlike @ref at(const json_pointer&), this function does not throw
+    if the given key @a key was not found.
+
+    @param[in] ptr  a JSON pointer to the element to access
+    @param[in] default_value  the value to return if @a ptr found no value
+
+    @tparam ValueType type compatible to JSON values, for instance `int` for
+    JSON integer numbers, `bool` for JSON booleans, or `std::vector` types for
+    JSON arrays. Note the type of the expected value at @a key and the default
+    value @a default_value must be compatible.
+
+    @return copy of the element at key @a key or @a default_value if @a key
+    is not found
+
+    @throw type_error.306 if the JSON value is not an object; in that case,
+    using `value()` with a key makes no sense.
+
+    @complexity Logarithmic in the size of the container.
+
+    @liveexample{The example below shows how object elements can be queried
+    with a default value.,json__value_ptr}
+
+    @sa @ref operator[](const json_pointer&) for unchecked access by reference
+
+    @since version 2.0.2
+    */
+    template<class ValueType, typename std::enable_if<
+                 std::is_convertible<json_t, ValueType>::value, int>::type = 0>
+    ValueType value(const json_pointer& ptr, const ValueType& default_value) const
+    {
+        // at only works for objects
+        if (JSON_LIKELY(is_object()))
+        {
+            // if pointer resolves a value, return it or use default value
+            JSON_TRY
+            {
+                return ptr.get_checked(this);
+            }
+            JSON_CATCH (out_of_range&)
+            {
+                return default_value;
+            }
+        }
+
+        JSON_THROW(type_error::create(306, "cannot use value() with", type_name()));
+    }
+
+    /*!
+    @brief overload for a default value of type const char*
+    @copydoc json::value(const json_pointer&, ValueType) const
+    */
+    std::string value(const json_pointer& ptr, const char* default_value) const
+    {
+        return value(ptr, std::string(default_value));
+    }
+
+    /*!
+    @brief access the first element
+
+    Returns a reference to the first element in the container. For a JSON
+    container `c`, the expression `c.front()` is equivalent to `*c.begin()`.
+
+    @return In case of a structured type (array or object), a reference to the
+    first element is returned. In case of number, string, or boolean values, a
+    reference to the value is returned.
+
+    @complexity Constant.
+
+    @pre The JSON value must not be `null` (would throw `std::out_of_range`)
+    or an empty array or object (undefined behavior, **guarded by
+    assertions**).
+    @post The JSON value remains unchanged.
+
+    @throw invalid_iterator.214 when called on `null` value
+
+    @liveexample{The following code shows an example for `front()`.,front}
+
+    @sa @ref back() -- access the last element
+
+    @since version 1.0.0
+    */
+    reference front()
+    {
+        return *begin();
+    }
+
+    /*!
+    @copydoc json::front()
+    */
+    const_reference front() const
+    {
+        return *cbegin();
+    }
+
+    /*!
+    @brief access the last element
+
+    Returns a reference to the last element in the container. For a JSON
+    container `c`, the expression `c.back()` is equivalent to
+    @code {.cpp}
+    auto tmp = c.end();
+    --tmp;
+    return *tmp;
+    @endcode
+
+    @return In case of a structured type (array or object), a reference to the
+    last element is returned. In case of number, string, or boolean values, a
+    reference to the value is returned.
+
+    @complexity Constant.
+
+    @pre The JSON value must not be `null` (would throw `std::out_of_range`)
+    or an empty array or object (undefined behavior, **guarded by
+    assertions**).
+    @post The JSON value remains unchanged.
+
+    @throw invalid_iterator.214 when called on a `null` value. See example
+    below.
+
+    @liveexample{The following code shows an example for `back()`.,back}
+
+    @sa @ref front() -- access the first element
+
+    @since version 1.0.0
+    */
+    reference back()
+    {
+        auto tmp = end();
+        --tmp;
+        return *tmp;
+    }
+
+    /*!
+    @copydoc json::back()
+    */
+    const_reference back() const
+    {
+        auto tmp = cend();
+        --tmp;
+        return *tmp;
+    }
+
+    /*!
+    @brief remove element given an iterator
+
+    Removes the element specified by iterator @a pos. The iterator @a pos must
+    be valid and dereferenceable. Thus the `end()` iterator (which is valid,
+    but is not dereferenceable) cannot be used as a value for @a pos.
+
+    If called on a primitive type other than `null`, the resulting JSON value
+    will be `null`.
+
+    @param[in] pos iterator to the element to remove
+
+    @tparam IteratorType an @ref iterator or @ref const_iterator
+
+    @post Invalidates iterators and references at or after the point of the
+    erase, including the `end()` iterator.
+
+    @throw type_error.307 if called on a `null` value; example: `"cannot use
+    erase() with null"`
+    @throw invalid_iterator.202 if called on an iterator which does not belong
+    to the current JSON value; example: `"iterator does not fit current
+    value"`
+    @throw invalid_iterator.205 if called on a primitive type with invalid
+    iterator (i.e., any iterator which is not `begin()`); example: `"iterator
+    out of range"`
+
+    @complexity The complexity depends on the type:
+    - objects: amortized constant
+    - arrays: linear in distance between @a pos and the end of the container
+    - strings: linear in the length of the string
+    - other types: constant
+
+    @liveexample{The example shows the result of `erase()` for different JSON
+    types.,erase__IteratorType}
+
+    @sa @ref erase(IteratorType, IteratorType) -- removes the elements in
+    the given range
+    @sa @ref erase(std::string_view) -- removes the element
+    from an object at the given key
+    @sa @ref erase(const size_type) -- removes the element from an array at
+    the given index
+
+    @since version 1.0.0
+    */
+    template<class IteratorType, typename std::enable_if<
+                 std::is_same<IteratorType, typename json_t::iterator>::value or
+                 std::is_same<IteratorType, typename json_t::const_iterator>::value, int>::type
+             = 0>
+    void erase(IteratorType pos)
+    {
+        // make sure iterator fits the current value
+        if (JSON_UNLIKELY(this != pos.m_object))
+        {
+            JSON_THROW(invalid_iterator::create(202, "iterator does not fit current value"));
+        }
+
+        switch (m_type)
+        {
+            case value_t::boolean:
+            case value_t::number_float:
+            case value_t::number_integer:
+            case value_t::number_unsigned:
+            case value_t::string:
+            {
+                if (JSON_UNLIKELY(not pos.m_it.primitive_iterator.is_begin()))
+                {
+                    JSON_THROW(invalid_iterator::create(205, "iterator out of range"));
+                }
+
+                if (is_string())
+                {
+                    std::allocator<std::string> alloc;
+					std::allocator_traits<decltype(alloc)>::destroy(alloc, m_value.string);
+					std::allocator_traits<decltype(alloc)>::deallocate(alloc, m_value.string, 1);
+                    m_value.string = nullptr;
+                }
+
+                m_type = value_t::null;
+                assert_invariant();
+                break;
+            }
+
+            case value_t::object:
+            {
+                m_value.object->erase(pos.m_it.object_iterator);
+                break;
+            }
+
+            case value_t::array:
+            {
+                m_value.array->erase(pos.m_it.array_iterator);
+                break;
+            }
+
+            default:
+                JSON_THROW(type_error::create(307, "cannot use erase() with", type_name()));
+        }
+    }
+
+    /*!
+    @brief remove elements given an iterator range
+
+    Removes the element specified by the range `[first; last)`. The iterator
+    @a first does not need to be dereferenceable if `first == last`: erasing
+    an empty range is a no-op.
+
+    If called on a primitive type other than `null`, the resulting JSON value
+    will be `null`.
+
+    @param[in] first iterator to the beginning of the range to remove
+    @param[in] last iterator past the end of the range to remove
+    @return Iterator following the last removed element. If the iterator @a
+    second refers to the last element, the `end()` iterator is returned.
+
+    @tparam IteratorType an @ref iterator or @ref const_iterator
+
+    @post Invalidates iterators and references at or after the point of the
+    erase, including the `end()` iterator.
+
+    @throw type_error.307 if called on a `null` value; example: `"cannot use
+    erase() with null"`
+    @throw invalid_iterator.203 if called on iterators which does not belong
+    to the current JSON value; example: `"iterators do not fit current value"`
+    @throw invalid_iterator.204 if called on a primitive type with invalid
+    iterators (i.e., if `first != begin()` and `last != end()`); example:
+    `"iterators out of range"`
+
+    @complexity The complexity depends on the type:
+    - objects: `log(size()) + std::distance(first, last)`
+    - arrays: linear in the distance between @a first and @a last, plus linear
+      in the distance between @a last and end of the container
+    - strings: linear in the length of the string
+    - other types: constant
+
+    @liveexample{The example shows the result of `erase()` for different JSON
+    types.,erase__IteratorType_IteratorType}
+
+    @sa @ref erase(IteratorType) -- removes the element at a given position
+    @sa @ref erase(const typename object_t::key_type&) -- removes the element
+    from an object at the given key
+    @sa @ref erase(const size_type) -- removes the element from an array at
+    the given index
+
+    @since version 1.0.0
+    */
+    template<class IteratorType, typename std::enable_if<
+                 std::is_same<IteratorType, typename json_t::iterator>::value or
+                 std::is_same<IteratorType, typename json_t::const_iterator>::value, int>::type
+             = 0>
+    IteratorType erase(IteratorType first, IteratorType last)
+    {
+        // make sure iterator fits the current value
+        if (JSON_UNLIKELY(this != first.m_object or this != last.m_object))
+        {
+            JSON_THROW(invalid_iterator::create(203, "iterators do not fit current value"));
+        }
+
+        IteratorType result = end();
+
+        switch (m_type)
+        {
+            case value_t::boolean:
+            case value_t::number_float:
+            case value_t::number_integer:
+            case value_t::number_unsigned:
+            case value_t::string:
+            {
+                if (JSON_LIKELY(not first.m_it.primitive_iterator.is_begin()
+                                or not last.m_it.primitive_iterator.is_end()))
+                {
+                    JSON_THROW(invalid_iterator::create(204, "iterators out of range"));
+                }
+
+                if (is_string())
+                {
+                    std::allocator<std::string> alloc;
+					std::allocator_traits<decltype(alloc)>::destroy(alloc, m_value.string);
+					std::allocator_traits<decltype(alloc)>::deallocate(alloc, m_value.string, 1);
+                    m_value.string = nullptr;
+                }
+
+                m_type = value_t::null;
+                assert_invariant();
+                break;
+            }
+
+            case value_t::array:
+            {
+                result.m_it.array_iterator = m_value.array->erase(first.m_it.array_iterator,
+                                             last.m_it.array_iterator);
+                break;
+            }
+
+            default:
+                JSON_THROW(type_error::create(307, "cannot use erase() with", type_name()));
+        }
+
+        return result;
+    }
+
+    /*!
+    @brief remove element from a JSON object given a key
+
+    Removes elements from a JSON object with the key value @a key.
+
+    @param[in] key value of the elements to remove
+
+    @return Number of elements removed. If @a ObjectType is the default
+    `std::map` type, the return value will always be `0` (@a key was not
+    found) or `1` (@a key was found).
+
+    @post References and iterators to the erased elements are invalidated.
+    Other references and iterators are not affected.
+
+    @throw type_error.307 when called on a type other than JSON object;
+    example: `"cannot use erase() with null"`
+
+    @complexity `log(size()) + count(key)`
+
+    @liveexample{The example shows the effect of `erase()`.,erase__key_type}
+
+    @sa @ref erase(IteratorType) -- removes the element at a given position
+    @sa @ref erase(IteratorType, IteratorType) -- removes the elements in
+    the given range
+    @sa @ref erase(const size_type) -- removes the element from an array at
+    the given index
+
+    @since version 1.0.0
+    */
+    size_type erase(std::string_view key);
+
+    /*!
+    @brief remove element from a JSON array given an index
+
+    Removes element from a JSON array at the index @a idx.
+
+    @param[in] idx index of the element to remove
+
+    @throw type_error.307 when called on a type other than JSON object;
+    example: `"cannot use erase() with null"`
+    @throw out_of_range.401 when `idx >= size()`; example: `"array index 17
+    is out of range"`
+
+    @complexity Linear in distance between @a idx and the end of the container.
+
+    @liveexample{The example shows the effect of `erase()`.,erase__size_type}
+
+    @sa @ref erase(IteratorType) -- removes the element at a given position
+    @sa @ref erase(IteratorType, IteratorType) -- removes the elements in
+    the given range
+    @sa @ref erase(const typename object_t::key_type&) -- removes the element
+    from an object at the given key
+
+    @since version 1.0.0
+    */
+    void erase(const size_type idx);
+
+    /// @}
+
+
+    ////////////
+    // lookup //
+    ////////////
+
+    /// @name lookup
+    /// @{
+
+    /*!
+    @brief find an element in a JSON object
+
+    Finds an element in a JSON object with key equivalent to @a key. If the
+    element is not found or the JSON value is not an object, end() is
+    returned.
+
+    @note This method always returns @ref end() when executed on a JSON type
+          that is not an object.
+
+    @param[in] key key value of the element to search for.
+
+    @return Iterator to an element with key equivalent to @a key. If no such
+    element is found or the JSON value is not an object, past-the-end (see
+    @ref end()) iterator is returned.
+
+    @complexity Logarithmic in the size of the JSON object.
+
+    @liveexample{The example shows how `find()` is used.,find__key_type}
+
+    @since version 1.0.0
+    */
+    iterator find(std::string_view key);
+
+    /*!
+    @brief find an element in a JSON object
+    @copydoc find(KeyT&&)
+    */
+    const_iterator find(std::string_view key) const;
+
+    /*!
+    @brief returns the number of occurrences of a key in a JSON object
+
+    Returns the number of elements with key @a key. If ObjectType is the
+    default `std::map` type, the return value will always be `0` (@a key was
+    not found) or `1` (@a key was found).
+
+    @note This method always returns `0` when executed on a JSON type that is
+          not an object.
+
+    @param[in] key key value of the element to count
+
+    @return Number of elements with key @a key. If the JSON value is not an
+    object, the return value will be `0`.
+
+    @complexity Logarithmic in the size of the JSON object.
+
+    @liveexample{The example shows how `count()` is used.,count}
+
+    @since version 1.0.0
+    */
+    size_type count(std::string_view key) const;
+
+    /// @}
+
+
+    ///////////////
+    // iterators //
+    ///////////////
+
+    /// @name iterators
+    /// @{
+
+    /*!
+    @brief returns an iterator to the first element
+
+    Returns an iterator to the first element.
+
+    @image html range-begin-end.svg "Illustration from cppreference.com"
+
+    @return iterator to the first element
+
+    @complexity Constant.
+
+    @requirement This function helps `json` satisfying the
+    [Container](http://en.cppreference.com/w/cpp/concept/Container)
+    requirements:
+    - The complexity is constant.
+
+    @liveexample{The following code shows an example for `begin()`.,begin}
+
+    @sa @ref cbegin() -- returns a const iterator to the beginning
+    @sa @ref end() -- returns an iterator to the end
+    @sa @ref cend() -- returns a const iterator to the end
+
+    @since version 1.0.0
+    */
+    iterator begin() noexcept
+    {
+        iterator result(this);
+        result.set_begin();
+        return result;
+    }
+
+    /*!
+    @copydoc json::cbegin()
+    */
+    const_iterator begin() const noexcept
+    {
+        return cbegin();
+    }
+
+    /*!
+    @brief returns a const iterator to the first element
+
+    Returns a const iterator to the first element.
+
+    @image html range-begin-end.svg "Illustration from cppreference.com"
+
+    @return const iterator to the first element
+
+    @complexity Constant.
+
+    @requirement This function helps `json` satisfying the
+    [Container](http://en.cppreference.com/w/cpp/concept/Container)
+    requirements:
+    - The complexity is constant.
+    - Has the semantics of `const_cast<const json&>(*this).begin()`.
+
+    @liveexample{The following code shows an example for `cbegin()`.,cbegin}
+
+    @sa @ref begin() -- returns an iterator to the beginning
+    @sa @ref end() -- returns an iterator to the end
+    @sa @ref cend() -- returns a const iterator to the end
+
+    @since version 1.0.0
+    */
+    const_iterator cbegin() const noexcept
+    {
+        const_iterator result(this);
+        result.set_begin();
+        return result;
+    }
+
+    /*!
+    @brief returns an iterator to one past the last element
+
+    Returns an iterator to one past the last element.
+
+    @image html range-begin-end.svg "Illustration from cppreference.com"
+
+    @return iterator one past the last element
+
+    @complexity Constant.
+
+    @requirement This function helps `json` satisfying the
+    [Container](http://en.cppreference.com/w/cpp/concept/Container)
+    requirements:
+    - The complexity is constant.
+
+    @liveexample{The following code shows an example for `end()`.,end}
+
+    @sa @ref cend() -- returns a const iterator to the end
+    @sa @ref begin() -- returns an iterator to the beginning
+    @sa @ref cbegin() -- returns a const iterator to the beginning
+
+    @since version 1.0.0
+    */
+    iterator end() noexcept
+    {
+        iterator result(this);
+        result.set_end();
+        return result;
+    }
+
+    /*!
+    @copydoc json::cend()
+    */
+    const_iterator end() const noexcept
+    {
+        return cend();
+    }
+
+    /*!
+    @brief returns a const iterator to one past the last element
+
+    Returns a const iterator to one past the last element.
+
+    @image html range-begin-end.svg "Illustration from cppreference.com"
+
+    @return const iterator one past the last element
+
+    @complexity Constant.
+
+    @requirement This function helps `json` satisfying the
+    [Container](http://en.cppreference.com/w/cpp/concept/Container)
+    requirements:
+    - The complexity is constant.
+    - Has the semantics of `const_cast<const json&>(*this).end()`.
+
+    @liveexample{The following code shows an example for `cend()`.,cend}
+
+    @sa @ref end() -- returns an iterator to the end
+    @sa @ref begin() -- returns an iterator to the beginning
+    @sa @ref cbegin() -- returns a const iterator to the beginning
+
+    @since version 1.0.0
+    */
+    const_iterator cend() const noexcept
+    {
+        const_iterator result(this);
+        result.set_end();
+        return result;
+    }
+
+    /*!
+    @brief returns an iterator to the reverse-beginning
+
+    Returns an iterator to the reverse-beginning; that is, the last element.
+
+    @image html range-rbegin-rend.svg "Illustration from cppreference.com"
+
+    @complexity Constant.
+
+    @requirement This function helps `json` satisfying the
+    [ReversibleContainer](http://en.cppreference.com/w/cpp/concept/ReversibleContainer)
+    requirements:
+    - The complexity is constant.
+    - Has the semantics of `reverse_iterator(end())`.
+
+    @liveexample{The following code shows an example for `rbegin()`.,rbegin}
+
+    @sa @ref crbegin() -- returns a const reverse iterator to the beginning
+    @sa @ref rend() -- returns a reverse iterator to the end
+    @sa @ref crend() -- returns a const reverse iterator to the end
+
+    @since version 1.0.0
+    */
+    reverse_iterator rbegin() noexcept
+    {
+        return reverse_iterator(end());
+    }
+
+    /*!
+    @copydoc json::crbegin()
+    */
+    const_reverse_iterator rbegin() const noexcept
+    {
+        return crbegin();
+    }
+
+    /*!
+    @brief returns an iterator to the reverse-end
+
+    Returns an iterator to the reverse-end; that is, one before the first
+    element.
+
+    @image html range-rbegin-rend.svg "Illustration from cppreference.com"
+
+    @complexity Constant.
+
+    @requirement This function helps `json` satisfying the
+    [ReversibleContainer](http://en.cppreference.com/w/cpp/concept/ReversibleContainer)
+    requirements:
+    - The complexity is constant.
+    - Has the semantics of `reverse_iterator(begin())`.
+
+    @liveexample{The following code shows an example for `rend()`.,rend}
+
+    @sa @ref crend() -- returns a const reverse iterator to the end
+    @sa @ref rbegin() -- returns a reverse iterator to the beginning
+    @sa @ref crbegin() -- returns a const reverse iterator to the beginning
+
+    @since version 1.0.0
+    */
+    reverse_iterator rend() noexcept
+    {
+        return reverse_iterator(begin());
+    }
+
+    /*!
+    @copydoc json::crend()
+    */
+    const_reverse_iterator rend() const noexcept
+    {
+        return crend();
+    }
+
+    /*!
+    @brief returns a const reverse iterator to the last element
+
+    Returns a const iterator to the reverse-beginning; that is, the last
+    element.
+
+    @image html range-rbegin-rend.svg "Illustration from cppreference.com"
+
+    @complexity Constant.
+
+    @requirement This function helps `json` satisfying the
+    [ReversibleContainer](http://en.cppreference.com/w/cpp/concept/ReversibleContainer)
+    requirements:
+    - The complexity is constant.
+    - Has the semantics of `const_cast<const json&>(*this).rbegin()`.
+
+    @liveexample{The following code shows an example for `crbegin()`.,crbegin}
+
+    @sa @ref rbegin() -- returns a reverse iterator to the beginning
+    @sa @ref rend() -- returns a reverse iterator to the end
+    @sa @ref crend() -- returns a const reverse iterator to the end
+
+    @since version 1.0.0
+    */
+    const_reverse_iterator crbegin() const noexcept
+    {
+        return const_reverse_iterator(cend());
+    }
+
+    /*!
+    @brief returns a const reverse iterator to one before the first
+
+    Returns a const reverse iterator to the reverse-end; that is, one before
+    the first element.
+
+    @image html range-rbegin-rend.svg "Illustration from cppreference.com"
+
+    @complexity Constant.
+
+    @requirement This function helps `json` satisfying the
+    [ReversibleContainer](http://en.cppreference.com/w/cpp/concept/ReversibleContainer)
+    requirements:
+    - The complexity is constant.
+    - Has the semantics of `const_cast<const json&>(*this).rend()`.
+
+    @liveexample{The following code shows an example for `crend()`.,crend}
+
+    @sa @ref rend() -- returns a reverse iterator to the end
+    @sa @ref rbegin() -- returns a reverse iterator to the beginning
+    @sa @ref crbegin() -- returns a const reverse iterator to the beginning
+
+    @since version 1.0.0
+    */
+    const_reverse_iterator crend() const noexcept
+    {
+        return const_reverse_iterator(cbegin());
+    }
+
+  public:
+    /*!
+    @brief helper to access iterator member functions in range-based for
+
+    This function allows to access @ref iterator::key() and @ref
+    iterator::value() during range-based for loops. In these loops, a
+    reference to the JSON values is returned, so there is no access to the
+    underlying iterator.
+
+    For loop without `items()` function:
+
+    @code{cpp}
+    for (auto it = j_object.begin(); it != j_object.end(); ++it)
+    {
+        std::cout << "key: " << it.key() << ", value:" << it.value() << '\n';
+    }
+    @endcode
+
+    Range-based for loop without `items()` function:
+
+    @code{cpp}
+    for (auto it : j_object)
+    {
+        // "it" is of type json::reference and has no key() member
+        std::cout << "value: " << it << '\n';
+    }
+    @endcode
+
+    Range-based for loop with `items()` function:
+
+    @code{cpp}
+    for (auto it : j_object.items())
+    {
+        std::cout << "key: " << it.key() << ", value:" << it.value() << '\n';
+    }
+    @endcode
+
+    @note When iterating over an array, `key()` will return the index of the
+          element as string (see example). For primitive types (e.g., numbers),
+          `key()` returns an empty string.
+
+    @return iteration proxy object wrapping @a ref with an interface to use in
+            range-based for loops
+
+    @liveexample{The following code shows how the function is used.,items}
+
+    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
+    changes in the JSON value.
+
+    @complexity Constant.
+
+    @since version 3.x.x.
+    */
+    iteration_proxy<iterator> items() noexcept
+    {
+        return iteration_proxy<iterator>(*this);
+    }
+
+    /*!
+    @copydoc items()
+    */
+    iteration_proxy<const_iterator> items() const noexcept
+    {
+        return iteration_proxy<const_iterator>(*this);
+    }
+
+    /// @}
+
+
+    //////////////
+    // capacity //
+    //////////////
+
+    /// @name capacity
+    /// @{
+
+    /*!
+    @brief checks whether the container is empty.
+
+    Checks if a JSON value has no elements (i.e. whether its @ref size is `0`).
+
+    @return The return value depends on the different types and is
+            defined as follows:
+            Value type  | return value
+            ----------- | -------------
+            null        | `true`
+            boolean     | `false`
+            string      | `false`
+            number      | `false`
+            object      | result of function `object_t::empty()`
+            array       | result of function `array_t::empty()`
+
+    @liveexample{The following code uses `empty()` to check if a JSON
+    object contains any elements.,empty}
+
+    @complexity Constant, as long as @ref array_t and @ref object_t satisfy
+    the Container concept; that is, their `empty()` functions have constant
+    complexity.
+
+    @iterators No changes.
+
+    @exceptionsafety No-throw guarantee: this function never throws exceptions.
+
+    @note This function does not return whether a string stored as JSON value
+    is empty - it returns whether the JSON container itself is empty which is
+    false in the case of a string.
+
+    @requirement This function helps `json` satisfying the
+    [Container](http://en.cppreference.com/w/cpp/concept/Container)
+    requirements:
+    - The complexity is constant.
+    - Has the semantics of `begin() == end()`.
+
+    @sa @ref size() -- returns the number of elements
+
+    @since version 1.0.0
+    */
+    bool empty() const noexcept;
+
+    /*!
+    @brief returns the number of elements
+
+    Returns the number of elements in a JSON value.
+
+    @return The return value depends on the different types and is
+            defined as follows:
+            Value type  | return value
+            ----------- | -------------
+            null        | `0`
+            boolean     | `1`
+            string      | `1`
+            number      | `1`
+            object      | result of function object_t::size()
+            array       | result of function array_t::size()
+
+    @liveexample{The following code calls `size()` on the different value
+    types.,size}
+
+    @complexity Constant, as long as @ref array_t and @ref object_t satisfy
+    the Container concept; that is, their size() functions have constant
+    complexity.
+
+    @iterators No changes.
+
+    @exceptionsafety No-throw guarantee: this function never throws exceptions.
+
+    @note This function does not return the length of a string stored as JSON
+    value - it returns the number of elements in the JSON value which is 1 in
+    the case of a string.
+
+    @requirement This function helps `json` satisfying the
+    [Container](http://en.cppreference.com/w/cpp/concept/Container)
+    requirements:
+    - The complexity is constant.
+    - Has the semantics of `std::distance(begin(), end())`.
+
+    @sa @ref empty() -- checks whether the container is empty
+    @sa @ref max_size() -- returns the maximal number of elements
+
+    @since version 1.0.0
+    */
+    size_type size() const noexcept;
+
+    /*!
+    @brief returns the maximum possible number of elements
+
+    Returns the maximum number of elements a JSON value is able to hold due to
+    system or library implementation limitations, i.e. `std::distance(begin(),
+    end())` for the JSON value.
+
+    @return The return value depends on the different types and is
+            defined as follows:
+            Value type  | return value
+            ----------- | -------------
+            null        | `0` (same as `size()`)
+            boolean     | `1` (same as `size()`)
+            string      | `1` (same as `size()`)
+            number      | `1` (same as `size()`)
+            object      | result of function `object_t::max_size()`
+            array       | result of function `array_t::max_size()`
+
+    @liveexample{The following code calls `max_size()` on the different value
+    types. Note the output is implementation specific.,max_size}
+
+    @complexity Constant, as long as @ref array_t and @ref object_t satisfy
+    the Container concept; that is, their `max_size()` functions have constant
+    complexity.
+
+    @iterators No changes.
+
+    @exceptionsafety No-throw guarantee: this function never throws exceptions.
+
+    @requirement This function helps `json` satisfying the
+    [Container](http://en.cppreference.com/w/cpp/concept/Container)
+    requirements:
+    - The complexity is constant.
+    - Has the semantics of returning `b.size()` where `b` is the largest
+      possible JSON value.
+
+    @sa @ref size() -- returns the number of elements
+
+    @since version 1.0.0
+    */
+    size_type max_size() const noexcept;
+
+    /// @}
+
+
+    ///////////////
+    // modifiers //
+    ///////////////
+
+    /// @name modifiers
+    /// @{
+
+    /*!
+    @brief clears the contents
+
+    Clears the content of a JSON value and resets it to the default value as
+    if @ref json(value_t) would have been called with the current value
+    type from @ref type():
+
+    Value type  | initial value
+    ----------- | -------------
+    null        | `null`
+    boolean     | `false`
+    string      | `""`
+    number      | `0`
+    object      | `{}`
+    array       | `[]`
+
+    @post Has the same effect as calling
+    @code {.cpp}
+    *this = json(type());
+    @endcode
+
+    @liveexample{The example below shows the effect of `clear()` to different
+    JSON types.,clear}
+
+    @complexity Linear in the size of the JSON value.
+
+    @iterators All iterators, pointers and references related to this container
+               are invalidated.
+
+    @exceptionsafety No-throw guarantee: this function never throws exceptions.
+
+    @sa @ref json(value_t) -- constructor that creates an object with the
+        same value than calling `clear()`
+
+    @since version 1.0.0
+    */
+    void clear() noexcept;
+
+    /*!
+    @brief add an object to an array
+
+    Appends the given element @a val to the end of the JSON value. If the
+    function is called on a JSON null value, an empty array is created before
+    appending @a val.
+
+    @param[in] val the value to add to the JSON array
+
+    @throw type_error.308 when called on a type other than JSON array or
+    null; example: `"cannot use push_back() with number"`
+
+    @complexity Amortized constant.
+
+    @liveexample{The example shows how `push_back()` and `+=` can be used to
+    add elements to a JSON array. Note how the `null` value was silently
+    converted to a JSON array.,push_back}
+
+    @since version 1.0.0
+    */
+    void push_back(json&& val);
+
+    /*!
+    @brief add an object to an array
+    @copydoc push_back(json&&)
+    */
+    reference operator+=(json&& val)
+    {
+        push_back(std::move(val));
+        return *this;
+    }
+
+    /*!
+    @brief add an object to an array
+    @copydoc push_back(json&&)
+    */
+    void push_back(const json& val);
+
+    /*!
+    @brief add an object to an array
+    @copydoc push_back(json&&)
+    */
+    reference operator+=(const json& val)
+    {
+        push_back(val);
+        return *this;
+    }
+
+    /*!
+    @brief add an object to an object
+
+    Inserts the given element @a val to the JSON object. If the function is
+    called on a JSON null value, an empty object is created before inserting
+    @a val.
+
+    @param[in] val the value to add to the JSON object
+
+    @throw type_error.308 when called on a type other than JSON object or
+    null; example: `"cannot use push_back() with number"`
+
+    @complexity Logarithmic in the size of the container, O(log(`size()`)).
+
+    @liveexample{The example shows how `push_back()` and `+=` can be used to
+    add elements to a JSON object. Note how the `null` value was silently
+    converted to a JSON object.,push_back__object_t__value}
+
+    @since version 1.0.0
+    */
+    template<typename T, typename U>
+    void push_back(const std::pair<T, U>& val)
+    {
+        // push_back only works for null objects or objects
+        if (JSON_UNLIKELY(not(is_null() or is_object())))
+        {
+            JSON_THROW(type_error::create(308, "cannot use push_back() with", type_name()));
+        }
+
+        // transform null object into an object
+        if (is_null())
+        {
+            m_type = value_t::object;
+            m_value = value_t::object;
+            assert_invariant();
+        }
+
+        // add element to array
+        m_value.object->try_emplace(val.first, std::move(val.second));
+    }
+
+    /*!
+    @brief add an object to an object
+    @copydoc push_back(const typename object_t::value_type&)
+    */
+    template<typename T, typename U>
+    reference operator+=(const std::pair<T, U>& val)
+    {
+        push_back(val);
+        return *this;
+    }
+
+    /*!
+    @brief add an object to an object
+
+    This function allows to use `push_back` with an initializer list. In case
+
+    1. the current value is an object,
+    2. the initializer list @a init contains only two elements, and
+    3. the first element of @a init is a string,
+
+    @a init is converted into an object element and added using
+    @ref push_back(const typename object_t::value_type&). Otherwise, @a init
+    is converted to a JSON value and added using @ref push_back(json&&).
+
+    @param[in] init  an initializer list
+
+    @complexity Linear in the size of the initializer list @a init.
+
+    @note This function is required to resolve an ambiguous overload error,
+          because pairs like `{"key", "value"}` can be both interpreted as
+          `object_t::value_type` or `std::initializer_list<json>`, see
+          https://github.com/nlohmann/json/issues/235 for more information.
+
+    @liveexample{The example shows how initializer lists are treated as
+    objects when possible.,push_back__initializer_list}
+    */
+    void push_back(initializer_list_t init);
+
+    /*!
+    @brief add an object to an object
+    @copydoc push_back(initializer_list_t)
+    */
+    reference operator+=(initializer_list_t init)
+    {
+        push_back(init);
+        return *this;
+    }
+
+    /*!
+    @brief add an object to an array
+
+    Creates a JSON value from the passed parameters @a args to the end of the
+    JSON value. If the function is called on a JSON null value, an empty array
+    is created before appending the value created from @a args.
+
+    @param[in] args arguments to forward to a constructor of @ref json
+    @tparam Args compatible types to create a @ref json object
+
+    @throw type_error.311 when called on a type other than JSON array or
+    null; example: `"cannot use emplace_back() with number"`
+
+    @complexity Amortized constant.
+
+    @liveexample{The example shows how `push_back()` can be used to add
+    elements to a JSON array. Note how the `null` value was silently converted
+    to a JSON array.,emplace_back}
+
+    @since version 2.0.8
+    */
+    template<class... Args>
+    void emplace_back(Args&& ... args)
+    {
+        // emplace_back only works for null objects or arrays
+        if (JSON_UNLIKELY(not(is_null() or is_array())))
+        {
+            JSON_THROW(type_error::create(311, "cannot use emplace_back() with", type_name()));
+        }
+
+        // transform null object into an array
+        if (is_null())
+        {
+            m_type = value_t::array;
+            m_value = value_t::array;
+            assert_invariant();
+        }
+
+        // add element to array (perfect forwarding)
+        m_value.array->emplace_back(std::forward<Args>(args)...);
+    }
+
+    /*!
+    @brief add an object to an object if key does not exist
+
+    Inserts a new element into a JSON object constructed in-place with the
+    given @a args if there is no element with the key in the container. If the
+    function is called on a JSON null value, an empty object is created before
+    appending the value created from @a args.
+
+    @param[in] args arguments to forward to a constructor of @ref json
+    @tparam Args compatible types to create a @ref json object
+
+    @return a pair consisting of an iterator to the inserted element, or the
+            already-existing element if no insertion happened, and a bool
+            denoting whether the insertion took place.
+
+    @throw type_error.311 when called on a type other than JSON object or
+    null; example: `"cannot use emplace() with number"`
+
+    @complexity Logarithmic in the size of the container, O(log(`size()`)).
+
+    @liveexample{The example shows how `emplace()` can be used to add elements
+    to a JSON object. Note how the `null` value was silently converted to a
+    JSON object. Further note how no value is added if there was already one
+    value stored with the same key.,emplace}
+
+    @since version 2.0.8
+    */
+    template<class... Args>
+    std::pair<iterator, bool> emplace(std::string_view key, Args&& ... args)
+    {
+        // emplace only works for null objects or arrays
+        if (JSON_UNLIKELY(not(is_null() or is_object())))
+        {
+            JSON_THROW(type_error::create(311, "cannot use emplace() with", type_name()));
+        }
+
+        // transform null object into an object
+        if (is_null())
+        {
+            m_type = value_t::object;
+            m_value = value_t::object;
+            assert_invariant();
+        }
+
+        // add element to array (perfect forwarding)
+        auto res = m_value.object->try_emplace(key, std::forward<Args>(args)...);
+        // create result iterator and set iterator to the result of emplace
+        auto it = begin();
+        it.m_it.object_iterator = res.first;
+
+        // return pair of iterator and boolean
+        return {it, res.second};
+    }
+
+    /*!
+    @brief inserts element
+
+    Inserts element @a val before iterator @a pos.
+
+    @param[in] pos iterator before which the content will be inserted; may be
+    the end() iterator
+    @param[in] val element to insert
+    @return iterator pointing to the inserted @a val.
+
+    @throw type_error.309 if called on JSON values other than arrays;
+    example: `"cannot use insert() with string"`
+    @throw invalid_iterator.202 if @a pos is not an iterator of *this;
+    example: `"iterator does not fit current value"`
+
+    @complexity Constant plus linear in the distance between @a pos and end of
+    the container.
+
+    @liveexample{The example shows how `insert()` is used.,insert}
+
+    @since version 1.0.0
+    */
+    iterator insert(const_iterator pos, const json& val);
+
+    /*!
+    @brief inserts element
+    @copydoc insert(const_iterator, const json&)
+    */
+    iterator insert(const_iterator pos, json&& val)
+    {
+        return insert(pos, val);
+    }
+
+    /*!
+    @brief inserts elements
+
+    Inserts @a cnt copies of @a val before iterator @a pos.
+
+    @param[in] pos iterator before which the content will be inserted; may be
+    the end() iterator
+    @param[in] cnt number of copies of @a val to insert
+    @param[in] val element to insert
+    @return iterator pointing to the first element inserted, or @a pos if
+    `cnt==0`
+
+    @throw type_error.309 if called on JSON values other than arrays; example:
+    `"cannot use insert() with string"`
+    @throw invalid_iterator.202 if @a pos is not an iterator of *this;
+    example: `"iterator does not fit current value"`
+
+    @complexity Linear in @a cnt plus linear in the distance between @a pos
+    and end of the container.
+
+    @liveexample{The example shows how `insert()` is used.,insert__count}
+
+    @since version 1.0.0
+    */
+    iterator insert(const_iterator pos, size_type cnt, const json& val);
+
+    /*!
+    @brief inserts elements
+
+    Inserts elements from range `[first, last)` before iterator @a pos.
+
+    @param[in] pos iterator before which the content will be inserted; may be
+    the end() iterator
+    @param[in] first begin of the range of elements to insert
+    @param[in] last end of the range of elements to insert
+
+    @throw type_error.309 if called on JSON values other than arrays; example:
+    `"cannot use insert() with string"`
+    @throw invalid_iterator.202 if @a pos is not an iterator of *this;
+    example: `"iterator does not fit current value"`
+    @throw invalid_iterator.210 if @a first and @a last do not belong to the
+    same JSON value; example: `"iterators do not fit"`
+    @throw invalid_iterator.211 if @a first or @a last are iterators into
+    container for which insert is called; example: `"passed iterators may not
+    belong to container"`
+
+    @return iterator pointing to the first element inserted, or @a pos if
+    `first==last`
+
+    @complexity Linear in `std::distance(first, last)` plus linear in the
+    distance between @a pos and end of the container.
+
+    @liveexample{The example shows how `insert()` is used.,insert__range}
+
+    @since version 1.0.0
+    */
+    iterator insert(const_iterator pos, const_iterator first, const_iterator last);
+
+    /*!
+    @brief inserts elements
+
+    Inserts elements from initializer list @a ilist before iterator @a pos.
+
+    @param[in] pos iterator before which the content will be inserted; may be
+    the end() iterator
+    @param[in] ilist initializer list to insert the values from
+
+    @throw type_error.309 if called on JSON values other than arrays; example:
+    `"cannot use insert() with string"`
+    @throw invalid_iterator.202 if @a pos is not an iterator of *this;
+    example: `"iterator does not fit current value"`
+
+    @return iterator pointing to the first element inserted, or @a pos if
+    `ilist` is empty
+
+    @complexity Linear in `ilist.size()` plus linear in the distance between
+    @a pos and end of the container.
+
+    @liveexample{The example shows how `insert()` is used.,insert__ilist}
+
+    @since version 1.0.0
+    */
+    iterator insert(const_iterator pos, initializer_list_t ilist);
+
+    /*!
+    @brief inserts elements
+
+    Inserts elements from range `[first, last)`.
+
+    @param[in] first begin of the range of elements to insert
+    @param[in] last end of the range of elements to insert
+
+    @throw type_error.309 if called on JSON values other than objects; example:
+    `"cannot use insert() with string"`
+    @throw invalid_iterator.202 if iterator @a first or @a last does does not
+    point to an object; example: `"iterators first and last must point to
+    objects"`
+    @throw invalid_iterator.210 if @a first and @a last do not belong to the
+    same JSON value; example: `"iterators do not fit"`
+
+    @complexity Logarithmic: `O(N*log(size() + N))`, where `N` is the number
+    of elements to insert.
+
+    @liveexample{The example shows how `insert()` is used.,insert__range_object}
+
+    @since version 3.0.0
+    */
+    void insert(const_iterator first, const_iterator last);
+
+    /*!
+    @brief updates a JSON object from another object, overwriting existing keys
+
+    Inserts all values from JSON object @a j and overwrites existing keys.
+
+    @param[in] j  JSON object to read values from
+
+    @throw type_error.312 if called on JSON values other than objects; example:
+    `"cannot use update() with string"`
+
+    @complexity O(N*log(size() + N)), where N is the number of elements to
+                insert.
+
+    @liveexample{The example shows how `update()` is used.,update}
+
+    @sa https://docs.python.org/3.6/library/stdtypes.html#dict.update
+
+    @since version 3.0.0
+    */
+    void update(const_reference j);
+
+    /*!
+    @brief updates a JSON object from another object, overwriting existing keys
+
+    Inserts all values from from range `[first, last)` and overwrites existing
+    keys.
+
+    @param[in] first begin of the range of elements to insert
+    @param[in] last end of the range of elements to insert
+
+    @throw type_error.312 if called on JSON values other than objects; example:
+    `"cannot use update() with string"`
+    @throw invalid_iterator.202 if iterator @a first or @a last does does not
+    point to an object; example: `"iterators first and last must point to
+    objects"`
+    @throw invalid_iterator.210 if @a first and @a last do not belong to the
+    same JSON value; example: `"iterators do not fit"`
+
+    @complexity O(N*log(size() + N)), where N is the number of elements to
+                insert.
+
+    @liveexample{The example shows how `update()` is used__range.,update}
+
+    @sa https://docs.python.org/3.6/library/stdtypes.html#dict.update
+
+    @since version 3.0.0
+    */
+    void update(const_iterator first, const_iterator last);
+
+    /*!
+    @brief exchanges the values
+
+    Exchanges the contents of the JSON value with those of @a other. Does not
+    invoke any move, copy, or swap operations on individual elements. All
+    iterators and references remain valid. The past-the-end iterator is
+    invalidated.
+
+    @param[in,out] other JSON value to exchange the contents with
+
+    @complexity Constant.
+
+    @liveexample{The example below shows how JSON values can be swapped with
+    `swap()`.,swap__reference}
+
+    @since version 1.0.0
+    */
+    void swap(reference other) noexcept (
+        std::is_nothrow_move_constructible<value_t>::value and
+        std::is_nothrow_move_assignable<value_t>::value and
+        std::is_nothrow_move_constructible<json_value>::value and
+        std::is_nothrow_move_assignable<json_value>::value
+    )
+    {
+        std::swap(m_type, other.m_type);
+        std::swap(m_value, other.m_value);
+        assert_invariant();
+    }
+
+    /*!
+    @brief exchanges the values
+
+    Exchanges the contents of a JSON array with those of @a other. Does not
+    invoke any move, copy, or swap operations on individual elements. All
+    iterators and references remain valid. The past-the-end iterator is
+    invalidated.
+
+    @param[in,out] other array to exchange the contents with
+
+    @throw type_error.310 when JSON value is not an array; example: `"cannot
+    use swap() with string"`
+
+    @complexity Constant.
+
+    @liveexample{The example below shows how arrays can be swapped with
+    `swap()`.,swap__std_vector_json}
+
+    @since version 1.0.0
+    */
+    void swap(array_t& other)
+    {
+        // swap only works for arrays
+        if (JSON_LIKELY(is_array()))
+        {
+            std::swap(*(m_value.array), other);
+        }
+        else
+        {
+            JSON_THROW(type_error::create(310, "cannot use swap() with", type_name()));
+        }
+    }
+
+    /*!
+    @brief exchanges the values
+
+    Exchanges the contents of a JSON object with those of @a other. Does not
+    invoke any move, copy, or swap operations on individual elements. All
+    iterators and references remain valid. The past-the-end iterator is
+    invalidated.
+
+    @param[in,out] other object to exchange the contents with
+
+    @throw type_error.310 when JSON value is not an object; example:
+    `"cannot use swap() with string"`
+
+    @complexity Constant.
+
+    @liveexample{The example below shows how objects can be swapped with
+    `swap()`.,swap__object_t}
+
+    @since version 1.0.0
+    */
+    void swap(object_t& other)
+    {
+        // swap only works for objects
+        if (JSON_LIKELY(is_object()))
+        {
+            std::swap(*(m_value.object), other);
+        }
+        else
+        {
+            JSON_THROW(type_error::create(310, "cannot use swap() with", type_name()));
+        }
+    }
+
+    /*!
+    @brief exchanges the values
+
+    Exchanges the contents of a JSON string with those of @a other. Does not
+    invoke any move, copy, or swap operations on individual elements. All
+    iterators and references remain valid. The past-the-end iterator is
+    invalidated.
+
+    @param[in,out] other string to exchange the contents with
+
+    @throw type_error.310 when JSON value is not a string; example: `"cannot
+    use swap() with boolean"`
+
+    @complexity Constant.
+
+    @liveexample{The example below shows how strings can be swapped with
+    `swap()`.,swap__std_string}
+
+    @since version 1.0.0
+    */
+    void swap(std::string& other)
+    {
+        // swap only works for strings
+        if (JSON_LIKELY(is_string()))
+        {
+            std::swap(*(m_value.string), other);
+        }
+        else
+        {
+            JSON_THROW(type_error::create(310, "cannot use swap() with", type_name()));
+        }
+    }
+
+    /// @}
+
+  public:
+    //////////////////////////////////////////
+    // lexicographical comparison operators //
+    //////////////////////////////////////////
+
+    /// @name lexicographical comparison operators
+    /// @{
+
+    /*!
+    @brief comparison: equal
+
+    Compares two JSON values for equality according to the following rules:
+    - Two JSON values are equal if (1) they are from the same type and (2)
+      their stored values are the same according to their respective
+      `operator==`.
+    - Integer and floating-point numbers are automatically converted before
+      comparison. Note than two NaN values are always treated as unequal.
+    - Two JSON null values are equal.
+
+    @note Floating-point inside JSON values numbers are compared with
+    `double::operator==`.
+    To compare floating-point while respecting an epsilon, an alternative
+    [comparison function](https://github.com/mariokonrad/marnav/blob/master/src/marnav/math/floatingpoint.hpp#L34-#L39)
+    could be used, for instance
+    @code {.cpp}
+    template<typename T, typename = typename std::enable_if<std::is_floating_point<T>::value, T>::type>
+    inline bool is_same(T a, T b, T epsilon = std::numeric_limits<T>::epsilon()) noexcept
+    {
+        return std::abs(a - b) <= epsilon;
+    }
+    @endcode
+
+    @note NaN values never compare equal to themselves or to other NaN values.
+
+    @param[in] lhs  first JSON value to consider
+    @param[in] rhs  second JSON value to consider
+    @return whether the values @a lhs and @a rhs are equal
+
+    @exceptionsafety No-throw guarantee: this function never throws exceptions.
+
+    @complexity Linear.
+
+    @liveexample{The example demonstrates comparing several JSON
+    types.,operator__equal}
+
+    @since version 1.0.0
+    */
+    friend bool operator==(const_reference lhs, const_reference rhs) noexcept;
+
+    /*!
+    @brief comparison: equal
+    @copydoc operator==(const_reference, const_reference)
+    */
+    template<typename ScalarType, typename std::enable_if<
+                 std::is_scalar<ScalarType>::value, int>::type = 0>
+    friend bool operator==(const_reference lhs, const ScalarType rhs) noexcept
+    {
+        return (lhs == json(rhs));
+    }
+
+    /*!
+    @brief comparison: equal
+    @copydoc operator==(const_reference, const_reference)
+    */
+    template<typename ScalarType, typename std::enable_if<
+                 std::is_scalar<ScalarType>::value, int>::type = 0>
+    friend bool operator==(const ScalarType lhs, const_reference rhs) noexcept
+    {
+        return (json(lhs) == rhs);
+    }
+
+    /*!
+    @brief comparison: not equal
+
+    Compares two JSON values for inequality by calculating `not (lhs == rhs)`.
+
+    @param[in] lhs  first JSON value to consider
+    @param[in] rhs  second JSON value to consider
+    @return whether the values @a lhs and @a rhs are not equal
+
+    @complexity Linear.
+
+    @exceptionsafety No-throw guarantee: this function never throws exceptions.
+
+    @liveexample{The example demonstrates comparing several JSON
+    types.,operator__notequal}
+
+    @since version 1.0.0
+    */
+    friend bool operator!=(const_reference lhs, const_reference rhs) noexcept
+    {
+        return not (lhs == rhs);
+    }
+
+    /*!
+    @brief comparison: not equal
+    @copydoc operator!=(const_reference, const_reference)
+    */
+    template<typename ScalarType, typename std::enable_if<
+                 std::is_scalar<ScalarType>::value, int>::type = 0>
+    friend bool operator!=(const_reference lhs, const ScalarType rhs) noexcept
+    {
+        return (lhs != json(rhs));
+    }
+
+    /*!
+    @brief comparison: not equal
+    @copydoc operator!=(const_reference, const_reference)
+    */
+    template<typename ScalarType, typename std::enable_if<
+                 std::is_scalar<ScalarType>::value, int>::type = 0>
+    friend bool operator!=(const ScalarType lhs, const_reference rhs) noexcept
+    {
+        return (json(lhs) != rhs);
+    }
+
+    /*!
+    @brief comparison: less than
+
+    Compares whether one JSON value @a lhs is less than another JSON value @a
+    rhs according to the following rules:
+    - If @a lhs and @a rhs have the same type, the values are compared using
+      the default `<` operator.
+    - Integer and floating-point numbers are automatically converted before
+      comparison
+    - In case @a lhs and @a rhs have different types, the values are ignored
+      and the order of the types is considered, see
+      @ref operator<(const value_t, const value_t).
+
+    @param[in] lhs  first JSON value to consider
+    @param[in] rhs  second JSON value to consider
+    @return whether @a lhs is less than @a rhs
+
+    @complexity Linear.
+
+    @exceptionsafety No-throw guarantee: this function never throws exceptions.
+
+    @liveexample{The example demonstrates comparing several JSON
+    types.,operator__less}
+
+    @since version 1.0.0
+    */
+    friend bool operator<(const_reference lhs, const_reference rhs) noexcept;
+
+    /*!
+    @brief comparison: less than
+    @copydoc operator<(const_reference, const_reference)
+    */
+    template<typename ScalarType, typename std::enable_if<
+                 std::is_scalar<ScalarType>::value, int>::type = 0>
+    friend bool operator<(const_reference lhs, const ScalarType rhs) noexcept
+    {
+        return (lhs < json(rhs));
+    }
+
+    /*!
+    @brief comparison: less than
+    @copydoc operator<(const_reference, const_reference)
+    */
+    template<typename ScalarType, typename std::enable_if<
+                 std::is_scalar<ScalarType>::value, int>::type = 0>
+    friend bool operator<(const ScalarType lhs, const_reference rhs) noexcept
+    {
+        return (json(lhs) < rhs);
+    }
+
+    /*!
+    @brief comparison: less than or equal
+
+    Compares whether one JSON value @a lhs is less than or equal to another
+    JSON value by calculating `not (rhs < lhs)`.
+
+    @param[in] lhs  first JSON value to consider
+    @param[in] rhs  second JSON value to consider
+    @return whether @a lhs is less than or equal to @a rhs
+
+    @complexity Linear.
+
+    @exceptionsafety No-throw guarantee: this function never throws exceptions.
+
+    @liveexample{The example demonstrates comparing several JSON
+    types.,operator__greater}
+
+    @since version 1.0.0
+    */
+    friend bool operator<=(const_reference lhs, const_reference rhs) noexcept
+    {
+        return not (rhs < lhs);
+    }
+
+    /*!
+    @brief comparison: less than or equal
+    @copydoc operator<=(const_reference, const_reference)
+    */
+    template<typename ScalarType, typename std::enable_if<
+                 std::is_scalar<ScalarType>::value, int>::type = 0>
+    friend bool operator<=(const_reference lhs, const ScalarType rhs) noexcept
+    {
+        return (lhs <= json(rhs));
+    }
+
+    /*!
+    @brief comparison: less than or equal
+    @copydoc operator<=(const_reference, const_reference)
+    */
+    template<typename ScalarType, typename std::enable_if<
+                 std::is_scalar<ScalarType>::value, int>::type = 0>
+    friend bool operator<=(const ScalarType lhs, const_reference rhs) noexcept
+    {
+        return (json(lhs) <= rhs);
+    }
+
+    /*!
+    @brief comparison: greater than
+
+    Compares whether one JSON value @a lhs is greater than another
+    JSON value by calculating `not (lhs <= rhs)`.
+
+    @param[in] lhs  first JSON value to consider
+    @param[in] rhs  second JSON value to consider
+    @return whether @a lhs is greater than to @a rhs
+
+    @complexity Linear.
+
+    @exceptionsafety No-throw guarantee: this function never throws exceptions.
+
+    @liveexample{The example demonstrates comparing several JSON
+    types.,operator__lessequal}
+
+    @since version 1.0.0
+    */
+    friend bool operator>(const_reference lhs, const_reference rhs) noexcept
+    {
+        return not (lhs <= rhs);
+    }
+
+    /*!
+    @brief comparison: greater than
+    @copydoc operator>(const_reference, const_reference)
+    */
+    template<typename ScalarType, typename std::enable_if<
+                 std::is_scalar<ScalarType>::value, int>::type = 0>
+    friend bool operator>(const_reference lhs, const ScalarType rhs) noexcept
+    {
+        return (lhs > json(rhs));
+    }
+
+    /*!
+    @brief comparison: greater than
+    @copydoc operator>(const_reference, const_reference)
+    */
+    template<typename ScalarType, typename std::enable_if<
+                 std::is_scalar<ScalarType>::value, int>::type = 0>
+    friend bool operator>(const ScalarType lhs, const_reference rhs) noexcept
+    {
+        return (json(lhs) > rhs);
+    }
+
+    /*!
+    @brief comparison: greater than or equal
+
+    Compares whether one JSON value @a lhs is greater than or equal to another
+    JSON value by calculating `not (lhs < rhs)`.
+
+    @param[in] lhs  first JSON value to consider
+    @param[in] rhs  second JSON value to consider
+    @return whether @a lhs is greater than or equal to @a rhs
+
+    @complexity Linear.
+
+    @exceptionsafety No-throw guarantee: this function never throws exceptions.
+
+    @liveexample{The example demonstrates comparing several JSON
+    types.,operator__greaterequal}
+
+    @since version 1.0.0
+    */
+    friend bool operator>=(const_reference lhs, const_reference rhs) noexcept
+    {
+        return not (lhs < rhs);
+    }
+
+    /*!
+    @brief comparison: greater than or equal
+    @copydoc operator>=(const_reference, const_reference)
+    */
+    template<typename ScalarType, typename std::enable_if<
+                 std::is_scalar<ScalarType>::value, int>::type = 0>
+    friend bool operator>=(const_reference lhs, const ScalarType rhs) noexcept
+    {
+        return (lhs >= json(rhs));
+    }
+
+    /*!
+    @brief comparison: greater than or equal
+    @copydoc operator>=(const_reference, const_reference)
+    */
+    template<typename ScalarType, typename std::enable_if<
+                 std::is_scalar<ScalarType>::value, int>::type = 0>
+    friend bool operator>=(const ScalarType lhs, const_reference rhs) noexcept
+    {
+        return (json(lhs) >= rhs);
+    }
+
+    /// @}
+
+    ///////////////////
+    // serialization //
+    ///////////////////
+
+    /// @name serialization
+    /// @{
+
+    /*!
+    @brief serialize to stream
+
+    Serialize the given JSON value @a j to the output stream @a o. The JSON
+    value will be serialized using the @ref dump member function.
+
+    - The indentation of the output can be controlled with the member variable
+      `width` of the output stream @a o. For instance, using the manipulator
+      `std::setw(4)` on @a o sets the indentation level to `4` and the
+      serialization result is the same as calling `dump(4)`.
+
+    - The indentation character can be controlled with the member variable
+      `fill` of the output stream @a o. For instance, the manipulator
+      `std::setfill('\\t')` sets indentation to use a tab character rather than
+      the default space character.
+
+    @param[in,out] o  stream to serialize to
+    @param[in] j  JSON value to serialize
+
+    @return the stream @a o
+
+    @throw type_error.316 if a string stored inside the JSON value is not
+                          UTF-8 encoded
+
+    @complexity Linear.
+
+    @liveexample{The example below shows the serialization with different
+    parameters to `width` to adjust the indentation level.,operator_serialize}
+
+    @since version 1.0.0; indentation character added in version 3.0.0
+    */
+    friend raw_ostream& operator<<(raw_ostream& o, const json& j);
+
+    /// @}
+
+
+    /////////////////////
+    // deserialization //
+    /////////////////////
+
+    /// @name deserialization
+    /// @{
+
+    /*!
+    @brief deserialize from a compatible input
+
+    This function reads from a compatible input. Examples are:
+    - an array of 1-byte values
+    - strings with character/literal type with size of 1 byte
+    - input streams
+    - container with contiguous storage of 1-byte values. Compatible container
+      types include `std::vector`, `std::string`, `std::array`,
+      and `std::initializer_list`. Furthermore, C-style
+      arrays can be used with `std::begin()`/`std::end()`. User-defined
+      containers can be used as long as they implement random-access iterators
+      and a contiguous storage.
+
+    @pre Each element of the container has a size of 1 byte. Violating this
+    precondition yields undefined behavior. **This precondition is enforced
+    with a static assertion.**
+
+    @pre The container storage is contiguous. Violating this precondition
+    yields undefined behavior. **This precondition is enforced with an
+    assertion.**
+    @pre Each element of the container has a size of 1 byte. Violating this
+    precondition yields undefined behavior. **This precondition is enforced
+    with a static assertion.**
+
+    @warning There is no way to enforce all preconditions at compile-time. If
+             the function is called with a noncompliant container and with
+             assertions switched off, the behavior is undefined and will most
+             likely yield segmentation violation.
+
+    @param[in] i  input to read from
+    @param[in] cb  a parser callback function of type @ref parser_callback_t
+    which is used to control the deserialization by filtering unwanted values
+    (optional)
+
+    @return result of the deserialization
+
+    @throw parse_error.101 if a parse error occurs; example: `""unexpected end
+    of input; expected string literal""`
+    @throw parse_error.102 if to_unicode fails or surrogate error
+    @throw parse_error.103 if to_unicode fails
+
+    @complexity Linear in the length of the input. The parser is a predictive
+    LL(1) parser. The complexity can be higher if the parser callback function
+    @a cb has a super-linear complexity.
+
+    @note A UTF-8 byte order mark is silently ignored.
+
+    @liveexample{The example below demonstrates the `parse()` function reading
+    from an array.,parse__array__parser_callback_t}
+
+    @liveexample{The example below demonstrates the `parse()` function with
+    and without callback function.,parse__string__parser_callback_t}
+
+    @liveexample{The example below demonstrates the `parse()` function with
+    and without callback function.,parse__istream__parser_callback_t}
+
+    @liveexample{The example below demonstrates the `parse()` function reading
+    from a contiguous container.,parse__contiguouscontainer__parser_callback_t}
+
+    @since version 2.0.3 (contiguous containers)
+    */
+    static json parse(std::string_view s,
+                            const parser_callback_t cb = nullptr,
+                            const bool allow_exceptions = true);
+
+    static json parse(std::span<const uint8_t> arr,
+                            const parser_callback_t cb = nullptr,
+                            const bool allow_exceptions = true);
+
+    /*!
+    @copydoc json parse(raw_istream&, const parser_callback_t)
+    */
+    static json parse(raw_istream& i,
+                            const parser_callback_t cb = nullptr,
+                            const bool allow_exceptions = true);
+
+    static bool accept(std::string_view s);
+
+    static bool accept(std::span<const uint8_t> arr);
+
+    static bool accept(raw_istream& i);
+
+    /*!
+    @brief deserialize from stream
+
+    Deserializes an input stream to a JSON value.
+
+    @param[in,out] i  input stream to read a serialized JSON value from
+    @param[in,out] j  JSON value to write the deserialized input to
+
+    @throw parse_error.101 in case of an unexpected token
+    @throw parse_error.102 if to_unicode fails or surrogate error
+    @throw parse_error.103 if to_unicode fails
+
+    @complexity Linear in the length of the input. The parser is a predictive
+    LL(1) parser.
+
+    @note A UTF-8 byte order mark is silently ignored.
+
+    @liveexample{The example below shows how a JSON value is constructed by
+    reading a serialization from a stream.,operator_deserialize}
+
+    @sa parse(std::istream&, const parser_callback_t) for a variant with a
+    parser callback function to filter values while parsing
+
+    @since version 1.0.0
+    */
+    friend raw_istream& operator>>(raw_istream& i, json& j);
+
+    /// @}
+
+    ///////////////////////////
+    // convenience functions //
+    ///////////////////////////
+
+    /*!
+    @brief return the type as string
+
+    Returns the type name as string to be used in error messages - usually to
+    indicate that a function was called on a wrong JSON type.
+
+    @return a string representation of a the @a m_type member:
+            Value type  | return value
+            ----------- | -------------
+            null        | `"null"`
+            boolean     | `"boolean"`
+            string      | `"string"`
+            number      | `"number"` (for all number types)
+            object      | `"object"`
+            array       | `"array"`
+            discarded   | `"discarded"`
+
+    @exceptionsafety No-throw guarantee: this function never throws exceptions.
+
+    @complexity Constant.
+
+    @liveexample{The following code exemplifies `type_name()` for all JSON
+    types.,type_name}
+
+    @sa @ref type() -- return the type of the JSON value
+    @sa @ref operator value_t() -- return the type of the JSON value (implicit)
+
+    @since version 1.0.0, public since 2.1.0, `const char*` and `noexcept`
+    since 3.0.0
+    */
+    const char* type_name() const noexcept;
+
+
+  private:
+    //////////////////////
+    // member variables //
+    //////////////////////
+
+    /// the type of the current element
+    value_t m_type = value_t::null;
+
+    /// the value of the current element
+    json_value m_value = {};
+
+    //////////////////////////////////////////
+    // binary serialization/deserialization //
+    //////////////////////////////////////////
+
+    /// @name binary serialization/deserialization support
+    /// @{
+
+  public:
+    /*!
+    @brief create a CBOR serialization of a given JSON value
+
+    Serializes a given JSON value @a j to a byte vector using the CBOR (Concise
+    Binary Object Representation) serialization format. CBOR is a binary
+    serialization format which aims to be more compact than JSON itself, yet
+    more efficient to parse.
+
+    The library uses the following mapping from JSON values types to
+    CBOR types according to the CBOR specification (RFC 7049):
+
+    JSON value type | value/range                                | CBOR type                          | first byte
+    --------------- | ------------------------------------------ | ---------------------------------- | ---------------
+    null            | `null`                                     | Null                               | 0xF6
+    boolean         | `true`                                     | True                               | 0xF5
+    boolean         | `false`                                    | False                              | 0xF4
+    number_integer  | -9223372036854775808..-2147483649          | Negative integer (8 bytes follow)  | 0x3B
+    number_integer  | -2147483648..-32769                        | Negative integer (4 bytes follow)  | 0x3A
+    number_integer  | -32768..-129                               | Negative integer (2 bytes follow)  | 0x39
+    number_integer  | -128..-25                                  | Negative integer (1 byte follow)   | 0x38
+    number_integer  | -24..-1                                    | Negative integer                   | 0x20..0x37
+    number_integer  | 0..23                                      | Integer                            | 0x00..0x17
+    number_integer  | 24..255                                    | Unsigned integer (1 byte follow)   | 0x18
+    number_integer  | 256..65535                                 | Unsigned integer (2 bytes follow)  | 0x19
+    number_integer  | 65536..4294967295                          | Unsigned integer (4 bytes follow)  | 0x1A
+    number_integer  | 4294967296..18446744073709551615           | Unsigned integer (8 bytes follow)  | 0x1B
+    number_unsigned | 0..23                                      | Integer                            | 0x00..0x17
+    number_unsigned | 24..255                                    | Unsigned integer (1 byte follow)   | 0x18
+    number_unsigned | 256..65535                                 | Unsigned integer (2 bytes follow)  | 0x19
+    number_unsigned | 65536..4294967295                          | Unsigned integer (4 bytes follow)  | 0x1A
+    number_unsigned | 4294967296..18446744073709551615           | Unsigned integer (8 bytes follow)  | 0x1B
+    number_float    | *any value*                                | Double-Precision Float             | 0xFB
+    string          | *length*: 0..23                            | UTF-8 string                       | 0x60..0x77
+    string          | *length*: 23..255                          | UTF-8 string (1 byte follow)       | 0x78
+    string          | *length*: 256..65535                       | UTF-8 string (2 bytes follow)      | 0x79
+    string          | *length*: 65536..4294967295                | UTF-8 string (4 bytes follow)      | 0x7A
+    string          | *length*: 4294967296..18446744073709551615 | UTF-8 string (8 bytes follow)      | 0x7B
+    array           | *size*: 0..23                              | array                              | 0x80..0x97
+    array           | *size*: 23..255                            | array (1 byte follow)              | 0x98
+    array           | *size*: 256..65535                         | array (2 bytes follow)             | 0x99
+    array           | *size*: 65536..4294967295                  | array (4 bytes follow)             | 0x9A
+    array           | *size*: 4294967296..18446744073709551615   | array (8 bytes follow)             | 0x9B
+    object          | *size*: 0..23                              | map                                | 0xA0..0xB7
+    object          | *size*: 23..255                            | map (1 byte follow)                | 0xB8
+    object          | *size*: 256..65535                         | map (2 bytes follow)               | 0xB9
+    object          | *size*: 65536..4294967295                  | map (4 bytes follow)               | 0xBA
+    object          | *size*: 4294967296..18446744073709551615   | map (8 bytes follow)               | 0xBB
+
+    @note The mapping is **complete** in the sense that any JSON value type
+          can be converted to a CBOR value.
+
+    @note If NaN or Infinity are stored inside a JSON number, they are
+          serialized properly. This behavior differs from the @ref dump()
+          function which serializes NaN or Infinity to `null`.
+
+    @note The following CBOR types are not used in the conversion:
+          - byte strings (0x40..0x5F)
+          - UTF-8 strings terminated by "break" (0x7F)
+          - arrays terminated by "break" (0x9F)
+          - maps terminated by "break" (0xBF)
+          - date/time (0xC0..0xC1)
+          - bignum (0xC2..0xC3)
+          - decimal fraction (0xC4)
+          - bigfloat (0xC5)
+          - tagged items (0xC6..0xD4, 0xD8..0xDB)
+          - expected conversions (0xD5..0xD7)
+          - simple values (0xE0..0xF3, 0xF8)
+          - undefined (0xF7)
+          - half and single-precision floats (0xF9-0xFA)
+          - break (0xFF)
+
+    @param[in] j  JSON value to serialize
+    @return MessagePack serialization as byte vector
+
+    @complexity Linear in the size of the JSON value @a j.
+
+    @liveexample{The example shows the serialization of a JSON value to a byte
+    vector in CBOR format.,to_cbor}
+
+    @sa http://cbor.io
+    @sa @ref from_cbor(raw_istream&, const bool strict) for the
+        analogous deserialization
+    @sa @ref to_msgpack(const json&) for the related MessagePack format
+    @sa @ref to_ubjson(const json&, const bool, const bool) for the
+             related UBJSON format
+
+    @since version 2.0.9
+    */
+    static std::vector<uint8_t> to_cbor(const json& j);
+    static std::span<uint8_t> to_cbor(const json& j, std::vector<uint8_t>& buf);
+    static std::span<uint8_t> to_cbor(const json& j, SmallVectorImpl<uint8_t>& buf);
+    static void to_cbor(raw_ostream& os, const json& j);
+
+    /*!
+    @brief create a MessagePack serialization of a given JSON value
+
+    Serializes a given JSON value @a j to a byte vector using the MessagePack
+    serialization format. MessagePack is a binary serialization format which
+    aims to be more compact than JSON itself, yet more efficient to parse.
+
+    The library uses the following mapping from JSON values types to
+    MessagePack types according to the MessagePack specification:
+
+    JSON value type | value/range                       | MessagePack type | first byte
+    --------------- | --------------------------------- | ---------------- | ----------
+    null            | `null`                            | nil              | 0xC0
+    boolean         | `true`                            | true             | 0xC3
+    boolean         | `false`                           | false            | 0xC2
+    number_integer  | -9223372036854775808..-2147483649 | int64            | 0xD3
+    number_integer  | -2147483648..-32769               | int32            | 0xD2
+    number_integer  | -32768..-129                      | int16            | 0xD1
+    number_integer  | -128..-33                         | int8             | 0xD0
+    number_integer  | -32..-1                           | negative fixint  | 0xE0..0xFF
+    number_integer  | 0..127                            | positive fixint  | 0x00..0x7F
+    number_integer  | 128..255                          | uint 8           | 0xCC
+    number_integer  | 256..65535                        | uint 16          | 0xCD
+    number_integer  | 65536..4294967295                 | uint 32          | 0xCE
+    number_integer  | 4294967296..18446744073709551615  | uint 64          | 0xCF
+    number_unsigned | 0..127                            | positive fixint  | 0x00..0x7F
+    number_unsigned | 128..255                          | uint 8           | 0xCC
+    number_unsigned | 256..65535                        | uint 16          | 0xCD
+    number_unsigned | 65536..4294967295                 | uint 32          | 0xCE
+    number_unsigned | 4294967296..18446744073709551615  | uint 64          | 0xCF
+    number_float    | *any value*                       | float 64         | 0xCB
+    string          | *length*: 0..31                   | fixstr           | 0xA0..0xBF
+    string          | *length*: 32..255                 | str 8            | 0xD9
+    string          | *length*: 256..65535              | str 16           | 0xDA
+    string          | *length*: 65536..4294967295       | str 32           | 0xDB
+    array           | *size*: 0..15                     | fixarray         | 0x90..0x9F
+    array           | *size*: 16..65535                 | array 16         | 0xDC
+    array           | *size*: 65536..4294967295         | array 32         | 0xDD
+    object          | *size*: 0..15                     | fix map          | 0x80..0x8F
+    object          | *size*: 16..65535                 | map 16           | 0xDE
+    object          | *size*: 65536..4294967295         | map 32           | 0xDF
+
+    @note The mapping is **complete** in the sense that any JSON value type
+          can be converted to a MessagePack value.
+
+    @note The following values can **not** be converted to a MessagePack value:
+          - strings with more than 4294967295 bytes
+          - arrays with more than 4294967295 elements
+          - objects with more than 4294967295 elements
+
+    @note The following MessagePack types are not used in the conversion:
+          - bin 8 - bin 32 (0xC4..0xC6)
+          - ext 8 - ext 32 (0xC7..0xC9)
+          - float 32 (0xCA)
+          - fixext 1 - fixext 16 (0xD4..0xD8)
+
+    @note Any MessagePack output created @ref to_msgpack can be successfully
+          parsed by @ref from_msgpack.
+
+    @note If NaN or Infinity are stored inside a JSON number, they are
+          serialized properly. This behavior differs from the @ref dump()
+          function which serializes NaN or Infinity to `null`.
+
+    @param[in] j  JSON value to serialize
+    @return MessagePack serialization as byte vector
+
+    @complexity Linear in the size of the JSON value @a j.
+
+    @liveexample{The example shows the serialization of a JSON value to a byte
+    vector in MessagePack format.,to_msgpack}
+
+    @sa http://msgpack.org
+    @sa @ref from_msgpack(const std::vector<uint8_t>&, const size_t) for the
+        analogous deserialization
+    @sa @ref to_cbor(const json& for the related CBOR format
+    @sa @ref to_ubjson(const json&, const bool, const bool) for the
+             related UBJSON format
+
+    @since version 2.0.9
+    */
+    static std::vector<uint8_t> to_msgpack(const json& j);
+    static std::span<uint8_t> to_msgpack(const json& j, std::vector<uint8_t>& buf);
+    static std::span<uint8_t> to_msgpack(const json& j, SmallVectorImpl<uint8_t>& buf);
+    static void to_msgpack(raw_ostream& os, const json& j);
+
+    /*!
+    @brief create a UBJSON serialization of a given JSON value
+
+    Serializes a given JSON value @a j to a byte vector using the UBJSON
+    (Universal Binary JSON) serialization format. UBJSON aims to be more compact
+    than JSON itself, yet more efficient to parse.
+
+    The library uses the following mapping from JSON values types to
+    UBJSON types according to the UBJSON specification:
+
+    JSON value type | value/range                       | UBJSON type | marker
+    --------------- | --------------------------------- | ----------- | ------
+    null            | `null`                            | null        | `Z`
+    boolean         | `true`                            | true        | `T`
+    boolean         | `false`                           | false       | `F`
+    number_integer  | -9223372036854775808..-2147483649 | int64       | `L`
+    number_integer  | -2147483648..-32769               | int32       | `l`
+    number_integer  | -32768..-129                      | int16       | `I`
+    number_integer  | -128..127                         | int8        | `i`
+    number_integer  | 128..255                          | uint8       | `U`
+    number_integer  | 256..32767                        | int16       | `I`
+    number_integer  | 32768..2147483647                 | int32       | `l`
+    number_integer  | 2147483648..9223372036854775807   | int64       | `L`
+    number_unsigned | 0..127                            | int8        | `i`
+    number_unsigned | 128..255                          | uint8       | `U`
+    number_unsigned | 256..32767                        | int16       | `I`
+    number_unsigned | 32768..2147483647                 | int32       | `l`
+    number_unsigned | 2147483648..9223372036854775807   | int64       | `L`
+    number_float    | *any value*                       | float64     | `D`
+    string          | *with shortest length indicator*  | string      | `S`
+    array           | *see notes on optimized format*   | array       | `[`
+    object          | *see notes on optimized format*   | map         | `{`
+
+    @note The mapping is **complete** in the sense that any JSON value type
+          can be converted to a UBJSON value.
+
+    @note The following values can **not** be converted to a UBJSON value:
+          - strings with more than 9223372036854775807 bytes (theoretical)
+          - unsigned integer numbers above 9223372036854775807
+
+    @note The following markers are not used in the conversion:
+          - `Z`: no-op values are not created.
+          - `C`: single-byte strings are serialized with `S` markers.
+
+    @note Any UBJSON output created @ref to_ubjson can be successfully parsed
+          by @ref from_ubjson.
+
+    @note If NaN or Infinity are stored inside a JSON number, they are
+          serialized properly. This behavior differs from the @ref dump()
+          function which serializes NaN or Infinity to `null`.
+
+    @note The optimized formats for containers are supported: Parameter
+          @a use_size adds size information to the beginning of a container and
+          removes the closing marker. Parameter @a use_type further checks
+          whether all elements of a container have the same type and adds the
+          type marker to the beginning of the container. The @a use_type
+          parameter must only be used together with @a use_size = true. Note
+          that @a use_size = true alone may result in larger representations -
+          the benefit of this parameter is that the receiving side is
+          immediately informed on the number of elements of the container.
+
+    @param[in] j  JSON value to serialize
+    @param[in] use_size  whether to add size annotations to container types
+    @param[in] use_type  whether to add type annotations to container types
+                         (must be combined with @a use_size = true)
+    @return UBJSON serialization as byte vector
+
+    @complexity Linear in the size of the JSON value @a j.
+
+    @liveexample{The example shows the serialization of a JSON value to a byte
+    vector in UBJSON format.,to_ubjson}
+
+    @sa http://ubjson.org
+    @sa @ref from_ubjson(raw_istream&, const bool strict) for the
+        analogous deserialization
+    @sa @ref to_cbor(const json& for the related CBOR format
+    @sa @ref to_msgpack(const json&) for the related MessagePack format
+
+    @since version 3.1.0
+    */
+    static std::vector<uint8_t> to_ubjson(const json& j,
+                                          const bool use_size = false,
+                                          const bool use_type = false);
+    static std::span<uint8_t> to_ubjson(const json& j, std::vector<uint8_t>& buf,
+                                   const bool use_size = false, const bool use_type = false);
+    static std::span<uint8_t> to_ubjson(const json& j, SmallVectorImpl<uint8_t>& buf,
+                                   const bool use_size = false, const bool use_type = false);
+    static void to_ubjson(raw_ostream& os, const json& j,
+                          const bool use_size = false, const bool use_type = false);
+
+    /*!
+    @brief create a JSON value from an input in CBOR format
+
+    Deserializes a given input @a i to a JSON value using the CBOR (Concise
+    Binary Object Representation) serialization format.
+
+    The library maps CBOR types to JSON value types as follows:
+
+    CBOR type              | JSON value type | first byte
+    ---------------------- | --------------- | ----------
+    Integer                | number_unsigned | 0x00..0x17
+    Unsigned integer       | number_unsigned | 0x18
+    Unsigned integer       | number_unsigned | 0x19
+    Unsigned integer       | number_unsigned | 0x1A
+    Unsigned integer       | number_unsigned | 0x1B
+    Negative integer       | number_integer  | 0x20..0x37
+    Negative integer       | number_integer  | 0x38
+    Negative integer       | number_integer  | 0x39
+    Negative integer       | number_integer  | 0x3A
+    Negative integer       | number_integer  | 0x3B
+    Negative integer       | number_integer  | 0x40..0x57
+    UTF-8 string           | string          | 0x60..0x77
+    UTF-8 string           | string          | 0x78
+    UTF-8 string           | string          | 0x79
+    UTF-8 string           | string          | 0x7A
+    UTF-8 string           | string          | 0x7B
+    UTF-8 string           | string          | 0x7F
+    array                  | array           | 0x80..0x97
+    array                  | array           | 0x98
+    array                  | array           | 0x99
+    array                  | array           | 0x9A
+    array                  | array           | 0x9B
+    array                  | array           | 0x9F
+    map                    | object          | 0xA0..0xB7
+    map                    | object          | 0xB8
+    map                    | object          | 0xB9
+    map                    | object          | 0xBA
+    map                    | object          | 0xBB
+    map                    | object          | 0xBF
+    False                  | `false`         | 0xF4
+    True                   | `true`          | 0xF5
+    Nill                   | `null`          | 0xF6
+    Half-Precision Float   | number_float    | 0xF9
+    Single-Precision Float | number_float    | 0xFA
+    Double-Precision Float | number_float    | 0xFB
+
+    @warning The mapping is **incomplete** in the sense that not all CBOR
+             types can be converted to a JSON value. The following CBOR types
+             are not supported and will yield parse errors (parse_error.112):
+             - byte strings (0x40..0x5F)
+             - date/time (0xC0..0xC1)
+             - bignum (0xC2..0xC3)
+             - decimal fraction (0xC4)
+             - bigfloat (0xC5)
+             - tagged items (0xC6..0xD4, 0xD8..0xDB)
+             - expected conversions (0xD5..0xD7)
+             - simple values (0xE0..0xF3, 0xF8)
+             - undefined (0xF7)
+
+    @warning CBOR allows map keys of any type, whereas JSON only allows
+             strings as keys in object values. Therefore, CBOR maps with keys
+             other than UTF-8 strings are rejected (parse_error.113).
+
+    @note Any CBOR output created @ref to_cbor can be successfully parsed by
+          @ref from_cbor.
+
+    @param[in] i  an input in CBOR format convertible to an input adapter
+    @param[in] strict  whether to expect the input to be consumed until EOF
+                       (true by default)
+    @return deserialized JSON value
+
+    @throw parse_error.110 if the given input ends prematurely or the end of
+    file was not reached when @a strict was set to true
+    @throw parse_error.112 if unsupported features from CBOR were
+    used in the given input @a v or if the input is not valid CBOR
+    @throw parse_error.113 if a string was expected as map key, but not found
+
+    @complexity Linear in the size of the input @a i.
+
+    @liveexample{The example shows the deserialization of a byte vector in CBOR
+    format to a JSON value.,from_cbor}
+
+    @sa http://cbor.io
+    @sa @ref to_cbor(const json&) for the analogous serialization
+    @sa @ref from_msgpack(raw_istream&, const bool) for the
+        related MessagePack format
+    @sa @ref from_ubjson(raw_istream&, const bool) for the related
+        UBJSON format
+
+    @since version 2.0.9; parameter @a start_index since 2.1.1; changed to
+           consume input adapters, removed start_index parameter, and added
+           @a strict parameter since 3.0.0
+    */
+    static json from_cbor(raw_istream& is,
+                                const bool strict = true);
+
+    /*!
+    @copydoc from_cbor(raw_istream&, const bool)
+    */
+    static json from_cbor(std::span<const uint8_t> arr, const bool strict = true);
+
+    /*!
+    @brief create a JSON value from an input in MessagePack format
+
+    Deserializes a given input @a i to a JSON value using the MessagePack
+    serialization format.
+
+    The library maps MessagePack types to JSON value types as follows:
+
+    MessagePack type | JSON value type | first byte
+    ---------------- | --------------- | ----------
+    positive fixint  | number_unsigned | 0x00..0x7F
+    fixmap           | object          | 0x80..0x8F
+    fixarray         | array           | 0x90..0x9F
+    fixstr           | string          | 0xA0..0xBF
+    nil              | `null`          | 0xC0
+    false            | `false`         | 0xC2
+    true             | `true`          | 0xC3
+    float 32         | number_float    | 0xCA
+    float 64         | number_float    | 0xCB
+    uint 8           | number_unsigned | 0xCC
+    uint 16          | number_unsigned | 0xCD
+    uint 32          | number_unsigned | 0xCE
+    uint 64          | number_unsigned | 0xCF
+    int 8            | number_integer  | 0xD0
+    int 16           | number_integer  | 0xD1
+    int 32           | number_integer  | 0xD2
+    int 64           | number_integer  | 0xD3
+    str 8            | string          | 0xD9
+    str 16           | string          | 0xDA
+    str 32           | string          | 0xDB
+    array 16         | array           | 0xDC
+    array 32         | array           | 0xDD
+    map 16           | object          | 0xDE
+    map 32           | object          | 0xDF
+    negative fixint  | number_integer  | 0xE0-0xFF
+
+    @warning The mapping is **incomplete** in the sense that not all
+             MessagePack types can be converted to a JSON value. The following
+             MessagePack types are not supported and will yield parse errors:
+              - bin 8 - bin 32 (0xC4..0xC6)
+              - ext 8 - ext 32 (0xC7..0xC9)
+              - fixext 1 - fixext 16 (0xD4..0xD8)
+
+    @note Any MessagePack output created @ref to_msgpack can be successfully
+          parsed by @ref from_msgpack.
+
+    @param[in] i  an input in MessagePack format convertible to an input
+                  adapter
+    @param[in] strict  whether to expect the input to be consumed until EOF
+                       (true by default)
+
+    @throw parse_error.110 if the given input ends prematurely or the end of
+    file was not reached when @a strict was set to true
+    @throw parse_error.112 if unsupported features from MessagePack were
+    used in the given input @a i or if the input is not valid MessagePack
+    @throw parse_error.113 if a string was expected as map key, but not found
+
+    @complexity Linear in the size of the input @a i.
+
+    @liveexample{The example shows the deserialization of a byte vector in
+    MessagePack format to a JSON value.,from_msgpack}
+
+    @sa http://msgpack.org
+    @sa @ref to_msgpack(const json&) for the analogous serialization
+    @sa @ref from_cbor(raw_istream&, const bool) for the related CBOR
+        format
+    @sa @ref from_ubjson(raw_istream&, const bool) for the related
+        UBJSON format
+
+    @since version 2.0.9; parameter @a start_index since 2.1.1; changed to
+           consume input adapters, removed start_index parameter, and added
+           @a strict parameter since 3.0.0
+    */
+    static json from_msgpack(raw_istream& is,
+                                   const bool strict = true);
+
+    /*!
+    @copydoc from_msgpack(raw_istream&, const bool)
+    */
+    static json from_msgpack(std::span<const uint8_t> arr, const bool strict = true);
+
+    /*!
+    @brief create a JSON value from an input in UBJSON format
+
+    Deserializes a given input @a i to a JSON value using the UBJSON (Universal
+    Binary JSON) serialization format.
+
+    The library maps UBJSON types to JSON value types as follows:
+
+    UBJSON type | JSON value type                         | marker
+    ----------- | --------------------------------------- | ------
+    no-op       | *no value, next value is read*          | `N`
+    null        | `null`                                  | `Z`
+    false       | `false`                                 | `F`
+    true        | `true`                                  | `T`
+    float32     | number_float                            | `d`
+    float64     | number_float                            | `D`
+    uint8       | number_unsigned                         | `U`
+    int8        | number_integer                          | `i`
+    int16       | number_integer                          | `I`
+    int32       | number_integer                          | `l`
+    int64       | number_integer                          | `L`
+    string      | string                                  | `S`
+    char        | string                                  | `C`
+    array       | array (optimized values are supported)  | `[`
+    object      | object (optimized values are supported) | `{`
+
+    @note The mapping is **complete** in the sense that any UBJSON value can
+          be converted to a JSON value.
+
+    @param[in] i  an input in UBJSON format convertible to an input adapter
+    @param[in] strict  whether to expect the input to be consumed until EOF
+                       (true by default)
+
+    @throw parse_error.110 if the given input ends prematurely or the end of
+    file was not reached when @a strict was set to true
+    @throw parse_error.112 if a parse error occurs
+    @throw parse_error.113 if a string could not be parsed successfully
+
+    @complexity Linear in the size of the input @a i.
+
+    @liveexample{The example shows the deserialization of a byte vector in
+    UBJSON format to a JSON value.,from_ubjson}
+
+    @sa http://ubjson.org
+    @sa @ref to_ubjson(const json&, const bool, const bool) for the
+             analogous serialization
+    @sa @ref from_cbor(raw_istream&, const bool) for the related CBOR
+        format
+    @sa @ref from_msgpack(raw_istream&, const bool) for the related
+        MessagePack format
+
+    @since version 3.1.0
+    */
+    static json from_ubjson(raw_istream& is,
+                                  const bool strict = true);
+
+    static json from_ubjson(std::span<const uint8_t> arr, const bool strict = true);
+
+    /// @}
+
+    //////////////////////////
+    // JSON Pointer support //
+    //////////////////////////
+
+    /// @name JSON Pointer functions
+    /// @{
+
+    /*!
+    @brief access specified element via JSON Pointer
+
+    Uses a JSON pointer to retrieve a reference to the respective JSON value.
+    No bound checking is performed. Similar to @ref operator[](const typename
+    object_t::key_type&), `null` values are created in arrays and objects if
+    necessary.
+
+    In particular:
+    - If the JSON pointer points to an object key that does not exist, it
+      is created an filled with a `null` value before a reference to it
+      is returned.
+    - If the JSON pointer points to an array index that does not exist, it
+      is created an filled with a `null` value before a reference to it
+      is returned. All indices between the current maximum and the given
+      index are also filled with `null`.
+    - The special value `-` is treated as a synonym for the index past the
+      end.
+
+    @param[in] ptr  a JSON pointer
+
+    @return reference to the element pointed to by @a ptr
+
+    @complexity Constant.
+
+    @throw parse_error.106   if an array index begins with '0'
+    @throw parse_error.109   if an array index was not a number
+    @throw out_of_range.404  if the JSON pointer can not be resolved
+
+    @liveexample{The behavior is shown in the example.,operatorjson_pointer}
+
+    @since version 2.0.0
+    */
+    reference operator[](const json_pointer& ptr)
+    {
+        return ptr.get_unchecked(this);
+    }
+
+    /*!
+    @brief access specified element via JSON Pointer
+
+    Uses a JSON pointer to retrieve a reference to the respective JSON value.
+    No bound checking is performed. The function does not change the JSON
+    value; no `null` values are created. In particular, the the special value
+    `-` yields an exception.
+
+    @param[in] ptr  JSON pointer to the desired element
+
+    @return const reference to the element pointed to by @a ptr
+
+    @complexity Constant.
+
+    @throw parse_error.106   if an array index begins with '0'
+    @throw parse_error.109   if an array index was not a number
+    @throw out_of_range.402  if the array index '-' is used
+    @throw out_of_range.404  if the JSON pointer can not be resolved
+
+    @liveexample{The behavior is shown in the example.,operatorjson_pointer_const}
+
+    @since version 2.0.0
+    */
+    const_reference operator[](const json_pointer& ptr) const
+    {
+        return ptr.get_unchecked(this);
+    }
+
+    /*!
+    @brief access specified element via JSON Pointer
+
+    Returns a reference to the element at with specified JSON pointer @a ptr,
+    with bounds checking.
+
+    @param[in] ptr  JSON pointer to the desired element
+
+    @return reference to the element pointed to by @a ptr
+
+    @throw parse_error.106 if an array index in the passed JSON pointer @a ptr
+    begins with '0'. See example below.
+
+    @throw parse_error.109 if an array index in the passed JSON pointer @a ptr
+    is not a number. See example below.
+
+    @throw out_of_range.401 if an array index in the passed JSON pointer @a ptr
+    is out of range. See example below.
+
+    @throw out_of_range.402 if the array index '-' is used in the passed JSON
+    pointer @a ptr. As `at` provides checked access (and no elements are
+    implicitly inserted), the index '-' is always invalid. See example below.
+
+    @throw out_of_range.403 if the JSON pointer describes a key of an object
+    which cannot be found. See example below.
+
+    @throw out_of_range.404 if the JSON pointer @a ptr can not be resolved.
+    See example below.
+
+    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
+    changes in the JSON value.
+
+    @complexity Constant.
+
+    @since version 2.0.0
+
+    @liveexample{The behavior is shown in the example.,at_json_pointer}
+    */
+    reference at(const json_pointer& ptr)
+    {
+        return ptr.get_checked(this);
+    }
+
+    /*!
+    @brief access specified element via JSON Pointer
+
+    Returns a const reference to the element at with specified JSON pointer @a
+    ptr, with bounds checking.
+
+    @param[in] ptr  JSON pointer to the desired element
+
+    @return reference to the element pointed to by @a ptr
+
+    @throw parse_error.106 if an array index in the passed JSON pointer @a ptr
+    begins with '0'. See example below.
+
+    @throw parse_error.109 if an array index in the passed JSON pointer @a ptr
+    is not a number. See example below.
+
+    @throw out_of_range.401 if an array index in the passed JSON pointer @a ptr
+    is out of range. See example below.
+
+    @throw out_of_range.402 if the array index '-' is used in the passed JSON
+    pointer @a ptr. As `at` provides checked access (and no elements are
+    implicitly inserted), the index '-' is always invalid. See example below.
+
+    @throw out_of_range.403 if the JSON pointer describes a key of an object
+    which cannot be found. See example below.
+
+    @throw out_of_range.404 if the JSON pointer @a ptr can not be resolved.
+    See example below.
+
+    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
+    changes in the JSON value.
+
+    @complexity Constant.
+
+    @since version 2.0.0
+
+    @liveexample{The behavior is shown in the example.,at_json_pointer_const}
+    */
+    const_reference at(const json_pointer& ptr) const
+    {
+        return ptr.get_checked(this);
+    }
+
+    /*!
+    @brief return flattened JSON value
+
+    The function creates a JSON object whose keys are JSON pointers (see [RFC
+    6901](https://tools.ietf.org/html/rfc6901)) and whose values are all
+    primitive. The original JSON value can be restored using the @ref
+    unflatten() function.
+
+    @return an object that maps JSON pointers to primitive values
+
+    @note Empty objects and arrays are flattened to `null` and will not be
+          reconstructed correctly by the @ref unflatten() function.
+
+    @complexity Linear in the size the JSON value.
+
+    @liveexample{The following code shows how a JSON object is flattened to an
+    object whose keys consist of JSON pointers.,flatten}
+
+    @sa @ref unflatten() for the reverse function
+
+    @since version 2.0.0
+    */
+    json flatten() const
+    {
+        json result(value_t::object);
+        json_pointer::flatten("", *this, result);
+        return result;
+    }
+
+    /*!
+    @brief unflatten a previously flattened JSON value
+
+    The function restores the arbitrary nesting of a JSON value that has been
+    flattened before using the @ref flatten() function. The JSON value must
+    meet certain constraints:
+    1. The value must be an object.
+    2. The keys must be JSON pointers (see
+       [RFC 6901](https://tools.ietf.org/html/rfc6901))
+    3. The mapped values must be primitive JSON types.
+
+    @return the original JSON from a flattened version
+
+    @note Empty objects and arrays are flattened by @ref flatten() to `null`
+          values and can not unflattened to their original type. Apart from
+          this example, for a JSON value `j`, the following is always true:
+          `j == j.flatten().unflatten()`.
+
+    @complexity Linear in the size the JSON value.
+
+    @throw type_error.314  if value is not an object
+    @throw type_error.315  if object values are not primitive
+
+    @liveexample{The following code shows how a flattened JSON object is
+    unflattened into the original nested JSON object.,unflatten}
+
+    @sa @ref flatten() for the reverse function
+
+    @since version 2.0.0
+    */
+    json unflatten() const
+    {
+        return json_pointer::unflatten(*this);
+    }
+
+    /// @}
+
+    //////////////////////////
+    // JSON Patch functions //
+    //////////////////////////
+
+    /// @name JSON Patch functions
+    /// @{
+
+    /*!
+    @brief applies a JSON patch
+
+    [JSON Patch](http://jsonpatch.com) defines a JSON document structure for
+    expressing a sequence of operations to apply to a JSON) document. With
+    this function, a JSON Patch is applied to the current JSON value by
+    executing all operations from the patch.
+
+    @param[in] json_patch  JSON patch document
+    @return patched document
+
+    @note The application of a patch is atomic: Either all operations succeed
+          and the patched document is returned or an exception is thrown. In
+          any case, the original value is not changed: the patch is applied
+          to a copy of the value.
+
+    @throw parse_error.104 if the JSON patch does not consist of an array of
+    objects
+
+    @throw parse_error.105 if the JSON patch is malformed (e.g., mandatory
+    attributes are missing); example: `"operation add must have member path"`
+
+    @throw out_of_range.401 if an array index is out of range.
+
+    @throw out_of_range.403 if a JSON pointer inside the patch could not be
+    resolved successfully in the current JSON value; example: `"key baz not
+    found"`
+
+    @throw out_of_range.405 if JSON pointer has no parent ("add", "remove",
+    "move")
+
+    @throw other_error.501 if "test" operation was unsuccessful
+
+    @complexity Linear in the size of the JSON value and the length of the
+    JSON patch. As usually only a fraction of the JSON value is affected by
+    the patch, the complexity can usually be neglected.
+
+    @liveexample{The following code shows how a JSON patch is applied to a
+    value.,patch}
+
+    @sa @ref diff -- create a JSON patch by comparing two JSON values
+
+    @sa [RFC 6902 (JSON Patch)](https://tools.ietf.org/html/rfc6902)
+    @sa [RFC 6901 (JSON Pointer)](https://tools.ietf.org/html/rfc6901)
+
+    @since version 2.0.0
+    */
+    json patch(const json& json_patch) const;
+
+    /*!
+    @brief creates a diff as a JSON patch
+
+    Creates a [JSON Patch](http://jsonpatch.com) so that value @a source can
+    be changed into the value @a target by calling @ref patch function.
+
+    @invariant For two JSON values @a source and @a target, the following code
+    yields always `true`:
+    @code {.cpp}
+    source.patch(diff(source, target)) == target;
+    @endcode
+
+    @note Currently, only `remove`, `add`, and `replace` operations are
+          generated.
+
+    @param[in] source  JSON value to compare from
+    @param[in] target  JSON value to compare against
+    @param[in] path    helper value to create JSON pointers
+
+    @return a JSON patch to convert the @a source to @a target
+
+    @complexity Linear in the lengths of @a source and @a target.
+
+    @liveexample{The following code shows how a JSON patch is created as a
+    diff for two JSON values.,diff}
+
+    @sa @ref patch -- apply a JSON patch
+    @sa @ref merge_patch -- apply a JSON Merge Patch
+
+    @sa [RFC 6902 (JSON Patch)](https://tools.ietf.org/html/rfc6902)
+
+    @since version 2.0.0
+    */
+    static json diff(const json& source, const json& target,
+                           const std::string& path = "");
+
+    /// @}
+
+    ////////////////////////////////
+    // JSON Merge Patch functions //
+    ////////////////////////////////
+
+    /// @name JSON Merge Patch functions
+    /// @{
+
+    /*!
+    @brief applies a JSON Merge Patch
+
+    The merge patch format is primarily intended for use with the HTTP PATCH
+    method as a means of describing a set of modifications to a target
+    resource's content. This function applies a merge patch to the current
+    JSON value.
+
+    The function implements the following algorithm from Section 2 of
+    [RFC 7396 (JSON Merge Patch)](https://tools.ietf.org/html/rfc7396):
+
+    ```
+    define MergePatch(Target, Patch):
+      if Patch is an Object:
+        if Target is not an Object:
+          Target = {} // Ignore the contents and set it to an empty Object
+        for each Name/Value pair in Patch:
+          if Value is null:
+            if Name exists in Target:
+              remove the Name/Value pair from Target
+          else:
+            Target[Name] = MergePatch(Target[Name], Value)
+        return Target
+      else:
+        return Patch
+    ```
+
+    Thereby, `Target` is the current object; that is, the patch is applied to
+    the current value.
+
+    @param[in] patch  the patch to apply
+
+    @complexity Linear in the lengths of @a patch.
+
+    @liveexample{The following code shows how a JSON Merge Patch is applied to
+    a JSON document.,merge_patch}
+
+    @sa @ref patch -- apply a JSON patch
+    @sa [RFC 7396 (JSON Merge Patch)](https://tools.ietf.org/html/rfc7396)
+
+    @since version 3.0.0
+    */
+    void merge_patch(const json& patch);
+
+    /// @}
+};
+} // namespace wpi
+
+///////////////////////
+// nonmember support //
+///////////////////////
+
+// specialization of std::swap, and std::hash
+namespace std
+{
+/*!
+@brief exchanges the values of two JSON objects
+
+@since version 1.0.0
+*/
+template<>
+inline void swap<wpi::json>(wpi::json& j1,
+                 wpi::json& j2) noexcept(
+                     is_nothrow_move_constructible<wpi::json>::value and
+                     is_nothrow_move_assignable<wpi::json>::value
+                 )
+{
+    j1.swap(j2);
+}
+
+/// hash value for JSON objects
+template<>
+struct hash<wpi::json>
+{
+    /*!
+    @brief return a hash value for a JSON object
+
+    @since version 1.0.0
+    */
+    std::size_t operator()(const wpi::json& j) const
+    {
+        // a naive hashing via the string representation
+        const auto& h = hash<std::string>();
+        return h(j.dump());
+    }
+};
+
+/// specialization for std::less<value_t>
+/// @note: do not remove the space after '<',
+///        see https://github.com/nlohmann/json/pull/679
+template<>
+struct less< ::wpi::detail::value_t>
+{
+    /*!
+    @brief compare two value_t enum values
+    @since version 3.0.0
+    */
+    bool operator()(wpi::detail::value_t lhs,
+                    wpi::detail::value_t rhs) const noexcept
+    {
+        return wpi::detail::operator<(lhs, rhs);
+    }
+};
+
+} // namespace std
+
+/*!
+@brief user-defined string literal for JSON values
+
+This operator implements a user-defined string literal for JSON objects. It
+can be used by adding `"_json"` to a string literal and returns a JSON object
+if no parse error occurred.
+
+@param[in] s  a string representation of a JSON object
+@param[in] n  the length of string @a s
+@return a JSON object
+
+@since version 1.0.0
+*/
+inline wpi::json operator "" _json(const char* s, std::size_t n)
+{
+    return wpi::json::parse(std::string_view(s, n));
+}
+
+/*!
+@brief user-defined string literal for JSON pointer
+
+This operator implements a user-defined string literal for JSON Pointers. It
+can be used by adding `"_json_pointer"` to a string literal and returns a JSON pointer
+object if no parse error occurred.
+
+@param[in] s  a string representation of a JSON Pointer
+@param[in] n  the length of string @a s
+@return a JSON pointer object
+
+@since version 2.0.0
+*/
+inline wpi::json::json_pointer operator "" _json_pointer(const char* s, std::size_t n)
+{
+    return wpi::json::json_pointer(std::string_view(s, n));
+}
+
+#ifndef WPI_JSON_IMPLEMENTATION
+
+// restore GCC/clang diagnostic settings
+#if defined(__clang__) || defined(__GNUC__) || defined(__GNUG__)
+    #pragma GCC diagnostic pop
+#endif
+#if defined(__clang__)
+    #pragma GCC diagnostic pop
+#endif
+
+// clean up
+#undef JSON_CATCH
+#undef JSON_THROW
+#undef JSON_TRY
+#undef JSON_LIKELY
+#undef JSON_UNLIKELY
+#undef NLOHMANN_BASIC_JSON_TPL_DECLARATION
+#undef NLOHMANN_BASIC_JSON_TPL
+#undef NLOHMANN_JSON_HAS_HELPER
+
+#endif  // WPI_JSON_IMPLEMENTATION
+
+#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/json_serializer.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/json/include/wpi/json_serializer.h
similarity index 100%
rename from third_party/allwpilib/wpiutil/src/main/native/include/wpi/json_serializer.h
rename to third_party/allwpilib/wpiutil/src/main/native/thirdparty/json/include/wpi/json_serializer.h
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/ConvertUTF.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/ConvertUTF.cpp
new file mode 100644
index 0000000..dbf41ab
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/ConvertUTF.cpp
@@ -0,0 +1,833 @@
+/*===--- ConvertUTF.c - Universal Character Names conversions ---------------===
+ *
+ * Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+ * See https://llvm.org/LICENSE.txt for license information.
+ * SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+ *
+ *===------------------------------------------------------------------------=*/
+/*
+ * Copyright 2001-2004 Unicode, Inc.
+ *
+ * Disclaimer
+ *
+ * This source code is provided as is by Unicode, Inc. No claims are
+ * made as to fitness for any particular purpose. No warranties of any
+ * kind are expressed or implied. The recipient agrees to determine
+ * applicability of information provided. If this file has been
+ * purchased on magnetic or optical media from Unicode, Inc., the
+ * sole remedy for any claim will be exchange of defective media
+ * within 90 days of receipt.
+ *
+ * Limitations on Rights to Redistribute This Code
+ *
+ * Unicode, Inc. hereby grants the right to freely use the information
+ * supplied in this file in the creation of products supporting the
+ * Unicode Standard, and to make copies of this file in any form
+ * for internal or external distribution as long as this notice
+ * remains attached.
+ */
+
+/* ---------------------------------------------------------------------
+
+    Conversions between UTF32, UTF-16, and UTF-8. Source code file.
+    Author: Mark E. Davis, 1994.
+    Rev History: Rick McGowan, fixes & updates May 2001.
+    Sept 2001: fixed const & error conditions per
+        mods suggested by S. Parent & A. Lillich.
+    June 2002: Tim Dodd added detection and handling of incomplete
+        source sequences, enhanced error detection, added casts
+        to eliminate compiler warnings.
+    July 2003: slight mods to back out aggressive FFFE detection.
+    Jan 2004: updated switches in from-UTF8 conversions.
+    Oct 2004: updated to use UNI_MAX_LEGAL_UTF32 in UTF-32 conversions.
+
+    See the header file "ConvertUTF.h" for complete documentation.
+
+------------------------------------------------------------------------ */
+
+#include "wpi/ConvertUTF.h"
+#ifdef CVTUTF_DEBUG
+#include <stdio.h>
+#endif
+#include <assert.h>
+
+#ifdef _WIN32
+#include "wpi/WindowsError.h"
+#include "Windows/WindowsSupport.h"
+#endif
+
+/*
+ * This code extensively uses fall-through switches.
+ * Keep the compiler from warning about that.
+ */
+#if defined(__clang__) && defined(__has_warning)
+# if __has_warning("-Wimplicit-fallthrough")
+#  define ConvertUTF_DISABLE_WARNINGS \
+    _Pragma("clang diagnostic push")  \
+    _Pragma("clang diagnostic ignored \"-Wimplicit-fallthrough\"")
+#  define ConvertUTF_RESTORE_WARNINGS \
+    _Pragma("clang diagnostic pop")
+# endif
+#elif defined(__GNUC__) && __GNUC__ > 6
+# define ConvertUTF_DISABLE_WARNINGS \
+   _Pragma("GCC diagnostic push")    \
+   _Pragma("GCC diagnostic ignored \"-Wimplicit-fallthrough\"")
+# define ConvertUTF_RESTORE_WARNINGS \
+   _Pragma("GCC diagnostic pop")
+#endif
+#ifndef ConvertUTF_DISABLE_WARNINGS
+# define ConvertUTF_DISABLE_WARNINGS
+#endif
+#ifndef ConvertUTF_RESTORE_WARNINGS
+# define ConvertUTF_RESTORE_WARNINGS
+#endif
+
+ConvertUTF_DISABLE_WARNINGS
+
+namespace wpi {
+
+static const int halfShift  = 10; /* used for shifting by 10 bits */
+
+static const UTF32 halfBase = 0x0010000UL;
+static const UTF32 halfMask = 0x3FFUL;
+
+#define UNI_SUR_HIGH_START  (UTF32)0xD800
+#define UNI_SUR_HIGH_END    (UTF32)0xDBFF
+#define UNI_SUR_LOW_START   (UTF32)0xDC00
+#define UNI_SUR_LOW_END     (UTF32)0xDFFF
+
+/* --------------------------------------------------------------------- */
+
+/*
+ * Index into the table below with the first byte of a UTF-8 sequence to
+ * get the number of trailing bytes that are supposed to follow it.
+ * Note that *legal* UTF-8 values can't have 4 or 5-bytes. The table is
+ * left as-is for anyone who may want to do such conversion, which was
+ * allowed in earlier algorithms.
+ */
+static const char trailingBytesForUTF8[256] = {
+    0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,
+    0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,
+    0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,
+    0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,
+    0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,
+    0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,
+    1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,
+    2,2,2,2,2,2,2,2,2,2,2,2,2,2,2,2, 3,3,3,3,3,3,3,3,4,4,4,4,5,5,5,5
+};
+
+/*
+ * Magic values subtracted from a buffer value during UTF8 conversion.
+ * This table contains as many values as there might be trailing bytes
+ * in a UTF-8 sequence.
+ */
+static const UTF32 offsetsFromUTF8[6] = { 0x00000000UL, 0x00003080UL, 0x000E2080UL,
+                     0x03C82080UL, 0xFA082080UL, 0x82082080UL };
+
+/*
+ * Once the bits are split out into bytes of UTF-8, this is a mask OR-ed
+ * into the first byte, depending on how many bytes follow.  There are
+ * as many entries in this table as there are UTF-8 sequence types.
+ * (I.e., one byte sequence, two byte... etc.). Remember that sequencs
+ * for *legal* UTF-8 will be 4 or fewer bytes total.
+ */
+static const UTF8 firstByteMark[7] = { 0x00, 0x00, 0xC0, 0xE0, 0xF0, 0xF8, 0xFC };
+
+/* --------------------------------------------------------------------- */
+
+/* The interface converts a whole buffer to avoid function-call overhead.
+ * Constants have been gathered. Loops & conditionals have been removed as
+ * much as possible for efficiency, in favor of drop-through switches.
+ * (See "Note A" at the bottom of the file for equivalent code.)
+ * If your compiler supports it, the "isLegalUTF8" call can be turned
+ * into an inline function.
+ */
+
+
+/* --------------------------------------------------------------------- */
+
+ConversionResult ConvertUTF32toUTF16 (
+        const UTF32** sourceStart, const UTF32* sourceEnd,
+        UTF16** targetStart, UTF16* targetEnd, ConversionFlags flags) {
+    ConversionResult result = conversionOK;
+    const UTF32* source = *sourceStart;
+    UTF16* target = *targetStart;
+    while (source < sourceEnd) {
+        UTF32 ch;
+        if (target >= targetEnd) {
+            result = targetExhausted; break;
+        }
+        ch = *source++;
+        if (ch <= UNI_MAX_BMP) { /* Target is a character <= 0xFFFF */
+            /* UTF-16 surrogate values are illegal in UTF-32; 0xffff or 0xfffe are both reserved values */
+            if (ch >= UNI_SUR_HIGH_START && ch <= UNI_SUR_LOW_END) {
+                if (flags == strictConversion) {
+                    --source; /* return to the illegal value itself */
+                    result = sourceIllegal;
+                    break;
+                } else {
+                    *target++ = UNI_REPLACEMENT_CHAR;
+                }
+            } else {
+                *target++ = (UTF16)ch; /* normal case */
+            }
+        } else if (ch > UNI_MAX_LEGAL_UTF32) {
+            if (flags == strictConversion) {
+                result = sourceIllegal;
+            } else {
+                *target++ = UNI_REPLACEMENT_CHAR;
+            }
+        } else {
+            /* target is a character in range 0xFFFF - 0x10FFFF. */
+            if (target + 1 >= targetEnd) {
+                --source; /* Back up source pointer! */
+                result = targetExhausted; break;
+            }
+            ch -= halfBase;
+            *target++ = (UTF16)((ch >> halfShift) + UNI_SUR_HIGH_START);
+            *target++ = (UTF16)((ch & halfMask) + UNI_SUR_LOW_START);
+        }
+    }
+    *sourceStart = source;
+    *targetStart = target;
+    return result;
+}
+
+/* --------------------------------------------------------------------- */
+
+ConversionResult ConvertUTF16toUTF32 (
+        const UTF16** sourceStart, const UTF16* sourceEnd,
+        UTF32** targetStart, UTF32* targetEnd, ConversionFlags flags) {
+    ConversionResult result = conversionOK;
+    const UTF16* source = *sourceStart;
+    UTF32* target = *targetStart;
+    UTF32 ch, ch2;
+    while (source < sourceEnd) {
+        const UTF16* oldSource = source; /*  In case we have to back up because of target overflow. */
+        ch = *source++;
+        /* If we have a surrogate pair, convert to UTF32 first. */
+        if (ch >= UNI_SUR_HIGH_START && ch <= UNI_SUR_HIGH_END) {
+            /* If the 16 bits following the high surrogate are in the source buffer... */
+            if (source < sourceEnd) {
+                ch2 = *source;
+                /* If it's a low surrogate, convert to UTF32. */
+                if (ch2 >= UNI_SUR_LOW_START && ch2 <= UNI_SUR_LOW_END) {
+                    ch = ((ch - UNI_SUR_HIGH_START) << halfShift)
+                        + (ch2 - UNI_SUR_LOW_START) + halfBase;
+                    ++source;
+                } else if (flags == strictConversion) { /* it's an unpaired high surrogate */
+                    --source; /* return to the illegal value itself */
+                    result = sourceIllegal;
+                    break;
+                }
+            } else { /* We don't have the 16 bits following the high surrogate. */
+                --source; /* return to the high surrogate */
+                result = sourceExhausted;
+                break;
+            }
+        } else if (flags == strictConversion) {
+            /* UTF-16 surrogate values are illegal in UTF-32 */
+            if (ch >= UNI_SUR_LOW_START && ch <= UNI_SUR_LOW_END) {
+                --source; /* return to the illegal value itself */
+                result = sourceIllegal;
+                break;
+            }
+        }
+        if (target >= targetEnd) {
+            source = oldSource; /* Back up source pointer! */
+            result = targetExhausted; break;
+        }
+        *target++ = ch;
+    }
+    *sourceStart = source;
+    *targetStart = target;
+#ifdef CVTUTF_DEBUG
+if (result == sourceIllegal) {
+    fprintf(stderr, "ConvertUTF16toUTF32 illegal seq 0x%04x,%04x\n", ch, ch2);
+    fflush(stderr);
+}
+#endif
+    return result;
+}
+ConversionResult ConvertUTF16toUTF8 (
+        const UTF16** sourceStart, const UTF16* sourceEnd,
+        UTF8** targetStart, UTF8* targetEnd, ConversionFlags flags) {
+    ConversionResult result = conversionOK;
+    const UTF16* source = *sourceStart;
+    UTF8* target = *targetStart;
+    while (source < sourceEnd) {
+        UTF32 ch;
+        unsigned short bytesToWrite = 0;
+        const UTF32 byteMask = 0xBF;
+        const UTF32 byteMark = 0x80;
+        const UTF16* oldSource = source; /* In case we have to back up because of target overflow. */
+        ch = *source++;
+        /* If we have a surrogate pair, convert to UTF32 first. */
+        if (ch >= UNI_SUR_HIGH_START && ch <= UNI_SUR_HIGH_END) {
+            /* If the 16 bits following the high surrogate are in the source buffer... */
+            if (source < sourceEnd) {
+                UTF32 ch2 = *source;
+                /* If it's a low surrogate, convert to UTF32. */
+                if (ch2 >= UNI_SUR_LOW_START && ch2 <= UNI_SUR_LOW_END) {
+                    ch = ((ch - UNI_SUR_HIGH_START) << halfShift)
+                        + (ch2 - UNI_SUR_LOW_START) + halfBase;
+                    ++source;
+                } else if (flags == strictConversion) { /* it's an unpaired high surrogate */
+                    --source; /* return to the illegal value itself */
+                    result = sourceIllegal;
+                    break;
+                }
+            } else { /* We don't have the 16 bits following the high surrogate. */
+                --source; /* return to the high surrogate */
+                result = sourceExhausted;
+                break;
+            }
+        } else if (flags == strictConversion) {
+            /* UTF-16 surrogate values are illegal in UTF-32 */
+            if (ch >= UNI_SUR_LOW_START && ch <= UNI_SUR_LOW_END) {
+                --source; /* return to the illegal value itself */
+                result = sourceIllegal;
+                break;
+            }
+        }
+        /* Figure out how many bytes the result will require */
+        if (ch < (UTF32)0x80) {      bytesToWrite = 1;
+        } else if (ch < (UTF32)0x800) {     bytesToWrite = 2;
+        } else if (ch < (UTF32)0x10000) {   bytesToWrite = 3;
+        } else if (ch < (UTF32)0x110000) {  bytesToWrite = 4;
+        } else {                            bytesToWrite = 3;
+                                            ch = UNI_REPLACEMENT_CHAR;
+        }
+
+        target += bytesToWrite;
+        if (target > targetEnd) {
+            source = oldSource; /* Back up source pointer! */
+            target -= bytesToWrite; result = targetExhausted; break;
+        }
+        switch (bytesToWrite) { /* note: everything falls through. */
+            case 4: *--target = (UTF8)((ch | byteMark) & byteMask); ch >>= 6;
+            case 3: *--target = (UTF8)((ch | byteMark) & byteMask); ch >>= 6;
+            case 2: *--target = (UTF8)((ch | byteMark) & byteMask); ch >>= 6;
+            case 1: *--target =  (UTF8)(ch | firstByteMark[bytesToWrite]);
+        }
+        target += bytesToWrite;
+    }
+    *sourceStart = source;
+    *targetStart = target;
+    return result;
+}
+
+/* --------------------------------------------------------------------- */
+
+ConversionResult ConvertUTF32toUTF8 (
+        const UTF32** sourceStart, const UTF32* sourceEnd,
+        UTF8** targetStart, UTF8* targetEnd, ConversionFlags flags) {
+    ConversionResult result = conversionOK;
+    const UTF32* source = *sourceStart;
+    UTF8* target = *targetStart;
+    while (source < sourceEnd) {
+        UTF32 ch;
+        unsigned short bytesToWrite = 0;
+        const UTF32 byteMask = 0xBF;
+        const UTF32 byteMark = 0x80;
+        ch = *source++;
+        if (flags == strictConversion ) {
+            /* UTF-16 surrogate values are illegal in UTF-32 */
+            if (ch >= UNI_SUR_HIGH_START && ch <= UNI_SUR_LOW_END) {
+                --source; /* return to the illegal value itself */
+                result = sourceIllegal;
+                break;
+            }
+        }
+        /*
+         * Figure out how many bytes the result will require. Turn any
+         * illegally large UTF32 things (> Plane 17) into replacement chars.
+         */
+        if (ch < (UTF32)0x80) {      bytesToWrite = 1;
+        } else if (ch < (UTF32)0x800) {     bytesToWrite = 2;
+        } else if (ch < (UTF32)0x10000) {   bytesToWrite = 3;
+        } else if (ch <= UNI_MAX_LEGAL_UTF32) {  bytesToWrite = 4;
+        } else {                            bytesToWrite = 3;
+                                            ch = UNI_REPLACEMENT_CHAR;
+                                            result = sourceIllegal;
+        }
+
+        target += bytesToWrite;
+        if (target > targetEnd) {
+            --source; /* Back up source pointer! */
+            target -= bytesToWrite; result = targetExhausted; break;
+        }
+        switch (bytesToWrite) { /* note: everything falls through. */
+            case 4: *--target = (UTF8)((ch | byteMark) & byteMask); ch >>= 6;
+            case 3: *--target = (UTF8)((ch | byteMark) & byteMask); ch >>= 6;
+            case 2: *--target = (UTF8)((ch | byteMark) & byteMask); ch >>= 6;
+            case 1: *--target = (UTF8) (ch | firstByteMark[bytesToWrite]);
+        }
+        target += bytesToWrite;
+    }
+    *sourceStart = source;
+    *targetStart = target;
+    return result;
+}
+
+/* --------------------------------------------------------------------- */
+
+/*
+ * Utility routine to tell whether a sequence of bytes is legal UTF-8.
+ * This must be called with the length pre-determined by the first byte.
+ * If not calling this from ConvertUTF8to*, then the length can be set by:
+ *  length = trailingBytesForUTF8[*source]+1;
+ * and the sequence is illegal right away if there aren't that many bytes
+ * available.
+ * If presented with a length > 4, this returns false.  The Unicode
+ * definition of UTF-8 goes up to 4-byte sequences.
+ */
+
+static Boolean isLegalUTF8(const UTF8 *source, int length) {
+    UTF8 a;
+    const UTF8 *srcptr = source+length;
+    switch (length) {
+    default: return false;
+        /* Everything else falls through when "true"... */
+    case 4: if ((a = (*--srcptr)) < 0x80 || a > 0xBF) return false;
+    case 3: if ((a = (*--srcptr)) < 0x80 || a > 0xBF) return false;
+    case 2: if ((a = (*--srcptr)) < 0x80 || a > 0xBF) return false;
+
+        switch (*source) {
+            /* no fall-through in this inner switch */
+            case 0xE0: if (a < 0xA0) return false; break;
+            case 0xED: if (a > 0x9F) return false; break;
+            case 0xF0: if (a < 0x90) return false; break;
+            case 0xF4: if (a > 0x8F) return false; break;
+            default:   if (a < 0x80) return false;
+        }
+
+    case 1: if (*source >= 0x80 && *source < 0xC2) return false;
+    }
+    if (*source > 0xF4) return false;
+    return true;
+}
+
+/* --------------------------------------------------------------------- */
+
+/*
+ * Exported function to return whether a UTF-8 sequence is legal or not.
+ * This is not used here; it's just exported.
+ */
+Boolean isLegalUTF8Sequence(const UTF8 *source, const UTF8 *sourceEnd) {
+    int length = trailingBytesForUTF8[*source]+1;
+    if (length > sourceEnd - source) {
+        return false;
+    }
+    return isLegalUTF8(source, length);
+}
+
+/* --------------------------------------------------------------------- */
+
+static unsigned
+findMaximalSubpartOfIllFormedUTF8Sequence(const UTF8 *source,
+                                          const UTF8 *sourceEnd) {
+  UTF8 b1, b2, b3;
+
+  assert(!isLegalUTF8Sequence(source, sourceEnd));
+
+  /*
+   * Unicode 6.3.0, D93b:
+   *
+   *   Maximal subpart of an ill-formed subsequence: The longest code unit
+   *   subsequence starting at an unconvertible offset that is either:
+   *   a. the initial subsequence of a well-formed code unit sequence, or
+   *   b. a subsequence of length one.
+   */
+
+  if (source == sourceEnd)
+    return 0;
+
+  /*
+   * Perform case analysis.  See Unicode 6.3.0, Table 3-7. Well-Formed UTF-8
+   * Byte Sequences.
+   */
+
+  b1 = *source;
+  ++source;
+  if (b1 >= 0xC2 && b1 <= 0xDF) {
+    /*
+     * First byte is valid, but we know that this code unit sequence is
+     * invalid, so the maximal subpart has to end after the first byte.
+     */
+    return 1;
+  }
+
+  if (source == sourceEnd)
+    return 1;
+
+  b2 = *source;
+  ++source;
+
+  if (b1 == 0xE0) {
+    return (b2 >= 0xA0 && b2 <= 0xBF) ? 2 : 1;
+  }
+  if (b1 >= 0xE1 && b1 <= 0xEC) {
+    return (b2 >= 0x80 && b2 <= 0xBF) ? 2 : 1;
+  }
+  if (b1 == 0xED) {
+    return (b2 >= 0x80 && b2 <= 0x9F) ? 2 : 1;
+  }
+  if (b1 >= 0xEE && b1 <= 0xEF) {
+    return (b2 >= 0x80 && b2 <= 0xBF) ? 2 : 1;
+  }
+  if (b1 == 0xF0) {
+    if (b2 >= 0x90 && b2 <= 0xBF) {
+      if (source == sourceEnd)
+        return 2;
+
+      b3 = *source;
+      return (b3 >= 0x80 && b3 <= 0xBF) ? 3 : 2;
+    }
+    return 1;
+  }
+  if (b1 >= 0xF1 && b1 <= 0xF3) {
+    if (b2 >= 0x80 && b2 <= 0xBF) {
+      if (source == sourceEnd)
+        return 2;
+
+      b3 = *source;
+      return (b3 >= 0x80 && b3 <= 0xBF) ? 3 : 2;
+    }
+    return 1;
+  }
+  if (b1 == 0xF4) {
+    if (b2 >= 0x80 && b2 <= 0x8F) {
+      if (source == sourceEnd)
+        return 2;
+
+      b3 = *source;
+      return (b3 >= 0x80 && b3 <= 0xBF) ? 3 : 2;
+    }
+    return 1;
+  }
+
+  assert((b1 >= 0x80 && b1 <= 0xC1) || b1 >= 0xF5);
+  /*
+   * There are no valid sequences that start with these bytes.  Maximal subpart
+   * is defined to have length 1 in these cases.
+   */
+  return 1;
+}
+
+/* --------------------------------------------------------------------- */
+
+/*
+ * Exported function to return the total number of bytes in a codepoint
+ * represented in UTF-8, given the value of the first byte.
+ */
+unsigned getNumBytesForUTF8(UTF8 first) {
+  return trailingBytesForUTF8[first] + 1;
+}
+
+/* --------------------------------------------------------------------- */
+
+/*
+ * Exported function to return whether a UTF-8 string is legal or not.
+ * This is not used here; it's just exported.
+ */
+Boolean isLegalUTF8String(const UTF8 **source, const UTF8 *sourceEnd) {
+    while (*source != sourceEnd) {
+        int length = trailingBytesForUTF8[**source] + 1;
+        if (length > sourceEnd - *source || !isLegalUTF8(*source, length))
+            return false;
+        *source += length;
+    }
+    return true;
+}
+
+/* --------------------------------------------------------------------- */
+
+ConversionResult ConvertUTF8toUTF16 (
+        const UTF8** sourceStart, const UTF8* sourceEnd,
+        UTF16** targetStart, UTF16* targetEnd, ConversionFlags flags) {
+    ConversionResult result = conversionOK;
+    const UTF8* source = *sourceStart;
+    UTF16* target = *targetStart;
+    while (source < sourceEnd) {
+        UTF32 ch = 0;
+        unsigned short extraBytesToRead = trailingBytesForUTF8[*source];
+        if (extraBytesToRead >= sourceEnd - source) {
+            result = sourceExhausted; break;
+        }
+        /* Do this check whether lenient or strict */
+        if (!isLegalUTF8(source, extraBytesToRead+1)) {
+            result = sourceIllegal;
+            break;
+        }
+        /*
+         * The cases all fall through. See "Note A" below.
+         */
+        switch (extraBytesToRead) {
+            case 5: ch += *source++; ch <<= 6; /* remember, illegal UTF-8 */
+            case 4: ch += *source++; ch <<= 6; /* remember, illegal UTF-8 */
+            case 3: ch += *source++; ch <<= 6;
+            case 2: ch += *source++; ch <<= 6;
+            case 1: ch += *source++; ch <<= 6;
+            case 0: ch += *source++;
+        }
+        ch -= offsetsFromUTF8[extraBytesToRead];
+
+        if (target >= targetEnd) {
+            source -= (extraBytesToRead+1); /* Back up source pointer! */
+            result = targetExhausted; break;
+        }
+        if (ch <= UNI_MAX_BMP) { /* Target is a character <= 0xFFFF */
+            /* UTF-16 surrogate values are illegal in UTF-32 */
+            if (ch >= UNI_SUR_HIGH_START && ch <= UNI_SUR_LOW_END) {
+                if (flags == strictConversion) {
+                    source -= (extraBytesToRead+1); /* return to the illegal value itself */
+                    result = sourceIllegal;
+                    break;
+                } else {
+                    *target++ = UNI_REPLACEMENT_CHAR;
+                }
+            } else {
+                *target++ = (UTF16)ch; /* normal case */
+            }
+        } else if (ch > UNI_MAX_UTF16) {
+            if (flags == strictConversion) {
+                result = sourceIllegal;
+                source -= (extraBytesToRead+1); /* return to the start */
+                break; /* Bail out; shouldn't continue */
+            } else {
+                *target++ = UNI_REPLACEMENT_CHAR;
+            }
+        } else {
+            /* target is a character in range 0xFFFF - 0x10FFFF. */
+            if (target + 1 >= targetEnd) {
+                source -= (extraBytesToRead+1); /* Back up source pointer! */
+                result = targetExhausted; break;
+            }
+            ch -= halfBase;
+            *target++ = (UTF16)((ch >> halfShift) + UNI_SUR_HIGH_START);
+            *target++ = (UTF16)((ch & halfMask) + UNI_SUR_LOW_START);
+        }
+    }
+    *sourceStart = source;
+    *targetStart = target;
+    return result;
+}
+
+/* --------------------------------------------------------------------- */
+
+static ConversionResult ConvertUTF8toUTF32Impl(
+        const UTF8** sourceStart, const UTF8* sourceEnd,
+        UTF32** targetStart, UTF32* targetEnd, ConversionFlags flags,
+        Boolean InputIsPartial) {
+    ConversionResult result = conversionOK;
+    const UTF8* source = *sourceStart;
+    UTF32* target = *targetStart;
+    while (source < sourceEnd) {
+        UTF32 ch = 0;
+        unsigned short extraBytesToRead = trailingBytesForUTF8[*source];
+        if (extraBytesToRead >= sourceEnd - source) {
+            if (flags == strictConversion || InputIsPartial) {
+                result = sourceExhausted;
+                break;
+            } else {
+                result = sourceIllegal;
+
+                /*
+                 * Replace the maximal subpart of ill-formed sequence with
+                 * replacement character.
+                 */
+                source += findMaximalSubpartOfIllFormedUTF8Sequence(source,
+                                                                    sourceEnd);
+                *target++ = UNI_REPLACEMENT_CHAR;
+                continue;
+            }
+        }
+        if (target >= targetEnd) {
+            result = targetExhausted; break;
+        }
+
+        /* Do this check whether lenient or strict */
+        if (!isLegalUTF8(source, extraBytesToRead+1)) {
+            result = sourceIllegal;
+            if (flags == strictConversion) {
+                /* Abort conversion. */
+                break;
+            } else {
+                /*
+                 * Replace the maximal subpart of ill-formed sequence with
+                 * replacement character.
+                 */
+                source += findMaximalSubpartOfIllFormedUTF8Sequence(source,
+                                                                    sourceEnd);
+                *target++ = UNI_REPLACEMENT_CHAR;
+                continue;
+            }
+        }
+        /*
+         * The cases all fall through. See "Note A" below.
+         */
+        switch (extraBytesToRead) {
+            case 5: ch += *source++; ch <<= 6;
+            case 4: ch += *source++; ch <<= 6;
+            case 3: ch += *source++; ch <<= 6;
+            case 2: ch += *source++; ch <<= 6;
+            case 1: ch += *source++; ch <<= 6;
+            case 0: ch += *source++;
+        }
+        ch -= offsetsFromUTF8[extraBytesToRead];
+
+        if (ch <= UNI_MAX_LEGAL_UTF32) {
+            /*
+             * UTF-16 surrogate values are illegal in UTF-32, and anything
+             * over Plane 17 (> 0x10FFFF) is illegal.
+             */
+            if (ch >= UNI_SUR_HIGH_START && ch <= UNI_SUR_LOW_END) {
+                if (flags == strictConversion) {
+                    source -= (extraBytesToRead+1); /* return to the illegal value itself */
+                    result = sourceIllegal;
+                    break;
+                } else {
+                    *target++ = UNI_REPLACEMENT_CHAR;
+                }
+            } else {
+                *target++ = ch;
+            }
+        } else { /* i.e., ch > UNI_MAX_LEGAL_UTF32 */
+            result = sourceIllegal;
+            *target++ = UNI_REPLACEMENT_CHAR;
+        }
+    }
+    *sourceStart = source;
+    *targetStart = target;
+    return result;
+}
+
+ConversionResult ConvertUTF8toUTF32Partial(const UTF8 **sourceStart,
+                                           const UTF8 *sourceEnd,
+                                           UTF32 **targetStart,
+                                           UTF32 *targetEnd,
+                                           ConversionFlags flags) {
+  return ConvertUTF8toUTF32Impl(sourceStart, sourceEnd, targetStart, targetEnd,
+                                flags, /*InputIsPartial=*/true);
+}
+
+ConversionResult ConvertUTF8toUTF32(const UTF8 **sourceStart,
+                                    const UTF8 *sourceEnd, UTF32 **targetStart,
+                                    UTF32 *targetEnd, ConversionFlags flags) {
+  return ConvertUTF8toUTF32Impl(sourceStart, sourceEnd, targetStart, targetEnd,
+                                flags, /*InputIsPartial=*/false);
+}
+
+/* ---------------------------------------------------------------------
+
+    Note A.
+    The fall-through switches in UTF-8 reading code save a
+    temp variable, some decrements & conditionals.  The switches
+    are equivalent to the following loop:
+        {
+            int tmpBytesToRead = extraBytesToRead+1;
+            do {
+                ch += *source++;
+                --tmpBytesToRead;
+                if (tmpBytesToRead) ch <<= 6;
+            } while (tmpBytesToRead > 0);
+        }
+    In UTF-8 writing code, the switches on "bytesToWrite" are
+    similarly unrolled loops.
+
+   --------------------------------------------------------------------- */
+
+#ifdef _WIN32
+
+namespace sys {
+namespace windows {
+std::error_code CodePageToUTF16(unsigned codepage,
+                                std::string_view original,
+                                wpi::SmallVectorImpl<wchar_t> &utf16) {
+  if (!original.empty()) {
+    int len = ::MultiByteToWideChar(codepage, MB_ERR_INVALID_CHARS, original.data(),
+                                    original.size(), utf16.begin(), 0);
+
+    if (len == 0) {
+      return mapWindowsError(::GetLastError());
+    }
+
+    utf16.reserve(len + 1);
+    utf16.resize_for_overwrite(len);
+
+    len = ::MultiByteToWideChar(codepage, MB_ERR_INVALID_CHARS, original.data(),
+                                original.size(), utf16.begin(), utf16.size());
+
+    if (len == 0) {
+      return mapWindowsError(::GetLastError());
+    }
+  }
+
+  // Make utf16 null terminated.
+  utf16.push_back(0);
+  utf16.pop_back();
+
+  return std::error_code();
+}
+
+std::error_code UTF8ToUTF16(std::string_view utf8,
+                            wpi::SmallVectorImpl<wchar_t> &utf16) {
+  return CodePageToUTF16(CP_UTF8, utf8, utf16);
+}
+
+std::error_code CurCPToUTF16(std::string_view curcp,
+                            wpi::SmallVectorImpl<wchar_t> &utf16) {
+  return CodePageToUTF16(CP_ACP, curcp, utf16);
+}
+
+static
+std::error_code UTF16ToCodePage(unsigned codepage, const wchar_t *utf16,
+                                size_t utf16_len,
+                                wpi::SmallVectorImpl<char> &converted) {
+  if (utf16_len) {
+    // Get length.
+    int len = ::WideCharToMultiByte(codepage, 0, utf16, utf16_len, converted.begin(),
+                                    0, NULL, NULL);
+
+    if (len == 0) {
+      return mapWindowsError(::GetLastError());
+    }
+
+    converted.reserve(len);
+    converted.resize_for_overwrite(len);
+
+    // Now do the actual conversion.
+    len = ::WideCharToMultiByte(codepage, 0, utf16, utf16_len, converted.data(),
+                                converted.size(), NULL, NULL);
+
+    if (len == 0) {
+      return mapWindowsError(::GetLastError());
+    }
+  }
+
+  // Make the new string null terminated.
+  converted.push_back(0);
+  converted.pop_back();
+
+  return std::error_code();
+}
+
+std::error_code UTF16ToUTF8(const wchar_t *utf16, size_t utf16_len,
+                            wpi::SmallVectorImpl<char> &utf8) {
+  return UTF16ToCodePage(CP_UTF8, utf16, utf16_len, utf8);
+}
+
+std::error_code UTF16ToCurCP(const wchar_t *utf16, size_t utf16_len,
+                             wpi::SmallVectorImpl<char> &curcp) {
+  return UTF16ToCodePage(CP_ACP, utf16, utf16_len, curcp);
+}
+
+} // end namespace windows
+} // end namespace sys
+
+#endif  // _WIN32
+
+} // namespace wpi
+
+ConvertUTF_RESTORE_WARNINGS
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/ConvertUTFWrapper.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/ConvertUTFWrapper.cpp
new file mode 100644
index 0000000..e95c04f
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/ConvertUTFWrapper.cpp
@@ -0,0 +1,253 @@
+//===-- ConvertUTFWrapper.cpp - Wrap ConvertUTF.h with clang data types -----===
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+
+#include <span>
+#include "wpi/ConvertUTF.h"
+#include "wpi/SmallVector.h"
+#include "wpi/ErrorHandling.h"
+#include "wpi/SwapByteOrder.h"
+#include <string>
+#include <string_view>
+#include <vector>
+
+namespace wpi {
+
+bool ConvertUTF8toWide(unsigned WideCharWidth, std::string_view Source,
+                       char *&ResultPtr, const UTF8 *&ErrorPtr) {
+  assert(WideCharWidth == 1 || WideCharWidth == 2 || WideCharWidth == 4);
+  ConversionResult result = conversionOK;
+  // Copy the character std::span over.
+  if (WideCharWidth == 1) {
+    const UTF8 *Pos = reinterpret_cast<const UTF8*>(Source.data());
+    if (!isLegalUTF8String(&Pos, reinterpret_cast<const UTF8*>(Source.data() + Source.size()))) {
+      result = sourceIllegal;
+      ErrorPtr = Pos;
+    } else {
+      memcpy(ResultPtr, Source.data(), Source.size());
+      ResultPtr += Source.size();
+    }
+  } else if (WideCharWidth == 2) {
+    const UTF8 *sourceStart = (const UTF8*)Source.data();
+    // FIXME: Make the type of the result buffer correct instead of
+    // using reinterpret_cast.
+    UTF16 *targetStart = reinterpret_cast<UTF16*>(ResultPtr);
+    ConversionFlags flags = strictConversion;
+    result = ConvertUTF8toUTF16(
+        &sourceStart, sourceStart + Source.size(),
+        &targetStart, targetStart + Source.size(), flags);
+    if (result == conversionOK)
+      ResultPtr = reinterpret_cast<char*>(targetStart);
+    else
+      ErrorPtr = sourceStart;
+  } else if (WideCharWidth == 4) {
+    const UTF8 *sourceStart = (const UTF8*)Source.data();
+    // FIXME: Make the type of the result buffer correct instead of
+    // using reinterpret_cast.
+    UTF32 *targetStart = reinterpret_cast<UTF32*>(ResultPtr);
+    ConversionFlags flags = strictConversion;
+    result = ConvertUTF8toUTF32(
+        &sourceStart, sourceStart + Source.size(),
+        &targetStart, targetStart + Source.size(), flags);
+    if (result == conversionOK)
+      ResultPtr = reinterpret_cast<char*>(targetStart);
+    else
+      ErrorPtr = sourceStart;
+  }
+  assert((result != targetExhausted)
+         && "ConvertUTF8toUTFXX exhausted target buffer");
+  return result == conversionOK;
+}
+
+bool ConvertCodePointToUTF8(unsigned Source, char *&ResultPtr) {
+  const UTF32 *SourceStart = &Source;
+  const UTF32 *SourceEnd = SourceStart + 1;
+  UTF8 *TargetStart = reinterpret_cast<UTF8 *>(ResultPtr);
+  UTF8 *TargetEnd = TargetStart + 4;
+  ConversionResult CR = ConvertUTF32toUTF8(&SourceStart, SourceEnd,
+                                           &TargetStart, TargetEnd,
+                                           strictConversion);
+  if (CR != conversionOK)
+    return false;
+
+  ResultPtr = reinterpret_cast<char*>(TargetStart);
+  return true;
+}
+
+bool hasUTF16ByteOrderMark(std::span<const char> S) {
+  return (S.size() >= 2 &&
+          ((S[0] == '\xff' && S[1] == '\xfe') ||
+           (S[0] == '\xfe' && S[1] == '\xff')));
+}
+
+bool convertUTF16ToUTF8String(std::span<const char> SrcBytes, SmallVectorImpl<char> &Out) {
+  assert(Out.empty());
+
+  // Error out on an uneven byte count.
+  if (SrcBytes.size() % 2)
+    return false;
+
+  // Avoid OOB by returning early on empty input.
+  if (SrcBytes.empty())
+    return true;
+
+  const UTF16 *Src = reinterpret_cast<const UTF16 *>(&*SrcBytes.begin());
+  const UTF16 *SrcEnd = reinterpret_cast<const UTF16 *>(&*SrcBytes.begin() + SrcBytes.size());
+
+  assert((uintptr_t)Src % sizeof(UTF16) == 0);
+
+  // Byteswap if necessary.
+  std::vector<UTF16> ByteSwapped;
+  if (Src[0] == UNI_UTF16_BYTE_ORDER_MARK_SWAPPED) {
+    ByteSwapped.insert(ByteSwapped.end(), Src, SrcEnd);
+    for (UTF16 &I : ByteSwapped)
+      I = wpi::ByteSwap_16(I);
+    Src = &ByteSwapped[0];
+    SrcEnd = &ByteSwapped[ByteSwapped.size() - 1] + 1;
+  }
+
+  // Skip the BOM for conversion.
+  if (Src[0] == UNI_UTF16_BYTE_ORDER_MARK_NATIVE)
+    Src++;
+
+  // Just allocate enough space up front.  We'll shrink it later.  Allocate
+  // enough that we can fit a null terminator without reallocating.
+  Out.resize(SrcBytes.size() * UNI_MAX_UTF8_BYTES_PER_CODE_POINT + 1);
+  UTF8 *Dst = reinterpret_cast<UTF8 *>(&Out[0]);
+  UTF8 *DstEnd = Dst + Out.size();
+
+  ConversionResult CR =
+      ConvertUTF16toUTF8(&Src, SrcEnd, &Dst, DstEnd, strictConversion);
+  assert(CR != targetExhausted);
+
+  if (CR != conversionOK) {
+    Out.clear();
+    return false;
+  }
+
+  Out.resize(reinterpret_cast<char *>(Dst) - &Out[0]);
+  Out.push_back(0);
+  Out.pop_back();
+  return true;
+}
+
+bool convertUTF16ToUTF8String(std::span<const UTF16> Src, SmallVectorImpl<char> &Out)
+{
+  return convertUTF16ToUTF8String(
+      std::span<const char>(reinterpret_cast<const char *>(Src.data()),
+      Src.size() * sizeof(UTF16)), Out);
+}
+
+bool convertUTF8ToUTF16String(std::string_view SrcUTF8,
+                              SmallVectorImpl<UTF16> &DstUTF16) {
+  assert(DstUTF16.empty());
+
+  // Avoid OOB by returning early on empty input.
+  if (SrcUTF8.empty()) {
+    DstUTF16.push_back(0);
+    DstUTF16.pop_back();
+    return true;
+  }
+
+  const UTF8 *Src = reinterpret_cast<const UTF8 *>(SrcUTF8.data());
+  const UTF8 *SrcEnd = reinterpret_cast<const UTF8 *>(SrcUTF8.data() + SrcUTF8.size());
+
+  // Allocate the same number of UTF-16 code units as UTF-8 code units. Encoding
+  // as UTF-16 should always require the same amount or less code units than the
+  // UTF-8 encoding.  Allocate one extra byte for the null terminator though,
+  // so that someone calling DstUTF16.data() gets a null terminated string.
+  // We resize down later so we don't have to worry that this over allocates.
+  DstUTF16.resize(SrcUTF8.size()+1);
+  UTF16 *Dst = &DstUTF16[0];
+  UTF16 *DstEnd = Dst + DstUTF16.size();
+
+  ConversionResult CR =
+      ConvertUTF8toUTF16(&Src, SrcEnd, &Dst, DstEnd, strictConversion);
+  assert(CR != targetExhausted);
+
+  if (CR != conversionOK) {
+    DstUTF16.clear();
+    return false;
+  }
+
+  DstUTF16.resize(Dst - &DstUTF16[0]);
+  DstUTF16.push_back(0);
+  DstUTF16.pop_back();
+  return true;
+}
+
+static_assert(sizeof(wchar_t) == 1 || sizeof(wchar_t) == 2 ||
+                  sizeof(wchar_t) == 4,
+              "Expected wchar_t to be 1, 2, or 4 bytes");
+
+template <typename TResult>
+static inline bool ConvertUTF8toWideInternal(std::string_view Source,
+                                             TResult &Result) {
+  // Even in the case of UTF-16, the number of bytes in a UTF-8 string is
+  // at least as large as the number of elements in the resulting wide
+  // string, because surrogate pairs take at least 4 bytes in UTF-8.
+  Result.resize(Source.size() + 1);
+  char *ResultPtr = reinterpret_cast<char *>(&Result[0]);
+  const UTF8 *ErrorPtr;
+  if (!ConvertUTF8toWide(sizeof(wchar_t), Source, ResultPtr, ErrorPtr)) {
+    Result.clear();
+    return false;
+  }
+  Result.resize(reinterpret_cast<wchar_t *>(ResultPtr) - &Result[0]);
+  return true;
+}
+
+bool ConvertUTF8toWide(std::string_view Source, std::wstring &Result) {
+  return ConvertUTF8toWideInternal(Source, Result);
+}
+
+bool ConvertUTF8toWide(const char *Source, std::wstring &Result) {
+  if (!Source) {
+    Result.clear();
+    return true;
+  }
+  return ConvertUTF8toWide(std::string_view(Source), Result);
+}
+
+bool convertWideToUTF8(const std::wstring &Source, SmallVectorImpl<char> &Result) {
+  if (sizeof(wchar_t) == 1) {
+    const UTF8 *Start = reinterpret_cast<const UTF8 *>(Source.data());
+    const UTF8 *End =
+        reinterpret_cast<const UTF8 *>(Source.data() + Source.size());
+    if (!isLegalUTF8String(&Start, End))
+      return false;
+    Result.resize(Source.size());
+    memcpy(&Result[0], Source.data(), Source.size());
+    return true;
+  } else if (sizeof(wchar_t) == 2) {
+    return convertUTF16ToUTF8String(
+        std::span<const UTF16>(reinterpret_cast<const UTF16 *>(Source.data()),
+                              Source.size()),
+        Result);
+  } else if (sizeof(wchar_t) == 4) {
+    const UTF32 *Start = reinterpret_cast<const UTF32 *>(Source.data());
+    const UTF32 *End =
+        reinterpret_cast<const UTF32 *>(Source.data() + Source.size());
+    Result.resize(UNI_MAX_UTF8_BYTES_PER_CODE_POINT * Source.size());
+    UTF8 *ResultPtr = reinterpret_cast<UTF8 *>(&Result[0]);
+    UTF8 *ResultEnd = reinterpret_cast<UTF8 *>(&Result[0] + Result.size());
+    if (ConvertUTF32toUTF8(&Start, End, &ResultPtr, ResultEnd,
+                           strictConversion) == conversionOK) {
+      Result.resize(reinterpret_cast<char *>(ResultPtr) - &Result[0]);
+      return true;
+    } else {
+      Result.clear();
+      return false;
+    }
+  } else {
+    wpi_unreachable(
+        "Control should never reach this point; see static_assert further up");
+  }
+}
+
+} // end namespace wpi
+
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/ErrorHandling.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/ErrorHandling.cpp
new file mode 100644
index 0000000..ea89b38
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/ErrorHandling.cpp
@@ -0,0 +1,245 @@
+//===- lib/Support/ErrorHandling.cpp - Callbacks for errors ---------------===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+//
+// This file defines an API used to indicate fatal error conditions.  Non-fatal
+// errors (most of them) should be handled through LLVMContext.
+//
+//===----------------------------------------------------------------------===//
+
+#include "wpi/ErrorHandling.h"
+#include "wpi/SmallVector.h"
+#include "wpi/Errc.h"
+#include "wpi/WindowsError.h"
+#include "fmt/format.h"
+#include <cassert>
+#include <cstdlib>
+#include <mutex>
+#include <new>
+
+#ifndef _WIN32
+#include <unistd.h>
+#endif
+#if defined(_MSC_VER)
+#include <io.h>
+#endif
+
+using namespace wpi;
+
+static fatal_error_handler_t ErrorHandler = nullptr;
+static void *ErrorHandlerUserData = nullptr;
+
+static fatal_error_handler_t BadAllocErrorHandler = nullptr;
+static void *BadAllocErrorHandlerUserData = nullptr;
+
+// Mutexes to synchronize installing error handlers and calling error handlers.
+// Do not use ManagedStatic, or that may allocate memory while attempting to
+// report an OOM.
+//
+// This usage of std::mutex has to be conditionalized behind ifdefs because
+// of this script:
+//   compiler-rt/lib/sanitizer_common/symbolizer/scripts/build_symbolizer.sh
+// That script attempts to statically link the LLVM symbolizer library with the
+// STL and hide all of its symbols with 'opt -internalize'. To reduce size, it
+// cuts out the threading portions of the hermetic copy of libc++ that it
+// builds. We can remove these ifdefs if that script goes away.
+static std::mutex ErrorHandlerMutex;
+static std::mutex BadAllocErrorHandlerMutex;
+
+void wpi::install_fatal_error_handler(fatal_error_handler_t handler,
+                                       void *user_data) {
+  std::scoped_lock Lock(ErrorHandlerMutex);
+  assert(!ErrorHandler && "Error handler already registered!\n");
+  ErrorHandler = handler;
+  ErrorHandlerUserData = user_data;
+}
+
+void wpi::remove_fatal_error_handler() {
+  std::scoped_lock Lock(ErrorHandlerMutex);
+  ErrorHandler = nullptr;
+  ErrorHandlerUserData = nullptr;
+}
+
+void wpi::report_fatal_error(const char *Reason, bool GenCrashDiag) {
+  report_fatal_error(std::string_view(Reason), GenCrashDiag);
+}
+
+void wpi::report_fatal_error(const std::string &Reason, bool GenCrashDiag) {
+  report_fatal_error(std::string_view(Reason), GenCrashDiag);
+}
+
+void wpi::report_fatal_error(std::string_view Reason, bool GenCrashDiag) {
+  wpi::fatal_error_handler_t handler = nullptr;
+  void* handlerData = nullptr;
+  {
+    // Only acquire the mutex while reading the handler, so as not to invoke a
+    // user-supplied callback under a lock.
+    std::scoped_lock Lock(ErrorHandlerMutex);
+    handler = ErrorHandler;
+    handlerData = ErrorHandlerUserData;
+  }
+
+  if (handler) {
+    handler(handlerData, std::string{Reason}.c_str(), GenCrashDiag);
+  } else {
+    fmt::print(stderr, "LLVM ERROR: {}\n", Reason);
+  }
+
+  exit(1);
+}
+
+void wpi::install_bad_alloc_error_handler(fatal_error_handler_t handler,
+                                           void *user_data) {
+  std::scoped_lock Lock(BadAllocErrorHandlerMutex);
+  assert(!ErrorHandler && "Bad alloc error handler already registered!\n");
+  BadAllocErrorHandler = handler;
+  BadAllocErrorHandlerUserData = user_data;
+}
+
+void wpi::remove_bad_alloc_error_handler() {
+  std::scoped_lock Lock(BadAllocErrorHandlerMutex);
+  BadAllocErrorHandler = nullptr;
+  BadAllocErrorHandlerUserData = nullptr;
+}
+
+void wpi::report_bad_alloc_error(const char *Reason, bool GenCrashDiag) {
+  fatal_error_handler_t Handler = nullptr;
+  void *HandlerData = nullptr;
+  {
+    // Only acquire the mutex while reading the handler, so as not to invoke a
+    // user-supplied callback under a lock.
+    std::scoped_lock Lock(BadAllocErrorHandlerMutex);
+    Handler = BadAllocErrorHandler;
+    HandlerData = BadAllocErrorHandlerUserData;
+  }
+
+  if (Handler) {
+    Handler(HandlerData, Reason, GenCrashDiag);
+    wpi_unreachable("bad alloc handler should not return");
+  }
+
+  // Don't call the normal error handler. It may allocate memory. Directly write
+  // an OOM to stderr and abort.
+  const char *OOMMessage = "LLVM ERROR: out of memory\n";
+  const char *Newline = "\n";
+#ifdef _WIN32
+  (void)!::_write(2, OOMMessage, strlen(OOMMessage));
+  (void)!::_write(2, Reason, strlen(Reason));
+  (void)!::_write(2, Newline, strlen(Newline));
+#else
+  (void)!::write(2, OOMMessage, strlen(OOMMessage));
+  (void)!::write(2, Reason, strlen(Reason));
+  (void)!::write(2, Newline, strlen(Newline));
+#endif
+  abort();
+}
+
+// Causes crash on allocation failure. It is called prior to the handler set by
+// 'install_bad_alloc_error_handler'.
+static void out_of_memory_new_handler() {
+  wpi::report_bad_alloc_error("Allocation failed");
+}
+
+// Installs new handler that causes crash on allocation failure. It is called by
+// InitLLVM.
+void wpi::install_out_of_memory_new_handler() {
+  std::new_handler old = std::set_new_handler(out_of_memory_new_handler);
+  (void)old;
+  assert((old == nullptr || old == out_of_memory_new_handler) &&
+         "new-handler already installed");
+}
+
+void wpi::wpi_unreachable_internal(const char *msg, const char *file,
+                                     unsigned line) {
+  // This code intentionally doesn't call the ErrorHandler callback, because
+  // wpi_unreachable is intended to be used to indicate "impossible"
+  // situations, and not legitimate runtime errors.
+  if (msg)
+    fmt::print(stderr, "{}\n", msg);
+  std::fputs("UNREACHABLE executed", stderr);
+  if (file)
+    fmt::print(stderr, " at {}:{}", file, line);
+  fmt::print(stderr, "!\n");
+  abort();
+#ifdef LLVM_BUILTIN_UNREACHABLE
+  // Windows systems and possibly others don't declare abort() to be noreturn,
+  // so use the unreachable builtin to avoid a Clang self-host warning.
+  LLVM_BUILTIN_UNREACHABLE;
+#endif
+}
+
+#ifdef _WIN32
+
+#include <winerror.h>
+
+// I'd rather not double the line count of the following.
+#define MAP_ERR_TO_COND(x, y)                                                  \
+  case x:                                                                      \
+    return std::make_error_code(std::errc::y)
+
+std::error_code wpi::mapWindowsError(unsigned EV) {
+  switch (EV) {
+    MAP_ERR_TO_COND(ERROR_ACCESS_DENIED, permission_denied);
+    MAP_ERR_TO_COND(ERROR_ALREADY_EXISTS, file_exists);
+    MAP_ERR_TO_COND(ERROR_BAD_NETPATH, no_such_file_or_directory);
+    MAP_ERR_TO_COND(ERROR_BAD_PATHNAME, no_such_file_or_directory);
+    MAP_ERR_TO_COND(ERROR_BAD_UNIT, no_such_device);
+    MAP_ERR_TO_COND(ERROR_BROKEN_PIPE, broken_pipe);
+    MAP_ERR_TO_COND(ERROR_BUFFER_OVERFLOW, filename_too_long);
+    MAP_ERR_TO_COND(ERROR_BUSY, device_or_resource_busy);
+    MAP_ERR_TO_COND(ERROR_BUSY_DRIVE, device_or_resource_busy);
+    MAP_ERR_TO_COND(ERROR_CANNOT_MAKE, permission_denied);
+    MAP_ERR_TO_COND(ERROR_CANTOPEN, io_error);
+    MAP_ERR_TO_COND(ERROR_CANTREAD, io_error);
+    MAP_ERR_TO_COND(ERROR_CANTWRITE, io_error);
+    MAP_ERR_TO_COND(ERROR_CURRENT_DIRECTORY, permission_denied);
+    MAP_ERR_TO_COND(ERROR_DEV_NOT_EXIST, no_such_device);
+    MAP_ERR_TO_COND(ERROR_DEVICE_IN_USE, device_or_resource_busy);
+    MAP_ERR_TO_COND(ERROR_DIR_NOT_EMPTY, directory_not_empty);
+    MAP_ERR_TO_COND(ERROR_DIRECTORY, invalid_argument);
+    MAP_ERR_TO_COND(ERROR_DISK_FULL, no_space_on_device);
+    MAP_ERR_TO_COND(ERROR_FILE_EXISTS, file_exists);
+    MAP_ERR_TO_COND(ERROR_FILE_NOT_FOUND, no_such_file_or_directory);
+    MAP_ERR_TO_COND(ERROR_HANDLE_DISK_FULL, no_space_on_device);
+    MAP_ERR_TO_COND(ERROR_INVALID_ACCESS, permission_denied);
+    MAP_ERR_TO_COND(ERROR_INVALID_DRIVE, no_such_device);
+    MAP_ERR_TO_COND(ERROR_INVALID_FUNCTION, function_not_supported);
+    MAP_ERR_TO_COND(ERROR_INVALID_HANDLE, invalid_argument);
+    MAP_ERR_TO_COND(ERROR_INVALID_NAME, invalid_argument);
+    MAP_ERR_TO_COND(ERROR_INVALID_PARAMETER, invalid_argument);
+    MAP_ERR_TO_COND(ERROR_LOCK_VIOLATION, no_lock_available);
+    MAP_ERR_TO_COND(ERROR_LOCKED, no_lock_available);
+    MAP_ERR_TO_COND(ERROR_NEGATIVE_SEEK, invalid_argument);
+    MAP_ERR_TO_COND(ERROR_NOACCESS, permission_denied);
+    MAP_ERR_TO_COND(ERROR_NOT_ENOUGH_MEMORY, not_enough_memory);
+    MAP_ERR_TO_COND(ERROR_NOT_READY, resource_unavailable_try_again);
+    MAP_ERR_TO_COND(ERROR_NOT_SUPPORTED, not_supported);
+    MAP_ERR_TO_COND(ERROR_OPEN_FAILED, io_error);
+    MAP_ERR_TO_COND(ERROR_OPEN_FILES, device_or_resource_busy);
+    MAP_ERR_TO_COND(ERROR_OUTOFMEMORY, not_enough_memory);
+    MAP_ERR_TO_COND(ERROR_PATH_NOT_FOUND, no_such_file_or_directory);
+    MAP_ERR_TO_COND(ERROR_READ_FAULT, io_error);
+    MAP_ERR_TO_COND(ERROR_REPARSE_TAG_INVALID, invalid_argument);
+    MAP_ERR_TO_COND(ERROR_RETRY, resource_unavailable_try_again);
+    MAP_ERR_TO_COND(ERROR_SEEK, io_error);
+    MAP_ERR_TO_COND(ERROR_SHARING_VIOLATION, permission_denied);
+    MAP_ERR_TO_COND(ERROR_TOO_MANY_OPEN_FILES, too_many_files_open);
+    MAP_ERR_TO_COND(ERROR_WRITE_FAULT, io_error);
+    MAP_ERR_TO_COND(ERROR_WRITE_PROTECT, permission_denied);
+    MAP_ERR_TO_COND(WSAEACCES, permission_denied);
+    MAP_ERR_TO_COND(WSAEBADF, bad_file_descriptor);
+    MAP_ERR_TO_COND(WSAEFAULT, bad_address);
+    MAP_ERR_TO_COND(WSAEINTR, interrupted);
+    MAP_ERR_TO_COND(WSAEINVAL, invalid_argument);
+    MAP_ERR_TO_COND(WSAEMFILE, too_many_files_open);
+    MAP_ERR_TO_COND(WSAENAMETOOLONG, filename_too_long);
+  default:
+    return std::error_code(EV, std::system_category());
+  }
+}
+
+#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/Hashing.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/Hashing.cpp
new file mode 100644
index 0000000..a719d3f
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/Hashing.cpp
@@ -0,0 +1,28 @@
+//===-------------- lib/Support/Hashing.cpp -------------------------------===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+//
+// This file provides implementation bits for the LLVM common hashing
+// infrastructure. Documentation and most of the other information is in the
+// header file.
+//
+//===----------------------------------------------------------------------===//
+
+#include "wpi/Hashing.h"
+
+using namespace wpi;
+
+// Provide a definition and static initializer for the fixed seed. This
+// initializer should always be zero to ensure its value can never appear to be
+// non-zero, even during dynamic initialization.
+uint64_t wpi::hashing::detail::fixed_seed_override = 0;
+
+// Implement the function for forced setting of the fixed seed.
+// FIXME: Use atomic operations here so that there is no data race.
+void wpi::set_fixed_execution_hash_seed(uint64_t fixed_value) {
+  hashing::detail::fixed_seed_override = fixed_value;
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/MemAlloc.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/MemAlloc.cpp
new file mode 100644
index 0000000..e2c662c
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/MemAlloc.cpp
@@ -0,0 +1,35 @@
+//===- MemAlloc.cpp - Memory allocation functions -------------------------===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+
+#include "wpi/MemAlloc.h"
+#include <new>
+
+// These are out of line to have __cpp_aligned_new not affect ABI.
+
+LLVM_ATTRIBUTE_RETURNS_NONNULL LLVM_ATTRIBUTE_RETURNS_NOALIAS void *
+wpi::allocate_buffer(size_t Size, size_t Alignment) {
+  return ::operator new(Size
+#ifdef __cpp_aligned_new
+                        ,
+                        std::align_val_t(Alignment)
+#endif
+  );
+}
+
+void wpi::deallocate_buffer(void *Ptr, size_t Size, size_t Alignment) {
+  ::operator delete(Ptr
+#ifdef __cpp_sized_deallocation
+                    ,
+                    Size
+#endif
+#ifdef __cpp_aligned_new
+                    ,
+                    std::align_val_t(Alignment)
+#endif
+  );
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/MemoryBuffer.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/MemoryBuffer.cpp
new file mode 100644
index 0000000..5beeb38
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/MemoryBuffer.cpp
@@ -0,0 +1,522 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+//===--- MemoryBuffer.cpp - Memory Buffer implementation ------------------===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+//  This file implements the MemoryBuffer interface.
+//
+//===----------------------------------------------------------------------===//
+
+#include "wpi/MemoryBuffer.h"
+
+#ifdef _MSC_VER
+// no matching operator delete
+#pragma warning(disable : 4291)
+#endif
+
+#ifdef _WIN32
+#ifndef WIN32_LEAN_AND_MEAN
+#define WIN32_LEAN_AND_MEAN
+#endif
+
+#include <windows.h>  // NOLINT(build/include_order)
+
+#endif
+
+#include <sys/stat.h>
+#include <sys/types.h>
+
+#ifdef _MSC_VER
+#include <io.h>
+#else
+#include <unistd.h>
+#endif
+
+#include <cassert>
+#include <cerrno>
+#include <cstring>
+#include <new>
+#include <system_error>
+
+#include "wpi/Errc.h"
+#include "wpi/Errno.h"
+#include "wpi/MappedFileRegion.h"
+#include "wpi/MathExtras.h"
+#include "wpi/SmallVector.h"
+#include "wpi/SmallVectorMemoryBuffer.h"
+#include "wpi/fs.h"
+
+#ifdef _WIN32
+#include "wpi/WindowsError.h"
+#endif
+
+using namespace wpi;
+
+//===----------------------------------------------------------------------===//
+// MemoryBuffer implementation itself.
+//===----------------------------------------------------------------------===//
+
+MemoryBuffer::~MemoryBuffer() {}
+
+/// init - Initialize this MemoryBuffer as a reference to externally allocated
+/// memory.
+void MemoryBuffer::Init(const uint8_t* bufStart, const uint8_t* bufEnd) {
+  m_bufferStart = bufStart;
+  m_bufferEnd = bufEnd;
+}
+
+//===----------------------------------------------------------------------===//
+// MemoryBufferMem implementation.
+//===----------------------------------------------------------------------===//
+
+/// CopyStringRef - Copies contents of a StringRef into a block of memory and
+/// null-terminates it.
+static void CopyStringView(uint8_t* memory, std::string_view data) {
+  if (!data.empty()) {
+    std::memcpy(memory, data.data(), data.size());
+  }
+  memory[data.size()] = 0;  // Null terminate string.
+}
+
+namespace {
+struct NamedBufferAlloc {
+  std::string_view name;
+  explicit NamedBufferAlloc(std::string_view name) : name(name) {}
+};
+}  // namespace
+
+void* operator new(size_t N, NamedBufferAlloc alloc) {
+  uint8_t* mem = static_cast<uint8_t*>(operator new(N + alloc.name.size() + 1));
+  CopyStringView(mem + N, alloc.name);
+  return mem;
+}
+
+namespace {
+/// MemoryBufferMem - Named MemoryBuffer pointing to a block of memory.
+template <typename MB>
+class MemoryBufferMem : public MB {
+ public:
+  explicit MemoryBufferMem(std::span<const uint8_t> inputData) {
+    MemoryBuffer::Init(inputData.data(), inputData.data() + inputData.size());
+  }
+
+  /// Disable sized deallocation for MemoryBufferMem, because it has
+  /// tail-allocated data.
+  void operator delete(void* p) { ::operator delete(p); }  // NOLINT
+
+  std::string_view GetBufferIdentifier() const override {
+    // The name is stored after the class itself.
+    return std::string_view(reinterpret_cast<const char*>(this + 1));
+  }
+
+  MemoryBuffer::BufferKind GetBufferKind() const override {
+    return MemoryBuffer::MemoryBuffer_Malloc;
+  }
+};
+}  // namespace
+
+template <typename MB>
+static std::unique_ptr<MB> GetFileAux(std::string_view filename,
+                                      std::error_code& ec, int64_t fileSize,
+                                      uint64_t mapSize, uint64_t offset);
+
+std::unique_ptr<MemoryBuffer> MemoryBuffer::GetMemBuffer(
+    std::span<const uint8_t> inputData, std::string_view bufferName) {
+  auto* ret = new (NamedBufferAlloc(bufferName))
+      MemoryBufferMem<MemoryBuffer>(inputData);
+  return std::unique_ptr<MemoryBuffer>(ret);
+}
+
+std::unique_ptr<MemoryBuffer> MemoryBuffer::GetMemBuffer(MemoryBufferRef ref) {
+  return std::unique_ptr<MemoryBuffer>(
+      GetMemBuffer(ref.GetBuffer(), ref.GetBufferIdentifier()));
+}
+
+static std::unique_ptr<WritableMemoryBuffer> GetMemBufferCopyImpl(
+    std::span<const uint8_t> inputData, std::string_view bufferName,
+    std::error_code& ec) {
+  auto buf =
+      WritableMemoryBuffer::GetNewUninitMemBuffer(inputData.size(), bufferName);
+  if (!buf) {
+    ec = make_error_code(errc::not_enough_memory);
+    return nullptr;
+  }
+  std::memcpy(buf->begin(), inputData.data(), inputData.size());
+  return buf;
+}
+
+std::unique_ptr<MemoryBuffer> MemoryBuffer::GetMemBufferCopy(
+    std::span<const uint8_t> inputData, std::string_view bufferName) {
+  std::error_code ec;
+  return GetMemBufferCopyImpl(inputData, bufferName, ec);
+}
+
+std::unique_ptr<MemoryBuffer> MemoryBuffer::GetFileSlice(
+    std::string_view filePath, std::error_code& ec, uint64_t mapSize,
+    uint64_t offset) {
+  return GetFileAux<MemoryBuffer>(filePath, ec, -1, mapSize, offset);
+}
+
+//===----------------------------------------------------------------------===//
+// MemoryBuffer::getFile implementation.
+//===----------------------------------------------------------------------===//
+
+namespace {
+
+template <typename MB>
+constexpr auto kMapMode = MappedFileRegion::kReadOnly;
+template <>
+constexpr auto kMapMode<MemoryBuffer> = MappedFileRegion::kReadOnly;
+template <>
+constexpr auto kMapMode<WritableMemoryBuffer> = MappedFileRegion::kPriv;
+template <>
+constexpr auto kMapMode<WriteThroughMemoryBuffer> =
+    MappedFileRegion::kReadWrite;
+
+/// Memory maps a file descriptor using MappedFileRegion.
+///
+/// This handles converting the offset into a legal offset on the platform.
+template <typename MB>
+class MemoryBufferMMapFile : public MB {
+  MappedFileRegion m_mfr;
+
+  static uint64_t getLegalMapOffset(uint64_t offset) {
+    return offset & ~(MappedFileRegion::GetAlignment() - 1);
+  }
+
+  static uint64_t getLegalMapSize(uint64_t len, uint64_t offset) {
+    return len + (offset - getLegalMapOffset(offset));
+  }
+
+  const uint8_t* getStart(uint64_t len, uint64_t offset) {
+    return m_mfr.const_data() + (offset - getLegalMapOffset(offset));
+  }
+
+ public:
+  MemoryBufferMMapFile(fs::file_t f, uint64_t len, uint64_t offset,
+                       std::error_code& ec)
+      : m_mfr(f, getLegalMapSize(len, offset), getLegalMapOffset(offset),
+              kMapMode<MB>, ec) {
+    if (!ec) {
+      const uint8_t* Start = getStart(len, offset);
+      MemoryBuffer::Init(Start, Start + len);
+    }
+  }
+
+  /// Disable sized deallocation for MemoryBufferMMapFile, because it has
+  /// tail-allocated data.
+  void operator delete(void* p) { ::operator delete(p); }  // NOLINT
+
+  std::string_view GetBufferIdentifier() const override {
+    // The name is stored after the class itself.
+    return std::string_view(reinterpret_cast<const char*>(this + 1));
+  }
+
+  MemoryBuffer::BufferKind GetBufferKind() const override {
+    return MemoryBuffer::MemoryBuffer_MMap;
+  }
+};
+}  // namespace
+
+static std::unique_ptr<WritableMemoryBuffer> GetMemoryBufferForStream(
+    fs::file_t f, std::string_view bufferName, std::error_code& ec) {
+  constexpr size_t ChunkSize = 4096 * 4;
+  SmallVector<uint8_t, ChunkSize> buffer;
+#ifdef _WIN32
+  DWORD readBytes;
+#else
+  ssize_t readBytes;
+#endif
+  // Read into Buffer until we hit EOF.
+  do {
+    buffer.resize_for_overwrite(buffer.size() + ChunkSize);
+#ifdef _WIN32
+    if (!ReadFile(f, buffer.end(), ChunkSize, &readBytes, nullptr)) {
+      ec = mapWindowsError(GetLastError());
+      return nullptr;
+    }
+#else
+    readBytes = sys::RetryAfterSignal(-1, ::read, f, buffer.end(), ChunkSize);
+    if (readBytes == -1) {
+      ec = std::error_code(errno, std::generic_category());
+      return nullptr;
+    }
+#endif
+  } while (readBytes != 0);
+
+  return GetMemBufferCopyImpl(buffer, bufferName, ec);
+}
+
+std::unique_ptr<MemoryBuffer> MemoryBuffer::GetFile(std::string_view filename,
+                                                    std::error_code& ec,
+                                                    int64_t fileSize) {
+  return GetFileAux<MemoryBuffer>(filename, ec, fileSize, fileSize, 0);
+}
+
+template <typename MB>
+static std::unique_ptr<MB> GetOpenFileImpl(fs::file_t f,
+                                           std::string_view filename,
+                                           std::error_code& ec,
+                                           uint64_t fileSize, uint64_t mapSize,
+                                           int64_t offset);
+
+template <typename MB>
+static std::unique_ptr<MB> GetFileAux(std::string_view filename,
+                                      std::error_code& ec, int64_t fileSize,
+                                      uint64_t mapSize, uint64_t offset) {
+  fs::file_t F = fs::OpenFileForRead(filename, ec, fs::OF_None);
+  if (ec) {
+    return nullptr;
+  }
+
+  auto Ret = GetOpenFileImpl<MB>(F, filename, ec, fileSize, mapSize, offset);
+  fs::CloseFile(F);
+  return Ret;
+}
+
+std::unique_ptr<WritableMemoryBuffer> WritableMemoryBuffer::GetFile(
+    std::string_view filename, std::error_code& ec, int64_t fileSize) {
+  return GetFileAux<WritableMemoryBuffer>(filename, ec, fileSize, fileSize, 0);
+}
+
+std::unique_ptr<WritableMemoryBuffer> WritableMemoryBuffer::GetFileSlice(
+    std::string_view filename, std::error_code& ec, uint64_t mapSize,
+    uint64_t offset) {
+  return GetFileAux<WritableMemoryBuffer>(filename, ec, -1, mapSize, offset);
+}
+
+std::unique_ptr<WritableMemoryBuffer>
+WritableMemoryBuffer::GetNewUninitMemBuffer(size_t size,
+                                            std::string_view bufferName) {
+  using MemBuffer = MemoryBufferMem<WritableMemoryBuffer>;
+  // Allocate space for the MemoryBuffer, the data and the name. It is important
+  // that MemoryBuffer and data are aligned so PointerIntPair works with them.
+  // TODO: Is 16-byte alignment enough?  We copy small object files with large
+  // alignment expectations into this buffer.
+  size_t alignedStringLen =
+      alignTo(sizeof(MemBuffer) + bufferName.size() + 1, 16);
+  size_t realLen = alignedStringLen + size + 1;
+  uint8_t* mem = static_cast<uint8_t*>(operator new(realLen, std::nothrow));
+  if (!mem) {
+    return nullptr;
+  }
+
+  // The name is stored after the class itself.
+  CopyStringView(mem + sizeof(MemBuffer), bufferName);
+
+  // The buffer begins after the name and must be aligned.
+  uint8_t* buf = mem + alignedStringLen;
+  buf[size] = 0;  // Null terminate buffer.
+
+  auto* ret = new (mem) MemBuffer({buf, size});
+  return std::unique_ptr<WritableMemoryBuffer>(ret);
+}
+
+std::unique_ptr<WritableMemoryBuffer> WritableMemoryBuffer::GetNewMemBuffer(
+    size_t size, std::string_view bufferName) {
+  auto sb = WritableMemoryBuffer::GetNewUninitMemBuffer(size, bufferName);
+  if (!sb) {
+    return nullptr;
+  }
+  std::memset(sb->begin(), 0, size);
+  return sb;
+}
+
+static std::unique_ptr<WriteThroughMemoryBuffer> GetReadWriteFile(
+    std::string_view filename, std::error_code& ec, uint64_t fileSize,
+    uint64_t mapSize, uint64_t offset) {
+  fs::file_t f =
+      fs::OpenFileForReadWrite(filename, ec, fs::CD_OpenExisting, fs::OF_None);
+  if (ec) {
+    return nullptr;
+  }
+
+  // Default is to map the full file.
+  if (mapSize == uint64_t(-1)) {
+    // If we don't know the file size, use fstat to find out.  fstat on an open
+    // file descriptor is cheaper than stat on a random path.
+    if (fileSize == uint64_t(-1)) {
+#ifdef _WIN32
+      // If this not a file or a block device (e.g. it's a named pipe
+      // or character device), we can't mmap it, so error out.
+      if (GetFileType(f) != FILE_TYPE_DISK) {
+        ec = std::error_code(errno, std::generic_category());
+        return nullptr;
+      }
+
+      LARGE_INTEGER fileSizeWin;
+      if (!GetFileSizeEx(f, &fileSizeWin)) {
+        ec = wpi::mapWindowsError(GetLastError());
+        return nullptr;
+      }
+      fileSize = fileSizeWin.QuadPart;
+#else
+      struct stat status;
+      if (fstat(f, &status) < 0) {
+        ec = std::error_code(errno, std::generic_category());
+        return nullptr;
+      }
+
+      // If this not a file or a block device (e.g. it's a named pipe
+      // or character device), we can't mmap it, so error out.
+      if (status.st_mode != S_IFREG && status.st_mode != S_IFBLK) {
+        ec = make_error_code(errc::invalid_argument);
+        return nullptr;
+      }
+
+      fileSize = status.st_size;
+#endif
+    }
+    mapSize = fileSize;
+  }
+
+  std::unique_ptr<WriteThroughMemoryBuffer> result(new (NamedBufferAlloc(
+      filename)) MemoryBufferMMapFile<WriteThroughMemoryBuffer>(f, mapSize,
+                                                                offset, ec));
+  if (ec) {
+    return nullptr;
+  }
+  return result;
+}
+
+std::unique_ptr<WriteThroughMemoryBuffer> WriteThroughMemoryBuffer::GetFile(
+    std::string_view filename, std::error_code& ec, int64_t fileSize) {
+  return GetReadWriteFile(filename, ec, fileSize, fileSize, 0);
+}
+
+/// Map a subrange of the specified file as a WritableMemoryBuffer.
+std::unique_ptr<WriteThroughMemoryBuffer>
+WriteThroughMemoryBuffer::GetFileSlice(std::string_view filename,
+                                       std::error_code& ec, uint64_t mapSize,
+                                       uint64_t offset) {
+  return GetReadWriteFile(filename, ec, -1, mapSize, offset);
+}
+
+template <typename MB>
+static std::unique_ptr<MB> GetOpenFileImpl(fs::file_t f,
+                                           std::string_view filename,
+                                           std::error_code& ec,
+                                           uint64_t fileSize, uint64_t mapSize,
+                                           int64_t offset) {
+  // Default is to map the full file.
+  if (mapSize == uint64_t(-1)) {
+    // If we don't know the file size, use fstat to find out.  fstat on an open
+    // file descriptor is cheaper than stat on a random path.
+    if (fileSize == uint64_t(-1)) {
+#ifdef _WIN32
+      // If this not a file or a block device (e.g. it's a named pipe
+      // or character device), we can't trust the size. Create the memory
+      // buffer by copying off the stream.
+      LARGE_INTEGER fileSizeWin;
+      if (GetFileType(f) != FILE_TYPE_DISK || !GetFileSizeEx(f, &fileSizeWin)) {
+        return GetMemoryBufferForStream(f, filename, ec);
+      }
+      fileSize = fileSizeWin.QuadPart;
+#else
+      struct stat status;
+      if (fstat(f, &status) < 0) {
+        ec = std::error_code(errno, std::generic_category());
+        return nullptr;
+      }
+
+      // If this not a file or a block device (e.g. it's a named pipe
+      // or character device), we can't trust the size. Create the memory
+      // buffer by copying off the stream.
+      if (status.st_mode != S_IFREG && status.st_mode != S_IFBLK) {
+        return GetMemoryBufferForStream(f, filename, ec);
+      }
+
+      fileSize = status.st_size;
+#endif
+    }
+    mapSize = fileSize;
+  }
+
+  // Don't use mmap for small files
+  if (mapSize >= 4 * 4096) {
+    std::unique_ptr<MB> result(new (NamedBufferAlloc(
+        filename)) MemoryBufferMMapFile<MB>(f, mapSize, offset, ec));
+    if (!ec) {
+      return result;
+    }
+  }
+
+  auto buf = WritableMemoryBuffer::GetNewUninitMemBuffer(mapSize, filename);
+  if (!buf) {
+    // Failed to create a buffer. The only way it can fail is if
+    // new(std::nothrow) returns 0.
+    ec = make_error_code(errc::not_enough_memory);
+    return nullptr;
+  }
+
+  uint8_t* bufPtr = buf.get()->begin();
+
+  size_t bytesLeft = mapSize;
+  while (bytesLeft) {
+#ifdef _WIN32
+    LARGE_INTEGER offsetWin;
+    offsetWin.QuadPart = offset;
+    DWORD numRead;
+    if (!SetFilePointerEx(f, offsetWin, nullptr, FILE_BEGIN) ||
+        !ReadFile(f, bufPtr, bytesLeft, &numRead, nullptr)) {
+      ec = mapWindowsError(GetLastError());
+      return nullptr;
+    }
+// TODO
+#else
+    ssize_t numRead = sys::RetryAfterSignal(-1, ::pread, f, bufPtr, bytesLeft,
+                                            mapSize - bytesLeft + offset);
+    if (numRead == -1) {
+      // Error while reading.
+      ec = std::error_code(errno, std::generic_category());
+      return nullptr;
+    }
+#endif
+    if (numRead == 0) {
+      std::memset(bufPtr, 0, bytesLeft);  // zero-initialize rest of the buffer.
+      break;
+    }
+    bytesLeft -= numRead;
+    bufPtr += numRead;
+  }
+
+  return buf;
+}
+
+std::unique_ptr<MemoryBuffer> MemoryBuffer::GetOpenFile(
+    fs::file_t f, std::string_view filename, std::error_code& ec,
+    uint64_t fileSize) {
+  return GetOpenFileImpl<MemoryBuffer>(f, filename, ec, fileSize, fileSize, 0);
+}
+
+std::unique_ptr<MemoryBuffer> MemoryBuffer::GetOpenFileSlice(
+    fs::file_t f, std::string_view filename, std::error_code& ec,
+    uint64_t mapSize, int64_t offset) {
+  assert(mapSize != uint64_t(-1));
+  return GetOpenFileImpl<MemoryBuffer>(f, filename, ec, -1, mapSize, offset);
+}
+
+std::unique_ptr<MemoryBuffer> MemoryBuffer::GetFileAsStream(
+    std::string_view filename, std::error_code& ec) {
+  fs::file_t f = fs::OpenFileForRead(filename, ec, fs::OF_None);
+  if (ec) {
+    return nullptr;
+  }
+  std::unique_ptr<MemoryBuffer> ret = GetMemoryBufferForStream(f, filename, ec);
+  fs::CloseFile(f);
+  return ret;
+}
+
+MemoryBufferRef MemoryBuffer::GetMemBufferRef() const {
+  return MemoryBufferRef(GetBuffer(), GetBufferIdentifier());
+}
+
+SmallVectorMemoryBuffer::~SmallVectorMemoryBuffer() {}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/SmallPtrSet.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/SmallPtrSet.cpp
new file mode 100644
index 0000000..f356728
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/SmallPtrSet.cpp
@@ -0,0 +1,270 @@
+//===- llvm/ADT/SmallPtrSet.cpp - 'Normally small' pointer set ------------===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+//
+// This file implements the SmallPtrSet class.  See SmallPtrSet.h for an
+// overview of the algorithm.
+//
+//===----------------------------------------------------------------------===//
+
+#include "wpi/SmallPtrSet.h"
+#include "wpi/DenseMapInfo.h"
+#include "wpi/MathExtras.h"
+#include "wpi/MemAlloc.h"
+#include <algorithm>
+#include <cassert>
+#include <cstdlib>
+
+using namespace wpi;
+
+void SmallPtrSetImplBase::shrink_and_clear() {
+  assert(!isSmall() && "Can't shrink a small set!");
+  free(CurArray);
+
+  // Reduce the number of buckets.
+  unsigned Size = size();
+  CurArraySize = Size > 16 ? 1 << (Log2_32_Ceil(Size) + 1) : 32;
+  NumNonEmpty = NumTombstones = 0;
+
+  // Install the new array.  Clear all the buckets to empty.
+  CurArray = (const void**)safe_malloc(sizeof(void*) * CurArraySize);
+
+  memset(CurArray, -1, CurArraySize*sizeof(void*));
+}
+
+std::pair<const void *const *, bool>
+SmallPtrSetImplBase::insert_imp_big(const void *Ptr) {
+  if (LLVM_UNLIKELY(size() * 4 >= CurArraySize * 3)) {
+    // If more than 3/4 of the array is full, grow.
+    Grow(CurArraySize < 64 ? 128 : CurArraySize * 2);
+  } else if (LLVM_UNLIKELY(CurArraySize - NumNonEmpty < CurArraySize / 8)) {
+    // If fewer of 1/8 of the array is empty (meaning that many are filled with
+    // tombstones), rehash.
+    Grow(CurArraySize);
+  }
+
+  // Okay, we know we have space.  Find a hash bucket.
+  const void **Bucket = const_cast<const void**>(FindBucketFor(Ptr));
+  if (*Bucket == Ptr)
+    return std::make_pair(Bucket, false); // Already inserted, good.
+
+  // Otherwise, insert it!
+  if (*Bucket == getTombstoneMarker())
+    --NumTombstones;
+  else
+    ++NumNonEmpty; // Track density.
+  *Bucket = Ptr;
+  incrementEpoch();
+  return std::make_pair(Bucket, true);
+}
+
+const void * const *SmallPtrSetImplBase::FindBucketFor(const void *Ptr) const {
+  unsigned Bucket = DenseMapInfo<void *>::getHashValue(Ptr) & (CurArraySize-1);
+  unsigned ArraySize = CurArraySize;
+  unsigned ProbeAmt = 1;
+  const void *const *Array = CurArray;
+  const void *const *Tombstone = nullptr;
+  while (true) {
+    // If we found an empty bucket, the pointer doesn't exist in the set.
+    // Return a tombstone if we've seen one so far, or the empty bucket if
+    // not.
+    if (LLVM_LIKELY(Array[Bucket] == getEmptyMarker()))
+      return Tombstone ? Tombstone : Array+Bucket;
+
+    // Found Ptr's bucket?
+    if (LLVM_LIKELY(Array[Bucket] == Ptr))
+      return Array+Bucket;
+
+    // If this is a tombstone, remember it.  If Ptr ends up not in the set, we
+    // prefer to return it than something that would require more probing.
+    if (Array[Bucket] == getTombstoneMarker() && !Tombstone)
+      Tombstone = Array+Bucket;  // Remember the first tombstone found.
+
+    // It's a hash collision or a tombstone. Reprobe.
+    Bucket = (Bucket + ProbeAmt++) & (ArraySize-1);
+  }
+}
+
+/// Grow - Allocate a larger backing store for the buckets and move it over.
+///
+void SmallPtrSetImplBase::Grow(unsigned NewSize) {
+  const void **OldBuckets = CurArray;
+  const void **OldEnd = EndPointer();
+  bool WasSmall = isSmall();
+
+  // Install the new array.  Clear all the buckets to empty.
+  const void **NewBuckets = (const void**) safe_malloc(sizeof(void*) * NewSize);
+
+  // Reset member only if memory was allocated successfully
+  CurArray = NewBuckets;
+  CurArraySize = NewSize;
+  memset(CurArray, -1, NewSize*sizeof(void*));
+
+  // Copy over all valid entries.
+  for (const void **BucketPtr = OldBuckets; BucketPtr != OldEnd; ++BucketPtr) {
+    // Copy over the element if it is valid.
+    const void *Elt = *BucketPtr;
+    if (Elt != getTombstoneMarker() && Elt != getEmptyMarker())
+      *const_cast<void**>(FindBucketFor(Elt)) = const_cast<void*>(Elt);
+  }
+
+  if (!WasSmall)
+    free(OldBuckets);
+  NumNonEmpty -= NumTombstones;
+  NumTombstones = 0;
+}
+
+SmallPtrSetImplBase::SmallPtrSetImplBase(const void **SmallStorage,
+                                         const SmallPtrSetImplBase &that) {
+  SmallArray = SmallStorage;
+
+  // If we're becoming small, prepare to insert into our stack space
+  if (that.isSmall()) {
+    CurArray = SmallArray;
+  // Otherwise, allocate new heap space (unless we were the same size)
+  } else {
+    CurArray = (const void**)safe_malloc(sizeof(void*) * that.CurArraySize);
+  }
+
+  // Copy over the that array.
+  CopyHelper(that);
+}
+
+SmallPtrSetImplBase::SmallPtrSetImplBase(const void **SmallStorage,
+                                         unsigned SmallSize,
+                                         SmallPtrSetImplBase &&that) {
+  SmallArray = SmallStorage;
+  MoveHelper(SmallSize, std::move(that));
+}
+
+void SmallPtrSetImplBase::CopyFrom(const SmallPtrSetImplBase &RHS) {
+  assert(&RHS != this && "Self-copy should be handled by the caller.");
+
+  if (isSmall() && RHS.isSmall())
+    assert(CurArraySize == RHS.CurArraySize &&
+           "Cannot assign sets with different small sizes");
+
+  // If we're becoming small, prepare to insert into our stack space
+  if (RHS.isSmall()) {
+    if (!isSmall())
+      free(CurArray);
+    CurArray = SmallArray;
+  // Otherwise, allocate new heap space (unless we were the same size)
+  } else if (CurArraySize != RHS.CurArraySize) {
+    if (isSmall())
+      CurArray = (const void**)safe_malloc(sizeof(void*) * RHS.CurArraySize);
+    else {
+      const void **T = (const void**)safe_realloc(CurArray,
+                                             sizeof(void*) * RHS.CurArraySize);
+      CurArray = T;
+    }
+  }
+
+  CopyHelper(RHS);
+}
+
+void SmallPtrSetImplBase::CopyHelper(const SmallPtrSetImplBase &RHS) {
+  // Copy over the new array size
+  CurArraySize = RHS.CurArraySize;
+
+  // Copy over the contents from the other set
+  std::copy(RHS.CurArray, RHS.EndPointer(), CurArray);
+
+  NumNonEmpty = RHS.NumNonEmpty;
+  NumTombstones = RHS.NumTombstones;
+}
+
+void SmallPtrSetImplBase::MoveFrom(unsigned SmallSize,
+                                   SmallPtrSetImplBase &&RHS) {
+  if (!isSmall())
+    free(CurArray);
+  MoveHelper(SmallSize, std::move(RHS));
+}
+
+void SmallPtrSetImplBase::MoveHelper(unsigned SmallSize,
+                                     SmallPtrSetImplBase &&RHS) {
+  assert(&RHS != this && "Self-move should be handled by the caller.");
+
+  if (RHS.isSmall()) {
+    // Copy a small RHS rather than moving.
+    CurArray = SmallArray;
+    std::copy(RHS.CurArray, RHS.CurArray + RHS.NumNonEmpty, CurArray);
+  } else {
+    CurArray = RHS.CurArray;
+    RHS.CurArray = RHS.SmallArray;
+  }
+
+  // Copy the rest of the trivial members.
+  CurArraySize = RHS.CurArraySize;
+  NumNonEmpty = RHS.NumNonEmpty;
+  NumTombstones = RHS.NumTombstones;
+
+  // Make the RHS small and empty.
+  RHS.CurArraySize = SmallSize;
+  assert(RHS.CurArray == RHS.SmallArray);
+  RHS.NumNonEmpty = 0;
+  RHS.NumTombstones = 0;
+}
+
+void SmallPtrSetImplBase::swap(SmallPtrSetImplBase &RHS) {
+  if (this == &RHS) return;
+
+  // We can only avoid copying elements if neither set is small.
+  if (!this->isSmall() && !RHS.isSmall()) {
+    std::swap(this->CurArray, RHS.CurArray);
+    std::swap(this->CurArraySize, RHS.CurArraySize);
+    std::swap(this->NumNonEmpty, RHS.NumNonEmpty);
+    std::swap(this->NumTombstones, RHS.NumTombstones);
+    return;
+  }
+
+  // FIXME: From here on we assume that both sets have the same small size.
+
+  // If only RHS is small, copy the small elements into LHS and move the pointer
+  // from LHS to RHS.
+  if (!this->isSmall() && RHS.isSmall()) {
+    assert(RHS.CurArray == RHS.SmallArray);
+    std::copy(RHS.CurArray, RHS.CurArray + RHS.NumNonEmpty, this->SmallArray);
+    std::swap(RHS.CurArraySize, this->CurArraySize);
+    std::swap(this->NumNonEmpty, RHS.NumNonEmpty);
+    std::swap(this->NumTombstones, RHS.NumTombstones);
+    RHS.CurArray = this->CurArray;
+    this->CurArray = this->SmallArray;
+    return;
+  }
+
+  // If only LHS is small, copy the small elements into RHS and move the pointer
+  // from RHS to LHS.
+  if (this->isSmall() && !RHS.isSmall()) {
+    assert(this->CurArray == this->SmallArray);
+    std::copy(this->CurArray, this->CurArray + this->NumNonEmpty,
+              RHS.SmallArray);
+    std::swap(RHS.CurArraySize, this->CurArraySize);
+    std::swap(RHS.NumNonEmpty, this->NumNonEmpty);
+    std::swap(RHS.NumTombstones, this->NumTombstones);
+    this->CurArray = RHS.CurArray;
+    RHS.CurArray = RHS.SmallArray;
+    return;
+  }
+
+  // Both a small, just swap the small elements.
+  assert(this->isSmall() && RHS.isSmall());
+  unsigned MinNonEmpty = std::min(this->NumNonEmpty, RHS.NumNonEmpty);
+  std::swap_ranges(this->SmallArray, this->SmallArray + MinNonEmpty,
+                   RHS.SmallArray);
+  if (this->NumNonEmpty > MinNonEmpty) {
+    std::copy(this->SmallArray + MinNonEmpty,
+              this->SmallArray + this->NumNonEmpty,
+              RHS.SmallArray + MinNonEmpty);
+  } else {
+    std::copy(RHS.SmallArray + MinNonEmpty, RHS.SmallArray + RHS.NumNonEmpty,
+              this->SmallArray + MinNonEmpty);
+  }
+  assert(this->CurArraySize == RHS.CurArraySize);
+  std::swap(this->NumNonEmpty, RHS.NumNonEmpty);
+  std::swap(this->NumTombstones, RHS.NumTombstones);
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/SmallVector.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/SmallVector.cpp
new file mode 100644
index 0000000..04f4e06
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/SmallVector.cpp
@@ -0,0 +1,129 @@
+//===- llvm/ADT/SmallVector.cpp - 'Normally small' vectors ----------------===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+//
+// This file implements the SmallVector class.
+//
+//===----------------------------------------------------------------------===//
+
+#include "wpi/SmallVector.h"
+#include "wpi/MemAlloc.h"
+#include <cstdint>
+#ifdef LLVM_ENABLE_EXCEPTIONS
+#include <stdexcept>
+#endif
+using namespace wpi;
+
+// Check that no bytes are wasted and everything is well-aligned.
+namespace {
+// These structures may cause binary compat warnings on AIX. Suppress the
+// warning since we are only using these types for the static assertions below.
+#if defined(_AIX)
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Waix-compat"
+#endif
+struct Struct16B {
+  alignas(16) void *X;
+};
+struct Struct32B {
+  alignas(32) void *X;
+};
+#if defined(_AIX)
+#pragma GCC diagnostic pop
+#endif
+}
+static_assert(sizeof(SmallVector<void *, 0>) ==
+                  sizeof(unsigned) * 2 + sizeof(void *),
+              "wasted space in SmallVector size 0");
+static_assert(alignof(SmallVector<Struct16B, 0>) >= alignof(Struct16B),
+              "wrong alignment for 16-byte aligned T");
+static_assert(alignof(SmallVector<Struct32B, 0>) >= alignof(Struct32B),
+              "wrong alignment for 32-byte aligned T");
+static_assert(sizeof(SmallVector<Struct16B, 0>) >= alignof(Struct16B),
+              "missing padding for 16-byte aligned T");
+static_assert(sizeof(SmallVector<Struct32B, 0>) >= alignof(Struct32B),
+              "missing padding for 32-byte aligned T");
+static_assert(sizeof(SmallVector<void *, 1>) ==
+                  sizeof(unsigned) * 2 + sizeof(void *) * 2,
+              "wasted space in SmallVector size 1");
+
+/// Report that MinSize doesn't fit into this vector's size type. Throws
+/// std::length_error or calls report_fatal_error.
+[[noreturn]] static void report_size_overflow(size_t MinSize, size_t MaxSize);
+static void report_size_overflow(size_t MinSize, size_t MaxSize) {
+  std::string Reason = "SmallVector unable to grow. Requested capacity (" +
+                       std::to_string(MinSize) +
+                       ") is larger than maximum value for size type (" +
+                       std::to_string(MaxSize) + ")";
+#ifdef LLVM_ENABLE_EXCEPTIONS
+  throw std::length_error(Reason);
+#else
+  report_fatal_error(Reason);
+#endif
+}
+
+/// Report that this vector is already at maximum capacity. Throws
+/// std::length_error or calls report_fatal_error.
+[[noreturn]] static void report_at_maximum_capacity(size_t MaxSize);
+static void report_at_maximum_capacity(size_t MaxSize) {
+  std::string Reason =
+      "SmallVector capacity unable to grow. Already at maximum size " +
+      std::to_string(MaxSize);
+#ifdef LLVM_ENABLE_EXCEPTIONS
+  throw std::length_error(Reason);
+#else
+  report_fatal_error(Reason);
+#endif
+}
+
+// Note: Moving this function into the header may cause performance regression.
+static size_t getNewCapacity(size_t MinSize, size_t TSize, size_t OldCapacity) {
+  constexpr size_t MaxSize = std::numeric_limits<unsigned>::max();
+
+  // Ensure we can fit the new capacity.
+  // This is only going to be applicable when the capacity is 32 bit.
+  if (MinSize > MaxSize)
+    report_size_overflow(MinSize, MaxSize);
+
+  // Ensure we can meet the guarantee of space for at least one more element.
+  // The above check alone will not catch the case where grow is called with a
+  // default MinSize of 0, but the current capacity cannot be increased.
+  // This is only going to be applicable when the capacity is 32 bit.
+  if (OldCapacity == MaxSize)
+    report_at_maximum_capacity(MaxSize);
+
+  // In theory 2*capacity can overflow if the capacity is 64 bit, but the
+  // original capacity would never be large enough for this to be a problem.
+  size_t NewCapacity = 2 * OldCapacity + 1; // Always grow.
+  return (std::min)((std::max)(NewCapacity, MinSize), MaxSize);
+}
+
+// Note: Moving this function into the header may cause performance regression.
+void *SmallVectorBase::mallocForGrow(size_t MinSize, size_t TSize,
+                                             size_t &NewCapacity) {
+  NewCapacity = getNewCapacity(MinSize, TSize, this->capacity());
+  return wpi::safe_malloc(NewCapacity * TSize);
+}
+
+// Note: Moving this function into the header may cause performance regression.
+void SmallVectorBase::grow_pod(void *FirstEl, size_t MinSize,
+                                       size_t TSize) {
+  size_t NewCapacity = getNewCapacity(MinSize, TSize, this->capacity());
+  void *NewElts;
+  if (BeginX == FirstEl) {
+    NewElts = safe_malloc(NewCapacity * TSize);
+
+    // Copy the elements over.  No need to run dtors on PODs.
+    memcpy(NewElts, this->BeginX, size() * TSize);
+  } else {
+    // If this wasn't grown from the inline copy, grow the allocated space.
+    NewElts = safe_realloc(this->BeginX, NewCapacity * TSize);
+  }
+
+  this->BeginX = NewElts;
+  this->Capacity = NewCapacity;
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/StringExtras.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/StringExtras.cpp
new file mode 100644
index 0000000..9307724
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/StringExtras.cpp
@@ -0,0 +1,442 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+//===-- StringExtras.cpp - Implement the StringExtras header --------------===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+// This file implements the StringExtras.h header
+//
+//===----------------------------------------------------------------------===//
+
+#include "wpi/StringExtras.h"
+
+#include <algorithm>
+#include <cstdlib>
+#include <string_view>
+
+#include "wpi/SmallString.h"
+#include "wpi/SmallVector.h"
+
+// strncasecmp() is not available on non-POSIX systems, so define an
+// alternative function here.
+static int ascii_strncasecmp(const char* lhs, const char* rhs,
+                             size_t length) noexcept {
+  for (size_t i = 0; i < length; ++i) {
+    unsigned char lhc = wpi::toLower(lhs[i]);
+    unsigned char rhc = wpi::toLower(rhs[i]);
+    if (lhc != rhc) {
+      return lhc < rhc ? -1 : 1;
+    }
+  }
+  return 0;
+}
+
+int wpi::compare_lower(std::string_view lhs, std::string_view rhs) noexcept {
+  if (int Res = ascii_strncasecmp(lhs.data(), rhs.data(),
+                                  (std::min)(lhs.size(), rhs.size()))) {
+    return Res;
+  }
+  if (lhs.size() == rhs.size()) {
+    return 0;
+  }
+  return lhs.size() < rhs.size() ? -1 : 1;
+}
+
+std::string_view::size_type wpi::find_lower(
+    std::string_view str, char ch, std::string_view::size_type from) noexcept {
+  char lch = toLower(ch);
+  auto s = drop_front(str, from);
+  while (!s.empty()) {
+    if (toLower(s.front()) == lch) {
+      return str.size() - s.size();
+    }
+    s.remove_prefix(1);
+  }
+  return std::string_view::npos;
+}
+
+std::string_view::size_type wpi::find_lower(
+    std::string_view str, std::string_view other,
+    std::string_view::size_type from) noexcept {
+  auto s = substr(str, from);
+  while (s.size() >= other.size()) {
+    if (starts_with_lower(s, other)) {
+      return from;
+    }
+    s.remove_prefix(1);
+    ++from;
+  }
+  return std::string_view::npos;
+}
+
+std::string_view::size_type wpi::rfind_lower(
+    std::string_view str, char ch, std::string_view::size_type from) noexcept {
+  from = (std::min)(from, str.size());
+  auto data = str.data();
+  std::string_view::size_type i = from;
+  while (i != 0) {
+    --i;
+    if (toLower(data[i]) == toLower(ch)) {
+      return i;
+    }
+  }
+  return std::string_view::npos;
+}
+
+std::string_view::size_type wpi::rfind_lower(std::string_view str,
+                                             std::string_view other) noexcept {
+  std::string_view::size_type n = other.size();
+  if (n > str.size()) {
+    return std::string_view::npos;
+  }
+  for (size_t i = str.size() - n + 1, e = 0; i != e;) {
+    --i;
+    if (equals_lower(substr(str, i, n), other)) {
+      return i;
+    }
+  }
+  return std::string_view::npos;
+}
+
+bool wpi::starts_with_lower(std::string_view str,
+                            std::string_view prefix) noexcept {
+  return str.size() >= prefix.size() &&
+         ascii_strncasecmp(str.data(), prefix.data(), prefix.size()) == 0;
+}
+
+bool wpi::ends_with_lower(std::string_view str,
+                          std::string_view suffix) noexcept {
+  return str.size() >= suffix.size() &&
+         ascii_strncasecmp(str.data() + str.size() - suffix.size(),
+                           suffix.data(), suffix.size()) == 0;
+}
+
+void wpi::split(std::string_view str, SmallVectorImpl<std::string_view>& arr,
+                std::string_view separator, int maxSplit,
+                bool keepEmpty) noexcept {
+  std::string_view s = str;
+
+  // Count down from maxSplit. When maxSplit is -1, this will just split
+  // "forever". This doesn't support splitting more than 2^31 times
+  // intentionally; if we ever want that we can make maxSplit a 64-bit integer
+  // but that seems unlikely to be useful.
+  while (maxSplit-- != 0) {
+    auto idx = s.find(separator);
+    if (idx == std::string_view::npos) {
+      break;
+    }
+
+    // Push this split.
+    if (keepEmpty || idx > 0) {
+      arr.push_back(slice(s, 0, idx));
+    }
+
+    // Jump forward.
+    s = slice(s, idx + separator.size(), std::string_view::npos);
+  }
+
+  // Push the tail.
+  if (keepEmpty || !s.empty()) {
+    arr.push_back(s);
+  }
+}
+
+void wpi::split(std::string_view str, SmallVectorImpl<std::string_view>& arr,
+                char separator, int maxSplit, bool keepEmpty) noexcept {
+  std::string_view s = str;
+
+  // Count down from maxSplit. When maxSplit is -1, this will just split
+  // "forever". This doesn't support splitting more than 2^31 times
+  // intentionally; if we ever want that we can make maxSplit a 64-bit integer
+  // but that seems unlikely to be useful.
+  while (maxSplit-- != 0) {
+    size_t idx = s.find(separator);
+    if (idx == std::string_view::npos) {
+      break;
+    }
+
+    // Push this split.
+    if (keepEmpty || idx > 0) {
+      arr.push_back(slice(s, 0, idx));
+    }
+
+    // Jump forward.
+    s = slice(s, idx + 1, std::string_view::npos);
+  }
+
+  // Push the tail.
+  if (keepEmpty || !s.empty()) {
+    arr.push_back(s);
+  }
+}
+
+static unsigned GetAutoSenseRadix(std::string_view& str) noexcept {
+  if (str.empty()) {
+    return 10;
+  }
+
+  if (wpi::starts_with(str, "0x") || wpi::starts_with(str, "0X")) {
+    str.remove_prefix(2);
+    return 16;
+  }
+
+  if (wpi::starts_with(str, "0b") || wpi::starts_with(str, "0B")) {
+    str.remove_prefix(2);
+    return 2;
+  }
+
+  if (wpi::starts_with(str, "0o")) {
+    str.remove_prefix(2);
+    return 8;
+  }
+
+  if (str[0] == '0' && str.size() > 1 && wpi::isDigit(str[1])) {
+    str.remove_prefix(1);
+    return 8;
+  }
+
+  return 10;
+}
+
+bool wpi::detail::ConsumeUnsignedInteger(
+    std::string_view& str, unsigned radix,
+    unsigned long long& result) noexcept {  // NOLINT(runtime/int)
+  // Autosense radix if not specified.
+  if (radix == 0) {
+    radix = GetAutoSenseRadix(str);
+  }
+
+  // Empty strings (after the radix autosense) are invalid.
+  if (str.empty()) {
+    return true;
+  }
+
+  // Parse all the bytes of the string given this radix.  Watch for overflow.
+  std::string_view str2 = str;
+  result = 0;
+  while (!str2.empty()) {
+    unsigned charVal;
+    if (str2[0] >= '0' && str2[0] <= '9') {
+      charVal = str2[0] - '0';
+    } else if (str2[0] >= 'a' && str2[0] <= 'z') {
+      charVal = str2[0] - 'a' + 10;
+    } else if (str2[0] >= 'A' && str2[0] <= 'Z') {
+      charVal = str2[0] - 'A' + 10;
+    } else {
+      break;
+    }
+
+    // If the parsed value is larger than the integer radix, we cannot
+    // consume any more characters.
+    if (charVal >= radix) {
+      break;
+    }
+
+    // Add in this character.
+    unsigned long long prevResult = result;  // NOLINT(runtime/int)
+    result = result * radix + charVal;
+
+    // Check for overflow by shifting back and seeing if bits were lost.
+    if (result / radix < prevResult) {
+      return true;
+    }
+
+    str2.remove_prefix(1);
+  }
+
+  // We consider the operation a failure if no characters were consumed
+  // successfully.
+  if (str.size() == str2.size()) {
+    return true;
+  }
+
+  str = str2;
+  return false;
+}
+
+bool wpi::detail::ConsumeSignedInteger(
+    std::string_view& str, unsigned radix,
+    long long& result) noexcept {  // NOLINT(runtime/int)
+  unsigned long long ullVal;       // NOLINT(runtime/int)
+
+  // Handle positive strings first.
+  if (str.empty() || str.front() != '-') {
+    if (wpi::detail::ConsumeUnsignedInteger(str, radix, ullVal) ||
+        // Check for value so large it overflows a signed value.
+        static_cast<long long>(ullVal) < 0) {  // NOLINT(runtime/int)
+      return true;
+    }
+    result = ullVal;
+    return false;
+  }
+
+  // Get the positive part of the value.
+  std::string_view str2 = wpi::drop_front(str, 1);
+  if (wpi::detail::ConsumeUnsignedInteger(str2, radix, ullVal) ||
+      // Reject values so large they'd overflow as negative signed, but allow
+      // "-0".  This negates the unsigned so that the negative isn't undefined
+      // on signed overflow.
+      static_cast<long long>(-ullVal) > 0) {  // NOLINT(runtime/int)
+    return true;
+  }
+
+  str = str2;
+  result = -ullVal;
+  return false;
+}
+
+bool wpi::detail::GetAsUnsignedInteger(
+    std::string_view str, unsigned radix,
+    unsigned long long& result) noexcept {  // NOLINT(runtime/int)
+  if (wpi::detail::ConsumeUnsignedInteger(str, radix, result)) {
+    return true;
+  }
+
+  // For getAsUnsignedInteger, we require the whole string to be consumed or
+  // else we consider it a failure.
+  return !str.empty();
+}
+
+bool wpi::detail::GetAsSignedInteger(
+    std::string_view str, unsigned radix,
+    long long& result) noexcept {  // NOLINT(runtime/int)
+  if (wpi::detail::ConsumeSignedInteger(str, radix, result)) {
+    return true;
+  }
+
+  // For getAsSignedInteger, we require the whole string to be consumed or else
+  // we consider it a failure.
+  return !str.empty();
+}
+
+template <>
+std::optional<float> wpi::parse_float<float>(std::string_view str) noexcept {
+  if (str.empty()) {
+    return std::nullopt;
+  }
+  wpi::SmallString<32> storage{str};
+  char* end;
+  float val = std::strtof(storage.c_str(), &end);
+  if (*end != '\0') {
+    return std::nullopt;
+  }
+  return val;
+}
+
+template <>
+std::optional<double> wpi::parse_float<double>(std::string_view str) noexcept {
+  if (str.empty()) {
+    return std::nullopt;
+  }
+  wpi::SmallString<32> storage{str};
+  char* end;
+  double val = std::strtod(storage.c_str(), &end);
+  if (*end != '\0') {
+    return std::nullopt;
+  }
+  return val;
+}
+
+template <>
+std::optional<long double> wpi::parse_float<long double>(
+    std::string_view str) noexcept {
+  if (str.empty()) {
+    return std::nullopt;
+  }
+  wpi::SmallString<32> storage{str};
+  char* end;
+  long double val = std::strtold(storage.c_str(), &end);
+  if (*end != '\0') {
+    return std::nullopt;
+  }
+  return val;
+}
+
+std::pair<std::string_view, std::string_view> wpi::UnescapeCString(
+    std::string_view str, wpi::SmallVectorImpl<char>& buf) {
+  buf.clear();
+  buf.reserve(str.size());
+  const char* s = str.data();
+  const char* end = str.data() + str.size();
+  for (; s != end && *s != '"'; ++s) {
+    if (*s != '\\' || (s + 1) >= end) {
+      buf.push_back(*s);
+      continue;
+    }
+    switch (*++s) {
+      case 'a':
+        buf.push_back('\a');
+        break;
+      case 'b':
+        buf.push_back('\b');
+        break;
+      case 'f':
+        buf.push_back('\f');
+        break;
+      case 'n':
+        buf.push_back('\n');
+        break;
+      case 'r':
+        buf.push_back('\r');
+        break;
+      case 't':
+        buf.push_back('\t');
+        break;
+      case 'v':
+        buf.push_back('\v');
+        break;
+      case 'x': {
+        // hex escape
+        if ((s + 1) >= end || !isxdigit(*(s + 1))) {
+          buf.push_back('x');  // treat it like a unknown escape
+          break;
+        }
+        unsigned int ch = wpi::hexDigitValue(*++s);
+        if ((s + 1) < end && std::isxdigit(*(s + 1))) {
+          ch <<= 4;
+          ch |= wpi::hexDigitValue(*++s);
+        }
+        buf.push_back(static_cast<char>(ch));
+        break;
+      }
+      case '0':
+      case '1':
+      case '2':
+      case '3':
+      case '4':
+      case '5':
+      case '6':
+      case '7':
+      case '8':
+      case '9': {
+        // octal escape
+        unsigned int ch = *s - '0';
+        if ((s + 1) < end && wpi::isDigit(*(s + 1))) {
+          ch <<= 3;
+          ch |= *++s - '0';
+        }
+        if ((s + 1) < end && wpi::isDigit(*(s + 1))) {
+          ch <<= 3;
+          ch |= *++s - '0';
+        }
+        buf.push_back(static_cast<char>(ch));
+        break;
+      }
+      default:
+        buf.push_back(*s);
+        break;
+    }
+  }
+  if (s == end) {
+    return {{buf.data(), buf.size()}, {}};
+  } else {
+    return {{buf.data(), buf.size()}, {s, static_cast<size_t>(end - s)}};
+  }
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/StringMap.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/StringMap.cpp
new file mode 100644
index 0000000..2405f2f
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/StringMap.cpp
@@ -0,0 +1,260 @@
+//===--- StringMap.cpp - String Hash table map implementation -------------===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+//
+// This file implements the StringMap class.
+//
+//===----------------------------------------------------------------------===//
+
+#include "wpi/StringMap.h"
+#include "wpi/DJB.h"
+#include "wpi/MathExtras.h"
+
+using namespace wpi;
+
+/// Returns the number of buckets to allocate to ensure that the DenseMap can
+/// accommodate \p NumEntries without need to grow().
+static unsigned getMinBucketToReserveForEntries(unsigned NumEntries) {
+  // Ensure that "NumEntries * 4 < NumBuckets * 3"
+  if (NumEntries == 0)
+    return 0;
+  // +1 is required because of the strict equality.
+  // For example if NumEntries is 48, we need to return 401.
+  return NextPowerOf2(NumEntries * 4 / 3 + 1);
+}
+
+StringMapImpl::StringMapImpl(unsigned InitSize, unsigned itemSize) {
+  ItemSize = itemSize;
+
+  // If a size is specified, initialize the table with that many buckets.
+  if (InitSize) {
+    // The table will grow when the number of entries reach 3/4 of the number of
+    // buckets. To guarantee that "InitSize" number of entries can be inserted
+    // in the table without growing, we allocate just what is needed here.
+    init(getMinBucketToReserveForEntries(InitSize));
+    return;
+  }
+
+  // Otherwise, initialize it with zero buckets to avoid the allocation.
+  TheTable = nullptr;
+  NumBuckets = 0;
+  NumItems = 0;
+  NumTombstones = 0;
+}
+
+void StringMapImpl::init(unsigned InitSize) {
+  assert((InitSize & (InitSize - 1)) == 0 &&
+         "Init Size must be a power of 2 or zero!");
+
+  unsigned NewNumBuckets = InitSize ? InitSize : 16;
+  NumItems = 0;
+  NumTombstones = 0;
+
+  TheTable = static_cast<StringMapEntryBase **>(safe_calloc(
+      NewNumBuckets + 1, sizeof(StringMapEntryBase **) + sizeof(unsigned)));
+
+  // Set the member only if TheTable was successfully allocated
+  NumBuckets = NewNumBuckets;
+
+  // Allocate one extra bucket, set it to look filled so the iterators stop at
+  // end.
+  TheTable[NumBuckets] = (StringMapEntryBase *)2;
+}
+
+/// LookupBucketFor - Look up the bucket that the specified string should end
+/// up in.  If it already exists as a key in the map, the Item pointer for the
+/// specified bucket will be non-null.  Otherwise, it will be null.  In either
+/// case, the FullHashValue field of the bucket will be set to the hash value
+/// of the string.
+unsigned StringMapImpl::LookupBucketFor(std::string_view Name) {
+  unsigned HTSize = NumBuckets;
+  if (HTSize == 0) { // Hash table unallocated so far?
+    init(16);
+    HTSize = NumBuckets;
+  }
+  unsigned FullHashValue = djbHash(Name, 0);
+  unsigned BucketNo = FullHashValue & (HTSize - 1);
+  unsigned *HashTable = (unsigned *)(TheTable + NumBuckets + 1);
+
+  unsigned ProbeAmt = 1;
+  int FirstTombstone = -1;
+  while (true) {
+    StringMapEntryBase *BucketItem = TheTable[BucketNo];
+    // If we found an empty bucket, this key isn't in the table yet, return it.
+    if (LLVM_LIKELY(!BucketItem)) {
+      // If we found a tombstone, we want to reuse the tombstone instead of an
+      // empty bucket.  This reduces probing.
+      if (FirstTombstone != -1) {
+        HashTable[FirstTombstone] = FullHashValue;
+        return FirstTombstone;
+      }
+
+      HashTable[BucketNo] = FullHashValue;
+      return BucketNo;
+    }
+
+    if (BucketItem == getTombstoneVal()) {
+      // Skip over tombstones.  However, remember the first one we see.
+      if (FirstTombstone == -1)
+        FirstTombstone = BucketNo;
+    } else if (LLVM_LIKELY(HashTable[BucketNo] == FullHashValue)) {
+      // If the full hash value matches, check deeply for a match.  The common
+      // case here is that we are only looking at the buckets (for item info
+      // being non-null and for the full hash value) not at the items.  This
+      // is important for cache locality.
+
+      // Do the comparison like this because Name isn't necessarily
+      // null-terminated!
+      char *ItemStr = (char *)BucketItem + ItemSize;
+      if (Name == std::string_view(ItemStr, BucketItem->getKeyLength())) {
+        // We found a match!
+        return BucketNo;
+      }
+    }
+
+    // Okay, we didn't find the item.  Probe to the next bucket.
+    BucketNo = (BucketNo + ProbeAmt) & (HTSize - 1);
+
+    // Use quadratic probing, it has fewer clumping artifacts than linear
+    // probing and has good cache behavior in the common case.
+    ++ProbeAmt;
+  }
+}
+
+/// FindKey - Look up the bucket that contains the specified key. If it exists
+/// in the map, return the bucket number of the key.  Otherwise return -1.
+/// This does not modify the map.
+int StringMapImpl::FindKey(std::string_view Key) const {
+  unsigned HTSize = NumBuckets;
+  if (HTSize == 0)
+    return -1; // Really empty table?
+  unsigned FullHashValue = djbHash(Key, 0);
+  unsigned BucketNo = FullHashValue & (HTSize - 1);
+  unsigned *HashTable = (unsigned *)(TheTable + NumBuckets + 1);
+
+  unsigned ProbeAmt = 1;
+  while (true) {
+    StringMapEntryBase *BucketItem = TheTable[BucketNo];
+    // If we found an empty bucket, this key isn't in the table yet, return.
+    if (LLVM_LIKELY(!BucketItem))
+      return -1;
+
+    if (BucketItem == getTombstoneVal()) {
+      // Ignore tombstones.
+    } else if (LLVM_LIKELY(HashTable[BucketNo] == FullHashValue)) {
+      // If the full hash value matches, check deeply for a match.  The common
+      // case here is that we are only looking at the buckets (for item info
+      // being non-null and for the full hash value) not at the items.  This
+      // is important for cache locality.
+
+      // Do the comparison like this because NameStart isn't necessarily
+      // null-terminated!
+      char *ItemStr = (char *)BucketItem + ItemSize;
+      if (Key == std::string_view(ItemStr, BucketItem->getKeyLength())) {
+        // We found a match!
+        return BucketNo;
+      }
+    }
+
+    // Okay, we didn't find the item.  Probe to the next bucket.
+    BucketNo = (BucketNo + ProbeAmt) & (HTSize - 1);
+
+    // Use quadratic probing, it has fewer clumping artifacts than linear
+    // probing and has good cache behavior in the common case.
+    ++ProbeAmt;
+  }
+}
+
+/// RemoveKey - Remove the specified StringMapEntry from the table, but do not
+/// delete it.  This aborts if the value isn't in the table.
+void StringMapImpl::RemoveKey(StringMapEntryBase *V) {
+  const char *VStr = (char *)V + ItemSize;
+  StringMapEntryBase *V2 = RemoveKey(std::string_view(VStr, V->getKeyLength()));
+  (void)V2;
+  assert(V == V2 && "Didn't find key?");
+}
+
+/// RemoveKey - Remove the StringMapEntry for the specified key from the
+/// table, returning it.  If the key is not in the table, this returns null.
+StringMapEntryBase *StringMapImpl::RemoveKey(std::string_view Key) {
+  int Bucket = FindKey(Key);
+  if (Bucket == -1)
+    return nullptr;
+
+  StringMapEntryBase *Result = TheTable[Bucket];
+  TheTable[Bucket] = getTombstoneVal();
+  --NumItems;
+  ++NumTombstones;
+  assert(NumItems + NumTombstones <= NumBuckets);
+
+  return Result;
+}
+
+/// RehashTable - Grow the table, redistributing values into the buckets with
+/// the appropriate mod-of-hashtable-size.
+unsigned StringMapImpl::RehashTable(unsigned BucketNo) {
+  unsigned NewSize;
+  unsigned *HashTable = (unsigned *)(TheTable + NumBuckets + 1);
+
+  // If the hash table is now more than 3/4 full, or if fewer than 1/8 of
+  // the buckets are empty (meaning that many are filled with tombstones),
+  // grow/rehash the table.
+  if (LLVM_UNLIKELY(NumItems * 4 > NumBuckets * 3)) {
+    NewSize = NumBuckets * 2;
+  } else if (LLVM_UNLIKELY(NumBuckets - (NumItems + NumTombstones) <=
+                           NumBuckets / 8)) {
+    NewSize = NumBuckets;
+  } else {
+    return BucketNo;
+  }
+
+  unsigned NewBucketNo = BucketNo;
+  // Allocate one extra bucket which will always be non-empty.  This allows the
+  // iterators to stop at end.
+  auto NewTableArray = static_cast<StringMapEntryBase **>(safe_calloc(
+      NewSize + 1, sizeof(StringMapEntryBase *) + sizeof(unsigned)));
+
+  unsigned *NewHashArray = (unsigned *)(NewTableArray + NewSize + 1);
+  NewTableArray[NewSize] = (StringMapEntryBase *)2;
+
+  // Rehash all the items into their new buckets.  Luckily :) we already have
+  // the hash values available, so we don't have to rehash any strings.
+  for (unsigned I = 0, E = NumBuckets; I != E; ++I) {
+    StringMapEntryBase *Bucket = TheTable[I];
+    if (Bucket && Bucket != getTombstoneVal()) {
+      // Fast case, bucket available.
+      unsigned FullHash = HashTable[I];
+      unsigned NewBucket = FullHash & (NewSize - 1);
+      if (!NewTableArray[NewBucket]) {
+        NewTableArray[FullHash & (NewSize - 1)] = Bucket;
+        NewHashArray[FullHash & (NewSize - 1)] = FullHash;
+        if (I == BucketNo)
+          NewBucketNo = NewBucket;
+        continue;
+      }
+
+      // Otherwise probe for a spot.
+      unsigned ProbeSize = 1;
+      do {
+        NewBucket = (NewBucket + ProbeSize++) & (NewSize - 1);
+      } while (NewTableArray[NewBucket]);
+
+      // Finally found a slot.  Fill it in.
+      NewTableArray[NewBucket] = Bucket;
+      NewHashArray[NewBucket] = FullHash;
+      if (I == BucketNo)
+        NewBucketNo = NewBucket;
+    }
+  }
+
+  free(TheTable);
+
+  TheTable = NewTableArray;
+  NumBuckets = NewSize;
+  NumTombstones = 0;
+  return NewBucketNo;
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/Windows/WindowsSupport.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/Windows/WindowsSupport.h
new file mode 100644
index 0000000..01200e2
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/Windows/WindowsSupport.h
@@ -0,0 +1,260 @@
+//===- WindowsSupport.h - Common Windows Include File -----------*- C++ -*-===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+//
+// This file defines things specific to Windows implementations.  In addition to
+// providing some helpers for working with win32 APIs, this header wraps
+// <windows.h> with some portability macros.  Always include WindowsSupport.h
+// instead of including <windows.h> directly.
+//
+//===----------------------------------------------------------------------===//
+
+//===----------------------------------------------------------------------===//
+//=== WARNING: Implementation here must contain only generic Win32 code that
+//===          is guaranteed to work on *all* Win32 variants.
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_WINDOWSSUPPORT_H
+#define WPIUTIL_WPI_WINDOWSSUPPORT_H
+
+// mingw-w64 tends to define it as 0x0502 in its headers.
+#undef _WIN32_WINNT
+#undef _WIN32_IE
+
+// Require at least Windows 7 API.
+#define _WIN32_WINNT 0x0601
+#define _WIN32_IE    0x0800 // MinGW at it again. FIXME: verify if still needed.
+#define WIN32_LEAN_AND_MEAN
+#ifndef NOMINMAX
+#define NOMINMAX
+#endif
+
+#include "wpi/SmallVector.h"
+#include "wpi/StringExtras.h"
+#include "wpi/Chrono.h"
+#include "wpi/Compiler.h"
+#include "wpi/ErrorHandling.h"
+#include "wpi/VersionTuple.h"
+#include <cassert>
+#include <string>
+#include <system_error>
+#define WIN32_NO_STATUS
+#include <windows.h>
+#undef WIN32_NO_STATUS
+#include <winternl.h>
+#include <ntstatus.h>
+
+// Must be included after windows.h
+#include <wincrypt.h>
+
+namespace wpi {
+
+/// Returns the Windows version as Major.Minor.0.BuildNumber. Uses
+/// RtlGetVersion or GetVersionEx under the hood depending on what is available.
+/// GetVersionEx is deprecated, but this API exposes the build number which can
+/// be useful for working around certain kernel bugs.
+inline wpi::VersionTuple GetWindowsOSVersion() {
+  typedef NTSTATUS(WINAPI* RtlGetVersionPtr)(PRTL_OSVERSIONINFOW);
+  HMODULE hMod = ::GetModuleHandleW(L"ntdll.dll");
+  if (hMod) {
+    auto getVer = (RtlGetVersionPtr)::GetProcAddress(hMod, "RtlGetVersion");
+    if (getVer) {
+      RTL_OSVERSIONINFOEXW info{};
+      info.dwOSVersionInfoSize = sizeof(info);
+      if (getVer((PRTL_OSVERSIONINFOW)&info) == ((NTSTATUS)0x00000000L)) {
+        return wpi::VersionTuple(info.dwMajorVersion, info.dwMinorVersion, 0,
+                                  info.dwBuildNumber);
+      }
+    }
+  }
+  return wpi::VersionTuple(0, 0, 0, 0);
+}
+
+/// Determines if the program is running on Windows 8 or newer. This
+/// reimplements one of the helpers in the Windows 8.1 SDK, which are intended
+/// to supercede raw calls to GetVersionEx. Old SDKs, Cygwin, and MinGW don't
+/// yet have VersionHelpers.h, so we have our own helper.
+inline bool RunningWindows8OrGreater() {
+  // Windows 8 is version 6.2, service pack 0.
+  return GetWindowsOSVersion() >= wpi::VersionTuple(6, 2, 0, 0);
+}
+
+/// Returns the Windows version as Major.Minor.0.BuildNumber. Uses
+/// RtlGetVersion or GetVersionEx under the hood depending on what is available.
+/// GetVersionEx is deprecated, but this API exposes the build number which can
+/// be useful for working around certain kernel bugs.
+wpi::VersionTuple GetWindowsOSVersion();
+
+bool MakeErrMsg(std::string *ErrMsg, const std::string &prefix);
+
+// Include GetLastError() in a fatal error message.
+[[noreturn]] inline void ReportLastErrorFatal(const char *Msg) {
+  std::string ErrMsg;
+  MakeErrMsg(&ErrMsg, Msg);
+  wpi::report_fatal_error(ErrMsg);
+}
+
+template <typename HandleTraits>
+class ScopedHandle {
+  typedef typename HandleTraits::handle_type handle_type;
+  handle_type Handle;
+
+  ScopedHandle(const ScopedHandle &other) = delete;
+  void operator=(const ScopedHandle &other) = delete;
+public:
+  ScopedHandle()
+    : Handle(HandleTraits::GetInvalid()) {}
+
+  explicit ScopedHandle(handle_type h)
+    : Handle(h) {}
+
+  ~ScopedHandle() {
+    if (HandleTraits::IsValid(Handle))
+      HandleTraits::Close(Handle);
+  }
+
+  handle_type take() {
+    handle_type t = Handle;
+    Handle = HandleTraits::GetInvalid();
+    return t;
+  }
+
+  ScopedHandle &operator=(handle_type h) {
+    if (HandleTraits::IsValid(Handle))
+      HandleTraits::Close(Handle);
+    Handle = h;
+    return *this;
+  }
+
+  // True if Handle is valid.
+  explicit operator bool() const {
+    return HandleTraits::IsValid(Handle) ? true : false;
+  }
+
+  operator handle_type() const {
+    return Handle;
+  }
+};
+
+struct CommonHandleTraits {
+  typedef HANDLE handle_type;
+
+  static handle_type GetInvalid() {
+    return INVALID_HANDLE_VALUE;
+  }
+
+  static void Close(handle_type h) {
+    ::CloseHandle(h);
+  }
+
+  static bool IsValid(handle_type h) {
+    return h != GetInvalid();
+  }
+};
+
+struct JobHandleTraits : CommonHandleTraits {
+  static handle_type GetInvalid() {
+    return NULL;
+  }
+};
+
+struct CryptContextTraits : CommonHandleTraits {
+  typedef HCRYPTPROV handle_type;
+
+  static handle_type GetInvalid() {
+    return 0;
+  }
+
+  static void Close(handle_type h) {
+    ::CryptReleaseContext(h, 0);
+  }
+
+  static bool IsValid(handle_type h) {
+    return h != GetInvalid();
+  }
+};
+
+struct RegTraits : CommonHandleTraits {
+  typedef HKEY handle_type;
+
+  static handle_type GetInvalid() {
+    return NULL;
+  }
+
+  static void Close(handle_type h) {
+    ::RegCloseKey(h);
+  }
+
+  static bool IsValid(handle_type h) {
+    return h != GetInvalid();
+  }
+};
+
+struct FindHandleTraits : CommonHandleTraits {
+  static void Close(handle_type h) {
+    ::FindClose(h);
+  }
+};
+
+struct FileHandleTraits : CommonHandleTraits {};
+
+typedef ScopedHandle<CommonHandleTraits> ScopedCommonHandle;
+typedef ScopedHandle<FileHandleTraits>   ScopedFileHandle;
+typedef ScopedHandle<CryptContextTraits> ScopedCryptContext;
+typedef ScopedHandle<RegTraits>          ScopedRegHandle;
+typedef ScopedHandle<FindHandleTraits>   ScopedFindHandle;
+typedef ScopedHandle<JobHandleTraits>    ScopedJobHandle;
+
+template <class T>
+class SmallVectorImpl;
+
+template <class T>
+typename SmallVectorImpl<T>::const_pointer
+c_str(SmallVectorImpl<T> &str) {
+  str.push_back(0);
+  str.pop_back();
+  return str.data();
+}
+
+namespace sys {
+
+inline std::chrono::nanoseconds toDuration(FILETIME Time) {
+  ULARGE_INTEGER TimeInteger;
+  TimeInteger.LowPart = Time.dwLowDateTime;
+  TimeInteger.HighPart = Time.dwHighDateTime;
+
+  // FILETIME's are # of 100 nanosecond ticks (1/10th of a microsecond)
+  return std::chrono::nanoseconds(100 * TimeInteger.QuadPart);
+}
+
+inline TimePoint<> toTimePoint(FILETIME Time) {
+  ULARGE_INTEGER TimeInteger;
+  TimeInteger.LowPart = Time.dwLowDateTime;
+  TimeInteger.HighPart = Time.dwHighDateTime;
+
+  // Adjust for different epoch
+  TimeInteger.QuadPart -= 11644473600ll * 10000000;
+
+  // FILETIME's are # of 100 nanosecond ticks (1/10th of a microsecond)
+  return TimePoint<>(std::chrono::nanoseconds(100 * TimeInteger.QuadPart));
+}
+
+inline FILETIME toFILETIME(TimePoint<> TP) {
+  ULARGE_INTEGER TimeInteger;
+  TimeInteger.QuadPart = TP.time_since_epoch().count() / 100;
+  TimeInteger.QuadPart += 11644473600ll * 10000000;
+
+  FILETIME Time;
+  Time.dwLowDateTime = TimeInteger.LowPart;
+  Time.dwHighDateTime = TimeInteger.HighPart;
+  return Time;
+}
+
+} // end namespace sys
+} // end namespace wpi.
+
+#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/raw_os_ostream.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/raw_os_ostream.cpp
new file mode 100644
index 0000000..682a9a0
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/raw_os_ostream.cpp
@@ -0,0 +1,29 @@
+//===--- raw_os_ostream.cpp - Implement the raw_os_ostream class ----------===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+//
+// This implements support adapting raw_ostream to std::ostream.
+//
+//===----------------------------------------------------------------------===//
+
+#include "wpi/raw_os_ostream.h"
+#include <ostream>
+using namespace wpi;
+
+//===----------------------------------------------------------------------===//
+//  raw_os_ostream
+//===----------------------------------------------------------------------===//
+
+raw_os_ostream::~raw_os_ostream() {
+  flush();
+}
+
+void raw_os_ostream::write_impl(const char *Ptr, size_t Size) {
+  OS.write(Ptr, Size);
+}
+
+uint64_t raw_os_ostream::current_pos() const { return OS.tellp(); }
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/raw_ostream.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/raw_ostream.cpp
new file mode 100644
index 0000000..a2d586b
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/raw_ostream.cpp
@@ -0,0 +1,730 @@
+//===--- raw_ostream.cpp - Implement the raw_ostream classes --------------===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+//
+// This implements support for bulk buffered stream output.
+//
+//===----------------------------------------------------------------------===//
+
+#ifdef _WIN32
+#define _CRT_NONSTDC_NO_WARNINGS
+#endif
+
+#include "wpi/raw_ostream.h"
+#include "wpi/SmallString.h"
+#include "wpi/SmallVector.h"
+#include "wpi/StringExtras.h"
+#include "wpi/Compiler.h"
+#include "wpi/ErrorHandling.h"
+#include "wpi/fs.h"
+#include "wpi/MathExtras.h"
+#include <algorithm>
+#include <cerrno>
+#include <cstdio>
+#include <sys/stat.h>
+
+// <fcntl.h> may provide O_BINARY.
+# include <fcntl.h>
+
+#ifndef _WIN32
+#include <unistd.h>
+#include <sys/uio.h>
+#endif
+
+#if defined(__CYGWIN__)
+#include <io.h>
+#endif
+
+#if defined(_MSC_VER)
+#include <io.h>
+#ifndef STDIN_FILENO
+# define STDIN_FILENO 0
+#endif
+#ifndef STDOUT_FILENO
+# define STDOUT_FILENO 1
+#endif
+#ifndef STDERR_FILENO
+# define STDERR_FILENO 2
+#endif
+#endif
+
+#ifdef _WIN32
+#include "wpi/ConvertUTF.h"
+#include "Windows/WindowsSupport.h"
+#endif
+
+using namespace wpi;
+
+constexpr raw_ostream::Colors raw_ostream::BLACK;
+constexpr raw_ostream::Colors raw_ostream::RED;
+constexpr raw_ostream::Colors raw_ostream::GREEN;
+constexpr raw_ostream::Colors raw_ostream::YELLOW;
+constexpr raw_ostream::Colors raw_ostream::BLUE;
+constexpr raw_ostream::Colors raw_ostream::MAGENTA;
+constexpr raw_ostream::Colors raw_ostream::CYAN;
+constexpr raw_ostream::Colors raw_ostream::WHITE;
+constexpr raw_ostream::Colors raw_ostream::SAVEDCOLOR;
+constexpr raw_ostream::Colors raw_ostream::RESET;
+
+namespace {
+// Find the length of an array.
+template <class T, std::size_t N>
+constexpr inline size_t array_lengthof(T (&)[N]) {
+  return N;
+}
+}  // namespace
+
+raw_ostream::~raw_ostream() {
+  // raw_ostream's subclasses should take care to flush the buffer
+  // in their destructors.
+  assert(OutBufCur == OutBufStart &&
+         "raw_ostream destructor called with non-empty buffer!");
+
+  if (BufferMode == BufferKind::InternalBuffer)
+    delete [] OutBufStart;
+}
+
+size_t raw_ostream::preferred_buffer_size() const {
+  // BUFSIZ is intended to be a reasonable default.
+  return BUFSIZ;
+}
+
+void raw_ostream::SetBuffered() {
+  // Ask the subclass to determine an appropriate buffer size.
+  if (size_t Size = preferred_buffer_size())
+    SetBufferSize(Size);
+  else
+    // It may return 0, meaning this stream should be unbuffered.
+    SetUnbuffered();
+}
+
+void raw_ostream::SetBufferAndMode(char *BufferStart, size_t Size,
+                                   BufferKind Mode) {
+  assert(((Mode == BufferKind::Unbuffered && !BufferStart && Size == 0) ||
+          (Mode != BufferKind::Unbuffered && BufferStart && Size != 0)) &&
+         "stream must be unbuffered or have at least one byte");
+  // Make sure the current buffer is free of content (we can't flush here; the
+  // child buffer management logic will be in write_impl).
+  assert(GetNumBytesInBuffer() == 0 && "Current buffer is non-empty!");
+
+  if (BufferMode == BufferKind::InternalBuffer)
+    delete [] OutBufStart;
+  OutBufStart = BufferStart;
+  OutBufEnd = OutBufStart+Size;
+  OutBufCur = OutBufStart;
+  BufferMode = Mode;
+
+  assert(OutBufStart <= OutBufEnd && "Invalid size!");
+}
+
+raw_ostream &raw_ostream::write_escaped(std::string_view Str,
+                                        bool UseHexEscapes) {
+  for (unsigned char c : Str) {
+    switch (c) {
+    case '\\':
+      *this << '\\' << '\\';
+      break;
+    case '\t':
+      *this << '\\' << 't';
+      break;
+    case '\n':
+      *this << '\\' << 'n';
+      break;
+    case '"':
+      *this << '\\' << '"';
+      break;
+    default:
+      if (isPrint(c)) {
+        *this << c;
+        break;
+      }
+
+      // Write out the escaped representation.
+      if (UseHexEscapes) {
+        *this << '\\' << 'x';
+        *this << hexdigit((c >> 4) & 0xF);
+        *this << hexdigit((c >> 0) & 0xF);
+      } else {
+        // Always use a full 3-character octal escape.
+        *this << '\\';
+        *this << char('0' + ((c >> 6) & 7));
+        *this << char('0' + ((c >> 3) & 7));
+        *this << char('0' + ((c >> 0) & 7));
+      }
+    }
+  }
+
+  return *this;
+}
+
+void raw_ostream::flush_nonempty() {
+  assert(OutBufCur > OutBufStart && "Invalid call to flush_nonempty.");
+  size_t Length = OutBufCur - OutBufStart;
+  OutBufCur = OutBufStart;
+  flush_tied_then_write(OutBufStart, Length);
+}
+
+raw_ostream &raw_ostream::write(unsigned char C) {
+  // Group exceptional cases into a single branch.
+  if (LLVM_UNLIKELY(OutBufCur >= OutBufEnd)) {
+    if (LLVM_UNLIKELY(!OutBufStart)) {
+      if (BufferMode == BufferKind::Unbuffered) {
+        flush_tied_then_write(reinterpret_cast<char *>(&C), 1);
+        return *this;
+      }
+      // Set up a buffer and start over.
+      SetBuffered();
+      return write(C);
+    }
+
+    flush_nonempty();
+  }
+
+  *OutBufCur++ = C;
+  return *this;
+}
+
+raw_ostream &raw_ostream::write(const char *Ptr, size_t Size) {
+  // Group exceptional cases into a single branch.
+  if (LLVM_UNLIKELY(size_t(OutBufEnd - OutBufCur) < Size)) {
+    if (LLVM_UNLIKELY(!OutBufStart)) {
+      if (BufferMode == BufferKind::Unbuffered) {
+        flush_tied_then_write(Ptr, Size);
+        return *this;
+      }
+      // Set up a buffer and start over.
+      SetBuffered();
+      return write(Ptr, Size);
+    }
+
+    size_t NumBytes = OutBufEnd - OutBufCur;
+
+    // If the buffer is empty at this point we have a string that is larger
+    // than the buffer. Directly write the chunk that is a multiple of the
+    // preferred buffer size and put the remainder in the buffer.
+    if (LLVM_UNLIKELY(OutBufCur == OutBufStart)) {
+      assert(NumBytes != 0 && "undefined behavior");
+      size_t BytesToWrite = Size - (Size % NumBytes);
+      flush_tied_then_write(Ptr, BytesToWrite);
+      size_t BytesRemaining = Size - BytesToWrite;
+      if (BytesRemaining > size_t(OutBufEnd - OutBufCur)) {
+        // Too much left over to copy into our buffer.
+        return write(Ptr + BytesToWrite, BytesRemaining);
+      }
+      copy_to_buffer(Ptr + BytesToWrite, BytesRemaining);
+      return *this;
+    }
+
+    // We don't have enough space in the buffer to fit the string in. Insert as
+    // much as possible, flush and start over with the remainder.
+    copy_to_buffer(Ptr, NumBytes);
+    flush_nonempty();
+    return write(Ptr + NumBytes, Size - NumBytes);
+  }
+
+  copy_to_buffer(Ptr, Size);
+
+  return *this;
+}
+
+void raw_ostream::copy_to_buffer(const char *Ptr, size_t Size) {
+  assert(Size <= size_t(OutBufEnd - OutBufCur) && "Buffer overrun!");
+
+  // Handle short strings specially, memcpy isn't very good at very short
+  // strings.
+  switch (Size) {
+  case 4: OutBufCur[3] = Ptr[3]; LLVM_FALLTHROUGH;
+  case 3: OutBufCur[2] = Ptr[2]; LLVM_FALLTHROUGH;
+  case 2: OutBufCur[1] = Ptr[1]; LLVM_FALLTHROUGH;
+  case 1: OutBufCur[0] = Ptr[0]; LLVM_FALLTHROUGH;
+  case 0: break;
+  default:
+    memcpy(OutBufCur, Ptr, Size);
+    break;
+  }
+
+  OutBufCur += Size;
+}
+
+void raw_ostream::flush_tied_then_write(const char *Ptr, size_t Size) {
+  if (TiedStream)
+    TiedStream->flush();
+  write_impl(Ptr, Size);
+}
+
+
+template <char C>
+static raw_ostream &write_padding(raw_ostream &OS, unsigned NumChars) {
+  static const char Chars[] = {C, C, C, C, C, C, C, C, C, C, C, C, C, C, C, C,
+                               C, C, C, C, C, C, C, C, C, C, C, C, C, C, C, C,
+                               C, C, C, C, C, C, C, C, C, C, C, C, C, C, C, C,
+                               C, C, C, C, C, C, C, C, C, C, C, C, C, C, C, C,
+                               C, C, C, C, C, C, C, C, C, C, C, C, C, C, C, C};
+
+  // Usually the indentation is small, handle it with a fastpath.
+  if (NumChars < array_lengthof(Chars))
+    return OS.write(Chars, NumChars);
+
+  while (NumChars) {
+    unsigned NumToWrite = std::min(NumChars,
+                                   (unsigned)array_lengthof(Chars)-1);
+    OS.write(Chars, NumToWrite);
+    NumChars -= NumToWrite;
+  }
+  return OS;
+}
+
+/// indent - Insert 'NumSpaces' spaces.
+raw_ostream &raw_ostream::indent(unsigned NumSpaces) {
+  return write_padding<' '>(*this, NumSpaces);
+}
+
+/// write_zeros - Insert 'NumZeros' nulls.
+raw_ostream &raw_ostream::write_zeros(unsigned NumZeros) {
+  return write_padding<'\0'>(*this, NumZeros);
+}
+
+void raw_ostream::anchor() {}
+
+//===----------------------------------------------------------------------===//
+//  raw_fd_ostream
+//===----------------------------------------------------------------------===//
+
+static int getFD(std::string_view Filename, std::error_code &EC,
+                 fs::CreationDisposition Disp, fs::FileAccess Access,
+                 fs::OpenFlags Flags) {
+  assert((Access & fs::FA_Write) &&
+         "Cannot make a raw_ostream from a read-only descriptor!");
+
+  // Handle "-" as stdout. Note that when we do this, we consider ourself
+  // the owner of stdout and may set the "binary" flag globally based on Flags.
+  if (Filename == "-") {
+    EC = std::error_code();
+    // Change stdout's text/binary mode based on the Flags.
+    if (!(Flags & fs::OF_Text)) {
+#if defined(_WIN32)
+      _setmode(_fileno(stdout), _O_BINARY);
+#endif
+    }
+    return STDOUT_FILENO;
+  }
+
+  fs::file_t F;
+  if (Access & fs::FA_Read)
+    F = fs::OpenFileForReadWrite(fs::path{std::string_view{Filename.data(), Filename.size()}}, EC, Disp, Flags);
+  else
+    F = fs::OpenFileForWrite(fs::path{std::string_view{Filename.data(), Filename.size()}}, EC, Disp, Flags);
+  if (EC)
+    return -1;
+  int FD = fs::FileToFd(F, EC, Flags);
+  if (EC)
+    return -1;
+
+  return FD;
+}
+
+raw_fd_ostream::raw_fd_ostream(std::string_view Filename, std::error_code &EC)
+    : raw_fd_ostream(Filename, EC, fs::CD_CreateAlways, fs::FA_Write,
+                     fs::OF_None) {}
+
+raw_fd_ostream::raw_fd_ostream(std::string_view Filename, std::error_code &EC,
+                               fs::CreationDisposition Disp)
+    : raw_fd_ostream(Filename, EC, Disp, fs::FA_Write, fs::OF_None) {}
+
+raw_fd_ostream::raw_fd_ostream(std::string_view Filename, std::error_code &EC,
+                               fs::FileAccess Access)
+    : raw_fd_ostream(Filename, EC, fs::CD_CreateAlways, Access,
+                     fs::OF_None) {}
+
+raw_fd_ostream::raw_fd_ostream(std::string_view Filename, std::error_code &EC,
+                               fs::OpenFlags Flags)
+    : raw_fd_ostream(Filename, EC, fs::CD_CreateAlways, fs::FA_Write,
+                     Flags) {}
+
+raw_fd_ostream::raw_fd_ostream(std::string_view Filename, std::error_code &EC,
+                               fs::CreationDisposition Disp,
+                               fs::FileAccess Access,
+                               fs::OpenFlags Flags)
+    : raw_fd_ostream(getFD(Filename, EC, Disp, Access, Flags), true) {}
+
+/// FD is the file descriptor that this writes to.  If ShouldClose is true, this
+/// closes the file when the stream is destroyed.
+raw_fd_ostream::raw_fd_ostream(int fd, bool shouldClose, bool unbuffered,
+                               OStreamKind K)
+    : raw_pwrite_stream(unbuffered, K), FD(fd), ShouldClose(shouldClose) {
+  if (FD < 0 ) {
+    ShouldClose = false;
+    return;
+  }
+
+  enable_colors(true);
+
+  // Do not attempt to close stdout or stderr. We used to try to maintain the
+  // property that tools that support writing file to stdout should not also
+  // write informational output to stdout, but in practice we were never able to
+  // maintain this invariant. Many features have been added to LLVM and clang
+  // (-fdump-record-layouts, optimization remarks, etc) that print to stdout, so
+  // users must simply be aware that mixed output and remarks is a possibility.
+  if (FD <= STDERR_FILENO)
+    ShouldClose = false;
+
+#ifdef _WIN32
+  // Check if this is a console device. This is not equivalent to isatty.
+  IsWindowsConsole =
+      ::GetFileType((HANDLE)::_get_osfhandle(fd)) == FILE_TYPE_CHAR;
+#endif
+
+  // Get the starting position.
+  off_t loc = ::lseek(FD, 0, SEEK_CUR);
+#ifdef _WIN32
+  SupportsSeeking = loc != (off_t)-1 && ::GetFileType(reinterpret_cast<HANDLE>(::_get_osfhandle(FD))) != FILE_TYPE_PIPE;
+#else
+  SupportsSeeking = !EC && loc != (off_t)-1;
+#endif
+  if (!SupportsSeeking)
+    pos = 0;
+  else
+    pos = static_cast<uint64_t>(loc);
+}
+
+raw_fd_ostream::~raw_fd_ostream() {
+  if (FD >= 0) {
+    flush();
+    if (ShouldClose && ::close(FD) < 0)
+      error_detected(std::error_code(errno, std::generic_category()));
+  }
+
+#ifdef __MINGW32__
+  // On mingw, global dtors should not call exit().
+  // report_fatal_error() invokes exit(). We know report_fatal_error()
+  // might not write messages to stderr when any errors were detected
+  // on FD == 2.
+  if (FD == 2) return;
+#endif
+
+  // If there are any pending errors, report them now. Clients wishing
+  // to avoid report_fatal_error calls should check for errors with
+  // has_error() and clear the error flag with clear_error() before
+  // destructing raw_ostream objects which may have errors.
+  if (has_error())
+    report_fatal_error("IO failure on output stream: " + error().message(),
+                       /*gen_crash_diag=*/false);
+}
+
+#if defined(_WIN32)
+// The most reliable way to print unicode in a Windows console is with
+// WriteConsoleW. To use that, first transcode from UTF-8 to UTF-16. This
+// assumes that LLVM programs always print valid UTF-8 to the console. The data
+// might not be UTF-8 for two major reasons:
+// 1. The program is printing binary (-filetype=obj -o -), in which case it
+// would have been gibberish anyway.
+// 2. The program is printing text in a semi-ascii compatible codepage like
+// shift-jis or cp1252.
+//
+// Most LLVM programs don't produce non-ascii text unless they are quoting
+// user source input. A well-behaved LLVM program should either validate that
+// the input is UTF-8 or transcode from the local codepage to UTF-8 before
+// quoting it. If they don't, this may mess up the encoding, but this is still
+// probably the best compromise we can make.
+static bool write_console_impl(int FD, std::string_view Data) {
+  SmallVector<wchar_t, 256> WideText;
+
+  // Fall back to ::write if it wasn't valid UTF-8.
+  if (auto EC = sys::windows::UTF8ToUTF16(Data, WideText))
+    return false;
+
+  // On Windows 7 and earlier, WriteConsoleW has a low maximum amount of data
+  // that can be written to the console at a time.
+  size_t MaxWriteSize = WideText.size();
+  if (!RunningWindows8OrGreater())
+    MaxWriteSize = 32767;
+
+  size_t WCharsWritten = 0;
+  do {
+    size_t WCharsToWrite =
+        std::min(MaxWriteSize, WideText.size() - WCharsWritten);
+    DWORD ActuallyWritten;
+    bool Success =
+        ::WriteConsoleW((HANDLE)::_get_osfhandle(FD), &WideText[WCharsWritten],
+                        WCharsToWrite, &ActuallyWritten,
+                        /*Reserved=*/nullptr);
+
+    // The most likely reason for WriteConsoleW to fail is that FD no longer
+    // points to a console. Fall back to ::write. If this isn't the first loop
+    // iteration, something is truly wrong.
+    if (!Success)
+      return false;
+
+    WCharsWritten += ActuallyWritten;
+  } while (WCharsWritten != WideText.size());
+  return true;
+}
+#endif
+
+void raw_fd_ostream::write_impl(const char *Ptr, size_t Size) {
+  assert(FD >= 0 && "File already closed.");
+  pos += Size;
+
+#if defined(_WIN32)
+  // If this is a Windows console device, try re-encoding from UTF-8 to UTF-16
+  // and using WriteConsoleW. If that fails, fall back to plain write().
+  if (IsWindowsConsole)
+    if (write_console_impl(FD, std::string_view(Ptr, Size)))
+      return;
+#endif
+
+  // The maximum write size is limited to INT32_MAX. A write
+  // greater than SSIZE_MAX is implementation-defined in POSIX,
+  // and Windows _write requires 32 bit input.
+  size_t MaxWriteSize = INT32_MAX;
+
+#if defined(__linux__)
+  // It is observed that Linux returns EINVAL for a very large write (>2G).
+  // Make it a reasonably small value.
+  MaxWriteSize = 1024 * 1024 * 1024;
+#endif
+
+  do {
+    size_t ChunkSize = std::min(Size, MaxWriteSize);
+#ifdef _WIN32
+    int ret = ::_write(FD, Ptr, ChunkSize);
+#else
+    ssize_t ret = ::write(FD, Ptr, ChunkSize);
+#endif
+
+    if (ret < 0) {
+      // If it's a recoverable error, swallow it and retry the write.
+      //
+      // Ideally we wouldn't ever see EAGAIN or EWOULDBLOCK here, since
+      // raw_ostream isn't designed to do non-blocking I/O. However, some
+      // programs, such as old versions of bjam, have mistakenly used
+      // O_NONBLOCK. For compatibility, emulate blocking semantics by
+      // spinning until the write succeeds. If you don't want spinning,
+      // don't use O_NONBLOCK file descriptors with raw_ostream.
+      if (errno == EINTR || errno == EAGAIN
+#ifdef EWOULDBLOCK
+          || errno == EWOULDBLOCK
+#endif
+          )
+        continue;
+
+      // Otherwise it's a non-recoverable error. Note it and quit.
+      error_detected(std::error_code(errno, std::generic_category()));
+      break;
+    }
+
+    // The write may have written some or all of the data. Update the
+    // size and buffer pointer to reflect the remainder that needs
+    // to be written. If there are no bytes left, we're done.
+    Ptr += ret;
+    Size -= ret;
+  } while (Size > 0);
+}
+
+void raw_fd_ostream::close() {
+  assert(ShouldClose);
+  ShouldClose = false;
+  flush();
+  if (::close(FD) < 0)
+    error_detected(std::error_code(errno, std::generic_category()));
+  FD = -1;
+}
+
+uint64_t raw_fd_ostream::seek(uint64_t off) {
+  assert(SupportsSeeking && "Stream does not support seeking!");
+  flush();
+#ifdef _WIN32
+  pos = ::_lseeki64(FD, off, SEEK_SET);
+#else
+  pos = ::lseek(FD, off, SEEK_SET);
+#endif
+  if (pos == (uint64_t)-1)
+    error_detected(std::error_code(errno, std::generic_category()));
+  return pos;
+}
+
+void raw_fd_ostream::pwrite_impl(const char *Ptr, size_t Size,
+                                 uint64_t Offset) {
+  uint64_t Pos = tell();
+  seek(Offset);
+  write(Ptr, Size);
+  seek(Pos);
+}
+
+size_t raw_fd_ostream::preferred_buffer_size() const {
+#if defined(_WIN32)
+  // Disable buffering for console devices. Console output is re-encoded from
+  // UTF-8 to UTF-16 on Windows, and buffering it would require us to split the
+  // buffer on a valid UTF-8 codepoint boundary. Terminal buffering is disabled
+  // below on most other OSs, so do the same thing on Windows and avoid that
+  // complexity.
+  if (IsWindowsConsole)
+    return 0;
+  return raw_ostream::preferred_buffer_size();
+#elif !defined(__minix)
+  // Minix has no st_blksize.
+  assert(FD >= 0 && "File not yet open!");
+  struct stat statbuf;
+  if (fstat(FD, &statbuf) != 0)
+    return 0;
+
+  // If this is a terminal, don't use buffering. Line buffering
+  // would be a more traditional thing to do, but it's not worth
+  // the complexity.
+  if (S_ISCHR(statbuf.st_mode) && is_displayed())
+    return 0;
+  // Return the preferred block size.
+  return statbuf.st_blksize;
+#else
+  return raw_ostream::preferred_buffer_size();
+#endif
+}
+
+void raw_fd_ostream::anchor() {}
+
+//===----------------------------------------------------------------------===//
+//  outs(), errs(), nulls()
+//===----------------------------------------------------------------------===//
+
+raw_fd_ostream &wpi::outs() {
+  // Set buffer settings to model stdout behavior.
+  std::error_code EC;
+  static raw_fd_ostream* S = new raw_fd_ostream("-", EC, fs::OF_None);
+  assert(!EC);
+  return *S;
+}
+
+raw_fd_ostream &wpi::errs() {
+  // Set standard error to be unbuffered and tied to outs() by default.
+  static raw_fd_ostream* S = new raw_fd_ostream(STDERR_FILENO, false, true);
+  return *S;
+}
+
+/// nulls() - This returns a reference to a raw_ostream which discards output.
+raw_ostream &wpi::nulls() {
+  static raw_null_ostream S;
+  return S;
+}
+
+//===----------------------------------------------------------------------===//
+// File Streams
+//===----------------------------------------------------------------------===//
+
+raw_fd_stream::raw_fd_stream(std::string_view Filename, std::error_code &EC)
+    : raw_fd_ostream(getFD(Filename, EC, fs::CD_CreateAlways,
+                           fs::FA_Write | fs::FA_Read,
+                           fs::OF_None),
+                     true, false, OStreamKind::OK_FDStream) {
+  if (EC)
+    return;
+
+  if (!isRegularFile())
+    EC = std::make_error_code(std::errc::invalid_argument);
+}
+
+bool raw_fd_stream::classof(const raw_ostream *OS) {
+  return OS->get_kind() == OStreamKind::OK_FDStream;
+}
+
+//===----------------------------------------------------------------------===//
+//  raw_string_ostream
+//===----------------------------------------------------------------------===//
+
+void raw_string_ostream::write_impl(const char *Ptr, size_t Size) {
+  OS.append(Ptr, Size);
+}
+
+//===----------------------------------------------------------------------===//
+//  raw_svector_ostream
+//===----------------------------------------------------------------------===//
+
+uint64_t raw_svector_ostream::current_pos() const { return OS.size(); }
+
+void raw_svector_ostream::write_impl(const char *Ptr, size_t Size) {
+  OS.append(Ptr, Ptr + Size);
+}
+
+void raw_svector_ostream::pwrite_impl(const char *Ptr, size_t Size,
+                                      uint64_t Offset) {
+  memcpy(OS.data() + Offset, Ptr, Size);
+}
+
+//===----------------------------------------------------------------------===//
+//  raw_vector_ostream
+//===----------------------------------------------------------------------===//
+
+uint64_t raw_vector_ostream::current_pos() const { return OS.size(); }
+
+void raw_vector_ostream::write_impl(const char *Ptr, size_t Size) {
+  OS.insert(OS.end(), Ptr, Ptr + Size);
+}
+
+void raw_vector_ostream::pwrite_impl(const char *Ptr, size_t Size,
+                                     uint64_t Offset) {
+  memcpy(OS.data() + Offset, Ptr, Size);
+}
+
+//===----------------------------------------------------------------------===//
+//  raw_usvector_ostream
+//===----------------------------------------------------------------------===//
+
+uint64_t raw_usvector_ostream::current_pos() const { return OS.size(); }
+
+void raw_usvector_ostream::write_impl(const char *Ptr, size_t Size) {
+  OS.append(reinterpret_cast<const uint8_t *>(Ptr),
+            reinterpret_cast<const uint8_t *>(Ptr) + Size);
+}
+
+void raw_usvector_ostream::pwrite_impl(const char *Ptr, size_t Size,
+                                       uint64_t Offset) {
+  memcpy(OS.data() + Offset, Ptr, Size);
+}
+
+//===----------------------------------------------------------------------===//
+//  raw_uvector_ostream
+//===----------------------------------------------------------------------===//
+
+uint64_t raw_uvector_ostream::current_pos() const { return OS.size(); }
+
+void raw_uvector_ostream::write_impl(const char *Ptr, size_t Size) {
+  OS.insert(OS.end(), reinterpret_cast<const uint8_t *>(Ptr),
+            reinterpret_cast<const uint8_t *>(Ptr) + Size);
+}
+
+void raw_uvector_ostream::pwrite_impl(const char *Ptr, size_t Size,
+                                      uint64_t Offset) {
+  memcpy(OS.data() + Offset, Ptr, Size);
+}
+
+//===----------------------------------------------------------------------===//
+//  raw_null_ostream
+//===----------------------------------------------------------------------===//
+
+raw_null_ostream::~raw_null_ostream() {
+#ifndef NDEBUG
+  // ~raw_ostream asserts that the buffer is empty. This isn't necessary
+  // with raw_null_ostream, but it's better to have raw_null_ostream follow
+  // the rules than to change the rules just for raw_null_ostream.
+  flush();
+#endif
+}
+
+void raw_null_ostream::write_impl(const char *Ptr, size_t Size) {
+}
+
+uint64_t raw_null_ostream::current_pos() const {
+  return 0;
+}
+
+void raw_null_ostream::pwrite_impl(const char *Ptr, size_t Size,
+                                   uint64_t Offset) {}
+
+void raw_pwrite_stream::anchor() {}
+
+void buffer_ostream::anchor() {}
+
+void buffer_unique_ostream::anchor() {}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/AlignOf.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/AlignOf.h
new file mode 100644
index 0000000..5d400e4
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/AlignOf.h
@@ -0,0 +1,34 @@
+//===--- AlignOf.h - Portable calculation of type alignment -----*- C++ -*-===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+//
+// This file defines the AlignedCharArrayUnion class.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_ALIGNOF_H
+#define WPIUTIL_WPI_ALIGNOF_H
+
+#include <type_traits>
+
+namespace wpi {
+
+/// A suitably aligned and sized character array member which can hold elements
+/// of any type.
+///
+/// This template is equivalent to std::aligned_union_t<1, ...>, but we cannot
+/// use it due to a bug in the MSVC x86 compiler:
+/// https://github.com/microsoft/STL/issues/1533
+/// Using `alignas` here works around the bug.
+template <typename T, typename... Ts> struct AlignedCharArrayUnion {
+  using AlignedUnion = std::aligned_union_t<1, T, Ts...>;
+  alignas(alignof(AlignedUnion)) char buffer[sizeof(AlignedUnion)];
+};
+
+} // end namespace wpi
+
+#endif // WPIUTIL_WPI_ALIGNOF_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/AllocatorBase.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/AllocatorBase.h
new file mode 100644
index 0000000..29ba16f
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/AllocatorBase.h
@@ -0,0 +1,104 @@
+//===- AllocatorBase.h - Simple memory allocation abstraction ---*- C++ -*-===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+/// \file
+///
+/// This file defines MallocAllocator. MallocAllocator conforms to the LLVM
+/// "Allocator" concept which consists of an Allocate method accepting a size
+/// and alignment, and a Deallocate accepting a pointer and size. Further, the
+/// LLVM "Allocator" concept has overloads of Allocate and Deallocate for
+/// setting size and alignment based on the final type. These overloads are
+/// typically provided by a base class template \c AllocatorBase.
+///
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_ALLOCATORBASE_H
+#define WPIUTIL_WPI_ALLOCATORBASE_H
+
+#include "wpi/Compiler.h"
+#include "wpi/MemAlloc.h"
+#include <type_traits>
+
+namespace wpi {
+
+/// CRTP base class providing obvious overloads for the core \c
+/// Allocate() methods of LLVM-style allocators.
+///
+/// This base class both documents the full public interface exposed by all
+/// LLVM-style allocators, and redirects all of the overloads to a single core
+/// set of methods which the derived class must define.
+template <typename DerivedT> class AllocatorBase {
+public:
+  /// Allocate \a Size bytes of \a Alignment aligned memory. This method
+  /// must be implemented by \c DerivedT.
+  void *Allocate(size_t Size, size_t Alignment) {
+#ifdef __clang__
+    static_assert(static_cast<void *(AllocatorBase::*)(size_t, size_t)>(
+                      &AllocatorBase::Allocate) !=
+                      static_cast<void *(DerivedT::*)(size_t, size_t)>(
+                          &DerivedT::Allocate),
+                  "Class derives from AllocatorBase without implementing the "
+                  "core Allocate(size_t, size_t) overload!");
+#endif
+    return static_cast<DerivedT *>(this)->Allocate(Size, Alignment);
+  }
+
+  /// Deallocate \a Ptr to \a Size bytes of memory allocated by this
+  /// allocator.
+  void Deallocate(const void *Ptr, size_t Size, size_t Alignment) {
+#ifdef __clang__
+    static_assert(
+        static_cast<void (AllocatorBase::*)(const void *, size_t, size_t)>(
+            &AllocatorBase::Deallocate) !=
+            static_cast<void (DerivedT::*)(const void *, size_t, size_t)>(
+                &DerivedT::Deallocate),
+        "Class derives from AllocatorBase without implementing the "
+        "core Deallocate(void *) overload!");
+#endif
+    return static_cast<DerivedT *>(this)->Deallocate(Ptr, Size, Alignment);
+  }
+
+  // The rest of these methods are helpers that redirect to one of the above
+  // core methods.
+
+  /// Allocate space for a sequence of objects without constructing them.
+  template <typename T> T *Allocate(size_t Num = 1) {
+    return static_cast<T *>(Allocate(Num * sizeof(T), alignof(T)));
+  }
+
+  /// Deallocate space for a sequence of objects without constructing them.
+  template <typename T>
+  std::enable_if_t<!std::is_same<std::remove_cv_t<T>, void>::value, void>
+  Deallocate(T *Ptr, size_t Num = 1) {
+    Deallocate(static_cast<const void *>(Ptr), Num * sizeof(T), alignof(T));
+  }
+};
+
+class MallocAllocator : public AllocatorBase<MallocAllocator> {
+public:
+  void Reset() {}
+
+  LLVM_ATTRIBUTE_RETURNS_NONNULL void *Allocate(size_t Size, size_t Alignment) {
+    return allocate_buffer(Size, Alignment);
+  }
+
+  // Pull in base class overloads.
+  using AllocatorBase<MallocAllocator>::Allocate;
+
+  void Deallocate(const void *Ptr, size_t Size, size_t Alignment) {
+    deallocate_buffer(const_cast<void *>(Ptr), Size, Alignment);
+  }
+
+  // Pull in base class overloads.
+  using AllocatorBase<MallocAllocator>::Deallocate;
+
+  void PrintStats() const {}
+};
+
+} // namespace wpi
+
+#endif // WPIUTIL_WPI_ALLOCATORBASE_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/Chrono.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/Chrono.h
new file mode 100644
index 0000000..221f6dc
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/Chrono.h
@@ -0,0 +1,63 @@
+//===- llvm/Support/Chrono.h - Utilities for Timing Manipulation-*- C++ -*-===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_CHRONO_H
+#define WPIUTIL_WPI_CHRONO_H
+
+#include "wpi/Compiler.h"
+
+#include <chrono>
+#include <ctime>
+#include <ratio>
+
+namespace wpi {
+
+class raw_ostream;
+
+namespace sys {
+
+/// A time point on the system clock. This is provided for two reasons:
+/// - to insulate us against subtle differences in behavior to differences in
+///   system clock precision (which is implementation-defined and differs
+///   between platforms).
+/// - to shorten the type name
+/// The default precision is nanoseconds. If you need a specific precision
+/// specify it explicitly. If unsure, use the default. If you need a time point
+/// on a clock other than the system_clock, use std::chrono directly.
+template <typename D = std::chrono::nanoseconds>
+using TimePoint = std::chrono::time_point<std::chrono::system_clock, D>;
+
+/// Convert a TimePoint to std::time_t
+inline std::time_t toTimeT(TimePoint<> TP) {
+  using namespace std::chrono;
+  return system_clock::to_time_t(
+      time_point_cast<system_clock::time_point::duration>(TP));
+}
+
+/// Convert a std::time_t to a TimePoint
+inline TimePoint<std::chrono::seconds>
+toTimePoint(std::time_t T) {
+  using namespace std::chrono;
+  return time_point_cast<seconds>(system_clock::from_time_t(T));
+}
+
+/// Convert a std::time_t + nanoseconds to a TimePoint
+inline TimePoint<>
+toTimePoint(std::time_t T, uint32_t nsec) {
+  using namespace std::chrono;
+  return time_point_cast<nanoseconds>(system_clock::from_time_t(T))
+    + nanoseconds(nsec);
+}
+
+} // namespace sys
+
+raw_ostream &operator<<(raw_ostream &OS, sys::TimePoint<> TP);
+
+} // namespace wpi
+
+#endif // WPIUTIL_WPI_CHRONO_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/Compiler.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/Compiler.h
new file mode 100644
index 0000000..c98386e
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/Compiler.h
@@ -0,0 +1,619 @@
+//===-- llvm/Support/Compiler.h - Compiler abstraction support --*- C++ -*-===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+//
+// This file defines several macros, based on the current compiler.  This allows
+// use of compiler-specific features in a way that remains portable. This header
+// can be included from either C or C++.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_COMPILER_H
+#define WPIUTIL_WPI_COMPILER_H
+
+
+#include <stddef.h>
+
+#if defined(_MSC_VER)
+#include <sal.h>
+#endif
+
+#ifndef __has_feature
+# define __has_feature(x) 0
+#endif
+
+#ifndef __has_extension
+# define __has_extension(x) 0
+#endif
+
+#ifndef __has_attribute
+# define __has_attribute(x) 0
+#endif
+
+#ifndef __has_builtin
+# define __has_builtin(x) 0
+#endif
+
+// Only use __has_cpp_attribute in C++ mode. GCC defines __has_cpp_attribute in
+// C mode, but the :: in __has_cpp_attribute(scoped::attribute) is invalid.
+#ifndef LLVM_HAS_CPP_ATTRIBUTE
+#if defined(__cplusplus) && defined(__has_cpp_attribute)
+# define LLVM_HAS_CPP_ATTRIBUTE(x) __has_cpp_attribute(x)
+#else
+# define LLVM_HAS_CPP_ATTRIBUTE(x) 0
+#endif
+#endif
+
+/// \macro LLVM_GNUC_PREREQ
+/// Extend the default __GNUC_PREREQ even if glibc's features.h isn't
+/// available.
+#ifndef LLVM_GNUC_PREREQ
+# if defined(__GNUC__) && defined(__GNUC_MINOR__) && defined(__GNUC_PATCHLEVEL__)
+#  define LLVM_GNUC_PREREQ(maj, min, patch) \
+    ((__GNUC__ << 20) + (__GNUC_MINOR__ << 10) + __GNUC_PATCHLEVEL__ >= \
+     ((maj) << 20) + ((min) << 10) + (patch))
+# elif defined(__GNUC__) && defined(__GNUC_MINOR__)
+#  define LLVM_GNUC_PREREQ(maj, min, patch) \
+    ((__GNUC__ << 20) + (__GNUC_MINOR__ << 10) >= ((maj) << 20) + ((min) << 10))
+# else
+#  define LLVM_GNUC_PREREQ(maj, min, patch) 0
+# endif
+#endif
+
+/// \macro LLVM_MSC_PREREQ
+/// Is the compiler MSVC of at least the specified version?
+/// The common \param version values to check for are:
+/// * 1910: VS2017, version 15.1 & 15.2
+/// * 1911: VS2017, version 15.3 & 15.4
+/// * 1912: VS2017, version 15.5
+/// * 1913: VS2017, version 15.6
+/// * 1914: VS2017, version 15.7
+/// * 1915: VS2017, version 15.8
+/// * 1916: VS2017, version 15.9
+/// * 1920: VS2019, version 16.0
+/// * 1921: VS2019, version 16.1
+/// * 1922: VS2019, version 16.2
+/// * 1923: VS2019, version 16.3
+/// * 1924: VS2019, version 16.4
+/// * 1925: VS2019, version 16.5
+/// * 1926: VS2019, version 16.6
+/// * 1927: VS2019, version 16.7
+/// * 1928: VS2019, version 16.8 + 16.9
+/// * 1929: VS2019, version 16.10 + 16.11
+/// * 1930: VS2022, version 17.0
+#ifndef LLVM_MSC_PREREQ
+#ifdef _MSC_VER
+#define LLVM_MSC_PREREQ(version) (_MSC_VER >= (version))
+
+// We require at least VS 2019.
+#if !defined(LLVM_FORCE_USE_OLD_TOOLCHAIN)
+#if !LLVM_MSC_PREREQ(1920)
+#error LLVM requires at least VS 2019.
+#endif
+#endif
+
+#else
+#define LLVM_MSC_PREREQ(version) 0
+#endif
+#endif
+
+/// Does the compiler support ref-qualifiers for *this?
+///
+/// Sadly, this is separate from just rvalue reference support because GCC
+/// and MSVC implemented this later than everything else. This appears to be
+/// corrected in MSVC 2019 but not MSVC 2017.
+/// FIXME: Remove LLVM_HAS_RVALUE_REFERENCE_THIS macro
+#define LLVM_HAS_RVALUE_REFERENCE_THIS 1
+
+/// Expands to '&' if ref-qualifiers for *this are supported.
+///
+/// This can be used to provide lvalue/rvalue overrides of member functions.
+/// The rvalue override should be guarded by LLVM_HAS_RVALUE_REFERENCE_THIS
+#ifndef LLVM_LVALUE_FUNCTION
+#if LLVM_HAS_RVALUE_REFERENCE_THIS
+#define LLVM_LVALUE_FUNCTION &
+#else
+#define LLVM_LVALUE_FUNCTION
+#endif
+#endif
+
+/// LLVM_LIBRARY_VISIBILITY - If a class marked with this attribute is linked
+/// into a shared library, then the class should be private to the library and
+/// not accessible from outside it.  Can also be used to mark variables and
+/// functions, making them private to any shared library they are linked into.
+/// On PE/COFF targets, library visibility is the default, so this isn't needed.
+///
+/// LLVM_EXTERNAL_VISIBILITY - classes, functions, and variables marked with
+/// this attribute will be made public and visible outside of any shared library
+/// they are linked in to.
+#if __has_attribute(visibility) && !defined(__MINGW32__) &&                    \
+    !defined(__CYGWIN__) && !defined(_WIN32)
+#define LLVM_LIBRARY_VISIBILITY __attribute__ ((visibility("hidden")))
+#if defined(LLVM_BUILD_LLVM_DYLIB) || defined(LLVM_BUILD_SHARED_LIBS)
+#define LLVM_EXTERNAL_VISIBILITY __attribute__((visibility("default")))
+#else
+#define LLVM_EXTERNAL_VISIBILITY
+#endif
+#else
+#define LLVM_LIBRARY_VISIBILITY
+#define LLVM_EXTERNAL_VISIBILITY
+#endif
+
+#ifndef LLVM_PREFETCH
+#if defined(__GNUC__)
+#define LLVM_PREFETCH(addr, rw, locality) __builtin_prefetch(addr, rw, locality)
+#else
+#define LLVM_PREFETCH(addr, rw, locality)
+#endif
+#endif
+
+#ifndef LLVM_ATTRIBUTE_USED
+#if __has_attribute(used)
+#define LLVM_ATTRIBUTE_USED __attribute__((__used__))
+#else
+#define LLVM_ATTRIBUTE_USED
+#endif
+#endif
+
+/// LLVM_NODISCARD - Warn if a type or return value is discarded.
+
+// Use the 'nodiscard' attribute in C++17 or newer mode.
+#ifndef LLVM_NODISCARD
+#if defined(__cplusplus) && __cplusplus > 201402L && LLVM_HAS_CPP_ATTRIBUTE(nodiscard)
+#define LLVM_NODISCARD [[nodiscard]]
+#elif LLVM_HAS_CPP_ATTRIBUTE(clang::warn_unused_result)
+#define LLVM_NODISCARD [[clang::warn_unused_result]]
+// Clang in C++14 mode claims that it has the 'nodiscard' attribute, but also
+// warns in the pedantic mode that 'nodiscard' is a C++17 extension (PR33518).
+// Use the 'nodiscard' attribute in C++14 mode only with GCC.
+// TODO: remove this workaround when PR33518 is resolved.
+#elif defined(__GNUC__) && LLVM_HAS_CPP_ATTRIBUTE(nodiscard)
+#define LLVM_NODISCARD [[nodiscard]]
+#else
+#define LLVM_NODISCARD
+#endif
+#endif
+
+// Indicate that a non-static, non-const C++ member function reinitializes
+// the entire object to a known state, independent of the previous state of
+// the object.
+//
+// The clang-tidy check bugprone-use-after-move recognizes this attribute as a
+// marker that a moved-from object has left the indeterminate state and can be
+// reused.
+#if LLVM_HAS_CPP_ATTRIBUTE(clang::reinitializes)
+#define LLVM_ATTRIBUTE_REINITIALIZES [[clang::reinitializes]]
+#else
+#define LLVM_ATTRIBUTE_REINITIALIZES
+#endif
+
+// Some compilers warn about unused functions. When a function is sometimes
+// used or not depending on build settings (e.g. a function only called from
+// within "assert"), this attribute can be used to suppress such warnings.
+//
+// However, it shouldn't be used for unused *variables*, as those have a much
+// more portable solution:
+//   (void)unused_var_name;
+// Prefer cast-to-void wherever it is sufficient.
+#ifndef LLVM_ATTRIBUTE_UNUSED
+#if __has_attribute(unused)
+#define LLVM_ATTRIBUTE_UNUSED __attribute__((__unused__))
+#else
+#define LLVM_ATTRIBUTE_UNUSED
+#endif
+#endif
+
+// FIXME: Provide this for PE/COFF targets.
+#if __has_attribute(weak) && !defined(__MINGW32__) && !defined(__CYGWIN__) &&  \
+    !defined(_WIN32)
+#define LLVM_ATTRIBUTE_WEAK __attribute__((__weak__))
+#else
+#define LLVM_ATTRIBUTE_WEAK
+#endif
+
+#ifndef LLVM_READNONE
+// Prior to clang 3.2, clang did not accept any spelling of
+// __has_attribute(const), so assume it is supported.
+#if defined(__clang__) || defined(__GNUC__)
+// aka 'CONST' but following LLVM Conventions.
+#define LLVM_READNONE __attribute__((__const__))
+#else
+#define LLVM_READNONE
+#endif
+#endif
+
+#ifndef LLVM_READONLY
+#if __has_attribute(pure) || defined(__GNUC__)
+// aka 'PURE' but following LLVM Conventions.
+#define LLVM_READONLY __attribute__((__pure__))
+#else
+#define LLVM_READONLY
+#endif
+#endif
+
+#if __has_attribute(minsize)
+#define LLVM_ATTRIBUTE_MINSIZE __attribute__((minsize))
+#else
+#define LLVM_ATTRIBUTE_MINSIZE
+#endif
+
+#ifndef LLVM_LIKELY
+#if __has_builtin(__builtin_expect) || defined(__GNUC__)
+#define LLVM_LIKELY(EXPR) __builtin_expect((bool)(EXPR), true)
+#define LLVM_UNLIKELY(EXPR) __builtin_expect((bool)(EXPR), false)
+#else
+#define LLVM_LIKELY(EXPR) (EXPR)
+#define LLVM_UNLIKELY(EXPR) (EXPR)
+#endif
+#endif
+
+/// LLVM_ATTRIBUTE_NOINLINE - On compilers where we have a directive to do so,
+/// mark a method "not for inlining".
+#ifndef LLVM_ATTRIBUTE_NOINLINE
+#if __has_attribute(noinline)
+#define LLVM_ATTRIBUTE_NOINLINE __attribute__((noinline))
+#elif defined(_MSC_VER)
+#define LLVM_ATTRIBUTE_NOINLINE __declspec(noinline)
+#else
+#define LLVM_ATTRIBUTE_NOINLINE
+#endif
+#endif
+
+/// LLVM_ATTRIBUTE_ALWAYS_INLINE - On compilers where we have a directive to do
+/// so, mark a method "always inline" because it is performance sensitive.
+#ifndef LLVM_ATTRIBUTE_ALWAYS_INLINE
+#if __has_attribute(always_inline)
+#define LLVM_ATTRIBUTE_ALWAYS_INLINE inline __attribute__((always_inline))
+#elif defined(_MSC_VER)
+#define LLVM_ATTRIBUTE_ALWAYS_INLINE __forceinline
+#else
+#define LLVM_ATTRIBUTE_ALWAYS_INLINE inline
+#endif
+#endif
+
+/// LLVM_ATTRIBUTE_NO_DEBUG - On compilers where we have a directive to do
+/// so, mark a method "no debug" because debug info makes the debugger
+/// experience worse.
+#if __has_attribute(nodebug)
+#define LLVM_ATTRIBUTE_NODEBUG __attribute__((nodebug))
+#else
+#define LLVM_ATTRIBUTE_NODEBUG
+#endif
+
+#ifndef LLVM_ATTRIBUTE_RETURNS_NONNULL
+#if __has_attribute(returns_nonnull)
+#define LLVM_ATTRIBUTE_RETURNS_NONNULL __attribute__((returns_nonnull))
+#elif defined(_MSC_VER)
+#define LLVM_ATTRIBUTE_RETURNS_NONNULL _Ret_notnull_
+#else
+#define LLVM_ATTRIBUTE_RETURNS_NONNULL
+#endif
+#endif
+
+/// \macro LLVM_ATTRIBUTE_RETURNS_NOALIAS Used to mark a function as returning a
+/// pointer that does not alias any other valid pointer.
+#ifndef LLVM_ATTRIBUTE_RETURNS_NOALIAS
+#ifdef __GNUC__
+#define LLVM_ATTRIBUTE_RETURNS_NOALIAS __attribute__((__malloc__))
+#elif defined(_MSC_VER)
+#define LLVM_ATTRIBUTE_RETURNS_NOALIAS __declspec(restrict)
+#else
+#define LLVM_ATTRIBUTE_RETURNS_NOALIAS
+#endif
+#endif
+
+/// LLVM_FALLTHROUGH - Mark fallthrough cases in switch statements.
+#ifndef LLVM_FALLTHROUGH
+#if defined(__cplusplus) && __cplusplus > 201402L && LLVM_HAS_CPP_ATTRIBUTE(fallthrough)
+#define LLVM_FALLTHROUGH [[fallthrough]]
+#elif LLVM_HAS_CPP_ATTRIBUTE(gnu::fallthrough)
+#define LLVM_FALLTHROUGH [[gnu::fallthrough]]
+#elif __has_attribute(fallthrough)
+#define LLVM_FALLTHROUGH __attribute__((fallthrough))
+#elif LLVM_HAS_CPP_ATTRIBUTE(clang::fallthrough)
+#define LLVM_FALLTHROUGH [[clang::fallthrough]]
+#else
+#define LLVM_FALLTHROUGH
+#endif
+#endif
+
+/// LLVM_REQUIRE_CONSTANT_INITIALIZATION - Apply this to globals to ensure that
+/// they are constant initialized.
+#if LLVM_HAS_CPP_ATTRIBUTE(clang::require_constant_initialization)
+#define LLVM_REQUIRE_CONSTANT_INITIALIZATION                                   \
+  [[clang::require_constant_initialization]]
+#else
+#define LLVM_REQUIRE_CONSTANT_INITIALIZATION
+#endif
+
+/// LLVM_GSL_OWNER - Apply this to owning classes like SmallVector to enable
+/// lifetime warnings.
+#if LLVM_HAS_CPP_ATTRIBUTE(gsl::Owner)
+#define LLVM_GSL_OWNER [[gsl::Owner]]
+#else
+#define LLVM_GSL_OWNER
+#endif
+
+/// LLVM_GSL_POINTER - Apply this to non-owning classes like
+/// std::string_view to enable lifetime warnings.
+#if LLVM_HAS_CPP_ATTRIBUTE(gsl::Pointer)
+#define LLVM_GSL_POINTER [[gsl::Pointer]]
+#else
+#define LLVM_GSL_POINTER
+#endif
+
+/// LLVM_EXTENSION - Support compilers where we have a keyword to suppress
+/// pedantic diagnostics.
+#ifndef LLVM_EXTENSION
+#ifdef __GNUC__
+#define LLVM_EXTENSION __extension__
+#else
+#define LLVM_EXTENSION
+#endif
+#endif
+
+// LLVM_ATTRIBUTE_DEPRECATED(decl, "message")
+// This macro will be removed.
+// Use C++14's attribute instead: [[deprecated("message")]]
+#ifndef LLVM_ATTRIBUTE_DEPRECATED
+#define LLVM_ATTRIBUTE_DEPRECATED(decl, message) [[deprecated(message)]] decl
+#endif
+
+/// LLVM_BUILTIN_UNREACHABLE - On compilers which support it, expands
+/// to an expression which states that it is undefined behavior for the
+/// compiler to reach this point.  Otherwise is not defined.
+#ifndef LLVM_BUILTIN_UNREACHABLE
+#if __has_builtin(__builtin_unreachable) || defined(__GNUC__)
+# define LLVM_BUILTIN_UNREACHABLE __builtin_unreachable()
+#elif defined(_MSC_VER)
+# define LLVM_BUILTIN_UNREACHABLE __assume(false)
+#else
+# define LLVM_BUILTIN_UNREACHABLE
+#endif
+#endif
+
+/// LLVM_BUILTIN_TRAP - On compilers which support it, expands to an expression
+/// which causes the program to exit abnormally.
+#ifndef LLVM_BUILTIN_TRAP
+#if __has_builtin(__builtin_trap) || defined(__GNUC__)
+# define LLVM_BUILTIN_TRAP __builtin_trap()
+#elif defined(_MSC_VER)
+// The __debugbreak intrinsic is supported by MSVC, does not require forward
+// declarations involving platform-specific typedefs (unlike RaiseException),
+// results in a call to vectored exception handlers, and encodes to a short
+// instruction that still causes the trapping behavior we want.
+# define LLVM_BUILTIN_TRAP __debugbreak()
+#else
+# define LLVM_BUILTIN_TRAP *(volatile int*)0x11 = 0
+#endif
+#endif
+
+/// LLVM_BUILTIN_DEBUGTRAP - On compilers which support it, expands to
+/// an expression which causes the program to break while running
+/// under a debugger.
+#ifndef LLVM_BUILTIN_DEBUGTRAP
+#if __has_builtin(__builtin_debugtrap)
+# define LLVM_BUILTIN_DEBUGTRAP __builtin_debugtrap()
+#elif defined(_MSC_VER)
+// The __debugbreak intrinsic is supported by MSVC and breaks while
+// running under the debugger, and also supports invoking a debugger
+// when the OS is configured appropriately.
+# define LLVM_BUILTIN_DEBUGTRAP __debugbreak()
+#else
+// Just continue execution when built with compilers that have no
+// support. This is a debugging aid and not intended to force the
+// program to abort if encountered.
+# define LLVM_BUILTIN_DEBUGTRAP
+#endif
+#endif
+
+/// \macro LLVM_ASSUME_ALIGNED
+/// Returns a pointer with an assumed alignment.
+#ifndef LLVM_ASSUME_ALIGNED
+#if __has_builtin(__builtin_assume_aligned) || defined(__GNUC__)
+# define LLVM_ASSUME_ALIGNED(p, a) __builtin_assume_aligned(p, a)
+#elif defined(LLVM_BUILTIN_UNREACHABLE)
+# define LLVM_ASSUME_ALIGNED(p, a) \
+           (((uintptr_t(p) % (a)) == 0) ? (p) : (LLVM_BUILTIN_UNREACHABLE, (p)))
+#else
+# define LLVM_ASSUME_ALIGNED(p, a) (p)
+#endif
+#endif
+
+/// \macro LLVM_PACKED
+/// Used to specify a packed structure.
+/// LLVM_PACKED(
+///    struct A {
+///      int i;
+///      int j;
+///      int k;
+///      long long l;
+///   });
+///
+/// LLVM_PACKED_START
+/// struct B {
+///   int i;
+///   int j;
+///   int k;
+///   long long l;
+/// };
+/// LLVM_PACKED_END
+#ifndef LLVM_PACKED
+#ifdef _MSC_VER
+# define LLVM_PACKED(d) __pragma(pack(push, 1)) d __pragma(pack(pop))
+# define LLVM_PACKED_START __pragma(pack(push, 1))
+# define LLVM_PACKED_END   __pragma(pack(pop))
+#else
+# define LLVM_PACKED(d) d __attribute__((packed))
+# define LLVM_PACKED_START _Pragma("pack(push, 1)")
+# define LLVM_PACKED_END   _Pragma("pack(pop)")
+#endif
+#endif
+
+/// \macro LLVM_PTR_SIZE
+/// A constant integer equivalent to the value of sizeof(void*).
+/// Generally used in combination with alignas or when doing computation in the
+/// preprocessor.
+#ifndef LLVM_PTR_SIZE
+#ifdef __SIZEOF_POINTER__
+# define LLVM_PTR_SIZE __SIZEOF_POINTER__
+#elif defined(_WIN64)
+# define LLVM_PTR_SIZE 8
+#elif defined(_WIN32)
+# define LLVM_PTR_SIZE 4
+#elif defined(_MSC_VER)
+# error "could not determine LLVM_PTR_SIZE as a constant int for MSVC"
+#else
+# define LLVM_PTR_SIZE sizeof(void *)
+#endif
+#endif
+
+/// \macro LLVM_MEMORY_SANITIZER_BUILD
+/// Whether LLVM itself is built with MemorySanitizer instrumentation.
+#if __has_feature(memory_sanitizer)
+# define LLVM_MEMORY_SANITIZER_BUILD 1
+# include <sanitizer/msan_interface.h>
+# define LLVM_NO_SANITIZE_MEMORY_ATTRIBUTE __attribute__((no_sanitize_memory))
+#else
+# define LLVM_MEMORY_SANITIZER_BUILD 0
+# define __msan_allocated_memory(p, size)
+# define __msan_unpoison(p, size)
+# define LLVM_NO_SANITIZE_MEMORY_ATTRIBUTE
+#endif
+
+/// \macro LLVM_ADDRESS_SANITIZER_BUILD
+/// Whether LLVM itself is built with AddressSanitizer instrumentation.
+#if __has_feature(address_sanitizer) || defined(__SANITIZE_ADDRESS__)
+# define LLVM_ADDRESS_SANITIZER_BUILD 1
+# include <sanitizer/asan_interface.h>
+#else
+# define LLVM_ADDRESS_SANITIZER_BUILD 0
+# define __asan_poison_memory_region(p, size)
+# define __asan_unpoison_memory_region(p, size)
+#endif
+
+/// \macro LLVM_THREAD_SANITIZER_BUILD
+/// Whether LLVM itself is built with ThreadSanitizer instrumentation.
+#if __has_feature(thread_sanitizer) || defined(__SANITIZE_THREAD__)
+# define LLVM_THREAD_SANITIZER_BUILD 1
+#else
+# define LLVM_THREAD_SANITIZER_BUILD 0
+#endif
+
+#if LLVM_THREAD_SANITIZER_BUILD
+// Thread Sanitizer is a tool that finds races in code.
+// See http://code.google.com/p/data-race-test/wiki/DynamicAnnotations .
+// tsan detects these exact functions by name.
+#ifdef __cplusplus
+extern "C" {
+#endif
+void AnnotateHappensAfter(const char *file, int line, const volatile void *cv);
+void AnnotateHappensBefore(const char *file, int line, const volatile void *cv);
+void AnnotateIgnoreWritesBegin(const char *file, int line);
+void AnnotateIgnoreWritesEnd(const char *file, int line);
+#ifdef __cplusplus
+}
+#endif
+
+// This marker is used to define a happens-before arc. The race detector will
+// infer an arc from the begin to the end when they share the same pointer
+// argument.
+# define TsanHappensBefore(cv) AnnotateHappensBefore(__FILE__, __LINE__, cv)
+
+// This marker defines the destination of a happens-before arc.
+# define TsanHappensAfter(cv) AnnotateHappensAfter(__FILE__, __LINE__, cv)
+
+// Ignore any races on writes between here and the next TsanIgnoreWritesEnd.
+# define TsanIgnoreWritesBegin() AnnotateIgnoreWritesBegin(__FILE__, __LINE__)
+
+// Resume checking for racy writes.
+# define TsanIgnoreWritesEnd() AnnotateIgnoreWritesEnd(__FILE__, __LINE__)
+#else
+# define TsanHappensBefore(cv)
+# define TsanHappensAfter(cv)
+# define TsanIgnoreWritesBegin()
+# define TsanIgnoreWritesEnd()
+#endif
+
+/// \macro LLVM_NO_SANITIZE
+/// Disable a particular sanitizer for a function.
+#ifndef LLVM_NO_SANITIZE
+#if __has_attribute(no_sanitize)
+#define LLVM_NO_SANITIZE(KIND) __attribute__((no_sanitize(KIND)))
+#else
+#define LLVM_NO_SANITIZE(KIND)
+#endif
+#endif
+
+/// Mark debug helper function definitions like dump() that should not be
+/// stripped from debug builds.
+/// Note that you should also surround dump() functions with
+/// `#if !defined(NDEBUG) || defined(LLVM_ENABLE_DUMP)` so they do always
+/// get stripped in release builds.
+// FIXME: Move this to a private config.h as it's not usable in public headers.
+#ifndef LLVM_DUMP_METHOD
+#if !defined(NDEBUG) || defined(LLVM_ENABLE_DUMP)
+#define LLVM_DUMP_METHOD LLVM_ATTRIBUTE_NOINLINE LLVM_ATTRIBUTE_USED
+#else
+#define LLVM_DUMP_METHOD LLVM_ATTRIBUTE_NOINLINE
+#endif
+#endif
+
+/// \macro LLVM_PRETTY_FUNCTION
+/// Gets a user-friendly looking function signature for the current scope
+/// using the best available method on each platform.  The exact format of the
+/// resulting string is implementation specific and non-portable, so this should
+/// only be used, for example, for logging or diagnostics.
+#ifndef LLVM_PRETTY_FUNCTION
+#if defined(_MSC_VER)
+#define LLVM_PRETTY_FUNCTION __FUNCSIG__
+#elif defined(__GNUC__) || defined(__clang__)
+#define LLVM_PRETTY_FUNCTION __PRETTY_FUNCTION__
+#else
+#define LLVM_PRETTY_FUNCTION __func__
+#endif
+#endif
+
+/// \macro LLVM_THREAD_LOCAL
+/// A thread-local storage specifier which can be used with globals,
+/// extern globals, and static globals.
+///
+/// This is essentially an extremely restricted analog to C++11's thread_local
+/// support. It uses thread_local if available, falling back on gcc __thread
+/// if not. __thread doesn't support many of the C++11 thread_local's
+/// features. You should only use this for PODs that you can statically
+/// initialize to some constant value. In almost all circumstances this is most
+/// appropriate for use with a pointer, integer, or small aggregation of
+/// pointers and integers.
+#if __has_feature(cxx_thread_local) || defined(_MSC_VER)
+#define LLVM_THREAD_LOCAL thread_local
+#else
+// Clang, GCC, and other compatible compilers used __thread prior to C++11 and
+// we only need the restricted functionality that provides.
+#define LLVM_THREAD_LOCAL __thread
+#endif
+
+/// \macro LLVM_ENABLE_EXCEPTIONS
+/// Whether LLVM is built with exception support.
+#if __has_feature(cxx_exceptions)
+#define LLVM_ENABLE_EXCEPTIONS 1
+#elif defined(__GNUC__) && defined(__EXCEPTIONS)
+#define LLVM_ENABLE_EXCEPTIONS 1
+#elif defined(_MSC_VER) && defined(_CPPUNWIND)
+#define LLVM_ENABLE_EXCEPTIONS 1
+#endif
+
+/// \macro LLVM_NO_PROFILE_INSTRUMENT_FUNCTION
+/// Disable the profile instrument for a function.
+#if __has_attribute(no_profile_instrument_function)
+#define LLVM_NO_PROFILE_INSTRUMENT_FUNCTION                                    \
+  __attribute__((no_profile_instrument_function))
+#else
+#define LLVM_NO_PROFILE_INSTRUMENT_FUNCTION
+#endif
+
+#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/ConvertUTF.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/ConvertUTF.h
new file mode 100644
index 0000000..436bc6d
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/ConvertUTF.h
@@ -0,0 +1,307 @@
+/*===--- ConvertUTF.h - Universal Character Names conversions ---------------===
+ *
+ * Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+ * See https://llvm.org/LICENSE.txt for license information.
+ * SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+ *
+ *==------------------------------------------------------------------------==*/
+/*
+ * Copyright 2001-2004 Unicode, Inc.
+ *
+ * Disclaimer
+ *
+ * This source code is provided as is by Unicode, Inc. No claims are
+ * made as to fitness for any particular purpose. No warranties of any
+ * kind are expressed or implied. The recipient agrees to determine
+ * applicability of information provided. If this file has been
+ * purchased on magnetic or optical media from Unicode, Inc., the
+ * sole remedy for any claim will be exchange of defective media
+ * within 90 days of receipt.
+ *
+ * Limitations on Rights to Redistribute This Code
+ *
+ * Unicode, Inc. hereby grants the right to freely use the information
+ * supplied in this file in the creation of products supporting the
+ * Unicode Standard, and to make copies of this file in any form
+ * for internal or external distribution as long as this notice
+ * remains attached.
+ */
+
+/* ---------------------------------------------------------------------
+
+    Conversions between UTF32, UTF-16, and UTF-8.  Header file.
+
+    Several funtions are included here, forming a complete set of
+    conversions between the three formats.  UTF-7 is not included
+    here, but is handled in a separate source file.
+
+    Each of these routines takes pointers to input buffers and output
+    buffers.  The input buffers are const.
+
+    Each routine converts the text between *sourceStart and sourceEnd,
+    putting the result into the buffer between *targetStart and
+    targetEnd. Note: the end pointers are *after* the last item: e.g.
+    *(sourceEnd - 1) is the last item.
+
+    The return result indicates whether the conversion was successful,
+    and if not, whether the problem was in the source or target buffers.
+    (Only the first encountered problem is indicated.)
+
+    After the conversion, *sourceStart and *targetStart are both
+    updated to point to the end of last text successfully converted in
+    the respective buffers.
+
+    Input parameters:
+        sourceStart - pointer to a pointer to the source buffer.
+                The contents of this are modified on return so that
+                it points at the next thing to be converted.
+        targetStart - similarly, pointer to pointer to the target buffer.
+        sourceEnd, targetEnd - respectively pointers to the ends of the
+                two buffers, for overflow checking only.
+
+    These conversion functions take a ConversionFlags argument. When this
+    flag is set to strict, both irregular sequences and isolated surrogates
+    will cause an error.  When the flag is set to lenient, both irregular
+    sequences and isolated surrogates are converted.
+
+    Whether the flag is strict or lenient, all illegal sequences will cause
+    an error return. This includes sequences such as: <F4 90 80 80>, <C0 80>,
+    or <A0> in UTF-8, and values above 0x10FFFF in UTF-32. Conformant code
+    must check for illegal sequences.
+
+    When the flag is set to lenient, characters over 0x10FFFF are converted
+    to the replacement character; otherwise (when the flag is set to strict)
+    they constitute an error.
+
+    Output parameters:
+        The value "sourceIllegal" is returned from some routines if the input
+        sequence is malformed.  When "sourceIllegal" is returned, the source
+        value will point to the illegal value that caused the problem. E.g.,
+        in UTF-8 when a sequence is malformed, it points to the start of the
+        malformed sequence.
+
+    Author: Mark E. Davis, 1994.
+    Rev History: Rick McGowan, fixes & updates May 2001.
+         Fixes & updates, Sept 2001.
+
+------------------------------------------------------------------------ */
+
+#ifndef WPIUTIL_WPI_CONVERTUTF_H
+#define WPIUTIL_WPI_CONVERTUTF_H
+
+#include <span>
+
+#include <cstddef>
+#include <string>
+#include <string_view>
+#include <system_error>
+
+// Wrap everything in namespace wpi so that programs can link with llvm and
+// their own version of the unicode libraries.
+
+namespace wpi {
+
+/* ---------------------------------------------------------------------
+    The following 4 definitions are compiler-specific.
+    The C standard does not guarantee that wchar_t has at least
+    16 bits, so wchar_t is no less portable than unsigned short!
+    All should be unsigned values to avoid sign extension during
+    bit mask & shift operations.
+------------------------------------------------------------------------ */
+
+typedef unsigned int    UTF32;  /* at least 32 bits */
+typedef unsigned short  UTF16;  /* at least 16 bits */
+typedef unsigned char   UTF8;   /* typically 8 bits */
+typedef bool   Boolean; /* 0 or 1 */
+
+/* Some fundamental constants */
+#define UNI_REPLACEMENT_CHAR (UTF32)0x0000FFFD
+#define UNI_MAX_BMP (UTF32)0x0000FFFF
+#define UNI_MAX_UTF16 (UTF32)0x0010FFFF
+#define UNI_MAX_UTF32 (UTF32)0x7FFFFFFF
+#define UNI_MAX_LEGAL_UTF32 (UTF32)0x0010FFFF
+
+#define UNI_MAX_UTF8_BYTES_PER_CODE_POINT 4
+
+#define UNI_UTF16_BYTE_ORDER_MARK_NATIVE  0xFEFF
+#define UNI_UTF16_BYTE_ORDER_MARK_SWAPPED 0xFFFE
+
+typedef enum {
+  conversionOK,           /* conversion successful */
+  sourceExhausted,        /* partial character in source, but hit end */
+  targetExhausted,        /* insuff. room in target for conversion */
+  sourceIllegal           /* source sequence is illegal/malformed */
+} ConversionResult;
+
+typedef enum {
+  strictConversion = 0,
+  lenientConversion
+} ConversionFlags;
+
+ConversionResult ConvertUTF8toUTF16 (
+  const UTF8** sourceStart, const UTF8* sourceEnd,
+  UTF16** targetStart, UTF16* targetEnd, ConversionFlags flags);
+
+/**
+ * Convert a partial UTF8 sequence to UTF32.  If the sequence ends in an
+ * incomplete code unit sequence, returns \c sourceExhausted.
+ */
+ConversionResult ConvertUTF8toUTF32Partial(
+  const UTF8** sourceStart, const UTF8* sourceEnd,
+  UTF32** targetStart, UTF32* targetEnd, ConversionFlags flags);
+
+/**
+ * Convert a partial UTF8 sequence to UTF32.  If the sequence ends in an
+ * incomplete code unit sequence, returns \c sourceIllegal.
+ */
+ConversionResult ConvertUTF8toUTF32(
+  const UTF8** sourceStart, const UTF8* sourceEnd,
+  UTF32** targetStart, UTF32* targetEnd, ConversionFlags flags);
+
+ConversionResult ConvertUTF16toUTF8 (
+  const UTF16** sourceStart, const UTF16* sourceEnd,
+  UTF8** targetStart, UTF8* targetEnd, ConversionFlags flags);
+
+ConversionResult ConvertUTF32toUTF8 (
+  const UTF32** sourceStart, const UTF32* sourceEnd,
+  UTF8** targetStart, UTF8* targetEnd, ConversionFlags flags);
+
+ConversionResult ConvertUTF16toUTF32 (
+  const UTF16** sourceStart, const UTF16* sourceEnd,
+  UTF32** targetStart, UTF32* targetEnd, ConversionFlags flags);
+
+ConversionResult ConvertUTF32toUTF16 (
+  const UTF32** sourceStart, const UTF32* sourceEnd,
+  UTF16** targetStart, UTF16* targetEnd, ConversionFlags flags);
+
+Boolean isLegalUTF8Sequence(const UTF8 *source, const UTF8 *sourceEnd);
+
+Boolean isLegalUTF8String(const UTF8 **source, const UTF8 *sourceEnd);
+
+unsigned getNumBytesForUTF8(UTF8 firstByte);
+
+/*************************************************************************/
+/* Below are LLVM-specific wrappers of the functions above. */
+
+template <typename T> class SmallVectorImpl;
+
+/**
+ * Convert an UTF8 string_view to UTF8, UTF16, or UTF32 depending on
+ * WideCharWidth. The converted data is written to ResultPtr, which needs to
+ * point to at least WideCharWidth * (Source.Size() + 1) bytes. On success,
+ * ResultPtr will point one after the end of the copied string. On failure,
+ * ResultPtr will not be changed, and ErrorPtr will be set to the location of
+ * the first character which could not be converted.
+ * \return true on success.
+ */
+bool ConvertUTF8toWide(unsigned WideCharWidth, std::string_view Source,
+                       char *&ResultPtr, const UTF8 *&ErrorPtr);
+
+/**
+* Converts a UTF-8 string_view to a std::wstring.
+* \return true on success.
+*/
+bool ConvertUTF8toWide(std::string_view Source, std::wstring &Result);
+
+/**
+* Converts a UTF-8 C-string to a std::wstring.
+* \return true on success.
+*/
+bool ConvertUTF8toWide(const char *Source, std::wstring &Result);
+
+/**
+* Converts a std::wstring to a UTF-8 encoded std::string.
+* \return true on success.
+*/
+bool convertWideToUTF8(const std::wstring &Source, SmallVectorImpl<char> &Result);
+
+
+/**
+ * Convert an Unicode code point to UTF8 sequence.
+ *
+ * \param Source a Unicode code point.
+ * \param [in,out] ResultPtr pointer to the output buffer, needs to be at least
+ * \c UNI_MAX_UTF8_BYTES_PER_CODE_POINT bytes.  On success \c ResultPtr is
+ * updated one past end of the converted sequence.
+ *
+ * \returns true on success.
+ */
+bool ConvertCodePointToUTF8(unsigned Source, char *&ResultPtr);
+
+/**
+ * Convert the first UTF8 sequence in the given source buffer to a UTF32
+ * code point.
+ *
+ * \param [in,out] source A pointer to the source buffer. If the conversion
+ * succeeds, this pointer will be updated to point to the byte just past the
+ * end of the converted sequence.
+ * \param sourceEnd A pointer just past the end of the source buffer.
+ * \param [out] target The converted code
+ * \param flags Whether the conversion is strict or lenient.
+ *
+ * \returns conversionOK on success
+ *
+ * \sa ConvertUTF8toUTF32
+ */
+inline ConversionResult convertUTF8Sequence(const UTF8 **source,
+                                            const UTF8 *sourceEnd,
+                                            UTF32 *target,
+                                            ConversionFlags flags) {
+  if (*source == sourceEnd)
+    return sourceExhausted;
+  unsigned size = getNumBytesForUTF8(**source);
+  if ((ptrdiff_t)size > sourceEnd - *source)
+    return sourceExhausted;
+  return ConvertUTF8toUTF32(source, *source + size, &target, target + 1, flags);
+}
+
+/**
+ * Returns true if a blob of text starts with a UTF-16 big or little endian byte
+ * order mark.
+ */
+bool hasUTF16ByteOrderMark(std::span<const char> SrcBytes);
+
+/**
+ * Converts a stream of raw bytes assumed to be UTF16 into a UTF8 std::string.
+ *
+ * \param [in] SrcBytes A buffer of what is assumed to be UTF-16 encoded text.
+ * \param [out] Out Converted UTF-8 is stored here on success.
+ * \returns true on success
+ */
+bool convertUTF16ToUTF8String(std::span<const char> SrcBytes, SmallVectorImpl<char> &Out);
+
+/**
+* Converts a UTF16 string into a UTF8 std::string.
+*
+* \param [in] Src A buffer of UTF-16 encoded text.
+* \param [out] Out Converted UTF-8 is stored here on success.
+* \returns true on success
+*/
+bool convertUTF16ToUTF8String(std::span<const UTF16> Src, SmallVectorImpl<char> &Out);
+
+/**
+ * Converts a UTF-8 string into a UTF-16 string with native endianness.
+ *
+ * \returns true on success
+ */
+bool convertUTF8ToUTF16String(std::string_view SrcUTF8,
+                              SmallVectorImpl<UTF16> &DstUTF16);
+
+#if defined(_WIN32)
+namespace sys {
+namespace windows {
+std::error_code UTF8ToUTF16(std::string_view utf8, SmallVectorImpl<wchar_t> &utf16);
+/// Convert to UTF16 from the current code page used in the system
+std::error_code CurCPToUTF16(std::string_view utf8, SmallVectorImpl<wchar_t> &utf16);
+std::error_code UTF16ToUTF8(const wchar_t *utf16, size_t utf16_len,
+                            SmallVectorImpl<char> &utf8);
+/// Convert from UTF16 to the current code page used in the system
+std::error_code UTF16ToCurCP(const wchar_t *utf16, size_t utf16_len,
+                             SmallVectorImpl<char> &utf8);
+} // namespace windows
+} // namespace sys
+#endif
+
+} /* end namespace wpi */
+
+#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/DJB.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/DJB.h
new file mode 100644
index 0000000..2615bba
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/DJB.h
@@ -0,0 +1,29 @@
+//===-- llvm/Support/DJB.h ---DJB Hash --------------------------*- C++ -*-===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+//
+// This file contains support for the DJ Bernstein hash function.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_DJB_H
+#define WPIUTIL_WPI_DJB_H
+
+#include <string_view>
+
+namespace wpi {
+
+/// The Bernstein hash function used by the DWARF accelerator tables.
+inline uint32_t djbHash(std::string_view Buffer, uint32_t H = 5381) {
+  for (unsigned char C : Buffer)
+    H = (H << 5) + H + C;
+  return H;
+}
+
+} // namespace wpi
+
+#endif // WPIUTIL_WPI_DJB_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/DenseMap.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/DenseMap.h
new file mode 100644
index 0000000..b1ffd43
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/DenseMap.h
@@ -0,0 +1,1309 @@
+//===- llvm/ADT/DenseMap.h - Dense probed hash table ------------*- C++ -*-===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+///
+/// \file
+/// This file defines the DenseMap class.
+///
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_DENSEMAP_H
+#define WPIUTIL_WPI_DENSEMAP_H
+
+#include "wpi/DenseMapInfo.h"
+#include "wpi/EpochTracker.h"
+#include "wpi/AlignOf.h"
+#include "wpi/Compiler.h"
+#include "wpi/MathExtras.h"
+#include "wpi/MemAlloc.h"
+#include "wpi/ReverseIteration.h"
+#include "wpi/type_traits.h"
+#include <algorithm>
+#include <cassert>
+#include <cstddef>
+#include <cstring>
+#include <initializer_list>
+#include <iterator>
+#include <new>
+#include <type_traits>
+#include <utility>
+
+namespace wpi {
+
+namespace detail {
+
+// We extend a pair to allow users to override the bucket type with their own
+// implementation without requiring two members.
+template <typename KeyT, typename ValueT>
+struct DenseMapPair : public std::pair<KeyT, ValueT> {
+  using std::pair<KeyT, ValueT>::pair;
+
+  KeyT &getFirst() { return std::pair<KeyT, ValueT>::first; }
+  const KeyT &getFirst() const { return std::pair<KeyT, ValueT>::first; }
+  ValueT &getSecond() { return std::pair<KeyT, ValueT>::second; }
+  const ValueT &getSecond() const { return std::pair<KeyT, ValueT>::second; }
+};
+
+} // end namespace detail
+
+template <typename KeyT, typename ValueT,
+          typename KeyInfoT = DenseMapInfo<KeyT>,
+          typename Bucket = wpi::detail::DenseMapPair<KeyT, ValueT>,
+          bool IsConst = false>
+class DenseMapIterator;
+
+template <typename DerivedT, typename KeyT, typename ValueT, typename KeyInfoT,
+          typename BucketT>
+class DenseMapBase : public DebugEpochBase {
+  template <typename T>
+  using const_arg_type_t = typename const_pointer_or_const_ref<T>::type;
+
+public:
+  using size_type = unsigned;
+  using key_type = KeyT;
+  using mapped_type = ValueT;
+  using value_type = BucketT;
+
+  using iterator = DenseMapIterator<KeyT, ValueT, KeyInfoT, BucketT>;
+  using const_iterator =
+      DenseMapIterator<KeyT, ValueT, KeyInfoT, BucketT, true>;
+
+  inline iterator begin() {
+    // When the map is empty, avoid the overhead of advancing/retreating past
+    // empty buckets.
+    if (empty())
+      return end();
+    if (shouldReverseIterate<KeyT>())
+      return makeIterator(getBucketsEnd() - 1, getBuckets(), *this);
+    return makeIterator(getBuckets(), getBucketsEnd(), *this);
+  }
+  inline iterator end() {
+    return makeIterator(getBucketsEnd(), getBucketsEnd(), *this, true);
+  }
+  inline const_iterator begin() const {
+    if (empty())
+      return end();
+    if (shouldReverseIterate<KeyT>())
+      return makeConstIterator(getBucketsEnd() - 1, getBuckets(), *this);
+    return makeConstIterator(getBuckets(), getBucketsEnd(), *this);
+  }
+  inline const_iterator end() const {
+    return makeConstIterator(getBucketsEnd(), getBucketsEnd(), *this, true);
+  }
+
+  LLVM_NODISCARD bool empty() const {
+    return getNumEntries() == 0;
+  }
+  unsigned size() const { return getNumEntries(); }
+
+  /// Grow the densemap so that it can contain at least \p NumEntries items
+  /// before resizing again.
+  void reserve(size_type NumEntries) {
+    auto NumBuckets = getMinBucketToReserveForEntries(NumEntries);
+    incrementEpoch();
+    if (NumBuckets > getNumBuckets())
+      grow(NumBuckets);
+  }
+
+  void clear() {
+    incrementEpoch();
+    if (getNumEntries() == 0 && getNumTombstones() == 0) return;
+
+    // If the capacity of the array is huge, and the # elements used is small,
+    // shrink the array.
+    if (getNumEntries() * 4 < getNumBuckets() && getNumBuckets() > 64) {
+      shrink_and_clear();
+      return;
+    }
+
+    const KeyT EmptyKey = getEmptyKey(), TombstoneKey = getTombstoneKey();
+    if (std::is_trivially_destructible<ValueT>::value) {
+      // Use a simpler loop when values don't need destruction.
+      for (BucketT *P = getBuckets(), *E = getBucketsEnd(); P != E; ++P)
+        P->getFirst() = EmptyKey;
+    } else {
+      unsigned NumEntries = getNumEntries();
+      for (BucketT *P = getBuckets(), *E = getBucketsEnd(); P != E; ++P) {
+        if (!KeyInfoT::isEqual(P->getFirst(), EmptyKey)) {
+          if (!KeyInfoT::isEqual(P->getFirst(), TombstoneKey)) {
+            P->getSecond().~ValueT();
+            --NumEntries;
+          }
+          P->getFirst() = EmptyKey;
+        }
+      }
+      assert(NumEntries == 0 && "Node count imbalance!");
+    }
+    setNumEntries(0);
+    setNumTombstones(0);
+  }
+
+  /// Return 1 if the specified key is in the map, 0 otherwise.
+  size_type count(const_arg_type_t<KeyT> Val) const {
+    const BucketT *TheBucket;
+    return LookupBucketFor(Val, TheBucket) ? 1 : 0;
+  }
+
+  iterator find(const_arg_type_t<KeyT> Val) {
+    BucketT *TheBucket;
+    if (LookupBucketFor(Val, TheBucket))
+      return makeIterator(TheBucket,
+                          shouldReverseIterate<KeyT>() ? getBuckets()
+                                                       : getBucketsEnd(),
+                          *this, true);
+    return end();
+  }
+  const_iterator find(const_arg_type_t<KeyT> Val) const {
+    const BucketT *TheBucket;
+    if (LookupBucketFor(Val, TheBucket))
+      return makeConstIterator(TheBucket,
+                               shouldReverseIterate<KeyT>() ? getBuckets()
+                                                            : getBucketsEnd(),
+                               *this, true);
+    return end();
+  }
+
+  /// Alternate version of find() which allows a different, and possibly
+  /// less expensive, key type.
+  /// The DenseMapInfo is responsible for supplying methods
+  /// getHashValue(LookupKeyT) and isEqual(LookupKeyT, KeyT) for each key
+  /// type used.
+  template<class LookupKeyT>
+  iterator find_as(const LookupKeyT &Val) {
+    BucketT *TheBucket;
+    if (LookupBucketFor(Val, TheBucket))
+      return makeIterator(TheBucket,
+                          shouldReverseIterate<KeyT>() ? getBuckets()
+                                                       : getBucketsEnd(),
+                          *this, true);
+    return end();
+  }
+  template<class LookupKeyT>
+  const_iterator find_as(const LookupKeyT &Val) const {
+    const BucketT *TheBucket;
+    if (LookupBucketFor(Val, TheBucket))
+      return makeConstIterator(TheBucket,
+                               shouldReverseIterate<KeyT>() ? getBuckets()
+                                                            : getBucketsEnd(),
+                               *this, true);
+    return end();
+  }
+
+  /// lookup - Return the entry for the specified key, or a default
+  /// constructed value if no such entry exists.
+  ValueT lookup(const_arg_type_t<KeyT> Val) const {
+    const BucketT *TheBucket;
+    if (LookupBucketFor(Val, TheBucket))
+      return TheBucket->getSecond();
+    return ValueT();
+  }
+
+  // Inserts key,value pair into the map if the key isn't already in the map.
+  // If the key is already in the map, it returns false and doesn't update the
+  // value.
+  std::pair<iterator, bool> insert(const std::pair<KeyT, ValueT> &KV) {
+    return try_emplace(KV.first, KV.second);
+  }
+
+  // Inserts key,value pair into the map if the key isn't already in the map.
+  // If the key is already in the map, it returns false and doesn't update the
+  // value.
+  std::pair<iterator, bool> insert(std::pair<KeyT, ValueT> &&KV) {
+    return try_emplace(std::move(KV.first), std::move(KV.second));
+  }
+
+  // Inserts key,value pair into the map if the key isn't already in the map.
+  // The value is constructed in-place if the key is not in the map, otherwise
+  // it is not moved.
+  template <typename... Ts>
+  std::pair<iterator, bool> try_emplace(KeyT &&Key, Ts &&... Args) {
+    BucketT *TheBucket;
+    if (LookupBucketFor(Key, TheBucket))
+      return std::make_pair(makeIterator(TheBucket,
+                                         shouldReverseIterate<KeyT>()
+                                             ? getBuckets()
+                                             : getBucketsEnd(),
+                                         *this, true),
+                            false); // Already in map.
+
+    // Otherwise, insert the new element.
+    TheBucket =
+        InsertIntoBucket(TheBucket, std::move(Key), std::forward<Ts>(Args)...);
+    return std::make_pair(makeIterator(TheBucket,
+                                       shouldReverseIterate<KeyT>()
+                                           ? getBuckets()
+                                           : getBucketsEnd(),
+                                       *this, true),
+                          true);
+  }
+
+  // Inserts key,value pair into the map if the key isn't already in the map.
+  // The value is constructed in-place if the key is not in the map, otherwise
+  // it is not moved.
+  template <typename... Ts>
+  std::pair<iterator, bool> try_emplace(const KeyT &Key, Ts &&... Args) {
+    BucketT *TheBucket;
+    if (LookupBucketFor(Key, TheBucket))
+      return std::make_pair(makeIterator(TheBucket,
+                                         shouldReverseIterate<KeyT>()
+                                             ? getBuckets()
+                                             : getBucketsEnd(),
+                                         *this, true),
+                            false); // Already in map.
+
+    // Otherwise, insert the new element.
+    TheBucket = InsertIntoBucket(TheBucket, Key, std::forward<Ts>(Args)...);
+    return std::make_pair(makeIterator(TheBucket,
+                                       shouldReverseIterate<KeyT>()
+                                           ? getBuckets()
+                                           : getBucketsEnd(),
+                                       *this, true),
+                          true);
+  }
+
+  /// Alternate version of insert() which allows a different, and possibly
+  /// less expensive, key type.
+  /// The DenseMapInfo is responsible for supplying methods
+  /// getHashValue(LookupKeyT) and isEqual(LookupKeyT, KeyT) for each key
+  /// type used.
+  template <typename LookupKeyT>
+  std::pair<iterator, bool> insert_as(std::pair<KeyT, ValueT> &&KV,
+                                      const LookupKeyT &Val) {
+    BucketT *TheBucket;
+    if (LookupBucketFor(Val, TheBucket))
+      return std::make_pair(makeIterator(TheBucket,
+                                         shouldReverseIterate<KeyT>()
+                                             ? getBuckets()
+                                             : getBucketsEnd(),
+                                         *this, true),
+                            false); // Already in map.
+
+    // Otherwise, insert the new element.
+    TheBucket = InsertIntoBucketWithLookup(TheBucket, std::move(KV.first),
+                                           std::move(KV.second), Val);
+    return std::make_pair(makeIterator(TheBucket,
+                                       shouldReverseIterate<KeyT>()
+                                           ? getBuckets()
+                                           : getBucketsEnd(),
+                                       *this, true),
+                          true);
+  }
+
+  /// insert - Range insertion of pairs.
+  template<typename InputIt>
+  void insert(InputIt I, InputIt E) {
+    for (; I != E; ++I)
+      insert(*I);
+  }
+
+  bool erase(const KeyT &Val) {
+    BucketT *TheBucket;
+    if (!LookupBucketFor(Val, TheBucket))
+      return false; // not in map.
+
+    TheBucket->getSecond().~ValueT();
+    TheBucket->getFirst() = getTombstoneKey();
+    decrementNumEntries();
+    incrementNumTombstones();
+    return true;
+  }
+  void erase(iterator I) {
+    BucketT *TheBucket = &*I;
+    TheBucket->getSecond().~ValueT();
+    TheBucket->getFirst() = getTombstoneKey();
+    decrementNumEntries();
+    incrementNumTombstones();
+  }
+
+  value_type& FindAndConstruct(const KeyT &Key) {
+    BucketT *TheBucket;
+    if (LookupBucketFor(Key, TheBucket))
+      return *TheBucket;
+
+    return *InsertIntoBucket(TheBucket, Key);
+  }
+
+  ValueT &operator[](const KeyT &Key) {
+    return FindAndConstruct(Key).second;
+  }
+
+  value_type& FindAndConstruct(KeyT &&Key) {
+    BucketT *TheBucket;
+    if (LookupBucketFor(Key, TheBucket))
+      return *TheBucket;
+
+    return *InsertIntoBucket(TheBucket, std::move(Key));
+  }
+
+  ValueT &operator[](KeyT &&Key) {
+    return FindAndConstruct(std::move(Key)).second;
+  }
+
+  /// isPointerIntoBucketsArray - Return true if the specified pointer points
+  /// somewhere into the DenseMap's array of buckets (i.e. either to a key or
+  /// value in the DenseMap).
+  bool isPointerIntoBucketsArray(const void *Ptr) const {
+    return Ptr >= getBuckets() && Ptr < getBucketsEnd();
+  }
+
+  /// getPointerIntoBucketsArray() - Return an opaque pointer into the buckets
+  /// array.  In conjunction with the previous method, this can be used to
+  /// determine whether an insertion caused the DenseMap to reallocate.
+  const void *getPointerIntoBucketsArray() const { return getBuckets(); }
+
+protected:
+  DenseMapBase() = default;
+
+  void destroyAll() {
+    if (getNumBuckets() == 0) // Nothing to do.
+      return;
+
+    const KeyT EmptyKey = getEmptyKey(), TombstoneKey = getTombstoneKey();
+    for (BucketT *P = getBuckets(), *E = getBucketsEnd(); P != E; ++P) {
+      if (!KeyInfoT::isEqual(P->getFirst(), EmptyKey) &&
+          !KeyInfoT::isEqual(P->getFirst(), TombstoneKey))
+        P->getSecond().~ValueT();
+      P->getFirst().~KeyT();
+    }
+  }
+
+  void initEmpty() {
+    setNumEntries(0);
+    setNumTombstones(0);
+
+    assert((getNumBuckets() & (getNumBuckets()-1)) == 0 &&
+           "# initial buckets must be a power of two!");
+    const KeyT EmptyKey = getEmptyKey();
+    for (BucketT *B = getBuckets(), *E = getBucketsEnd(); B != E; ++B)
+      ::new (&B->getFirst()) KeyT(EmptyKey);
+  }
+
+  /// Returns the number of buckets to allocate to ensure that the DenseMap can
+  /// accommodate \p NumEntries without need to grow().
+  unsigned getMinBucketToReserveForEntries(unsigned NumEntries) {
+    // Ensure that "NumEntries * 4 < NumBuckets * 3"
+    if (NumEntries == 0)
+      return 0;
+    // +1 is required because of the strict equality.
+    // For example if NumEntries is 48, we need to return 401.
+    return static_cast<unsigned>(NextPowerOf2(NumEntries * 4 / 3 + 1));
+  }
+
+  void moveFromOldBuckets(BucketT *OldBucketsBegin, BucketT *OldBucketsEnd) {
+    initEmpty();
+
+    // Insert all the old elements.
+    const KeyT EmptyKey = getEmptyKey();
+    const KeyT TombstoneKey = getTombstoneKey();
+    for (BucketT *B = OldBucketsBegin, *E = OldBucketsEnd; B != E; ++B) {
+      if (!KeyInfoT::isEqual(B->getFirst(), EmptyKey) &&
+          !KeyInfoT::isEqual(B->getFirst(), TombstoneKey)) {
+        // Insert the key/value into the new table.
+        BucketT *DestBucket;
+        bool FoundVal = LookupBucketFor(B->getFirst(), DestBucket);
+        (void)FoundVal; // silence warning.
+        assert(!FoundVal && "Key already in new map?");
+        DestBucket->getFirst() = std::move(B->getFirst());
+        ::new (&DestBucket->getSecond()) ValueT(std::move(B->getSecond()));
+        incrementNumEntries();
+
+        // Free the value.
+        B->getSecond().~ValueT();
+      }
+      B->getFirst().~KeyT();
+    }
+  }
+
+  template <typename OtherBaseT>
+  void copyFrom(
+      const DenseMapBase<OtherBaseT, KeyT, ValueT, KeyInfoT, BucketT> &other) {
+    assert(&other != this);
+    assert(getNumBuckets() == other.getNumBuckets());
+
+    setNumEntries(other.getNumEntries());
+    setNumTombstones(other.getNumTombstones());
+
+    if (std::is_trivially_copyable<KeyT>::value &&
+        std::is_trivially_copyable<ValueT>::value)
+      memcpy(reinterpret_cast<void *>(getBuckets()), other.getBuckets(),
+             getNumBuckets() * sizeof(BucketT));
+    else
+      for (size_t i = 0; i < getNumBuckets(); ++i) {
+        ::new (&getBuckets()[i].getFirst())
+            KeyT(other.getBuckets()[i].getFirst());
+        if (!KeyInfoT::isEqual(getBuckets()[i].getFirst(), getEmptyKey()) &&
+            !KeyInfoT::isEqual(getBuckets()[i].getFirst(), getTombstoneKey()))
+          ::new (&getBuckets()[i].getSecond())
+              ValueT(other.getBuckets()[i].getSecond());
+      }
+  }
+
+  static unsigned getHashValue(const KeyT &Val) {
+    return KeyInfoT::getHashValue(Val);
+  }
+
+  template<typename LookupKeyT>
+  static unsigned getHashValue(const LookupKeyT &Val) {
+    return KeyInfoT::getHashValue(Val);
+  }
+
+  static const KeyT getEmptyKey() {
+    static_assert(std::is_base_of<DenseMapBase, DerivedT>::value,
+                  "Must pass the derived type to this template!");
+    return KeyInfoT::getEmptyKey();
+  }
+
+  static const KeyT getTombstoneKey() {
+    return KeyInfoT::getTombstoneKey();
+  }
+
+private:
+  iterator makeIterator(BucketT *P, BucketT *E,
+                        DebugEpochBase &Epoch,
+                        bool NoAdvance=false) {
+    if (shouldReverseIterate<KeyT>()) {
+      BucketT *B = P == getBucketsEnd() ? getBuckets() : P + 1;
+      return iterator(B, E, Epoch, NoAdvance);
+    }
+    return iterator(P, E, Epoch, NoAdvance);
+  }
+
+  const_iterator makeConstIterator(const BucketT *P, const BucketT *E,
+                                   const DebugEpochBase &Epoch,
+                                   const bool NoAdvance=false) const {
+    if (shouldReverseIterate<KeyT>()) {
+      const BucketT *B = P == getBucketsEnd() ? getBuckets() : P + 1;
+      return const_iterator(B, E, Epoch, NoAdvance);
+    }
+    return const_iterator(P, E, Epoch, NoAdvance);
+  }
+
+  unsigned getNumEntries() const {
+    return static_cast<const DerivedT *>(this)->getNumEntries();
+  }
+
+  void setNumEntries(unsigned Num) {
+    static_cast<DerivedT *>(this)->setNumEntries(Num);
+  }
+
+  void incrementNumEntries() {
+    setNumEntries(getNumEntries() + 1);
+  }
+
+  void decrementNumEntries() {
+    setNumEntries(getNumEntries() - 1);
+  }
+
+  unsigned getNumTombstones() const {
+    return static_cast<const DerivedT *>(this)->getNumTombstones();
+  }
+
+  void setNumTombstones(unsigned Num) {
+    static_cast<DerivedT *>(this)->setNumTombstones(Num);
+  }
+
+  void incrementNumTombstones() {
+    setNumTombstones(getNumTombstones() + 1);
+  }
+
+  void decrementNumTombstones() {
+    setNumTombstones(getNumTombstones() - 1);
+  }
+
+  const BucketT *getBuckets() const {
+    return static_cast<const DerivedT *>(this)->getBuckets();
+  }
+
+  BucketT *getBuckets() {
+    return static_cast<DerivedT *>(this)->getBuckets();
+  }
+
+  unsigned getNumBuckets() const {
+    return static_cast<const DerivedT *>(this)->getNumBuckets();
+  }
+
+  BucketT *getBucketsEnd() {
+    return getBuckets() + getNumBuckets();
+  }
+
+  const BucketT *getBucketsEnd() const {
+    return getBuckets() + getNumBuckets();
+  }
+
+  void grow(unsigned AtLeast) {
+    static_cast<DerivedT *>(this)->grow(AtLeast);
+  }
+
+  void shrink_and_clear() {
+    static_cast<DerivedT *>(this)->shrink_and_clear();
+  }
+
+  template <typename KeyArg, typename... ValueArgs>
+  BucketT *InsertIntoBucket(BucketT *TheBucket, KeyArg &&Key,
+                            ValueArgs &&... Values) {
+    TheBucket = InsertIntoBucketImpl(Key, Key, TheBucket);
+
+    TheBucket->getFirst() = std::forward<KeyArg>(Key);
+    ::new (&TheBucket->getSecond()) ValueT(std::forward<ValueArgs>(Values)...);
+    return TheBucket;
+  }
+
+  template <typename LookupKeyT>
+  BucketT *InsertIntoBucketWithLookup(BucketT *TheBucket, KeyT &&Key,
+                                      ValueT &&Value, LookupKeyT &Lookup) {
+    TheBucket = InsertIntoBucketImpl(Key, Lookup, TheBucket);
+
+    TheBucket->getFirst() = std::move(Key);
+    ::new (&TheBucket->getSecond()) ValueT(std::move(Value));
+    return TheBucket;
+  }
+
+  template <typename LookupKeyT>
+  BucketT *InsertIntoBucketImpl(const KeyT &Key, const LookupKeyT &Lookup,
+                                BucketT *TheBucket) {
+    incrementEpoch();
+
+    // If the load of the hash table is more than 3/4, or if fewer than 1/8 of
+    // the buckets are empty (meaning that many are filled with tombstones),
+    // grow the table.
+    //
+    // The later case is tricky.  For example, if we had one empty bucket with
+    // tons of tombstones, failing lookups (e.g. for insertion) would have to
+    // probe almost the entire table until it found the empty bucket.  If the
+    // table completely filled with tombstones, no lookup would ever succeed,
+    // causing infinite loops in lookup.
+    unsigned NewNumEntries = getNumEntries() + 1;
+    unsigned NumBuckets = getNumBuckets();
+    if (LLVM_UNLIKELY(NewNumEntries * 4 >= NumBuckets * 3)) {
+      this->grow(NumBuckets * 2);
+      LookupBucketFor(Lookup, TheBucket);
+      NumBuckets = getNumBuckets();
+    } else if (LLVM_UNLIKELY(NumBuckets-(NewNumEntries+getNumTombstones()) <=
+                             NumBuckets/8)) {
+      this->grow(NumBuckets);
+      LookupBucketFor(Lookup, TheBucket);
+    }
+    assert(TheBucket);
+
+    // Only update the state after we've grown our bucket space appropriately
+    // so that when growing buckets we have self-consistent entry count.
+    incrementNumEntries();
+
+    // If we are writing over a tombstone, remember this.
+    const KeyT EmptyKey = getEmptyKey();
+    if (!KeyInfoT::isEqual(TheBucket->getFirst(), EmptyKey))
+      decrementNumTombstones();
+
+    return TheBucket;
+  }
+
+  /// LookupBucketFor - Lookup the appropriate bucket for Val, returning it in
+  /// FoundBucket.  If the bucket contains the key and a value, this returns
+  /// true, otherwise it returns a bucket with an empty marker or tombstone and
+  /// returns false.
+  template<typename LookupKeyT>
+  bool LookupBucketFor(const LookupKeyT &Val,
+                       const BucketT *&FoundBucket) const {
+    const BucketT *BucketsPtr = getBuckets();
+    const unsigned NumBuckets = getNumBuckets();
+
+    if (NumBuckets == 0) {
+      FoundBucket = nullptr;
+      return false;
+    }
+
+    // FoundTombstone - Keep track of whether we find a tombstone while probing.
+    const BucketT *FoundTombstone = nullptr;
+    const KeyT EmptyKey = getEmptyKey();
+    const KeyT TombstoneKey = getTombstoneKey();
+    assert(!KeyInfoT::isEqual(Val, EmptyKey) &&
+           !KeyInfoT::isEqual(Val, TombstoneKey) &&
+           "Empty/Tombstone value shouldn't be inserted into map!");
+
+    unsigned BucketNo = getHashValue(Val) & (NumBuckets-1);
+    unsigned ProbeAmt = 1;
+    while (true) {
+      const BucketT *ThisBucket = BucketsPtr + BucketNo;
+      // Found Val's bucket?  If so, return it.
+      if (LLVM_LIKELY(KeyInfoT::isEqual(Val, ThisBucket->getFirst()))) {
+        FoundBucket = ThisBucket;
+        return true;
+      }
+
+      // If we found an empty bucket, the key doesn't exist in the set.
+      // Insert it and return the default value.
+      if (LLVM_LIKELY(KeyInfoT::isEqual(ThisBucket->getFirst(), EmptyKey))) {
+        // If we've already seen a tombstone while probing, fill it in instead
+        // of the empty bucket we eventually probed to.
+        FoundBucket = FoundTombstone ? FoundTombstone : ThisBucket;
+        return false;
+      }
+
+      // If this is a tombstone, remember it.  If Val ends up not in the map, we
+      // prefer to return it than something that would require more probing.
+      if (KeyInfoT::isEqual(ThisBucket->getFirst(), TombstoneKey) &&
+          !FoundTombstone)
+        FoundTombstone = ThisBucket;  // Remember the first tombstone found.
+
+      // Otherwise, it's a hash collision or a tombstone, continue quadratic
+      // probing.
+      BucketNo += ProbeAmt++;
+      BucketNo &= (NumBuckets-1);
+    }
+  }
+
+  template <typename LookupKeyT>
+  bool LookupBucketFor(const LookupKeyT &Val, BucketT *&FoundBucket) {
+    const BucketT *ConstFoundBucket;
+    bool Result = const_cast<const DenseMapBase *>(this)
+      ->LookupBucketFor(Val, ConstFoundBucket);
+    FoundBucket = const_cast<BucketT *>(ConstFoundBucket);
+    return Result;
+  }
+
+public:
+  /// Return the approximate size (in bytes) of the actual map.
+  /// This is just the raw memory used by DenseMap.
+  /// If entries are pointers to objects, the size of the referenced objects
+  /// are not included.
+  size_t getMemorySize() const {
+    return getNumBuckets() * sizeof(BucketT);
+  }
+};
+
+/// Equality comparison for DenseMap.
+///
+/// Iterates over elements of LHS confirming that each (key, value) pair in LHS
+/// is also in RHS, and that no additional pairs are in RHS.
+/// Equivalent to N calls to RHS.find and N value comparisons. Amortized
+/// complexity is linear, worst case is O(N^2) (if every hash collides).
+template <typename DerivedT, typename KeyT, typename ValueT, typename KeyInfoT,
+          typename BucketT>
+bool operator==(
+    const DenseMapBase<DerivedT, KeyT, ValueT, KeyInfoT, BucketT> &LHS,
+    const DenseMapBase<DerivedT, KeyT, ValueT, KeyInfoT, BucketT> &RHS) {
+  if (LHS.size() != RHS.size())
+    return false;
+
+  for (auto &KV : LHS) {
+    auto I = RHS.find(KV.first);
+    if (I == RHS.end() || I->second != KV.second)
+      return false;
+  }
+
+  return true;
+}
+
+/// Inequality comparison for DenseMap.
+///
+/// Equivalent to !(LHS == RHS). See operator== for performance notes.
+template <typename DerivedT, typename KeyT, typename ValueT, typename KeyInfoT,
+          typename BucketT>
+bool operator!=(
+    const DenseMapBase<DerivedT, KeyT, ValueT, KeyInfoT, BucketT> &LHS,
+    const DenseMapBase<DerivedT, KeyT, ValueT, KeyInfoT, BucketT> &RHS) {
+  return !(LHS == RHS);
+}
+
+template <typename KeyT, typename ValueT,
+          typename KeyInfoT = DenseMapInfo<KeyT>,
+          typename BucketT = wpi::detail::DenseMapPair<KeyT, ValueT>>
+class DenseMap : public DenseMapBase<DenseMap<KeyT, ValueT, KeyInfoT, BucketT>,
+                                     KeyT, ValueT, KeyInfoT, BucketT> {
+  friend class DenseMapBase<DenseMap, KeyT, ValueT, KeyInfoT, BucketT>;
+
+  // Lift some types from the dependent base class into this class for
+  // simplicity of referring to them.
+  using BaseT = DenseMapBase<DenseMap, KeyT, ValueT, KeyInfoT, BucketT>;
+
+  BucketT *Buckets;
+  unsigned NumEntries;
+  unsigned NumTombstones;
+  unsigned NumBuckets;
+
+public:
+  /// Create a DenseMap with an optional \p InitialReserve that guarantee that
+  /// this number of elements can be inserted in the map without grow()
+  explicit DenseMap(unsigned InitialReserve = 0) { init(InitialReserve); }
+
+  DenseMap(const DenseMap &other) : BaseT() {
+    init(0);
+    copyFrom(other);
+  }
+
+  DenseMap(DenseMap &&other) : BaseT() {
+    init(0);
+    swap(other);
+  }
+
+  template<typename InputIt>
+  DenseMap(const InputIt &I, const InputIt &E) {
+    init(std::distance(I, E));
+    this->insert(I, E);
+  }
+
+  DenseMap(std::initializer_list<typename BaseT::value_type> Vals) {
+    init(Vals.size());
+    this->insert(Vals.begin(), Vals.end());
+  }
+
+  ~DenseMap() {
+    this->destroyAll();
+    deallocate_buffer(Buckets, sizeof(BucketT) * NumBuckets, alignof(BucketT));
+  }
+
+  void swap(DenseMap& RHS) {
+    this->incrementEpoch();
+    RHS.incrementEpoch();
+    std::swap(Buckets, RHS.Buckets);
+    std::swap(NumEntries, RHS.NumEntries);
+    std::swap(NumTombstones, RHS.NumTombstones);
+    std::swap(NumBuckets, RHS.NumBuckets);
+  }
+
+  DenseMap& operator=(const DenseMap& other) {
+    if (&other != this)
+      copyFrom(other);
+    return *this;
+  }
+
+  DenseMap& operator=(DenseMap &&other) {
+    this->destroyAll();
+    deallocate_buffer(Buckets, sizeof(BucketT) * NumBuckets, alignof(BucketT));
+    init(0);
+    swap(other);
+    return *this;
+  }
+
+  void copyFrom(const DenseMap& other) {
+    this->destroyAll();
+    deallocate_buffer(Buckets, sizeof(BucketT) * NumBuckets, alignof(BucketT));
+    if (allocateBuckets(other.NumBuckets)) {
+      this->BaseT::copyFrom(other);
+    } else {
+      NumEntries = 0;
+      NumTombstones = 0;
+    }
+  }
+
+  void init(unsigned InitNumEntries) {
+    auto InitBuckets = BaseT::getMinBucketToReserveForEntries(InitNumEntries);
+    if (allocateBuckets(InitBuckets)) {
+      this->BaseT::initEmpty();
+    } else {
+      NumEntries = 0;
+      NumTombstones = 0;
+    }
+  }
+
+  void grow(unsigned AtLeast) {
+    unsigned OldNumBuckets = NumBuckets;
+    BucketT *OldBuckets = Buckets;
+
+    allocateBuckets(std::max<unsigned>(64, static_cast<unsigned>(NextPowerOf2(AtLeast-1))));
+    assert(Buckets);
+    if (!OldBuckets) {
+      this->BaseT::initEmpty();
+      return;
+    }
+
+    this->moveFromOldBuckets(OldBuckets, OldBuckets+OldNumBuckets);
+
+    // Free the old table.
+    deallocate_buffer(OldBuckets, sizeof(BucketT) * OldNumBuckets,
+                      alignof(BucketT));
+  }
+
+  void shrink_and_clear() {
+    unsigned OldNumBuckets = NumBuckets;
+    unsigned OldNumEntries = NumEntries;
+    this->destroyAll();
+
+    // Reduce the number of buckets.
+    unsigned NewNumBuckets = 0;
+    if (OldNumEntries)
+      NewNumBuckets = (std::max)(64, 1 << (Log2_32_Ceil(OldNumEntries) + 1));
+    if (NewNumBuckets == NumBuckets) {
+      this->BaseT::initEmpty();
+      return;
+    }
+
+    deallocate_buffer(Buckets, sizeof(BucketT) * OldNumBuckets,
+                      alignof(BucketT));
+    init(NewNumBuckets);
+  }
+
+private:
+  unsigned getNumEntries() const {
+    return NumEntries;
+  }
+
+  void setNumEntries(unsigned Num) {
+    NumEntries = Num;
+  }
+
+  unsigned getNumTombstones() const {
+    return NumTombstones;
+  }
+
+  void setNumTombstones(unsigned Num) {
+    NumTombstones = Num;
+  }
+
+  BucketT *getBuckets() const {
+    return Buckets;
+  }
+
+  unsigned getNumBuckets() const {
+    return NumBuckets;
+  }
+
+  bool allocateBuckets(unsigned Num) {
+    NumBuckets = Num;
+    if (NumBuckets == 0) {
+      Buckets = nullptr;
+      return false;
+    }
+
+    Buckets = static_cast<BucketT *>(
+        allocate_buffer(sizeof(BucketT) * NumBuckets, alignof(BucketT)));
+    return true;
+  }
+};
+
+template <typename KeyT, typename ValueT, unsigned InlineBuckets = 4,
+          typename KeyInfoT = DenseMapInfo<KeyT>,
+          typename BucketT = wpi::detail::DenseMapPair<KeyT, ValueT>>
+class SmallDenseMap
+    : public DenseMapBase<
+          SmallDenseMap<KeyT, ValueT, InlineBuckets, KeyInfoT, BucketT>, KeyT,
+          ValueT, KeyInfoT, BucketT> {
+  friend class DenseMapBase<SmallDenseMap, KeyT, ValueT, KeyInfoT, BucketT>;
+
+  // Lift some types from the dependent base class into this class for
+  // simplicity of referring to them.
+  using BaseT = DenseMapBase<SmallDenseMap, KeyT, ValueT, KeyInfoT, BucketT>;
+
+  static_assert(isPowerOf2_64(InlineBuckets),
+                "InlineBuckets must be a power of 2.");
+
+  unsigned Small : 1;
+  unsigned NumEntries : 31;
+  unsigned NumTombstones;
+
+  struct LargeRep {
+    BucketT *Buckets;
+    unsigned NumBuckets;
+  };
+
+  /// A "union" of an inline bucket array and the struct representing
+  /// a large bucket. This union will be discriminated by the 'Small' bit.
+  AlignedCharArrayUnion<BucketT[InlineBuckets], LargeRep> storage;
+
+public:
+  explicit SmallDenseMap(unsigned NumInitBuckets = 0) {
+    init(NumInitBuckets);
+  }
+
+  SmallDenseMap(const SmallDenseMap &other) : BaseT() {
+    init(0);
+    copyFrom(other);
+  }
+
+  SmallDenseMap(SmallDenseMap &&other) : BaseT() {
+    init(0);
+    swap(other);
+  }
+
+  template<typename InputIt>
+  SmallDenseMap(const InputIt &I, const InputIt &E) {
+    init(NextPowerOf2(std::distance(I, E)));
+    this->insert(I, E);
+  }
+
+  SmallDenseMap(std::initializer_list<typename BaseT::value_type> Vals)
+      : SmallDenseMap(Vals.begin(), Vals.end()) {}
+
+  ~SmallDenseMap() {
+    this->destroyAll();
+    deallocateBuckets();
+  }
+
+  void swap(SmallDenseMap& RHS) {
+    unsigned TmpNumEntries = RHS.NumEntries;
+    RHS.NumEntries = NumEntries;
+    NumEntries = TmpNumEntries;
+    std::swap(NumTombstones, RHS.NumTombstones);
+
+    const KeyT EmptyKey = this->getEmptyKey();
+    const KeyT TombstoneKey = this->getTombstoneKey();
+    if (Small && RHS.Small) {
+      // If we're swapping inline bucket arrays, we have to cope with some of
+      // the tricky bits of DenseMap's storage system: the buckets are not
+      // fully initialized. Thus we swap every key, but we may have
+      // a one-directional move of the value.
+      for (unsigned i = 0, e = InlineBuckets; i != e; ++i) {
+        BucketT *LHSB = &getInlineBuckets()[i],
+                *RHSB = &RHS.getInlineBuckets()[i];
+        bool hasLHSValue = (!KeyInfoT::isEqual(LHSB->getFirst(), EmptyKey) &&
+                            !KeyInfoT::isEqual(LHSB->getFirst(), TombstoneKey));
+        bool hasRHSValue = (!KeyInfoT::isEqual(RHSB->getFirst(), EmptyKey) &&
+                            !KeyInfoT::isEqual(RHSB->getFirst(), TombstoneKey));
+        if (hasLHSValue && hasRHSValue) {
+          // Swap together if we can...
+          std::swap(*LHSB, *RHSB);
+          continue;
+        }
+        // Swap separately and handle any asymmetry.
+        std::swap(LHSB->getFirst(), RHSB->getFirst());
+        if (hasLHSValue) {
+          ::new (&RHSB->getSecond()) ValueT(std::move(LHSB->getSecond()));
+          LHSB->getSecond().~ValueT();
+        } else if (hasRHSValue) {
+          ::new (&LHSB->getSecond()) ValueT(std::move(RHSB->getSecond()));
+          RHSB->getSecond().~ValueT();
+        }
+      }
+      return;
+    }
+    if (!Small && !RHS.Small) {
+      std::swap(getLargeRep()->Buckets, RHS.getLargeRep()->Buckets);
+      std::swap(getLargeRep()->NumBuckets, RHS.getLargeRep()->NumBuckets);
+      return;
+    }
+
+    SmallDenseMap &SmallSide = Small ? *this : RHS;
+    SmallDenseMap &LargeSide = Small ? RHS : *this;
+
+    // First stash the large side's rep and move the small side across.
+    LargeRep TmpRep = std::move(*LargeSide.getLargeRep());
+    LargeSide.getLargeRep()->~LargeRep();
+    LargeSide.Small = true;
+    // This is similar to the standard move-from-old-buckets, but the bucket
+    // count hasn't actually rotated in this case. So we have to carefully
+    // move construct the keys and values into their new locations, but there
+    // is no need to re-hash things.
+    for (unsigned i = 0, e = InlineBuckets; i != e; ++i) {
+      BucketT *NewB = &LargeSide.getInlineBuckets()[i],
+              *OldB = &SmallSide.getInlineBuckets()[i];
+      ::new (&NewB->getFirst()) KeyT(std::move(OldB->getFirst()));
+      OldB->getFirst().~KeyT();
+      if (!KeyInfoT::isEqual(NewB->getFirst(), EmptyKey) &&
+          !KeyInfoT::isEqual(NewB->getFirst(), TombstoneKey)) {
+        ::new (&NewB->getSecond()) ValueT(std::move(OldB->getSecond()));
+        OldB->getSecond().~ValueT();
+      }
+    }
+
+    // The hard part of moving the small buckets across is done, just move
+    // the TmpRep into its new home.
+    SmallSide.Small = false;
+    new (SmallSide.getLargeRep()) LargeRep(std::move(TmpRep));
+  }
+
+  SmallDenseMap& operator=(const SmallDenseMap& other) {
+    if (&other != this)
+      copyFrom(other);
+    return *this;
+  }
+
+  SmallDenseMap& operator=(SmallDenseMap &&other) {
+    this->destroyAll();
+    deallocateBuckets();
+    init(0);
+    swap(other);
+    return *this;
+  }
+
+  void copyFrom(const SmallDenseMap& other) {
+    this->destroyAll();
+    deallocateBuckets();
+    Small = true;
+    if (other.getNumBuckets() > InlineBuckets) {
+      Small = false;
+      new (getLargeRep()) LargeRep(allocateBuckets(other.getNumBuckets()));
+    }
+    this->BaseT::copyFrom(other);
+  }
+
+  void init(unsigned InitBuckets) {
+    Small = true;
+    if (InitBuckets > InlineBuckets) {
+      Small = false;
+      new (getLargeRep()) LargeRep(allocateBuckets(InitBuckets));
+    }
+    this->BaseT::initEmpty();
+  }
+
+  void grow(unsigned AtLeast) {
+    if (AtLeast > InlineBuckets)
+      AtLeast = std::max<unsigned>(64, NextPowerOf2(AtLeast-1));
+
+    if (Small) {
+      // First move the inline buckets into a temporary storage.
+      AlignedCharArrayUnion<BucketT[InlineBuckets]> TmpStorage;
+      BucketT *TmpBegin = reinterpret_cast<BucketT *>(&TmpStorage);
+      BucketT *TmpEnd = TmpBegin;
+
+      // Loop over the buckets, moving non-empty, non-tombstones into the
+      // temporary storage. Have the loop move the TmpEnd forward as it goes.
+      const KeyT EmptyKey = this->getEmptyKey();
+      const KeyT TombstoneKey = this->getTombstoneKey();
+      for (BucketT *P = getBuckets(), *E = P + InlineBuckets; P != E; ++P) {
+        if (!KeyInfoT::isEqual(P->getFirst(), EmptyKey) &&
+            !KeyInfoT::isEqual(P->getFirst(), TombstoneKey)) {
+          assert(size_t(TmpEnd - TmpBegin) < InlineBuckets &&
+                 "Too many inline buckets!");
+          ::new (&TmpEnd->getFirst()) KeyT(std::move(P->getFirst()));
+          ::new (&TmpEnd->getSecond()) ValueT(std::move(P->getSecond()));
+          ++TmpEnd;
+          P->getSecond().~ValueT();
+        }
+        P->getFirst().~KeyT();
+      }
+
+      // AtLeast == InlineBuckets can happen if there are many tombstones,
+      // and grow() is used to remove them. Usually we always switch to the
+      // large rep here.
+      if (AtLeast > InlineBuckets) {
+        Small = false;
+        new (getLargeRep()) LargeRep(allocateBuckets(AtLeast));
+      }
+      this->moveFromOldBuckets(TmpBegin, TmpEnd);
+      return;
+    }
+
+    LargeRep OldRep = std::move(*getLargeRep());
+    getLargeRep()->~LargeRep();
+    if (AtLeast <= InlineBuckets) {
+      Small = true;
+    } else {
+      new (getLargeRep()) LargeRep(allocateBuckets(AtLeast));
+    }
+
+    this->moveFromOldBuckets(OldRep.Buckets, OldRep.Buckets+OldRep.NumBuckets);
+
+    // Free the old table.
+    deallocate_buffer(OldRep.Buckets, sizeof(BucketT) * OldRep.NumBuckets,
+                      alignof(BucketT));
+  }
+
+  void shrink_and_clear() {
+    unsigned OldSize = this->size();
+    this->destroyAll();
+
+    // Reduce the number of buckets.
+    unsigned NewNumBuckets = 0;
+    if (OldSize) {
+      NewNumBuckets = 1 << (Log2_32_Ceil(OldSize) + 1);
+      if (NewNumBuckets > InlineBuckets && NewNumBuckets < 64u)
+        NewNumBuckets = 64;
+    }
+    if ((Small && NewNumBuckets <= InlineBuckets) ||
+        (!Small && NewNumBuckets == getLargeRep()->NumBuckets)) {
+      this->BaseT::initEmpty();
+      return;
+    }
+
+    deallocateBuckets();
+    init(NewNumBuckets);
+  }
+
+private:
+  unsigned getNumEntries() const {
+    return NumEntries;
+  }
+
+  void setNumEntries(unsigned Num) {
+    // NumEntries is hardcoded to be 31 bits wide.
+    assert(Num < (1U << 31) && "Cannot support more than 1<<31 entries");
+    NumEntries = Num;
+  }
+
+  unsigned getNumTombstones() const {
+    return NumTombstones;
+  }
+
+  void setNumTombstones(unsigned Num) {
+    NumTombstones = Num;
+  }
+
+  const BucketT *getInlineBuckets() const {
+    assert(Small);
+    // Note that this cast does not violate aliasing rules as we assert that
+    // the memory's dynamic type is the small, inline bucket buffer, and the
+    // 'storage' is a POD containing a char buffer.
+    return reinterpret_cast<const BucketT *>(&storage);
+  }
+
+  BucketT *getInlineBuckets() {
+    return const_cast<BucketT *>(
+      const_cast<const SmallDenseMap *>(this)->getInlineBuckets());
+  }
+
+  const LargeRep *getLargeRep() const {
+    assert(!Small);
+    // Note, same rule about aliasing as with getInlineBuckets.
+    return reinterpret_cast<const LargeRep *>(&storage);
+  }
+
+  LargeRep *getLargeRep() {
+    return const_cast<LargeRep *>(
+      const_cast<const SmallDenseMap *>(this)->getLargeRep());
+  }
+
+  const BucketT *getBuckets() const {
+    return Small ? getInlineBuckets() : getLargeRep()->Buckets;
+  }
+
+  BucketT *getBuckets() {
+    return const_cast<BucketT *>(
+      const_cast<const SmallDenseMap *>(this)->getBuckets());
+  }
+
+  unsigned getNumBuckets() const {
+    return Small ? InlineBuckets : getLargeRep()->NumBuckets;
+  }
+
+  void deallocateBuckets() {
+    if (Small)
+      return;
+
+    deallocate_buffer(getLargeRep()->Buckets,
+                      sizeof(BucketT) * getLargeRep()->NumBuckets,
+                      alignof(BucketT));
+    getLargeRep()->~LargeRep();
+  }
+
+  LargeRep allocateBuckets(unsigned Num) {
+    assert(Num > InlineBuckets && "Must allocate more buckets than are inline");
+    LargeRep Rep = {static_cast<BucketT *>(allocate_buffer(
+                        sizeof(BucketT) * Num, alignof(BucketT))),
+                    Num};
+    return Rep;
+  }
+};
+
+template <typename KeyT, typename ValueT, typename KeyInfoT, typename Bucket,
+          bool IsConst>
+class DenseMapIterator : DebugEpochBase::HandleBase {
+  friend class DenseMapIterator<KeyT, ValueT, KeyInfoT, Bucket, true>;
+  friend class DenseMapIterator<KeyT, ValueT, KeyInfoT, Bucket, false>;
+
+public:
+  using difference_type = ptrdiff_t;
+  using value_type =
+      typename std::conditional<IsConst, const Bucket, Bucket>::type;
+  using pointer = value_type *;
+  using reference = value_type &;
+  using iterator_category = std::forward_iterator_tag;
+
+private:
+  pointer Ptr = nullptr;
+  pointer End = nullptr;
+
+public:
+  DenseMapIterator() = default;
+
+  DenseMapIterator(pointer Pos, pointer E, const DebugEpochBase &Epoch,
+                   bool NoAdvance = false)
+      : DebugEpochBase::HandleBase(&Epoch), Ptr(Pos), End(E) {
+    assert(isHandleInSync() && "invalid construction!");
+
+    if (NoAdvance) return;
+    if (shouldReverseIterate<KeyT>()) {
+      RetreatPastEmptyBuckets();
+      return;
+    }
+    AdvancePastEmptyBuckets();
+  }
+
+  // Converting ctor from non-const iterators to const iterators. SFINAE'd out
+  // for const iterator destinations so it doesn't end up as a user defined copy
+  // constructor.
+  template <bool IsConstSrc,
+            typename = std::enable_if_t<!IsConstSrc && IsConst>>
+  DenseMapIterator(
+      const DenseMapIterator<KeyT, ValueT, KeyInfoT, Bucket, IsConstSrc> &I)
+      : DebugEpochBase::HandleBase(I), Ptr(I.Ptr), End(I.End) {}
+
+  reference operator*() const {
+    assert(isHandleInSync() && "invalid iterator access!");
+    assert(Ptr != End && "dereferencing end() iterator");
+    if (shouldReverseIterate<KeyT>())
+      return Ptr[-1];
+    return *Ptr;
+  }
+  pointer operator->() const {
+    assert(isHandleInSync() && "invalid iterator access!");
+    assert(Ptr != End && "dereferencing end() iterator");
+    if (shouldReverseIterate<KeyT>())
+      return &(Ptr[-1]);
+    return Ptr;
+  }
+
+  friend bool operator==(const DenseMapIterator &LHS,
+                         const DenseMapIterator &RHS) {
+    assert((!LHS.Ptr || LHS.isHandleInSync()) && "handle not in sync!");
+    assert((!RHS.Ptr || RHS.isHandleInSync()) && "handle not in sync!");
+    assert(LHS.getEpochAddress() == RHS.getEpochAddress() &&
+           "comparing incomparable iterators!");
+    return LHS.Ptr == RHS.Ptr;
+  }
+
+  friend bool operator!=(const DenseMapIterator &LHS,
+                         const DenseMapIterator &RHS) {
+    return !(LHS == RHS);
+  }
+
+  inline DenseMapIterator& operator++() {  // Preincrement
+    assert(isHandleInSync() && "invalid iterator access!");
+    assert(Ptr != End && "incrementing end() iterator");
+    if (shouldReverseIterate<KeyT>()) {
+      --Ptr;
+      RetreatPastEmptyBuckets();
+      return *this;
+    }
+    ++Ptr;
+    AdvancePastEmptyBuckets();
+    return *this;
+  }
+  DenseMapIterator operator++(int) {  // Postincrement
+    assert(isHandleInSync() && "invalid iterator access!");
+    DenseMapIterator tmp = *this; ++*this; return tmp;
+  }
+
+private:
+  void AdvancePastEmptyBuckets() {
+    assert(Ptr <= End);
+    const KeyT Empty = KeyInfoT::getEmptyKey();
+    const KeyT Tombstone = KeyInfoT::getTombstoneKey();
+
+    while (Ptr != End && (KeyInfoT::isEqual(Ptr->getFirst(), Empty) ||
+                          KeyInfoT::isEqual(Ptr->getFirst(), Tombstone)))
+      ++Ptr;
+  }
+
+  void RetreatPastEmptyBuckets() {
+    assert(Ptr >= End);
+    const KeyT Empty = KeyInfoT::getEmptyKey();
+    const KeyT Tombstone = KeyInfoT::getTombstoneKey();
+
+    while (Ptr != End && (KeyInfoT::isEqual(Ptr[-1].getFirst(), Empty) ||
+                          KeyInfoT::isEqual(Ptr[-1].getFirst(), Tombstone)))
+      --Ptr;
+  }
+};
+
+template <typename KeyT, typename ValueT, typename KeyInfoT>
+inline size_t capacity_in_bytes(const DenseMap<KeyT, ValueT, KeyInfoT> &X) {
+  return X.getMemorySize();
+}
+
+} // end namespace wpi
+
+#endif // WPIUTIL_WPI_DENSEMAP_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/DenseMapInfo.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/DenseMapInfo.h
new file mode 100644
index 0000000..0ff8fc9
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/DenseMapInfo.h
@@ -0,0 +1,293 @@
+//===- llvm/ADT/DenseMapInfo.h - Type traits for DenseMap -------*- C++ -*-===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+///
+/// \file
+/// This file defines DenseMapInfo traits for DenseMap.
+///
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_DENSEMAPINFO_H
+#define WPIUTIL_WPI_DENSEMAPINFO_H
+
+#include <cassert>
+#include <cstddef>
+#include <cstdint>
+#include <tuple>
+#include <utility>
+
+namespace wpi {
+
+namespace detail {
+
+/// Simplistic combination of 32-bit hash values into 32-bit hash values.
+static inline unsigned combineHashValue(unsigned a, unsigned b) {
+  uint64_t key = (uint64_t)a << 32 | (uint64_t)b;
+  key += ~(key << 32);
+  key ^= (key >> 22);
+  key += ~(key << 13);
+  key ^= (key >> 8);
+  key += (key << 3);
+  key ^= (key >> 15);
+  key += ~(key << 27);
+  key ^= (key >> 31);
+  return (unsigned)key;
+}
+
+} // end namespace detail
+
+/// An information struct used to provide DenseMap with the various necessary
+/// components for a given value type `T`. `Enable` is an optional additional
+/// parameter that is used to support SFINAE (generally using std::enable_if_t)
+/// in derived DenseMapInfo specializations; in non-SFINAE use cases this should
+/// just be `void`.
+template<typename T, typename Enable = void>
+struct DenseMapInfo {
+  //static inline T getEmptyKey();
+  //static inline T getTombstoneKey();
+  //static unsigned getHashValue(const T &Val);
+  //static bool isEqual(const T &LHS, const T &RHS);
+};
+
+// Provide DenseMapInfo for all pointers. Come up with sentinel pointer values
+// that are aligned to alignof(T) bytes, but try to avoid requiring T to be
+// complete. This allows clients to instantiate DenseMap<T*, ...> with forward
+// declared key types. Assume that no pointer key type requires more than 4096
+// bytes of alignment.
+template<typename T>
+struct DenseMapInfo<T*> {
+  // The following should hold, but it would require T to be complete:
+  // static_assert(alignof(T) <= (1 << Log2MaxAlign),
+  //               "DenseMap does not support pointer keys requiring more than "
+  //               "Log2MaxAlign bits of alignment");
+  static constexpr uintptr_t Log2MaxAlign = 12;
+
+  static inline T* getEmptyKey() {
+    uintptr_t Val = static_cast<uintptr_t>(-1);
+    Val <<= Log2MaxAlign;
+    return reinterpret_cast<T*>(Val);
+  }
+
+  static inline T* getTombstoneKey() {
+    uintptr_t Val = static_cast<uintptr_t>(-2);
+    Val <<= Log2MaxAlign;
+    return reinterpret_cast<T*>(Val);
+  }
+
+  static unsigned getHashValue(const T *PtrVal) {
+    return (unsigned((uintptr_t)PtrVal) >> 4) ^
+           (unsigned((uintptr_t)PtrVal) >> 9);
+  }
+
+  static bool isEqual(const T *LHS, const T *RHS) { return LHS == RHS; }
+};
+
+// Provide DenseMapInfo for chars.
+template<> struct DenseMapInfo<char> {
+  static inline char getEmptyKey() { return ~0; }
+  static inline char getTombstoneKey() { return ~0 - 1; }
+  static unsigned getHashValue(const char& Val) { return Val * 37U; }
+
+  static bool isEqual(const char &LHS, const char &RHS) {
+    return LHS == RHS;
+  }
+};
+
+// Provide DenseMapInfo for unsigned chars.
+template <> struct DenseMapInfo<unsigned char> {
+  static inline unsigned char getEmptyKey() { return ~0; }
+  static inline unsigned char getTombstoneKey() { return ~0 - 1; }
+  static unsigned getHashValue(const unsigned char &Val) { return Val * 37U; }
+
+  static bool isEqual(const unsigned char &LHS, const unsigned char &RHS) {
+    return LHS == RHS;
+  }
+};
+
+// Provide DenseMapInfo for unsigned shorts.
+template <> struct DenseMapInfo<unsigned short> {
+  static inline unsigned short getEmptyKey() { return 0xFFFF; }
+  static inline unsigned short getTombstoneKey() { return 0xFFFF - 1; }
+  static unsigned getHashValue(const unsigned short &Val) { return Val * 37U; }
+
+  static bool isEqual(const unsigned short &LHS, const unsigned short &RHS) {
+    return LHS == RHS;
+  }
+};
+
+// Provide DenseMapInfo for unsigned ints.
+template<> struct DenseMapInfo<unsigned> {
+  static inline unsigned getEmptyKey() { return ~0U; }
+  static inline unsigned getTombstoneKey() { return ~0U - 1; }
+  static unsigned getHashValue(const unsigned& Val) { return Val * 37U; }
+
+  static bool isEqual(const unsigned& LHS, const unsigned& RHS) {
+    return LHS == RHS;
+  }
+};
+
+// Provide DenseMapInfo for unsigned longs.
+template<> struct DenseMapInfo<unsigned long> {
+  static inline unsigned long getEmptyKey() { return ~0UL; }
+  static inline unsigned long getTombstoneKey() { return ~0UL - 1L; }
+
+  static unsigned getHashValue(const unsigned long& Val) {
+    return (unsigned)(Val * 37UL);
+  }
+
+  static bool isEqual(const unsigned long& LHS, const unsigned long& RHS) {
+    return LHS == RHS;
+  }
+};
+
+// Provide DenseMapInfo for unsigned long longs.
+template<> struct DenseMapInfo<unsigned long long> {
+  static inline unsigned long long getEmptyKey() { return ~0ULL; }
+  static inline unsigned long long getTombstoneKey() { return ~0ULL - 1ULL; }
+
+  static unsigned getHashValue(const unsigned long long& Val) {
+    return (unsigned)(Val * 37ULL);
+  }
+
+  static bool isEqual(const unsigned long long& LHS,
+                      const unsigned long long& RHS) {
+    return LHS == RHS;
+  }
+};
+
+// Provide DenseMapInfo for shorts.
+template <> struct DenseMapInfo<short> {
+  static inline short getEmptyKey() { return 0x7FFF; }
+  static inline short getTombstoneKey() { return -0x7FFF - 1; }
+  static unsigned getHashValue(const short &Val) { return Val * 37U; }
+  static bool isEqual(const short &LHS, const short &RHS) { return LHS == RHS; }
+};
+
+// Provide DenseMapInfo for ints.
+template<> struct DenseMapInfo<int> {
+  static inline int getEmptyKey() { return 0x7fffffff; }
+  static inline int getTombstoneKey() { return -0x7fffffff - 1; }
+  static unsigned getHashValue(const int& Val) { return (unsigned)(Val * 37U); }
+
+  static bool isEqual(const int& LHS, const int& RHS) {
+    return LHS == RHS;
+  }
+};
+
+// Provide DenseMapInfo for longs.
+template<> struct DenseMapInfo<long> {
+  static inline long getEmptyKey() {
+    return (1UL << (sizeof(long) * 8 - 1)) - 1UL;
+  }
+
+  static inline long getTombstoneKey() { return getEmptyKey() - 1L; }
+
+  static unsigned getHashValue(const long& Val) {
+    return (unsigned)(Val * 37UL);
+  }
+
+  static bool isEqual(const long& LHS, const long& RHS) {
+    return LHS == RHS;
+  }
+};
+
+// Provide DenseMapInfo for long longs.
+template<> struct DenseMapInfo<long long> {
+  static inline long long getEmptyKey() { return 0x7fffffffffffffffLL; }
+  static inline long long getTombstoneKey() { return -0x7fffffffffffffffLL-1; }
+
+  static unsigned getHashValue(const long long& Val) {
+    return (unsigned)(Val * 37ULL);
+  }
+
+  static bool isEqual(const long long& LHS,
+                      const long long& RHS) {
+    return LHS == RHS;
+  }
+};
+
+// Provide DenseMapInfo for all pairs whose members have info.
+template<typename T, typename U>
+struct DenseMapInfo<std::pair<T, U>> {
+  using Pair = std::pair<T, U>;
+  using FirstInfo = DenseMapInfo<T>;
+  using SecondInfo = DenseMapInfo<U>;
+
+  static inline Pair getEmptyKey() {
+    return std::make_pair(FirstInfo::getEmptyKey(),
+                          SecondInfo::getEmptyKey());
+  }
+
+  static inline Pair getTombstoneKey() {
+    return std::make_pair(FirstInfo::getTombstoneKey(),
+                          SecondInfo::getTombstoneKey());
+  }
+
+  static unsigned getHashValue(const Pair& PairVal) {
+    return detail::combineHashValue(FirstInfo::getHashValue(PairVal.first),
+                                    SecondInfo::getHashValue(PairVal.second));
+  }
+
+  static bool isEqual(const Pair &LHS, const Pair &RHS) {
+    return FirstInfo::isEqual(LHS.first, RHS.first) &&
+           SecondInfo::isEqual(LHS.second, RHS.second);
+  }
+};
+
+// Provide DenseMapInfo for all tuples whose members have info.
+template <typename... Ts> struct DenseMapInfo<std::tuple<Ts...>> {
+  using Tuple = std::tuple<Ts...>;
+
+  static inline Tuple getEmptyKey() {
+    return Tuple(DenseMapInfo<Ts>::getEmptyKey()...);
+  }
+
+  static inline Tuple getTombstoneKey() {
+    return Tuple(DenseMapInfo<Ts>::getTombstoneKey()...);
+  }
+
+  template <unsigned I>
+  static unsigned getHashValueImpl(const Tuple &values, std::false_type) {
+    using EltType = typename std::tuple_element<I, Tuple>::type;
+    std::integral_constant<bool, I + 1 == sizeof...(Ts)> atEnd;
+    return detail::combineHashValue(
+        DenseMapInfo<EltType>::getHashValue(std::get<I>(values)),
+        getHashValueImpl<I + 1>(values, atEnd));
+  }
+
+  template <unsigned I>
+  static unsigned getHashValueImpl(const Tuple &, std::true_type) {
+    return 0;
+  }
+
+  static unsigned getHashValue(const std::tuple<Ts...> &values) {
+    std::integral_constant<bool, 0 == sizeof...(Ts)> atEnd;
+    return getHashValueImpl<0>(values, atEnd);
+  }
+
+  template <unsigned I>
+  static bool isEqualImpl(const Tuple &lhs, const Tuple &rhs, std::false_type) {
+    using EltType = typename std::tuple_element<I, Tuple>::type;
+    std::integral_constant<bool, I + 1 == sizeof...(Ts)> atEnd;
+    return DenseMapInfo<EltType>::isEqual(std::get<I>(lhs), std::get<I>(rhs)) &&
+           isEqualImpl<I + 1>(lhs, rhs, atEnd);
+  }
+
+  template <unsigned I>
+  static bool isEqualImpl(const Tuple &, const Tuple &, std::true_type) {
+    return true;
+  }
+
+  static bool isEqual(const Tuple &lhs, const Tuple &rhs) {
+    std::integral_constant<bool, 0 == sizeof...(Ts)> atEnd;
+    return isEqualImpl<0>(lhs, rhs, atEnd);
+  }
+};
+
+} // end namespace wpi
+
+#endif // WPIUTIL_WPI_DENSEMAPINFO_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/Endian.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/Endian.h
new file mode 100644
index 0000000..d243a13
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/Endian.h
@@ -0,0 +1,429 @@
+//===- Endian.h - Utilities for IO with endian specific data ----*- C++ -*-===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+//
+// This file declares generic functions to read and write endian specific data.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_ENDIAN_H
+#define WPIUTIL_WPI_ENDIAN_H
+
+#include "wpi/Compiler.h"
+#include "wpi/SwapByteOrder.h"
+#include <cassert>
+#include <cstddef>
+#include <cstdint>
+#include <cstring>
+#include <type_traits>
+
+namespace wpi {
+namespace support {
+
+enum endianness {big, little, native};
+
+// These are named values for common alignments.
+enum {aligned = 0, unaligned = 1};
+
+namespace detail {
+
+/// ::value is either alignment, or alignof(T) if alignment is 0.
+template<class T, int alignment>
+struct PickAlignment {
+ enum { value = alignment == 0 ? alignof(T) : alignment };
+};
+
+} // end namespace detail
+
+namespace endian {
+
+constexpr endianness system_endianness() {
+  return sys::IsBigEndianHost ? big : little;
+}
+
+template <typename value_type>
+inline value_type byte_swap(value_type value, endianness endian) {
+  if ((endian != native) && (endian != system_endianness()))
+    sys::swapByteOrder(value);
+  return value;
+}
+
+/// Swap the bytes of value to match the given endianness.
+template<typename value_type, endianness endian>
+inline value_type byte_swap(value_type value) {
+  if constexpr ((endian != native) && (endian != system_endianness()))
+    sys::swapByteOrder(value);
+  return value;
+}
+
+/// Read a value of a particular endianness from memory.
+template <typename value_type, std::size_t alignment>
+inline value_type read(const void *memory, endianness endian) {
+  value_type ret;
+
+  memcpy(&ret,
+         LLVM_ASSUME_ALIGNED(
+             memory, (detail::PickAlignment<value_type, alignment>::value)),
+         sizeof(value_type));
+  return byte_swap<value_type>(ret, endian);
+}
+
+template<typename value_type,
+         endianness endian,
+         std::size_t alignment>
+inline value_type read(const void *memory) {
+  return read<value_type, alignment>(memory, endian);
+}
+
+/// Read a value of a particular endianness from a buffer, and increment the
+/// buffer past that value.
+template <typename value_type, std::size_t alignment, typename CharT>
+inline value_type readNext(const CharT *&memory, endianness endian) {
+  value_type ret = read<value_type, alignment>(memory, endian);
+  memory += sizeof(value_type);
+  return ret;
+}
+
+template<typename value_type, endianness endian, std::size_t alignment,
+         typename CharT>
+inline value_type readNext(const CharT *&memory) {
+  return readNext<value_type, alignment, CharT>(memory, endian);
+}
+
+/// Write a value to memory with a particular endianness.
+template <typename value_type, std::size_t alignment>
+inline void write(void *memory, value_type value, endianness endian) {
+  value = byte_swap<value_type>(value, endian);
+  memcpy(LLVM_ASSUME_ALIGNED(
+             memory, (detail::PickAlignment<value_type, alignment>::value)),
+         &value, sizeof(value_type));
+}
+
+template<typename value_type,
+         endianness endian,
+         std::size_t alignment>
+inline void write(void *memory, value_type value) {
+  write<value_type, alignment>(memory, value, endian);
+}
+
+template <typename value_type>
+using make_unsigned_t = std::make_unsigned_t<value_type>;
+
+/// Read a value of a particular endianness from memory, for a location
+/// that starts at the given bit offset within the first byte.
+template <typename value_type, endianness endian, std::size_t alignment>
+inline value_type readAtBitAlignment(const void *memory, uint64_t startBit) {
+  assert(startBit < 8);
+  if (startBit == 0)
+    return read<value_type, endian, alignment>(memory);
+  else {
+    // Read two values and compose the result from them.
+    value_type val[2];
+    memcpy(&val[0],
+           LLVM_ASSUME_ALIGNED(
+               memory, (detail::PickAlignment<value_type, alignment>::value)),
+           sizeof(value_type) * 2);
+    val[0] = byte_swap<value_type, endian>(val[0]);
+    val[1] = byte_swap<value_type, endian>(val[1]);
+
+    // Shift bits from the lower value into place.
+    make_unsigned_t<value_type> lowerVal = val[0] >> startBit;
+    // Mask off upper bits after right shift in case of signed type.
+    make_unsigned_t<value_type> numBitsFirstVal =
+        (sizeof(value_type) * 8) - startBit;
+    lowerVal &= ((make_unsigned_t<value_type>)1 << numBitsFirstVal) - 1;
+
+    // Get the bits from the upper value.
+    make_unsigned_t<value_type> upperVal =
+        val[1] & (((make_unsigned_t<value_type>)1 << startBit) - 1);
+    // Shift them in to place.
+    upperVal <<= numBitsFirstVal;
+
+    return lowerVal | upperVal;
+  }
+}
+
+/// Write a value to memory with a particular endianness, for a location
+/// that starts at the given bit offset within the first byte.
+template <typename value_type, endianness endian, std::size_t alignment>
+inline void writeAtBitAlignment(void *memory, value_type value,
+                                uint64_t startBit) {
+  assert(startBit < 8);
+  if (startBit == 0)
+    write<value_type, endian, alignment>(memory, value);
+  else {
+    // Read two values and shift the result into them.
+    value_type val[2];
+    memcpy(&val[0],
+           LLVM_ASSUME_ALIGNED(
+               memory, (detail::PickAlignment<value_type, alignment>::value)),
+           sizeof(value_type) * 2);
+    val[0] = byte_swap<value_type, endian>(val[0]);
+    val[1] = byte_swap<value_type, endian>(val[1]);
+
+    // Mask off any existing bits in the upper part of the lower value that
+    // we want to replace.
+    val[0] &= ((make_unsigned_t<value_type>)1 << startBit) - 1;
+    make_unsigned_t<value_type> numBitsFirstVal =
+        (sizeof(value_type) * 8) - startBit;
+    make_unsigned_t<value_type> lowerVal = value;
+    if (startBit > 0) {
+      // Mask off the upper bits in the new value that are not going to go into
+      // the lower value. This avoids a left shift of a negative value, which
+      // is undefined behavior.
+      lowerVal &= (((make_unsigned_t<value_type>)1 << numBitsFirstVal) - 1);
+      // Now shift the new bits into place
+      lowerVal <<= startBit;
+    }
+    val[0] |= lowerVal;
+
+    // Mask off any existing bits in the lower part of the upper value that
+    // we want to replace.
+    val[1] &= ~(((make_unsigned_t<value_type>)1 << startBit) - 1);
+    // Next shift the bits that go into the upper value into position.
+    make_unsigned_t<value_type> upperVal = value >> numBitsFirstVal;
+    // Mask off upper bits after right shift in case of signed type.
+    upperVal &= ((make_unsigned_t<value_type>)1 << startBit) - 1;
+    val[1] |= upperVal;
+
+    // Finally, rewrite values.
+    val[0] = byte_swap<value_type, endian>(val[0]);
+    val[1] = byte_swap<value_type, endian>(val[1]);
+    memcpy(LLVM_ASSUME_ALIGNED(
+               memory, (detail::PickAlignment<value_type, alignment>::value)),
+           &val[0], sizeof(value_type) * 2);
+  }
+}
+
+} // end namespace endian
+
+namespace detail {
+
+template <typename ValueType, endianness Endian, std::size_t Alignment,
+          std::size_t ALIGN = PickAlignment<ValueType, Alignment>::value>
+struct packed_endian_specific_integral {
+  using value_type = ValueType;
+  static constexpr endianness endian = Endian;
+  static constexpr std::size_t alignment = Alignment;
+
+  packed_endian_specific_integral() = default;
+
+  explicit packed_endian_specific_integral(value_type val) { *this = val; }
+
+  operator value_type() const {
+    return endian::read<value_type, endian, alignment>(
+      (const void*)Value.buffer);
+  }
+
+  void operator=(value_type newValue) {
+    endian::write<value_type, endian, alignment>(
+      (void*)Value.buffer, newValue);
+  }
+
+  packed_endian_specific_integral &operator+=(value_type newValue) {
+    *this = *this + newValue;
+    return *this;
+  }
+
+  packed_endian_specific_integral &operator-=(value_type newValue) {
+    *this = *this - newValue;
+    return *this;
+  }
+
+  packed_endian_specific_integral &operator|=(value_type newValue) {
+    *this = *this | newValue;
+    return *this;
+  }
+
+  packed_endian_specific_integral &operator&=(value_type newValue) {
+    *this = *this & newValue;
+    return *this;
+  }
+
+private:
+  struct {
+    alignas(ALIGN) char buffer[sizeof(value_type)];
+  } Value;
+
+public:
+  struct ref {
+    explicit ref(void *Ptr) : Ptr(Ptr) {}
+
+    operator value_type() const {
+      return endian::read<value_type, endian, alignment>(Ptr);
+    }
+
+    void operator=(value_type NewValue) {
+      endian::write<value_type, endian, alignment>(Ptr, NewValue);
+    }
+
+  private:
+    void *Ptr;
+  };
+};
+
+} // end namespace detail
+
+using ulittle16_t =
+    detail::packed_endian_specific_integral<uint16_t, little, unaligned>;
+using ulittle32_t =
+    detail::packed_endian_specific_integral<uint32_t, little, unaligned>;
+using ulittle64_t =
+    detail::packed_endian_specific_integral<uint64_t, little, unaligned>;
+
+using little16_t =
+    detail::packed_endian_specific_integral<int16_t, little, unaligned>;
+using little32_t =
+    detail::packed_endian_specific_integral<int32_t, little, unaligned>;
+using little64_t =
+    detail::packed_endian_specific_integral<int64_t, little, unaligned>;
+
+using aligned_ulittle16_t =
+    detail::packed_endian_specific_integral<uint16_t, little, aligned>;
+using aligned_ulittle32_t =
+    detail::packed_endian_specific_integral<uint32_t, little, aligned>;
+using aligned_ulittle64_t =
+    detail::packed_endian_specific_integral<uint64_t, little, aligned>;
+
+using aligned_little16_t =
+    detail::packed_endian_specific_integral<int16_t, little, aligned>;
+using aligned_little32_t =
+    detail::packed_endian_specific_integral<int32_t, little, aligned>;
+using aligned_little64_t =
+    detail::packed_endian_specific_integral<int64_t, little, aligned>;
+
+using ubig16_t =
+    detail::packed_endian_specific_integral<uint16_t, big, unaligned>;
+using ubig32_t =
+    detail::packed_endian_specific_integral<uint32_t, big, unaligned>;
+using ubig64_t =
+    detail::packed_endian_specific_integral<uint64_t, big, unaligned>;
+
+using big16_t =
+    detail::packed_endian_specific_integral<int16_t, big, unaligned>;
+using big32_t =
+    detail::packed_endian_specific_integral<int32_t, big, unaligned>;
+using big64_t =
+    detail::packed_endian_specific_integral<int64_t, big, unaligned>;
+
+using aligned_ubig16_t =
+    detail::packed_endian_specific_integral<uint16_t, big, aligned>;
+using aligned_ubig32_t =
+    detail::packed_endian_specific_integral<uint32_t, big, aligned>;
+using aligned_ubig64_t =
+    detail::packed_endian_specific_integral<uint64_t, big, aligned>;
+
+using aligned_big16_t =
+    detail::packed_endian_specific_integral<int16_t, big, aligned>;
+using aligned_big32_t =
+    detail::packed_endian_specific_integral<int32_t, big, aligned>;
+using aligned_big64_t =
+    detail::packed_endian_specific_integral<int64_t, big, aligned>;
+
+using unaligned_uint16_t =
+    detail::packed_endian_specific_integral<uint16_t, native, unaligned>;
+using unaligned_uint32_t =
+    detail::packed_endian_specific_integral<uint32_t, native, unaligned>;
+using unaligned_uint64_t =
+    detail::packed_endian_specific_integral<uint64_t, native, unaligned>;
+
+using unaligned_int16_t =
+    detail::packed_endian_specific_integral<int16_t, native, unaligned>;
+using unaligned_int32_t =
+    detail::packed_endian_specific_integral<int32_t, native, unaligned>;
+using unaligned_int64_t =
+    detail::packed_endian_specific_integral<int64_t, native, unaligned>;
+
+template <typename T>
+using little_t = detail::packed_endian_specific_integral<T, little, unaligned>;
+template <typename T>
+using big_t = detail::packed_endian_specific_integral<T, big, unaligned>;
+
+template <typename T>
+using aligned_little_t =
+    detail::packed_endian_specific_integral<T, little, aligned>;
+template <typename T>
+using aligned_big_t = detail::packed_endian_specific_integral<T, big, aligned>;
+
+namespace endian {
+
+template <typename T> inline T read(const void *P, endianness E) {
+  return read<T, unaligned>(P, E);
+}
+
+template <typename T, endianness E> inline T read(const void *P) {
+  return *(const detail::packed_endian_specific_integral<T, E, unaligned> *)P;
+}
+
+inline uint16_t read16(const void *P, endianness E) {
+  return read<uint16_t>(P, E);
+}
+inline uint32_t read32(const void *P, endianness E) {
+  return read<uint32_t>(P, E);
+}
+inline uint64_t read64(const void *P, endianness E) {
+  return read<uint64_t>(P, E);
+}
+
+template <endianness E> inline uint16_t read16(const void *P) {
+  return read<uint16_t, E>(P);
+}
+template <endianness E> inline uint32_t read32(const void *P) {
+  return read<uint32_t, E>(P);
+}
+template <endianness E> inline uint64_t read64(const void *P) {
+  return read<uint64_t, E>(P);
+}
+
+inline uint16_t read16le(const void *P) { return read16<little>(P); }
+inline uint32_t read32le(const void *P) { return read32<little>(P); }
+inline uint64_t read64le(const void *P) { return read64<little>(P); }
+inline uint16_t read16be(const void *P) { return read16<big>(P); }
+inline uint32_t read32be(const void *P) { return read32<big>(P); }
+inline uint64_t read64be(const void *P) { return read64<big>(P); }
+
+template <typename T> inline void write(void *P, T V, endianness E) {
+  write<T, unaligned>(P, V, E);
+}
+
+template <typename T, endianness E> inline void write(void *P, T V) {
+  *(detail::packed_endian_specific_integral<T, E, unaligned> *)P = V;
+}
+
+inline void write16(void *P, uint16_t V, endianness E) {
+  write<uint16_t>(P, V, E);
+}
+inline void write32(void *P, uint32_t V, endianness E) {
+  write<uint32_t>(P, V, E);
+}
+inline void write64(void *P, uint64_t V, endianness E) {
+  write<uint64_t>(P, V, E);
+}
+
+template <endianness E> inline void write16(void *P, uint16_t V) {
+  write<uint16_t, E>(P, V);
+}
+template <endianness E> inline void write32(void *P, uint32_t V) {
+  write<uint32_t, E>(P, V);
+}
+template <endianness E> inline void write64(void *P, uint64_t V) {
+  write<uint64_t, E>(P, V);
+}
+
+inline void write16le(void *P, uint16_t V) { write16<little>(P, V); }
+inline void write32le(void *P, uint32_t V) { write32<little>(P, V); }
+inline void write64le(void *P, uint64_t V) { write64<little>(P, V); }
+inline void write16be(void *P, uint16_t V) { write16<big>(P, V); }
+inline void write32be(void *P, uint32_t V) { write32<big>(P, V); }
+inline void write64be(void *P, uint64_t V) { write64<big>(P, V); }
+
+} // end namespace endian
+
+} // end namespace support
+} // end namespace wpi
+
+#endif // WPIUTIL_WPI_ENDIAN_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/EpochTracker.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/EpochTracker.h
new file mode 100644
index 0000000..6417c05
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/EpochTracker.h
@@ -0,0 +1,98 @@
+//===- llvm/ADT/EpochTracker.h - ADT epoch tracking --------------*- C++ -*-==//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+///
+/// \file
+/// This file defines the DebugEpochBase and DebugEpochBase::HandleBase classes.
+/// These can be used to write iterators that are fail-fast when LLVM is built
+/// with asserts enabled.
+///
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_EPOCHTRACKER_H
+#define WPIUTIL_WPI_EPOCHTRACKER_H
+
+
+#include <cstdint>
+
+namespace wpi {
+
+#ifndef NDEBUG //ifndef LLVM_ENABLE_ABI_BREAKING_CHECKS
+
+/// A base class for data structure classes wishing to make iterators
+/// ("handles") pointing into themselves fail-fast.  When building without
+/// asserts, this class is empty and does nothing.
+///
+/// DebugEpochBase does not by itself track handles pointing into itself.  The
+/// expectation is that routines touching the handles will poll on
+/// isHandleInSync at appropriate points to assert that the handle they're using
+/// is still valid.
+///
+class DebugEpochBase {
+  uint64_t Epoch;
+
+public:
+  DebugEpochBase() : Epoch(0) {}
+
+  /// Calling incrementEpoch invalidates all handles pointing into the
+  /// calling instance.
+  void incrementEpoch() { ++Epoch; }
+
+  /// The destructor calls incrementEpoch to make use-after-free bugs
+  /// more likely to crash deterministically.
+  ~DebugEpochBase() { incrementEpoch(); }
+
+  /// A base class for iterator classes ("handles") that wish to poll for
+  /// iterator invalidating modifications in the underlying data structure.
+  /// When LLVM is built without asserts, this class is empty and does nothing.
+  ///
+  /// HandleBase does not track the parent data structure by itself.  It expects
+  /// the routines modifying the data structure to call incrementEpoch when they
+  /// make an iterator-invalidating modification.
+  ///
+  class HandleBase {
+    const uint64_t *EpochAddress;
+    uint64_t EpochAtCreation;
+
+  public:
+    HandleBase() : EpochAddress(nullptr), EpochAtCreation(UINT64_MAX) {}
+
+    explicit HandleBase(const DebugEpochBase *Parent)
+        : EpochAddress(&Parent->Epoch), EpochAtCreation(Parent->Epoch) {}
+
+    /// Returns true if the DebugEpochBase this Handle is linked to has
+    /// not called incrementEpoch on itself since the creation of this
+    /// HandleBase instance.
+    bool isHandleInSync() const { return *EpochAddress == EpochAtCreation; }
+
+    /// Returns a pointer to the epoch word stored in the data structure
+    /// this handle points into.  Can be used to check if two iterators point
+    /// into the same data structure.
+    const void *getEpochAddress() const { return EpochAddress; }
+  };
+};
+
+#else
+
+class DebugEpochBase {
+public:
+  void incrementEpoch() {}
+
+  class HandleBase {
+  public:
+    HandleBase() = default;
+    explicit HandleBase(const DebugEpochBase *) {}
+    bool isHandleInSync() const { return true; }
+    const void *getEpochAddress() const { return nullptr; }
+  };
+};
+
+#endif // LLVM_ENABLE_ABI_BREAKING_CHECKS
+
+} // namespace wpi
+
+#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/Errc.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/Errc.h
new file mode 100644
index 0000000..dee28df
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/Errc.h
@@ -0,0 +1,86 @@
+//===- llvm/Support/Errc.h - Defines the wpi::errc enum --------*- C++ -*-===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+//
+// While std::error_code works OK on all platforms we use, there are some
+// some problems with std::errc that can be avoided by using our own
+// enumeration:
+//
+// * std::errc is a namespace in some implementations. That means that ADL
+//   doesn't work and it is sometimes necessary to write std::make_error_code
+//   or in templates:
+//   using std::make_error_code;
+//   make_error_code(...);
+//
+//   with this enum it is safe to always just use make_error_code.
+//
+// * Some implementations define fewer names than others. This header has
+//   the intersection of all the ones we support.
+//
+// * std::errc is just marked with is_error_condition_enum. This means that
+//   common patterns like AnErrorCode == errc::no_such_file_or_directory take
+//   4 virtual calls instead of two comparisons.
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_ERRC_H
+#define WPIUTIL_WPI_ERRC_H
+
+#include <system_error>
+
+namespace wpi {
+enum class errc {
+  argument_list_too_long = int(std::errc::argument_list_too_long),
+  argument_out_of_domain = int(std::errc::argument_out_of_domain),
+  bad_address = int(std::errc::bad_address),
+  bad_file_descriptor = int(std::errc::bad_file_descriptor),
+  broken_pipe = int(std::errc::broken_pipe),
+  device_or_resource_busy = int(std::errc::device_or_resource_busy),
+  directory_not_empty = int(std::errc::directory_not_empty),
+  executable_format_error = int(std::errc::executable_format_error),
+  file_exists = int(std::errc::file_exists),
+  file_too_large = int(std::errc::file_too_large),
+  filename_too_long = int(std::errc::filename_too_long),
+  function_not_supported = int(std::errc::function_not_supported),
+  illegal_byte_sequence = int(std::errc::illegal_byte_sequence),
+  inappropriate_io_control_operation =
+      int(std::errc::inappropriate_io_control_operation),
+  interrupted = int(std::errc::interrupted),
+  invalid_argument = int(std::errc::invalid_argument),
+  invalid_seek = int(std::errc::invalid_seek),
+  io_error = int(std::errc::io_error),
+  is_a_directory = int(std::errc::is_a_directory),
+  no_child_process = int(std::errc::no_child_process),
+  no_lock_available = int(std::errc::no_lock_available),
+  no_space_on_device = int(std::errc::no_space_on_device),
+  no_such_device_or_address = int(std::errc::no_such_device_or_address),
+  no_such_device = int(std::errc::no_such_device),
+  no_such_file_or_directory = int(std::errc::no_such_file_or_directory),
+  no_such_process = int(std::errc::no_such_process),
+  not_a_directory = int(std::errc::not_a_directory),
+  not_enough_memory = int(std::errc::not_enough_memory),
+  not_supported = int(std::errc::not_supported),
+  operation_not_permitted = int(std::errc::operation_not_permitted),
+  permission_denied = int(std::errc::permission_denied),
+  read_only_file_system = int(std::errc::read_only_file_system),
+  resource_deadlock_would_occur = int(std::errc::resource_deadlock_would_occur),
+  resource_unavailable_try_again =
+      int(std::errc::resource_unavailable_try_again),
+  result_out_of_range = int(std::errc::result_out_of_range),
+  too_many_files_open_in_system = int(std::errc::too_many_files_open_in_system),
+  too_many_files_open = int(std::errc::too_many_files_open),
+  too_many_links = int(std::errc::too_many_links)
+};
+
+inline std::error_code make_error_code(errc E) {
+  return std::error_code(static_cast<int>(E), std::generic_category());
+}
+}
+
+namespace std {
+template <> struct is_error_code_enum<wpi::errc> : std::true_type {};
+}
+#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/Errno.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/Errno.h
new file mode 100644
index 0000000..febfc37
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/Errno.h
@@ -0,0 +1,37 @@
+//===- llvm/Support/Errno.h - Portable+convenient errno handling -*- C++ -*-===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+//
+// This file declares some portable and convenient functions to deal with errno.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_ERRNO_H
+#define WPIUTIL_WPI_ERRNO_H
+
+#include <cerrno>
+#include <string>
+#include <type_traits>
+
+namespace wpi {
+namespace sys {
+
+template <typename FailT, typename Fun, typename... Args>
+inline decltype(auto) RetryAfterSignal(const FailT &Fail, const Fun &F,
+                                       const Args &... As) {
+  decltype(F(As...)) Res;
+  do {
+    errno = 0;
+    Res = F(As...);
+  } while (Res == Fail && errno == EINTR);
+  return Res;
+}
+
+}  // namespace sys
+}  // namespace wpi
+
+#endif // WPIUTIL_WPI_ERRNO_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/ErrorHandling.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/ErrorHandling.h
new file mode 100644
index 0000000..7b43671
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/ErrorHandling.h
@@ -0,0 +1,141 @@
+//===- llvm/Support/ErrorHandling.h - Fatal error handling ------*- C++ -*-===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+//
+// This file defines an API used to indicate fatal error conditions.  Non-fatal
+// errors (most of them) should be handled through LLVMContext.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_ERRORHANDLING_H
+#define WPIUTIL_WPI_ERRORHANDLING_H
+
+#include "wpi/Compiler.h"
+#include <string>
+#include <string_view>
+
+namespace wpi {
+
+  /// An error handler callback.
+  typedef void (*fatal_error_handler_t)(void *user_data,
+                                        const char *reason,
+                                        bool gen_crash_diag);
+
+  /// install_fatal_error_handler - Installs a new error handler to be used
+  /// whenever a serious (non-recoverable) error is encountered by LLVM.
+  ///
+  /// If no error handler is installed the default is to print the error message
+  /// to stderr, and call exit(1).  If an error handler is installed then it is
+  /// the handler's responsibility to log the message, it will no longer be
+  /// printed to stderr.  If the error handler returns, then exit(1) will be
+  /// called.
+  ///
+  /// It is dangerous to naively use an error handler which throws an exception.
+  /// Even though some applications desire to gracefully recover from arbitrary
+  /// faults, blindly throwing exceptions through unfamiliar code isn't a way to
+  /// achieve this.
+  ///
+  /// \param user_data - An argument which will be passed to the install error
+  /// handler.
+  void install_fatal_error_handler(fatal_error_handler_t handler,
+                                   void *user_data = nullptr);
+
+  /// Restores default error handling behavior.
+  void remove_fatal_error_handler();
+
+  /// ScopedFatalErrorHandler - This is a simple helper class which just
+  /// calls install_fatal_error_handler in its constructor and
+  /// remove_fatal_error_handler in its destructor.
+  struct ScopedFatalErrorHandler {
+    explicit ScopedFatalErrorHandler(fatal_error_handler_t handler,
+                                     void *user_data = nullptr) {
+      install_fatal_error_handler(handler, user_data);
+    }
+
+    ~ScopedFatalErrorHandler() { remove_fatal_error_handler(); }
+  };
+
+/// Reports a serious error, calling any installed error handler. These
+/// functions are intended to be used for error conditions which are outside
+/// the control of the compiler (I/O errors, invalid user input, etc.)
+///
+/// If no error handler is installed the default is to print the message to
+/// standard error, followed by a newline.
+/// After the error handler is called this function will call abort(), it
+/// does not return.
+[[noreturn]] void report_fatal_error(const char *reason,
+                                     bool gen_crash_diag = true);
+[[noreturn]] void report_fatal_error(const std::string &reason,
+                                     bool gen_crash_diag = true);
+[[noreturn]] void report_fatal_error(std::string_view reason,
+                                     bool gen_crash_diag = true);
+
+/// Installs a new bad alloc error handler that should be used whenever a
+/// bad alloc error, e.g. failing malloc/calloc, is encountered by LLVM.
+///
+/// The user can install a bad alloc handler, in order to define the behavior
+/// in case of failing allocations, e.g. throwing an exception. Note that this
+/// handler must not trigger any additional allocations itself.
+///
+/// If no error handler is installed the default is to print the error message
+/// to stderr, and call exit(1).  If an error handler is installed then it is
+/// the handler's responsibility to log the message, it will no longer be
+/// printed to stderr.  If the error handler returns, then exit(1) will be
+/// called.
+///
+///
+/// \param user_data - An argument which will be passed to the installed error
+/// handler.
+void install_bad_alloc_error_handler(fatal_error_handler_t handler,
+                                     void *user_data = nullptr);
+
+/// Restores default bad alloc error handling behavior.
+void remove_bad_alloc_error_handler();
+
+void install_out_of_memory_new_handler();
+
+/// Reports a bad alloc error, calling any user defined bad alloc
+/// error handler. In contrast to the generic 'report_fatal_error'
+/// functions, this function might not terminate, e.g. the user
+/// defined error handler throws an exception, but it won't return.
+///
+/// Note: When throwing an exception in the bad alloc handler, make sure that
+/// the following unwind succeeds, e.g. do not trigger additional allocations
+/// in the unwind chain.
+///
+/// If no error handler is installed (default), throws a bad_alloc exception
+/// if LLVM is compiled with exception support. Otherwise prints the error
+/// to standard error and calls abort().
+[[noreturn]] void report_bad_alloc_error(const char *Reason,
+                                         bool GenCrashDiag = true);
+
+/// This function calls abort(), and prints the optional message to stderr.
+/// Use the wpi_unreachable macro (that adds location info), instead of
+/// calling this function directly.
+[[noreturn]] void
+wpi_unreachable_internal(const char *msg = nullptr, const char *file = nullptr,
+                          unsigned line = 0);
+}
+
+/// Marks that the current location is not supposed to be reachable.
+/// In !NDEBUG builds, prints the message and location info to stderr.
+/// In NDEBUG builds, becomes an optimizer hint that the current location
+/// is not supposed to be reachable.  On compilers that don't support
+/// such hints, prints a reduced message instead and aborts the program.
+///
+/// Use this instead of assert(0).  It conveys intent more clearly and
+/// allows compilers to omit some unnecessary code.
+#ifndef NDEBUG
+#define wpi_unreachable(msg) \
+  ::wpi::wpi_unreachable_internal(msg, __FILE__, __LINE__)
+#elif defined(LLVM_BUILTIN_UNREACHABLE)
+#define wpi_unreachable(msg) LLVM_BUILTIN_UNREACHABLE
+#else
+#define wpi_unreachable(msg) ::wpi::wpi_unreachable_internal()
+#endif
+
+#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/FunctionExtras.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/FunctionExtras.h
new file mode 100644
index 0000000..681b87e
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/FunctionExtras.h
@@ -0,0 +1,427 @@
+//===- FunctionExtras.h - Function type erasure utilities -------*- C++ -*-===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+/// \file
+/// This file provides a collection of function (or more generally, callable)
+/// type erasure utilities supplementing those provided by the standard library
+/// in `<function>`.
+///
+/// It provides `unique_function`, which works like `std::function` but supports
+/// move-only callable objects and const-qualification.
+///
+/// Future plans:
+/// - Add a `function` that provides ref-qualified support, which doesn't work
+///   with `std::function`.
+/// - Provide support for specifying multiple signatures to type erase callable
+///   objects with an overload set, such as those produced by generic lambdas.
+/// - Expand to include a copyable utility that directly replaces std::function
+///   but brings the above improvements.
+///
+/// Note that LLVM's utilities are greatly simplified by not supporting
+/// allocators.
+///
+/// If the standard library ever begins to provide comparable facilities we can
+/// consider switching to those.
+///
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_FUNCTIONEXTRAS_H
+#define WPIUTIL_WPI_FUNCTIONEXTRAS_H
+
+#include "wpi/PointerIntPair.h"
+#include "wpi/PointerUnion.h"
+#include "wpi/STLForwardCompat.h"
+#include "wpi/MemAlloc.h"
+#include "wpi/type_traits.h"
+#include <cstring>
+#include <memory>
+#include <type_traits>
+
+namespace wpi {
+
+/// unique_function is a type-erasing functor similar to std::function.
+///
+/// It can hold move-only function objects, like lambdas capturing unique_ptrs.
+/// Accordingly, it is movable but not copyable.
+///
+/// It supports const-qualification:
+/// - unique_function<int() const> has a const operator().
+///   It can only hold functions which themselves have a const operator().
+/// - unique_function<int()> has a non-const operator().
+///   It can hold functions with a non-const operator(), like mutable lambdas.
+template <typename FunctionT> class unique_function;
+
+// GCC warns on OutOfLineStorage
+#if defined(__GNUC__) && !defined(__clang__)
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Warray-bounds"
+#pragma GCC diagnostic ignored "-Wmaybe-uninitialized"
+#endif
+
+namespace detail {
+
+template <typename T>
+using EnableIfTrivial =
+    std::enable_if_t<wpi::is_trivially_move_constructible<T>::value &&
+                     std::is_trivially_destructible<T>::value>;
+template <typename CallableT, typename ThisT>
+using EnableUnlessSameType =
+    std::enable_if_t<!std::is_same<remove_cvref_t<CallableT>, ThisT>::value>;
+template <typename CallableT, typename Ret, typename... Params>
+using EnableIfCallable = std::enable_if_t<wpi::disjunction<
+    std::is_void<Ret>,
+    std::is_same<decltype(std::declval<CallableT>()(std::declval<Params>()...)),
+                 Ret>,
+    std::is_same<const decltype(std::declval<CallableT>()(
+                     std::declval<Params>()...)),
+                 Ret>,
+    std::is_convertible<decltype(std::declval<CallableT>()(
+                            std::declval<Params>()...)),
+                        Ret>>::value>;
+
+template <typename ReturnT, typename... ParamTs> class UniqueFunctionBase {
+protected:
+  static constexpr size_t InlineStorageSize = sizeof(void *) * 4;
+
+  template <typename T, class = void>
+  struct IsSizeLessThanThresholdT : std::false_type {};
+
+  template <typename T>
+  struct IsSizeLessThanThresholdT<
+      T, std::enable_if_t<sizeof(T) <= 2 * sizeof(void *)>> : std::true_type {};
+
+  // Provide a type function to map parameters that won't observe extra copies
+  // or moves and which are small enough to likely pass in register to values
+  // and all other types to l-value reference types. We use this to compute the
+  // types used in our erased call utility to minimize copies and moves unless
+  // doing so would force things unnecessarily into memory.
+  //
+  // The heuristic used is related to common ABI register passing conventions.
+  // It doesn't have to be exact though, and in one way it is more strict
+  // because we want to still be able to observe either moves *or* copies.
+  template <typename T> struct AdjustedParamTBase {
+    static_assert(!std::is_reference<T>::value,
+                  "references should be handled by template specialization");
+    using type = typename std::conditional<
+        wpi::is_trivially_copy_constructible<T>::value &&
+            wpi::is_trivially_move_constructible<T>::value &&
+            IsSizeLessThanThresholdT<T>::value,
+        T, T &>::type;
+  };
+
+  // This specialization ensures that 'AdjustedParam<V<T>&>' or
+  // 'AdjustedParam<V<T>&&>' does not trigger a compile-time error when 'T' is
+  // an incomplete type and V a templated type.
+  template <typename T> struct AdjustedParamTBase<T &> { using type = T &; };
+  template <typename T> struct AdjustedParamTBase<T &&> { using type = T &; };
+
+  template <typename T>
+  using AdjustedParamT = typename AdjustedParamTBase<T>::type;
+
+  // The type of the erased function pointer we use as a callback to dispatch to
+  // the stored callable when it is trivial to move and destroy.
+  using CallPtrT = ReturnT (*)(void *CallableAddr,
+                               AdjustedParamT<ParamTs>... Params);
+  using MovePtrT = void (*)(void *LHSCallableAddr, void *RHSCallableAddr);
+  using DestroyPtrT = void (*)(void *CallableAddr);
+
+  /// A struct to hold a single trivial callback with sufficient alignment for
+  /// our bitpacking.
+  struct alignas(8) TrivialCallback {
+    CallPtrT CallPtr;
+  };
+
+  /// A struct we use to aggregate three callbacks when we need full set of
+  /// operations.
+  struct alignas(8) NonTrivialCallbacks {
+    CallPtrT CallPtr;
+    MovePtrT MovePtr;
+    DestroyPtrT DestroyPtr;
+  };
+
+  // Create a pointer union between either a pointer to a static trivial call
+  // pointer in a struct or a pointer to a static struct of the call, move, and
+  // destroy pointers.
+  using CallbackPointerUnionT =
+      PointerUnion<TrivialCallback *, NonTrivialCallbacks *>;
+
+  // The main storage buffer. This will either have a pointer to out-of-line
+  // storage or an inline buffer storing the callable.
+  union StorageUnionT {
+    // For out-of-line storage we keep a pointer to the underlying storage and
+    // the size. This is enough to deallocate the memory.
+    struct OutOfLineStorageT {
+      void *StoragePtr;
+      size_t Size;
+      size_t Alignment;
+    } OutOfLineStorage;
+    static_assert(
+        sizeof(OutOfLineStorageT) <= InlineStorageSize,
+        "Should always use all of the out-of-line storage for inline storage!");
+
+    // For in-line storage, we just provide an aligned character buffer. We
+    // provide four pointers worth of storage here.
+    // This is mutable as an inlined `const unique_function<void() const>` may
+    // still modify its own mutable members.
+    mutable
+        typename std::aligned_storage<InlineStorageSize, alignof(void *)>::type
+            InlineStorage;
+  } StorageUnion;
+
+  // A compressed pointer to either our dispatching callback or our table of
+  // dispatching callbacks and the flag for whether the callable itself is
+  // stored inline or not.
+  PointerIntPair<CallbackPointerUnionT, 1, bool> CallbackAndInlineFlag;
+
+  bool isInlineStorage() const { return CallbackAndInlineFlag.getInt(); }
+
+  bool isTrivialCallback() const {
+    return CallbackAndInlineFlag.getPointer().template is<TrivialCallback *>();
+  }
+
+  CallPtrT getTrivialCallback() const {
+    return CallbackAndInlineFlag.getPointer().template get<TrivialCallback *>()->CallPtr;
+  }
+
+  NonTrivialCallbacks *getNonTrivialCallbacks() const {
+    return CallbackAndInlineFlag.getPointer()
+        .template get<NonTrivialCallbacks *>();
+  }
+
+  CallPtrT getCallPtr() const {
+    return isTrivialCallback() ? getTrivialCallback()
+                               : getNonTrivialCallbacks()->CallPtr;
+  }
+
+  // These three functions are only const in the narrow sense. They return
+  // mutable pointers to function state.
+  // This allows unique_function<T const>::operator() to be const, even if the
+  // underlying functor may be internally mutable.
+  //
+  // const callers must ensure they're only used in const-correct ways.
+  void *getCalleePtr() const {
+    return isInlineStorage() ? getInlineStorage() : getOutOfLineStorage();
+  }
+  void *getInlineStorage() const { return &StorageUnion.InlineStorage; }
+  void *getOutOfLineStorage() const {
+    return StorageUnion.OutOfLineStorage.StoragePtr;
+  }
+
+  size_t getOutOfLineStorageSize() const {
+    return StorageUnion.OutOfLineStorage.Size;
+  }
+  size_t getOutOfLineStorageAlignment() const {
+    return StorageUnion.OutOfLineStorage.Alignment;
+  }
+
+  void setOutOfLineStorage(void *Ptr, size_t Size, size_t Alignment) {
+    StorageUnion.OutOfLineStorage = {Ptr, Size, Alignment};
+  }
+
+  template <typename CalledAsT>
+  static ReturnT CallImpl(void *CallableAddr,
+                          AdjustedParamT<ParamTs>... Params) {
+    auto &Func = *reinterpret_cast<CalledAsT *>(CallableAddr);
+    return Func(std::forward<ParamTs>(Params)...);
+  }
+
+  template <typename CallableT>
+  static void MoveImpl(void *LHSCallableAddr, void *RHSCallableAddr) noexcept {
+    new (LHSCallableAddr)
+        CallableT(std::move(*reinterpret_cast<CallableT *>(RHSCallableAddr)));
+  }
+
+  template <typename CallableT>
+  static void DestroyImpl(void *CallableAddr) noexcept {
+    reinterpret_cast<CallableT *>(CallableAddr)->~CallableT();
+  }
+
+  // The pointers to call/move/destroy functions are determined for each
+  // callable type (and called-as type, which determines the overload chosen).
+  // (definitions are out-of-line).
+
+  // By default, we need an object that contains all the different
+  // type erased behaviors needed. Create a static instance of the struct type
+  // here and each instance will contain a pointer to it.
+  // Wrap in a struct to avoid https://gcc.gnu.org/PR71954
+  template <typename CallableT, typename CalledAs, typename Enable = void>
+  struct CallbacksHolder {
+    static NonTrivialCallbacks Callbacks;
+  };
+  // See if we can create a trivial callback. We need the callable to be
+  // trivially moved and trivially destroyed so that we don't have to store
+  // type erased callbacks for those operations.
+  template <typename CallableT, typename CalledAs>
+  struct CallbacksHolder<CallableT, CalledAs, EnableIfTrivial<CallableT>> {
+    static TrivialCallback Callbacks;
+  };
+
+  // A simple tag type so the call-as type to be passed to the constructor.
+  template <typename T> struct CalledAs {};
+
+  // Essentially the "main" unique_function constructor, but subclasses
+  // provide the qualified type to be used for the call.
+  // (We always store a T, even if the call will use a pointer to const T).
+  template <typename CallableT, typename CalledAsT>
+  UniqueFunctionBase(CallableT Callable, CalledAs<CalledAsT>) {
+    bool IsInlineStorage = true;
+    void *CallableAddr = getInlineStorage();
+    if (sizeof(CallableT) > InlineStorageSize ||
+        alignof(CallableT) > alignof(decltype(StorageUnion.InlineStorage))) {
+      IsInlineStorage = false;
+      // Allocate out-of-line storage. FIXME: Use an explicit alignment
+      // parameter in C++17 mode.
+      auto Size = sizeof(CallableT);
+      auto Alignment = alignof(CallableT);
+      CallableAddr = allocate_buffer(Size, Alignment);
+      setOutOfLineStorage(CallableAddr, Size, Alignment);
+    }
+
+    // Now move into the storage.
+    new (CallableAddr) CallableT(std::move(Callable));
+    CallbackAndInlineFlag.setPointerAndInt(
+        &CallbacksHolder<CallableT, CalledAsT>::Callbacks, IsInlineStorage);
+  }
+
+  ~UniqueFunctionBase() {
+    if (!CallbackAndInlineFlag.getPointer())
+      return;
+
+    // Cache this value so we don't re-check it after type-erased operations.
+    bool IsInlineStorage = isInlineStorage();
+
+    if (!isTrivialCallback())
+      getNonTrivialCallbacks()->DestroyPtr(
+          IsInlineStorage ? getInlineStorage() : getOutOfLineStorage());
+
+    if (!IsInlineStorage)
+      deallocate_buffer(getOutOfLineStorage(), getOutOfLineStorageSize(),
+                        getOutOfLineStorageAlignment());
+  }
+
+  UniqueFunctionBase(UniqueFunctionBase &&RHS) noexcept {
+    // Copy the callback and inline flag.
+    CallbackAndInlineFlag = RHS.CallbackAndInlineFlag;
+
+    // If the RHS is empty, just copying the above is sufficient.
+    if (!RHS)
+      return;
+
+    if (!isInlineStorage()) {
+      // The out-of-line case is easiest to move.
+      StorageUnion.OutOfLineStorage = RHS.StorageUnion.OutOfLineStorage;
+    } else if (isTrivialCallback()) {
+      // Move is trivial, just memcpy the bytes across.
+      memcpy(getInlineStorage(), RHS.getInlineStorage(), InlineStorageSize);
+    } else {
+      // Non-trivial move, so dispatch to a type-erased implementation.
+      getNonTrivialCallbacks()->MovePtr(getInlineStorage(),
+                                        RHS.getInlineStorage());
+    }
+
+    // Clear the old callback and inline flag to get back to as-if-null.
+    RHS.CallbackAndInlineFlag = {};
+
+#ifndef NDEBUG
+    // In debug builds, we also scribble across the rest of the storage.
+    memset(RHS.getInlineStorage(), 0xAD, InlineStorageSize);
+#endif
+  }
+
+  UniqueFunctionBase &operator=(UniqueFunctionBase &&RHS) noexcept {
+    if (this == &RHS)
+      return *this;
+
+    // Because we don't try to provide any exception safety guarantees we can
+    // implement move assignment very simply by first destroying the current
+    // object and then move-constructing over top of it.
+    this->~UniqueFunctionBase();
+    new (this) UniqueFunctionBase(std::move(RHS));
+    return *this;
+  }
+
+  UniqueFunctionBase() = default;
+
+public:
+  explicit operator bool() const {
+    return (bool)CallbackAndInlineFlag.getPointer();
+  }
+};
+
+template <typename R, typename... P>
+template <typename CallableT, typename CalledAsT, typename Enable>
+typename UniqueFunctionBase<R, P...>::NonTrivialCallbacks UniqueFunctionBase<
+    R, P...>::CallbacksHolder<CallableT, CalledAsT, Enable>::Callbacks = {
+    &CallImpl<CalledAsT>, &MoveImpl<CallableT>, &DestroyImpl<CallableT>};
+
+template <typename R, typename... P>
+template <typename CallableT, typename CalledAsT>
+typename UniqueFunctionBase<R, P...>::TrivialCallback
+    UniqueFunctionBase<R, P...>::CallbacksHolder<
+        CallableT, CalledAsT, EnableIfTrivial<CallableT>>::Callbacks{
+        &CallImpl<CalledAsT>};
+
+} // namespace detail
+
+template <typename R, typename... P>
+class unique_function<R(P...)> : public detail::UniqueFunctionBase<R, P...> {
+  using Base = detail::UniqueFunctionBase<R, P...>;
+
+public:
+  unique_function() = default;
+  unique_function(std::nullptr_t) {}
+  unique_function(unique_function &&) = default;
+  unique_function(const unique_function &) = delete;
+  unique_function &operator=(unique_function &&) = default;
+  unique_function &operator=(const unique_function &) = delete;
+
+  template <typename CallableT>
+  unique_function(
+      CallableT Callable,
+      detail::EnableUnlessSameType<CallableT, unique_function> * = nullptr,
+      detail::EnableIfCallable<CallableT, R, P...> * = nullptr)
+      : Base(std::forward<CallableT>(Callable),
+             typename Base::template CalledAs<CallableT>{}) {}
+
+  R operator()(P... Params) {
+    return this->getCallPtr()(this->getCalleePtr(), Params...);
+  }
+};
+
+template <typename R, typename... P>
+class unique_function<R(P...) const>
+    : public detail::UniqueFunctionBase<R, P...> {
+  using Base = detail::UniqueFunctionBase<R, P...>;
+
+public:
+  unique_function() = default;
+  unique_function(std::nullptr_t) {}
+  unique_function(unique_function &&) = default;
+  unique_function(const unique_function &) = delete;
+  unique_function &operator=(unique_function &&) = default;
+  unique_function &operator=(const unique_function &) = delete;
+
+  template <typename CallableT>
+  unique_function(
+      CallableT Callable,
+      detail::EnableUnlessSameType<CallableT, unique_function> * = nullptr,
+      detail::EnableIfCallable<const CallableT, R, P...> * = nullptr)
+      : Base(std::forward<CallableT>(Callable),
+             typename Base::template CalledAs<const CallableT>{}) {}
+
+  R operator()(P... Params) const {
+    return this->getCallPtr()(this->getCalleePtr(), Params...);
+  }
+};
+
+#if defined(__GNUC__) && !defined(__clang__)
+#pragma GCC diagnostic pop
+#endif
+
+} // end namespace wpi
+
+#endif // WPIUTIL_WPI_FUNCTIONEXTRAS_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/Hashing.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/Hashing.h
new file mode 100644
index 0000000..0d4a4c6
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/Hashing.h
@@ -0,0 +1,698 @@
+//===-- llvm/ADT/Hashing.h - Utilities for hashing --------------*- C++ -*-===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+//
+// This file implements the newly proposed standard C++ interfaces for hashing
+// arbitrary data and building hash functions for user-defined types. This
+// interface was originally proposed in N3333[1] and is currently under review
+// for inclusion in a future TR and/or standard.
+//
+// The primary interfaces provide are comprised of one type and three functions:
+//
+//  -- 'hash_code' class is an opaque type representing the hash code for some
+//     data. It is the intended product of hashing, and can be used to implement
+//     hash tables, checksumming, and other common uses of hashes. It is not an
+//     integer type (although it can be converted to one) because it is risky
+//     to assume much about the internals of a hash_code. In particular, each
+//     execution of the program has a high probability of producing a different
+//     hash_code for a given input. Thus their values are not stable to save or
+//     persist, and should only be used during the execution for the
+//     construction of hashing datastructures.
+//
+//  -- 'hash_value' is a function designed to be overloaded for each
+//     user-defined type which wishes to be used within a hashing context. It
+//     should be overloaded within the user-defined type's namespace and found
+//     via ADL. Overloads for primitive types are provided by this library.
+//
+//  -- 'hash_combine' and 'hash_combine_range' are functions designed to aid
+//      programmers in easily and intuitively combining a set of data into
+//      a single hash_code for their object. They should only logically be used
+//      within the implementation of a 'hash_value' routine or similar context.
+//
+// Note that 'hash_combine_range' contains very special logic for hashing
+// a contiguous array of integers or pointers. This logic is *extremely* fast,
+// on a modern Intel "Gainestown" Xeon (Nehalem uarch) @2.2 GHz, these were
+// benchmarked at over 6.5 GiB/s for large keys, and <20 cycles/hash for keys
+// under 32-bytes.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_HASHING_H
+#define WPIUTIL_WPI_HASHING_H
+
+#include "wpi/ErrorHandling.h"
+#include "wpi/SwapByteOrder.h"
+#include "wpi/type_traits.h"
+#include <algorithm>
+#include <cassert>
+#include <cstring>
+#include <string>
+#include <tuple>
+#include <utility>
+
+#ifdef _WIN32
+#pragma warning(push)
+#pragma warning(disable : 26495)
+#endif
+
+namespace wpi {
+template <typename T, typename Enable> struct DenseMapInfo;
+
+/// An opaque object representing a hash code.
+///
+/// This object represents the result of hashing some entity. It is intended to
+/// be used to implement hashtables or other hashing-based data structures.
+/// While it wraps and exposes a numeric value, this value should not be
+/// trusted to be stable or predictable across processes or executions.
+///
+/// In order to obtain the hash_code for an object 'x':
+/// \code
+///   using wpi::hash_value;
+///   wpi::hash_code code = hash_value(x);
+/// \endcode
+class hash_code {
+  size_t value;
+
+public:
+  /// Default construct a hash_code.
+  /// Note that this leaves the value uninitialized.
+  hash_code() = default;
+
+  /// Form a hash code directly from a numerical value.
+  hash_code(size_t value) : value(value) {}
+
+  /// Convert the hash code to its numerical value for use.
+  /*explicit*/ operator size_t() const { return value; }
+
+  friend bool operator==(const hash_code &lhs, const hash_code &rhs) {
+    return lhs.value == rhs.value;
+  }
+  friend bool operator!=(const hash_code &lhs, const hash_code &rhs) {
+    return lhs.value != rhs.value;
+  }
+
+  /// Allow a hash_code to be directly run through hash_value.
+  friend size_t hash_value(const hash_code &code) { return code.value; }
+};
+
+/// Compute a hash_code for any integer value.
+///
+/// Note that this function is intended to compute the same hash_code for
+/// a particular value without regard to the pre-promotion type. This is in
+/// contrast to hash_combine which may produce different hash_codes for
+/// differing argument types even if they would implicit promote to a common
+/// type without changing the value.
+template <typename T>
+std::enable_if_t<is_integral_or_enum<T>::value, hash_code> hash_value(T value);
+
+/// Compute a hash_code for a pointer's address.
+///
+/// N.B.: This hashes the *address*. Not the value and not the type.
+template <typename T> hash_code hash_value(const T *ptr);
+
+/// Compute a hash_code for a pair of objects.
+template <typename T, typename U>
+hash_code hash_value(const std::pair<T, U> &arg);
+
+/// Compute a hash_code for a tuple.
+template <typename... Ts>
+hash_code hash_value(const std::tuple<Ts...> &arg);
+
+/// Compute a hash_code for a standard string.
+template <typename T>
+hash_code hash_value(const std::basic_string<T> &arg);
+
+
+/// Override the execution seed with a fixed value.
+///
+/// This hashing library uses a per-execution seed designed to change on each
+/// run with high probability in order to ensure that the hash codes are not
+/// attackable and to ensure that output which is intended to be stable does
+/// not rely on the particulars of the hash codes produced.
+///
+/// That said, there are use cases where it is important to be able to
+/// reproduce *exactly* a specific behavior. To that end, we provide a function
+/// which will forcibly set the seed to a fixed value. This must be done at the
+/// start of the program, before any hashes are computed. Also, it cannot be
+/// undone. This makes it thread-hostile and very hard to use outside of
+/// immediately on start of a simple program designed for reproducible
+/// behavior.
+void set_fixed_execution_hash_seed(uint64_t fixed_value);
+
+
+// All of the implementation details of actually computing the various hash
+// code values are held within this namespace. These routines are included in
+// the header file mainly to allow inlining and constant propagation.
+namespace hashing {
+namespace detail {
+
+inline uint64_t fetch64(const char *p) {
+  uint64_t result;
+  memcpy(&result, p, sizeof(result));
+  if (sys::IsBigEndianHost)
+    sys::swapByteOrder(result);
+  return result;
+}
+
+inline uint32_t fetch32(const char *p) {
+  uint32_t result;
+  memcpy(&result, p, sizeof(result));
+  if (sys::IsBigEndianHost)
+    sys::swapByteOrder(result);
+  return result;
+}
+
+/// Some primes between 2^63 and 2^64 for various uses.
+static constexpr uint64_t k0 = 0xc3a5c85c97cb3127ULL;
+static constexpr uint64_t k1 = 0xb492b66fbe98f273ULL;
+static constexpr uint64_t k2 = 0x9ae16a3b2f90404fULL;
+static constexpr uint64_t k3 = 0xc949d7c7509e6557ULL;
+
+/// Bitwise right rotate.
+/// Normally this will compile to a single instruction, especially if the
+/// shift is a manifest constant.
+inline uint64_t rotate(uint64_t val, size_t shift) {
+  // Avoid shifting by 64: doing so yields an undefined result.
+  return shift == 0 ? val : ((val >> shift) | (val << (64 - shift)));
+}
+
+inline uint64_t shift_mix(uint64_t val) {
+  return val ^ (val >> 47);
+}
+
+inline uint64_t hash_16_bytes(uint64_t low, uint64_t high) {
+  // Murmur-inspired hashing.
+  const uint64_t kMul = 0x9ddfea08eb382d69ULL;
+  uint64_t a = (low ^ high) * kMul;
+  a ^= (a >> 47);
+  uint64_t b = (high ^ a) * kMul;
+  b ^= (b >> 47);
+  b *= kMul;
+  return b;
+}
+
+inline uint64_t hash_1to3_bytes(const char *s, size_t len, uint64_t seed) {
+  uint8_t a = s[0];
+  uint8_t b = s[len >> 1];
+  uint8_t c = s[len - 1];
+  uint32_t y = static_cast<uint32_t>(a) + (static_cast<uint32_t>(b) << 8);
+  uint32_t z = static_cast<uint32_t>(len) + (static_cast<uint32_t>(c) << 2);
+  return shift_mix(y * k2 ^ z * k3 ^ seed) * k2;
+}
+
+inline uint64_t hash_4to8_bytes(const char *s, size_t len, uint64_t seed) {
+  uint64_t a = fetch32(s);
+  return hash_16_bytes(len + (a << 3), seed ^ fetch32(s + len - 4));
+}
+
+inline uint64_t hash_9to16_bytes(const char *s, size_t len, uint64_t seed) {
+  uint64_t a = fetch64(s);
+  uint64_t b = fetch64(s + len - 8);
+  return hash_16_bytes(seed ^ a, rotate(b + len, len)) ^ b;
+}
+
+inline uint64_t hash_17to32_bytes(const char *s, size_t len, uint64_t seed) {
+  uint64_t a = fetch64(s) * k1;
+  uint64_t b = fetch64(s + 8);
+  uint64_t c = fetch64(s + len - 8) * k2;
+  uint64_t d = fetch64(s + len - 16) * k0;
+  return hash_16_bytes(rotate(a - b, 43) + rotate(c ^ seed, 30) + d,
+                       a + rotate(b ^ k3, 20) - c + len + seed);
+}
+
+inline uint64_t hash_33to64_bytes(const char *s, size_t len, uint64_t seed) {
+  uint64_t z = fetch64(s + 24);
+  uint64_t a = fetch64(s) + (len + fetch64(s + len - 16)) * k0;
+  uint64_t b = rotate(a + z, 52);
+  uint64_t c = rotate(a, 37);
+  a += fetch64(s + 8);
+  c += rotate(a, 7);
+  a += fetch64(s + 16);
+  uint64_t vf = a + z;
+  uint64_t vs = b + rotate(a, 31) + c;
+  a = fetch64(s + 16) + fetch64(s + len - 32);
+  z = fetch64(s + len - 8);
+  b = rotate(a + z, 52);
+  c = rotate(a, 37);
+  a += fetch64(s + len - 24);
+  c += rotate(a, 7);
+  a += fetch64(s + len - 16);
+  uint64_t wf = a + z;
+  uint64_t ws = b + rotate(a, 31) + c;
+  uint64_t r = shift_mix((vf + ws) * k2 + (wf + vs) * k0);
+  return shift_mix((seed ^ (r * k0)) + vs) * k2;
+}
+
+inline uint64_t hash_short(const char *s, size_t length, uint64_t seed) {
+  if (length >= 4 && length <= 8)
+    return hash_4to8_bytes(s, length, seed);
+  if (length > 8 && length <= 16)
+    return hash_9to16_bytes(s, length, seed);
+  if (length > 16 && length <= 32)
+    return hash_17to32_bytes(s, length, seed);
+  if (length > 32)
+    return hash_33to64_bytes(s, length, seed);
+  if (length != 0)
+    return hash_1to3_bytes(s, length, seed);
+
+  return k2 ^ seed;
+}
+
+/// The intermediate state used during hashing.
+/// Currently, the algorithm for computing hash codes is based on CityHash and
+/// keeps 56 bytes of arbitrary state.
+struct hash_state {
+  uint64_t h0 = 0, h1 = 0, h2 = 0, h3 = 0, h4 = 0, h5 = 0, h6 = 0;
+
+  /// Create a new hash_state structure and initialize it based on the
+  /// seed and the first 64-byte chunk.
+  /// This effectively performs the initial mix.
+  static hash_state create(const char *s, uint64_t seed) {
+    hash_state state = {
+      0, seed, hash_16_bytes(seed, k1), rotate(seed ^ k1, 49),
+      seed * k1, shift_mix(seed), 0 };
+    state.h6 = hash_16_bytes(state.h4, state.h5);
+    state.mix(s);
+    return state;
+  }
+
+  /// Mix 32-bytes from the input sequence into the 16-bytes of 'a'
+  /// and 'b', including whatever is already in 'a' and 'b'.
+  static void mix_32_bytes(const char *s, uint64_t &a, uint64_t &b) {
+    a += fetch64(s);
+    uint64_t c = fetch64(s + 24);
+    b = rotate(b + a + c, 21);
+    uint64_t d = a;
+    a += fetch64(s + 8) + fetch64(s + 16);
+    b += rotate(a, 44) + d;
+    a += c;
+  }
+
+  /// Mix in a 64-byte buffer of data.
+  /// We mix all 64 bytes even when the chunk length is smaller, but we
+  /// record the actual length.
+  void mix(const char *s) {
+    h0 = rotate(h0 + h1 + h3 + fetch64(s + 8), 37) * k1;
+    h1 = rotate(h1 + h4 + fetch64(s + 48), 42) * k1;
+    h0 ^= h6;
+    h1 += h3 + fetch64(s + 40);
+    h2 = rotate(h2 + h5, 33) * k1;
+    h3 = h4 * k1;
+    h4 = h0 + h5;
+    mix_32_bytes(s, h3, h4);
+    h5 = h2 + h6;
+    h6 = h1 + fetch64(s + 16);
+    mix_32_bytes(s + 32, h5, h6);
+    std::swap(h2, h0);
+  }
+
+  /// Compute the final 64-bit hash code value based on the current
+  /// state and the length of bytes hashed.
+  uint64_t finalize(size_t length) {
+    return hash_16_bytes(hash_16_bytes(h3, h5) + shift_mix(h1) * k1 + h2,
+                         hash_16_bytes(h4, h6) + shift_mix(length) * k1 + h0);
+  }
+};
+
+
+/// A global, fixed seed-override variable.
+///
+/// This variable can be set using the \see wpi::set_fixed_execution_seed
+/// function. See that function for details. Do not, under any circumstances,
+/// set or read this variable.
+extern uint64_t fixed_seed_override;
+
+inline uint64_t get_execution_seed() {
+  // FIXME: This needs to be a per-execution seed. This is just a placeholder
+  // implementation. Switching to a per-execution seed is likely to flush out
+  // instability bugs and so will happen as its own commit.
+  //
+  // However, if there is a fixed seed override set the first time this is
+  // called, return that instead of the per-execution seed.
+  const uint64_t seed_prime = 0xff51afd7ed558ccdULL;
+  static uint64_t seed = fixed_seed_override ? fixed_seed_override : seed_prime;
+  return seed;
+}
+
+
+/// Trait to indicate whether a type's bits can be hashed directly.
+///
+/// A type trait which is true if we want to combine values for hashing by
+/// reading the underlying data. It is false if values of this type must
+/// first be passed to hash_value, and the resulting hash_codes combined.
+//
+// FIXME: We want to replace is_integral_or_enum and is_pointer here with
+// a predicate which asserts that comparing the underlying storage of two
+// values of the type for equality is equivalent to comparing the two values
+// for equality. For all the platforms we care about, this holds for integers
+// and pointers, but there are platforms where it doesn't and we would like to
+// support user-defined types which happen to satisfy this property.
+template <typename T> struct is_hashable_data
+  : std::integral_constant<bool, ((is_integral_or_enum<T>::value ||
+                                   std::is_pointer<T>::value) &&
+                                  64 % sizeof(T) == 0)> {};
+
+// Special case std::pair to detect when both types are viable and when there
+// is no alignment-derived padding in the pair. This is a bit of a lie because
+// std::pair isn't truly POD, but it's close enough in all reasonable
+// implementations for our use case of hashing the underlying data.
+template <typename T, typename U> struct is_hashable_data<std::pair<T, U> >
+  : std::integral_constant<bool, (is_hashable_data<T>::value &&
+                                  is_hashable_data<U>::value &&
+                                  (sizeof(T) + sizeof(U)) ==
+                                   sizeof(std::pair<T, U>))> {};
+
+/// Helper to get the hashable data representation for a type.
+/// This variant is enabled when the type itself can be used.
+template <typename T>
+std::enable_if_t<is_hashable_data<T>::value, T>
+get_hashable_data(const T &value) {
+  return value;
+}
+/// Helper to get the hashable data representation for a type.
+/// This variant is enabled when we must first call hash_value and use the
+/// result as our data.
+template <typename T>
+std::enable_if_t<!is_hashable_data<T>::value, size_t>
+get_hashable_data(const T &value) {
+  using ::wpi::hash_value;
+  return hash_value(value);
+}
+
+/// Helper to store data from a value into a buffer and advance the
+/// pointer into that buffer.
+///
+/// This routine first checks whether there is enough space in the provided
+/// buffer, and if not immediately returns false. If there is space, it
+/// copies the underlying bytes of value into the buffer, advances the
+/// buffer_ptr past the copied bytes, and returns true.
+template <typename T>
+bool store_and_advance(char *&buffer_ptr, char *buffer_end, const T& value,
+                       size_t offset = 0) {
+  size_t store_size = sizeof(value) - offset;
+  if (buffer_ptr + store_size > buffer_end)
+    return false;
+  const char *value_data = reinterpret_cast<const char *>(&value);
+  memcpy(buffer_ptr, value_data + offset, store_size);
+  buffer_ptr += store_size;
+  return true;
+}
+
+/// Implement the combining of integral values into a hash_code.
+///
+/// This overload is selected when the value type of the iterator is
+/// integral. Rather than computing a hash_code for each object and then
+/// combining them, this (as an optimization) directly combines the integers.
+template <typename InputIteratorT>
+hash_code hash_combine_range_impl(InputIteratorT first, InputIteratorT last) {
+  const uint64_t seed = get_execution_seed();
+  char buffer[64], *buffer_ptr = buffer;
+  char *const buffer_end = std::end(buffer);
+  while (first != last && store_and_advance(buffer_ptr, buffer_end,
+                                            get_hashable_data(*first)))
+    ++first;
+  if (first == last)
+    return hash_short(buffer, buffer_ptr - buffer, seed);
+  assert(buffer_ptr == buffer_end);
+
+  hash_state state = state.create(buffer, seed);
+  size_t length = 64;
+  while (first != last) {
+    // Fill up the buffer. We don't clear it, which re-mixes the last round
+    // when only a partial 64-byte chunk is left.
+    buffer_ptr = buffer;
+    while (first != last && store_and_advance(buffer_ptr, buffer_end,
+                                              get_hashable_data(*first)))
+      ++first;
+
+    // Rotate the buffer if we did a partial fill in order to simulate doing
+    // a mix of the last 64-bytes. That is how the algorithm works when we
+    // have a contiguous byte sequence, and we want to emulate that here.
+    std::rotate(buffer, buffer_ptr, buffer_end);
+
+    // Mix this chunk into the current state.
+    state.mix(buffer);
+    length += buffer_ptr - buffer;
+  };
+
+  return state.finalize(length);
+}
+
+/// Implement the combining of integral values into a hash_code.
+///
+/// This overload is selected when the value type of the iterator is integral
+/// and when the input iterator is actually a pointer. Rather than computing
+/// a hash_code for each object and then combining them, this (as an
+/// optimization) directly combines the integers. Also, because the integers
+/// are stored in contiguous memory, this routine avoids copying each value
+/// and directly reads from the underlying memory.
+template <typename ValueT>
+std::enable_if_t<is_hashable_data<ValueT>::value, hash_code>
+hash_combine_range_impl(ValueT *first, ValueT *last) {
+  const uint64_t seed = get_execution_seed();
+  const char *s_begin = reinterpret_cast<const char *>(first);
+  const char *s_end = reinterpret_cast<const char *>(last);
+  const size_t length = std::distance(s_begin, s_end);
+  if (length <= 64)
+    return hash_short(s_begin, length, seed);
+
+  const char *s_aligned_end = s_begin + (length & ~63);
+  hash_state state = state.create(s_begin, seed);
+  s_begin += 64;
+  while (s_begin != s_aligned_end) {
+    state.mix(s_begin);
+    s_begin += 64;
+  }
+  if (length & 63)
+    state.mix(s_end - 64);
+
+  return state.finalize(length);
+}
+
+} // namespace detail
+} // namespace hashing
+
+
+/// Compute a hash_code for a sequence of values.
+///
+/// This hashes a sequence of values. It produces the same hash_code as
+/// 'hash_combine(a, b, c, ...)', but can run over arbitrary sized sequences
+/// and is significantly faster given pointers and types which can be hashed as
+/// a sequence of bytes.
+template <typename InputIteratorT>
+hash_code hash_combine_range(InputIteratorT first, InputIteratorT last) {
+  return ::wpi::hashing::detail::hash_combine_range_impl(first, last);
+}
+
+
+// Implementation details for hash_combine.
+namespace hashing {
+namespace detail {
+
+/// Helper class to manage the recursive combining of hash_combine
+/// arguments.
+///
+/// This class exists to manage the state and various calls involved in the
+/// recursive combining of arguments used in hash_combine. It is particularly
+/// useful at minimizing the code in the recursive calls to ease the pain
+/// caused by a lack of variadic functions.
+struct hash_combine_recursive_helper {
+  char buffer[64] = {};
+  hash_state state;
+  const uint64_t seed;
+
+public:
+  /// Construct a recursive hash combining helper.
+  ///
+  /// This sets up the state for a recursive hash combine, including getting
+  /// the seed and buffer setup.
+  hash_combine_recursive_helper()
+    : seed(get_execution_seed()) {}
+
+  /// Combine one chunk of data into the current in-flight hash.
+  ///
+  /// This merges one chunk of data into the hash. First it tries to buffer
+  /// the data. If the buffer is full, it hashes the buffer into its
+  /// hash_state, empties it, and then merges the new chunk in. This also
+  /// handles cases where the data straddles the end of the buffer.
+  template <typename T>
+  char *combine_data(size_t &length, char *buffer_ptr, char *buffer_end, T data) {
+    if (!store_and_advance(buffer_ptr, buffer_end, data)) {
+      // Check for skew which prevents the buffer from being packed, and do
+      // a partial store into the buffer to fill it. This is only a concern
+      // with the variadic combine because that formation can have varying
+      // argument types.
+      size_t partial_store_size = buffer_end - buffer_ptr;
+      memcpy(buffer_ptr, &data, partial_store_size);
+
+      // If the store fails, our buffer is full and ready to hash. We have to
+      // either initialize the hash state (on the first full buffer) or mix
+      // this buffer into the existing hash state. Length tracks the *hashed*
+      // length, not the buffered length.
+      if (length == 0) {
+        state = state.create(buffer, seed);
+        length = 64;
+      } else {
+        // Mix this chunk into the current state and bump length up by 64.
+        state.mix(buffer);
+        length += 64;
+      }
+      // Reset the buffer_ptr to the head of the buffer for the next chunk of
+      // data.
+      buffer_ptr = buffer;
+
+      // Try again to store into the buffer -- this cannot fail as we only
+      // store types smaller than the buffer.
+      if (!store_and_advance(buffer_ptr, buffer_end, data,
+                             partial_store_size))
+        wpi_unreachable("buffer smaller than stored type");
+    }
+    return buffer_ptr;
+  }
+
+  /// Recursive, variadic combining method.
+  ///
+  /// This function recurses through each argument, combining that argument
+  /// into a single hash.
+  template <typename T, typename ...Ts>
+  hash_code combine(size_t length, char *buffer_ptr, char *buffer_end,
+                    const T &arg, const Ts &...args) {
+    buffer_ptr = combine_data(length, buffer_ptr, buffer_end, get_hashable_data(arg));
+
+    // Recurse to the next argument.
+    return combine(length, buffer_ptr, buffer_end, args...);
+  }
+
+  /// Base case for recursive, variadic combining.
+  ///
+  /// The base case when combining arguments recursively is reached when all
+  /// arguments have been handled. It flushes the remaining buffer and
+  /// constructs a hash_code.
+  hash_code combine(size_t length, char *buffer_ptr, char *buffer_end) {
+    // Check whether the entire set of values fit in the buffer. If so, we'll
+    // use the optimized short hashing routine and skip state entirely.
+    if (length == 0)
+      return hash_short(buffer, buffer_ptr - buffer, seed);
+
+    // Mix the final buffer, rotating it if we did a partial fill in order to
+    // simulate doing a mix of the last 64-bytes. That is how the algorithm
+    // works when we have a contiguous byte sequence, and we want to emulate
+    // that here.
+    std::rotate(buffer, buffer_ptr, buffer_end);
+
+    // Mix this chunk into the current state.
+    state.mix(buffer);
+    length += buffer_ptr - buffer;
+
+    return state.finalize(length);
+  }
+};
+
+} // namespace detail
+} // namespace hashing
+
+/// Combine values into a single hash_code.
+///
+/// This routine accepts a varying number of arguments of any type. It will
+/// attempt to combine them into a single hash_code. For user-defined types it
+/// attempts to call a \see hash_value overload (via ADL) for the type. For
+/// integer and pointer types it directly combines their data into the
+/// resulting hash_code.
+///
+/// The result is suitable for returning from a user's hash_value
+/// *implementation* for their user-defined type. Consumers of a type should
+/// *not* call this routine, they should instead call 'hash_value'.
+template <typename ...Ts> hash_code hash_combine(const Ts &...args) {
+  // Recursively hash each argument using a helper class.
+  ::wpi::hashing::detail::hash_combine_recursive_helper helper;
+  return helper.combine(0, helper.buffer, helper.buffer + 64, args...);
+}
+
+// Implementation details for implementations of hash_value overloads provided
+// here.
+namespace hashing {
+namespace detail {
+
+/// Helper to hash the value of a single integer.
+///
+/// Overloads for smaller integer types are not provided to ensure consistent
+/// behavior in the presence of integral promotions. Essentially,
+/// "hash_value('4')" and "hash_value('0' + 4)" should be the same.
+inline hash_code hash_integer_value(uint64_t value) {
+  // Similar to hash_4to8_bytes but using a seed instead of length.
+  const uint64_t seed = get_execution_seed();
+  const char *s = reinterpret_cast<const char *>(&value);
+  const uint64_t a = fetch32(s);
+  return hash_16_bytes(seed + (a << 3), fetch32(s + 4));
+}
+
+} // namespace detail
+} // namespace hashing
+
+// Declared and documented above, but defined here so that any of the hashing
+// infrastructure is available.
+template <typename T>
+std::enable_if_t<is_integral_or_enum<T>::value, hash_code> hash_value(T value) {
+  return ::wpi::hashing::detail::hash_integer_value(
+      static_cast<uint64_t>(value));
+}
+
+// Declared and documented above, but defined here so that any of the hashing
+// infrastructure is available.
+template <typename T> hash_code hash_value(const T *ptr) {
+  return ::wpi::hashing::detail::hash_integer_value(
+    reinterpret_cast<uintptr_t>(ptr));
+}
+
+// Declared and documented above, but defined here so that any of the hashing
+// infrastructure is available.
+template <typename T, typename U>
+hash_code hash_value(const std::pair<T, U> &arg) {
+  return hash_combine(arg.first, arg.second);
+}
+
+// Implementation details for the hash_value overload for std::tuple<...>(...).
+namespace hashing {
+namespace detail {
+
+template <typename... Ts, std::size_t... Indices>
+hash_code hash_value_tuple_helper(const std::tuple<Ts...> &arg,
+                                  std::index_sequence<Indices...>) {
+  return hash_combine(std::get<Indices>(arg)...);
+}
+
+} // namespace detail
+} // namespace hashing
+
+template <typename... Ts>
+hash_code hash_value(const std::tuple<Ts...> &arg) {
+  // TODO: Use std::apply when LLVM starts using C++17.
+  return ::wpi::hashing::detail::hash_value_tuple_helper(
+      arg, typename std::index_sequence_for<Ts...>());
+}
+
+// Declared and documented above, but defined here so that any of the hashing
+// infrastructure is available.
+template <typename T>
+hash_code hash_value(const std::basic_string<T> &arg) {
+  return hash_combine_range(arg.begin(), arg.end());
+}
+
+template <> struct DenseMapInfo<hash_code, void> {
+  static inline hash_code getEmptyKey() { return hash_code(-1); }
+  static inline hash_code getTombstoneKey() { return hash_code(-2); }
+  static unsigned getHashValue(hash_code val) { return val; }
+  static bool isEqual(hash_code LHS, hash_code RHS) { return LHS == RHS; }
+};
+
+} // namespace wpi
+
+#ifdef _WIN32
+#pragma warning(pop)
+#endif
+
+#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/MapVector.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/MapVector.h
new file mode 100644
index 0000000..e4706c7
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/MapVector.h
@@ -0,0 +1,240 @@
+//===- llvm/ADT/MapVector.h - Map w/ deterministic value order --*- C++ -*-===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+///
+/// \file
+/// This file implements a map that provides insertion order iteration. The
+/// interface is purposefully minimal. The key is assumed to be cheap to copy
+/// and 2 copies are kept, one for indexing in a DenseMap, one for iteration in
+/// a std::vector.
+///
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_MAPVECTOR_H
+#define WPIUTIL_WPI_MAPVECTOR_H
+
+#include "wpi/DenseMap.h"
+#include "wpi/SmallVector.h"
+#include <cassert>
+#include <cstddef>
+#include <iterator>
+#include <type_traits>
+#include <utility>
+#include <vector>
+
+namespace wpi {
+
+/// This class implements a map that also provides access to all stored values
+/// in a deterministic order. The values are kept in a std::vector and the
+/// mapping is done with DenseMap from Keys to indexes in that vector.
+template<typename KeyT, typename ValueT,
+         typename MapType = DenseMap<KeyT, unsigned>,
+         typename VectorType = std::vector<std::pair<KeyT, ValueT>>>
+class MapVector {
+  MapType Map;
+  VectorType Vector;
+
+  static_assert(
+      std::is_integral<typename MapType::mapped_type>::value,
+      "The mapped_type of the specified Map must be an integral type");
+
+public:
+  using key_type = KeyT;
+  using value_type = typename VectorType::value_type;
+  using size_type = typename VectorType::size_type;
+
+  using iterator = typename VectorType::iterator;
+  using const_iterator = typename VectorType::const_iterator;
+  using reverse_iterator = typename VectorType::reverse_iterator;
+  using const_reverse_iterator = typename VectorType::const_reverse_iterator;
+
+  /// Clear the MapVector and return the underlying vector.
+  VectorType takeVector() {
+    Map.clear();
+    return std::move(Vector);
+  }
+
+  size_type size() const { return Vector.size(); }
+
+  /// Grow the MapVector so that it can contain at least \p NumEntries items
+  /// before resizing again.
+  void reserve(size_type NumEntries) {
+    Map.reserve(NumEntries);
+    Vector.reserve(NumEntries);
+  }
+
+  iterator begin() { return Vector.begin(); }
+  const_iterator begin() const { return Vector.begin(); }
+  iterator end() { return Vector.end(); }
+  const_iterator end() const { return Vector.end(); }
+
+  reverse_iterator rbegin() { return Vector.rbegin(); }
+  const_reverse_iterator rbegin() const { return Vector.rbegin(); }
+  reverse_iterator rend() { return Vector.rend(); }
+  const_reverse_iterator rend() const { return Vector.rend(); }
+
+  bool empty() const {
+    return Vector.empty();
+  }
+
+  std::pair<KeyT, ValueT>       &front()       { return Vector.front(); }
+  const std::pair<KeyT, ValueT> &front() const { return Vector.front(); }
+  std::pair<KeyT, ValueT>       &back()        { return Vector.back(); }
+  const std::pair<KeyT, ValueT> &back()  const { return Vector.back(); }
+
+  void clear() {
+    Map.clear();
+    Vector.clear();
+  }
+
+  void swap(MapVector &RHS) {
+    std::swap(Map, RHS.Map);
+    std::swap(Vector, RHS.Vector);
+  }
+
+  ValueT &operator[](const KeyT &Key) {
+    std::pair<KeyT, typename MapType::mapped_type> Pair = std::make_pair(Key, 0);
+    std::pair<typename MapType::iterator, bool> Result = Map.insert(Pair);
+    auto &I = Result.first->second;
+    if (Result.second) {
+      Vector.push_back(std::make_pair(Key, ValueT()));
+      I = Vector.size() - 1;
+    }
+    return Vector[I].second;
+  }
+
+  // Returns a copy of the value.  Only allowed if ValueT is copyable.
+  ValueT lookup(const KeyT &Key) const {
+    static_assert(std::is_copy_constructible<ValueT>::value,
+                  "Cannot call lookup() if ValueT is not copyable.");
+    typename MapType::const_iterator Pos = Map.find(Key);
+    return Pos == Map.end()? ValueT() : Vector[Pos->second].second;
+  }
+
+  std::pair<iterator, bool> insert(const std::pair<KeyT, ValueT> &KV) {
+    std::pair<KeyT, typename MapType::mapped_type> Pair = std::make_pair(KV.first, 0);
+    std::pair<typename MapType::iterator, bool> Result = Map.insert(Pair);
+    auto &I = Result.first->second;
+    if (Result.second) {
+      Vector.push_back(std::make_pair(KV.first, KV.second));
+      I = Vector.size() - 1;
+      return std::make_pair(std::prev(end()), true);
+    }
+    return std::make_pair(begin() + I, false);
+  }
+
+  std::pair<iterator, bool> insert(std::pair<KeyT, ValueT> &&KV) {
+    // Copy KV.first into the map, then move it into the vector.
+    std::pair<KeyT, typename MapType::mapped_type> Pair = std::make_pair(KV.first, 0);
+    std::pair<typename MapType::iterator, bool> Result = Map.insert(Pair);
+    auto &I = Result.first->second;
+    if (Result.second) {
+      Vector.push_back(std::move(KV));
+      I = Vector.size() - 1;
+      return std::make_pair(std::prev(end()), true);
+    }
+    return std::make_pair(begin() + I, false);
+  }
+
+  size_type count(const KeyT &Key) const {
+    typename MapType::const_iterator Pos = Map.find(Key);
+    return Pos == Map.end()? 0 : 1;
+  }
+
+  iterator find(const KeyT &Key) {
+    typename MapType::const_iterator Pos = Map.find(Key);
+    return Pos == Map.end()? Vector.end() :
+                            (Vector.begin() + Pos->second);
+  }
+
+  const_iterator find(const KeyT &Key) const {
+    typename MapType::const_iterator Pos = Map.find(Key);
+    return Pos == Map.end()? Vector.end() :
+                            (Vector.begin() + Pos->second);
+  }
+
+  /// Remove the last element from the vector.
+  void pop_back() {
+    typename MapType::iterator Pos = Map.find(Vector.back().first);
+    Map.erase(Pos);
+    Vector.pop_back();
+  }
+
+  /// Remove the element given by Iterator.
+  ///
+  /// Returns an iterator to the element following the one which was removed,
+  /// which may be end().
+  ///
+  /// \note This is a deceivingly expensive operation (linear time).  It's
+  /// usually better to use \a remove_if() if possible.
+  typename VectorType::iterator erase(typename VectorType::iterator Iterator) {
+    Map.erase(Iterator->first);
+    auto Next = Vector.erase(Iterator);
+    if (Next == Vector.end())
+      return Next;
+
+    // Update indices in the map.
+    size_t Index = Next - Vector.begin();
+    for (auto &I : Map) {
+      assert(I.second != Index && "Index was already erased!");
+      if (I.second > Index)
+        --I.second;
+    }
+    return Next;
+  }
+
+  /// Remove all elements with the key value Key.
+  ///
+  /// Returns the number of elements removed.
+  size_type erase(const KeyT &Key) {
+    auto Iterator = find(Key);
+    if (Iterator == end())
+      return 0;
+    erase(Iterator);
+    return 1;
+  }
+
+  /// Remove the elements that match the predicate.
+  ///
+  /// Erase all elements that match \c Pred in a single pass.  Takes linear
+  /// time.
+  template <class Predicate> void remove_if(Predicate Pred);
+};
+
+template <typename KeyT, typename ValueT, typename MapType, typename VectorType>
+template <class Function>
+void MapVector<KeyT, ValueT, MapType, VectorType>::remove_if(Function Pred) {
+  auto O = Vector.begin();
+  for (auto I = O, E = Vector.end(); I != E; ++I) {
+    if (Pred(*I)) {
+      // Erase from the map.
+      Map.erase(I->first);
+      continue;
+    }
+
+    if (I != O) {
+      // Move the value and update the index in the map.
+      *O = std::move(*I);
+      Map[O->first] = O - Vector.begin();
+    }
+    ++O;
+  }
+  // Erase trailing entries in the vector.
+  Vector.erase(O, Vector.end());
+}
+
+/// A MapVector that performs no allocations if smaller than a certain
+/// size.
+template <typename KeyT, typename ValueT, unsigned N>
+struct SmallMapVector
+    : MapVector<KeyT, ValueT, SmallDenseMap<KeyT, unsigned, N>,
+                SmallVector<std::pair<KeyT, ValueT>, N>> {
+};
+
+} // end namespace wpi
+
+#endif // WPIUTIL_WPI_MAPVECTOR_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/MathExtras.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/MathExtras.h
new file mode 100644
index 0000000..ea669ee
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/MathExtras.h
@@ -0,0 +1,955 @@
+//===-- llvm/Support/MathExtras.h - Useful math functions -------*- C++ -*-===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+//
+// This file contains some functions that are useful for math stuff.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_MATHEXTRAS_H
+#define WPIUTIL_WPI_MATHEXTRAS_H
+
+#include "wpi/Compiler.h"
+#include <cassert>
+#include <climits>
+#include <cmath>
+#include <cstdint>
+#include <cstring>
+#include <limits>
+#include <type_traits>
+
+#ifdef __ANDROID_NDK__
+#include <android/api-level.h>
+#endif
+
+#ifdef _MSC_VER
+// Declare these intrinsics manually rather including intrin.h. It's very
+// expensive, and MathExtras.h is popular.
+// #include <intrin.h>
+extern "C" {
+unsigned char _BitScanForward(unsigned long *_Index, unsigned long _Mask);
+unsigned char _BitScanForward64(unsigned long *_Index, unsigned __int64 _Mask);
+unsigned char _BitScanReverse(unsigned long *_Index, unsigned long _Mask);
+unsigned char _BitScanReverse64(unsigned long *_Index, unsigned __int64 _Mask);
+}
+#endif
+
+namespace wpi {
+
+/// The behavior an operation has on an input of 0.
+enum ZeroBehavior {
+  /// The returned value is undefined.
+  ZB_Undefined,
+  /// The returned value is numeric_limits<T>::max()
+  ZB_Max,
+  /// The returned value is numeric_limits<T>::digits
+  ZB_Width
+};
+
+namespace detail {
+template <typename T, std::size_t SizeOfT> struct TrailingZerosCounter {
+  static unsigned count(T Val, ZeroBehavior) {
+    if (!Val)
+      return std::numeric_limits<T>::digits;
+    if (Val & 0x1)
+      return 0;
+
+    // Bisection method.
+    unsigned ZeroBits = 0;
+    T Shift = std::numeric_limits<T>::digits >> 1;
+    T Mask = (std::numeric_limits<T>::max)() >> Shift;
+    while (Shift) {
+      if ((Val & Mask) == 0) {
+        Val >>= Shift;
+        ZeroBits |= Shift;
+      }
+      Shift >>= 1;
+      Mask >>= Shift;
+    }
+    return ZeroBits;
+  }
+};
+
+#if defined(__GNUC__) || defined(_MSC_VER)
+template <typename T> struct TrailingZerosCounter<T, 4> {
+  static unsigned count(T Val, ZeroBehavior ZB) {
+    if (ZB != ZB_Undefined && Val == 0)
+      return 32;
+
+#if __has_builtin(__builtin_ctz) || defined(__GNUC__)
+    return __builtin_ctz(Val);
+#elif defined(_MSC_VER)
+    unsigned long Index;
+    _BitScanForward(&Index, Val);
+    return Index;
+#endif
+  }
+};
+
+#if !defined(_MSC_VER) || defined(_M_X64)
+template <typename T> struct TrailingZerosCounter<T, 8> {
+  static unsigned count(T Val, ZeroBehavior ZB) {
+    if (ZB != ZB_Undefined && Val == 0)
+      return 64;
+
+#if __has_builtin(__builtin_ctzll) || defined(__GNUC__)
+    return __builtin_ctzll(Val);
+#elif defined(_MSC_VER)
+    unsigned long Index;
+    _BitScanForward64(&Index, Val);
+    return Index;
+#endif
+  }
+};
+#endif
+#endif
+} // namespace detail
+
+/// Count number of 0's from the least significant bit to the most
+///   stopping at the first 1.
+///
+/// Only unsigned integral types are allowed.
+///
+/// \param ZB the behavior on an input of 0. Only ZB_Width and ZB_Undefined are
+///   valid arguments.
+template <typename T>
+unsigned countTrailingZeros(T Val, ZeroBehavior ZB = ZB_Width) {
+  static_assert(std::numeric_limits<T>::is_integer &&
+                    !std::numeric_limits<T>::is_signed,
+                "Only unsigned integral types are allowed.");
+  return wpi::detail::TrailingZerosCounter<T, sizeof(T)>::count(Val, ZB);
+}
+
+namespace detail {
+template <typename T, std::size_t SizeOfT> struct LeadingZerosCounter {
+  static unsigned count(T Val, ZeroBehavior) {
+    if (!Val)
+      return std::numeric_limits<T>::digits;
+
+    // Bisection method.
+    unsigned ZeroBits = 0;
+    for (T Shift = std::numeric_limits<T>::digits >> 1; Shift; Shift >>= 1) {
+      T Tmp = Val >> Shift;
+      if (Tmp)
+        Val = Tmp;
+      else
+        ZeroBits |= Shift;
+    }
+    return ZeroBits;
+  }
+};
+
+#if defined(__GNUC__) || defined(_MSC_VER)
+template <typename T> struct LeadingZerosCounter<T, 4> {
+  static unsigned count(T Val, ZeroBehavior ZB) {
+    if (ZB != ZB_Undefined && Val == 0)
+      return 32;
+
+#if __has_builtin(__builtin_clz) || defined(__GNUC__)
+    return __builtin_clz(Val);
+#elif defined(_MSC_VER)
+    unsigned long Index;
+    _BitScanReverse(&Index, Val);
+    return Index ^ 31;
+#endif
+  }
+};
+
+#if !defined(_MSC_VER) || defined(_M_X64)
+template <typename T> struct LeadingZerosCounter<T, 8> {
+  static unsigned count(T Val, ZeroBehavior ZB) {
+    if (ZB != ZB_Undefined && Val == 0)
+      return 64;
+
+#if __has_builtin(__builtin_clzll) || defined(__GNUC__)
+    return __builtin_clzll(Val);
+#elif defined(_MSC_VER)
+    unsigned long Index;
+    _BitScanReverse64(&Index, Val);
+    return Index ^ 63;
+#endif
+  }
+};
+#endif
+#endif
+} // namespace detail
+
+/// Count number of 0's from the most significant bit to the least
+///   stopping at the first 1.
+///
+/// Only unsigned integral types are allowed.
+///
+/// \param ZB the behavior on an input of 0. Only ZB_Width and ZB_Undefined are
+///   valid arguments.
+template <typename T>
+unsigned countLeadingZeros(T Val, ZeroBehavior ZB = ZB_Width) {
+  static_assert(std::numeric_limits<T>::is_integer &&
+                    !std::numeric_limits<T>::is_signed,
+                "Only unsigned integral types are allowed.");
+  return wpi::detail::LeadingZerosCounter<T, sizeof(T)>::count(Val, ZB);
+}
+
+/// Get the index of the first set bit starting from the least
+///   significant bit.
+///
+/// Only unsigned integral types are allowed.
+///
+/// \param ZB the behavior on an input of 0. Only ZB_Max and ZB_Undefined are
+///   valid arguments.
+template <typename T> T findFirstSet(T Val, ZeroBehavior ZB = ZB_Max) {
+  if (ZB == ZB_Max && Val == 0)
+    return (std::numeric_limits<T>::max)();
+
+  return countTrailingZeros(Val, ZB_Undefined);
+}
+
+/// Create a bitmask with the N right-most bits set to 1, and all other
+/// bits set to 0.  Only unsigned types are allowed.
+template <typename T> T maskTrailingOnes(unsigned N) {
+  static_assert(std::is_unsigned<T>::value, "Invalid type!");
+  const unsigned Bits = CHAR_BIT * sizeof(T);
+  assert(N <= Bits && "Invalid bit index");
+  return N == 0 ? 0 : (T(-1) >> (Bits - N));
+}
+
+/// Create a bitmask with the N left-most bits set to 1, and all other
+/// bits set to 0.  Only unsigned types are allowed.
+template <typename T> T maskLeadingOnes(unsigned N) {
+  return ~maskTrailingOnes<T>(CHAR_BIT * sizeof(T) - N);
+}
+
+/// Create a bitmask with the N right-most bits set to 0, and all other
+/// bits set to 1.  Only unsigned types are allowed.
+template <typename T> T maskTrailingZeros(unsigned N) {
+  return maskLeadingOnes<T>(CHAR_BIT * sizeof(T) - N);
+}
+
+/// Create a bitmask with the N left-most bits set to 0, and all other
+/// bits set to 1.  Only unsigned types are allowed.
+template <typename T> T maskLeadingZeros(unsigned N) {
+  return maskTrailingOnes<T>(CHAR_BIT * sizeof(T) - N);
+}
+
+/// Get the index of the last set bit starting from the least
+///   significant bit.
+///
+/// Only unsigned integral types are allowed.
+///
+/// \param ZB the behavior on an input of 0. Only ZB_Max and ZB_Undefined are
+///   valid arguments.
+template <typename T> T findLastSet(T Val, ZeroBehavior ZB = ZB_Max) {
+  if (ZB == ZB_Max && Val == 0)
+    return (std::numeric_limits<T>::max)();
+
+  // Use ^ instead of - because both gcc and llvm can remove the associated ^
+  // in the __builtin_clz intrinsic on x86.
+  return countLeadingZeros(Val, ZB_Undefined) ^
+         (std::numeric_limits<T>::digits - 1);
+}
+
+/// Macro compressed bit reversal table for 256 bits.
+///
+/// http://graphics.stanford.edu/~seander/bithacks.html#BitReverseTable
+static const unsigned char BitReverseTable256[256] = {
+#define R2(n) n, n + 2 * 64, n + 1 * 64, n + 3 * 64
+#define R4(n) R2(n), R2(n + 2 * 16), R2(n + 1 * 16), R2(n + 3 * 16)
+#define R6(n) R4(n), R4(n + 2 * 4), R4(n + 1 * 4), R4(n + 3 * 4)
+  R6(0), R6(2), R6(1), R6(3)
+#undef R2
+#undef R4
+#undef R6
+};
+
+/// Reverse the bits in \p Val.
+template <typename T>
+T reverseBits(T Val) {
+  unsigned char in[sizeof(Val)];
+  unsigned char out[sizeof(Val)];
+  std::memcpy(in, &Val, sizeof(Val));
+  for (unsigned i = 0; i < sizeof(Val); ++i)
+    out[(sizeof(Val) - i) - 1] = BitReverseTable256[in[i]];
+  std::memcpy(&Val, out, sizeof(Val));
+  return Val;
+}
+
+#if __has_builtin(__builtin_bitreverse8)
+template<>
+inline uint8_t reverseBits<uint8_t>(uint8_t Val) {
+  return __builtin_bitreverse8(Val);
+}
+#endif
+
+#if __has_builtin(__builtin_bitreverse16)
+template<>
+inline uint16_t reverseBits<uint16_t>(uint16_t Val) {
+  return __builtin_bitreverse16(Val);
+}
+#endif
+
+#if __has_builtin(__builtin_bitreverse32)
+template<>
+inline uint32_t reverseBits<uint32_t>(uint32_t Val) {
+  return __builtin_bitreverse32(Val);
+}
+#endif
+
+#if __has_builtin(__builtin_bitreverse64)
+template<>
+inline uint64_t reverseBits<uint64_t>(uint64_t Val) {
+  return __builtin_bitreverse64(Val);
+}
+#endif
+
+// NOTE: The following support functions use the _32/_64 extensions instead of
+// type overloading so that signed and unsigned integers can be used without
+// ambiguity.
+
+/// Return the high 32 bits of a 64 bit value.
+constexpr inline uint32_t Hi_32(uint64_t Value) {
+  return static_cast<uint32_t>(Value >> 32);
+}
+
+/// Return the low 32 bits of a 64 bit value.
+constexpr inline uint32_t Lo_32(uint64_t Value) {
+  return static_cast<uint32_t>(Value);
+}
+
+/// Make a 64-bit integer from a high / low pair of 32-bit integers.
+constexpr inline uint64_t Make_64(uint32_t High, uint32_t Low) {
+  return ((uint64_t)High << 32) | (uint64_t)Low;
+}
+
+/// Checks if an integer fits into the given bit width.
+template <unsigned N> constexpr inline bool isInt(int64_t x) {
+  return N >= 64 || (-(INT64_C(1)<<(N-1)) <= x && x < (INT64_C(1)<<(N-1)));
+}
+// Template specializations to get better code for common cases.
+template <> constexpr inline bool isInt<8>(int64_t x) {
+  return static_cast<int8_t>(x) == x;
+}
+template <> constexpr inline bool isInt<16>(int64_t x) {
+  return static_cast<int16_t>(x) == x;
+}
+template <> constexpr inline bool isInt<32>(int64_t x) {
+  return static_cast<int32_t>(x) == x;
+}
+
+/// Checks if a signed integer is an N bit number shifted left by S.
+template <unsigned N, unsigned S>
+constexpr inline bool isShiftedInt(int64_t x) {
+  static_assert(
+      N > 0, "isShiftedInt<0> doesn't make sense (refers to a 0-bit number.");
+  static_assert(N + S <= 64, "isShiftedInt<N, S> with N + S > 64 is too wide.");
+  return isInt<N + S>(x) && (x % (UINT64_C(1) << S) == 0);
+}
+
+/// Checks if an unsigned integer fits into the given bit width.
+///
+/// This is written as two functions rather than as simply
+///
+///   return N >= 64 || X < (UINT64_C(1) << N);
+///
+/// to keep MSVC from (incorrectly) warning on isUInt<64> that we're shifting
+/// left too many places.
+template <unsigned N>
+constexpr inline std::enable_if_t<(N < 64), bool> isUInt(uint64_t X) {
+  static_assert(N > 0, "isUInt<0> doesn't make sense");
+  return X < (UINT64_C(1) << (N));
+}
+template <unsigned N>
+constexpr inline std::enable_if_t<N >= 64, bool> isUInt(uint64_t) {
+  return true;
+}
+
+// Template specializations to get better code for common cases.
+template <> constexpr inline bool isUInt<8>(uint64_t x) {
+  return static_cast<uint8_t>(x) == x;
+}
+template <> constexpr inline bool isUInt<16>(uint64_t x) {
+  return static_cast<uint16_t>(x) == x;
+}
+template <> constexpr inline bool isUInt<32>(uint64_t x) {
+  return static_cast<uint32_t>(x) == x;
+}
+
+/// Checks if a unsigned integer is an N bit number shifted left by S.
+template <unsigned N, unsigned S>
+constexpr inline bool isShiftedUInt(uint64_t x) {
+  static_assert(
+      N > 0, "isShiftedUInt<0> doesn't make sense (refers to a 0-bit number)");
+  static_assert(N + S <= 64,
+                "isShiftedUInt<N, S> with N + S > 64 is too wide.");
+  // Per the two static_asserts above, S must be strictly less than 64.  So
+  // 1 << S is not undefined behavior.
+  return isUInt<N + S>(x) && (x % (UINT64_C(1) << S) == 0);
+}
+
+/// Gets the maximum value for a N-bit unsigned integer.
+inline uint64_t maxUIntN(uint64_t N) {
+  assert(N > 0 && N <= 64 && "integer width out of range");
+
+  // uint64_t(1) << 64 is undefined behavior, so we can't do
+  //   (uint64_t(1) << N) - 1
+  // without checking first that N != 64.  But this works and doesn't have a
+  // branch.
+  return UINT64_MAX >> (64 - N);
+}
+
+#ifdef _WIN32
+#pragma warning(push)
+#pragma warning(disable : 4146)
+#endif
+
+/// Gets the minimum value for a N-bit signed integer.
+inline int64_t minIntN(int64_t N) {
+  assert(N > 0 && N <= 64 && "integer width out of range");
+
+  return UINT64_C(1) + ~(UINT64_C(1) << (N - 1));
+}
+
+#ifdef _WIN32
+#pragma warning(pop)
+#endif
+
+/// Gets the maximum value for a N-bit signed integer.
+inline int64_t maxIntN(int64_t N) {
+  assert(N > 0 && N <= 64 && "integer width out of range");
+
+  // This relies on two's complement wraparound when N == 64, so we convert to
+  // int64_t only at the very end to avoid UB.
+  return (UINT64_C(1) << (N - 1)) - 1;
+}
+
+/// Checks if an unsigned integer fits into the given (dynamic) bit width.
+inline bool isUIntN(unsigned N, uint64_t x) {
+  return N >= 64 || x <= maxUIntN(N);
+}
+
+/// Checks if an signed integer fits into the given (dynamic) bit width.
+inline bool isIntN(unsigned N, int64_t x) {
+  return N >= 64 || (minIntN(N) <= x && x <= maxIntN(N));
+}
+
+/// Return true if the argument is a non-empty sequence of ones starting at the
+/// least significant bit with the remainder zero (32 bit version).
+/// Ex. isMask_32(0x0000FFFFU) == true.
+constexpr inline bool isMask_32(uint32_t Value) {
+  return Value && ((Value + 1) & Value) == 0;
+}
+
+/// Return true if the argument is a non-empty sequence of ones starting at the
+/// least significant bit with the remainder zero (64 bit version).
+constexpr inline bool isMask_64(uint64_t Value) {
+  return Value && ((Value + 1) & Value) == 0;
+}
+
+/// Return true if the argument contains a non-empty sequence of ones with the
+/// remainder zero (32 bit version.) Ex. isShiftedMask_32(0x0000FF00U) == true.
+constexpr inline bool isShiftedMask_32(uint32_t Value) {
+  return Value && isMask_32((Value - 1) | Value);
+}
+
+/// Return true if the argument contains a non-empty sequence of ones with the
+/// remainder zero (64 bit version.)
+constexpr inline bool isShiftedMask_64(uint64_t Value) {
+  return Value && isMask_64((Value - 1) | Value);
+}
+
+/// Return true if the argument is a power of two > 0.
+/// Ex. isPowerOf2_32(0x00100000U) == true (32 bit edition.)
+constexpr inline bool isPowerOf2_32(uint32_t Value) {
+  return Value && !(Value & (Value - 1));
+}
+
+/// Return true if the argument is a power of two > 0 (64 bit edition.)
+constexpr inline bool isPowerOf2_64(uint64_t Value) {
+  return Value && !(Value & (Value - 1));
+}
+
+/// Count the number of ones from the most significant bit to the first
+/// zero bit.
+///
+/// Ex. countLeadingOnes(0xFF0FFF00) == 8.
+/// Only unsigned integral types are allowed.
+///
+/// \param ZB the behavior on an input of all ones. Only ZB_Width and
+/// ZB_Undefined are valid arguments.
+template <typename T>
+unsigned countLeadingOnes(T Value, ZeroBehavior ZB = ZB_Width) {
+  static_assert(std::numeric_limits<T>::is_integer &&
+                    !std::numeric_limits<T>::is_signed,
+                "Only unsigned integral types are allowed.");
+  return countLeadingZeros<T>(~Value, ZB);
+}
+
+/// Count the number of ones from the least significant bit to the first
+/// zero bit.
+///
+/// Ex. countTrailingOnes(0x00FF00FF) == 8.
+/// Only unsigned integral types are allowed.
+///
+/// \param ZB the behavior on an input of all ones. Only ZB_Width and
+/// ZB_Undefined are valid arguments.
+template <typename T>
+unsigned countTrailingOnes(T Value, ZeroBehavior ZB = ZB_Width) {
+  static_assert(std::numeric_limits<T>::is_integer &&
+                    !std::numeric_limits<T>::is_signed,
+                "Only unsigned integral types are allowed.");
+  return countTrailingZeros<T>(~Value, ZB);
+}
+
+namespace detail {
+template <typename T, std::size_t SizeOfT> struct PopulationCounter {
+  static unsigned count(T Value) {
+    // Generic version, forward to 32 bits.
+    static_assert(SizeOfT <= 4, "Not implemented!");
+#if defined(__GNUC__)
+    return __builtin_popcount(Value);
+#else
+    uint32_t v = Value;
+    v = v - ((v >> 1) & 0x55555555);
+    v = (v & 0x33333333) + ((v >> 2) & 0x33333333);
+    return ((v + (v >> 4) & 0xF0F0F0F) * 0x1010101) >> 24;
+#endif
+  }
+};
+
+template <typename T> struct PopulationCounter<T, 8> {
+  static unsigned count(T Value) {
+#if defined(__GNUC__)
+    return __builtin_popcountll(Value);
+#else
+    uint64_t v = Value;
+    v = v - ((v >> 1) & 0x5555555555555555ULL);
+    v = (v & 0x3333333333333333ULL) + ((v >> 2) & 0x3333333333333333ULL);
+    v = (v + (v >> 4)) & 0x0F0F0F0F0F0F0F0FULL;
+    return unsigned((uint64_t)(v * 0x0101010101010101ULL) >> 56);
+#endif
+  }
+};
+} // namespace detail
+
+/// Count the number of set bits in a value.
+/// Ex. countPopulation(0xF000F000) = 8
+/// Returns 0 if the word is zero.
+template <typename T>
+inline unsigned countPopulation(T Value) {
+  static_assert(std::numeric_limits<T>::is_integer &&
+                    !std::numeric_limits<T>::is_signed,
+                "Only unsigned integral types are allowed.");
+  return detail::PopulationCounter<T, sizeof(T)>::count(Value);
+}
+
+/// Compile time Log2.
+/// Valid only for positive powers of two.
+template <size_t kValue> constexpr inline size_t CTLog2() {
+  static_assert(kValue > 0 && wpi::isPowerOf2_64(kValue),
+                "Value is not a valid power of 2");
+  return 1 + CTLog2<kValue / 2>();
+}
+
+template <> constexpr inline size_t CTLog2<1>() { return 0; }
+
+/// Return the log base 2 of the specified value.
+inline double Log2(double Value) {
+#if defined(__ANDROID_API__) && __ANDROID_API__ < 18
+  return __builtin_log(Value) / __builtin_log(2.0);
+#else
+  return std::log2(Value);
+#endif
+}
+
+/// Return the floor log base 2 of the specified value, -1 if the value is zero.
+/// (32 bit edition.)
+/// Ex. Log2_32(32) == 5, Log2_32(1) == 0, Log2_32(0) == -1, Log2_32(6) == 2
+inline unsigned Log2_32(uint32_t Value) {
+  return static_cast<unsigned>(31 - countLeadingZeros(Value));
+}
+
+/// Return the floor log base 2 of the specified value, -1 if the value is zero.
+/// (64 bit edition.)
+inline unsigned Log2_64(uint64_t Value) {
+  return static_cast<unsigned>(63 - countLeadingZeros(Value));
+}
+
+/// Return the ceil log base 2 of the specified value, 32 if the value is zero.
+/// (32 bit edition).
+/// Ex. Log2_32_Ceil(32) == 5, Log2_32_Ceil(1) == 0, Log2_32_Ceil(6) == 3
+inline unsigned Log2_32_Ceil(uint32_t Value) {
+  return static_cast<unsigned>(32 - countLeadingZeros(Value - 1));
+}
+
+/// Return the ceil log base 2 of the specified value, 64 if the value is zero.
+/// (64 bit edition.)
+inline unsigned Log2_64_Ceil(uint64_t Value) {
+  return static_cast<unsigned>(64 - countLeadingZeros(Value - 1));
+}
+
+/// Return the greatest common divisor of the values using Euclid's algorithm.
+template <typename T>
+inline T greatestCommonDivisor(T A, T B) {
+  while (B) {
+    T Tmp = B;
+    B = A % B;
+    A = Tmp;
+  }
+  return A;
+}
+
+inline uint64_t GreatestCommonDivisor64(uint64_t A, uint64_t B) {
+  return greatestCommonDivisor<uint64_t>(A, B);
+}
+
+/// This function takes a 64-bit integer and returns the bit equivalent double.
+inline double BitsToDouble(uint64_t Bits) {
+  double D;
+  static_assert(sizeof(uint64_t) == sizeof(double), "Unexpected type sizes");
+  memcpy(&D, &Bits, sizeof(Bits));
+  return D;
+}
+
+/// This function takes a 32-bit integer and returns the bit equivalent float.
+inline float BitsToFloat(uint32_t Bits) {
+  float F;
+  static_assert(sizeof(uint32_t) == sizeof(float), "Unexpected type sizes");
+  memcpy(&F, &Bits, sizeof(Bits));
+  return F;
+}
+
+/// This function takes a double and returns the bit equivalent 64-bit integer.
+/// Note that copying doubles around changes the bits of NaNs on some hosts,
+/// notably x86, so this routine cannot be used if these bits are needed.
+inline uint64_t DoubleToBits(double Double) {
+  uint64_t Bits;
+  static_assert(sizeof(uint64_t) == sizeof(double), "Unexpected type sizes");
+  memcpy(&Bits, &Double, sizeof(Double));
+  return Bits;
+}
+
+/// This function takes a float and returns the bit equivalent 32-bit integer.
+/// Note that copying floats around changes the bits of NaNs on some hosts,
+/// notably x86, so this routine cannot be used if these bits are needed.
+inline uint32_t FloatToBits(float Float) {
+  uint32_t Bits;
+  static_assert(sizeof(uint32_t) == sizeof(float), "Unexpected type sizes");
+  memcpy(&Bits, &Float, sizeof(Float));
+  return Bits;
+}
+
+/// A and B are either alignments or offsets. Return the minimum alignment that
+/// may be assumed after adding the two together.
+constexpr inline uint64_t MinAlign(uint64_t A, uint64_t B) {
+  // The largest power of 2 that divides both A and B.
+  //
+  // Replace "-Value" by "1+~Value" in the following commented code to avoid
+  // MSVC warning C4146
+  //    return (A | B) & -(A | B);
+  return (A | B) & (1 + ~(A | B));
+}
+
+/// Returns the next power of two (in 64-bits) that is strictly greater than A.
+/// Returns zero on overflow.
+inline uint64_t NextPowerOf2(uint64_t A) {
+  A |= (A >> 1);
+  A |= (A >> 2);
+  A |= (A >> 4);
+  A |= (A >> 8);
+  A |= (A >> 16);
+  A |= (A >> 32);
+  return A + 1;
+}
+
+/// Returns the power of two which is less than or equal to the given value.
+/// Essentially, it is a floor operation across the domain of powers of two.
+inline uint64_t PowerOf2Floor(uint64_t A) {
+  if (!A) return 0;
+  return 1ull << (63 - countLeadingZeros(A, ZB_Undefined));
+}
+
+/// Returns the power of two which is greater than or equal to the given value.
+/// Essentially, it is a ceil operation across the domain of powers of two.
+inline uint64_t PowerOf2Ceil(uint64_t A) {
+  if (!A)
+    return 0;
+  return NextPowerOf2(A - 1);
+}
+
+/// Returns the next integer (mod 2**64) that is greater than or equal to
+/// \p Value and is a multiple of \p Align. \p Align must be non-zero.
+///
+/// If non-zero \p Skew is specified, the return value will be a minimal
+/// integer that is greater than or equal to \p Value and equal to
+/// \p Align * N + \p Skew for some integer N. If \p Skew is larger than
+/// \p Align, its value is adjusted to '\p Skew mod \p Align'.
+///
+/// Examples:
+/// \code
+///   alignTo(5, 8) = 8
+///   alignTo(17, 8) = 24
+///   alignTo(~0LL, 8) = 0
+///   alignTo(321, 255) = 510
+///
+///   alignTo(5, 8, 7) = 7
+///   alignTo(17, 8, 1) = 17
+///   alignTo(~0LL, 8, 3) = 3
+///   alignTo(321, 255, 42) = 552
+/// \endcode
+inline uint64_t alignTo(uint64_t Value, uint64_t Align, uint64_t Skew = 0) {
+  assert(Align != 0u && "Align can't be 0.");
+  Skew %= Align;
+  return (Value + Align - 1 - Skew) / Align * Align + Skew;
+}
+
+/// Returns the next integer (mod 2**64) that is greater than or equal to
+/// \p Value and is a multiple of \c Align. \c Align must be non-zero.
+template <uint64_t Align> constexpr inline uint64_t alignTo(uint64_t Value) {
+  static_assert(Align != 0u, "Align must be non-zero");
+  return (Value + Align - 1) / Align * Align;
+}
+
+/// Returns the integer ceil(Numerator / Denominator).
+inline uint64_t divideCeil(uint64_t Numerator, uint64_t Denominator) {
+  return alignTo(Numerator, Denominator) / Denominator;
+}
+
+/// Returns the integer nearest(Numerator / Denominator).
+inline uint64_t divideNearest(uint64_t Numerator, uint64_t Denominator) {
+  return (Numerator + (Denominator / 2)) / Denominator;
+}
+
+/// Returns the largest uint64_t less than or equal to \p Value and is
+/// \p Skew mod \p Align. \p Align must be non-zero
+inline uint64_t alignDown(uint64_t Value, uint64_t Align, uint64_t Skew = 0) {
+  assert(Align != 0u && "Align can't be 0.");
+  Skew %= Align;
+  return (Value - Skew) / Align * Align + Skew;
+}
+
+/// Sign-extend the number in the bottom B bits of X to a 32-bit integer.
+/// Requires 0 < B <= 32.
+template <unsigned B> constexpr inline int32_t SignExtend32(uint32_t X) {
+  static_assert(B > 0, "Bit width can't be 0.");
+  static_assert(B <= 32, "Bit width out of range.");
+  return int32_t(X << (32 - B)) >> (32 - B);
+}
+
+/// Sign-extend the number in the bottom B bits of X to a 32-bit integer.
+/// Requires 0 < B <= 32.
+inline int32_t SignExtend32(uint32_t X, unsigned B) {
+  assert(B > 0 && "Bit width can't be 0.");
+  assert(B <= 32 && "Bit width out of range.");
+  return int32_t(X << (32 - B)) >> (32 - B);
+}
+
+/// Sign-extend the number in the bottom B bits of X to a 64-bit integer.
+/// Requires 0 < B <= 64.
+template <unsigned B> constexpr inline int64_t SignExtend64(uint64_t x) {
+  static_assert(B > 0, "Bit width can't be 0.");
+  static_assert(B <= 64, "Bit width out of range.");
+  return int64_t(x << (64 - B)) >> (64 - B);
+}
+
+/// Sign-extend the number in the bottom B bits of X to a 64-bit integer.
+/// Requires 0 < B <= 64.
+inline int64_t SignExtend64(uint64_t X, unsigned B) {
+  assert(B > 0 && "Bit width can't be 0.");
+  assert(B <= 64 && "Bit width out of range.");
+  return int64_t(X << (64 - B)) >> (64 - B);
+}
+
+/// Subtract two unsigned integers, X and Y, of type T and return the absolute
+/// value of the result.
+template <typename T>
+std::enable_if_t<std::is_unsigned<T>::value, T> AbsoluteDifference(T X, T Y) {
+  return X > Y ? (X - Y) : (Y - X);
+}
+
+/// Add two unsigned integers, X and Y, of type T.  Clamp the result to the
+/// maximum representable value of T on overflow.  ResultOverflowed indicates if
+/// the result is larger than the maximum representable value of type T.
+template <typename T>
+std::enable_if_t<std::is_unsigned<T>::value, T>
+SaturatingAdd(T X, T Y, bool *ResultOverflowed = nullptr) {
+  bool Dummy;
+  bool &Overflowed = ResultOverflowed ? *ResultOverflowed : Dummy;
+  // Hacker's Delight, p. 29
+  T Z = X + Y;
+  Overflowed = (Z < X || Z < Y);
+  if (Overflowed)
+    return (std::numeric_limits<T>::max)();
+  else
+    return Z;
+}
+
+/// Multiply two unsigned integers, X and Y, of type T.  Clamp the result to the
+/// maximum representable value of T on overflow.  ResultOverflowed indicates if
+/// the result is larger than the maximum representable value of type T.
+template <typename T>
+std::enable_if_t<std::is_unsigned<T>::value, T>
+SaturatingMultiply(T X, T Y, bool *ResultOverflowed = nullptr) {
+  bool Dummy;
+  bool &Overflowed = ResultOverflowed ? *ResultOverflowed : Dummy;
+
+  // Hacker's Delight, p. 30 has a different algorithm, but we don't use that
+  // because it fails for uint16_t (where multiplication can have undefined
+  // behavior due to promotion to int), and requires a division in addition
+  // to the multiplication.
+
+  Overflowed = false;
+
+  // Log2(Z) would be either Log2Z or Log2Z + 1.
+  // Special case: if X or Y is 0, Log2_64 gives -1, and Log2Z
+  // will necessarily be less than Log2Max as desired.
+  int Log2Z = Log2_64(X) + Log2_64(Y);
+  const T Max = (std::numeric_limits<T>::max)();
+  int Log2Max = Log2_64(Max);
+  if (Log2Z < Log2Max) {
+    return X * Y;
+  }
+  if (Log2Z > Log2Max) {
+    Overflowed = true;
+    return Max;
+  }
+
+  // We're going to use the top bit, and maybe overflow one
+  // bit past it. Multiply all but the bottom bit then add
+  // that on at the end.
+  T Z = (X >> 1) * Y;
+  if (Z & ~(Max >> 1)) {
+    Overflowed = true;
+    return Max;
+  }
+  Z <<= 1;
+  if (X & 1)
+    return SaturatingAdd(Z, Y, ResultOverflowed);
+
+  return Z;
+}
+
+/// Multiply two unsigned integers, X and Y, and add the unsigned integer, A to
+/// the product. Clamp the result to the maximum representable value of T on
+/// overflow. ResultOverflowed indicates if the result is larger than the
+/// maximum representable value of type T.
+template <typename T>
+std::enable_if_t<std::is_unsigned<T>::value, T>
+SaturatingMultiplyAdd(T X, T Y, T A, bool *ResultOverflowed = nullptr) {
+  bool Dummy;
+  bool &Overflowed = ResultOverflowed ? *ResultOverflowed : Dummy;
+
+  T Product = SaturatingMultiply(X, Y, &Overflowed);
+  if (Overflowed)
+    return Product;
+
+  return SaturatingAdd(A, Product, &Overflowed);
+}
+
+/// Use this rather than HUGE_VALF; the latter causes warnings on MSVC.
+extern const float huge_valf;
+
+
+/// Add two signed integers, computing the two's complement truncated result,
+/// returning true if overflow occured.
+template <typename T>
+std::enable_if_t<std::is_signed<T>::value, T> AddOverflow(T X, T Y, T &Result) {
+#if __has_builtin(__builtin_add_overflow)
+  return __builtin_add_overflow(X, Y, &Result);
+#else
+  // Perform the unsigned addition.
+  using U = std::make_unsigned_t<T>;
+  const U UX = static_cast<U>(X);
+  const U UY = static_cast<U>(Y);
+  const U UResult = UX + UY;
+
+  // Convert to signed.
+  Result = static_cast<T>(UResult);
+
+  // Adding two positive numbers should result in a positive number.
+  if (X > 0 && Y > 0)
+    return Result <= 0;
+  // Adding two negatives should result in a negative number.
+  if (X < 0 && Y < 0)
+    return Result >= 0;
+  return false;
+#endif
+}
+
+/// Subtract two signed integers, computing the two's complement truncated
+/// result, returning true if an overflow ocurred.
+template <typename T>
+std::enable_if_t<std::is_signed<T>::value, T> SubOverflow(T X, T Y, T &Result) {
+#if __has_builtin(__builtin_sub_overflow)
+  return __builtin_sub_overflow(X, Y, &Result);
+#else
+  // Perform the unsigned addition.
+  using U = std::make_unsigned_t<T>;
+  const U UX = static_cast<U>(X);
+  const U UY = static_cast<U>(Y);
+  const U UResult = UX - UY;
+
+  // Convert to signed.
+  Result = static_cast<T>(UResult);
+
+  // Subtracting a positive number from a negative results in a negative number.
+  if (X <= 0 && Y > 0)
+    return Result >= 0;
+  // Subtracting a negative number from a positive results in a positive number.
+  if (X >= 0 && Y < 0)
+    return Result <= 0;
+  return false;
+#endif
+}
+
+/// Multiply two signed integers, computing the two's complement truncated
+/// result, returning true if an overflow ocurred.
+template <typename T>
+std::enable_if_t<std::is_signed<T>::value, T> MulOverflow(T X, T Y, T &Result) {
+  // Perform the unsigned multiplication on absolute values.
+  using U = std::make_unsigned_t<T>;
+  const U UX = X < 0 ? (0 - static_cast<U>(X)) : static_cast<U>(X);
+  const U UY = Y < 0 ? (0 - static_cast<U>(Y)) : static_cast<U>(Y);
+  const U UResult = UX * UY;
+
+  // Convert to signed.
+  const bool IsNegative = (X < 0) ^ (Y < 0);
+  Result = IsNegative ? (0 - UResult) : UResult;
+
+  // If any of the args was 0, result is 0 and no overflow occurs.
+  if (UX == 0 || UY == 0)
+    return false;
+
+  // UX and UY are in [1, 2^n], where n is the number of digits.
+  // Check how the max allowed absolute value (2^n for negative, 2^(n-1) for
+  // positive) divided by an argument compares to the other.
+  if (IsNegative)
+    return UX > (static_cast<U>((std::numeric_limits<T>::max)()) + U(1)) / UY;
+  else
+    return UX > (static_cast<U>((std::numeric_limits<T>::max)())) / UY;
+}
+
+// Typesafe implementation of the signum function.
+// Returns -1 if negative, 1 if positive, 0 if 0.
+template <typename T>
+constexpr int sgn(T val) {
+  return (T(0) < val) - (val < T(0));
+}
+
+/**
+ * Linearly interpolates between two values.
+ *
+ * @param startValue The start value.
+ * @param endValue The end value.
+ * @param t The fraction for interpolation.
+ *
+ * @return The interpolated value.
+ */
+template <typename T>
+constexpr T Lerp(const T& startValue, const T& endValue, double t) {
+  return startValue + (endValue - startValue) * t;
+}
+} // End wpi namespace
+
+#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/MemAlloc.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/MemAlloc.h
new file mode 100644
index 0000000..32909ff
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/MemAlloc.h
@@ -0,0 +1,100 @@
+//===- MemAlloc.h - Memory allocation functions -----------------*- C++ -*-===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+/// \file
+///
+/// This file defines counterparts of C library allocation functions defined in
+/// the namespace 'std'. The new allocation functions crash on allocation
+/// failure instead of returning null pointer.
+///
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_MEMALLOC_H
+#define WPIUTIL_WPI_MEMALLOC_H
+
+#include "wpi/Compiler.h"
+#include "wpi/ErrorHandling.h"
+#include <cstdlib>
+
+namespace wpi {
+
+#ifdef _WIN32
+#pragma warning(push)
+// Warning on NONNULL, report is not known to abort
+#pragma warning(disable : 6387)
+#pragma warning(disable : 28196)
+#pragma warning(disable : 28183)
+#endif
+
+LLVM_ATTRIBUTE_RETURNS_NONNULL inline void *safe_malloc(size_t Sz) {
+  void *Result = std::malloc(Sz);
+  if (Result == nullptr) {
+    // It is implementation-defined whether allocation occurs if the space
+    // requested is zero (ISO/IEC 9899:2018 7.22.3). Retry, requesting
+    // non-zero, if the space requested was zero.
+    if (Sz == 0)
+      return safe_malloc(1);
+    report_bad_alloc_error("Allocation failed");
+  }
+  return Result;
+}
+
+LLVM_ATTRIBUTE_RETURNS_NONNULL inline void *safe_calloc(size_t Count,
+                                                        size_t Sz) {
+  void *Result = std::calloc(Count, Sz);
+  if (Result == nullptr) {
+    // It is implementation-defined whether allocation occurs if the space
+    // requested is zero (ISO/IEC 9899:2018 7.22.3). Retry, requesting
+    // non-zero, if the space requested was zero.
+    if (Count == 0 || Sz == 0)
+      return safe_malloc(1);
+    report_bad_alloc_error("Allocation failed");
+  }
+  return Result;
+}
+
+LLVM_ATTRIBUTE_RETURNS_NONNULL inline void *safe_realloc(void *Ptr, size_t Sz) {
+  void *Result = std::realloc(Ptr, Sz);
+  if (Result == nullptr) {
+    // It is implementation-defined whether allocation occurs if the space
+    // requested is zero (ISO/IEC 9899:2018 7.22.3). Retry, requesting
+    // non-zero, if the space requested was zero.
+    if (Sz == 0)
+      return safe_malloc(1);
+    report_bad_alloc_error("Allocation failed");
+  }
+  return Result;
+}
+
+/// Allocate a buffer of memory with the given size and alignment.
+///
+/// When the compiler supports aligned operator new, this will use it to to
+/// handle even over-aligned allocations.
+///
+/// However, this doesn't make any attempt to leverage the fancier techniques
+/// like posix_memalign due to portability. It is mostly intended to allow
+/// compatibility with platforms that, after aligned allocation was added, use
+/// reduced default alignment.
+LLVM_ATTRIBUTE_RETURNS_NONNULL LLVM_ATTRIBUTE_RETURNS_NOALIAS void *
+allocate_buffer(size_t Size, size_t Alignment);
+
+/// Deallocate a buffer of memory with the given size and alignment.
+///
+/// If supported, this will used the sized delete operator. Also if supported,
+/// this will pass the alignment to the delete operator.
+///
+/// The pointer must have been allocated with the corresponding new operator,
+/// most likely using the above helper.
+void deallocate_buffer(void *Ptr, size_t Size, size_t Alignment);
+
+} // namespace wpi
+
+#ifdef _WIN32
+#pragma warning(pop)
+#endif
+
+#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/MemoryBuffer.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/MemoryBuffer.h
new file mode 100644
index 0000000..7907c07
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/MemoryBuffer.h
@@ -0,0 +1,239 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+//===--- MemoryBuffer.h - Memory Buffer Interface ---------------*- C++ -*-===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+//  This file defines the MemoryBuffer interface.
+//
+//===----------------------------------------------------------------------===//
+
+#pragma once
+
+#include <stdint.h>
+
+#include <cstddef>
+#include <memory>
+#include <span>
+#include <string_view>
+#include <system_error>
+
+// Duplicated from fs.h to avoid a dependency
+namespace fs {
+#if defined(_WIN32)
+// A Win32 HANDLE is a typedef of void*
+using file_t = void*;
+#else
+using file_t = int;
+#endif
+}  // namespace fs
+
+namespace wpi {
+
+class MemoryBufferRef;
+
+/// This interface provides simple read-only access to a block of memory, and
+/// provides simple methods for reading files and standard input into a memory
+/// buffer.
+class MemoryBuffer {
+  const uint8_t* m_bufferStart;  // Start of the buffer.
+  const uint8_t* m_bufferEnd;    // End of the buffer.
+
+ protected:
+  MemoryBuffer() = default;
+
+  void Init(const uint8_t* bufStart, const uint8_t* bufEnd);
+
+ public:
+  MemoryBuffer(const MemoryBuffer&) = delete;
+  MemoryBuffer& operator=(const MemoryBuffer&) = delete;
+  virtual ~MemoryBuffer();
+
+  const uint8_t* begin() const { return m_bufferStart; }
+  const uint8_t* end() const { return m_bufferEnd; }
+  size_t size() const { return m_bufferEnd - m_bufferStart; }
+
+  std::span<const uint8_t> GetBuffer() const { return {begin(), end()}; }
+
+  /// Return an identifier for this buffer, typically the filename it was read
+  /// from.
+  virtual std::string_view GetBufferIdentifier() const {
+    return "Unknown buffer";
+  }
+
+  /// Open the specified file as a MemoryBuffer, returning a new MemoryBuffer
+  /// if successful, otherwise returning null. If FileSize is specified, this
+  /// means that the client knows that the file exists and that it has the
+  /// specified size.
+  static std::unique_ptr<MemoryBuffer> GetFile(std::string_view filename,
+                                               std::error_code& ec,
+                                               int64_t fileSize = -1);
+
+  /// Read all of the specified file into a MemoryBuffer as a stream
+  /// (i.e. until EOF reached). This is useful for special files that
+  /// look like a regular file but have 0 size (e.g. /proc/cpuinfo on Linux).
+  static std::unique_ptr<MemoryBuffer> GetFileAsStream(
+      std::string_view filename, std::error_code& ec);
+
+  /// Given an already-open file descriptor, map some slice of it into a
+  /// MemoryBuffer. The slice is specified by an \p Offset and \p MapSize.
+  static std::unique_ptr<MemoryBuffer> GetOpenFileSlice(
+      fs::file_t f, std::string_view filename, std::error_code& ec,
+      uint64_t mapSize, int64_t offset);
+
+  /// Given an already-open file descriptor, read the file and return a
+  /// MemoryBuffer.
+  static std::unique_ptr<MemoryBuffer> GetOpenFile(fs::file_t f,
+                                                   std::string_view filename,
+                                                   std::error_code& ec,
+                                                   uint64_t fileSize);
+
+  /// Open the specified memory range as a MemoryBuffer.
+  static std::unique_ptr<MemoryBuffer> GetMemBuffer(
+      std::span<const uint8_t> inputData, std::string_view bufferName = "");
+
+  static std::unique_ptr<MemoryBuffer> GetMemBuffer(MemoryBufferRef ref);
+
+  /// Open the specified memory range as a MemoryBuffer, copying the contents
+  /// and taking ownership of it.
+  static std::unique_ptr<MemoryBuffer> GetMemBufferCopy(
+      std::span<const uint8_t> inputData, std::string_view bufferName = "");
+
+  /// Map a subrange of the specified file as a MemoryBuffer.
+  static std::unique_ptr<MemoryBuffer> GetFileSlice(std::string_view filename,
+                                                    std::error_code& ec,
+                                                    uint64_t mapSize,
+                                                    uint64_t offset);
+
+  //===--------------------------------------------------------------------===//
+  // Provided for performance analysis.
+  //===--------------------------------------------------------------------===//
+
+  /// The kind of memory backing used to support the MemoryBuffer.
+  enum BufferKind { MemoryBuffer_Malloc, MemoryBuffer_MMap };
+
+  /// Return information on the memory mechanism used to support the
+  /// MemoryBuffer.
+  virtual BufferKind GetBufferKind() const = 0;
+
+  MemoryBufferRef GetMemBufferRef() const;
+};
+
+/// This class is an extension of MemoryBuffer, which allows copy-on-write
+/// access to the underlying contents.  It only supports creation methods that
+/// are guaranteed to produce a writable buffer.  For example, mapping a file
+/// read-only is not supported.
+class WritableMemoryBuffer : public MemoryBuffer {
+ protected:
+  WritableMemoryBuffer() = default;
+
+ public:
+  using MemoryBuffer::begin;
+  using MemoryBuffer::end;
+  using MemoryBuffer::GetBuffer;
+  using MemoryBuffer::size;
+
+  // const_cast is well-defined here, because the underlying buffer is
+  // guaranteed to have been initialized with a mutable buffer.
+  uint8_t* begin() { return const_cast<uint8_t*>(MemoryBuffer::begin()); }
+  uint8_t* end() { return const_cast<uint8_t*>(MemoryBuffer::end()); }
+  std::span<uint8_t> GetBuffer() { return {begin(), end()}; }
+
+  static std::unique_ptr<WritableMemoryBuffer> GetFile(
+      std::string_view filename, std::error_code& ec, int64_t fileSize = -1);
+
+  /// Map a subrange of the specified file as a WritableMemoryBuffer.
+  static std::unique_ptr<WritableMemoryBuffer> GetFileSlice(
+      std::string_view filename, std::error_code& ec, uint64_t mapSize,
+      uint64_t offset);
+
+  /// Allocate a new MemoryBuffer of the specified size that is not initialized.
+  /// Note that the caller should initialize the memory allocated by this
+  /// method. The memory is owned by the MemoryBuffer object.
+  static std::unique_ptr<WritableMemoryBuffer> GetNewUninitMemBuffer(
+      size_t size, std::string_view bufferName = "");
+
+  /// Allocate a new zero-initialized MemoryBuffer of the specified size. Note
+  /// that the caller need not initialize the memory allocated by this method.
+  /// The memory is owned by the MemoryBuffer object.
+  static std::unique_ptr<WritableMemoryBuffer> GetNewMemBuffer(
+      size_t size, std::string_view bufferName = "");
+
+ private:
+  // Hide these base class factory function so one can't write
+  //   WritableMemoryBuffer::getXXX()
+  // and be surprised that they got a read-only Buffer.
+  using MemoryBuffer::GetFileAsStream;
+  using MemoryBuffer::GetMemBuffer;
+  using MemoryBuffer::GetMemBufferCopy;
+  using MemoryBuffer::GetOpenFile;
+  using MemoryBuffer::GetOpenFileSlice;
+};
+
+/// This class is an extension of MemoryBuffer, which allows write access to
+/// the underlying contents and committing those changes to the original source.
+/// It only supports creation methods that are guaranteed to produce a writable
+/// buffer.  For example, mapping a file read-only is not supported.
+class WriteThroughMemoryBuffer : public MemoryBuffer {
+ protected:
+  WriteThroughMemoryBuffer() = default;
+
+ public:
+  using MemoryBuffer::begin;
+  using MemoryBuffer::end;
+  using MemoryBuffer::GetBuffer;
+  using MemoryBuffer::size;
+
+  // const_cast is well-defined here, because the underlying buffer is
+  // guaranteed to have been initialized with a mutable buffer.
+  uint8_t* begin() { return const_cast<uint8_t*>(MemoryBuffer::begin()); }
+  uint8_t* end() { return const_cast<uint8_t*>(MemoryBuffer::end()); }
+  std::span<uint8_t> GetBuffer() { return {begin(), end()}; }
+
+  static std::unique_ptr<WriteThroughMemoryBuffer> GetFile(
+      std::string_view filename, std::error_code& ec, int64_t fileSize = -1);
+
+  /// Map a subrange of the specified file as a ReadWriteMemoryBuffer.
+  static std::unique_ptr<WriteThroughMemoryBuffer> GetFileSlice(
+      std::string_view filename, std::error_code& ec, uint64_t mapSize,
+      uint64_t offset);
+
+ private:
+  // Hide these base class factory function so one can't write
+  //   WritableMemoryBuffer::getXXX()
+  // and be surprised that they got a read-only Buffer.
+  using MemoryBuffer::GetFileAsStream;
+  using MemoryBuffer::GetMemBuffer;
+  using MemoryBuffer::GetMemBufferCopy;
+  using MemoryBuffer::GetOpenFile;
+  using MemoryBuffer::GetOpenFileSlice;
+};
+
+class MemoryBufferRef {
+  std::span<const uint8_t> m_buffer;
+  std::string_view m_id;
+
+ public:
+  MemoryBufferRef() = default;
+  MemoryBufferRef(MemoryBuffer& buffer)  // NOLINT
+      : m_buffer(buffer.GetBuffer()), m_id(buffer.GetBufferIdentifier()) {}
+  MemoryBufferRef(std::span<const uint8_t> buffer, std::string_view id)
+      : m_buffer(buffer), m_id(id) {}
+
+  std::span<const uint8_t> GetBuffer() const { return m_buffer; }
+
+  std::string_view GetBufferIdentifier() const { return m_id; }
+
+  const uint8_t* begin() const { return &*m_buffer.begin(); }
+  const uint8_t* end() const { return &*m_buffer.end(); }
+  size_t size() const { return m_buffer.size(); }
+};
+
+}  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/PointerIntPair.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/PointerIntPair.h
new file mode 100644
index 0000000..34ff4e1
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/PointerIntPair.h
@@ -0,0 +1,233 @@
+//===- llvm/ADT/PointerIntPair.h - Pair for pointer and int -----*- C++ -*-===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+///
+/// \file
+/// This file defines the PointerIntPair class.
+///
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_POINTERINTPAIR_H
+#define WPIUTIL_WPI_POINTERINTPAIR_H
+
+#include "wpi/Compiler.h"
+#include "wpi/PointerLikeTypeTraits.h"
+#include "wpi/type_traits.h"
+#include <cassert>
+#include <cstdint>
+#include <limits>
+
+namespace wpi {
+
+template <typename T, typename Enable> struct DenseMapInfo;
+template <typename PointerT, unsigned IntBits, typename PtrTraits>
+struct PointerIntPairInfo;
+
+/// PointerIntPair - This class implements a pair of a pointer and small
+/// integer.  It is designed to represent this in the space required by one
+/// pointer by bitmangling the integer into the low part of the pointer.  This
+/// can only be done for small integers: typically up to 3 bits, but it depends
+/// on the number of bits available according to PointerLikeTypeTraits for the
+/// type.
+///
+/// Note that PointerIntPair always puts the IntVal part in the highest bits
+/// possible.  For example, PointerIntPair<void*, 1, bool> will put the bit for
+/// the bool into bit #2, not bit #0, which allows the low two bits to be used
+/// for something else.  For example, this allows:
+///   PointerIntPair<PointerIntPair<void*, 1, bool>, 1, bool>
+/// ... and the two bools will land in different bits.
+template <typename PointerTy, unsigned IntBits, typename IntType = unsigned,
+          typename PtrTraits = PointerLikeTypeTraits<PointerTy>,
+          typename Info = PointerIntPairInfo<PointerTy, IntBits, PtrTraits>>
+class PointerIntPair {
+  // Used by MSVC visualizer and generally helpful for debugging/visualizing.
+  using InfoTy = Info;
+  intptr_t Value = 0;
+
+public:
+  constexpr PointerIntPair() = default;
+
+  PointerIntPair(PointerTy PtrVal, IntType IntVal) {
+    setPointerAndInt(PtrVal, IntVal);
+  }
+
+  explicit PointerIntPair(PointerTy PtrVal) { initWithPointer(PtrVal); }
+
+  PointerTy getPointer() const { return Info::getPointer(Value); }
+
+  IntType getInt() const { return (IntType)Info::getInt(Value); }
+
+  void setPointer(PointerTy PtrVal) LLVM_LVALUE_FUNCTION {
+    Value = Info::updatePointer(Value, PtrVal);
+  }
+
+  void setInt(IntType IntVal) LLVM_LVALUE_FUNCTION {
+    Value = Info::updateInt(Value, static_cast<intptr_t>(IntVal));
+  }
+
+  void initWithPointer(PointerTy PtrVal) LLVM_LVALUE_FUNCTION {
+    Value = Info::updatePointer(0, PtrVal);
+  }
+
+  void setPointerAndInt(PointerTy PtrVal, IntType IntVal) LLVM_LVALUE_FUNCTION {
+    Value = Info::updateInt(Info::updatePointer(0, PtrVal),
+                            static_cast<intptr_t>(IntVal));
+  }
+
+  PointerTy const *getAddrOfPointer() const {
+    return const_cast<PointerIntPair *>(this)->getAddrOfPointer();
+  }
+
+  PointerTy *getAddrOfPointer() {
+    assert(Value == reinterpret_cast<intptr_t>(getPointer()) &&
+           "Can only return the address if IntBits is cleared and "
+           "PtrTraits doesn't change the pointer");
+    return reinterpret_cast<PointerTy *>(&Value);
+  }
+
+  void *getOpaqueValue() const { return reinterpret_cast<void *>(Value); }
+
+  void setFromOpaqueValue(void *Val) LLVM_LVALUE_FUNCTION {
+    Value = reinterpret_cast<intptr_t>(Val);
+  }
+
+  static PointerIntPair getFromOpaqueValue(void *V) {
+    PointerIntPair P;
+    P.setFromOpaqueValue(V);
+    return P;
+  }
+
+  // Allow PointerIntPairs to be created from const void * if and only if the
+  // pointer type could be created from a const void *.
+  static PointerIntPair getFromOpaqueValue(const void *V) {
+    (void)PtrTraits::getFromVoidPointer(V);
+    return getFromOpaqueValue(const_cast<void *>(V));
+  }
+
+  bool operator==(const PointerIntPair &RHS) const {
+    return Value == RHS.Value;
+  }
+
+  bool operator!=(const PointerIntPair &RHS) const {
+    return Value != RHS.Value;
+  }
+
+  bool operator<(const PointerIntPair &RHS) const { return Value < RHS.Value; }
+  bool operator>(const PointerIntPair &RHS) const { return Value > RHS.Value; }
+
+  bool operator<=(const PointerIntPair &RHS) const {
+    return Value <= RHS.Value;
+  }
+
+  bool operator>=(const PointerIntPair &RHS) const {
+    return Value >= RHS.Value;
+  }
+};
+
+
+template <typename PointerT, unsigned IntBits, typename PtrTraits>
+struct PointerIntPairInfo {
+  static_assert(PtrTraits::NumLowBitsAvailable <
+                    std::numeric_limits<uintptr_t>::digits,
+                "cannot use a pointer type that has all bits free");
+  static_assert(IntBits <= PtrTraits::NumLowBitsAvailable,
+                "PointerIntPair with integer size too large for pointer");
+  enum MaskAndShiftConstants : uintptr_t {
+    /// PointerBitMask - The bits that come from the pointer.
+    PointerBitMask =
+        ~(uintptr_t)(((intptr_t)1 << PtrTraits::NumLowBitsAvailable) - 1),
+
+    /// IntShift - The number of low bits that we reserve for other uses, and
+    /// keep zero.
+    IntShift = (uintptr_t)PtrTraits::NumLowBitsAvailable - IntBits,
+
+    /// IntMask - This is the unshifted mask for valid bits of the int type.
+    IntMask = (uintptr_t)(((intptr_t)1 << IntBits) - 1),
+
+    // ShiftedIntMask - This is the bits for the integer shifted in place.
+    ShiftedIntMask = (uintptr_t)(IntMask << IntShift)
+  };
+
+  static PointerT getPointer(intptr_t Value) {
+    return PtrTraits::getFromVoidPointer(
+        reinterpret_cast<void *>(Value & PointerBitMask));
+  }
+
+  static intptr_t getInt(intptr_t Value) {
+    return (Value >> IntShift) & IntMask;
+  }
+
+  static intptr_t updatePointer(intptr_t OrigValue, PointerT Ptr) {
+    intptr_t PtrWord =
+        reinterpret_cast<intptr_t>(PtrTraits::getAsVoidPointer(Ptr));
+    assert((PtrWord & ~PointerBitMask) == 0 &&
+           "Pointer is not sufficiently aligned");
+    // Preserve all low bits, just update the pointer.
+    return PtrWord | (OrigValue & ~PointerBitMask);
+  }
+
+  static intptr_t updateInt(intptr_t OrigValue, intptr_t Int) {
+    intptr_t IntWord = static_cast<intptr_t>(Int);
+    assert((IntWord & ~IntMask) == 0 && "Integer too large for field");
+
+    // Preserve all bits other than the ones we are updating.
+    return (OrigValue & ~ShiftedIntMask) | IntWord << IntShift;
+  }
+};
+
+// Provide specialization of DenseMapInfo for PointerIntPair.
+template <typename PointerTy, unsigned IntBits, typename IntType>
+struct DenseMapInfo<PointerIntPair<PointerTy, IntBits, IntType>, void> {
+  using Ty = PointerIntPair<PointerTy, IntBits, IntType>;
+
+  static Ty getEmptyKey() {
+    uintptr_t Val = static_cast<uintptr_t>(-1);
+    Val <<= PointerLikeTypeTraits<Ty>::NumLowBitsAvailable;
+    return Ty::getFromOpaqueValue(reinterpret_cast<void *>(Val));
+  }
+
+  static Ty getTombstoneKey() {
+    uintptr_t Val = static_cast<uintptr_t>(-2);
+    Val <<= PointerLikeTypeTraits<PointerTy>::NumLowBitsAvailable;
+    return Ty::getFromOpaqueValue(reinterpret_cast<void *>(Val));
+  }
+
+  static unsigned getHashValue(Ty V) {
+    uintptr_t IV = reinterpret_cast<uintptr_t>(V.getOpaqueValue());
+    return unsigned(IV) ^ unsigned(IV >> 9);
+  }
+
+  static bool isEqual(const Ty &LHS, const Ty &RHS) { return LHS == RHS; }
+};
+
+// Teach SmallPtrSet that PointerIntPair is "basically a pointer".
+template <typename PointerTy, unsigned IntBits, typename IntType,
+          typename PtrTraits>
+struct PointerLikeTypeTraits<
+    PointerIntPair<PointerTy, IntBits, IntType, PtrTraits>> {
+  static inline void *
+  getAsVoidPointer(const PointerIntPair<PointerTy, IntBits, IntType> &P) {
+    return P.getOpaqueValue();
+  }
+
+  static inline PointerIntPair<PointerTy, IntBits, IntType>
+  getFromVoidPointer(void *P) {
+    return PointerIntPair<PointerTy, IntBits, IntType>::getFromOpaqueValue(P);
+  }
+
+  static inline PointerIntPair<PointerTy, IntBits, IntType>
+  getFromVoidPointer(const void *P) {
+    return PointerIntPair<PointerTy, IntBits, IntType>::getFromOpaqueValue(P);
+  }
+
+  static constexpr int NumLowBitsAvailable =
+      PtrTraits::NumLowBitsAvailable - IntBits;
+};
+
+} // end namespace wpi
+
+#endif // WPIUTIL_WPI_POINTERINTPAIR_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/PointerLikeTypeTraits.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/PointerLikeTypeTraits.h
new file mode 100644
index 0000000..ffca61a
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/PointerLikeTypeTraits.h
@@ -0,0 +1,152 @@
+//===- llvm/Support/PointerLikeTypeTraits.h - Pointer Traits ----*- C++ -*-===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+//
+// This file defines the PointerLikeTypeTraits class.  This allows data
+// structures to reason about pointers and other things that are pointer sized.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_POINTERLIKETYPETRAITS_H
+#define WPIUTIL_WPI_POINTERLIKETYPETRAITS_H
+
+#include <cassert>
+#include <cstdint>
+#include <type_traits>
+
+namespace wpi {
+
+/// A traits type that is used to handle pointer types and things that are just
+/// wrappers for pointers as a uniform entity.
+template <typename T> struct PointerLikeTypeTraits;
+
+namespace detail {
+/// A tiny meta function to compute the log2 of a compile time constant.
+template <size_t N>
+struct ConstantLog2
+    : std::integral_constant<size_t, ConstantLog2<N / 2>::value + 1> {};
+template <> struct ConstantLog2<1> : std::integral_constant<size_t, 0> {};
+
+// Provide a trait to check if T is pointer-like.
+template <typename T, typename U = void> struct HasPointerLikeTypeTraits {
+  static const bool value = false;
+};
+
+// sizeof(T) is valid only for a complete T.
+template <typename T>
+struct HasPointerLikeTypeTraits<
+    T, decltype((sizeof(PointerLikeTypeTraits<T>) + sizeof(T)), void())> {
+  static const bool value = true;
+};
+
+template <typename T> struct IsPointerLike {
+  static const bool value = HasPointerLikeTypeTraits<T>::value;
+};
+
+template <typename T> struct IsPointerLike<T *> {
+  static const bool value = true;
+};
+} // namespace detail
+
+// Provide PointerLikeTypeTraits for non-cvr pointers.
+template <typename T> struct PointerLikeTypeTraits<T *> {
+  static inline void *getAsVoidPointer(T *P) { return P; }
+  static inline T *getFromVoidPointer(void *P) { return static_cast<T *>(P); }
+
+  static constexpr int NumLowBitsAvailable =
+      detail::ConstantLog2<alignof(T)>::value;
+};
+
+template <> struct PointerLikeTypeTraits<void *> {
+  static inline void *getAsVoidPointer(void *P) { return P; }
+  static inline void *getFromVoidPointer(void *P) { return P; }
+
+  /// Note, we assume here that void* is related to raw malloc'ed memory and
+  /// that malloc returns objects at least 4-byte aligned. However, this may be
+  /// wrong, or pointers may be from something other than malloc. In this case,
+  /// you should specify a real typed pointer or avoid this template.
+  ///
+  /// All clients should use assertions to do a run-time check to ensure that
+  /// this is actually true.
+  static constexpr int NumLowBitsAvailable = 2;
+};
+
+// Provide PointerLikeTypeTraits for const things.
+template <typename T> struct PointerLikeTypeTraits<const T> {
+  typedef PointerLikeTypeTraits<T> NonConst;
+
+  static inline const void *getAsVoidPointer(const T P) {
+    return NonConst::getAsVoidPointer(P);
+  }
+  static inline const T getFromVoidPointer(const void *P) {
+    return NonConst::getFromVoidPointer(const_cast<void *>(P));
+  }
+  static constexpr int NumLowBitsAvailable = NonConst::NumLowBitsAvailable;
+};
+
+// Provide PointerLikeTypeTraits for const pointers.
+template <typename T> struct PointerLikeTypeTraits<const T *> {
+  typedef PointerLikeTypeTraits<T *> NonConst;
+
+  static inline const void *getAsVoidPointer(const T *P) {
+    return NonConst::getAsVoidPointer(const_cast<T *>(P));
+  }
+  static inline const T *getFromVoidPointer(const void *P) {
+    return NonConst::getFromVoidPointer(const_cast<void *>(P));
+  }
+  static constexpr int NumLowBitsAvailable = NonConst::NumLowBitsAvailable;
+};
+
+// Provide PointerLikeTypeTraits for uintptr_t.
+template <> struct PointerLikeTypeTraits<uintptr_t> {
+  static inline void *getAsVoidPointer(uintptr_t P) {
+    return reinterpret_cast<void *>(P);
+  }
+  static inline uintptr_t getFromVoidPointer(void *P) {
+    return reinterpret_cast<uintptr_t>(P);
+  }
+  // No bits are available!
+  static constexpr int NumLowBitsAvailable = 0;
+};
+
+/// Provide suitable custom traits struct for function pointers.
+///
+/// Function pointers can't be directly given these traits as functions can't
+/// have their alignment computed with `alignof` and we need different casting.
+///
+/// To rely on higher alignment for a specialized use, you can provide a
+/// customized form of this template explicitly with higher alignment, and
+/// potentially use alignment attributes on functions to satisfy that.
+template <int Alignment, typename FunctionPointerT>
+struct FunctionPointerLikeTypeTraits {
+  static constexpr int NumLowBitsAvailable =
+      detail::ConstantLog2<Alignment>::value;
+  static inline void *getAsVoidPointer(FunctionPointerT P) {
+    assert((reinterpret_cast<uintptr_t>(P) &
+            ~((uintptr_t)-1 << NumLowBitsAvailable)) == 0 &&
+           "Alignment not satisfied for an actual function pointer!");
+    return reinterpret_cast<void *>(P);
+  }
+  static inline FunctionPointerT getFromVoidPointer(void *P) {
+    return reinterpret_cast<FunctionPointerT>(P);
+  }
+};
+
+/// Provide a default specialization for function pointers that assumes 4-byte
+/// alignment.
+///
+/// We assume here that functions used with this are always at least 4-byte
+/// aligned. This means that, for example, thumb functions won't work or systems
+/// with weird unaligned function pointers won't work. But all practical systems
+/// we support satisfy this requirement.
+template <typename ReturnT, typename... ParamTs>
+struct PointerLikeTypeTraits<ReturnT (*)(ParamTs...)>
+    : FunctionPointerLikeTypeTraits<4, ReturnT (*)(ParamTs...)> {};
+
+} // end namespace wpi
+
+#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/PointerUnion.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/PointerUnion.h
new file mode 100644
index 0000000..cc12bbc
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/PointerUnion.h
@@ -0,0 +1,295 @@
+//===- llvm/ADT/PointerUnion.h - Discriminated Union of 2 Ptrs --*- C++ -*-===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+///
+/// \file
+/// This file defines the PointerUnion class, which is a discriminated union of
+/// pointer types.
+///
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_POINTERUNION_H
+#define WPIUTIL_WPI_POINTERUNION_H
+
+#include "wpi/DenseMapInfo.h"
+#include "wpi/PointerIntPair.h"
+#include "wpi/PointerLikeTypeTraits.h"
+#include <algorithm>
+#include <cassert>
+#include <cstddef>
+#include <cstdint>
+#include <type_traits>
+
+namespace wpi {
+
+namespace detail {
+template <typename T, typename... Us> struct TypesAreDistinct;
+template <typename T, typename... Us>
+struct TypesAreDistinct
+    : std::integral_constant<bool, !std::disjunction_v<std::is_same<T, Us>...> &&
+                                       TypesAreDistinct<Us...>::value> {};
+template <typename T> struct TypesAreDistinct<T> : std::true_type {};
+} // namespace detail
+
+/// Determine if all types in Ts are distinct.
+///
+/// Useful to statically assert when Ts is intended to describe a non-multi set
+/// of types.
+///
+/// Expensive (currently quadratic in sizeof(Ts...)), and so should only be
+/// asserted once per instantiation of a type which requires it.
+template <typename... Ts> struct TypesAreDistinct;
+template <> struct TypesAreDistinct<> : std::true_type {};
+template <typename... Ts>
+struct TypesAreDistinct
+    : std::integral_constant<bool, detail::TypesAreDistinct<Ts...>::value> {};
+
+/// Find the first index where a type appears in a list of types.
+///
+/// FirstIndexOfType<T, Us...>::value is the first index of T in Us.
+///
+/// Typically only meaningful when it is otherwise statically known that the
+/// type pack has no duplicate types. This should be guaranteed explicitly with
+/// static_assert(TypesAreDistinct<Us...>::value).
+///
+/// It is a compile-time error to instantiate when T is not present in Us, i.e.
+/// if is_one_of<T, Us...>::value is false.
+template <typename T, typename... Us> struct FirstIndexOfType;
+template <typename T, typename U, typename... Us>
+struct FirstIndexOfType<T, U, Us...>
+    : std::integral_constant<size_t, 1 + FirstIndexOfType<T, Us...>::value> {};
+template <typename T, typename... Us>
+struct FirstIndexOfType<T, T, Us...> : std::integral_constant<size_t, 0> {};
+
+/// Find the type at a given index in a list of types.
+///
+/// TypeAtIndex<I, Ts...> is the type at index I in Ts.
+template <size_t I, typename... Ts>
+using TypeAtIndex = std::tuple_element_t<I, std::tuple<Ts...>>;
+
+namespace pointer_union_detail {
+  /// Determine the number of bits required to store integers with values < n.
+  /// This is ceil(log2(n)).
+  constexpr int bitsRequired(unsigned n) {
+    return n > 1 ? 1 + bitsRequired((n + 1) / 2) : 0;
+  }
+
+  template <typename... Ts> constexpr int lowBitsAvailable() {
+    return std::min<int>({PointerLikeTypeTraits<Ts>::NumLowBitsAvailable...});
+  }
+
+  /// Find the first type in a list of types.
+  template <typename T, typename...> struct GetFirstType {
+    using type = T;
+  };
+
+  /// Provide PointerLikeTypeTraits for void* that is used by PointerUnion
+  /// for the template arguments.
+  template <typename ...PTs> class PointerUnionUIntTraits {
+  public:
+    static inline void *getAsVoidPointer(void *P) { return P; }
+    static inline void *getFromVoidPointer(void *P) { return P; }
+    static constexpr int NumLowBitsAvailable = lowBitsAvailable<PTs...>();
+  };
+
+  template <typename Derived, typename ValTy, int I, typename ...Types>
+  class PointerUnionMembers;
+
+  template <typename Derived, typename ValTy, int I>
+  class PointerUnionMembers<Derived, ValTy, I> {
+  protected:
+    ValTy Val;
+    PointerUnionMembers() = default;
+    PointerUnionMembers(ValTy Val) : Val(Val) {}
+
+    friend struct PointerLikeTypeTraits<Derived>;
+  };
+
+  template <typename Derived, typename ValTy, int I, typename Type,
+            typename ...Types>
+  class PointerUnionMembers<Derived, ValTy, I, Type, Types...>
+      : public PointerUnionMembers<Derived, ValTy, I + 1, Types...> {
+    using Base = PointerUnionMembers<Derived, ValTy, I + 1, Types...>;
+  public:
+    using Base::Base;
+    PointerUnionMembers() = default;
+    PointerUnionMembers(Type V)
+        : Base(ValTy(const_cast<void *>(
+                         PointerLikeTypeTraits<Type>::getAsVoidPointer(V)),
+                     I)) {}
+
+    using Base::operator=;
+    Derived &operator=(Type V) {
+      this->Val = ValTy(
+          const_cast<void *>(PointerLikeTypeTraits<Type>::getAsVoidPointer(V)),
+          I);
+      return static_cast<Derived &>(*this);
+    };
+  };
+}
+
+/// A discriminated union of two or more pointer types, with the discriminator
+/// in the low bit of the pointer.
+///
+/// This implementation is extremely efficient in space due to leveraging the
+/// low bits of the pointer, while exposing a natural and type-safe API.
+///
+/// Common use patterns would be something like this:
+///    PointerUnion<int*, float*> P;
+///    P = (int*)0;
+///    printf("%d %d", P.is<int*>(), P.is<float*>());  // prints "1 0"
+///    X = P.get<int*>();     // ok.
+///    Y = P.get<float*>();   // runtime assertion failure.
+///    Z = P.get<double*>();  // compile time failure.
+///    P = (float*)0;
+///    Y = P.get<float*>();   // ok.
+///    X = P.get<int*>();     // runtime assertion failure.
+///    PointerUnion<int*, int*> Q; // compile time failure.
+template <typename... PTs>
+class PointerUnion
+    : public pointer_union_detail::PointerUnionMembers<
+          PointerUnion<PTs...>,
+          PointerIntPair<
+              void *, pointer_union_detail::bitsRequired(sizeof...(PTs)), int,
+              pointer_union_detail::PointerUnionUIntTraits<PTs...>>,
+          0, PTs...> {
+  static_assert(TypesAreDistinct<PTs...>::value,
+                "PointerUnion alternative types cannot be repeated");
+  // The first type is special because we want to directly cast a pointer to a
+  // default-initialized union to a pointer to the first type. But we don't
+  // want PointerUnion to be a 'template <typename First, typename ...Rest>'
+  // because it's much more convenient to have a name for the whole pack. So
+  // split off the first type here.
+  using First = TypeAtIndex<0, PTs...>;
+  using Base = typename PointerUnion::PointerUnionMembers;
+
+public:
+  PointerUnion() = default;
+
+  PointerUnion(std::nullptr_t) : PointerUnion() {}
+  using Base::Base;
+
+  /// Test if the pointer held in the union is null, regardless of
+  /// which type it is.
+  bool isNull() const { return !this->Val.getPointer(); }
+
+  explicit operator bool() const { return !isNull(); }
+
+  /// Test if the Union currently holds the type matching T.
+  template <typename T> bool is() const {
+    return this->Val.getInt() == FirstIndexOfType<T, PTs...>::value;
+  }
+
+  /// Returns the value of the specified pointer type.
+  ///
+  /// If the specified pointer type is incorrect, assert.
+  template <typename T> T get() const {
+    assert(is<T>() && "Invalid accessor called");
+    return PointerLikeTypeTraits<T>::getFromVoidPointer(this->Val.getPointer());
+  }
+
+  /// Returns the current pointer if it is of the specified pointer type,
+  /// otherwise returns null.
+  template <typename T> T dyn_cast() const {
+    if (is<T>())
+      return get<T>();
+    return T();
+  }
+
+  /// If the union is set to the first pointer type get an address pointing to
+  /// it.
+  First const *getAddrOfPtr1() const {
+    return const_cast<PointerUnion *>(this)->getAddrOfPtr1();
+  }
+
+  /// If the union is set to the first pointer type get an address pointing to
+  /// it.
+  First *getAddrOfPtr1() {
+    assert(is<First>() && "Val is not the first pointer");
+    assert(
+        PointerLikeTypeTraits<First>::getAsVoidPointer(get<First>()) ==
+            this->Val.getPointer() &&
+        "Can't get the address because PointerLikeTypeTraits changes the ptr");
+    return const_cast<First *>(
+        reinterpret_cast<const First *>(this->Val.getAddrOfPointer()));
+  }
+
+  /// Assignment from nullptr which just clears the union.
+  const PointerUnion &operator=(std::nullptr_t) {
+    this->Val.initWithPointer(nullptr);
+    return *this;
+  }
+
+  /// Assignment from elements of the union.
+  using Base::operator=;
+
+  void *getOpaqueValue() const { return this->Val.getOpaqueValue(); }
+  static inline PointerUnion getFromOpaqueValue(void *VP) {
+    PointerUnion V;
+    V.Val = decltype(V.Val)::getFromOpaqueValue(VP);
+    return V;
+  }
+};
+
+template <typename ...PTs>
+bool operator==(PointerUnion<PTs...> lhs, PointerUnion<PTs...> rhs) {
+  return lhs.getOpaqueValue() == rhs.getOpaqueValue();
+}
+
+template <typename ...PTs>
+bool operator!=(PointerUnion<PTs...> lhs, PointerUnion<PTs...> rhs) {
+  return lhs.getOpaqueValue() != rhs.getOpaqueValue();
+}
+
+template <typename ...PTs>
+bool operator<(PointerUnion<PTs...> lhs, PointerUnion<PTs...> rhs) {
+  return lhs.getOpaqueValue() < rhs.getOpaqueValue();
+}
+
+// Teach SmallPtrSet that PointerUnion is "basically a pointer", that has
+// # low bits available = min(PT1bits,PT2bits)-1.
+template <typename ...PTs>
+struct PointerLikeTypeTraits<PointerUnion<PTs...>> {
+  static inline void *getAsVoidPointer(const PointerUnion<PTs...> &P) {
+    return P.getOpaqueValue();
+  }
+
+  static inline PointerUnion<PTs...> getFromVoidPointer(void *P) {
+    return PointerUnion<PTs...>::getFromOpaqueValue(P);
+  }
+
+  // The number of bits available are the min of the pointer types minus the
+  // bits needed for the discriminator.
+  static constexpr int NumLowBitsAvailable = PointerLikeTypeTraits<decltype(
+      PointerUnion<PTs...>::Val)>::NumLowBitsAvailable;
+};
+
+// Teach DenseMap how to use PointerUnions as keys.
+template <typename ...PTs> struct DenseMapInfo<PointerUnion<PTs...>> {
+  using Union = PointerUnion<PTs...>;
+  using FirstInfo =
+      DenseMapInfo<typename pointer_union_detail::GetFirstType<PTs...>::type>;
+
+  static inline Union getEmptyKey() { return Union(FirstInfo::getEmptyKey()); }
+
+  static inline Union getTombstoneKey() {
+    return Union(FirstInfo::getTombstoneKey());
+  }
+
+  static unsigned getHashValue(const Union &UnionVal) {
+    intptr_t key = (intptr_t)UnionVal.getOpaqueValue();
+    return DenseMapInfo<intptr_t>::getHashValue(key);
+  }
+
+  static bool isEqual(const Union &LHS, const Union &RHS) {
+    return LHS == RHS;
+  }
+};
+
+} // end namespace wpi
+
+#endif // WPIUTIL_WPI_POINTERUNION_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/ReverseIteration.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/ReverseIteration.h
new file mode 100644
index 0000000..f46d38d
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/ReverseIteration.h
@@ -0,0 +1,18 @@
+#ifndef WPIUTIL_WPI_REVERSEITERATION_H
+#define WPIUTIL_WPI_REVERSEITERATION_H
+
+#include "wpi/PointerLikeTypeTraits.h"
+
+namespace wpi {
+
+template<class T = void *>
+bool shouldReverseIterate() {
+#if LLVM_ENABLE_REVERSE_ITERATION
+  return detail::IsPointerLike<T>::value;
+#else
+  return false;
+#endif
+}
+
+}
+#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/STLForwardCompat.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/STLForwardCompat.h
new file mode 100644
index 0000000..7f8f068
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/STLForwardCompat.h
@@ -0,0 +1,83 @@
+//===- STLForwardCompat.h - Library features from future STLs ------C++ -*-===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+///
+/// \file
+/// This file contains library features backported from future STL versions.
+///
+/// These should be replaced with their STL counterparts as the C++ version LLVM
+/// is compiled with is updated.
+///
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_STLFORWARDCOMPAT_H
+#define WPIUTIL_WPI_STLFORWARDCOMPAT_H
+
+#include <type_traits>
+
+namespace wpi {
+
+//===----------------------------------------------------------------------===//
+//     Features from C++17
+//===----------------------------------------------------------------------===//
+
+template <typename T>
+struct negation // NOLINT(readability-identifier-naming)
+    : std::integral_constant<bool, !bool(T::value)> {};
+
+template <typename...>
+struct conjunction // NOLINT(readability-identifier-naming)
+    : std::true_type {};
+template <typename B1> struct conjunction<B1> : B1 {};
+template <typename B1, typename... Bn>
+struct conjunction<B1, Bn...>
+    : std::conditional<bool(B1::value), conjunction<Bn...>, B1>::type {};
+
+template <typename...>
+struct disjunction // NOLINT(readability-identifier-naming)
+    : std::false_type {};
+template <typename B1> struct disjunction<B1> : B1 {};
+template <typename B1, typename... Bn>
+struct disjunction<B1, Bn...>
+    : std::conditional<bool(B1::value), B1, disjunction<Bn...>>::type {};
+
+struct in_place_t // NOLINT(readability-identifier-naming)
+{
+  explicit in_place_t() = default;
+};
+/// \warning This must not be odr-used, as it cannot be made \c inline in C++14.
+constexpr in_place_t in_place; // NOLINT(readability-identifier-naming)
+
+template <typename T>
+struct in_place_type_t // NOLINT(readability-identifier-naming)
+{
+  explicit in_place_type_t() = default;
+};
+
+template <std::size_t I>
+struct in_place_index_t // NOLINT(readability-identifier-naming)
+{
+  explicit in_place_index_t() = default;
+};
+
+//===----------------------------------------------------------------------===//
+//     Features from C++20
+//===----------------------------------------------------------------------===//
+
+template <typename T>
+struct remove_cvref // NOLINT(readability-identifier-naming)
+{
+  using type = std::remove_cv_t<std::remove_reference_t<T>>;
+};
+
+template <typename T>
+using remove_cvref_t // NOLINT(readability-identifier-naming)
+    = typename wpi::remove_cvref<T>::type;
+
+} // namespace wpi
+
+#endif // WPIUTIL_WPI_STLFORWARDCOMPAT_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/SmallPtrSet.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/SmallPtrSet.h
new file mode 100644
index 0000000..1ada1e0
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/SmallPtrSet.h
@@ -0,0 +1,518 @@
+//===- llvm/ADT/SmallPtrSet.h - 'Normally small' pointer set ----*- C++ -*-===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+///
+/// \file
+/// This file defines the SmallPtrSet class.  See the doxygen comment for
+/// SmallPtrSetImplBase for more details on the algorithm used.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_SMALLPTRSET_H
+#define WPIUTIL_WPI_SMALLPTRSET_H
+
+#include "wpi/EpochTracker.h"
+#include "wpi/Compiler.h"
+#include "wpi/ReverseIteration.h"
+#include "wpi/type_traits.h"
+#include <cassert>
+#include <cstddef>
+#include <cstdlib>
+#include <cstring>
+#include <initializer_list>
+#include <iterator>
+#include <utility>
+
+namespace wpi {
+
+/// SmallPtrSetImplBase - This is the common code shared among all the
+/// SmallPtrSet<>'s, which is almost everything.  SmallPtrSet has two modes, one
+/// for small and one for large sets.
+///
+/// Small sets use an array of pointers allocated in the SmallPtrSet object,
+/// which is treated as a simple array of pointers.  When a pointer is added to
+/// the set, the array is scanned to see if the element already exists, if not
+/// the element is 'pushed back' onto the array.  If we run out of space in the
+/// array, we grow into the 'large set' case.  SmallSet should be used when the
+/// sets are often small.  In this case, no memory allocation is used, and only
+/// light-weight and cache-efficient scanning is used.
+///
+/// Large sets use a classic exponentially-probed hash table.  Empty buckets are
+/// represented with an illegal pointer value (-1) to allow null pointers to be
+/// inserted.  Tombstones are represented with another illegal pointer value
+/// (-2), to allow deletion.  The hash table is resized when the table is 3/4 or
+/// more.  When this happens, the table is doubled in size.
+///
+class SmallPtrSetImplBase : public DebugEpochBase {
+  friend class SmallPtrSetIteratorImpl;
+
+protected:
+  /// SmallArray - Points to a fixed size set of buckets, used in 'small mode'.
+  const void **SmallArray;
+  /// CurArray - This is the current set of buckets.  If equal to SmallArray,
+  /// then the set is in 'small mode'.
+  const void **CurArray;
+  /// CurArraySize - The allocated size of CurArray, always a power of two.
+  unsigned CurArraySize;
+
+  /// Number of elements in CurArray that contain a value or are a tombstone.
+  /// If small, all these elements are at the beginning of CurArray and the rest
+  /// is uninitialized.
+  unsigned NumNonEmpty;
+  /// Number of tombstones in CurArray.
+  unsigned NumTombstones;
+
+  // Helpers to copy and move construct a SmallPtrSet.
+  SmallPtrSetImplBase(const void **SmallStorage,
+                      const SmallPtrSetImplBase &that);
+  SmallPtrSetImplBase(const void **SmallStorage, unsigned SmallSize,
+                      SmallPtrSetImplBase &&that);
+
+  explicit SmallPtrSetImplBase(const void **SmallStorage, unsigned SmallSize)
+      : SmallArray(SmallStorage), CurArray(SmallStorage),
+        CurArraySize(SmallSize), NumNonEmpty(0), NumTombstones(0) {
+    assert(SmallSize && (SmallSize & (SmallSize-1)) == 0 &&
+           "Initial size must be a power of two!");
+  }
+
+  ~SmallPtrSetImplBase() {
+    if (!isSmall())
+      free(CurArray);
+  }
+
+public:
+  using size_type = unsigned;
+
+  SmallPtrSetImplBase &operator=(const SmallPtrSetImplBase &) = delete;
+
+  LLVM_NODISCARD bool empty() const { return size() == 0; }
+  size_type size() const { return NumNonEmpty - NumTombstones; }
+
+  void clear() {
+    incrementEpoch();
+    // If the capacity of the array is huge, and the # elements used is small,
+    // shrink the array.
+    if (!isSmall()) {
+      if (size() * 4 < CurArraySize && CurArraySize > 32)
+        return shrink_and_clear();
+      // Fill the array with empty markers.
+      memset(CurArray, -1, CurArraySize * sizeof(void *));
+    }
+
+    NumNonEmpty = 0;
+    NumTombstones = 0;
+  }
+
+protected:
+  static void *getTombstoneMarker() { return reinterpret_cast<void*>(-2); }
+
+  static void *getEmptyMarker() {
+    // Note that -1 is chosen to make clear() efficiently implementable with
+    // memset and because it's not a valid pointer value.
+    return reinterpret_cast<void*>(-1);
+  }
+
+  const void **EndPointer() const {
+    return isSmall() ? CurArray + NumNonEmpty : CurArray + CurArraySize;
+  }
+
+  /// insert_imp - This returns true if the pointer was new to the set, false if
+  /// it was already in the set.  This is hidden from the client so that the
+  /// derived class can check that the right type of pointer is passed in.
+  std::pair<const void *const *, bool> insert_imp(const void *Ptr) {
+    if (isSmall()) {
+      // Check to see if it is already in the set.
+      const void **LastTombstone = nullptr;
+      for (const void **APtr = SmallArray, **E = SmallArray + NumNonEmpty;
+           APtr != E; ++APtr) {
+        const void *Value = *APtr;
+        if (Value == Ptr)
+          return std::make_pair(APtr, false);
+        if (Value == getTombstoneMarker())
+          LastTombstone = APtr;
+      }
+
+      // Did we find any tombstone marker?
+      if (LastTombstone != nullptr) {
+        *LastTombstone = Ptr;
+        --NumTombstones;
+        incrementEpoch();
+        return std::make_pair(LastTombstone, true);
+      }
+
+      // Nope, there isn't.  If we stay small, just 'pushback' now.
+      if (NumNonEmpty < CurArraySize) {
+        SmallArray[NumNonEmpty++] = Ptr;
+        incrementEpoch();
+        return std::make_pair(SmallArray + (NumNonEmpty - 1), true);
+      }
+      // Otherwise, hit the big set case, which will call grow.
+    }
+    return insert_imp_big(Ptr);
+  }
+
+  /// erase_imp - If the set contains the specified pointer, remove it and
+  /// return true, otherwise return false.  This is hidden from the client so
+  /// that the derived class can check that the right type of pointer is passed
+  /// in.
+  bool erase_imp(const void * Ptr) {
+    const void *const *P = find_imp(Ptr);
+    if (P == EndPointer())
+      return false;
+
+    const void **Loc = const_cast<const void **>(P);
+    assert(*Loc == Ptr && "broken find!");
+    *Loc = getTombstoneMarker();
+    NumTombstones++;
+    return true;
+  }
+
+  /// Returns the raw pointer needed to construct an iterator.  If element not
+  /// found, this will be EndPointer.  Otherwise, it will be a pointer to the
+  /// slot which stores Ptr;
+  const void *const * find_imp(const void * Ptr) const {
+    if (isSmall()) {
+      // Linear search for the item.
+      for (const void *const *APtr = SmallArray,
+                      *const *E = SmallArray + NumNonEmpty; APtr != E; ++APtr)
+        if (*APtr == Ptr)
+          return APtr;
+      return EndPointer();
+    }
+
+    // Big set case.
+    auto *Bucket = FindBucketFor(Ptr);
+    if (*Bucket == Ptr)
+      return Bucket;
+    return EndPointer();
+  }
+
+private:
+  bool isSmall() const { return CurArray == SmallArray; }
+
+  std::pair<const void *const *, bool> insert_imp_big(const void *Ptr);
+
+  const void * const *FindBucketFor(const void *Ptr) const;
+  void shrink_and_clear();
+
+  /// Grow - Allocate a larger backing store for the buckets and move it over.
+  void Grow(unsigned NewSize);
+
+protected:
+  /// swap - Swaps the elements of two sets.
+  /// Note: This method assumes that both sets have the same small size.
+  void swap(SmallPtrSetImplBase &RHS);
+
+  void CopyFrom(const SmallPtrSetImplBase &RHS);
+  void MoveFrom(unsigned SmallSize, SmallPtrSetImplBase &&RHS);
+
+private:
+  /// Code shared by MoveFrom() and move constructor.
+  void MoveHelper(unsigned SmallSize, SmallPtrSetImplBase &&RHS);
+  /// Code shared by CopyFrom() and copy constructor.
+  void CopyHelper(const SmallPtrSetImplBase &RHS);
+};
+
+/// SmallPtrSetIteratorImpl - This is the common base class shared between all
+/// instances of SmallPtrSetIterator.
+class SmallPtrSetIteratorImpl {
+protected:
+  const void *const *Bucket;
+  const void *const *End;
+
+public:
+  explicit SmallPtrSetIteratorImpl(const void *const *BP, const void*const *E)
+    : Bucket(BP), End(E) {
+    if (shouldReverseIterate()) {
+      RetreatIfNotValid();
+      return;
+    }
+    AdvanceIfNotValid();
+  }
+
+  bool operator==(const SmallPtrSetIteratorImpl &RHS) const {
+    return Bucket == RHS.Bucket;
+  }
+  bool operator!=(const SmallPtrSetIteratorImpl &RHS) const {
+    return Bucket != RHS.Bucket;
+  }
+
+protected:
+  /// AdvanceIfNotValid - If the current bucket isn't valid, advance to a bucket
+  /// that is.   This is guaranteed to stop because the end() bucket is marked
+  /// valid.
+  void AdvanceIfNotValid() {
+    assert(Bucket <= End);
+    while (Bucket != End &&
+           (*Bucket == SmallPtrSetImplBase::getEmptyMarker() ||
+            *Bucket == SmallPtrSetImplBase::getTombstoneMarker()))
+      ++Bucket;
+  }
+  void RetreatIfNotValid() {
+    assert(Bucket >= End);
+    while (Bucket != End &&
+           (Bucket[-1] == SmallPtrSetImplBase::getEmptyMarker() ||
+            Bucket[-1] == SmallPtrSetImplBase::getTombstoneMarker())) {
+      --Bucket;
+    }
+  }
+};
+
+/// SmallPtrSetIterator - This implements a const_iterator for SmallPtrSet.
+template <typename PtrTy>
+class SmallPtrSetIterator : public SmallPtrSetIteratorImpl,
+                            DebugEpochBase::HandleBase {
+  using PtrTraits = PointerLikeTypeTraits<PtrTy>;
+
+public:
+  using value_type = PtrTy;
+  using reference = PtrTy;
+  using pointer = PtrTy;
+  using difference_type = std::ptrdiff_t;
+  using iterator_category = std::forward_iterator_tag;
+
+  explicit SmallPtrSetIterator(const void *const *BP, const void *const *E,
+                               const DebugEpochBase &Epoch)
+      : SmallPtrSetIteratorImpl(BP, E), DebugEpochBase::HandleBase(&Epoch) {}
+
+  // Most methods are provided by the base class.
+
+  const PtrTy operator*() const {
+    assert(isHandleInSync() && "invalid iterator access!");
+    if (shouldReverseIterate()) {
+      assert(Bucket > End);
+      return PtrTraits::getFromVoidPointer(const_cast<void *>(Bucket[-1]));
+    }
+    assert(Bucket < End);
+    return PtrTraits::getFromVoidPointer(const_cast<void*>(*Bucket));
+  }
+
+  inline SmallPtrSetIterator& operator++() {          // Preincrement
+    assert(isHandleInSync() && "invalid iterator access!");
+    if (shouldReverseIterate()) {
+      --Bucket;
+      RetreatIfNotValid();
+      return *this;
+    }
+    ++Bucket;
+    AdvanceIfNotValid();
+    return *this;
+  }
+
+  SmallPtrSetIterator operator++(int) {        // Postincrement
+    SmallPtrSetIterator tmp = *this;
+    ++*this;
+    return tmp;
+  }
+};
+
+/// RoundUpToPowerOfTwo - This is a helper template that rounds N up to the next
+/// power of two (which means N itself if N is already a power of two).
+template<unsigned N>
+struct RoundUpToPowerOfTwo;
+
+/// RoundUpToPowerOfTwoH - If N is not a power of two, increase it.  This is a
+/// helper template used to implement RoundUpToPowerOfTwo.
+template<unsigned N, bool isPowerTwo>
+struct RoundUpToPowerOfTwoH {
+  enum { Val = N };
+};
+template<unsigned N>
+struct RoundUpToPowerOfTwoH<N, false> {
+  enum {
+    // We could just use NextVal = N+1, but this converges faster.  N|(N-1) sets
+    // the right-most zero bits to one all at once, e.g. 0b0011000 -> 0b0011111.
+    Val = RoundUpToPowerOfTwo<(N|(N-1)) + 1>::Val
+  };
+};
+
+template<unsigned N>
+struct RoundUpToPowerOfTwo {
+  enum { Val = RoundUpToPowerOfTwoH<N, (N&(N-1)) == 0>::Val };
+};
+
+/// A templated base class for \c SmallPtrSet which provides the
+/// typesafe interface that is common across all small sizes.
+///
+/// This is particularly useful for passing around between interface boundaries
+/// to avoid encoding a particular small size in the interface boundary.
+template <typename PtrType>
+class SmallPtrSetImpl : public SmallPtrSetImplBase {
+  using ConstPtrType = typename add_const_past_pointer<PtrType>::type;
+  using PtrTraits = PointerLikeTypeTraits<PtrType>;
+  using ConstPtrTraits = PointerLikeTypeTraits<ConstPtrType>;
+
+protected:
+  // Forward constructors to the base.
+  using SmallPtrSetImplBase::SmallPtrSetImplBase;
+
+public:
+  using iterator = SmallPtrSetIterator<PtrType>;
+  using const_iterator = SmallPtrSetIterator<PtrType>;
+  using key_type = ConstPtrType;
+  using value_type = PtrType;
+
+  SmallPtrSetImpl(const SmallPtrSetImpl &) = delete;
+
+  /// Inserts Ptr if and only if there is no element in the container equal to
+  /// Ptr. The bool component of the returned pair is true if and only if the
+  /// insertion takes place, and the iterator component of the pair points to
+  /// the element equal to Ptr.
+  std::pair<iterator, bool> insert(PtrType Ptr) {
+    auto p = insert_imp(PtrTraits::getAsVoidPointer(Ptr));
+    return std::make_pair(makeIterator(p.first), p.second);
+  }
+
+  /// Insert the given pointer with an iterator hint that is ignored. This is
+  /// identical to calling insert(Ptr), but allows SmallPtrSet to be used by
+  /// std::insert_iterator and std::inserter().
+  iterator insert(iterator, PtrType Ptr) {
+    return insert(Ptr).first;
+  }
+
+  /// erase - If the set contains the specified pointer, remove it and return
+  /// true, otherwise return false.
+  bool erase(PtrType Ptr) {
+    return erase_imp(PtrTraits::getAsVoidPointer(Ptr));
+  }
+  /// count - Return 1 if the specified pointer is in the set, 0 otherwise.
+  size_type count(ConstPtrType Ptr) const {
+    return find_imp(ConstPtrTraits::getAsVoidPointer(Ptr)) != EndPointer();
+  }
+  iterator find(ConstPtrType Ptr) const {
+    return makeIterator(find_imp(ConstPtrTraits::getAsVoidPointer(Ptr)));
+  }
+  bool contains(ConstPtrType Ptr) const {
+    return find_imp(ConstPtrTraits::getAsVoidPointer(Ptr)) != EndPointer();
+  }
+
+  template <typename IterT>
+  void insert(IterT I, IterT E) {
+    for (; I != E; ++I)
+      insert(*I);
+  }
+
+  void insert(std::initializer_list<PtrType> IL) {
+    insert(IL.begin(), IL.end());
+  }
+
+  iterator begin() const {
+    if (shouldReverseIterate())
+      return makeIterator(EndPointer() - 1);
+    return makeIterator(CurArray);
+  }
+  iterator end() const { return makeIterator(EndPointer()); }
+
+private:
+  /// Create an iterator that dereferences to same place as the given pointer.
+  iterator makeIterator(const void *const *P) const {
+    if (shouldReverseIterate())
+      return iterator(P == EndPointer() ? CurArray : P + 1, CurArray, *this);
+    return iterator(P, EndPointer(), *this);
+  }
+};
+
+/// Equality comparison for SmallPtrSet.
+///
+/// Iterates over elements of LHS confirming that each value from LHS is also in
+/// RHS, and that no additional values are in RHS.
+template <typename PtrType>
+bool operator==(const SmallPtrSetImpl<PtrType> &LHS,
+                const SmallPtrSetImpl<PtrType> &RHS) {
+  if (LHS.size() != RHS.size())
+    return false;
+
+  for (const auto *KV : LHS)
+    if (!RHS.count(KV))
+      return false;
+
+  return true;
+}
+
+/// Inequality comparison for SmallPtrSet.
+///
+/// Equivalent to !(LHS == RHS).
+template <typename PtrType>
+bool operator!=(const SmallPtrSetImpl<PtrType> &LHS,
+                const SmallPtrSetImpl<PtrType> &RHS) {
+  return !(LHS == RHS);
+}
+
+/// SmallPtrSet - This class implements a set which is optimized for holding
+/// SmallSize or less elements.  This internally rounds up SmallSize to the next
+/// power of two if it is not already a power of two.  See the comments above
+/// SmallPtrSetImplBase for details of the algorithm.
+template<class PtrType, unsigned SmallSize>
+class SmallPtrSet : public SmallPtrSetImpl<PtrType> {
+  // In small mode SmallPtrSet uses linear search for the elements, so it is
+  // not a good idea to choose this value too high. You may consider using a
+  // DenseSet<> instead if you expect many elements in the set.
+  static_assert(SmallSize <= 32, "SmallSize should be small");
+
+  using BaseT = SmallPtrSetImpl<PtrType>;
+
+  // Make sure that SmallSize is a power of two, round up if not.
+  enum { SmallSizePowTwo = RoundUpToPowerOfTwo<SmallSize>::Val };
+  /// SmallStorage - Fixed size storage used in 'small mode'.
+  const void *SmallStorage[SmallSizePowTwo];
+
+public:
+  SmallPtrSet() : BaseT(SmallStorage, SmallSizePowTwo) {}
+  SmallPtrSet(const SmallPtrSet &that) : BaseT(SmallStorage, that) {}
+  SmallPtrSet(SmallPtrSet &&that)
+      : BaseT(SmallStorage, SmallSizePowTwo, std::move(that)) {}
+
+  template<typename It>
+  SmallPtrSet(It I, It E) : BaseT(SmallStorage, SmallSizePowTwo) {
+    this->insert(I, E);
+  }
+
+  SmallPtrSet(std::initializer_list<PtrType> IL)
+      : BaseT(SmallStorage, SmallSizePowTwo) {
+    this->insert(IL.begin(), IL.end());
+  }
+
+  SmallPtrSet<PtrType, SmallSize> &
+  operator=(const SmallPtrSet<PtrType, SmallSize> &RHS) {
+    if (&RHS != this)
+      this->CopyFrom(RHS);
+    return *this;
+  }
+
+  SmallPtrSet<PtrType, SmallSize> &
+  operator=(SmallPtrSet<PtrType, SmallSize> &&RHS) {
+    if (&RHS != this)
+      this->MoveFrom(SmallSizePowTwo, std::move(RHS));
+    return *this;
+  }
+
+  SmallPtrSet<PtrType, SmallSize> &
+  operator=(std::initializer_list<PtrType> IL) {
+    this->clear();
+    this->insert(IL.begin(), IL.end());
+    return *this;
+  }
+
+  /// swap - Swaps the elements of two sets.
+  void swap(SmallPtrSet<PtrType, SmallSize> &RHS) {
+    SmallPtrSetImplBase::swap(RHS);
+  }
+};
+
+} // end namespace wpi
+
+namespace std {
+
+  /// Implement std::swap in terms of SmallPtrSet swap.
+  template<class T, unsigned N>
+  inline void swap(wpi::SmallPtrSet<T, N> &LHS, wpi::SmallPtrSet<T, N> &RHS) {
+    LHS.swap(RHS);
+  }
+
+} // end namespace std
+
+#endif // WPIUTIL_WPI_SMALLPTRSET_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/SmallSet.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/SmallSet.h
new file mode 100644
index 0000000..7b1b283
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/SmallSet.h
@@ -0,0 +1,286 @@
+//===- llvm/ADT/SmallSet.h - 'Normally small' sets --------------*- C++ -*-===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+///
+/// \file
+/// This file defines the SmallSet class.
+///
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_SMALLSET_H
+#define WPIUTIL_WPI_SMALLSET_H
+
+#include "wpi/SmallPtrSet.h"
+#include "wpi/SmallVector.h"
+#include "wpi/iterator.h"
+#include "wpi/Compiler.h"
+#include "wpi/type_traits.h"
+#include <cstddef>
+#include <functional>
+#include <optional>
+#include <set>
+#include <type_traits>
+#include <utility>
+
+namespace wpi {
+
+/// SmallSetIterator - This class implements a const_iterator for SmallSet by
+/// delegating to the underlying SmallVector or Set iterators.
+template <typename T, unsigned N, typename C>
+class SmallSetIterator
+    : public iterator_facade_base<SmallSetIterator<T, N, C>,
+                                  std::forward_iterator_tag, T> {
+private:
+  using SetIterTy = typename std::set<T, C>::const_iterator;
+  using VecIterTy = typename SmallVector<T, N>::const_iterator;
+  using SelfTy = SmallSetIterator<T, N, C>;
+
+  /// Iterators to the parts of the SmallSet containing the data. They are set
+  /// depending on isSmall.
+  union {
+    SetIterTy SetIter;
+    VecIterTy VecIter;
+  };
+
+  bool isSmall;
+
+public:
+  SmallSetIterator(SetIterTy SetIter) : SetIter(SetIter), isSmall(false) {}
+
+  SmallSetIterator(VecIterTy VecIter) : VecIter(VecIter), isSmall(true) {}
+
+  // Spell out destructor, copy/move constructor and assignment operators for
+  // MSVC STL, where set<T>::const_iterator is not trivially copy constructible.
+  ~SmallSetIterator() {
+    if (isSmall)
+      VecIter.~VecIterTy();
+    else
+      SetIter.~SetIterTy();
+  }
+
+  SmallSetIterator(const SmallSetIterator &Other) : isSmall(Other.isSmall) {
+    if (isSmall)
+      VecIter = Other.VecIter;
+    else
+      // Use placement new, to make sure SetIter is properly constructed, even
+      // if it is not trivially copy-able (e.g. in MSVC).
+      new (&SetIter) SetIterTy(Other.SetIter);
+  }
+
+  SmallSetIterator(SmallSetIterator &&Other) : isSmall(Other.isSmall) {
+    if (isSmall)
+      VecIter = std::move(Other.VecIter);
+    else
+      // Use placement new, to make sure SetIter is properly constructed, even
+      // if it is not trivially copy-able (e.g. in MSVC).
+      new (&SetIter) SetIterTy(std::move(Other.SetIter));
+  }
+
+  SmallSetIterator& operator=(const SmallSetIterator& Other) {
+    // Call destructor for SetIter, so it gets properly destroyed if it is
+    // not trivially destructible in case we are setting VecIter.
+    if (!isSmall)
+      SetIter.~SetIterTy();
+
+    isSmall = Other.isSmall;
+    if (isSmall)
+      VecIter = Other.VecIter;
+    else
+      new (&SetIter) SetIterTy(Other.SetIter);
+    return *this;
+  }
+
+  SmallSetIterator& operator=(SmallSetIterator&& Other) {
+    // Call destructor for SetIter, so it gets properly destroyed if it is
+    // not trivially destructible in case we are setting VecIter.
+    if (!isSmall)
+      SetIter.~SetIterTy();
+
+    isSmall = Other.isSmall;
+    if (isSmall)
+      VecIter = std::move(Other.VecIter);
+    else
+      new (&SetIter) SetIterTy(std::move(Other.SetIter));
+    return *this;
+  }
+
+  bool operator==(const SmallSetIterator &RHS) const {
+    if (isSmall != RHS.isSmall)
+      return false;
+    if (isSmall)
+      return VecIter == RHS.VecIter;
+    return SetIter == RHS.SetIter;
+  }
+
+  SmallSetIterator &operator++() { // Preincrement
+    if (isSmall)
+      VecIter++;
+    else
+      SetIter++;
+    return *this;
+  }
+
+  const T &operator*() const { return isSmall ? *VecIter : *SetIter; }
+};
+
+/// SmallSet - This maintains a set of unique values, optimizing for the case
+/// when the set is small (less than N).  In this case, the set can be
+/// maintained with no mallocs.  If the set gets large, we expand to using an
+/// std::set to maintain reasonable lookup times.
+template <typename T, unsigned N, typename C = std::less<T>>
+class SmallSet {
+  /// Use a SmallVector to hold the elements here (even though it will never
+  /// reach its 'large' stage) to avoid calling the default ctors of elements
+  /// we will never use.
+  SmallVector<T, N> Vector;
+  std::set<T, C> Set;
+
+  using VIterator = typename SmallVector<T, N>::const_iterator;
+  using mutable_iterator = typename SmallVector<T, N>::iterator;
+
+  // In small mode SmallPtrSet uses linear search for the elements, so it is
+  // not a good idea to choose this value too high. You may consider using a
+  // DenseSet<> instead if you expect many elements in the set.
+  static_assert(N <= 32, "N should be small");
+
+public:
+  using size_type = size_t;
+  using const_iterator = SmallSetIterator<T, N, C>;
+
+  SmallSet() = default;
+
+  LLVM_NODISCARD bool empty() const {
+    return Vector.empty() && Set.empty();
+  }
+
+  size_type size() const {
+    return isSmall() ? Vector.size() : Set.size();
+  }
+
+  /// count - Return 1 if the element is in the set, 0 otherwise.
+  size_type count(const T &V) const {
+    if (isSmall()) {
+      // Since the collection is small, just do a linear search.
+      return vfind(V) == Vector.end() ? 0 : 1;
+    } else {
+      return Set.count(V);
+    }
+  }
+
+  /// insert - Insert an element into the set if it isn't already there.
+  /// Returns true if the element is inserted (it was not in the set before).
+  /// The first value of the returned pair is unused and provided for
+  /// partial compatibility with the standard library self-associative container
+  /// concept.
+  // FIXME: Add iterators that abstract over the small and large form, and then
+  // return those here.
+  std::pair<std::nullopt_t, bool> insert(const T &V) {
+    if (!isSmall())
+      return std::make_pair(std::nullopt, Set.insert(V).second);
+
+    VIterator I = vfind(V);
+    if (I != Vector.end())    // Don't reinsert if it already exists.
+      return std::make_pair(std::nullopt, false);
+    if (Vector.size() < N) {
+      Vector.push_back(V);
+      return std::make_pair(std::nullopt, true);
+    }
+
+    // Otherwise, grow from vector to set.
+    while (!Vector.empty()) {
+      Set.insert(Vector.back());
+      Vector.pop_back();
+    }
+    Set.insert(V);
+    return std::make_pair(std::nullopt, true);
+  }
+
+  template <typename IterT>
+  void insert(IterT I, IterT E) {
+    for (; I != E; ++I)
+      insert(*I);
+  }
+
+  bool erase(const T &V) {
+    if (!isSmall())
+      return Set.erase(V);
+    for (mutable_iterator I = Vector.begin(), E = Vector.end(); I != E; ++I)
+      if (*I == V) {
+        Vector.erase(I);
+        return true;
+      }
+    return false;
+  }
+
+  void clear() {
+    Vector.clear();
+    Set.clear();
+  }
+
+  const_iterator begin() const {
+    if (isSmall())
+      return {Vector.begin()};
+    return {Set.begin()};
+  }
+
+  const_iterator end() const {
+    if (isSmall())
+      return {Vector.end()};
+    return {Set.end()};
+  }
+
+  /// Check if the SmallSet contains the given element.
+  bool contains(const T &V) const {
+    if (isSmall())
+      return vfind(V) != Vector.end();
+    return Set.find(V) != Set.end();
+  }
+
+private:
+  bool isSmall() const { return Set.empty(); }
+
+  VIterator vfind(const T &V) const {
+    for (VIterator I = Vector.begin(), E = Vector.end(); I != E; ++I)
+      if (*I == V)
+        return I;
+    return Vector.end();
+  }
+};
+
+/// If this set is of pointer values, transparently switch over to using
+/// SmallPtrSet for performance.
+template <typename PointeeType, unsigned N>
+class SmallSet<PointeeType*, N> : public SmallPtrSet<PointeeType*, N> {};
+
+/// Equality comparison for SmallSet.
+///
+/// Iterates over elements of LHS confirming that each element is also a member
+/// of RHS, and that RHS contains no additional values.
+/// Equivalent to N calls to RHS.count.
+/// For small-set mode amortized complexity is O(N^2)
+/// For large-set mode amortized complexity is linear, worst case is O(N^2) (if
+/// every hash collides).
+template <typename T, unsigned LN, unsigned RN, typename C>
+bool operator==(const SmallSet<T, LN, C> &LHS, const SmallSet<T, RN, C> &RHS) {
+  if (LHS.size() != RHS.size())
+    return false;
+
+  // All elements in LHS must also be in RHS
+  return std::all_of(LHS.begin(), LHS.end(), [&RHS](const T &E) { return RHS.count(E); });
+}
+
+/// Inequality comparison for SmallSet.
+///
+/// Equivalent to !(LHS == RHS). See operator== for performance notes.
+template <typename T, unsigned LN, unsigned RN, typename C>
+bool operator!=(const SmallSet<T, LN, C> &LHS, const SmallSet<T, RN, C> &RHS) {
+  return !(LHS == RHS);
+}
+
+} // end namespace wpi
+
+#endif // WPIUTIL_WPI_SMALLSET_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/SmallString.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/SmallString.h
new file mode 100644
index 0000000..4a53fee
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/SmallString.h
@@ -0,0 +1,215 @@
+//===- llvm/ADT/SmallString.h - 'Normally small' strings --------*- C++ -*-===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+///
+/// \file
+/// This file defines the SmallString class.
+///
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_SMALLSTRING_H
+#define WPIUTIL_WPI_SMALLSTRING_H
+
+#include "wpi/SmallVector.h"
+#include <cstddef>
+#include <string>
+#include <string_view>
+
+namespace wpi {
+
+/// SmallString - A SmallString is just a SmallVector with methods and accessors
+/// that make it work better as a string (e.g. operator+ etc).
+template<unsigned InternalLen>
+class SmallString : public SmallVector<char, InternalLen> {
+public:
+  /// Default ctor - Initialize to empty.
+  SmallString() = default;
+
+  /// Initialize from a std::string_view.
+  SmallString(std::string_view S) : SmallVector<char, InternalLen>(S.begin(), S.end()) {}
+
+  /// Initialize by concatenating a list of std::string_views.
+  SmallString(std::initializer_list<std::string_view> Refs)
+      : SmallVector<char, InternalLen>() {
+    this->append(Refs);
+  }
+
+  /// Initialize with a range.
+  template<typename ItTy>
+  SmallString(ItTy S, ItTy E) : SmallVector<char, InternalLen>(S, E) {}
+
+  /// @}
+  /// @name String Assignment
+  /// @{
+
+  using SmallVector<char, InternalLen>::assign;
+
+  /// Assign from a std::string_view.
+  void assign(std::string_view RHS) {
+    SmallVectorImpl<char>::assign(RHS.begin(), RHS.end());
+  }
+
+  /// Assign from a list of std::string_views.
+  void assign(std::initializer_list<std::string_view> Refs) {
+    this->clear();
+    append(Refs);
+  }
+
+  /// @}
+  /// @name String Concatenation
+  /// @{
+
+  using SmallVector<char, InternalLen>::append;
+
+  /// Append from a std::string_view.
+  void append(std::string_view RHS) {
+    SmallVectorImpl<char>::append(RHS.begin(), RHS.end());
+  }
+
+  /// Append from a list of std::string_views.
+  void append(std::initializer_list<std::string_view> Refs) {
+    size_t CurrentSize = this->size();
+    size_t SizeNeeded = CurrentSize;
+    for (std::string_view Ref : Refs)
+      SizeNeeded += Ref.size();
+    this->resize_for_overwrite(SizeNeeded);
+    for (std::string_view Ref : Refs) {
+      std::copy(Ref.begin(), Ref.end(), this->begin() + CurrentSize);
+      CurrentSize += Ref.size();
+    }
+    assert(CurrentSize == this->size());
+  }
+
+  /// @}
+  /// @name String Comparison
+  /// @{
+
+  /// Compare two strings; the result is -1, 0, or 1 if this string is
+  /// lexicographically less than, equal to, or greater than the \p RHS.
+  int compare(std::string_view RHS) const {
+    return str().compare(RHS);
+  }
+
+  /// @}
+  /// @name String Searching
+  /// @{
+
+  /// find - Search for the first character \p C in the string.
+  ///
+  /// \return - The index of the first occurrence of \p C, or npos if not
+  /// found.
+  size_t find(char C, size_t From = 0) const {
+    return str().find(C, From);
+  }
+
+  /// Search for the first string \p Str in the string.
+  ///
+  /// \returns The index of the first occurrence of \p Str, or npos if not
+  /// found.
+  size_t find(std::string_view Str, size_t From = 0) const {
+    return str().find(Str, From);
+  }
+
+  /// Search for the last character \p C in the string.
+  ///
+  /// \returns The index of the last occurrence of \p C, or npos if not
+  /// found.
+  size_t rfind(char C, size_t From = std::string_view::npos) const {
+    return str().rfind(C, From);
+  }
+
+  /// Search for the last string \p Str in the string.
+  ///
+  /// \returns The index of the last occurrence of \p Str, or npos if not
+  /// found.
+  size_t rfind(std::string_view Str) const {
+    return str().rfind(Str);
+  }
+
+  /// Find the first character in the string that is \p C, or npos if not
+  /// found. Same as find.
+  size_t find_first_of(char C, size_t From = 0) const {
+    return str().find_first_of(C, From);
+  }
+
+  /// Find the first character in the string that is in \p Chars, or npos if
+  /// not found.
+  ///
+  /// Complexity: O(size() + Chars.size())
+  size_t find_first_of(std::string_view Chars, size_t From = 0) const {
+    return str().find_first_of(Chars, From);
+  }
+
+  /// Find the first character in the string that is not \p C or npos if not
+  /// found.
+  size_t find_first_not_of(char C, size_t From = 0) const {
+    return str().find_first_not_of(C, From);
+  }
+
+  /// Find the first character in the string that is not in the string
+  /// \p Chars, or npos if not found.
+  ///
+  /// Complexity: O(size() + Chars.size())
+  size_t find_first_not_of(std::string_view Chars, size_t From = 0) const {
+    return str().find_first_not_of(Chars, From);
+  }
+
+  /// Find the last character in the string that is \p C, or npos if not
+  /// found.
+  size_t find_last_of(char C, size_t From = std::string_view::npos) const {
+    return str().find_last_of(C, From);
+  }
+
+  /// Find the last character in the string that is in \p C, or npos if not
+  /// found.
+  ///
+  /// Complexity: O(size() + Chars.size())
+  size_t find_last_of(
+      std::string_view Chars, size_t From = std::string_view::npos) const {
+    return str().find_last_of(Chars, From);
+  }
+
+  /// @}
+
+  // Extra methods.
+
+  /// Explicit conversion to std::string_view.
+  std::string_view str() const { return std::string_view(this->begin(), this->size()); }
+
+  // TODO: Make this const, if it's safe...
+  const char* c_str() {
+    this->push_back(0);
+    this->pop_back();
+    return this->data();
+  }
+
+  /// Implicit conversion to std::string_view.
+  operator std::string_view() const { return str(); }
+
+  explicit operator std::string() const {
+    return std::string(this->data(), this->size());
+  }
+
+  // Extra operators.
+  SmallString &operator=(std::string_view RHS) {
+    this->assign(RHS);
+    return *this;
+  }
+
+  SmallString &operator+=(std::string_view RHS) {
+    this->append(RHS.begin(), RHS.end());
+    return *this;
+  }
+  SmallString &operator+=(char C) {
+    this->push_back(C);
+    return *this;
+  }
+};
+
+} // end namespace wpi
+
+#endif // WPIUTIL_WPI_SMALLSTRING_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/SmallVector.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/SmallVector.h
new file mode 100644
index 0000000..134ce67
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/SmallVector.h
@@ -0,0 +1,1312 @@
+//===- llvm/ADT/SmallVector.h - 'Normally small' vectors --------*- C++ -*-===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+///
+/// /file
+/// This file defines the SmallVector class.
+///
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_SMALLVECTOR_H
+#define WPIUTIL_WPI_SMALLVECTOR_H
+
+// This file uses std::memcpy() to copy std::pair<unsigned int, unsigned int>.
+// That type is POD, but the standard doesn't guarantee that. GCC doesn't treat
+// the type as POD so it throws a warning. We want to consider this a warning
+// instead of an error.
+#if __GNUC__ >= 8
+#pragma GCC diagnostic warning "-Wclass-memaccess"
+#endif
+
+#include "wpi/Compiler.h"
+#include "wpi/type_traits.h"
+#include <algorithm>
+#include <cassert>
+#include <cstddef>
+#include <cstdlib>
+#include <cstring>
+#include <functional>
+#include <initializer_list>
+#include <iterator>
+#include <limits>
+#include <memory>
+#include <new>
+#include <type_traits>
+#include <utility>
+
+namespace wpi {
+
+template <typename IteratorT> class iterator_range;
+
+/// This is all the stuff common to all SmallVectors.
+///
+/// The template parameter specifies the type which should be used to hold the
+/// Size and Capacity of the SmallVector, so it can be adjusted.
+/// Using 32 bit size is desirable to shrink the size of the SmallVector.
+/// Using 64 bit size is desirable for cases like SmallVector<char>, where a
+/// 32 bit size would limit the vector to ~4GB. SmallVectors are used for
+/// buffering bitcode output - which can exceed 4GB.
+class SmallVectorBase {
+protected:
+  void *BeginX;
+  unsigned Size = 0, Capacity;
+
+  /// The maximum value of the Size_T used.
+  static constexpr size_t SizeTypeMax() {
+    return (std::numeric_limits<unsigned>::max)();
+  }
+
+  SmallVectorBase() = delete;
+  SmallVectorBase(void *FirstEl, size_t TotalCapacity)
+      : BeginX(FirstEl), Capacity(static_cast<unsigned>(TotalCapacity)) {}
+
+  /// This is a helper for \a grow() that's out of line to reduce code
+  /// duplication.  This function will report a fatal error if it can't grow at
+  /// least to \p MinSize.
+  void *mallocForGrow(size_t MinSize, size_t TSize, size_t &NewCapacity);
+
+  /// This is an implementation of the grow() method which only works
+  /// on POD-like data types and is out of line to reduce code duplication.
+  /// This function will report a fatal error if it cannot increase capacity.
+  void grow_pod(void *FirstEl, size_t MinSize, size_t TSize);
+
+public:
+  size_t size() const { return Size; }
+  size_t capacity() const { return Capacity; }
+
+  LLVM_NODISCARD bool empty() const { return !Size; }
+
+protected:
+  /// Set the array size to \p N, which the current array must have enough
+  /// capacity for.
+  ///
+  /// This does not construct or destroy any elements in the vector.
+  void set_size(size_t N) {
+    assert(N <= capacity());
+    Size = static_cast<unsigned>(N);
+  }
+};
+
+/// Figure out the offset of the first element.
+template <class T, typename = void> struct SmallVectorAlignmentAndSize {
+  alignas(SmallVectorBase) char Base[sizeof(
+      SmallVectorBase)];
+  alignas(T) char FirstEl[sizeof(T)];
+};
+
+/// This is the part of SmallVectorTemplateBase which does not depend on whether
+/// the type T is a POD. The extra dummy template argument is used by ArrayRef
+/// to avoid unnecessarily requiring T to be complete.
+template <typename T, typename = void>
+class SmallVectorTemplateCommon
+    : public SmallVectorBase {
+  using Base = SmallVectorBase;
+
+  /// Find the address of the first element.  For this pointer math to be valid
+  /// with small-size of 0 for T with lots of alignment, it's important that
+  /// SmallVectorStorage is properly-aligned even for small-size of 0.
+  void *getFirstEl() const {
+    return const_cast<void *>(reinterpret_cast<const void *>(
+        reinterpret_cast<const char *>(this) +
+        offsetof(SmallVectorAlignmentAndSize<T>, FirstEl)));
+  }
+  // Space after 'FirstEl' is clobbered, do not add any instance vars after it.
+
+protected:
+  SmallVectorTemplateCommon(size_t Size) : Base(getFirstEl(), Size) {}
+
+  void grow_pod(size_t MinSize, size_t TSize) {
+    Base::grow_pod(getFirstEl(), MinSize, TSize);
+  }
+
+  /// Return true if this is a smallvector which has not had dynamic
+  /// memory allocated for it.
+  bool isSmall() const { return this->BeginX == getFirstEl(); }
+
+  /// Put this vector in a state of being small.
+  void resetToSmall() {
+    this->BeginX = getFirstEl();
+    this->Size = this->Capacity = 0; // FIXME: Setting Capacity to 0 is suspect.
+  }
+
+  /// Return true if V is an internal reference to the given range.
+  bool isReferenceToRange(const void *V, const void *First, const void *Last) const {
+    // Use std::less to avoid UB.
+    std::less<> LessThan;
+    return !LessThan(V, First) && LessThan(V, Last);
+  }
+
+  /// Return true if V is an internal reference to this vector.
+  bool isReferenceToStorage(const void *V) const {
+    return isReferenceToRange(V, this->begin(), this->end());
+  }
+
+  /// Return true if First and Last form a valid (possibly empty) range in this
+  /// vector's storage.
+  bool isRangeInStorage(const void *First, const void *Last) const {
+    // Use std::less to avoid UB.
+    std::less<> LessThan;
+    return !LessThan(First, this->begin()) && !LessThan(Last, First) &&
+           !LessThan(this->end(), Last);
+  }
+
+  /// Return true unless Elt will be invalidated by resizing the vector to
+  /// NewSize.
+  bool isSafeToReferenceAfterResize(const void *Elt, size_t NewSize) {
+    // Past the end.
+    if (LLVM_LIKELY(!isReferenceToStorage(Elt)))
+      return true;
+
+    // Return false if Elt will be destroyed by shrinking.
+    if (NewSize <= this->size())
+      return Elt < this->begin() + NewSize;
+
+    // Return false if we need to grow.
+    return NewSize <= this->capacity();
+  }
+
+  /// Check whether Elt will be invalidated by resizing the vector to NewSize.
+  void assertSafeToReferenceAfterResize(const void *Elt, size_t NewSize) {
+    assert(isSafeToReferenceAfterResize(Elt, NewSize) &&
+           "Attempting to reference an element of the vector in an operation "
+           "that invalidates it");
+  }
+
+  /// Check whether Elt will be invalidated by increasing the size of the
+  /// vector by N.
+  void assertSafeToAdd(const void *Elt, size_t N = 1) {
+    this->assertSafeToReferenceAfterResize(Elt, this->size() + N);
+  }
+
+  /// Check whether any part of the range will be invalidated by clearing.
+  void assertSafeToReferenceAfterClear(const T *From, const T *To) {
+    if (From == To)
+      return;
+    this->assertSafeToReferenceAfterResize(From, 0);
+    this->assertSafeToReferenceAfterResize(To - 1, 0);
+  }
+  template <
+      class ItTy,
+      std::enable_if_t<!std::is_same<std::remove_const_t<ItTy>, T *>::value,
+                       bool> = false>
+  void assertSafeToReferenceAfterClear(ItTy, ItTy) {}
+
+  /// Check whether any part of the range will be invalidated by growing.
+  void assertSafeToAddRange(const T *From, const T *To) {
+    if (From == To)
+      return;
+    this->assertSafeToAdd(From, To - From);
+    this->assertSafeToAdd(To - 1, To - From);
+  }
+  template <
+      class ItTy,
+      std::enable_if_t<!std::is_same<std::remove_const_t<ItTy>, T *>::value,
+                       bool> = false>
+  void assertSafeToAddRange(ItTy, ItTy) {}
+
+  /// Reserve enough space to add one element, and return the updated element
+  /// pointer in case it was a reference to the storage.
+  template <class U>
+  static const T *reserveForParamAndGetAddressImpl(U *This, const T &Elt,
+                                                   size_t N) {
+    size_t NewSize = This->size() + N;
+    if (LLVM_LIKELY(NewSize <= This->capacity()))
+      return &Elt;
+
+    bool ReferencesStorage = false;
+    int64_t Index = -1;
+    if (!U::TakesParamByValue) {
+      if (LLVM_UNLIKELY(This->isReferenceToStorage(&Elt))) {
+        ReferencesStorage = true;
+        Index = &Elt - This->begin();
+      }
+    }
+    This->grow(NewSize);
+    return ReferencesStorage ? This->begin() + Index : &Elt;
+  }
+
+public:
+  using size_type = size_t;
+  using difference_type = ptrdiff_t;
+  using value_type = T;
+  using iterator = T *;
+  using const_iterator = const T *;
+
+  using const_reverse_iterator = std::reverse_iterator<const_iterator>;
+  using reverse_iterator = std::reverse_iterator<iterator>;
+
+  using reference = T &;
+  using const_reference = const T &;
+  using pointer = T *;
+  using const_pointer = const T *;
+
+  using Base::capacity;
+  using Base::empty;
+  using Base::size;
+
+  // forward iterator creation methods.
+  iterator begin() { return (iterator)this->BeginX; }
+  const_iterator begin() const { return (const_iterator)this->BeginX; }
+  iterator end() { return begin() + size(); }
+  const_iterator end() const { return begin() + size(); }
+
+  // reverse iterator creation methods.
+  reverse_iterator rbegin()            { return reverse_iterator(end()); }
+  const_reverse_iterator rbegin() const{ return const_reverse_iterator(end()); }
+  reverse_iterator rend()              { return reverse_iterator(begin()); }
+  const_reverse_iterator rend() const { return const_reverse_iterator(begin());}
+
+  size_type size_in_bytes() const { return size() * sizeof(T); }
+  size_type max_size() const {
+    return (std::min)(this->SizeTypeMax(), size_type(-1) / sizeof(T));
+  }
+
+  size_t capacity_in_bytes() const { return capacity() * sizeof(T); }
+
+  /// Return a pointer to the vector's buffer, even if empty().
+  pointer data() { return pointer(begin()); }
+  /// Return a pointer to the vector's buffer, even if empty().
+  const_pointer data() const { return const_pointer(begin()); }
+
+  reference operator[](size_type idx) {
+    assert(idx < size());
+    return begin()[idx];
+  }
+  const_reference operator[](size_type idx) const {
+    assert(idx < size());
+    return begin()[idx];
+  }
+
+  reference front() {
+    assert(!empty());
+    return begin()[0];
+  }
+  const_reference front() const {
+    assert(!empty());
+    return begin()[0];
+  }
+
+  reference back() {
+    assert(!empty());
+    return end()[-1];
+  }
+  const_reference back() const {
+    assert(!empty());
+    return end()[-1];
+  }
+};
+
+/// SmallVectorTemplateBase<TriviallyCopyable = false> - This is where we put
+/// method implementations that are designed to work with non-trivial T's.
+///
+/// We approximate is_trivially_copyable with trivial move/copy construction and
+/// trivial destruction. While the standard doesn't specify that you're allowed
+/// copy these types with memcpy, there is no way for the type to observe this.
+/// This catches the important case of std::pair<POD, POD>, which is not
+/// trivially assignable.
+template <typename T, bool = (is_trivially_copy_constructible<T>::value) &&
+                             (is_trivially_move_constructible<T>::value) &&
+                             std::is_trivially_destructible<T>::value>
+class SmallVectorTemplateBase : public SmallVectorTemplateCommon<T> {
+  friend class SmallVectorTemplateCommon<T>;
+
+protected:
+  static constexpr bool TakesParamByValue = false;
+  using ValueParamT = const T &;
+
+  SmallVectorTemplateBase(size_t Size) : SmallVectorTemplateCommon<T>(Size) {}
+
+  static void destroy_range(T *S, T *E) {
+    while (S != E) {
+      --E;
+      E->~T();
+    }
+  }
+
+  /// Move the range [I, E) into the uninitialized memory starting with "Dest",
+  /// constructing elements as needed.
+  template<typename It1, typename It2>
+  static void uninitialized_move(It1 I, It1 E, It2 Dest) {
+    std::uninitialized_copy(std::make_move_iterator(I),
+                            std::make_move_iterator(E), Dest);
+  }
+
+  /// Copy the range [I, E) onto the uninitialized memory starting with "Dest",
+  /// constructing elements as needed.
+  template<typename It1, typename It2>
+  static void uninitialized_copy(It1 I, It1 E, It2 Dest) {
+    std::uninitialized_copy(I, E, Dest);
+  }
+
+  /// Grow the allocated memory (without initializing new elements), doubling
+  /// the size of the allocated memory. Guarantees space for at least one more
+  /// element, or MinSize more elements if specified.
+  void grow(size_t MinSize = 0);
+
+  /// Create a new allocation big enough for \p MinSize and pass back its size
+  /// in \p NewCapacity. This is the first section of \a grow().
+  T *mallocForGrow(size_t MinSize, size_t &NewCapacity) {
+    return static_cast<T *>(
+        SmallVectorBase::mallocForGrow(
+            MinSize, sizeof(T), NewCapacity));
+  }
+
+  /// Move existing elements over to the new allocation \p NewElts, the middle
+  /// section of \a grow().
+  void moveElementsForGrow(T *NewElts);
+
+  /// Transfer ownership of the allocation, finishing up \a grow().
+  void takeAllocationForGrow(T *NewElts, size_t NewCapacity);
+
+  /// Reserve enough space to add one element, and return the updated element
+  /// pointer in case it was a reference to the storage.
+  const T *reserveForParamAndGetAddress(const T &Elt, size_t N = 1) {
+    return this->reserveForParamAndGetAddressImpl(this, Elt, N);
+  }
+
+  /// Reserve enough space to add one element, and return the updated element
+  /// pointer in case it was a reference to the storage.
+  T *reserveForParamAndGetAddress(T &Elt, size_t N = 1) {
+    return const_cast<T *>(
+        this->reserveForParamAndGetAddressImpl(this, Elt, N));
+  }
+
+  static T &&forward_value_param(T &&V) { return std::move(V); }
+  static const T &forward_value_param(const T &V) { return V; }
+
+  void growAndAssign(size_t NumElts, const T &Elt) {
+    // Grow manually in case Elt is an internal reference.
+    size_t NewCapacity;
+    T *NewElts = mallocForGrow(NumElts, NewCapacity);
+    std::uninitialized_fill_n(NewElts, NumElts, Elt);
+    this->destroy_range(this->begin(), this->end());
+    takeAllocationForGrow(NewElts, NewCapacity);
+    this->set_size(NumElts);
+  }
+
+  template <typename... ArgTypes> T &growAndEmplaceBack(ArgTypes &&... Args) {
+    // Grow manually in case one of Args is an internal reference.
+    size_t NewCapacity;
+    T *NewElts = mallocForGrow(0, NewCapacity);
+    ::new ((void *)(NewElts + this->size())) T(std::forward<ArgTypes>(Args)...);
+    moveElementsForGrow(NewElts);
+    takeAllocationForGrow(NewElts, NewCapacity);
+    this->set_size(this->size() + 1);
+    return this->back();
+  }
+
+public:
+  void push_back(const T &Elt) {
+    const T *EltPtr = reserveForParamAndGetAddress(Elt);
+    ::new ((void *)this->end()) T(*EltPtr);
+    this->set_size(this->size() + 1);
+  }
+
+  void push_back(T &&Elt) {
+    T *EltPtr = reserveForParamAndGetAddress(Elt);
+    ::new ((void *)this->end()) T(::std::move(*EltPtr));
+    this->set_size(this->size() + 1);
+  }
+
+  void pop_back() {
+    this->set_size(this->size() - 1);
+    this->end()->~T();
+  }
+};
+
+// Define this out-of-line to dissuade the C++ compiler from inlining it.
+template <typename T, bool TriviallyCopyable>
+void SmallVectorTemplateBase<T, TriviallyCopyable>::grow(size_t MinSize) {
+  size_t NewCapacity;
+  T *NewElts = mallocForGrow(MinSize, NewCapacity);
+  moveElementsForGrow(NewElts);
+  takeAllocationForGrow(NewElts, NewCapacity);
+}
+
+// Define this out-of-line to dissuade the C++ compiler from inlining it.
+template <typename T, bool TriviallyCopyable>
+void SmallVectorTemplateBase<T, TriviallyCopyable>::moveElementsForGrow(
+    T *NewElts) {
+  // Move the elements over.
+  this->uninitialized_move(this->begin(), this->end(), NewElts);
+
+  // Destroy the original elements.
+  destroy_range(this->begin(), this->end());
+}
+
+// Define this out-of-line to dissuade the C++ compiler from inlining it.
+template <typename T, bool TriviallyCopyable>
+void SmallVectorTemplateBase<T, TriviallyCopyable>::takeAllocationForGrow(
+    T *NewElts, size_t NewCapacity) {
+  // If this wasn't grown from the inline copy, deallocate the old space.
+  if (!this->isSmall())
+    free(this->begin());
+
+  this->BeginX = NewElts;
+  this->Capacity = static_cast<unsigned>(NewCapacity);
+}
+
+/// SmallVectorTemplateBase<TriviallyCopyable = true> - This is where we put
+/// method implementations that are designed to work with trivially copyable
+/// T's. This allows using memcpy in place of copy/move construction and
+/// skipping destruction.
+template <typename T>
+class SmallVectorTemplateBase<T, true> : public SmallVectorTemplateCommon<T> {
+  friend class SmallVectorTemplateCommon<T>;
+
+protected:
+  /// True if it's cheap enough to take parameters by value. Doing so avoids
+  /// overhead related to mitigations for reference invalidation.
+  static constexpr bool TakesParamByValue = sizeof(T) <= 2 * sizeof(void *);
+
+  /// Either const T& or T, depending on whether it's cheap enough to take
+  /// parameters by value.
+  using ValueParamT =
+      typename std::conditional<TakesParamByValue, T, const T &>::type;
+
+  SmallVectorTemplateBase(size_t Size) : SmallVectorTemplateCommon<T>(Size) {}
+
+  // No need to do a destroy loop for POD's.
+  static void destroy_range(T *, T *) {}
+
+  /// Move the range [I, E) onto the uninitialized memory
+  /// starting with "Dest", constructing elements into it as needed.
+  template<typename It1, typename It2>
+  static void uninitialized_move(It1 I, It1 E, It2 Dest) {
+    // Just do a copy.
+    uninitialized_copy(I, E, Dest);
+  }
+
+  /// Copy the range [I, E) onto the uninitialized memory
+  /// starting with "Dest", constructing elements into it as needed.
+  template<typename It1, typename It2>
+  static void uninitialized_copy(It1 I, It1 E, It2 Dest) {
+    // Arbitrary iterator types; just use the basic implementation.
+    std::uninitialized_copy(I, E, Dest);
+  }
+
+  /// Copy the range [I, E) onto the uninitialized memory
+  /// starting with "Dest", constructing elements into it as needed.
+  template <typename T1, typename T2>
+  static void uninitialized_copy(
+      T1 *I, T1 *E, T2 *Dest,
+      std::enable_if_t<std::is_same<typename std::remove_const<T1>::type,
+                                    T2>::value> * = nullptr) {
+    // Use memcpy for PODs iterated by pointers (which includes SmallVector
+    // iterators): std::uninitialized_copy optimizes to memmove, but we can
+    // use memcpy here. Note that I and E are iterators and thus might be
+    // invalid for memcpy if they are equal.
+    if (I != E)
+      memcpy(reinterpret_cast<void *>(Dest), I, (E - I) * sizeof(T));
+  }
+
+  /// Double the size of the allocated memory, guaranteeing space for at
+  /// least one more element or MinSize if specified.
+  void grow(size_t MinSize = 0) { this->grow_pod(MinSize, sizeof(T)); }
+
+  /// Reserve enough space to add one element, and return the updated element
+  /// pointer in case it was a reference to the storage.
+  const T *reserveForParamAndGetAddress(const T &Elt, size_t N = 1) {
+    return this->reserveForParamAndGetAddressImpl(this, Elt, N);
+  }
+
+  /// Reserve enough space to add one element, and return the updated element
+  /// pointer in case it was a reference to the storage.
+  T *reserveForParamAndGetAddress(T &Elt, size_t N = 1) {
+    return const_cast<T *>(
+        this->reserveForParamAndGetAddressImpl(this, Elt, N));
+  }
+
+  /// Copy \p V or return a reference, depending on \a ValueParamT.
+  static ValueParamT forward_value_param(ValueParamT V) { return V; }
+
+  void growAndAssign(size_t NumElts, T Elt) {
+    // Elt has been copied in case it's an internal reference, side-stepping
+    // reference invalidation problems without losing the realloc optimization.
+    this->set_size(0);
+    this->grow(NumElts);
+    std::uninitialized_fill_n(this->begin(), NumElts, Elt);
+    this->set_size(NumElts);
+  }
+
+  template <typename... ArgTypes> T &growAndEmplaceBack(ArgTypes &&... Args) {
+    // Use push_back with a copy in case Args has an internal reference,
+    // side-stepping reference invalidation problems without losing the realloc
+    // optimization.
+    push_back(T(std::forward<ArgTypes>(Args)...));
+    return this->back();
+  }
+
+public:
+  void push_back(ValueParamT Elt) {
+    const T *EltPtr = reserveForParamAndGetAddress(Elt);
+    memcpy(reinterpret_cast<void *>(this->end()), EltPtr, sizeof(T));
+    this->set_size(this->size() + 1);
+  }
+
+  void pop_back() { this->set_size(this->size() - 1); }
+};
+
+/// This class consists of common code factored out of the SmallVector class to
+/// reduce code duplication based on the SmallVector 'N' template parameter.
+template <typename T>
+class SmallVectorImpl : public SmallVectorTemplateBase<T> {
+  using SuperClass = SmallVectorTemplateBase<T>;
+
+public:
+  using iterator = typename SuperClass::iterator;
+  using const_iterator = typename SuperClass::const_iterator;
+  using reference = typename SuperClass::reference;
+  using size_type = typename SuperClass::size_type;
+
+protected:
+  using SmallVectorTemplateBase<T>::TakesParamByValue;
+  using ValueParamT = typename SuperClass::ValueParamT;
+
+  // Default ctor - Initialize to empty.
+  explicit SmallVectorImpl(unsigned N)
+      : SmallVectorTemplateBase<T>(N) {}
+
+  void assignRemote(SmallVectorImpl &&RHS) {
+    this->destroy_range(this->begin(), this->end());
+    if (!this->isSmall())
+      free(this->begin());
+    this->BeginX = RHS.BeginX;
+    this->Size = RHS.Size;
+    this->Capacity = RHS.Capacity;
+    RHS.resetToSmall();
+  }
+
+public:
+  SmallVectorImpl(const SmallVectorImpl &) = delete;
+
+  ~SmallVectorImpl() {
+    // Subclass has already destructed this vector's elements.
+    // If this wasn't grown from the inline copy, deallocate the old space.
+    if (!this->isSmall())
+      free(this->begin());
+  }
+
+  void clear() {
+    this->destroy_range(this->begin(), this->end());
+    this->Size = 0;
+  }
+
+private:
+  // Make set_size() private to avoid misuse in subclasses.
+  using SuperClass::set_size;
+
+  template <bool ForOverwrite> void resizeImpl(size_type N) {
+    if (N == this->size())
+      return;
+
+    if (N < this->size()) {
+      this->truncate(N);
+      return;
+    }
+
+    this->reserve(N);
+    for (auto I = this->end(), E = this->begin() + N; I != E; ++I)
+      if (ForOverwrite)
+        new (&*I) T;
+      else
+        new (&*I) T();
+    this->set_size(N);
+  }
+
+public:
+  void resize(size_type N) { resizeImpl<false>(N); }
+
+  /// Like resize, but \ref T is POD, the new values won't be initialized.
+  void resize_for_overwrite(size_type N) { resizeImpl<true>(N); }
+
+  /// Like resize, but requires that \p N is less than \a size().
+  void truncate(size_type N) {
+    assert(this->size() >= N && "Cannot increase size with truncate");
+    this->destroy_range(this->begin() + N, this->end());
+    this->set_size(N);
+  }
+
+  void resize(size_type N, ValueParamT NV) {
+    if (N == this->size())
+      return;
+
+    if (N < this->size()) {
+      this->truncate(N);
+      return;
+    }
+
+    // N > this->size(). Defer to append.
+    this->append(N - this->size(), NV);
+  }
+
+  void reserve(size_type N) {
+    if (this->capacity() < N)
+      this->grow(N);
+  }
+
+  void pop_back_n(size_type NumItems) {
+    assert(this->size() >= NumItems);
+    truncate(this->size() - NumItems);
+  }
+
+  LLVM_NODISCARD T pop_back_val() {
+    T Result = ::std::move(this->back());
+    this->pop_back();
+    return Result;
+  }
+
+  void swap(SmallVectorImpl &RHS);
+
+  /// Add the specified range to the end of the SmallVector.
+  template <typename in_iter,
+            typename = std::enable_if_t<std::is_convertible<
+                typename std::iterator_traits<in_iter>::iterator_category,
+                std::input_iterator_tag>::value>>
+  void append(in_iter in_start, in_iter in_end) {
+    this->assertSafeToAddRange(in_start, in_end);
+    size_type NumInputs = std::distance(in_start, in_end);
+    this->reserve(this->size() + NumInputs);
+    this->uninitialized_copy(in_start, in_end, this->end());
+    this->set_size(this->size() + NumInputs);
+  }
+
+  /// Append \p NumInputs copies of \p Elt to the end.
+  void append(size_type NumInputs, ValueParamT Elt) {
+    const T *EltPtr = this->reserveForParamAndGetAddress(Elt, NumInputs);
+    std::uninitialized_fill_n(this->end(), NumInputs, *EltPtr);
+    this->set_size(this->size() + NumInputs);
+  }
+
+  void append(std::initializer_list<T> IL) {
+    append(IL.begin(), IL.end());
+  }
+
+  void append(const SmallVectorImpl &RHS) { append(RHS.begin(), RHS.end()); }
+
+  void assign(size_type NumElts, ValueParamT Elt) {
+    // Note that Elt could be an internal reference.
+    if (NumElts > this->capacity()) {
+      this->growAndAssign(NumElts, Elt);
+      return;
+    }
+
+    // Assign over existing elements.
+    std::fill_n(this->begin(), (std::min)(NumElts, this->size()), Elt);
+    if (NumElts > this->size())
+      std::uninitialized_fill_n(this->end(), NumElts - this->size(), Elt);
+    else if (NumElts < this->size())
+      this->destroy_range(this->begin() + NumElts, this->end());
+    this->set_size(NumElts);
+  }
+
+  // FIXME: Consider assigning over existing elements, rather than clearing &
+  // re-initializing them - for all assign(...) variants.
+
+  template <typename in_iter,
+            typename = std::enable_if_t<std::is_convertible<
+                typename std::iterator_traits<in_iter>::iterator_category,
+                std::input_iterator_tag>::value>>
+  void assign(in_iter in_start, in_iter in_end) {
+    this->assertSafeToReferenceAfterClear(in_start, in_end);
+    clear();
+    append(in_start, in_end);
+  }
+
+  void assign(std::initializer_list<T> IL) {
+    clear();
+    append(IL);
+  }
+
+  void assign(const SmallVectorImpl &RHS) { assign(RHS.begin(), RHS.end()); }
+
+  iterator erase(const_iterator CI) {
+    // Just cast away constness because this is a non-const member function.
+    iterator I = const_cast<iterator>(CI);
+
+    assert(this->isReferenceToStorage(CI) && "Iterator to erase is out of bounds.");
+
+    iterator N = I;
+    // Shift all elts down one.
+    std::move(I+1, this->end(), I);
+    // Drop the last elt.
+    this->pop_back();
+    return(N);
+  }
+
+  iterator erase(const_iterator CS, const_iterator CE) {
+    // Just cast away constness because this is a non-const member function.
+    iterator S = const_cast<iterator>(CS);
+    iterator E = const_cast<iterator>(CE);
+
+    assert(this->isRangeInStorage(S, E) && "Range to erase is out of bounds.");
+
+    iterator N = S;
+    // Shift all elts down.
+    iterator I = std::move(E, this->end(), S);
+    // Drop the last elts.
+    this->destroy_range(I, this->end());
+    this->set_size(I - this->begin());
+    return(N);
+  }
+
+private:
+  template <class ArgType> iterator insert_one_impl(iterator I, ArgType &&Elt) {
+    // Callers ensure that ArgType is derived from T.
+    static_assert(
+        std::is_same<std::remove_const_t<std::remove_reference_t<ArgType>>,
+                     T>::value,
+        "ArgType must be derived from T!");
+
+    if (I == this->end()) {  // Important special case for empty vector.
+      this->push_back(::std::forward<ArgType>(Elt));
+      return this->end()-1;
+    }
+
+    assert(this->isReferenceToStorage(I) && "Insertion iterator is out of bounds.");
+
+    // Grow if necessary.
+    size_t Index = I - this->begin();
+    std::remove_reference_t<ArgType> *EltPtr =
+        this->reserveForParamAndGetAddress(Elt);
+    I = this->begin() + Index;
+
+    ::new ((void*) this->end()) T(::std::move(this->back()));
+    // Push everything else over.
+    std::move_backward(I, this->end()-1, this->end());
+    this->set_size(this->size() + 1);
+
+    // If we just moved the element we're inserting, be sure to update
+    // the reference (never happens if TakesParamByValue).
+    static_assert(!TakesParamByValue || std::is_same<ArgType, T>::value,
+                  "ArgType must be 'T' when taking by value!");
+    if (!TakesParamByValue && this->isReferenceToRange(EltPtr, I, this->end()))
+      ++EltPtr;
+
+    *I = ::std::forward<ArgType>(*EltPtr);
+    return I;
+  }
+
+public:
+  iterator insert(iterator I, T &&Elt) {
+    return insert_one_impl(I, this->forward_value_param(std::move(Elt)));
+  }
+
+  iterator insert(iterator I, const T &Elt) {
+    return insert_one_impl(I, this->forward_value_param(Elt));
+  }
+
+  iterator insert(iterator I, size_type NumToInsert, ValueParamT Elt) {
+    // Convert iterator to elt# to avoid invalidating iterator when we reserve()
+    size_t InsertElt = I - this->begin();
+
+    if (I == this->end()) {  // Important special case for empty vector.
+      append(NumToInsert, Elt);
+      return this->begin()+InsertElt;
+    }
+
+    assert(this->isReferenceToStorage(I) && "Insertion iterator is out of bounds.");
+
+    // Ensure there is enough space, and get the (maybe updated) address of
+    // Elt.
+    const T *EltPtr = this->reserveForParamAndGetAddress(Elt, NumToInsert);
+
+    // Uninvalidate the iterator.
+    I = this->begin()+InsertElt;
+
+    // If there are more elements between the insertion point and the end of the
+    // range than there are being inserted, we can use a simple approach to
+    // insertion.  Since we already reserved space, we know that this won't
+    // reallocate the vector.
+    if (size_t(this->end()-I) >= NumToInsert) {
+      T *OldEnd = this->end();
+      append(std::move_iterator<iterator>(this->end() - NumToInsert),
+             std::move_iterator<iterator>(this->end()));
+
+      // Copy the existing elements that get replaced.
+      std::move_backward(I, OldEnd-NumToInsert, OldEnd);
+
+      // If we just moved the element we're inserting, be sure to update
+      // the reference (never happens if TakesParamByValue).
+      if (!TakesParamByValue && I <= EltPtr && EltPtr < this->end())
+        EltPtr += NumToInsert;
+
+      std::fill_n(I, NumToInsert, *EltPtr);
+      return I;
+    }
+
+    // Otherwise, we're inserting more elements than exist already, and we're
+    // not inserting at the end.
+
+    // Move over the elements that we're about to overwrite.
+    T *OldEnd = this->end();
+    this->set_size(this->size() + NumToInsert);
+    size_t NumOverwritten = OldEnd-I;
+    this->uninitialized_move(I, OldEnd, this->end()-NumOverwritten);
+
+    // If we just moved the element we're inserting, be sure to update
+    // the reference (never happens if TakesParamByValue).
+    if (!TakesParamByValue && I <= EltPtr && EltPtr < this->end())
+      EltPtr += NumToInsert;
+
+    // Replace the overwritten part.
+    std::fill_n(I, NumOverwritten, *EltPtr);
+
+    // Insert the non-overwritten middle part.
+    std::uninitialized_fill_n(OldEnd, NumToInsert - NumOverwritten, *EltPtr);
+    return I;
+  }
+
+  template <typename ItTy,
+            typename = std::enable_if_t<std::is_convertible<
+                typename std::iterator_traits<ItTy>::iterator_category,
+                std::input_iterator_tag>::value>>
+  iterator insert(iterator I, ItTy From, ItTy To) {
+    // Convert iterator to elt# to avoid invalidating iterator when we reserve()
+    size_t InsertElt = I - this->begin();
+
+    if (I == this->end()) {  // Important special case for empty vector.
+      append(From, To);
+      return this->begin()+InsertElt;
+    }
+
+    assert(this->isReferenceToStorage(I) && "Insertion iterator is out of bounds.");
+
+    // Check that the reserve that follows doesn't invalidate the iterators.
+    this->assertSafeToAddRange(From, To);
+
+    size_t NumToInsert = std::distance(From, To);
+
+    // Ensure there is enough space.
+    reserve(this->size() + NumToInsert);
+
+    // Uninvalidate the iterator.
+    I = this->begin()+InsertElt;
+
+    // If there are more elements between the insertion point and the end of the
+    // range than there are being inserted, we can use a simple approach to
+    // insertion.  Since we already reserved space, we know that this won't
+    // reallocate the vector.
+    if (size_t(this->end()-I) >= NumToInsert) {
+      T *OldEnd = this->end();
+      append(std::move_iterator<iterator>(this->end() - NumToInsert),
+             std::move_iterator<iterator>(this->end()));
+
+      // Copy the existing elements that get replaced.
+      std::move_backward(I, OldEnd-NumToInsert, OldEnd);
+
+      std::copy(From, To, I);
+      return I;
+    }
+
+    // Otherwise, we're inserting more elements than exist already, and we're
+    // not inserting at the end.
+
+    // Move over the elements that we're about to overwrite.
+    T *OldEnd = this->end();
+    this->set_size(this->size() + NumToInsert);
+    size_t NumOverwritten = OldEnd-I;
+    this->uninitialized_move(I, OldEnd, this->end()-NumOverwritten);
+
+    // Replace the overwritten part.
+    for (T *J = I; NumOverwritten > 0; --NumOverwritten) {
+      *J = *From;
+      ++J; ++From;
+    }
+
+    // Insert the non-overwritten middle part.
+    this->uninitialized_copy(From, To, OldEnd);
+    return I;
+  }
+
+  void insert(iterator I, std::initializer_list<T> IL) {
+    insert(I, IL.begin(), IL.end());
+  }
+
+  template <typename... ArgTypes> reference emplace_back(ArgTypes &&... Args) {
+    if (LLVM_UNLIKELY(this->size() >= this->capacity()))
+      return this->growAndEmplaceBack(std::forward<ArgTypes>(Args)...);
+
+    ::new ((void *)this->end()) T(std::forward<ArgTypes>(Args)...);
+    this->set_size(this->size() + 1);
+    return this->back();
+  }
+
+  SmallVectorImpl &operator=(const SmallVectorImpl &RHS);
+
+  SmallVectorImpl &operator=(SmallVectorImpl &&RHS);
+
+  bool operator==(const SmallVectorImpl &RHS) const {
+    if (this->size() != RHS.size()) return false;
+    return std::equal(this->begin(), this->end(), RHS.begin());
+  }
+  bool operator!=(const SmallVectorImpl &RHS) const {
+    return !(*this == RHS);
+  }
+
+  bool operator<(const SmallVectorImpl &RHS) const {
+    return std::lexicographical_compare(this->begin(), this->end(),
+                                        RHS.begin(), RHS.end());
+  }
+};
+
+template <typename T>
+void SmallVectorImpl<T>::swap(SmallVectorImpl<T> &RHS) {
+  if (this == &RHS) return;
+
+  // We can only avoid copying elements if neither vector is small.
+  if (!this->isSmall() && !RHS.isSmall()) {
+    std::swap(this->BeginX, RHS.BeginX);
+    std::swap(this->Size, RHS.Size);
+    std::swap(this->Capacity, RHS.Capacity);
+    return;
+  }
+  this->reserve(RHS.size());
+  RHS.reserve(this->size());
+
+  // Swap the shared elements.
+  size_t NumShared = this->size();
+  if (NumShared > RHS.size()) NumShared = RHS.size();
+  for (size_type i = 0; i != NumShared; ++i)
+    std::swap((*this)[i], RHS[i]);
+
+  // Copy over the extra elts.
+  if (this->size() > RHS.size()) {
+    size_t EltDiff = this->size() - RHS.size();
+    this->uninitialized_copy(this->begin()+NumShared, this->end(), RHS.end());
+    RHS.set_size(RHS.size() + EltDiff);
+    this->destroy_range(this->begin()+NumShared, this->end());
+    this->set_size(NumShared);
+  } else if (RHS.size() > this->size()) {
+    size_t EltDiff = RHS.size() - this->size();
+    this->uninitialized_copy(RHS.begin()+NumShared, RHS.end(), this->end());
+    this->set_size(this->size() + EltDiff);
+    this->destroy_range(RHS.begin()+NumShared, RHS.end());
+    RHS.set_size(NumShared);
+  }
+}
+
+template <typename T>
+SmallVectorImpl<T> &SmallVectorImpl<T>::
+  operator=(const SmallVectorImpl<T> &RHS) {
+  // Avoid self-assignment.
+  if (this == &RHS) return *this;
+
+  // If we already have sufficient space, assign the common elements, then
+  // destroy any excess.
+  size_t RHSSize = RHS.size();
+  size_t CurSize = this->size();
+  if (CurSize >= RHSSize) {
+    // Assign common elements.
+    iterator NewEnd;
+    if (RHSSize)
+      NewEnd = std::copy(RHS.begin(), RHS.begin()+RHSSize, this->begin());
+    else
+      NewEnd = this->begin();
+
+    // Destroy excess elements.
+    this->destroy_range(NewEnd, this->end());
+
+    // Trim.
+    this->set_size(RHSSize);
+    return *this;
+  }
+
+  // If we have to grow to have enough elements, destroy the current elements.
+  // This allows us to avoid copying them during the grow.
+  // FIXME: don't do this if they're efficiently moveable.
+  if (this->capacity() < RHSSize) {
+    // Destroy current elements.
+    this->clear();
+    CurSize = 0;
+    this->grow(RHSSize);
+  } else if (CurSize) {
+    // Otherwise, use assignment for the already-constructed elements.
+    std::copy(RHS.begin(), RHS.begin()+CurSize, this->begin());
+  }
+
+  // Copy construct the new elements in place.
+  this->uninitialized_copy(RHS.begin()+CurSize, RHS.end(),
+                           this->begin()+CurSize);
+
+  // Set end.
+  this->set_size(RHSSize);
+  return *this;
+}
+
+template <typename T>
+SmallVectorImpl<T> &SmallVectorImpl<T>::operator=(SmallVectorImpl<T> &&RHS) {
+  // Avoid self-assignment.
+  if (this == &RHS) return *this;
+
+  // If the RHS isn't small, clear this vector and then steal its buffer.
+  if (!RHS.isSmall()) {
+    this->assignRemote(std::move(RHS));
+    return *this;
+  }
+
+  // If we already have sufficient space, assign the common elements, then
+  // destroy any excess.
+  size_t RHSSize = RHS.size();
+  size_t CurSize = this->size();
+  if (CurSize >= RHSSize) {
+    // Assign common elements.
+    iterator NewEnd = this->begin();
+    if (RHSSize)
+      NewEnd = std::move(RHS.begin(), RHS.end(), NewEnd);
+
+    // Destroy excess elements and trim the bounds.
+    this->destroy_range(NewEnd, this->end());
+    this->set_size(RHSSize);
+
+    // Clear the RHS.
+    RHS.clear();
+
+    return *this;
+  }
+
+  // If we have to grow to have enough elements, destroy the current elements.
+  // This allows us to avoid copying them during the grow.
+  // FIXME: this may not actually make any sense if we can efficiently move
+  // elements.
+  if (this->capacity() < RHSSize) {
+    // Destroy current elements.
+    this->clear();
+    CurSize = 0;
+    this->grow(RHSSize);
+  } else if (CurSize) {
+    // Otherwise, use assignment for the already-constructed elements.
+    std::move(RHS.begin(), RHS.begin()+CurSize, this->begin());
+  }
+
+  // Move-construct the new elements in place.
+  this->uninitialized_move(RHS.begin()+CurSize, RHS.end(),
+                           this->begin()+CurSize);
+
+  // Set end.
+  this->set_size(RHSSize);
+
+  RHS.clear();
+  return *this;
+}
+
+/// Storage for the SmallVector elements.  This is specialized for the N=0 case
+/// to avoid allocating unnecessary storage.
+template <typename T, unsigned N>
+struct SmallVectorStorage {
+  alignas(T) char InlineElts[N * sizeof(T)];
+};
+
+/// We need the storage to be properly aligned even for small-size of 0 so that
+/// the pointer math in \a SmallVectorTemplateCommon::getFirstEl() is
+/// well-defined.
+template <typename T> struct alignas(T) SmallVectorStorage<T, 0> {};
+
+/// Forward declaration of SmallVector so that
+/// calculateSmallVectorDefaultInlinedElements can reference
+/// `sizeof(SmallVector<T, 0>)`.
+template <typename T, unsigned N> class LLVM_GSL_OWNER SmallVector;
+
+/// Helper class for calculating the default number of inline elements for
+/// `SmallVector<T>`.
+///
+/// This should be migrated to a constexpr function when our minimum
+/// compiler support is enough for multi-statement constexpr functions.
+template <typename T> struct CalculateSmallVectorDefaultInlinedElements {
+  // Parameter controlling the default number of inlined elements
+  // for `SmallVector<T>`.
+  //
+  // The default number of inlined elements ensures that
+  // 1. There is at least one inlined element.
+  // 2. `sizeof(SmallVector<T>) <= kPreferredSmallVectorSizeof` unless
+  // it contradicts 1.
+  static constexpr size_t kPreferredSmallVectorSizeof = 64;
+
+  // static_assert that sizeof(T) is not "too big".
+  //
+  // Because our policy guarantees at least one inlined element, it is possible
+  // for an arbitrarily large inlined element to allocate an arbitrarily large
+  // amount of inline storage. We generally consider it an antipattern for a
+  // SmallVector to allocate an excessive amount of inline storage, so we want
+  // to call attention to these cases and make sure that users are making an
+  // intentional decision if they request a lot of inline storage.
+  //
+  // We want this assertion to trigger in pathological cases, but otherwise
+  // not be too easy to hit. To accomplish that, the cutoff is actually somewhat
+  // larger than kPreferredSmallVectorSizeof (otherwise,
+  // `SmallVector<SmallVector<T>>` would be one easy way to trip it, and that
+  // pattern seems useful in practice).
+  //
+  // One wrinkle is that this assertion is in theory non-portable, since
+  // sizeof(T) is in general platform-dependent. However, we don't expect this
+  // to be much of an issue, because most LLVM development happens on 64-bit
+  // hosts, and therefore sizeof(T) is expected to *decrease* when compiled for
+  // 32-bit hosts, dodging the issue. The reverse situation, where development
+  // happens on a 32-bit host and then fails due to sizeof(T) *increasing* on a
+  // 64-bit host, is expected to be very rare.
+  static_assert(
+      sizeof(T) <= 256,
+      "You are trying to use a default number of inlined elements for "
+      "`SmallVector<T>` but `sizeof(T)` is really big! Please use an "
+      "explicit number of inlined elements with `SmallVector<T, N>` to make "
+      "sure you really want that much inline storage.");
+
+  // Discount the size of the header itself when calculating the maximum inline
+  // bytes.
+  static constexpr size_t PreferredInlineBytes =
+      kPreferredSmallVectorSizeof - sizeof(SmallVector<T, 0>);
+  static constexpr size_t NumElementsThatFit = PreferredInlineBytes / sizeof(T);
+  static constexpr size_t value =
+      NumElementsThatFit == 0 ? 1 : NumElementsThatFit;
+};
+
+/// This is a 'vector' (really, a variable-sized array), optimized
+/// for the case when the array is small.  It contains some number of elements
+/// in-place, which allows it to avoid heap allocation when the actual number of
+/// elements is below that threshold.  This allows normal "small" cases to be
+/// fast without losing generality for large inputs.
+///
+/// \note
+/// In the absence of a well-motivated choice for the number of inlined
+/// elements \p N, it is recommended to use \c SmallVector<T> (that is,
+/// omitting the \p N). This will choose a default number of inlined elements
+/// reasonable for allocation on the stack (for example, trying to keep \c
+/// sizeof(SmallVector<T>) around 64 bytes).
+///
+/// \warning This does not attempt to be exception safe.
+///
+/// \see https://llvm.org/docs/ProgrammersManual.html#llvm-adt-smallvector-h
+template <typename T,
+          unsigned N = CalculateSmallVectorDefaultInlinedElements<T>::value>
+class LLVM_GSL_OWNER SmallVector : public SmallVectorImpl<T>,
+                                   SmallVectorStorage<T, N> {
+public:
+  SmallVector() : SmallVectorImpl<T>(N) {}
+
+  ~SmallVector() {
+    // Destroy the constructed elements in the vector.
+    this->destroy_range(this->begin(), this->end());
+  }
+
+  explicit SmallVector(size_t Size, const T &Value = T())
+    : SmallVectorImpl<T>(N) {
+    this->assign(Size, Value);
+  }
+
+  template <typename ItTy,
+            typename = std::enable_if_t<std::is_convertible<
+                typename std::iterator_traits<ItTy>::iterator_category,
+                std::input_iterator_tag>::value>>
+  SmallVector(ItTy S, ItTy E) : SmallVectorImpl<T>(N) {
+    this->append(S, E);
+  }
+
+  template <typename RangeTy>
+  explicit SmallVector(const iterator_range<RangeTy> &R)
+      : SmallVectorImpl<T>(N) {
+    this->append(R.begin(), R.end());
+  }
+
+  SmallVector(std::initializer_list<T> IL) : SmallVectorImpl<T>(N) {
+    this->assign(IL);
+  }
+
+  SmallVector(const SmallVector &RHS) : SmallVectorImpl<T>(N) {
+    if (!RHS.empty())
+      SmallVectorImpl<T>::operator=(RHS);
+  }
+
+  SmallVector &operator=(const SmallVector &RHS) {
+    SmallVectorImpl<T>::operator=(RHS);
+    return *this;
+  }
+
+  SmallVector(SmallVector &&RHS) : SmallVectorImpl<T>(N) {
+    if (!RHS.empty())
+      SmallVectorImpl<T>::operator=(::std::move(RHS));
+  }
+
+  SmallVector(SmallVectorImpl<T> &&RHS) : SmallVectorImpl<T>(N) {
+    if (!RHS.empty())
+      SmallVectorImpl<T>::operator=(::std::move(RHS));
+  }
+
+  SmallVector &operator=(SmallVector &&RHS) {
+    if (N) {
+      SmallVectorImpl<T>::operator=(::std::move(RHS));
+      return *this;
+    }
+    // SmallVectorImpl<T>::operator= does not leverage N==0. Optimize the
+    // case.
+    if (this == &RHS)
+      return *this;
+    if (RHS.empty()) {
+      this->destroy_range(this->begin(), this->end());
+      this->Size = 0;
+    } else {
+      this->assignRemote(std::move(RHS));
+    }
+    return *this;
+  }
+
+  SmallVector &operator=(SmallVectorImpl<T> &&RHS) {
+    SmallVectorImpl<T>::operator=(::std::move(RHS));
+    return *this;
+  }
+
+  SmallVector &operator=(std::initializer_list<T> IL) {
+    this->assign(IL);
+    return *this;
+  }
+};
+
+template <typename T, unsigned N>
+inline size_t capacity_in_bytes(const SmallVector<T, N> &X) {
+  return X.capacity_in_bytes();
+}
+
+template <typename RangeType>
+using ValueTypeFromRangeType =
+    typename std::remove_const<typename std::remove_reference<
+        decltype(*std::begin(std::declval<RangeType &>()))>::type>::type;
+
+/// Given a range of type R, iterate the entire range and return a
+/// SmallVector with elements of the vector.  This is useful, for example,
+/// when you want to iterate a range and then sort the results.
+template <unsigned Size, typename R>
+SmallVector<ValueTypeFromRangeType<R>, Size> to_vector(R &&Range) {
+  return {std::begin(Range), std::end(Range)};
+}
+template <typename R>
+SmallVector<ValueTypeFromRangeType<R>,
+            CalculateSmallVectorDefaultInlinedElements<
+                ValueTypeFromRangeType<R>>::value>
+to_vector(R &&Range) {
+  return {std::begin(Range), std::end(Range)};
+}
+
+} // end namespace wpi
+
+namespace std {
+
+  /// Implement std::swap in terms of SmallVector swap.
+  template<typename T>
+  inline void
+  swap(wpi::SmallVectorImpl<T> &LHS, wpi::SmallVectorImpl<T> &RHS) {
+    LHS.swap(RHS);
+  }
+
+  /// Implement std::swap in terms of SmallVector swap.
+  template<typename T, unsigned N>
+  inline void
+  swap(wpi::SmallVector<T, N> &LHS, wpi::SmallVector<T, N> &RHS) {
+    LHS.swap(RHS);
+  }
+
+} // end namespace std
+
+#endif // WPIUTIL_WPI_SMALLVECTOR_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/SmallVectorMemoryBuffer.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/SmallVectorMemoryBuffer.h
new file mode 100644
index 0000000..6173714
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/SmallVectorMemoryBuffer.h
@@ -0,0 +1,63 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+//===- SmallVectorMemoryBuffer.h --------------------------------*- C++ -*-===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+// This file declares a wrapper class to hold the memory into which an
+// object will be generated.
+//
+//===----------------------------------------------------------------------===//
+
+#pragma once
+
+#include <string>
+#include <string_view>
+#include <utility>
+
+#include "wpi/MemoryBuffer.h"
+#include "wpi/SmallVector.h"
+#include "wpi/raw_ostream.h"
+
+namespace wpi {
+
+/// SmallVector-backed MemoryBuffer instance.
+///
+/// This class enables efficient construction of MemoryBuffers from SmallVector
+/// instances.
+class SmallVectorMemoryBuffer : public MemoryBuffer {
+ public:
+  /// Construct an SmallVectorMemoryBuffer from the given SmallVector
+  /// r-value.
+  SmallVectorMemoryBuffer(SmallVectorImpl<uint8_t>&& sv)  // NOLINT
+      : m_sv(std::move(sv)), m_bufferName("<in-memory object>") {
+    Init(this->m_sv.begin(), this->m_sv.end());
+  }
+
+  /// Construct a named SmallVectorMemoryBuffer from the given
+  /// SmallVector r-value and StringRef.
+  SmallVectorMemoryBuffer(SmallVectorImpl<uint8_t>&& sv, std::string_view name)
+      : m_sv(std::move(sv)), m_bufferName(name) {
+    Init(this->m_sv.begin(), this->m_sv.end());
+  }
+
+  // Key function.
+  ~SmallVectorMemoryBuffer() override;
+
+  std::string_view GetBufferIdentifier() const override { return m_bufferName; }
+
+  BufferKind GetBufferKind() const override { return MemoryBuffer_Malloc; }
+
+ private:
+  SmallVector<uint8_t, 0> m_sv;
+  std::string m_bufferName;
+};
+
+}  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/StringExtras.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/StringExtras.h
new file mode 100644
index 0000000..75c637b
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/StringExtras.h
@@ -0,0 +1,724 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+//===- llvm/ADT/StringExtras.h - Useful string functions --------*- C++ -*-===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+// This file contains some functions that are useful when dealing with strings.
+//
+//===----------------------------------------------------------------------===//
+
+#pragma once
+
+#include <limits>
+#include <optional>
+#include <string>
+#include <string_view>
+#include <type_traits>
+#include <utility>
+
+namespace wpi {
+
+template <typename T>
+class SmallVectorImpl;
+
+/// hexdigit - Return the hexadecimal character for the
+/// given number \p X (which should be less than 16).
+constexpr char hexdigit(unsigned X, bool LowerCase = false) noexcept {
+  const char HexChar = LowerCase ? 'a' : 'A';
+  return X < 10 ? '0' + X : HexChar + X - 10;
+}
+
+/// Interpret the given character \p C as a hexadecimal digit and return its
+/// value.
+///
+/// If \p C is not a valid hex digit, -1U is returned.
+constexpr unsigned hexDigitValue(char C) noexcept {
+  if (C >= '0' && C <= '9') {
+    return C - '0';
+  }
+  if (C >= 'a' && C <= 'f') {
+    return C - 'a' + 10U;
+  }
+  if (C >= 'A' && C <= 'F') {
+    return C - 'A' + 10U;
+  }
+  return (std::numeric_limits<unsigned>::max)();
+}
+
+/// Checks if character \p C is one of the 10 decimal digits.
+constexpr bool isDigit(char C) noexcept {
+  return C >= '0' && C <= '9';
+}
+
+/// Checks if character \p C is a hexadecimal numeric character.
+constexpr bool isHexDigit(char C) noexcept {
+  return hexDigitValue(C) != (std::numeric_limits<unsigned>::max)();
+}
+
+/// Checks if character \p C is a valid letter as classified by "C" locale.
+constexpr bool isAlpha(char C) noexcept {
+  return ('a' <= C && C <= 'z') || ('A' <= C && C <= 'Z');
+}
+
+/// Checks whether character \p C is either a decimal digit or an uppercase or
+/// lowercase letter as classified by "C" locale.
+constexpr bool isAlnum(char C) noexcept {
+  return isAlpha(C) || isDigit(C);
+}
+
+/// Checks whether character \p C is valid ASCII (high bit is zero).
+constexpr bool isASCII(char C) noexcept {
+  return static_cast<unsigned char>(C) <= 127;
+}
+
+/// Checks whether character \p C is printable.
+///
+/// Locale-independent version of the C standard library isprint whose results
+/// may differ on different platforms.
+constexpr bool isPrint(char C) noexcept {
+  unsigned char UC = static_cast<unsigned char>(C);
+  return (0x20 <= UC) && (UC <= 0x7E);
+}
+
+/// Returns the corresponding lowercase character if \p x is uppercase.
+constexpr char toLower(char x) noexcept {
+  if (x >= 'A' && x <= 'Z') {
+    return x - 'A' + 'a';
+  }
+  return x;
+}
+
+/// Returns the corresponding uppercase character if \p x is lowercase.
+constexpr char toUpper(char x) noexcept {
+  if (x >= 'a' && x <= 'z') {
+    return x - 'a' + 'A';
+  }
+  return x;
+}
+
+inline std::string utohexstr(unsigned long long val,  // NOLINT(runtime/int)
+                             bool lowerCase = false) {
+  char buf[17];
+  char* bufptr = std::end(buf);
+
+  if (val == 0) {
+    *--bufptr = '0';
+  }
+
+  while (val) {
+    unsigned char mod = static_cast<unsigned char>(val) & 15;
+    *--bufptr = hexdigit(mod, lowerCase);
+    val >>= 4;
+  }
+
+  return std::string(bufptr, std::end(buf));
+}
+
+/**
+ * equals - Check for string equality, this is more efficient than
+ * compare() when the relative ordering of inequal strings isn't needed.
+ */
+constexpr bool equals(std::string_view lhs, std::string_view rhs) noexcept {
+  auto length = lhs.size();
+  return length == rhs.size() && std::string_view::traits_type::compare(
+                                     lhs.data(), rhs.data(), length) == 0;
+}
+
+/**
+ * compare_lower - Compare two strings, ignoring case.
+ */
+int compare_lower(std::string_view lhs, std::string_view rhs) noexcept;
+
+/**
+ * equals_lower - Check for string equality, ignoring case.
+ */
+constexpr bool equals_lower(std::string_view lhs,
+                            std::string_view rhs) noexcept {
+  return lhs.size() == rhs.size() && compare_lower(lhs, rhs) == 0;
+}
+
+/**
+ * Search for the first character @p ch in @p str, ignoring case.
+ *
+ * @returns The index of the first occurrence of @p ch, or npos if not
+ * found.
+ */
+std::string_view::size_type find_lower(
+    std::string_view str, char ch,
+    std::string_view::size_type from = 0) noexcept;
+
+/**
+ * Search for the first string @p other in @p str, ignoring case.
+ *
+ * @returns The index of the first occurrence of @p other, or npos if not
+ * found.
+ */
+std::string_view::size_type find_lower(
+    std::string_view str, std::string_view other,
+    std::string_view::size_type from = 0) noexcept;
+
+/**
+ * Search for the first string @p other in @p str, ignoring case.
+ *
+ * @returns The index of the first occurrence of @p other, or npos if not
+ * found.
+ */
+inline std::string_view::size_type find_lower(
+    std::string_view str, const char* other,
+    std::string_view::size_type from = 0) noexcept {
+  return find_lower(str, std::string_view{other}, from);
+}
+
+/**
+ * Search for the last character @p ch in @p str, ignoring case.
+ *
+ * @returns The index of the last occurrence of @p ch, or npos if not
+ * found.
+ */
+std::string_view::size_type rfind_lower(
+    std::string_view str, char ch,
+    std::string_view::size_type from = std::string_view::npos) noexcept;
+
+/**
+ * Search for the last string @p other in @p str, ignoring case.
+ *
+ * @returns The index of the last occurrence of @p other, or npos if not
+ * found.
+ */
+std::string_view::size_type rfind_lower(std::string_view str,
+                                        std::string_view other) noexcept;
+
+/**
+ * Search for the last string @p other in @p str, ignoring case.
+ *
+ * @returns The index of the last occurrence of @p other, or npos if not
+ * found.
+ */
+inline std::string_view::size_type rfind_lower(std::string_view str,
+                                               const char* other) noexcept {
+  return rfind_lower(str, std::string_view{other});
+}
+
+/**
+ * Returns the substring of @p str from [start, start + n).
+ *
+ * @param start The index of the starting character in the substring; if
+ * the index is npos or greater than the length of the string then the
+ * empty substring will be returned.
+ *
+ * @param n The number of characters to included in the substring. If n
+ * exceeds the number of characters remaining in the string, the string
+ * suffix (starting with @p start) will be returned.
+ */
+constexpr std::string_view substr(
+    std::string_view str, std::string_view::size_type start,
+    std::string_view::size_type n = std::string_view::npos) noexcept {
+  auto length = str.size();
+  start = (std::min)(start, length);
+  return {str.data() + start, (std::min)(n, length - start)};
+}
+
+/**
+ * Checks if @p str starts with the given @p prefix.
+ */
+constexpr bool starts_with(std::string_view str,
+                           std::string_view prefix) noexcept {
+  return substr(str, 0, prefix.size()) == prefix;
+}
+
+/**
+ * Checks if @p str starts with the given @p prefix.
+ */
+constexpr bool starts_with(std::string_view str, char prefix) noexcept {
+  return !str.empty() && std::string_view::traits_type::eq(str.front(), prefix);
+}
+
+/**
+ * Checks if @p str starts with the given @p prefix.
+ */
+constexpr bool starts_with(std::string_view str, const char* prefix) noexcept {
+  return starts_with(str, std::string_view(prefix));
+}
+
+/**
+ * Checks if @p str starts with the given @p prefix, ignoring case.
+ */
+bool starts_with_lower(std::string_view str, std::string_view prefix) noexcept;
+
+/**
+ * Checks if @p str starts with the given @p prefix, ignoring case.
+ */
+constexpr bool starts_with_lower(std::string_view str, char prefix) noexcept {
+  return !str.empty() && toLower(str.front()) == toLower(prefix);
+}
+
+/**
+ * Checks if @p str starts with the given @p prefix, ignoring case.
+ */
+inline bool starts_with_lower(std::string_view str,
+                              const char* prefix) noexcept {
+  return starts_with_lower(str, std::string_view(prefix));
+}
+
+/**
+ * Checks if @p str ends with the given @p suffix.
+ */
+constexpr bool ends_with(std::string_view str,
+                         std::string_view suffix) noexcept {
+  return str.size() >= suffix.size() &&
+         str.compare(str.size() - suffix.size(), std::string_view::npos,
+                     suffix) == 0;
+}
+
+/**
+ * Checks if @p str ends with the given @p suffix.
+ */
+constexpr bool ends_with(std::string_view str, char suffix) noexcept {
+  return !str.empty() && std::string_view::traits_type::eq(str.back(), suffix);
+}
+
+/**
+ * Checks if @p str ends with the given @p suffix.
+ */
+constexpr bool ends_with(std::string_view str, const char* suffix) noexcept {
+  return ends_with(str, std::string_view(suffix));
+}
+
+/**
+ * Checks if @p str ends with the given @p suffix, ignoring case.
+ */
+bool ends_with_lower(std::string_view str, std::string_view suffix) noexcept;
+
+/**
+ * Checks if @p str ends with the given @p suffix, ignoring case.
+ */
+constexpr bool ends_with_lower(std::string_view str, char suffix) noexcept {
+  return !str.empty() && toLower(str.back()) == toLower(suffix);
+}
+
+/**
+ * Checks if @p str ends with the given @p suffix, ignoring case.
+ */
+inline bool ends_with_lower(std::string_view str, const char* suffix) noexcept {
+  return ends_with_lower(str, std::string_view(suffix));
+}
+
+/**
+ * Checks if @p str contains the substring @p other.
+ */
+constexpr bool contains(std::string_view str, std::string_view other) noexcept {
+  return str.find(other) != std::string_view::npos;
+}
+
+/**
+ * Checks if @p str contains the substring @p other.
+ */
+constexpr bool contains(std::string_view str, char ch) noexcept {
+  return str.find(ch) != std::string_view::npos;
+}
+
+/**
+ * Checks if @p str contains the substring @p other.
+ */
+constexpr bool contains(std::string_view str, const char* other) noexcept {
+  return str.find(other) != std::string_view::npos;
+}
+
+/**
+ * Checks if @p str contains the substring @p other, ignoring case.
+ */
+inline bool contains_lower(std::string_view str,
+                           std::string_view other) noexcept {
+  return find_lower(str, other) != std::string_view::npos;
+}
+
+/**
+ * Checks if @p str contains the substring @p other, ignoring case.
+ */
+inline bool contains_lower(std::string_view str, char ch) noexcept {
+  return find_lower(str, ch) != std::string_view::npos;
+}
+
+/**
+ * Checks if @p str contains the substring @p other, ignoring case.
+ */
+inline bool contains_lower(std::string_view str, const char* other) noexcept {
+  return find_lower(str, other) != std::string_view::npos;
+}
+
+/**
+ * Return a string_view equal to @p str but with the first @p n elements
+ * dropped.
+ */
+constexpr std::string_view drop_front(
+    std::string_view str, std::string_view::size_type n = 1) noexcept {
+  str.remove_prefix(n);
+  return str;
+}
+
+/**
+ * Return a string_view equal to @p str but with the last @p n elements dropped.
+ */
+constexpr std::string_view drop_back(
+    std::string_view str, std::string_view::size_type n = 1) noexcept {
+  str.remove_suffix(n);
+  return str;
+}
+
+/**
+ * Returns a view equal to @p str but with only the first @p n
+ * elements remaining.  If @p n is greater than the length of the
+ * string, the entire string is returned.
+ */
+constexpr std::string_view take_front(
+    std::string_view str, std::string_view::size_type n = 1) noexcept {
+  auto length = str.size();
+  if (n >= length) {
+    return str;
+  }
+  return drop_back(str, length - n);
+}
+
+/**
+ * Returns a view equal to @p str but with only the last @p n
+ * elements remaining.  If @p n is greater than the length of the
+ * string, the entire string is returned.
+ */
+constexpr std::string_view take_back(
+    std::string_view str, std::string_view::size_type n = 1) noexcept {
+  auto length = str.size();
+  if (n >= length) {
+    return str;
+  }
+  return drop_front(str, length - n);
+}
+
+/**
+ * Returns a reference to the substring of @p str from [start, end).
+ *
+ * @param start The index of the starting character in the substring; if
+ * the index is npos or greater than the length of the string then the
+ * empty substring will be returned.
+ *
+ * @param end The index following the last character to include in the
+ * substring. If this is npos or exceeds the number of characters
+ * remaining in the string, the string suffix (starting with @p start)
+ * will be returned. If this is less than @p start, an empty string will
+ * be returned.
+ */
+constexpr std::string_view slice(std::string_view str,
+                                 std::string_view::size_type start,
+                                 std::string_view::size_type end) noexcept {
+  auto length = str.size();
+  start = (std::min)(start, length);
+  end = (std::min)((std::max)(start, end), length);
+  return {str.data() + start, end - start};
+}
+
+/**
+ * Splits @p str into two substrings around the first occurrence of a separator
+ * character.
+ *
+ * If @p separator is in the string, then the result is a pair (LHS, RHS)
+ * such that (str == LHS + separator + RHS) is true and RHS is
+ * maximal. If @p separator is not in the string, then the result is a
+ * pair (LHS, RHS) where (str == LHS) and (RHS == "").
+ *
+ * @param separator The character to split on.
+ * @returns The split substrings.
+ */
+constexpr std::pair<std::string_view, std::string_view> split(
+    std::string_view str, char separator) noexcept {
+  auto idx = str.find(separator);
+  if (idx == std::string_view::npos) {
+    return {str, {}};
+  }
+  return {slice(str, 0, idx), slice(str, idx + 1, std::string_view::npos)};
+}
+
+/**
+ * Splits @p str into two substrings around the first occurrence of a separator
+ * string.
+ *
+ * If @p separator is in the string, then the result is a pair (LHS, RHS)
+ * such that (str == LHS + separator + RHS) is true and RHS is
+ * maximal. If @p separator is not in the string, then the result is a
+ * pair (LHS, RHS) where (str == LHS) and (RHS == "").
+ *
+ * @param separator The string to split on.
+ * @return The split substrings.
+ */
+constexpr std::pair<std::string_view, std::string_view> split(
+    std::string_view str, std::string_view separator) noexcept {
+  auto idx = str.find(separator);
+  if (idx == std::string_view::npos) {
+    return {str, {}};
+  }
+  return {slice(str, 0, idx),
+          slice(str, idx + separator.size(), std::string_view::npos)};
+}
+
+/**
+ * Splits @p str into two substrings around the last occurrence of a separator
+ * character.
+ *
+ * If @p separator is in the string, then the result is a pair (LHS, RHS)
+ * such that (str == LHS + separator + RHS) is true and RHS is
+ * minimal. If @p separator is not in the string, then the result is a
+ * pair (LHS, RHS) where (str == LHS) and (RHS == "").
+ *
+ * @param separator The string to split on.
+ * @return The split substrings.
+ */
+constexpr std::pair<std::string_view, std::string_view> rsplit(
+    std::string_view str, char separator) noexcept {
+  auto idx = str.rfind(separator);
+  if (idx == std::string_view::npos) {
+    return {str, {}};
+  }
+  return {slice(str, 0, idx), slice(str, idx + 1, std::string_view::npos)};
+}
+
+/**
+ * Splits @p str into two substrings around the last occurrence of a separator
+ * string.
+ *
+ * If @p separator is in the string, then the result is a pair (LHS, RHS)
+ * such that (str == LHS + separator + RHS) is true and RHS is
+ * minimal. If @p separator is not in the string, then the result is a
+ * pair (LHS, RHS) where (str == LHS) and (RHS == "").
+ *
+ * @param separator The string to split on.
+ * @return The split substrings.
+ */
+constexpr std::pair<std::string_view, std::string_view> rsplit(
+    std::string_view str, std::string_view separator) noexcept {
+  auto idx = str.rfind(separator);
+  if (idx == std::string_view::npos) {
+    return {str, {}};
+  }
+  return {slice(str, 0, idx),
+          slice(str, idx + separator.size(), std::string_view::npos)};
+}
+
+/**
+ * Splits @p str into substrings around the occurrences of a separator string.
+ *
+ * Each substring is stored in @p arr. If @p maxSplit is >= 0, at most
+ * @p maxSplit splits are done and consequently <= @p maxSplit + 1
+ * elements are added to arr.
+ * If @p keepEmpty is false, empty strings are not added to @p arr. They
+ * still count when considering @p maxSplit
+ * An useful invariant is that
+ * separator.join(arr) == str if maxSplit == -1 and keepEmpty == true
+ *
+ * @param arr Where to put the substrings.
+ * @param separator The string to split on.
+ * @param maxSplit The maximum number of times the string is split.
+ * @param keepEmpty True if empty substring should be added.
+ */
+void split(std::string_view str, SmallVectorImpl<std::string_view>& arr,
+           std::string_view separator, int maxSplit = -1,
+           bool keepEmpty = true) noexcept;
+
+/**
+ * Splits @p str into substrings around the occurrences of a separator
+ * character.
+ *
+ * Each substring is stored in @p arr. If @p maxSplit is >= 0, at most
+ * @p maxSplit splits are done and consequently <= @p maxSplit + 1
+ * elements are added to arr.
+ * If @p keepEmpty is false, empty strings are not added to @p arr. They
+ * still count when considering @p maxSplit
+ * An useful invariant is that
+ * separator.join(arr) == str if maxSplit == -1 and keepEmpty == true
+ *
+ * @param arr Where to put the substrings.
+ * @param separator The character to split on.
+ * @param maxSplit The maximum number of times the string is split.
+ * @param keepEmpty True if empty substring should be added.
+ */
+void split(std::string_view str, SmallVectorImpl<std::string_view>& arr,
+           char separator, int maxSplit = -1, bool keepEmpty = true) noexcept;
+
+/**
+ * Returns @p str with consecutive @p ch characters starting from the
+ * the left removed.
+ */
+constexpr std::string_view ltrim(std::string_view str, char ch) noexcept {
+  return drop_front(str, (std::min)(str.size(), str.find_first_not_of(ch)));
+}
+
+/**
+ * Returns @p str with consecutive characters in @p chars starting from
+ * the left removed.
+ */
+constexpr std::string_view ltrim(
+    std::string_view str, std::string_view chars = " \t\n\v\f\r") noexcept {
+  return drop_front(str, (std::min)(str.size(), str.find_first_not_of(chars)));
+}
+
+/**
+ * Returns @p str with consecutive @p Char characters starting from the
+ * right removed.
+ */
+constexpr std::string_view rtrim(std::string_view str, char ch) noexcept {
+  return drop_back(
+      str, str.size() - (std::min)(str.size(), str.find_last_not_of(ch) + 1));
+}
+
+/**
+ * Returns @p str with consecutive characters in @p chars starting from
+ * the right removed.
+ */
+constexpr std::string_view rtrim(
+    std::string_view str, std::string_view chars = " \t\n\v\f\r") noexcept {
+  return drop_back(
+      str,
+      str.size() - (std::min)(str.size(), str.find_last_not_of(chars) + 1));
+}
+
+/**
+ * Returns @p str with consecutive @p ch characters starting from the
+ * left and right removed.
+ */
+constexpr std::string_view trim(std::string_view str, char ch) noexcept {
+  return rtrim(ltrim(str, ch), ch);
+}
+
+/**
+ * Returns @p str with consecutive characters in @p chars starting from
+ * the left and right removed.
+ */
+constexpr std::string_view trim(
+    std::string_view str, std::string_view chars = " \t\n\v\f\r") noexcept {
+  return rtrim(ltrim(str, chars), chars);
+}
+
+namespace detail {
+bool GetAsUnsignedInteger(
+    std::string_view str, unsigned radix,
+    unsigned long long& result) noexcept;  // NOLINT(runtime/int)
+bool GetAsSignedInteger(std::string_view str, unsigned radix,
+                        long long& result) noexcept;  // NOLINT(runtime/int)
+
+bool ConsumeUnsignedInteger(
+    std::string_view& str, unsigned radix,
+    unsigned long long& result) noexcept;  // NOLINT(runtime/int)
+bool ConsumeSignedInteger(std::string_view& str, unsigned radix,
+                          long long& result) noexcept;  // NOLINT(runtime/int)
+}  // namespace detail
+
+/**
+ * Parses the string @p str as an integer of the specified radix.  If
+ * @p radix is specified as zero, this does radix autosensing using
+ * extended C rules: 0 is octal, 0x is hex, 0b is binary.
+ *
+ * If the string is invalid or if only a subset of the string is valid,
+ * this returns nullopt to signify the error.  The string is considered
+ * erroneous if empty or if it overflows T.
+ */
+template <typename T,
+          std::enable_if_t<std::numeric_limits<T>::is_signed, bool> = true>
+inline std::optional<T> parse_integer(std::string_view str,
+                                      unsigned radix) noexcept {
+  long long val;  // NOLINT(runtime/int)
+  if (detail::GetAsSignedInteger(str, radix, val) ||
+      static_cast<T>(val) != val) {
+    return std::nullopt;
+  }
+  return val;
+}
+
+template <typename T,
+          std::enable_if_t<!std::numeric_limits<T>::is_signed, bool> = true>
+inline std::optional<T> parse_integer(std::string_view str,
+                                      unsigned radix) noexcept {
+  using Int = unsigned long long;  // NOLINT(runtime/int)
+  Int val;
+  // The additional cast to unsigned long long is required to avoid the
+  // Visual C++ warning C4805: '!=' : unsafe mix of type 'bool' and type
+  // 'unsigned __int64' when instantiating getAsInteger with T = bool.
+  if (detail::GetAsUnsignedInteger(str, radix, val) ||
+      static_cast<Int>(static_cast<T>(val)) != val) {
+    return std::nullopt;
+  }
+  return val;
+}
+
+/**
+ * Parses the string @p str as an integer of the specified radix.  If
+ * @p radix is specified as zero, this does radix autosensing using
+ * extended C rules: 0 is octal, 0x is hex, 0b is binary.
+ *
+ * If the string does not begin with a number of the specified radix,
+ * this returns nullopt to signify the error. The string is considered
+ * erroneous if empty or if it overflows T.
+ * The portion of the string representing the discovered numeric value
+ * is removed from the beginning of the string.
+ */
+template <typename T,
+          std::enable_if_t<std::numeric_limits<T>::is_signed, bool> = true>
+inline std::optional<T> consume_integer(std::string_view* str,
+                                        unsigned radix) noexcept {
+  using Int = long long;  // NOLINT(runtime/int)
+  Int val;
+  if (detail::ConsumeSignedInteger(*str, radix, val) ||
+      static_cast<Int>(static_cast<T>(val)) != val) {
+    return std::nullopt;
+  }
+  return val;
+}
+
+template <typename T,
+          std::enable_if_t<!std::numeric_limits<T>::is_signed, bool> = true>
+inline std::optional<T> consume_integer(std::string_view* str,
+                                        unsigned radix) noexcept {
+  using Int = unsigned long long;  // NOLINT(runtime/int)
+  Int val;
+  if (detail::ConsumeUnsignedInteger(*str, radix, val) ||
+      static_cast<Int>(static_cast<T>(val)) != val) {
+    return std::nullopt;
+  }
+  return val;
+}
+
+/**
+ * Parses the string @p str as a floating point value.
+ *
+ * If the string is invalid or if only a subset of the string is valid,
+ * this returns nullopt to signify the error.  The string is considered
+ * erroneous if empty or if it overflows T.
+ */
+template <typename T>
+std::optional<T> parse_float(std::string_view str) noexcept;
+
+template <>
+std::optional<float> parse_float<float>(std::string_view str) noexcept;
+template <>
+std::optional<double> parse_float<double>(std::string_view str) noexcept;
+template <>
+std::optional<long double> parse_float<long double>(
+    std::string_view str) noexcept;
+
+/**
+ * Unescapes a C-style string (reverse operation to raw_ostream::write_escaped).
+ * Scans through @p str until either the end is reached or an unescaped double
+ * quote character is found.
+ *
+ * @param str input string
+ * @param buf buffer for unescaped characters
+ * @return pair of the unescaped string and any remaining input
+ */
+std::pair<std::string_view, std::string_view> UnescapeCString(
+    std::string_view str, SmallVectorImpl<char>& buf);
+
+}  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/StringMap.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/StringMap.h
new file mode 100644
index 0000000..c7da670
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/StringMap.h
@@ -0,0 +1,593 @@
+//===- StringMap.h - String Hash table map interface ------------*- C++ -*-===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+///
+/// \file
+/// This file defines the StringMap class.
+///
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_STRINGMAP_H
+#define WPIUTIL_WPI_STRINGMAP_H
+
+#include "wpi/StringMapEntry.h"
+#include "wpi/iterator.h"
+#include "wpi/AllocatorBase.h"
+#include "wpi/MemAlloc.h"
+#include "wpi/SmallVector.h"
+#include "wpi/iterator.h"
+#include "wpi/iterator_range.h"
+#include "wpi/PointerLikeTypeTraits.h"
+#include <initializer_list>
+#include <iterator>
+
+namespace wpi {
+
+template <typename ValueTy> class StringMapConstIterator;
+template <typename ValueTy> class StringMapIterator;
+template <typename ValueTy> class StringMapKeyIterator;
+
+/// StringMapImpl - This is the base class of StringMap that is shared among
+/// all of its instantiations.
+class StringMapImpl {
+protected:
+  // Array of NumBuckets pointers to entries, null pointers are holes.
+  // TheTable[NumBuckets] contains a sentinel value for easy iteration. Followed
+  // by an array of the actual hash values as unsigned integers.
+  StringMapEntryBase **TheTable = nullptr;
+  unsigned NumBuckets = 0;
+  unsigned NumItems = 0;
+  unsigned NumTombstones = 0;
+  unsigned ItemSize;
+
+protected:
+  explicit StringMapImpl(unsigned itemSize) : ItemSize(itemSize) {}
+  StringMapImpl(StringMapImpl &&RHS) noexcept
+      : TheTable(RHS.TheTable), NumBuckets(RHS.NumBuckets),
+        NumItems(RHS.NumItems), NumTombstones(RHS.NumTombstones),
+        ItemSize(RHS.ItemSize) {
+    RHS.TheTable = nullptr;
+    RHS.NumBuckets = 0;
+    RHS.NumItems = 0;
+    RHS.NumTombstones = 0;
+  }
+
+  StringMapImpl(unsigned InitSize, unsigned ItemSize);
+  unsigned RehashTable(unsigned BucketNo = 0);
+
+  /// LookupBucketFor - Look up the bucket that the specified string should end
+  /// up in.  If it already exists as a key in the map, the Item pointer for the
+  /// specified bucket will be non-null.  Otherwise, it will be null.  In either
+  /// case, the FullHashValue field of the bucket will be set to the hash value
+  /// of the string.
+  unsigned LookupBucketFor(std::string_view Key);
+
+  /// FindKey - Look up the bucket that contains the specified key. If it exists
+  /// in the map, return the bucket number of the key.  Otherwise return -1.
+  /// This does not modify the map.
+  int FindKey(std::string_view Key) const;
+
+  /// RemoveKey - Remove the specified StringMapEntry from the table, but do not
+  /// delete it.  This aborts if the value isn't in the table.
+  void RemoveKey(StringMapEntryBase *V);
+
+  /// RemoveKey - Remove the StringMapEntry for the specified key from the
+  /// table, returning it.  If the key is not in the table, this returns null.
+  StringMapEntryBase *RemoveKey(std::string_view Key);
+
+  /// Allocate the table with the specified number of buckets and otherwise
+  /// setup the map as empty.
+  void init(unsigned Size);
+
+public:
+  static constexpr uintptr_t TombstoneIntVal =
+      static_cast<uintptr_t>(-1)
+      << PointerLikeTypeTraits<StringMapEntryBase *>::NumLowBitsAvailable;
+
+  static StringMapEntryBase *getTombstoneVal() {
+    return reinterpret_cast<StringMapEntryBase *>(TombstoneIntVal);
+  }
+
+  unsigned getNumBuckets() const { return NumBuckets; }
+  unsigned getNumItems() const { return NumItems; }
+
+  bool empty() const { return NumItems == 0; }
+  unsigned size() const { return NumItems; }
+
+  void swap(StringMapImpl &Other) {
+    std::swap(TheTable, Other.TheTable);
+    std::swap(NumBuckets, Other.NumBuckets);
+    std::swap(NumItems, Other.NumItems);
+    std::swap(NumTombstones, Other.NumTombstones);
+  }
+};
+
+/// StringMap - This is an unconventional map that is specialized for handling
+/// keys that are "strings", which are basically ranges of bytes. This does some
+/// funky memory allocation and hashing things to make it extremely efficient,
+/// storing the string data *after* the value in the map.
+template <typename ValueTy, typename AllocatorTy = MallocAllocator>
+class StringMap : public StringMapImpl {
+  AllocatorTy Allocator;
+
+public:
+  using MapEntryTy = StringMapEntry<ValueTy>;
+
+  StringMap() : StringMapImpl(static_cast<unsigned>(sizeof(MapEntryTy))) {}
+
+  explicit StringMap(unsigned InitialSize)
+      : StringMapImpl(InitialSize, static_cast<unsigned>(sizeof(MapEntryTy))) {}
+
+  explicit StringMap(AllocatorTy A)
+      : StringMapImpl(static_cast<unsigned>(sizeof(MapEntryTy))), Allocator(A) {
+  }
+
+  StringMap(unsigned InitialSize, AllocatorTy A)
+      : StringMapImpl(InitialSize, static_cast<unsigned>(sizeof(MapEntryTy))),
+        Allocator(A) {}
+
+  StringMap(std::initializer_list<std::pair<std::string_view, ValueTy>> List)
+      : StringMapImpl(List.size(), static_cast<unsigned>(sizeof(MapEntryTy))) {
+    insert(List);
+  }
+
+  StringMap(StringMap &&RHS)
+      : StringMapImpl(std::move(RHS)), Allocator(std::move(RHS.Allocator)) {}
+
+  StringMap(const StringMap &RHS)
+      : StringMapImpl(static_cast<unsigned>(sizeof(MapEntryTy))),
+        Allocator(RHS.Allocator) {
+    if (RHS.empty())
+      return;
+
+    // Allocate TheTable of the same size as RHS's TheTable, and set the
+    // sentinel appropriately (and NumBuckets).
+    init(RHS.NumBuckets);
+    unsigned *HashTable = (unsigned *)(TheTable + NumBuckets + 1),
+             *RHSHashTable = (unsigned *)(RHS.TheTable + NumBuckets + 1);
+
+    NumItems = RHS.NumItems;
+    NumTombstones = RHS.NumTombstones;
+    for (unsigned I = 0, E = NumBuckets; I != E; ++I) {
+      StringMapEntryBase *Bucket = RHS.TheTable[I];
+      if (!Bucket || Bucket == getTombstoneVal()) {
+        TheTable[I] = Bucket;
+        continue;
+      }
+
+      TheTable[I] = MapEntryTy::Create(
+          static_cast<MapEntryTy *>(Bucket)->getKey(), Allocator,
+          static_cast<MapEntryTy *>(Bucket)->getValue());
+      HashTable[I] = RHSHashTable[I];
+    }
+
+    // Note that here we've copied everything from the RHS into this object,
+    // tombstones included. We could, instead, have re-probed for each key to
+    // instantiate this new object without any tombstone buckets. The
+    // assumption here is that items are rarely deleted from most StringMaps,
+    // and so tombstones are rare, so the cost of re-probing for all inputs is
+    // not worthwhile.
+  }
+
+  StringMap &operator=(StringMap RHS) {
+    StringMapImpl::swap(RHS);
+    std::swap(Allocator, RHS.Allocator);
+    return *this;
+  }
+
+  ~StringMap() {
+    // Delete all the elements in the map, but don't reset the elements
+    // to default values.  This is a copy of clear(), but avoids unnecessary
+    // work not required in the destructor.
+    if (!empty()) {
+      for (unsigned I = 0, E = NumBuckets; I != E; ++I) {
+        StringMapEntryBase *Bucket = TheTable[I];
+        if (Bucket && Bucket != getTombstoneVal()) {
+          static_cast<MapEntryTy *>(Bucket)->Destroy(Allocator);
+        }
+      }
+    }
+    free(TheTable);
+  }
+
+  AllocatorTy &getAllocator() { return Allocator; }
+  const AllocatorTy &getAllocator() const { return Allocator; }
+
+  using key_type = const char *;
+  using mapped_type = ValueTy;
+  using value_type = StringMapEntry<ValueTy>;
+  using size_type = size_t;
+
+  using const_iterator = StringMapConstIterator<ValueTy>;
+  using iterator = StringMapIterator<ValueTy>;
+
+  iterator begin() { return iterator(TheTable, NumBuckets == 0); }
+  iterator end() { return iterator(TheTable + NumBuckets, true); }
+  const_iterator begin() const {
+    return const_iterator(TheTable, NumBuckets == 0);
+  }
+  const_iterator end() const {
+    return const_iterator(TheTable + NumBuckets, true);
+  }
+
+  iterator_range<StringMapKeyIterator<ValueTy>> keys() const {
+    return make_range(StringMapKeyIterator<ValueTy>(begin()),
+                      StringMapKeyIterator<ValueTy>(end()));
+  }
+
+  iterator find(std::string_view Key) {
+    int Bucket = FindKey(Key);
+    if (Bucket == -1)
+      return end();
+    return iterator(TheTable + Bucket, true);
+  }
+
+  const_iterator find(std::string_view Key) const {
+    int Bucket = FindKey(Key);
+    if (Bucket == -1)
+      return end();
+    return const_iterator(TheTable + Bucket, true);
+  }
+
+  /// lookup - Return the entry for the specified key, or a default
+  /// constructed value if no such entry exists.
+  ValueTy lookup(std::string_view Key) const {
+    const_iterator it = find(Key);
+    if (it != end())
+      return it->second;
+    return ValueTy();
+  }
+
+  /// Lookup the ValueTy for the \p Key, or create a default constructed value
+  /// if the key is not in the map.
+  ValueTy &operator[](std::string_view Key) { return try_emplace(Key).first->second; }
+
+  /// count - Return 1 if the element is in the map, 0 otherwise.
+  size_type count(std::string_view Key) const { return find(Key) == end() ? 0 : 1; }
+
+  template <typename InputTy>
+  size_type count(const StringMapEntry<InputTy> &MapEntry) const {
+    return count(MapEntry.getKey());
+  }
+
+  /// equal - check whether both of the containers are equal.
+  bool operator==(const StringMap &RHS) const {
+    if (size() != RHS.size())
+      return false;
+
+    for (const auto &KeyValue : *this) {
+      auto FindInRHS = RHS.find(KeyValue.getKey());
+
+      if (FindInRHS == RHS.end())
+        return false;
+
+      if (!(KeyValue.getValue() == FindInRHS->getValue()))
+        return false;
+    }
+
+    return true;
+  }
+
+  bool operator!=(const StringMap &RHS) const { return !(*this == RHS); }
+
+  /// insert - Insert the specified key/value pair into the map.  If the key
+  /// already exists in the map, return false and ignore the request, otherwise
+  /// insert it and return true.
+  bool insert(MapEntryTy *KeyValue) {
+    unsigned BucketNo = LookupBucketFor(KeyValue->getKey());
+    StringMapEntryBase *&Bucket = TheTable[BucketNo];
+    if (Bucket && Bucket != getTombstoneVal())
+      return false; // Already exists in map.
+
+    if (Bucket == getTombstoneVal())
+      --NumTombstones;
+    Bucket = KeyValue;
+    ++NumItems;
+    assert(NumItems + NumTombstones <= NumBuckets);
+
+    RehashTable();
+    return true;
+  }
+
+  /// insert - Inserts the specified key/value pair into the map if the key
+  /// isn't already in the map. The bool component of the returned pair is true
+  /// if and only if the insertion takes place, and the iterator component of
+  /// the pair points to the element with key equivalent to the key of the pair.
+  std::pair<iterator, bool> insert(std::pair<std::string_view, ValueTy> KV) {
+    return try_emplace(KV.first, std::move(KV.second));
+  }
+
+  /// Inserts elements from range [first, last). If multiple elements in the
+  /// range have keys that compare equivalent, it is unspecified which element
+  /// is inserted .
+  template <typename InputIt> void insert(InputIt First, InputIt Last) {
+    for (InputIt It = First; It != Last; ++It)
+      insert(*It);
+  }
+
+  ///  Inserts elements from initializer list ilist. If multiple elements in
+  /// the range have keys that compare equivalent, it is unspecified which
+  /// element is inserted
+  void insert(std::initializer_list<std::pair<std::string_view, ValueTy>> List) {
+    insert(List.begin(), List.end());
+  }
+
+  /// Inserts an element or assigns to the current element if the key already
+  /// exists. The return type is the same as try_emplace.
+  template <typename V>
+  std::pair<iterator, bool> insert_or_assign(std::string_view Key, V &&Val) {
+    auto Ret = try_emplace(Key, std::forward<V>(Val));
+    if (!Ret.second)
+      Ret.first->second = std::forward<V>(Val);
+    return Ret;
+  }
+
+  /// Emplace a new element for the specified key into the map if the key isn't
+  /// already in the map. The bool component of the returned pair is true
+  /// if and only if the insertion takes place, and the iterator component of
+  /// the pair points to the element with key equivalent to the key of the pair.
+  template <typename... ArgsTy>
+  std::pair<iterator, bool> try_emplace(std::string_view Key, ArgsTy &&... Args) {
+    unsigned BucketNo = LookupBucketFor(Key);
+    StringMapEntryBase *&Bucket = TheTable[BucketNo];
+    if (Bucket && Bucket != getTombstoneVal())
+      return std::make_pair(iterator(TheTable + BucketNo, false),
+                            false); // Already exists in map.
+
+    if (Bucket == getTombstoneVal())
+      --NumTombstones;
+    Bucket = MapEntryTy::Create(Key, Allocator, std::forward<ArgsTy>(Args)...);
+    ++NumItems;
+    assert(NumItems + NumTombstones <= NumBuckets);
+
+    BucketNo = RehashTable(BucketNo);
+    return std::make_pair(iterator(TheTable + BucketNo, false), true);
+  }
+
+  // clear - Empties out the StringMap
+  void clear() {
+    if (empty())
+      return;
+
+    // Zap all values, resetting the keys back to non-present (not tombstone),
+    // which is safe because we're removing all elements.
+    for (unsigned I = 0, E = NumBuckets; I != E; ++I) {
+      StringMapEntryBase *&Bucket = TheTable[I];
+      if (Bucket && Bucket != getTombstoneVal()) {
+        static_cast<MapEntryTy *>(Bucket)->Destroy(Allocator);
+      }
+      Bucket = nullptr;
+    }
+
+    NumItems = 0;
+    NumTombstones = 0;
+  }
+
+  /// remove - Remove the specified key/value pair from the map, but do not
+  /// erase it.  This aborts if the key is not in the map.
+  void remove(MapEntryTy *KeyValue) { RemoveKey(KeyValue); }
+
+  void erase(iterator I) {
+    MapEntryTy &V = *I;
+    remove(&V);
+    V.Destroy(Allocator);
+  }
+
+  bool erase(std::string_view Key) {
+    iterator I = find(Key);
+    if (I == end())
+      return false;
+    erase(I);
+    return true;
+  }
+};
+
+template <typename DerivedTy, typename ValueTy>
+class StringMapIterBase
+    : public iterator_facade_base<DerivedTy, std::forward_iterator_tag,
+                                  ValueTy> {
+protected:
+  StringMapEntryBase **Ptr = nullptr;
+
+public:
+  StringMapIterBase() = default;
+
+  explicit StringMapIterBase(StringMapEntryBase **Bucket,
+                             bool NoAdvance = false)
+      : Ptr(Bucket) {
+    if (!NoAdvance)
+      AdvancePastEmptyBuckets();
+  }
+
+  DerivedTy &operator=(const DerivedTy &Other) {
+    Ptr = Other.Ptr;
+    return static_cast<DerivedTy &>(*this);
+  }
+
+  friend bool operator==(const DerivedTy &LHS, const DerivedTy &RHS) {
+    return LHS.Ptr == RHS.Ptr;
+  }
+
+  DerivedTy &operator++() { // Preincrement
+    ++Ptr;
+    AdvancePastEmptyBuckets();
+    return static_cast<DerivedTy &>(*this);
+  }
+
+  DerivedTy operator++(int) { // Post-increment
+    DerivedTy Tmp(Ptr);
+    ++*this;
+    return Tmp;
+  }
+
+  DerivedTy &operator--() { // Predecrement
+    --Ptr;
+    ReversePastEmptyBuckets();
+    return static_cast<DerivedTy &>(*this);
+  }
+
+  DerivedTy operator--(int) { // Post-decrement
+    DerivedTy Tmp(Ptr);
+    --*this;
+    return Tmp;
+  }
+
+private:
+  void AdvancePastEmptyBuckets() {
+    while (*Ptr == nullptr || *Ptr == StringMapImpl::getTombstoneVal())
+      ++Ptr;
+  }
+  void ReversePastEmptyBuckets() {
+    while (*Ptr == nullptr || *Ptr == StringMapImpl::getTombstoneVal())
+      --Ptr;
+  }
+};
+
+template <typename ValueTy>
+class StringMapConstIterator
+    : public StringMapIterBase<StringMapConstIterator<ValueTy>,
+                               const StringMapEntry<ValueTy>> {
+  using base = StringMapIterBase<StringMapConstIterator<ValueTy>,
+                                 const StringMapEntry<ValueTy>>;
+
+public:
+  StringMapConstIterator() = default;
+  explicit StringMapConstIterator(StringMapEntryBase **Bucket,
+                                  bool NoAdvance = false)
+      : base(Bucket, NoAdvance) {}
+
+  const StringMapEntry<ValueTy> &operator*() const {
+    return *static_cast<const StringMapEntry<ValueTy> *>(*this->Ptr);
+  }
+};
+
+template <typename ValueTy>
+class StringMapIterator : public StringMapIterBase<StringMapIterator<ValueTy>,
+                                                   StringMapEntry<ValueTy>> {
+  using base =
+      StringMapIterBase<StringMapIterator<ValueTy>, StringMapEntry<ValueTy>>;
+
+public:
+  StringMapIterator() = default;
+  explicit StringMapIterator(StringMapEntryBase **Bucket,
+                             bool NoAdvance = false)
+      : base(Bucket, NoAdvance) {}
+
+  StringMapEntry<ValueTy> &operator*() const {
+    return *static_cast<StringMapEntry<ValueTy> *>(*this->Ptr);
+  }
+
+  operator StringMapConstIterator<ValueTy>() const {
+    return StringMapConstIterator<ValueTy>(this->Ptr, true);
+  }
+};
+
+template <typename ValueTy>
+class StringMapKeyIterator
+    : public iterator_adaptor_base<StringMapKeyIterator<ValueTy>,
+                                   StringMapConstIterator<ValueTy>,
+                                   std::forward_iterator_tag, std::string_view> {
+  using base = iterator_adaptor_base<StringMapKeyIterator<ValueTy>,
+                                     StringMapConstIterator<ValueTy>,
+                                     std::forward_iterator_tag, std::string_view>;
+
+public:
+  StringMapKeyIterator() = default;
+  explicit StringMapKeyIterator(StringMapConstIterator<ValueTy> Iter)
+      : base(std::move(Iter)) {}
+
+  std::string_view operator*() const { return this->wrapped()->getKey(); }
+};
+
+template <typename ValueTy>
+bool operator==(const StringMap<ValueTy>& lhs, const StringMap<ValueTy>& rhs) {
+  // same instance?
+  if (&lhs == &rhs) return true;
+
+  // first check that sizes are identical
+  if (lhs.size() != rhs.size()) return false;
+
+  // copy into vectors and sort by key
+  SmallVector<StringMapConstIterator<ValueTy>, 16> lhs_items;
+  lhs_items.reserve(lhs.size());
+  for (auto i = lhs.begin(), end = lhs.end(); i != end; ++i)
+    lhs_items.push_back(i);
+  std::sort(lhs_items.begin(), lhs_items.end(),
+            [](const StringMapConstIterator<ValueTy>& a,
+               const StringMapConstIterator<ValueTy>& b) {
+              return a->getKey() < b->getKey();
+            });
+
+  SmallVector<StringMapConstIterator<ValueTy>, 16> rhs_items;
+  rhs_items.reserve(rhs.size());
+  for (auto i = rhs.begin(), end = rhs.end(); i != end; ++i)
+    rhs_items.push_back(i);
+  std::sort(rhs_items.begin(), rhs_items.end(),
+            [](const StringMapConstIterator<ValueTy>& a,
+               const StringMapConstIterator<ValueTy>& b) {
+              return a->getKey() < b->getKey();
+            });
+
+  // compare vector keys and values
+  for (auto a = lhs_items.begin(), b = rhs_items.begin(),
+            aend = lhs_items.end(), bend = rhs_items.end();
+       a != aend && b != bend; ++a, ++b) {
+    if ((*a)->first() != (*b)->first() || (*a)->second != (*b)->second)
+      return false;
+  }
+  return true;
+}
+
+template <typename ValueTy>
+inline bool operator!=(const StringMap<ValueTy>& lhs,
+                       const StringMap<ValueTy>& rhs) {
+  return !(lhs == rhs);
+}
+
+template <typename ValueTy>
+bool operator<(const StringMap<ValueTy>& lhs, const StringMap<ValueTy>& rhs) {
+  // same instance?
+  if (&lhs == &rhs) return false;
+
+  // copy into vectors and sort by key
+  SmallVector<std::string_view, 16> lhs_keys;
+  lhs_keys.reserve(lhs.size());
+  for (auto i = lhs.begin(), end = lhs.end(); i != end; ++i)
+    lhs_keys.push_back(i->getKey());
+  std::sort(lhs_keys.begin(), lhs_keys.end());
+
+  SmallVector<std::string_view, 16> rhs_keys;
+  rhs_keys.reserve(rhs.size());
+  for (auto i = rhs.begin(), end = rhs.end(); i != end; ++i)
+    rhs_keys.push_back(i->getKey());
+  std::sort(rhs_keys.begin(), rhs_keys.end());
+
+  // use std::vector comparison
+  return lhs_keys < rhs_keys;
+}
+
+template <typename ValueTy>
+inline bool operator<=(const StringMap<ValueTy>& lhs,
+                       const StringMap<ValueTy>& rhs) {
+  return !(rhs < lhs);
+}
+
+template <typename ValueTy>
+inline bool operator>(const StringMap<ValueTy>& lhs,
+                      const StringMap<ValueTy>& rhs) {
+  return !(lhs <= rhs);
+}
+
+template <typename ValueTy>
+inline bool operator>=(const StringMap<ValueTy>& lhs,
+                       const StringMap<ValueTy>& rhs) {
+  return !(lhs < rhs);
+}
+
+} // end namespace wpi
+
+#endif // WPIUTIL_WPI_STRINGMAP_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/StringMapEntry.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/StringMapEntry.h
new file mode 100644
index 0000000..2b33aa6
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/StringMapEntry.h
@@ -0,0 +1,153 @@
+//===- StringMapEntry.h - String Hash table map interface -------*- C++ -*-===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+///
+/// \file
+/// This file defines the StringMapEntry class - it is intended to be a low
+/// dependency implementation detail of StringMap that is more suitable for
+/// inclusion in public headers than StringMap.h itself is.
+///
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_STRINGMAPENTRY_H
+#define WPIUTIL_WPI_STRINGMAPENTRY_H
+
+#include "wpi/MemAlloc.h"
+
+#include <cassert>
+#include <cstring>
+#include <optional>
+#include <string_view>
+
+namespace wpi {
+
+/// StringMapEntryBase - Shared base class of StringMapEntry instances.
+class StringMapEntryBase {
+  size_t keyLength;
+
+public:
+  explicit StringMapEntryBase(size_t keyLength) : keyLength(keyLength) {}
+
+  size_t getKeyLength() const { return keyLength; }
+
+protected:
+  /// Helper to tail-allocate \p Key. It'd be nice to generalize this so it
+  /// could be reused elsewhere, maybe even taking an wpi::function_ref to
+  /// type-erase the allocator and put it in a source file.
+  template <typename AllocatorTy>
+  static void *allocateWithKey(size_t EntrySize, size_t EntryAlign,
+                               std::string_view Key, AllocatorTy &Allocator);
+};
+
+// Define out-of-line to dissuade inlining.
+template <typename AllocatorTy>
+void *StringMapEntryBase::allocateWithKey(size_t EntrySize, size_t EntryAlign,
+                                          std::string_view Key,
+                                          AllocatorTy &Allocator) {
+  size_t KeyLength = Key.size();
+
+  // Allocate a new item with space for the string at the end and a null
+  // terminator.
+  size_t AllocSize = EntrySize + KeyLength + 1;
+  void *Allocation = Allocator.Allocate(AllocSize, EntryAlign);
+  assert(Allocation && "Unhandled out-of-memory");
+
+  // Copy the string information.
+  char *Buffer = reinterpret_cast<char *>(Allocation) + EntrySize;
+  if (KeyLength > 0)
+    ::memcpy(Buffer, Key.data(), KeyLength);
+  Buffer[KeyLength] = 0; // Null terminate for convenience of clients.
+  return Allocation;
+}
+
+/// StringMapEntryStorage - Holds the value in a StringMapEntry.
+///
+/// Factored out into a separate base class to make it easier to specialize.
+/// This is primarily intended to support StringSet, which doesn't need a value
+/// stored at all.
+template <typename ValueTy>
+class StringMapEntryStorage : public StringMapEntryBase {
+public:
+  ValueTy second;
+
+  explicit StringMapEntryStorage(size_t keyLength)
+      : StringMapEntryBase(keyLength), second() {}
+  template <typename... InitTy>
+  StringMapEntryStorage(size_t keyLength, InitTy &&... initVals)
+      : StringMapEntryBase(keyLength),
+        second(std::forward<InitTy>(initVals)...) {}
+  StringMapEntryStorage(StringMapEntryStorage &e) = delete;
+
+  const ValueTy &getValue() const { return second; }
+  ValueTy &getValue() { return second; }
+
+  void setValue(const ValueTy &V) { second = V; }
+};
+
+template <> class StringMapEntryStorage<std::nullopt_t> : public StringMapEntryBase {
+public:
+  explicit StringMapEntryStorage(size_t keyLength, std::nullopt_t = std::nullopt)
+      : StringMapEntryBase(keyLength) {}
+  StringMapEntryStorage(StringMapEntryStorage &entry) = delete;
+
+  std::nullopt_t getValue() const { return std::nullopt; }
+};
+
+/// StringMapEntry - This is used to represent one value that is inserted into
+/// a StringMap.  It contains the Value itself and the key: the string length
+/// and data.
+template <typename ValueTy>
+class StringMapEntry final : public StringMapEntryStorage<ValueTy> {
+public:
+  using StringMapEntryStorage<ValueTy>::StringMapEntryStorage;
+
+  std::string_view getKey() const {
+    return std::string_view(getKeyData(), this->getKeyLength());
+  }
+
+  /// getKeyData - Return the start of the string data that is the key for this
+  /// value.  The string data is always stored immediately after the
+  /// StringMapEntry object.
+  const char *getKeyData() const {
+    return reinterpret_cast<const char *>(this + 1);
+  }
+
+  std::string_view first() const {
+    return std::string_view(getKeyData(), this->getKeyLength());
+  }
+
+  /// Create a StringMapEntry for the specified key construct the value using
+  /// \p InitiVals.
+  template <typename AllocatorTy, typename... InitTy>
+  static StringMapEntry *Create(std::string_view key, AllocatorTy &allocator,
+                                InitTy &&... initVals) {
+    return new (StringMapEntryBase::allocateWithKey(
+        sizeof(StringMapEntry), alignof(StringMapEntry), key, allocator))
+        StringMapEntry(key.size(), std::forward<InitTy>(initVals)...);
+  }
+
+  /// GetStringMapEntryFromKeyData - Given key data that is known to be embedded
+  /// into a StringMapEntry, return the StringMapEntry itself.
+  static StringMapEntry &GetStringMapEntryFromKeyData(const char *keyData) {
+    char *ptr = const_cast<char *>(keyData) - sizeof(StringMapEntry<ValueTy>);
+    return *reinterpret_cast<StringMapEntry *>(ptr);
+  }
+
+  /// Destroy - Destroy this StringMapEntry, releasing memory back to the
+  /// specified allocator.
+  template <typename AllocatorTy> void Destroy(AllocatorTy &allocator) {
+    // Free memory referenced by the item.
+    size_t AllocSize = sizeof(StringMapEntry) + this->getKeyLength() + 1;
+    this->~StringMapEntry();
+    allocator.Deallocate(static_cast<void *>(this), AllocSize,
+                         alignof(StringMapEntry));
+  }
+};
+
+} // end namespace wpi
+
+#endif // WPIUTIL_WPI_STRINGMAPENTRY_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/SwapByteOrder.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/SwapByteOrder.h
new file mode 100644
index 0000000..ab2791a
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/SwapByteOrder.h
@@ -0,0 +1,165 @@
+//===- SwapByteOrder.h - Generic and optimized byte swaps -------*- C++ -*-===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+//
+// This file declares generic and optimized functions to swap the byte order of
+// an integral type.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_SWAPBYTEORDER_H
+#define WPIUTIL_WPI_SWAPBYTEORDER_H
+
+#include <cstddef>
+#include <cstdint>
+#include <type_traits>
+#if defined(_MSC_VER) && !defined(_DEBUG)
+#include <stdlib.h>
+#endif
+
+#if defined(__linux__) || defined(__GNU__) || defined(__HAIKU__) ||            \
+    defined(__Fuchsia__) || defined(__EMSCRIPTEN__)
+#include <endian.h>
+#elif defined(_AIX)
+#include <sys/machine.h>
+#elif defined(__sun)
+/* Solaris provides _BIG_ENDIAN/_LITTLE_ENDIAN selector in sys/types.h */
+#include <sys/types.h>
+#define BIG_ENDIAN 4321
+#define LITTLE_ENDIAN 1234
+#if defined(_BIG_ENDIAN)
+#define BYTE_ORDER BIG_ENDIAN
+#else
+#define BYTE_ORDER LITTLE_ENDIAN
+#endif
+#elif defined(__MVS__)
+#define BIG_ENDIAN 4321
+#define LITTLE_ENDIAN 1234
+#define BYTE_ORDER BIG_ENDIAN
+#else
+#if !defined(BYTE_ORDER) && !defined(_WIN32)
+#include <machine/endian.h>
+#endif
+#endif
+
+namespace wpi {
+
+/// ByteSwap_16 - This function returns a byte-swapped representation of
+/// the 16-bit argument.
+inline uint16_t ByteSwap_16(uint16_t value) {
+#if defined(_MSC_VER) && !defined(_DEBUG)
+  // The DLL version of the runtime lacks these functions (bug!?), but in a
+  // release build they're replaced with BSWAP instructions anyway.
+  return _byteswap_ushort(value);
+#else
+  uint16_t Hi = value << 8;
+  uint16_t Lo = value >> 8;
+  return Hi | Lo;
+#endif
+}
+
+/// This function returns a byte-swapped representation of the 32-bit argument.
+inline uint32_t ByteSwap_32(uint32_t value) {
+#if defined(__llvm__) || (defined(__GNUC__) && !defined(__ICC))
+  return __builtin_bswap32(value);
+#elif defined(_MSC_VER) && !defined(_DEBUG)
+  return _byteswap_ulong(value);
+#else
+  uint32_t Byte0 = value & 0x000000FF;
+  uint32_t Byte1 = value & 0x0000FF00;
+  uint32_t Byte2 = value & 0x00FF0000;
+  uint32_t Byte3 = value & 0xFF000000;
+  return (Byte0 << 24) | (Byte1 << 8) | (Byte2 >> 8) | (Byte3 >> 24);
+#endif
+}
+
+/// This function returns a byte-swapped representation of the 64-bit argument.
+inline uint64_t ByteSwap_64(uint64_t value) {
+#if defined(__llvm__) || (defined(__GNUC__) && !defined(__ICC))
+  return __builtin_bswap64(value);
+#elif defined(_MSC_VER) && !defined(_DEBUG)
+  return _byteswap_uint64(value);
+#else
+  uint64_t Hi = ByteSwap_32(uint32_t(value));
+  uint32_t Lo = ByteSwap_32(uint32_t(value >> 32));
+  return (Hi << 32) | Lo;
+#endif
+}
+
+namespace sys {
+
+#if defined(BYTE_ORDER) && defined(BIG_ENDIAN) && BYTE_ORDER == BIG_ENDIAN
+constexpr bool IsBigEndianHost = true;
+#else
+constexpr bool IsBigEndianHost = false;
+#endif
+
+static const bool IsLittleEndianHost = !IsBigEndianHost;
+
+inline unsigned char  getSwappedBytes(unsigned char C) { return C; }
+inline   signed char  getSwappedBytes(signed char C) { return C; }
+inline          char  getSwappedBytes(char C) { return C; }
+
+inline unsigned short getSwappedBytes(unsigned short C) { return ByteSwap_16(C); }
+inline   signed short getSwappedBytes(  signed short C) { return ByteSwap_16(C); }
+
+inline unsigned int   getSwappedBytes(unsigned int   C) { return ByteSwap_32(C); }
+inline   signed int   getSwappedBytes(  signed int   C) { return ByteSwap_32(C); }
+
+inline unsigned long getSwappedBytes(unsigned long C) {
+  // Handle LLP64 and LP64 platforms.
+  return sizeof(long) == sizeof(int) ? ByteSwap_32((uint32_t)C)
+                                     : ByteSwap_64((uint64_t)C);
+}
+inline signed long getSwappedBytes(signed long C) {
+  // Handle LLP64 and LP64 platforms.
+  return sizeof(long) == sizeof(int) ? ByteSwap_32((uint32_t)C)
+                                     : ByteSwap_64((uint64_t)C);
+}
+
+inline unsigned long long getSwappedBytes(unsigned long long C) {
+  return ByteSwap_64(C);
+}
+inline signed long long getSwappedBytes(signed long long C) {
+  return ByteSwap_64(C);
+}
+
+inline float getSwappedBytes(float C) {
+  union {
+    uint32_t i;
+    float f;
+  } in, out;
+  in.f = C;
+  out.i = ByteSwap_32(in.i);
+  return out.f;
+}
+
+inline double getSwappedBytes(double C) {
+  union {
+    uint64_t i;
+    double d;
+  } in, out;
+  in.d = C;
+  out.i = ByteSwap_64(in.i);
+  return out.d;
+}
+
+template <typename T>
+inline std::enable_if_t<std::is_enum<T>::value, T> getSwappedBytes(T C) {
+  return static_cast<T>(
+      getSwappedBytes(static_cast<std::underlying_type_t<T>>(C)));
+}
+
+template<typename T>
+inline void swapByteOrder(T &Value) {
+  Value = getSwappedBytes(Value);
+}
+
+} // end namespace sys
+} // end namespace wpi
+
+#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/VersionTuple.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/VersionTuple.h
new file mode 100644
index 0000000..c08ff37
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/VersionTuple.h
@@ -0,0 +1,164 @@
+//===- VersionTuple.h - Version Number Handling -----------------*- C++ -*-===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+///
+/// \file
+/// Defines the llvm::VersionTuple class, which represents a version in
+/// the form major[.minor[.subminor]].
+///
+//===----------------------------------------------------------------------===//
+#ifndef WPIUTIL_WPI_VERSIONTUPLE_H
+#define WPIUTIL_WPI_VERSIONTUPLE_H
+
+#include "wpi/DenseMapInfo.h"
+#include "wpi/Hashing.h"
+#include <optional>
+#include <string>
+#include <tuple>
+
+namespace wpi {
+class raw_ostream;
+
+/// Represents a version number in the form major[.minor[.subminor[.build]]].
+class VersionTuple {
+  unsigned Major : 32;
+
+  unsigned Minor : 31;
+  unsigned HasMinor : 1;
+
+  unsigned Subminor : 31;
+  unsigned HasSubminor : 1;
+
+  unsigned Build : 31;
+  unsigned HasBuild : 1;
+
+public:
+  VersionTuple()
+      : Major(0), Minor(0), HasMinor(false), Subminor(0), HasSubminor(false),
+        Build(0), HasBuild(false) {}
+
+  explicit VersionTuple(unsigned Major)
+      : Major(Major), Minor(0), HasMinor(false), Subminor(0),
+        HasSubminor(false), Build(0), HasBuild(false) {}
+
+  explicit VersionTuple(unsigned Major, unsigned Minor)
+      : Major(Major), Minor(Minor), HasMinor(true), Subminor(0),
+        HasSubminor(false), Build(0), HasBuild(false) {}
+
+  explicit VersionTuple(unsigned Major, unsigned Minor, unsigned Subminor)
+      : Major(Major), Minor(Minor), HasMinor(true), Subminor(Subminor),
+        HasSubminor(true), Build(0), HasBuild(false) {}
+
+  explicit VersionTuple(unsigned Major, unsigned Minor, unsigned Subminor,
+                        unsigned Build)
+      : Major(Major), Minor(Minor), HasMinor(true), Subminor(Subminor),
+        HasSubminor(true), Build(Build), HasBuild(true) {}
+
+  /// Determine whether this version information is empty
+  /// (e.g., all version components are zero).
+  bool empty() const {
+    return Major == 0 && Minor == 0 && Subminor == 0 && Build == 0;
+  }
+
+  /// Retrieve the major version number.
+  unsigned getMajor() const { return Major; }
+
+  /// Retrieve the minor version number, if provided.
+  std::optional<unsigned> getMinor() const {
+    if (!HasMinor)
+      return std::nullopt;
+    return Minor;
+  }
+
+  /// Retrieve the subminor version number, if provided.
+  std::optional<unsigned> getSubminor() const {
+    if (!HasSubminor)
+      return std::nullopt;
+    return Subminor;
+  }
+
+  /// Retrieve the build version number, if provided.
+  std::optional<unsigned> getBuild() const {
+    if (!HasBuild)
+      return std::nullopt;
+    return Build;
+  }
+
+  /// Return a version tuple that contains only the first 3 version components.
+  VersionTuple withoutBuild() const {
+    if (HasBuild)
+      return VersionTuple(Major, Minor, Subminor);
+    return *this;
+  }
+
+  /// Return a version tuple that contains only components that are non-zero.
+  VersionTuple normalize() const {
+    VersionTuple Result = *this;
+    if (Result.Build == 0) {
+      Result.HasBuild = false;
+      if (Result.Subminor == 0) {
+        Result.HasSubminor = false;
+        if (Result.Minor == 0)
+          Result.HasMinor = false;
+      }
+    }
+    return Result;
+  }
+
+  /// Determine if two version numbers are equivalent. If not
+  /// provided, minor and subminor version numbers are considered to be zero.
+  friend bool operator==(const VersionTuple &X, const VersionTuple &Y) {
+    return X.Major == Y.Major && X.Minor == Y.Minor &&
+           X.Subminor == Y.Subminor && X.Build == Y.Build;
+  }
+
+  /// Determine if two version numbers are not equivalent.
+  ///
+  /// If not provided, minor and subminor version numbers are considered to be
+  /// zero.
+  friend bool operator!=(const VersionTuple &X, const VersionTuple &Y) {
+    return !(X == Y);
+  }
+
+  /// Determine whether one version number precedes another.
+  ///
+  /// If not provided, minor and subminor version numbers are considered to be
+  /// zero.
+  friend bool operator<(const VersionTuple &X, const VersionTuple &Y) {
+    return std::tie(X.Major, X.Minor, X.Subminor, X.Build) <
+           std::tie(Y.Major, Y.Minor, Y.Subminor, Y.Build);
+  }
+
+  /// Determine whether one version number follows another.
+  ///
+  /// If not provided, minor and subminor version numbers are considered to be
+  /// zero.
+  friend bool operator>(const VersionTuple &X, const VersionTuple &Y) {
+    return Y < X;
+  }
+
+  /// Determine whether one version number precedes or is
+  /// equivalent to another.
+  ///
+  /// If not provided, minor and subminor version numbers are considered to be
+  /// zero.
+  friend bool operator<=(const VersionTuple &X, const VersionTuple &Y) {
+    return !(Y < X);
+  }
+
+  /// Determine whether one version number follows or is
+  /// equivalent to another.
+  ///
+  /// If not provided, minor and subminor version numbers are considered to be
+  /// zero.
+  friend bool operator>=(const VersionTuple &X, const VersionTuple &Y) {
+    return !(X < Y);
+  }
+};
+
+} // end namespace wpi
+#endif // WPIUTIL_WPI_VERSIONTUPLE_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/WindowsError.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/WindowsError.h
new file mode 100644
index 0000000..54a5236
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/WindowsError.h
@@ -0,0 +1,18 @@
+//===-- WindowsError.h - Support for mapping windows errors to posix-------===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_WINDOWSERROR_H
+#define WPIUTIL_WPI_WINDOWSERROR_H
+
+#include <system_error>
+
+namespace wpi {
+std::error_code mapWindowsError(unsigned EV);
+}
+
+#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/function_ref.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/function_ref.h
similarity index 100%
rename from third_party/allwpilib/wpiutil/src/main/native/include/wpi/function_ref.h
rename to third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/function_ref.h
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/iterator.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/iterator.h
new file mode 100644
index 0000000..f959fac
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/iterator.h
@@ -0,0 +1,378 @@
+//===- iterator.h - Utilities for using and defining iterators --*- C++ -*-===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_ITERATOR_H
+#define WPIUTIL_WPI_ITERATOR_H
+
+#include "wpi/iterator_range.h"
+#include <cstddef>
+#include <iterator>
+#include <type_traits>
+#include <utility>
+
+namespace wpi {
+
+/// CRTP base class which implements the entire standard iterator facade
+/// in terms of a minimal subset of the interface.
+///
+/// Use this when it is reasonable to implement most of the iterator
+/// functionality in terms of a core subset. If you need special behavior or
+/// there are performance implications for this, you may want to override the
+/// relevant members instead.
+///
+/// Note, one abstraction that this does *not* provide is implementing
+/// subtraction in terms of addition by negating the difference. Negation isn't
+/// always information preserving, and I can see very reasonable iterator
+/// designs where this doesn't work well. It doesn't really force much added
+/// boilerplate anyways.
+///
+/// Another abstraction that this doesn't provide is implementing increment in
+/// terms of addition of one. These aren't equivalent for all iterator
+/// categories, and respecting that adds a lot of complexity for little gain.
+///
+/// Iterators are expected to have const rules analogous to pointers, with a
+/// single, const-qualified operator*() that returns ReferenceT. This matches
+/// the second and third pointers in the following example:
+/// \code
+///   int Value;
+///   { int *I = &Value; }             // ReferenceT 'int&'
+///   { int *const I = &Value; }       // ReferenceT 'int&'; const
+///   { const int *I = &Value; }       // ReferenceT 'const int&'
+///   { const int *const I = &Value; } // ReferenceT 'const int&'; const
+/// \endcode
+/// If an iterator facade returns a handle to its own state, then T (and
+/// PointerT and ReferenceT) should usually be const-qualified. Otherwise, if
+/// clients are expected to modify the handle itself, the field can be declared
+/// mutable or use const_cast.
+///
+/// Classes wishing to use `iterator_facade_base` should implement the following
+/// methods:
+///
+/// Forward Iterators:
+///   (All of the following methods)
+///   - DerivedT &operator=(const DerivedT &R);
+///   - bool operator==(const DerivedT &R) const;
+///   - T &operator*() const;
+///   - DerivedT &operator++();
+///
+/// Bidirectional Iterators:
+///   (All methods of forward iterators, plus the following)
+///   - DerivedT &operator--();
+///
+/// Random-access Iterators:
+///   (All methods of bidirectional iterators excluding the following)
+///   - DerivedT &operator++();
+///   - DerivedT &operator--();
+///   (and plus the following)
+///   - bool operator<(const DerivedT &RHS) const;
+///   - DifferenceTypeT operator-(const DerivedT &R) const;
+///   - DerivedT &operator+=(DifferenceTypeT N);
+///   - DerivedT &operator-=(DifferenceTypeT N);
+///
+template <typename DerivedT, typename IteratorCategoryT, typename T,
+          typename DifferenceTypeT = std::ptrdiff_t, typename PointerT = T *,
+          typename ReferenceT = T &>
+class iterator_facade_base {
+public:
+  using iterator_category = IteratorCategoryT;
+  using value_type = T;
+  using difference_type = DifferenceTypeT;
+  using pointer = PointerT;
+  using reference = ReferenceT;
+
+protected:
+  enum {
+    IsRandomAccess = std::is_base_of<std::random_access_iterator_tag,
+                                     IteratorCategoryT>::value,
+    IsBidirectional = std::is_base_of<std::bidirectional_iterator_tag,
+                                      IteratorCategoryT>::value,
+  };
+
+  /// A proxy object for computing a reference via indirecting a copy of an
+  /// iterator. This is used in APIs which need to produce a reference via
+  /// indirection but for which the iterator object might be a temporary. The
+  /// proxy preserves the iterator internally and exposes the indirected
+  /// reference via a conversion operator.
+  class ReferenceProxy {
+    friend iterator_facade_base;
+
+    DerivedT I;
+
+    ReferenceProxy(DerivedT I) : I(std::move(I)) {}
+
+  public:
+    operator ReferenceT() const { return *I; }
+  };
+
+  /// A proxy object for computing a pointer via indirecting a copy of a
+  /// reference. This is used in APIs which need to produce a pointer but for
+  /// which the reference might be a temporary. The proxy preserves the
+  /// reference internally and exposes the pointer via a arrow operator.
+  class PointerProxy {
+    friend iterator_facade_base;
+
+    ReferenceT R;
+
+    template <typename RefT>
+    PointerProxy(RefT &&R) : R(std::forward<RefT>(R)) {}
+
+  public:
+    PointerT operator->() const { return &R; }
+  };
+
+public:
+  DerivedT operator+(DifferenceTypeT n) const {
+    static_assert(std::is_base_of<iterator_facade_base, DerivedT>::value,
+                  "Must pass the derived type to this template!");
+    static_assert(
+        IsRandomAccess,
+        "The '+' operator is only defined for random access iterators.");
+    DerivedT tmp = *static_cast<const DerivedT *>(this);
+    tmp += n;
+    return tmp;
+  }
+  friend DerivedT operator+(DifferenceTypeT n, const DerivedT &i) {
+    static_assert(
+        IsRandomAccess,
+        "The '+' operator is only defined for random access iterators.");
+    return i + n;
+  }
+  DerivedT operator-(DifferenceTypeT n) const {
+    static_assert(
+        IsRandomAccess,
+        "The '-' operator is only defined for random access iterators.");
+    DerivedT tmp = *static_cast<const DerivedT *>(this);
+    tmp -= n;
+    return tmp;
+  }
+
+  DerivedT &operator++() {
+    static_assert(std::is_base_of<iterator_facade_base, DerivedT>::value,
+                  "Must pass the derived type to this template!");
+    return static_cast<DerivedT *>(this)->operator+=(1);
+  }
+  DerivedT operator++(int) {
+    DerivedT tmp = *static_cast<DerivedT *>(this);
+    ++*static_cast<DerivedT *>(this);
+    return tmp;
+  }
+  DerivedT &operator--() {
+    static_assert(
+        IsBidirectional,
+        "The decrement operator is only defined for bidirectional iterators.");
+    return static_cast<DerivedT *>(this)->operator-=(1);
+  }
+  DerivedT operator--(int) {
+    static_assert(
+        IsBidirectional,
+        "The decrement operator is only defined for bidirectional iterators.");
+    DerivedT tmp = *static_cast<DerivedT *>(this);
+    --*static_cast<DerivedT *>(this);
+    return tmp;
+  }
+
+#ifndef __cpp_impl_three_way_comparison
+  bool operator!=(const DerivedT &RHS) const {
+    return !(static_cast<const DerivedT &>(*this) == RHS);
+  }
+#endif
+
+  bool operator>(const DerivedT &RHS) const {
+    static_assert(
+        IsRandomAccess,
+        "Relational operators are only defined for random access iterators.");
+    return !(static_cast<const DerivedT &>(*this) < RHS) &&
+           !(static_cast<const DerivedT &>(*this) == RHS);
+  }
+  bool operator<=(const DerivedT &RHS) const {
+    static_assert(
+        IsRandomAccess,
+        "Relational operators are only defined for random access iterators.");
+    return !(static_cast<const DerivedT &>(*this) > RHS);
+  }
+  bool operator>=(const DerivedT &RHS) const {
+    static_assert(
+        IsRandomAccess,
+        "Relational operators are only defined for random access iterators.");
+    return !(static_cast<const DerivedT &>(*this) < RHS);
+  }
+
+  PointerProxy operator->() const {
+    return static_cast<const DerivedT *>(this)->operator*();
+  }
+  ReferenceProxy operator[](DifferenceTypeT n) const {
+    static_assert(IsRandomAccess,
+                  "Subscripting is only defined for random access iterators.");
+    return static_cast<const DerivedT *>(this)->operator+(n);
+  }
+};
+
+/// CRTP base class for adapting an iterator to a different type.
+///
+/// This class can be used through CRTP to adapt one iterator into another.
+/// Typically this is done through providing in the derived class a custom \c
+/// operator* implementation. Other methods can be overridden as well.
+template <
+    typename DerivedT, typename WrappedIteratorT,
+    typename IteratorCategoryT =
+        typename std::iterator_traits<WrappedIteratorT>::iterator_category,
+    typename T = typename std::iterator_traits<WrappedIteratorT>::value_type,
+    typename DifferenceTypeT =
+        typename std::iterator_traits<WrappedIteratorT>::difference_type,
+    typename PointerT = std::conditional_t<
+        std::is_same<T, typename std::iterator_traits<
+                            WrappedIteratorT>::value_type>::value,
+        typename std::iterator_traits<WrappedIteratorT>::pointer, T *>,
+    typename ReferenceT = std::conditional_t<
+        std::is_same<T, typename std::iterator_traits<
+                            WrappedIteratorT>::value_type>::value,
+        typename std::iterator_traits<WrappedIteratorT>::reference, T &>>
+class iterator_adaptor_base
+    : public iterator_facade_base<DerivedT, IteratorCategoryT, T,
+                                  DifferenceTypeT, PointerT, ReferenceT> {
+  using BaseT = typename iterator_adaptor_base::iterator_facade_base;
+
+protected:
+  WrappedIteratorT I;
+
+  iterator_adaptor_base() = default;
+
+  explicit iterator_adaptor_base(WrappedIteratorT u) : I(std::move(u)) {
+    static_assert(std::is_base_of<iterator_adaptor_base, DerivedT>::value,
+                  "Must pass the derived type to this template!");
+  }
+
+  const WrappedIteratorT &wrapped() const { return I; }
+
+public:
+  using difference_type = DifferenceTypeT;
+
+  DerivedT &operator+=(difference_type n) {
+    static_assert(
+        BaseT::IsRandomAccess,
+        "The '+=' operator is only defined for random access iterators.");
+    I += n;
+    return *static_cast<DerivedT *>(this);
+  }
+  DerivedT &operator-=(difference_type n) {
+    static_assert(
+        BaseT::IsRandomAccess,
+        "The '-=' operator is only defined for random access iterators.");
+    I -= n;
+    return *static_cast<DerivedT *>(this);
+  }
+  using BaseT::operator-;
+  difference_type operator-(const DerivedT &RHS) const {
+    static_assert(
+        BaseT::IsRandomAccess,
+        "The '-' operator is only defined for random access iterators.");
+    return I - RHS.I;
+  }
+
+  // We have to explicitly provide ++ and -- rather than letting the facade
+  // forward to += because WrappedIteratorT might not support +=.
+  using BaseT::operator++;
+  DerivedT &operator++() {
+    ++I;
+    return *static_cast<DerivedT *>(this);
+  }
+  using BaseT::operator--;
+  DerivedT &operator--() {
+    static_assert(
+        BaseT::IsBidirectional,
+        "The decrement operator is only defined for bidirectional iterators.");
+    --I;
+    return *static_cast<DerivedT *>(this);
+  }
+
+  friend bool operator==(const iterator_adaptor_base &LHS,
+                         const iterator_adaptor_base &RHS) {
+    return LHS.I == RHS.I;
+  }
+  friend bool operator<(const iterator_adaptor_base &LHS,
+                        const iterator_adaptor_base &RHS) {
+    static_assert(
+        BaseT::IsRandomAccess,
+        "Relational operators are only defined for random access iterators.");
+    return LHS.I < RHS.I;
+  }
+
+  ReferenceT operator*() const { return *I; }
+};
+
+/// An iterator type that allows iterating over the pointees via some
+/// other iterator.
+///
+/// The typical usage of this is to expose a type that iterates over Ts, but
+/// which is implemented with some iterator over T*s:
+///
+/// \code
+///   using iterator = pointee_iterator<SmallVectorImpl<T *>::iterator>;
+/// \endcode
+template <typename WrappedIteratorT,
+          typename T = std::remove_reference_t<decltype(
+              **std::declval<WrappedIteratorT>())>>
+struct pointee_iterator
+    : iterator_adaptor_base<
+          pointee_iterator<WrappedIteratorT, T>, WrappedIteratorT,
+          typename std::iterator_traits<WrappedIteratorT>::iterator_category,
+          T> {
+  pointee_iterator() = default;
+  template <typename U>
+  pointee_iterator(U &&u)
+      : pointee_iterator::iterator_adaptor_base(std::forward<U &&>(u)) {}
+
+  T &operator*() const { return **this->I; }
+};
+
+template <typename RangeT, typename WrappedIteratorT =
+                               decltype(std::begin(std::declval<RangeT>()))>
+iterator_range<pointee_iterator<WrappedIteratorT>>
+make_pointee_range(RangeT &&Range) {
+  using PointeeIteratorT = pointee_iterator<WrappedIteratorT>;
+  return make_range(PointeeIteratorT(std::begin(std::forward<RangeT>(Range))),
+                    PointeeIteratorT(std::end(std::forward<RangeT>(Range))));
+}
+
+template <typename WrappedIteratorT,
+          typename T = decltype(&*std::declval<WrappedIteratorT>())>
+class pointer_iterator
+    : public iterator_adaptor_base<
+          pointer_iterator<WrappedIteratorT, T>, WrappedIteratorT,
+          typename std::iterator_traits<WrappedIteratorT>::iterator_category,
+          T> {
+  mutable T Ptr;
+
+public:
+  pointer_iterator() = default;
+
+  explicit pointer_iterator(WrappedIteratorT u)
+      : pointer_iterator::iterator_adaptor_base(std::move(u)) {}
+
+  T &operator*() const { return Ptr = &*this->I; }
+};
+
+template <typename RangeT, typename WrappedIteratorT =
+                               decltype(std::begin(std::declval<RangeT>()))>
+iterator_range<pointer_iterator<WrappedIteratorT>>
+make_pointer_range(RangeT &&Range) {
+  using PointerIteratorT = pointer_iterator<WrappedIteratorT>;
+  return make_range(PointerIteratorT(std::begin(std::forward<RangeT>(Range))),
+                    PointerIteratorT(std::end(std::forward<RangeT>(Range))));
+}
+
+template <typename WrappedIteratorT,
+          typename T1 = std::remove_reference_t<decltype(
+              **std::declval<WrappedIteratorT>())>,
+          typename T2 = std::add_pointer_t<T1>>
+using raw_pointer_iterator =
+    pointer_iterator<pointee_iterator<WrappedIteratorT, T1>, T2>;
+
+} // end namespace wpi
+
+#endif // WPIUTIL_WPI_ITERATOR_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/iterator_range.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/iterator_range.h
new file mode 100644
index 0000000..ce0e4ee
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/iterator_range.h
@@ -0,0 +1,63 @@
+//===- iterator_range.h - A range adaptor for iterators ---------*- C++ -*-===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+/// \file
+/// This provides a very simple, boring adaptor for a begin and end iterator
+/// into a range type. This should be used to build range views that work well
+/// with range based for loops and range based constructors.
+///
+/// Note that code here follows more standards-based coding conventions as it
+/// is mirroring proposed interfaces for standardization.
+///
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_ITERATOR_RANGE_H
+#define WPIUTIL_WPI_ITERATOR_RANGE_H
+
+#include <utility>
+
+namespace wpi {
+
+/// A range adaptor for a pair of iterators.
+///
+/// This just wraps two iterators into a range-compatible interface. Nothing
+/// fancy at all.
+template <typename IteratorT>
+class iterator_range {
+  IteratorT begin_iterator, end_iterator;
+
+public:
+  //TODO: Add SFINAE to test that the Container's iterators match the range's
+  //      iterators.
+  template <typename Container>
+  iterator_range(Container &&c)
+  //TODO: Consider ADL/non-member begin/end calls.
+      : begin_iterator(c.begin()), end_iterator(c.end()) {}
+  iterator_range(IteratorT begin_iterator, IteratorT end_iterator)
+      : begin_iterator(std::move(begin_iterator)),
+        end_iterator(std::move(end_iterator)) {}
+
+  IteratorT begin() const { return begin_iterator; }
+  IteratorT end() const { return end_iterator; }
+  bool empty() const { return begin_iterator == end_iterator; }
+};
+
+/// Convenience function for iterating over sub-ranges.
+///
+/// This provides a bit of syntactic sugar to make using sub-ranges
+/// in for loops a bit easier. Analogous to std::make_pair().
+template <class T> iterator_range<T> make_range(T x, T y) {
+  return iterator_range<T>(std::move(x), std::move(y));
+}
+
+template <typename T> iterator_range<T> make_range(std::pair<T, T> p) {
+  return iterator_range<T>(std::move(p.first), std::move(p.second));
+}
+
+}
+
+#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/raw_os_ostream.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/raw_os_ostream.h
new file mode 100644
index 0000000..87cd596
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/raw_os_ostream.h
@@ -0,0 +1,41 @@
+//===- raw_os_ostream.h - std::ostream adaptor for raw_ostream --*- C++ -*-===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+//
+//  This file defines the raw_os_ostream class.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_RAW_OS_OSTREAM_H
+#define WPIUTIL_WPI_RAW_OS_OSTREAM_H
+
+#include "wpi/raw_ostream.h"
+#include <iosfwd>
+
+namespace wpi {
+
+/// raw_os_ostream - A raw_ostream that writes to an std::ostream.  This is a
+/// simple adaptor class.  It does not check for output errors; clients should
+/// use the underlying stream to detect errors.
+class raw_os_ostream : public raw_ostream {
+  std::ostream &OS;
+
+  /// write_impl - See raw_ostream::write_impl.
+  void write_impl(const char *Ptr, size_t Size) override;
+
+  /// current_pos - Return the current position within the stream, not
+  /// counting the bytes currently in the buffer.
+  uint64_t current_pos() const override;
+
+public:
+  raw_os_ostream(std::ostream &O) : OS(O) {}
+  ~raw_os_ostream() override;
+};
+
+} // end wpi namespace
+
+#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/raw_ostream.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/raw_ostream.h
new file mode 100644
index 0000000..350262b
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/raw_ostream.h
@@ -0,0 +1,762 @@
+//===--- raw_ostream.h - Raw output stream ----------------------*- C++ -*-===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+//
+//  This file defines the raw_ostream class.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_RAW_OSTREAM_H
+#define WPIUTIL_WPI_RAW_OSTREAM_H
+
+#include "wpi/SmallVector.h"
+#include <span>
+#include <cassert>
+#include <cstddef>
+#include <cstdint>
+#include <cstring>
+#include <string>
+#if __cplusplus > 201402L
+#include <string_view>
+#endif
+#include <system_error>
+#include <type_traits>
+#include <vector>
+
+
+namespace fs {
+enum FileAccess : unsigned;
+enum OpenFlags : unsigned;
+enum CreationDisposition : unsigned;
+class FileLocker;
+} // end namespace fs
+
+namespace wpi {
+
+/// This class implements an extremely fast bulk output stream that can *only*
+/// output to a stream.  It does not support seeking, reopening, rewinding, line
+/// buffered disciplines etc. It is a simple buffer that outputs
+/// a chunk at a time.
+class raw_ostream {
+public:
+  // Class kinds to support LLVM-style RTTI.
+  enum class OStreamKind {
+    OK_OStream,
+    OK_FDStream,
+  };
+
+private:
+  OStreamKind Kind;
+
+  /// The buffer is handled in such a way that the buffer is
+  /// uninitialized, unbuffered, or out of space when OutBufCur >=
+  /// OutBufEnd. Thus a single comparison suffices to determine if we
+  /// need to take the slow path to write a single character.
+  ///
+  /// The buffer is in one of three states:
+  ///  1. Unbuffered (BufferMode == Unbuffered)
+  ///  1. Uninitialized (BufferMode != Unbuffered && OutBufStart == 0).
+  ///  2. Buffered (BufferMode != Unbuffered && OutBufStart != 0 &&
+  ///               OutBufEnd - OutBufStart >= 1).
+  ///
+  /// If buffered, then the raw_ostream owns the buffer if (BufferMode ==
+  /// InternalBuffer); otherwise the buffer has been set via SetBuffer and is
+  /// managed by the subclass.
+  ///
+  /// If a subclass installs an external buffer using SetBuffer then it can wait
+  /// for a \see write_impl() call to handle the data which has been put into
+  /// this buffer.
+  char *OutBufStart, *OutBufEnd, *OutBufCur;
+
+  /// Optional stream this stream is tied to. If this stream is written to, the
+  /// tied-to stream will be flushed first.
+  raw_ostream *TiedStream = nullptr;
+
+  enum class BufferKind {
+    Unbuffered = 0,
+    InternalBuffer,
+    ExternalBuffer
+  } BufferMode;
+
+public:
+  // color order matches ANSI escape sequence, don't change
+  enum class Colors {
+    BLACK = 0,
+    RED,
+    GREEN,
+    YELLOW,
+    BLUE,
+    MAGENTA,
+    CYAN,
+    WHITE,
+    SAVEDCOLOR,
+    RESET,
+  };
+
+  static constexpr Colors BLACK = Colors::BLACK;
+  static constexpr Colors RED = Colors::RED;
+  static constexpr Colors GREEN = Colors::GREEN;
+  static constexpr Colors YELLOW = Colors::YELLOW;
+  static constexpr Colors BLUE = Colors::BLUE;
+  static constexpr Colors MAGENTA = Colors::MAGENTA;
+  static constexpr Colors CYAN = Colors::CYAN;
+  static constexpr Colors WHITE = Colors::WHITE;
+  static constexpr Colors SAVEDCOLOR = Colors::SAVEDCOLOR;
+  static constexpr Colors RESET = Colors::RESET;
+
+  explicit raw_ostream(bool unbuffered = false,
+                       OStreamKind K = OStreamKind::OK_OStream)
+      : Kind(K), BufferMode(unbuffered ? BufferKind::Unbuffered
+                                       : BufferKind::InternalBuffer) {
+    // Start out ready to flush.
+    OutBufStart = OutBufEnd = OutBufCur = nullptr;
+  }
+
+  raw_ostream(const raw_ostream &) = delete;
+  void operator=(const raw_ostream &) = delete;
+
+  virtual ~raw_ostream();
+
+  /// tell - Return the current offset with the file.
+  uint64_t tell() const { return current_pos() + GetNumBytesInBuffer(); }
+
+  OStreamKind get_kind() const { return Kind; }
+
+  //===--------------------------------------------------------------------===//
+  // Configuration Interface
+  //===--------------------------------------------------------------------===//
+
+  /// If possible, pre-allocate \p ExtraSize bytes for stream data.
+  /// i.e. it extends internal buffers to keep additional ExtraSize bytes.
+  /// So that the stream could keep at least tell() + ExtraSize bytes
+  /// without re-allocations. reserveExtraSpace() does not change
+  /// the size/data of the stream.
+  virtual void reserveExtraSpace(uint64_t ExtraSize) {}
+
+  /// Set the stream to be buffered, with an automatically determined buffer
+  /// size.
+  void SetBuffered();
+
+  /// Set the stream to be buffered, using the specified buffer size.
+  void SetBufferSize(size_t Size) {
+    flush();
+    SetBufferAndMode(new char[Size], Size, BufferKind::InternalBuffer);
+  }
+
+  size_t GetBufferSize() const {
+    // If we're supposed to be buffered but haven't actually gotten around
+    // to allocating the buffer yet, return the value that would be used.
+    if (BufferMode != BufferKind::Unbuffered && OutBufStart == nullptr)
+      return preferred_buffer_size();
+
+    // Otherwise just return the size of the allocated buffer.
+    return OutBufEnd - OutBufStart;
+  }
+
+  /// Set the stream to be unbuffered. When unbuffered, the stream will flush
+  /// after every write. This routine will also flush the buffer immediately
+  /// when the stream is being set to unbuffered.
+  void SetUnbuffered() {
+    flush();
+    SetBufferAndMode(nullptr, 0, BufferKind::Unbuffered);
+  }
+
+  size_t GetNumBytesInBuffer() const {
+    return OutBufCur - OutBufStart;
+  }
+
+  //===--------------------------------------------------------------------===//
+  // Data Output Interface
+  //===--------------------------------------------------------------------===//
+
+  void flush() {
+    if (OutBufCur != OutBufStart)
+      flush_nonempty();
+  }
+
+  raw_ostream &operator<<(char C) {
+    if (OutBufCur >= OutBufEnd)
+      return write(C);
+    *OutBufCur++ = C;
+    return *this;
+  }
+
+  raw_ostream &operator<<(unsigned char C) {
+    if (OutBufCur >= OutBufEnd)
+      return write(C);
+    *OutBufCur++ = C;
+    return *this;
+  }
+
+  raw_ostream &operator<<(signed char C) {
+    if (OutBufCur >= OutBufEnd)
+      return write(C);
+    *OutBufCur++ = C;
+    return *this;
+  }
+
+  raw_ostream &operator<<(std::span<const uint8_t> Arr) {
+    // Inline fast path, particularly for arrays with a known length.
+    size_t Size = Arr.size();
+
+    // Make sure we can use the fast path.
+    if (Size > (size_t)(OutBufEnd - OutBufCur))
+      return write(Arr.data(), Size);
+
+    if (Size) {
+      memcpy(OutBufCur, Arr.data(), Size);
+      OutBufCur += Size;
+    }
+    return *this;
+  }
+
+  raw_ostream &operator<<(std::string_view Str) {
+    // Inline fast path, particularly for strings with a known length.
+    size_t Size = Str.size();
+
+    // Make sure we can use the fast path.
+    if (Size > (size_t)(OutBufEnd - OutBufCur))
+      return write(Str.data(), Size);
+
+    if (Size) {
+      memcpy(OutBufCur, Str.data(), Size);
+      OutBufCur += Size;
+    }
+    return *this;
+  }
+
+  raw_ostream &operator<<(const char *Str) {
+    // Inline fast path, particularly for constant strings where a sufficiently
+    // smart compiler will simplify strlen.
+
+    return this->operator<<(std::string_view(Str));
+  }
+
+  raw_ostream &operator<<(const std::string &Str) {
+    // Avoid the fast path, it would only increase code size for a marginal win.
+    return write(Str.data(), Str.length());
+  }
+
+  raw_ostream &operator<<(const SmallVectorImpl<char> &Str) {
+    return write(Str.data(), Str.size());
+  }
+
+  raw_ostream &operator<<(const std::vector<uint8_t> &Arr) {
+    // Avoid the fast path, it would only increase code size for a marginal win.
+    return write(Arr.data(), Arr.size());
+  }
+
+  raw_ostream &operator<<(const SmallVectorImpl<uint8_t> &Arr) {
+    return write(Arr.data(), Arr.size());
+  }
+
+  /// Output \p Str, turning '\\', '\t', '\n', '"', and anything that doesn't
+  /// satisfy wpi::isPrint into an escape sequence.
+  raw_ostream &write_escaped(std::string_view Str, bool UseHexEscapes = false);
+
+  raw_ostream &write(unsigned char C);
+  raw_ostream &write(const char *Ptr, size_t Size);
+  raw_ostream &write(const uint8_t *Ptr, size_t Size) {
+    return write(reinterpret_cast<const char *>(Ptr), Size);
+  }
+
+  /// indent - Insert 'NumSpaces' spaces.
+  raw_ostream &indent(unsigned NumSpaces);
+
+  /// write_zeros - Insert 'NumZeros' nulls.
+  raw_ostream &write_zeros(unsigned NumZeros);
+
+  /// Changes the foreground color of text that will be output from this point
+  /// forward.
+  /// @param Color ANSI color to use, the special SAVEDCOLOR can be used to
+  /// change only the bold attribute, and keep colors untouched
+  /// @param Bold bold/brighter text, default false
+  /// @param BG if true change the background, default: change foreground
+  /// @returns itself so it can be used within << invocations
+  virtual raw_ostream &changeColor(enum Colors Color, bool Bold = false,
+                                   bool BG = false)  {
+    (void)Color;
+    (void)Bold;
+    (void)BG;
+    return *this;
+  }
+
+  /// Resets the colors to terminal defaults. Call this when you are done
+  /// outputting colored text, or before program exit.
+  virtual raw_ostream &resetColor() { return *this; }
+
+  /// Reverses the foreground and background colors.
+  virtual raw_ostream &reverseColor() { return *this; }
+
+  /// This function determines if this stream is connected to a "tty" or
+  /// "console" window. That is, the output would be displayed to the user
+  /// rather than being put on a pipe or stored in a file.
+  virtual bool is_displayed() const { return false; }
+
+  /// This function determines if this stream is displayed and supports colors.
+  /// The result is unaffected by calls to enable_color().
+  virtual bool has_colors() const { return is_displayed(); }
+
+  // Enable or disable colors. Once enable_colors(false) is called,
+  // changeColor() has no effect until enable_colors(true) is called.
+  virtual void enable_colors(bool /*enable*/) {}
+
+  bool colors_enabled() const { return false; }
+
+  /// Tie this stream to the specified stream. Replaces any existing tied-to
+  /// stream. Specifying a nullptr unties the stream.
+  void tie(raw_ostream *TieTo) { TiedStream = TieTo; }
+
+  //===--------------------------------------------------------------------===//
+  // Subclass Interface
+  //===--------------------------------------------------------------------===//
+
+private:
+  /// The is the piece of the class that is implemented by subclasses.  This
+  /// writes the \p Size bytes starting at
+  /// \p Ptr to the underlying stream.
+  ///
+  /// This function is guaranteed to only be called at a point at which it is
+  /// safe for the subclass to install a new buffer via SetBuffer.
+  ///
+  /// \param Ptr The start of the data to be written. For buffered streams this
+  /// is guaranteed to be the start of the buffer.
+  ///
+  /// \param Size The number of bytes to be written.
+  ///
+  /// \invariant { Size > 0 }
+  virtual void write_impl(const char *Ptr, size_t Size) = 0;
+
+  /// Return the current position within the stream, not counting the bytes
+  /// currently in the buffer.
+  virtual uint64_t current_pos() const = 0;
+
+protected:
+  /// Use the provided buffer as the raw_ostream buffer. This is intended for
+  /// use only by subclasses which can arrange for the output to go directly
+  /// into the desired output buffer, instead of being copied on each flush.
+  void SetBuffer(char *BufferStart, size_t Size) {
+    SetBufferAndMode(BufferStart, Size, BufferKind::ExternalBuffer);
+  }
+
+  /// Return an efficient buffer size for the underlying output mechanism.
+  virtual size_t preferred_buffer_size() const;
+
+  /// Return the beginning of the current stream buffer, or 0 if the stream is
+  /// unbuffered.
+  const char *getBufferStart() const { return OutBufStart; }
+
+  //===--------------------------------------------------------------------===//
+  // Private Interface
+  //===--------------------------------------------------------------------===//
+private:
+  /// Install the given buffer and mode.
+  void SetBufferAndMode(char *BufferStart, size_t Size, BufferKind Mode);
+
+  /// Flush the current buffer, which is known to be non-empty. This outputs the
+  /// currently buffered data and resets the buffer to empty.
+  void flush_nonempty();
+
+  /// Copy data into the buffer. Size must not be greater than the number of
+  /// unused bytes in the buffer.
+  void copy_to_buffer(const char *Ptr, size_t Size);
+
+  /// Flush the tied-to stream (if present) and then write the required data.
+  void flush_tied_then_write(const char *Ptr, size_t Size);
+
+  virtual void anchor();
+};
+
+/// Call the appropriate insertion operator, given an rvalue reference to a
+/// raw_ostream object and return a stream of the same type as the argument.
+template <typename OStream, typename T>
+std::enable_if_t<!std::is_reference<OStream>::value &&
+                     std::is_base_of<raw_ostream, OStream>::value,
+                 OStream &&>
+operator<<(OStream &&OS, const T &Value) {
+  OS << Value;
+  return std::move(OS);
+}
+
+/// An abstract base class for streams implementations that also support a
+/// pwrite operation. This is useful for code that can mostly stream out data,
+/// but needs to patch in a header that needs to know the output size.
+class raw_pwrite_stream : public raw_ostream {
+  virtual void pwrite_impl(const char *Ptr, size_t Size, uint64_t Offset) = 0;
+  void anchor() override;
+
+public:
+  explicit raw_pwrite_stream(bool Unbuffered = false,
+                             OStreamKind K = OStreamKind::OK_OStream)
+      : raw_ostream(Unbuffered, K) {}
+  void pwrite(const char *Ptr, size_t Size, uint64_t Offset) {
+#ifndef NDEBUG
+    uint64_t Pos = tell();
+    // /dev/null always reports a pos of 0, so we cannot perform this check
+    // in that case.
+    if (Pos)
+      assert(Size + Offset <= Pos && "We don't support extending the stream");
+#endif
+    pwrite_impl(Ptr, Size, Offset);
+  }
+};
+
+//===----------------------------------------------------------------------===//
+// File Output Streams
+//===----------------------------------------------------------------------===//
+
+/// A raw_ostream that writes to a file descriptor.
+///
+class raw_fd_ostream : public raw_pwrite_stream {
+  int FD;
+  bool ShouldClose;
+  bool SupportsSeeking = false;
+  bool IsRegularFile = false;
+
+#ifdef _WIN32
+  /// True if this fd refers to a Windows console device. Mintty and other
+  /// terminal emulators are TTYs, but they are not consoles.
+  bool IsWindowsConsole = false;
+#endif
+
+  std::error_code EC;
+
+  uint64_t pos = 0;
+
+  /// See raw_ostream::write_impl.
+  void write_impl(const char *Ptr, size_t Size) override;
+
+  void pwrite_impl(const char *Ptr, size_t Size, uint64_t Offset) override;
+
+  /// Return the current position within the stream, not counting the bytes
+  /// currently in the buffer.
+  uint64_t current_pos() const override { return pos; }
+
+  /// Determine an efficient buffer size.
+  size_t preferred_buffer_size() const override;
+
+  void anchor() override;
+
+protected:
+  /// Set the flag indicating that an output error has been encountered.
+  void error_detected(std::error_code EC) { this->EC = EC; }
+
+  /// Return the file descriptor.
+  int get_fd() const { return FD; }
+
+  // Update the file position by increasing \p Delta.
+  void inc_pos(uint64_t Delta) { pos += Delta; }
+
+public:
+  /// Open the specified file for writing. If an error occurs, information
+  /// about the error is put into EC, and the stream should be immediately
+  /// destroyed;
+  /// \p Flags allows optional flags to control how the file will be opened.
+  ///
+  /// As a special case, if Filename is "-", then the stream will use
+  /// STDOUT_FILENO instead of opening a file. This will not close the stdout
+  /// descriptor.
+  raw_fd_ostream(std::string_view Filename, std::error_code &EC);
+  raw_fd_ostream(std::string_view Filename, std::error_code &EC,
+                 fs::CreationDisposition Disp);
+  raw_fd_ostream(std::string_view Filename, std::error_code &EC,
+                 fs::FileAccess Access);
+  raw_fd_ostream(std::string_view Filename, std::error_code &EC,
+                 fs::OpenFlags Flags);
+  raw_fd_ostream(std::string_view Filename, std::error_code &EC,
+                 fs::CreationDisposition Disp, fs::FileAccess Access,
+                 fs::OpenFlags Flags);
+
+  /// FD is the file descriptor that this writes to.  If ShouldClose is true,
+  /// this closes the file when the stream is destroyed. If FD is for stdout or
+  /// stderr, it will not be closed.
+  raw_fd_ostream(int fd, bool shouldClose, bool unbuffered = false,
+                 OStreamKind K = OStreamKind::OK_OStream);
+
+  ~raw_fd_ostream() override;
+
+  /// Manually flush the stream and close the file. Note that this does not call
+  /// fsync.
+  void close();
+
+  bool supportsSeeking() const { return SupportsSeeking; }
+
+  bool isRegularFile() const { return IsRegularFile; }
+
+  /// Flushes the stream and repositions the underlying file descriptor position
+  /// to the offset specified from the beginning of the file.
+  uint64_t seek(uint64_t off);
+
+  std::error_code error() const { return EC; }
+
+  /// Return the value of the flag in this raw_fd_ostream indicating whether an
+  /// output error has been encountered.
+  /// This doesn't implicitly flush any pending output.  Also, it doesn't
+  /// guarantee to detect all errors unless the stream has been closed.
+  bool has_error() const { return bool(EC); }
+
+  /// Set the flag read by has_error() to false. If the error flag is set at the
+  /// time when this raw_ostream's destructor is called, report_fatal_error is
+  /// called to report the error. Use clear_error() after handling the error to
+  /// avoid this behavior.
+  ///
+  ///   "Errors should never pass silently.
+  ///    Unless explicitly silenced."
+  ///      - from The Zen of Python, by Tim Peters
+  ///
+  void clear_error() { EC = std::error_code(); }
+};
+
+/// This returns a reference to a raw_fd_ostream for standard output. Use it
+/// like: outs() << "foo" << "bar";
+raw_fd_ostream &outs();
+
+/// This returns a reference to a raw_ostream for standard error.
+/// Use it like: errs() << "foo" << "bar";
+/// By default, the stream is tied to stdout to ensure stdout is flushed before
+/// stderr is written, to ensure the error messages are written in their
+/// expected place.
+raw_fd_ostream &errs();
+
+/// This returns a reference to a raw_ostream which simply discards output.
+raw_ostream &nulls();
+
+//===----------------------------------------------------------------------===//
+// File Streams
+//===----------------------------------------------------------------------===//
+
+/// A raw_ostream of a file for reading/writing/seeking.
+///
+class raw_fd_stream : public raw_fd_ostream {
+public:
+  /// Open the specified file for reading/writing/seeking. If an error occurs,
+  /// information about the error is put into EC, and the stream should be
+  /// immediately destroyed.
+  raw_fd_stream(std::string_view Filename, std::error_code &EC);
+
+  /// Check if \p OS is a pointer of type raw_fd_stream*.
+  static bool classof(const raw_ostream *OS);
+};
+
+//===----------------------------------------------------------------------===//
+// Output Stream Adaptors
+//===----------------------------------------------------------------------===//
+
+/// A raw_ostream that writes to an std::string.  This is a simple adaptor
+/// class. This class does not encounter output errors.
+/// raw_string_ostream operates without a buffer, delegating all memory
+/// management to the std::string. Thus the std::string is always up-to-date,
+/// may be used directly and there is no need to call flush().
+class raw_string_ostream : public raw_ostream {
+  std::string &OS;
+
+  /// See raw_ostream::write_impl.
+  void write_impl(const char *Ptr, size_t Size) override;
+
+  /// Return the current position within the stream, not counting the bytes
+  /// currently in the buffer.
+  uint64_t current_pos() const override { return OS.size(); }
+
+public:
+  explicit raw_string_ostream(std::string &O) : OS(O) {
+    SetUnbuffered();
+  }
+
+  /// Returns the string's reference. In most cases it is better to simply use
+  /// the underlying std::string directly.
+  /// TODO: Consider removing this API.
+  std::string &str() { return OS; }
+
+  void reserveExtraSpace(uint64_t ExtraSize) override {
+    OS.reserve(tell() + ExtraSize);
+  }
+};
+
+/// A raw_ostream that writes to an SmallVector or SmallString.  This is a
+/// simple adaptor class. This class does not encounter output errors.
+/// raw_svector_ostream operates without a buffer, delegating all memory
+/// management to the SmallString. Thus the SmallString is always up-to-date,
+/// may be used directly and there is no need to call flush().
+class raw_svector_ostream : public raw_pwrite_stream {
+  SmallVectorImpl<char> &OS;
+
+  /// See raw_ostream::write_impl.
+  void write_impl(const char *Ptr, size_t Size) override;
+
+  void pwrite_impl(const char *Ptr, size_t Size, uint64_t Offset) override;
+
+  /// Return the current position within the stream.
+  uint64_t current_pos() const override;
+
+public:
+  /// Construct a new raw_svector_ostream.
+  ///
+  /// \param O The vector to write to; this should generally have at least 128
+  /// bytes free to avoid any extraneous memory overhead.
+  explicit raw_svector_ostream(SmallVectorImpl<char> &O) : OS(O) {
+    SetUnbuffered();
+  }
+
+  ~raw_svector_ostream() override = default;
+
+  void flush() = delete;
+
+  /// Return a std::string_view for the vector contents.
+  std::string_view str() const { return std::string_view(OS.data(), OS.size()); }
+
+  void reserveExtraSpace(uint64_t ExtraSize) override {
+    OS.reserve(tell() + ExtraSize);
+  }
+};
+
+/// A raw_ostream that writes to a vector.  This is a
+/// simple adaptor class. This class does not encounter output errors.
+/// raw_vector_ostream operates without a buffer, delegating all memory
+/// management to the vector. Thus the vector is always up-to-date,
+/// may be used directly and there is no need to call flush().
+class raw_vector_ostream : public raw_pwrite_stream {
+  std::vector<char> &OS;
+
+  /// See raw_ostream::write_impl.
+  void write_impl(const char *Ptr, size_t Size) override;
+
+  void pwrite_impl(const char *Ptr, size_t Size, uint64_t Offset) override;
+
+  /// Return the current position within the stream.
+  uint64_t current_pos() const override;
+
+public:
+  /// Construct a new raw_svector_ostream.
+  ///
+  /// \param O The vector to write to; this should generally have at least 128
+  /// bytes free to avoid any extraneous memory overhead.
+  explicit raw_vector_ostream(std::vector<char> &O) : OS(O) {
+    SetUnbuffered();
+  }
+
+  ~raw_vector_ostream() override = default;
+
+  void flush() = delete;
+
+  /// Return a std::string_view for the vector contents.
+  std::string_view str() { return std::string_view(OS.data(), OS.size()); }
+};
+
+/// A raw_ostream that writes to an SmallVector or SmallString.  This is a
+/// simple adaptor class. This class does not encounter output errors.
+/// raw_svector_ostream operates without a buffer, delegating all memory
+/// management to the SmallString. Thus the SmallString is always up-to-date,
+/// may be used directly and there is no need to call flush().
+class raw_usvector_ostream : public raw_pwrite_stream {
+  SmallVectorImpl<uint8_t> &OS;
+
+  /// See raw_ostream::write_impl.
+  void write_impl(const char *Ptr, size_t Size) override;
+
+  void pwrite_impl(const char *Ptr, size_t Size, uint64_t Offset) override;
+
+  /// Return the current position within the stream.
+  uint64_t current_pos() const override;
+
+public:
+  /// Construct a new raw_svector_ostream.
+  ///
+  /// \param O The vector to write to; this should generally have at least 128
+  /// bytes free to avoid any extraneous memory overhead.
+  explicit raw_usvector_ostream(SmallVectorImpl<uint8_t> &O) : OS(O) {
+    SetUnbuffered();
+  }
+
+  ~raw_usvector_ostream() override = default;
+
+  void flush() = delete;
+
+  /// Return an std::span for the vector contents.
+  std::span<uint8_t> array() { return {OS.data(), OS.size()}; }
+  std::span<const uint8_t> array() const { return {OS.data(), OS.size()}; }
+};
+
+/// A raw_ostream that writes to a vector.  This is a
+/// simple adaptor class. This class does not encounter output errors.
+/// raw_vector_ostream operates without a buffer, delegating all memory
+/// management to the vector. Thus the vector is always up-to-date,
+/// may be used directly and there is no need to call flush().
+class raw_uvector_ostream : public raw_pwrite_stream {
+  std::vector<uint8_t> &OS;
+
+  /// See raw_ostream::write_impl.
+  void write_impl(const char *Ptr, size_t Size) override;
+
+  void pwrite_impl(const char *Ptr, size_t Size, uint64_t Offset) override;
+
+  /// Return the current position within the stream.
+  uint64_t current_pos() const override;
+
+public:
+  /// Construct a new raw_svector_ostream.
+  ///
+  /// \param O The vector to write to; this should generally have at least 128
+  /// bytes free to avoid any extraneous memory overhead.
+  explicit raw_uvector_ostream(std::vector<uint8_t> &O) : OS(O) {
+    SetUnbuffered();
+  }
+
+  ~raw_uvector_ostream() override = default;
+
+  void flush() = delete;
+
+  /// Return a std::span for the vector contents.
+  std::span<uint8_t> array() { return {OS.data(), OS.size()}; }
+  std::span<const uint8_t> array() const { return {OS.data(), OS.size()}; }
+};
+
+
+/// A raw_ostream that discards all output.
+class raw_null_ostream : public raw_pwrite_stream {
+  /// See raw_ostream::write_impl.
+  void write_impl(const char *Ptr, size_t size) override;
+  void pwrite_impl(const char *Ptr, size_t Size, uint64_t Offset) override;
+
+  /// Return the current position within the stream, not counting the bytes
+  /// currently in the buffer.
+  uint64_t current_pos() const override;
+
+public:
+  explicit raw_null_ostream() = default;
+  ~raw_null_ostream() override;
+};
+
+class buffer_ostream : public raw_svector_ostream {
+  raw_ostream &OS;
+  SmallVector<char, 0> Buffer;
+
+  virtual void anchor() override;
+
+public:
+  buffer_ostream(raw_ostream &OS) : raw_svector_ostream(Buffer), OS(OS) {}
+  ~buffer_ostream() override { OS << str(); }
+};
+
+class buffer_unique_ostream : public raw_svector_ostream {
+  std::unique_ptr<raw_ostream> OS;
+  SmallVector<char, 0> Buffer;
+
+  virtual void anchor() override;
+
+public:
+  buffer_unique_ostream(std::unique_ptr<raw_ostream> OS)
+      : raw_svector_ostream(Buffer), OS(std::move(OS)) {
+    // Turn off buffering on OS, which we now own, to avoid allocating a buffer
+    // when the destructor writes only to be immediately flushed again.
+    this->OS->SetUnbuffered();
+  }
+  ~buffer_unique_ostream() override { *OS << str(); }
+};
+
+} // end namespace wpi
+
+#endif // WPIUTIL_WPI_RAW_OSTREAM_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/type_traits.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/type_traits.h
new file mode 100644
index 0000000..53e18d3
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/llvm/include/wpi/type_traits.h
@@ -0,0 +1,104 @@
+//===- llvm/Support/type_traits.h - Simplfied type traits -------*- C++ -*-===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+//
+// This file provides useful additions to the standard type_traits library.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_TYPE_TRAITS_H
+#define WPIUTIL_WPI_TYPE_TRAITS_H
+
+#include "wpi/Compiler.h"
+#include <type_traits>
+#include <utility>
+
+namespace wpi {
+
+
+/// Metafunction that determines whether the given type is either an
+/// integral type or an enumeration type, including enum classes.
+///
+/// Note that this accepts potentially more integral types than is_integral
+/// because it is based on being implicitly convertible to an integral type.
+/// Also note that enum classes aren't implicitly convertible to integral types,
+/// the value may therefore need to be explicitly converted before being used.
+template <typename T> class is_integral_or_enum {
+  using UnderlyingT = std::remove_reference_t<T>;
+
+public:
+  static const bool value =
+      !std::is_class<UnderlyingT>::value && // Filter conversion operators.
+      !std::is_pointer<UnderlyingT>::value &&
+      !std::is_floating_point<UnderlyingT>::value &&
+      (std::is_enum<UnderlyingT>::value ||
+       std::is_convertible<UnderlyingT, unsigned long long>::value);
+};
+
+/// If T is a pointer, just return it. If it is not, return T&.
+template<typename T, typename Enable = void>
+struct add_lvalue_reference_if_not_pointer { using type = T &; };
+
+template <typename T>
+struct add_lvalue_reference_if_not_pointer<
+    T, std::enable_if_t<std::is_pointer<T>::value>> {
+  using type = T;
+};
+
+/// If T is a pointer to X, return a pointer to const X. If it is not,
+/// return const T.
+template<typename T, typename Enable = void>
+struct add_const_past_pointer { using type = const T; };
+
+template <typename T>
+struct add_const_past_pointer<T, std::enable_if_t<std::is_pointer<T>::value>> {
+  using type = const std::remove_pointer_t<T> *;
+};
+
+template <typename T, typename Enable = void>
+struct const_pointer_or_const_ref {
+  using type = const T &;
+};
+template <typename T>
+struct const_pointer_or_const_ref<T,
+                                  std::enable_if_t<std::is_pointer<T>::value>> {
+  using type = typename add_const_past_pointer<T>::type;
+};
+
+namespace detail {
+/// Internal utility to detect trivial copy construction.
+template<typename T> union copy_construction_triviality_helper {
+    T t;
+    copy_construction_triviality_helper() = default;
+    copy_construction_triviality_helper(const copy_construction_triviality_helper&) = default;
+    ~copy_construction_triviality_helper() = default;
+};
+/// Internal utility to detect trivial move construction.
+template<typename T> union move_construction_triviality_helper {
+    T t;
+    move_construction_triviality_helper() = default;
+    move_construction_triviality_helper(move_construction_triviality_helper&&) = default;
+    ~move_construction_triviality_helper() = default;
+};
+
+template<class T>
+union trivial_helper {
+    T t;
+};
+
+} // end namespace detail
+
+template <typename T>
+using is_trivially_move_constructible = std::is_trivially_move_constructible<T>;
+
+template <typename T>
+using is_trivially_copy_constructible = std::is_trivially_copy_constructible<T>;
+
+
+} // end namespace wpi
+
+#endif // WPIUTIL_WPI_TYPE_TRAITS_H
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/aligned_allocator.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/aligned_allocator.hpp
new file mode 100644
index 0000000..8118ec4
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/aligned_allocator.hpp
@@ -0,0 +1,197 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_ALIGNED_ALLOCATOR_HPP_INCLUDED
+#define WPI_MEMORY_ALIGNED_ALLOCATOR_HPP_INCLUDED
+
+/// \file
+/// Class \ref wpi::memory::aligned_allocator and related functions.
+
+#include <type_traits>
+
+#include "detail/assert.hpp"
+#include "detail/utility.hpp"
+#include "allocator_traits.hpp"
+#include "config.hpp"
+
+namespace wpi
+{
+    namespace memory
+    {
+        /// A \concept{concept_rawallocator,RawAllocator} adapter that ensures a minimum alignment.
+        /// It adjusts the alignment value so that it is always larger than the minimum and forwards to the specified allocator.
+        /// \ingroup adapter
+        template <class RawAllocator>
+        class aligned_allocator : WPI_EBO(allocator_traits<RawAllocator>::allocator_type)
+        {
+            using traits            = allocator_traits<RawAllocator>;
+            using composable_traits = composable_allocator_traits<RawAllocator>;
+            using composable        = is_composable_allocator<typename traits::allocator_type>;
+
+        public:
+            using allocator_type = typename allocator_traits<RawAllocator>::allocator_type;
+            using is_stateful    = std::true_type;
+
+            /// \effects Creates it passing it the minimum alignment value and the allocator object.
+            /// \requires \c min_alignment must be less than \c this->max_alignment().
+            explicit aligned_allocator(std::size_t min_alignment, allocator_type&& alloc = {})
+            : allocator_type(detail::move(alloc)), min_alignment_(min_alignment)
+            {
+                WPI_MEMORY_ASSERT(min_alignment_ <= max_alignment());
+            }
+
+            /// @{
+            /// \effects Moves the \c aligned_allocator object.
+            /// It simply moves the underlying allocator.
+            aligned_allocator(aligned_allocator&& other) noexcept
+            : allocator_type(detail::move(other)), min_alignment_(other.min_alignment_)
+            {
+            }
+
+            aligned_allocator& operator=(aligned_allocator&& other) noexcept
+            {
+                allocator_type::operator=(detail::move(other));
+                min_alignment_          = other.min_alignment_;
+                return *this;
+            }
+            /// @}
+
+            /// @{
+            /// \effects Forwards to the underlying allocator through the \ref allocator_traits.
+            /// If the \c alignment is less than the \c min_alignment(), it is set to the minimum alignment.
+            void* allocate_node(std::size_t size, std::size_t alignment)
+            {
+                if (min_alignment_ > alignment)
+                    alignment = min_alignment_;
+                return traits::allocate_node(get_allocator(), size, alignment);
+            }
+
+            void* allocate_array(std::size_t count, std::size_t size, std::size_t alignment)
+            {
+                if (min_alignment_ > alignment)
+                    alignment = min_alignment_;
+                return traits::allocate_array(get_allocator(), count, size, alignment);
+            }
+
+            void deallocate_node(void* ptr, std::size_t size, std::size_t alignment) noexcept
+            {
+                if (min_alignment_ > alignment)
+                    alignment = min_alignment_;
+                traits::deallocate_node(get_allocator(), ptr, size, alignment);
+            }
+
+            void deallocate_array(void* ptr, std::size_t count, std::size_t size,
+                                  std::size_t alignment) noexcept
+            {
+                if (min_alignment_ > alignment)
+                    alignment = min_alignment_;
+                traits::deallocate_array(get_allocator(), ptr, count, size, alignment);
+            }
+            /// @}
+
+            /// @{
+            /// \effects Forwards to the underlying allocator through the \ref composable_allocator_traits.
+            /// If the \c alignment is less than the \c min_alignment(), it is set to the minimum alignment.
+            /// \requires The underyling allocator must be composable.
+            WPI_ENABLE_IF(composable::value)
+            void* try_allocate_node(std::size_t size, std::size_t alignment) noexcept
+            {
+                if (min_alignment_ > alignment)
+                    alignment = min_alignment_;
+                return composable_traits::try_allocate_node(get_allocator(), size, alignment);
+            }
+
+            WPI_ENABLE_IF(composable::value)
+            void* try_allocate_array(std::size_t count, std::size_t size,
+                                     std::size_t alignment) noexcept
+            {
+                if (min_alignment_ > alignment)
+                    alignment = min_alignment_;
+                return composable_traits::try_allocate_array(get_allocator(), count, size,
+                                                             alignment);
+            }
+
+            WPI_ENABLE_IF(composable::value)
+            bool try_deallocate_node(void* ptr, std::size_t size, std::size_t alignment) noexcept
+            {
+                if (min_alignment_ > alignment)
+                    alignment = min_alignment_;
+                return composable_traits::try_deallocate_node(get_allocator(), ptr, size,
+                                                              alignment);
+            }
+
+            WPI_ENABLE_IF(composable::value)
+            bool try_deallocate_array(void* ptr, std::size_t count, std::size_t size,
+                                      std::size_t alignment) noexcept
+            {
+                if (min_alignment_ > alignment)
+                    alignment = min_alignment_;
+                return composable_traits::try_deallocate_array(get_allocator(), ptr, count, size,
+                                                               alignment);
+            }
+            /// @}
+
+            /// @{
+            /// \returns The value returned by the \ref allocator_traits for the underlying allocator.
+            std::size_t max_node_size() const
+            {
+                return traits::max_node_size(get_allocator());
+            }
+
+            std::size_t max_array_size() const
+            {
+                return traits::max_array_size(get_allocator());
+            }
+
+            std::size_t max_alignment() const
+            {
+                return traits::max_alignment(get_allocator());
+            }
+            /// @}
+
+            /// @{
+            /// \returns A reference to the underlying allocator.
+            allocator_type& get_allocator() noexcept
+            {
+                return *this;
+            }
+
+            const allocator_type& get_allocator() const noexcept
+            {
+                return *this;
+            }
+            /// @}
+
+            /// \returns The minimum alignment.
+            std::size_t min_alignment() const noexcept
+            {
+                return min_alignment_;
+            }
+
+            /// \effects Sets the minimum alignment to a new value.
+            /// \requires \c min_alignment must be less than \c this->max_alignment().
+            void set_min_alignment(std::size_t min_alignment)
+            {
+                WPI_MEMORY_ASSERT(min_alignment <= max_alignment());
+                min_alignment_ = min_alignment;
+            }
+
+        private:
+            std::size_t min_alignment_;
+        };
+
+        /// \returns A new \ref aligned_allocator created by forwarding the parameters to the constructor.
+        /// \relates aligned_allocator
+        template <class RawAllocator>
+        auto make_aligned_allocator(std::size_t min_alignment, RawAllocator&& allocator) noexcept
+            -> aligned_allocator<typename std::decay<RawAllocator>::type>
+        {
+            return aligned_allocator<
+                typename std::decay<RawAllocator>::type>{min_alignment,
+                                                         detail::forward<RawAllocator>(allocator)};
+        }
+    } // namespace memory
+} // namespace wpi
+
+#endif // WPI_MEMORY_ALIGNED_ALLOCATOR_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/allocator_storage.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/allocator_storage.hpp
new file mode 100644
index 0000000..8dab2e0
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/allocator_storage.hpp
@@ -0,0 +1,932 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_ALLOCATOR_STORAGE_HPP_INCLUDED
+#define WPI_MEMORY_ALLOCATOR_STORAGE_HPP_INCLUDED
+
+/// \file
+/// Class template \ref wpi::memory::allocator_storage, some policies and resulting typedefs.
+
+#include <new>
+#include <type_traits>
+
+#include "detail/utility.hpp"
+#include "config.hpp"
+#include "allocator_traits.hpp"
+#include "threading.hpp"
+
+namespace wpi
+{
+    namespace memory
+    {
+        namespace detail
+        {
+            template <class Alloc>
+            void* try_allocate_node(std::true_type, Alloc& alloc, std::size_t size,
+                                    std::size_t alignment) noexcept
+            {
+                return composable_allocator_traits<Alloc>::try_allocate_node(alloc, size,
+                                                                             alignment);
+            }
+
+            template <class Alloc>
+            void* try_allocate_array(std::true_type, Alloc& alloc, std::size_t count,
+                                     std::size_t size, std::size_t alignment) noexcept
+            {
+                return composable_allocator_traits<Alloc>::try_allocate_array(alloc, count, size,
+                                                                              alignment);
+            }
+
+            template <class Alloc>
+            bool try_deallocate_node(std::true_type, Alloc& alloc, void* ptr, std::size_t size,
+                                     std::size_t alignment) noexcept
+            {
+                return composable_allocator_traits<Alloc>::try_deallocate_node(alloc, ptr, size,
+                                                                               alignment);
+            }
+
+            template <class Alloc>
+            bool try_deallocate_array(std::true_type, Alloc& alloc, void* ptr, std::size_t count,
+                                      std::size_t size, std::size_t alignment) noexcept
+            {
+                return composable_allocator_traits<Alloc>::try_deallocate_array(alloc, ptr, count,
+                                                                                size, alignment);
+            }
+
+            template <class Alloc>
+            void* try_allocate_node(std::false_type, Alloc&, std::size_t, std::size_t) noexcept
+            {
+                WPI_MEMORY_UNREACHABLE("Allocator is not compositioning");
+                return nullptr;
+            }
+
+            template <class Alloc>
+            void* try_allocate_array(std::false_type, Alloc&, std::size_t, std::size_t,
+                                     std::size_t) noexcept
+            {
+                WPI_MEMORY_UNREACHABLE("Allocator is not compositioning");
+                return nullptr;
+            }
+
+            template <class Alloc>
+            bool try_deallocate_node(std::false_type, Alloc&, void*, std::size_t,
+                                     std::size_t) noexcept
+            {
+                WPI_MEMORY_UNREACHABLE("Allocator is not compositioning");
+                return false;
+            }
+
+            template <class Alloc>
+            bool try_deallocate_array(std::false_type, Alloc&, void*, std::size_t, std::size_t,
+                                      std::size_t) noexcept
+            {
+                WPI_MEMORY_UNREACHABLE("Allocator is not compositioning");
+                return false;
+            }
+        } // namespace detail
+
+        /// A \concept{concept_rawallocator,RawAllocator} that stores another allocator.
+        /// The \concept{concept_storagepolicy,StoragePolicy} defines the allocator type being stored and how it is stored.
+        /// The \c Mutex controls synchronization of the access.
+        /// \ingroup storage
+        template <class StoragePolicy, class Mutex>
+        class allocator_storage
+        : WPI_EBO(StoragePolicy,
+                        detail::mutex_storage<
+                            detail::mutex_for<typename StoragePolicy::allocator_type, Mutex>>)
+        {
+            using traits = allocator_traits<typename StoragePolicy::allocator_type>;
+            using composable_traits =
+                composable_allocator_traits<typename StoragePolicy::allocator_type>;
+            using composable   = is_composable_allocator<typename StoragePolicy::allocator_type>;
+            using actual_mutex = const detail::mutex_storage<
+                detail::mutex_for<typename StoragePolicy::allocator_type, Mutex>>;
+
+        public:
+            using allocator_type = typename StoragePolicy::allocator_type;
+            using storage_policy = StoragePolicy;
+            using mutex          = Mutex;
+            using is_stateful    = typename traits::is_stateful;
+
+            /// \effects Creates it by default-constructing the \c StoragePolicy.
+            /// \requires The \c StoragePolicy must be default-constructible.
+            /// \notes The default constructor may create an invalid allocator storage not associated with any allocator.
+            /// If that is the case, it must not be used.
+            allocator_storage() = default;
+
+            /// \effects Creates it by passing it an allocator.
+            /// The allocator will be forwarded to the \c StoragePolicy, it decides whether it will be moved, its address stored or something else.
+            /// \requires The expression <tt>new storage_policy(std::forward<Alloc>(alloc))</tt> must be well-formed,
+            /// otherwise this constructor does not participate in overload resolution.
+            template <
+                class Alloc,
+                // MSVC seems to ignore access rights in SFINAE below
+                // use this to prevent this constructor being chosen instead of move for types inheriting from it
+                WPI_REQUIRES(
+                    (!std::is_base_of<allocator_storage, typename std::decay<Alloc>::type>::value))>
+            allocator_storage(Alloc&& alloc,
+                              WPI_SFINAE(new storage_policy(detail::forward<Alloc>(alloc))))
+            : storage_policy(detail::forward<Alloc>(alloc))
+            {
+            }
+
+            /// \effects Creates it by passing it another \c allocator_storage with a different \c StoragePolicy but the same \c Mutex type.
+            /// Initializes it with the result of \c other.get_allocator().
+            /// \requires The expression <tt>new storage_policy(other.get_allocator())</tt> must be well-formed,
+            /// otherwise this constructor does not participate in overload resolution.
+            template <class OtherPolicy>
+            allocator_storage(const allocator_storage<OtherPolicy, Mutex>& other,
+                              WPI_SFINAE(new storage_policy(other.get_allocator())))
+            : storage_policy(other.get_allocator())
+            {
+            }
+
+            /// @{
+            /// \effects Moves the \c allocator_storage object.
+            /// A moved-out \c allocator_storage object must still store a valid allocator object.
+            allocator_storage(allocator_storage&& other) noexcept
+            : storage_policy(detail::move(other)),
+              detail::mutex_storage<
+                  detail::mutex_for<typename StoragePolicy::allocator_type, Mutex>>(
+                  detail::move(other))
+            {
+            }
+
+            allocator_storage& operator=(allocator_storage&& other) noexcept
+            {
+                storage_policy::                                 operator=(detail::move(other));
+                detail::mutex_storage<detail::mutex_for<typename StoragePolicy::allocator_type,
+                                                        Mutex>>::operator=(detail::move(other));
+                return *this;
+            }
+            /// @}
+
+            /// @{
+            /// \effects Copies the \c allocator_storage object.
+            /// \requires The \c StoragePolicy must be copyable.
+            allocator_storage(const allocator_storage&) = default;
+            allocator_storage& operator=(const allocator_storage&) = default;
+            /// @}
+
+            /// @{
+            /// \effects Calls the function on the stored allocator.
+            /// The \c Mutex will be locked during the operation.
+            void* allocate_node(std::size_t size, std::size_t alignment)
+            {
+                std::lock_guard<actual_mutex> lock(*this);
+                auto&&                        alloc = get_allocator();
+                return traits::allocate_node(alloc, size, alignment);
+            }
+
+            void* allocate_array(std::size_t count, std::size_t size, std::size_t alignment)
+            {
+                std::lock_guard<actual_mutex> lock(*this);
+                auto&&                        alloc = get_allocator();
+                return traits::allocate_array(alloc, count, size, alignment);
+            }
+
+            void deallocate_node(void* ptr, std::size_t size, std::size_t alignment) noexcept
+            {
+                std::lock_guard<actual_mutex> lock(*this);
+                auto&&                        alloc = get_allocator();
+                traits::deallocate_node(alloc, ptr, size, alignment);
+            }
+
+            void deallocate_array(void* ptr, std::size_t count, std::size_t size,
+                                  std::size_t alignment) noexcept
+            {
+                std::lock_guard<actual_mutex> lock(*this);
+                auto&&                        alloc = get_allocator();
+                traits::deallocate_array(alloc, ptr, count, size, alignment);
+            }
+
+            std::size_t max_node_size() const
+            {
+                std::lock_guard<actual_mutex> lock(*this);
+                auto&&                        alloc = get_allocator();
+                return traits::max_node_size(alloc);
+            }
+
+            std::size_t max_array_size() const
+            {
+                std::lock_guard<actual_mutex> lock(*this);
+                auto&&                        alloc = get_allocator();
+                return traits::max_array_size(alloc);
+            }
+
+            std::size_t max_alignment() const
+            {
+                std::lock_guard<actual_mutex> lock(*this);
+                auto&&                        alloc = get_allocator();
+                return traits::max_alignment(alloc);
+            }
+            /// @}
+
+            /// @{
+            /// \effects Calls the function on the stored composable allocator.
+            /// The \c Mutex will be locked during the operation.
+            /// \requires The allocator must be composable,
+            /// i.e. \ref is_composable() must return `true`.
+            /// \note This check is done at compile-time where possible,
+            /// and at runtime in the case of type-erased storage.
+            WPI_ENABLE_IF(composable::value)
+            void* try_allocate_node(std::size_t size, std::size_t alignment) noexcept
+            {
+                WPI_MEMORY_ASSERT(is_composable());
+                std::lock_guard<actual_mutex> lock(*this);
+                auto&&                        alloc = get_allocator();
+                return composable_traits::try_allocate_node(alloc, size, alignment);
+            }
+
+            WPI_ENABLE_IF(composable::value)
+            void* try_allocate_array(std::size_t count, std::size_t size,
+                                     std::size_t alignment) noexcept
+            {
+                WPI_MEMORY_ASSERT(is_composable());
+                std::lock_guard<actual_mutex> lock(*this);
+                auto&&                        alloc = get_allocator();
+                return composable_traits::try_allocate_array(alloc, count, size, alignment);
+            }
+
+            WPI_ENABLE_IF(composable::value)
+            bool try_deallocate_node(void* ptr, std::size_t size, std::size_t alignment) noexcept
+            {
+                WPI_MEMORY_ASSERT(is_composable());
+                std::lock_guard<actual_mutex> lock(*this);
+                auto&&                        alloc = get_allocator();
+                return composable_traits::try_deallocate_node(alloc, ptr, size, alignment);
+            }
+
+            WPI_ENABLE_IF(composable::value)
+            bool try_deallocate_array(void* ptr, std::size_t count, std::size_t size,
+                                      std::size_t alignment) noexcept
+            {
+                WPI_MEMORY_ASSERT(is_composable());
+                std::lock_guard<actual_mutex> lock(*this);
+                auto&&                        alloc = get_allocator();
+                return composable_traits::try_deallocate_array(alloc, ptr, count, size, alignment);
+            }
+            /// @}
+
+            /// @{
+            /// \effects Forwards to the \c StoragePolicy.
+            /// \returns Returns a reference to the stored allocator.
+            /// \note This does not lock the \c Mutex.
+            auto get_allocator() noexcept
+                -> decltype(std::declval<storage_policy>().get_allocator())
+            {
+                return storage_policy::get_allocator();
+            }
+
+            auto get_allocator() const noexcept
+                -> decltype(std::declval<const storage_policy>().get_allocator())
+            {
+                return storage_policy::get_allocator();
+            }
+            /// @}
+
+            /// @{
+            /// \returns A proxy object that acts like a pointer to the stored allocator.
+            /// It cannot be reassigned to point to another allocator object and only moving is supported, which is destructive.
+            /// As long as the proxy object lives and is not moved from, the \c Mutex will be kept locked.
+            auto lock() noexcept -> WPI_IMPL_DEFINED(decltype(detail::lock_allocator(
+                std::declval<storage_policy>().get_allocator(), std::declval<actual_mutex&>())))
+            {
+                return detail::lock_allocator(get_allocator(), static_cast<actual_mutex&>(*this));
+            }
+
+            auto lock() const noexcept -> WPI_IMPL_DEFINED(decltype(
+                detail::lock_allocator(std::declval<const storage_policy>().get_allocator(),
+                                       std::declval<actual_mutex&>())))
+            {
+                return detail::lock_allocator(get_allocator(), static_cast<actual_mutex&>(*this));
+            }
+            /// @}.
+
+            /// \returns Whether or not the stored allocator is composable,
+            /// that is you can use the compositioning functions.
+            /// \note Due to type-erased allocators,
+            /// this function can not be `constexpr`.
+            bool is_composable() const noexcept
+            {
+                return StoragePolicy::is_composable();
+            }
+        };
+
+        /// Tag type that enables type-erasure in \ref reference_storage.
+        /// It can be used everywhere a \ref allocator_reference is used internally.
+        /// \ingroup storage
+        struct any_allocator
+        {
+        };
+
+        /// A \concept{concept_storagepolicy,StoragePolicy} that stores the allocator directly.
+        /// It embeds the allocator inside it, i.e. moving the storage policy will move the allocator.
+        /// \ingroup storage
+        template <class RawAllocator>
+        class direct_storage : WPI_EBO(allocator_traits<RawAllocator>::allocator_type)
+        {
+            static_assert(!std::is_same<RawAllocator, any_allocator>::value,
+                          "cannot type-erase in direct_storage");
+
+        public:
+            using allocator_type = typename allocator_traits<RawAllocator>::allocator_type;
+
+            /// \effects Creates it by default-constructing the allocator.
+            /// \requires The \c RawAllcoator must be default constructible.
+            direct_storage() = default;
+
+            /// \effects Creates it by moving in an allocator object.
+            direct_storage(allocator_type&& allocator) noexcept
+            : allocator_type(detail::move(allocator))
+            {
+            }
+
+            /// @{
+            /// \effects Moves the \c direct_storage object.
+            /// This will move the stored allocator.
+            direct_storage(direct_storage&& other) noexcept : allocator_type(detail::move(other)) {}
+
+            direct_storage& operator=(direct_storage&& other) noexcept
+            {
+                allocator_type::operator=(detail::move(other));
+                return *this;
+            }
+            /// @}
+
+            /// @{
+            /// \returns A (\c const) reference to the stored allocator.
+            allocator_type& get_allocator() noexcept
+            {
+                return *this;
+            }
+
+            const allocator_type& get_allocator() const noexcept
+            {
+                return *this;
+            }
+            /// @}
+
+        protected:
+            ~direct_storage() noexcept = default;
+
+            bool is_composable() const noexcept
+            {
+                return is_composable_allocator<allocator_type>::value;
+            }
+        };
+
+        /// An alias template for \ref allocator_storage using the \ref direct_storage policy without a mutex.
+        /// It has the effect of giving any \concept{concept_rawallocator,RawAllocator} the interface with all member functions,
+        /// avoiding the need to wrap it inside the \ref allocator_traits.
+        /// \ingroup storage
+        template <class RawAllocator>
+        WPI_ALIAS_TEMPLATE(allocator_adapter,
+                                 allocator_storage<direct_storage<RawAllocator>, no_mutex>);
+
+        /// \returns A new \ref allocator_adapter object created by forwarding to the constructor.
+        /// \relates allocator_adapter
+        template <class RawAllocator>
+        auto make_allocator_adapter(RawAllocator&& allocator) noexcept
+            -> allocator_adapter<typename std::decay<RawAllocator>::type>
+        {
+            return {detail::forward<RawAllocator>(allocator)};
+        }
+
+/// An alias template for \ref allocator_storage using the \ref direct_storage policy with a mutex.
+/// It has a similar effect as \ref allocator_adapter but performs synchronization.
+/// The \c Mutex will default to \c std::mutex if threading is supported,
+/// otherwise there is no default.
+/// \ingroup storage
+#if WPI_HOSTED_IMPLEMENTATION
+        template <class RawAllocator, class Mutex = std::mutex>
+        WPI_ALIAS_TEMPLATE(thread_safe_allocator,
+                                 allocator_storage<direct_storage<RawAllocator>, Mutex>);
+#else
+        template <class RawAllocator, class Mutex>
+        WPI_ALIAS_TEMPLATE(thread_safe_allocator,
+                                 allocator_storage<direct_storage<RawAllocator>, Mutex>);
+#endif
+
+#if WPI_HOSTED_IMPLEMENTATION
+        /// \returns A new \ref thread_safe_allocator object created by forwarding to the constructor/
+        /// \relates thread_safe_allocator
+        template <class RawAllocator>
+        auto make_thread_safe_allocator(RawAllocator&& allocator)
+            -> thread_safe_allocator<typename std::decay<RawAllocator>::type>
+        {
+            return detail::forward<RawAllocator>(allocator);
+        }
+#endif
+
+        /// \returns A new \ref thread_safe_allocator object created by forwarding to the constructor,
+        /// specifying a certain mutex type.
+        /// \requires It requires threading support from the implementation.
+        /// \relates thread_safe_allocator
+        template <class Mutex, class RawAllocator>
+        auto make_thread_safe_allocator(RawAllocator&& allocator)
+            -> thread_safe_allocator<typename std::decay<RawAllocator>::type, Mutex>
+        {
+            return detail::forward<RawAllocator>(allocator);
+        }
+
+        namespace detail
+        {
+            struct reference_stateful
+            {
+            };
+            struct reference_stateless
+            {
+            };
+            struct reference_shared
+            {
+            };
+
+            reference_stateful  reference_type(std::true_type stateful, std::false_type shared);
+            reference_stateless reference_type(std::false_type stateful, std::true_type shared);
+            reference_stateless reference_type(std::false_type stateful, std::false_type shared);
+            reference_shared    reference_type(std::true_type stateful, std::true_type shared);
+
+            template <class RawAllocator, class Tag>
+            class reference_storage_impl;
+
+            // reference to stateful: stores a pointer to an allocator
+            template <class RawAllocator>
+            class reference_storage_impl<RawAllocator, reference_stateful>
+            {
+            protected:
+                reference_storage_impl() noexcept : alloc_(nullptr) {}
+
+                reference_storage_impl(RawAllocator& allocator) noexcept : alloc_(&allocator) {}
+
+                bool is_valid() const noexcept
+                {
+                    return alloc_ != nullptr;
+                }
+
+                RawAllocator& get_allocator() const noexcept
+                {
+                    WPI_MEMORY_ASSERT(alloc_ != nullptr);
+                    return *alloc_;
+                }
+
+            private:
+                RawAllocator* alloc_;
+            };
+
+            // reference to stateless: store in static storage
+            template <class RawAllocator>
+            class reference_storage_impl<RawAllocator, reference_stateless>
+            {
+            protected:
+                reference_storage_impl() noexcept = default;
+
+                reference_storage_impl(const RawAllocator&) noexcept {}
+
+                bool is_valid() const noexcept
+                {
+                    return true;
+                }
+
+                RawAllocator& get_allocator() const noexcept
+                {
+                    static RawAllocator alloc;
+                    return alloc;
+                }
+            };
+
+            // reference to shared: stores RawAllocator directly
+            template <class RawAllocator>
+            class reference_storage_impl<RawAllocator, reference_shared>
+            {
+            protected:
+                reference_storage_impl() noexcept = default;
+
+                reference_storage_impl(const RawAllocator& alloc) noexcept : alloc_(alloc) {}
+
+                bool is_valid() const noexcept
+                {
+                    return true;
+                }
+
+                RawAllocator& get_allocator() const noexcept
+                {
+                    return alloc_;
+                }
+
+            private:
+                mutable RawAllocator alloc_;
+            };
+        } // namespace detail
+
+        /// Specifies whether or not a \concept{concept_rawallocator,RawAllocator} has shared semantics.
+        /// It is shared, if - like \ref allocator_reference - if multiple objects refer to the same internal allocator and if it can be copied.
+        /// This sharing is stateful, however, stateless allocators are not considered shared in the meaning of this traits. <br>
+        /// If a \c RawAllocator is shared, it will be directly embedded inside \ref reference_storage since it already provides \ref allocator_reference like semantics, so there is no need to add them manually,<br>
+        /// Specialize it for your own types, if they provide sharing semantics and can be copied.
+        /// They also must provide an `operator==` to check whether two allocators refer to the same shared one.
+        /// \note This makes no guarantees about the lifetime of the shared object, the sharing allocators can either own or refer to a shared object.
+        /// \ingroup storage
+        template <class RawAllocator>
+        struct is_shared_allocator : std::false_type
+        {
+        };
+
+        /// A \concept{concept_storagepolicy,StoragePolicy} that stores a reference to an allocator.
+        /// For stateful allocators it only stores a pointer to an allocator object and copying/moving only copies the pointer.
+        /// For stateless allocators it does not store anything, an allocator will be constructed as needed.
+        /// For allocators that are already shared (determined through \ref is_shared_allocator) it will store the allocator type directly.
+        /// \note It does not take ownership over the allocator in the stateful case, the user has to ensure that the allocator object stays valid.
+        /// In the other cases the lifetime does not matter.
+        /// \ingroup storage
+        template <class RawAllocator>
+        class reference_storage
+#ifndef DOXYGEN
+        : WPI_EBO(detail::reference_storage_impl<
+                        typename allocator_traits<RawAllocator>::allocator_type,
+                        decltype(detail::reference_type(
+                            typename allocator_traits<RawAllocator>::is_stateful{},
+                            is_shared_allocator<RawAllocator>{}))>)
+#endif
+        {
+            using storage = detail::reference_storage_impl<
+                typename allocator_traits<RawAllocator>::allocator_type,
+                decltype(
+                    detail::reference_type(typename allocator_traits<RawAllocator>::is_stateful{},
+                                           is_shared_allocator<RawAllocator>{}))>;
+
+        public:
+            using allocator_type = typename allocator_traits<RawAllocator>::allocator_type;
+
+            /// Default constructor.
+            /// \effects If the allocator is stateless, this has no effect and the object is usable as an allocator.
+            /// If the allocator is stateful, creates an invalid reference without any associated allocator.
+            /// Then it must not be used.
+            /// If the allocator is shared, default constructs the shared allocator.
+            /// If the shared allocator does not have a default constructor, this constructor is ill-formed.
+            reference_storage() noexcept = default;
+
+            /// \effects Creates it from a stateless or shared allocator.
+            /// It will not store anything, only creates the allocator as needed.
+            /// \requires The \c RawAllocator is stateless or shared.
+            reference_storage(const allocator_type& alloc) noexcept : storage(alloc) {}
+
+            /// \effects Creates it from a reference to a stateful allocator.
+            /// It will store a pointer to this allocator object.
+            /// \note The user has to take care that the lifetime of the reference does not exceed the allocator lifetime.
+            reference_storage(allocator_type& alloc) noexcept : storage(alloc) {}
+
+            /// @{
+            /// \effects Copies the \c allocator_reference object.
+            /// Only copies the pointer to it in the stateful case.
+            reference_storage(const reference_storage&) noexcept = default;
+            reference_storage& operator=(const reference_storage&) noexcept = default;
+            /// @}
+
+            /// \returns Whether or not the reference is valid.
+            /// It is only invalid, if it was created by the default constructor and the allocator is stateful.
+            explicit operator bool() const noexcept
+            {
+                return storage::is_valid();
+            }
+
+            /// \returns Returns a reference to the allocator.
+            /// \requires The reference must be valid.
+            allocator_type& get_allocator() const noexcept
+            {
+                return storage::get_allocator();
+            }
+
+        protected:
+            ~reference_storage() noexcept = default;
+
+            bool is_composable() const noexcept
+            {
+                return is_composable_allocator<allocator_type>::value;
+            }
+        };
+
+        /// Specialization of the class template \ref reference_storage that is type-erased.
+        /// It is triggered by the tag type \ref any_allocator.
+        /// The specialization can store a reference to any allocator type.
+        /// \ingroup storage
+        template <>
+        class reference_storage<any_allocator>
+        {
+            class base_allocator
+            {
+            public:
+                using is_stateful = std::true_type;
+
+                virtual ~base_allocator() = default;
+
+                virtual void clone(void* storage) const noexcept = 0;
+
+                void* allocate_node(std::size_t size, std::size_t alignment)
+                {
+                    return allocate_impl(1, size, alignment);
+                }
+
+                void* allocate_array(std::size_t count, std::size_t size, std::size_t alignment)
+                {
+                    return allocate_impl(count, size, alignment);
+                }
+
+                void deallocate_node(void* node, std::size_t size, std::size_t alignment) noexcept
+                {
+                    deallocate_impl(node, 1, size, alignment);
+                }
+
+                void deallocate_array(void* array, std::size_t count, std::size_t size,
+                                      std::size_t alignment) noexcept
+                {
+                    deallocate_impl(array, count, size, alignment);
+                }
+
+                void* try_allocate_node(std::size_t size, std::size_t alignment) noexcept
+                {
+                    return try_allocate_impl(1, size, alignment);
+                }
+
+                void* try_allocate_array(std::size_t count, std::size_t size,
+                                         std::size_t alignment) noexcept
+                {
+                    return try_allocate_impl(count, size, alignment);
+                }
+
+                bool try_deallocate_node(void* node, std::size_t size,
+                                         std::size_t alignment) noexcept
+                {
+                    return try_deallocate_impl(node, 1, size, alignment);
+                }
+
+                bool try_deallocate_array(void* array, std::size_t count, std::size_t size,
+                                          std::size_t alignment) noexcept
+                {
+                    return try_deallocate_impl(array, count, size, alignment);
+                }
+
+                // count 1 means node
+                virtual void* allocate_impl(std::size_t count, std::size_t size,
+                                            std::size_t alignment)            = 0;
+                virtual void  deallocate_impl(void* ptr, std::size_t count, std::size_t size,
+                                              std::size_t alignment) noexcept = 0;
+
+                virtual void* try_allocate_impl(std::size_t count, std::size_t size,
+                                                std::size_t alignment) noexcept = 0;
+
+                virtual bool try_deallocate_impl(void* ptr, std::size_t count, std::size_t size,
+                                                 std::size_t alignment) noexcept = 0;
+
+                std::size_t max_node_size() const
+                {
+                    return max(query::node_size);
+                }
+
+                std::size_t max_array_size() const
+                {
+                    return max(query::array_size);
+                }
+
+                std::size_t max_alignment() const
+                {
+                    return max(query::alignment);
+                }
+
+                virtual bool is_composable() const noexcept = 0;
+
+            protected:
+                enum class query
+                {
+                    node_size,
+                    array_size,
+                    alignment
+                };
+
+                virtual std::size_t max(query q) const = 0;
+            };
+
+        public:
+            using allocator_type = WPI_IMPL_DEFINED(base_allocator);
+
+            /// \effects Creates it from a reference to any stateful \concept{concept_rawallocator,RawAllocator}.
+            /// It will store a pointer to this allocator object.
+            /// \note The user has to take care that the lifetime of the reference does not exceed the allocator lifetime.
+            template <class RawAllocator>
+            reference_storage(RawAllocator& alloc) noexcept
+            {
+                static_assert(sizeof(basic_allocator<RawAllocator>)
+                                  <= sizeof(basic_allocator<default_instantiation>),
+                              "requires all instantiations to have certain maximum size");
+                ::new (static_cast<void*>(&storage_)) basic_allocator<RawAllocator>(alloc);
+            }
+
+            // \effects Creates it from any stateless \concept{concept_rawallocator,RawAllocator}.
+            /// It will not store anything, only creates the allocator as needed.
+            /// \requires The \c RawAllocator is stateless.
+            template <class RawAllocator>
+            reference_storage(
+                const RawAllocator& alloc,
+                WPI_REQUIRES(!allocator_traits<RawAllocator>::is_stateful::value)) noexcept
+            {
+                static_assert(sizeof(basic_allocator<RawAllocator>)
+                                  <= sizeof(basic_allocator<default_instantiation>),
+                              "requires all instantiations to have certain maximum size");
+                ::new (static_cast<void*>(&storage_)) basic_allocator<RawAllocator>(alloc);
+            }
+
+            /// \effects Creates it from the internal base class for the type-erasure.
+            /// Has the same effect as if the actual stored allocator were passed to the other constructor overloads.
+            /// \note This constructor is used internally to avoid double-nesting.
+            reference_storage(const WPI_IMPL_DEFINED(base_allocator) & alloc) noexcept
+            {
+                alloc.clone(&storage_);
+            }
+
+            /// \effects Creates it from the internal base class for the type-erasure.
+            /// Has the same effect as if the actual stored allocator were passed to the other constructor overloads.
+            /// \note This constructor is used internally to avoid double-nesting.
+            reference_storage(WPI_IMPL_DEFINED(base_allocator) & alloc) noexcept
+            : reference_storage(static_cast<const base_allocator&>(alloc))
+            {
+            }
+
+            /// @{
+            /// \effects Copies the \c reference_storage object.
+            /// It only copies the pointer to the allocator.
+            reference_storage(const reference_storage& other) noexcept
+            {
+                other.get_allocator().clone(&storage_);
+            }
+
+            reference_storage& operator=(const reference_storage& other) noexcept
+            {
+                get_allocator().~allocator_type();
+                other.get_allocator().clone(&storage_);
+                return *this;
+            }
+            /// @}
+
+            /// \returns A reference to the allocator.
+            /// The actual type is implementation-defined since it is the base class used in the type-erasure,
+            /// but it provides the full \concept{concept_rawallocator,RawAllocator} member functions.
+            /// \note There is no way to access any custom member functions of the allocator type.
+            allocator_type& get_allocator() const noexcept
+            {
+                auto mem = static_cast<void*>(&storage_);
+                return *static_cast<base_allocator*>(mem);
+            }
+
+        protected:
+            ~reference_storage() noexcept
+            {
+                get_allocator().~allocator_type();
+            }
+
+            bool is_composable() const noexcept
+            {
+                return get_allocator().is_composable();
+            }
+
+        private:
+            template <class RawAllocator>
+            class basic_allocator
+            : public base_allocator,
+              private detail::reference_storage_impl<
+                  typename allocator_traits<RawAllocator>::allocator_type,
+                  decltype(
+                      detail::reference_type(typename allocator_traits<RawAllocator>::is_stateful{},
+                                             is_shared_allocator<RawAllocator>{}))>
+            {
+                using traits     = allocator_traits<RawAllocator>;
+                using composable = is_composable_allocator<typename traits::allocator_type>;
+                using storage    = detail::reference_storage_impl<
+                    typename allocator_traits<RawAllocator>::allocator_type,
+                    decltype(detail::reference_type(typename allocator_traits<
+                                                        RawAllocator>::is_stateful{},
+                                                    is_shared_allocator<RawAllocator>{}))>;
+
+            public:
+                // non stateful
+                basic_allocator(const RawAllocator& alloc) noexcept : storage(alloc) {}
+
+                // stateful
+                basic_allocator(RawAllocator& alloc) noexcept : storage(alloc) {}
+
+            private:
+                typename traits::allocator_type& get() const noexcept
+                {
+                    return storage::get_allocator();
+                }
+
+                void clone(void* storage) const noexcept override
+                {
+                    ::new (storage) basic_allocator(get());
+                }
+
+                void* allocate_impl(std::size_t count, std::size_t size,
+                                    std::size_t alignment) override
+                {
+                    auto&& alloc = get();
+                    if (count == 1u)
+                        return traits::allocate_node(alloc, size, alignment);
+                    else
+                        return traits::allocate_array(alloc, count, size, alignment);
+                }
+
+                void deallocate_impl(void* ptr, std::size_t count, std::size_t size,
+                                     std::size_t alignment) noexcept override
+                {
+                    auto&& alloc = get();
+                    if (count == 1u)
+                        traits::deallocate_node(alloc, ptr, size, alignment);
+                    else
+                        traits::deallocate_array(alloc, ptr, count, size, alignment);
+                }
+
+                void* try_allocate_impl(std::size_t count, std::size_t size,
+                                        std::size_t alignment) noexcept override
+                {
+                    auto&& alloc = get();
+                    if (count == 1u)
+                        return detail::try_allocate_node(composable{}, alloc, size, alignment);
+                    else
+                        return detail::try_allocate_array(composable{}, alloc, count, size,
+                                                          alignment);
+                }
+
+                bool try_deallocate_impl(void* ptr, std::size_t count, std::size_t size,
+                                         std::size_t alignment) noexcept override
+                {
+                    auto&& alloc = get();
+                    if (count == 1u)
+                        return detail::try_deallocate_node(composable{}, alloc, ptr, size,
+                                                           alignment);
+                    else
+                        return detail::try_deallocate_array(composable{}, alloc, ptr, count, size,
+                                                            alignment);
+                }
+
+                bool is_composable() const noexcept override
+                {
+                    return composable::value;
+                }
+
+                std::size_t max(query q) const override
+                {
+                    auto&& alloc = get();
+                    if (q == query::node_size)
+                        return traits::max_node_size(alloc);
+                    else if (q == query::array_size)
+                        return traits::max_array_size(alloc);
+                    return traits::max_alignment(alloc);
+                }
+            };
+
+            // use a stateful instantiation to determine size and alignment
+            // base_allocator is stateful
+            using default_instantiation = basic_allocator<base_allocator>;
+            alignas(default_instantiation) mutable char storage_[sizeof(default_instantiation)];
+        };
+
+        /// An alias template for \ref allocator_storage using the \ref reference_storage policy.
+        /// It will store a reference to the given allocator type. The tag type \ref any_allocator enables type-erasure.
+        /// Wrap the allocator in a \ref thread_safe_allocator if you want thread safety.
+        /// \ingroup storage
+        template <class RawAllocator>
+        WPI_ALIAS_TEMPLATE(allocator_reference,
+                                 allocator_storage<reference_storage<RawAllocator>, no_mutex>);
+
+        /// \returns A new \ref allocator_reference object by forwarding the allocator to the constructor.
+        /// \relates allocator_reference
+        template <class RawAllocator>
+        auto make_allocator_reference(RawAllocator&& allocator) noexcept
+            -> allocator_reference<typename std::decay<RawAllocator>::type>
+        {
+            return {detail::forward<RawAllocator>(allocator)};
+        }
+
+        /// An alias for the \ref reference_storage specialization using type-erasure.
+        /// \ingroup storage
+        using any_reference_storage = reference_storage<any_allocator>;
+
+        /// An alias for \ref allocator_storage using the \ref any_reference_storage.
+        /// It will store a reference to any \concept{concept_rawallocator,RawAllocator}.
+        /// This is the same as passing the tag type \ref any_allocator to the alias \ref allocator_reference.
+        /// Wrap the allocator in a \ref thread_safe_allocator if you want thread safety.
+        /// \ingroup storage
+        using any_allocator_reference = allocator_storage<any_reference_storage, no_mutex>;
+
+        /// \returns A new \ref any_allocator_reference object by forwarding the allocator to the constructor.
+        /// \relates any_allocator_reference
+        template <class RawAllocator>
+        auto make_any_allocator_reference(RawAllocator&& allocator) noexcept
+            -> any_allocator_reference
+        {
+            return {detail::forward<RawAllocator>(allocator)};
+        }
+    } // namespace memory
+} // namespace wpi
+
+#endif // WPI_MEMORY_ALLOCATOR_STORAGE_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/allocator_traits.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/allocator_traits.hpp
new file mode 100644
index 0000000..47b6ffb
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/allocator_traits.hpp
@@ -0,0 +1,603 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_ALLOCATOR_TRAITS_HPP_INCLUDED
+#define WPI_MEMORY_ALLOCATOR_TRAITS_HPP_INCLUDED
+
+/// \file
+/// The default specialization of the \ref wpi::memory::allocator_traits.
+
+#include <cstddef>
+#include <type_traits>
+
+#include "detail/align.hpp"
+#include "detail/utility.hpp"
+#include "config.hpp"
+
+#if WPI_HOSTED_IMPLEMENTATION
+#include <memory>
+#endif
+
+namespace wpi
+{
+    namespace memory
+    {
+        namespace detail
+        {
+            template <class Allocator>
+            std::true_type has_construct(int, WPI_SFINAE(std::declval<Allocator>().construct(
+                                                  std::declval<typename Allocator::pointer>(),
+                                                  std::declval<typename Allocator::value_type>())));
+
+            template <class Allocator>
+            std::false_type has_construct(short);
+
+            template <class Allocator>
+            std::true_type has_destroy(int, WPI_SFINAE(std::declval<Allocator>().destroy(
+                                                std::declval<typename Allocator::pointer>())));
+
+            template <class Allocator>
+            std::false_type has_destroy(short);
+
+            template <class Allocator>
+            struct check_standard_allocator
+            {
+                using custom_construct = decltype(has_construct<Allocator>(0));
+                using custom_destroy   = decltype(has_destroy<Allocator>(0));
+
+                using valid = std::integral_constant<bool, !custom_construct::value
+                                                               && !custom_destroy::value>;
+            };
+        } // namespace detail
+
+        /// Traits class that checks whether or not a standard \c Allocator can be used as \concept{concept_rawallocator,RawAllocator}.
+        /// It checks the existence of a custom \c construct(), \c destroy() function, if provided,
+        /// it cannot be used since it would not be called.<br>
+        /// Specialize it for custom \c Allocator types to override this check.
+        /// \ingroup core
+        template <class Allocator>
+        struct allocator_is_raw_allocator
+        : WPI_EBO(detail::check_standard_allocator<Allocator>::valid)
+        {
+        };
+
+        /// Specialization of \ref allocator_is_raw_allocator that allows \c std::allocator again.
+        /// \ingroup core
+        template <typename T>
+        struct allocator_is_raw_allocator<std::allocator<T>> : std::true_type
+        {
+        };
+
+        namespace traits_detail // use seperate namespace to avoid name clashes
+        {
+            // full_concept has the best conversion rank, error the lowest
+            // used to give priority to the functions
+            struct error
+            {
+                operator void*() const noexcept
+                {
+                    WPI_MEMORY_UNREACHABLE(
+                        "this is just to hide an error and move static_assert to the front");
+                    return nullptr;
+                }
+            };
+            struct std_concept : error
+            {
+            };
+            struct min_concept : std_concept
+            {
+            };
+            struct full_concept : min_concept
+            {
+            };
+
+            // used to delay assert in handle_error() until instantiation
+            template <typename T>
+            struct invalid_allocator_concept
+            {
+                static const bool error = false;
+            };
+
+            //=== allocator_type ===//
+            // if Allocator has a member template `rebind`, use that to rebind to `char`
+            // else if Allocator has a member `value_type`, rebind by changing argument
+            // else does nothing
+            template <class Allocator>
+            auto rebind_impl(int) -> typename Allocator::template rebind<char>::other&;
+
+            template <class Allocator, typename T>
+            struct allocator_rebinder
+            {
+                using type = Allocator&;
+            };
+
+            template <template <typename, typename...> class Alloc, typename U, typename... Args,
+                      typename T>
+            struct allocator_rebinder<Alloc<U, Args...>, T>
+            {
+                using type = Alloc<T, Args...>&;
+            };
+
+            template <class Allocator, typename = typename Allocator::value_type>
+            auto rebind_impl(char) -> typename allocator_rebinder<Allocator, char>::type;
+
+            template <class Allocator>
+            auto rebind_impl(...) -> Allocator&;
+
+            template <class Allocator>
+            struct allocator_type_impl // required for MSVC
+            {
+                using type = decltype(rebind_impl<Allocator>(0));
+            };
+
+            template <class Allocator>
+            using allocator_type =
+                typename std::decay<typename allocator_type_impl<Allocator>::type>::type;
+
+            //=== is_stateful ===//
+            // first try to access Allocator::is_stateful,
+            // then use whether or not the type is empty
+            template <class Allocator>
+            auto is_stateful(full_concept) -> decltype(typename Allocator::is_stateful{});
+
+            template <class Allocator, bool IsEmpty>
+            struct is_stateful_impl;
+
+            template <class Allocator>
+            struct is_stateful_impl<Allocator, true>
+            {
+                static_assert(std::is_default_constructible<Allocator>::value,
+                              "RawAllocator is empty but not default constructible ."
+                              "This means it is not a stateless allocator. "
+                              "If this is actually intended provide the appropriate is_stateful "
+                              "typedef in your class.");
+                using type = std::false_type;
+            };
+
+            template <class Allocator>
+            struct is_stateful_impl<Allocator, false>
+            {
+                using type = std::true_type;
+            };
+
+            template <class Allocator>
+            auto is_stateful(min_concept) ->
+                typename is_stateful_impl<Allocator, std::is_empty<Allocator>::value>::type;
+
+            //=== allocate_node() ===//
+            // first try Allocator::allocate_node
+            // then assume std_allocator and call Allocator::allocate
+            // then error
+            template <class Allocator>
+            auto allocate_node(full_concept, Allocator& alloc, std::size_t size,
+                               std::size_t alignment)
+                -> WPI_AUTO_RETURN_TYPE(alloc.allocate_node(size, alignment), void*)
+
+                    template <class Allocator>
+                    auto allocate_node(std_concept, Allocator& alloc, std::size_t size, std::size_t)
+                        -> WPI_AUTO_RETURN(static_cast<void*>(alloc.allocate(size)))
+
+                            template <class Allocator>
+                            error allocate_node(error, Allocator&, std::size_t, std::size_t)
+            {
+                static_assert(invalid_allocator_concept<Allocator>::error,
+                              "type is not a RawAllocator as it does not provide: void* "
+                              "allocate_node(std::size_t, "
+                              "std::size_t)");
+                return {};
+            }
+
+            //=== deallocate_node() ===//
+            // first try Allocator::deallocate_node
+            // then assume std_allocator and call Allocator::deallocate
+            // then error
+            template <class Allocator>
+            auto deallocate_node(full_concept, Allocator& alloc, void* ptr, std::size_t size,
+                                 std::size_t alignment) noexcept
+                -> WPI_AUTO_RETURN_TYPE(alloc.deallocate_node(ptr, size, alignment), void)
+
+                    template <class Allocator>
+                    auto deallocate_node(std_concept, Allocator& alloc, void* ptr, std::size_t size,
+                                         std::size_t) noexcept
+                -> WPI_AUTO_RETURN_TYPE(alloc.deallocate(static_cast<char*>(ptr), size), void)
+
+                    template <class Allocator>
+                    error deallocate_node(error, Allocator&, void*, std::size_t, std::size_t)
+            {
+                static_assert(invalid_allocator_concept<Allocator>::error,
+                              "type is not a RawAllocator as it does not provide: void "
+                              "deallocate_node(void*, std::size_t, "
+                              "std::size_t)");
+                return error{};
+            }
+
+            //=== allocate_array() ===//
+            // first try Allocator::allocate_array
+            // then forward to allocate_node()
+            template <class Allocator>
+            auto allocate_array(full_concept, Allocator& alloc, std::size_t count, std::size_t size,
+                                std::size_t alignment)
+                -> WPI_AUTO_RETURN_TYPE(alloc.allocate_array(count, size, alignment), void*)
+
+                    template <class Allocator>
+                    void* allocate_array(min_concept, Allocator& alloc, std::size_t count,
+                                         std::size_t size, std::size_t alignment)
+            {
+                return allocate_node(full_concept{}, alloc, count * size, alignment);
+            }
+
+            //=== deallocate_array() ===//
+            // first try Allocator::deallocate_array
+            // then forward to deallocate_node()
+            template <class Allocator>
+            auto deallocate_array(full_concept, Allocator& alloc, void* ptr, std::size_t count,
+                                  std::size_t size, std::size_t alignment) noexcept
+                -> WPI_AUTO_RETURN_TYPE(alloc.deallocate_array(ptr, count, size, alignment),
+                                              void)
+
+                    template <class Allocator>
+                    void deallocate_array(min_concept, Allocator& alloc, void* ptr,
+                                          std::size_t count, std::size_t size,
+                                          std::size_t alignment) noexcept
+            {
+                deallocate_node(full_concept{}, alloc, ptr, count * size, alignment);
+            }
+
+            //=== max_node_size() ===//
+            // first try Allocator::max_node_size()
+            // then return maximum value
+            template <class Allocator>
+            auto max_node_size(full_concept, const Allocator& alloc)
+                -> WPI_AUTO_RETURN_TYPE(alloc.max_node_size(), std::size_t)
+
+                    template <class Allocator>
+                    std::size_t max_node_size(min_concept, const Allocator&) noexcept
+            {
+                return std::size_t(-1);
+            }
+
+            //=== max_node_size() ===//
+            // first try Allocator::max_array_size()
+            // then forward to max_node_size()
+            template <class Allocator>
+            auto max_array_size(full_concept, const Allocator& alloc)
+                -> WPI_AUTO_RETURN_TYPE(alloc.max_array_size(), std::size_t)
+
+                    template <class Allocator>
+                    std::size_t max_array_size(min_concept, const Allocator& alloc)
+            {
+                return max_node_size(full_concept{}, alloc);
+            }
+
+            //=== max_alignment() ===//
+            // first try Allocator::max_alignment()
+            // then return detail::max_alignment
+            template <class Allocator>
+            auto max_alignment(full_concept, const Allocator& alloc)
+                -> WPI_AUTO_RETURN_TYPE(alloc.max_alignment(), std::size_t)
+
+                    template <class Allocator>
+                    std::size_t max_alignment(min_concept, const Allocator&)
+            {
+                return detail::max_alignment;
+            }
+        } // namespace traits_detail
+
+        /// The default specialization of the allocator_traits for a \concept{concept_rawallocator,RawAllocator}.
+        /// See the last link for the requirements on types that do not specialize this class and the interface documentation.
+        /// Any specialization must provide the same interface.
+        /// \ingroup core
+        template <class Allocator>
+        class allocator_traits
+        {
+        public:
+            using allocator_type = traits_detail::allocator_type<Allocator>;
+            using is_stateful =
+                decltype(traits_detail::is_stateful<Allocator>(traits_detail::full_concept{}));
+
+            static void* allocate_node(allocator_type& state, std::size_t size,
+                                       std::size_t alignment)
+            {
+                static_assert(allocator_is_raw_allocator<Allocator>::value,
+                              "Allocator cannot be used as RawAllocator because it provides custom "
+                              "construct()/destroy()");
+                return traits_detail::allocate_node(traits_detail::full_concept{}, state, size,
+                                                    alignment);
+            }
+
+            static void* allocate_array(allocator_type& state, std::size_t count, std::size_t size,
+                                        std::size_t alignment)
+            {
+                static_assert(allocator_is_raw_allocator<Allocator>::value,
+                              "Allocator cannot be used as RawAllocator because it provides custom "
+                              "construct()/destroy()");
+                return traits_detail::allocate_array(traits_detail::full_concept{}, state, count,
+                                                     size, alignment);
+            }
+
+            static void deallocate_node(allocator_type& state, void* node, std::size_t size,
+                                        std::size_t alignment) noexcept
+            {
+                static_assert(allocator_is_raw_allocator<Allocator>::value,
+                              "Allocator cannot be used as RawAllocator because it provides custom "
+                              "construct()/destroy()");
+                traits_detail::deallocate_node(traits_detail::full_concept{}, state, node, size,
+                                               alignment);
+            }
+
+            static void deallocate_array(allocator_type& state, void* array, std::size_t count,
+                                         std::size_t size, std::size_t alignment) noexcept
+            {
+                static_assert(allocator_is_raw_allocator<Allocator>::value,
+                              "Allocator cannot be used as RawAllocator because it provides custom "
+                              "construct()/destroy()");
+                traits_detail::deallocate_array(traits_detail::full_concept{}, state, array, count,
+                                                size, alignment);
+            }
+
+            static std::size_t max_node_size(const allocator_type& state)
+            {
+                static_assert(allocator_is_raw_allocator<Allocator>::value,
+                              "Allocator cannot be used as RawAllocator because it provides custom "
+                              "construct()/destroy()");
+                return traits_detail::max_node_size(traits_detail::full_concept{}, state);
+            }
+
+            static std::size_t max_array_size(const allocator_type& state)
+            {
+                static_assert(allocator_is_raw_allocator<Allocator>::value,
+                              "Allocator cannot be used as RawAllocator because it provides custom "
+                              "construct()/destroy()");
+                return traits_detail::max_array_size(traits_detail::full_concept{}, state);
+            }
+
+            static std::size_t max_alignment(const allocator_type& state)
+            {
+                static_assert(allocator_is_raw_allocator<Allocator>::value,
+                              "Allocator cannot be used as RawAllocator because it provides custom "
+                              "construct()/destroy()");
+                return traits_detail::max_alignment(traits_detail::full_concept{}, state);
+            }
+
+#if !defined(DOXYGEN)
+            using foonathan_memory_default_traits = std::true_type;
+#endif
+        };
+
+        namespace detail
+        {
+            template <class RawAllocator>
+            typename allocator_traits<RawAllocator>::foonathan_memory_default_traits
+                alloc_uses_default_traits(RawAllocator&);
+
+            std::false_type alloc_uses_default_traits(...);
+
+            template <typename T>
+            struct has_invalid_alloc_function
+            : std::is_same<decltype(
+                               traits_detail::allocate_node(traits_detail::full_concept{},
+                                                            std::declval<typename allocator_traits<
+                                                                T>::allocator_type&>(),
+                                                            0, 0)),
+                           traits_detail::error>
+            {
+            };
+
+            template <typename T>
+            struct has_invalid_dealloc_function
+            : std::is_same<
+                  decltype(traits_detail::deallocate_node(traits_detail::full_concept{},
+                                                          std::declval<typename allocator_traits<
+                                                              T>::allocator_type&>(),
+                                                          nullptr, 0, 0)),
+                  traits_detail::error>
+            {
+            };
+
+            template <typename T, class DefaultTraits>
+            struct is_raw_allocator : std::true_type
+            {
+            };
+
+            template <typename T>
+            struct is_raw_allocator<T, std::integral_constant<bool, true>>
+            : std::integral_constant<bool, allocator_is_raw_allocator<T>::value
+                                               && !(has_invalid_alloc_function<T>::value
+                                                    || has_invalid_dealloc_function<T>::value)>
+            {
+            };
+        } // namespace detail
+
+        /// Traits that check whether a type models concept \concept{concept_rawallocator,RawAllocator}.<br>
+        /// It must either provide the necessary functions for the default traits specialization or has specialized it.
+        /// \ingroup core
+        template <typename T>
+        struct is_raw_allocator
+        : detail::is_raw_allocator<T,
+                                   decltype(detail::alloc_uses_default_traits(std::declval<T&>()))>
+        {
+        };
+
+        namespace traits_detail
+        {
+            //=== try_allocate_node() ===//
+            // try Allocator::try_allocate_node
+            // otherwise error
+            template <class Allocator>
+            auto try_allocate_node(full_concept, Allocator& alloc, std::size_t size,
+                                   std::size_t alignment) noexcept
+                -> WPI_AUTO_RETURN_TYPE(alloc.try_allocate_node(size, alignment), void*)
+
+                    template <class Allocator>
+                    error try_allocate_node(error, Allocator&, std::size_t, std::size_t)
+            {
+                static_assert(invalid_allocator_concept<Allocator>::error,
+                              "type is not a composable RawAllocator as it does not provide: void* "
+                              "try_allocate_node(std::size_t, "
+                              "std::size_t)");
+                return {};
+            }
+
+            //=== try_deallocate_node() ===//
+            // try Allocator::try_deallocate_node
+            // otherwise error
+            template <class Allocator>
+            auto try_deallocate_node(full_concept, Allocator& alloc, void* ptr, std::size_t size,
+                                     std::size_t alignment) noexcept
+                -> WPI_AUTO_RETURN_TYPE(alloc.try_deallocate_node(ptr, size, alignment), bool)
+
+                    template <class Allocator>
+                    error try_deallocate_node(error, Allocator&, void*, std::size_t, std::size_t)
+            {
+                static_assert(invalid_allocator_concept<Allocator>::error,
+                              "type is not a composable RawAllocator as it does not provide: bool "
+                              "try_deallocate_node(void*, std::size_t, "
+                              "std::size_t)");
+                return error{};
+            }
+
+            //=== try_allocate_array() ===//
+            // first try Allocator::try_allocate_array
+            // then forward to try_allocate_node()
+            template <class Allocator>
+            auto try_allocate_array(full_concept, Allocator& alloc, std::size_t count,
+                                    std::size_t size, std::size_t alignment) noexcept
+                -> WPI_AUTO_RETURN_TYPE(alloc.try_allocate_array(count, size, alignment),
+                                              void*)
+
+                    template <class Allocator>
+                    void* try_allocate_array(min_concept, Allocator& alloc, std::size_t count,
+                                             std::size_t size, std::size_t alignment)
+            {
+                return try_allocate_node(full_concept{}, alloc, count * size, alignment);
+            }
+
+            //=== try_deallocate_array() ===//
+            // first try Allocator::try_deallocate_array
+            // then forward to try_deallocate_node()
+            template <class Allocator>
+            auto try_deallocate_array(full_concept, Allocator& alloc, void* ptr, std::size_t count,
+                                      std::size_t size, std::size_t alignment) noexcept
+                -> WPI_AUTO_RETURN_TYPE(alloc.try_deallocate_array(ptr, count, size,
+                                                                         alignment),
+                                              bool)
+
+                    template <class Allocator>
+                    bool try_deallocate_array(min_concept, Allocator& alloc, void* ptr,
+                                              std::size_t count, std::size_t size,
+                                              std::size_t alignment) noexcept
+            {
+                return try_deallocate_node(full_concept{}, alloc, ptr, count * size, alignment);
+            }
+        } // namespace traits_detail
+
+        /// The default specialization of the composable_allocator_traits for a \concept{concept_composableallocator,ComposableAllocator}.
+        /// See the last link for the requirements on types that do not specialize this class and the interface documentation.
+        /// Any specialization must provide the same interface.
+        /// \ingroup core
+        template <class Allocator>
+        class composable_allocator_traits
+        {
+        public:
+            using allocator_type = typename allocator_traits<Allocator>::allocator_type;
+
+            static void* try_allocate_node(allocator_type& state, std::size_t size,
+                                           std::size_t alignment) noexcept
+            {
+                static_assert(is_raw_allocator<Allocator>::value,
+                              "ComposableAllocator must be RawAllocator");
+                return traits_detail::try_allocate_node(traits_detail::full_concept{}, state, size,
+                                                        alignment);
+            }
+
+            static void* try_allocate_array(allocator_type& state, std::size_t count,
+                                            std::size_t size, std::size_t alignment) noexcept
+            {
+                static_assert(is_raw_allocator<Allocator>::value,
+                              "ComposableAllocator must be RawAllocator");
+                return traits_detail::try_allocate_array(traits_detail::full_concept{}, state,
+                                                         count, size, alignment);
+            }
+
+            static bool try_deallocate_node(allocator_type& state, void* node, std::size_t size,
+                                            std::size_t alignment) noexcept
+            {
+                static_assert(is_raw_allocator<Allocator>::value,
+                              "ComposableAllocator must be RawAllocator");
+                return traits_detail::try_deallocate_node(traits_detail::full_concept{}, state,
+                                                          node, size, alignment);
+            }
+
+            static bool try_deallocate_array(allocator_type& state, void* array, std::size_t count,
+                                             std::size_t size, std::size_t alignment) noexcept
+            {
+                static_assert(is_raw_allocator<Allocator>::value,
+                              "ComposableAllocator must be RawAllocator");
+                return traits_detail::try_deallocate_array(traits_detail::full_concept{}, state,
+                                                           array, count, size, alignment);
+            }
+
+#if !defined(DOXYGEN)
+            using foonathan_memory_default_traits = std::true_type;
+#endif
+        };
+
+        namespace detail
+        {
+            template <class RawAllocator>
+            typename composable_allocator_traits<RawAllocator>::foonathan_memory_default_traits
+                composable_alloc_uses_default_traits(RawAllocator&);
+
+            std::false_type composable_alloc_uses_default_traits(...);
+
+            template <typename T>
+            struct has_invalid_try_alloc_function
+            : std::is_same<
+                  decltype(traits_detail::try_allocate_node(traits_detail::full_concept{},
+                                                            std::declval<typename allocator_traits<
+                                                                T>::allocator_type&>(),
+                                                            0, 0)),
+                  traits_detail::error>
+            {
+            };
+
+            template <typename T>
+            struct has_invalid_try_dealloc_function
+            : std::is_same<
+                  decltype(
+                      traits_detail::try_deallocate_node(traits_detail::full_concept{},
+                                                         std::declval<typename allocator_traits<
+                                                             T>::allocator_type&>(),
+                                                         nullptr, 0, 0)),
+                  traits_detail::error>
+            {
+            };
+
+            template <typename T, class DefaultTraits>
+            struct is_composable_allocator : memory::is_raw_allocator<T>
+            {
+            };
+
+            template <typename T>
+            struct is_composable_allocator<T, std::integral_constant<bool, true>>
+            : std::integral_constant<bool, memory::is_raw_allocator<T>::value
+                                               && !(has_invalid_try_alloc_function<T>::value
+                                                    || has_invalid_try_dealloc_function<T>::value)>
+            {
+            };
+        } // namespace detail
+
+        /// Traits that check whether a type models concept \concept{concept_rawallocator,ComposableAllocator}.<br>
+        /// It must be a \concept{concept_rawallocator,RawAllocator} and either provide the necessary functions for the default traits specialization or has specialized it.
+        /// \ingroup core
+        template <typename T>
+        struct is_composable_allocator
+        : detail::is_composable_allocator<T, decltype(detail::composable_alloc_uses_default_traits(
+                                                 std::declval<T&>()))>
+        {
+        };
+    } // namespace memory
+} // namespace wpi
+
+#endif // WPI_MEMORY_ALLOCATOR_TRAITS_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/config.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/config.hpp
new file mode 100644
index 0000000..067ecd2
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/config.hpp
@@ -0,0 +1,148 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+/// \file
+/// Configuration macros.
+
+#ifndef WPI_MEMORY_CONFIG_HPP_INCLUDED
+#define WPI_MEMORY_CONFIG_HPP_INCLUDED
+
+#include <cstddef>
+
+#if !defined(DOXYGEN)
+#define WPI_MEMORY_IMPL_IN_CONFIG_HPP
+#include "config_impl.hpp"
+#undef WPI_MEMORY_IMPL_IN_CONFIG_HPP
+#endif
+
+// exception support
+#ifndef WPI_HAS_EXCEPTION_SUPPORT
+#if defined(__GNUC__) && !defined(__EXCEPTIONS)
+#define WPI_HAS_EXCEPTION_SUPPORT 0
+#elif defined(_MSC_VER) && !_HAS_EXCEPTIONS
+#define WPI_HAS_EXCEPTION_SUPPORT 0
+#else
+#define WPI_HAS_EXCEPTION_SUPPORT 1
+#endif
+#endif
+
+#if WPI_HAS_EXCEPTION_SUPPORT
+#define WPI_THROW(Ex) throw(Ex)
+#else
+#include <cstdlib>
+#define WPI_THROW(Ex) ((Ex), std::abort())
+#endif
+
+// hosted implementation
+#ifndef WPI_HOSTED_IMPLEMENTATION
+#if !_MSC_VER && !__STDC_HOSTED__
+#define WPI_HOSTED_IMPLEMENTATION 0
+#else
+#define WPI_HOSTED_IMPLEMENTATION 1
+#endif
+#endif
+
+// log prefix
+#define WPI_MEMORY_LOG_PREFIX "wpi::memory"
+
+// version
+#define WPI_MEMORY_VERSION                                                                   \
+    (WPI_MEMORY_VERSION_MAJOR * 100 + WPI_MEMORY_VERSION_MINOR)
+
+// use this macro to mark implementation-defined types
+// gives it more semantics and useful with doxygen
+// add PREDEFINED: WPI_IMPL_DEFINED():=implementation_defined
+#ifndef WPI_IMPL_DEFINED
+#define WPI_IMPL_DEFINED(...) __VA_ARGS__
+#endif
+
+// use this macro to mark base class which only purpose is EBO
+// gives it more semantics and useful with doxygen
+// add PREDEFINED: WPI_EBO():=
+#ifndef WPI_EBO
+#define WPI_EBO(...) __VA_ARGS__
+#endif
+
+#ifndef WPI_ALIAS_TEMPLATE
+// defines a template alias
+// usage:
+// template <typename T>
+// WPI_ALIAS_TEMPLATE(bar, foo<T, int>);
+// useful for doxygen
+#ifdef DOXYGEN
+#define WPI_ALIAS_TEMPLATE(Name, ...)                                                        \
+    class Name : public __VA_ARGS__                                                                \
+    {                                                                                              \
+    }
+#else
+#define WPI_ALIAS_TEMPLATE(Name, ...) using Name = __VA_ARGS__
+#endif
+#endif
+
+#ifdef DOXYGEN
+// dummy definitions of config macros for doxygen
+
+/// The major version number.
+/// \ingroup core
+#define WPI_MEMORY_VERSION_MAJOR 1
+
+/// The minor version number.
+/// \ingroup core
+#define WPI_MEMORY_VERSION_MINOR 1
+
+/// The total version number of the form \c Mmm.
+/// \ingroup core
+#define WPI_MEMORY_VERSION                                                                   \
+    (WPI_MEMORY_VERSION_MAJOR * 100 + WPI_MEMORY_VERSION_MINOR)
+
+/// Whether or not the allocation size will be checked,
+/// i.e. the \ref wpi::memory::bad_allocation_size thrown.
+/// \ingroup core
+#define WPI_MEMORY_CHECK_ALLOCATION_SIZE 1
+
+/// Whether or not internal assertions in the library are enabled.
+/// \ingroup core
+#define WPI_MEMORY_DEBUG_ASSERT 1
+
+/// Whether or not allocated memory will be filled with special values.
+/// \ingroup core
+#define WPI_MEMORY_DEBUG_FILL 1
+
+/// The size of the fence memory, it has no effect if \ref WPI_MEMORY_DEBUG_FILL is \c false.
+/// \note For most allocators, the actual value doesn't matter and they use appropriate defaults to ensure alignment etc.
+/// \ingroup core
+#define WPI_MEMORY_DEBUG_FENCE 1
+
+/// Whether or not leak checking is enabled.
+/// \ingroup core
+#define WPI_MEMORY_DEBUG_LEAK_CHECK 1
+
+/// Whether or not the deallocation functions will check for pointers that were never allocated by an allocator.
+/// \ingroup core
+#define WPI_MEMORY_DEBUG_POINTER_CHECK 1
+
+/// Whether or not the deallocation functions will check for double free errors.
+/// This option makes no sense if \ref WPI_MEMORY_DEBUG_POINTER_CHECK is \c false.
+/// \ingroup core
+#define WPI_MEMORY_DEBUG_DOUBLE_DEALLOC_CHECK 1
+
+/// Whether or not everything is in namespace <tt>wpi::memory</tt>.
+/// If \c false, a namespace alias <tt>namespace memory = wpi::memory</tt> is automatically inserted into each header,
+/// allowing to qualify everything with <tt>wpi::</tt>.
+/// \note This option breaks in combination with using <tt>using namespace wpi;</tt>.
+/// \ingroup core
+#define WPI_MEMORY_NAMESPACE_PREFIX 1
+
+/// The mode of the automatic \ref wpi::memory::temporary_stack creation.
+/// Set to `2` to enable automatic lifetime management of the per-thread stack through nifty counter.
+/// Then all memory will be freed upon program termination automatically.
+/// Set to `1` to disable automatic lifetime managment of the per-thread stack,
+/// requires managing it through the \ref wpi::memory::temporary_stack_initializer.
+/// Set to `0` to disable the per-thread stack completely.
+/// \ref get_temporary_stack() will abort the program upon call.
+/// \ingroup allocator
+#define WPI_MEMORY_TEMPORARY_STACK_MODE 2
+#endif
+
+#endif // WPI_MEMORY_CONFIG_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/config_impl.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/config_impl.hpp
new file mode 100644
index 0000000..1f72375
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/config_impl.hpp
@@ -0,0 +1,34 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+// Copyright (C) 2015-2020 Jonathan Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#pragma once
+
+#include <cstddef>
+
+//=== options ===//
+#define WPI_MEMORY_CHECK_ALLOCATION_SIZE 1
+#define WPI_MEMORY_IMPL_DEFAULT_ALLOCATOR heap_allocator
+#ifdef NDEBUG
+#define WPI_MEMORY_DEBUG_ASSERT 0
+#define WPI_MEMORY_DEBUG_FILL 0
+#define WPI_MEMORY_DEBUG_FENCE 0
+#define WPI_MEMORY_DEBUG_LEAK_CHECK 0
+#define WPI_MEMORY_DEBUG_POINTER_CHECK 0
+#define WPI_MEMORY_DEBUG_DOUBLE_DEALLOC_CHECK 0
+#else
+#define WPI_MEMORY_DEBUG_ASSERT 1
+#define WPI_MEMORY_DEBUG_FILL 1
+#define WPI_MEMORY_DEBUG_FENCE 8
+#define WPI_MEMORY_DEBUG_LEAK_CHECK 1
+#define WPI_MEMORY_DEBUG_POINTER_CHECK 1
+#define WPI_MEMORY_DEBUG_DOUBLE_DEALLOC_CHECK 1
+#endif
+#define WPI_MEMORY_EXTERN_TEMPLATE 1
+#define WPI_MEMORY_TEMPORARY_STACK_MODE 2
+
+#define WPI_MEMORY_NO_NODE_SIZE 1
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/container.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/container.hpp
new file mode 100644
index 0000000..fd1547f
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/container.hpp
@@ -0,0 +1,362 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_CONTAINER_HPP_INCLUDED
+#define WPI_MEMORY_CONTAINER_HPP_INCLUDED
+
+/// \file
+/// Aliasas for STL containers using a certain \concept{concept_rawallocator,RawAllocator}.
+/// \note Only available on a hosted implementation.
+
+#include "config.hpp"
+#if !WPI_HOSTED_IMPLEMENTATION
+#error "This header is only available for a hosted implementation."
+#endif
+
+#include <functional>
+#include <utility>
+
+#include <deque>
+#include <forward_list>
+#include <list>
+#include <map>
+#include <queue>
+#include <scoped_allocator>
+#include <set>
+#include <stack>
+#include <string>
+#include <unordered_map>
+#include <unordered_set>
+#include <vector>
+
+#include "std_allocator.hpp"
+#include "threading.hpp"
+
+namespace wpi
+{
+    namespace memory
+    {
+        /// \ingroup adapter
+        /// @{
+
+        /// Alias template for an STL container that uses a certain
+        /// \concept{concept_rawallocator,RawAllocator}. It is just a shorthand for a passing in the \c
+        /// RawAllocator wrapped in a \ref wpi::memory::std_allocator.
+        template <typename T, class RawAllocator>
+        WPI_ALIAS_TEMPLATE(vector, std::vector<T, std_allocator<T, RawAllocator>>);
+
+        /// Same as above but uses \c std::scoped_allocator_adaptor so the allocator is inherited by all
+        /// nested containers.
+        template <typename T, class RawAllocator>
+        WPI_ALIAS_TEMPLATE(
+            vector_scoped_alloc,
+            std::vector<T, std::scoped_allocator_adaptor<std_allocator<T, RawAllocator>>>);
+
+        /// \copydoc vector
+        template <typename T, class RawAllocator>
+        WPI_ALIAS_TEMPLATE(deque, std::deque<T, std_allocator<T, RawAllocator>>);
+        /// \copydoc vector_scoped_alloc
+        template <typename T, class RawAllocator>
+        WPI_ALIAS_TEMPLATE(
+            deque_scoped_alloc,
+            std::deque<T, std::scoped_allocator_adaptor<std_allocator<T, RawAllocator>>>);
+
+        /// \copydoc vector
+        template <typename T, class RawAllocator>
+        WPI_ALIAS_TEMPLATE(list, std::list<T, std_allocator<T, RawAllocator>>);
+        /// \copydoc vector_scoped_alloc
+        template <typename T, class RawAllocator>
+        WPI_ALIAS_TEMPLATE(
+            list_scoped_alloc,
+            std::list<T, std::scoped_allocator_adaptor<std_allocator<T, RawAllocator>>>);
+
+        /// \copydoc vector
+        template <typename T, class RawAllocator>
+        WPI_ALIAS_TEMPLATE(forward_list,
+                                 std::forward_list<T, std_allocator<T, RawAllocator>>);
+        /// \copydoc vector_scoped_alloc
+        template <typename T, class RawAllocator>
+        WPI_ALIAS_TEMPLATE(
+            forward_list_scoped_alloc,
+            std::forward_list<T, std::scoped_allocator_adaptor<std_allocator<T, RawAllocator>>>);
+
+        /// \copydoc vector
+        template <typename T, class RawAllocator>
+        WPI_ALIAS_TEMPLATE(set, std::set<T, std::less<T>, std_allocator<T, RawAllocator>>);
+        /// \copydoc vector_scoped_alloc
+        template <typename T, class RawAllocator>
+        WPI_ALIAS_TEMPLATE(
+            set_scoped_alloc,
+            std::set<T, std::less<T>,
+                     std::scoped_allocator_adaptor<std_allocator<T, RawAllocator>>>);
+
+        /// \copydoc vector
+        template <typename T, class RawAllocator>
+        WPI_ALIAS_TEMPLATE(multiset,
+                                 std::multiset<T, std::less<T>, std_allocator<T, RawAllocator>>);
+        /// \copydoc vector_scoped_alloc
+        template <typename T, class RawAllocator>
+        WPI_ALIAS_TEMPLATE(
+            multiset_scoped_alloc,
+            std::multiset<T, std::less<T>,
+                          std::scoped_allocator_adaptor<std_allocator<T, RawAllocator>>>);
+
+        /// \copydoc vector
+        template <typename Key, typename Value, class RawAllocator>
+        WPI_ALIAS_TEMPLATE(
+            map, std::map<Key, Value, std::less<Key>,
+                          std_allocator<std::pair<const Key, Value>, RawAllocator>>);
+        /// \copydoc vector_scoped_alloc
+        template <typename Key, typename Value, class RawAllocator>
+        WPI_ALIAS_TEMPLATE(
+            map_scoped_alloc,
+            std::map<Key, Value, std::less<Key>,
+                     std::scoped_allocator_adaptor<
+                         std_allocator<std::pair<const Key, Value>, RawAllocator>>>);
+
+        /// \copydoc vector
+        template <typename Key, typename Value, class RawAllocator>
+        WPI_ALIAS_TEMPLATE(
+            multimap, std::multimap<Key, Value, std::less<Key>,
+                                    std_allocator<std::pair<const Key, Value>, RawAllocator>>);
+        /// \copydoc vector_scoped_alloc
+        template <typename Key, typename Value, class RawAllocator>
+        WPI_ALIAS_TEMPLATE(
+            multimap_scoped_alloc,
+            std::multimap<Key, Value, std::less<Key>,
+                          std::scoped_allocator_adaptor<
+                              std_allocator<std::pair<const Key, Value>, RawAllocator>>>);
+
+        /// \copydoc vector
+        template <typename T, class RawAllocator>
+        WPI_ALIAS_TEMPLATE(
+            unordered_set,
+            std::unordered_set<T, std::hash<T>, std::equal_to<T>, std_allocator<T, RawAllocator>>);
+        /// \copydoc vector_scoped_alloc
+        template <typename T, class RawAllocator>
+        WPI_ALIAS_TEMPLATE(
+            unordered_set_scoped_alloc,
+            std::unordered_set<T, std::hash<T>, std::equal_to<T>,
+                               std::scoped_allocator_adaptor<std_allocator<T, RawAllocator>>>);
+
+        /// \copydoc vector
+        template <typename T, class RawAllocator>
+        WPI_ALIAS_TEMPLATE(unordered_multiset,
+                                 std::unordered_multiset<T, std::hash<T>, std::equal_to<T>,
+                                                         std_allocator<T, RawAllocator>>);
+        /// \copydoc vector_scoped_alloc
+        template <typename T, class RawAllocator>
+        WPI_ALIAS_TEMPLATE(
+            unordered_multiset_scoped_alloc,
+            std::unordered_multiset<T, std::hash<T>, std::equal_to<T>,
+                                    std::scoped_allocator_adaptor<std_allocator<T, RawAllocator>>>);
+
+        /// \copydoc vector
+        template <typename Key, typename Value, class RawAllocator>
+        WPI_ALIAS_TEMPLATE(
+            unordered_map,
+            std::unordered_map<Key, Value, std::hash<Key>, std::equal_to<Key>,
+                               std_allocator<std::pair<const Key, Value>, RawAllocator>>);
+        /// \copydoc vector_scoped_alloc
+        template <typename Key, typename Value, class RawAllocator>
+        WPI_ALIAS_TEMPLATE(
+            unordered_map_scoped_alloc,
+            std::unordered_map<Key, Value, std::hash<Key>, std::equal_to<Key>,
+                               std::scoped_allocator_adaptor<
+                                   std_allocator<std::pair<const Key, Value>, RawAllocator>>>);
+
+        /// \copydoc vector
+        template <typename Key, typename Value, class RawAllocator>
+        WPI_ALIAS_TEMPLATE(
+            unordered_multimap,
+            std::unordered_multimap<Key, Value, std::hash<Key>, std::equal_to<Key>,
+                                    std_allocator<std::pair<const Key, Value>, RawAllocator>>);
+        /// \copydoc vector_scoped_alloc
+        template <typename Key, typename Value, class RawAllocator>
+        WPI_ALIAS_TEMPLATE(
+            unordered_multimap_scoped_alloc,
+            std::unordered_multimap<Key, Value, std::hash<Key>, std::equal_to<Key>,
+                                    std::scoped_allocator_adaptor<
+                                        std_allocator<std::pair<const Key, Value>, RawAllocator>>>);
+
+        /// \copydoc vector
+        template <typename T, class RawAllocator>
+        WPI_ALIAS_TEMPLATE(stack, std::stack<T, deque<T, RawAllocator>>);
+        /// \copydoc vector_scoped_alloc
+        template <typename T, class RawAllocator>
+        WPI_ALIAS_TEMPLATE(stack_scoped_alloc,
+                                 std::stack<T, deque_scoped_alloc<T, RawAllocator>>);
+
+        /// \copydoc vector
+        template <typename T, class RawAllocator>
+        WPI_ALIAS_TEMPLATE(queue, std::queue<T, deque<T, RawAllocator>>);
+        /// \copydoc vector_scoped_alloc
+        template <typename T, class RawAllocator>
+        WPI_ALIAS_TEMPLATE(queue_scoped_alloc,
+                                 std::queue<T, deque_scoped_alloc<T, RawAllocator>>);
+
+        /// \copydoc vector
+        template <typename T, class RawAllocator>
+        WPI_ALIAS_TEMPLATE(priority_queue, std::priority_queue<T, deque<T, RawAllocator>>);
+        /// \copydoc vector_scoped_alloc
+        template <typename T, class RawAllocator>
+        WPI_ALIAS_TEMPLATE(priority_queue_scoped_alloc,
+                                 std::priority_queue<T, deque_scoped_alloc<T, RawAllocator>>);
+
+        /// \copydoc vector
+        template <class RawAllocator>
+        WPI_ALIAS_TEMPLATE(
+            string,
+            std::basic_string<char, std::char_traits<char>, std_allocator<char, RawAllocator>>);
+        /// @}
+
+        /// @{
+        /// Convenience function to create a container adapter using a certain
+        /// \concept{concept_rawallocator,RawAllocator}. \returns An empty adapter with an
+        /// implementation container using a reference to a given allocator. \ingroup adapter
+        template <typename T, class RawAllocator, class Container = deque<T, RawAllocator>>
+        std::stack<T, Container> make_stack(RawAllocator& allocator)
+        {
+            return std::stack<T, Container>{Container(allocator)};
+        }
+
+        /// \copydoc make_stack
+        template <typename T, class RawAllocator, class Container = deque<T, RawAllocator>>
+        std::queue<T, Container> make_queue(RawAllocator& allocator)
+        {
+            return std::queue<T, Container>{Container(allocator)};
+        }
+
+        /// \copydoc make_stack
+        template <typename T, class RawAllocator, class Container = deque<T, RawAllocator>,
+                  class Compare = std::less<T>>
+        std::priority_queue<T, Container, Compare> make_priority_queue(RawAllocator& allocator,
+                                                                       Compare       comp = {})
+        {
+            return std::priority_queue<T, Container, Compare>{detail::move(comp),
+                                                              Container(allocator)};
+        }
+        /// @}
+
+#if !defined(DOXYGEN)
+
+#include "detail/container_node_sizes.hpp"
+
+#if !defined(WPI_MEMORY_NO_NODE_SIZE)
+        /// \exclude
+        namespace detail
+        {
+            template <typename T, class StdAllocator>
+            struct shared_ptr_node_size
+            {
+                static_assert(sizeof(T) != sizeof(T), "unsupported allocator type");
+            };
+
+            template <typename T, class RawAllocator>
+            struct shared_ptr_node_size<T, std_allocator<T, RawAllocator>>
+            : std::conditional<allocator_traits<RawAllocator>::is_stateful::value,
+                               memory::shared_ptr_stateful_node_size<T>,
+                               memory::shared_ptr_stateless_node_size<T>>::type
+            {
+                static_assert(sizeof(std_allocator<T, RawAllocator>) <= sizeof(void*),
+                              "fix node size debugger");
+            };
+
+        } // namespace detail
+
+        template <typename T, class StdAllocator>
+        struct shared_ptr_node_size : detail::shared_ptr_node_size<T, StdAllocator>
+        {
+        };
+#endif
+
+#else
+        /// \ingroup adapter
+        /// @{
+
+        /// Contains the node size of a node based STL container with a specific type.
+        /// These classes are auto-generated and only available if the tools are build and without
+        /// cross-compiling.
+        template <typename T>
+        struct forward_list_node_size : std::integral_constant<std::size_t, implementation_defined>
+        {
+        };
+
+        /// \copydoc forward_list_node_size
+        template <typename T>
+        struct list_node_size : std::integral_constant<std::size_t, implementation_defined>
+        {
+        };
+
+        /// \copydoc forward_list_node_size
+        template <typename T>
+        struct set_node_size : std::integral_constant<std::size_t, implementation_defined>
+        {
+        };
+
+        /// \copydoc forward_list_node_size
+        template <typename T>
+        struct multiset_node_size : std::integral_constant<std::size_t, implementation_defined>
+        {
+        };
+
+        /// \copydoc forward_list_node_size
+        template <typename T>
+        struct unordered_set_node_size : std::integral_constant<std::size_t, implementation_defined>
+        {
+        };
+
+        /// \copydoc forward_list_node_size
+        template <typename T>
+        struct unordered_multiset_node_size
+        : std::integral_constant<std::size_t, implementation_defined>
+        {
+        };
+
+        /// \copydoc forward_list_node_size
+        template <typename T>
+        struct map_node_size : std::integral_constant<std::size_t, implementation_defined>
+        {
+        };
+
+        /// \copydoc forward_list_node_size
+        template <typename T>
+        struct multimap_node_size : std::integral_constant<std::size_t, implementation_defined>
+        {
+        };
+
+        /// \copydoc forward_list_node_size
+        template <typename T>
+        struct unordered_map_node_size : std::integral_constant<std::size_t, implementation_defined>
+        {
+        };
+
+        /// \copydoc forward_list_node_size
+        template <typename T>
+        struct unordered_multimap_node_size
+        : std::integral_constant<std::size_t, implementation_defined>
+        {
+        };
+
+        /// \copydoc forward_list_node_size
+        template <typename T, class StdAllocator>
+        struct shared_ptr_node_size : std::integral_constant<std::size_t, implementation_defined>
+        {
+        };
+/// @}
+#endif
+
+#if !defined(WPI_MEMORY_NO_NODE_SIZE)
+        /// The node size required by \ref allocate_shared.
+        /// \note This is similar to \ref shared_ptr_node_size but takes a
+        /// \concept{concept_rawallocator,RawAllocator} instead.
+        template <typename T, class RawAllocator>
+        struct allocate_shared_node_size : shared_ptr_node_size<T, std_allocator<T, RawAllocator>>
+        {
+        };
+#endif
+    } // namespace memory
+} // namespace wpi
+
+#endif // WPI_MEMORY_CONTAINER_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/debugging.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/debugging.hpp
new file mode 100644
index 0000000..b04050f
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/debugging.hpp
@@ -0,0 +1,114 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_DEBUGGING_HPP_INCLUDED
+#define WPI_MEMORY_DEBUGGING_HPP_INCLUDED
+
+/// \file
+/// Debugging facilities.
+
+#include "config.hpp"
+
+namespace wpi
+{
+    namespace memory
+    {
+        struct allocator_info;
+
+        /// The magic values that are used for debug filling.
+        /// If \ref WPI_MEMORY_DEBUG_FILL is \c true, memory will be filled to help detect use-after-free or missing initialization errors.
+        /// These are the constants for the different types.
+        /// \ingroup core
+        enum class debug_magic : unsigned char
+        {
+            /// Marks internal memory used by the allocator - "allocated block".
+            internal_memory = 0xAB,
+            /// Marks internal memory currently not used by the allocator - "freed block".
+            internal_freed_memory = 0xFB,
+            /// Marks allocated, but not yet used memory - "clean memory".
+            new_memory = 0xCD,
+            /// Marks freed memory - "dead memory".
+            freed_memory = 0xDD,
+            /// Marks buffer memory used to ensure proper alignment.
+            /// This memory can also serve as \ref debug_magic::fence_memory.
+            alignment_memory = 0xED,
+            /// Marks buffer memory used to protect against overflow - "fence memory".
+            /// The option \ref WPI_MEMORY_DEBUG_FENCE controls the size of a memory fence that will be placed before or after a memory block.
+            /// It helps catching buffer overflows.
+            fence_memory = 0xFD
+        };
+
+        /// The type of the handler called when a memory leak is detected.
+        /// Leak checking can be controlled via the option \ref WPI_MEMORY_DEBUG_LEAK_CHECK
+        /// and only affects calls through the \ref allocator_traits, not direct calls.
+        /// The handler gets the \ref allocator_info and the amount of memory leaked.
+        /// This can also be negative, meaning that more memory has been freed than allocated.
+        /// \requiredbe A leak handler shall log the leak, abort the program, do nothing or anything else that seems appropriate.
+        /// It must not throw any exceptions since it is called in the cleanup process.
+        /// \defaultbe On a hosted implementation it logs the leak to \c stderr and returns, continuing execution.
+        /// On a freestanding implementation it does nothing.
+        /// \ingroup core
+        using leak_handler = void (*)(const allocator_info& info, std::ptrdiff_t amount);
+
+        /// Exchanges the \ref leak_handler.
+        /// \effects Sets \c h as the new \ref leak_handler in an atomic operation.
+        /// A \c nullptr sets the default \ref leak_handler.
+        /// \returns The previous \ref leak_handler. This is never \c nullptr.
+        /// \ingroup core
+        leak_handler set_leak_handler(leak_handler h);
+
+        /// Returns the \ref leak_handler.
+        /// \returns The current \ref leak_handler. This is never \c nullptr.
+        /// \ingroup core
+        leak_handler get_leak_handler();
+
+        /// The type of the handler called when an invalid pointer is passed to a deallocation function.
+        /// Pointer checking can be controlled via the options \ref WPI_MEMORY_DEBUG_POINTER_CHECK and \ref WPI_MEMORY_DEBUG_DOUBLE_DEALLOC_CHECK.
+        /// The handler gets the \ref allocator_info and the invalid pointer.
+        /// \requiredbe An invalid pointer handler shall terminate the program.
+        /// It must not throw any exceptions since it might be called in the cleanup process.
+        /// \defaultbe On a hosted implementation it logs the information to \c stderr and calls \c std::abort().
+        /// On a freestanding implementation it only calls \c std::abort().
+        /// \ingroup core
+        using invalid_pointer_handler = void (*)(const allocator_info& info, const void* ptr);
+
+        /// Exchanges the \ref invalid_pointer_handler.
+        /// \effects Sets \c h as the new \ref invalid_pointer_handler in an atomic operation.
+        /// A \c nullptr sets the default \ref invalid_pointer_handler.
+        /// \returns The previous \ref invalid_pointer_handler. This is never \c nullptr.
+        /// \ingroup core
+        invalid_pointer_handler set_invalid_pointer_handler(invalid_pointer_handler h);
+
+        /// Returns the \ref invalid_pointer_handler.
+        /// \returns The current \ref invalid_pointer_handler. This is never \c nullptr.
+        /// \ingroup core
+        invalid_pointer_handler get_invalid_pointer_handler();
+
+        /// The type of the handler called when a buffer under/overflow is detected.
+        /// If \ref WPI_MEMORY_DEBUG_FILL is \c true and \ref WPI_MEMORY_DEBUG_FENCE has a non-zero value
+        /// the allocator classes check if a write into the fence has occured upon deallocation.
+        /// The handler gets the memory block belonging to the corrupted fence, its size and the exact address.
+        /// \requiredbe A buffer overflow handler shall terminate the program.
+        /// It must not throw any exceptions since it me be called in the cleanup process.
+        /// \defaultbe On a hosted implementation it logs the information to \c stderr and calls \c std::abort().
+        /// On a freestanding implementation it only calls \c std::abort().
+        /// \ingroup core
+        using buffer_overflow_handler = void (*)(const void* memory, std::size_t size,
+                                                 const void* write_ptr);
+
+        /// Exchanges the \ref buffer_overflow_handler.
+        /// \effects Sets \c h as the new \ref buffer_overflow_handler in an atomic operation.
+        /// A \c nullptr sets the default \ref buffer_overflow_handler.
+        /// \returns The previous \ref buffer_overflow_handler. This is never \c nullptr.
+        /// \ingroup core
+        buffer_overflow_handler set_buffer_overflow_handler(buffer_overflow_handler h);
+
+        /// Returns the \ref buffer_overflow_handler.
+        /// \returns The current \ref buffer_overflow_handler. This is never \c nullptr.
+        /// \ingroup core
+        buffer_overflow_handler get_buffer_overflow_handler();
+    } // namespace memory
+} // namespace wpi
+
+#endif // WPI_MEMORY_DEBUGGING_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/default_allocator.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/default_allocator.hpp
new file mode 100644
index 0000000..107a641
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/default_allocator.hpp
@@ -0,0 +1,37 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_DEFAULT_ALLOCATOR_HPP_INCLUDED
+#define WPI_MEMORY_DEFAULT_ALLOCATOR_HPP_INCLUDED
+
+/// \file
+/// The typedef \ref wpi::memory::default_allocator.
+
+#include "config.hpp"
+#include "heap_allocator.hpp"
+#include "new_allocator.hpp"
+#include "static_allocator.hpp"
+#include "virtual_memory.hpp"
+
+#if WPI_HOSTED_IMPLEMENTATION
+#include "malloc_allocator.hpp"
+#endif
+
+namespace wpi
+{
+    namespace memory
+    {
+        /// The default \concept{concept_rawallocator,RawAllocator} that will be used as \concept{concept_blockallocator,BlockAllocator} in memory arenas.
+        /// Arena allocators like \ref memory_stack or \ref memory_pool allocate memory by subdividing a huge block.
+        /// They get a \concept{concept_blockallocator,BlockAllocator} that will be used for their internal allocation,
+        /// this type is the default value.
+        /// \requiredbe Its type can be changed via the CMake option \c WPI_MEMORY_DEFAULT_ALLCOATOR,
+        /// but it must be one of the following: \ref heap_allocator, \ref new_allocator, \ref malloc_allocator, \ref static_allocator, \ref virtual_memory_allocator.
+        /// \defaultbe The default is \ref heap_allocator.
+        /// \ingroup allocator
+        using default_allocator = WPI_IMPL_DEFINED(WPI_MEMORY_IMPL_DEFAULT_ALLOCATOR);
+    } // namespace memory
+} // namespace wpi
+
+#endif // WPI_MEMORY_DEFAULT_ALLOCATOR_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/deleter.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/deleter.hpp
new file mode 100644
index 0000000..01c967c
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/deleter.hpp
@@ -0,0 +1,308 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_DELETER_HPP_INCLUDED
+#define WPI_MEMORY_DELETER_HPP_INCLUDED
+
+/// \file
+/// \c Deleter classes using a \concept{concept_rawallocator,RawAllocator}.
+
+#include <type_traits>
+
+#include "allocator_storage.hpp"
+#include "config.hpp"
+#include "threading.hpp"
+
+namespace wpi
+{
+    namespace memory
+    {
+        /// A deleter class that deallocates the memory through a specified \concept{concept_rawallocator,RawAllocator}.
+        ///
+        /// It deallocates memory for a specified type but does not call its destructors.
+        /// \ingroup adapter
+        template <typename Type, class RawAllocator>
+        class allocator_deallocator : WPI_EBO(allocator_reference<RawAllocator>)
+        {
+            static_assert(!std::is_abstract<Type>::value,
+                          "use allocator_polymorphic_deallocator for storing base classes");
+
+        public:
+            using allocator_type = typename allocator_reference<RawAllocator>::allocator_type;
+            using value_type     = Type;
+
+            /// \effects Creates it without any associated allocator.
+            /// The deallocator must not be used if that is the case.
+            /// \notes This functions is useful if you have want to create an empty smart pointer without giving it an allocator.
+            allocator_deallocator() noexcept = default;
+
+            /// \effects Creates it by passing it an \ref allocator_reference.
+            /// It will store the reference to it and uses the referenced allocator object for the deallocation.
+            allocator_deallocator(allocator_reference<RawAllocator> alloc) noexcept
+            : allocator_reference<RawAllocator>(alloc)
+            {
+            }
+
+            /// \effects Deallocates the memory given to it.
+            /// Calls \c deallocate_node(pointer, sizeof(value_type), alignof(value_type)) on the referenced allocator object.
+            /// \requires The deallocator must not have been created by the default constructor.
+            void operator()(value_type* pointer) noexcept
+            {
+                this->deallocate_node(pointer, sizeof(value_type), alignof(value_type));
+            }
+
+            /// \returns The reference to the allocator.
+            /// It has the same type as the call to \ref allocator_reference::get_allocator().
+            /// \requires The deallocator must not be created by the default constructor.
+            auto get_allocator() const noexcept
+                -> decltype(std::declval<allocator_reference<allocator_type>>().get_allocator())
+            {
+                return this->allocator_reference<allocator_type>::get_allocator();
+            }
+        };
+
+        /// Specialization of \ref allocator_deallocator for array types.
+        /// Otherwise the same behavior.
+        /// \ingroup adapter
+        template <typename Type, class RawAllocator>
+        class allocator_deallocator<Type[], RawAllocator>
+        : WPI_EBO(allocator_reference<RawAllocator>)
+        {
+            static_assert(!std::is_abstract<Type>::value, "must not create polymorphic arrays");
+
+        public:
+            using allocator_type = typename allocator_reference<RawAllocator>::allocator_type;
+            using value_type     = Type;
+
+            /// \effects Creates it without any associated allocator.
+            /// The deallocator must not be used if that is the case.
+            /// \notes This functions is useful if you have want to create an empty smart pointer without giving it an allocator.
+            allocator_deallocator() noexcept : size_(0u) {}
+
+            /// \effects Creates it by passing it an \ref allocator_reference and the size of the array that will be deallocated.
+            /// It will store the reference to the allocator and uses the referenced allocator object for the deallocation.
+            allocator_deallocator(allocator_reference<RawAllocator> alloc,
+                                  std::size_t                       size) noexcept
+            : allocator_reference<RawAllocator>(alloc), size_(size)
+            {
+            }
+
+            /// \effects Deallocates the memory given to it.
+            /// Calls \c deallocate_array(pointer, size, sizeof(value_type), alignof(value_type))
+            /// on the referenced allocator object with the size given in the constructor.
+            /// \requires The deallocator must not have been created by the default constructor.
+            void operator()(value_type* pointer) noexcept
+            {
+                this->deallocate_array(pointer, size_, sizeof(value_type), alignof(value_type));
+            }
+
+            /// \returns The reference to the allocator.
+            /// It has the same type as the call to \ref allocator_reference::get_allocator().
+            /// \requires The deallocator must not have been created by the default constructor.
+            auto get_allocator() const noexcept
+                -> decltype(std::declval<allocator_reference<allocator_type>>().get_allocator())
+            {
+                return this->allocator_reference<allocator_type>::get_allocator();
+            }
+
+            /// \returns The size of the array that will be deallocated.
+            /// This is the same value as passed in the constructor, or `0` if it was created by the default constructor.
+            std::size_t array_size() const noexcept
+            {
+                return size_;
+            }
+
+        private:
+            std::size_t size_;
+        };
+
+        /// A deleter class that deallocates the memory of a derived type through a specified \concept{concept_rawallocator,RawAllocator}.
+        ///
+        /// It can only be created from a \ref allocator_deallocator and thus must only be used for smart pointers initialized by derived-to-base conversion of the pointer.
+        /// \ingroup adapter
+        template <typename BaseType, class RawAllocator>
+        class allocator_polymorphic_deallocator : WPI_EBO(allocator_reference<RawAllocator>)
+        {
+        public:
+            using allocator_type = typename allocator_reference<RawAllocator>::allocator_type;
+            using value_type     = BaseType;
+
+            /// \effects Creates it from a deallocator for a derived type.
+            /// It will deallocate the memory as if done by the derived type.
+            template <typename T, WPI_REQUIRES((std::is_base_of<BaseType, T>::value))>
+            allocator_polymorphic_deallocator(allocator_deallocator<T, RawAllocator> dealloc)
+            : allocator_reference<RawAllocator>(dealloc.get_allocator()),
+              derived_size_(sizeof(T)),
+              derived_alignment_(alignof(T))
+            {
+            }
+
+            /// \effects Deallocates the memory given to it.
+            /// Calls \c deallocate_node(pointer, size, alignment) on the referenced allocator object,
+            /// where \c size and \c alignment are the values of the type it was created with.
+            void operator()(value_type* pointer) noexcept
+            {
+                this->deallocate_node(pointer, derived_size_, derived_alignment_);
+            }
+
+            /// \returns The reference to the allocator.
+            /// It has the same type as the call to \ref allocator_reference::get_allocator().
+            auto get_allocator() const noexcept
+                -> decltype(std::declval<allocator_reference<allocator_type>>().get_allocator())
+            {
+                return this->allocator_reference<allocator_type>::get_allocator();
+            }
+
+        private:
+            std::size_t derived_size_, derived_alignment_;
+        };
+
+        /// Similar to \ref allocator_deallocator but calls the destructors of the object.
+        /// Otherwise behaves the same.
+        /// \ingroup adapter
+        template <typename Type, class RawAllocator>
+        class allocator_deleter : WPI_EBO(allocator_reference<RawAllocator>)
+        {
+            static_assert(!std::is_abstract<Type>::value,
+                          "use allocator_polymorphic_deleter for storing base classes");
+
+        public:
+            using allocator_type = typename allocator_reference<RawAllocator>::allocator_type;
+            using value_type     = Type;
+
+            /// \effects Creates it without any associated allocator.
+            /// The deleter must not be used if that is the case.
+            /// \notes This functions is useful if you have want to create an empty smart pointer without giving it an allocator.
+            allocator_deleter() noexcept = default;
+
+            /// \effects Creates it by passing it an \ref allocator_reference.
+            /// It will store the reference to it and uses the referenced allocator object for the deallocation.
+            allocator_deleter(allocator_reference<RawAllocator> alloc) noexcept
+            : allocator_reference<RawAllocator>(alloc)
+            {
+            }
+
+            /// \effects Calls the destructor and deallocates the memory given to it.
+            /// Calls \c deallocate_node(pointer, sizeof(value_type), alignof(value_type))
+            /// on the referenced allocator object for the deallocation.
+            /// \requires The deleter must not have been created by the default constructor.
+            void operator()(value_type* pointer) noexcept
+            {
+                pointer->~value_type();
+                this->deallocate_node(pointer, sizeof(value_type), alignof(value_type));
+            }
+
+            /// \returns The reference to the allocator.
+            /// It has the same type as the call to \ref allocator_reference::get_allocator().
+            auto get_allocator() const noexcept
+                -> decltype(std::declval<allocator_reference<allocator_type>>().get_allocator())
+            {
+                return this->allocator_reference<allocator_type>::get_allocator();
+            }
+        };
+
+        /// Specialization of \ref allocator_deleter for array types.
+        /// Otherwise the same behavior.
+        /// \ingroup adapter
+        template <typename Type, class RawAllocator>
+        class allocator_deleter<Type[], RawAllocator>
+        : WPI_EBO(allocator_reference<RawAllocator>)
+        {
+            static_assert(!std::is_abstract<Type>::value, "must not create polymorphic arrays");
+
+        public:
+            using allocator_type = typename allocator_reference<RawAllocator>::allocator_type;
+            using value_type     = Type;
+
+            /// \effects Creates it without any associated allocator.
+            /// The deleter must not be used if that is the case.
+            /// \notes This functions is useful if you have want to create an empty smart pointer without giving it an allocator.
+            allocator_deleter() noexcept : size_(0u) {}
+
+            /// \effects Creates it by passing it an \ref allocator_reference and the size of the array that will be deallocated.
+            /// It will store the reference to the allocator and uses the referenced allocator object for the deallocation.
+            allocator_deleter(allocator_reference<RawAllocator> alloc, std::size_t size) noexcept
+            : allocator_reference<RawAllocator>(alloc), size_(size)
+            {
+            }
+
+            /// \effects Calls the destructors and deallocates the memory given to it.
+            /// Calls \c deallocate_array(pointer, size, sizeof(value_type), alignof(value_type))
+            /// on the referenced allocator object with the size given in the constructor for the deallocation.
+            /// \requires The deleter must not have been created by the default constructor.
+            void operator()(value_type* pointer) noexcept
+            {
+                for (auto cur = pointer; cur != pointer + size_; ++cur)
+                    cur->~value_type();
+                this->deallocate_array(pointer, size_, sizeof(value_type), alignof(value_type));
+            }
+
+            /// \returns The reference to the allocator.
+            /// It has the same type as the call to \ref allocator_reference::get_allocator().
+            /// \requires The deleter must not be created by the default constructor.
+            auto get_allocator() const noexcept
+                -> decltype(std::declval<allocator_reference<allocator_type>>().get_allocator())
+            {
+                return this->allocator_reference<allocator_type>::get_allocator();
+            }
+
+            /// \returns The size of the array that will be deallocated.
+            /// This is the same value as passed in the constructor, or `0` if it was created by the default constructor.
+            std::size_t array_size() const noexcept
+            {
+                return size_;
+            }
+
+        private:
+            std::size_t size_;
+        };
+
+        /// Similar to \ref allocator_polymorphic_deallocator but calls the destructors of the object.
+        /// Otherwise behaves the same.
+        /// \note It has a relatively high space overhead, so only use it if you have to.
+        /// \ingroup adapter
+        template <typename BaseType, class RawAllocator>
+        class allocator_polymorphic_deleter : WPI_EBO(allocator_reference<RawAllocator>)
+        {
+        public:
+            using allocator_type = typename allocator_reference<RawAllocator>::allocator_type;
+            using value_type     = BaseType;
+
+            /// \effects Creates it from a deleter for a derived type.
+            /// It will deallocate the memory as if done by the derived type.
+            template <typename T, WPI_REQUIRES((std::is_base_of<BaseType, T>::value))>
+            allocator_polymorphic_deleter(allocator_deleter<T, RawAllocator> deleter)
+            : allocator_reference<RawAllocator>(deleter.get_allocator()),
+              derived_size_(sizeof(T)),
+              derived_alignment_(alignof(T))
+            {
+                WPI_MEMORY_ASSERT(std::size_t(derived_size_) == sizeof(T)
+                                        && std::size_t(derived_alignment_) == alignof(T));
+            }
+
+            /// \effects Deallocates the memory given to it.
+            /// Calls \c deallocate_node(pointer, size, alignment) on the referenced allocator object,
+            /// where \c size and \c alignment are the values of the type it was created with.
+            void operator()(value_type* pointer) noexcept
+            {
+                pointer->~value_type();
+                this->deallocate_node(pointer, derived_size_, derived_alignment_);
+            }
+
+            /// \returns The reference to the allocator.
+            /// It has the same type as the call to \ref allocator_reference::get_allocator().
+            auto get_allocator() const noexcept
+                -> decltype(std::declval<allocator_reference<allocator_type>>().get_allocator())
+            {
+                return this->allocator_reference<allocator_type>::get_allocator();
+            }
+
+        private:
+            unsigned short derived_size_,
+                derived_alignment_; // use unsigned short here to save space
+        };
+    } // namespace memory
+} // namespace wpi
+
+#endif //WPI_MEMORY_DELETER_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/detail/align.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/detail/align.hpp
new file mode 100644
index 0000000..99d6bcc
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/detail/align.hpp
@@ -0,0 +1,52 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_DETAIL_ALIGN_HPP_INCLUDED
+#define WPI_MEMORY_DETAIL_ALIGN_HPP_INCLUDED
+
+#include <cstdint>
+
+#include "../config.hpp"
+#include "assert.hpp"
+
+namespace wpi
+{
+    namespace memory
+    {
+        namespace detail
+        {
+            // whether or not an alignment is valid, i.e. a power of two not zero
+            constexpr bool is_valid_alignment(std::size_t alignment) noexcept
+            {
+                return alignment && (alignment & (alignment - 1)) == 0u;
+            }
+
+            // returns the offset needed to align ptr for given alignment
+            // alignment must be valid
+            inline std::size_t align_offset(std::uintptr_t address, std::size_t alignment) noexcept
+            {
+                WPI_MEMORY_ASSERT(is_valid_alignment(alignment));
+                auto misaligned = address & (alignment - 1);
+                return misaligned != 0 ? (alignment - misaligned) : 0;
+            }
+            inline std::size_t align_offset(void* ptr, std::size_t alignment) noexcept
+            {
+                return align_offset(reinterpret_cast<std::uintptr_t>(ptr), alignment);
+            }
+
+            // whether or not the pointer is aligned for given alignment
+            // alignment must be valid
+            bool is_aligned(void* ptr, std::size_t alignment) noexcept;
+
+            // maximum alignment value
+            constexpr std::size_t max_alignment = alignof(std::max_align_t);
+            static_assert(is_valid_alignment(max_alignment), "ehm..?");
+
+            // returns the minimum alignment required for a node of given size
+            std::size_t alignment_for(std::size_t size) noexcept;
+        } // namespace detail
+    }     // namespace memory
+} // namespace wpi
+
+#endif // WPI_MEMORY_DETAIL_ALIGN_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/detail/assert.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/detail/assert.hpp
new file mode 100644
index 0000000..b8a7372
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/detail/assert.hpp
@@ -0,0 +1,57 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_DETAIL_ASSERT_HPP_INCLUDED
+#define WPI_MEMORY_DETAIL_ASSERT_HPP_INCLUDED
+
+#include <cstdlib>
+
+#include "../config.hpp"
+
+namespace wpi
+{
+    namespace memory
+    {
+        namespace detail
+        {
+            // handles a failed assertion
+            void handle_failed_assert(const char* msg, const char* file, int line,
+                                      const char* fnc) noexcept;
+
+            void handle_warning(const char* msg, const char* file, int line,
+                                const char* fnc) noexcept;
+
+// note: debug assertion macros don't use fully qualified name
+// because they should only be used in this library, where the whole namespace is available
+// can be override via command line definitions
+#if WPI_MEMORY_DEBUG_ASSERT && !defined(WPI_MEMORY_ASSERT)
+#define WPI_MEMORY_ASSERT(Expr)                                                              \
+    static_cast<void>((Expr)                                                                       \
+                      || (detail::handle_failed_assert("Assertion \"" #Expr "\" failed", __FILE__, \
+                                                       __LINE__, __func__),                        \
+                          true))
+
+#define WPI_MEMORY_ASSERT_MSG(Expr, Msg)                                                     \
+    static_cast<void>((Expr)                                                                       \
+                      || (detail::handle_failed_assert("Assertion \"" #Expr "\" failed: " Msg,     \
+                                                       __FILE__, __LINE__, __func__),              \
+                          true))
+
+#define WPI_MEMORY_UNREACHABLE(Msg)                                                          \
+    detail::handle_failed_assert("Unreachable code reached: " Msg, __FILE__, __LINE__, __func__)
+
+#define WPI_MEMORY_WARNING(Msg) detail::handle_warning(Msg, __FILE__, __LINE__, __func__)
+
+#elif !defined(WPI_MEMORY_ASSERT)
+#define WPI_MEMORY_ASSERT(Expr)
+#define WPI_MEMORY_ASSERT_MSG(Expr, Msg)
+#define WPI_MEMORY_UNREACHABLE(Msg) std::abort()
+#define WPI_MEMORY_WARNING(Msg)
+#endif
+        } // namespace detail
+    }     // namespace memory
+} // namespace wpi
+
+#endif // WPI_MEMORY_DETAIL_ASSERT_HPP_INCLUDED
+
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/detail/container_node_sizes.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/detail/container_node_sizes.hpp
new file mode 100644
index 0000000..37949ca
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/detail/container_node_sizes.hpp
@@ -0,0 +1,10 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_DETAIL_CONTAINER_NODE_SIZES_HPP_INCLUDED
+#define WPI_MEMORY_DETAIL_CONTAINER_NODE_SIZES_HPP_INCLUDED
+
+#include "container_node_sizes_impl.hpp"
+
+#endif //WPI_MEMORY_DETAIL_CONTAINER_NODE_SIZES_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/detail/debug_helpers.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/detail/debug_helpers.hpp
new file mode 100644
index 0000000..3ef2eed
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/detail/debug_helpers.hpp
@@ -0,0 +1,235 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_DEBUG_HELPERS_HPP_INCLUDED
+#define WPI_MEMORY_DEBUG_HELPERS_HPP_INCLUDED
+
+#include <atomic>
+#include <type_traits>
+
+#include "../config.hpp"
+
+namespace wpi
+{
+    namespace memory
+    {
+        enum class debug_magic : unsigned char;
+        struct allocator_info;
+
+        namespace detail
+        {
+            using debug_fill_enabled = std::integral_constant<bool, WPI_MEMORY_DEBUG_FILL>;
+            constexpr std::size_t debug_fence_size =
+                WPI_MEMORY_DEBUG_FILL ? WPI_MEMORY_DEBUG_FENCE : 0u;
+
+#if WPI_MEMORY_DEBUG_FILL
+            // fills size bytes of memory with debug_magic
+            void debug_fill(void* memory, std::size_t size, debug_magic m) noexcept;
+
+            // returns nullptr if memory is filled with debug_magic
+            // else returns pointer to mismatched byte
+            void* debug_is_filled(void* memory, std::size_t size, debug_magic m) noexcept;
+
+            // fills fence, new and fence
+            // returns after fence
+            void* debug_fill_new(void* memory, std::size_t node_size,
+                                 std::size_t fence_size = debug_fence_size) noexcept;
+
+            // fills free memory and returns memory starting at fence
+            void* debug_fill_free(void* memory, std::size_t node_size,
+                                  std::size_t fence_size = debug_fence_size) noexcept;
+
+            // fills internal memory
+            void debug_fill_internal(void* memory, std::size_t size, bool free) noexcept;
+#else
+            inline void debug_fill(void*, std::size_t, debug_magic) noexcept {}
+
+            inline void* debug_is_filled(void*, std::size_t, debug_magic) noexcept
+            {
+                return nullptr;
+            }
+
+            inline void* debug_fill_new(void* memory, std::size_t, std::size_t) noexcept
+            {
+                return memory;
+            }
+
+            inline void* debug_fill_free(void* memory, std::size_t, std::size_t) noexcept
+            {
+                return static_cast<char*>(memory);
+            }
+
+            inline void debug_fill_internal(void*, std::size_t, bool) noexcept {}
+#endif
+
+            void debug_handle_invalid_ptr(const allocator_info& info, void* ptr);
+
+            // validates given ptr by evaluating the Functor
+            // if the Functor returns false, calls the debug_leak_checker
+            // note: ptr is just used as the information passed to the invalid ptr handler
+            template <class Functor>
+            void debug_check_pointer(Functor condition, const allocator_info& info, void* ptr)
+            {
+#if WPI_MEMORY_DEBUG_POINTER_CHECK
+                if (!condition())
+                    debug_handle_invalid_ptr(info, ptr);
+#else
+                (void)ptr;
+                (void)condition;
+                (void)info;
+#endif
+            }
+
+            // validates ptr by using a more expensive double-dealloc check
+            template <class Functor>
+            void debug_check_double_dealloc(Functor condition, const allocator_info& info,
+                                            void* ptr)
+            {
+#if WPI_MEMORY_DEBUG_DOUBLE_DEALLOC_CHECK
+                debug_check_pointer(condition, info, ptr);
+#else
+                (void)condition;
+                (void)info;
+                (void)ptr;
+#endif
+            }
+
+            void debug_handle_memory_leak(const allocator_info& info, std::ptrdiff_t amount);
+
+            // does no leak checking, null overhead
+            template <class Handler>
+            class no_leak_checker
+            {
+            public:
+                no_leak_checker() noexcept {}
+                no_leak_checker(no_leak_checker&&) noexcept {}
+                ~no_leak_checker() noexcept {}
+
+                no_leak_checker& operator=(no_leak_checker&&) noexcept
+                {
+                    return *this;
+                }
+
+                void on_allocate(std::size_t) noexcept {}
+                void on_deallocate(std::size_t) noexcept {}
+            };
+
+            // does leak checking per-object
+            // leak is detected upon destructor
+            template <class Handler>
+            class object_leak_checker : Handler
+            {
+            public:
+                object_leak_checker() noexcept : allocated_(0) {}
+
+                object_leak_checker(object_leak_checker&& other) noexcept
+                : allocated_(other.allocated_)
+                {
+                    other.allocated_ = 0;
+                }
+
+                ~object_leak_checker() noexcept
+                {
+                    if (allocated_ != 0)
+                        this->operator()(allocated_);
+                }
+
+                object_leak_checker& operator=(object_leak_checker&& other) noexcept
+                {
+                    allocated_       = other.allocated_;
+                    other.allocated_ = 0;
+                    return *this;
+                }
+
+                void on_allocate(std::size_t size) noexcept
+                {
+                    allocated_ += std::ptrdiff_t(size);
+                }
+
+                void on_deallocate(std::size_t size) noexcept
+                {
+                    allocated_ -= std::ptrdiff_t(size);
+                }
+
+            private:
+                std::ptrdiff_t allocated_;
+            };
+
+            // does leak checking on a global basis
+            // call macro WPI_MEMORY_GLOBAL_LEAK_CHECKER(handler, var_name) in the header
+            // when last counter gets destroyed, leak is detected
+            template <class Handler>
+            class global_leak_checker_impl
+            {
+            public:
+                struct counter : Handler
+                {
+                    counter()
+                    {
+                        ++no_counter_objects_;
+                    }
+
+                    ~counter()
+                    {
+                        --no_counter_objects_;
+                        if (no_counter_objects_ == 0u && allocated_ != 0u)
+                            this->operator()(allocated_);
+                    }
+                };
+
+                global_leak_checker_impl() noexcept {}
+                global_leak_checker_impl(global_leak_checker_impl&&) noexcept {}
+                ~global_leak_checker_impl() noexcept {}
+
+                global_leak_checker_impl& operator=(global_leak_checker_impl&&) noexcept
+                {
+                    return *this;
+                }
+
+                void on_allocate(std::size_t size) noexcept
+                {
+                    allocated_ += std::ptrdiff_t(size);
+                }
+
+                void on_deallocate(std::size_t size) noexcept
+                {
+                    allocated_ -= std::ptrdiff_t(size);
+                }
+
+            private:
+                static std::atomic<std::size_t>    no_counter_objects_;
+                static std::atomic<std::ptrdiff_t> allocated_;
+            };
+
+            template <class Handler>
+            std::atomic<std::size_t> global_leak_checker_impl<Handler>::no_counter_objects_(0u);
+
+            template <class Handler>
+            std::atomic<std::ptrdiff_t> global_leak_checker_impl<Handler>::allocated_(0);
+
+#if WPI_MEMORY_DEBUG_LEAK_CHECK
+            template <class Handler>
+            using global_leak_checker = global_leak_checker_impl<Handler>;
+
+#define WPI_MEMORY_GLOBAL_LEAK_CHECKER(handler, var_name)                                    \
+    static wpi::memory::detail::global_leak_checker<handler>::counter var_name;
+#else
+            template <class Handler>
+            using global_leak_checker = no_leak_checker<int>; // only one instantiation
+
+#define WPI_MEMORY_GLOBAL_LEAK_CHECKER(handler, var_name)
+#endif
+
+#if WPI_MEMORY_DEBUG_LEAK_CHECK
+            template <class Handler>
+            using default_leak_checker = object_leak_checker<Handler>;
+#else
+            template <class Handler>
+            using default_leak_checker = no_leak_checker<Handler>;
+#endif
+        } // namespace detail
+    }     // namespace memory
+} // namespace wpi
+
+#endif // WPI_MEMORY_DEBUG_HELPERS_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/detail/ebo_storage.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/detail/ebo_storage.hpp
new file mode 100644
index 0000000..de53f7f
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/detail/ebo_storage.hpp
@@ -0,0 +1,42 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_DETAIL_EBO_STORAGE_HPP_INCLUDED
+#define WPI_MEMORY_DETAIL_EBO_STORAGE_HPP_INCLUDED
+
+#include "utility.hpp"
+#include "../config.hpp"
+
+namespace wpi
+{
+    namespace memory
+    {
+        namespace detail
+        {
+            template <int Tag, typename T>
+            class ebo_storage : T
+            {
+            protected:
+                ebo_storage(const T& t) : T(t) {}
+
+                ebo_storage(T&& t) noexcept(std::is_nothrow_move_constructible<T>::value)
+                : T(detail::move(t))
+                {
+                }
+
+                T& get() noexcept
+                {
+                    return *this;
+                }
+
+                const T& get() const noexcept
+                {
+                    return *this;
+                }
+            };
+        } // namespace detail
+    }     // namespace memory
+} // namespace wpi
+
+#endif // WPI_MEMORY_DETAIL_EBO_STORAGE_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/detail/free_list.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/detail/free_list.hpp
new file mode 100644
index 0000000..612706d
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/detail/free_list.hpp
@@ -0,0 +1,228 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_DETAILL_FREE_LIST_HPP_INCLUDED
+#define WPI_MEMORY_DETAILL_FREE_LIST_HPP_INCLUDED
+
+#include <cstddef>
+#include <cstdint>
+
+#include "align.hpp"
+#include "utility.hpp"
+#include "../config.hpp"
+
+namespace wpi
+{
+    namespace memory
+    {
+        namespace detail
+        {
+            // stores free blocks for a memory pool
+            // memory blocks are fragmented and stored in a list
+            // debug: fills memory and uses a bigger node_size for fence memory
+            class free_memory_list
+            {
+            public:
+                // minimum element size
+                static constexpr auto min_element_size = sizeof(char*);
+                // alignment
+                static constexpr auto min_element_alignment = alignof(char*);
+
+                // minimal size of the block that needs to be inserted
+                static constexpr std::size_t min_block_size(std::size_t node_size,
+                                                            std::size_t number_of_nodes)
+                {
+                    return (node_size < min_element_size ? min_element_size : node_size)
+                           * number_of_nodes;
+                }
+
+                //=== constructor ===//
+                free_memory_list(std::size_t node_size) noexcept;
+
+                // calls other constructor plus insert
+                free_memory_list(std::size_t node_size, void* mem, std::size_t size) noexcept;
+
+                free_memory_list(free_memory_list&& other) noexcept;
+                ~free_memory_list() noexcept = default;
+
+                free_memory_list& operator=(free_memory_list&& other) noexcept;
+
+                friend void swap(free_memory_list& a, free_memory_list& b) noexcept;
+
+                //=== insert/allocation/deallocation ===//
+                // inserts a new memory block, by splitting it up and setting the links
+                // does not own memory!
+                // mem must be aligned for alignment()
+                // pre: size != 0
+                void insert(void* mem, std::size_t size) noexcept;
+
+                // returns the usable size
+                // i.e. how many memory will be actually inserted and usable on a call to insert()
+                std::size_t usable_size(std::size_t size) const noexcept
+                {
+                    // Round down to next multiple of node size.
+                    return (size / node_size_) * node_size_;
+                }
+
+                // returns a single block from the list
+                // pre: !empty()
+                void* allocate() noexcept;
+
+                // returns a memory block big enough for n bytes
+                // might fail even if capacity is sufficient
+                void* allocate(std::size_t n) noexcept;
+
+                // deallocates a single block
+                void deallocate(void* ptr) noexcept;
+
+                // deallocates multiple blocks with n bytes total
+                void deallocate(void* ptr, std::size_t n) noexcept;
+
+                //=== getter ===//
+                std::size_t node_size() const noexcept
+                {
+                    return node_size_;
+                }
+
+                // alignment of all nodes
+                std::size_t alignment() const noexcept;
+
+                // number of nodes remaining
+                std::size_t capacity() const noexcept
+                {
+                    return capacity_;
+                }
+
+                bool empty() const noexcept
+                {
+                    return first_ == nullptr;
+                }
+
+            private:
+                void insert_impl(void* mem, std::size_t size) noexcept;
+
+                char*       first_;
+                std::size_t node_size_, capacity_;
+            };
+
+            void swap(free_memory_list& a, free_memory_list& b) noexcept;
+
+            // same as above but keeps the nodes ordered
+            // this allows array allocations, that is, consecutive nodes
+            // debug: fills memory and uses a bigger node_size for fence memory
+            class ordered_free_memory_list
+            {
+            public:
+                // minimum element size
+                static constexpr auto min_element_size = sizeof(char*);
+                // alignment
+                static constexpr auto min_element_alignment = alignof(char*);
+
+                // minimal size of the block that needs to be inserted
+                static constexpr std::size_t min_block_size(std::size_t node_size,
+                                                            std::size_t number_of_nodes)
+                {
+                    return (node_size < min_element_size ? min_element_size : node_size)
+                           * number_of_nodes;
+                }
+
+                //=== constructor ===//
+                ordered_free_memory_list(std::size_t node_size) noexcept;
+
+                ordered_free_memory_list(std::size_t node_size, void* mem,
+                                         std::size_t size) noexcept
+                : ordered_free_memory_list(node_size)
+                {
+                    insert(mem, size);
+                }
+
+                ordered_free_memory_list(ordered_free_memory_list&& other) noexcept;
+
+                ~ordered_free_memory_list() noexcept = default;
+
+                ordered_free_memory_list& operator=(ordered_free_memory_list&& other) noexcept
+                {
+                    ordered_free_memory_list tmp(detail::move(other));
+                    swap(*this, tmp);
+                    return *this;
+                }
+
+                friend void swap(ordered_free_memory_list& a, ordered_free_memory_list& b) noexcept;
+
+                //=== insert/allocation/deallocation ===//
+                // inserts a new memory block, by splitting it up and setting the links
+                // does not own memory!
+                // mem must be aligned for alignment()
+                // pre: size != 0
+                void insert(void* mem, std::size_t size) noexcept;
+
+                // returns the usable size
+                // i.e. how many memory will be actually inserted and usable on a call to insert()
+                std::size_t usable_size(std::size_t size) const noexcept
+                {
+                    // Round down to next multiple of node size.
+                    return (size / node_size_) * node_size_;
+                }
+
+                // returns a single block from the list
+                // pre: !empty()
+                void* allocate() noexcept;
+
+                // returns a memory block big enough for n bytes (!, not nodes)
+                // might fail even if capacity is sufficient
+                void* allocate(std::size_t n) noexcept;
+
+                // deallocates a single block
+                void deallocate(void* ptr) noexcept;
+
+                // deallocates multiple blocks with n bytes total
+                void deallocate(void* ptr, std::size_t n) noexcept;
+
+                //=== getter ===//
+                std::size_t node_size() const noexcept
+                {
+                    return node_size_;
+                }
+
+                // alignment of all nodes
+                std::size_t alignment() const noexcept;
+
+                // number of nodes remaining
+                std::size_t capacity() const noexcept
+                {
+                    return capacity_;
+                }
+
+                bool empty() const noexcept
+                {
+                    return capacity_ == 0u;
+                }
+
+            private:
+                // returns previous pointer
+                char* insert_impl(void* mem, std::size_t size) noexcept;
+
+                char* begin_node() noexcept;
+                char* end_node() noexcept;
+
+                std::uintptr_t begin_proxy_, end_proxy_;
+                std::size_t    node_size_, capacity_;
+                char *         last_dealloc_, *last_dealloc_prev_;
+            };
+
+            void swap(ordered_free_memory_list& a, ordered_free_memory_list& b) noexcept;
+
+#if WPI_MEMORY_DEBUG_DOUBLE_DEALLOC_CHECK
+            // use ordered version to allow pointer check
+            using node_free_memory_list  = ordered_free_memory_list;
+            using array_free_memory_list = ordered_free_memory_list;
+#else
+            using node_free_memory_list  = free_memory_list;
+            using array_free_memory_list = ordered_free_memory_list;
+#endif
+        } // namespace detail
+    }     // namespace memory
+} // namespace wpi
+
+#endif // WPI_MEMORY_DETAILL_FREE_LIST_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/detail/free_list_array.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/detail/free_list_array.hpp
new file mode 100644
index 0000000..ec57e1e
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/detail/free_list_array.hpp
@@ -0,0 +1,126 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_DETAIL_FREE_LIST_ARRAY_HPP
+#define WPI_MEMORY_DETAIL_FREE_LIST_ARRAY_HPP
+
+#include "align.hpp"
+#include "assert.hpp"
+#include "memory_stack.hpp"
+#include "../config.hpp"
+
+namespace wpi
+{
+    namespace memory
+    {
+        namespace detail
+        {
+            // an array of free_memory_list types
+            // indexed via size, AccessPolicy does necessary conversions
+            // requires trivial destructible FreeList type
+            template <class FreeList, class AccessPolicy>
+            class free_list_array
+            {
+                // not supported on GCC 4.7
+                //static_assert(std::is_trivially_destructible<FreeList>::value,
+                //            "free list must be trivially destructible");
+            public:
+                // creates sufficient elements to support up to given maximum node size
+                // all lists are initially empty
+                // actual number is calculated via policy
+                // memory is taken from fixed_memory_stack, it must be sufficient
+                free_list_array(fixed_memory_stack& stack, const char* end,
+                                std::size_t max_node_size) noexcept
+                : no_elements_(AccessPolicy::index_from_size(max_node_size) - min_size_index + 1)
+                {
+                    array_ = static_cast<FreeList*>(
+                        stack.allocate(end, no_elements_ * sizeof(FreeList), alignof(FreeList)));
+                    WPI_MEMORY_ASSERT_MSG(array_, "insufficient memory for free lists");
+                    for (std::size_t i = 0u; i != no_elements_; ++i)
+                    {
+                        auto node_size = AccessPolicy::size_from_index(i + min_size_index);
+                        ::new (static_cast<void*>(array_ + i)) FreeList(node_size);
+                    }
+                }
+
+                // move constructor, does not actually move the elements, just the pointer
+                free_list_array(free_list_array&& other) noexcept
+                : array_(other.array_), no_elements_(other.no_elements_)
+                {
+                    other.array_       = nullptr;
+                    other.no_elements_ = 0u;
+                }
+
+                // destructor, does nothing, list must be trivially destructible!
+                ~free_list_array() noexcept = default;
+
+                free_list_array& operator=(free_list_array&& other) noexcept
+                {
+                    array_       = other.array_;
+                    no_elements_ = other.no_elements_;
+
+                    other.array_       = nullptr;
+                    other.no_elements_ = 0u;
+                    return *this;
+                }
+
+                // access free list for given size
+                FreeList& get(std::size_t node_size) const noexcept
+                {
+                    auto i = AccessPolicy::index_from_size(node_size);
+                    if (i < min_size_index)
+                        i = min_size_index;
+                    return array_[i - min_size_index];
+                }
+
+                // number of free lists
+                std::size_t size() const noexcept
+                {
+                    return no_elements_;
+                }
+
+                // maximum supported node size
+                std::size_t max_node_size() const noexcept
+                {
+                    return AccessPolicy::size_from_index(no_elements_ + min_size_index - 1);
+                }
+
+            private:
+                static const std::size_t min_size_index;
+
+                FreeList*   array_;
+                std::size_t no_elements_;
+            };
+
+            template <class FL, class AP>
+            const std::size_t free_list_array<FL, AP>::min_size_index =
+                AP::index_from_size(FL::min_element_size);
+
+            // AccessPolicy that maps size to indices 1:1
+            // creates a free list for each size!
+            struct identity_access_policy
+            {
+                static std::size_t index_from_size(std::size_t size) noexcept
+                {
+                    return size;
+                }
+
+                static std::size_t size_from_index(std::size_t index) noexcept
+                {
+                    return index;
+                }
+            };
+
+            // AccessPolicy that maps sizes to the integral log2
+            // this creates more nodes and never wastes more than half the size
+            struct log2_access_policy
+            {
+                static std::size_t index_from_size(std::size_t size) noexcept;
+                static std::size_t size_from_index(std::size_t index) noexcept;
+            };
+        } // namespace detail
+    }     // namespace memory
+} // namespace wpi
+
+#endif //WPI_MEMORY_DETAIL_FREE_LIST_ARRAY_HPP
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/detail/ilog2.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/detail/ilog2.hpp
new file mode 100644
index 0000000..5cf125a
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/detail/ilog2.hpp
@@ -0,0 +1,69 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_DETAIL_ILOG2_HPP_INCLUDED
+#define WPI_MEMORY_DETAIL_ILOG2_HPP_INCLUDED
+
+#include <climits>
+#include <cstdint>
+
+#include "../config.hpp"
+
+namespace wpi
+{
+    namespace memory
+    {
+        namespace detail
+        {
+            // undefined for 0
+            template <typename UInt>
+            constexpr bool is_power_of_two(UInt x)
+            {
+                return (x & (x - 1)) == 0;
+            }
+
+            inline std::size_t ilog2_base(std::uint64_t x)
+            {
+#if defined(__GNUC__)
+                unsigned long long value = x;
+                return sizeof(value) * CHAR_BIT - static_cast<unsigned>(__builtin_clzll(value));
+#else
+                // Adapted from https://stackoverflow.com/a/40943402
+                std::size_t clz = 64;
+                std::size_t c   = 32;
+                do
+                {
+                    auto tmp = x >> c;
+                    if (tmp != 0)
+                    {
+                        clz -= c;
+                        x = tmp;
+                    }
+                    c = c >> 1;
+                } while (c != 0);
+                clz -= x ? 1 : 0;
+
+                return 64 - clz;
+#endif
+            }
+
+            // ilog2() implementation, cuts part after the comma
+            // e.g. 1 -> 0, 2 -> 1, 3 -> 1, 4 -> 2, 5 -> 2
+            inline std::size_t ilog2(std::uint64_t x)
+            {
+                return ilog2_base(x) - 1;
+            }
+
+            // ceiling ilog2() implementation, adds one if part after comma
+            // e.g. 1 -> 0, 2 -> 1, 3 -> 2, 4 -> 2, 5 -> 3
+            inline std::size_t ilog2_ceil(std::uint64_t x)
+            {
+                // only subtract one if power of two
+                return ilog2_base(x) - std::size_t(is_power_of_two(x));
+            }
+        } // namespace detail
+    }     // namespace memory
+} // namespace wpi
+
+#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/detail/lowlevel_allocator.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/detail/lowlevel_allocator.hpp
new file mode 100644
index 0000000..2ac45a5
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/detail/lowlevel_allocator.hpp
@@ -0,0 +1,86 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_DETAIL_LOWLEVEL_ALLOCATOR_HPP_INCLUDED
+#define WPI_MEMORY_DETAIL_LOWLEVEL_ALLOCATOR_HPP_INCLUDED
+
+#include <type_traits>
+
+#include "../config.hpp"
+#include "../error.hpp"
+#include "align.hpp"
+#include "debug_helpers.hpp"
+#include "assert.hpp"
+
+namespace wpi
+{
+    namespace memory
+    {
+        namespace detail
+        {
+            template <class Functor>
+            struct lowlevel_allocator_leak_handler
+            {
+                void operator()(std::ptrdiff_t amount)
+                {
+                    debug_handle_memory_leak(Functor::info(), amount);
+                }
+            };
+
+            // Functor controls low-level allocation:
+            // static allocator_info info()
+            // static void* allocate(std::size_t size, std::size_t alignment);
+            // static void deallocate(void *memory, std::size_t size, std::size_t alignment);
+            // static std::size_t max_node_size();
+            template <class Functor>
+            class lowlevel_allocator : global_leak_checker<lowlevel_allocator_leak_handler<Functor>>
+            {
+            public:
+                using is_stateful = std::false_type;
+
+                lowlevel_allocator() noexcept {}
+                lowlevel_allocator(lowlevel_allocator&&) noexcept {}
+                ~lowlevel_allocator() noexcept {}
+
+                lowlevel_allocator& operator=(lowlevel_allocator&&) noexcept
+                {
+                    return *this;
+                }
+
+                void* allocate_node(std::size_t size, std::size_t alignment)
+                {
+                    auto actual_size = size + (debug_fence_size ? 2 * max_alignment : 0u);
+
+                    auto memory = Functor::allocate(actual_size, alignment);
+                    if (!memory)
+                        WPI_THROW(out_of_memory(Functor::info(), actual_size));
+
+                    this->on_allocate(actual_size);
+
+                    return debug_fill_new(memory, size, max_alignment);
+                }
+
+                void deallocate_node(void* node, std::size_t size, std::size_t alignment) noexcept
+                {
+                    auto actual_size = size + (debug_fence_size ? 2 * max_alignment : 0u);
+
+                    auto memory = debug_fill_free(node, size, max_alignment);
+                    Functor::deallocate(memory, actual_size, alignment);
+
+                    this->on_deallocate(actual_size);
+                }
+
+                std::size_t max_node_size() const noexcept
+                {
+                    return Functor::max_node_size();
+                }
+            };
+
+#define WPI_MEMORY_LL_ALLOCATOR_LEAK_CHECKER(functor, var_name)                              \
+    WPI_MEMORY_GLOBAL_LEAK_CHECKER(lowlevel_allocator_leak_handler<functor>, var_name)
+        } // namespace detail
+    }     // namespace memory
+} // namespace wpi
+
+#endif // WPI_MEMORY_DETAIL_LOWLEVEL_ALLOCATOR_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/detail/memory_stack.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/detail/memory_stack.hpp
new file mode 100644
index 0000000..e49d480
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/detail/memory_stack.hpp
@@ -0,0 +1,120 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_DETAIL_MEMORY_STACK_HPP_INCLUDED
+#define WPI_MEMORY_DETAIL_MEMORY_STACK_HPP_INCLUDED
+
+#include <cstddef>
+
+#include "../config.hpp"
+#include "align.hpp"
+#include "debug_helpers.hpp"
+#include "../debugging.hpp"
+
+namespace wpi
+{
+    namespace memory
+    {
+        namespace detail
+        {
+            // simple memory stack implementation that does not support growing
+            class fixed_memory_stack
+            {
+            public:
+                fixed_memory_stack() noexcept : fixed_memory_stack(nullptr) {}
+
+                // gives it the current pointer, the end pointer must be maintained seperataly
+                explicit fixed_memory_stack(void* memory) noexcept
+                : cur_(static_cast<char*>(memory))
+                {
+                }
+
+                fixed_memory_stack(fixed_memory_stack&& other) noexcept : cur_(other.cur_)
+                {
+                    other.cur_ = nullptr;
+                }
+
+                ~fixed_memory_stack() noexcept = default;
+
+                fixed_memory_stack& operator=(fixed_memory_stack&& other) noexcept
+                {
+                    cur_       = other.cur_;
+                    other.cur_ = nullptr;
+                    return *this;
+                }
+
+                // bumps the top pointer without filling it
+                void bump(std::size_t offset) noexcept
+                {
+                    cur_ += offset;
+                }
+
+                // bumps the top pointer by offset and fills
+                void bump(std::size_t offset, debug_magic m) noexcept
+                {
+                    detail::debug_fill(cur_, offset, m);
+                    bump(offset);
+                }
+
+                // same as bump(offset, m) but returns old value
+                void* bump_return(std::size_t offset,
+                                  debug_magic m = debug_magic::new_memory) noexcept
+                {
+                    auto memory = cur_;
+                    detail::debug_fill(memory, offset, m);
+                    cur_ += offset;
+                    return memory;
+                }
+
+                // allocates memory by advancing the stack, returns nullptr if insufficient
+                // debug: mark memory as new_memory, put fence in front and back
+                void* allocate(const char* end, std::size_t size, std::size_t alignment,
+                               std::size_t fence_size = debug_fence_size) noexcept
+                {
+                    if (cur_ == nullptr)
+                        return nullptr;
+
+                    auto remaining = std::size_t(end - cur_);
+                    auto offset    = align_offset(cur_ + fence_size, alignment);
+                    if (fence_size + offset + size + fence_size > remaining)
+                        return nullptr;
+
+                    return allocate_unchecked(size, offset, fence_size);
+                }
+
+                // same as allocate() but does not check the size
+                // note: pass it the align OFFSET, not the alignment
+                void* allocate_unchecked(std::size_t size, std::size_t align_offset,
+                                         std::size_t fence_size = debug_fence_size) noexcept
+                {
+                    bump(fence_size, debug_magic::fence_memory);
+                    bump(align_offset, debug_magic::alignment_memory);
+                    auto mem = bump_return(size);
+                    bump(fence_size, debug_magic::fence_memory);
+                    return mem;
+                }
+
+                // unwindws the stack to a certain older position
+                // debug: marks memory from new top to old top as freed
+                // doesn't check for invalid pointer
+                void unwind(char* top) noexcept
+                {
+                    debug_fill(top, std::size_t(cur_ - top), debug_magic::freed_memory);
+                    cur_ = top;
+                }
+
+                // returns the current top
+                char* top() const noexcept
+                {
+                    return cur_;
+                }
+
+            private:
+                char* cur_;
+            };
+        } // namespace detail
+    }     // namespace memory
+} // namespace wpi
+
+#endif // WPI_MEMORY_DETAIL_MEMORY_STACK_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/detail/small_free_list.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/detail/small_free_list.hpp
new file mode 100644
index 0000000..682417d
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/detail/small_free_list.hpp
@@ -0,0 +1,164 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_DETAIL_SMALL_FREE_LIST_HPP_INCLUDED
+#define WPI_MEMORY_DETAIL_SMALL_FREE_LIST_HPP_INCLUDED
+
+#include <cstddef>
+#include <climits>
+
+#include "../config.hpp"
+#include "utility.hpp"
+#include "align.hpp"
+
+namespace wpi
+{
+    namespace memory
+    {
+        namespace detail
+        {
+            struct chunk_base
+            {
+                chunk_base* prev = this;
+                chunk_base* next = this;
+
+                unsigned char first_free = 0; // first free node for the linked list
+                unsigned char capacity   = 0; // total number of free nodes available
+                unsigned char no_nodes   = 0; // total number of nodes in memory
+
+                chunk_base() noexcept = default;
+
+                chunk_base(unsigned char no) noexcept : capacity(no), no_nodes(no) {}
+            };
+
+            constexpr std::size_t chunk_memory_offset =
+                sizeof(chunk_base) % detail::max_alignment == 0 ?
+                    sizeof(chunk_base) :
+                    (sizeof(chunk_base) / detail::max_alignment + 1) * detail::max_alignment;
+            constexpr std::size_t chunk_max_nodes = UCHAR_MAX;
+
+            struct chunk;
+
+            // the same as free_memory_list but optimized for small node sizes
+            // it is slower and does not support arrays
+            // but has very small overhead
+            // debug: allocate() and deallocate() mark memory as new and freed, respectively
+            // node_size is increased via two times fence size and fence is put in front and after
+            class small_free_memory_list
+            {
+                static constexpr std::size_t chunk_count(std::size_t number_of_nodes)
+                {
+                    return number_of_nodes / chunk_max_nodes
+                           + (number_of_nodes % chunk_max_nodes == 0 ? 0 : 1);
+                }
+
+            public:
+                // minimum element size
+                static constexpr std::size_t min_element_size = 1;
+                // alignment
+                static constexpr std::size_t min_element_alignment = 1;
+
+                // minimal size of the block that needs to be inserted
+                static constexpr std::size_t min_block_size(std::size_t node_size,
+                                                            std::size_t number_of_nodes)
+                {
+                    return chunk_count(number_of_nodes)
+                           * (chunk_memory_offset + chunk_max_nodes * node_size);
+                }
+
+                //=== constructor ===//
+                small_free_memory_list(std::size_t node_size) noexcept;
+
+                // does not own memory!
+                small_free_memory_list(std::size_t node_size, void* mem, std::size_t size) noexcept;
+
+                small_free_memory_list(small_free_memory_list&& other) noexcept;
+
+                ~small_free_memory_list() noexcept = default;
+
+                small_free_memory_list& operator=(small_free_memory_list&& other) noexcept
+                {
+                    small_free_memory_list tmp(detail::move(other));
+                    swap(*this, tmp);
+                    return *this;
+                }
+
+                friend void swap(small_free_memory_list& a, small_free_memory_list& b) noexcept;
+
+                //=== insert/alloc/dealloc ===//
+                // inserts new memory of given size into the free list
+                // mem must be aligned for maximum alignment
+                void insert(void* mem, std::size_t size) noexcept;
+
+                // returns the usable size
+                // i.e. how many memory will be actually inserted and usable on a call to insert()
+                std::size_t usable_size(std::size_t size) const noexcept;
+
+                // allocates a node big enough for the node size
+                // pre: !empty()
+                void* allocate() noexcept;
+
+                // always returns nullptr, because array allocations are not supported
+                void* allocate(std::size_t) noexcept
+                {
+                    return nullptr;
+                }
+
+                // deallocates the node previously allocated via allocate()
+                void deallocate(void* node) noexcept;
+
+                // forwards to insert()
+                void deallocate(void* mem, std::size_t size) noexcept
+                {
+                    insert(mem, size);
+                }
+
+                // hint for allocate() to be prepared to allocate n nodes
+                // it searches for a chunk that has n nodes free
+                // returns false, if there is none like that
+                // never fails for n == 1 if not empty()
+                // pre: capacity() >= n * node_size()
+                bool find_chunk(std::size_t n) noexcept
+                {
+                    return find_chunk_impl(n) != nullptr;
+                }
+
+                //=== getter ===//
+                std::size_t node_size() const noexcept
+                {
+                    return node_size_;
+                }
+
+                // the alignment of all nodes
+                std::size_t alignment() const noexcept;
+
+                // number of nodes remaining
+                std::size_t capacity() const noexcept
+                {
+                    return capacity_;
+                }
+
+                bool empty() const noexcept
+                {
+                    return capacity_ == 0u;
+                }
+
+            private:
+                chunk* find_chunk_impl(std::size_t n = 1) noexcept;
+                chunk* find_chunk_impl(unsigned char* node, chunk_base* first,
+                                       chunk_base* last) noexcept;
+                chunk* find_chunk_impl(unsigned char* node) noexcept;
+
+                chunk_base  base_;
+                std::size_t node_size_, capacity_;
+                chunk_base *alloc_chunk_, *dealloc_chunk_;
+            };
+
+            // for some reason, this is required in order to define it
+            void swap(small_free_memory_list& a, small_free_memory_list& b) noexcept;
+        } // namespace detail
+    }     // namespace memory
+} // namespace wpi
+
+#endif // WPI_MEMORY_DETAIL_SMALL_FREE_LIST_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/detail/utility.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/detail/utility.hpp
new file mode 100644
index 0000000..c746fa2
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/detail/utility.hpp
@@ -0,0 +1,118 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_DETAIL_UTILITY_HPP
+#define WPI_MEMORY_DETAIL_UTILITY_HPP
+
+// implementation of some functions from <utility> to prevent dependencies on it
+
+#include <type_traits>
+
+#include "../config.hpp"
+
+#if WPI_HOSTED_IMPLEMENTATION
+#include <utility>
+#endif
+
+namespace wpi
+{
+    namespace memory
+    {
+        namespace detail
+        {
+            // move - taken from http://stackoverflow.com/a/7518365
+            template <typename T>
+            typename std::remove_reference<T>::type&& move(T&& arg) noexcept
+            {
+                return static_cast<typename std::remove_reference<T>::type&&>(arg);
+            }
+            // forward - taken from http://stackoverflow.com/a/27501759
+            template <class T>
+            T&& forward(typename std::remove_reference<T>::type& t) noexcept
+            {
+                return static_cast<T&&>(t);
+            }
+            template <class T>
+            T&& forward(typename std::remove_reference<T>::type&& t) noexcept
+            {
+                static_assert(!std::is_lvalue_reference<T>::value,
+                              "Can not forward an rvalue as an lvalue.");
+                return static_cast<T&&>(t);
+            }
+
+            namespace swap_
+            {
+#if WPI_HOSTED_IMPLEMENTATION
+                using std::swap;
+#else
+                template <typename T>
+                void swap(T& a, T& b)
+                {
+                    T tmp = move(a);
+                    a     = move(b);
+                    b     = move(tmp);
+                }
+#endif
+            } // namespace swap_
+
+            // ADL aware swap
+            template <typename T>
+            void adl_swap(T& a, T& b) noexcept
+            {
+                using swap_::swap;
+                swap(a, b);
+            }
+
+// fancier syntax for enable_if
+// used as (template) parameter
+// also useful for doxygen
+// define PREDEFINED: WPI_REQUIRES(x):=
+#define WPI_REQUIRES(Expr) typename std::enable_if<(Expr), int>::type = 0
+
+// same as above, but as return type
+// also useful for doxygen:
+// defined PREDEFINED: WPI_REQUIRES_RET(x,r):=r
+#define WPI_REQUIRES_RET(Expr, ...) typename std::enable_if<(Expr), __VA_ARGS__>::type
+
+// fancier syntax for enable_if on non-templated member function
+#define WPI_ENABLE_IF(Expr)                                                                  \
+    template <typename Dummy = std::true_type, WPI_REQUIRES(Dummy::value && (Expr))>
+
+// fancier syntax for general expression SFINAE
+// used as (template) parameter
+// also useful for doxygen:
+// define PREDEFINED: WPI_SFINAE(x):=
+#define WPI_SFINAE(Expr) decltype((Expr), int()) = 0
+
+// avoids code repetition for one-line forwarding functions
+#define WPI_AUTO_RETURN(Expr)                                                                \
+    decltype(Expr)                                                                                 \
+    {                                                                                              \
+        return Expr;                                                                               \
+    }
+
+// same as above, but requires certain type
+#define WPI_AUTO_RETURN_TYPE(Expr, T)                                                        \
+    decltype(Expr)                                                                                 \
+    {                                                                                              \
+        static_assert(std::is_same<decltype(Expr), T>::value,                                      \
+                      #Expr " does not have the return type " #T);                                 \
+        return Expr;                                                                               \
+    }
+
+            // whether or not a type is an instantiation of a template
+            template <template <typename...> class Template, typename T>
+            struct is_instantiation_of : std::false_type
+            {
+            };
+
+            template <template <typename...> class Template, typename... Args>
+            struct is_instantiation_of<Template, Template<Args...>> : std::true_type
+            {
+            };
+        } // namespace detail
+    }     // namespace memory
+} // namespace wpi
+
+#endif //WPI_MEMORY_DETAIL_UTILITY_HPP
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/error.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/error.hpp
new file mode 100644
index 0000000..5ff99cf
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/error.hpp
@@ -0,0 +1,289 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+/// \file
+/// The exception classes.
+
+#ifndef WPI_MEMORY_ERROR_HPP_INCLUDED
+#define WPI_MEMORY_ERROR_HPP_INCLUDED
+
+#include <cstddef>
+#include <new>
+
+#include "config.hpp"
+
+namespace wpi
+{
+    namespace memory
+    {
+        /// Contains information about an allocator.
+        /// It can be used for logging in the various handler functions.
+        /// \ingroup core
+        struct allocator_info
+        {
+            /// The name of the allocator.
+            /// It is a NTBS whose lifetime is not managed by this object,
+            /// it must be stored elsewhere or be a string literal.
+            const char* name;
+
+            /// A pointer representing an allocator.
+            /// It does not necessarily point to the beginning of the allocator object,
+            /// the only guarantee is that different allocator objects result in a different pointer value.
+            /// For stateless allocators it is sometimes \c nullptr.
+            /// \note The pointer must not be cast back to any allocator type.
+            const void* allocator;
+
+            /// \effects Creates it by giving it the name of the allocator and a pointer.
+            constexpr allocator_info(const char* n, const void* alloc) noexcept
+            : name(n), allocator(alloc)
+            {
+            }
+
+            /// @{
+            /// \effects Compares two \ref allocator_info objects, they are equal, if the \ref allocator is the same.
+            /// \returns The result of the comparision.
+            friend constexpr bool operator==(const allocator_info& a,
+                                             const allocator_info& b) noexcept
+            {
+                return a.allocator == b.allocator;
+            }
+
+            friend constexpr bool operator!=(const allocator_info& a,
+                                             const allocator_info& b) noexcept
+            {
+                return a.allocator != b.allocator;
+            }
+            /// @}
+        };
+
+        /// The exception class thrown when a low level allocator runs out of memory.
+        /// It is derived from \c std::bad_alloc.
+        /// This can happen if a low level allocation function like \c std::malloc() runs out of memory.
+        /// Throwing can be prohibited by the handler function.
+        /// \ingroup core
+        class out_of_memory : public std::bad_alloc
+        {
+        public:
+            /// The type of the handler called in the constructor of \ref out_of_memory.
+            /// When an out of memory situation is encountered and the exception class created,
+            /// this handler gets called.
+            /// It is especially useful if exception support is disabled.
+            /// It gets the \ref allocator_info and the amount of memory that was tried to be allocated.
+            /// \requiredbe It can log the error, throw a different exception derived from \c std::bad_alloc or abort the program.
+            /// If it returns, this exception object will be created and thrown.
+            /// \defaultbe On a hosted implementation it logs the error on \c stderr and continues execution,
+            /// leading to this exception being thrown.
+            /// On a freestanding implementation it does nothing.
+            /// \note It is different from \c std::new_handler; it will not be called in a loop trying to allocate memory
+            /// or something like that. Its only job is to report the error.
+            using handler = void (*)(const allocator_info& info, std::size_t amount);
+
+            /// \effects Sets \c h as the new \ref handler in an atomic operation.
+            /// A \c nullptr sets the default \ref handler.
+            /// \returns The previous \ref handler. This is never \c nullptr.
+            static handler set_handler(handler h);
+
+            /// \returns The current \ref handler. This is never \c nullptr.
+            static handler get_handler();
+
+            /// \effects Creates it by passing it the \ref allocator_info and the amount of memory failed to be allocated.
+            /// It also calls the \ref handler to control whether or not it will be thrown.
+            out_of_memory(const allocator_info& info, std::size_t amount);
+
+            /// \returns A static NTBS that describes the error.
+            /// It does not contain any specific information since there is no memory for formatting.
+            const char* what() const noexcept override;
+
+            /// \returns The \ref allocator_info passed to it in the constructor.
+            const allocator_info& allocator() const noexcept
+            {
+                return info_;
+            }
+
+            /// \returns The amount of memory that was tried to be allocated.
+            /// This is the value passed in the constructor.
+            std::size_t failed_allocation_size() const noexcept
+            {
+                return amount_;
+            }
+
+        private:
+            allocator_info info_;
+            std::size_t    amount_;
+        };
+
+        /// A special case of \ref out_of_memory errors
+        /// thrown when a low-level allocator with a fixed size runs out of memory.
+        /// For example, thrown by \ref fixed_block_allocator or \ref static_allocator.<br>
+        /// It is derived from \ref out_of_memory but does not provide its own handler.
+        /// \ingroup core
+        class out_of_fixed_memory : public out_of_memory
+        {
+        public:
+            /// \effects Just forwards to \ref out_of_memory.
+            out_of_fixed_memory(const allocator_info& info, std::size_t amount)
+            : out_of_memory(info, amount)
+            {
+            }
+
+            /// \returns A static NTBS that describes the error.
+            /// It does not contain any specific information since there is no memory for formatting.
+            const char* what() const noexcept override;
+        };
+
+        /// The exception class thrown when an allocation size is bigger than the supported maximum.
+        /// This size is either the node, array or alignment parameter in a call to an allocation function.
+        /// If those exceed the supported maximum returned by \c max_node_size(), \c max_array_size() or \c max_alignment(),
+        /// one of its derived classes will be thrown or this class if in a situation where the type is unknown.
+        /// It is derived from \c std::bad_alloc.
+        /// Throwing can be prohibited by the handler function.
+        /// \note Even if all parameters are less than the maximum, \ref out_of_memory or a similar exception can be thrown,
+        /// because the maximum functions return an upper bound and not the actual supported maximum size,
+        /// since it always depends on fence memory, alignment buffer and the like.
+        /// \note A user should only \c catch for \c bad_allocation_size, not the derived classes.
+        /// \note Most checks will only be done if \ref WPI_MEMORY_CHECK_ALLOCATION_SIZE is \c true.
+        /// \ingroup core
+        class bad_allocation_size : public std::bad_alloc
+        {
+        public:
+            /// The type of the handler called in the constructor of \ref bad_allocation_size.
+            /// When a bad allocation size is detected and the exception object created,
+            /// this handler gets called.
+            /// It is especially useful if exception support is disabled.
+            /// It gets the \ref allocator_info, the size passed to the function and the supported size
+            /// (the latter is still an upper bound).
+            /// \requiredbe It can log the error, throw a different exception derived from \c std::bad_alloc or abort the program.
+            /// If it returns, this exception object will be created and thrown.
+            /// \defaultbe On a hosted implementation it logs the error on \c stderr and continues execution,
+            /// leading to this exception being thrown.
+            /// On a freestanding implementation it does nothing.
+            using handler = void (*)(const allocator_info& info, std::size_t passed,
+                                     std::size_t supported);
+
+            /// \effects Sets \c h as the new \ref handler in an atomic operation.
+            /// A \c nullptr sets the default \ref handler.
+            /// \returns The previous \ref handler. This is never \c nullptr.
+            static handler set_handler(handler h);
+
+            /// \returns The current \ref handler. This is never \c nullptr.
+            static handler get_handler();
+
+            /// \effects Creates it by passing it the \ref allocator_info, the size passed to the allocation function
+            /// and an upper bound on the supported size.
+            /// It also calls the \ref handler to control whether or not it will be thrown.
+            bad_allocation_size(const allocator_info& info, std::size_t passed,
+                                std::size_t supported);
+
+            /// \returns A static NTBS that describes the error.
+            /// It does not contain any specific information since there is no memory for formatting.
+            const char* what() const noexcept override;
+
+            /// \returns The \ref allocator_info passed to it in the constructor.
+            const allocator_info& allocator() const noexcept
+            {
+                return info_;
+            }
+
+            /// \returns The size or alignment value that was passed to the allocation function
+            /// which was too big. This is the same value passed to the constructor.
+            std::size_t passed_value() const noexcept
+            {
+                return passed_;
+            }
+
+            /// \returns An upper bound on the maximum supported size/alignment.
+            /// It is only an upper bound, values below can fail, but values above will always fail.
+            std::size_t supported_value() const noexcept
+            {
+                return supported_;
+            }
+
+        private:
+            allocator_info info_;
+            std::size_t    passed_, supported_;
+        };
+
+        /// The exception class thrown when the node size exceeds the supported maximum,
+        /// i.e. it is bigger than \c max_node_size().
+        /// It is derived from \ref bad_allocation_size but does not override the handler.
+        /// \ingroup core
+        class bad_node_size : public bad_allocation_size
+        {
+        public:
+            /// \effects Just forwards to \ref bad_allocation_size.
+            bad_node_size(const allocator_info& info, std::size_t passed, std::size_t supported)
+            : bad_allocation_size(info, passed, supported)
+            {
+            }
+
+            /// \returns A static NTBS that describes the error.
+            /// It does not contain any specific information since there is no memory for formatting.
+            const char* what() const noexcept override;
+        };
+
+        /// The exception class thrown when the array size exceeds the supported maximum,
+        /// i.e. it is bigger than \c max_array_size().
+        /// It is derived from \ref bad_allocation_size but does not override the handler.
+        /// \ingroup core
+        class bad_array_size : public bad_allocation_size
+        {
+        public:
+            /// \effects Just forwards to \ref bad_allocation_size.
+            bad_array_size(const allocator_info& info, std::size_t passed, std::size_t supported)
+            : bad_allocation_size(info, passed, supported)
+            {
+            }
+
+            /// \returns A static NTBS that describes the error.
+            /// It does not contain any specific information since there is no memory for formatting.
+            const char* what() const noexcept override;
+        };
+
+        /// The exception class thrown when the alignment exceeds the supported maximum,
+        /// i.e. it is bigger than \c max_alignment().
+        /// It is derived from \ref bad_allocation_size but does not override the handler.
+        /// \ingroup core
+        class bad_alignment : public bad_allocation_size
+        {
+        public:
+            /// \effects Just forwards to \ref bad_allocation_size.
+            /// \c passed is <tt>count * size</tt>, \c supported the size in bytes.
+            bad_alignment(const allocator_info& info, std::size_t passed, std::size_t supported)
+            : bad_allocation_size(info, passed, supported)
+            {
+            }
+
+            /// \returns A static NTBS that describes the error.
+            /// It does not contain any specific information since there is no memory for formatting.
+            const char* what() const noexcept override;
+        };
+
+        namespace detail
+        {
+            template <class Ex, typename Func>
+            void check_allocation_size(std::size_t passed, Func f, const allocator_info& info)
+            {
+#if WPI_MEMORY_CHECK_ALLOCATION_SIZE
+                auto supported = f();
+                if (passed > supported)
+                    WPI_THROW(Ex(info, passed, supported));
+#else
+                (void)passed;
+                (void)f;
+                (void)info;
+#endif
+            }
+
+            template <class Ex>
+            void check_allocation_size(std::size_t passed, std::size_t supported,
+                                       const allocator_info& info)
+            {
+                check_allocation_size<Ex>(
+                    passed, [&] { return supported; }, info);
+            }
+        } // namespace detail
+    }     // namespace memory
+} // namespace wpi
+
+#endif // WPI_MEMORY_ERROR_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/fallback_allocator.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/fallback_allocator.hpp
new file mode 100644
index 0000000..3bf530e
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/fallback_allocator.hpp
@@ -0,0 +1,212 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_FALLBACK_ALLOCATOR_HPP_INCLUDED
+#define WPI_MEMORY_FALLBACK_ALLOCATOR_HPP_INCLUDED
+
+/// \file
+//// Class template \ref wpi::memory::fallback_allocator.
+
+#include "detail/ebo_storage.hpp"
+#include "detail/utility.hpp"
+#include "allocator_traits.hpp"
+#include "config.hpp"
+
+namespace wpi
+{
+    namespace memory
+    {
+        /// A \concept{raw_allocator,RawAllocator} with a fallback.
+        /// Allocation first tries `Default`, if it fails,
+        /// it uses `Fallback`.
+        /// \requires `Default` must be a composable \concept{concept_rawallocator,RawAllocator},
+        /// `Fallback` must be a \concept{concept_rawallocator,RawAllocator}.
+        /// \ingroup adapter
+        template <class Default, class Fallback>
+        class fallback_allocator
+        : WPI_EBO(detail::ebo_storage<0, typename allocator_traits<Default>::allocator_type>),
+          WPI_EBO(detail::ebo_storage<1, typename allocator_traits<Fallback>::allocator_type>)
+        {
+            using default_traits             = allocator_traits<Default>;
+            using default_composable_traits  = composable_allocator_traits<Default>;
+            using fallback_traits            = allocator_traits<Fallback>;
+            using fallback_composable_traits = composable_allocator_traits<Fallback>;
+            using fallback_composable =
+                is_composable_allocator<typename fallback_traits::allocator_type>;
+
+        public:
+            using default_allocator_type  = typename allocator_traits<Default>::allocator_type;
+            using fallback_allocator_type = typename allocator_traits<Fallback>::allocator_type;
+
+            using is_stateful =
+                std::integral_constant<bool, default_traits::is_stateful::value
+                                                 || fallback_traits::is_stateful::value>;
+
+            /// \effects Default constructs both allocators.
+            /// \notes This function only participates in overload resolution, if both allocators are not stateful.
+            WPI_ENABLE_IF(!is_stateful::value)
+            fallback_allocator()
+            : detail::ebo_storage<0, default_allocator_type>({}),
+              detail::ebo_storage<1, fallback_allocator_type>({})
+            {
+            }
+
+            /// \effects Constructs the allocator by passing in the two allocators it has.
+            explicit fallback_allocator(default_allocator_type&&  default_alloc,
+                                        fallback_allocator_type&& fallback_alloc = {})
+            : detail::ebo_storage<0, default_allocator_type>(detail::move(default_alloc)),
+              detail::ebo_storage<1, fallback_allocator_type>(detail::move(fallback_alloc))
+            {
+            }
+
+            /// @{
+            /// \effects First calls the compositioning (de)allocation function on the `default_allocator_type`.
+            /// If that fails, uses the non-compositioning function of the `fallback_allocator_type`.
+            void* allocate_node(std::size_t size, std::size_t alignment)
+            {
+                auto ptr = default_composable_traits::try_allocate_node(get_default_allocator(),
+                                                                        size, alignment);
+                if (!ptr)
+                    ptr = fallback_traits::allocate_node(get_fallback_allocator(), size, alignment);
+                return ptr;
+            }
+
+            void* allocate_array(std::size_t count, std::size_t size, std::size_t alignment)
+            {
+                auto ptr = default_composable_traits::try_allocate_array(get_default_allocator(),
+                                                                         count, size, alignment);
+                if (!ptr)
+                    ptr = fallback_traits::allocate_array(get_fallback_allocator(), count, size,
+                                                          alignment);
+                return ptr;
+            }
+
+            void deallocate_node(void* ptr, std::size_t size, std::size_t alignment) noexcept
+            {
+                auto res = default_composable_traits::try_deallocate_node(get_default_allocator(),
+                                                                          ptr, size, alignment);
+                if (!res)
+                    fallback_traits::deallocate_node(get_fallback_allocator(), ptr, size,
+                                                     alignment);
+            }
+
+            void deallocate_array(void* ptr, std::size_t count, std::size_t size,
+                                  std::size_t alignment) noexcept
+            {
+                auto res =
+                    default_composable_traits::try_deallocate_array(get_default_allocator(), ptr,
+                                                                    count, size, alignment);
+                if (!res)
+                    fallback_traits::deallocate_array(get_fallback_allocator(), ptr, count, size,
+                                                      alignment);
+            }
+            /// @}
+
+            /// @{
+            /// \effects First calls the compositioning (de)allocation function on the `default_allocator_type`.
+            /// If that fails, uses the compositioning function of the `fallback_allocator_type`.
+            /// \requires The `fallback_allocator_type` msut be composable.
+            WPI_ENABLE_IF(fallback_composable::value)
+            void* try_allocate_node(std::size_t size, std::size_t alignment) noexcept
+            {
+                auto ptr = default_composable_traits::try_allocate_node(get_default_allocator(),
+                                                                        size, alignment);
+                if (!ptr)
+                    ptr = fallback_composable_traits::try_allocate_node(get_fallback_allocator(),
+                                                                        size, alignment);
+                return ptr;
+            }
+
+            WPI_ENABLE_IF(fallback_composable::value)
+            void* allocate_array(std::size_t count, std::size_t size,
+                                 std::size_t alignment) noexcept
+            {
+                auto ptr = default_composable_traits::try_allocate_array(get_default_allocator(),
+                                                                         count, size, alignment);
+                if (!ptr)
+                    ptr = fallback_composable_traits::try_allocate_array(get_fallback_allocator(),
+                                                                         count, size, alignment);
+                return ptr;
+            }
+
+            WPI_ENABLE_IF(fallback_composable::value)
+            bool try_deallocate_node(void* ptr, std::size_t size, std::size_t alignment) noexcept
+            {
+                auto res = default_composable_traits::try_deallocate_node(get_default_allocator(),
+                                                                          ptr, size, alignment);
+                if (!res)
+                    res = fallback_composable_traits::try_deallocate_node(get_fallback_allocator(),
+                                                                          ptr, size, alignment);
+                return res;
+            }
+
+            WPI_ENABLE_IF(fallback_composable::value)
+            bool try_deallocate_array(void* ptr, std::size_t count, std::size_t size,
+                                      std::size_t alignment) noexcept
+            {
+                auto res =
+                    default_composable_traits::try_deallocate_array(get_default_allocator(), ptr,
+                                                                    count, size, alignment);
+                if (!res)
+                    res = fallback_composable_traits::try_deallocate_array(get_fallback_allocator(),
+                                                                           ptr, count, size,
+                                                                           alignment);
+                return res;
+            }
+            /// @}
+
+            /// @{
+            /// \returns The maximum of the two values from both allocators.
+            std::size_t max_node_size() const
+            {
+                auto def      = default_traits::max_node_size(get_default_allocator());
+                auto fallback = fallback_traits::max_node_size(get_fallback_allocator());
+                return fallback > def ? fallback : def;
+            }
+
+            std::size_t max_array_size() const
+            {
+                auto def      = default_traits::max_array_size(get_default_allocator());
+                auto fallback = fallback_traits::max_array_size(get_fallback_allocator());
+                return fallback > def ? fallback : def;
+            }
+
+            std::size_t max_alignment() const
+            {
+                auto def      = default_traits::max_alignment(get_default_allocator());
+                auto fallback = fallback_traits::max_alignment(get_fallback_allocator());
+                return fallback > def ? fallback : def;
+            }
+            /// @}
+
+            /// @{
+            /// \returns A (`const`) reference to the default allocator.
+            default_allocator_type& get_default_allocator() noexcept
+            {
+                return detail::ebo_storage<0, default_allocator_type>::get();
+            }
+
+            const default_allocator_type& get_default_allocator() const noexcept
+            {
+                return detail::ebo_storage<0, default_allocator_type>::get();
+            }
+            /// @}
+
+            /// @{
+            /// \returns A (`const`) reference to the fallback allocator.
+            fallback_allocator_type& get_fallback_allocator() noexcept
+            {
+                return detail::ebo_storage<1, fallback_allocator_type>::get();
+            }
+
+            const fallback_allocator_type& get_fallback_allocator() const noexcept
+            {
+                return detail::ebo_storage<1, fallback_allocator_type>::get();
+            }
+            /// @}
+        };
+    } // namespace memory
+} // namespace wpi
+
+#endif // WPI_MEMORY_FALLBACK_ALLOCATOR_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/heap_allocator.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/heap_allocator.hpp
new file mode 100644
index 0000000..0724937
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/heap_allocator.hpp
@@ -0,0 +1,83 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_HEAP_ALLOCATOR_HPP_INCLUDED
+#define WPI_MEMORY_HEAP_ALLOCATOR_HPP_INCLUDED
+
+/// \file
+/// Class \ref wpi::memory::heap_allocator and related functions.
+
+#include "detail/lowlevel_allocator.hpp"
+#include "config.hpp"
+
+#if WPI_MEMORY_EXTERN_TEMPLATE
+#include "allocator_traits.hpp"
+#endif
+
+namespace wpi
+{
+    namespace memory
+    {
+        struct allocator_info;
+
+        /// Allocates heap memory.
+        /// This function is used by the \ref heap_allocator to allocate the heap memory.
+        /// It is not defined on a freestanding implementation, a definition must be provided by the library user.
+        /// \requiredbe This function shall return a block of uninitialized memory that is aligned for \c max_align_t and has the given size.
+        /// The size parameter will not be zero.
+        /// It shall return a \c nullptr if no memory is available.
+        /// It must be thread safe.
+        /// \defaultbe On a hosted implementation this function uses OS specific facilities, \c std::malloc is used as fallback.
+        /// \ingroup allocator
+        void* heap_alloc(std::size_t size) noexcept;
+
+        /// Deallocates heap memory.
+        /// This function is used by the \ref heap_allocator to allocate the heap memory.
+        /// It is not defined on a freestanding implementation, a definition must be provided by the library user.
+        /// \requiredbe This function gets a pointer from a previous call to \ref heap_alloc with the same size.
+        /// It shall free the memory.
+        /// The pointer will not be zero.
+        /// It must be thread safe.
+        /// \defaultbe On a hosted implementation this function uses OS specific facilities, \c std::free is used as fallback.
+        /// \ingroup allocator
+        void heap_dealloc(void* ptr, std::size_t size) noexcept;
+
+        namespace detail
+        {
+            struct heap_allocator_impl
+            {
+                static allocator_info info() noexcept;
+
+                static void* allocate(std::size_t size, std::size_t) noexcept
+                {
+                    return heap_alloc(size);
+                }
+
+                static void deallocate(void* ptr, std::size_t size, std::size_t) noexcept
+                {
+                    heap_dealloc(ptr, size);
+                }
+
+                static std::size_t max_node_size() noexcept;
+            };
+
+            WPI_MEMORY_LL_ALLOCATOR_LEAK_CHECKER(heap_allocator_impl,
+                                                       heap_alloator_leak_checker)
+        } // namespace detail
+
+        /// A stateless \concept{concept_rawallocator,RawAllocator} that allocates memory from the heap.
+        /// It uses the two functions \ref heap_alloc and \ref heap_dealloc for the allocation,
+        /// which default to \c std::malloc and \c std::free.
+        /// \ingroup allocator
+        using heap_allocator =
+            WPI_IMPL_DEFINED(detail::lowlevel_allocator<detail::heap_allocator_impl>);
+
+#if WPI_MEMORY_EXTERN_TEMPLATE
+        extern template class detail::lowlevel_allocator<detail::heap_allocator_impl>;
+        extern template class allocator_traits<heap_allocator>;
+#endif
+    } // namespace memory
+} // namespace wpi
+
+#endif // WPI_MEMORY_HEAP_ALLOCATOR_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/iteration_allocator.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/iteration_allocator.hpp
new file mode 100644
index 0000000..d35a927
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/iteration_allocator.hpp
@@ -0,0 +1,305 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_ITERATION_ALLOCATOR_HPP_INCLUDED
+#define WPI_MEMORY_ITERATION_ALLOCATOR_HPP_INCLUDED
+
+/// \file
+/// Class template \ref wpi::memory::iteration_allocator.
+
+#include "detail/debug_helpers.hpp"
+#include "detail/memory_stack.hpp"
+#include "default_allocator.hpp"
+#include "error.hpp"
+#include "memory_arena.hpp"
+
+namespace wpi
+{
+    namespace memory
+    {
+        namespace detail
+        {
+            template <class BlockOrRawAllocator>
+            using iteration_block_allocator =
+                make_block_allocator_t<BlockOrRawAllocator, fixed_block_allocator>;
+        } // namespace detail
+
+        /// A stateful \concept{concept_rawallocator,RawAllocator} that is designed for allocations in a loop.
+        /// It uses `N` stacks for the allocation, one of them is always active.
+        /// Allocation uses the currently active stack.
+        /// Calling \ref iteration_allocator::next_iteration() at the end of the loop,
+        /// will make the next stack active for allocation,
+        /// effectively releasing all of its memory.
+        /// Any memory allocated will thus be usable for `N` iterations of the loop.
+        /// This type of allocator is a generalization of the double frame allocator.
+        /// \ingroup allocator
+        template <std::size_t N, class BlockOrRawAllocator = default_allocator>
+        class iteration_allocator
+        : WPI_EBO(detail::iteration_block_allocator<BlockOrRawAllocator>)
+        {
+        public:
+            using allocator_type = detail::iteration_block_allocator<BlockOrRawAllocator>;
+
+            /// \effects Creates it with a given initial block size and and other constructor arguments for the \concept{concept_blockallocator,BlockAllocator}.
+            /// It will allocate the first (and only) block and evenly divide it on all the stacks it uses.
+            template <typename... Args>
+            explicit iteration_allocator(std::size_t block_size, Args&&... args)
+            : allocator_type(block_size, detail::forward<Args>(args)...), cur_(0u)
+            {
+                block_         = get_allocator().allocate_block();
+                auto cur       = static_cast<char*>(block_.memory);
+                auto size_each = block_.size / N;
+                for (auto i = 0u; i != N; ++i)
+                {
+                    stacks_[i] = detail::fixed_memory_stack(cur);
+                    cur += size_each;
+                }
+            }
+
+            iteration_allocator(iteration_allocator&& other) noexcept
+            : allocator_type(detail::move(other)),
+              block_(other.block_),
+              cur_(detail::move(other.cur_))
+            {
+                for (auto i = 0u; i != N; ++i)
+                    stacks_[i] = detail::move(other.stacks_[i]);
+
+                other.cur_ = N;
+            }
+
+            ~iteration_allocator() noexcept
+            {
+                if (cur_ < N)
+                    get_allocator().deallocate_block(block_);
+            }
+
+            iteration_allocator& operator=(iteration_allocator&& other) noexcept
+            {
+                allocator_type::operator=(detail::move(other));
+                block_                  = other.block_;
+                cur_                    = other.cur_;
+
+                for (auto i = 0u; i != N; ++i)
+                    stacks_[i] = detail::move(other.stacks_[i]);
+
+                other.cur_ = N;
+
+                return *this;
+            }
+
+            /// \effects Allocates a memory block of given size and alignment.
+            /// It simply moves the top marker of the currently active stack.
+            /// \returns A \concept{concept_node,node} with given size and alignment.
+            /// \throws \ref out_of_fixed_memory if the current stack does not have any memory left.
+            /// \requires \c size and \c alignment must be valid.
+            void* allocate(std::size_t size, std::size_t alignment)
+            {
+                auto& stack = stacks_[cur_];
+
+                auto fence  = detail::debug_fence_size;
+                auto offset = detail::align_offset(stack.top() + fence, alignment);
+                if (!stack.top()
+                    || (fence + offset + size + fence > std::size_t(block_end(cur_) - stack.top())))
+                    WPI_THROW(out_of_fixed_memory(info(), size));
+                return stack.allocate_unchecked(size, offset);
+            }
+
+            /// \effects Allocates a memory block of given size and alignment
+            /// similar to \ref allocate().
+            /// \returns A \concept{concept_node,node} with given size and alignment
+            /// or `nullptr` if the current stack does not have any memory left.
+            void* try_allocate(std::size_t size, std::size_t alignment) noexcept
+            {
+                auto& stack = stacks_[cur_];
+                return stack.allocate(block_end(cur_), size, alignment);
+            }
+
+            /// \effects Goes to the next internal stack.
+            /// This will clear the stack whose \ref max_iterations() lifetime has reached,
+            /// and use it for all allocations in this iteration.
+            /// \note This function should be called at the end of the loop.
+            void next_iteration() noexcept
+            {
+                WPI_MEMORY_ASSERT_MSG(cur_ != N, "moved-from allocator");
+                cur_ = (cur_ + 1) % N;
+                stacks_[cur_].unwind(block_start(cur_));
+            }
+
+            /// \returns The number of iteration each allocation will live.
+            /// This is the template parameter `N`.
+            static std::size_t max_iterations() noexcept
+            {
+                return N;
+            }
+
+            /// \returns The index of the current iteration.
+            /// This is modulo \ref max_iterations().
+            std::size_t cur_iteration() const noexcept
+            {
+                return cur_;
+            }
+
+            /// \returns A reference to the \concept{concept_blockallocator,BlockAllocator} used for managing the memory.
+            /// \requires It is undefined behavior to move this allocator out into another object.
+            allocator_type& get_allocator() noexcept
+            {
+                return *this;
+            }
+
+            /// \returns The amount of memory remaining in the stack with the given index.
+            /// This is the number of bytes that are available for allocation.
+            std::size_t capacity_left(std::size_t i) const noexcept
+            {
+                return std::size_t(block_end(i) - stacks_[i].top());
+            }
+
+            /// \returns The amount of memory remaining in the currently active stack.
+            std::size_t capacity_left() const noexcept
+            {
+                return capacity_left(cur_iteration());
+            }
+
+        private:
+            allocator_info info() const noexcept
+            {
+                return {WPI_MEMORY_LOG_PREFIX "::iteration_allocator", this};
+            }
+
+            char* block_start(std::size_t i) const noexcept
+            {
+                WPI_MEMORY_ASSERT_MSG(i <= N, "moved from state");
+                auto ptr = static_cast<char*>(block_.memory);
+                return ptr + (i * block_.size / N);
+            }
+
+            char* block_end(std::size_t i) const noexcept
+            {
+                WPI_MEMORY_ASSERT_MSG(i < N, "moved from state");
+                return block_start(i + 1);
+            }
+
+            detail::fixed_memory_stack stacks_[N];
+            memory_block               block_;
+            std::size_t                cur_;
+
+            friend allocator_traits<iteration_allocator<N, BlockOrRawAllocator>>;
+            friend composable_allocator_traits<iteration_allocator<N, BlockOrRawAllocator>>;
+        };
+
+        /// An alias for \ref iteration_allocator for two iterations.
+        /// \ingroup allocator
+        template <class BlockOrRawAllocator = default_allocator>
+        WPI_ALIAS_TEMPLATE(double_frame_allocator,
+                                 iteration_allocator<2, BlockOrRawAllocator>);
+
+#if WPI_MEMORY_EXTERN_TEMPLATE
+        extern template class iteration_allocator<2>;
+#endif
+
+        /// Specialization of the \ref allocator_traits for \ref iteration_allocator.
+        /// \note It is not allowed to mix calls through the specialization and through the member functions,
+        /// i.e. \ref memory_stack::allocate() and this \c allocate_node().
+        /// \ingroup allocator
+        template <std::size_t N, class BlockAllocator>
+        class allocator_traits<iteration_allocator<N, BlockAllocator>>
+        {
+        public:
+            using allocator_type = iteration_allocator<N, BlockAllocator>;
+            using is_stateful    = std::true_type;
+
+            /// \returns The result of \ref iteration_allocator::allocate().
+            static void* allocate_node(allocator_type& state, std::size_t size,
+                                       std::size_t alignment)
+            {
+                return state.allocate(size, alignment);
+            }
+
+            /// \returns The result of \ref memory_stack::allocate().
+            static void* allocate_array(allocator_type& state, std::size_t count, std::size_t size,
+                                        std::size_t alignment)
+            {
+                return allocate_node(state, count * size, alignment);
+            }
+
+            /// @{
+            /// \effects Does nothing.
+            /// Actual deallocation can only be done via \ref memory_stack::unwind().
+            static void deallocate_node(allocator_type&, void*, std::size_t, std::size_t) noexcept
+            {
+            }
+
+            static void deallocate_array(allocator_type&, void*, std::size_t, std::size_t,
+                                         std::size_t) noexcept
+            {
+            }
+            /// @}
+
+            /// @{
+            /// \returns The maximum size which is \ref iteration_allocator::capacity_left().
+            static std::size_t max_node_size(const allocator_type& state) noexcept
+            {
+                return state.capacity_left();
+            }
+
+            static std::size_t max_array_size(const allocator_type& state) noexcept
+            {
+                return state.capacity_left();
+            }
+            /// @}
+
+            /// \returns The maximum possible value since there is no alignment restriction
+            /// (except indirectly through \ref memory_stack::next_capacity()).
+            static std::size_t max_alignment(const allocator_type&) noexcept
+            {
+                return std::size_t(-1);
+            }
+        };
+
+        /// Specialization of the \ref composable_allocator_traits for \ref iteration_allocator classes.
+        /// \ingroup allocator
+        template <std::size_t N, class BlockAllocator>
+        class composable_allocator_traits<iteration_allocator<N, BlockAllocator>>
+        {
+        public:
+            using allocator_type = iteration_allocator<N, BlockAllocator>;
+
+            /// \returns The result of \ref memory_stack::try_allocate().
+            static void* try_allocate_node(allocator_type& state, std::size_t size,
+                                           std::size_t alignment) noexcept
+            {
+                return state.try_allocate(size, alignment);
+            }
+
+            /// \returns The result of \ref memory_stack::try_allocate().
+            static void* try_allocate_array(allocator_type& state, std::size_t count,
+                                            std::size_t size, std::size_t alignment) noexcept
+            {
+                return state.try_allocate(count * size, alignment);
+            }
+
+            /// @{
+            /// \effects Does nothing.
+            /// \returns Whether the memory will be deallocated by \ref memory_stack::unwind().
+            static bool try_deallocate_node(allocator_type& state, void* ptr, std::size_t,
+                                            std::size_t) noexcept
+            {
+                return state.block_.contains(ptr);
+            }
+
+            static bool try_deallocate_array(allocator_type& state, void* ptr, std::size_t count,
+                                             std::size_t size, std::size_t alignment) noexcept
+            {
+                return try_deallocate_node(state, ptr, count * size, alignment);
+            }
+            /// @}
+        };
+
+#if WPI_MEMORY_EXTERN_TEMPLATE
+        extern template class allocator_traits<iteration_allocator<2>>;
+        extern template class composable_allocator_traits<iteration_allocator<2>>;
+#endif
+    } // namespace memory
+} // namespace wpi
+
+#endif // WPI_MEMORY_ITERATION_ALLOCATOR_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/joint_allocator.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/joint_allocator.hpp
new file mode 100644
index 0000000..db67d46
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/joint_allocator.hpp
@@ -0,0 +1,927 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_JOINT_ALLOCATOR_HPP_INCLUDED
+#define WPI_MEMORY_JOINT_ALLOCATOR_HPP_INCLUDED
+
+/// \file
+/// Class template \ref wpi::memory::joint_ptr, \ref wpi::memory::joint_allocator and related.
+
+#include <initializer_list>
+#include <new>
+
+#include "detail/align.hpp"
+#include "detail/memory_stack.hpp"
+#include "detail/utility.hpp"
+#include "allocator_storage.hpp"
+#include "config.hpp"
+#include "default_allocator.hpp"
+#include "error.hpp"
+
+namespace wpi
+{
+    namespace memory
+    {
+        template <typename T, class RawAllocator>
+        class joint_ptr;
+
+        template <typename T>
+        class joint_type;
+
+        namespace detail
+        {
+            // the stack that allocates the joint memory
+            class joint_stack
+            {
+            public:
+                joint_stack(void* mem, std::size_t cap) noexcept
+                : stack_(static_cast<char*>(mem)), end_(static_cast<char*>(mem) + cap)
+                {
+                }
+
+                void* allocate(std::size_t size, std::size_t alignment) noexcept
+                {
+                    return stack_.allocate(end_, size, alignment, 0u);
+                }
+
+                bool bump(std::size_t offset) noexcept
+                {
+                    if (offset > std::size_t(end_ - stack_.top()))
+                        return false;
+                    stack_.bump(offset);
+                    return true;
+                }
+
+                char* top() noexcept
+                {
+                    return stack_.top();
+                }
+
+                const char* top() const noexcept
+                {
+                    return stack_.top();
+                }
+
+                void unwind(void* ptr) noexcept
+                {
+                    stack_.unwind(static_cast<char*>(ptr));
+                }
+
+                std::size_t capacity(const char* mem) const noexcept
+                {
+                    return std::size_t(end_ - mem);
+                }
+
+                std::size_t capacity_left() const noexcept
+                {
+                    return std::size_t(end_ - top());
+                }
+
+                std::size_t capacity_used(const char* mem) const noexcept
+                {
+                    return std::size_t(top() - mem);
+                }
+
+            private:
+                detail::fixed_memory_stack stack_;
+                char*                      end_;
+            };
+
+            template <typename T>
+            detail::joint_stack& get_stack(joint_type<T>& obj) noexcept;
+
+            template <typename T>
+            const detail::joint_stack& get_stack(const joint_type<T>& obj) noexcept;
+        } // namespace detail
+
+        /// Tag type that can't be created.
+        ///
+        /// It isued by \ref joint_ptr.
+        /// \ingroup allocator
+        class joint
+        {
+            joint(std::size_t cap) noexcept : capacity(cap) {}
+
+            std::size_t capacity;
+
+            template <typename T, class RawAllocator>
+            friend class joint_ptr;
+            template <typename T>
+            friend class joint_type;
+        };
+
+        /// Tag type to make the joint size more explicit.
+        ///
+        /// It is used by \ref joint_ptr.
+        /// \ingroup allocator
+        struct joint_size
+        {
+            std::size_t size;
+
+            explicit joint_size(std::size_t s) noexcept : size(s) {}
+        };
+
+        /// CRTP base class for all objects that want to use joint memory.
+        ///
+        /// This will disable default copy/move operations
+        /// and inserts additional members for the joint memory management.
+        /// \ingroup allocator
+        template <typename T>
+        class joint_type
+        {
+        protected:
+            /// \effects Creates the base class,
+            /// the tag type cannot be created by the user.
+            /// \note This ensures that you cannot create joint types yourself.
+            joint_type(joint j) noexcept;
+
+            joint_type(const joint_type&) = delete;
+            joint_type(joint_type&&)      = delete;
+
+        private:
+            detail::joint_stack stack_;
+
+            template <typename U>
+            friend detail::joint_stack& detail::get_stack(joint_type<U>& obj) noexcept;
+            template <typename U>
+            friend const detail::joint_stack& detail::get_stack(const joint_type<U>& obj) noexcept;
+        };
+
+        namespace detail
+        {
+            template <typename T>
+            detail::joint_stack& get_stack(joint_type<T>& obj) noexcept
+            {
+                return obj.stack_;
+            }
+
+            template <typename T>
+            const detail::joint_stack& get_stack(const joint_type<T>& obj) noexcept
+            {
+                return obj.stack_;
+            }
+
+            template <typename T>
+            char* get_memory(joint_type<T>& obj) noexcept
+            {
+                auto mem = static_cast<void*>(&obj);
+                return static_cast<char*>(mem) + sizeof(T);
+            }
+
+            template <typename T>
+            const char* get_memory(const joint_type<T>& obj) noexcept
+            {
+                auto mem = static_cast<const void*>(&obj);
+                return static_cast<const char*>(mem) + sizeof(T);
+            }
+
+        } // namespace detail
+
+        template <typename T>
+        joint_type<T>::joint_type(joint j) noexcept : stack_(detail::get_memory(*this), j.capacity)
+        {
+            WPI_MEMORY_ASSERT(stack_.top() == detail::get_memory(*this));
+            WPI_MEMORY_ASSERT(stack_.capacity_left() == j.capacity);
+        }
+
+        /// A pointer to an object where all allocations are joint.
+        ///
+        /// It can either own an object or not (be `nullptr`).
+        /// When it owns an object, it points to a memory block.
+        /// This memory block contains both the actual object (of the type `T`)
+        /// and space for allocations of `T`s members.
+        ///
+        /// The type `T` must be derived from \ref joint_type and every constructor must take \ref joint
+        /// as first parameter.
+        /// This prevents that you create joint objects yourself,
+        /// without the additional storage.
+        /// The default copy and move constructors are also deleted,
+        /// you need to write them yourself.
+        ///
+        /// You can only access the object through the pointer,
+        /// use \ref joint_allocator or \ref joint_array as members of `T`,
+        /// to enable the memory sharing.
+        /// If you are using \ref joint_allocator inside STL containers,
+        /// make sure that you do not call their regular copy/move constructors,
+        /// but instead the version where you pass an allocator.
+        ///
+        /// The memory block will be managed by the given \concept{concept_rawallocator,RawAllocator},
+        /// it is stored in an \ref allocator_reference and not owned by the pointer directly.
+        /// \ingroup allocator
+        template <typename T, class RawAllocator>
+        class joint_ptr : WPI_EBO(allocator_reference<RawAllocator>)
+        {
+            static_assert(std::is_base_of<joint_type<T>, T>::value,
+                          "T must be derived of joint_type<T>");
+
+        public:
+            using element_type   = T;
+            using allocator_type = typename allocator_reference<RawAllocator>::allocator_type;
+
+            //=== constructors/destructor/assignment ===//
+            /// @{
+            /// \effects Creates it with a \concept{concept_rawallocator,RawAllocator}, but does not own a new object.
+            explicit joint_ptr(allocator_type& alloc) noexcept
+            : allocator_reference<RawAllocator>(alloc), ptr_(nullptr)
+            {
+            }
+
+            explicit joint_ptr(const allocator_type& alloc) noexcept
+            : allocator_reference<RawAllocator>(alloc), ptr_(nullptr)
+            {
+            }
+            /// @}
+
+            /// @{
+            /// \effects Reserves memory for the object and the additional size,
+            /// and creates the object by forwarding the arguments to its constructor.
+            /// The \concept{concept_rawallocator,RawAllocator} will be used for the allocation.
+            template <typename... Args>
+            joint_ptr(allocator_type& alloc, joint_size additional_size, Args&&... args)
+            : joint_ptr(alloc)
+            {
+                create(additional_size.size, detail::forward<Args>(args)...);
+            }
+
+            template <typename... Args>
+            joint_ptr(const allocator_type& alloc, joint_size additional_size, Args&&... args)
+            : joint_ptr(alloc)
+            {
+                create(additional_size.size, detail::forward<Args>(args)...);
+            }
+            /// @}
+
+            /// \effects Move-constructs the pointer.
+            /// Ownership will be transferred from `other` to the new object.
+            joint_ptr(joint_ptr&& other) noexcept
+            : allocator_reference<RawAllocator>(detail::move(other)), ptr_(other.ptr_)
+            {
+                other.ptr_ = nullptr;
+            }
+
+            /// \effects Destroys the object and deallocates its storage.
+            ~joint_ptr() noexcept
+            {
+                reset();
+            }
+
+            /// \effects Move-assings the pointer.
+            /// The previously owned object will be destroyed,
+            /// and ownership of `other` transferred.
+            joint_ptr& operator=(joint_ptr&& other) noexcept
+            {
+                joint_ptr tmp(detail::move(other));
+                swap(*this, tmp);
+                return *this;
+            }
+
+            /// \effects Same as `reset()`.
+            joint_ptr& operator=(std::nullptr_t) noexcept
+            {
+                reset();
+                return *this;
+            }
+
+            /// \effects Swaps to pointers and their ownership and allocator.
+            friend void swap(joint_ptr& a, joint_ptr& b) noexcept
+            {
+                detail::adl_swap(static_cast<allocator_reference<RawAllocator>&>(a),
+                                 static_cast<allocator_reference<RawAllocator>&>(b));
+                detail::adl_swap(a.ptr_, b.ptr_);
+            }
+
+            //=== modifiers ===//
+            /// \effects Destroys the object it refers to,
+            /// if there is any.
+            void reset() noexcept
+            {
+                if (ptr_)
+                {
+                    (**this).~element_type();
+                    this->deallocate_node(ptr_,
+                                          sizeof(element_type)
+                                              + detail::get_stack(*ptr_).capacity(
+                                                  detail::get_memory(*ptr_)),
+                                          alignof(element_type));
+                    ptr_ = nullptr;
+                }
+            }
+
+            //=== accessors ===//
+            /// \returns `true` if the pointer does own an object,
+            /// `false` otherwise.
+            explicit operator bool() const noexcept
+            {
+                return ptr_ != nullptr;
+            }
+
+            /// \returns A reference to the object it owns.
+            /// \requires The pointer must own an object,
+            /// i.e. `operator bool()` must return `true`.
+            element_type& operator*() const noexcept
+            {
+                WPI_MEMORY_ASSERT(ptr_);
+                return *get();
+            }
+
+            /// \returns A pointer to the object it owns.
+            /// \requires The pointer must own an object,
+            /// i.e. `operator bool()` must return `true`.
+            element_type* operator->() const noexcept
+            {
+                WPI_MEMORY_ASSERT(ptr_);
+                return get();
+            }
+
+            /// \returns A pointer to the object it owns
+            /// or `nullptr`, if it does not own any object.
+            element_type* get() const noexcept
+            {
+                return static_cast<element_type*>(ptr_);
+            }
+
+            /// \returns A reference to the allocator it will use for the deallocation.
+            auto get_allocator() const noexcept
+                -> decltype(std::declval<allocator_reference<allocator_type>>().get_allocator())
+            {
+                return this->allocator_reference<allocator_type>::get_allocator();
+            }
+
+        private:
+            template <typename... Args>
+            void create(std::size_t additional_size, Args&&... args)
+            {
+                auto mem = this->allocate_node(sizeof(element_type) + additional_size,
+                                               alignof(element_type));
+
+                element_type* ptr = nullptr;
+#if WPI_HAS_EXCEPTION_SUPPORT
+                try
+                {
+                    ptr = ::new (mem)
+                        element_type(joint(additional_size), detail::forward<Args>(args)...);
+                }
+                catch (...)
+                {
+                    this->deallocate_node(mem, sizeof(element_type) + additional_size,
+                                          alignof(element_type));
+                    throw;
+                }
+#else
+                ptr = ::new (mem)
+                    element_type(joint(additional_size), detail::forward<Args>(args)...);
+#endif
+                ptr_ = ptr;
+            }
+
+            joint_type<T>* ptr_;
+
+            friend class joint_allocator;
+        };
+
+        /// @{
+        /// \returns `!ptr`,
+        /// i.e. if `ptr` does not own anything.
+        /// \relates joint_ptr
+        template <typename T, class RawAllocator>
+        bool operator==(const joint_ptr<T, RawAllocator>& ptr, std::nullptr_t)
+        {
+            return !ptr;
+        }
+
+        template <typename T, class RawAllocator>
+        bool operator==(std::nullptr_t, const joint_ptr<T, RawAllocator>& ptr)
+        {
+            return ptr == nullptr;
+        }
+        /// @}
+
+        /// @{
+        /// \returns `ptr.get() == p`,
+        /// i.e. if `ptr` ownws the object referred to by `p`.
+        /// \relates joint_ptr
+        template <typename T, class RawAllocator>
+        bool operator==(const joint_ptr<T, RawAllocator>& ptr, T* p)
+        {
+            return ptr.get() == p;
+        }
+
+        template <typename T, class RawAllocator>
+        bool operator==(T* p, const joint_ptr<T, RawAllocator>& ptr)
+        {
+            return ptr == p;
+        }
+        /// @}
+
+        /// @{
+        /// \returns `!(ptr == nullptr)`,
+        /// i.e. if `ptr` does own something.
+        /// \relates joint_ptr
+        template <typename T, class RawAllocator>
+        bool operator!=(const joint_ptr<T, RawAllocator>& ptr, std::nullptr_t)
+        {
+            return !(ptr == nullptr);
+        }
+
+        template <typename T, class RawAllocator>
+        bool operator!=(std::nullptr_t, const joint_ptr<T, RawAllocator>& ptr)
+        {
+            return ptr != nullptr;
+        }
+        /// @}
+
+        /// @{
+        /// \returns `!(ptr == p)`,
+        /// i.e. if `ptr` does not ownw the object referred to by `p`.
+        /// \relates joint_ptr
+        template <typename T, class RawAllocator>
+        bool operator!=(const joint_ptr<T, RawAllocator>& ptr, T* p)
+        {
+            return !(ptr == p);
+        }
+
+        template <typename T, class RawAllocator>
+        bool operator!=(T* p, const joint_ptr<T, RawAllocator>& ptr)
+        {
+            return ptr != p;
+        }
+        /// @}
+
+        /// @{
+        /// \returns A new \ref joint_ptr as if created with the same arguments passed to the constructor.
+        /// \relatesalso joint_ptr
+        /// \ingroup allocator
+        template <typename T, class RawAllocator, typename... Args>
+        auto allocate_joint(RawAllocator& alloc, joint_size additional_size, Args&&... args)
+            -> joint_ptr<T, RawAllocator>
+        {
+            return joint_ptr<T, RawAllocator>(alloc, additional_size,
+                                              detail::forward<Args>(args)...);
+        }
+
+        template <typename T, class RawAllocator, typename... Args>
+        auto allocate_joint(const RawAllocator& alloc, joint_size additional_size, Args&&... args)
+            -> joint_ptr<T, RawAllocator>
+        {
+            return joint_ptr<T, RawAllocator>(alloc, additional_size,
+                                              detail::forward<Args>(args)...);
+        }
+        /// @}
+
+        /// @{
+        /// \returns A new \ref joint_ptr that points to a copy of `joint`.
+        /// It will allocate as much memory as needed and forward to the copy constructor.
+        /// \ingroup allocator
+        template <class RawAllocator, typename T>
+        auto clone_joint(RawAllocator& alloc, const joint_type<T>& joint)
+            -> joint_ptr<T, RawAllocator>
+        {
+            return joint_ptr<T, RawAllocator>(alloc,
+                                              joint_size(detail::get_stack(joint).capacity_used(
+                                                  detail::get_memory(joint))),
+                                              static_cast<const T&>(joint));
+        }
+
+        template <class RawAllocator, typename T>
+        auto clone_joint(const RawAllocator& alloc, const joint_type<T>& joint)
+            -> joint_ptr<T, RawAllocator>
+        {
+            return joint_ptr<T, RawAllocator>(alloc,
+                                              joint_size(detail::get_stack(joint).capacity_used(
+                                                  detail::get_memory(joint))),
+                                              static_cast<const T&>(joint));
+        }
+        /// @}
+
+        /// A \concept{concept_rawallocator,RawAllocator} that uses the additional joint memory for its allocation.
+        ///
+        /// It is somewhat limited and allows only allocation once.
+        /// All joint allocators for an object share the joint memory and must not be used in multiple threads.
+        /// The memory it returns is owned by a \ref joint_ptr and will be destroyed through it.
+        /// \ingroup allocator
+        class joint_allocator
+        {
+        public:
+#if defined(__GNUC__) && (!defined(_GLIBCXX_USE_CXX11_ABI) || _GLIBCXX_USE_CXX11_ABI == 0)
+            // std::string requires default constructor for the small string optimization when using gcc's old ABI
+            // so add one, but it must never be used for allocation
+            joint_allocator() noexcept : stack_(nullptr) {}
+#endif
+
+            /// \effects Creates it using the joint memory of the given object.
+            template <typename T>
+            joint_allocator(joint_type<T>& j) noexcept : stack_(&detail::get_stack(j))
+            {
+            }
+
+            joint_allocator(const joint_allocator& other) noexcept = default;
+            joint_allocator& operator=(const joint_allocator& other) noexcept = default;
+
+            /// \effects Allocates a node with given properties.
+            /// \returns A pointer to the new node.
+            /// \throws \ref out_of_fixed_memory exception if this function has been called for a second time
+            /// or the joint memory block is exhausted.
+            void* allocate_node(std::size_t size, std::size_t alignment)
+            {
+                WPI_MEMORY_ASSERT(stack_);
+                auto mem = stack_->allocate(size, alignment);
+                if (!mem)
+                    WPI_THROW(out_of_fixed_memory(info(), size));
+                return mem;
+            }
+
+            /// \effects Deallocates the node, if possible.
+            /// \note It is only possible if it was the last allocation.
+            void deallocate_node(void* ptr, std::size_t size, std::size_t) noexcept
+            {
+                WPI_MEMORY_ASSERT(stack_);
+                auto end = static_cast<char*>(ptr) + size;
+                if (end == stack_->top())
+                    stack_->unwind(ptr);
+            }
+
+        private:
+            allocator_info info() const noexcept
+            {
+                return allocator_info(WPI_MEMORY_LOG_PREFIX "::joint_allocator", this);
+            }
+
+            detail::joint_stack* stack_;
+
+            friend bool operator==(const joint_allocator& lhs, const joint_allocator& rhs) noexcept;
+        };
+
+        /// @{
+        /// \returns Whether `lhs` and `rhs` use the same joint memory for the allocation.
+        /// \relates joint_allocator
+        inline bool operator==(const joint_allocator& lhs, const joint_allocator& rhs) noexcept
+        {
+            return lhs.stack_ == rhs.stack_;
+        }
+
+        inline bool operator!=(const joint_allocator& lhs, const joint_allocator& rhs) noexcept
+        {
+            return !(lhs == rhs);
+        }
+        /// @}
+
+        /// Specialization of \ref is_shared_allocator to mark \ref joint_allocator as shared.
+        /// This allows using it as \ref allocator_reference directly.
+        /// \ingroup allocator
+        template <>
+        struct is_shared_allocator<joint_allocator> : std::true_type
+        {
+        };
+
+        /// Specialization of \ref is_thread_safe_allocator to mark \ref joint_allocator as thread safe.
+        /// This is an optimization to get rid of the mutex in \ref allocator_storage,
+        /// as joint allocator must not be shared between threads.
+        /// \note The allocator is *not* thread safe, it just must not be shared.
+        template <>
+        struct is_thread_safe_allocator<joint_allocator> : std::true_type
+        {
+        };
+
+#if !defined(DOXYGEN)
+        template <class RawAllocator>
+        struct propagation_traits;
+#endif
+
+        /// Specialization of the \ref propagation_traits for the \ref joint_allocator.
+        /// A joint allocator does not propagate on assignment
+        /// and it is not allowed to use the regular copy/move constructor of allocator aware containers,
+        /// instead it needs the copy/move constructor with allocator.
+        /// \note This is required because the container constructor will end up copying/moving the allocator.
+        /// But this is not allowed as you need the allocator with the correct joined memory.
+        /// Copying can be customized (i.e. forbidden), but sadly not move, so keep that in mind.
+        /// \ingroup allocator
+        template <>
+        struct propagation_traits<joint_allocator>
+        {
+            using propagate_on_container_swap            = std::false_type;
+            using propagate_on_container_move_assignment = std::false_type;
+            using propagate_on_container_copy_assignment = std::false_type;
+
+            template <class AllocReference>
+            static AllocReference select_on_container_copy_construction(const AllocReference&)
+            {
+                static_assert(always_false<AllocReference>::value,
+                              "you must not use the regular copy constructor");
+            }
+
+        private:
+            template <typename T>
+            struct always_false : std::false_type
+            {
+            };
+        };
+
+        /// A zero overhead dynamic array using joint memory.
+        ///
+        /// If you use, e.g. `std::vector` with \ref joint_allocator,
+        /// this has a slight additional overhead.
+        /// This type is joint memory aware and has no overhead.
+        ///
+        /// It has a dynamic, but fixed size,
+        /// it cannot grow after it has been created.
+        /// \ingroup allocator
+        template <typename T>
+        class joint_array
+        {
+        public:
+            using value_type     = T;
+            using iterator       = value_type*;
+            using const_iterator = const value_type*;
+
+            //=== constructors ===//
+            /// \effects Creates with `size` default-constructed objects using the specified joint memory.
+            /// \throws \ref out_of_fixed_memory if `size` is too big
+            /// and anything thrown by `T`s constructor.
+            /// If an allocation is thrown, the memory will be released directly.
+            template <typename JointType>
+            joint_array(std::size_t size, joint_type<JointType>& j)
+            : joint_array(detail::get_stack(j), size)
+            {
+            }
+
+            /// \effects Creates with `size` copies of `val`  using the specified joint memory.
+            /// \throws \ref out_of_fixed_memory if `size` is too big
+            /// and anything thrown by `T`s constructor.
+            /// If an allocation is thrown, the memory will be released directly.
+            template <typename JointType>
+            joint_array(std::size_t size, const value_type& val, joint_type<JointType>& j)
+            : joint_array(detail::get_stack(j), size, val)
+            {
+            }
+
+            /// \effects Creates with the copies of the objects in the initializer list using the specified joint memory.
+            /// \throws \ref out_of_fixed_memory if the size is too big
+            /// and anything thrown by `T`s constructor.
+            /// If an allocation is thrown, the memory will be released directly.
+            template <typename JointType>
+            joint_array(std::initializer_list<value_type> ilist, joint_type<JointType>& j)
+            : joint_array(detail::get_stack(j), ilist)
+            {
+            }
+
+            /// \effects Creates it by forwarding each element of the range to `T`s constructor  using the specified joint memory.
+            /// \throws \ref out_of_fixed_memory if the size is too big
+            /// and anything thrown by `T`s constructor.
+            /// If an allocation is thrown, the memory will be released directly.
+            template <typename InIter, typename JointType,
+                      typename = decltype(*std::declval<InIter&>()++)>
+            joint_array(InIter begin, InIter end, joint_type<JointType>& j)
+            : joint_array(detail::get_stack(j), begin, end)
+            {
+            }
+
+            joint_array(const joint_array&) = delete;
+
+            /// \effects Copy constructs each element from `other` into the storage of the specified joint memory.
+            /// \throws \ref out_of_fixed_memory if the size is too big
+            /// and anything thrown by `T`s constructor.
+            /// If an allocation is thrown, the memory will be released directly.
+            template <typename JointType>
+            joint_array(const joint_array& other, joint_type<JointType>& j)
+            : joint_array(detail::get_stack(j), other)
+            {
+            }
+
+            joint_array(joint_array&&) = delete;
+
+            /// \effects Move constructs each element from `other` into the storage of the specified joint memory.
+            /// \throws \ref out_of_fixed_memory if the size is too big
+            /// and anything thrown by `T`s constructor.
+            /// If an allocation is thrown, the memory will be released directly.
+            template <typename JointType>
+            joint_array(joint_array&& other, joint_type<JointType>& j)
+            : joint_array(detail::get_stack(j), detail::move(other))
+            {
+            }
+
+            /// \effects Destroys all objects,
+            /// but does not release the storage.
+            ~joint_array() noexcept
+            {
+                for (std::size_t i = 0u; i != size_; ++i)
+                    ptr_[i].~T();
+            }
+
+            joint_array& operator=(const joint_array&) = delete;
+            joint_array& operator=(joint_array&&) = delete;
+
+            //=== accessors ===//
+            /// @{
+            /// \returns A reference to the `i`th object.
+            /// \requires `i < size()`.
+            value_type& operator[](std::size_t i) noexcept
+            {
+                WPI_MEMORY_ASSERT(i < size_);
+                return ptr_[i];
+            }
+
+            const value_type& operator[](std::size_t i) const noexcept
+            {
+                WPI_MEMORY_ASSERT(i < size_);
+                return ptr_[i];
+            }
+            /// @}
+
+            /// @{
+            /// \returns A pointer to the first object.
+            /// It points to contiguous memory and can be used to access the objects directly.
+            value_type* data() noexcept
+            {
+                return ptr_;
+            }
+
+            const value_type* data() const noexcept
+            {
+                return ptr_;
+            }
+            /// @}
+
+            /// @{
+            /// \returns A random access iterator to the first element.
+            iterator begin() noexcept
+            {
+                return ptr_;
+            }
+
+            const_iterator begin() const noexcept
+            {
+                return ptr_;
+            }
+            /// @}
+
+            /// @{
+            /// \returns A random access iterator one past the last element.
+            iterator end() noexcept
+            {
+                return ptr_ + size_;
+            }
+
+            const_iterator end() const noexcept
+            {
+                return ptr_ + size_;
+            }
+            /// @}
+
+            /// \returns The number of elements in the array.
+            std::size_t size() const noexcept
+            {
+                return size_;
+            }
+
+            /// \returns `true` if the array is empty, `false` otherwise.
+            bool empty() const noexcept
+            {
+                return size_ == 0u;
+            }
+
+        private:
+            // allocate only
+            struct allocate_only
+            {
+            };
+            joint_array(allocate_only, detail::joint_stack& stack, std::size_t size)
+            : ptr_(nullptr), size_(0u)
+            {
+                ptr_ = static_cast<T*>(stack.allocate(size * sizeof(T), alignof(T)));
+                if (!ptr_)
+                    WPI_THROW(out_of_fixed_memory(info(), size * sizeof(T)));
+            }
+
+            class builder
+            {
+            public:
+                builder(detail::joint_stack& stack, T* ptr) noexcept
+                : stack_(&stack), objects_(ptr), size_(0u)
+                {
+                }
+
+                ~builder() noexcept
+                {
+                    for (std::size_t i = 0u; i != size_; ++i)
+                        objects_[i].~T();
+
+                    if (size_)
+                        stack_->unwind(objects_);
+                }
+
+                builder(builder&&) = delete;
+                builder& operator=(builder&&) = delete;
+
+                template <typename... Args>
+                T* create(Args&&... args)
+                {
+                    auto ptr = ::new (static_cast<void*>(&objects_[size_]))
+                        T(detail::forward<Args>(args)...);
+                    ++size_;
+                    return ptr;
+                }
+
+                std::size_t size() const noexcept
+                {
+                    return size_;
+                }
+
+                std::size_t release() noexcept
+                {
+                    auto res = size_;
+                    size_    = 0u;
+                    return res;
+                }
+
+            private:
+                detail::joint_stack* stack_;
+                T*                   objects_;
+                std::size_t          size_;
+            };
+
+            joint_array(detail::joint_stack& stack, std::size_t size)
+            : joint_array(allocate_only{}, stack, size)
+            {
+                builder b(stack, ptr_);
+                for (auto i = 0u; i != size; ++i)
+                    b.create();
+                size_ = b.release();
+            }
+
+            joint_array(detail::joint_stack& stack, std::size_t size, const value_type& value)
+            : joint_array(allocate_only{}, stack, size)
+            {
+                builder b(stack, ptr_);
+                for (auto i = 0u; i != size; ++i)
+                    b.create(value);
+                size_ = b.release();
+            }
+
+            joint_array(detail::joint_stack& stack, std::initializer_list<value_type> ilist)
+            : joint_array(allocate_only{}, stack, ilist.size())
+            {
+                builder b(stack, ptr_);
+                for (auto& elem : ilist)
+                    b.create(elem);
+                size_ = b.release();
+            }
+
+            joint_array(detail::joint_stack& stack, const joint_array& other)
+            : joint_array(allocate_only{}, stack, other.size())
+            {
+                builder b(stack, ptr_);
+                for (auto& elem : other)
+                    b.create(elem);
+                size_ = b.release();
+            }
+
+            joint_array(detail::joint_stack& stack, joint_array&& other)
+            : joint_array(allocate_only{}, stack, other.size())
+            {
+                builder b(stack, ptr_);
+                for (auto& elem : other)
+                    b.create(detail::move(elem));
+                size_ = b.release();
+            }
+
+            template <typename InIter>
+            joint_array(detail::joint_stack& stack, InIter begin, InIter end)
+            : ptr_(nullptr), size_(0u)
+            {
+                if (begin == end)
+                    return;
+
+                ptr_ = static_cast<T*>(stack.allocate(sizeof(T), alignof(T)));
+                if (!ptr_)
+                    WPI_THROW(out_of_fixed_memory(info(), sizeof(T)));
+
+                builder b(stack, ptr_);
+                b.create(*begin++);
+
+                for (auto last = ptr_; begin != end; ++begin)
+                {
+                    // just bump stack to get more memory
+                    if (!stack.bump(sizeof(T)))
+                        WPI_THROW(out_of_fixed_memory(info(), b.size() * sizeof(T)));
+
+                    auto cur = b.create(*begin);
+                    WPI_MEMORY_ASSERT(last + 1 == cur);
+                    last = cur;
+                }
+
+                size_ = b.release();
+            }
+
+            allocator_info info() const noexcept
+            {
+                return {WPI_MEMORY_LOG_PREFIX "::joint_array", this};
+            }
+
+            value_type* ptr_;
+            std::size_t size_;
+        };
+    } // namespace memory
+} // namespace wpi
+
+#endif // WPI_MEMORY_JOINT_ALLOCATOR_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/malloc_allocator.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/malloc_allocator.hpp
new file mode 100644
index 0000000..3be9820
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/malloc_allocator.hpp
@@ -0,0 +1,71 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_MALLOC_ALLOCATOR_HPP_INCLUDED
+#define WPI_MEMORY_MALLOC_ALLOCATOR_HPP_INCLUDED
+
+/// \file
+/// Class \ref wpi::memory::malloc_allocator.
+/// \note Only available on a hosted implementation.
+
+#include "config.hpp"
+#if !WPI_HOSTED_IMPLEMENTATION
+#error "This header is only available for a hosted implementation."
+#endif
+
+#include <cstdlib>
+#include <memory>
+
+#include "detail/lowlevel_allocator.hpp"
+
+#if WPI_MEMORY_EXTERN_TEMPLATE
+#include "allocator_traits.hpp"
+#endif
+
+namespace wpi
+{
+    namespace memory
+    {
+        struct allocator_info;
+
+        namespace detail
+        {
+            struct malloc_allocator_impl
+            {
+                static allocator_info info() noexcept;
+
+                static void* allocate(std::size_t size, std::size_t) noexcept
+                {
+                    return std::malloc(size);
+                }
+
+                static void deallocate(void* ptr, std::size_t, std::size_t) noexcept
+                {
+                    std::free(ptr);
+                }
+
+                static std::size_t max_node_size() noexcept
+                {
+                    return std::allocator_traits<std::allocator<char>>::max_size({});
+                }
+            };
+
+            WPI_MEMORY_LL_ALLOCATOR_LEAK_CHECKER(malloc_allocator_impl,
+                                                       malloc_alloator_leak_checker)
+        } // namespace detail
+
+        /// A stateless \concept{concept_rawallocator,RawAllocator} that allocates memory using <tt>std::malloc()</tt>.
+        /// It throws \ref out_of_memory when the allocation fails.
+        /// \ingroup allocator
+        using malloc_allocator =
+            WPI_IMPL_DEFINED(detail::lowlevel_allocator<detail::malloc_allocator_impl>);
+
+#if WPI_MEMORY_EXTERN_TEMPLATE
+        extern template class detail::lowlevel_allocator<detail::malloc_allocator_impl>;
+        extern template class allocator_traits<malloc_allocator>;
+#endif
+    } // namespace memory
+} // namespace wpi
+
+#endif //WPI_MEMORY_MALLOC_ALLOCATOR_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/memory_arena.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/memory_arena.hpp
new file mode 100644
index 0000000..a634993
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/memory_arena.hpp
@@ -0,0 +1,693 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_MEMORY_ARENA_HPP_INCLUDED
+#define WPI_MEMORY_MEMORY_ARENA_HPP_INCLUDED
+
+/// \file
+/// Class \ref wpi::memory::memory_arena and related functionality regarding \concept{concept_blockallocator,BlockAllocators}.
+
+#include <type_traits>
+
+#include "detail/debug_helpers.hpp"
+#include "detail/assert.hpp"
+#include "detail/utility.hpp"
+#include "allocator_traits.hpp"
+#include "config.hpp"
+#include "default_allocator.hpp"
+#include "error.hpp"
+
+namespace wpi
+{
+    namespace memory
+    {
+        /// A memory block.
+        /// It is defined by its starting address and size.
+        /// \ingroup core
+        struct memory_block
+        {
+            void*       memory; ///< The address of the memory block (might be \c nullptr).
+            std::size_t size;   ///< The size of the memory block (might be \c 0).
+
+            /// \effects Creates an invalid memory block with starting address \c nullptr and size \c 0.
+            memory_block() noexcept : memory_block(nullptr, std::size_t(0)) {}
+
+            /// \effects Creates a memory block from a given starting address and size.
+            memory_block(void* mem, std::size_t s) noexcept : memory(mem), size(s) {}
+
+            /// \effects Creates a memory block from a [begin,end) range.
+            memory_block(void* begin, void* end) noexcept
+            : memory_block(begin, static_cast<std::size_t>(static_cast<char*>(end)
+                                                           - static_cast<char*>(begin)))
+            {
+            }
+
+            /// \returns Whether or not a pointer is inside the memory.
+            bool contains(const void* address) const noexcept
+            {
+                auto mem  = static_cast<const char*>(memory);
+                auto addr = static_cast<const char*>(address);
+                return addr >= mem && addr < mem + size;
+            }
+        };
+
+        namespace detail
+        {
+            template <class BlockAllocator>
+            std::true_type is_block_allocator_impl(
+                int,
+                WPI_SFINAE(std::declval<memory_block&>() =
+                                     std::declval<BlockAllocator&>().allocate_block()),
+                WPI_SFINAE(std::declval<std::size_t&>() =
+                                     std::declval<BlockAllocator&>().next_block_size()),
+                WPI_SFINAE(std::declval<BlockAllocator>().deallocate_block(memory_block{})));
+
+            template <typename T>
+            std::false_type is_block_allocator_impl(short);
+        } // namespace detail
+
+        /// Traits that check whether a type models concept \concept{concept_blockallocator,BlockAllocator}.
+        /// \ingroup core
+        template <typename T>
+        struct is_block_allocator : decltype(detail::is_block_allocator_impl<T>(0))
+        {
+        };
+
+#if !defined(DOXYGEN)
+        template <class BlockAllocator, bool Cached = true>
+        class memory_arena;
+#endif
+
+        /// @{
+        /// Controls the caching of \ref memory_arena.
+        /// By default, deallocated blocks are put onto a cache, so they can be reused later;
+        /// this tag value enable/disable it..<br>
+        /// This can be useful, e.g. if there will never be blocks available for deallocation.
+        /// The (tiny) overhead for the cache can then be disabled.
+        /// An example is \ref memory_pool.
+        /// \ingroup core
+        constexpr bool cached_arena   = true;
+        constexpr bool uncached_arena = false;
+        /// @}
+
+        namespace detail
+        {
+            // stores memory block in an intrusive linked list and allows LIFO access
+            class memory_block_stack
+            {
+            public:
+                memory_block_stack() noexcept : head_(nullptr) {}
+
+                ~memory_block_stack() noexcept {}
+
+                memory_block_stack(memory_block_stack&& other) noexcept : head_(other.head_)
+                {
+                    other.head_ = nullptr;
+                }
+
+                memory_block_stack& operator=(memory_block_stack&& other) noexcept
+                {
+                    memory_block_stack tmp(detail::move(other));
+                    swap(*this, tmp);
+                    return *this;
+                }
+
+                friend void swap(memory_block_stack& a, memory_block_stack& b) noexcept
+                {
+                    detail::adl_swap(a.head_, b.head_);
+                }
+
+                // the raw allocated block returned from an allocator
+                using allocated_mb = memory_block;
+
+                // the inserted block slightly smaller to allow for the fixup value
+                using inserted_mb = memory_block;
+
+                // how much an inserted block is smaller
+                static constexpr std::size_t implementation_offset() noexcept
+                {
+                    // node size rounded up to the next multiple of max_alignment.
+                    return (sizeof(node) / max_alignment + (sizeof(node) % max_alignment != 0))
+                           * max_alignment;
+                }
+
+                // pushes a memory block
+                void push(allocated_mb block) noexcept;
+
+                // pops a memory block and returns the original block
+                allocated_mb pop() noexcept;
+
+                // steals the top block from another stack
+                void steal_top(memory_block_stack& other) noexcept;
+
+                // returns the last pushed() inserted memory block
+                inserted_mb top() const noexcept
+                {
+                    WPI_MEMORY_ASSERT(head_);
+                    auto mem = static_cast<void*>(head_);
+                    return {static_cast<char*>(mem) + implementation_offset(), head_->usable_size};
+                }
+
+                bool empty() const noexcept
+                {
+                    return head_ == nullptr;
+                }
+
+                bool owns(const void* ptr) const noexcept;
+
+                // O(n) size
+                std::size_t size() const noexcept;
+
+            private:
+                struct node
+                {
+                    node*       prev;
+                    std::size_t usable_size;
+
+                    node(node* p, std::size_t size) noexcept : prev(p), usable_size(size) {}
+                };
+
+                node* head_;
+            };
+
+            template <bool Cached>
+            class memory_arena_cache;
+
+            template <>
+            class memory_arena_cache<cached_arena>
+            {
+            protected:
+                bool cache_empty() const noexcept
+                {
+                    return cached_.empty();
+                }
+
+                std::size_t cache_size() const noexcept
+                {
+                    return cached_.size();
+                }
+
+                std::size_t cached_block_size() const noexcept
+                {
+                    return cached_.top().size;
+                }
+
+                bool take_from_cache(detail::memory_block_stack& used) noexcept
+                {
+                    if (cached_.empty())
+                        return false;
+                    used.steal_top(cached_);
+                    return true;
+                }
+
+                template <class BlockAllocator>
+                void do_deallocate_block(BlockAllocator&, detail::memory_block_stack& used) noexcept
+                {
+                    cached_.steal_top(used);
+                }
+
+                template <class BlockAllocator>
+                void do_shrink_to_fit(BlockAllocator& alloc) noexcept
+                {
+                    detail::memory_block_stack to_dealloc;
+                    // pop from cache and push to temporary stack
+                    // this revers order
+                    while (!cached_.empty())
+                        to_dealloc.steal_top(cached_);
+                    // now dealloc everything
+                    while (!to_dealloc.empty())
+                        alloc.deallocate_block(to_dealloc.pop());
+                }
+
+            private:
+                detail::memory_block_stack cached_;
+            };
+
+            template <>
+            class memory_arena_cache<uncached_arena>
+            {
+            protected:
+                bool cache_empty() const noexcept
+                {
+                    return true;
+                }
+
+                std::size_t cache_size() const noexcept
+                {
+                    return 0u;
+                }
+
+                std::size_t cached_block_size() const noexcept
+                {
+                    return 0u;
+                }
+
+                bool take_from_cache(detail::memory_block_stack&) noexcept
+                {
+                    return false;
+                }
+
+                template <class BlockAllocator>
+                void do_deallocate_block(BlockAllocator&             alloc,
+                                         detail::memory_block_stack& used) noexcept
+                {
+                    alloc.deallocate_block(used.pop());
+                }
+
+                template <class BlockAllocator>
+                void do_shrink_to_fit(BlockAllocator&) noexcept
+                {
+                }
+            };
+        } // namespace detail
+
+        /// A memory arena that manages huge memory blocks for a higher-level allocator.
+        /// Some allocators like \ref memory_stack work on huge memory blocks,
+        /// this class manages them fro those allocators.
+        /// It uses a \concept{concept_blockallocator,BlockAllocator} for the allocation of those blocks.
+        /// The memory blocks in use are put onto a stack like structure, deallocation will pop from the top,
+        /// so it is only possible to deallocate the last allocated block of the arena.
+        /// By default, blocks are not really deallocated but stored in a cache.
+        /// This can be disabled with the second template parameter,
+        /// passing it \ref uncached_arena (or \c false) disables it,
+        /// \ref cached_arena (or \c true) enables it explicitly.
+        /// \ingroup core
+        template <class BlockAllocator, bool Cached /* = true */>
+        class memory_arena : WPI_EBO(BlockAllocator),
+                             WPI_EBO(detail::memory_arena_cache<Cached>)
+        {
+            static_assert(is_block_allocator<BlockAllocator>::value,
+                          "BlockAllocator is not a BlockAllocator!");
+            using cache = detail::memory_arena_cache<Cached>;
+
+        public:
+            using allocator_type = BlockAllocator;
+            using is_cached      = std::integral_constant<bool, Cached>;
+
+            /// \returns The minimum block size required for an arena containing the given amount of memory.
+            /// If an arena is created with the result of `min_block_size(n)`, the resulting capacity will be exactly `n`.
+            /// \requires `byte_size` must be a positive number.
+            static constexpr std::size_t min_block_size(std::size_t byte_size) noexcept
+            {
+                return detail::memory_block_stack::implementation_offset() + byte_size;
+            }
+
+            /// \effects Creates it by giving it the size and other arguments for the \concept{concept_blockallocator,BlockAllocator}.
+            /// It forwards these arguments to its constructor.
+            /// \requires \c block_size must be greater than \c min_block_size(0) and other requirements depending on the \concept{concept_blockallocator,BlockAllocator}.
+            /// \throws Anything thrown by the constructor of the \c BlockAllocator.
+            template <typename... Args>
+            explicit memory_arena(std::size_t block_size, Args&&... args)
+            : allocator_type(block_size, detail::forward<Args>(args)...)
+            {
+                WPI_MEMORY_ASSERT(block_size > min_block_size(0));
+            }
+
+            /// \effects Deallocates all memory blocks that where requested back to the \concept{concept_blockallocator,BlockAllocator}.
+            ~memory_arena() noexcept
+            {
+                // clear cache
+                shrink_to_fit();
+                // now deallocate everything
+                while (!used_.empty())
+                    allocator_type::deallocate_block(used_.pop());
+            }
+
+            /// @{
+            /// \effects Moves the arena.
+            /// The new arena takes ownership over all the memory blocks from the other arena object,
+            /// which is empty after that.
+            /// This does not invalidate any memory blocks.
+            memory_arena(memory_arena&& other) noexcept
+            : allocator_type(detail::move(other)),
+              cache(detail::move(other)),
+              used_(detail::move(other.used_))
+            {
+            }
+
+            memory_arena& operator=(memory_arena&& other) noexcept
+            {
+                memory_arena tmp(detail::move(other));
+                swap(*this, tmp);
+                return *this;
+            }
+            /// @}
+
+            /// \effects Swaps to memory arena objects.
+            /// This does not invalidate any memory blocks.
+            friend void swap(memory_arena& a, memory_arena& b) noexcept
+            {
+                detail::adl_swap(static_cast<allocator_type&>(a), static_cast<allocator_type&>(b));
+                detail::adl_swap(static_cast<cache&>(a), static_cast<cache&>(b));
+                detail::adl_swap(a.used_, b.used_);
+            }
+
+            /// \effects Allocates a new memory block.
+            /// It first uses a cache of previously deallocated blocks, if caching is enabled,
+            /// if it is empty, allocates a new one.
+            /// \returns The new \ref memory_block.
+            /// \throws Anything thrown by the \concept{concept_blockallocator,BlockAllocator} allocation function.
+            memory_block allocate_block()
+            {
+                if (!this->take_from_cache(used_))
+                    used_.push(allocator_type::allocate_block());
+
+                auto block = used_.top();
+                detail::debug_fill_internal(block.memory, block.size, false);
+                return block;
+            }
+
+            /// \returns The current memory block.
+            /// This is the memory block that will be deallocated by the next call to \ref deallocate_block().
+            memory_block current_block() const noexcept
+            {
+                return used_.top();
+            }
+
+            /// \effects Deallocates the current memory block.
+            /// The current memory block is the block on top of the stack of blocks.
+            /// If caching is enabled, it does not really deallocate it but puts it onto a cache for later use,
+            /// use \ref shrink_to_fit() to purge that cache.
+            void deallocate_block() noexcept
+            {
+                auto block = used_.top();
+                detail::debug_fill_internal(block.memory, block.size, true);
+                this->do_deallocate_block(get_allocator(), used_);
+            }
+
+            /// \returns If `ptr` is in memory owned by the arena.
+            bool owns(const void* ptr) const noexcept
+            {
+                return used_.owns(ptr);
+            }
+
+            /// \effects Purges the cache of unused memory blocks by returning them.
+            /// The memory blocks will be deallocated in reversed order of allocation.
+            /// Does nothing if caching is disabled.
+            void shrink_to_fit() noexcept
+            {
+                this->do_shrink_to_fit(get_allocator());
+            }
+
+            /// \returns The capacity of the arena, i.e. how many blocks are used and cached.
+            std::size_t capacity() const noexcept
+            {
+                return size() + cache_size();
+            }
+
+            /// \returns The size of the cache, i.e. how many blocks can be allocated without allocation.
+            std::size_t cache_size() const noexcept
+            {
+                return cache::cache_size();
+            }
+
+            /// \returns The size of the arena, i.e. how many blocks are in use.
+            /// It is always smaller or equal to the \ref capacity().
+            std::size_t size() const noexcept
+            {
+                return used_.size();
+            }
+
+            /// \returns The size of the next memory block,
+            /// i.e. of the next call to \ref allocate_block().
+            /// If there are blocks in the cache, returns size of the next one.
+            /// Otherwise forwards to the \concept{concept_blockallocator,BlockAllocator} and subtracts an implementation offset.
+            std::size_t next_block_size() const noexcept
+            {
+                return this->cache_empty() ?
+                           allocator_type::next_block_size()
+                               - detail::memory_block_stack::implementation_offset() :
+                           this->cached_block_size();
+            }
+
+            /// \returns A reference of the \concept{concept_blockallocator,BlockAllocator} object.
+            /// \requires It is undefined behavior to move this allocator out into another object.
+            allocator_type& get_allocator() noexcept
+            {
+                return *this;
+            }
+
+        private:
+            detail::memory_block_stack used_;
+        };
+
+#if WPI_MEMORY_EXTERN_TEMPLATE
+        extern template class memory_arena<static_block_allocator, true>;
+        extern template class memory_arena<static_block_allocator, false>;
+        extern template class memory_arena<virtual_block_allocator, true>;
+        extern template class memory_arena<virtual_block_allocator, false>;
+#endif
+
+        /// A \concept{concept_blockallocator,BlockAllocator} that uses a given \concept{concept_rawallocator,RawAllocator} for allocating the blocks.
+        /// It calls the \c allocate_array() function with a node of size \c 1 and maximum alignment on the used allocator for the block allocation.
+        /// The size of the next memory block will grow by a given factor after each allocation,
+        /// allowing an amortized constant allocation time in the higher level allocator.
+        /// The factor can be given as rational in the template parameter, default is \c 2.
+        /// \ingroup adapter
+        template <class RawAllocator = default_allocator, unsigned Num = 2, unsigned Den = 1>
+        class growing_block_allocator
+        : WPI_EBO(allocator_traits<RawAllocator>::allocator_type)
+        {
+            static_assert(float(Num) / Den >= 1.0, "invalid growth factor");
+
+            using traits = allocator_traits<RawAllocator>;
+
+        public:
+            using allocator_type = typename traits::allocator_type;
+
+            /// \effects Creates it by giving it the initial block size, the allocator object and the growth factor.
+            /// By default, it uses a default-constructed allocator object and a growth factor of \c 2.
+            /// \requires \c block_size must be greater than 0.
+            explicit growing_block_allocator(std::size_t    block_size,
+                                             allocator_type alloc = allocator_type()) noexcept
+            : allocator_type(detail::move(alloc)), block_size_(block_size)
+            {
+            }
+
+            /// \effects Allocates a new memory block and increases the block size for the next allocation.
+            /// \returns The new \ref memory_block.
+            /// \throws Anything thrown by the \c allocate_array() function of the \concept{concept_rawallocator,RawAllocator}.
+            memory_block allocate_block()
+            {
+                auto memory =
+                    traits::allocate_array(get_allocator(), block_size_, 1, detail::max_alignment);
+                memory_block block(memory, block_size_);
+                block_size_ = grow_block_size(block_size_);
+                return block;
+            }
+
+            /// \effects Deallocates a previously allocated memory block.
+            /// This does not decrease the block size.
+            /// \requires \c block must be previously returned by a call to \ref allocate_block().
+            void deallocate_block(memory_block block) noexcept
+            {
+                traits::deallocate_array(get_allocator(), block.memory, block.size, 1,
+                                         detail::max_alignment);
+            }
+
+            /// \returns The size of the memory block returned by the next call to \ref allocate_block().
+            std::size_t next_block_size() const noexcept
+            {
+                return block_size_;
+            }
+
+            /// \returns A reference to the used \concept{concept_rawallocator,RawAllocator} object.
+            allocator_type& get_allocator() noexcept
+            {
+                return *this;
+            }
+
+            /// \returns The growth factor.
+            static float growth_factor() noexcept
+            {
+                static constexpr auto factor = float(Num) / Den;
+                return factor;
+            }
+
+            static std::size_t grow_block_size(std::size_t block_size) noexcept
+            {
+                return block_size * Num / Den;
+            }
+
+        private:
+            std::size_t block_size_;
+        };
+
+#if WPI_MEMORY_EXTERN_TEMPLATE
+        extern template class growing_block_allocator<>;
+        extern template class memory_arena<growing_block_allocator<>, true>;
+        extern template class memory_arena<growing_block_allocator<>, false>;
+#endif
+
+        /// A \concept{concept_blockallocator,BlockAllocator} that allows only one block allocation.
+        /// It can be used to prevent higher-level allocators from expanding.
+        /// The one block allocation is performed through the \c allocate_array() function of the given \concept{concept_rawallocator,RawAllocator}.
+        /// \ingroup adapter
+        template <class RawAllocator = default_allocator>
+        class fixed_block_allocator : WPI_EBO(allocator_traits<RawAllocator>::allocator_type)
+        {
+            using traits = allocator_traits<RawAllocator>;
+
+        public:
+            using allocator_type = typename traits::allocator_type;
+
+            /// \effects Creates it by passing it the size of the block and the allocator object.
+            /// \requires \c block_size must be greater than 0,
+            explicit fixed_block_allocator(std::size_t    block_size,
+                                           allocator_type alloc = allocator_type()) noexcept
+            : allocator_type(detail::move(alloc)), block_size_(block_size)
+            {
+            }
+
+            /// \effects Allocates a new memory block or throws an exception if there was already one allocation.
+            /// \returns The new \ref memory_block.
+            /// \throws Anything thrown by the \c allocate_array() function of the \concept{concept_rawallocator,RawAllocator} or \ref out_of_memory if this is not the first call.
+            memory_block allocate_block()
+            {
+                if (block_size_)
+                {
+                    auto         mem = traits::allocate_array(get_allocator(), block_size_, 1,
+                                                      detail::max_alignment);
+                    memory_block block(mem, block_size_);
+                    block_size_ = 0u;
+                    return block;
+                }
+                WPI_THROW(out_of_fixed_memory(info(), block_size_));
+            }
+
+            /// \effects Deallocates the previously allocated memory block.
+            /// It also resets and allows a new call again.
+            void deallocate_block(memory_block block) noexcept
+            {
+                detail::debug_check_pointer([&] { return block_size_ == 0u; }, info(),
+                                            block.memory);
+                traits::deallocate_array(get_allocator(), block.memory, block.size, 1,
+                                         detail::max_alignment);
+                block_size_ = block.size;
+            }
+
+            /// \returns The size of the next block which is either the initial size or \c 0.
+            std::size_t next_block_size() const noexcept
+            {
+                return block_size_;
+            }
+
+            /// \returns A reference to the used \concept{concept_rawallocator,RawAllocator} object.
+            allocator_type& get_allocator() noexcept
+            {
+                return *this;
+            }
+
+        private:
+            allocator_info info() noexcept
+            {
+                return {WPI_MEMORY_LOG_PREFIX "::fixed_block_allocator", this};
+            }
+
+            std::size_t block_size_;
+        };
+
+#if WPI_MEMORY_EXTERN_TEMPLATE
+        extern template class fixed_block_allocator<>;
+        extern template class memory_arena<fixed_block_allocator<>, true>;
+        extern template class memory_arena<fixed_block_allocator<>, false>;
+#endif
+
+        namespace detail
+        {
+            template <class RawAlloc>
+            using default_block_wrapper = growing_block_allocator<RawAlloc>;
+
+            template <template <class...> class Wrapper, class BlockAllocator, typename... Args>
+            BlockAllocator make_block_allocator(std::true_type, std::size_t block_size,
+                                                Args&&... args)
+            {
+                return BlockAllocator(block_size, detail::forward<Args>(args)...);
+            }
+
+            template <template <class...> class Wrapper, class RawAlloc>
+            auto make_block_allocator(std::false_type, std::size_t block_size,
+                                      RawAlloc alloc = RawAlloc()) -> Wrapper<RawAlloc>
+            {
+                return Wrapper<RawAlloc>(block_size, detail::move(alloc));
+            }
+        } // namespace detail
+
+        /// Takes either a \concept{concept_blockallocator,BlockAllocator} or a \concept{concept_rawallocator,RawAllocator}.
+        /// In the first case simply aliases the type unchanged, in the second to \ref growing_block_allocator (or the template in `BlockAllocator`) with the \concept{concept_rawallocator,RawAllocator}.
+        /// Using this allows passing normal \concept{concept_rawallocator,RawAllocators} as \concept{concept_blockallocator,BlockAllocators}.
+        /// \ingroup core
+        template <class BlockOrRawAllocator,
+                  template <typename...> class BlockAllocator = detail::default_block_wrapper>
+        using make_block_allocator_t = WPI_IMPL_DEFINED(
+            typename std::conditional<is_block_allocator<BlockOrRawAllocator>::value,
+                                      BlockOrRawAllocator,
+                                      BlockAllocator<BlockOrRawAllocator>>::type);
+
+        /// @{
+        /// Helper function make a \concept{concept_blockallocator,BlockAllocator}.
+        /// \returns A \concept{concept_blockallocator,BlockAllocator} of the given type created with the given arguments.
+        /// \requires Same requirements as the constructor.
+        /// \ingroup core
+        template <class BlockOrRawAllocator, typename... Args>
+        make_block_allocator_t<BlockOrRawAllocator> make_block_allocator(std::size_t block_size,
+                                                                         Args&&... args)
+        {
+            return detail::make_block_allocator<
+                detail::default_block_wrapper,
+                BlockOrRawAllocator>(is_block_allocator<BlockOrRawAllocator>{}, block_size,
+                                     detail::forward<Args>(args)...);
+        }
+
+        template <template <class...> class BlockAllocator, class BlockOrRawAllocator,
+                  typename... Args>
+        make_block_allocator_t<BlockOrRawAllocator, BlockAllocator> make_block_allocator(
+            std::size_t block_size, Args&&... args)
+        {
+            return detail::make_block_allocator<
+                BlockAllocator, BlockOrRawAllocator>(is_block_allocator<BlockOrRawAllocator>{},
+                                                     block_size, detail::forward<Args>(args)...);
+        }
+        /// @}
+
+        namespace literals
+        {
+            /// Syntax sugar to express sizes with unit prefixes.
+            /// \returns The number of bytes `value` is in the given unit.
+            /// \ingroup core
+            /// @{
+            constexpr std::size_t operator"" _KiB(unsigned long long value) noexcept
+            {
+                return std::size_t(value * 1024);
+            }
+
+            constexpr std::size_t operator"" _KB(unsigned long long value) noexcept
+            {
+                return std::size_t(value * 1000);
+            }
+
+            constexpr std::size_t operator"" _MiB(unsigned long long value) noexcept
+            {
+                return std::size_t(value * 1024 * 1024);
+            }
+
+            constexpr std::size_t operator"" _MB(unsigned long long value) noexcept
+            {
+                return std::size_t(value * 1000 * 1000);
+            }
+
+            constexpr std::size_t operator"" _GiB(unsigned long long value) noexcept
+            {
+                return std::size_t(value * 1024 * 1024 * 1024);
+            }
+
+            constexpr std::size_t operator"" _GB(unsigned long long value) noexcept
+            {
+                return std::size_t(value * 1000 * 1000 * 1000);
+            }
+        } // namespace literals
+    }     // namespace memory
+} // namespace wpi
+
+#endif // WPI_MEMORY_MEMORY_ARENA_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/memory_pool.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/memory_pool.hpp
new file mode 100644
index 0000000..09c2b66
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/memory_pool.hpp
@@ -0,0 +1,433 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_MEMORY_POOL_HPP_INCLUDED
+#define WPI_MEMORY_MEMORY_POOL_HPP_INCLUDED
+
+// Inform that wpi::memory::memory_pool::min_block_size API is available
+#define WPI_MEMORY_MEMORY_POOL_HAS_MIN_BLOCK_SIZE
+
+/// \file
+/// Class \ref wpi::memory::memory_pool and its \ref wpi::memory::allocator_traits specialization.
+
+#include <type_traits>
+
+#include "detail/align.hpp"
+#include "detail/debug_helpers.hpp"
+#include "detail/assert.hpp"
+#include "config.hpp"
+#include "error.hpp"
+#include "memory_arena.hpp"
+#include "memory_pool_type.hpp"
+
+namespace wpi
+{
+    namespace memory
+    {
+        namespace detail
+        {
+            struct memory_pool_leak_handler
+            {
+                void operator()(std::ptrdiff_t amount);
+            };
+        } // namespace detail
+
+        /// A stateful \concept{concept_rawallocator,RawAllocator} that manages \concept{concept_node,nodes} of fixed size.
+        /// It uses a \ref memory_arena with a given \c BlockOrRawAllocator defaulting to \ref growing_block_allocator,
+        /// subdivides them in small nodes of given size and puts them onto a free list.
+        /// Allocation and deallocation simply remove or add nodes from this list and are thus fast.
+        /// The way the list is maintained can be controlled via the \c PoolType
+        /// which is either \ref node_pool, \ref array_pool or \ref small_node_pool.<br>
+        /// This kind of allocator is ideal for fixed size allocations and deallocations in any order,
+        /// for example in a node based container like \c std::list.
+        /// It is not so good for different allocation sizes and has some drawbacks for arrays
+        /// as described in \ref memory_pool_type.hpp.
+        /// \ingroup allocator
+        template <typename PoolType = node_pool, class BlockOrRawAllocator = default_allocator>
+        class memory_pool
+        : WPI_EBO(detail::default_leak_checker<detail::memory_pool_leak_handler>)
+        {
+            using free_list    = typename PoolType::type;
+            using leak_checker = detail::default_leak_checker<detail::memory_pool_leak_handler>;
+
+        public:
+            using allocator_type = make_block_allocator_t<BlockOrRawAllocator>;
+            using pool_type      = PoolType;
+
+            static constexpr std::size_t min_node_size =
+                WPI_IMPL_DEFINED(free_list::min_element_size);
+
+            /// \returns The minimum block size required for certain number of \concept{concept_node,node}.
+            /// \requires \c node_size must be a valid \concept{concept_node,node size}
+            /// and \c number_of_nodes must be a non-zero value.
+            /// \note MSVC's implementation of \c std::list for example is never empty and always allocates proxy nodes.
+            /// To get enough memory for \c N elements of a list, \c number_of_nodes needs to include the proxy count in addition to \c N.
+            static constexpr std::size_t min_block_size(std::size_t node_size,
+                                                        std::size_t number_of_nodes) noexcept
+            {
+                return detail::memory_block_stack::implementation_offset()
+                       + free_list::min_block_size(node_size, number_of_nodes);
+            }
+
+            /// \effects Creates it by specifying the size each \concept{concept_node,node} will have,
+            /// the initial block size for the arena and other constructor arguments for the \concept{concept_blockallocator,BlockAllocator}.
+            /// If the \c node_size is less than the \c min_node_size, the \c min_node_size will be the actual node size.
+            /// It will allocate an initial memory block with given size from the \concept{concept_blockallocator,BlockAllocator}
+            /// and puts it onto the free list.
+            /// \requires \c node_size must be a valid \concept{concept_node,node size}
+            /// and \c block_size must be at least \c min_block_size(node_size, 1).
+            template <typename... Args>
+            memory_pool(std::size_t node_size, std::size_t block_size, Args&&... args)
+            : arena_(block_size, detail::forward<Args>(args)...), free_list_(node_size)
+            {
+                allocate_block();
+            }
+
+            /// \effects Destroys the \ref memory_pool by returning all memory blocks,
+            /// regardless of properly deallocated back to the \concept{concept_blockallocator,BlockAllocator}.
+            ~memory_pool() noexcept {}
+
+            /// @{
+            /// \effects Moving a \ref memory_pool object transfers ownership over the free list,
+            /// i.e. the moved from pool is completely empty and the new one has all its memory.
+            /// That means that it is not allowed to call \ref deallocate_node() on a moved-from allocator
+            /// even when passing it memory that was previously allocated by this object.
+            memory_pool(memory_pool&& other) noexcept
+            : leak_checker(detail::move(other)),
+              arena_(detail::move(other.arena_)),
+              free_list_(detail::move(other.free_list_))
+            {
+            }
+
+            memory_pool& operator=(memory_pool&& other) noexcept
+            {
+                leak_checker::operator=(detail::move(other));
+                arena_                = detail::move(other.arena_);
+                free_list_            = detail::move(other.free_list_);
+                return *this;
+            }
+            /// @}
+
+            /// \effects Allocates a single \concept{concept_node,node} by removing it from the free list.
+            /// If the free list is empty, a new memory block will be allocated from the arena and put onto it.
+            /// The new block size will be \ref next_capacity() big.
+            /// \returns A node of size \ref node_size() suitable aligned,
+            /// i.e. suitable for any type where <tt>sizeof(T) < node_size()</tt>.
+            /// \throws Anything thrown by the used \concept{concept_blockallocator,BlockAllocator}'s allocation function if a growth is needed.
+            void* allocate_node()
+            {
+                if (free_list_.empty())
+                    allocate_block();
+                WPI_MEMORY_ASSERT(!free_list_.empty());
+                return free_list_.allocate();
+            }
+
+            /// \effects Allocates a single \concept{concept_node,node} similar to \ref allocate_node().
+            /// But if the free list is empty, a new block will *not* be allocated.
+            /// \returns A suitable aligned node of size \ref node_size() or `nullptr`.
+            void* try_allocate_node() noexcept
+            {
+                return free_list_.empty() ? nullptr : free_list_.allocate();
+            }
+
+            /// \effects Allocates an \concept{concept_array,array} of nodes by searching for \c n continuous nodes on the list and removing them.
+            /// Depending on the \c PoolType this can be a slow operation or not allowed at all.
+            /// This can sometimes lead to a growth, even if technically there is enough continuous memory on the free list.
+            /// \returns An array of \c n nodes of size \ref node_size() suitable aligned.
+            /// \throws Anything thrown by the used \concept{concept_blockallocator,BlockAllocator}'s allocation function if a growth is needed,
+            /// or \ref bad_array_size if <tt>n * node_size()</tt> is too big.
+            /// \requires \c n must be valid \concept{concept_array,array count}.
+            void* allocate_array(std::size_t n)
+            {
+                detail::check_allocation_size<bad_array_size>(
+                    n * node_size(), [&] { return pool_type::value ? next_capacity() : 0; },
+                    info());
+                return allocate_array(n, node_size());
+            }
+
+            /// \effects Allocates an \concept{concept_array,array} of nodes similar to \ref allocate_array().
+            /// But it will never allocate a new memory block.
+            /// \returns An array of \c n nodes of size \ref node_size() suitable aligned
+            /// or `nullptr`.
+            void* try_allocate_array(std::size_t n) noexcept
+            {
+                return try_allocate_array(n, node_size());
+            }
+
+            /// \effects Deallocates a single \concept{concept_node,node} by putting it back onto the free list.
+            /// \requires \c ptr must be a result from a previous call to \ref allocate_node() on the same free list,
+            /// i.e. either this allocator object or a new object created by moving this to it.
+            void deallocate_node(void* ptr) noexcept
+            {
+                free_list_.deallocate(ptr);
+            }
+
+            /// \effects Deallocates a single \concept{concept_node,node} but it does not be a result of a previous call to \ref allocate_node().
+            /// \returns `true` if the node could be deallocated, `false` otherwise.
+            /// \note Some free list implementations can deallocate any memory,
+            /// doesn't matter where it is coming from.
+            bool try_deallocate_node(void* ptr) noexcept
+            {
+                if (!arena_.owns(ptr))
+                    return false;
+                free_list_.deallocate(ptr);
+                return true;
+            }
+
+            /// \effects Deallocates an \concept{concept_array,array} by putting it back onto the free list.
+            /// \requires \c ptr must be a result from a previous call to \ref allocate_array() with the same \c n on the same free list,
+            /// i.e. either this allocator object or a new object created by moving this to it.
+            void deallocate_array(void* ptr, std::size_t n) noexcept
+            {
+                WPI_MEMORY_ASSERT_MSG(pool_type::value, "does not support array allocations");
+                free_list_.deallocate(ptr, n * node_size());
+            }
+
+            /// \effects Deallocates an \concept{concept_array,array} but it does not be a result of a previous call to \ref allocate_array().
+            /// \returns `true` if the node could be deallocated, `false` otherwise.
+            /// \note Some free list implementations can deallocate any memory,
+            /// doesn't matter where it is coming from.
+            bool try_deallocate_array(void* ptr, std::size_t n) noexcept
+            {
+                return try_deallocate_array(ptr, n, node_size());
+            }
+
+            /// \returns The size of each \concept{concept_node,node} in the pool,
+            /// this is either the same value as in the constructor or \c min_node_size if the value was too small.
+            std::size_t node_size() const noexcept
+            {
+                return free_list_.node_size();
+            }
+
+            /// \effects Returns the total amount of bytes remaining on the free list.
+            /// Divide it by \ref node_size() to get the number of nodes that can be allocated without growing the arena.
+            /// \note Array allocations may lead to a growth even if the capacity_left left is big enough.
+            std::size_t capacity_left() const noexcept
+            {
+                return free_list_.capacity() * node_size();
+            }
+
+            /// \returns The size of the next memory block after the free list gets empty and the arena grows.
+            /// \ref capacity_left() will increase by this amount.
+            /// \note Due to fence memory in debug mode this cannot be just divided by the \ref node_size() to get the number of nodes.
+            std::size_t next_capacity() const noexcept
+            {
+                return free_list_.usable_size(arena_.next_block_size());
+            }
+
+            /// \returns A reference to the \concept{concept_blockallocator,BlockAllocator} used for managing the arena.
+            /// \requires It is undefined behavior to move this allocator out into another object.
+            allocator_type& get_allocator() noexcept
+            {
+                return arena_.get_allocator();
+            }
+
+        private:
+            allocator_info info() const noexcept
+            {
+                return {WPI_MEMORY_LOG_PREFIX "::memory_pool", this};
+            }
+
+            void allocate_block()
+            {
+                auto mem = arena_.allocate_block();
+                free_list_.insert(static_cast<char*>(mem.memory), mem.size);
+            }
+
+            void* allocate_array(std::size_t n, std::size_t node_size)
+            {
+                auto mem = free_list_.empty() ? nullptr : free_list_.allocate(n * node_size);
+                if (!mem)
+                {
+                    allocate_block();
+                    mem = free_list_.allocate(n * node_size);
+                    if (!mem)
+                        WPI_THROW(bad_array_size(info(), n * node_size, capacity_left()));
+                }
+                return mem;
+            }
+
+            void* try_allocate_array(std::size_t n, std::size_t node_size) noexcept
+            {
+                return !pool_type::value || free_list_.empty() ? nullptr :
+                                                                 free_list_.allocate(n * node_size);
+            }
+
+            bool try_deallocate_array(void* ptr, std::size_t n, std::size_t node_size) noexcept
+            {
+                if (!pool_type::value || !arena_.owns(ptr))
+                    return false;
+                free_list_.deallocate(ptr, n * node_size);
+                return true;
+            }
+
+            memory_arena<allocator_type, false> arena_;
+            free_list                           free_list_;
+
+            friend allocator_traits<memory_pool<PoolType, BlockOrRawAllocator>>;
+            friend composable_allocator_traits<memory_pool<PoolType, BlockOrRawAllocator>>;
+        };
+
+#if WPI_MEMORY_EXTERN_TEMPLATE
+        extern template class memory_pool<node_pool>;
+        extern template class memory_pool<array_pool>;
+        extern template class memory_pool<small_node_pool>;
+#endif
+
+        template <class Type, class Alloc>
+        constexpr std::size_t memory_pool<Type, Alloc>::min_node_size;
+
+        /// Specialization of the \ref allocator_traits for \ref memory_pool classes.
+        /// \note It is not allowed to mix calls through the specialization and through the member functions,
+        /// i.e. \ref memory_pool::allocate_node() and this \c allocate_node().
+        /// \ingroup allocator
+        template <typename PoolType, class ImplRawAllocator>
+        class allocator_traits<memory_pool<PoolType, ImplRawAllocator>>
+        {
+        public:
+            using allocator_type = memory_pool<PoolType, ImplRawAllocator>;
+            using is_stateful    = std::true_type;
+
+            /// \returns The result of \ref memory_pool::allocate_node().
+            /// \throws Anything thrown by the pool allocation function
+            /// or a \ref bad_allocation_size exception.
+            static void* allocate_node(allocator_type& state, std::size_t size,
+                                       std::size_t alignment)
+            {
+                detail::check_allocation_size<bad_node_size>(size, max_node_size(state),
+                                                             state.info());
+                detail::check_allocation_size<bad_alignment>(
+                    alignment, [&] { return max_alignment(state); }, state.info());
+                auto mem = state.allocate_node();
+                state.on_allocate(size);
+                return mem;
+            }
+
+            /// \effects Forwards to \ref memory_pool::allocate_array()
+            /// with the number of nodes adjusted to be the minimum,
+            /// i.e. when the \c size is less than the \ref memory_pool::node_size().
+            /// \returns A \concept{concept_array,array} with specified properties.
+            /// \requires The \ref memory_pool has to support array allocations.
+            /// \throws Anything thrown by the pool allocation function.
+            static void* allocate_array(allocator_type& state, std::size_t count, std::size_t size,
+                                        std::size_t alignment)
+            {
+                detail::check_allocation_size<bad_node_size>(size, max_node_size(state),
+                                                             state.info());
+                detail::check_allocation_size<bad_alignment>(
+                    alignment, [&] { return max_alignment(state); }, state.info());
+                detail::check_allocation_size<bad_array_size>(count * size, max_array_size(state),
+                                                              state.info());
+                auto mem = state.allocate_array(count, size);
+                state.on_allocate(count * size);
+                return mem;
+            }
+
+            /// \effects Just forwards to \ref memory_pool::deallocate_node().
+            static void deallocate_node(allocator_type& state, void* node, std::size_t size,
+                                        std::size_t) noexcept
+            {
+                state.deallocate_node(node);
+                state.on_deallocate(size);
+            }
+
+            /// \effects Forwards to \ref memory_pool::deallocate_array() with the same size adjustment.
+            static void deallocate_array(allocator_type& state, void* array, std::size_t count,
+                                         std::size_t size, std::size_t) noexcept
+            {
+                state.free_list_.deallocate(array, count * size);
+                state.on_deallocate(count * size);
+            }
+
+            /// \returns The maximum size of each node which is \ref memory_pool::node_size().
+            static std::size_t max_node_size(const allocator_type& state) noexcept
+            {
+                return state.node_size();
+            }
+
+            /// \returns An upper bound on the maximum array size which is \ref memory_pool::next_capacity().
+            static std::size_t max_array_size(const allocator_type& state) noexcept
+            {
+                return state.next_capacity();
+            }
+
+            /// \returns The maximum alignment which is the next bigger power of two if less than \c alignof(std::max_align_t)
+            /// or the maximum alignment itself otherwise.
+            static std::size_t max_alignment(const allocator_type& state) noexcept
+            {
+                return state.free_list_.alignment();
+            }
+        };
+
+        /// Specialization of the \ref composable_allocator_traits for \ref memory_pool classes.
+        /// \ingroup allocator
+        template <typename PoolType, class BlockOrRawAllocator>
+        class composable_allocator_traits<memory_pool<PoolType, BlockOrRawAllocator>>
+        {
+            using traits = allocator_traits<memory_pool<PoolType, BlockOrRawAllocator>>;
+
+        public:
+            using allocator_type = memory_pool<PoolType, BlockOrRawAllocator>;
+
+            /// \returns The result of \ref memory_pool::try_allocate_node()
+            /// or `nullptr` if the allocation size was too big.
+            static void* try_allocate_node(allocator_type& state, std::size_t size,
+                                           std::size_t alignment) noexcept
+            {
+                if (size > traits::max_node_size(state) || alignment > traits::max_alignment(state))
+                    return nullptr;
+                return state.try_allocate_node();
+            }
+
+            /// \effects Forwards to \ref memory_pool::try_allocate_array()
+            /// with the number of nodes adjusted to be the minimum,
+            /// if the \c size is less than the \ref memory_pool::node_size().
+            /// \returns A \concept{concept_array,array} with specified properties
+            /// or `nullptr` if it was unable to allocate.
+            static void* try_allocate_array(allocator_type& state, std::size_t count,
+                                            std::size_t size, std::size_t alignment) noexcept
+            {
+                if (size > traits::max_node_size(state)
+                    || count * size > traits::max_array_size(state)
+                    || alignment > traits::max_alignment(state))
+                    return nullptr;
+                return state.try_allocate_array(count, size);
+            }
+
+            /// \effects Just forwards to \ref memory_pool::try_deallocate_node().
+            /// \returns Whether the deallocation was successful.
+            static bool try_deallocate_node(allocator_type& state, void* node, std::size_t size,
+                                            std::size_t alignment) noexcept
+            {
+                if (size > traits::max_node_size(state) || alignment > traits::max_alignment(state))
+                    return false;
+                return state.try_deallocate_node(node);
+            }
+
+            /// \effects Forwards to \ref memory_pool::deallocate_array() with the same size adjustment.
+            /// \returns Whether the deallocation was successful.
+            static bool try_deallocate_array(allocator_type& state, void* array, std::size_t count,
+                                             std::size_t size, std::size_t alignment) noexcept
+            {
+                if (size > traits::max_node_size(state)
+                    || count * size > traits::max_array_size(state)
+                    || alignment > traits::max_alignment(state))
+                    return false;
+                return state.try_deallocate_array(array, count, size);
+            }
+        };
+
+#if WPI_MEMORY_EXTERN_TEMPLATE
+        extern template class allocator_traits<memory_pool<node_pool>>;
+        extern template class allocator_traits<memory_pool<array_pool>>;
+        extern template class allocator_traits<memory_pool<small_node_pool>>;
+
+        extern template class composable_allocator_traits<memory_pool<node_pool>>;
+        extern template class composable_allocator_traits<memory_pool<array_pool>>;
+        extern template class composable_allocator_traits<memory_pool<small_node_pool>>;
+#endif
+    } // namespace memory
+} // namespace wpi
+
+#endif // WPI_MEMORY_MEMORY_POOL_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/memory_pool_collection.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/memory_pool_collection.hpp
new file mode 100644
index 0000000..294dd0a
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/memory_pool_collection.hpp
@@ -0,0 +1,569 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_MEMORY_POOL_COLLECTION_HPP_INCLUDED
+#define WPI_MEMORY_MEMORY_POOL_COLLECTION_HPP_INCLUDED
+
+/// \file
+/// Class \ref wpi::memory::memory_pool_collection and related classes.
+
+#include <type_traits>
+
+#include "detail/align.hpp"
+#include "detail/assert.hpp"
+#include "detail/memory_stack.hpp"
+#include "detail/free_list_array.hpp"
+#include "config.hpp"
+#include "debugging.hpp"
+#include "error.hpp"
+#include "memory_arena.hpp"
+#include "memory_pool_type.hpp"
+
+namespace wpi
+{
+    namespace memory
+    {
+        namespace detail
+        {
+            struct memory_pool_collection_leak_handler
+            {
+                void operator()(std::ptrdiff_t amount);
+            };
+        } // namespace detail
+
+        /// A \c BucketDistribution for \ref memory_pool_collection defining that there is a bucket, i.e. pool, for each size.
+        /// That means that for each possible size up to an upper bound there will be a seperate free list.
+        /// Allocating a node will not waste any memory.
+        /// \ingroup allocator
+        struct identity_buckets
+        {
+            using type = detail::identity_access_policy;
+        };
+
+        /// A \c BucketDistribution for \ref memory_pool_collection defining that there is a bucket, i.e. pool, for each power of two.
+        /// That means for each power of two up to an upper bound there will be a separate free list.
+        /// Allocating a node will only waste half of the memory.
+        /// \ingroup allocator
+        struct log2_buckets
+        {
+            using type = detail::log2_access_policy;
+        };
+
+        /// A stateful \concept{concept_rawallocator,RawAllocator} that behaves as a collection of multiple \ref memory_pool objects.
+        /// It maintains a list of multiple free lists, whose types are controlled via the \c PoolType tags defined in \ref memory_pool_type.hpp,
+        /// each of a different size as defined in the \c BucketDistribution (\ref identity_buckets or \ref log2_buckets).
+        /// Allocating a node of given size will use the appropriate free list.<br>
+        /// This allocator is ideal for \concept{concept_node,node} allocations in any order but with a predefined set of sizes,
+        /// not only one size like \ref memory_pool.
+        /// \ingroup allocator
+        template <class PoolType, class BucketDistribution,
+                  class BlockOrRawAllocator = default_allocator>
+        class memory_pool_collection
+        : WPI_EBO(detail::default_leak_checker<detail::memory_pool_collection_leak_handler>)
+        {
+            using free_list_array =
+                detail::free_list_array<typename PoolType::type, typename BucketDistribution::type>;
+            using leak_checker =
+                detail::default_leak_checker<detail::memory_pool_collection_leak_handler>;
+
+        public:
+            using allocator_type      = make_block_allocator_t<BlockOrRawAllocator>;
+            using pool_type           = PoolType;
+            using bucket_distribution = BucketDistribution;
+
+            /// \effects Creates it by giving it the maximum node size it should be able to allocate,
+            /// the size of the initial memory block and other constructor arguments for the \concept{concept_blockallocator,BlockAllocator}.
+            /// The \c BucketDistribution controls how many free lists are created,
+            /// but unlike in \ref memory_pool all free lists are initially empty and the first memory block queued.
+            /// \requires \c max_node_size must be a valid \concept{concept_node,node} size
+            /// and \c block_size must be non-zero.
+            template <typename... Args>
+            memory_pool_collection(std::size_t max_node_size, std::size_t block_size,
+                                   Args&&... args)
+            : arena_(block_size, detail::forward<Args>(args)...),
+              stack_(allocate_block()),
+              pools_(stack_, block_end(), max_node_size)
+            {
+            }
+
+            /// \effects Destroys the \ref memory_pool_collection by returning all memory blocks,
+            /// regardless of properly deallocated back to the \concept{concept_blockallocator,BlockAllocator}.
+            ~memory_pool_collection() noexcept = default;
+
+            /// @{
+            /// \effects Moving a \ref memory_pool_collection object transfers ownership over the free lists,
+            /// i.e. the moved from pool is completely empty and the new one has all its memory.
+            /// That means that it is not allowed to call \ref deallocate_node() on a moved-from allocator
+            /// even when passing it memory that was previously allocated by this object.
+            memory_pool_collection(memory_pool_collection&& other) noexcept
+            : leak_checker(detail::move(other)),
+              arena_(detail::move(other.arena_)),
+              stack_(detail::move(other.stack_)),
+              pools_(detail::move(other.pools_))
+            {
+            }
+
+            memory_pool_collection& operator=(memory_pool_collection&& other) noexcept
+            {
+                leak_checker::operator=(detail::move(other));
+                arena_                = detail::move(other.arena_);
+                stack_                = detail::move(other.stack_);
+                pools_                = detail::move(other.pools_);
+                return *this;
+            }
+            /// @}
+
+            /// \effects Allocates a \concept{concept_node,node} of given size.
+            /// It first finds the appropriate free list as defined in the \c BucketDistribution.
+            /// If it is empty, it will use an implementation defined amount of memory from the arena
+            /// and inserts it in it.
+            /// If the arena is empty too, it will request a new memory block from the \concept{concept_blockallocator,BlockAllocator}
+            /// of size \ref next_capacity() and puts part of it onto this free list.
+            /// Then it removes a node from it.
+            /// \returns A \concept{concept_node,node} of given size suitable aligned,
+            /// i.e. suitable for any type where <tt>sizeof(T) < node_size</tt>.
+            /// \throws Anything thrown by the \concept{concept_blockallocator,BlockAllocator} if a growth is needed or a \ref bad_node_size exception if the node size is too big.
+            void* allocate_node(std::size_t node_size)
+            {
+                detail::check_allocation_size<bad_node_size>(
+                    node_size, [&] { return max_node_size(); }, info());
+                auto& pool = pools_.get(node_size);
+                if (pool.empty())
+                {
+                    auto block = reserve_memory(pool, def_capacity());
+                    pool.insert(block.memory, block.size);
+                }
+
+                auto mem = pool.allocate();
+                WPI_MEMORY_ASSERT(mem);
+                return mem;
+            }
+
+            /// \effects Allocates a \concept{concept_node,node} of given size.
+            /// It is similar to \ref allocate_node() but will return `nullptr` on any failure,
+            /// instead of growing the arnea and possibly throwing.
+            /// \returns A \concept{concept_node,node} of given size suitable aligned
+            /// or `nullptr` in case of failure.
+            void* try_allocate_node(std::size_t node_size) noexcept
+            {
+                if (node_size > max_node_size())
+                    return nullptr;
+                auto& pool = pools_.get(node_size);
+                if (pool.empty())
+                {
+                    try_reserve_memory(pool, def_capacity());
+                    return pool.empty() ? nullptr : pool.allocate();
+                }
+                else
+                    return pool.allocate();
+            }
+
+            /// \effects Allocates an \concept{concept_array,array} of nodes by searching for \c n continuous nodes on the appropriate free list and removing them.
+            /// Depending on the \c PoolType this can be a slow operation or not allowed at all.
+            /// This can sometimes lead to a growth on the free list, even if technically there is enough continuous memory on the free list.
+            /// Otherwise has the same behavior as \ref allocate_node().
+            /// \returns An array of \c n nodes of size \c node_size suitable aligned.
+            /// \throws Anything thrown by the used \concept{concept_blockallocator,BlockAllocator}'s allocation function if a growth is needed,
+            /// or a \ref bad_allocation_size exception.
+            /// \requires \c count must be valid \concept{concept_array,array count} and
+            /// \c node_size must be valid \concept{concept_node,node size}.
+            void* allocate_array(std::size_t count, std::size_t node_size)
+            {
+                detail::check_allocation_size<bad_node_size>(
+                    node_size, [&] { return max_node_size(); }, info());
+
+                auto& pool = pools_.get(node_size);
+
+                // try allocating if not empty
+                // for pools without array allocation support, allocate() will always return nullptr
+                auto mem = pool.empty() ? nullptr : pool.allocate(count * node_size);
+                if (!mem)
+                {
+                    // reserve more memory
+                    auto block = reserve_memory(pool, def_capacity());
+                    pool.insert(block.memory, block.size);
+
+                    mem = pool.allocate(count * node_size);
+                    if (!mem)
+                    {
+                        // reserve more then the default capacity if that didn't work either
+                        detail::check_allocation_size<bad_array_size>(
+                            count * node_size,
+                            [&] { return next_capacity() - pool.alignment() + 1; }, info());
+
+                        block = reserve_memory(pool, count * node_size);
+                        pool.insert(block.memory, block.size);
+
+                        mem = pool.allocate(count * node_size);
+                        WPI_MEMORY_ASSERT(mem);
+                    }
+                }
+
+                return mem;
+            }
+
+            /// \effects Allocates a \concept{concept_array,array} of given size.
+            /// It is similar to \ref allocate_node() but will return `nullptr` on any failure,
+            /// instead of growing the arnea and possibly throwing.
+            /// \returns A \concept{concept_array,array} of given size suitable aligned
+            /// or `nullptr` in case of failure.
+            void* try_allocate_array(std::size_t count, std::size_t node_size) noexcept
+            {
+                if (!pool_type::value || node_size > max_node_size())
+                    return nullptr;
+                auto& pool = pools_.get(node_size);
+                if (pool.empty())
+                {
+                    try_reserve_memory(pool, def_capacity());
+                    return pool.empty() ? nullptr : pool.allocate(count * node_size);
+                }
+                else
+                    return pool.allocate(count * node_size);
+            }
+
+            /// \effects Deallocates a \concept{concept_node,node} by putting it back onto the appropriate free list.
+            /// \requires \c ptr must be a result from a previous call to \ref allocate_node() with the same size on the same free list,
+            /// i.e. either this allocator object or a new object created by moving this to it.
+            void deallocate_node(void* ptr, std::size_t node_size) noexcept
+            {
+                pools_.get(node_size).deallocate(ptr);
+            }
+
+            /// \effects Deallocates a \concept{concept_node,node} similar to \ref deallocate_node().
+            /// But it checks if it can deallocate this memory.
+            /// \returns `true` if the node could be deallocated,
+            /// `false` otherwise.
+            bool try_deallocate_node(void* ptr, std::size_t node_size) noexcept
+            {
+                if (node_size > max_node_size() || !arena_.owns(ptr))
+                    return false;
+                pools_.get(node_size).deallocate(ptr);
+                return true;
+            }
+
+            /// \effects Deallocates an \concept{concept_array,array} by putting it back onto the free list.
+            /// \requires \c ptr must be a result from a previous call to \ref allocate_array() with the same sizes on the same free list,
+            /// i.e. either this allocator object or a new object created by moving this to it.
+            void deallocate_array(void* ptr, std::size_t count, std::size_t node_size) noexcept
+            {
+                pools_.get(node_size).deallocate(ptr, count * node_size);
+            }
+
+            /// \effects Deallocates a \concept{concept_array,array} similar to \ref deallocate_array().
+            /// But it checks if it can deallocate this memory.
+            /// \returns `true` if the array could be deallocated,
+            /// `false` otherwise.
+            bool try_deallocate_array(void* ptr, std::size_t count, std::size_t node_size) noexcept
+            {
+                if (!pool_type::value || node_size > max_node_size() || !arena_.owns(ptr))
+                    return false;
+                pools_.get(node_size).deallocate(ptr, count * node_size);
+                return true;
+            }
+
+            /// \effects Inserts more memory on the free list for nodes of given size.
+            /// It will try to put \c capacity_left bytes from the arena onto the free list defined over the \c BucketDistribution,
+            /// if the arena is empty, a new memory block is requested from the \concept{concept_blockallocator,BlockAllocator}
+            /// and it will be used.
+            /// \throws Anything thrown by the \concept{concept_blockallocator,BlockAllocator} if a growth is needed.
+            /// \requires \c node_size must be valid \concept{concept_node,node size} less than or equal to \ref max_node_size(),
+            /// \c capacity_left must be less than \ref next_capacity().
+            void reserve(std::size_t node_size, std::size_t capacity)
+            {
+                WPI_MEMORY_ASSERT_MSG(node_size <= max_node_size(), "node_size too big");
+                auto& pool = pools_.get(node_size);
+                reserve_memory(pool, capacity);
+            }
+
+            /// \returns The maximum node size for which is a free list.
+            /// This is the value passed to it in the constructor.
+            std::size_t max_node_size() const noexcept
+            {
+                return pools_.max_node_size();
+            }
+
+            /// \returns The amount of nodes available in the free list for nodes of given size
+            /// as defined over the \c BucketDistribution.
+            /// This is the number of nodes that can be allocated without the free list requesting more memory from the arena.
+            /// \note Array allocations may lead to a growth even if the capacity_left is big enough.
+            std::size_t pool_capacity_left(std::size_t node_size) const noexcept
+            {
+                WPI_MEMORY_ASSERT_MSG(node_size <= max_node_size(), "node_size too big");
+                return pools_.get(node_size).capacity();
+            }
+
+            /// \returns The amount of memory available in the arena not inside the free lists.
+            /// This is the number of bytes that can be inserted into the free lists
+            /// without requesting more memory from the \concept{concept_blockallocator,BlockAllocator}.
+            /// \note Array allocations may lead to a growth even if the capacity is big enough.
+            std::size_t capacity_left() const noexcept
+            {
+                return std::size_t(block_end() - stack_.top());
+            }
+
+            /// \returns The size of the next memory block after \ref capacity_left() arena grows.
+            /// This is the amount of memory that can be distributed in the pools.
+            /// \note If the `PoolType` is \ref small_node_pool, the exact usable memory is lower than that.
+            std::size_t next_capacity() const noexcept
+            {
+                return arena_.next_block_size();
+            }
+
+            /// \returns A reference to the \concept{concept_blockallocator,BlockAllocator} used for managing the arena.
+            /// \requires It is undefined behavior to move this allocator out into another object.
+            allocator_type& get_allocator() noexcept
+            {
+                return arena_.get_allocator();
+            }
+
+        private:
+            allocator_info info() const noexcept
+            {
+                return {WPI_MEMORY_LOG_PREFIX "::memory_pool_collection", this};
+            }
+
+            std::size_t def_capacity() const noexcept
+            {
+                return arena_.next_block_size() / pools_.size();
+            }
+
+            detail::fixed_memory_stack allocate_block()
+            {
+                return detail::fixed_memory_stack(arena_.allocate_block().memory);
+            }
+
+            const char* block_end() const noexcept
+            {
+                auto block = arena_.current_block();
+                return static_cast<const char*>(block.memory) + block.size;
+            }
+
+            bool insert_rest(typename pool_type::type& pool) noexcept
+            {
+                if (auto remaining = std::size_t(block_end() - stack_.top()))
+                {
+                    auto offset = detail::align_offset(stack_.top(), detail::max_alignment);
+                    if (offset < remaining)
+                    {
+                        detail::debug_fill(stack_.top(), offset, debug_magic::alignment_memory);
+                        pool.insert(stack_.top() + offset, remaining - offset);
+                        return true;
+                    }
+                }
+
+                return false;
+            }
+
+            void try_reserve_memory(typename pool_type::type& pool, std::size_t capacity) noexcept
+            {
+                auto mem = stack_.allocate(block_end(), capacity, detail::max_alignment);
+                if (!mem)
+                    insert_rest(pool);
+                else
+                    pool.insert(mem, capacity);
+            }
+
+            memory_block reserve_memory(typename pool_type::type& pool, std::size_t capacity)
+            {
+                auto mem = stack_.allocate(block_end(), capacity, detail::max_alignment);
+                if (!mem)
+                {
+                    insert_rest(pool);
+                    // get new block
+                    stack_ = allocate_block();
+
+                    // allocate ensuring alignment
+                    mem = stack_.allocate(block_end(), capacity, detail::max_alignment);
+                    WPI_MEMORY_ASSERT(mem);
+                }
+                return {mem, capacity};
+            }
+
+            memory_arena<allocator_type, false> arena_;
+            detail::fixed_memory_stack          stack_;
+            free_list_array                     pools_;
+
+            friend allocator_traits<memory_pool_collection>;
+        };
+
+#if WPI_MEMORY_EXTERN_TEMPLATE
+        extern template class memory_pool_collection<node_pool, identity_buckets>;
+        extern template class memory_pool_collection<array_pool, identity_buckets>;
+        extern template class memory_pool_collection<small_node_pool, identity_buckets>;
+
+        extern template class memory_pool_collection<node_pool, log2_buckets>;
+        extern template class memory_pool_collection<array_pool, log2_buckets>;
+        extern template class memory_pool_collection<small_node_pool, log2_buckets>;
+#endif
+
+        /// An alias for \ref memory_pool_collection using the \ref identity_buckets policy
+        /// and a \c PoolType defaulting to \ref node_pool.
+        /// \ingroup allocator
+        template <class PoolType = node_pool, class ImplAllocator = default_allocator>
+        WPI_ALIAS_TEMPLATE(bucket_allocator,
+                                 memory_pool_collection<PoolType, identity_buckets, ImplAllocator>);
+
+        template <class Allocator>
+        class allocator_traits;
+
+        /// Specialization of the \ref allocator_traits for \ref memory_pool_collection classes.
+        /// \note It is not allowed to mix calls through the specialization and through the member functions,
+        /// i.e. \ref memory_pool_collection::allocate_node() and this \c allocate_node().
+        /// \ingroup allocator
+        template <class Pool, class BucketDist, class RawAllocator>
+        class allocator_traits<memory_pool_collection<Pool, BucketDist, RawAllocator>>
+        {
+        public:
+            using allocator_type = memory_pool_collection<Pool, BucketDist, RawAllocator>;
+            using is_stateful    = std::true_type;
+
+            /// \returns The result of \ref memory_pool_collection::allocate_node().
+            /// \throws Anything thrown by the pool allocation function
+            /// or a \ref bad_allocation_size exception if \c size / \c alignment exceeds \ref max_node_size() / the suitable alignment value,
+            /// i.e. the node is over-aligned.
+            static void* allocate_node(allocator_type& state, std::size_t size,
+                                       std::size_t alignment)
+            {
+                // node already checked
+                detail::check_allocation_size<bad_alignment>(
+                    alignment, [&] { return detail::alignment_for(size); }, state.info());
+                auto mem = state.allocate_node(size);
+                state.on_allocate(size);
+                return mem;
+            }
+
+            /// \returns The result of \ref memory_pool_collection::allocate_array().
+            /// \throws Anything thrown by the pool allocation function or a \ref bad_allocation_size exception.
+            /// \requires The \ref memory_pool_collection has to support array allocations.
+            static void* allocate_array(allocator_type& state, std::size_t count, std::size_t size,
+                                        std::size_t alignment)
+            {
+                // node and array already checked
+                detail::check_allocation_size<bad_alignment>(
+                    alignment, [&] { return detail::alignment_for(size); }, state.info());
+                auto mem = state.allocate_array(count, size);
+                state.on_allocate(count * size);
+                return mem;
+            }
+
+            /// \effects Calls \ref memory_pool_collection::deallocate_node().
+            static void deallocate_node(allocator_type& state, void* node, std::size_t size,
+                                        std::size_t) noexcept
+            {
+                state.deallocate_node(node, size);
+                state.on_deallocate(size);
+            }
+
+            /// \effects Calls \ref memory_pool_collection::deallocate_array().
+            /// \requires The \ref memory_pool_collection has to support array allocations.
+            static void deallocate_array(allocator_type& state, void* array, std::size_t count,
+                                         std::size_t size, std::size_t) noexcept
+            {
+                state.deallocate_array(array, count, size);
+                state.on_deallocate(count * size);
+            }
+
+            /// \returns The maximum size of each node which is \ref memory_pool_collection::max_node_size().
+            static std::size_t max_node_size(const allocator_type& state) noexcept
+            {
+                return state.max_node_size();
+            }
+
+            /// \returns An upper bound on the maximum array size which is \ref memory_pool::next_capacity().
+            static std::size_t max_array_size(const allocator_type& state) noexcept
+            {
+                return state.next_capacity();
+            }
+
+            /// \returns Just \c alignof(std::max_align_t) since the actual maximum alignment depends on the node size,
+            /// the nodes must not be over-aligned.
+            static std::size_t max_alignment(const allocator_type&) noexcept
+            {
+                return detail::max_alignment;
+            }
+        };
+
+        /// Specialization of the \ref composable_allocator_traits for \ref memory_pool_collection classes.
+        /// \ingroup allocator
+        template <class Pool, class BucketDist, class RawAllocator>
+        class composable_allocator_traits<memory_pool_collection<Pool, BucketDist, RawAllocator>>
+        {
+            using traits = allocator_traits<memory_pool_collection<Pool, BucketDist, RawAllocator>>;
+
+        public:
+            using allocator_type = memory_pool_collection<Pool, BucketDist, RawAllocator>;
+
+            /// \returns The result of \ref memory_pool_collection::try_allocate_node()
+            /// or `nullptr` if the allocation size was too big.
+            static void* try_allocate_node(allocator_type& state, std::size_t size,
+                                           std::size_t alignment) noexcept
+            {
+                if (alignment > traits::max_alignment(state))
+                    return nullptr;
+                return state.try_allocate_node(size);
+            }
+
+            /// \returns The result of \ref memory_pool_collection::try_allocate_array()
+            /// or `nullptr` if the allocation size was too big.
+            static void* try_allocate_array(allocator_type& state, std::size_t count,
+                                            std::size_t size, std::size_t alignment) noexcept
+            {
+                if (count * size > traits::max_array_size(state)
+                    || alignment > traits::max_alignment(state))
+                    return nullptr;
+                return state.try_allocate_array(count, size);
+            }
+
+            /// \effects Just forwards to \ref memory_pool_collection::try_deallocate_node().
+            /// \returns Whether the deallocation was successful.
+            static bool try_deallocate_node(allocator_type& state, void* node, std::size_t size,
+                                            std::size_t alignment) noexcept
+            {
+                if (alignment > traits::max_alignment(state))
+                    return false;
+                return state.try_deallocate_node(node, size);
+            }
+
+            /// \effects Forwards to \ref memory_pool_collection::deallocate_array().
+            /// \returns Whether the deallocation was successful.
+            static bool try_deallocate_array(allocator_type& state, void* array, std::size_t count,
+                                             std::size_t size, std::size_t alignment) noexcept
+            {
+                if (count * size > traits::max_array_size(state)
+                    || alignment > traits::max_alignment(state))
+                    return false;
+                return state.try_deallocate_array(array, count, size);
+            }
+        };
+
+#if WPI_MEMORY_EXTERN_TEMPLATE
+        extern template class allocator_traits<memory_pool_collection<node_pool, identity_buckets>>;
+        extern template class allocator_traits<
+            memory_pool_collection<array_pool, identity_buckets>>;
+        extern template class allocator_traits<
+            memory_pool_collection<small_node_pool, identity_buckets>>;
+
+        extern template class allocator_traits<memory_pool_collection<node_pool, log2_buckets>>;
+        extern template class allocator_traits<memory_pool_collection<array_pool, log2_buckets>>;
+        extern template class allocator_traits<
+            memory_pool_collection<small_node_pool, log2_buckets>>;
+
+        extern template class composable_allocator_traits<
+            memory_pool_collection<node_pool, identity_buckets>>;
+        extern template class composable_allocator_traits<
+            memory_pool_collection<array_pool, identity_buckets>>;
+        extern template class composable_allocator_traits<
+            memory_pool_collection<small_node_pool, identity_buckets>>;
+
+        extern template class composable_allocator_traits<
+            memory_pool_collection<node_pool, log2_buckets>>;
+        extern template class composable_allocator_traits<
+            memory_pool_collection<array_pool, log2_buckets>>;
+        extern template class composable_allocator_traits<
+            memory_pool_collection<small_node_pool, log2_buckets>>;
+#endif
+    } // namespace memory
+} // namespace wpi
+
+#endif // WPI_MEMORY_MEMORY_POOL_COLLECTION_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/memory_pool_type.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/memory_pool_type.hpp
new file mode 100644
index 0000000..a7c8ff8
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/memory_pool_type.hpp
@@ -0,0 +1,53 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_MEMORY_POOL_TYPE_HPP_INCLUDED
+#define WPI_MEMORY_MEMORY_POOL_TYPE_HPP_INCLUDED
+
+/// \file
+/// The \c PoolType tag types.
+
+#include <type_traits>
+
+#include "detail/free_list.hpp"
+#include "detail/small_free_list.hpp"
+#include "config.hpp"
+
+namespace wpi
+{
+    namespace memory
+    {
+        /// Tag type defining a memory pool optimized for nodes.
+        /// It does not support array allocations that great and may trigger a growth even if there is enough memory.
+        /// But it is the fastest pool type.
+        /// \ingroup allocator
+        struct node_pool : WPI_EBO(std::true_type)
+        {
+            using type = detail::node_free_memory_list;
+        };
+
+        /// Tag type defining a memory pool optimized for arrays.
+        /// It keeps the nodes oredered inside the free list and searches the list for an appropriate memory block.
+        /// Array allocations are still pretty slow, if the array gets big enough it can get slower than \c new.
+        /// Node allocations are still fast, unless there is deallocation in random order.
+        /// \note Use this tag type only if you really need to have a memory pool!
+        /// \ingroup allocator
+        struct array_pool : WPI_EBO(std::true_type)
+        {
+            using type = detail::array_free_memory_list;
+        };
+
+        /// Tag type defining a memory pool optimized for small nodes.
+        /// The free list is intrusive and thus requires that each node has at least the size of a pointer.
+        /// This tag type does not have this requirement and thus allows zero-memory-overhead allocations of small nodes.
+        /// It is a little bit slower than \ref node_pool and does not support arrays.
+        /// \ingroup allocator
+        struct small_node_pool : WPI_EBO(std::false_type)
+        {
+            using type = detail::small_free_memory_list;
+        };
+    } // namespace memory
+} // namespace wpi
+
+#endif // WPI_MEMORY_MEMORY_POOL_TYPE_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/memory_resource_adapter.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/memory_resource_adapter.hpp
new file mode 100644
index 0000000..e805f9b
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/memory_resource_adapter.hpp
@@ -0,0 +1,239 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_MEMORY_RESOURCE_ADAPTER_HPP_INCLUDED
+#define WPI_MEMORY_MEMORY_RESOURCE_ADAPTER_HPP_INCLUDED
+
+/// \file
+/// Class \ref wpi::memory::memory_resource_adapter and \ref wpi::memory::memory_resource_allocator to allow usage of PMRs.
+
+#include "detail/assert.hpp"
+#include "detail/utility.hpp"
+#include "config.hpp"
+#include "allocator_traits.hpp"
+
+#if defined(__has_include) && __has_include(<memory_resource>)
+
+#if !defined(__GNUC__) || __cplusplus >= 201703L
+// The experimental/memory_resource header lacks a check for C++17 on older GCC,
+// so we have to do it for them.
+#include <memory_resource>
+#endif
+
+#elif defined(__has_include) && __has_include(<experimental/memory_resource>)
+
+#if !defined(__GNUC__) || __cplusplus >= 201402L
+// The experimental/memory_resource header lacks a check for C++14 on older GCC,
+// so we have to do it for them.
+#include <experimental/memory_resource>
+#endif
+
+#endif
+
+#if defined(__cpp_lib_memory_resource)
+
+// We use std::pmr::memory_resource.
+namespace wpi_memory_pmr = std::pmr;
+
+#elif defined(__cpp_lib_experimental_memory_resources)
+
+// We use std::experimental::pmr::memory_resource.
+namespace wpi_memory_pmr = std::experimental::pmr;
+
+#else
+
+// We use our own implementation.
+namespace wpi_memory_pmr
+{
+    // see N3916 for documentation
+    class memory_resource
+    {
+        static const std::size_t max_alignment = alignof(std::max_align_t);
+
+    public:
+        virtual ~memory_resource() noexcept {}
+        void* allocate(std::size_t bytes, std::size_t alignment = max_alignment)
+        {
+            return do_allocate(bytes, alignment);
+        }
+        void deallocate(void* p, std::size_t bytes, std::size_t alignment = max_alignment)
+        {
+            do_deallocate(p, bytes, alignment);
+        }
+        bool is_equal(const memory_resource& other) const noexcept
+        {
+            return do_is_equal(other);
+        }
+
+    protected:
+        virtual void* do_allocate(std::size_t bytes, std::size_t alignment)            = 0;
+        virtual void  do_deallocate(void* p, std::size_t bytes, std::size_t alignment) = 0;
+        virtual bool  do_is_equal(const memory_resource& other) const noexcept         = 0;
+    };
+    inline bool operator==(const memory_resource& a, const memory_resource& b) noexcept
+    {
+        return &a == &b || a.is_equal(b);
+    }
+    inline bool operator!=(const memory_resource& a, const memory_resource& b) noexcept
+    {
+        return !(a == b);
+    }
+} // namespace wpi_memory_pmr
+
+#endif
+
+namespace wpi
+{
+    namespace memory
+    {
+        /// The \c memory_resource abstract base class used in the implementation.
+        /// \ingroup adapter
+        WPI_ALIAS_TEMPLATE(memory_resource, foonathan_memory_pmr::memory_resource);
+
+        /// Wraps a \concept{concept_rawallocator,RawAllocator} and makes it a \ref memory_resource.
+        /// \ingroup adapter
+        template <class RawAllocator>
+        class memory_resource_adapter
+        : public memory_resource,
+          WPI_EBO(allocator_traits<RawAllocator>::allocator_type)
+        {
+        public:
+            using allocator_type = typename allocator_traits<RawAllocator>::allocator_type;
+
+            /// \effects Creates the resource by moving in the allocator.
+            memory_resource_adapter(allocator_type&& other) noexcept
+            : allocator_type(detail::move(other))
+            {
+            }
+
+            /// @{
+            /// \returns A reference to the wrapped allocator.
+            allocator_type& get_allocator() noexcept
+            {
+                return *this;
+            }
+
+            const allocator_type& get_allocator() const noexcept
+            {
+                return *this;
+            }
+            /// @}
+
+        protected:
+            using traits_type = allocator_traits<RawAllocator>;
+
+            /// \effects Allocates raw memory with given size and alignment.
+            /// It forwards to \c allocate_node() or \c allocate_array() depending on the size.
+            /// \returns The new memory as returned by the \concept{concept_rawallocator,RawAllocator}.
+            /// \throws Anything thrown by the allocation function.
+            void* do_allocate(std::size_t bytes, std::size_t alignment) override
+            {
+                auto max = traits_type::max_node_size(*this);
+                if (bytes <= max)
+                    return traits_type::allocate_node(*this, bytes, alignment);
+                auto div = bytes / max;
+                auto mod = bytes % max;
+                auto n   = div + (mod != 0);
+                return traits_type::allocate_array(*this, n, max, alignment);
+            }
+
+            /// \effects Deallocates memory previously allocated by \ref do_allocate.
+            /// It forwards to \c deallocate_node() or \c deallocate_array() depending on the size.
+            /// \throws Nothing.
+            void do_deallocate(void* p, std::size_t bytes, std::size_t alignment) override
+            {
+                auto max = traits_type::max_node_size(*this);
+                if (bytes <= max)
+                    traits_type::deallocate_node(*this, p, bytes, alignment);
+                else
+                {
+                    auto div = bytes / max;
+                    auto mod = bytes % max;
+                    auto n   = div + (mod != 0);
+                    traits_type::deallocate_array(*this, p, n, max, alignment);
+                }
+            }
+
+            /// \returns Whether or not \c *this is equal to \c other
+            /// by comparing the addresses.
+            bool do_is_equal(const memory_resource& other) const noexcept override
+            {
+                return this == &other;
+            }
+        };
+
+        /// Wraps a \ref memory_resource and makes it a \concept{concept_rawallocator,RawAllocator}.
+        /// \ingroup adapter
+        class memory_resource_allocator
+        {
+        public:
+            /// \effects Creates it by giving it a pointer to the \ref memory_resource.
+            /// \requires \c ptr must not be \c nullptr.
+            memory_resource_allocator(memory_resource* ptr) noexcept : ptr_(ptr)
+            {
+                WPI_MEMORY_ASSERT(ptr);
+            }
+
+            /// \effects Allocates a node by forwarding to the \c allocate() function.
+            /// \returns The node as returned by the \ref memory_resource.
+            /// \throws Anything thrown by the \c allocate() function.
+            void* allocate_node(std::size_t size, std::size_t alignment)
+            {
+                return ptr_->allocate(size, alignment);
+            }
+
+            /// \effects Deallocates a node by forwarding to the \c deallocate() function.
+            void deallocate_node(void* ptr, std::size_t size, std::size_t alignment) noexcept
+            {
+                ptr_->deallocate(ptr, size, alignment);
+            }
+
+            /// \returns The maximum alignment which is the maximum value of type \c std::size_t.
+            std::size_t max_alignment() const noexcept
+            {
+                return std::size_t(-1);
+            }
+
+            /// \returns A pointer to the used \ref memory_resource, this is never \c nullptr.
+            memory_resource* resource() const noexcept
+            {
+                return ptr_;
+            }
+
+        private:
+            memory_resource* ptr_;
+        };
+
+        /// @{
+        /// \returns Whether `lhs` and `rhs` share the same resource.
+        /// \relates memory_resource_allocator
+        inline bool operator==(const memory_resource_allocator& lhs,
+                               const memory_resource_allocator& rhs) noexcept
+        {
+            return lhs.resource() == rhs.resource();
+        }
+
+        inline bool operator!=(const memory_resource_allocator& lhs,
+                               const memory_resource_allocator& rhs) noexcept
+        {
+            return !(lhs == rhs);
+        }
+        /// @}
+
+#if !defined(DOXYGEN)
+        template <class RawAllocator>
+        struct is_shared_allocator;
+#endif
+
+        /// Specialization of \ref is_shared_allocator to mark \ref memory_resource_allocator as shared.
+        /// This allows using it as \ref allocator_reference directly.
+        /// \ingroup adapter
+        template <>
+        struct is_shared_allocator<memory_resource_allocator> : std::true_type
+        {
+        };
+    } // namespace memory
+} // namespace wpi
+
+#endif // WPI_MEMORY_MEMORY_RESOURCE_ADAPTER_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/memory_stack.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/memory_stack.hpp
new file mode 100644
index 0000000..4c9f524
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/memory_stack.hpp
@@ -0,0 +1,489 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_MEMORY_STACK_HPP_INCLUDED
+#define WPI_MEMORY_MEMORY_STACK_HPP_INCLUDED
+
+/// \file
+/// Class \ref wpi::memory::memory_stack and its \ref wpi::memory::allocator_traits specialization.
+
+// Inform that wpi::memory::memory_stack::min_block_size API is available
+#define WPI_MEMORY_MEMORY_STACK_HAS_MIN_BLOCK_SIZE
+
+#include <cstdint>
+#include <type_traits>
+
+#include "detail/assert.hpp"
+#include "detail/memory_stack.hpp"
+#include "config.hpp"
+#include "error.hpp"
+#include "memory_arena.hpp"
+
+namespace wpi
+{
+    namespace memory
+    {
+#if !defined(DOXYGEN)
+        template <class Impl>
+        class memory_stack;
+#endif
+
+        namespace detail
+        {
+            class stack_marker
+            {
+                std::size_t index;
+                char*       top;
+                const char* end;
+
+                stack_marker(std::size_t i, const detail::fixed_memory_stack& s,
+                             const char* e) noexcept
+                : index(i), top(s.top()), end(e)
+                {
+                }
+
+                friend bool operator==(const stack_marker& lhs, const stack_marker& rhs) noexcept
+                {
+                    if (lhs.index != rhs.index)
+                        return false;
+                    WPI_MEMORY_ASSERT_MSG(lhs.end == rhs.end, "you must not compare two "
+                                                                    "stack markers from different "
+                                                                    "stacks");
+                    return lhs.top == rhs.top;
+                }
+
+                friend bool operator!=(const stack_marker& lhs, const stack_marker& rhs) noexcept
+                {
+                    return !(rhs == lhs);
+                }
+
+                friend bool operator<(const stack_marker& lhs, const stack_marker& rhs) noexcept
+                {
+                    if (lhs.index != rhs.index)
+                        return lhs.index < rhs.index;
+                    WPI_MEMORY_ASSERT_MSG(lhs.end == rhs.end, "you must not compare two "
+                                                                    "stack markers from different "
+                                                                    "stacks");
+                    return lhs.top < rhs.top;
+                }
+
+                friend bool operator>(const stack_marker& lhs, const stack_marker& rhs) noexcept
+                {
+                    return rhs < lhs;
+                }
+
+                friend bool operator<=(const stack_marker& lhs, const stack_marker& rhs) noexcept
+                {
+                    return !(rhs < lhs);
+                }
+
+                friend bool operator>=(const stack_marker& lhs, const stack_marker& rhs) noexcept
+                {
+                    return !(lhs < rhs);
+                }
+
+                template <class Impl>
+                friend class memory::memory_stack;
+            };
+
+            struct memory_stack_leak_handler
+            {
+                void operator()(std::ptrdiff_t amount);
+            };
+        } // namespace detail
+
+        /// A stateful \concept{concept_rawallocator,RawAllocator} that provides stack-like (LIFO) allocations.
+        /// It uses a \ref memory_arena with a given \c BlockOrRawAllocator defaulting to \ref growing_block_allocator to allocate huge blocks
+        /// and saves a marker to the current top.
+        /// Allocation simply moves this marker by the appropriate number of bytes and returns the pointer at the old marker position,
+        /// deallocation is not directly supported, only setting the marker to a previously queried position.
+        /// \ingroup allocator
+        template <class BlockOrRawAllocator = default_allocator>
+        class memory_stack
+        : WPI_EBO(detail::default_leak_checker<detail::memory_stack_leak_handler>)
+        {
+        public:
+            using allocator_type = make_block_allocator_t<BlockOrRawAllocator>;
+
+            /// \returns The minimum block size required for a stack containing the given amount of memory.
+            /// If a stack is created with the result of `min_block_size(n)`, the resulting capacity will be exactly `n`.
+            /// \requires `byte_size` must be a positive number.
+            /// \note Due to debug fence sizes, the actual amount of usable memory can vary.
+            /// However, this is impossible to compute without knowing the exact allocation pattern before,
+            /// so this is just a rough estimate.
+            static constexpr std::size_t min_block_size(std::size_t byte_size) noexcept
+            {
+                return detail::memory_block_stack::implementation_offset() + byte_size;
+            }
+
+            /// \effects Creates it with a given initial block size and and other constructor arguments for the \concept{concept_blockallocator,BlockAllocator}.
+            /// It will allocate the first block and sets the top to its beginning.
+            /// \requires \c block_size must be at least \c min_block_size(1).
+            template <typename... Args>
+            explicit memory_stack(std::size_t block_size, Args&&... args)
+            : arena_(block_size, detail::forward<Args>(args)...),
+              stack_(arena_.allocate_block().memory)
+            {
+            }
+
+            /// \effects Allocates a memory block of given size and alignment.
+            /// It simply moves the top marker.
+            /// If there is not enough space on the current memory block,
+            /// a new one will be allocated by the \concept{concept_blockallocator,BlockAllocator} or taken from a cache
+            /// and used for the allocation.
+            /// \returns A \concept{concept_node,node} with given size and alignment.
+            /// \throws Anything thrown by the \concept{concept_blockallocator,BlockAllocator} on growth
+            /// or \ref bad_allocation_size if \c size is too big.
+            /// \requires \c size and \c alignment must be valid.
+            void* allocate(std::size_t size, std::size_t alignment)
+            {
+                auto fence  = detail::debug_fence_size;
+                auto offset = detail::align_offset(stack_.top() + fence, alignment);
+
+                if (!stack_.top()
+                    || fence + offset + size + fence > std::size_t(block_end() - stack_.top()))
+                {
+                    // need to grow
+                    auto block = arena_.allocate_block();
+                    stack_     = detail::fixed_memory_stack(block.memory);
+
+                    // new alignment required for over-aligned types
+                    offset = detail::align_offset(stack_.top() + fence, alignment);
+
+                    auto needed = fence + offset + size + fence;
+                    detail::check_allocation_size<bad_allocation_size>(needed, block.size, info());
+                }
+
+                return stack_.allocate_unchecked(size, offset);
+            }
+
+            /// \effects Allocates a memory block of given size and alignment,
+            /// similar to \ref allocate().
+            /// But it does not attempt a growth if the arena is empty.
+            /// \returns A \concept{concept_node,node} with given size and alignment
+            /// or `nullptr` if there wasn't enough memory available.
+            void* try_allocate(std::size_t size, std::size_t alignment) noexcept
+            {
+                return stack_.allocate(block_end(), size, alignment);
+            }
+
+            /// The marker type that is used for unwinding.
+            /// The exact type is implementation defined,
+            /// it is only required that it is efficiently copyable
+            /// and has all the comparision operators defined for two markers on the same stack.
+            /// Two markers are equal, if they are copies or created from two `top()` calls without a call to `unwind()` or `allocate()`.
+            /// A marker `a` is less than marker `b`, if after `a` was obtained, there was one or more call to `allocate()` and no call to `unwind()`.
+            using marker = WPI_IMPL_DEFINED(detail::stack_marker);
+
+            /// \returns A marker to the current top of the stack.
+            marker top() const noexcept
+            {
+                return {arena_.size() - 1, stack_, block_end()};
+            }
+
+            /// \effects Unwinds the stack to a certain marker position.
+            /// This sets the top pointer of the stack to the position described by the marker
+            /// and has the effect of deallocating all memory allocated since the marker was obtained.
+            /// If any memory blocks are unused after the operation,
+            /// they are not deallocated but put in a cache for later use,
+            /// call \ref shrink_to_fit() to actually deallocate them.
+            /// \requires The marker must point to memory that is still in use and was the whole time,
+            /// i.e. it must have been pointed below the top at all time.
+            void unwind(marker m) noexcept
+            {
+                WPI_MEMORY_ASSERT(m <= top());
+                detail::debug_check_pointer([&] { return m.index <= arena_.size() - 1; }, info(),
+                                            m.top);
+
+                if (std::size_t to_deallocate = (arena_.size() - 1) - m.index) // different index
+                {
+                    arena_.deallocate_block();
+                    for (std::size_t i = 1; i != to_deallocate; ++i)
+                        arena_.deallocate_block();
+
+                    detail::debug_check_pointer(
+                        [&] {
+                            auto cur = arena_.current_block();
+                            return m.end == static_cast<char*>(cur.memory) + cur.size;
+                        },
+                        info(), m.top);
+
+                    // mark memory from new top to end of the block as freed
+                    detail::debug_fill_free(m.top, std::size_t(m.end - m.top), 0);
+                    stack_ = detail::fixed_memory_stack(m.top);
+                }
+                else // same index
+                {
+                    detail::debug_check_pointer([&] { return stack_.top() >= m.top; }, info(),
+                                                m.top);
+                    stack_.unwind(m.top);
+                }
+            }
+
+            /// \effects \ref unwind() does not actually do any deallocation of blocks on the \concept{concept_blockallocator,BlockAllocator},
+            /// unused memory is stored in a cache for later reuse.
+            /// This function clears that cache.
+            void shrink_to_fit() noexcept
+            {
+                arena_.shrink_to_fit();
+            }
+
+            /// \returns The amount of memory remaining in the current block.
+            /// This is the number of bytes that are available for allocation
+            /// before the cache or \concept{concept_blockallocator,BlockAllocator} needs to be used.
+            std::size_t capacity_left() const noexcept
+            {
+                return std::size_t(block_end() - stack_.top());
+            }
+
+            /// \returns The size of the next memory block after the current block is exhausted and the arena grows.
+            /// This function just forwards to the \ref memory_arena.
+            /// \note All of it is available for the stack to use, but due to fences and alignment buffers,
+            /// this may not be the exact amount of memory usable for the user.
+            std::size_t next_capacity() const noexcept
+            {
+                return arena_.next_block_size();
+            }
+
+            /// \returns A reference to the \concept{concept_blockallocator,BlockAllocator} used for managing the arena.
+            /// \requires It is undefined behavior to move this allocator out into another object.
+            allocator_type& get_allocator() noexcept
+            {
+                return arena_.get_allocator();
+            }
+
+        private:
+            allocator_info info() const noexcept
+            {
+                return {WPI_MEMORY_LOG_PREFIX "::memory_stack", this};
+            }
+
+            const char* block_end() const noexcept
+            {
+                auto block = arena_.current_block();
+                return static_cast<const char*>(block.memory) + block.size;
+            }
+
+            memory_arena<allocator_type> arena_;
+            detail::fixed_memory_stack   stack_;
+
+            friend allocator_traits<memory_stack<BlockOrRawAllocator>>;
+            friend composable_allocator_traits<memory_stack<BlockOrRawAllocator>>;
+        };
+
+        /// Simple utility that automatically unwinds a `Stack` to a previously saved location.
+        /// A `Stack` is anything that provides a `marker`, a `top()` function returning a `marker`
+        /// and an `unwind()` function to unwind to a `marker`,
+        /// like a \ref wpi::memory::memory_stack
+        /// \ingroup allocator
+        template <class Stack = memory_stack<>>
+        class memory_stack_raii_unwind
+        {
+        public:
+            using stack_type  = Stack;
+            using marker_type = typename stack_type::marker;
+
+            /// \effects Same as `memory_stack_raii_unwind(stack, stack.top())`.
+            explicit memory_stack_raii_unwind(stack_type& stack) noexcept
+            : memory_stack_raii_unwind(stack, stack.top())
+            {
+            }
+
+            /// \effects Creates the unwinder by giving it the stack and the marker.
+            /// \requires The stack must live longer than this object.
+            memory_stack_raii_unwind(stack_type& stack, marker_type marker) noexcept
+            : marker_(marker), stack_(&stack)
+            {
+            }
+
+            /// \effects Move constructs the unwinder by taking the saved position from `other`.
+            /// `other.will_unwind()` will return `false` after it.
+            memory_stack_raii_unwind(memory_stack_raii_unwind&& other) noexcept
+            : marker_(other.marker_), stack_(other.stack_)
+            {
+                other.stack_ = nullptr;
+            }
+
+            /// \effects Unwinds to the previously saved location,
+            /// if there is any, by calling `unwind()`.
+            ~memory_stack_raii_unwind() noexcept
+            {
+                if (stack_)
+                    stack_->unwind(marker_);
+            }
+
+            /// \effects Move assigns the unwinder by taking the saved position from `other`.
+            /// `other.will_unwind()` will return `false` after it.
+            memory_stack_raii_unwind& operator=(memory_stack_raii_unwind&& other) noexcept
+            {
+                if (stack_)
+                    stack_->unwind(marker_);
+
+                marker_ = other.marker_;
+                stack_  = other.stack_;
+
+                other.stack_ = nullptr;
+
+                return *this;
+            }
+
+            /// \effects Removes the location without unwinding it.
+            /// `will_unwind()` will return `false`.
+            void release() noexcept
+            {
+                stack_ = nullptr;
+            }
+
+            /// \effects Unwinds to the saved location explictly.
+            /// \requires `will_unwind()` must return `true`.
+            void unwind() noexcept
+            {
+                WPI_MEMORY_ASSERT(will_unwind());
+                stack_->unwind(marker_);
+            }
+
+            /// \returns Whether or not the unwinder will actually unwind.
+            /// \note It will not unwind if it is in the moved-from state.
+            bool will_unwind() const noexcept
+            {
+                return stack_ != nullptr;
+            }
+
+            /// \returns The saved marker, if there is any.
+            /// \requires `will_unwind()` must return `true`.
+            marker_type get_marker() const noexcept
+            {
+                WPI_MEMORY_ASSERT(will_unwind());
+                return marker_;
+            }
+
+            /// \returns The stack it will unwind.
+            /// \requires `will_unwind()` must return `true`.
+            stack_type& get_stack() const noexcept
+            {
+                WPI_MEMORY_ASSERT(will_unwind());
+                return *stack_;
+            }
+
+        private:
+            marker_type marker_;
+            stack_type* stack_;
+        };
+
+#if WPI_MEMORY_EXTERN_TEMPLATE
+        extern template class memory_stack<>;
+        extern template class memory_stack_raii_unwind<memory_stack<>>;
+#endif
+
+        /// Specialization of the \ref allocator_traits for \ref memory_stack classes.
+        /// \note It is not allowed to mix calls through the specialization and through the member functions,
+        /// i.e. \ref memory_stack::allocate() and this \c allocate_node().
+        /// \ingroup allocator
+        template <class BlockAllocator>
+        class allocator_traits<memory_stack<BlockAllocator>>
+        {
+        public:
+            using allocator_type = memory_stack<BlockAllocator>;
+            using is_stateful    = std::true_type;
+
+            /// \returns The result of \ref memory_stack::allocate().
+            static void* allocate_node(allocator_type& state, std::size_t size,
+                                       std::size_t alignment)
+            {
+                auto mem = state.allocate(size, alignment);
+                state.on_allocate(size);
+                return mem;
+            }
+
+            /// \returns The result of \ref memory_stack::allocate().
+            static void* allocate_array(allocator_type& state, std::size_t count, std::size_t size,
+                                        std::size_t alignment)
+            {
+                return allocate_node(state, count * size, alignment);
+            }
+
+            /// @{
+            /// \effects Does nothing besides bookmarking for leak checking, if that is enabled.
+            /// Actual deallocation can only be done via \ref memory_stack::unwind().
+            static void deallocate_node(allocator_type& state, void*, std::size_t size,
+                                        std::size_t) noexcept
+            {
+                state.on_deallocate(size);
+            }
+
+            static void deallocate_array(allocator_type& state, void* ptr, std::size_t count,
+                                         std::size_t size, std::size_t alignment) noexcept
+            {
+                deallocate_node(state, ptr, count * size, alignment);
+            }
+            /// @}
+
+            /// @{
+            /// \returns The maximum size which is \ref memory_stack::next_capacity().
+            static std::size_t max_node_size(const allocator_type& state) noexcept
+            {
+                return state.next_capacity();
+            }
+
+            static std::size_t max_array_size(const allocator_type& state) noexcept
+            {
+                return state.next_capacity();
+            }
+            /// @}
+
+            /// \returns The maximum possible value since there is no alignment restriction
+            /// (except indirectly through \ref memory_stack::next_capacity()).
+            static std::size_t max_alignment(const allocator_type&) noexcept
+            {
+                return std::size_t(-1);
+            }
+        };
+
+        /// Specialization of the \ref composable_allocator_traits for \ref memory_stack classes.
+        /// \ingroup allocator
+        template <class BlockAllocator>
+        class composable_allocator_traits<memory_stack<BlockAllocator>>
+        {
+        public:
+            using allocator_type = memory_stack<BlockAllocator>;
+
+            /// \returns The result of \ref memory_stack::try_allocate().
+            static void* try_allocate_node(allocator_type& state, std::size_t size,
+                                           std::size_t alignment) noexcept
+            {
+                return state.try_allocate(size, alignment);
+            }
+
+            /// \returns The result of \ref memory_stack::try_allocate().
+            static void* try_allocate_array(allocator_type& state, std::size_t count,
+                                            std::size_t size, std::size_t alignment) noexcept
+            {
+                return state.try_allocate(count * size, alignment);
+            }
+
+            /// @{
+            /// \effects Does nothing.
+            /// \returns Whether the memory will be deallocated by \ref memory_stack::unwind().
+            static bool try_deallocate_node(allocator_type& state, void* ptr, std::size_t,
+                                            std::size_t) noexcept
+            {
+                return state.arena_.owns(ptr);
+            }
+
+            static bool try_deallocate_array(allocator_type& state, void* ptr, std::size_t count,
+                                             std::size_t size, std::size_t alignment) noexcept
+            {
+                return try_deallocate_node(state, ptr, count * size, alignment);
+            }
+            /// @}
+        };
+
+#if WPI_MEMORY_EXTERN_TEMPLATE
+        extern template class allocator_traits<memory_stack<>>;
+        extern template class composable_allocator_traits<memory_stack<>>;
+#endif
+    } // namespace memory
+} // namespace wpi
+
+#endif // WPI_MEMORY_MEMORY_STACK_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/namespace_alias.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/namespace_alias.hpp
new file mode 100644
index 0000000..bf2b95d
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/namespace_alias.hpp
@@ -0,0 +1,37 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_NAMESPACE_ALIAS_HPP_INCLUDED
+#define WPI_MEMORY_NAMESPACE_ALIAS_HPP_INCLUDED
+
+/// \file
+/// Convenient namespace alias.
+
+/// \defgroup core Core components
+
+/// \defgroup allocator Allocator implementations
+
+/// \defgroup adapter Adapters and Wrappers
+
+/// \defgroup storage Allocator storage
+
+/// \namespace wpi
+/// Foonathan namespace.
+
+/// \namespace wpi::memory
+/// Memory namespace.
+
+/// \namespace wpi::memory::literals
+/// Literals namespace.
+
+namespace wpi
+{
+    namespace memory
+    {
+    }
+} // namespace wpi
+
+namespace memory = wpi::memory;
+
+#endif // WPI_MEMORY_NAMESPACE_ALIAS_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/new_allocator.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/new_allocator.hpp
new file mode 100644
index 0000000..8e24f2f
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/new_allocator.hpp
@@ -0,0 +1,55 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_NEW_ALLOCATOR_HPP_INCLUDED
+#define WPI_MEMORY_NEW_ALLOCATOR_HPP_INCLUDED
+
+/// \file
+/// Class \ref wpi::memory::new_allocator.
+
+#include "detail/lowlevel_allocator.hpp"
+#include "config.hpp"
+
+#if WPI_MEMORY_EXTERN_TEMPLATE
+#include "allocator_traits.hpp"
+#endif
+
+namespace wpi
+{
+    namespace memory
+    {
+        struct allocator_info;
+
+        namespace detail
+        {
+            struct new_allocator_impl
+            {
+                static allocator_info info() noexcept;
+
+                static void* allocate(std::size_t size, std::size_t) noexcept;
+
+                static void deallocate(void* ptr, std::size_t size, std::size_t) noexcept;
+
+                static std::size_t max_node_size() noexcept;
+            };
+
+            WPI_MEMORY_LL_ALLOCATOR_LEAK_CHECKER(new_allocator_impl,
+                                                       new_alloator_leak_checker)
+        } // namespace detail
+
+        /// A stateless \concept{concept_rawallocator,RawAllocator} that allocates memory using (nothrow) <tt>operator new</tt>.
+        /// If the operator returns \c nullptr, it behaves like \c new and loops calling \c std::new_handler,
+        /// but instead of throwing a \c std::bad_alloc exception, it throws \ref out_of_memory.
+        /// \ingroup allocator
+        using new_allocator =
+            WPI_IMPL_DEFINED(detail::lowlevel_allocator<detail::new_allocator_impl>);
+
+#if WPI_MEMORY_EXTERN_TEMPLATE
+        extern template class detail::lowlevel_allocator<detail::new_allocator_impl>;
+        extern template class allocator_traits<new_allocator>;
+#endif
+    } // namespace memory
+} // namespace wpi
+
+#endif // WPI_MEMORY_NEW_ALLOCATOR_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/segregator.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/segregator.hpp
new file mode 100644
index 0000000..fcd02ac
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/segregator.hpp
@@ -0,0 +1,448 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_SEGREGATOR_HPP_INCLUDED
+#define WPI_MEMORY_SEGREGATOR_HPP_INCLUDED
+
+/// \file
+/// Class template \ref wpi::memory::segregator and related classes.
+
+#include "detail/ebo_storage.hpp"
+#include "detail/utility.hpp"
+#include "allocator_traits.hpp"
+#include "config.hpp"
+#include "error.hpp"
+
+namespace wpi
+{
+    namespace memory
+    {
+        /// A \concept{concept_segregatable,Segregatable} that allocates until a maximum size.
+        /// \ingroup adapter
+        template <class RawAllocator>
+        class threshold_segregatable : WPI_EBO(allocator_traits<RawAllocator>::allocator_type)
+        {
+        public:
+            using allocator_type = typename allocator_traits<RawAllocator>::allocator_type;
+
+            /// \effects Creates it by passing the maximum size it will allocate
+            /// and the allocator it uses.
+            explicit threshold_segregatable(std::size_t    max_size,
+                                            allocator_type alloc = allocator_type())
+            : allocator_type(detail::move(alloc)), max_size_(max_size)
+            {
+            }
+
+            /// \returns `true` if `size` is less then or equal to the maximum size,
+            /// `false` otherwise.
+            /// \note A return value of `true` means that the allocator will be used for the allocation.
+            bool use_allocate_node(std::size_t size, std::size_t) noexcept
+            {
+                return size <= max_size_;
+            }
+
+            /// \returns `true` if `count * size` is less then or equal to the maximum size,
+            /// `false` otherwise.
+            /// \note A return value of `true` means that the allocator will be used for the allocation.
+            bool use_allocate_array(std::size_t count, std::size_t size, std::size_t) noexcept
+            {
+                return count * size <= max_size_;
+            }
+
+            /// @{
+            /// \returns A reference to the allocator it owns.
+            allocator_type& get_allocator() noexcept
+            {
+                return *this;
+            }
+
+            const allocator_type& get_allocator() const noexcept
+            {
+                return *this;
+            }
+            /// @}
+
+        private:
+            std::size_t max_size_;
+        };
+
+        /// \returns A \ref threshold_segregatable with the same parameter.
+        template <class RawAllocator>
+        threshold_segregatable<typename std::decay<RawAllocator>::type> threshold(
+            std::size_t max_size, RawAllocator&& alloc)
+        {
+            return threshold_segregatable<
+                typename std::decay<RawAllocator>::type>(max_size,
+                                                         std::forward<RawAllocator>(alloc));
+        }
+
+        /// A composable \concept{concept_rawallocator,RawAllocator} that will always fail.
+        /// This is useful for compositioning or as last resort in \ref binary_segregator.
+        /// \ingroup allocator
+        class null_allocator
+        {
+        public:
+            /// \effects Will always throw.
+            /// \throws A \ref out_of_fixed_memory exception.
+            void* allocate_node(std::size_t size, std::size_t)
+            {
+                throw out_of_fixed_memory(info(), size);
+            }
+
+            /// \requires Must not be called.
+            void deallocate_node(void*, std::size_t, std::size_t) noexcept
+            {
+                WPI_MEMORY_UNREACHABLE("cannot be called with proper values");
+            }
+
+            /// \effects Does nothing.
+            /// \returns Always returns `nullptr`.
+            void* try_allocate_node(std::size_t, std::size_t) noexcept
+            {
+                return nullptr;
+            }
+
+            /// \effects Does nothing.
+            /// \returns Always returns `false`.
+            bool try_deallocate_node(void*, std::size_t, std::size_t) noexcept
+            {
+                return false;
+            }
+
+        private:
+            allocator_info info() const noexcept
+            {
+                return {WPI_MEMORY_LOG_PREFIX "::null_allocator", this};
+            }
+        };
+
+        /// A \concept{concept_rawallocator,RawAllocator} that either uses the \concept{concept_segregatable,Segregatable} or the other `RawAllocator`.
+        /// It is a faster alternative to \ref fallback_allocator that doesn't require a composable allocator
+        /// and decides about the allocator to use purely with the `Segregatable` based on size and alignment.
+        /// \ingroup adapter
+        template <class Segregatable, class RawAllocator>
+        class binary_segregator
+        : WPI_EBO(
+              detail::ebo_storage<1, typename allocator_traits<RawAllocator>::allocator_type>)
+        {
+            using segregatable_traits = allocator_traits<typename Segregatable::allocator_type>;
+            using fallback_traits     = allocator_traits<RawAllocator>;
+
+        public:
+            using segregatable                = Segregatable;
+            using segregatable_allocator_type = typename segregatable::allocator_type;
+            using fallback_allocator_type = typename allocator_traits<RawAllocator>::allocator_type;
+
+            /// \effects Creates it by giving the \concept{concept_segregatable,Segregatable}
+            /// and the \concept{concept_rawallocator,RawAllocator}.
+            explicit binary_segregator(segregatable            s,
+                                       fallback_allocator_type fallback = fallback_allocator_type())
+            : detail::ebo_storage<1, fallback_allocator_type>(detail::move(fallback)),
+              s_(detail::move(s))
+            {
+            }
+
+            /// @{
+            /// \effects Uses the \concept{concept_segregatable,Segregatable} to decide which allocator to use.
+            /// Then forwards to the chosen allocator.
+            void* allocate_node(std::size_t size, std::size_t alignment)
+            {
+                if (get_segregatable().use_allocate_node(size, alignment))
+                    return segregatable_traits::allocate_node(get_segregatable_allocator(), size,
+                                                              alignment);
+                else
+                    return fallback_traits::allocate_node(get_fallback_allocator(), size,
+                                                          alignment);
+            }
+
+            void deallocate_node(void* ptr, std::size_t size, std::size_t alignment) noexcept
+            {
+                if (get_segregatable().use_allocate_node(size, alignment))
+                    segregatable_traits::deallocate_node(get_segregatable_allocator(), ptr, size,
+                                                         alignment);
+                else
+                    fallback_traits::deallocate_node(get_fallback_allocator(), ptr, size,
+                                                     alignment);
+            }
+
+            void* allocate_array(std::size_t count, std::size_t size, std::size_t alignment)
+            {
+                if (get_segregatable().use_allocate_array(count, size, alignment))
+                    return segregatable_traits::allocate_array(get_segregatable_allocator(), count,
+                                                               size, alignment);
+                else
+                    return fallback_traits::allocate_array(get_fallback_allocator(), count, size,
+                                                           alignment);
+            }
+
+            void deallocate_array(void* array, std::size_t count, std::size_t size,
+                                  std::size_t alignment) noexcept
+            {
+                if (get_segregatable().use_allocate_array(count, size, alignment))
+                    segregatable_traits::deallocate_array(get_segregatable_allocator(), array,
+                                                          count, size, alignment);
+                else
+                    fallback_traits::deallocate_array(get_fallback_allocator(), array, count, size,
+                                                      alignment);
+            }
+            /// @}
+
+            /// @{
+            /// \returns The maximum value of the fallback.
+            /// \note It assumes that the fallback will be used for larger allocations,
+            /// and the `Segregatable` for smaller ones.
+            std::size_t max_node_size() const
+            {
+                return fallback_traits::max_node_size(get_fallback_allocator());
+            }
+
+            std::size_t max_array_size() const
+            {
+                return fallback_traits::max_array_size(get_fallback_allocator());
+            }
+
+            std::size_t max_alignemnt() const
+            {
+                return fallback_traits::max_alignment(get_fallback_allocator());
+            }
+            /// @}
+
+            /// @{
+            /// \returns A reference to the segregatable allocator.
+            /// This is the one primarily used.
+            segregatable_allocator_type& get_segregatable_allocator() noexcept
+            {
+                return get_segregatable().get_allocator();
+            }
+
+            const segregatable_allocator_type& get_segregatable_allocator() const noexcept
+            {
+                return get_segregatable().get_allocator();
+            }
+            /// @}
+
+            /// @{
+            /// \returns A reference to the fallback allocator.
+            /// It will be used if the \concept{concept_segregator,Segregator} doesn't want the alloction.
+            fallback_allocator_type& get_fallback_allocator() noexcept
+            {
+                return detail::ebo_storage<1, fallback_allocator_type>::get();
+            }
+
+            const fallback_allocator_type& get_fallback_allocator() const noexcept
+            {
+                return detail::ebo_storage<1, fallback_allocator_type>::get();
+            }
+            /// @}
+
+        private:
+            segregatable& get_segregatable() noexcept
+            {
+                return s_;
+            }
+
+            segregatable s_;
+        };
+
+        namespace detail
+        {
+            template <class... Segregatables>
+            struct make_segregator_t;
+
+            template <class Segregatable>
+            struct make_segregator_t<Segregatable>
+            {
+                using type = binary_segregator<Segregatable, null_allocator>;
+            };
+
+            template <class Segregatable, class RawAllocator>
+            struct make_segregator_t<Segregatable, RawAllocator>
+            {
+                using type = binary_segregator<Segregatable, RawAllocator>;
+            };
+
+            template <class Segregatable, class... Tail>
+            struct make_segregator_t<Segregatable, Tail...>
+            {
+                using type =
+                    binary_segregator<Segregatable, typename make_segregator_t<Tail...>::type>;
+            };
+
+            template <class Segregator, class Fallback = null_allocator>
+            auto make_segregator(Segregator&& seg, Fallback&& f = null_allocator{})
+                -> binary_segregator<typename std::decay<Segregator>::type,
+                                     typename std::decay<Fallback>::type>
+            {
+                return binary_segregator<
+                    typename std::decay<Segregator>::type,
+                    typename std::decay<Fallback>::type>(std::forward<Segregator>(seg),
+                                                         std::forward<Fallback>(f));
+            }
+
+            template <class Segregator, typename... Rest>
+            auto make_segregator(Segregator&& seg, Rest&&... rest)
+                -> binary_segregator<typename std::decay<Segregator>::type,
+                                     decltype(make_segregator(std::forward<Rest>(rest)...))>
+            {
+                return binary_segregator<typename std::decay<Segregator>::type,
+                                         decltype(make_segregator(std::forward<Rest>(
+                                             rest)...))>(std::forward<Segregator>(seg),
+                                                         make_segregator(
+                                                             std::forward<Rest>(rest)...));
+            }
+
+            template <std::size_t I, class Segregator>
+            struct segregatable_type;
+
+            template <class Segregator, class Fallback>
+            struct segregatable_type<0, binary_segregator<Segregator, Fallback>>
+            {
+                using type = typename Segregator::allocator_type;
+
+                static type& get(binary_segregator<Segregator, Fallback>& s)
+                {
+                    return s.get_segregatable_allocator();
+                }
+
+                static const type& get(const binary_segregator<Segregator, Fallback>& s)
+                {
+                    return s.get_segregatable_allocator();
+                }
+            };
+
+            template <std::size_t I, class Segregator, class Fallback>
+            struct segregatable_type<I, binary_segregator<Segregator, Fallback>>
+            {
+                using base = segregatable_type<I - 1, Fallback>;
+                using type = typename base::type;
+
+                static type& get(binary_segregator<Segregator, Fallback>& s)
+                {
+                    return base::get(s.get_fallback_allocator());
+                }
+
+                static const type& get(const binary_segregator<Segregator, Fallback>& s)
+                {
+                    return base::get(s.get_fallback_allocator());
+                }
+            };
+
+            template <class Fallback>
+            struct fallback_type
+            {
+                using type = Fallback;
+
+                static const std::size_t size = 0u;
+
+                static type& get(Fallback& f)
+                {
+                    return f;
+                }
+
+                static const type& get(const Fallback& f)
+                {
+                    return f;
+                }
+            };
+
+            template <class Segregator, class Fallback>
+            struct fallback_type<binary_segregator<Segregator, Fallback>>
+            {
+                using base = fallback_type<Fallback>;
+                using type = typename base::type;
+
+                static const std::size_t size = base::size + 1u;
+
+                static type& get(binary_segregator<Segregator, Fallback>& s)
+                {
+                    return base::get(s.get_fallback_allocator());
+                }
+
+                static const type& get(const binary_segregator<Segregator, Fallback>& s)
+                {
+                    return base::get(s.get_fallback_allocator());
+                }
+            };
+        } // namespace detail
+
+        /// Creates multiple nested \ref binary_segregator.
+        /// If you pass one type, it must be a \concept{concept_segregatable,Segregatable}.
+        /// Then the result is a \ref binary_segregator with that `Segregatable` and \ref null_allocator as fallback.
+        /// If you pass two types, the first one must be a `Segregatable`,
+        /// the second one a \concept{concept_rawallocator,RawAllocator}.
+        /// Then the result is a simple \ref binary_segregator with those arguments.
+        /// If you pass more than one, the last one must be a `RawAllocator` all others `Segregatable`,
+        /// the result is `binary_segregator<Head, segregator<Tail...>>`.
+        /// \note It will result in an allocator that tries each `Segregatable` in the order specified
+        /// using the last parameter as final fallback.
+        /// \ingroup adapter
+        template <class... Allocators>
+        WPI_ALIAS_TEMPLATE(segregator,
+                                 typename detail::make_segregator_t<Allocators...>::type);
+
+        /// \returns A \ref segregator created from the allocators `args`.
+        /// \relates segregator
+        template <typename... Args>
+        auto make_segregator(Args&&... args) -> segregator<typename std::decay<Args>::type...>
+        {
+            return detail::make_segregator(std::forward<Args>(args)...);
+        }
+
+        /// The number of \concept{concept_segregatable,Segregatable} a \ref segregator has.
+        /// \relates segregator
+        template <class Segregator>
+        struct segregator_size
+        {
+            static const std::size_t value = detail::fallback_type<Segregator>::size;
+        };
+
+        /// The type of the `I`th \concept{concept_segregatable,Segregatable}.
+        /// \relates segregator
+        template <std::size_t I, class Segregator>
+        using segregatable_allocator_type = typename detail::segregatable_type<I, Segregator>::type;
+
+        /// @{
+        /// \returns The `I`th \concept{concept_segregatable,Segregatable}.
+        /// \relates segregrator
+        template <std::size_t I, class Segregator, class Fallback>
+        auto get_segregatable_allocator(binary_segregator<Segregator, Fallback>& s)
+            -> segregatable_allocator_type<I, binary_segregator<Segregator, Fallback>>&
+        {
+            return detail::segregatable_type<I, binary_segregator<Segregator, Fallback>>::get(s);
+        }
+
+        template <std::size_t I, class Segregator, class Fallback>
+        auto get_segregatable_allocator(const binary_segregator<Segregator, Fallback>& s)
+            -> const segregatable_allocator_type<I, binary_segregator<Segregator, Fallback>>
+        {
+            return detail::segregatable_type<I, binary_segregator<Segregator, Fallback>>::get(s);
+        }
+        /// @}
+
+        /// The type of the final fallback \concept{concept_rawallocator,RawAllocator}.
+        /// \relates segregator
+        template <class Segregator>
+        using fallback_allocator_type = typename detail::fallback_type<Segregator>::type;
+
+        /// @{
+        /// \returns The final fallback \concept{concept_rawallocator,RawAllocator}.
+        /// \relates segregator
+        template <class Segregator, class Fallback>
+        auto get_fallback_allocator(binary_segregator<Segregator, Fallback>& s)
+            -> fallback_allocator_type<binary_segregator<Segregator, Fallback>>&
+        {
+            return detail::fallback_type<binary_segregator<Segregator, Fallback>>::get(s);
+        }
+
+        template <class Segregator, class Fallback>
+        auto get_fallback_allocator(const binary_segregator<Segregator, Fallback>& s)
+            -> const fallback_allocator_type<binary_segregator<Segregator, Fallback>>&
+        {
+            return detail::fallback_type<binary_segregator<Segregator, Fallback>>::get(s);
+        }
+        /// @}
+    } // namespace memory
+} // namespace wpi
+
+#endif // WPI_MEMORY_SEGREGATOR_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/smart_ptr.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/smart_ptr.hpp
new file mode 100644
index 0000000..877efd7
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/smart_ptr.hpp
@@ -0,0 +1,210 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_SMART_PTR_HPP_INCLUDED
+#define WPI_MEMORY_SMART_PTR_HPP_INCLUDED
+
+/// \file
+/// \c std::make_unique() / \c std::make_shared() replacement allocating memory through a \concept{concept_rawallocator,RawAllocator}.
+/// \note Only available on a hosted implementation.
+
+#include "config.hpp"
+#if !WPI_HOSTED_IMPLEMENTATION
+#error "This header is only available for a hosted implementation."
+#endif
+
+#include <memory>
+#include <type_traits>
+
+#include "detail/utility.hpp"
+#include "deleter.hpp"
+#include "std_allocator.hpp"
+
+namespace wpi
+{
+    namespace memory
+    {
+        namespace detail
+        {
+            template <typename T, class RawAllocator, typename... Args>
+            auto allocate_unique(allocator_reference<RawAllocator> alloc, Args&&... args)
+                -> std::unique_ptr<T, allocator_deleter<T, RawAllocator>>
+            {
+                using raw_ptr = std::unique_ptr<T, allocator_deallocator<T, RawAllocator>>;
+
+                auto memory = alloc.allocate_node(sizeof(T), alignof(T));
+                // raw_ptr deallocates memory in case of constructor exception
+                raw_ptr result(static_cast<T*>(memory), {alloc});
+                // call constructor
+                ::new (memory) T(detail::forward<Args>(args)...);
+                // pass ownership to return value using a deleter that calls destructor
+                return {result.release(), {alloc}};
+            }
+
+            template <typename T, typename... Args>
+            void construct(std::true_type, T* cur, T* end, Args&&... args)
+            {
+                for (; cur != end; ++cur)
+                    ::new (static_cast<void*>(cur)) T(detail::forward<Args>(args)...);
+            }
+
+            template <typename T, typename... Args>
+            void construct(std::false_type, T* begin, T* end, Args&&... args)
+            {
+#if WPI_HAS_EXCEPTION_SUPPORT
+                auto cur = begin;
+                try
+                {
+                    for (; cur != end; ++cur)
+                        ::new (static_cast<void*>(cur)) T(detail::forward<Args>(args)...);
+                }
+                catch (...)
+                {
+                    for (auto el = begin; el != cur; ++el)
+                        el->~T();
+                    throw;
+                }
+#else
+                construct(std::true_type{}, begin, end, detail::forward<Args>(args)...);
+#endif
+            }
+
+            template <typename T, class RawAllocator>
+            auto allocate_array_unique(std::size_t size, allocator_reference<RawAllocator> alloc)
+                -> std::unique_ptr<T[], allocator_deleter<T[], RawAllocator>>
+            {
+                using raw_ptr = std::unique_ptr<T[], allocator_deallocator<T[], RawAllocator>>;
+
+                auto memory = alloc.allocate_array(size, sizeof(T), alignof(T));
+                // raw_ptr deallocates memory in case of constructor exception
+                raw_ptr result(static_cast<T*>(memory), {alloc, size});
+                construct(std::integral_constant<bool, noexcept(T())>{}, result.get(),
+                          result.get() + size);
+                // pass ownership to return value using a deleter that calls destructor
+                return {result.release(), {alloc, size}};
+            }
+        } // namespace detail
+
+        /// A \c std::unique_ptr that deletes using a \concept{concept_rawallocator,RawAllocator}.
+        ///
+        /// It is an alias template using \ref allocator_deleter as \c Deleter class.
+        /// \ingroup adapter
+        template <typename T, class RawAllocator>
+        WPI_ALIAS_TEMPLATE(unique_ptr,
+                                 std::unique_ptr<T, allocator_deleter<T, RawAllocator>>);
+
+        /// A \c std::unique_ptr that deletes using a \concept{concept_rawallocator,RawAllocator} and allows polymorphic types.
+        ///
+        /// It can only be created by converting a regular unique pointer to a pointer to a derived class,
+        /// and is meant to be used inside containers.
+        /// It is an alias template using \ref allocator_polymorphic_deleter as \c Deleter class.
+        /// \note It has a relatively high overhead, so only use it if you have to.
+        /// \ingroup adapter
+        template <class BaseType, class RawAllocator>
+        WPI_ALIAS_TEMPLATE(
+            unique_base_ptr,
+            std::unique_ptr<BaseType, allocator_polymorphic_deleter<BaseType, RawAllocator>>);
+
+        /// Creates a \c std::unique_ptr using a \concept{concept_rawallocator,RawAllocator} for the allocation.
+        /// \effects Allocates memory for the given type using the allocator
+        /// and creates a new object inside it passing the given arguments to its constructor.
+        /// \returns A \c std::unique_ptr owning that memory.
+        /// \note If the allocator is stateful a reference to the \c RawAllocator will be stored inside the deleter,
+        /// the caller has to ensure that the object lives as long as the smart pointer.
+        /// \ingroup adapter
+        template <typename T, class RawAllocator, typename... Args>
+        auto allocate_unique(RawAllocator&& alloc, Args&&... args) -> WPI_REQUIRES_RET(
+            !std::is_array<T>::value,
+            std::unique_ptr<T, allocator_deleter<T, typename std::decay<RawAllocator>::type>>)
+        {
+            return detail::allocate_unique<T>(make_allocator_reference(
+                                                  detail::forward<RawAllocator>(alloc)),
+                                              detail::forward<Args>(args)...);
+        }
+
+        /// Creates a \c std::unique_ptr using a type-erased \concept{concept_rawallocator,RawAllocator} for the allocation.
+        /// It is the same as the other overload but stores the reference to the allocator type-erased inside the \c std::unique_ptr.
+        /// \effects Allocates memory for the given type using the allocator
+        /// and creates a new object inside it passing the given arguments to its constructor.
+        /// \returns A \c std::unique_ptr with a type-erased allocator reference owning that memory.
+        /// \note If the allocator is stateful a reference to the \c RawAllocator will be stored inside the deleter,
+        /// the caller has to ensure that the object lives as long as the smart pointer.
+        /// \ingroup adapter
+        template <typename T, class RawAllocator, typename... Args>
+        auto allocate_unique(any_allocator, RawAllocator&& alloc, Args&&... args)
+            -> WPI_REQUIRES_RET(!std::is_array<T>::value,
+                                      std::unique_ptr<T, allocator_deleter<T, any_allocator>>)
+        {
+            return detail::allocate_unique<T, any_allocator>(make_allocator_reference(
+                                                                 detail::forward<RawAllocator>(
+                                                                     alloc)),
+                                                             detail::forward<Args>(args)...);
+        }
+
+        /// Creates a \c std::unique_ptr owning an array using a \concept{concept_rawallocator,RawAllocator} for the allocation.
+        /// \effects Allocates memory for an array of given size and value initializes each element inside of it.
+        /// \returns A \c std::unique_ptr owning that array.
+        /// \note If the allocator is stateful a reference to the \c RawAllocator will be stored inside the deleter,
+        /// the caller has to ensure that the object lives as long as the smart pointer.
+        /// \ingroup adapter
+        template <typename T, class RawAllocator>
+        auto allocate_unique(RawAllocator&& alloc, std::size_t size) -> WPI_REQUIRES_RET(
+            std::is_array<T>::value,
+            std::unique_ptr<T, allocator_deleter<T, typename std::decay<RawAllocator>::type>>)
+        {
+            return detail::allocate_array_unique<
+                typename std::remove_extent<T>::type>(size,
+                                                      make_allocator_reference(
+                                                          detail::forward<RawAllocator>(alloc)));
+        }
+
+        /// Creates a \c std::unique_ptr owning an array using a type-erased \concept{concept_rawallocator,RawAllocator} for the allocation.
+        /// It is the same as the other overload but stores the reference to the allocator type-erased inside the \c std::unique_ptr.
+        /// \effects Allocates memory for an array of given size and value initializes each element inside of it.
+        /// \returns A \c std::unique_ptr with a type-erased allocator reference owning that array.
+        /// \note If the allocator is stateful a reference to the \c RawAllocator will be stored inside the deleter,
+        /// the caller has to ensure that the object lives as long as the smart pointer.
+        /// \ingroup adapter
+        template <typename T, class RawAllocator>
+        auto allocate_unique(any_allocator, RawAllocator&& alloc, std::size_t size)
+            -> WPI_REQUIRES_RET(std::is_array<T>::value,
+                                      std::unique_ptr<T, allocator_deleter<T, any_allocator>>)
+        {
+            return detail::allocate_array_unique<typename std::remove_extent<T>::type,
+                                                 any_allocator>(size,
+                                                                make_allocator_reference(
+                                                                    detail::forward<RawAllocator>(
+                                                                        alloc)));
+        }
+
+        /// Creates a \c std::shared_ptr using a \concept{concept_rawallocator,RawAllocator} for the allocation.
+        /// It is similar to \c std::allocate_shared but uses a \c RawAllocator (and thus also supports any \c Allocator).
+        /// \effects Calls \ref std_allocator::make_std_allocator to wrap the allocator and forwards to \c std::allocate_shared.
+        /// \returns A \c std::shared_ptr created using \c std::allocate_shared.
+        /// \note If the allocator is stateful a reference to the \c RawAllocator will be stored inside the shared pointer,
+        /// the caller has to ensure that the object lives as long as the smart pointer.
+        /// \ingroup adapter
+        template <typename T, class RawAllocator, typename... Args>
+        std::shared_ptr<T> allocate_shared(RawAllocator&& alloc, Args&&... args)
+        {
+            return std::allocate_shared<T>(make_std_allocator<T>(
+                                               detail::forward<RawAllocator>(alloc)),
+                                           detail::forward<Args>(args)...);
+        }
+
+#if !defined(DOXYGEN)
+#include "detail/container_node_sizes.hpp"
+#else
+        /// Contains the node size needed for a `std::shared_ptr`.
+        /// These classes are auto-generated and only available if the tools are build and without cross-compiling.
+        /// \ingroup adapter
+        template <typename T>
+        struct shared_ptr_node_size : std::integral_constant<std::size_t, implementation_defined>
+        {
+        };
+#endif
+    } // namespace memory
+} // namespace wpi
+
+#endif // WPI_MEMORY_SMART_PTR_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/static_allocator.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/static_allocator.hpp
new file mode 100644
index 0000000..efbbf73
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/static_allocator.hpp
@@ -0,0 +1,179 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_STATIC_ALLOCATOR_HPP_INCLUDED
+#define WPI_MEMORY_STATIC_ALLOCATOR_HPP_INCLUDED
+
+/// \file
+/// Allocators using a static, fixed-sized storage.
+
+#include <type_traits>
+
+#include "detail/align.hpp"
+#include "detail/assert.hpp"
+#include "detail/memory_stack.hpp"
+#include "detail/utility.hpp"
+#include "config.hpp"
+
+#if WPI_MEMORY_EXTERN_TEMPLATE
+#include "allocator_traits.hpp"
+#endif
+
+namespace wpi
+{
+    namespace memory
+    {
+        /// Storage for a \ref static_allocator.
+        /// Its constructor will take a reference to it and use it for its allocation.
+        /// The storage type is simply a \c char array aligned for maximum alignment.
+        /// \note It is not allowed to access the memory of the storage.
+        /// \ingroup allocator
+        template <std::size_t Size>
+        struct static_allocator_storage
+        {
+            alignas(detail::max_alignment) char storage[Size];
+        };
+
+        static_assert(sizeof(static_allocator_storage<1024>) == 1024, "");
+        static_assert(alignof(static_allocator_storage<1024>) == detail::max_alignment, "");
+
+        struct allocator_info;
+
+        /// A stateful \concept{concept_rawallocator,RawAllocator} that uses a fixed sized storage for the allocations.
+        /// It works on a \ref static_allocator_storage and uses its memory for all allocations.
+        /// Deallocations are not supported, memory cannot be marked as freed.<br>
+        /// \note It is not allowed to share an \ref static_allocator_storage between multiple \ref static_allocator objects.
+        /// \ingroup allocator
+        class static_allocator
+        {
+        public:
+            using is_stateful = std::true_type;
+
+            /// \effects Creates it by passing it a \ref static_allocator_storage by reference.
+            /// It will take the address of the storage and use its memory for the allocation.
+            /// \requires The storage object must live as long as the allocator object.
+            /// It must not be shared between multiple allocators,
+            /// i.e. the object must not have been passed to a constructor before.
+            template <std::size_t Size>
+            static_allocator(static_allocator_storage<Size>& storage) noexcept
+            : stack_(&storage), end_(stack_.top() + Size)
+            {
+            }
+
+            /// \effects A \concept{concept_rawallocator,RawAllocator} allocation function.
+            /// It uses the specified \ref static_allocator_storage.
+            /// \returns A pointer to a \concept{concept_node,node}, it will never be \c nullptr.
+            /// \throws An exception of type \ref out_of_memory or whatever is thrown by its handler if the storage is exhausted.
+            void* allocate_node(std::size_t size, std::size_t alignment);
+
+            /// \effects A \concept{concept_rawallocator,RawAllocator} deallocation function.
+            /// It does nothing, deallocation is not supported by this allocator.
+            void deallocate_node(void*, std::size_t, std::size_t) noexcept {}
+
+            /// \returns The maximum node size which is the capacity remaining inside the \ref static_allocator_storage.
+            std::size_t max_node_size() const noexcept
+            {
+                return static_cast<std::size_t>(end_ - stack_.top());
+            }
+
+            /// \returns The maximum possible value since there is no alignment restriction
+            /// (except indirectly through the size of the \ref static_allocator_storage).
+            std::size_t max_alignment() const noexcept
+            {
+                return std::size_t(-1);
+            }
+
+        private:
+            allocator_info info() const noexcept;
+
+            detail::fixed_memory_stack stack_;
+            const char*                end_;
+        };
+
+#if WPI_MEMORY_EXTERN_TEMPLATE
+        extern template class allocator_traits<static_allocator>;
+#endif
+
+        struct memory_block;
+
+        /// A \concept{concept_blockallocator,BlockAllocator} that allocates the blocks from a fixed size storage.
+        /// It works on a \ref static_allocator_storage and uses it for all allocations,
+        /// deallocations are only allowed in reversed order which is guaranteed by \ref memory_arena.
+        /// \note It is not allowed to share an \ref static_allocator_storage between multiple \ref static_allocator objects.
+        /// \ingroup allocator
+        class static_block_allocator
+        {
+        public:
+            /// \effects Creates it by passing it the block size and a \ref static_allocator_storage by reference.
+            /// It will take the address of the storage and use it to allocate \c block_size'd blocks.
+            /// \requires The storage object must live as long as the allocator object.
+            /// It must not be shared between multiple allocators,
+            /// i.e. the object must not have been passed to a constructor before.
+            /// The size of the \ref static_allocator_storage must be a multiple of the (non-null) block size.
+            template <std::size_t Size>
+            static_block_allocator(std::size_t                     block_size,
+                                   static_allocator_storage<Size>& storage) noexcept
+            : cur_(static_cast<char*>(static_cast<void*>(&storage))),
+              end_(cur_ + Size),
+              block_size_(block_size)
+            {
+                WPI_MEMORY_ASSERT(block_size <= Size);
+                WPI_MEMORY_ASSERT(Size % block_size == 0u);
+            }
+
+            ~static_block_allocator() noexcept = default;
+
+            /// @{
+            /// \effects Moves the block allocator, it transfers ownership over the \ref static_allocator_storage.
+            /// This does not invalidate any memory blocks.
+            static_block_allocator(static_block_allocator&& other) noexcept
+            : cur_(other.cur_), end_(other.end_), block_size_(other.block_size_)
+            {
+                other.cur_ = other.end_ = nullptr;
+                other.block_size_       = 0;
+            }
+
+            static_block_allocator& operator=(static_block_allocator&& other) noexcept
+            {
+                static_block_allocator tmp(detail::move(other));
+                swap(*this, tmp);
+                return *this;
+            }
+            /// @}
+
+            /// \effects Swaps the ownership over the \ref static_allocator_storage.
+            /// This does not invalidate any memory blocks.
+            friend void swap(static_block_allocator& a, static_block_allocator& b) noexcept
+            {
+                detail::adl_swap(a.cur_, b.cur_);
+                detail::adl_swap(a.end_, b.end_);
+                detail::adl_swap(a.block_size_, b.block_size_);
+            }
+
+            /// \effects Allocates a new block by returning the \ref next_block_size() bytes.
+            /// \returns The new memory block.
+            memory_block allocate_block();
+
+            /// \effects Deallocates the last memory block by marking the block as free again.
+            /// This block will be returned again by the next call to \ref allocate_block().
+            /// \requires \c block must be the current top block of the memory,
+            /// this is guaranteed by \ref memory_arena.
+            void deallocate_block(memory_block block) noexcept;
+
+            /// \returns The next block size, this is the size passed to the constructor.
+            std::size_t next_block_size() const noexcept
+            {
+                return block_size_;
+            }
+
+        private:
+            allocator_info info() const noexcept;
+
+            char *      cur_, *end_;
+            std::size_t block_size_;
+        };
+    } // namespace memory
+} // namespace wpi
+
+#endif //WPI_MEMORY_STATIC_ALLOCATOR_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/std_allocator.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/std_allocator.hpp
new file mode 100644
index 0000000..f727a1c
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/std_allocator.hpp
@@ -0,0 +1,360 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_STD_ALLOCATOR_HPP_INCLUDED
+#define WPI_MEMORY_STD_ALLOCATOR_HPP_INCLUDED
+
+/// \file
+/// Class \ref wpi::memory::std_allocator and related classes and functions.
+
+#include <new>
+#include <type_traits>
+
+#include "detail/utility.hpp"
+#include "config.hpp"
+#include "allocator_storage.hpp"
+#include "threading.hpp"
+
+namespace wpi
+{
+    namespace memory
+    {
+        namespace traits_detail
+        {
+            template <class RawAllocator>
+            auto propagate_on_container_swap(std_concept) ->
+                typename RawAllocator::propagate_on_container_swap;
+
+            template <class RawAllocator>
+            auto propagate_on_container_swap(min_concept) -> std::true_type;
+
+            template <class RawAllocator>
+            auto propagate_on_container_move_assignment(std_concept) ->
+                typename RawAllocator::propagate_on_container_move_assignment;
+
+            template <class RawAllocator>
+            auto propagate_on_container_move_assignment(min_concept) -> std::true_type;
+
+            template <class RawAllocator>
+            auto propagate_on_container_copy_assignment(std_concept) ->
+                typename RawAllocator::propagate_on_container_copy_assignment;
+
+            template <class RawAllocator>
+            auto propagate_on_container_copy_assignment(min_concept) -> std::true_type;
+        } // namespace traits_detail
+
+        /// Controls the propagation of a \ref std_allocator for a certain \concept{concept_rawallocator,RawAllocator}.
+        /// \ingroup adapter
+        template <class RawAllocator>
+        struct propagation_traits
+        {
+            using propagate_on_container_swap =
+                decltype(traits_detail::propagate_on_container_swap<RawAllocator>(
+                    traits_detail::full_concept{}));
+
+            using propagate_on_container_move_assignment =
+                decltype(traits_detail::propagate_on_container_move_assignment<RawAllocator>(
+                    traits_detail::full_concept{}));
+
+            using propagate_on_container_copy_assignment =
+                decltype(traits_detail::propagate_on_container_copy_assignment<RawAllocator>(
+                    traits_detail::full_concept{}));
+
+            template <class AllocReference>
+            static AllocReference select_on_container_copy_construction(const AllocReference& alloc)
+            {
+                return alloc;
+            }
+        };
+
+        /// Wraps a \concept{concept_rawallocator,RawAllocator} and makes it a "normal" \c Allocator.
+        /// It allows using a \c RawAllocator anywhere a \c Allocator is required.
+        /// \ingroup adapter
+        template <typename T, class RawAllocator>
+        class std_allocator :
+#if defined _MSC_VER && defined __clang__
+            WPI_EBO(protected allocator_reference<RawAllocator>)
+#else
+            WPI_EBO(allocator_reference<RawAllocator>)
+#endif
+        {
+            using alloc_reference = allocator_reference<RawAllocator>;
+            // if it is any_allocator_reference an optimized implementation can be used
+            using is_any = std::is_same<alloc_reference, any_allocator_reference>;
+
+            using prop_traits = propagation_traits<RawAllocator>;
+
+        public:
+            //=== typedefs ===//
+            using value_type      = T;
+            using pointer         = T*;
+            using const_pointer   = const T*;
+            using reference       = T&;
+            using const_reference = const T&;
+            using size_type       = std::size_t;
+            using difference_type = std::ptrdiff_t;
+
+            using propagate_on_container_swap = typename prop_traits::propagate_on_container_swap;
+            using propagate_on_container_move_assignment =
+                typename prop_traits::propagate_on_container_move_assignment;
+            using propagate_on_container_copy_assignment =
+                typename prop_traits::propagate_on_container_copy_assignment;
+
+            template <typename U>
+            struct rebind
+            {
+                using other = std_allocator<U, RawAllocator>;
+            };
+
+            using allocator_type = typename alloc_reference::allocator_type;
+
+            //=== constructor ===//
+            /// \effects Default constructs it by storing a default constructed, stateless \c RawAllocator inside the reference.
+            /// \requires The \c RawAllocator type is stateless, otherwise the body of this function will not compile.
+            std_allocator() noexcept : alloc_reference(allocator_type{})
+            {
+#if !defined(__GNUC__) || (defined(_GLIBCXX_USE_CXX11_ABI) && _GLIBCXX_USE_CXX11_ABI != 0)
+                // std::string requires default constructor for the small string optimization when using gcc's old ABI
+                // so don't assert then to allow joint allocator
+                static_assert(!alloc_reference::is_stateful::value,
+                              "default constructor must not be used for stateful allocators");
+#endif
+            }
+
+            /// \effects Creates it from a reference to a \c RawAllocator.
+            /// It will store an \ref allocator_reference to it.
+            /// \requires The expression <tt>allocator_reference<RawAllocator>(alloc)</tt> is well-formed,
+            /// that is either \c RawAlloc is the same as \c RawAllocator or \c RawAllocator is the tag type \ref any_allocator.
+            /// If the requirement is not fulfilled this function does not participate in overload resolution.
+            /// \note The caller has to ensure that the lifetime of the \c RawAllocator is at least as long as the lifetime
+            /// of this \ref std_allocator object.
+            template <
+                class RawAlloc,
+                // MSVC seems to ignore access rights in decltype SFINAE below
+                // use this to prevent this constructor being chosen instead of move/copy for types inheriting from it
+                WPI_REQUIRES((!std::is_base_of<std_allocator, RawAlloc>::value))>
+            std_allocator(RawAlloc& alloc, WPI_SFINAE(alloc_reference(alloc))) noexcept
+            : alloc_reference(alloc)
+            {
+            }
+
+            /// \effects Creates it from a stateless, temporary \c RawAllocator object.
+            /// It will not store a reference but create it on the fly.
+            /// \requires The \c RawAllocator is stateless
+            /// and the expression <tt>allocator_reference<RawAllocator>(alloc)</tt> is well-formed as above,
+            /// otherwise this function does not participate in overload resolution.
+            template <
+                class RawAlloc,
+                // MSVC seems to ignore access rights in decltype SFINAE below
+                // use this to prevent this constructor being chosen instead of move/copy for types inheriting from it
+                WPI_REQUIRES((!std::is_base_of<std_allocator, RawAlloc>::value))>
+            std_allocator(const RawAlloc& alloc, WPI_SFINAE(alloc_reference(alloc))) noexcept
+            : alloc_reference(alloc)
+            {
+            }
+
+            /// \effects Creates it from another \ref allocator_reference using the same allocator type.
+            std_allocator(const alloc_reference& alloc) noexcept : alloc_reference(alloc) {}
+
+            /// \details Implicit conversion from any other \ref allocator_storage is forbidden
+            /// to prevent accidentally wrapping another \ref allocator_storage inside a \ref allocator_reference.
+            template <class StoragePolicy, class OtherMut>
+            std_allocator(const allocator_storage<StoragePolicy, OtherMut>&) = delete;
+
+            /// @{
+            /// \effects Creates it from another \ref std_allocator allocating a different type.
+            /// This is required by the \c Allcoator concept and simply takes the same \ref allocator_reference.
+            template <typename U>
+            std_allocator(const std_allocator<U, RawAllocator>& alloc) noexcept
+            : alloc_reference(alloc)
+            {
+            }
+
+            template <typename U>
+            std_allocator(std_allocator<U, RawAllocator>& alloc) noexcept : alloc_reference(alloc)
+            {
+            }
+            /// @}
+
+            /// \returns A copy of the allocator.
+            /// This is required by the \c Allocator concept and forwards to the \ref propagation_traits.
+            std_allocator<T, RawAllocator> select_on_container_copy_construction() const
+            {
+                return prop_traits::select_on_container_copy_construction(*this);
+            }
+
+            //=== allocation/deallocation ===//
+            /// \effects Allocates memory using the underlying \concept{concept_rawallocator,RawAllocator}.
+            /// If \c n is \c 1, it will call <tt>allocate_node(sizeof(T), alignof(T))</tt>,
+            /// otherwise <tt>allocate_array(n, sizeof(T), alignof(T))</tt>.
+            /// \returns A pointer to a memory block suitable for \c n objects of type \c T.
+            /// \throws Anything thrown by the \c RawAllocator.
+            pointer allocate(size_type n, void* = nullptr)
+            {
+                return static_cast<pointer>(allocate_impl(is_any{}, n));
+            }
+
+            /// \effects Deallcoates memory using the underlying \concept{concept_rawallocator,RawAllocator}.
+            /// It will forward to the deallocation function in the same way as in \ref allocate().
+            /// \requires The pointer must come from a previous call to \ref allocate() with the same \c n on this object or any copy of it.
+            void deallocate(pointer p, size_type n) noexcept
+            {
+                deallocate_impl(is_any{}, p, n);
+            }
+
+            //=== construction/destruction ===//
+            /// \effects Creates an object of type \c U at given address using the passed arguments.
+            template <typename U, typename... Args>
+            void construct(U* p, Args&&... args)
+            {
+                void* mem = p;
+                ::new (mem) U(detail::forward<Args>(args)...);
+            }
+
+            /// \effects Calls the destructor for an object of type \c U at given address.
+            template <typename U>
+            void destroy(U* p) noexcept
+            {
+                // This is to avoid a MSVS 2015 'unreferenced formal parameter' warning
+                (void)p;
+                p->~U();
+            }
+
+            //=== getter ===//
+            /// \returns The maximum size for an allocation which is <tt>max_array_size() / sizeof(value_type)</tt>.
+            /// This is only an upper bound, not the exact maximum.
+            size_type max_size() const noexcept
+            {
+                return this->max_array_size() / sizeof(value_type);
+            }
+
+            /// @{
+            /// \effects Returns a reference to the referenced allocator.
+            /// \returns For stateful allocators: A (\c const) reference to the stored allocator.
+            /// For stateless allocators: A temporary constructed allocator.
+            auto get_allocator() noexcept
+                -> decltype(std::declval<alloc_reference>().get_allocator())
+            {
+                return alloc_reference::get_allocator();
+            }
+
+            auto get_allocator() const noexcept
+                -> decltype(std::declval<const alloc_reference>().get_allocator())
+            {
+                return alloc_reference::get_allocator();
+            }
+            /// @}
+
+        private:
+            // any_allocator_reference: use virtual function which already does a dispatch on node/array
+            void* allocate_impl(std::true_type, size_type n)
+            {
+                return get_allocator().allocate_impl(n, sizeof(T), alignof(T));
+            }
+
+            void deallocate_impl(std::true_type, void* ptr, size_type n)
+            {
+                get_allocator().deallocate_impl(ptr, n, sizeof(T), alignof(T));
+            }
+
+            // alloc_reference: decide between node/array
+            void* allocate_impl(std::false_type, size_type n)
+            {
+                if (n == 1)
+                    return this->allocate_node(sizeof(T), alignof(T));
+                else
+                    return this->allocate_array(n, sizeof(T), alignof(T));
+            }
+
+            void deallocate_impl(std::false_type, void* ptr, size_type n)
+            {
+                if (n == 1)
+                    this->deallocate_node(ptr, sizeof(T), alignof(T));
+                else
+                    this->deallocate_array(ptr, n, sizeof(T), alignof(T));
+            }
+
+            template <typename U> // stateful
+            bool equal_to_impl(std::true_type,
+                               const std_allocator<U, RawAllocator>& other) const noexcept
+            {
+                return &get_allocator() == &other.get_allocator();
+            }
+
+            template <typename U> // non-stateful
+            bool equal_to_impl(std::false_type,
+                               const std_allocator<U, RawAllocator>&) const noexcept
+            {
+                return true;
+            }
+
+            template <typename U> // shared
+            bool equal_to(std::true_type,
+                          const std_allocator<U, RawAllocator>& other) const noexcept
+            {
+                return get_allocator() == other.get_allocator();
+            }
+
+            template <typename U> // not shared
+            bool equal_to(std::false_type,
+                          const std_allocator<U, RawAllocator>& other) const noexcept
+            {
+                return equal_to_impl(typename allocator_traits<RawAllocator>::is_stateful{}, other);
+            }
+
+            template <typename T1, typename T2, class Impl>
+            friend bool operator==(const std_allocator<T1, Impl>& lhs,
+                                   const std_allocator<T2, Impl>& rhs) noexcept;
+
+            template <typename U, class OtherRawAllocator>
+            friend class std_allocator;
+        };
+
+        /// \effects Compares two \ref std_allocator object, they are equal if either stateless or reference the same allocator.
+        /// \returns The result of the comparision for equality.
+        /// \relates std_allocator
+        template <typename T, typename U, class Impl>
+        bool operator==(const std_allocator<T, Impl>& lhs,
+                        const std_allocator<U, Impl>& rhs) noexcept
+        {
+            return lhs.equal_to(is_shared_allocator<Impl>{}, rhs);
+        }
+
+        /// \effects Compares two \ref std_allocator object, they are equal if either stateless or reference the same allocator.
+        /// \returns The result of the comparision for inequality.
+        /// \relates std_allocator
+        template <typename T, typename U, class Impl>
+        bool operator!=(const std_allocator<T, Impl>& lhs,
+                        const std_allocator<U, Impl>& rhs) noexcept
+        {
+            return !(lhs == rhs);
+        }
+
+        /// \returns A new \ref std_allocator for a given type using a certain allocator object.
+        /// \relates std_allocator
+        template <typename T, class RawAllocator>
+        auto make_std_allocator(RawAllocator&& allocator) noexcept
+            -> std_allocator<T, typename std::decay<RawAllocator>::type>
+        {
+            return {detail::forward<RawAllocator>(allocator)};
+        }
+
+        /// An alias template for \ref std_allocator using a type-erased \concept{concept_rawallocator,RawAllocator}.
+        /// This is the same as using a \ref std_allocator with the tag type \ref any_allocator.
+        /// The implementation is optimized to call fewer virtual functions.
+        /// \ingroup adapter
+        template <typename T>
+        WPI_ALIAS_TEMPLATE(any_std_allocator, std_allocator<T, any_allocator>);
+
+        /// \returns A new \ref any_std_allocator for a given type using a certain allocator object.
+        /// \relates any_std_allocator
+        template <typename T, class RawAllocator>
+        any_std_allocator<T> make_any_std_allocator(RawAllocator&& allocator) noexcept
+        {
+            return {detail::forward<RawAllocator>(allocator)};
+        }
+    } // namespace memory
+} // namespace wpi
+
+#endif // WPI_MEMORY_STD_ALLOCATOR_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/temporary_allocator.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/temporary_allocator.hpp
new file mode 100644
index 0000000..7eba76f
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/temporary_allocator.hpp
@@ -0,0 +1,335 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_TEMPORARY_ALLOCATOR_HPP_INCLUDED
+#define WPI_MEMORY_TEMPORARY_ALLOCATOR_HPP_INCLUDED
+
+/// \file
+/// Class \ref wpi::memory::temporary_allocator and related functions.
+
+#include "config.hpp"
+#include "memory_stack.hpp"
+
+#if WPI_MEMORY_TEMPORARY_STACK_MODE >= 2
+#include <atomic>
+#endif
+
+namespace wpi
+{
+    namespace memory
+    {
+        class temporary_allocator;
+        class temporary_stack;
+
+        namespace detail
+        {
+            class temporary_block_allocator
+            {
+            public:
+                explicit temporary_block_allocator(std::size_t block_size) noexcept;
+
+                memory_block allocate_block();
+
+                void deallocate_block(memory_block block);
+
+                std::size_t next_block_size() const noexcept
+                {
+                    return block_size_;
+                }
+
+                using growth_tracker = void (*)(std::size_t size);
+
+                growth_tracker set_growth_tracker(growth_tracker t) noexcept;
+
+                growth_tracker get_growth_tracker() noexcept;
+
+            private:
+                growth_tracker tracker_;
+                std::size_t    block_size_;
+            };
+
+            using temporary_stack_impl = memory_stack<temporary_block_allocator>;
+
+            class temporary_stack_list;
+
+#if WPI_MEMORY_TEMPORARY_STACK_MODE >= 2
+            class temporary_stack_list_node
+            {
+            public:
+                // doesn't add into list
+                temporary_stack_list_node() noexcept : in_use_(true) {}
+
+                temporary_stack_list_node(int) noexcept;
+
+                ~temporary_stack_list_node() noexcept {}
+
+            private:
+                temporary_stack_list_node* next_ = nullptr;
+                std::atomic<bool>          in_use_;
+
+                friend temporary_stack_list;
+            };
+
+            static class temporary_allocator_dtor_t
+            {
+            public:
+                temporary_allocator_dtor_t() noexcept;
+                ~temporary_allocator_dtor_t() noexcept;
+            } temporary_allocator_dtor;
+#else
+            class temporary_stack_list_node
+            {
+            protected:
+                temporary_stack_list_node() noexcept {}
+
+                temporary_stack_list_node(int) noexcept {}
+
+                ~temporary_stack_list_node() noexcept {}
+            };
+#endif
+        } // namespace detail
+
+        /// A wrapper around the \ref memory_stack that is used by the \ref temporary_allocator.
+        /// There should be at least one per-thread.
+        /// \ingroup allocator
+        class temporary_stack : WPI_EBO(detail::temporary_stack_list_node)
+        {
+        public:
+            /// The type of the handler called when the internal \ref memory_stack grows.
+            /// It gets the size of the new block that will be allocated.
+            /// \requiredbe The handler shall log the growth, throw an exception or aborts the program.
+            /// If this function does not return, the growth is prevented but the allocator unusable until memory is freed.
+            /// \defaultbe The default handler does nothing.
+            using growth_tracker = detail::temporary_block_allocator::growth_tracker;
+
+            /// \effects Sets \c h as the new \ref growth_tracker.
+            /// A \c nullptr sets the default \ref growth_tracker.
+            /// Each thread has its own, separate tracker.
+            /// \returns The previous \ref growth_tracker. This is never \c nullptr.
+            growth_tracker set_growth_tracker(growth_tracker t) noexcept
+            {
+                return stack_.get_allocator().set_growth_tracker(t);
+            }
+
+            /// \returns The current \ref growth_tracker. This is never \c nullptr.
+            growth_tracker get_growth_tracker() noexcept
+            {
+                return stack_.get_allocator().get_growth_tracker();
+            }
+
+            /// \effects Creates it with a given initial size of the stack.
+            /// It can grow if needed, although that is expensive.
+            /// \requires `initial_size` must be greater than `0`.
+            explicit temporary_stack(std::size_t initial_size) : stack_(initial_size), top_(nullptr)
+            {
+            }
+
+            /// \returns `next_capacity()` of the internal `memory_stack`.
+            std::size_t next_capacity() const noexcept
+            {
+                return stack_.next_capacity();
+            }
+
+        private:
+            temporary_stack(int i, std::size_t initial_size)
+            : detail::temporary_stack_list_node(i), stack_(initial_size), top_(nullptr)
+            {
+            }
+
+            using marker = detail::temporary_stack_impl::marker;
+
+            marker top() const noexcept
+            {
+                return stack_.top();
+            }
+
+            void unwind(marker m) noexcept
+            {
+                stack_.unwind(m);
+            }
+
+            detail::temporary_stack_impl stack_;
+            temporary_allocator*         top_;
+
+#if !defined(DOXYGEN)
+            friend temporary_allocator;
+            friend memory_stack_raii_unwind<temporary_stack>;
+            friend detail::temporary_stack_list;
+#endif
+        };
+
+        /// Manually takes care of the lifetime of the per-thread \ref temporary_stack.
+        /// The constructor will create it, if not already done, and the destructor will destroy it, if not already done.
+        /// \note If there are multiple objects in a thread,
+        /// this will lead to unnecessary construction and destruction of the stack.
+        /// It is thus adviced to create one object on the top-level function of the thread, e.g. in `main()`.
+        /// \note If `WPI_MEMORY_TEMPORARY_STACK_MODE == 2`, it is not necessary to use this class,
+        /// the nifty counter will clean everything upon program termination.
+        /// But it can still be used as an optimization if you have a thread that is terminated long before program exit.
+        /// The automatic clean up will only occur much later.
+        /// \note If `WPI_MEMORY_TEMPORARY_STACK_MODE == 0`, the use of this class has no effect,
+        /// because the per-thread stack is disabled.
+        /// \relatesalso temporary_stack
+        class temporary_stack_initializer
+        {
+        public:
+            static constexpr std::size_t default_stack_size = 4096u;
+
+            static const struct defer_create_t
+            {
+                defer_create_t() noexcept {}
+            } defer_create;
+
+            /// \effects Does not create the per-thread stack.
+            /// It will be created by the first call to \ref get_temporary_stack() in the current thread.
+            /// \note If `WPI_MEMORY_TEMPORARY_STACK_MODE == 0`, this function has no effect.
+            temporary_stack_initializer(defer_create_t) noexcept {}
+
+            /// \effects Creates the per-thread stack with the given default size if it wasn't already created.
+            /// \requires `initial_size` must not be `0` if `WPI_MEMORY_TEMPORARY_STACK_MODE != 0`.
+            /// \note If `WPI_MEMORY_TEMPORARY_STACK_MODE == 0`, this function will issue a warning in debug mode.
+            /// This can be disabled by passing `0` as the initial size.
+            temporary_stack_initializer(std::size_t initial_size = default_stack_size);
+
+            /// \effects Destroys the per-thread stack if it isn't already destroyed.
+            ~temporary_stack_initializer() noexcept;
+
+            temporary_stack_initializer(temporary_stack_initializer&&) = delete;
+            temporary_stack_initializer& operator=(temporary_stack_initializer&&) = delete;
+        };
+
+        /// \effects Creates the per-thread \ref temporary_stack with the given initial size,
+        /// if it wasn't already created.
+        /// \returns The per-thread \ref temporary_stack.
+        /// \requires There must be a per-thread temporary stack (\ref WPI_MEMORY_TEMPORARY_STACK_MODE must not be equal to `0`).
+        /// \note If \ref WPI_MEMORY_TEMPORARY_STACK_MODE is equal to `1`,
+        /// this function can create the temporary stack.
+        /// But if there is no \ref temporary_stack_initializer, it won't be destroyed.
+        /// \relatesalso temporary_stack
+        temporary_stack& get_temporary_stack(
+            std::size_t initial_size = temporary_stack_initializer::default_stack_size);
+
+        /// A stateful \concept{concept_rawallocator,RawAllocator} that handles temporary allocations.
+        /// It works similar to \c alloca() but uses a seperate \ref memory_stack for the allocations,
+        /// instead of the actual program stack.
+        /// This avoids the stack overflow error and is portable,
+        /// with a similar speed.
+        /// All allocations done in the scope of the allocator object are automatically freed when the object is destroyed.
+        /// \ingroup allocator
+        class temporary_allocator
+        {
+        public:
+            /// \effects Creates it by using the \ref get_temporary_stack() to get the temporary stack.
+            /// \requires There must be a per-thread temporary stack (\ref WPI_MEMORY_TEMPORARY_STACK_MODE must not be equal to `0`).
+            temporary_allocator();
+
+            /// \effects Creates it by giving it the \ref temporary_stack it uses for allocation.
+            explicit temporary_allocator(temporary_stack& stack);
+
+            ~temporary_allocator() noexcept;
+
+            temporary_allocator(temporary_allocator&&) = delete;
+            temporary_allocator& operator=(temporary_allocator&&) = delete;
+
+            /// \effects Allocates memory from the internal \ref memory_stack by forwarding to it.
+            /// \returns The result of \ref memory_stack::allocate().
+            /// \requires `is_active()` must return `true`.
+            void* allocate(std::size_t size, std::size_t alignment);
+
+            /// \returns Whether or not the allocator object is active.
+            /// \note The active allocator object is the last object created for one stack.
+            /// Moving changes the active allocator.
+            bool is_active() const noexcept;
+
+            /// \effects Instructs it to release unnecessary memory after automatic unwinding occurs.
+            /// This will effectively forward to \ref memory_stack::shrink_to_fit() of the internal stack.
+            /// \note Like the use of the \ref temporary_stack_initializer this can be used as an optimization,
+            /// to tell when the thread's \ref temporary_stack isn't needed anymore and can be destroyed.
+            /// \note It doesn't call shrink to fit immediately, only in the destructor!
+            void shrink_to_fit() noexcept;
+
+            /// \returns The internal stack the temporary allocator is using.
+            /// \requires `is_active()` must return `true`.
+            temporary_stack& get_stack() const noexcept
+            {
+                return unwind_.get_stack();
+            }
+
+        private:
+            memory_stack_raii_unwind<temporary_stack> unwind_;
+            temporary_allocator*                      prev_;
+            bool                                      shrink_to_fit_;
+        };
+
+        template <class Allocator>
+        class allocator_traits;
+
+        /// Specialization of the \ref allocator_traits for \ref temporary_allocator classes.
+        /// \note It is not allowed to mix calls through the specialization and through the member functions,
+        /// i.e. \ref temporary_allocator::allocate() and this \c allocate_node().
+        /// \ingroup allocator
+        template <>
+        class allocator_traits<temporary_allocator>
+        {
+        public:
+            using allocator_type = temporary_allocator;
+            using is_stateful    = std::true_type;
+
+            /// \returns The result of \ref temporary_allocator::allocate().
+            static void* allocate_node(allocator_type& state, std::size_t size,
+                                       std::size_t alignment)
+            {
+                detail::check_allocation_size<bad_node_size>(size,
+                                                             [&] { return max_node_size(state); },
+                                                             {WPI_MEMORY_LOG_PREFIX
+                                                              "::temporary_allocator",
+                                                              &state});
+                return state.allocate(size, alignment);
+            }
+
+            /// \returns The result of \ref temporary_allocator::allocate().
+            static void* allocate_array(allocator_type& state, std::size_t count, std::size_t size,
+                                        std::size_t alignment)
+            {
+                return allocate_node(state, count * size, alignment);
+            }
+
+            /// @{
+            /// \effects Does nothing besides bookmarking for leak checking, if that is enabled.
+            /// Actual deallocation will be done automatically if the allocator object goes out of scope.
+            static void deallocate_node(const allocator_type&, void*, std::size_t,
+                                        std::size_t) noexcept
+            {
+            }
+
+            static void deallocate_array(const allocator_type&, void*, std::size_t, std::size_t,
+                                         std::size_t) noexcept
+            {
+            }
+            /// @}
+
+            /// @{
+            /// \returns The maximum size which is \ref memory_stack::next_capacity() of the internal stack.
+            static std::size_t max_node_size(const allocator_type& state) noexcept
+            {
+                return state.get_stack().next_capacity();
+            }
+
+            static std::size_t max_array_size(const allocator_type& state) noexcept
+            {
+                return max_node_size(state);
+            }
+            /// @}
+
+            /// \returns The maximum possible value since there is no alignment restriction
+            /// (except indirectly through \ref memory_stack::next_capacity()).
+            static std::size_t max_alignment(const allocator_type&) noexcept
+            {
+                return std::size_t(-1);
+            }
+        };
+    } // namespace memory
+} // namespace wpi
+
+#endif // WPI_MEMORY_TEMPORARY_ALLOCATOR_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/threading.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/threading.hpp
new file mode 100644
index 0000000..0314ea4
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/threading.hpp
@@ -0,0 +1,155 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_THREADING_HPP_INCLUDED
+#define WPI_MEMORY_THREADING_HPP_INCLUDED
+
+/// \file
+/// The mutex types.
+
+#include <type_traits>
+
+#include "allocator_traits.hpp"
+#include "config.hpp"
+
+#if WPI_HOSTED_IMPLEMENTATION
+#include <mutex>
+#endif
+
+namespace wpi
+{
+    namespace memory
+    {
+        /// A dummy \c Mutex class that does not lock anything.
+        /// It is a valid \c Mutex and can be used to disable locking anywhere a \c Mutex is requested.
+        /// \ingroup core
+        struct no_mutex
+        {
+            void lock() noexcept {}
+
+            bool try_lock() noexcept
+            {
+                return true;
+            }
+
+            void unlock() noexcept {}
+        };
+
+        /// Specifies whether or not a \concept{concept_rawallocator,RawAllocator} is thread safe as-is.
+        /// This allows to use \ref no_mutex as an optimization.
+        /// Note that stateless allocators are implictly thread-safe.
+        /// Specialize it only for your own stateful allocators.
+        /// \ingroup core
+        template <class RawAllocator>
+        struct is_thread_safe_allocator
+        : std::integral_constant<bool, !allocator_traits<RawAllocator>::is_stateful::value>
+        {
+        };
+
+        namespace detail
+        {
+            // selects a mutex for an Allocator
+            // stateless allocators don't need locking
+            template <class RawAllocator, class Mutex>
+            using mutex_for =
+                typename std::conditional<is_thread_safe_allocator<RawAllocator>::value, no_mutex,
+                                          Mutex>::type;
+
+            // storage for mutexes to use EBO
+            // it provides const lock/unlock function, inherit from it
+            template <class Mutex>
+            class mutex_storage
+            {
+            public:
+                mutex_storage() noexcept = default;
+                mutex_storage(const mutex_storage&) noexcept {}
+
+                mutex_storage& operator=(const mutex_storage&) noexcept
+                {
+                    return *this;
+                }
+
+                void lock() const
+                {
+                    mutex_.lock();
+                }
+
+                void unlock() const noexcept
+                {
+                    mutex_.unlock();
+                }
+
+            protected:
+                ~mutex_storage() noexcept = default;
+
+            private:
+                mutable Mutex mutex_;
+            };
+
+            template <>
+            class mutex_storage<no_mutex>
+            {
+            public:
+                mutex_storage() noexcept = default;
+
+                void lock() const noexcept {}
+                void unlock() const noexcept {}
+
+            protected:
+                ~mutex_storage() noexcept = default;
+            };
+
+            // non changeable pointer to an Allocator that keeps a lock
+            // I don't think EBO is necessary here...
+            template <class Alloc, class Mutex>
+            class locked_allocator
+            {
+            public:
+                locked_allocator(Alloc& alloc, Mutex& m) noexcept : mutex_(&m), alloc_(&alloc)
+                {
+                    mutex_->lock();
+                }
+
+                locked_allocator(locked_allocator&& other) noexcept
+                : mutex_(other.mutex_), alloc_(other.alloc_)
+                {
+                    other.mutex_ = nullptr;
+                    other.alloc_ = nullptr;
+                }
+
+                ~locked_allocator() noexcept
+                {
+                    if (mutex_)
+                        mutex_->unlock();
+                }
+
+                locked_allocator& operator=(locked_allocator&& other) noexcept = delete;
+
+                Alloc& operator*() const noexcept
+                {
+                    WPI_MEMORY_ASSERT(alloc_);
+                    return *alloc_;
+                }
+
+                Alloc* operator->() const noexcept
+                {
+                    WPI_MEMORY_ASSERT(alloc_);
+                    return alloc_;
+                }
+
+            private:
+                Mutex* mutex_; // don't use unqiue_lock to avoid dependency
+                Alloc* alloc_;
+            };
+
+            template <class Alloc, class Mutex>
+            locked_allocator<Alloc, Mutex> lock_allocator(Alloc& a, Mutex& m)
+            {
+                return {a, m};
+            }
+        } // namespace detail
+    }     // namespace memory
+} // namespace wpi
+
+#endif // WPI_MEMORY_THREADING_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/tracking.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/tracking.hpp
new file mode 100644
index 0000000..ccbc343
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/tracking.hpp
@@ -0,0 +1,430 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_TRACKING_HPP_INCLUDED
+#define WPI_MEMORY_TRACKING_HPP_INCLUDED
+
+/// \file
+/// Class \ref wpi::memory::tracked_allocator and related classes and functions.
+
+#include "detail/utility.hpp"
+#include "allocator_traits.hpp"
+#include "memory_arena.hpp"
+
+namespace wpi
+{
+    namespace memory
+    {
+        namespace detail
+        {
+            template <class Allocator, class Tracker>
+            auto set_tracker(int, Allocator& allocator, Tracker* tracker) noexcept
+                -> decltype(allocator.get_allocator().set_tracker(tracker))
+            {
+                return allocator.get_allocator().set_tracker(tracker);
+            }
+            template <class Allocator, class Tracker>
+            void set_tracker(short, Allocator&, Tracker*) noexcept
+            {
+            }
+
+            // used with deeply_tracked_allocator
+            template <class Tracker, class BlockAllocator>
+            class deeply_tracked_block_allocator : WPI_EBO(BlockAllocator)
+            {
+            public:
+                template <typename... Args>
+                deeply_tracked_block_allocator(std::size_t block_size, Args&&... args)
+                : BlockAllocator(block_size, detail::forward<Args>(args)...), tracker_(nullptr)
+                {
+                }
+
+                memory_block allocate_block()
+                {
+                    auto block = BlockAllocator::allocate_block();
+                    if (tracker_) // on first call tracker_ is nullptr
+                        tracker_->on_allocator_growth(block.memory, block.size);
+                    return block;
+                }
+
+                void deallocate_block(memory_block block) noexcept
+                {
+                    if (tracker_) // on last call tracker_ is nullptr again
+                        tracker_->on_allocator_shrinking(block.memory, block.size);
+                    BlockAllocator::deallocate_block(block);
+                }
+
+                std::size_t next_block_size() const noexcept
+                {
+                    return BlockAllocator::next_block_size();
+                }
+
+                void set_tracker(Tracker* tracker) noexcept
+                {
+                    tracker_ = tracker;
+                }
+
+            private:
+                Tracker* tracker_;
+            };
+        } // namespace detail
+
+        /// A \concept{concept_blockallocator,BlockAllocator} adapter that tracks another allocator using a \concept{concept_tracker,tracker}.
+        /// It wraps another \concept{concept_blockallocator,BlockAllocator} and calls the tracker function before forwarding to it.
+        /// The class can then be used anywhere a \concept{concept_blockallocator,BlockAllocator} is required and the memory usage will be tracked.<br>
+        /// It will only call the <tt>on_allocator_growth()</tt> and <tt>on_allocator_shrinking()</tt> tracking functions,
+        /// since a \concept{concept_blockallocator,BlockAllocator} is normally used inside higher allocators only.
+        /// \ingroup adapter
+        template <class Tracker, class BlockOrRawAllocator>
+        class tracked_block_allocator
+        : WPI_EBO(Tracker, make_block_allocator_t<BlockOrRawAllocator>)
+        {
+        public:
+            using allocator_type = make_block_allocator_t<BlockOrRawAllocator>;
+            using tracker        = Tracker;
+
+            /// @{
+            /// \effects Creates it by giving it a \concept{concept_tracker,tracker} and the tracked \concept{concept_rawallocator,RawAllocator}.
+            /// It will embed both objects.
+            explicit tracked_block_allocator(tracker t = {}) noexcept : tracker(detail::move(t)) {}
+
+            tracked_block_allocator(tracker t, allocator_type&& alloc) noexcept
+            : tracker(detail::move(t)), allocator_type(detail::move(alloc))
+            {
+            }
+            /// @}
+
+            /// \effects Creates it in the form required by the concept.
+            /// The allocator will be constructed using \c block_size and \c args.
+            template <typename... Args>
+            tracked_block_allocator(std::size_t block_size, tracker t, Args&&... args)
+            : tracker(detail::move(t)), allocator_type(block_size, detail::forward<Args>(args)...)
+            {
+            }
+
+            /// \effects Calls <tt>Tracker::on_allocator_growth()</tt> after forwarding to the allocator.
+            /// \returns The block as the returned by the allocator.
+            memory_block allocate_block()
+            {
+                auto block = allocator_type::allocate_block();
+                this->on_allocator_growth(block.memory, block.size);
+                return block;
+            }
+
+            /// \effects Calls <tt>Tracker::on_allocator_shrinking()</tt> and forwards to the allocator.
+            void deallocate_block(memory_block block) noexcept
+            {
+                this->on_allocator_shrinking(block.memory, block.size);
+                allocator_type::deallocate_block(block);
+            }
+
+            /// \returns The next block size as returned by the allocator.
+            std::size_t next_block_size() const noexcept
+            {
+                return allocator_type::next_block_size();
+            }
+
+            /// @{
+            /// \returns A (const) reference to the used allocator.
+            allocator_type& get_allocator() noexcept
+            {
+                return *this;
+            }
+
+            const allocator_type& get_allocator() const noexcept
+            {
+                return *this;
+            }
+            /// @}
+
+            /// @{
+            /// \returns A (const) reference to the tracker.
+            tracker& get_tracker() noexcept
+            {
+                return *this;
+            }
+
+            const tracker& get_tracker() const noexcept
+            {
+                return *this;
+            }
+            /// @}
+        };
+
+        /// Similar to \ref tracked_block_allocator, but shares the tracker with the higher level allocator.
+        /// This allows tracking both (de-)allocations and growth with one tracker.
+        /// \note Due to implementation reasons, it cannot track growth and shrinking in the constructor/destructor of the higher level allocator.
+        /// \ingroup adapter
+        template <class Tracker, class BlockOrRawAllocator>
+        using deeply_tracked_block_allocator = WPI_IMPL_DEFINED(
+            detail::deeply_tracked_block_allocator<Tracker,
+                                                   make_block_allocator_t<BlockOrRawAllocator>>);
+
+        /// A \concept{concept_rawallocator,RawAllocator} adapter that tracks another allocator using a \concept{concept_tracker,tracker}.
+        /// It wraps another \concept{concept_rawallocator,RawAllocator} and calls the tracker function before forwarding to it.
+        /// The class can then be used anywhere a \concept{concept_rawallocator,RawAllocator} is required and the memory usage will be tracked.<br>
+        /// If the \concept{concept_rawallocator,RawAllocator} uses \ref deeply_tracked_block_allocator as \concept{concept_blockallocator,BlockAllocator},
+        /// it will also track growth and shrinking of the allocator.
+        /// \ingroup adapter
+        template <class Tracker, class RawAllocator>
+        class tracked_allocator
+        : WPI_EBO(Tracker, allocator_traits<RawAllocator>::allocator_type)
+        {
+            using traits            = allocator_traits<RawAllocator>;
+            using composable_traits = composable_allocator_traits<RawAllocator>;
+
+        public:
+            using allocator_type = typename allocator_traits<RawAllocator>::allocator_type;
+            using tracker        = Tracker;
+
+            using is_stateful = std::integral_constant<bool, traits::is_stateful::value
+                                                                 || !std::is_empty<Tracker>::value>;
+
+            /// @{
+            /// \effects Creates it by giving it a \concept{concept_tracker,tracker} and the tracked \concept{concept_rawallocator,RawAllocator}.
+            /// It will embed both objects.
+            /// \note This will never call the <tt>Tracker::on_allocator_growth()</tt> function.
+            explicit tracked_allocator(tracker t = {}) noexcept
+            : tracked_allocator(detail::move(t), allocator_type{})
+            {
+            }
+
+            tracked_allocator(tracker t, allocator_type&& allocator) noexcept
+            : tracker(detail::move(t)), allocator_type(detail::move(allocator))
+            {
+                detail::set_tracker(0, get_allocator(), &get_tracker());
+            }
+            /// @}
+
+            /// \effects Destroys both tracker and allocator.
+            /// \note This will never call the <tt>Tracker::on_allocator_shrinking()</tt> function.
+            ~tracked_allocator() noexcept
+            {
+                detail::set_tracker(0, get_allocator(), static_cast<tracker*>(nullptr));
+            }
+
+            /// @{
+            /// \effects Moving moves both the tracker and the allocator.
+            tracked_allocator(tracked_allocator&& other) noexcept
+            : tracker(detail::move(other)), allocator_type(detail::move(other))
+            {
+                detail::set_tracker(0, get_allocator(), &get_tracker());
+            }
+
+            tracked_allocator& operator=(tracked_allocator&& other) noexcept
+            {
+                tracker::       operator=(detail::move(other));
+                allocator_type::operator=(detail::move(other));
+                detail::set_tracker(0, get_allocator(), &get_tracker());
+                return *this;
+            }
+            /// @}
+
+            /// \effects Calls <tt>Tracker::on_node_allocation()</tt> and forwards to the allocator.
+            /// If a growth occurs and the allocator is deeply tracked, also calls <tt>Tracker::on_allocator_growth()</tt>.
+            /// \returns The result of <tt>allocate_node()</tt>
+            void* allocate_node(std::size_t size, std::size_t alignment)
+            {
+                auto mem = traits::allocate_node(get_allocator(), size, alignment);
+                this->on_node_allocation(mem, size, alignment);
+                return mem;
+            }
+
+            /// \effects Calls the composable node allocation function.
+            /// If allocation was successful, also calls `Tracker::on_node_allocation()`.
+            /// \returns The result of `try_allocate_node()`.
+            void* try_allocate_node(std::size_t size, std::size_t alignment) noexcept
+            {
+                auto mem = composable_traits::try_allocate_node(get_allocator(), size, alignment);
+                if (mem)
+                    this->on_node_allocation(mem, size, alignment);
+                return mem;
+            }
+
+            /// \effects Calls <tt>Tracker::on_array_allocation()</tt> and forwards to the allocator.
+            /// If a growth occurs and the allocator is deeply tracked, also calls <tt>Tracker::on_allocator_growth()</tt>.
+            /// \returns The result of <tt>allocate_array()</tt>
+            void* allocate_array(std::size_t count, std::size_t size, std::size_t alignment)
+            {
+                auto mem = traits::allocate_array(get_allocator(), count, size, alignment);
+                this->on_array_allocation(mem, count, size, alignment);
+                return mem;
+            }
+
+            /// \effects Calls the composable array allocation function.
+            /// If allocation was succesful, also calls `Tracker::on_array_allocation()`.
+            /// \returns The result of `try_allocate_array()`.
+            void* try_allocate_array(std::size_t count, std::size_t size,
+                                     std::size_t alignment) noexcept
+            {
+                auto mem =
+                    composable_traits::try_allocate_array(get_allocator(), count, size, alignment);
+                if (mem)
+                    this->on_array_allocation(mem, count, size, alignment);
+                return mem;
+            }
+
+            /// \effects Calls <tt>Tracker::on_node_deallocation()</tt> and forwards to the allocator's <tt>deallocate_node()</tt>.
+            /// If shrinking occurs and the allocator is deeply tracked, also calls <tt>Tracker::on_allocator_shrinking()</tt>.
+            void deallocate_node(void* ptr, std::size_t size, std::size_t alignment) noexcept
+            {
+                this->on_node_deallocation(ptr, size, alignment);
+                traits::deallocate_node(get_allocator(), ptr, size, alignment);
+            }
+
+            /// \effects Calls the composable node deallocation function.
+            /// If it was succesful, also calls `Tracker::on_node_deallocation()`.
+            /// \returns The result of `try_deallocate_node()`.
+            bool try_deallocate_node(void* ptr, std::size_t size, std::size_t alignment) noexcept
+            {
+                auto res =
+                    composable_traits::try_deallocate_node(get_allocator(), ptr, size, alignment);
+                if (res)
+                    this->on_node_deallocation(ptr, size, alignment);
+                return res;
+            }
+
+            /// \effects Calls <tt>Tracker::on_array_deallocation()</tt> and forwards to the allocator's <tt>deallocate_array()</tt>.
+            /// If shrinking occurs and the allocator is deeply tracked, also calls <tt>Tracker::on_allocator_shrinking()</tt>.
+            void deallocate_array(void* ptr, std::size_t count, std::size_t size,
+                                  std::size_t alignment) noexcept
+            {
+                this->on_array_deallocation(ptr, count, size, alignment);
+                traits::deallocate_array(get_allocator(), ptr, count, size, alignment);
+            }
+
+            /// \effects Calls the composable array deallocation function.
+            /// If it was succesful, also calls `Tracker::on_array_deallocation()`.
+            /// \returns The result of `try_deallocate_array()`.
+            bool try_deallocate_array(void* ptr, std::size_t count, std::size_t size,
+                                      std::size_t alignment) noexcept
+            {
+                auto res = composable_traits::try_deallocate_array(ptr, count, size, alignment);
+                if (res)
+                    this->on_array_deallocation(ptr, count, size, alignment);
+                return res;
+            }
+
+            /// @{
+            /// \returns The result of the corresponding function on the wrapped allocator.
+            std::size_t max_node_size() const
+            {
+                return traits::max_node_size(get_allocator());
+            }
+
+            std::size_t max_array_size() const
+            {
+                return traits::max_array_size(get_allocator());
+            }
+
+            std::size_t max_alignment() const
+            {
+                return traits::max_alignment(get_allocator());
+            }
+            /// @}
+
+            /// @{
+            /// \returns A (\c const) reference to the wrapped allocator.
+            allocator_type& get_allocator() noexcept
+            {
+                return *this;
+            }
+
+            const allocator_type& get_allocator() const noexcept
+            {
+                return *this;
+            }
+            /// @}
+
+            /// @{
+            /// \returns A (\c const) reference to the tracker.
+            tracker& get_tracker() noexcept
+            {
+                return *this;
+            }
+
+            const tracker& get_tracker() const noexcept
+            {
+                return *this;
+            }
+            /// @}
+        };
+
+        /// \effects Takes a \concept{concept_rawallocator,RawAllocator} and wraps it with a \concept{concept_tracker,tracker}.
+        /// \returns A \ref tracked_allocator with the corresponding parameters forwarded to the constructor.
+        /// \relates tracked_allocator
+        template <class Tracker, class RawAllocator>
+        auto make_tracked_allocator(Tracker t, RawAllocator&& alloc)
+            -> tracked_allocator<Tracker, typename std::decay<RawAllocator>::type>
+        {
+            return tracked_allocator<Tracker, typename std::decay<RawAllocator>::type>{detail::move(
+                                                                                           t),
+                                                                                       detail::move(
+                                                                                           alloc)};
+        }
+
+        namespace detail
+        {
+            template <typename T, bool Block>
+            struct is_block_or_raw_allocator_impl : std::true_type
+            {
+            };
+
+            template <typename T>
+            struct is_block_or_raw_allocator_impl<T, false> : memory::is_raw_allocator<T>
+            {
+            };
+
+            template <typename T>
+            struct is_block_or_raw_allocator
+            : is_block_or_raw_allocator_impl<T, memory::is_block_allocator<T>::value>
+            {
+            };
+
+            template <class RawAllocator, class BlockAllocator>
+            struct rebind_block_allocator;
+
+            template <template <typename...> class RawAllocator, typename... Args,
+                      class OtherBlockAllocator>
+            struct rebind_block_allocator<RawAllocator<Args...>, OtherBlockAllocator>
+            {
+                using type =
+                    RawAllocator<typename std::conditional<is_block_or_raw_allocator<Args>::value,
+                                                           OtherBlockAllocator, Args>::type...>;
+            };
+
+            template <class Tracker, class RawAllocator>
+            using deeply_tracked_block_allocator_for =
+                memory::deeply_tracked_block_allocator<Tracker,
+                                                       typename RawAllocator::allocator_type>;
+
+            template <class Tracker, class RawAllocator>
+            using rebound_allocator = typename rebind_block_allocator<
+                RawAllocator, deeply_tracked_block_allocator_for<Tracker, RawAllocator>>::type;
+        } // namespace detail
+
+        /// A \ref tracked_allocator that has rebound any \concept{concept_blockallocator,BlockAllocator} to the corresponding \ref deeply_tracked_block_allocator.
+        /// This makes it a deeply tracked allocator.<br>
+        /// It replaces each template argument of the given \concept{concept_rawallocator,RawAllocator} for which \ref is_block_allocator or \ref is_raw_allocator is \c true with a \ref deeply_tracked_block_allocator.
+        /// \ingroup adapter
+        template <class Tracker, class RawAllocator>
+        WPI_ALIAS_TEMPLATE(
+            deeply_tracked_allocator,
+            tracked_allocator<Tracker, detail::rebound_allocator<Tracker, RawAllocator>>);
+
+        /// \effects Takes a \concept{concept_rawallocator,RawAllocator} and deeply wraps it with a \concept{concept_tracker,tracker}.
+        /// \returns A \ref deeply_tracked_allocator with the corresponding parameters forwarded to the constructor.
+        /// \relates deeply_tracked_allocator
+        template <class RawAllocator, class Tracker, typename... Args>
+        auto make_deeply_tracked_allocator(Tracker t, Args&&... args)
+            -> deeply_tracked_allocator<Tracker, RawAllocator>
+        {
+            return deeply_tracked_allocator<Tracker, RawAllocator>(detail::move(t),
+                                                                   {detail::forward<Args>(
+                                                                       args)...});
+        }
+    } // namespace memory
+} // namespace wpi
+
+#endif // WPI_MEMORY_TRACKING_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/virtual_memory.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/virtual_memory.hpp
new file mode 100644
index 0000000..33d82f7
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/include/wpi/memory/virtual_memory.hpp
@@ -0,0 +1,202 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_VIRTUAL_MEMORY_HPP_INCLUDED
+#define WPI_MEMORY_VIRTUAL_MEMORY_HPP_INCLUDED
+
+/// \file
+/// Virtual memory api and (low-level) allocator classes.
+
+#include <cstddef>
+#include <type_traits>
+
+#include "detail/debug_helpers.hpp"
+#include "detail/utility.hpp"
+#include "config.hpp"
+
+#if WPI_MEMORY_EXTERN_TEMPLATE
+#include "allocator_traits.hpp"
+#endif
+
+namespace wpi
+{
+    namespace memory
+    {
+        namespace detail
+        {
+            struct virtual_memory_allocator_leak_handler
+            {
+                void operator()(std::ptrdiff_t amount);
+            };
+
+            WPI_MEMORY_GLOBAL_LEAK_CHECKER(virtual_memory_allocator_leak_handler,
+                                                 virtual_memory_allocator_leak_checker)
+        } // namespace detail
+
+        /// The page size of the virtual memory.
+        /// All virtual memory allocations must be multiple of this size.
+        /// It is usually 4KiB.
+        /// \ingroup allocator
+        /// \deprecated use \ref get_virtual_memory_page_size instead.
+        extern const std::size_t virtual_memory_page_size;
+
+        /// \returns the page size of the virtual memory.
+        /// All virtual memory allocations must be multiple of this size.
+        /// It is usually 4KiB.
+        /// \ingroup allocator
+        std::size_t get_virtual_memory_page_size() noexcept;
+
+        /// Reserves virtual memory.
+        /// \effects Reserves the given number of pages.
+        /// Each page is \ref virtual_memory_page_size big.
+        /// \returns The address of the first reserved page,
+        /// or \c nullptr in case of error.
+        /// \note The memory may not be used, it must first be commited.
+        /// \ingroup allocator
+        void* virtual_memory_reserve(std::size_t no_pages) noexcept;
+
+        /// Releases reserved virtual memory.
+        /// \effects Returns previously reserved pages to the system.
+        /// \requires \c pages must come from a previous call to \ref virtual_memory_reserve with the same \c calc_no_pages,
+        /// it must not be \c nullptr.
+        /// \ingroup allocator
+        void virtual_memory_release(void* pages, std::size_t no_pages) noexcept;
+
+        /// Commits reserved virtual memory.
+        /// \effects Marks \c calc_no_pages pages starting at the given address available for use.
+        /// \returns The beginning of the committed area, i.e. \c memory, or \c nullptr in case of error.
+        /// \requires The memory must be previously reserved.
+        /// \ingroup allocator
+        void* virtual_memory_commit(void* memory, std::size_t no_pages) noexcept;
+
+        /// Decommits commited virtual memory.
+        /// \effects Puts commited memory back in the reserved state.
+        /// \requires \c memory must come from a previous call to \ref virtual_memory_commit with the same \c calc_no_pages
+        /// it must not be \c nullptr.
+        /// \ingroup allocator
+        void virtual_memory_decommit(void* memory, std::size_t no_pages) noexcept;
+
+        /// A stateless \concept{concept_rawallocator,RawAllocator} that allocates memory using the virtual memory allocation functions.
+        /// It does not prereserve any memory and will always reserve and commit combined.
+        /// \ingroup allocator
+        class virtual_memory_allocator
+        : WPI_EBO(detail::global_leak_checker<detail::virtual_memory_allocator_leak_handler>)
+        {
+        public:
+            using is_stateful = std::false_type;
+
+            virtual_memory_allocator() noexcept = default;
+            virtual_memory_allocator(virtual_memory_allocator&&) noexcept {}
+            ~virtual_memory_allocator() noexcept = default;
+
+            virtual_memory_allocator& operator=(virtual_memory_allocator&&) noexcept
+            {
+                return *this;
+            }
+
+            /// \effects A \concept{concept_rawallocator,RawAllocator} allocation function.
+            /// It uses \ref virtual_memory_reserve followed by \ref virtual_memory_commit for the allocation.
+            /// The number of pages allocated will be the minimum to hold \c size continuous bytes,
+            /// i.e. \c size will be rounded up to the next multiple.
+            /// If debug fences are activated, one additional page before and after the memory will be allocated.
+            /// \returns A pointer to a \concept{concept_node,node}, it will never be \c nullptr.
+            /// It will always be aligned on a fence boundary, regardless of the alignment parameter.
+            /// \throws An exception of type \ref out_of_memory or whatever is thrown by its handler if the allocation fails.
+            void* allocate_node(std::size_t size, std::size_t alignment);
+
+            /// \effects A \concept{concept_rawallocator,RawAllocator} deallocation function.
+            /// It calls \ref virtual_memory_decommit followed by \ref virtual_memory_release for the deallocation.
+            void deallocate_node(void* node, std::size_t size, std::size_t alignment) noexcept;
+
+            /// \returns The maximum node size by returning the maximum value.
+            std::size_t max_node_size() const noexcept;
+
+            /// \returns The maximum alignment which is the same as the \ref virtual_memory_page_size.
+            std::size_t max_alignment() const noexcept;
+        };
+
+#if WPI_MEMORY_EXTERN_TEMPLATE
+        extern template class allocator_traits<virtual_memory_allocator>;
+#endif
+
+        struct memory_block;
+        struct allocator_info;
+
+        /// A \concept{concept_blockallocator,BlockAllocator} that reserves virtual memory and commits it part by part.
+        /// It is similar to \ref memory_stack but does not support growing and uses virtual memory,
+        /// also meant for big blocks not small allocations.
+        /// \ingroup allocator
+        class virtual_block_allocator
+        {
+        public:
+            /// \effects Creates it giving it the block size and the total number of blocks it can allocate.
+            /// It reserves enough virtual memory for <tt>block_size * no_blocks</tt>.
+            /// \requires \c block_size must be non-zero and a multiple of the \ref virtual_memory_page_size.
+            /// \c no_blocks must be bigger than \c 1.
+            /// \throws \ref out_of_memory if it cannot reserve the virtual memory.
+            explicit virtual_block_allocator(std::size_t block_size, std::size_t no_blocks);
+
+            /// \effects Releases the reserved virtual memory.
+            ~virtual_block_allocator() noexcept;
+
+            /// @{
+            /// \effects Moves the block allocator, it transfers ownership over the reserved area.
+            /// This does not invalidate any memory blocks.
+            virtual_block_allocator(virtual_block_allocator&& other) noexcept
+            : cur_(other.cur_), end_(other.end_), block_size_(other.block_size_)
+            {
+                other.cur_ = other.end_ = nullptr;
+                other.block_size_       = 0;
+            }
+
+            virtual_block_allocator& operator=(virtual_block_allocator&& other) noexcept
+            {
+                virtual_block_allocator tmp(detail::move(other));
+                swap(*this, tmp);
+                return *this;
+            }
+            /// @}
+
+            /// \effects Swaps the ownership over the reserved memory.
+            /// This does not invalidate any memory blocks.
+            friend void swap(virtual_block_allocator& a, virtual_block_allocator& b) noexcept
+            {
+                detail::adl_swap(a.cur_, b.cur_);
+                detail::adl_swap(a.end_, b.end_);
+                detail::adl_swap(a.block_size_, b.block_size_);
+            }
+
+            /// \effects Allocates a new memory block by committing the next \ref next_block_size() number of bytes.
+            /// \returns The \ref memory_block committed.
+            /// \throws \ref out_of_memory if it cannot commit the memory or the \ref capacity_left() is exhausted.
+            memory_block allocate_block();
+
+            /// \effects Deallocates the last allocated memory block by decommitting it.
+            /// This block will be returned again on the next call to \ref allocate_block().
+            /// \requires \c block must be the current top block of the memory,
+            /// this is guaranteed by \ref memory_arena.
+            void deallocate_block(memory_block block) noexcept;
+
+            /// \returns The next block size, this is the block size of the constructor.
+            std::size_t next_block_size() const noexcept
+            {
+                return block_size_;
+            }
+
+            /// \returns The number of blocks that can be committed until it runs out of memory.
+            std::size_t capacity_left() const noexcept
+            {
+                return static_cast<std::size_t>(end_ - cur_) / block_size_;
+            }
+
+        private:
+            allocator_info info() noexcept;
+
+            char *      cur_, *end_;
+            std::size_t block_size_;
+        };
+    } // namespace memory
+} // namespace wpi
+
+#endif //WPI_MEMORY_VIRTUAL_MEMORY_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/debugging.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/debugging.cpp
new file mode 100644
index 0000000..be1b033
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/debugging.cpp
@@ -0,0 +1,109 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#include "wpi/memory/debugging.hpp"
+
+#if WPI_HOSTED_IMPLEMENTATION
+#include <cstdio>
+#endif
+
+#include <atomic>
+#include <cstdlib>
+
+#include "wpi/memory/error.hpp"
+
+using namespace wpi::memory;
+
+namespace
+{
+    void default_leak_handler(const allocator_info& info, std::ptrdiff_t amount) noexcept
+    {
+#if WPI_HOSTED_IMPLEMENTATION
+        if (amount > 0)
+            std::fprintf(stderr, "[%s] Allocator %s (at %p) leaked %zu bytes.\n",
+                         WPI_MEMORY_LOG_PREFIX, info.name, info.allocator,
+                         std::size_t(amount));
+        else
+            std::fprintf(stderr,
+                         "[%s] Allocator %s (at %p) has deallocated %zu bytes more than "
+                         "ever allocated "
+                         "(it's amazing you're able to see this message!).\n",
+                         WPI_MEMORY_LOG_PREFIX, info.name, info.allocator,
+                         std::size_t(-amount));
+#else
+        (void)info;
+        (void)amount;
+#endif
+    }
+
+    std::atomic<leak_handler> leak_h(default_leak_handler);
+} // namespace
+
+leak_handler wpi::memory::set_leak_handler(leak_handler h)
+{
+    return leak_h.exchange(h ? h : default_leak_handler);
+}
+
+leak_handler wpi::memory::get_leak_handler()
+{
+    return leak_h;
+}
+
+namespace
+{
+    void default_invalid_ptr_handler(const allocator_info& info, const void* ptr) noexcept
+    {
+#if WPI_HOSTED_IMPLEMENTATION
+        std::fprintf(stderr,
+                     "[%s] Deallocation function of allocator %s (at %p) received invalid "
+                     "pointer %p\n",
+                     WPI_MEMORY_LOG_PREFIX, info.name, info.allocator, ptr);
+#endif
+        (void)info;
+        (void)ptr;
+        std::abort();
+    }
+
+    std::atomic<invalid_pointer_handler> invalid_ptr_h(default_invalid_ptr_handler);
+} // namespace
+
+invalid_pointer_handler wpi::memory::set_invalid_pointer_handler(invalid_pointer_handler h)
+{
+    return invalid_ptr_h.exchange(h ? h : default_invalid_ptr_handler);
+}
+
+invalid_pointer_handler wpi::memory::get_invalid_pointer_handler()
+{
+    return invalid_ptr_h;
+}
+
+namespace
+{
+    void default_buffer_overflow_handler(const void* memory, std::size_t node_size,
+                                         const void* ptr) noexcept
+    {
+#if WPI_HOSTED_IMPLEMENTATION
+        std::fprintf(stderr,
+                     "[%s] Buffer overflow at address %p detected, corresponding memory "
+                     "block %p has only size %zu.\n",
+                     WPI_MEMORY_LOG_PREFIX, ptr, memory, node_size);
+#endif
+        (void)memory;
+        (void)node_size;
+        (void)ptr;
+        std::abort();
+    }
+
+    std::atomic<buffer_overflow_handler> buffer_overflow_h(default_buffer_overflow_handler);
+} // namespace
+
+buffer_overflow_handler wpi::memory::set_buffer_overflow_handler(buffer_overflow_handler h)
+{
+    return buffer_overflow_h.exchange(h ? h : default_buffer_overflow_handler);
+}
+
+buffer_overflow_handler wpi::memory::get_buffer_overflow_handler()
+{
+    return buffer_overflow_h;
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/detail/align.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/detail/align.cpp
new file mode 100644
index 0000000..e1c4f2a
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/detail/align.cpp
@@ -0,0 +1,22 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#include "wpi/memory/detail/align.hpp"
+
+#include "wpi/memory/detail/ilog2.hpp"
+
+using namespace wpi::memory;
+using namespace detail;
+
+bool wpi::memory::detail::is_aligned(void* ptr, std::size_t alignment) noexcept
+{
+    WPI_MEMORY_ASSERT(is_valid_alignment(alignment));
+    auto address = reinterpret_cast<std::uintptr_t>(ptr);
+    return address % alignment == 0u;
+}
+
+std::size_t wpi::memory::detail::alignment_for(std::size_t size) noexcept
+{
+    return size >= max_alignment ? max_alignment : (std::size_t(1) << ilog2(size));
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/detail/assert.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/detail/assert.cpp
new file mode 100644
index 0000000..497f7f8
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/detail/assert.cpp
@@ -0,0 +1,34 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#include "wpi/memory/detail/assert.hpp"
+
+#if WPI_HOSTED_IMPLEMENTATION
+#include <cstdio>
+#endif
+
+#include <cstdlib>
+
+#include "wpi/memory/error.hpp"
+
+using namespace wpi::memory;
+using namespace detail;
+
+void detail::handle_failed_assert(const char* msg, const char* file, int line,
+                                  const char* fnc) noexcept
+{
+#if WPI_HOSTED_IMPLEMENTATION
+    std::fprintf(stderr, "[%s] Assertion failure in function %s (%s:%d): %s.\n",
+                 WPI_MEMORY_LOG_PREFIX, fnc, file, line, msg);
+#endif
+    std::abort();
+}
+
+void detail::handle_warning(const char* msg, const char* file, int line, const char* fnc) noexcept
+{
+#if WPI_HOSTED_IMPLEMENTATION
+    std::fprintf(stderr, "[%s] Warning triggered in function %s (%s:%d): %s.\n",
+                 WPI_MEMORY_LOG_PREFIX, fnc, file, line, msg);
+#endif
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/detail/debug_helpers.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/detail/debug_helpers.cpp
new file mode 100644
index 0000000..b5afb20
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/detail/debug_helpers.cpp
@@ -0,0 +1,87 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#include "wpi/memory/detail/debug_helpers.hpp"
+
+#if WPI_HOSTED_IMPLEMENTATION
+#include <cstring>
+#endif
+
+#include "wpi/memory/debugging.hpp"
+
+using namespace wpi::memory;
+using namespace detail;
+
+#if WPI_MEMORY_DEBUG_FILL
+void detail::debug_fill(void* memory, std::size_t size, debug_magic m) noexcept
+{
+#if WPI_HOSTED_IMPLEMENTATION
+    std::memset(memory, static_cast<int>(m), size);
+#else
+    // do the naive loop :(
+    auto ptr = static_cast<unsigned char*>(memory);
+    for (std::size_t i = 0u; i != size; ++i)
+        *ptr++ = static_cast<unsigned char>(m);
+#endif
+}
+
+void* detail::debug_is_filled(void* memory, std::size_t size, debug_magic m) noexcept
+{
+    auto byte = static_cast<unsigned char*>(memory);
+    for (auto end = byte + size; byte != end; ++byte)
+        if (*byte != static_cast<unsigned char>(m))
+            return byte;
+    return nullptr;
+}
+
+void* detail::debug_fill_new(void* memory, std::size_t node_size, std::size_t fence_size) noexcept
+{
+    if (!debug_fence_size)
+        fence_size = 0u; // force override of fence_size
+
+    auto mem = static_cast<char*>(memory);
+    debug_fill(mem, fence_size, debug_magic::fence_memory);
+
+    mem += fence_size;
+    debug_fill(mem, node_size, debug_magic::new_memory);
+
+    debug_fill(mem + node_size, fence_size, debug_magic::fence_memory);
+
+    return mem;
+}
+
+void* detail::debug_fill_free(void* memory, std::size_t node_size, std::size_t fence_size) noexcept
+{
+    if (!debug_fence_size)
+        fence_size = 0u; // force override of fence_size
+
+    debug_fill(memory, node_size, debug_magic::freed_memory);
+
+    auto pre_fence = static_cast<unsigned char*>(memory) - fence_size;
+    if (auto pre_dirty = debug_is_filled(pre_fence, fence_size, debug_magic::fence_memory))
+        get_buffer_overflow_handler()(memory, node_size, pre_dirty);
+
+    auto post_mem = static_cast<unsigned char*>(memory) + node_size;
+    if (auto post_dirty = debug_is_filled(post_mem, fence_size, debug_magic::fence_memory))
+        get_buffer_overflow_handler()(memory, node_size, post_dirty);
+
+    return pre_fence;
+}
+
+void detail::debug_fill_internal(void* memory, std::size_t size, bool free) noexcept
+{
+    debug_fill(memory, size,
+               free ? debug_magic::internal_freed_memory : debug_magic::internal_memory);
+}
+#endif
+
+void detail::debug_handle_invalid_ptr(const allocator_info& info, void* ptr)
+{
+    get_invalid_pointer_handler()(info, ptr);
+}
+
+void detail::debug_handle_memory_leak(const allocator_info& info, std::ptrdiff_t amount)
+{
+    get_leak_handler()(info, amount);
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/detail/free_list.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/detail/free_list.cpp
new file mode 100644
index 0000000..2ca7034
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/detail/free_list.cpp
@@ -0,0 +1,557 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#include "wpi/memory/detail/free_list.hpp"
+
+#include "wpi/memory/detail/align.hpp"
+#include "wpi/memory/detail/debug_helpers.hpp"
+#include "wpi/memory/detail/assert.hpp"
+#include "wpi/memory/debugging.hpp"
+#include "wpi/memory/error.hpp"
+
+#include "free_list_utils.hpp"
+
+using namespace wpi::memory;
+using namespace detail;
+
+namespace
+{
+    // i.e. array
+    struct interval
+    {
+        char* prev;  // last before
+        char* first; // first in
+        char* last;  // last in
+        char* next;  // first after
+
+        // number of nodes in the interval
+        std::size_t size(std::size_t node_size) const noexcept
+        {
+            // last is inclusive, so add actual_size to it
+            // note: cannot use next, might not be directly after
+            auto end = last + node_size;
+            WPI_MEMORY_ASSERT(static_cast<std::size_t>(end - first) % node_size == 0u);
+            return static_cast<std::size_t>(end - first) / node_size;
+        }
+    };
+
+    // searches for n consecutive bytes
+    // begin and end are the proxy nodes
+    // assumes list is not empty
+    // similar to list_search_array()
+    interval list_search_array(char* first, std::size_t bytes_needed,
+                               std::size_t node_size) noexcept
+    {
+        interval i;
+        i.prev  = nullptr;
+        i.first = first;
+        // i.last/next are used as iterator for the end of the interval
+        i.last = first;
+        i.next = list_get_next(first);
+
+        auto bytes_so_far = node_size;
+        while (i.next)
+        {
+            if (i.last + node_size != i.next) // not continous
+            {
+                // restart at next
+                i.prev  = i.last;
+                i.first = i.next;
+                i.last  = i.next;
+                i.next  = list_get_next(i.last);
+
+                bytes_so_far = node_size;
+            }
+            else
+            {
+                // extend interval
+                auto new_next = list_get_next(i.next);
+                i.last        = i.next;
+                i.next        = new_next;
+
+                bytes_so_far += node_size;
+                if (bytes_so_far >= bytes_needed)
+                    return i;
+            }
+        }
+        // not enough continuous space
+        return {nullptr, nullptr, nullptr, nullptr};
+    }
+
+    // similar to list_search_array()
+    // begin/end are proxy nodes
+    interval xor_list_search_array(char* begin, char* end, std::size_t bytes_needed,
+                                   std::size_t node_size) noexcept
+    {
+        interval i;
+        i.prev  = begin;
+        i.first = xor_list_get_other(begin, nullptr);
+        // i.last/next are used as iterator for the end of the interval
+        i.last = i.first;
+        i.next = xor_list_get_other(i.last, i.prev);
+
+        auto bytes_so_far = node_size;
+        while (i.next != end)
+        {
+            if (i.last + node_size != i.next) // not continous
+            {
+                // restart at i.next
+                i.prev  = i.last;
+                i.first = i.next;
+                i.last  = i.next;
+                i.next  = xor_list_get_other(i.first, i.prev);
+
+                bytes_so_far = node_size;
+            }
+            else
+            {
+                // extend interval
+                auto new_next = xor_list_get_other(i.next, i.last);
+                i.last        = i.next;
+                i.next        = new_next;
+
+                bytes_so_far += node_size;
+                if (bytes_so_far >= bytes_needed)
+                    return i;
+            }
+        }
+        // not enough continuous space
+        return {nullptr, nullptr, nullptr, nullptr};
+    }
+} // namespace
+
+constexpr std::size_t free_memory_list::min_element_size;
+constexpr std::size_t free_memory_list::min_element_alignment;
+
+free_memory_list::free_memory_list(std::size_t node_size) noexcept
+: first_(nullptr),
+  node_size_(node_size > min_element_size ? node_size : min_element_size),
+  capacity_(0u)
+{
+}
+
+free_memory_list::free_memory_list(std::size_t node_size, void* mem, std::size_t size) noexcept
+: free_memory_list(node_size)
+{
+    insert(mem, size);
+}
+
+free_memory_list::free_memory_list(free_memory_list&& other) noexcept
+: first_(other.first_), node_size_(other.node_size_), capacity_(other.capacity_)
+{
+    other.first_    = nullptr;
+    other.capacity_ = 0u;
+}
+
+free_memory_list& free_memory_list::operator=(free_memory_list&& other) noexcept
+{
+    free_memory_list tmp(detail::move(other));
+    swap(*this, tmp);
+    return *this;
+}
+
+void wpi::memory::detail::swap(free_memory_list& a, free_memory_list& b) noexcept
+{
+    detail::adl_swap(a.first_, b.first_);
+    detail::adl_swap(a.node_size_, b.node_size_);
+    detail::adl_swap(a.capacity_, b.capacity_);
+}
+
+void free_memory_list::insert(void* mem, std::size_t size) noexcept
+{
+    WPI_MEMORY_ASSERT(mem);
+    WPI_MEMORY_ASSERT(is_aligned(mem, alignment()));
+    detail::debug_fill_internal(mem, size, false);
+
+    insert_impl(mem, size);
+}
+
+void* free_memory_list::allocate() noexcept
+{
+    WPI_MEMORY_ASSERT(!empty());
+    --capacity_;
+
+    auto mem = first_;
+    first_   = list_get_next(first_);
+    return detail::debug_fill_new(mem, node_size_, 0);
+}
+
+void* free_memory_list::allocate(std::size_t n) noexcept
+{
+    WPI_MEMORY_ASSERT(!empty());
+    if (n <= node_size_)
+        return allocate();
+
+    auto i = list_search_array(first_, n, node_size_);
+    if (i.first == nullptr)
+        return nullptr;
+
+    if (i.prev)
+        list_set_next(i.prev, i.next); // change next from previous to first after
+    else
+        first_ = i.next;
+    capacity_ -= i.size(node_size_);
+
+    return detail::debug_fill_new(i.first, n, 0);
+}
+
+void free_memory_list::deallocate(void* ptr) noexcept
+{
+    ++capacity_;
+
+    auto node = static_cast<char*>(detail::debug_fill_free(ptr, node_size_, 0));
+    list_set_next(node, first_);
+    first_ = node;
+}
+
+void free_memory_list::deallocate(void* ptr, std::size_t n) noexcept
+{
+    if (n <= node_size_)
+        deallocate(ptr);
+    else
+    {
+        auto mem = detail::debug_fill_free(ptr, n, 0);
+        insert_impl(mem, n);
+    }
+}
+
+std::size_t free_memory_list::alignment() const noexcept
+{
+    return alignment_for(node_size_);
+}
+
+void free_memory_list::insert_impl(void* mem, std::size_t size) noexcept
+{
+    auto no_nodes = size / node_size_;
+    WPI_MEMORY_ASSERT(no_nodes > 0);
+
+    auto cur = static_cast<char*>(mem);
+    for (std::size_t i = 0u; i != no_nodes - 1; ++i)
+    {
+        list_set_next(cur, cur + node_size_);
+        cur += node_size_;
+    }
+    list_set_next(cur, first_);
+    first_ = static_cast<char*>(mem);
+
+    capacity_ += no_nodes;
+}
+
+namespace
+{
+    // converts a block into a linked list
+    void xor_link_block(void* memory, std::size_t node_size, std::size_t no_nodes, char* prev,
+                        char* next) noexcept
+    {
+        auto cur = static_cast<char*>(memory);
+        xor_list_change(prev, next, cur); // change next pointer of prev
+
+        auto last_cur = prev;
+        for (std::size_t i = 0u; i != no_nodes - 1; ++i)
+        {
+            xor_list_set(cur, last_cur,
+                         cur + node_size); // cur gets last_cur and next node in continous memory
+            last_cur = cur;
+            cur += node_size;
+        }
+        xor_list_set(cur, last_cur, next); // last memory node gets next as next
+        xor_list_change(next, prev, cur);  // change prev pointer of next
+    }
+
+    struct pos
+    {
+        char *prev, *next;
+    };
+
+    // finds position to insert memory to keep list ordered
+    // first_prev -> first -> ... (memory somewhere here) ... -> last -> last_next
+    pos find_pos_interval(const allocator_info& info, char* memory, char* first_prev, char* first,
+                          char* last, char* last_next) noexcept
+    {
+        // note: first_prev/last_next can be the proxy nodes, then first_prev isn't necessarily less than first!
+        WPI_MEMORY_ASSERT(less(first, memory) && less(memory, last));
+
+        // need to insert somewhere in the middle
+        // search through the entire list
+        // search from both ends at once
+        auto cur_forward  = first;
+        auto prev_forward = first_prev;
+
+        auto cur_backward  = last;
+        auto prev_backward = last_next;
+
+        do
+        {
+            if (greater(cur_forward, memory))
+                return {prev_forward, cur_forward};
+            else if (less(cur_backward, memory))
+                // the next position is the previous backwards pointer
+                return {cur_backward, prev_backward};
+            debug_check_double_dealloc([&]
+                                       { return cur_forward != memory && cur_backward != memory; },
+                                       info, memory);
+            xor_list_iter_next(cur_forward, prev_forward);
+            xor_list_iter_next(cur_backward, prev_backward);
+        } while (less(prev_forward, prev_backward));
+
+        // ran outside of list
+        debug_check_double_dealloc([] { return false; }, info, memory);
+        return {nullptr, nullptr};
+    }
+
+    // finds the position in the entire list
+    pos find_pos(const allocator_info& info, char* memory, char* begin_node, char* end_node,
+                 char* last_dealloc, char* last_dealloc_prev) noexcept
+    {
+        auto first = xor_list_get_other(begin_node, nullptr);
+        auto last  = xor_list_get_other(end_node, nullptr);
+
+        if (greater(first, memory))
+            // insert at front
+            return {begin_node, first};
+        else if (less(last, memory))
+            // insert at the end
+            return {last, end_node};
+        else if (less(last_dealloc_prev, memory) && less(memory, last_dealloc))
+            // insert before last_dealloc
+            return {last_dealloc_prev, last_dealloc};
+        else if (less(memory, last_dealloc))
+            // insert into [first, last_dealloc_prev]
+            return find_pos_interval(info, memory, begin_node, first, last_dealloc_prev,
+                                     last_dealloc);
+        else if (greater(memory, last_dealloc))
+            // insert into (last_dealloc, last]
+            return find_pos_interval(info, memory, last_dealloc_prev, last_dealloc, last, end_node);
+
+        WPI_MEMORY_UNREACHABLE("memory must be in some half or outside");
+        return {nullptr, nullptr};
+    }
+} // namespace
+
+constexpr std::size_t ordered_free_memory_list::min_element_size;
+constexpr std::size_t ordered_free_memory_list::min_element_alignment;
+
+ordered_free_memory_list::ordered_free_memory_list(std::size_t node_size) noexcept
+: node_size_(node_size > min_element_size ? node_size : min_element_size),
+  capacity_(0u),
+  last_dealloc_(end_node()),
+  last_dealloc_prev_(begin_node())
+{
+    xor_list_set(begin_node(), nullptr, end_node());
+    xor_list_set(end_node(), begin_node(), nullptr);
+}
+
+ordered_free_memory_list::ordered_free_memory_list(ordered_free_memory_list&& other) noexcept
+: node_size_(other.node_size_), capacity_(other.capacity_)
+{
+    if (!other.empty())
+    {
+        auto first = xor_list_get_other(other.begin_node(), nullptr);
+        auto last  = xor_list_get_other(other.end_node(), nullptr);
+
+        xor_list_set(begin_node(), nullptr, first);
+        xor_list_change(first, other.begin_node(), begin_node());
+        xor_list_change(last, other.end_node(), end_node());
+        xor_list_set(end_node(), last, nullptr);
+
+        other.capacity_ = 0u;
+        xor_list_set(other.begin_node(), nullptr, other.end_node());
+        xor_list_set(other.end_node(), other.begin_node(), nullptr);
+    }
+    else
+    {
+        xor_list_set(begin_node(), nullptr, end_node());
+        xor_list_set(end_node(), begin_node(), nullptr);
+    }
+
+    // for programming convenience, last_dealloc is reset
+    last_dealloc_prev_ = begin_node();
+    last_dealloc_      = xor_list_get_other(last_dealloc_prev_, nullptr);
+}
+
+void wpi::memory::detail::swap(ordered_free_memory_list& a,
+                                     ordered_free_memory_list& b) noexcept
+{
+    auto a_first = xor_list_get_other(a.begin_node(), nullptr);
+    auto a_last  = xor_list_get_other(a.end_node(), nullptr);
+
+    auto b_first = xor_list_get_other(b.begin_node(), nullptr);
+    auto b_last  = xor_list_get_other(b.end_node(), nullptr);
+
+    if (!a.empty())
+    {
+        xor_list_set(b.begin_node(), nullptr, a_first);
+        xor_list_change(a_first, a.begin_node(), b.begin_node());
+        xor_list_change(a_last, a.end_node(), b.end_node());
+        xor_list_set(b.end_node(), a_last, nullptr);
+    }
+    else
+    {
+        xor_list_set(b.begin_node(), nullptr, b.end_node());
+        xor_list_set(b.end_node(), b.begin_node(), nullptr);
+    }
+
+    if (!b.empty())
+    {
+        xor_list_set(a.begin_node(), nullptr, b_first);
+        xor_list_change(b_first, b.begin_node(), a.begin_node());
+        xor_list_change(b_last, b.end_node(), a.end_node());
+        xor_list_set(a.end_node(), b_last, nullptr);
+    }
+    else
+    {
+        xor_list_set(a.begin_node(), nullptr, a.end_node());
+        xor_list_set(a.end_node(), a.begin_node(), nullptr);
+    }
+
+    detail::adl_swap(a.node_size_, b.node_size_);
+    detail::adl_swap(a.capacity_, b.capacity_);
+
+    // for programming convenience, last_dealloc is reset
+    a.last_dealloc_prev_ = a.begin_node();
+    a.last_dealloc_      = xor_list_get_other(a.last_dealloc_prev_, nullptr);
+
+    b.last_dealloc_prev_ = b.begin_node();
+    b.last_dealloc_      = xor_list_get_other(b.last_dealloc_prev_, nullptr);
+}
+
+void ordered_free_memory_list::insert(void* mem, std::size_t size) noexcept
+{
+    WPI_MEMORY_ASSERT(mem);
+    WPI_MEMORY_ASSERT(is_aligned(mem, alignment()));
+    detail::debug_fill_internal(mem, size, false);
+
+    insert_impl(mem, size);
+}
+
+void* ordered_free_memory_list::allocate() noexcept
+{
+    WPI_MEMORY_ASSERT(!empty());
+
+    // remove first node
+    auto prev = begin_node();
+    auto node = xor_list_get_other(prev, nullptr);
+    auto next = xor_list_get_other(node, prev);
+
+    xor_list_set(prev, nullptr, next); // link prev to next
+    xor_list_change(next, node, prev); // change prev of next
+    --capacity_;
+
+    if (node == last_dealloc_)
+    {
+        // move last_dealloc_ one further in
+        last_dealloc_ = next;
+        WPI_MEMORY_ASSERT(last_dealloc_prev_ == prev);
+    }
+    else if (node == last_dealloc_prev_)
+    {
+        // now the previous node is the node before ours
+        last_dealloc_prev_ = prev;
+        WPI_MEMORY_ASSERT(last_dealloc_ == next);
+    }
+
+    return detail::debug_fill_new(node, node_size_, 0);
+}
+
+void* ordered_free_memory_list::allocate(std::size_t n) noexcept
+{
+    WPI_MEMORY_ASSERT(!empty());
+
+    if (n <= node_size_)
+        return allocate();
+
+    auto i = xor_list_search_array(begin_node(), end_node(), n, node_size_);
+    if (i.first == nullptr)
+        return nullptr;
+
+    xor_list_change(i.prev, i.first, i.next); // change next pointer from i.prev to i.next
+    xor_list_change(i.next, i.last, i.prev);  // change prev pointer from i.next to i.prev
+    capacity_ -= i.size(node_size_);
+
+    // if last_dealloc_ points into the array being removed
+    if ((less_equal(i.first, last_dealloc_) && less_equal(last_dealloc_, i.last)))
+    {
+        // move last_dealloc just outside range
+        last_dealloc_      = i.next;
+        last_dealloc_prev_ = i.prev;
+    }
+    // if the previous deallocation is the last element of the array
+    else if (last_dealloc_prev_ == i.last)
+    {
+        // it is now the last element before the array
+        WPI_MEMORY_ASSERT(last_dealloc_ == i.next);
+        last_dealloc_prev_ = i.prev;
+    }
+
+    return detail::debug_fill_new(i.first, n, 0);
+}
+
+void ordered_free_memory_list::deallocate(void* ptr) noexcept
+{
+    auto node = static_cast<char*>(debug_fill_free(ptr, node_size_, 0));
+
+    auto p =
+        find_pos(allocator_info(WPI_MEMORY_LOG_PREFIX "::detail::ordered_free_memory_list",
+                                this),
+                 node, begin_node(), end_node(), last_dealloc_, last_dealloc_prev_);
+
+    xor_list_insert(node, p.prev, p.next);
+    ++capacity_;
+
+    last_dealloc_      = node;
+    last_dealloc_prev_ = p.prev;
+}
+
+void ordered_free_memory_list::deallocate(void* ptr, std::size_t n) noexcept
+{
+    if (n <= node_size_)
+        deallocate(ptr);
+    else
+    {
+        auto mem  = detail::debug_fill_free(ptr, n, 0);
+        auto prev = insert_impl(mem, n);
+
+        last_dealloc_      = static_cast<char*>(mem);
+        last_dealloc_prev_ = prev;
+    }
+}
+
+std::size_t ordered_free_memory_list::alignment() const noexcept
+{
+    return alignment_for(node_size_);
+}
+
+char* ordered_free_memory_list::insert_impl(void* mem, std::size_t size) noexcept
+{
+    auto no_nodes = size / node_size_;
+    WPI_MEMORY_ASSERT(no_nodes > 0);
+
+    auto p =
+        find_pos(allocator_info(WPI_MEMORY_LOG_PREFIX "::detail::ordered_free_memory_list",
+                                this),
+                 static_cast<char*>(mem), begin_node(), end_node(), last_dealloc_,
+                 last_dealloc_prev_);
+
+    xor_link_block(mem, node_size_, no_nodes, p.prev, p.next);
+    capacity_ += no_nodes;
+
+    if (p.prev == last_dealloc_prev_)
+    {
+        last_dealloc_ = static_cast<char*>(mem);
+    }
+
+    return p.prev;
+}
+
+char* ordered_free_memory_list::begin_node() noexcept
+{
+    void* mem = &begin_proxy_;
+    return static_cast<char*>(mem);
+}
+
+char* ordered_free_memory_list::end_node() noexcept
+{
+    void* mem = &end_proxy_;
+    return static_cast<char*>(mem);
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/detail/free_list_array.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/detail/free_list_array.cpp
new file mode 100644
index 0000000..f4658da
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/detail/free_list_array.cpp
@@ -0,0 +1,22 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#include "wpi/memory/detail/free_list_array.hpp"
+
+#include "wpi/memory/detail/assert.hpp"
+#include "wpi/memory/detail/ilog2.hpp"
+
+using namespace wpi::memory;
+using namespace detail;
+
+std::size_t log2_access_policy::index_from_size(std::size_t size) noexcept
+{
+    WPI_MEMORY_ASSERT_MSG(size, "size must not be zero");
+    return ilog2_ceil(size);
+}
+
+std::size_t log2_access_policy::size_from_index(std::size_t index) noexcept
+{
+    return std::size_t(1) << index;
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/detail/free_list_utils.hpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/detail/free_list_utils.hpp
new file mode 100644
index 0000000..a752837
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/detail/free_list_utils.hpp
@@ -0,0 +1,149 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#ifndef WPI_MEMORY_SRC_DETAIL_FREE_LIST_UTILS_HPP_INCLUDED
+#define WPI_MEMORY_SRC_DETAIL_FREE_LIST_UTILS_HPP_INCLUDED
+
+#include <cstdint>
+
+#include "wpi/memory/config.hpp"
+#include "wpi/memory/detail/align.hpp"
+#include "wpi/memory/detail/assert.hpp"
+
+#if WPI_HOSTED_IMPLEMENTATION
+#include <cstring>
+#include <functional>
+#endif
+
+namespace wpi
+{
+    namespace memory
+    {
+        namespace detail
+        {
+            //=== storage ===///
+            // reads stored integer value
+            inline std::uintptr_t get_int(void* address) noexcept
+            {
+                WPI_MEMORY_ASSERT(address);
+                std::uintptr_t res;
+#if WPI_HOSTED_IMPLEMENTATION
+                std::memcpy(&res, address, sizeof(std::uintptr_t));
+#else
+                auto mem = static_cast<char*>(static_cast<void*>(&res));
+                for (auto i = 0u; i != sizeof(std::uintptr_t); ++i)
+                    mem[i] = static_cast<char*>(address)[i];
+#endif
+                return res;
+            }
+
+            // sets stored integer value
+            inline void set_int(void* address, std::uintptr_t i) noexcept
+            {
+                WPI_MEMORY_ASSERT(address);
+#if WPI_HOSTED_IMPLEMENTATION
+                std::memcpy(address, &i, sizeof(std::uintptr_t));
+#else
+                auto mem = static_cast<char*>(static_cast<void*>(&i));
+                for (auto i = 0u; i != sizeof(std::uintptr_t); ++i)
+                    static_cast<char*>(address)[i] = mem[i];
+#endif
+            }
+
+            // pointer to integer
+            inline std::uintptr_t to_int(char* ptr) noexcept
+            {
+                return reinterpret_cast<std::uintptr_t>(ptr);
+            }
+
+            // integer to pointer
+            inline char* from_int(std::uintptr_t i) noexcept
+            {
+                return reinterpret_cast<char*>(i);
+            }
+
+            //=== intrusive linked list ===//
+            // reads a stored pointer value
+            inline char* list_get_next(void* address) noexcept
+            {
+                return from_int(get_int(address));
+            }
+
+            // stores a pointer value
+            inline void list_set_next(void* address, char* ptr) noexcept
+            {
+                set_int(address, to_int(ptr));
+            }
+
+            //=== intrusive xor linked list ===//
+            // returns the other pointer given one pointer
+            inline char* xor_list_get_other(void* address, char* prev_or_next) noexcept
+            {
+                return from_int(get_int(address) ^ to_int(prev_or_next));
+            }
+
+            // sets the next and previous pointer (order actually does not matter)
+            inline void xor_list_set(void* address, char* prev, char* next) noexcept
+            {
+                set_int(address, to_int(prev) ^ to_int(next));
+            }
+
+            // changes other pointer given one pointer
+            inline void xor_list_change(void* address, char* old_ptr, char* new_ptr) noexcept
+            {
+                WPI_MEMORY_ASSERT(address);
+                auto other = xor_list_get_other(address, old_ptr);
+                xor_list_set(address, other, new_ptr);
+            }
+
+            // advances a pointer pair forward/backward
+            inline void xor_list_iter_next(char*& cur, char*& prev) noexcept
+            {
+                auto next = xor_list_get_other(cur, prev);
+                prev      = cur;
+                cur       = next;
+            }
+
+            // links new node between prev and next
+            inline void xor_list_insert(char* new_node, char* prev, char* next) noexcept
+            {
+                xor_list_set(new_node, prev, next);
+                xor_list_change(prev, next, new_node); // change prev's next to new_node
+                xor_list_change(next, prev, new_node); // change next's prev to new_node
+            }
+
+            //=== sorted list utils ===//
+            // if std::less/std::greater not available compare integer representation and hope it works
+            inline bool less(void* a, void* b) noexcept
+            {
+#if WPI_HOSTED_IMPLEMENTATION
+                return std::less<void*>()(a, b);
+#else
+                return to_int(a) < to_int(b);
+#endif
+            }
+
+            inline bool less_equal(void* a, void* b) noexcept
+            {
+                return a == b || less(a, b);
+            }
+
+            inline bool greater(void* a, void* b) noexcept
+            {
+#if WPI_HOSTED_IMPLEMENTATION
+                return std::greater<void*>()(a, b);
+#else
+                return to_int(a) < to_int(b);
+#endif
+            }
+
+            inline bool greater_equal(void* a, void* b) noexcept
+            {
+                return a == b || greater(a, b);
+            }
+        } // namespace detail
+    }     // namespace memory
+} // namespace wpi
+
+#endif // WPI_MEMORY_SRC_DETAIL_FREE_LIST_UTILS_HPP_INCLUDED
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/detail/small_free_list.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/detail/small_free_list.cpp
new file mode 100644
index 0000000..3508daa
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/detail/small_free_list.cpp
@@ -0,0 +1,395 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#include "wpi/memory/detail/small_free_list.hpp"
+
+#include <new>
+
+#include "wpi/memory/detail/debug_helpers.hpp"
+#include "wpi/memory/detail/assert.hpp"
+#include "wpi/memory/error.hpp"
+
+#include "free_list_utils.hpp"
+
+using namespace wpi::memory;
+using namespace detail;
+
+struct wpi::memory::detail::chunk : chunk_base
+{
+    // gives it the size of the memory block it is created in and the size of a node
+    chunk(std::size_t total_memory, std::size_t node_size) noexcept
+    : chunk_base(static_cast<unsigned char>((total_memory - chunk_memory_offset) / node_size))
+    {
+        static_assert(sizeof(chunk) == sizeof(chunk_base), "chunk must not have members");
+        WPI_MEMORY_ASSERT((total_memory - chunk_memory_offset) / node_size
+                                <= chunk_max_nodes);
+        WPI_MEMORY_ASSERT(capacity > 0);
+        auto p = list_memory();
+        for (unsigned char i = 0u; i != no_nodes; p += node_size)
+            *p = ++i;
+    }
+
+    // returns memory of the free list
+    unsigned char* list_memory() noexcept
+    {
+        auto mem = static_cast<void*>(this);
+        return static_cast<unsigned char*>(mem) + chunk_memory_offset;
+    }
+
+    // returns the nth node
+    unsigned char* node_memory(unsigned char i, std::size_t node_size) noexcept
+    {
+        WPI_MEMORY_ASSERT(i < no_nodes);
+        return list_memory() + i * node_size;
+    }
+
+    // checks whether a node came from this chunk
+    bool from(unsigned char* node, std::size_t node_size) noexcept
+    {
+        auto begin = list_memory();
+        auto end   = list_memory() + no_nodes * node_size;
+        return (begin <= node) & (node < end);
+    }
+
+    // checks whether a node is already in this chunk
+    bool contains(unsigned char* node, std::size_t node_size) noexcept
+    {
+        auto cur_index = first_free;
+        while (cur_index != no_nodes)
+        {
+            auto cur_mem = node_memory(cur_index, node_size);
+            if (cur_mem == node)
+                return true;
+            cur_index = *cur_mem;
+        }
+        return false;
+    }
+
+    // allocates a single node
+    // chunk most not be empty
+    unsigned char* allocate(std::size_t node_size) noexcept
+    {
+        --capacity;
+
+        auto node  = node_memory(first_free, node_size);
+        first_free = *node;
+        return node;
+    }
+
+    // deallocates a single node given its address and index
+    // it must be from this chunk
+    void deallocate(unsigned char* node, unsigned char node_index) noexcept
+    {
+        ++capacity;
+
+        *node      = first_free;
+        first_free = node_index;
+    }
+};
+
+namespace
+{
+    // converts a chunk_base to a chunk (if it is one)
+    chunk* make_chunk(chunk_base* c) noexcept
+    {
+        return static_cast<chunk*>(c);
+    }
+
+    // same as above but also requires a certain size
+    chunk* make_chunk(chunk_base* c, std::size_t size_needed) noexcept
+    {
+        WPI_MEMORY_ASSERT(size_needed <= chunk_max_nodes);
+        return c->capacity >= size_needed ? make_chunk(c) : nullptr;
+    }
+
+    // checks if memory was from a chunk, assumes chunk isn't proxy
+    chunk* from_chunk(chunk_base* c, unsigned char* node, std::size_t node_size) noexcept
+    {
+        auto res = make_chunk(c);
+        return res->from(node, node_size) ? res : nullptr;
+    }
+
+    // inserts already interconnected chunks into the list
+    // list will be kept ordered
+    void insert_chunks(chunk_base* list, chunk_base* begin, chunk_base* end) noexcept
+    {
+        WPI_MEMORY_ASSERT(begin && end);
+
+        if (list->next == list) // empty
+        {
+            begin->prev = list;
+            end->next   = list->next;
+            list->next  = begin;
+            list->prev  = end;
+        }
+        else if (less(list->prev, begin)) // insert at end
+        {
+            list->prev->next = begin;
+            begin->prev      = list->prev;
+            end->next        = list;
+            list->prev       = end;
+        }
+        else
+        {
+            auto prev = list;
+            auto cur  = list->next;
+            while (less(cur, begin))
+            {
+                prev = cur;
+                cur  = cur->next;
+            }
+            WPI_MEMORY_ASSERT(greater(cur, end));
+            WPI_MEMORY_ASSERT(prev == list || less(prev, begin));
+            prev->next  = begin;
+            begin->prev = prev;
+            end->next   = cur;
+            cur->prev   = end;
+        }
+    }
+} // namespace
+
+constexpr std::size_t small_free_memory_list::min_element_size;
+constexpr std::size_t small_free_memory_list::min_element_alignment;
+
+small_free_memory_list::small_free_memory_list(std::size_t node_size) noexcept
+: node_size_(node_size), capacity_(0u), alloc_chunk_(&base_), dealloc_chunk_(&base_)
+{
+}
+
+small_free_memory_list::small_free_memory_list(std::size_t node_size, void* mem,
+                                               std::size_t size) noexcept
+: small_free_memory_list(node_size)
+{
+    insert(mem, size);
+}
+
+small_free_memory_list::small_free_memory_list(small_free_memory_list&& other) noexcept
+: node_size_(other.node_size_),
+  capacity_(other.capacity_),
+  // reset markers for simplicity
+  alloc_chunk_(&base_),
+  dealloc_chunk_(&base_)
+{
+    if (!other.empty())
+    {
+        base_.next             = other.base_.next;
+        base_.prev             = other.base_.prev;
+        other.base_.next->prev = &base_;
+        other.base_.prev->next = &base_;
+
+        other.base_.next = &other.base_;
+        other.base_.prev = &other.base_;
+        other.capacity_  = 0u;
+    }
+    else
+    {
+        base_.next = &base_;
+        base_.prev = &base_;
+    }
+}
+
+void wpi::memory::detail::swap(small_free_memory_list& a, small_free_memory_list& b) noexcept
+{
+    auto b_next = b.base_.next;
+    auto b_prev = b.base_.prev;
+
+    if (!a.empty())
+    {
+        b.base_.next       = a.base_.next;
+        b.base_.prev       = a.base_.prev;
+        b.base_.next->prev = &b.base_;
+        b.base_.prev->next = &b.base_;
+    }
+    else
+    {
+        b.base_.next = &b.base_;
+        b.base_.prev = &b.base_;
+    }
+
+    if (!b.empty())
+    {
+        a.base_.next       = b_next;
+        a.base_.prev       = b_prev;
+        a.base_.next->prev = &a.base_;
+        a.base_.prev->next = &a.base_;
+    }
+    else
+    {
+        a.base_.next = &a.base_;
+        a.base_.prev = &a.base_;
+    }
+
+    detail::adl_swap(a.node_size_, b.node_size_);
+    detail::adl_swap(a.capacity_, b.capacity_);
+
+    // reset markers for simplicity
+    a.alloc_chunk_ = a.dealloc_chunk_ = &a.base_;
+    b.alloc_chunk_ = b.dealloc_chunk_ = &b.base_;
+}
+
+void small_free_memory_list::insert(void* mem, std::size_t size) noexcept
+{
+    WPI_MEMORY_ASSERT(mem);
+    WPI_MEMORY_ASSERT(is_aligned(mem, max_alignment));
+    debug_fill_internal(mem, size, false);
+
+    auto total_chunk_size = chunk_memory_offset + node_size_ * chunk_max_nodes;
+    auto align_buffer     = align_offset(total_chunk_size, alignof(chunk));
+
+    auto no_chunks = size / (total_chunk_size + align_buffer);
+    auto remainder = size % (total_chunk_size + align_buffer);
+
+    auto memory          = static_cast<char*>(mem);
+    auto construct_chunk = [&](std::size_t total_memory, std::size_t node_size)
+    {
+        WPI_MEMORY_ASSERT(align_offset(memory, alignof(chunk)) == 0);
+        return ::new (static_cast<void*>(memory)) chunk(total_memory, node_size);
+    };
+
+    auto prev = static_cast<chunk_base*>(nullptr);
+    for (auto i = std::size_t(0); i != no_chunks; ++i)
+    {
+        auto c = construct_chunk(total_chunk_size, node_size_);
+
+        c->prev = prev;
+        if (prev)
+            prev->next = c;
+        prev = c;
+
+        memory += total_chunk_size;
+        memory += align_buffer;
+    }
+
+    auto new_nodes = no_chunks * chunk_max_nodes;
+    if (remainder >= chunk_memory_offset + node_size_) // at least one node
+    {
+        auto c = construct_chunk(remainder, node_size_);
+
+        c->prev = prev;
+        if (prev)
+            prev->next = c;
+        prev = c;
+
+        new_nodes += c->no_nodes;
+    }
+
+    WPI_MEMORY_ASSERT_MSG(new_nodes > 0, "memory block too small");
+    insert_chunks(&base_, static_cast<chunk_base*>(mem), prev);
+    capacity_ += new_nodes;
+}
+
+std::size_t small_free_memory_list::usable_size(std::size_t size) const noexcept
+{
+    auto total_chunk_size = chunk_memory_offset + node_size_ * chunk_max_nodes;
+    auto no_chunks        = size / total_chunk_size;
+    auto remainder        = size % total_chunk_size;
+
+    return no_chunks * chunk_max_nodes * node_size_
+           + (remainder > chunk_memory_offset ? remainder - chunk_memory_offset : 0u);
+}
+
+void* small_free_memory_list::allocate() noexcept
+{
+    auto chunk   = find_chunk_impl(1);
+    alloc_chunk_ = chunk;
+    WPI_MEMORY_ASSERT(chunk && chunk->capacity >= 1);
+
+    --capacity_;
+
+    auto mem = chunk->allocate(node_size_);
+    WPI_MEMORY_ASSERT(mem);
+    return detail::debug_fill_new(mem, node_size_, 0);
+}
+
+void small_free_memory_list::deallocate(void* mem) noexcept
+{
+    auto info =
+        allocator_info(WPI_MEMORY_LOG_PREFIX "::detail::small_free_memory_list", this);
+
+    auto node = static_cast<unsigned char*>(detail::debug_fill_free(mem, node_size_, 0));
+
+    auto chunk     = find_chunk_impl(node);
+    dealloc_chunk_ = chunk;
+    // memory was never allocated from list
+    detail::debug_check_pointer([&] { return chunk != nullptr; }, info, mem);
+
+    auto offset = static_cast<std::size_t>(node - chunk->list_memory());
+    // memory is not at the right position
+    debug_check_pointer([&] { return offset % node_size_ == 0u; }, info, mem);
+    // double-free
+    debug_check_double_dealloc([&] { return !chunk->contains(node, node_size_); }, info, mem);
+
+    auto index = offset / node_size_;
+    WPI_MEMORY_ASSERT(index < chunk->no_nodes);
+    chunk->deallocate(node, static_cast<unsigned char>(index));
+
+    ++capacity_;
+}
+
+std::size_t small_free_memory_list::alignment() const noexcept
+{
+    return alignment_for(node_size_);
+}
+
+chunk* small_free_memory_list::find_chunk_impl(std::size_t n) noexcept
+{
+    if (auto c = make_chunk(alloc_chunk_, n))
+        return c;
+    else if ((c = make_chunk(dealloc_chunk_, n)) != nullptr)
+        return c;
+
+    auto cur_forward  = alloc_chunk_->next;
+    auto cur_backward = alloc_chunk_->prev;
+
+    do
+    {
+        if (auto c = make_chunk(cur_forward, n))
+            return c;
+        else if ((c = make_chunk(cur_backward, n)) != nullptr)
+            return c;
+
+        cur_forward  = cur_forward->next;
+        cur_backward = cur_backward->prev;
+        WPI_MEMORY_ASSERT(cur_forward != alloc_chunk_);
+        WPI_MEMORY_ASSERT(cur_backward != alloc_chunk_);
+    } while (true);
+    WPI_MEMORY_UNREACHABLE("there is memory available somewhere...");
+    return nullptr;
+}
+
+chunk* small_free_memory_list::find_chunk_impl(unsigned char* node, chunk_base* first,
+                                               chunk_base* last) noexcept
+{
+    do
+    {
+        if (auto c = from_chunk(first, node, node_size_))
+            return c;
+        else if ((c = from_chunk(last, node, node_size_)) != nullptr)
+            return c;
+
+        first = first->next;
+        last  = last->prev;
+    } while (!greater(first, last));
+    return nullptr;
+}
+
+chunk* small_free_memory_list::find_chunk_impl(unsigned char* node) noexcept
+{
+    if (auto c = from_chunk(dealloc_chunk_, node, node_size_))
+        return c;
+    else if ((c = from_chunk(alloc_chunk_, node, node_size_)) != nullptr)
+        return c;
+    else if (less(dealloc_chunk_, node))
+    {
+        // node is in (dealloc_chunk_, base_.prev]
+        return find_chunk_impl(node, dealloc_chunk_->next, base_.prev);
+    }
+    else if (greater(dealloc_chunk_, node))
+    {
+        // node is in [base.next, dealloc_chunk_)
+        return find_chunk_impl(node, base_.next, dealloc_chunk_->prev);
+    }
+    WPI_MEMORY_UNREACHABLE("must be in one half");
+    return nullptr;
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/error.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/error.cpp
new file mode 100644
index 0000000..6261819
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/error.cpp
@@ -0,0 +1,106 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#include "wpi/memory/error.hpp"
+
+#include <atomic>
+
+#if WPI_HOSTED_IMPLEMENTATION
+#include <cstdio>
+#endif
+
+using namespace wpi::memory;
+
+namespace
+{
+    void default_out_of_memory_handler(const allocator_info& info, std::size_t amount) noexcept
+    {
+#if WPI_HOSTED_IMPLEMENTATION
+        std::fprintf(stderr,
+                     "[%s] Allocator %s (at %p) ran out of memory trying to allocate %zu bytes.\n",
+                     WPI_MEMORY_LOG_PREFIX, info.name, info.allocator, amount);
+#endif
+    }
+
+    std::atomic<out_of_memory::handler> out_of_memory_h(default_out_of_memory_handler);
+} // namespace
+
+out_of_memory::handler out_of_memory::set_handler(out_of_memory::handler h)
+{
+    return out_of_memory_h.exchange(h ? h : default_out_of_memory_handler);
+}
+
+out_of_memory::handler out_of_memory::get_handler()
+{
+    return out_of_memory_h;
+}
+
+out_of_memory::out_of_memory(const allocator_info& info, std::size_t amount)
+: info_(info), amount_(amount)
+{
+    out_of_memory_h.load()(info, amount);
+}
+
+const char* out_of_memory::what() const noexcept
+{
+    return "low-level allocator is out of memory";
+}
+
+const char* out_of_fixed_memory::what() const noexcept
+{
+    return "fixed size allocator is out of memory";
+}
+
+namespace
+{
+    void default_bad_alloc_size_handler(const allocator_info& info, std::size_t passed,
+                                        std::size_t supported) noexcept
+    {
+#if WPI_HOSTED_IMPLEMENTATION
+        std::fprintf(stderr,
+                     "[%s] Allocator %s (at %p) received invalid size/alignment %zu, "
+                     "max supported is %zu\n",
+                     WPI_MEMORY_LOG_PREFIX, info.name, info.allocator, passed, supported);
+#endif
+    }
+
+    std::atomic<bad_allocation_size::handler> bad_alloc_size_h(default_bad_alloc_size_handler);
+} // namespace
+
+bad_allocation_size::handler bad_allocation_size::set_handler(bad_allocation_size::handler h)
+{
+    return bad_alloc_size_h.exchange(h ? h : default_bad_alloc_size_handler);
+}
+
+bad_allocation_size::handler bad_allocation_size::get_handler()
+{
+    return bad_alloc_size_h;
+}
+
+bad_allocation_size::bad_allocation_size(const allocator_info& info, std::size_t passed,
+                                         std::size_t supported)
+: info_(info), passed_(passed), supported_(supported)
+{
+    bad_alloc_size_h.load()(info_, passed_, supported_);
+}
+
+const char* bad_allocation_size::what() const noexcept
+{
+    return "allocation node size exceeds supported maximum of allocator";
+}
+
+const char* bad_node_size::what() const noexcept
+{
+    return "allocation node size exceeds supported maximum of allocator";
+}
+
+const char* bad_array_size::what() const noexcept
+{
+    return "allocation array size exceeds supported maximum of allocator";
+}
+
+const char* bad_alignment::what() const noexcept
+{
+    return "allocation alignment exceeds supported maximum of allocator";
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/heap_allocator.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/heap_allocator.cpp
new file mode 100644
index 0000000..0f559bd
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/heap_allocator.cpp
@@ -0,0 +1,85 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#include "wpi/memory/heap_allocator.hpp"
+
+#include "wpi/memory/error.hpp"
+
+using namespace wpi::memory;
+
+#ifdef _WIN32
+#include <malloc.h>
+#include <windows.h>
+
+namespace
+{
+    HANDLE get_process_heap() noexcept
+    {
+        static auto heap = GetProcessHeap();
+        return heap;
+    }
+
+    std::size_t max_size() noexcept
+    {
+        return _HEAP_MAXREQ;
+    }
+} // namespace
+
+void* wpi::memory::heap_alloc(std::size_t size) noexcept
+{
+    return HeapAlloc(get_process_heap(), 0, size);
+}
+
+void wpi::memory::heap_dealloc(void* ptr, std::size_t) noexcept
+{
+    HeapFree(get_process_heap(), 0, ptr);
+}
+
+#elif WPI_HOSTED_IMPLEMENTATION
+#include <cstdlib>
+#include <memory>
+
+void* wpi::memory::heap_alloc(std::size_t size) noexcept
+{
+    return std::malloc(size);
+}
+
+void wpi::memory::heap_dealloc(void* ptr, std::size_t) noexcept
+{
+    std::free(ptr);
+}
+
+namespace
+{
+    std::size_t max_size() noexcept
+    {
+        return std::allocator_traits<std::allocator<char>>::max_size({});
+    }
+} // namespace
+#else
+// no implementation for heap_alloc/heap_dealloc
+
+namespace
+{
+    std::size_t max_size() noexcept
+    {
+        return std::size_t(-1);
+    }
+} // namespace
+#endif
+
+allocator_info detail::heap_allocator_impl::info() noexcept
+{
+    return {WPI_MEMORY_LOG_PREFIX "::heap_allocator", nullptr};
+}
+
+std::size_t detail::heap_allocator_impl::max_node_size() noexcept
+{
+    return max_size();
+}
+
+#if WPI_MEMORY_EXTERN_TEMPLATE
+template class detail::lowlevel_allocator<detail::heap_allocator_impl>;
+template class wpi::memory::allocator_traits<heap_allocator>;
+#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/iteration_allocator.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/iteration_allocator.cpp
new file mode 100644
index 0000000..c174c13
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/iteration_allocator.cpp
@@ -0,0 +1,13 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#include "wpi/memory/iteration_allocator.hpp"
+
+using namespace wpi::memory;
+
+#if WPI_MEMORY_EXTERN_TEMPLATE
+template class wpi::memory::iteration_allocator<2>;
+template class wpi::memory::allocator_traits<iteration_allocator<2>>;
+template class wpi::memory::composable_allocator_traits<iteration_allocator<2>>;
+#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/malloc_allocator.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/malloc_allocator.cpp
new file mode 100644
index 0000000..f54817a
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/malloc_allocator.cpp
@@ -0,0 +1,24 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#include "wpi/memory/config.hpp"
+#if WPI_HOSTED_IMPLEMENTATION
+
+#include "wpi/memory/malloc_allocator.hpp"
+
+#include "wpi/memory/error.hpp"
+
+using namespace wpi::memory;
+
+allocator_info detail::malloc_allocator_impl::info() noexcept
+{
+    return {WPI_MEMORY_LOG_PREFIX "::malloc_allocator", nullptr};
+}
+
+#if WPI_MEMORY_EXTERN_TEMPLATE
+template class detail::lowlevel_allocator<detail::malloc_allocator_impl>;
+template class wpi::memory::allocator_traits<malloc_allocator>;
+#endif
+
+#endif // WPI_HOSTED_IMPLEMENTATION
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/memory_arena.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/memory_arena.cpp
new file mode 100644
index 0000000..d8454be
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/memory_arena.cpp
@@ -0,0 +1,73 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#include "wpi/memory/memory_arena.hpp"
+
+#include <new>
+
+#include "wpi/memory/detail/align.hpp"
+
+using namespace wpi::memory;
+using namespace detail;
+
+void memory_block_stack::push(allocated_mb block) noexcept
+{
+    WPI_MEMORY_ASSERT(block.size >= sizeof(node));
+    WPI_MEMORY_ASSERT(is_aligned(block.memory, max_alignment));
+    auto next = ::new (block.memory) node(head_, block.size - implementation_offset());
+    head_     = next;
+}
+
+memory_block_stack::allocated_mb memory_block_stack::pop() noexcept
+{
+    WPI_MEMORY_ASSERT(head_);
+    auto to_pop = head_;
+    head_       = head_->prev;
+    return {to_pop, to_pop->usable_size + implementation_offset()};
+}
+
+void memory_block_stack::steal_top(memory_block_stack& other) noexcept
+{
+    WPI_MEMORY_ASSERT(other.head_);
+    auto to_steal = other.head_;
+    other.head_   = other.head_->prev;
+
+    to_steal->prev = head_;
+    head_          = to_steal;
+}
+
+bool memory_block_stack::owns(const void* ptr) const noexcept
+{
+    auto address = static_cast<const char*>(ptr);
+    for (auto cur = head_; cur; cur = cur->prev)
+    {
+        auto mem = static_cast<char*>(static_cast<void*>(cur));
+        if (address >= mem && address < mem + cur->usable_size)
+            return true;
+    }
+    return false;
+}
+
+std::size_t memory_block_stack::size() const noexcept
+{
+    std::size_t res = 0u;
+    for (auto cur = head_; cur; cur = cur->prev)
+        ++res;
+    return res;
+}
+
+#if WPI_MEMORY_EXTERN_TEMPLATE
+template class wpi::memory::memory_arena<static_block_allocator, true>;
+template class wpi::memory::memory_arena<static_block_allocator, false>;
+template class wpi::memory::memory_arena<virtual_block_allocator, true>;
+template class wpi::memory::memory_arena<virtual_block_allocator, false>;
+
+template class wpi::memory::growing_block_allocator<>;
+template class wpi::memory::memory_arena<growing_block_allocator<>, true>;
+template class wpi::memory::memory_arena<growing_block_allocator<>, false>;
+
+template class wpi::memory::fixed_block_allocator<>;
+template class wpi::memory::memory_arena<fixed_block_allocator<>, true>;
+template class wpi::memory::memory_arena<fixed_block_allocator<>, false>;
+#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/memory_pool.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/memory_pool.cpp
new file mode 100644
index 0000000..5a5e5ab
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/memory_pool.cpp
@@ -0,0 +1,28 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#include "wpi/memory/memory_pool.hpp"
+
+#include "wpi/memory/debugging.hpp"
+
+using namespace wpi::memory;
+
+void detail::memory_pool_leak_handler::operator()(std::ptrdiff_t amount)
+{
+    get_leak_handler()({WPI_MEMORY_LOG_PREFIX "::memory_pool", this}, amount);
+}
+
+#if WPI_MEMORY_EXTERN_TEMPLATE
+template class wpi::memory::memory_pool<node_pool>;
+template class wpi::memory::memory_pool<array_pool>;
+template class wpi::memory::memory_pool<small_node_pool>;
+
+template class wpi::memory::allocator_traits<memory_pool<node_pool>>;
+template class wpi::memory::allocator_traits<memory_pool<array_pool>>;
+template class wpi::memory::allocator_traits<memory_pool<small_node_pool>>;
+
+template class wpi::memory::composable_allocator_traits<memory_pool<node_pool>>;
+template class wpi::memory::composable_allocator_traits<memory_pool<array_pool>>;
+template class wpi::memory::composable_allocator_traits<memory_pool<small_node_pool>>;
+#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/memory_pool_collection.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/memory_pool_collection.cpp
new file mode 100644
index 0000000..6366811
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/memory_pool_collection.cpp
@@ -0,0 +1,51 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#include "wpi/memory/memory_pool_collection.hpp"
+
+#include "wpi/memory/debugging.hpp"
+
+using namespace wpi::memory;
+
+void detail::memory_pool_collection_leak_handler::operator()(std::ptrdiff_t amount)
+{
+    get_leak_handler()({WPI_MEMORY_LOG_PREFIX "::memory_pool_collection", this}, amount);
+}
+
+#if WPI_MEMORY_EXTERN_TEMPLATE
+template class wpi::memory::memory_pool_collection<node_pool, identity_buckets>;
+template class wpi::memory::memory_pool_collection<array_pool, identity_buckets>;
+template class wpi::memory::memory_pool_collection<small_node_pool, identity_buckets>;
+
+template class wpi::memory::memory_pool_collection<node_pool, log2_buckets>;
+template class wpi::memory::memory_pool_collection<array_pool, log2_buckets>;
+template class wpi::memory::memory_pool_collection<small_node_pool, log2_buckets>;
+
+template class wpi::memory::allocator_traits<
+    memory_pool_collection<node_pool, identity_buckets>>;
+template class wpi::memory::allocator_traits<
+    memory_pool_collection<array_pool, identity_buckets>>;
+template class wpi::memory::allocator_traits<
+    memory_pool_collection<small_node_pool, identity_buckets>>;
+
+template class wpi::memory::allocator_traits<memory_pool_collection<node_pool, log2_buckets>>;
+template class wpi::memory::allocator_traits<
+    memory_pool_collection<array_pool, log2_buckets>>;
+template class wpi::memory::allocator_traits<
+    memory_pool_collection<small_node_pool, log2_buckets>>;
+
+template class wpi::memory::composable_allocator_traits<
+    memory_pool_collection<node_pool, identity_buckets>>;
+template class wpi::memory::composable_allocator_traits<
+    memory_pool_collection<array_pool, identity_buckets>>;
+template class wpi::memory::composable_allocator_traits<
+    memory_pool_collection<small_node_pool, identity_buckets>>;
+
+template class wpi::memory::composable_allocator_traits<
+    memory_pool_collection<node_pool, log2_buckets>>;
+template class wpi::memory::composable_allocator_traits<
+    memory_pool_collection<array_pool, log2_buckets>>;
+template class wpi::memory::composable_allocator_traits<
+    memory_pool_collection<small_node_pool, log2_buckets>>;
+#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/memory_stack.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/memory_stack.cpp
new file mode 100644
index 0000000..8db5728
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/memory_stack.cpp
@@ -0,0 +1,21 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#include "wpi/memory/memory_stack.hpp"
+
+#include "wpi/memory/debugging.hpp"
+
+using namespace wpi::memory;
+
+void detail::memory_stack_leak_handler::operator()(std::ptrdiff_t amount)
+{
+    get_leak_handler()({WPI_MEMORY_LOG_PREFIX "::memory_stack", this}, amount);
+}
+
+#if WPI_MEMORY_EXTERN_TEMPLATE
+template class wpi::memory::memory_stack<>;
+template class wpi::memory::memory_stack_raii_unwind<memory_stack<>>;
+template class wpi::memory::allocator_traits<memory_stack<>>;
+template class wpi::memory::composable_allocator_traits<memory_stack<>>;
+#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/new_allocator.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/new_allocator.cpp
new file mode 100644
index 0000000..2791182
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/new_allocator.cpp
@@ -0,0 +1,72 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#include "wpi/memory/new_allocator.hpp"
+
+#if WPI_HOSTED_IMPLEMENTATION
+#include <memory>
+#endif
+
+#include <new>
+
+#include "wpi/memory/error.hpp"
+
+using namespace wpi::memory;
+
+allocator_info detail::new_allocator_impl::info() noexcept
+{
+    return {WPI_MEMORY_LOG_PREFIX "::new_allocator", nullptr};
+}
+
+void* detail::new_allocator_impl::allocate(std::size_t size, size_t) noexcept
+{
+    void* memory = nullptr;
+    while (true)
+    {
+        memory = ::operator new(size, std::nothrow);
+        if (memory)
+            break;
+
+        auto handler = std::get_new_handler();
+        if (handler)
+        {
+#if WPI_HAS_EXCEPTION_SUPPORT
+            try
+            {
+                handler();
+            }
+            catch (...)
+            {
+                return nullptr;
+            }
+#else
+            handler();
+#endif
+        }
+        else
+        {
+            return nullptr;
+        }
+    }
+    return memory;
+}
+
+void detail::new_allocator_impl::deallocate(void* ptr, std::size_t, size_t) noexcept
+{
+    ::operator delete(ptr);
+}
+
+std::size_t detail::new_allocator_impl::max_node_size() noexcept
+{
+#if WPI_HOSTED_IMPLEMENTATION
+    return std::allocator_traits<std::allocator<char>>::max_size({});
+#else
+    return std::size_t(-1);
+#endif
+}
+
+#if WPI_MEMORY_EXTERN_TEMPLATE
+template class detail::lowlevel_allocator<detail::new_allocator_impl>;
+template class wpi::memory::allocator_traits<new_allocator>;
+#endif
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/static_allocator.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/static_allocator.cpp
new file mode 100644
index 0000000..15a88bf
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/static_allocator.cpp
@@ -0,0 +1,50 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#include "wpi/memory/static_allocator.hpp"
+
+#include "wpi/memory/detail/debug_helpers.hpp"
+#include "wpi/memory/error.hpp"
+#include "wpi/memory/memory_arena.hpp"
+
+using namespace wpi::memory;
+
+void* static_allocator::allocate_node(std::size_t size, std::size_t alignment)
+{
+    auto mem = stack_.allocate(end_, size, alignment);
+    if (!mem)
+        WPI_THROW(out_of_fixed_memory(info(), size));
+    return mem;
+}
+
+allocator_info static_allocator::info() const noexcept
+{
+    return {WPI_MEMORY_LOG_PREFIX "::static_allocator", this};
+}
+
+#if WPI_MEMORY_EXTERN_TEMPLATE
+template class wpi::memory::allocator_traits<static_allocator>;
+#endif
+
+memory_block static_block_allocator::allocate_block()
+{
+    if (cur_ + block_size_ > end_)
+        WPI_THROW(out_of_fixed_memory(info(), block_size_));
+    auto mem = cur_;
+    cur_ += block_size_;
+    return {mem, block_size_};
+}
+
+void static_block_allocator::deallocate_block(memory_block block) noexcept
+{
+    detail::
+        debug_check_pointer([&] { return static_cast<char*>(block.memory) + block.size == cur_; },
+                            info(), block.memory);
+    cur_ -= block_size_;
+}
+
+allocator_info static_block_allocator::info() const noexcept
+{
+    return {WPI_MEMORY_LOG_PREFIX "::static_block_allocator", this};
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/temporary_allocator.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/temporary_allocator.cpp
new file mode 100644
index 0000000..fa85e99
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/temporary_allocator.cpp
@@ -0,0 +1,322 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#include "wpi/memory/temporary_allocator.hpp"
+
+#include <new>
+#include <type_traits>
+
+#include "wpi/memory/detail/assert.hpp"
+#include "wpi/memory/default_allocator.hpp"
+#include "wpi/memory/error.hpp"
+
+using namespace wpi::memory;
+
+namespace
+{
+    void default_growth_tracker(std::size_t) noexcept {}
+
+    using temporary_impl_allocator        = default_allocator;
+    using temporary_impl_allocator_traits = allocator_traits<temporary_impl_allocator>;
+} // namespace
+
+detail::temporary_block_allocator::temporary_block_allocator(std::size_t block_size) noexcept
+: tracker_(default_growth_tracker), block_size_(block_size)
+{
+}
+
+detail::temporary_block_allocator::growth_tracker detail::temporary_block_allocator::
+    set_growth_tracker(growth_tracker t) noexcept
+{
+    auto old = tracker_;
+    tracker_ = t;
+    return old;
+}
+
+detail::temporary_block_allocator::growth_tracker detail::temporary_block_allocator::
+    get_growth_tracker() noexcept
+{
+    return tracker_;
+}
+
+memory_block detail::temporary_block_allocator::allocate_block()
+{
+    auto alloc  = temporary_impl_allocator();
+    auto memory = temporary_impl_allocator_traits::allocate_array(alloc, block_size_, 1,
+                                                                  detail::max_alignment);
+    auto block  = memory_block(memory, block_size_);
+    block_size_ = growing_block_allocator<temporary_impl_allocator>::grow_block_size(block_size_);
+    return block;
+}
+
+void detail::temporary_block_allocator::deallocate_block(memory_block block)
+{
+    auto alloc = temporary_impl_allocator();
+    temporary_impl_allocator_traits::deallocate_array(alloc, block.memory, block.size, 1,
+                                                      detail::max_alignment);
+}
+
+#if WPI_MEMORY_TEMPORARY_STACK_MODE >= 2
+// lifetime managment through the nifty counter and the list
+// note: I could have used a simple `thread_local` variable for the temporary stack
+// but this could lead to issues with destruction order
+// and more importantly I have to support platforms that can't handle non-trivial thread local's
+// hence I need to dynamically allocate the stack's and store them in a container
+// on program exit the container is iterated and all stack's are properly destroyed
+// if a thread exit can be detected, the dynamic memory of the stack is already released,
+// but not the stack itself destroyed
+
+#if !defined(__MINGW64__)
+
+// only use the thread exit detector if we have thread local and are not running on MinGW due to a bug
+// see: https://sourceforge.net/p/mingw-w64/bugs/527/
+#define WPI_MEMORY_THREAD_EXIT_DETECTOR 1
+
+#else
+#define WPI_MEMORY_THREAD_EXIT_DETECTOR 0
+
+#if defined(_MSC_VER)
+#pragma message(                                                                                   \
+    "thread_local doesn't support destructors, need to use the temporary_stack_initializer to ensure proper cleanup of the temporary memory")
+#else
+#warning                                                                                           \
+    "thread_local doesn't support destructors, need to use the temporary_stack_initializer to ensure proper cleanup of the temporary memory"
+#endif
+
+#endif
+
+static class detail::temporary_stack_list
+{
+public:
+    std::atomic<temporary_stack_list_node*> first;
+
+    temporary_stack* create_new(std::size_t size)
+    {
+        auto storage =
+            default_allocator().allocate_node(sizeof(temporary_stack), alignof(temporary_stack));
+        return ::new (storage) temporary_stack(0, size);
+    }
+
+    temporary_stack* find_unused()
+    {
+        for (auto ptr = first.load(); ptr; ptr = ptr->next_)
+        {
+            auto value = false;
+            if (ptr->in_use_.compare_exchange_strong(value, true))
+                return static_cast<temporary_stack*>(ptr);
+        }
+
+        return nullptr;
+    }
+
+    temporary_stack* create(std::size_t size)
+    {
+        if (auto ptr = find_unused())
+        {
+            WPI_MEMORY_ASSERT(ptr->in_use_);
+            ptr->stack_ = detail::temporary_stack_impl(size);
+            return ptr;
+        }
+        return create_new(size);
+    }
+
+    void clear(temporary_stack& stack)
+    {
+        // stack should be empty now, so shrink_to_fit() clears all memory
+        stack.stack_.shrink_to_fit();
+        stack.in_use_ = false; // mark as free
+    }
+
+    void destroy()
+    {
+        for (auto ptr = first.exchange(nullptr); ptr;)
+        {
+            auto stack = static_cast<temporary_stack*>(ptr);
+            auto next  = ptr->next_;
+
+            stack->~temporary_stack();
+            default_allocator().deallocate_node(stack, sizeof(temporary_stack),
+                                                alignof(temporary_stack));
+
+            ptr = next;
+        }
+
+        WPI_MEMORY_ASSERT_MSG(!first.load(),
+                                    "destroy() called while other threads are still running");
+    }
+} temporary_stack_list_obj;
+
+namespace
+{
+    thread_local std::size_t      nifty_counter;
+    thread_local temporary_stack* temp_stack = nullptr;
+
+#if WPI_MEMORY_THREAD_EXIT_DETECTOR
+    // don't use this on a bug
+    thread_local struct thread_exit_detector_t
+    {
+        ~thread_exit_detector_t() noexcept
+        {
+            if (temp_stack)
+                // clear automatically on thread exit, as the initializer's destructor does
+                // note: if another's thread_local variable destructor is called after this one
+                // and that destructor uses the temporary allocator
+                // the stack needs to grow again
+                // but who does temporary allocation in a destructor?!
+                temporary_stack_list_obj.clear(*temp_stack);
+        }
+    } thread_exit_detector;
+#endif
+} // namespace
+
+detail::temporary_stack_list_node::temporary_stack_list_node(int) noexcept : in_use_(true)
+{
+    next_ = temporary_stack_list_obj.first.load();
+    while (!temporary_stack_list_obj.first.compare_exchange_weak(next_, this))
+        ;
+#if WPI_MEMORY_THREAD_EXIT_DETECTOR
+    (void)&thread_exit_detector; // ODR-use it, so it will be created
+#endif
+}
+
+detail::temporary_allocator_dtor_t::temporary_allocator_dtor_t() noexcept
+{
+    ++nifty_counter;
+}
+
+detail::temporary_allocator_dtor_t::~temporary_allocator_dtor_t() noexcept
+{
+    if (--nifty_counter == 0u && temp_stack)
+        temporary_stack_list_obj.destroy();
+}
+
+temporary_stack_initializer::temporary_stack_initializer(std::size_t initial_size)
+{
+    if (!temp_stack)
+        temp_stack = temporary_stack_list_obj.create(initial_size);
+}
+
+temporary_stack_initializer::~temporary_stack_initializer() noexcept
+{
+    // don't destroy, nifty counter does that
+    // but can get rid of all the memory
+    if (temp_stack)
+        temporary_stack_list_obj.clear(*temp_stack);
+}
+
+temporary_stack& wpi::memory::get_temporary_stack(std::size_t initial_size)
+{
+    if (!temp_stack)
+        temp_stack = temporary_stack_list_obj.create(initial_size);
+    return *temp_stack;
+}
+
+#elif WPI_MEMORY_TEMPORARY_STACK_MODE == 1
+
+namespace
+{
+    WPI_THREAD_LOCAL alignas(
+        temporary_stack) char temporary_stack_storage[sizeof(temporary_stack)];
+    WPI_THREAD_LOCAL bool is_created = false;
+
+    temporary_stack& get() noexcept
+    {
+        WPI_MEMORY_ASSERT(is_created);
+        return *static_cast<temporary_stack*>(static_cast<void*>(&temporary_stack_storage));
+    }
+
+    void create(std::size_t initial_size)
+    {
+        if (!is_created)
+        {
+            ::new (static_cast<void*>(&temporary_stack_storage)) temporary_stack(initial_size);
+            is_created = true;
+        }
+    }
+} // namespace
+
+// explicit lifetime managment
+temporary_stack_initializer::temporary_stack_initializer(std::size_t initial_size)
+{
+    create(initial_size);
+}
+
+temporary_stack_initializer::~temporary_stack_initializer()
+{
+    if (is_created)
+        get().~temporary_stack();
+}
+
+temporary_stack& wpi::memory::get_temporary_stack(std::size_t initial_size)
+{
+    create(initial_size);
+    return get();
+}
+
+#else
+
+// no lifetime managment
+
+temporary_stack_initializer::temporary_stack_initializer(std::size_t initial_size)
+{
+    if (initial_size != 0u)
+        WPI_MEMORY_WARNING("temporary_stack_initializer() has no effect if "
+                                 "WPI_MEMORY_TEMPORARY_STACK == 0 (pass an initial size of 0 "
+                                 "to disable this message)");
+}
+
+temporary_stack_initializer::~temporary_stack_initializer() {}
+
+temporary_stack& wpi::memory::get_temporary_stack(std::size_t)
+{
+    WPI_MEMORY_UNREACHABLE("get_temporary_stack() called but stack is disabled by "
+                                 "WPI_MEMORY_TEMPORARY_STACK == 0");
+    std::abort();
+}
+
+#endif
+
+const temporary_stack_initializer::defer_create_t temporary_stack_initializer::defer_create;
+
+temporary_allocator::temporary_allocator() : temporary_allocator(get_temporary_stack()) {}
+
+temporary_allocator::temporary_allocator(temporary_stack& stack)
+: unwind_(stack), prev_(stack.top_), shrink_to_fit_(false)
+{
+    WPI_MEMORY_ASSERT(!prev_ || prev_->is_active());
+    stack.top_ = this;
+}
+
+temporary_allocator::~temporary_allocator() noexcept
+{
+    if (is_active())
+    {
+        auto& stack = unwind_.get_stack();
+        stack.top_  = prev_;
+        unwind_.unwind(); // manually call it now...
+        if (shrink_to_fit_)
+            // to call shrink_to_fit() afterwards
+            stack.stack_.shrink_to_fit();
+    }
+}
+
+void* temporary_allocator::allocate(std::size_t size, std::size_t alignment)
+{
+    WPI_MEMORY_ASSERT_MSG(is_active(), "object isn't the active allocator");
+    return unwind_.get_stack().stack_.allocate(size, alignment);
+}
+
+void temporary_allocator::shrink_to_fit() noexcept
+{
+    shrink_to_fit_ = true;
+}
+
+bool temporary_allocator::is_active() const noexcept
+{
+    WPI_MEMORY_ASSERT(unwind_.will_unwind());
+    auto res = unwind_.get_stack().top_ == this;
+    // check that prev is actually before this
+    WPI_MEMORY_ASSERT(!res || !prev_ || prev_->unwind_.get_marker() <= unwind_.get_marker());
+    return res;
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/virtual_memory.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/virtual_memory.cpp
new file mode 100644
index 0000000..fd7960f
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/memory/src/virtual_memory.cpp
@@ -0,0 +1,240 @@
+// Copyright (C) 2015-2021 Müller <jonathanmueller.dev@gmail.com>
+// This file is subject to the license terms in the LICENSE file
+// found in the top-level directory of this distribution.
+
+#include "wpi/memory/virtual_memory.hpp"
+
+#include "wpi/memory/detail/debug_helpers.hpp"
+#include "wpi/memory/error.hpp"
+#include "wpi/memory/memory_arena.hpp"
+
+using namespace wpi::memory;
+
+void detail::virtual_memory_allocator_leak_handler::operator()(std::ptrdiff_t amount)
+{
+    detail::debug_handle_memory_leak({WPI_MEMORY_LOG_PREFIX "::virtual_memory_allocator",
+                                      nullptr},
+                                     amount);
+}
+
+#if defined(_WIN32)
+#include <windows.h>
+
+namespace
+{
+    std::size_t get_page_size() noexcept
+    {
+        static_assert(sizeof(std::size_t) >= sizeof(DWORD), "possible loss of data");
+
+        SYSTEM_INFO info;
+        GetSystemInfo(&info);
+        return std::size_t(info.dwPageSize);
+    }
+} // namespace
+
+const std::size_t wpi::memory::virtual_memory_page_size = get_page_size();
+
+void* wpi::memory::virtual_memory_reserve(std::size_t no_pages) noexcept
+{
+    auto pages =
+#if (_MSC_VER <= 1900) || WINAPI_FAMILY_PARTITION(WINAPI_PARTITION_DESKTOP)
+        VirtualAlloc(nullptr, no_pages * virtual_memory_page_size, MEM_RESERVE, PAGE_READWRITE);
+#else
+        VirtualAllocFromApp(nullptr, no_pages * virtual_memory_page_size, MEM_RESERVE,
+                            PAGE_READWRITE);
+#endif
+    return pages;
+}
+
+void wpi::memory::virtual_memory_release(void* pages, std::size_t) noexcept
+{
+    auto result = VirtualFree(pages, 0u, MEM_RELEASE);
+    WPI_MEMORY_ASSERT_MSG(result, "cannot release pages");
+}
+
+void* wpi::memory::virtual_memory_commit(void* memory, std::size_t no_pages) noexcept
+{
+    auto region =
+#if (_MSC_VER <= 1900) || WINAPI_FAMILY_PARTITION(WINAPI_PARTITION_DESKTOP)
+        VirtualAlloc(memory, no_pages * virtual_memory_page_size, MEM_COMMIT, PAGE_READWRITE);
+#else
+        VirtualAllocFromApp(memory, no_pages * virtual_memory_page_size, MEM_COMMIT,
+                            PAGE_READWRITE);
+#endif
+    if (!region)
+        return nullptr;
+    WPI_MEMORY_ASSERT(region == memory);
+    return region;
+}
+
+void wpi::memory::virtual_memory_decommit(void* memory, std::size_t no_pages) noexcept
+{
+    auto result = VirtualFree(memory, no_pages * virtual_memory_page_size, MEM_DECOMMIT);
+    WPI_MEMORY_ASSERT_MSG(result, "cannot decommit memory");
+}
+#elif defined(__unix__) || defined(__APPLE__) || defined(__VXWORKS__)                              \
+    || defined(__QNXNTO__) // POSIX systems
+#include <sys/mman.h>
+#include <unistd.h>
+
+#if defined(PAGESIZE)
+const std::size_t wpi::memory::virtual_memory_page_size = PAGESIZE;
+#elif defined(PAGE_SIZE)
+const std::size_t wpi::memory::virtual_memory_page_size = PAGE_SIZE;
+#else
+const std::size_t wpi::memory::virtual_memory_page_size =
+    static_cast<std::size_t>(sysconf(_SC_PAGESIZE));
+#endif
+
+#ifndef MAP_ANONYMOUS
+#define MAP_ANONYMOUS MAP_ANON
+#endif
+
+void* wpi::memory::virtual_memory_reserve(std::size_t no_pages) noexcept
+{
+    auto pages = mmap(nullptr, no_pages * virtual_memory_page_size, PROT_NONE,
+                      MAP_PRIVATE | MAP_ANONYMOUS, -1, 0);
+    return pages == MAP_FAILED ? nullptr : pages;
+}
+
+void wpi::memory::virtual_memory_release(void* pages, std::size_t no_pages) noexcept
+{
+    auto result = munmap(pages, no_pages * virtual_memory_page_size);
+    WPI_MEMORY_ASSERT_MSG(result == 0, "cannot release pages");
+    (void)result;
+}
+
+void* wpi::memory::virtual_memory_commit(void* memory, std::size_t no_pages) noexcept
+{
+    auto size   = no_pages * virtual_memory_page_size;
+    auto result = mprotect(memory, size, PROT_WRITE | PROT_READ);
+    if (result != 0)
+        return nullptr;
+
+// advise that the memory will be needed
+#if defined(MADV_WILLNEED)
+    madvise(memory, size, MADV_WILLNEED);
+#elif defined(POSIX_MADV_WILLNEED)
+    posix_madvise(memory, size, POSIX_MADV_WILLNEED);
+#endif
+
+    return memory;
+}
+
+void wpi::memory::virtual_memory_decommit(void* memory, std::size_t no_pages) noexcept
+{
+    auto size = no_pages * virtual_memory_page_size;
+// advise that the memory won't be needed anymore
+#if defined(MADV_FREE)
+    madvise(memory, size, MADV_FREE);
+#elif defined(MADV_DONTNEED)
+    madvise(memory, size, MADV_DONTNEED);
+#elif defined(POSIX_MADV_DONTNEED)
+    posix_madvise(memory, size, POSIX_MADV_DONTNEED);
+#endif
+
+    auto result = mprotect(memory, size, PROT_NONE);
+    WPI_MEMORY_ASSERT_MSG(result == 0, "cannot decommit memory");
+    (void)result;
+}
+#else
+#warning "virtual memory functions not available on your platform, define your own"
+#endif
+
+std::size_t wpi::memory::get_virtual_memory_page_size() noexcept
+{
+    return virtual_memory_page_size;
+}
+
+namespace
+{
+    std::size_t calc_no_pages(std::size_t size) noexcept
+    {
+        auto div  = size / virtual_memory_page_size;
+        auto rest = size % virtual_memory_page_size;
+
+        return div + (rest != 0u) + (detail::debug_fence_size ? 2u : 1u);
+    }
+} // namespace
+
+void* virtual_memory_allocator::allocate_node(std::size_t size, std::size_t)
+{
+    auto no_pages = calc_no_pages(size);
+    auto pages    = virtual_memory_reserve(no_pages);
+    if (!pages || !virtual_memory_commit(pages, no_pages))
+        WPI_THROW(
+            out_of_memory({WPI_MEMORY_LOG_PREFIX "::virtual_memory_allocator", nullptr},
+                          no_pages * virtual_memory_page_size));
+    on_allocate(size);
+
+    return detail::debug_fill_new(pages, size, virtual_memory_page_size);
+}
+
+void virtual_memory_allocator::deallocate_node(void* node, std::size_t size, std::size_t) noexcept
+{
+    auto pages = detail::debug_fill_free(node, size, virtual_memory_page_size);
+
+    on_deallocate(size);
+
+    auto no_pages = calc_no_pages(size);
+    virtual_memory_decommit(pages, no_pages);
+    virtual_memory_release(pages, no_pages);
+}
+
+std::size_t virtual_memory_allocator::max_node_size() const noexcept
+{
+    return std::size_t(-1);
+}
+
+std::size_t virtual_memory_allocator::max_alignment() const noexcept
+{
+    return virtual_memory_page_size;
+}
+
+#if WPI_MEMORY_EXTERN_TEMPLATE
+template class wpi::memory::allocator_traits<virtual_memory_allocator>;
+#endif
+
+virtual_block_allocator::virtual_block_allocator(std::size_t block_size, std::size_t no_blocks)
+: block_size_(block_size)
+{
+    WPI_MEMORY_ASSERT(block_size % virtual_memory_page_size == 0u);
+    WPI_MEMORY_ASSERT(no_blocks > 0);
+    auto total_size = block_size_ * no_blocks;
+    auto no_pages   = total_size / virtual_memory_page_size;
+
+    cur_ = static_cast<char*>(virtual_memory_reserve(no_pages));
+    if (!cur_)
+        WPI_THROW(out_of_memory(info(), total_size));
+    end_ = cur_ + total_size;
+}
+
+virtual_block_allocator::~virtual_block_allocator() noexcept
+{
+    virtual_memory_release(cur_, static_cast<std::size_t>(end_ - cur_) / virtual_memory_page_size);
+}
+
+memory_block virtual_block_allocator::allocate_block()
+{
+    if (std::size_t(end_ - cur_) < block_size_)
+        WPI_THROW(out_of_fixed_memory(info(), block_size_));
+    auto mem = virtual_memory_commit(cur_, block_size_ / virtual_memory_page_size);
+    if (!mem)
+        WPI_THROW(out_of_fixed_memory(info(), block_size_));
+    cur_ += block_size_;
+    return {mem, block_size_};
+}
+
+void virtual_block_allocator::deallocate_block(memory_block block) noexcept
+{
+    detail::debug_check_pointer([&]
+                                { return static_cast<char*>(block.memory) == cur_ - block_size_; },
+                                info(), block.memory);
+    cur_ -= block_size_;
+    virtual_memory_decommit(cur_, block_size_);
+}
+
+allocator_info virtual_block_allocator::info() noexcept
+{
+    return {WPI_MEMORY_LOG_PREFIX "::virtual_block_allocator", this};
+}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/mpack.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/mpack/include/wpi/mpack.h
similarity index 100%
rename from third_party/allwpilib/wpiutil/src/main/native/include/wpi/mpack.h
rename to third_party/allwpilib/wpiutil/src/main/native/thirdparty/mpack/include/wpi/mpack.h
diff --git a/third_party/allwpilib/wpiutil/src/main/native/thirdparty/mpack/src/mpack.cpp b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/mpack/src/mpack.cpp
new file mode 100644
index 0000000..af5fbd0
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/mpack/src/mpack.cpp
@@ -0,0 +1,7261 @@
+/**
+ * The MIT License (MIT)
+ * 
+ * Copyright (c) 2015-2021 Nicholas Fraser and the MPack authors
+ * 
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ * 
+ * The above copyright notice and this permission notice shall be included in all
+ * copies or substantial portions of the Software.
+ * 
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+ * SOFTWARE.
+ * 
+ */
+
+/*
+ * This is the MPack 1.1 amalgamation package.
+ *
+ * http://github.com/ludocode/mpack
+ */
+
+#define MPACK_INTERNAL 1
+#define MPACK_EMIT_INLINE_DEFS 0
+
+#include "wpi/mpack.h"
+
+
+/* mpack/mpack-platform.c.c */
+
+
+// We define MPACK_EMIT_INLINE_DEFS and include mpack.h to emit
+// standalone definitions of all (non-static) inline functions in MPack.
+
+#define MPACK_INTERNAL 1
+#define MPACK_EMIT_INLINE_DEFS 0
+
+/* #include "mpack-platform.h" */
+/* #include "mpack.h" */
+
+MPACK_SILENCE_WARNINGS_BEGIN
+namespace mpack {
+
+#if MPACK_DEBUG
+
+#if MPACK_STDIO
+void mpack_assert_fail_format(const char* format, ...) {
+    char buffer[512];
+    va_list args;
+    va_start(args, format);
+    vsnprintf(buffer, sizeof(buffer), format, args);
+    va_end(args);
+    buffer[sizeof(buffer) - 1] = 0;
+    mpack_assert_fail_wrapper(buffer);
+}
+
+void mpack_break_hit_format(const char* format, ...) {
+    char buffer[512];
+    va_list args;
+    va_start(args, format);
+    vsnprintf(buffer, sizeof(buffer), format, args);
+    va_end(args);
+    buffer[sizeof(buffer) - 1] = 0;
+    mpack_break_hit(buffer);
+}
+#endif
+
+#if !MPACK_CUSTOM_ASSERT
+void mpack_assert_fail(const char* message) {
+    MPACK_UNUSED(message);
+
+    #if MPACK_STDIO
+    fprintf(stderr, "%s\n", message);
+    #endif
+}
+#endif
+
+// We split the assert failure from the wrapper so that a
+// custom assert function can return.
+void mpack_assert_fail_wrapper(const char* message) {
+
+    #ifdef MPACK_GCOV
+    // gcov marks even __builtin_unreachable() as an uncovered line. this
+    // silences it.
+    (mpack_assert_fail(message), __builtin_unreachable());
+
+    #else
+    mpack_assert_fail(message);
+
+    // mpack_assert_fail() is not supposed to return. in case it does, we
+    // abort.
+
+    #if !MPACK_NO_BUILTINS
+    #if defined(__GNUC__) || defined(__clang__)
+    __builtin_trap();
+    #elif defined(WIN32)
+    __debugbreak();
+    #endif
+    #endif
+
+    #if (defined(__GNUC__) || defined(__clang__)) && !MPACK_NO_BUILTINS
+    __builtin_abort();
+    #elif MPACK_STDLIB
+    abort();
+    #endif
+
+    MPACK_UNREACHABLE;
+    #endif
+}
+
+#if !MPACK_CUSTOM_BREAK
+
+// If we have a custom assert handler, break wraps it by default.
+// This allows users of MPack to only implement mpack_assert_fail() without
+// having to worry about the difference between assert and break.
+//
+// MPACK_CUSTOM_BREAK is available to define a separate break handler
+// (which is needed by the unit test suite), but this is not offered in
+// mpack-config.h for simplicity.
+
+#if MPACK_CUSTOM_ASSERT
+void mpack_break_hit(const char* message) {
+    mpack_assert_fail_wrapper(message);
+}
+#else
+void mpack_break_hit(const char* message) {
+    MPACK_UNUSED(message);
+
+    #if MPACK_STDIO
+    fprintf(stderr, "%s\n", message);
+    #endif
+
+    #if defined(__GNUC__) || defined(__clang__) && !MPACK_NO_BUILTINS
+    __builtin_trap();
+    #elif defined(WIN32) && !MPACK_NO_BUILTINS
+    __debugbreak();
+    #elif MPACK_STDLIB
+    abort();
+    #endif
+}
+#endif
+
+#endif
+
+#endif
+
+
+
+// The below are adapted from the C wikibook:
+//     https://en.wikibooks.org/wiki/C_Programming/Strings
+
+#ifndef mpack_memcmp
+int mpack_memcmp(const void* s1, const void* s2, size_t n) {
+     const unsigned char *us1 = (const unsigned char *) s1;
+     const unsigned char *us2 = (const unsigned char *) s2;
+     while (n-- != 0) {
+         if (*us1 != *us2)
+             return (*us1 < *us2) ? -1 : +1;
+         us1++;
+         us2++;
+     }
+     return 0;
+}
+#endif
+
+#ifndef mpack_memcpy
+void* mpack_memcpy(void* MPACK_RESTRICT s1, const void* MPACK_RESTRICT s2, size_t n) {
+    char* MPACK_RESTRICT dst = (char *)s1;
+    const char* MPACK_RESTRICT src = (const char *)s2;
+    while (n-- != 0)
+        *dst++ = *src++;
+    return s1;
+}
+#endif
+
+#ifndef mpack_memmove
+void* mpack_memmove(void* s1, const void* s2, size_t n) {
+    char *p1 = (char *)s1;
+    const char *p2 = (const char *)s2;
+    if (p2 < p1 && p1 < p2 + n) {
+        p2 += n;
+        p1 += n;
+        while (n-- != 0)
+            *--p1 = *--p2;
+    } else
+        while (n-- != 0)
+            *p1++ = *p2++;
+    return s1;
+}
+#endif
+
+#ifndef mpack_memset
+void* mpack_memset(void* s, int c, size_t n) {
+    unsigned char *us = (unsigned char *)s;
+    unsigned char uc = (unsigned char)c;
+    while (n-- != 0)
+        *us++ = uc;
+    return s;
+}
+#endif
+
+#ifndef mpack_strlen
+size_t mpack_strlen(const char* s) {
+    const char* p = s;
+    while (*p != '\0')
+        p++;
+    return (size_t)(p - s);
+}
+#endif
+
+
+
+#if defined(MPACK_MALLOC) && !defined(MPACK_REALLOC)
+void* mpack_realloc(void* old_ptr, size_t used_size, size_t new_size) {
+    if (new_size == 0) {
+        if (old_ptr)
+            MPACK_FREE(old_ptr);
+        return NULL;
+    }
+
+    void* new_ptr = MPACK_MALLOC(new_size);
+    if (new_ptr == NULL)
+        return NULL;
+
+    mpack_memcpy(new_ptr, old_ptr, used_size);
+    MPACK_FREE(old_ptr);
+    return new_ptr;
+}
+#endif
+
+}  // namespace mpack
+MPACK_SILENCE_WARNINGS_END
+
+/* mpack/mpack-common.c.c */
+
+#define MPACK_INTERNAL 1
+
+/* #include "mpack-common.h" */
+
+MPACK_SILENCE_WARNINGS_BEGIN
+namespace mpack {
+
+const char* mpack_error_to_string(mpack_error_t error) {
+    #if MPACK_STRINGS
+    switch (error) {
+        #define MPACK_ERROR_STRING_CASE(e) case e: return #e
+        MPACK_ERROR_STRING_CASE(mpack_ok);
+        MPACK_ERROR_STRING_CASE(mpack_error_io);
+        MPACK_ERROR_STRING_CASE(mpack_error_invalid);
+        MPACK_ERROR_STRING_CASE(mpack_error_unsupported);
+        MPACK_ERROR_STRING_CASE(mpack_error_type);
+        MPACK_ERROR_STRING_CASE(mpack_error_too_big);
+        MPACK_ERROR_STRING_CASE(mpack_error_memory);
+        MPACK_ERROR_STRING_CASE(mpack_error_bug);
+        MPACK_ERROR_STRING_CASE(mpack_error_data);
+        MPACK_ERROR_STRING_CASE(mpack_error_eof);
+        #undef MPACK_ERROR_STRING_CASE
+    }
+    mpack_assert(0, "unrecognized error %i", (int)error);
+    return "(unknown mpack_error_t)";
+    #else
+    MPACK_UNUSED(error);
+    return "";
+    #endif
+}
+
+const char* mpack_type_to_string(mpack_type_t type) {
+    #if MPACK_STRINGS
+    switch (type) {
+        #define MPACK_TYPE_STRING_CASE(e) case e: return #e
+        MPACK_TYPE_STRING_CASE(mpack_type_missing);
+        MPACK_TYPE_STRING_CASE(mpack_type_nil);
+        MPACK_TYPE_STRING_CASE(mpack_type_bool);
+        MPACK_TYPE_STRING_CASE(mpack_type_float);
+        MPACK_TYPE_STRING_CASE(mpack_type_double);
+        MPACK_TYPE_STRING_CASE(mpack_type_int);
+        MPACK_TYPE_STRING_CASE(mpack_type_uint);
+        MPACK_TYPE_STRING_CASE(mpack_type_str);
+        MPACK_TYPE_STRING_CASE(mpack_type_bin);
+        MPACK_TYPE_STRING_CASE(mpack_type_array);
+        MPACK_TYPE_STRING_CASE(mpack_type_map);
+        #if MPACK_EXTENSIONS
+        MPACK_TYPE_STRING_CASE(mpack_type_ext);
+        #endif
+        #undef MPACK_TYPE_STRING_CASE
+    }
+    mpack_assert(0, "unrecognized type %i", (int)type);
+    return "(unknown mpack_type_t)";
+    #else
+    MPACK_UNUSED(type);
+    return "";
+    #endif
+}
+
+int mpack_tag_cmp(mpack_tag_t left, mpack_tag_t right) {
+
+    // positive numbers may be stored as int; convert to uint
+    if (left.type == mpack_type_int && left.v.i >= 0) {
+        left.type = mpack_type_uint;
+        left.v.u = (uint64_t)left.v.i;
+    }
+    if (right.type == mpack_type_int && right.v.i >= 0) {
+        right.type = mpack_type_uint;
+        right.v.u = (uint64_t)right.v.i;
+    }
+
+    if (left.type != right.type)
+        return ((int)left.type < (int)right.type) ? -1 : 1;
+
+    switch (left.type) {
+        case mpack_type_missing: // fallthrough
+        case mpack_type_nil:
+            return 0;
+
+        case mpack_type_bool:
+            return (int)left.v.b - (int)right.v.b;
+
+        case mpack_type_int:
+            if (left.v.i == right.v.i)
+                return 0;
+            return (left.v.i < right.v.i) ? -1 : 1;
+
+        case mpack_type_uint:
+            if (left.v.u == right.v.u)
+                return 0;
+            return (left.v.u < right.v.u) ? -1 : 1;
+
+        case mpack_type_array:
+        case mpack_type_map:
+            if (left.v.n == right.v.n)
+                return 0;
+            return (left.v.n < right.v.n) ? -1 : 1;
+
+        case mpack_type_str:
+        case mpack_type_bin:
+            if (left.v.l == right.v.l)
+                return 0;
+            return (left.v.l < right.v.l) ? -1 : 1;
+
+        #if MPACK_EXTENSIONS
+        case mpack_type_ext:
+            if (left.exttype == right.exttype) {
+                if (left.v.l == right.v.l)
+                    return 0;
+                return (left.v.l < right.v.l) ? -1 : 1;
+            }
+            return (int)left.exttype - (int)right.exttype;
+        #endif
+
+        // floats should not normally be compared for equality. we compare
+        // with memcmp() to silence compiler warnings, but this will return
+        // equal if both are NaNs with the same representation (though we may
+        // want this, for instance if you are for some bizarre reason using
+        // floats as map keys.) i'm not sure what the right thing to
+        // do is here. check for NaN first? always return false if the type
+        // is float? use operator== and pragmas to silence compiler warning?
+        // please send me your suggestions.
+        // note also that we don't convert floats to doubles, so when this is
+        // used for ordering purposes, all floats are ordered before all
+        // doubles.
+        case mpack_type_float:
+            return mpack_memcmp(&left.v.f, &right.v.f, sizeof(left.v.f));
+        case mpack_type_double:
+            return mpack_memcmp(&left.v.d, &right.v.d, sizeof(left.v.d));
+    }
+
+    mpack_assert(0, "unrecognized type %i", (int)left.type);
+    return false;
+}
+
+#if MPACK_DEBUG && MPACK_STDIO
+static char mpack_hex_char(uint8_t hex_value) {
+    // Older compilers (e.g. GCC 4.4.7) promote the result of this ternary to
+    // int and warn under -Wconversion, so we have to cast it back to char.
+    return (char)((hex_value < 10) ? (char)('0' + hex_value) : (char)('a' + (hex_value - 10)));
+}
+
+static void mpack_tag_debug_complete_bin_ext(mpack_tag_t tag, size_t string_length, char* buffer, size_t buffer_size,
+        const char* prefix, size_t prefix_size)
+{
+    // If at any point in this function we run out of space in the buffer, we
+    // bail out. The outer tag print wrapper will make sure we have a
+    // null-terminator.
+
+    if (string_length == 0 || string_length >= buffer_size)
+        return;
+    buffer += string_length;
+    buffer_size -= string_length;
+
+    size_t total = mpack_tag_bytes(&tag);
+    if (total == 0) {
+        strncpy(buffer, ">", buffer_size);
+        return;
+    }
+
+    strncpy(buffer, ": ", buffer_size);
+    if (buffer_size < 2)
+        return;
+    buffer += 2;
+    buffer_size -= 2;
+
+    size_t hex_bytes = 0;
+    size_t i;
+    for (i = 0; i < MPACK_PRINT_BYTE_COUNT && i < prefix_size && buffer_size > 2; ++i) {
+        uint8_t byte = (uint8_t)prefix[i];
+        buffer[0] = mpack_hex_char((uint8_t)(byte >> 4));
+        buffer[1] = mpack_hex_char((uint8_t)(byte & 0xfu));
+        buffer += 2;
+        buffer_size -= 2;
+        ++hex_bytes;
+    }
+
+    if (buffer_size != 0)
+        mpack_snprintf(buffer, buffer_size, "%s>", (total > hex_bytes) ? "..." : "");
+}
+
+static void mpack_tag_debug_pseudo_json_bin(mpack_tag_t tag, char* buffer, size_t buffer_size,
+        const char* prefix, size_t prefix_size)
+{
+    mpack_assert(mpack_tag_type(&tag) == mpack_type_bin);
+    size_t length = (size_t)mpack_snprintf(buffer, buffer_size, "<binary data of length %u", tag.v.l);
+    mpack_tag_debug_complete_bin_ext(tag, length, buffer, buffer_size, prefix, prefix_size);
+}
+
+#if MPACK_EXTENSIONS
+static void mpack_tag_debug_pseudo_json_ext(mpack_tag_t tag, char* buffer, size_t buffer_size,
+        const char* prefix, size_t prefix_size)
+{
+    mpack_assert(mpack_tag_type(&tag) == mpack_type_ext);
+    size_t length = (size_t)mpack_snprintf(buffer, buffer_size, "<ext data of type %i and length %u",
+            mpack_tag_ext_exttype(&tag), mpack_tag_ext_length(&tag));
+    mpack_tag_debug_complete_bin_ext(tag, length, buffer, buffer_size, prefix, prefix_size);
+}
+#endif
+
+static void mpack_tag_debug_pseudo_json_impl(mpack_tag_t tag, char* buffer, size_t buffer_size,
+        const char* prefix, size_t prefix_size)
+{
+    switch (tag.type) {
+        case mpack_type_missing:
+            mpack_snprintf(buffer, buffer_size, "<missing!>");
+            return;
+        case mpack_type_nil:
+            mpack_snprintf(buffer, buffer_size, "null");
+            return;
+        case mpack_type_bool:
+            mpack_snprintf(buffer, buffer_size, tag.v.b ? "true" : "false");
+            return;
+        case mpack_type_int:
+            mpack_snprintf(buffer, buffer_size, "%" PRIi64, tag.v.i);
+            return;
+        case mpack_type_uint:
+            mpack_snprintf(buffer, buffer_size, "%" PRIu64, tag.v.u);
+            return;
+        case mpack_type_float:
+            #if MPACK_FLOAT
+            mpack_snprintf(buffer, buffer_size, "%f", tag.v.f);
+            #else
+            mpack_snprintf(buffer, buffer_size, "<float>");
+            #endif
+            return;
+        case mpack_type_double:
+            #if MPACK_DOUBLE
+            mpack_snprintf(buffer, buffer_size, "%f", tag.v.d);
+            #else
+            mpack_snprintf(buffer, buffer_size, "<double>");
+            #endif
+            return;
+
+        case mpack_type_str:
+            mpack_snprintf(buffer, buffer_size, "<string of %u bytes>", tag.v.l);
+            return;
+        case mpack_type_bin:
+            mpack_tag_debug_pseudo_json_bin(tag, buffer, buffer_size, prefix, prefix_size);
+            return;
+        #if MPACK_EXTENSIONS
+        case mpack_type_ext:
+            mpack_tag_debug_pseudo_json_ext(tag, buffer, buffer_size, prefix, prefix_size);
+            return;
+        #endif
+
+        case mpack_type_array:
+            mpack_snprintf(buffer, buffer_size, "<array of %u elements>", tag.v.n);
+            return;
+        case mpack_type_map:
+            mpack_snprintf(buffer, buffer_size, "<map of %u key-value pairs>", tag.v.n);
+            return;
+    }
+
+    mpack_snprintf(buffer, buffer_size, "<unknown!>");
+}
+
+void mpack_tag_debug_pseudo_json(mpack_tag_t tag, char* buffer, size_t buffer_size,
+        const char* prefix, size_t prefix_size)
+{
+    mpack_assert(buffer_size > 0, "buffer size cannot be zero!");
+    buffer[0] = 0;
+
+    mpack_tag_debug_pseudo_json_impl(tag, buffer, buffer_size, prefix, prefix_size);
+
+    // We always null-terminate the buffer manually just in case the snprintf()
+    // function doesn't null-terminate when the string doesn't fit.
+    buffer[buffer_size - 1] = 0;
+}
+
+static void mpack_tag_debug_describe_impl(mpack_tag_t tag, char* buffer, size_t buffer_size) {
+    switch (tag.type) {
+        case mpack_type_missing:
+            mpack_snprintf(buffer, buffer_size, "missing");
+            return;
+        case mpack_type_nil:
+            mpack_snprintf(buffer, buffer_size, "nil");
+            return;
+        case mpack_type_bool:
+            mpack_snprintf(buffer, buffer_size, tag.v.b ? "true" : "false");
+            return;
+        case mpack_type_int:
+            mpack_snprintf(buffer, buffer_size, "int %" PRIi64, tag.v.i);
+            return;
+        case mpack_type_uint:
+            mpack_snprintf(buffer, buffer_size, "uint %" PRIu64, tag.v.u);
+            return;
+        case mpack_type_float:
+            #if MPACK_FLOAT
+            mpack_snprintf(buffer, buffer_size, "float %f", tag.v.f);
+            #else
+            mpack_snprintf(buffer, buffer_size, "float");
+            #endif
+            return;
+        case mpack_type_double:
+            #if MPACK_DOUBLE
+            mpack_snprintf(buffer, buffer_size, "double %f", tag.v.d);
+            #else
+            mpack_snprintf(buffer, buffer_size, "double");
+            #endif
+            return;
+        case mpack_type_str:
+            mpack_snprintf(buffer, buffer_size, "str of %u bytes", tag.v.l);
+            return;
+        case mpack_type_bin:
+            mpack_snprintf(buffer, buffer_size, "bin of %u bytes", tag.v.l);
+            return;
+        #if MPACK_EXTENSIONS
+        case mpack_type_ext:
+            mpack_snprintf(buffer, buffer_size, "ext of type %i, %u bytes",
+                    mpack_tag_ext_exttype(&tag), mpack_tag_ext_length(&tag));
+            return;
+        #endif
+        case mpack_type_array:
+            mpack_snprintf(buffer, buffer_size, "array of %u elements", tag.v.n);
+            return;
+        case mpack_type_map:
+            mpack_snprintf(buffer, buffer_size, "map of %u key-value pairs", tag.v.n);
+            return;
+    }
+
+    mpack_snprintf(buffer, buffer_size, "unknown!");
+}
+
+void mpack_tag_debug_describe(mpack_tag_t tag, char* buffer, size_t buffer_size) {
+    mpack_assert(buffer_size > 0, "buffer size cannot be zero!");
+    buffer[0] = 0;
+
+    mpack_tag_debug_describe_impl(tag, buffer, buffer_size);
+
+    // We always null-terminate the buffer manually just in case the snprintf()
+    // function doesn't null-terminate when the string doesn't fit.
+    buffer[buffer_size - 1] = 0;
+}
+#endif
+
+
+
+#if MPACK_READ_TRACKING || MPACK_WRITE_TRACKING
+
+#ifndef MPACK_TRACKING_INITIAL_CAPACITY
+// seems like a reasonable number. we grow by doubling, and it only
+// needs to be as long as the maximum depth of the message.
+#define MPACK_TRACKING_INITIAL_CAPACITY 8
+#endif
+
+mpack_error_t mpack_track_init(mpack_track_t* track) {
+    track->count = 0;
+    track->capacity = MPACK_TRACKING_INITIAL_CAPACITY;
+    track->elements = (mpack_track_element_t*)MPACK_MALLOC(sizeof(mpack_track_element_t) * track->capacity);
+    if (track->elements == NULL)
+        return mpack_error_memory;
+    return mpack_ok;
+}
+
+mpack_error_t mpack_track_grow(mpack_track_t* track) {
+    mpack_assert(track->elements, "null track elements!");
+    mpack_assert(track->count == track->capacity, "incorrect growing?");
+
+    size_t new_capacity = track->capacity * 2;
+
+    mpack_track_element_t* new_elements = (mpack_track_element_t*)mpack_realloc(track->elements,
+            sizeof(mpack_track_element_t) * track->count, sizeof(mpack_track_element_t) * new_capacity);
+    if (new_elements == NULL)
+        return mpack_error_memory;
+
+    track->elements = new_elements;
+    track->capacity = new_capacity;
+    return mpack_ok;
+}
+
+mpack_error_t mpack_track_push(mpack_track_t* track, mpack_type_t type, uint32_t count) {
+    mpack_assert(track->elements, "null track elements!");
+    mpack_log("track pushing %s count %i\n", mpack_type_to_string(type), (int)count);
+
+    // grow if needed
+    if (track->count == track->capacity) {
+        mpack_error_t error = mpack_track_grow(track);
+        if (error != mpack_ok)
+            return error;
+    }
+
+    // insert new track
+    track->elements[track->count].type = type;
+    track->elements[track->count].left = count;
+    track->elements[track->count].builder = false;
+    track->elements[track->count].key_needs_value = false;
+    ++track->count;
+    return mpack_ok;
+}
+
+// TODO dedupe this
+mpack_error_t mpack_track_push_builder(mpack_track_t* track, mpack_type_t type) {
+    mpack_assert(track->elements, "null track elements!");
+    mpack_log("track pushing %s builder\n", mpack_type_to_string(type));
+
+    // grow if needed
+    if (track->count == track->capacity) {
+        mpack_error_t error = mpack_track_grow(track);
+        if (error != mpack_ok)
+            return error;
+    }
+
+    // insert new track
+    track->elements[track->count].type = type;
+    track->elements[track->count].left = 0;
+    track->elements[track->count].builder = true;
+    track->elements[track->count].key_needs_value = false;
+    ++track->count;
+    return mpack_ok;
+}
+
+static mpack_error_t mpack_track_pop_impl(mpack_track_t* track, mpack_type_t type, bool builder) {
+    mpack_assert(track->elements, "null track elements!");
+    mpack_log("track popping %s\n", mpack_type_to_string(type));
+
+    if (track->count == 0) {
+        mpack_break("attempting to close a %s but nothing was opened!", mpack_type_to_string(type));
+        return mpack_error_bug;
+    }
+
+    mpack_track_element_t* element = &track->elements[track->count - 1];
+
+    if (element->type != type) {
+        mpack_break("attempting to close a %s but the open element is a %s!",
+                mpack_type_to_string(type), mpack_type_to_string(element->type));
+        return mpack_error_bug;
+    }
+
+    if (element->key_needs_value) {
+        mpack_assert(type == mpack_type_map, "key_needs_value can only be true for maps!");
+        mpack_break("attempting to close a %s but an odd number of elements were written",
+                mpack_type_to_string(type));
+        return mpack_error_bug;
+    }
+
+    if (element->left != 0) {
+        mpack_break("attempting to close a %s but there are %i %s left",
+                mpack_type_to_string(type), element->left,
+                (type == mpack_type_map || type == mpack_type_array) ? "elements" : "bytes");
+        return mpack_error_bug;
+    }
+
+    if (element->builder != builder) {
+        mpack_break("attempting to pop a %sbuilder but the open element is %sa builder",
+                builder ? "" : "non-",
+                element->builder ? "" : "not ");
+        return mpack_error_bug;
+    }
+
+    --track->count;
+    return mpack_ok;
+}
+
+mpack_error_t mpack_track_pop(mpack_track_t* track, mpack_type_t type) {
+    return mpack_track_pop_impl(track, type, false);
+}
+
+mpack_error_t mpack_track_pop_builder(mpack_track_t* track, mpack_type_t type) {
+    return mpack_track_pop_impl(track, type, true);
+}
+
+mpack_error_t mpack_track_peek_element(mpack_track_t* track, bool read) {
+    MPACK_UNUSED(read);
+    mpack_assert(track->elements, "null track elements!");
+
+    // if there are no open elements, that's fine, we can read/write elements at will
+    if (track->count == 0)
+        return mpack_ok;
+
+    mpack_track_element_t* element = &track->elements[track->count - 1];
+
+    if (element->type != mpack_type_map && element->type != mpack_type_array) {
+        mpack_break("elements cannot be %s within an %s", read ? "read" : "written",
+                mpack_type_to_string(element->type));
+        return mpack_error_bug;
+    }
+
+    if (!element->builder && element->left == 0 && !element->key_needs_value) {
+        mpack_break("too many elements %s for %s", read ? "read" : "written",
+                mpack_type_to_string(element->type));
+        return mpack_error_bug;
+    }
+
+    return mpack_ok;
+}
+
+mpack_error_t mpack_track_element(mpack_track_t* track, bool read) {
+    mpack_error_t error = mpack_track_peek_element(track, read);
+    if (track->count == 0 || error != mpack_ok)
+        return error;
+
+    mpack_track_element_t* element = &track->elements[track->count - 1];
+
+    if (element->type == mpack_type_map) {
+        if (!element->key_needs_value) {
+            element->key_needs_value = true;
+            return mpack_ok; // don't decrement
+        }
+        element->key_needs_value = false;
+    }
+
+    if (!element->builder)
+        --element->left;
+    return mpack_ok;
+}
+
+mpack_error_t mpack_track_bytes(mpack_track_t* track, bool read, size_t count) {
+    MPACK_UNUSED(read);
+    mpack_assert(track->elements, "null track elements!");
+
+    if (count > MPACK_UINT32_MAX) {
+        mpack_break("%s more bytes than could possibly fit in a str/bin/ext!",
+                read ? "reading" : "writing");
+        return mpack_error_bug;
+    }
+
+    if (track->count == 0) {
+        mpack_break("bytes cannot be %s with no open bin, str or ext", read ? "read" : "written");
+        return mpack_error_bug;
+    }
+
+    mpack_track_element_t* element = &track->elements[track->count - 1];
+
+    if (element->type == mpack_type_map || element->type == mpack_type_array) {
+        mpack_break("bytes cannot be %s within an %s", read ? "read" : "written",
+                mpack_type_to_string(element->type));
+        return mpack_error_bug;
+    }
+
+    if (element->left < count) {
+        mpack_break("too many bytes %s for %s", read ? "read" : "written",
+                mpack_type_to_string(element->type));
+        return mpack_error_bug;
+    }
+
+    element->left -= (uint32_t)count;
+    return mpack_ok;
+}
+
+mpack_error_t mpack_track_str_bytes_all(mpack_track_t* track, bool read, size_t count) {
+    mpack_error_t error = mpack_track_bytes(track, read, count);
+    if (error != mpack_ok)
+        return error;
+
+    mpack_track_element_t* element = &track->elements[track->count - 1];
+
+    if (element->type != mpack_type_str) {
+        mpack_break("the open type must be a string, not a %s", mpack_type_to_string(element->type));
+        return mpack_error_bug;
+    }
+
+    if (element->left != 0) {
+        mpack_break("not all bytes were read; the wrong byte count was requested for a string read.");
+        return mpack_error_bug;
+    }
+
+    return mpack_ok;
+}
+
+mpack_error_t mpack_track_check_empty(mpack_track_t* track) {
+    if (track->count != 0) {
+        mpack_break("unclosed %s", mpack_type_to_string(track->elements[0].type));
+        return mpack_error_bug;
+    }
+    return mpack_ok;
+}
+
+mpack_error_t mpack_track_destroy(mpack_track_t* track, bool cancel) {
+    mpack_error_t error = cancel ? mpack_ok : mpack_track_check_empty(track);
+    if (track->elements) {
+        MPACK_FREE(track->elements);
+        track->elements = NULL;
+    }
+    return error;
+}
+#endif
+
+
+
+static bool mpack_utf8_check_impl(const uint8_t* str, size_t count, bool allow_null) {
+    while (count > 0) {
+        uint8_t lead = str[0];
+
+        // NUL
+        if (!allow_null && lead == '\0') // we don't allow NUL bytes in MPack C-strings
+            return false;
+
+        // ASCII
+        if (lead <= 0x7F) {
+            ++str;
+            --count;
+
+        // 2-byte sequence
+        } else if ((lead & 0xE0) == 0xC0) {
+            if (count < 2) // truncated sequence
+                return false;
+
+            uint8_t cont = str[1];
+            if ((cont & 0xC0) != 0x80) // not a continuation byte
+                return false;
+
+            str += 2;
+            count -= 2;
+
+            uint32_t z = ((uint32_t)(lead & ~0xE0) << 6) |
+                          (uint32_t)(cont & ~0xC0);
+
+            if (z < 0x80) // overlong sequence
+                return false;
+
+        // 3-byte sequence
+        } else if ((lead & 0xF0) == 0xE0) {
+            if (count < 3) // truncated sequence
+                return false;
+
+            uint8_t cont1 = str[1];
+            if ((cont1 & 0xC0) != 0x80) // not a continuation byte
+                return false;
+            uint8_t cont2 = str[2];
+            if ((cont2 & 0xC0) != 0x80) // not a continuation byte
+                return false;
+
+            str += 3;
+            count -= 3;
+
+            uint32_t z = ((uint32_t)(lead  & ~0xF0) << 12) |
+                         ((uint32_t)(cont1 & ~0xC0) <<  6) |
+                          (uint32_t)(cont2 & ~0xC0);
+
+            if (z < 0x800) // overlong sequence
+                return false;
+            if (z >= 0xD800 && z <= 0xDFFF) // surrogate
+                return false;
+
+        // 4-byte sequence
+        } else if ((lead & 0xF8) == 0xF0) {
+            if (count < 4) // truncated sequence
+                return false;
+
+            uint8_t cont1 = str[1];
+            if ((cont1 & 0xC0) != 0x80) // not a continuation byte
+                return false;
+            uint8_t cont2 = str[2];
+            if ((cont2 & 0xC0) != 0x80) // not a continuation byte
+                return false;
+            uint8_t cont3 = str[3];
+            if ((cont3 & 0xC0) != 0x80) // not a continuation byte
+                return false;
+
+            str += 4;
+            count -= 4;
+
+            uint32_t z = ((uint32_t)(lead  & ~0xF8) << 18) |
+                         ((uint32_t)(cont1 & ~0xC0) << 12) |
+                         ((uint32_t)(cont2 & ~0xC0) <<  6) |
+                          (uint32_t)(cont3 & ~0xC0);
+
+            if (z < 0x10000) // overlong sequence
+                return false;
+            if (z > 0x10FFFF) // codepoint limit
+                return false;
+
+        } else {
+            return false; // continuation byte without a lead, or lead for a 5-byte sequence or longer
+        }
+    }
+    return true;
+}
+
+bool mpack_utf8_check(const char* str, size_t bytes) {
+    return mpack_utf8_check_impl((const uint8_t*)str, bytes, true);
+}
+
+bool mpack_utf8_check_no_null(const char* str, size_t bytes) {
+    return mpack_utf8_check_impl((const uint8_t*)str, bytes, false);
+}
+
+bool mpack_str_check_no_null(const char* str, size_t bytes) {
+    size_t i;
+    for (i = 0; i < bytes; ++i)
+        if (str[i] == '\0')
+            return false;
+    return true;
+}
+
+#if MPACK_DEBUG && MPACK_STDIO
+void mpack_print_append(mpack_print_t* print, const char* data, size_t count) {
+
+    // copy whatever fits into the buffer
+    size_t copy = print->size - print->count;
+    if (copy > count)
+        copy = count;
+    mpack_memcpy(print->buffer + print->count, data, copy);
+    print->count += copy;
+    data += copy;
+    count -= copy;
+
+    // if we don't need to flush or can't flush there's nothing else to do
+    if (count == 0 || print->callback == NULL)
+        return;
+
+    // flush the buffer
+    print->callback(print->context, print->buffer, print->count);
+
+    if (count > print->size / 2) {
+        // flush the rest of the data
+        print->count = 0;
+        print->callback(print->context, data, count);
+    } else {
+        // copy the rest of the data into the buffer
+        mpack_memcpy(print->buffer, data, count);
+        print->count = count;
+    }
+
+}
+
+void mpack_print_flush(mpack_print_t* print) {
+    if (print->count > 0 && print->callback != NULL) {
+        print->callback(print->context, print->buffer, print->count);
+        print->count = 0;
+    }
+}
+
+void mpack_print_file_callback(void* context, const char* data, size_t count) {
+    FILE* file = (FILE*)context;
+    fwrite(data, 1, count, file);
+}
+#endif
+
+}  // namespace mpack
+MPACK_SILENCE_WARNINGS_END
+
+/* mpack/mpack-writer.c.c */
+
+#define MPACK_INTERNAL 1
+
+/* #include "mpack-writer.h" */
+
+MPACK_SILENCE_WARNINGS_BEGIN
+namespace mpack {
+
+#if MPACK_WRITER
+
+#if MPACK_BUILDER
+static void mpack_builder_flush(mpack_writer_t* writer);
+#endif
+
+#if MPACK_WRITE_TRACKING
+static void mpack_writer_flag_if_error(mpack_writer_t* writer, mpack_error_t error) {
+    if (error != mpack_ok)
+        mpack_writer_flag_error(writer, error);
+}
+
+void mpack_writer_track_push(mpack_writer_t* writer, mpack_type_t type, uint32_t count) {
+    if (writer->error == mpack_ok)
+        mpack_writer_flag_if_error(writer, mpack_track_push(&writer->track, type, count));
+}
+
+void mpack_writer_track_push_builder(mpack_writer_t* writer, mpack_type_t type) {
+    if (writer->error == mpack_ok)
+        mpack_writer_flag_if_error(writer, mpack_track_push_builder(&writer->track, type));
+}
+
+void mpack_writer_track_pop(mpack_writer_t* writer, mpack_type_t type) {
+    if (writer->error == mpack_ok)
+        mpack_writer_flag_if_error(writer, mpack_track_pop(&writer->track, type));
+}
+
+void mpack_writer_track_pop_builder(mpack_writer_t* writer, mpack_type_t type) {
+    if (writer->error == mpack_ok)
+        mpack_writer_flag_if_error(writer, mpack_track_pop_builder(&writer->track, type));
+}
+
+void mpack_writer_track_bytes(mpack_writer_t* writer, size_t count) {
+    if (writer->error == mpack_ok)
+        mpack_writer_flag_if_error(writer, mpack_track_bytes(&writer->track, false, count));
+}
+#endif
+
+// This should probably be renamed. It's not solely used for tracking.
+static inline void mpack_writer_track_element(mpack_writer_t* writer) {
+    (void)writer;
+
+    #if MPACK_WRITE_TRACKING
+    if (writer->error == mpack_ok)
+        mpack_writer_flag_if_error(writer, mpack_track_element(&writer->track, false));
+    #endif
+
+    #if MPACK_BUILDER
+    if (writer->builder.current_build != NULL) {
+        mpack_build_t* build = writer->builder.current_build;
+        // We only track this write if it's not nested within another non-build
+        // map or array.
+        if (build->nested_compound_elements == 0) {
+            if (build->type != mpack_type_map) {
+                ++build->count;
+                mpack_log("adding element to build %p, now %u elements\n", (void*)build, build->count);
+            } else if (build->key_needs_value) {
+                build->key_needs_value = false;
+                ++build->count;
+            } else {
+                build->key_needs_value = true;
+            }
+        }
+    }
+    #endif
+}
+
+static void mpack_writer_clear(mpack_writer_t* writer) {
+    #if MPACK_COMPATIBILITY
+    writer->version = mpack_version_current;
+    #endif
+    writer->flush = NULL;
+    writer->error_fn = NULL;
+    writer->teardown = NULL;
+    writer->context = NULL;
+
+    writer->buffer = NULL;
+    writer->position = NULL;
+    writer->end = NULL;
+    writer->error = mpack_ok;
+
+    #if MPACK_WRITE_TRACKING
+    mpack_memset(&writer->track, 0, sizeof(writer->track));
+    #endif
+
+    #if MPACK_BUILDER
+    writer->builder.current_build = NULL;
+    writer->builder.latest_build = NULL;
+    writer->builder.current_page = NULL;
+    writer->builder.pages = NULL;
+    writer->builder.stash_buffer = NULL;
+    writer->builder.stash_position = NULL;
+    writer->builder.stash_end = NULL;
+    #endif
+}
+
+void mpack_writer_init(mpack_writer_t* writer, char* buffer, size_t size) {
+    mpack_assert(buffer != NULL, "cannot initialize writer with empty buffer");
+    mpack_writer_clear(writer);
+    writer->buffer = buffer;
+    writer->position = buffer;
+    writer->end = writer->buffer + size;
+
+    #if MPACK_WRITE_TRACKING
+    mpack_writer_flag_if_error(writer, mpack_track_init(&writer->track));
+    #endif
+
+    mpack_log("===========================\n");
+    mpack_log("initializing writer with buffer size %i\n", (int)size);
+}
+
+void mpack_writer_init_error(mpack_writer_t* writer, mpack_error_t error) {
+    mpack_writer_clear(writer);
+    writer->error = error;
+
+    mpack_log("===========================\n");
+    mpack_log("initializing writer in error state %i\n", (int)error);
+}
+
+void mpack_writer_set_flush(mpack_writer_t* writer, mpack_writer_flush_t flush) {
+    MPACK_STATIC_ASSERT(MPACK_WRITER_MINIMUM_BUFFER_SIZE >= MPACK_MAXIMUM_TAG_SIZE,
+            "minimum buffer size must fit any tag!");
+    MPACK_STATIC_ASSERT(31 + MPACK_TAG_SIZE_FIXSTR >= MPACK_WRITER_MINIMUM_BUFFER_SIZE,
+            "minimum buffer size must fit the largest possible fixstr!");
+
+    if (mpack_writer_buffer_size(writer) < MPACK_WRITER_MINIMUM_BUFFER_SIZE) {
+        mpack_break("buffer size is %i, but minimum buffer size for flush is %i",
+                (int)mpack_writer_buffer_size(writer), MPACK_WRITER_MINIMUM_BUFFER_SIZE);
+        mpack_writer_flag_error(writer, mpack_error_bug);
+        return;
+    }
+
+    writer->flush = flush;
+}
+
+#ifdef MPACK_MALLOC
+typedef struct mpack_growable_writer_t {
+    char** target_data;
+    size_t* target_size;
+} mpack_growable_writer_t;
+
+static char* mpack_writer_get_reserved(mpack_writer_t* writer) {
+    // This is in a separate function in order to avoid false strict aliasing
+    // warnings. We aren't actually violating strict aliasing (the reserved
+    // space is only ever dereferenced as an mpack_growable_writer_t.)
+    return (char*)writer->reserved;
+}
+
+static void mpack_growable_writer_flush(mpack_writer_t* writer, const char* data, size_t count) {
+
+    // This is an intrusive flush function which modifies the writer's buffer
+    // in response to a flush instead of emptying it in order to add more
+    // capacity for data. This removes the need to copy data from a fixed buffer
+    // into a growable one, improving performance.
+    //
+    // There are three ways flush can be called:
+    //   - flushing the buffer during writing (used is zero, count is all data, data is buffer)
+    //   - flushing extra data during writing (used is all flushed data, count is extra data, data is not buffer)
+    //   - flushing during teardown (used and count are both all flushed data, data is buffer)
+    //
+    // In the first two cases, we grow the buffer by at least double, enough
+    // to ensure that new data will fit. We ignore the teardown flush.
+
+    if (data == writer->buffer) {
+
+        // teardown, do nothing
+        if (mpack_writer_buffer_used(writer) == count)
+            return;
+
+        // otherwise leave the data in the buffer and just grow
+        writer->position = writer->buffer + count;
+        count = 0;
+    }
+
+    size_t used = mpack_writer_buffer_used(writer);
+    size_t size = mpack_writer_buffer_size(writer);
+
+    mpack_log("flush size %i used %i data %p buffer %p\n",
+            (int)count, (int)used, data, writer->buffer);
+
+    mpack_assert(data == writer->buffer || used + count > size,
+            "extra flush for %i but there is %i space left in the buffer! (%i/%i)",
+            (int)count, (int)mpack_writer_buffer_left(writer), (int)used, (int)size);
+
+    // grow to fit the data
+    // TODO: this really needs to correctly test for overflow
+    size_t new_size = size * 2;
+    while (new_size < used + count)
+        new_size *= 2;
+
+    mpack_log("flush growing buffer size from %i to %i\n", (int)size, (int)new_size);
+
+    // grow the buffer
+    char* new_buffer = (char*)mpack_realloc(writer->buffer, used, new_size);
+    if (new_buffer == NULL) {
+        mpack_writer_flag_error(writer, mpack_error_memory);
+        return;
+    }
+    writer->position = new_buffer + used;
+    writer->buffer = new_buffer;
+    writer->end = writer->buffer + new_size;
+
+    // append the extra data
+    if (count > 0) {
+        mpack_memcpy(writer->position, data, count);
+        writer->position += count;
+    }
+
+    mpack_log("new buffer %p, used %i\n", new_buffer, (int)mpack_writer_buffer_used(writer));
+}
+
+static void mpack_growable_writer_teardown(mpack_writer_t* writer) {
+    mpack_growable_writer_t* growable_writer = (mpack_growable_writer_t*)mpack_writer_get_reserved(writer);
+
+    if (mpack_writer_error(writer) == mpack_ok) {
+
+        // shrink the buffer to an appropriate size if the data is
+        // much smaller than the buffer
+        if (mpack_writer_buffer_used(writer) < mpack_writer_buffer_size(writer) / 2) {
+            size_t used = mpack_writer_buffer_used(writer);
+
+            // We always return a non-null pointer that must be freed, even if
+            // nothing was written. malloc() and realloc() do not necessarily
+            // do this so we enforce it ourselves.
+            size_t size = (used != 0) ? used : 1;
+
+            char* buffer = (char*)mpack_realloc(writer->buffer, used, size);
+            if (!buffer) {
+                MPACK_FREE(writer->buffer);
+                mpack_writer_flag_error(writer, mpack_error_memory);
+                return;
+            }
+            writer->buffer = buffer;
+            writer->end = (writer->position = writer->buffer + used);
+        }
+
+        *growable_writer->target_data = writer->buffer;
+        *growable_writer->target_size = mpack_writer_buffer_used(writer);
+        writer->buffer = NULL;
+
+    } else if (writer->buffer) {
+        MPACK_FREE(writer->buffer);
+        writer->buffer = NULL;
+    }
+
+    writer->context = NULL;
+}
+
+void mpack_writer_init_growable(mpack_writer_t* writer, char** target_data, size_t* target_size) {
+    mpack_assert(target_data != NULL, "cannot initialize writer without a destination for the data");
+    mpack_assert(target_size != NULL, "cannot initialize writer without a destination for the size");
+
+    *target_data = NULL;
+    *target_size = 0;
+
+    MPACK_STATIC_ASSERT(sizeof(mpack_growable_writer_t) <= sizeof(writer->reserved),
+            "not enough reserved space for growable writer!");
+    mpack_growable_writer_t* growable_writer = (mpack_growable_writer_t*)mpack_writer_get_reserved(writer);
+
+    growable_writer->target_data = target_data;
+    growable_writer->target_size = target_size;
+
+    size_t capacity = MPACK_BUFFER_SIZE;
+    char* buffer = (char*)MPACK_MALLOC(capacity);
+    if (buffer == NULL) {
+        mpack_writer_init_error(writer, mpack_error_memory);
+        return;
+    }
+
+    mpack_writer_init(writer, buffer, capacity);
+    mpack_writer_set_flush(writer, mpack_growable_writer_flush);
+    mpack_writer_set_teardown(writer, mpack_growable_writer_teardown);
+}
+#endif
+
+#if MPACK_STDIO
+static void mpack_file_writer_flush(mpack_writer_t* writer, const char* buffer, size_t count) {
+    FILE* file = (FILE*)writer->context;
+    size_t written = fwrite((const void*)buffer, 1, count, file);
+    if (written != count)
+        mpack_writer_flag_error(writer, mpack_error_io);
+}
+
+static void mpack_file_writer_teardown(mpack_writer_t* writer) {
+    MPACK_FREE(writer->buffer);
+    writer->buffer = NULL;
+    writer->context = NULL;
+}
+
+static void mpack_file_writer_teardown_close(mpack_writer_t* writer) {
+    FILE* file = (FILE*)writer->context;
+
+    if (file) {
+        int ret = fclose(file);
+        if (ret != 0)
+            mpack_writer_flag_error(writer, mpack_error_io);
+    }
+
+    mpack_file_writer_teardown(writer);
+}
+
+void mpack_writer_init_stdfile(mpack_writer_t* writer, FILE* file, bool close_when_done) {
+    mpack_assert(file != NULL, "file is NULL");
+
+    size_t capacity = MPACK_BUFFER_SIZE;
+    char* buffer = (char*)MPACK_MALLOC(capacity);
+    if (buffer == NULL) {
+        mpack_writer_init_error(writer, mpack_error_memory);
+        if (close_when_done) {
+            fclose(file);
+        }
+        return;
+    }
+
+    mpack_writer_init(writer, buffer, capacity);
+    mpack_writer_set_context(writer, file);
+    mpack_writer_set_flush(writer, mpack_file_writer_flush);
+    mpack_writer_set_teardown(writer, close_when_done ?
+            mpack_file_writer_teardown_close :
+            mpack_file_writer_teardown);
+}
+
+void mpack_writer_init_filename(mpack_writer_t* writer, const char* filename) {
+    mpack_assert(filename != NULL, "filename is NULL");
+
+    FILE* file = fopen(filename, "wb");
+    if (file == NULL) {
+        mpack_writer_init_error(writer, mpack_error_io);
+        return;
+    }
+
+    mpack_writer_init_stdfile(writer, file, true);
+}
+#endif
+
+void mpack_writer_flag_error(mpack_writer_t* writer, mpack_error_t error) {
+    mpack_log("writer %p setting error %i: %s\n", (void*)writer, (int)error, mpack_error_to_string(error));
+
+    if (writer->error == mpack_ok) {
+        writer->error = error;
+        if (writer->error_fn)
+            writer->error_fn(writer, writer->error);
+    }
+}
+
+MPACK_STATIC_INLINE void mpack_writer_flush_unchecked(mpack_writer_t* writer) {
+    // This is a bit ugly; we reset used before calling flush so that
+    // a flush function can distinguish between flushing the buffer
+    // versus flushing external data. see mpack_growable_writer_flush()
+    size_t used = mpack_writer_buffer_used(writer);
+    writer->position = writer->buffer;
+    writer->flush(writer, writer->buffer, used);
+}
+
+void mpack_writer_flush_message(mpack_writer_t* writer) {
+    if (writer->error != mpack_ok)
+        return;
+
+    #if MPACK_WRITE_TRACKING
+    // You cannot flush while there are elements open.
+    mpack_writer_flag_if_error(writer, mpack_track_check_empty(&writer->track));
+    if (writer->error != mpack_ok)
+        return;
+    #endif
+
+    #if MPACK_BUILDER
+    if (writer->builder.current_build != NULL) {
+        mpack_break("cannot call mpack_writer_flush_message() while there are elements open!");
+        mpack_writer_flag_error(writer, mpack_error_bug);
+        return;
+    }
+    #endif
+
+    if (writer->flush == NULL) {
+        mpack_break("cannot call mpack_writer_flush_message() without a flush function!");
+        mpack_writer_flag_error(writer, mpack_error_bug);
+        return;
+    }
+
+    if (mpack_writer_buffer_used(writer) > 0)
+        mpack_writer_flush_unchecked(writer);
+}
+
+// Ensures there are at least count bytes free in the buffer. This
+// will flag an error if the flush function fails to make enough
+// room in the buffer.
+MPACK_NOINLINE static bool mpack_writer_ensure(mpack_writer_t* writer, size_t count) {
+    mpack_assert(count != 0, "cannot ensure zero bytes!");
+    mpack_assert(count <= MPACK_WRITER_MINIMUM_BUFFER_SIZE,
+            "cannot ensure %i bytes, this is more than the minimum buffer size %i!",
+            (int)count, (int)MPACK_WRITER_MINIMUM_BUFFER_SIZE);
+    mpack_assert(count > mpack_writer_buffer_left(writer),
+            "request to ensure %i bytes but there are already %i left in the buffer!",
+            (int)count, (int)mpack_writer_buffer_left(writer));
+
+    mpack_log("ensuring %i bytes, %i left\n", (int)count, (int)mpack_writer_buffer_left(writer));
+
+    if (mpack_writer_error(writer) != mpack_ok)
+        return false;
+
+    #if MPACK_BUILDER
+    // if we have a build in progress, we just ask the builder for a page.
+    // either it will have space for a tag, or it will flag a memory error.
+    if (writer->builder.current_build != NULL) {
+        mpack_builder_flush(writer);
+        return mpack_writer_error(writer) == mpack_ok;
+    }
+    #endif
+
+    if (writer->flush == NULL) {
+        mpack_writer_flag_error(writer, mpack_error_too_big);
+        return false;
+    }
+
+    mpack_writer_flush_unchecked(writer);
+    if (mpack_writer_error(writer) != mpack_ok)
+        return false;
+
+    if (mpack_writer_buffer_left(writer) >= count)
+        return true;
+
+    mpack_writer_flag_error(writer, mpack_error_io);
+    return false;
+}
+
+// Writes encoded bytes to the buffer when we already know the data
+// does not fit in the buffer (i.e. it straddles the edge of the
+// buffer.) If there is a flush function, it is guaranteed to be
+// called; otherwise mpack_error_too_big is raised.
+MPACK_NOINLINE static void mpack_write_native_straddle(mpack_writer_t* writer, const char* p, size_t count) {
+    mpack_assert(count == 0 || p != NULL, "data pointer for %i bytes is NULL", (int)count);
+
+    if (mpack_writer_error(writer) != mpack_ok)
+        return;
+    mpack_log("big write for %i bytes from %p, %i space left in buffer\n",
+            (int)count, p, (int)mpack_writer_buffer_left(writer));
+    mpack_assert(count > mpack_writer_buffer_left(writer),
+            "big write requested for %i bytes, but there is %i available "
+            "space in buffer. should have called mpack_write_native() instead",
+            (int)count, (int)(mpack_writer_buffer_left(writer)));
+
+    #if MPACK_BUILDER
+    // if we have a build in progress, we can't flush. we need to copy all
+    // bytes into as many build buffer pages as it takes.
+    if (writer->builder.current_build != NULL) {
+        while (true) {
+            size_t step = (size_t)(writer->end - writer->position);
+            if (step > count)
+                step = count;
+            mpack_memcpy(writer->position, p, step);
+            writer->position += step;
+            p += step;
+            count -= step;
+
+            if (count == 0)
+                return;
+
+            mpack_builder_flush(writer);
+            if (mpack_writer_error(writer) != mpack_ok)
+                return;
+            mpack_assert(writer->position != writer->end);
+        }
+    }
+    #endif
+
+    // we'll need a flush function
+    if (!writer->flush) {
+        mpack_writer_flag_error(writer, mpack_error_too_big);
+        return;
+    }
+
+    // flush the buffer
+    mpack_writer_flush_unchecked(writer);
+    if (mpack_writer_error(writer) != mpack_ok)
+        return;
+
+    // note that an intrusive flush function (such as mpack_growable_writer_flush())
+    // may have changed size and/or reset used to a non-zero value. we treat both as
+    // though they may have changed, and there may still be data in the buffer.
+
+    // flush the extra data directly if it doesn't fit in the buffer
+    if (count > mpack_writer_buffer_left(writer)) {
+        writer->flush(writer, p, count);
+        if (mpack_writer_error(writer) != mpack_ok)
+            return;
+    } else {
+        mpack_memcpy(writer->position, p, count);
+        writer->position += count;
+    }
+}
+
+// Writes encoded bytes to the buffer, flushing if necessary.
+MPACK_STATIC_INLINE void mpack_write_native(mpack_writer_t* writer, const char* p, size_t count) {
+    mpack_assert(count == 0 || p != NULL, "data pointer for %i bytes is NULL", (int)count);
+
+    if (mpack_writer_buffer_left(writer) < count) {
+        mpack_write_native_straddle(writer, p, count);
+    } else {
+        mpack_memcpy(writer->position, p, count);
+        writer->position += count;
+    }
+}
+
+mpack_error_t mpack_writer_destroy(mpack_writer_t* writer) {
+
+    // clean up tracking, asserting if we're not already in an error state
+    #if MPACK_WRITE_TRACKING
+    mpack_track_destroy(&writer->track, writer->error != mpack_ok);
+    #endif
+
+    // flush any outstanding data
+    if (mpack_writer_error(writer) == mpack_ok && mpack_writer_buffer_used(writer) != 0 && writer->flush != NULL) {
+        writer->flush(writer, writer->buffer, mpack_writer_buffer_used(writer));
+        writer->flush = NULL;
+    }
+
+    if (writer->teardown) {
+        writer->teardown(writer);
+        writer->teardown = NULL;
+    }
+
+    return writer->error;
+}
+
+void mpack_write_tag(mpack_writer_t* writer, mpack_tag_t value) {
+    switch (value.type) {
+        case mpack_type_missing:
+            mpack_break("cannot write a missing value!");
+            mpack_writer_flag_error(writer, mpack_error_bug);
+            return;
+
+        case mpack_type_nil:    mpack_write_nil   (writer);            return;
+        case mpack_type_bool:   mpack_write_bool  (writer, value.v.b); return;
+        case mpack_type_int:    mpack_write_int   (writer, value.v.i); return;
+        case mpack_type_uint:   mpack_write_uint  (writer, value.v.u); return;
+
+        case mpack_type_float:
+            #if MPACK_FLOAT
+            mpack_write_float
+            #else
+            mpack_write_raw_float
+            #endif
+                (writer, value.v.f);
+            return;
+        case mpack_type_double:
+            #if MPACK_DOUBLE
+            mpack_write_double
+            #else
+            mpack_write_raw_double
+            #endif
+                (writer, value.v.d);
+            return;
+
+        case mpack_type_str: mpack_start_str(writer, value.v.l); return;
+        case mpack_type_bin: mpack_start_bin(writer, value.v.l); return;
+
+        #if MPACK_EXTENSIONS
+        case mpack_type_ext:
+            mpack_start_ext(writer, mpack_tag_ext_exttype(&value), mpack_tag_ext_length(&value));
+            return;
+        #endif
+
+        case mpack_type_array: mpack_start_array(writer, value.v.n); return;
+        case mpack_type_map:   mpack_start_map(writer, value.v.n);   return;
+    }
+
+    mpack_break("unrecognized type %i", (int)value.type);
+    mpack_writer_flag_error(writer, mpack_error_bug);
+}
+
+MPACK_STATIC_INLINE void mpack_write_byte_element(mpack_writer_t* writer, char value) {
+    mpack_writer_track_element(writer);
+    if (MPACK_LIKELY(mpack_writer_buffer_left(writer) >= 1) || mpack_writer_ensure(writer, 1))
+        *(writer->position++) = value;
+}
+
+void mpack_write_nil(mpack_writer_t* writer) {
+    mpack_write_byte_element(writer, (char)0xc0);
+}
+
+void mpack_write_bool(mpack_writer_t* writer, bool value) {
+    mpack_write_byte_element(writer, (char)(0xc2 | (value ? 1 : 0)));
+}
+
+void mpack_write_true(mpack_writer_t* writer) {
+    mpack_write_byte_element(writer, (char)0xc3);
+}
+
+void mpack_write_false(mpack_writer_t* writer) {
+    mpack_write_byte_element(writer, (char)0xc2);
+}
+
+void mpack_write_object_bytes(mpack_writer_t* writer, const char* data, size_t bytes) {
+    mpack_writer_track_element(writer);
+    mpack_write_native(writer, data, bytes);
+}
+
+/*
+ * Encode functions
+ */
+
+MPACK_STATIC_INLINE void mpack_encode_fixuint(char* p, uint8_t value) {
+    mpack_assert(value <= 127);
+    mpack_store_u8(p, value);
+}
+
+MPACK_STATIC_INLINE void mpack_encode_u8(char* p, uint8_t value) {
+    mpack_assert(value > 127);
+    mpack_store_u8(p, 0xcc);
+    mpack_store_u8(p + 1, value);
+}
+
+MPACK_STATIC_INLINE void mpack_encode_u16(char* p, uint16_t value) {
+    mpack_assert(value > MPACK_UINT8_MAX);
+    mpack_store_u8(p, 0xcd);
+    mpack_store_u16(p + 1, value);
+}
+
+MPACK_STATIC_INLINE void mpack_encode_u32(char* p, uint32_t value) {
+    mpack_assert(value > MPACK_UINT16_MAX);
+    mpack_store_u8(p, 0xce);
+    mpack_store_u32(p + 1, value);
+}
+
+MPACK_STATIC_INLINE void mpack_encode_u64(char* p, uint64_t value) {
+    mpack_assert(value > MPACK_UINT32_MAX);
+    mpack_store_u8(p, 0xcf);
+    mpack_store_u64(p + 1, value);
+}
+
+MPACK_STATIC_INLINE void mpack_encode_fixint(char* p, int8_t value) {
+    // this can encode positive or negative fixints
+    mpack_assert(value >= -32);
+    mpack_store_i8(p, value);
+}
+
+MPACK_STATIC_INLINE void mpack_encode_i8(char* p, int8_t value) {
+    mpack_assert(value < -32);
+    mpack_store_u8(p, 0xd0);
+    mpack_store_i8(p + 1, value);
+}
+
+MPACK_STATIC_INLINE void mpack_encode_i16(char* p, int16_t value) {
+    mpack_assert(value < MPACK_INT8_MIN);
+    mpack_store_u8(p, 0xd1);
+    mpack_store_i16(p + 1, value);
+}
+
+MPACK_STATIC_INLINE void mpack_encode_i32(char* p, int32_t value) {
+    mpack_assert(value < MPACK_INT16_MIN);
+    mpack_store_u8(p, 0xd2);
+    mpack_store_i32(p + 1, value);
+}
+
+MPACK_STATIC_INLINE void mpack_encode_i64(char* p, int64_t value) {
+    mpack_assert(value < MPACK_INT32_MIN);
+    mpack_store_u8(p, 0xd3);
+    mpack_store_i64(p + 1, value);
+}
+
+#if MPACK_FLOAT
+MPACK_STATIC_INLINE void mpack_encode_float(char* p, float value) {
+    mpack_store_u8(p, 0xca);
+    mpack_store_float(p + 1, value);
+}
+#else
+MPACK_STATIC_INLINE void mpack_encode_raw_float(char* p, uint32_t value) {
+    mpack_store_u8(p, 0xca);
+    mpack_store_u32(p + 1, value);
+}
+#endif
+
+#if MPACK_DOUBLE
+MPACK_STATIC_INLINE void mpack_encode_double(char* p, double value) {
+    mpack_store_u8(p, 0xcb);
+    mpack_store_double(p + 1, value);
+}
+#else
+MPACK_STATIC_INLINE void mpack_encode_raw_double(char* p, uint64_t value) {
+    mpack_store_u8(p, 0xcb);
+    mpack_store_u64(p + 1, value);
+}
+#endif
+
+MPACK_STATIC_INLINE void mpack_encode_fixarray(char* p, uint8_t count) {
+    mpack_assert(count <= 15);
+    mpack_store_u8(p, (uint8_t)(0x90 | count));
+}
+
+MPACK_STATIC_INLINE void mpack_encode_array16(char* p, uint16_t count) {
+    mpack_assert(count > 15);
+    mpack_store_u8(p, 0xdc);
+    mpack_store_u16(p + 1, count);
+}
+
+MPACK_STATIC_INLINE void mpack_encode_array32(char* p, uint32_t count) {
+    mpack_assert(count > MPACK_UINT16_MAX);
+    mpack_store_u8(p, 0xdd);
+    mpack_store_u32(p + 1, count);
+}
+
+MPACK_STATIC_INLINE void mpack_encode_fixmap(char* p, uint8_t count) {
+    mpack_assert(count <= 15);
+    mpack_store_u8(p, (uint8_t)(0x80 | count));
+}
+
+MPACK_STATIC_INLINE void mpack_encode_map16(char* p, uint16_t count) {
+    mpack_assert(count > 15);
+    mpack_store_u8(p, 0xde);
+    mpack_store_u16(p + 1, count);
+}
+
+MPACK_STATIC_INLINE void mpack_encode_map32(char* p, uint32_t count) {
+    mpack_assert(count > MPACK_UINT16_MAX);
+    mpack_store_u8(p, 0xdf);
+    mpack_store_u32(p + 1, count);
+}
+
+MPACK_STATIC_INLINE void mpack_encode_fixstr(char* p, uint8_t count) {
+    mpack_assert(count <= 31);
+    mpack_store_u8(p, (uint8_t)(0xa0 | count));
+}
+
+MPACK_STATIC_INLINE void mpack_encode_str8(char* p, uint8_t count) {
+    mpack_assert(count > 31);
+    mpack_store_u8(p, 0xd9);
+    mpack_store_u8(p + 1, count);
+}
+
+MPACK_STATIC_INLINE void mpack_encode_str16(char* p, uint16_t count) {
+    // we might be encoding a raw in compatibility mode, so we
+    // allow count to be in the range [32, MPACK_UINT8_MAX].
+    mpack_assert(count > 31);
+    mpack_store_u8(p, 0xda);
+    mpack_store_u16(p + 1, count);
+}
+
+MPACK_STATIC_INLINE void mpack_encode_str32(char* p, uint32_t count) {
+    mpack_assert(count > MPACK_UINT16_MAX);
+    mpack_store_u8(p, 0xdb);
+    mpack_store_u32(p + 1, count);
+}
+
+MPACK_STATIC_INLINE void mpack_encode_bin8(char* p, uint8_t count) {
+    mpack_store_u8(p, 0xc4);
+    mpack_store_u8(p + 1, count);
+}
+
+MPACK_STATIC_INLINE void mpack_encode_bin16(char* p, uint16_t count) {
+    mpack_assert(count > MPACK_UINT8_MAX);
+    mpack_store_u8(p, 0xc5);
+    mpack_store_u16(p + 1, count);
+}
+
+MPACK_STATIC_INLINE void mpack_encode_bin32(char* p, uint32_t count) {
+    mpack_assert(count > MPACK_UINT16_MAX);
+    mpack_store_u8(p, 0xc6);
+    mpack_store_u32(p + 1, count);
+}
+
+#if MPACK_EXTENSIONS
+MPACK_STATIC_INLINE void mpack_encode_fixext1(char* p, int8_t exttype) {
+    mpack_store_u8(p, 0xd4);
+    mpack_store_i8(p + 1, exttype);
+}
+
+MPACK_STATIC_INLINE void mpack_encode_fixext2(char* p, int8_t exttype) {
+    mpack_store_u8(p, 0xd5);
+    mpack_store_i8(p + 1, exttype);
+}
+
+MPACK_STATIC_INLINE void mpack_encode_fixext4(char* p, int8_t exttype) {
+    mpack_store_u8(p, 0xd6);
+    mpack_store_i8(p + 1, exttype);
+}
+
+MPACK_STATIC_INLINE void mpack_encode_fixext8(char* p, int8_t exttype) {
+    mpack_store_u8(p, 0xd7);
+    mpack_store_i8(p + 1, exttype);
+}
+
+MPACK_STATIC_INLINE void mpack_encode_fixext16(char* p, int8_t exttype) {
+    mpack_store_u8(p, 0xd8);
+    mpack_store_i8(p + 1, exttype);
+}
+
+MPACK_STATIC_INLINE void mpack_encode_ext8(char* p, int8_t exttype, uint8_t count) {
+    mpack_assert(count != 1 && count != 2 && count != 4 && count != 8 && count != 16);
+    mpack_store_u8(p, 0xc7);
+    mpack_store_u8(p + 1, count);
+    mpack_store_i8(p + 2, exttype);
+}
+
+MPACK_STATIC_INLINE void mpack_encode_ext16(char* p, int8_t exttype, uint16_t count) {
+    mpack_assert(count > MPACK_UINT8_MAX);
+    mpack_store_u8(p, 0xc8);
+    mpack_store_u16(p + 1, count);
+    mpack_store_i8(p + 3, exttype);
+}
+
+MPACK_STATIC_INLINE void mpack_encode_ext32(char* p, int8_t exttype, uint32_t count) {
+    mpack_assert(count > MPACK_UINT16_MAX);
+    mpack_store_u8(p, 0xc9);
+    mpack_store_u32(p + 1, count);
+    mpack_store_i8(p + 5, exttype);
+}
+
+MPACK_STATIC_INLINE void mpack_encode_timestamp_4(char* p, uint32_t seconds) {
+    mpack_encode_fixext4(p, MPACK_EXTTYPE_TIMESTAMP);
+    mpack_store_u32(p + MPACK_TAG_SIZE_FIXEXT4, seconds);
+}
+
+MPACK_STATIC_INLINE void mpack_encode_timestamp_8(char* p, int64_t seconds, uint32_t nanoseconds) {
+    mpack_assert(nanoseconds <= MPACK_TIMESTAMP_NANOSECONDS_MAX);
+    mpack_encode_fixext8(p, MPACK_EXTTYPE_TIMESTAMP);
+    uint64_t encoded = ((uint64_t)nanoseconds << 34) | (uint64_t)seconds;
+    mpack_store_u64(p + MPACK_TAG_SIZE_FIXEXT8, encoded);
+}
+
+MPACK_STATIC_INLINE void mpack_encode_timestamp_12(char* p, int64_t seconds, uint32_t nanoseconds) {
+    mpack_assert(nanoseconds <= MPACK_TIMESTAMP_NANOSECONDS_MAX);
+    mpack_encode_ext8(p, MPACK_EXTTYPE_TIMESTAMP, 12);
+    mpack_store_u32(p + MPACK_TAG_SIZE_EXT8, nanoseconds);
+    mpack_store_i64(p + MPACK_TAG_SIZE_EXT8 + 4, seconds);
+}
+#endif
+
+
+
+/*
+ * Write functions
+ */
+
+// This is a macro wrapper to the encode functions to encode
+// directly into the buffer. If mpack_writer_ensure() fails
+// it will flag an error so we don't have to do anything.
+#define MPACK_WRITE_ENCODED(encode_fn, size, ...) do {                                                 \
+    if (MPACK_LIKELY(mpack_writer_buffer_left(writer) >= size) || mpack_writer_ensure(writer, size)) { \
+        MPACK_EXPAND(encode_fn(writer->position, __VA_ARGS__));                                        \
+        writer->position += size;                                                                      \
+    }                                                                                                  \
+} while (0)
+
+void mpack_write_u8(mpack_writer_t* writer, uint8_t value) {
+    #if MPACK_OPTIMIZE_FOR_SIZE
+    mpack_write_u64(writer, value);
+    #else
+    mpack_writer_track_element(writer);
+    if (value <= 127) {
+        MPACK_WRITE_ENCODED(mpack_encode_fixuint, MPACK_TAG_SIZE_FIXUINT, value);
+    } else {
+        MPACK_WRITE_ENCODED(mpack_encode_u8, MPACK_TAG_SIZE_U8, value);
+    }
+    #endif
+}
+
+void mpack_write_u16(mpack_writer_t* writer, uint16_t value) {
+    #if MPACK_OPTIMIZE_FOR_SIZE
+    mpack_write_u64(writer, value);
+    #else
+    mpack_writer_track_element(writer);
+    if (value <= 127) {
+        MPACK_WRITE_ENCODED(mpack_encode_fixuint, MPACK_TAG_SIZE_FIXUINT, (uint8_t)value);
+    } else if (value <= MPACK_UINT8_MAX) {
+        MPACK_WRITE_ENCODED(mpack_encode_u8, MPACK_TAG_SIZE_U8, (uint8_t)value);
+    } else {
+        MPACK_WRITE_ENCODED(mpack_encode_u16, MPACK_TAG_SIZE_U16, value);
+    }
+    #endif
+}
+
+void mpack_write_u32(mpack_writer_t* writer, uint32_t value) {
+    #if MPACK_OPTIMIZE_FOR_SIZE
+    mpack_write_u64(writer, value);
+    #else
+    mpack_writer_track_element(writer);
+    if (value <= 127) {
+        MPACK_WRITE_ENCODED(mpack_encode_fixuint, MPACK_TAG_SIZE_FIXUINT, (uint8_t)value);
+    } else if (value <= MPACK_UINT8_MAX) {
+        MPACK_WRITE_ENCODED(mpack_encode_u8, MPACK_TAG_SIZE_U8, (uint8_t)value);
+    } else if (value <= MPACK_UINT16_MAX) {
+        MPACK_WRITE_ENCODED(mpack_encode_u16, MPACK_TAG_SIZE_U16, (uint16_t)value);
+    } else {
+        MPACK_WRITE_ENCODED(mpack_encode_u32, MPACK_TAG_SIZE_U32, value);
+    }
+    #endif
+}
+
+void mpack_write_u64(mpack_writer_t* writer, uint64_t value) {
+    mpack_writer_track_element(writer);
+
+    if (value <= 127) {
+        MPACK_WRITE_ENCODED(mpack_encode_fixuint, MPACK_TAG_SIZE_FIXUINT, (uint8_t)value);
+    } else if (value <= MPACK_UINT8_MAX) {
+        MPACK_WRITE_ENCODED(mpack_encode_u8, MPACK_TAG_SIZE_U8, (uint8_t)value);
+    } else if (value <= MPACK_UINT16_MAX) {
+        MPACK_WRITE_ENCODED(mpack_encode_u16, MPACK_TAG_SIZE_U16, (uint16_t)value);
+    } else if (value <= MPACK_UINT32_MAX) {
+        MPACK_WRITE_ENCODED(mpack_encode_u32, MPACK_TAG_SIZE_U32, (uint32_t)value);
+    } else {
+        MPACK_WRITE_ENCODED(mpack_encode_u64, MPACK_TAG_SIZE_U64, value);
+    }
+}
+
+void mpack_write_i8(mpack_writer_t* writer, int8_t value) {
+    #if MPACK_OPTIMIZE_FOR_SIZE
+    mpack_write_i64(writer, value);
+    #else
+    mpack_writer_track_element(writer);
+    if (value >= -32) {
+        // we encode positive and negative fixints together
+        MPACK_WRITE_ENCODED(mpack_encode_fixint, MPACK_TAG_SIZE_FIXINT, (int8_t)value);
+    } else {
+        MPACK_WRITE_ENCODED(mpack_encode_i8, MPACK_TAG_SIZE_I8, (int8_t)value);
+    }
+    #endif
+}
+
+void mpack_write_i16(mpack_writer_t* writer, int16_t value) {
+    #if MPACK_OPTIMIZE_FOR_SIZE
+    mpack_write_i64(writer, value);
+    #else
+    mpack_writer_track_element(writer);
+    if (value >= -32) {
+        if (value <= 127) {
+            // we encode positive and negative fixints together
+            MPACK_WRITE_ENCODED(mpack_encode_fixint, MPACK_TAG_SIZE_FIXINT, (int8_t)value);
+        } else if (value <= MPACK_UINT8_MAX) {
+            MPACK_WRITE_ENCODED(mpack_encode_u8, MPACK_TAG_SIZE_U8, (uint8_t)value);
+        } else {
+            MPACK_WRITE_ENCODED(mpack_encode_u16, MPACK_TAG_SIZE_U16, (uint16_t)value);
+        }
+    } else if (value >= MPACK_INT8_MIN) {
+        MPACK_WRITE_ENCODED(mpack_encode_i8, MPACK_TAG_SIZE_I8, (int8_t)value);
+    } else {
+        MPACK_WRITE_ENCODED(mpack_encode_i16, MPACK_TAG_SIZE_I16, (int16_t)value);
+    }
+    #endif
+}
+
+void mpack_write_i32(mpack_writer_t* writer, int32_t value) {
+    #if MPACK_OPTIMIZE_FOR_SIZE
+    mpack_write_i64(writer, value);
+    #else
+    mpack_writer_track_element(writer);
+    if (value >= -32) {
+        if (value <= 127) {
+            // we encode positive and negative fixints together
+            MPACK_WRITE_ENCODED(mpack_encode_fixint, MPACK_TAG_SIZE_FIXINT, (int8_t)value);
+        } else if (value <= MPACK_UINT8_MAX) {
+            MPACK_WRITE_ENCODED(mpack_encode_u8, MPACK_TAG_SIZE_U8, (uint8_t)value);
+        } else if (value <= MPACK_UINT16_MAX) {
+            MPACK_WRITE_ENCODED(mpack_encode_u16, MPACK_TAG_SIZE_U16, (uint16_t)value);
+        } else {
+            MPACK_WRITE_ENCODED(mpack_encode_u32, MPACK_TAG_SIZE_U32, (uint32_t)value);
+        }
+    } else if (value >= MPACK_INT8_MIN) {
+        MPACK_WRITE_ENCODED(mpack_encode_i8, MPACK_TAG_SIZE_I8, (int8_t)value);
+    } else if (value >= MPACK_INT16_MIN) {
+        MPACK_WRITE_ENCODED(mpack_encode_i16, MPACK_TAG_SIZE_I16, (int16_t)value);
+    } else {
+        MPACK_WRITE_ENCODED(mpack_encode_i32, MPACK_TAG_SIZE_I32, value);
+    }
+    #endif
+}
+
+void mpack_write_i64(mpack_writer_t* writer, int64_t value) {
+    #if MPACK_OPTIMIZE_FOR_SIZE
+    if (value > 127) {
+        // for non-fix positive ints we call the u64 writer to save space
+        mpack_write_u64(writer, (uint64_t)value);
+        return;
+    }
+    #endif
+
+    mpack_writer_track_element(writer);
+    if (value >= -32) {
+        #if MPACK_OPTIMIZE_FOR_SIZE
+        MPACK_WRITE_ENCODED(mpack_encode_fixint, MPACK_TAG_SIZE_FIXINT, (int8_t)value);
+        #else
+        if (value <= 127) {
+            MPACK_WRITE_ENCODED(mpack_encode_fixint, MPACK_TAG_SIZE_FIXINT, (int8_t)value);
+        } else if (value <= MPACK_UINT8_MAX) {
+            MPACK_WRITE_ENCODED(mpack_encode_u8, MPACK_TAG_SIZE_U8, (uint8_t)value);
+        } else if (value <= MPACK_UINT16_MAX) {
+            MPACK_WRITE_ENCODED(mpack_encode_u16, MPACK_TAG_SIZE_U16, (uint16_t)value);
+        } else if (value <= MPACK_UINT32_MAX) {
+            MPACK_WRITE_ENCODED(mpack_encode_u32, MPACK_TAG_SIZE_U32, (uint32_t)value);
+        } else {
+            MPACK_WRITE_ENCODED(mpack_encode_u64, MPACK_TAG_SIZE_U64, (uint64_t)value);
+        }
+        #endif
+    } else if (value >= MPACK_INT8_MIN) {
+        MPACK_WRITE_ENCODED(mpack_encode_i8, MPACK_TAG_SIZE_I8, (int8_t)value);
+    } else if (value >= MPACK_INT16_MIN) {
+        MPACK_WRITE_ENCODED(mpack_encode_i16, MPACK_TAG_SIZE_I16, (int16_t)value);
+    } else if (value >= MPACK_INT32_MIN) {
+        MPACK_WRITE_ENCODED(mpack_encode_i32, MPACK_TAG_SIZE_I32, (int32_t)value);
+    } else {
+        MPACK_WRITE_ENCODED(mpack_encode_i64, MPACK_TAG_SIZE_I64, value);
+    }
+}
+
+#if MPACK_FLOAT
+void mpack_write_float(mpack_writer_t* writer, float value) {
+    mpack_writer_track_element(writer);
+    MPACK_WRITE_ENCODED(mpack_encode_float, MPACK_TAG_SIZE_FLOAT, value);
+}
+#else
+void mpack_write_raw_float(mpack_writer_t* writer, uint32_t value) {
+    mpack_writer_track_element(writer);
+    MPACK_WRITE_ENCODED(mpack_encode_raw_float, MPACK_TAG_SIZE_FLOAT, value);
+}
+#endif
+
+#if MPACK_DOUBLE
+void mpack_write_double(mpack_writer_t* writer, double value) {
+    mpack_writer_track_element(writer);
+    MPACK_WRITE_ENCODED(mpack_encode_double, MPACK_TAG_SIZE_DOUBLE, value);
+}
+#else
+void mpack_write_raw_double(mpack_writer_t* writer, uint64_t value) {
+    mpack_writer_track_element(writer);
+    MPACK_WRITE_ENCODED(mpack_encode_raw_double, MPACK_TAG_SIZE_DOUBLE, value);
+}
+#endif
+
+#if MPACK_EXTENSIONS
+void mpack_write_timestamp(mpack_writer_t* writer, int64_t seconds, uint32_t nanoseconds) {
+    #if MPACK_COMPATIBILITY
+    if (writer->version <= mpack_version_v4) {
+        mpack_break("Timestamps require spec version v5 or later. This writer is in v%i mode.", (int)writer->version);
+        mpack_writer_flag_error(writer, mpack_error_bug);
+        return;
+    }
+    #endif
+
+    if (nanoseconds > MPACK_TIMESTAMP_NANOSECONDS_MAX) {
+        mpack_break("timestamp nanoseconds out of bounds: %u", nanoseconds);
+        mpack_writer_flag_error(writer, mpack_error_bug);
+        return;
+    }
+
+    mpack_writer_track_element(writer);
+
+    if (seconds < 0 || seconds >= (MPACK_INT64_C(1) << 34)) {
+        MPACK_WRITE_ENCODED(mpack_encode_timestamp_12, MPACK_EXT_SIZE_TIMESTAMP12, seconds, nanoseconds);
+    } else if (seconds > MPACK_UINT32_MAX || nanoseconds > 0) {
+        MPACK_WRITE_ENCODED(mpack_encode_timestamp_8, MPACK_EXT_SIZE_TIMESTAMP8, seconds, nanoseconds);
+    } else {
+        MPACK_WRITE_ENCODED(mpack_encode_timestamp_4, MPACK_EXT_SIZE_TIMESTAMP4, (uint32_t)seconds);
+    }
+}
+#endif
+
+static void mpack_write_array_notrack(mpack_writer_t* writer, uint32_t count) {
+    if (count <= 15) {
+        MPACK_WRITE_ENCODED(mpack_encode_fixarray, MPACK_TAG_SIZE_FIXARRAY, (uint8_t)count);
+    } else if (count <= MPACK_UINT16_MAX) {
+        MPACK_WRITE_ENCODED(mpack_encode_array16, MPACK_TAG_SIZE_ARRAY16, (uint16_t)count);
+    } else {
+        MPACK_WRITE_ENCODED(mpack_encode_array32, MPACK_TAG_SIZE_ARRAY32, (uint32_t)count);
+    }
+}
+
+static void mpack_write_map_notrack(mpack_writer_t* writer, uint32_t count) {
+    if (count <= 15) {
+        MPACK_WRITE_ENCODED(mpack_encode_fixmap, MPACK_TAG_SIZE_FIXMAP, (uint8_t)count);
+    } else if (count <= MPACK_UINT16_MAX) {
+        MPACK_WRITE_ENCODED(mpack_encode_map16, MPACK_TAG_SIZE_MAP16, (uint16_t)count);
+    } else {
+        MPACK_WRITE_ENCODED(mpack_encode_map32, MPACK_TAG_SIZE_MAP32, (uint32_t)count);
+    }
+}
+
+void mpack_start_array(mpack_writer_t* writer, uint32_t count) {
+    mpack_writer_track_element(writer);
+    mpack_write_array_notrack(writer, count);
+    mpack_writer_track_push(writer, mpack_type_array, count);
+    mpack_builder_compound_push(writer);
+}
+
+void mpack_start_map(mpack_writer_t* writer, uint32_t count) {
+    mpack_writer_track_element(writer);
+    mpack_write_map_notrack(writer, count);
+    mpack_writer_track_push(writer, mpack_type_map, count);
+    mpack_builder_compound_push(writer);
+}
+
+static void mpack_start_str_notrack(mpack_writer_t* writer, uint32_t count) {
+    if (count <= 31) {
+        MPACK_WRITE_ENCODED(mpack_encode_fixstr, MPACK_TAG_SIZE_FIXSTR, (uint8_t)count);
+
+    // str8 is only supported in v5 or later.
+    } else if (count <= MPACK_UINT8_MAX
+            #if MPACK_COMPATIBILITY
+            && writer->version >= mpack_version_v5
+            #endif
+            ) {
+        MPACK_WRITE_ENCODED(mpack_encode_str8, MPACK_TAG_SIZE_STR8, (uint8_t)count);
+
+    } else if (count <= MPACK_UINT16_MAX) {
+        MPACK_WRITE_ENCODED(mpack_encode_str16, MPACK_TAG_SIZE_STR16, (uint16_t)count);
+    } else {
+        MPACK_WRITE_ENCODED(mpack_encode_str32, MPACK_TAG_SIZE_STR32, (uint32_t)count);
+    }
+}
+
+static void mpack_start_bin_notrack(mpack_writer_t* writer, uint32_t count) {
+    #if MPACK_COMPATIBILITY
+    // In the v4 spec, there was only the raw type for any kind of
+    // variable-length data. In v4 mode, we support the bin functions,
+    // but we produce an old-style raw.
+    if (writer->version <= mpack_version_v4) {
+        mpack_start_str_notrack(writer, count);
+        return;
+    }
+    #endif
+
+    if (count <= MPACK_UINT8_MAX) {
+        MPACK_WRITE_ENCODED(mpack_encode_bin8, MPACK_TAG_SIZE_BIN8, (uint8_t)count);
+    } else if (count <= MPACK_UINT16_MAX) {
+        MPACK_WRITE_ENCODED(mpack_encode_bin16, MPACK_TAG_SIZE_BIN16, (uint16_t)count);
+    } else {
+        MPACK_WRITE_ENCODED(mpack_encode_bin32, MPACK_TAG_SIZE_BIN32, (uint32_t)count);
+    }
+}
+
+void mpack_start_str(mpack_writer_t* writer, uint32_t count) {
+    mpack_writer_track_element(writer);
+    mpack_start_str_notrack(writer, count);
+    mpack_writer_track_push(writer, mpack_type_str, count);
+}
+
+void mpack_start_bin(mpack_writer_t* writer, uint32_t count) {
+    mpack_writer_track_element(writer);
+    mpack_start_bin_notrack(writer, count);
+    mpack_writer_track_push(writer, mpack_type_bin, count);
+}
+
+#if MPACK_EXTENSIONS
+void mpack_start_ext(mpack_writer_t* writer, int8_t exttype, uint32_t count) {
+    #if MPACK_COMPATIBILITY
+    if (writer->version <= mpack_version_v4) {
+        mpack_break("Ext types require spec version v5 or later. This writer is in v%i mode.", (int)writer->version);
+        mpack_writer_flag_error(writer, mpack_error_bug);
+        return;
+    }
+    #endif
+
+    mpack_writer_track_element(writer);
+
+    if (count == 1) {
+        MPACK_WRITE_ENCODED(mpack_encode_fixext1, MPACK_TAG_SIZE_FIXEXT1, exttype);
+    } else if (count == 2) {
+        MPACK_WRITE_ENCODED(mpack_encode_fixext2, MPACK_TAG_SIZE_FIXEXT2, exttype);
+    } else if (count == 4) {
+        MPACK_WRITE_ENCODED(mpack_encode_fixext4, MPACK_TAG_SIZE_FIXEXT4, exttype);
+    } else if (count == 8) {
+        MPACK_WRITE_ENCODED(mpack_encode_fixext8, MPACK_TAG_SIZE_FIXEXT8, exttype);
+    } else if (count == 16) {
+        MPACK_WRITE_ENCODED(mpack_encode_fixext16, MPACK_TAG_SIZE_FIXEXT16, exttype);
+    } else if (count <= MPACK_UINT8_MAX) {
+        MPACK_WRITE_ENCODED(mpack_encode_ext8, MPACK_TAG_SIZE_EXT8, exttype, (uint8_t)count);
+    } else if (count <= MPACK_UINT16_MAX) {
+        MPACK_WRITE_ENCODED(mpack_encode_ext16, MPACK_TAG_SIZE_EXT16, exttype, (uint16_t)count);
+    } else {
+        MPACK_WRITE_ENCODED(mpack_encode_ext32, MPACK_TAG_SIZE_EXT32, exttype, (uint32_t)count);
+    }
+
+    mpack_writer_track_push(writer, mpack_type_ext, count);
+}
+#endif
+
+
+
+/*
+ * Compound helpers and other functions
+ */
+
+void mpack_write_str(mpack_writer_t* writer, const char* data, uint32_t count) {
+    mpack_assert(data != NULL, "data for string of length %i is NULL", (int)count);
+
+    #if MPACK_OPTIMIZE_FOR_SIZE
+    mpack_writer_track_element(writer);
+    mpack_start_str_notrack(writer, count);
+    mpack_write_native(writer, data, count);
+    #else
+
+    mpack_writer_track_element(writer);
+
+    if (count <= 31) {
+        // The minimum buffer size when using a flush function is guaranteed to
+        // fit the largest possible fixstr.
+        size_t size = count + MPACK_TAG_SIZE_FIXSTR;
+        if (MPACK_LIKELY(mpack_writer_buffer_left(writer) >= size) || mpack_writer_ensure(writer, size)) {
+            char* MPACK_RESTRICT p = writer->position;
+            mpack_encode_fixstr(p, (uint8_t)count);
+            mpack_memcpy(p + MPACK_TAG_SIZE_FIXSTR, data, count);
+            writer->position += count + MPACK_TAG_SIZE_FIXSTR;
+        }
+        return;
+    }
+
+    if (count <= MPACK_UINT8_MAX
+            #if MPACK_COMPATIBILITY
+            && writer->version >= mpack_version_v5
+            #endif
+            ) {
+        if (count + MPACK_TAG_SIZE_STR8 <= mpack_writer_buffer_left(writer)) {
+            char* MPACK_RESTRICT p = writer->position;
+            mpack_encode_str8(p, (uint8_t)count);
+            mpack_memcpy(p + MPACK_TAG_SIZE_STR8, data, count);
+            writer->position += count + MPACK_TAG_SIZE_STR8;
+        } else {
+            MPACK_WRITE_ENCODED(mpack_encode_str8, MPACK_TAG_SIZE_STR8, (uint8_t)count);
+            mpack_write_native(writer, data, count);
+        }
+        return;
+    }
+
+    // str16 and str32 are likely to be a significant fraction of the buffer
+    // size, so we don't bother with a combined space check in order to
+    // minimize code size.
+    if (count <= MPACK_UINT16_MAX) {
+        MPACK_WRITE_ENCODED(mpack_encode_str16, MPACK_TAG_SIZE_STR16, (uint16_t)count);
+        mpack_write_native(writer, data, count);
+    } else {
+        MPACK_WRITE_ENCODED(mpack_encode_str32, MPACK_TAG_SIZE_STR32, (uint32_t)count);
+        mpack_write_native(writer, data, count);
+    }
+
+    #endif
+}
+
+void mpack_write_bin(mpack_writer_t* writer, const char* data, uint32_t count) {
+    mpack_assert(data != NULL, "data pointer for bin of %i bytes is NULL", (int)count);
+    mpack_start_bin(writer, count);
+    mpack_write_bytes(writer, data, count);
+    mpack_finish_bin(writer);
+}
+
+#if MPACK_EXTENSIONS
+void mpack_write_ext(mpack_writer_t* writer, int8_t exttype, const char* data, uint32_t count) {
+    mpack_assert(data != NULL, "data pointer for ext of type %i and %i bytes is NULL", exttype, (int)count);
+    mpack_start_ext(writer, exttype, count);
+    mpack_write_bytes(writer, data, count);
+    mpack_finish_ext(writer);
+}
+#endif
+
+void mpack_write_bytes(mpack_writer_t* writer, const char* data, size_t count) {
+    mpack_assert(data != NULL, "data pointer for %i bytes is NULL", (int)count);
+    mpack_writer_track_bytes(writer, count);
+    mpack_write_native(writer, data, count);
+}
+
+void mpack_write_cstr(mpack_writer_t* writer, const char* cstr) {
+    mpack_assert(cstr != NULL, "cstr pointer is NULL");
+    size_t length = mpack_strlen(cstr);
+    if (length > MPACK_UINT32_MAX)
+        mpack_writer_flag_error(writer, mpack_error_invalid);
+    mpack_write_str(writer, cstr, (uint32_t)length);
+}
+
+void mpack_write_cstr_or_nil(mpack_writer_t* writer, const char* cstr) {
+    if (cstr)
+        mpack_write_cstr(writer, cstr);
+    else
+        mpack_write_nil(writer);
+}
+
+void mpack_write_utf8(mpack_writer_t* writer, const char* str, uint32_t length) {
+    mpack_assert(str != NULL, "data for string of length %i is NULL", (int)length);
+    if (!mpack_utf8_check(str, length)) {
+        mpack_writer_flag_error(writer, mpack_error_invalid);
+        return;
+    }
+    mpack_write_str(writer, str, length);
+}
+
+void mpack_write_utf8_cstr(mpack_writer_t* writer, const char* cstr) {
+    mpack_assert(cstr != NULL, "cstr pointer is NULL");
+    size_t length = mpack_strlen(cstr);
+    if (length > MPACK_UINT32_MAX) {
+        mpack_writer_flag_error(writer, mpack_error_invalid);
+        return;
+    }
+    mpack_write_utf8(writer, cstr, (uint32_t)length);
+}
+
+void mpack_write_utf8_cstr_or_nil(mpack_writer_t* writer, const char* cstr) {
+    if (cstr)
+        mpack_write_utf8_cstr(writer, cstr);
+    else
+        mpack_write_nil(writer);
+}
+
+/*
+ * Builder implementation
+ *
+ * When a writer is in build mode, it diverts writes to an internal growable
+ * buffer. All elements other than builder start tags are encoded as normal
+ * into the builder buffer (even nested maps and arrays of known size, e.g.
+ * `mpack_start_array()`.) But for compound elements of unknown size, an
+ * mpack_build_t is written to the buffer instead.
+ *
+ * The mpack_build_t tracks everything needed to re-constitute the final
+ * message once all sizes are known. When the last build element is completed,
+ * the builder resolves the build by walking through the builds, outputting the
+ * final encoded tag, and copying everything in between to the writer's true
+ * buffer.
+ *
+ * To make things extra complicated, the builder buffer is not contiguous. It's
+ * allocated in pages, where the first page may be an internal page in the
+ * writer. But, each mpack_build_t must itself be contiguous and aligned
+ * properly within the buffer. This means bytes can be skipped (and wasted)
+ * before the builds or at the end of pages.
+ *
+ * To keep track of this, builds store both their element count and the number
+ * of encoded bytes that follow, and pages store the number of bytes used. As
+ * elements are written, each element adds to the count in the current open
+ * build, and the number of bytes written adds to the current page and the byte
+ * count in the last started build (whether or not it is completed.)
+ */
+
+#if MPACK_BUILDER
+
+#ifdef MPACK_ALIGNOF
+    #define MPACK_BUILD_ALIGNMENT MPACK_ALIGNOF(mpack_build_t)
+#else
+    // without alignof, we just align to the greater of size_t, void* and uint64_t.
+    // (we do this even though we don't have uint64_t in it in case we add it later.)
+    #define MPACK_BUILD_ALIGNMENT_MAX(x, y) ((x) > (y) ? (x) : (y))
+    #define MPACK_BUILD_ALIGNMENT (MPACK_BUILD_ALIGNMENT_MAX(sizeof(void*), \
+                MPACK_BUILD_ALIGNMENT_MAX(sizeof(size_t), sizeof(uint64_t))))
+#endif
+
+static inline void mpack_builder_check_sizes(mpack_writer_t* writer) {
+
+    // We check internal and page sizes here so that we don't have to check
+    // them again. A new page with a build in it will have a page header,
+    // build, and minimum space for a tag. This will perform horribly and waste
+    // tons of memory if the page size is small, so you're best off just
+    // sticking with the defaults.
+    //
+    // These are all known at compile time, so if they are large
+    // enough this function should trivially optimize to a no-op.
+
+    #if MPACK_BUILDER_INTERNAL_STORAGE
+    // make sure the internal storage is big enough to be useful
+    MPACK_STATIC_ASSERT(MPACK_BUILDER_INTERNAL_STORAGE_SIZE >= (sizeof(mpack_builder_page_t) +
+            sizeof(mpack_build_t) + MPACK_WRITER_MINIMUM_BUFFER_SIZE),
+            "MPACK_BUILDER_INTERNAL_STORAGE_SIZE is too small to be useful!");
+    if (MPACK_BUILDER_INTERNAL_STORAGE_SIZE < (sizeof(mpack_builder_page_t) +
+            sizeof(mpack_build_t) + MPACK_WRITER_MINIMUM_BUFFER_SIZE))
+    {
+        mpack_break("MPACK_BUILDER_INTERNAL_STORAGE_SIZE is too small to be useful!");
+        mpack_writer_flag_error(writer, mpack_error_bug);
+    }
+    #endif
+
+    // make sure the builder page size is big enough to be useful
+    MPACK_STATIC_ASSERT(MPACK_BUILDER_PAGE_SIZE >= (sizeof(mpack_builder_page_t) +
+            sizeof(mpack_build_t) + MPACK_WRITER_MINIMUM_BUFFER_SIZE),
+            "MPACK_BUILDER_PAGE_SIZE is too small to be useful!");
+    if (MPACK_BUILDER_PAGE_SIZE < (sizeof(mpack_builder_page_t) +
+            sizeof(mpack_build_t) + MPACK_WRITER_MINIMUM_BUFFER_SIZE))
+    {
+        mpack_break("MPACK_BUILDER_PAGE_SIZE is too small to be useful!");
+        mpack_writer_flag_error(writer, mpack_error_bug);
+    }
+}
+
+static inline size_t mpack_builder_page_size(mpack_writer_t* writer, mpack_builder_page_t* page) {
+    #if MPACK_BUILDER_INTERNAL_STORAGE
+    if ((char*)page == writer->builder.internal)
+        return sizeof(writer->builder.internal);
+    #else
+    (void)writer;
+    (void)page;
+    #endif
+    return MPACK_BUILDER_PAGE_SIZE;
+}
+
+static inline size_t mpack_builder_align_build(size_t bytes_used) {
+    size_t offset = bytes_used;
+    offset += MPACK_BUILD_ALIGNMENT - 1;
+    offset -= offset % MPACK_BUILD_ALIGNMENT;
+    mpack_log("aligned %zi to %zi\n", bytes_used, offset);
+    return offset;
+}
+
+static inline void mpack_builder_free_page(mpack_writer_t* writer, mpack_builder_page_t* page) {
+    mpack_log("freeing page %p\n", (void*)page);
+    #if MPACK_BUILDER_INTERNAL_STORAGE
+    if ((char*)page == writer->builder.internal)
+        return;
+    #else
+    (void)writer;
+    #endif
+    MPACK_FREE(page);
+}
+
+static inline size_t mpack_builder_page_remaining(mpack_writer_t* writer, mpack_builder_page_t* page) {
+    return mpack_builder_page_size(writer, page) - page->bytes_used;
+}
+
+static void mpack_builder_configure_buffer(mpack_writer_t* writer) {
+    if (mpack_writer_error(writer) != mpack_ok)
+        return;
+    mpack_builder_t* builder = &writer->builder;
+
+    mpack_builder_page_t* page = builder->current_page;
+    mpack_assert(page != NULL, "page is null??");
+
+    // This diverts the writer into the remainder of the current page of our
+    // build buffer.
+    writer->buffer = (char*)page + page->bytes_used;
+    writer->position = (char*)page + page->bytes_used;
+    writer->end = (char*)page + mpack_builder_page_size(writer, page);
+    mpack_log("configuring buffer from %p to %p\n", (void*)writer->position, (void*)writer->end);
+}
+
+static void mpack_builder_add_page(mpack_writer_t* writer) {
+    mpack_builder_t* builder = &writer->builder;
+    mpack_assert(writer->error == mpack_ok);
+
+    mpack_log("adding a page.\n");
+    mpack_builder_page_t* page = (mpack_builder_page_t*)MPACK_MALLOC(MPACK_BUILDER_PAGE_SIZE);
+    if (page == NULL) {
+        mpack_writer_flag_error(writer, mpack_error_memory);
+        return;
+    }
+
+    page->next = NULL;
+    page->bytes_used = sizeof(mpack_builder_page_t);
+    builder->current_page->next = page;
+    builder->current_page = page;
+}
+
+// Checks how many bytes the writer wrote to the page, adding it to the page's
+// bytes_used. This must be followed up with mpack_builder_configure_buffer()
+// (after adding a new page, build, etc) to reset the writer's buffer pointers.
+static void mpack_builder_apply_writes(mpack_writer_t* writer) {
+    mpack_assert(writer->error == mpack_ok);
+    mpack_builder_t* builder = &writer->builder;
+    mpack_log("latest build is %p\n", (void*)builder->latest_build);
+
+    // The difference between buffer and current is the number of bytes that
+    // were written to the page.
+    size_t bytes_written = (size_t)(writer->position - writer->buffer);
+    mpack_log("applying write of %zi bytes to build %p\n", bytes_written, (void*)builder->latest_build);
+
+    mpack_assert(builder->current_page != NULL);
+    mpack_assert(builder->latest_build != NULL);
+    builder->current_page->bytes_used += bytes_written;
+    builder->latest_build->bytes += bytes_written;
+    mpack_log("latest build %p now has %zi bytes\n", (void*)builder->latest_build, builder->latest_build->bytes);
+}
+
+static void mpack_builder_flush(mpack_writer_t* writer) {
+    mpack_assert(writer->error == mpack_ok);
+    mpack_builder_apply_writes(writer);
+    mpack_builder_add_page(writer);
+    mpack_builder_configure_buffer(writer);
+}
+
+MPACK_NOINLINE static void mpack_builder_begin(mpack_writer_t* writer) {
+    mpack_builder_t* builder = &writer->builder;
+    mpack_assert(writer->error == mpack_ok);
+    mpack_assert(builder->current_build == NULL);
+    mpack_assert(builder->latest_build == NULL);
+    mpack_assert(builder->pages == NULL);
+
+    // If this is the first build, we need to stash the real buffer backing our
+    // writer. We'll be diverting the writer to our build buffer.
+    builder->stash_buffer = writer->buffer;
+    builder->stash_position = writer->position;
+    builder->stash_end = writer->end;
+
+    mpack_builder_page_t* page;
+
+    // we've checked that both these sizes are large enough above.
+    #if MPACK_BUILDER_INTERNAL_STORAGE
+    page = (mpack_builder_page_t*)builder->internal;
+    mpack_log("beginning builder with internal storage %p\n", (void*)page);
+    #else
+    page = (mpack_builder_page_t*)MPACK_MALLOC(MPACK_BUILDER_PAGE_SIZE);
+    if (page == NULL) {
+        mpack_writer_flag_error(writer, mpack_error_memory);
+        return;
+    }
+    mpack_log("beginning builder with allocated page %p\n", (void*)page);
+    #endif
+
+    page->next = NULL;
+    page->bytes_used = sizeof(mpack_builder_page_t);
+    builder->pages = page;
+    builder->current_page = page;
+}
+
+static void mpack_builder_build(mpack_writer_t* writer, mpack_type_t type) {
+    mpack_builder_check_sizes(writer);
+    if (mpack_writer_error(writer) != mpack_ok)
+        return;
+
+    mpack_writer_track_element(writer);
+    mpack_writer_track_push_builder(writer, type);
+
+    mpack_builder_t* builder = &writer->builder;
+
+    if (builder->current_build == NULL) {
+        mpack_builder_begin(writer);
+    } else {
+        mpack_builder_apply_writes(writer);
+    }
+    if (mpack_writer_error(writer) != mpack_ok)
+        return;
+
+    // find aligned space for a new build. if there isn't enough space in the
+    // current page, we discard the remaining space in it and allocate a new
+    // page.
+    size_t offset = mpack_builder_align_build(builder->current_page->bytes_used);
+    if (offset + sizeof(mpack_build_t) > mpack_builder_page_size(writer, builder->current_page)) {
+        mpack_log("not enough space for a build. %zi bytes used of %zi in this page\n",
+                builder->current_page->bytes_used, mpack_builder_page_size(writer, builder->current_page));
+        mpack_builder_add_page(writer);
+        // there is always enough space in a fresh page.
+        offset = mpack_builder_align_build(builder->current_page->bytes_used);
+    }
+
+    // allocate the build within the page. note that we don't keep track of the
+    // space wasted due to the offset. instead the previous build has stored
+    // how many bytes follow it, and we'll redo this offset calculation to find
+    // this build after it.
+    mpack_builder_page_t* page = builder->current_page;
+    page->bytes_used = offset + sizeof(mpack_build_t);
+    mpack_assert(page->bytes_used <= mpack_builder_page_size(writer, page));
+    mpack_build_t* build = (mpack_build_t*)((char*)page + offset);
+    mpack_log("created new build %p within page %p, which now has %zi bytes used\n",
+            (void*)build, (void*)page, page->bytes_used);
+
+    // configure the new build
+    build->parent = builder->current_build;
+    build->bytes = 0;
+    build->count = 0;
+    build->type = type;
+    build->key_needs_value = false;
+    build->nested_compound_elements = 0;
+
+    mpack_log("setting current and latest build to new build %p\n", (void*)build);
+    builder->current_build = build;
+    builder->latest_build = build;
+
+    // we always need to provide a buffer that meets the minimum buffer size.
+    // if there isn't enough space, we discard the remaining space in the
+    // current page and allocate a new one.
+    if (mpack_builder_page_remaining(writer, page) < MPACK_WRITER_MINIMUM_BUFFER_SIZE) {
+        mpack_log("less than minimum buffer size in current page. %zi bytes used of %zi in this page\n",
+                builder->current_page->bytes_used, mpack_builder_page_size(writer, builder->current_page));
+        mpack_builder_add_page(writer);
+        if (mpack_writer_error(writer) != mpack_ok)
+            return;
+    }
+    mpack_assert(mpack_builder_page_remaining(writer, builder->current_page) >= MPACK_WRITER_MINIMUM_BUFFER_SIZE);
+    mpack_builder_configure_buffer(writer);
+}
+
+MPACK_NOINLINE
+static void mpack_builder_resolve(mpack_writer_t* writer) {
+    mpack_builder_t* builder = &writer->builder;
+
+    // The starting page is the internal storage (if we have it), otherwise
+    // it's the first page in the array
+    mpack_builder_page_t* page =
+        #if MPACK_BUILDER_INTERNAL_STORAGE
+        (mpack_builder_page_t*)builder->internal
+        #else
+        builder->pages
+        #endif
+        ;
+
+    // We start by restoring the writer's original buffer so we can write the
+    // data for real.
+    writer->buffer = builder->stash_buffer;
+    writer->position = builder->stash_position;
+    writer->end = builder->stash_end;
+
+    // We can also close out the build now.
+    builder->current_build = NULL;
+    builder->latest_build = NULL;
+    builder->current_page = NULL;
+    builder->pages = NULL;
+
+    // the starting page always starts with the first build
+    size_t offset = mpack_builder_align_build(sizeof(mpack_builder_page_t));
+    mpack_build_t* build = (mpack_build_t*)((char*)page + offset);
+    mpack_log("starting resolve with build %p in page %p\n", (void*)build, (void*)page);
+
+    // encoded data immediately follows the build
+    offset += sizeof(mpack_build_t);
+
+    // Walk the list of builds, writing everything out in the buffer. Note that
+    // we don't check for errors anywhere. The lower-level write functions will
+    // all check for errors. We need to walk all pages anyway to free them, so
+    // there's not much point in optimizing an error path at the expense of the
+    // normal path.
+    while (true) {
+
+        // write out the container tag
+        mpack_log("writing out an %s with count %u followed by %zi bytes\n",
+                mpack_type_to_string(build->type), build->count, build->bytes);
+        switch (build->type) {
+            case mpack_type_map:
+                mpack_write_map_notrack(writer, build->count);
+                break;
+            case mpack_type_array:
+                mpack_write_array_notrack(writer, build->count);
+                break;
+            default:
+                mpack_break("invalid type in builder?");
+                mpack_writer_flag_error(writer, mpack_error_bug);
+                return;
+        }
+
+        // figure out how many bytes follow this container. we're going to be
+        // freeing pages as we write, so we need to be done with this build.
+        size_t left = build->bytes;
+        build = NULL;
+
+        // write out all bytes following this container
+        while (left > 0) {
+            size_t bytes_used = page->bytes_used;
+            if (offset < bytes_used) {
+                size_t step = bytes_used - offset;
+                if (step > left)
+                    step = left;
+                mpack_log("writing out %zi bytes starting at %p in page %p\n",
+                        step, (void*)((char*)page + offset), (void*)page);
+                mpack_write_native(writer, (char*)page + offset, step);
+                offset += step;
+                left -= step;
+            }
+
+            if (left == 0) {
+                mpack_log("done writing bytes for this build\n");
+                break;
+            }
+
+            // still need to write more bytes. free this page and jump to the
+            // next one.
+            mpack_builder_page_t* next_page = page->next;
+            mpack_builder_free_page(writer, page);
+            page = next_page;
+            // bytes on the next page immediately follow the header.
+            offset = sizeof(mpack_builder_page_t);
+        }
+
+        // now see if we can find another build.
+        offset = mpack_builder_align_build(offset);
+        if (offset + sizeof(mpack_build_t) >= mpack_builder_page_size(writer, page)) {
+            mpack_log("not enough room in this page for another build\n");
+            mpack_builder_page_t* next_page = page->next;
+            mpack_builder_free_page(writer, page);
+            page = next_page;
+            if (page == NULL) {
+                mpack_log("no more pages\n");
+                // there are no more pages. we're done.
+                break;
+            }
+            offset = mpack_builder_align_build(sizeof(mpack_builder_page_t));
+        }
+        if (offset + sizeof(mpack_build_t) > page->bytes_used) {
+            // there is no more data. we're done.
+            mpack_log("no more data\n");
+            mpack_builder_free_page(writer, page);
+            break;
+        }
+
+        // we've found another build. loop around!
+        build = (mpack_build_t*)((char*)page + offset);
+        offset += sizeof(mpack_build_t);
+        mpack_log("found build %p\n", (void*)build);
+    }
+
+    mpack_log("done resolve.\n");
+}
+
+static void mpack_builder_complete(mpack_writer_t* writer, mpack_type_t type) {
+    if (mpack_writer_error(writer) != mpack_ok)
+        return;
+
+    mpack_writer_track_pop_builder(writer, type);
+    mpack_builder_t* builder = &writer->builder;
+    mpack_assert(builder->current_build != NULL, "no build in progress!");
+    mpack_assert(builder->latest_build != NULL, "missing latest build!");
+    mpack_assert(builder->current_build->type == type, "completing wrong type!");
+    mpack_log("completing build %p\n", (void*)builder->current_build);
+
+    if (builder->current_build->key_needs_value) {
+        mpack_break("an odd number of elements were written in a map!");
+        mpack_writer_flag_error(writer, mpack_error_bug);
+        return;
+    }
+
+    if (builder->current_build->nested_compound_elements != 0) {
+        mpack_break("there is a nested unfinished non-build map or array in this build.");
+        mpack_writer_flag_error(writer, mpack_error_bug);
+        return;
+    }
+
+    // We need to apply whatever writes have been made to the current build
+    // before popping it.
+    mpack_builder_apply_writes(writer);
+
+    // For a nested build, we just switch the current build back to its parent.
+    if (builder->current_build->parent != NULL) {
+        mpack_log("setting current build to parent build %p. latest is still %p.\n",
+                (void*)builder->current_build->parent, (void*)builder->latest_build);
+        builder->current_build = builder->current_build->parent;
+        mpack_builder_configure_buffer(writer);
+    } else {
+        // We're completing the final build.
+        mpack_builder_resolve(writer);
+    }
+}
+
+void mpack_build_map(mpack_writer_t* writer) {
+    mpack_builder_build(writer, mpack_type_map);
+}
+
+void mpack_build_array(mpack_writer_t* writer) {
+    mpack_builder_build(writer, mpack_type_array);
+}
+
+void mpack_complete_map(mpack_writer_t* writer) {
+    mpack_builder_complete(writer, mpack_type_map);
+}
+
+void mpack_complete_array(mpack_writer_t* writer) {
+    mpack_builder_complete(writer, mpack_type_array);
+}
+
+#endif // MPACK_BUILDER
+#endif // MPACK_WRITER
+
+}  // namespace mpack
+MPACK_SILENCE_WARNINGS_END
+
+/* mpack/mpack-reader.c.c */
+
+#define MPACK_INTERNAL 1
+
+/* #include "mpack-reader.h" */
+
+MPACK_SILENCE_WARNINGS_BEGIN
+namespace mpack {
+
+#if MPACK_READER
+
+static void mpack_reader_skip_using_fill(mpack_reader_t* reader, size_t count);
+
+void mpack_reader_init(mpack_reader_t* reader, char* buffer, size_t size, size_t count) {
+    mpack_assert(buffer != NULL, "buffer is NULL");
+
+    mpack_memset(reader, 0, sizeof(*reader));
+    reader->buffer = buffer;
+    reader->size = size;
+    reader->data = buffer;
+    reader->end = buffer + count;
+
+    #if MPACK_READ_TRACKING
+    mpack_reader_flag_if_error(reader, mpack_track_init(&reader->track));
+    #endif
+
+    mpack_log("===========================\n");
+    mpack_log("initializing reader with buffer size %i\n", (int)size);
+}
+
+void mpack_reader_init_error(mpack_reader_t* reader, mpack_error_t error) {
+    mpack_memset(reader, 0, sizeof(*reader));
+    reader->error = error;
+
+    mpack_log("===========================\n");
+    mpack_log("initializing reader error state %i\n", (int)error);
+}
+
+void mpack_reader_init_data(mpack_reader_t* reader, const char* data, size_t count) {
+    mpack_assert(data != NULL, "data is NULL");
+
+    mpack_memset(reader, 0, sizeof(*reader));
+    reader->data = data;
+    reader->end = data + count;
+
+    #if MPACK_READ_TRACKING
+    mpack_reader_flag_if_error(reader, mpack_track_init(&reader->track));
+    #endif
+
+    mpack_log("===========================\n");
+    mpack_log("initializing reader with data size %i\n", (int)count);
+}
+
+void mpack_reader_set_fill(mpack_reader_t* reader, mpack_reader_fill_t fill) {
+    MPACK_STATIC_ASSERT(MPACK_READER_MINIMUM_BUFFER_SIZE >= MPACK_MAXIMUM_TAG_SIZE,
+            "minimum buffer size must fit any tag!");
+
+    if (reader->size == 0) {
+        mpack_break("cannot use fill function without a writeable buffer!");
+        mpack_reader_flag_error(reader, mpack_error_bug);
+        return;
+    }
+
+    if (reader->size < MPACK_READER_MINIMUM_BUFFER_SIZE) {
+        mpack_break("buffer size is %i, but minimum buffer size for fill is %i",
+                (int)reader->size, MPACK_READER_MINIMUM_BUFFER_SIZE);
+        mpack_reader_flag_error(reader, mpack_error_bug);
+        return;
+    }
+
+    reader->fill = fill;
+}
+
+void mpack_reader_set_skip(mpack_reader_t* reader, mpack_reader_skip_t skip) {
+    mpack_assert(reader->size != 0, "cannot use skip function without a writeable buffer!");
+    reader->skip = skip;
+}
+
+#if MPACK_STDIO
+static size_t mpack_file_reader_fill(mpack_reader_t* reader, char* buffer, size_t count) {
+    if (feof((FILE *)reader->context)) {
+       mpack_reader_flag_error(reader, mpack_error_eof);
+       return 0;
+    }
+    return fread((void*)buffer, 1, count, (FILE*)reader->context);
+}
+
+static void mpack_file_reader_skip(mpack_reader_t* reader, size_t count) {
+    if (mpack_reader_error(reader) != mpack_ok)
+        return;
+    FILE* file = (FILE*)reader->context;
+
+    // We call ftell() to test whether the stream is seekable
+    // without causing a file error.
+    if (ftell(file) >= 0) {
+        mpack_log("seeking forward %i bytes\n", (int)count);
+        if (fseek(file, (long int)count, SEEK_CUR) == 0)
+            return;
+        mpack_log("fseek() didn't return zero!\n");
+        if (ferror(file)) {
+            mpack_reader_flag_error(reader, mpack_error_io);
+            return;
+        }
+    }
+
+    // If the stream is not seekable, fall back to the fill function.
+    mpack_reader_skip_using_fill(reader, count);
+}
+
+static void mpack_file_reader_teardown(mpack_reader_t* reader) {
+    MPACK_FREE(reader->buffer);
+    reader->buffer = NULL;
+    reader->context = NULL;
+    reader->size = 0;
+    reader->fill = NULL;
+    reader->skip = NULL;
+    reader->teardown = NULL;
+}
+
+static void mpack_file_reader_teardown_close(mpack_reader_t* reader) {
+    FILE* file = (FILE*)reader->context;
+
+    if (file) {
+        int ret = fclose(file);
+        if (ret != 0)
+            mpack_reader_flag_error(reader, mpack_error_io);
+    }
+
+    mpack_file_reader_teardown(reader);
+}
+
+void mpack_reader_init_stdfile(mpack_reader_t* reader, FILE* file, bool close_when_done) {
+    mpack_assert(file != NULL, "file is NULL");
+
+    size_t capacity = MPACK_BUFFER_SIZE;
+    char* buffer = (char*)MPACK_MALLOC(capacity);
+    if (buffer == NULL) {
+        mpack_reader_init_error(reader, mpack_error_memory);
+        if (close_when_done) {
+            fclose(file);
+        }
+        return;
+    }
+
+    mpack_reader_init(reader, buffer, capacity, 0);
+    mpack_reader_set_context(reader, file);
+    mpack_reader_set_fill(reader, mpack_file_reader_fill);
+    mpack_reader_set_skip(reader, mpack_file_reader_skip);
+    mpack_reader_set_teardown(reader, close_when_done ?
+            mpack_file_reader_teardown_close :
+            mpack_file_reader_teardown);
+}
+
+void mpack_reader_init_filename(mpack_reader_t* reader, const char* filename) {
+    mpack_assert(filename != NULL, "filename is NULL");
+
+    FILE* file = fopen(filename, "rb");
+    if (file == NULL) {
+        mpack_reader_init_error(reader, mpack_error_io);
+        return;
+    }
+
+    mpack_reader_init_stdfile(reader, file, true);
+}
+#endif
+
+mpack_error_t mpack_reader_destroy(mpack_reader_t* reader) {
+
+    // clean up tracking, asserting if we're not already in an error state
+    #if MPACK_READ_TRACKING
+    mpack_reader_flag_if_error(reader, mpack_track_destroy(&reader->track, mpack_reader_error(reader) != mpack_ok));
+    #endif
+
+    if (reader->teardown)
+        reader->teardown(reader);
+    reader->teardown = NULL;
+
+    return reader->error;
+}
+
+size_t mpack_reader_remaining(mpack_reader_t* reader, const char** data) {
+    if (mpack_reader_error(reader) != mpack_ok)
+        return 0;
+
+    #if MPACK_READ_TRACKING
+    if (mpack_reader_flag_if_error(reader, mpack_track_check_empty(&reader->track)) != mpack_ok)
+        return 0;
+    #endif
+
+    if (data)
+        *data = reader->data;
+    return (size_t)(reader->end - reader->data);
+}
+
+void mpack_reader_flag_error(mpack_reader_t* reader, mpack_error_t error) {
+    mpack_log("reader %p setting error %i: %s\n", (void*)reader, (int)error, mpack_error_to_string(error));
+
+    if (reader->error == mpack_ok) {
+        reader->error = error;
+        reader->end = reader->data;
+        if (reader->error_fn)
+            reader->error_fn(reader, error);
+    }
+}
+
+// Loops on the fill function, reading between the minimum and
+// maximum number of bytes and flagging an error if it fails.
+MPACK_NOINLINE static size_t mpack_fill_range(mpack_reader_t* reader, char* p, size_t min_bytes, size_t max_bytes) {
+    mpack_assert(reader->fill != NULL, "mpack_fill_range() called with no fill function?");
+    mpack_assert(min_bytes > 0, "cannot fill zero bytes!");
+    mpack_assert(max_bytes >= min_bytes, "min_bytes %i cannot be larger than max_bytes %i!",
+            (int)min_bytes, (int)max_bytes);
+
+    size_t count = 0;
+    while (count < min_bytes) {
+        size_t read = reader->fill(reader, p + count, max_bytes - count);
+
+        // Reader fill functions can flag an error or return 0 on failure. We
+        // also guard against functions that return -1 just in case.
+        if (mpack_reader_error(reader) != mpack_ok)
+            return 0;
+        if (read == 0 || read == ((size_t)(-1))) {
+            mpack_reader_flag_error(reader, mpack_error_io);
+            return 0;
+        }
+
+        count += read;
+    }
+    return count;
+}
+
+MPACK_NOINLINE bool mpack_reader_ensure_straddle(mpack_reader_t* reader, size_t count) {
+    mpack_assert(count != 0, "cannot ensure zero bytes!");
+    mpack_assert(reader->error == mpack_ok, "reader cannot be in an error state!");
+
+    mpack_assert(count > (size_t)(reader->end - reader->data),
+            "straddling ensure requested for %i bytes, but there are %i bytes "
+            "left in buffer. call mpack_reader_ensure() instead",
+            (int)count, (int)(reader->end - reader->data));
+
+    // we'll need a fill function to get more data. if there's no
+    // fill function, the buffer should contain an entire MessagePack
+    // object, so we raise mpack_error_invalid instead of mpack_error_io
+    // on truncated data.
+    if (reader->fill == NULL) {
+        mpack_reader_flag_error(reader, mpack_error_invalid);
+        return false;
+    }
+
+    // we need enough space in the buffer. if the buffer is not
+    // big enough, we return mpack_error_too_big (since this is
+    // for an in-place read larger than the buffer size.)
+    if (count > reader->size) {
+        mpack_reader_flag_error(reader, mpack_error_too_big);
+        return false;
+    }
+
+    // move the existing data to the start of the buffer
+    size_t left = (size_t)(reader->end - reader->data);
+    mpack_memmove(reader->buffer, reader->data, left);
+    reader->end -= reader->data - reader->buffer;
+    reader->data = reader->buffer;
+
+    // read at least the necessary number of bytes, accepting up to the
+    // buffer size
+    size_t read = mpack_fill_range(reader, reader->buffer + left,
+            count - left, reader->size - left);
+    if (mpack_reader_error(reader) != mpack_ok)
+        return false;
+    reader->end += read;
+    return true;
+}
+
+// Reads count bytes into p. Used when there are not enough bytes
+// left in the buffer to satisfy a read.
+MPACK_NOINLINE void mpack_read_native_straddle(mpack_reader_t* reader, char* p, size_t count) {
+    mpack_assert(count == 0 || p != NULL, "data pointer for %i bytes is NULL", (int)count);
+
+    if (mpack_reader_error(reader) != mpack_ok) {
+        mpack_memset(p, 0, count);
+        return;
+    }
+
+    size_t left = (size_t)(reader->end - reader->data);
+    mpack_log("big read for %i bytes into %p, %i left in buffer, buffer size %i\n",
+            (int)count, p, (int)left, (int)reader->size);
+
+    if (count <= left) {
+        mpack_assert(0,
+                "big read requested for %i bytes, but there are %i bytes "
+                "left in buffer. call mpack_read_native() instead",
+                (int)count, (int)left);
+        mpack_reader_flag_error(reader, mpack_error_bug);
+        mpack_memset(p, 0, count);
+        return;
+    }
+
+    // we'll need a fill function to get more data. if there's no
+    // fill function, the buffer should contain an entire MessagePack
+    // object, so we raise mpack_error_invalid instead of mpack_error_io
+    // on truncated data.
+    if (reader->fill == NULL) {
+        mpack_reader_flag_error(reader, mpack_error_invalid);
+        mpack_memset(p, 0, count);
+        return;
+    }
+
+    if (reader->size == 0) {
+        // somewhat debatable what error should be returned here. when
+        // initializing a reader with an in-memory buffer it's not
+        // necessarily a bug if the data is blank; it might just have
+        // been truncated to zero. for this reason we return the same
+        // error as if the data was truncated.
+        mpack_reader_flag_error(reader, mpack_error_io);
+        mpack_memset(p, 0, count);
+        return;
+    }
+
+    // flush what's left of the buffer
+    if (left > 0) {
+        mpack_log("flushing %i bytes remaining in buffer\n", (int)left);
+        mpack_memcpy(p, reader->data, left);
+        count -= left;
+        p += left;
+        reader->data += left;
+    }
+
+    // if the remaining data needed is some small fraction of the
+    // buffer size, we'll try to fill the buffer as much as possible
+    // and copy the needed data out.
+    if (count <= reader->size / MPACK_READER_SMALL_FRACTION_DENOMINATOR) {
+        size_t read = mpack_fill_range(reader, reader->buffer, count, reader->size);
+        if (mpack_reader_error(reader) != mpack_ok)
+            return;
+        mpack_memcpy(p, reader->buffer, count);
+        reader->data = reader->buffer + count;
+        reader->end = reader->buffer + read;
+
+    // otherwise we read the remaining data directly into the target.
+    } else {
+        mpack_log("reading %i additional bytes\n", (int)count);
+        mpack_fill_range(reader, p, count, count);
+    }
+}
+
+MPACK_NOINLINE static void mpack_skip_bytes_straddle(mpack_reader_t* reader, size_t count) {
+
+    // we'll need at least a fill function to skip more data. if there's
+    // no fill function, the buffer should contain an entire MessagePack
+    // object, so we raise mpack_error_invalid instead of mpack_error_io
+    // on truncated data. (see mpack_read_native_straddle())
+    if (reader->fill == NULL) {
+        mpack_log("reader has no fill function!\n");
+        mpack_reader_flag_error(reader, mpack_error_invalid);
+        return;
+    }
+
+    // discard whatever's left in the buffer
+    size_t left = (size_t)(reader->end - reader->data);
+    mpack_log("discarding %i bytes still in buffer\n", (int)left);
+    count -= left;
+    reader->data = reader->end;
+
+    // use the skip function if we've got one, and if we're trying
+    // to skip a lot of data. if we only need to skip some tiny
+    // fraction of the buffer size, it's probably better to just
+    // fill the buffer and skip from it instead of trying to seek.
+    if (reader->skip && count > reader->size / 16) {
+        mpack_log("calling skip function for %i bytes\n", (int)count);
+        reader->skip(reader, count);
+        return;
+    }
+
+    mpack_reader_skip_using_fill(reader, count);
+}
+
+void mpack_skip_bytes(mpack_reader_t* reader, size_t count) {
+    if (mpack_reader_error(reader) != mpack_ok)
+        return;
+    mpack_log("skip requested for %i bytes\n", (int)count);
+
+    mpack_reader_track_bytes(reader, count);
+
+    // check if we have enough in the buffer already
+    size_t left = (size_t)(reader->end - reader->data);
+    if (left >= count) {
+        mpack_log("skipping %u bytes still in buffer\n", (uint32_t)count);
+        reader->data += count;
+        return;
+    }
+
+    mpack_skip_bytes_straddle(reader, count);
+}
+
+MPACK_NOINLINE static void mpack_reader_skip_using_fill(mpack_reader_t* reader, size_t count) {
+    mpack_assert(reader->fill != NULL, "missing fill function!");
+    mpack_assert(reader->data == reader->end, "there are bytes left in the buffer!");
+    mpack_assert(reader->error == mpack_ok, "should not have called this in an error state (%i)", reader->error);
+    mpack_log("skip using fill for %i bytes\n", (int)count);
+
+    // fill and discard multiples of the buffer size
+    while (count > reader->size) {
+        mpack_log("filling and discarding buffer of %i bytes\n", (int)reader->size);
+        if (mpack_fill_range(reader, reader->buffer, reader->size, reader->size) < reader->size) {
+            mpack_reader_flag_error(reader, mpack_error_io);
+            return;
+        }
+        count -= reader->size;
+    }
+
+    // fill the buffer as much as possible
+    reader->data = reader->buffer;
+    size_t read = mpack_fill_range(reader, reader->buffer, count, reader->size);
+    if (read < count) {
+        mpack_reader_flag_error(reader, mpack_error_io);
+        return;
+    }
+    reader->end = reader->data + read;
+    mpack_log("filled %i bytes into buffer; discarding %i bytes\n", (int)read, (int)count);
+    reader->data += count;
+}
+
+void mpack_read_bytes(mpack_reader_t* reader, char* p, size_t count) {
+    mpack_assert(p != NULL, "destination for read of %i bytes is NULL", (int)count);
+    mpack_reader_track_bytes(reader, count);
+    mpack_read_native(reader, p, count);
+}
+
+void mpack_read_utf8(mpack_reader_t* reader, char* p, size_t byte_count) {
+    mpack_assert(p != NULL, "destination for read of %i bytes is NULL", (int)byte_count);
+    mpack_reader_track_str_bytes_all(reader, byte_count);
+    mpack_read_native(reader, p, byte_count);
+
+    if (mpack_reader_error(reader) == mpack_ok && !mpack_utf8_check(p, byte_count))
+        mpack_reader_flag_error(reader, mpack_error_type);
+}
+
+static void mpack_read_cstr_unchecked(mpack_reader_t* reader, char* buf, size_t buffer_size, size_t byte_count) {
+    mpack_assert(buf != NULL, "destination for read of %i bytes is NULL", (int)byte_count);
+    mpack_assert(buffer_size >= 1, "buffer size is zero; you must have room for at least a null-terminator");
+
+    if (mpack_reader_error(reader)) {
+        buf[0] = 0;
+        return;
+    }
+
+    if (byte_count > buffer_size - 1) {
+        mpack_reader_flag_error(reader, mpack_error_too_big);
+        buf[0] = 0;
+        return;
+    }
+
+    mpack_reader_track_str_bytes_all(reader, byte_count);
+    mpack_read_native(reader, buf, byte_count);
+    buf[byte_count] = 0;
+}
+
+void mpack_read_cstr(mpack_reader_t* reader, char* buf, size_t buffer_size, size_t byte_count) {
+    mpack_read_cstr_unchecked(reader, buf, buffer_size, byte_count);
+
+    // check for null bytes
+    if (mpack_reader_error(reader) == mpack_ok && !mpack_str_check_no_null(buf, byte_count)) {
+        buf[0] = 0;
+        mpack_reader_flag_error(reader, mpack_error_type);
+    }
+}
+
+void mpack_read_utf8_cstr(mpack_reader_t* reader, char* buf, size_t buffer_size, size_t byte_count) {
+    mpack_read_cstr_unchecked(reader, buf, buffer_size, byte_count);
+
+    // check encoding
+    if (mpack_reader_error(reader) == mpack_ok && !mpack_utf8_check_no_null(buf, byte_count)) {
+        buf[0] = 0;
+        mpack_reader_flag_error(reader, mpack_error_type);
+    }
+}
+
+#ifdef MPACK_MALLOC
+// Reads native bytes with error callback disabled. This allows MPack reader functions
+// to hold an allocated buffer and read native data into it without leaking it in
+// case of a non-local jump (longjmp, throw) out of an error handler.
+static void mpack_read_native_noerrorfn(mpack_reader_t* reader, char* p, size_t count) {
+    mpack_assert(reader->error == mpack_ok, "cannot call if an error is already flagged!");
+    mpack_reader_error_t error_fn = reader->error_fn;
+    reader->error_fn = NULL;
+    mpack_read_native(reader, p, count);
+    reader->error_fn = error_fn;
+}
+
+char* mpack_read_bytes_alloc_impl(mpack_reader_t* reader, size_t count, bool null_terminated) {
+
+    // track the bytes first in case it jumps
+    mpack_reader_track_bytes(reader, count);
+    if (mpack_reader_error(reader) != mpack_ok)
+        return NULL;
+
+    // cannot allocate zero bytes. this is not an error.
+    if (count == 0 && null_terminated == false)
+        return NULL;
+
+    // allocate data
+    char* data = (char*)MPACK_MALLOC(count + (null_terminated ? 1 : 0)); // TODO: can this overflow?
+    if (data == NULL) {
+        mpack_reader_flag_error(reader, mpack_error_memory);
+        return NULL;
+    }
+
+    // read with error callback disabled so we don't leak our buffer
+    mpack_read_native_noerrorfn(reader, data, count);
+
+    // report flagged errors
+    if (mpack_reader_error(reader) != mpack_ok) {
+        MPACK_FREE(data);
+        if (reader->error_fn)
+            reader->error_fn(reader, mpack_reader_error(reader));
+        return NULL;
+    }
+
+    if (null_terminated)
+        data[count] = '\0';
+    return data;
+}
+#endif
+
+// read inplace without tracking (since there are different
+// tracking modes for different inplace readers)
+static const char* mpack_read_bytes_inplace_notrack(mpack_reader_t* reader, size_t count) {
+    if (mpack_reader_error(reader) != mpack_ok)
+        return NULL;
+
+    // if we have enough bytes already in the buffer, we can return it directly.
+    if ((size_t)(reader->end - reader->data) >= count) {
+        const char* bytes = reader->data;
+        reader->data += count;
+        return bytes;
+    }
+
+    if (!mpack_reader_ensure(reader, count))
+        return NULL;
+
+    const char* bytes = reader->data;
+    reader->data += count;
+    return bytes;
+}
+
+const char* mpack_read_bytes_inplace(mpack_reader_t* reader, size_t count) {
+    mpack_reader_track_bytes(reader, count);
+    return mpack_read_bytes_inplace_notrack(reader, count);
+}
+
+const char* mpack_read_utf8_inplace(mpack_reader_t* reader, size_t count) {
+    mpack_reader_track_str_bytes_all(reader, count);
+    const char* str = mpack_read_bytes_inplace_notrack(reader, count);
+
+    if (mpack_reader_error(reader) == mpack_ok && !mpack_utf8_check(str, count)) {
+        mpack_reader_flag_error(reader, mpack_error_type);
+        return NULL;
+    }
+
+    return str;
+}
+
+static size_t mpack_parse_tag(mpack_reader_t* reader, mpack_tag_t* tag) {
+    mpack_assert(reader->error == mpack_ok, "reader cannot be in an error state!");
+
+    if (!mpack_reader_ensure(reader, 1))
+        return 0;
+    uint8_t type = mpack_load_u8(reader->data);
+
+    // unfortunately, by far the fastest way to parse a tag is to switch
+    // on the first byte, and to explicitly list every possible byte. so for
+    // infix types, the list of cases is quite large.
+    //
+    // in size-optimized builds, we switch on the top four bits first to
+    // handle most infix types with a smaller jump table to save space.
+
+    #if MPACK_OPTIMIZE_FOR_SIZE
+    switch (type >> 4) {
+
+        // positive fixnum
+        case 0x0: case 0x1: case 0x2: case 0x3:
+        case 0x4: case 0x5: case 0x6: case 0x7:
+            *tag = mpack_tag_make_uint(type);
+            return 1;
+
+        // negative fixnum
+        case 0xe: case 0xf:
+            *tag = mpack_tag_make_int((int8_t)type);
+            return 1;
+
+        // fixmap
+        case 0x8:
+            *tag = mpack_tag_make_map(type & ~0xf0u);
+            return 1;
+
+        // fixarray
+        case 0x9:
+            *tag = mpack_tag_make_array(type & ~0xf0u);
+            return 1;
+
+        // fixstr
+        case 0xa: case 0xb:
+            *tag = mpack_tag_make_str(type & ~0xe0u);
+            return 1;
+
+        // not one of the common infix types
+        default:
+            break;
+
+    }
+    #endif
+
+    // handle individual type tags
+    switch (type) {
+
+        #if !MPACK_OPTIMIZE_FOR_SIZE
+        // positive fixnum
+        case 0x00: case 0x01: case 0x02: case 0x03: case 0x04: case 0x05: case 0x06: case 0x07:
+        case 0x08: case 0x09: case 0x0a: case 0x0b: case 0x0c: case 0x0d: case 0x0e: case 0x0f:
+        case 0x10: case 0x11: case 0x12: case 0x13: case 0x14: case 0x15: case 0x16: case 0x17:
+        case 0x18: case 0x19: case 0x1a: case 0x1b: case 0x1c: case 0x1d: case 0x1e: case 0x1f:
+        case 0x20: case 0x21: case 0x22: case 0x23: case 0x24: case 0x25: case 0x26: case 0x27:
+        case 0x28: case 0x29: case 0x2a: case 0x2b: case 0x2c: case 0x2d: case 0x2e: case 0x2f:
+        case 0x30: case 0x31: case 0x32: case 0x33: case 0x34: case 0x35: case 0x36: case 0x37:
+        case 0x38: case 0x39: case 0x3a: case 0x3b: case 0x3c: case 0x3d: case 0x3e: case 0x3f:
+        case 0x40: case 0x41: case 0x42: case 0x43: case 0x44: case 0x45: case 0x46: case 0x47:
+        case 0x48: case 0x49: case 0x4a: case 0x4b: case 0x4c: case 0x4d: case 0x4e: case 0x4f:
+        case 0x50: case 0x51: case 0x52: case 0x53: case 0x54: case 0x55: case 0x56: case 0x57:
+        case 0x58: case 0x59: case 0x5a: case 0x5b: case 0x5c: case 0x5d: case 0x5e: case 0x5f:
+        case 0x60: case 0x61: case 0x62: case 0x63: case 0x64: case 0x65: case 0x66: case 0x67:
+        case 0x68: case 0x69: case 0x6a: case 0x6b: case 0x6c: case 0x6d: case 0x6e: case 0x6f:
+        case 0x70: case 0x71: case 0x72: case 0x73: case 0x74: case 0x75: case 0x76: case 0x77:
+        case 0x78: case 0x79: case 0x7a: case 0x7b: case 0x7c: case 0x7d: case 0x7e: case 0x7f:
+            *tag = mpack_tag_make_uint(type);
+            return 1;
+
+        // negative fixnum
+        case 0xe0: case 0xe1: case 0xe2: case 0xe3: case 0xe4: case 0xe5: case 0xe6: case 0xe7:
+        case 0xe8: case 0xe9: case 0xea: case 0xeb: case 0xec: case 0xed: case 0xee: case 0xef:
+        case 0xf0: case 0xf1: case 0xf2: case 0xf3: case 0xf4: case 0xf5: case 0xf6: case 0xf7:
+        case 0xf8: case 0xf9: case 0xfa: case 0xfb: case 0xfc: case 0xfd: case 0xfe: case 0xff:
+            *tag = mpack_tag_make_int((int8_t)type);
+            return 1;
+
+        // fixmap
+        case 0x80: case 0x81: case 0x82: case 0x83: case 0x84: case 0x85: case 0x86: case 0x87:
+        case 0x88: case 0x89: case 0x8a: case 0x8b: case 0x8c: case 0x8d: case 0x8e: case 0x8f:
+            *tag = mpack_tag_make_map(type & ~0xf0u);
+            return 1;
+
+        // fixarray
+        case 0x90: case 0x91: case 0x92: case 0x93: case 0x94: case 0x95: case 0x96: case 0x97:
+        case 0x98: case 0x99: case 0x9a: case 0x9b: case 0x9c: case 0x9d: case 0x9e: case 0x9f:
+            *tag = mpack_tag_make_array(type & ~0xf0u);
+            return 1;
+
+        // fixstr
+        case 0xa0: case 0xa1: case 0xa2: case 0xa3: case 0xa4: case 0xa5: case 0xa6: case 0xa7:
+        case 0xa8: case 0xa9: case 0xaa: case 0xab: case 0xac: case 0xad: case 0xae: case 0xaf:
+        case 0xb0: case 0xb1: case 0xb2: case 0xb3: case 0xb4: case 0xb5: case 0xb6: case 0xb7:
+        case 0xb8: case 0xb9: case 0xba: case 0xbb: case 0xbc: case 0xbd: case 0xbe: case 0xbf:
+            *tag = mpack_tag_make_str(type & ~0xe0u);
+            return 1;
+        #endif
+
+        // nil
+        case 0xc0:
+            *tag = mpack_tag_make_nil();
+            return 1;
+
+        // bool
+        case 0xc2: case 0xc3:
+            *tag = mpack_tag_make_bool((bool)(type & 1));
+            return 1;
+
+        // bin8
+        case 0xc4:
+            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_BIN8))
+                return 0;
+            *tag = mpack_tag_make_bin(mpack_load_u8(reader->data + 1));
+            return MPACK_TAG_SIZE_BIN8;
+
+        // bin16
+        case 0xc5:
+            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_BIN16))
+                return 0;
+            *tag = mpack_tag_make_bin(mpack_load_u16(reader->data + 1));
+            return MPACK_TAG_SIZE_BIN16;
+
+        // bin32
+        case 0xc6:
+            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_BIN32))
+                return 0;
+            *tag = mpack_tag_make_bin(mpack_load_u32(reader->data + 1));
+            return MPACK_TAG_SIZE_BIN32;
+
+        #if MPACK_EXTENSIONS
+        // ext8
+        case 0xc7:
+            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_EXT8))
+                return 0;
+            *tag = mpack_tag_make_ext(mpack_load_i8(reader->data + 2), mpack_load_u8(reader->data + 1));
+            return MPACK_TAG_SIZE_EXT8;
+
+        // ext16
+        case 0xc8:
+            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_EXT16))
+                return 0;
+            *tag = mpack_tag_make_ext(mpack_load_i8(reader->data + 3), mpack_load_u16(reader->data + 1));
+            return MPACK_TAG_SIZE_EXT16;
+
+        // ext32
+        case 0xc9:
+            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_EXT32))
+                return 0;
+            *tag = mpack_tag_make_ext(mpack_load_i8(reader->data + 5), mpack_load_u32(reader->data + 1));
+            return MPACK_TAG_SIZE_EXT32;
+        #endif
+
+        // float
+        case 0xca:
+            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_FLOAT))
+                return 0;
+            #if MPACK_FLOAT
+            *tag = mpack_tag_make_float(mpack_load_float(reader->data + 1));
+            #else
+            *tag = mpack_tag_make_raw_float(mpack_load_u32(reader->data + 1));
+            #endif
+            return MPACK_TAG_SIZE_FLOAT;
+
+        // double
+        case 0xcb:
+            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_DOUBLE))
+                return 0;
+            #if MPACK_DOUBLE
+            *tag = mpack_tag_make_double(mpack_load_double(reader->data + 1));
+            #else
+            *tag = mpack_tag_make_raw_double(mpack_load_u64(reader->data + 1));
+            #endif
+            return MPACK_TAG_SIZE_DOUBLE;
+
+        // uint8
+        case 0xcc:
+            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_U8))
+                return 0;
+            *tag = mpack_tag_make_uint(mpack_load_u8(reader->data + 1));
+            return MPACK_TAG_SIZE_U8;
+
+        // uint16
+        case 0xcd:
+            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_U16))
+                return 0;
+            *tag = mpack_tag_make_uint(mpack_load_u16(reader->data + 1));
+            return MPACK_TAG_SIZE_U16;
+
+        // uint32
+        case 0xce:
+            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_U32))
+                return 0;
+            *tag = mpack_tag_make_uint(mpack_load_u32(reader->data + 1));
+            return MPACK_TAG_SIZE_U32;
+
+        // uint64
+        case 0xcf:
+            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_U64))
+                return 0;
+            *tag = mpack_tag_make_uint(mpack_load_u64(reader->data + 1));
+            return MPACK_TAG_SIZE_U64;
+
+        // int8
+        case 0xd0:
+            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_I8))
+                return 0;
+            *tag = mpack_tag_make_int(mpack_load_i8(reader->data + 1));
+            return MPACK_TAG_SIZE_I8;
+
+        // int16
+        case 0xd1:
+            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_I16))
+                return 0;
+            *tag = mpack_tag_make_int(mpack_load_i16(reader->data + 1));
+            return MPACK_TAG_SIZE_I16;
+
+        // int32
+        case 0xd2:
+            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_I32))
+                return 0;
+            *tag = mpack_tag_make_int(mpack_load_i32(reader->data + 1));
+            return MPACK_TAG_SIZE_I32;
+
+        // int64
+        case 0xd3:
+            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_I64))
+                return 0;
+            *tag = mpack_tag_make_int(mpack_load_i64(reader->data + 1));
+            return MPACK_TAG_SIZE_I64;
+
+        #if MPACK_EXTENSIONS
+        // fixext1
+        case 0xd4:
+            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_FIXEXT1))
+                return 0;
+            *tag = mpack_tag_make_ext(mpack_load_i8(reader->data + 1), 1);
+            return MPACK_TAG_SIZE_FIXEXT1;
+
+        // fixext2
+        case 0xd5:
+            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_FIXEXT2))
+                return 0;
+            *tag = mpack_tag_make_ext(mpack_load_i8(reader->data + 1), 2);
+            return MPACK_TAG_SIZE_FIXEXT2;
+
+        // fixext4
+        case 0xd6:
+            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_FIXEXT4))
+                return 0;
+            *tag = mpack_tag_make_ext(mpack_load_i8(reader->data + 1), 4);
+            return 2;
+
+        // fixext8
+        case 0xd7:
+            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_FIXEXT8))
+                return 0;
+            *tag = mpack_tag_make_ext(mpack_load_i8(reader->data + 1), 8);
+            return MPACK_TAG_SIZE_FIXEXT8;
+
+        // fixext16
+        case 0xd8:
+            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_FIXEXT16))
+                return 0;
+            *tag = mpack_tag_make_ext(mpack_load_i8(reader->data + 1), 16);
+            return MPACK_TAG_SIZE_FIXEXT16;
+        #endif
+
+        // str8
+        case 0xd9:
+            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_STR8))
+                return 0;
+            *tag = mpack_tag_make_str(mpack_load_u8(reader->data + 1));
+            return MPACK_TAG_SIZE_STR8;
+
+        // str16
+        case 0xda:
+            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_STR16))
+                return 0;
+            *tag = mpack_tag_make_str(mpack_load_u16(reader->data + 1));
+            return MPACK_TAG_SIZE_STR16;
+
+        // str32
+        case 0xdb:
+            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_STR32))
+                return 0;
+            *tag = mpack_tag_make_str(mpack_load_u32(reader->data + 1));
+            return MPACK_TAG_SIZE_STR32;
+
+        // array16
+        case 0xdc:
+            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_ARRAY16))
+                return 0;
+            *tag = mpack_tag_make_array(mpack_load_u16(reader->data + 1));
+            return MPACK_TAG_SIZE_ARRAY16;
+
+        // array32
+        case 0xdd:
+            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_ARRAY32))
+                return 0;
+            *tag = mpack_tag_make_array(mpack_load_u32(reader->data + 1));
+            return MPACK_TAG_SIZE_ARRAY32;
+
+        // map16
+        case 0xde:
+            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_MAP16))
+                return 0;
+            *tag = mpack_tag_make_map(mpack_load_u16(reader->data + 1));
+            return MPACK_TAG_SIZE_MAP16;
+
+        // map32
+        case 0xdf:
+            if (!mpack_reader_ensure(reader, MPACK_TAG_SIZE_MAP32))
+                return 0;
+            *tag = mpack_tag_make_map(mpack_load_u32(reader->data + 1));
+            return MPACK_TAG_SIZE_MAP32;
+
+        // reserved
+        case 0xc1:
+            mpack_reader_flag_error(reader, mpack_error_invalid);
+            return 0;
+
+        #if !MPACK_EXTENSIONS
+        // ext
+        case 0xc7: // fallthrough
+        case 0xc8: // fallthrough
+        case 0xc9: // fallthrough
+        // fixext
+        case 0xd4: // fallthrough
+        case 0xd5: // fallthrough
+        case 0xd6: // fallthrough
+        case 0xd7: // fallthrough
+        case 0xd8:
+            mpack_reader_flag_error(reader, mpack_error_unsupported);
+            return 0;
+        #endif
+
+        #if MPACK_OPTIMIZE_FOR_SIZE
+        // any other bytes should have been handled by the infix switch
+        default:
+            break;
+        #endif
+    }
+
+    mpack_assert(0, "unreachable");
+    return 0;
+}
+
+mpack_tag_t mpack_read_tag(mpack_reader_t* reader) {
+    mpack_log("reading tag\n");
+
+    // make sure we can read a tag
+    if (mpack_reader_error(reader) != mpack_ok)
+        return mpack_tag_nil();
+    if (mpack_reader_track_element(reader) != mpack_ok)
+        return mpack_tag_nil();
+
+    mpack_tag_t tag = MPACK_TAG_ZERO;
+    size_t count = mpack_parse_tag(reader, &tag);
+    if (count == 0)
+        return mpack_tag_nil();
+
+    #if MPACK_READ_TRACKING
+    mpack_error_t track_error = mpack_ok;
+
+    switch (tag.type) {
+        case mpack_type_map:
+        case mpack_type_array:
+            track_error = mpack_track_push(&reader->track, tag.type, tag.v.n);
+            break;
+        #if MPACK_EXTENSIONS
+        case mpack_type_ext:
+        #endif
+        case mpack_type_str:
+        case mpack_type_bin:
+            track_error = mpack_track_push(&reader->track, tag.type, tag.v.l);
+            break;
+        default:
+            break;
+    }
+
+    if (track_error != mpack_ok) {
+        mpack_reader_flag_error(reader, track_error);
+        return mpack_tag_nil();
+    }
+    #endif
+
+    reader->data += count;
+    return tag;
+}
+
+mpack_tag_t mpack_peek_tag(mpack_reader_t* reader) {
+    mpack_log("peeking tag\n");
+
+    // make sure we can peek a tag
+    if (mpack_reader_error(reader) != mpack_ok)
+        return mpack_tag_nil();
+    if (mpack_reader_track_peek_element(reader) != mpack_ok)
+        return mpack_tag_nil();
+
+    mpack_tag_t tag = MPACK_TAG_ZERO;
+    if (mpack_parse_tag(reader, &tag) == 0)
+        return mpack_tag_nil();
+    return tag;
+}
+
+void mpack_discard(mpack_reader_t* reader) {
+    mpack_tag_t var = mpack_read_tag(reader);
+    if (mpack_reader_error(reader))
+        return;
+    switch (var.type) {
+        case mpack_type_str:
+            mpack_skip_bytes(reader, var.v.l);
+            mpack_done_str(reader);
+            break;
+        case mpack_type_bin:
+            mpack_skip_bytes(reader, var.v.l);
+            mpack_done_bin(reader);
+            break;
+        #if MPACK_EXTENSIONS
+        case mpack_type_ext:
+            mpack_skip_bytes(reader, var.v.l);
+            mpack_done_ext(reader);
+            break;
+        #endif
+        case mpack_type_array: {
+            for (; var.v.n > 0; --var.v.n) {
+                mpack_discard(reader);
+                if (mpack_reader_error(reader))
+                    break;
+            }
+            mpack_done_array(reader);
+            break;
+        }
+        case mpack_type_map: {
+            for (; var.v.n > 0; --var.v.n) {
+                mpack_discard(reader);
+                mpack_discard(reader);
+                if (mpack_reader_error(reader))
+                    break;
+            }
+            mpack_done_map(reader);
+            break;
+        }
+        default:
+            break;
+    }
+}
+
+#if MPACK_EXTENSIONS
+mpack_timestamp_t mpack_read_timestamp(mpack_reader_t* reader, size_t size) {
+    mpack_timestamp_t timestamp = {0, 0};
+
+    if (size != 4 && size != 8 && size != 12) {
+        mpack_reader_flag_error(reader, mpack_error_invalid);
+        return timestamp;
+    }
+
+    char buf[12];
+    mpack_read_bytes(reader, buf, size);
+    mpack_done_ext(reader);
+    if (mpack_reader_error(reader) != mpack_ok)
+        return timestamp;
+
+    switch (size) {
+        case 4:
+            timestamp.seconds = (int64_t)(uint64_t)mpack_load_u32(buf);
+            break;
+
+        case 8: {
+            uint64_t packed = mpack_load_u64(buf);
+            timestamp.seconds = (int64_t)(packed & ((MPACK_UINT64_C(1) << 34) - 1));
+            timestamp.nanoseconds = (uint32_t)(packed >> 34);
+            break;
+        }
+
+        case 12:
+            timestamp.nanoseconds = mpack_load_u32(buf);
+            timestamp.seconds = mpack_load_i64(buf + 4);
+            break;
+
+        default:
+            mpack_assert(false, "unreachable");
+            break;
+    }
+
+    if (timestamp.nanoseconds > MPACK_TIMESTAMP_NANOSECONDS_MAX) {
+        mpack_reader_flag_error(reader, mpack_error_invalid);
+        mpack_timestamp_t zero = {0, 0};
+        return zero;
+    }
+
+    return timestamp;
+}
+#endif
+
+#if MPACK_READ_TRACKING
+void mpack_done_type(mpack_reader_t* reader, mpack_type_t type) {
+    if (mpack_reader_error(reader) == mpack_ok)
+        mpack_reader_flag_if_error(reader, mpack_track_pop(&reader->track, type));
+}
+#endif
+
+#if MPACK_DEBUG && MPACK_STDIO
+static size_t mpack_print_read_prefix(mpack_reader_t* reader, size_t length, char* buffer, size_t buffer_size) {
+    if (length == 0)
+        return 0;
+
+    size_t read = (length < buffer_size) ? length : buffer_size;
+    mpack_read_bytes(reader, buffer, read);
+    if (mpack_reader_error(reader) != mpack_ok)
+        return 0;
+
+    mpack_skip_bytes(reader, length - read);
+    return read;
+}
+
+static void mpack_print_element(mpack_reader_t* reader, mpack_print_t* print, size_t depth) {
+    mpack_tag_t val = mpack_read_tag(reader);
+    if (mpack_reader_error(reader) != mpack_ok)
+        return;
+
+    // We read some bytes from bin and ext so we can print its prefix in hex.
+    char buffer[MPACK_PRINT_BYTE_COUNT];
+    size_t count = 0;
+    size_t i, j;
+
+    switch (val.type) {
+        case mpack_type_str:
+            mpack_print_append_cstr(print, "\"");
+            for (i = 0; i < val.v.l; ++i) {
+                char c;
+                mpack_read_bytes(reader, &c, 1);
+                if (mpack_reader_error(reader) != mpack_ok)
+                    return;
+                switch (c) {
+                    case '\n': mpack_print_append_cstr(print, "\\n"); break;
+                    case '\\': mpack_print_append_cstr(print, "\\\\"); break;
+                    case '"': mpack_print_append_cstr(print, "\\\""); break;
+                    default: mpack_print_append(print, &c, 1); break;
+                }
+            }
+            mpack_print_append_cstr(print, "\"");
+            mpack_done_str(reader);
+            return;
+
+        case mpack_type_array:
+            mpack_print_append_cstr(print, "[\n");
+            for (i = 0; i < val.v.n; ++i) {
+                for (j = 0; j < depth + 1; ++j)
+                    mpack_print_append_cstr(print, "    ");
+                mpack_print_element(reader, print, depth + 1);
+                if (mpack_reader_error(reader) != mpack_ok)
+                    return;
+                if (i != val.v.n - 1)
+                    mpack_print_append_cstr(print, ",");
+                mpack_print_append_cstr(print, "\n");
+            }
+            for (i = 0; i < depth; ++i)
+                mpack_print_append_cstr(print, "    ");
+            mpack_print_append_cstr(print, "]");
+            mpack_done_array(reader);
+            return;
+
+        case mpack_type_map:
+            mpack_print_append_cstr(print, "{\n");
+            for (i = 0; i < val.v.n; ++i) {
+                for (j = 0; j < depth + 1; ++j)
+                    mpack_print_append_cstr(print, "    ");
+                mpack_print_element(reader, print, depth + 1);
+                if (mpack_reader_error(reader) != mpack_ok)
+                    return;
+                mpack_print_append_cstr(print, ": ");
+                mpack_print_element(reader, print, depth + 1);
+                if (mpack_reader_error(reader) != mpack_ok)
+                    return;
+                if (i != val.v.n - 1)
+                    mpack_print_append_cstr(print, ",");
+                mpack_print_append_cstr(print, "\n");
+            }
+            for (i = 0; i < depth; ++i)
+                mpack_print_append_cstr(print, "    ");
+            mpack_print_append_cstr(print, "}");
+            mpack_done_map(reader);
+            return;
+
+        // The above cases return so as not to print a pseudo-json value. The
+        // below cases break and print pseudo-json.
+
+        case mpack_type_bin:
+            count = mpack_print_read_prefix(reader, mpack_tag_bin_length(&val), buffer, sizeof(buffer));
+            mpack_done_bin(reader);
+            break;
+
+        #if MPACK_EXTENSIONS
+        case mpack_type_ext:
+            count = mpack_print_read_prefix(reader, mpack_tag_ext_length(&val), buffer, sizeof(buffer));
+            mpack_done_ext(reader);
+            break;
+        #endif
+
+        default:
+            break;
+    }
+
+    char buf[256];
+    mpack_tag_debug_pseudo_json(val, buf, sizeof(buf), buffer, count);
+    mpack_print_append_cstr(print, buf);
+}
+
+static void mpack_print_and_destroy(mpack_reader_t* reader, mpack_print_t* print, size_t depth) {
+    size_t i;
+    for (i = 0; i < depth; ++i)
+        mpack_print_append_cstr(print, "    ");
+    mpack_print_element(reader, print, depth);
+
+    size_t remaining = mpack_reader_remaining(reader, NULL);
+
+    char buf[256];
+    if (mpack_reader_destroy(reader) != mpack_ok) {
+        mpack_snprintf(buf, sizeof(buf), "\n<mpack parsing error %s>", mpack_error_to_string(mpack_reader_error(reader)));
+        buf[sizeof(buf) - 1] = '\0';
+        mpack_print_append_cstr(print, buf);
+    } else if (remaining > 0) {
+        mpack_snprintf(buf, sizeof(buf), "\n<%i extra bytes at end of message>", (int)remaining);
+        buf[sizeof(buf) - 1] = '\0';
+        mpack_print_append_cstr(print, buf);
+    }
+}
+
+static void mpack_print_data(const char* data, size_t len, mpack_print_t* print, size_t depth) {
+    mpack_reader_t reader;
+    mpack_reader_init_data(&reader, data, len);
+    mpack_print_and_destroy(&reader, print, depth);
+}
+
+void mpack_print_data_to_buffer(const char* data, size_t data_size, char* buffer, size_t buffer_size) {
+    if (buffer_size == 0) {
+        mpack_assert(false, "buffer size is zero!");
+        return;
+    }
+
+    mpack_print_t print;
+    mpack_memset(&print, 0, sizeof(print));
+    print.buffer = buffer;
+    print.size = buffer_size;
+    mpack_print_data(data, data_size, &print, 0);
+    mpack_print_append(&print, "",  1); // null-terminator
+    mpack_print_flush(&print);
+
+    // we always make sure there's a null-terminator at the end of the buffer
+    // in case we ran out of space.
+    print.buffer[print.size - 1] = '\0';
+}
+
+void mpack_print_data_to_callback(const char* data, size_t size, mpack_print_callback_t callback, void* context) {
+    char buffer[1024];
+    mpack_print_t print;
+    mpack_memset(&print, 0, sizeof(print));
+    print.buffer = buffer;
+    print.size = sizeof(buffer);
+    print.callback = callback;
+    print.context = context;
+    mpack_print_data(data, size, &print, 0);
+    mpack_print_flush(&print);
+}
+
+void mpack_print_data_to_file(const char* data, size_t len, FILE* file) {
+    mpack_assert(data != NULL, "data is NULL");
+    mpack_assert(file != NULL, "file is NULL");
+
+    char buffer[1024];
+    mpack_print_t print;
+    mpack_memset(&print, 0, sizeof(print));
+    print.buffer = buffer;
+    print.size = sizeof(buffer);
+    print.callback = &mpack_print_file_callback;
+    print.context = file;
+
+    mpack_print_data(data, len, &print, 2);
+    mpack_print_append_cstr(&print, "\n");
+    mpack_print_flush(&print);
+}
+
+void mpack_print_stdfile_to_callback(FILE* file, mpack_print_callback_t callback, void* context) {
+    char buffer[1024];
+    mpack_print_t print;
+    mpack_memset(&print, 0, sizeof(print));
+    print.buffer = buffer;
+    print.size = sizeof(buffer);
+    print.callback = callback;
+    print.context = context;
+
+    mpack_reader_t reader;
+    mpack_reader_init_stdfile(&reader, file, false);
+    mpack_print_and_destroy(&reader, &print, 0);
+    mpack_print_flush(&print);
+}
+#endif
+
+#endif
+
+}  // namespace mpack
+MPACK_SILENCE_WARNINGS_END
+
+/* mpack/mpack-expect.c.c */
+
+#define MPACK_INTERNAL 1
+
+/* #include "mpack-expect.h" */
+
+MPACK_SILENCE_WARNINGS_BEGIN
+namespace mpack {
+
+#if MPACK_EXPECT
+
+
+// Helpers
+
+MPACK_STATIC_INLINE uint8_t mpack_expect_native_u8(mpack_reader_t* reader) {
+    if (mpack_reader_error(reader) != mpack_ok)
+        return 0;
+    uint8_t type;
+    if (!mpack_reader_ensure(reader, sizeof(type)))
+        return 0;
+    type = mpack_load_u8(reader->data);
+    reader->data += sizeof(type);
+    return type;
+}
+
+#if !MPACK_OPTIMIZE_FOR_SIZE
+MPACK_STATIC_INLINE uint16_t mpack_expect_native_u16(mpack_reader_t* reader) {
+    if (mpack_reader_error(reader) != mpack_ok)
+        return 0;
+    uint16_t type;
+    if (!mpack_reader_ensure(reader, sizeof(type)))
+        return 0;
+    type = mpack_load_u16(reader->data);
+    reader->data += sizeof(type);
+    return type;
+}
+
+MPACK_STATIC_INLINE uint32_t mpack_expect_native_u32(mpack_reader_t* reader) {
+    if (mpack_reader_error(reader) != mpack_ok)
+        return 0;
+    uint32_t type;
+    if (!mpack_reader_ensure(reader, sizeof(type)))
+        return 0;
+    type = mpack_load_u32(reader->data);
+    reader->data += sizeof(type);
+    return type;
+}
+#endif
+
+MPACK_STATIC_INLINE uint8_t mpack_expect_type_byte(mpack_reader_t* reader) {
+    mpack_reader_track_element(reader);
+    return mpack_expect_native_u8(reader);
+}
+
+
+// Basic Number Functions
+
+uint8_t mpack_expect_u8(mpack_reader_t* reader) {
+    mpack_tag_t var = mpack_read_tag(reader);
+    if (var.type == mpack_type_uint) {
+        if (var.v.u <= MPACK_UINT8_MAX)
+            return (uint8_t)var.v.u;
+    } else if (var.type == mpack_type_int) {
+        if (var.v.i >= 0 && var.v.i <= MPACK_UINT8_MAX)
+            return (uint8_t)var.v.i;
+    }
+    mpack_reader_flag_error(reader, mpack_error_type);
+    return 0;
+}
+
+uint16_t mpack_expect_u16(mpack_reader_t* reader) {
+    mpack_tag_t var = mpack_read_tag(reader);
+    if (var.type == mpack_type_uint) {
+        if (var.v.u <= MPACK_UINT16_MAX)
+            return (uint16_t)var.v.u;
+    } else if (var.type == mpack_type_int) {
+        if (var.v.i >= 0 && var.v.i <= MPACK_UINT16_MAX)
+            return (uint16_t)var.v.i;
+    }
+    mpack_reader_flag_error(reader, mpack_error_type);
+    return 0;
+}
+
+uint32_t mpack_expect_u32(mpack_reader_t* reader) {
+    mpack_tag_t var = mpack_read_tag(reader);
+    if (var.type == mpack_type_uint) {
+        if (var.v.u <= MPACK_UINT32_MAX)
+            return (uint32_t)var.v.u;
+    } else if (var.type == mpack_type_int) {
+        if (var.v.i >= 0 && var.v.i <= MPACK_UINT32_MAX)
+            return (uint32_t)var.v.i;
+    }
+    mpack_reader_flag_error(reader, mpack_error_type);
+    return 0;
+}
+
+uint64_t mpack_expect_u64(mpack_reader_t* reader) {
+    mpack_tag_t var = mpack_read_tag(reader);
+    if (var.type == mpack_type_uint) {
+        return var.v.u;
+    } else if (var.type == mpack_type_int) {
+        if (var.v.i >= 0)
+            return (uint64_t)var.v.i;
+    }
+    mpack_reader_flag_error(reader, mpack_error_type);
+    return 0;
+}
+
+int8_t mpack_expect_i8(mpack_reader_t* reader) {
+    mpack_tag_t var = mpack_read_tag(reader);
+    if (var.type == mpack_type_uint) {
+        if (var.v.u <= MPACK_INT8_MAX)
+            return (int8_t)var.v.u;
+    } else if (var.type == mpack_type_int) {
+        if (var.v.i >= MPACK_INT8_MIN && var.v.i <= MPACK_INT8_MAX)
+            return (int8_t)var.v.i;
+    }
+    mpack_reader_flag_error(reader, mpack_error_type);
+    return 0;
+}
+
+int16_t mpack_expect_i16(mpack_reader_t* reader) {
+    mpack_tag_t var = mpack_read_tag(reader);
+    if (var.type == mpack_type_uint) {
+        if (var.v.u <= MPACK_INT16_MAX)
+            return (int16_t)var.v.u;
+    } else if (var.type == mpack_type_int) {
+        if (var.v.i >= MPACK_INT16_MIN && var.v.i <= MPACK_INT16_MAX)
+            return (int16_t)var.v.i;
+    }
+    mpack_reader_flag_error(reader, mpack_error_type);
+    return 0;
+}
+
+int32_t mpack_expect_i32(mpack_reader_t* reader) {
+    mpack_tag_t var = mpack_read_tag(reader);
+    if (var.type == mpack_type_uint) {
+        if (var.v.u <= MPACK_INT32_MAX)
+            return (int32_t)var.v.u;
+    } else if (var.type == mpack_type_int) {
+        if (var.v.i >= MPACK_INT32_MIN && var.v.i <= MPACK_INT32_MAX)
+            return (int32_t)var.v.i;
+    }
+    mpack_reader_flag_error(reader, mpack_error_type);
+    return 0;
+}
+
+int64_t mpack_expect_i64(mpack_reader_t* reader) {
+    mpack_tag_t var = mpack_read_tag(reader);
+    if (var.type == mpack_type_uint) {
+        if (var.v.u <= MPACK_INT64_MAX)
+            return (int64_t)var.v.u;
+    } else if (var.type == mpack_type_int) {
+        return var.v.i;
+    }
+    mpack_reader_flag_error(reader, mpack_error_type);
+    return 0;
+}
+
+#if MPACK_FLOAT
+float mpack_expect_float(mpack_reader_t* reader) {
+    mpack_tag_t var = mpack_read_tag(reader);
+    if (var.type == mpack_type_uint)
+        return (float)var.v.u;
+    if (var.type == mpack_type_int)
+        return (float)var.v.i;
+    if (var.type == mpack_type_float)
+        return var.v.f;
+
+    if (var.type == mpack_type_double) {
+        #if MPACK_DOUBLE
+        return (float)var.v.d;
+        #else
+        return mpack_shorten_raw_double_to_float(var.v.d);
+        #endif
+    }
+
+    mpack_reader_flag_error(reader, mpack_error_type);
+    return 0.0f;
+}
+#endif
+
+#if MPACK_DOUBLE
+double mpack_expect_double(mpack_reader_t* reader) {
+    mpack_tag_t var = mpack_read_tag(reader);
+    if (var.type == mpack_type_uint)
+        return (double)var.v.u;
+    else if (var.type == mpack_type_int)
+        return (double)var.v.i;
+    else if (var.type == mpack_type_float)
+        return (double)var.v.f;
+    else if (var.type == mpack_type_double)
+        return var.v.d;
+    mpack_reader_flag_error(reader, mpack_error_type);
+    return 0.0;
+}
+#endif
+
+#if MPACK_FLOAT
+float mpack_expect_float_strict(mpack_reader_t* reader) {
+    mpack_tag_t var = mpack_read_tag(reader);
+    if (var.type == mpack_type_float)
+        return var.v.f;
+    mpack_reader_flag_error(reader, mpack_error_type);
+    return 0.0f;
+}
+#endif
+
+#if MPACK_DOUBLE
+double mpack_expect_double_strict(mpack_reader_t* reader) {
+    mpack_tag_t var = mpack_read_tag(reader);
+    if (var.type == mpack_type_float)
+        return (double)var.v.f;
+    else if (var.type == mpack_type_double)
+        return var.v.d;
+    mpack_reader_flag_error(reader, mpack_error_type);
+    return 0.0;
+}
+#endif
+
+#if !MPACK_FLOAT
+uint32_t mpack_expect_raw_float(mpack_reader_t* reader) {
+    mpack_tag_t var = mpack_read_tag(reader);
+    if (var.type == mpack_type_float)
+        return var.v.f;
+    mpack_reader_flag_error(reader, mpack_error_type);
+    return 0;
+}
+#endif
+
+#if !MPACK_DOUBLE
+uint64_t mpack_expect_raw_double(mpack_reader_t* reader) {
+    mpack_tag_t var = mpack_read_tag(reader);
+    if (var.type == mpack_type_double)
+        return var.v.d;
+    mpack_reader_flag_error(reader, mpack_error_type);
+    return 0;
+}
+#endif
+
+
+// Ranged Number Functions
+//
+// All ranged functions are identical other than the type, so we
+// define their content with a macro. The prototypes are still written
+// out in full to support ctags/IDE tools.
+
+#define MPACK_EXPECT_RANGE_IMPL(name, type_t)                           \
+                                                                        \
+    /* make sure the range is sensible */                               \
+    mpack_assert(min_value <= max_value,                                \
+            "min_value %i must be less than or equal to max_value %i",  \
+            min_value, max_value);                                      \
+                                                                        \
+    /* read the value */                                                \
+    type_t val = mpack_expect_##name(reader);                           \
+    if (mpack_reader_error(reader) != mpack_ok)                         \
+        return min_value;                                               \
+                                                                        \
+    /* make sure it fits */                                             \
+    if (val < min_value || val > max_value) {                           \
+        mpack_reader_flag_error(reader, mpack_error_type);              \
+        return min_value;                                               \
+    }                                                                   \
+                                                                        \
+    return val;
+
+uint8_t mpack_expect_u8_range(mpack_reader_t* reader, uint8_t min_value, uint8_t max_value) {MPACK_EXPECT_RANGE_IMPL(u8, uint8_t)}
+uint16_t mpack_expect_u16_range(mpack_reader_t* reader, uint16_t min_value, uint16_t max_value) {MPACK_EXPECT_RANGE_IMPL(u16, uint16_t)}
+uint32_t mpack_expect_u32_range(mpack_reader_t* reader, uint32_t min_value, uint32_t max_value) {MPACK_EXPECT_RANGE_IMPL(u32, uint32_t)}
+uint64_t mpack_expect_u64_range(mpack_reader_t* reader, uint64_t min_value, uint64_t max_value) {MPACK_EXPECT_RANGE_IMPL(u64, uint64_t)}
+
+int8_t mpack_expect_i8_range(mpack_reader_t* reader, int8_t min_value, int8_t max_value) {MPACK_EXPECT_RANGE_IMPL(i8, int8_t)}
+int16_t mpack_expect_i16_range(mpack_reader_t* reader, int16_t min_value, int16_t max_value) {MPACK_EXPECT_RANGE_IMPL(i16, int16_t)}
+int32_t mpack_expect_i32_range(mpack_reader_t* reader, int32_t min_value, int32_t max_value) {MPACK_EXPECT_RANGE_IMPL(i32, int32_t)}
+int64_t mpack_expect_i64_range(mpack_reader_t* reader, int64_t min_value, int64_t max_value) {MPACK_EXPECT_RANGE_IMPL(i64, int64_t)}
+
+#if MPACK_FLOAT
+float mpack_expect_float_range(mpack_reader_t* reader, float min_value, float max_value) {MPACK_EXPECT_RANGE_IMPL(float, float)}
+#endif
+#if MPACK_DOUBLE
+double mpack_expect_double_range(mpack_reader_t* reader, double min_value, double max_value) {MPACK_EXPECT_RANGE_IMPL(double, double)}
+#endif
+
+uint32_t mpack_expect_map_range(mpack_reader_t* reader, uint32_t min_value, uint32_t max_value) {MPACK_EXPECT_RANGE_IMPL(map, uint32_t)}
+uint32_t mpack_expect_array_range(mpack_reader_t* reader, uint32_t min_value, uint32_t max_value) {MPACK_EXPECT_RANGE_IMPL(array, uint32_t)}
+
+
+// Matching Number Functions
+
+void mpack_expect_uint_match(mpack_reader_t* reader, uint64_t value) {
+    if (mpack_expect_u64(reader) != value)
+        mpack_reader_flag_error(reader, mpack_error_type);
+}
+
+void mpack_expect_int_match(mpack_reader_t* reader, int64_t value) {
+    if (mpack_expect_i64(reader) != value)
+        mpack_reader_flag_error(reader, mpack_error_type);
+}
+
+
+// Other Basic Types
+
+void mpack_expect_nil(mpack_reader_t* reader) {
+    if (mpack_expect_type_byte(reader) != 0xc0)
+        mpack_reader_flag_error(reader, mpack_error_type);
+}
+
+bool mpack_expect_bool(mpack_reader_t* reader) {
+    uint8_t type = mpack_expect_type_byte(reader);
+    if ((type & ~1) != 0xc2)
+        mpack_reader_flag_error(reader, mpack_error_type);
+    return (bool)(type & 1);
+}
+
+void mpack_expect_true(mpack_reader_t* reader) {
+    if (mpack_expect_bool(reader) != true)
+        mpack_reader_flag_error(reader, mpack_error_type);
+}
+
+void mpack_expect_false(mpack_reader_t* reader) {
+    if (mpack_expect_bool(reader) != false)
+        mpack_reader_flag_error(reader, mpack_error_type);
+}
+
+#if MPACK_EXTENSIONS
+mpack_timestamp_t mpack_expect_timestamp(mpack_reader_t* reader) {
+    mpack_timestamp_t zero = {0, 0};
+
+    mpack_tag_t tag = mpack_read_tag(reader);
+    if (tag.type != mpack_type_ext) {
+        mpack_reader_flag_error(reader, mpack_error_type);
+        return zero;
+    }
+    if (mpack_tag_ext_exttype(&tag) != MPACK_EXTTYPE_TIMESTAMP) {
+        mpack_reader_flag_error(reader, mpack_error_type);
+        return zero;
+    }
+
+    return mpack_read_timestamp(reader, mpack_tag_ext_length(&tag));
+}
+
+int64_t mpack_expect_timestamp_truncate(mpack_reader_t* reader) {
+    return mpack_expect_timestamp(reader).seconds;
+}
+#endif
+
+
+// Compound Types
+
+uint32_t mpack_expect_map(mpack_reader_t* reader) {
+    mpack_tag_t var = mpack_read_tag(reader);
+    if (var.type == mpack_type_map)
+        return var.v.n;
+    mpack_reader_flag_error(reader, mpack_error_type);
+    return 0;
+}
+
+void mpack_expect_map_match(mpack_reader_t* reader, uint32_t count) {
+    if (mpack_expect_map(reader) != count)
+        mpack_reader_flag_error(reader, mpack_error_type);
+}
+
+bool mpack_expect_map_or_nil(mpack_reader_t* reader, uint32_t* count) {
+    mpack_assert(count != NULL, "count cannot be NULL");
+
+    mpack_tag_t var = mpack_read_tag(reader);
+    if (var.type == mpack_type_nil) {
+        *count = 0;
+        return false;
+    }
+    if (var.type == mpack_type_map) {
+        *count = var.v.n;
+        return true;
+    }
+    mpack_reader_flag_error(reader, mpack_error_type);
+    *count = 0;
+    return false;
+}
+
+bool mpack_expect_map_max_or_nil(mpack_reader_t* reader, uint32_t max_count, uint32_t* count) {
+    mpack_assert(count != NULL, "count cannot be NULL");
+
+    bool has_map = mpack_expect_map_or_nil(reader, count);
+    if (has_map && *count > max_count) {
+        *count = 0;
+        mpack_reader_flag_error(reader, mpack_error_type);
+        return false;
+    }
+    return has_map;
+}
+
+uint32_t mpack_expect_array(mpack_reader_t* reader) {
+    mpack_tag_t var = mpack_read_tag(reader);
+    if (var.type == mpack_type_array)
+        return var.v.n;
+    mpack_reader_flag_error(reader, mpack_error_type);
+    return 0;
+}
+
+void mpack_expect_array_match(mpack_reader_t* reader, uint32_t count) {
+    if (mpack_expect_array(reader) != count)
+        mpack_reader_flag_error(reader, mpack_error_type);
+}
+
+bool mpack_expect_array_or_nil(mpack_reader_t* reader, uint32_t* count) {
+    mpack_assert(count != NULL, "count cannot be NULL");
+
+    mpack_tag_t var = mpack_read_tag(reader);
+    if (var.type == mpack_type_nil) {
+        *count = 0;
+        return false;
+    }
+    if (var.type == mpack_type_array) {
+        *count = var.v.n;
+        return true;
+    }
+    mpack_reader_flag_error(reader, mpack_error_type);
+    *count = 0;
+    return false;
+}
+
+bool mpack_expect_array_max_or_nil(mpack_reader_t* reader, uint32_t max_count, uint32_t* count) {
+    mpack_assert(count != NULL, "count cannot be NULL");
+
+    bool has_array = mpack_expect_array_or_nil(reader, count);
+    if (has_array && *count > max_count) {
+        *count = 0;
+        mpack_reader_flag_error(reader, mpack_error_type);
+        return false;
+    }
+    return has_array;
+}
+
+#ifdef MPACK_MALLOC
+void* mpack_expect_array_alloc_impl(mpack_reader_t* reader, size_t element_size, uint32_t max_count, uint32_t* out_count, bool allow_nil) {
+    mpack_assert(out_count != NULL, "out_count cannot be NULL");
+    *out_count = 0;
+
+    uint32_t count;
+    bool has_array = true;
+    if (allow_nil)
+        has_array = mpack_expect_array_max_or_nil(reader, max_count, &count);
+    else
+        count = mpack_expect_array_max(reader, max_count);
+    if (mpack_reader_error(reader))
+        return NULL;
+
+    // size 0 is not an error; we return NULL for no elements.
+    if (count == 0) {
+        // we call mpack_done_array() automatically ONLY if we are using
+        // the _or_nil variant. this is the only way to allow nil and empty
+        // to work the same way.
+        if (allow_nil && has_array)
+            mpack_done_array(reader);
+        return NULL;
+    }
+
+    void* p = MPACK_MALLOC(element_size * count);
+    if (p == NULL) {
+        mpack_reader_flag_error(reader, mpack_error_memory);
+        return NULL;
+    }
+
+    *out_count = count;
+    return p;
+}
+#endif
+
+
+// Str, Bin and Ext Functions
+
+uint32_t mpack_expect_str(mpack_reader_t* reader) {
+    #if MPACK_OPTIMIZE_FOR_SIZE
+    mpack_tag_t var = mpack_read_tag(reader);
+    if (var.type == mpack_type_str)
+        return var.v.l;
+    mpack_reader_flag_error(reader, mpack_error_type);
+    return 0;
+    #else
+    uint8_t type = mpack_expect_type_byte(reader);
+    uint32_t count;
+
+    if ((type >> 5) == 5) {
+        count = type & (uint8_t)~0xe0;
+    } else if (type == 0xd9) {
+        count = mpack_expect_native_u8(reader);
+    } else if (type == 0xda) {
+        count = mpack_expect_native_u16(reader);
+    } else if (type == 0xdb) {
+        count = mpack_expect_native_u32(reader);
+    } else {
+        mpack_reader_flag_error(reader, mpack_error_type);
+        return 0;
+    }
+
+    #if MPACK_READ_TRACKING
+    mpack_reader_flag_if_error(reader, mpack_track_push(&reader->track, mpack_type_str, count));
+    #endif
+    return count;
+    #endif
+}
+
+size_t mpack_expect_str_buf(mpack_reader_t* reader, char* buf, size_t bufsize) {
+    mpack_assert(buf != NULL, "buf cannot be NULL");
+
+    size_t length = mpack_expect_str(reader);
+    if (mpack_reader_error(reader))
+        return 0;
+
+    if (length > bufsize) {
+        mpack_reader_flag_error(reader, mpack_error_too_big);
+        return 0;
+    }
+
+    mpack_read_bytes(reader, buf, length);
+    if (mpack_reader_error(reader))
+        return 0;
+
+    mpack_done_str(reader);
+    return length;
+}
+
+size_t mpack_expect_utf8(mpack_reader_t* reader, char* buf, size_t size) {
+    mpack_assert(buf != NULL, "buf cannot be NULL");
+
+    size_t length = mpack_expect_str_buf(reader, buf, size);
+
+    if (!mpack_utf8_check(buf, length)) {
+        mpack_reader_flag_error(reader, mpack_error_type);
+        return 0;
+    }
+
+    return length;
+}
+
+uint32_t mpack_expect_bin(mpack_reader_t* reader) {
+    mpack_tag_t var = mpack_read_tag(reader);
+    if (var.type == mpack_type_bin)
+        return var.v.l;
+    mpack_reader_flag_error(reader, mpack_error_type);
+    return 0;
+}
+
+size_t mpack_expect_bin_buf(mpack_reader_t* reader, char* buf, size_t bufsize) {
+    mpack_assert(buf != NULL, "buf cannot be NULL");
+
+    size_t binsize = mpack_expect_bin(reader);
+    if (mpack_reader_error(reader))
+        return 0;
+    if (binsize > bufsize) {
+        mpack_reader_flag_error(reader, mpack_error_too_big);
+        return 0;
+    }
+    mpack_read_bytes(reader, buf, binsize);
+    if (mpack_reader_error(reader))
+        return 0;
+    mpack_done_bin(reader);
+    return binsize;
+}
+
+void mpack_expect_bin_size_buf(mpack_reader_t* reader, char* buf, uint32_t size) {
+    mpack_assert(buf != NULL, "buf cannot be NULL");
+    mpack_expect_bin_size(reader, size);
+    mpack_read_bytes(reader, buf, size);
+    mpack_done_bin(reader);
+}
+
+#if MPACK_EXTENSIONS
+uint32_t mpack_expect_ext(mpack_reader_t* reader, int8_t* type) {
+    mpack_tag_t var = mpack_read_tag(reader);
+    if (var.type == mpack_type_ext) {
+        *type = mpack_tag_ext_exttype(&var);
+        return mpack_tag_ext_length(&var);
+    }
+    *type = 0;
+    mpack_reader_flag_error(reader, mpack_error_type);
+    return 0;
+}
+
+size_t mpack_expect_ext_buf(mpack_reader_t* reader, int8_t* type, char* buf, size_t bufsize) {
+    mpack_assert(buf != NULL, "buf cannot be NULL");
+
+    size_t extsize = mpack_expect_ext(reader, type);
+    if (mpack_reader_error(reader))
+        return 0;
+    if (extsize > bufsize) {
+        *type = 0;
+        mpack_reader_flag_error(reader, mpack_error_too_big);
+        return 0;
+    }
+    mpack_read_bytes(reader, buf, extsize);
+    if (mpack_reader_error(reader)) {
+        *type = 0;
+        return 0;
+    }
+    mpack_done_ext(reader);
+    return extsize;
+}
+#endif
+
+void mpack_expect_cstr(mpack_reader_t* reader, char* buf, size_t bufsize) {
+    uint32_t length = mpack_expect_str(reader);
+    mpack_read_cstr(reader, buf, bufsize, length);
+    mpack_done_str(reader);
+}
+
+void mpack_expect_utf8_cstr(mpack_reader_t* reader, char* buf, size_t bufsize) {
+    uint32_t length = mpack_expect_str(reader);
+    mpack_read_utf8_cstr(reader, buf, bufsize, length);
+    mpack_done_str(reader);
+}
+
+#ifdef MPACK_MALLOC
+static char* mpack_expect_cstr_alloc_unchecked(mpack_reader_t* reader, size_t maxsize, size_t* out_length) {
+    mpack_assert(out_length != NULL, "out_length cannot be NULL");
+    *out_length = 0;
+
+    // make sure argument makes sense
+    if (maxsize < 1) {
+        mpack_break("maxsize is zero; you must have room for at least a null-terminator");
+        mpack_reader_flag_error(reader, mpack_error_bug);
+        return NULL;
+    }
+
+    if (SIZE_MAX < MPACK_UINT32_MAX) {
+        if (maxsize > SIZE_MAX)
+            maxsize = SIZE_MAX;
+    } else {
+        if (maxsize > (size_t)MPACK_UINT32_MAX)
+            maxsize = (size_t)MPACK_UINT32_MAX;
+    }
+
+    size_t length = mpack_expect_str_max(reader, (uint32_t)maxsize - 1);
+    char* str = mpack_read_bytes_alloc_impl(reader, length, true);
+    mpack_done_str(reader);
+
+    if (str)
+        *out_length = length;
+    return str;
+}
+
+char* mpack_expect_cstr_alloc(mpack_reader_t* reader, size_t maxsize) {
+    size_t length;
+    char* str = mpack_expect_cstr_alloc_unchecked(reader, maxsize, &length);
+
+    if (str && !mpack_str_check_no_null(str, length)) {
+        MPACK_FREE(str);
+        mpack_reader_flag_error(reader, mpack_error_type);
+        return NULL;
+    }
+
+    return str;
+}
+
+char* mpack_expect_utf8_cstr_alloc(mpack_reader_t* reader, size_t maxsize) {
+    size_t length;
+    char* str = mpack_expect_cstr_alloc_unchecked(reader, maxsize, &length);
+
+    if (str && !mpack_utf8_check_no_null(str, length)) {
+        MPACK_FREE(str);
+        mpack_reader_flag_error(reader, mpack_error_type);
+        return NULL;
+    }
+
+    return str;
+}
+#endif
+
+void mpack_expect_str_match(mpack_reader_t* reader, const char* str, size_t len) {
+    mpack_assert(str != NULL, "str cannot be NULL");
+
+    // expect a str the correct length
+    if (len > MPACK_UINT32_MAX)
+        mpack_reader_flag_error(reader, mpack_error_type);
+    mpack_expect_str_length(reader, (uint32_t)len);
+    if (mpack_reader_error(reader))
+        return;
+    mpack_reader_track_bytes(reader, (uint32_t)len);
+
+    // check each byte one by one (matched strings are likely to be very small)
+    for (; len > 0; --len) {
+        if (mpack_expect_native_u8(reader) != *str++) {
+            mpack_reader_flag_error(reader, mpack_error_type);
+            return;
+        }
+    }
+
+    mpack_done_str(reader);
+}
+
+void mpack_expect_tag(mpack_reader_t* reader, mpack_tag_t expected) {
+    mpack_tag_t actual = mpack_read_tag(reader);
+    if (!mpack_tag_equal(actual, expected))
+        mpack_reader_flag_error(reader, mpack_error_type);
+}
+
+#ifdef MPACK_MALLOC
+char* mpack_expect_bin_alloc(mpack_reader_t* reader, size_t maxsize, size_t* size) {
+    mpack_assert(size != NULL, "size cannot be NULL");
+    *size = 0;
+
+    if (SIZE_MAX < MPACK_UINT32_MAX) {
+        if (maxsize > SIZE_MAX)
+            maxsize = SIZE_MAX;
+    } else {
+        if (maxsize > (size_t)MPACK_UINT32_MAX)
+            maxsize = (size_t)MPACK_UINT32_MAX;
+    }
+
+    size_t length = mpack_expect_bin_max(reader, (uint32_t)maxsize);
+    if (mpack_reader_error(reader))
+        return NULL;
+
+    char* data = mpack_read_bytes_alloc(reader, length);
+    mpack_done_bin(reader);
+
+    if (data)
+        *size = length;
+    return data;
+}
+#endif
+
+#if MPACK_EXTENSIONS && defined(MPACK_MALLOC)
+char* mpack_expect_ext_alloc(mpack_reader_t* reader, int8_t* type, size_t maxsize, size_t* size) {
+    mpack_assert(size != NULL, "size cannot be NULL");
+    *size = 0;
+
+    if (SIZE_MAX < MPACK_UINT32_MAX) {
+        if (maxsize > SIZE_MAX)
+            maxsize = SIZE_MAX;
+    } else {
+        if (maxsize > (size_t)MPACK_UINT32_MAX)
+            maxsize = (size_t)MPACK_UINT32_MAX;
+    }
+
+    size_t length = mpack_expect_ext_max(reader, type, (uint32_t)maxsize);
+    if (mpack_reader_error(reader))
+        return NULL;
+
+    char* data = mpack_read_bytes_alloc(reader, length);
+    mpack_done_ext(reader);
+
+    if (data) {
+        *size = length;
+    } else {
+        *type = 0;
+    }
+    return data;
+}
+#endif
+
+size_t mpack_expect_enum(mpack_reader_t* reader, const char* strings[], size_t count) {
+
+    // read the string in-place
+    size_t keylen = mpack_expect_str(reader);
+    const char* key = mpack_read_bytes_inplace(reader, keylen);
+    mpack_done_str(reader);
+    if (mpack_reader_error(reader) != mpack_ok)
+        return count;
+
+    // find what key it matches
+    size_t i;
+    for (i = 0; i < count; ++i) {
+        const char* other = strings[i];
+        size_t otherlen = mpack_strlen(other);
+        if (keylen == otherlen && mpack_memcmp(key, other, keylen) == 0)
+            return i;
+    }
+
+    // no matches
+    mpack_reader_flag_error(reader, mpack_error_type);
+    return count;
+}
+
+size_t mpack_expect_enum_optional(mpack_reader_t* reader, const char* strings[], size_t count) {
+    if (mpack_reader_error(reader) != mpack_ok)
+        return count;
+
+    mpack_assert(count != 0, "count cannot be zero; no strings are valid!");
+    mpack_assert(strings != NULL, "strings cannot be NULL");
+
+    // the key is only recognized if it is a string
+    if (mpack_peek_tag(reader).type != mpack_type_str) {
+        mpack_discard(reader);
+        return count;
+    }
+
+    // read the string in-place
+    size_t keylen = mpack_expect_str(reader);
+    const char* key = mpack_read_bytes_inplace(reader, keylen);
+    mpack_done_str(reader);
+    if (mpack_reader_error(reader) != mpack_ok)
+        return count;
+
+    // find what key it matches
+    size_t i;
+    for (i = 0; i < count; ++i) {
+        const char* other = strings[i];
+        size_t otherlen = mpack_strlen(other);
+        if (keylen == otherlen && mpack_memcmp(key, other, keylen) == 0)
+            return i;
+    }
+
+    // no matches
+    return count;
+}
+
+size_t mpack_expect_key_uint(mpack_reader_t* reader, bool found[], size_t count) {
+    if (mpack_reader_error(reader) != mpack_ok)
+        return count;
+
+    if (count == 0) {
+        mpack_break("count cannot be zero; no keys are valid!");
+        mpack_reader_flag_error(reader, mpack_error_bug);
+        return count;
+    }
+    mpack_assert(found != NULL, "found cannot be NULL");
+
+    // the key is only recognized if it is an unsigned int
+    if (mpack_peek_tag(reader).type != mpack_type_uint) {
+        mpack_discard(reader);
+        return count;
+    }
+
+    // read the key
+    uint64_t value = mpack_expect_u64(reader);
+    if (mpack_reader_error(reader) != mpack_ok)
+        return count;
+
+    // unrecognized keys are fine, we just return count
+    if (value >= count)
+        return count;
+
+    // check if this key is a duplicate
+    if (found[value]) {
+        mpack_reader_flag_error(reader, mpack_error_invalid);
+        return count;
+    }
+
+    found[value] = true;
+    return (size_t)value;
+}
+
+size_t mpack_expect_key_cstr(mpack_reader_t* reader, const char* keys[], bool found[], size_t count) {
+    size_t i = mpack_expect_enum_optional(reader, keys, count);
+
+    // unrecognized keys are fine, we just return count
+    if (i == count)
+        return count;
+
+    // check if this key is a duplicate
+    mpack_assert(found != NULL, "found cannot be NULL");
+    if (found[i]) {
+        mpack_reader_flag_error(reader, mpack_error_invalid);
+        return count;
+    }
+
+    found[i] = true;
+    return i;
+}
+
+#endif
+
+}  // namespace mpack
+MPACK_SILENCE_WARNINGS_END
+
+/* mpack/mpack-node.c.c */
+
+#define MPACK_INTERNAL 1
+
+/* #include "mpack-node.h" */
+
+MPACK_SILENCE_WARNINGS_BEGIN
+namespace mpack {
+
+#if MPACK_NODE
+
+MPACK_STATIC_INLINE const char* mpack_node_data_unchecked(mpack_node_t node) {
+    mpack_assert(mpack_node_error(node) == mpack_ok, "tree is in an error state!");
+
+    mpack_type_t type = node.data->type;
+    MPACK_UNUSED(type);
+    #if MPACK_EXTENSIONS
+    mpack_assert(type == mpack_type_str || type == mpack_type_bin || type == mpack_type_ext,
+            "node of type %i (%s) is not a data type!", type, mpack_type_to_string(type));
+    #else
+    mpack_assert(type == mpack_type_str || type == mpack_type_bin,
+            "node of type %i (%s) is not a data type!", type, mpack_type_to_string(type));
+    #endif
+
+    return node.tree->data + node.data->value.offset;
+}
+
+#if MPACK_EXTENSIONS
+MPACK_STATIC_INLINE int8_t mpack_node_exttype_unchecked(mpack_node_t node) {
+    mpack_assert(mpack_node_error(node) == mpack_ok, "tree is in an error state!");
+
+    mpack_type_t type = node.data->type;
+    MPACK_UNUSED(type);
+    mpack_assert(type == mpack_type_ext, "node of type %i (%s) is not an ext type!",
+            type, mpack_type_to_string(type));
+
+    // the exttype of an ext node is stored in the byte preceding the data
+    return mpack_load_i8(mpack_node_data_unchecked(node) - 1);
+}
+#endif
+
+
+
+/*
+ * Tree Parsing
+ */
+
+#ifdef MPACK_MALLOC
+
+// fix up the alloc size to make sure it exactly fits the
+// maximum number of nodes it can contain (the allocator will
+// waste it back anyway, but we round it down just in case)
+
+#define MPACK_NODES_PER_PAGE \
+    ((MPACK_NODE_PAGE_SIZE - sizeof(mpack_tree_page_t)) / sizeof(mpack_node_data_t) + 1)
+
+#define MPACK_PAGE_ALLOC_SIZE \
+    (sizeof(mpack_tree_page_t) + sizeof(mpack_node_data_t) * (MPACK_NODES_PER_PAGE - 1))
+
+#endif
+
+#ifdef MPACK_MALLOC
+/*
+ * Fills the tree until we have at least enough bytes for the current node.
+ */
+static bool mpack_tree_reserve_fill(mpack_tree_t* tree) {
+    mpack_assert(tree->parser.state == mpack_tree_parse_state_in_progress);
+
+    size_t bytes = tree->parser.current_node_reserved;
+    mpack_assert(bytes > tree->parser.possible_nodes_left,
+            "there are already enough bytes! call mpack_tree_ensure() instead.");
+    mpack_log("filling to reserve %i bytes\n", (int)bytes);
+
+    // if the necessary bytes would put us over the maximum tree
+    // size, fail right away.
+    // TODO: check for overflow?
+    if (tree->data_length + bytes > tree->max_size) {
+        mpack_tree_flag_error(tree, mpack_error_too_big);
+        return false;
+    }
+
+    // we'll need a read function to fetch more data. if there's
+    // no read function, the data should contain an entire message
+    // (or messages), so we flag it as invalid.
+    if (tree->read_fn == NULL) {
+        mpack_log("tree has no read function!\n");
+        mpack_tree_flag_error(tree, mpack_error_invalid);
+        return false;
+    }
+
+    // expand the buffer if needed
+    if (tree->data_length + bytes > tree->buffer_capacity) {
+
+        // TODO: check for overflow?
+        size_t new_capacity = (tree->buffer_capacity == 0) ? MPACK_BUFFER_SIZE : tree->buffer_capacity;
+        while (new_capacity < tree->data_length + bytes)
+            new_capacity *= 2;
+        if (new_capacity > tree->max_size)
+            new_capacity = tree->max_size;
+
+        mpack_log("expanding buffer from %i to %i\n", (int)tree->buffer_capacity, (int)new_capacity);
+
+        char* new_buffer;
+        if (tree->buffer == NULL)
+            new_buffer = (char*)MPACK_MALLOC(new_capacity);
+        else
+            new_buffer = (char*)mpack_realloc(tree->buffer, tree->data_length, new_capacity);
+
+        if (new_buffer == NULL) {
+            mpack_tree_flag_error(tree, mpack_error_memory);
+            return false;
+        }
+
+        tree->data = new_buffer;
+        tree->buffer = new_buffer;
+        tree->buffer_capacity = new_capacity;
+    }
+
+    // request as much data as possible, looping until we have
+    // all the data we need
+    do {
+        size_t read = tree->read_fn(tree, tree->buffer + tree->data_length, tree->buffer_capacity - tree->data_length);
+
+        // If the fill function encounters an error, it should flag an error on
+        // the tree.
+        if (mpack_tree_error(tree) != mpack_ok)
+            return false;
+
+        // We guard against fill functions that return -1 just in case.
+        if (read == (size_t)(-1)) {
+            mpack_tree_flag_error(tree, mpack_error_io);
+            return false;
+        }
+
+        // If the fill function returns 0, the data is not available yet. We
+        // return false to stop parsing the current node.
+        if (read == 0) {
+            mpack_log("not enough data.\n");
+            return false;
+        }
+
+        mpack_log("read %u more bytes\n", (uint32_t)read);
+        tree->data_length += read;
+        tree->parser.possible_nodes_left += read;
+    } while (tree->parser.possible_nodes_left < bytes);
+
+    return true;
+}
+#endif
+
+/*
+ * Ensures there are enough additional bytes in the tree for the current node
+ * (including reserved bytes for the children of this node, and in addition to
+ * the reserved bytes for children of previous compound nodes), reading more
+ * data if needed.
+ *
+ * extra_bytes is the number of additional bytes to reserve for the current
+ * node beyond the type byte (since one byte is already reserved for each node
+ * by its parent array or map.)
+ *
+ * This may reallocate the tree, which means the tree->data pointer may change!
+ *
+ * Returns false if not enough bytes could be read.
+ */
+MPACK_STATIC_INLINE bool mpack_tree_reserve_bytes(mpack_tree_t* tree, size_t extra_bytes) {
+    mpack_assert(tree->parser.state == mpack_tree_parse_state_in_progress);
+
+    // We guard against overflow here. A compound type could declare more than
+    // MPACK_UINT32_MAX contents which overflows SIZE_MAX on 32-bit platforms. We
+    // flag mpack_error_invalid instead of mpack_error_too_big since it's far
+    // more likely that the message is corrupt than that the data is valid but
+    // not parseable on this architecture (see test_read_node_possible() in
+    // test-node.c .)
+    if ((uint64_t)tree->parser.current_node_reserved + (uint64_t)extra_bytes > SIZE_MAX) {
+        mpack_tree_flag_error(tree, mpack_error_invalid);
+        return false;
+    }
+
+    tree->parser.current_node_reserved += extra_bytes;
+
+    // Note that possible_nodes_left already accounts for reserved bytes for
+    // children of previous compound nodes. So even if there are hundreds of
+    // bytes left in the buffer, we might need to read anyway.
+    if (tree->parser.current_node_reserved <= tree->parser.possible_nodes_left)
+        return true;
+
+    #ifdef MPACK_MALLOC
+    return mpack_tree_reserve_fill(tree);
+    #else
+    return false;
+    #endif
+}
+
+MPACK_STATIC_INLINE size_t mpack_tree_parser_stack_capacity(mpack_tree_t* tree) {
+    #ifdef MPACK_MALLOC
+    return tree->parser.stack_capacity;
+    #else
+    return sizeof(tree->parser.stack) / sizeof(tree->parser.stack[0]);
+    #endif
+}
+
+static bool mpack_tree_push_stack(mpack_tree_t* tree, mpack_node_data_t* first_child, size_t total) {
+    mpack_tree_parser_t* parser = &tree->parser;
+    mpack_assert(parser->state == mpack_tree_parse_state_in_progress);
+
+    // No need to push empty containers
+    if (total == 0)
+        return true;
+
+    // Make sure we have enough room in the stack
+    if (parser->level + 1 == mpack_tree_parser_stack_capacity(tree)) {
+        #ifdef MPACK_MALLOC
+        size_t new_capacity = parser->stack_capacity * 2;
+        mpack_log("growing parse stack to capacity %i\n", (int)new_capacity);
+
+        // Replace the stack-allocated parsing stack
+        if (!parser->stack_owned) {
+            mpack_level_t* new_stack = (mpack_level_t*)MPACK_MALLOC(sizeof(mpack_level_t) * new_capacity);
+            if (!new_stack) {
+                mpack_tree_flag_error(tree, mpack_error_memory);
+                return false;
+            }
+            mpack_memcpy(new_stack, parser->stack, sizeof(mpack_level_t) * parser->stack_capacity);
+            parser->stack = new_stack;
+            parser->stack_owned = true;
+
+        // Realloc the allocated parsing stack
+        } else {
+            mpack_level_t* new_stack = (mpack_level_t*)mpack_realloc(parser->stack,
+                    sizeof(mpack_level_t) * parser->stack_capacity, sizeof(mpack_level_t) * new_capacity);
+            if (!new_stack) {
+                mpack_tree_flag_error(tree, mpack_error_memory);
+                return false;
+            }
+            parser->stack = new_stack;
+        }
+        parser->stack_capacity = new_capacity;
+        #else
+        mpack_tree_flag_error(tree, mpack_error_too_big);
+        return false;
+        #endif
+    }
+
+    // Push the contents of this node onto the parsing stack
+    ++parser->level;
+    parser->stack[parser->level].child = first_child;
+    parser->stack[parser->level].left = total;
+    return true;
+}
+
+static bool mpack_tree_parse_children(mpack_tree_t* tree, mpack_node_data_t* node) {
+    mpack_tree_parser_t* parser = &tree->parser;
+    mpack_assert(parser->state == mpack_tree_parse_state_in_progress);
+
+    mpack_type_t type = node->type;
+    size_t total = node->len;
+
+    // Calculate total elements to read
+    if (type == mpack_type_map) {
+        if ((uint64_t)total * 2 > SIZE_MAX) {
+            mpack_tree_flag_error(tree, mpack_error_too_big);
+            return false;
+        }
+        total *= 2;
+    }
+
+    // Make sure we are under our total node limit (TODO can this overflow?)
+    tree->node_count += total;
+    if (tree->node_count > tree->max_nodes) {
+        mpack_tree_flag_error(tree, mpack_error_too_big);
+        return false;
+    }
+
+    // Each node is at least one byte. Count these bytes now to make
+    // sure there is enough data left.
+    if (!mpack_tree_reserve_bytes(tree, total))
+        return false;
+
+    // If there are enough nodes left in the current page, no need to grow
+    if (total <= parser->nodes_left) {
+        node->value.children = parser->nodes;
+        parser->nodes += total;
+        parser->nodes_left -= total;
+
+    } else {
+
+        #ifdef MPACK_MALLOC
+
+        // We can't grow if we're using a fixed pool (i.e. we didn't start with a page)
+        if (!tree->next) {
+            mpack_tree_flag_error(tree, mpack_error_too_big);
+            return false;
+        }
+
+        // Otherwise we need to grow, and the node's children need to be contiguous.
+        // This is a heuristic to decide whether we should waste the remaining space
+        // in the current page and start a new one, or give the children their
+        // own page. With a fraction of 1/8, this causes at most 12% additional
+        // waste. Note that reducing this too much causes less cache coherence and
+        // more malloc() overhead due to smaller allocations, so there's a tradeoff
+        // here. This heuristic could use some improvement, especially with custom
+        // page sizes.
+
+        mpack_tree_page_t* page;
+
+        if (total > MPACK_NODES_PER_PAGE || parser->nodes_left > MPACK_NODES_PER_PAGE / 8) {
+            // TODO: this should check for overflow
+            page = (mpack_tree_page_t*)MPACK_MALLOC(
+                    sizeof(mpack_tree_page_t) + sizeof(mpack_node_data_t) * (total - 1));
+            if (page == NULL) {
+                mpack_tree_flag_error(tree, mpack_error_memory);
+                return false;
+            }
+            mpack_log("allocated seperate page %p for %i children, %i left in page of %i total\n",
+                    (void*)page, (int)total, (int)parser->nodes_left, (int)MPACK_NODES_PER_PAGE);
+
+            node->value.children = page->nodes;
+
+        } else {
+            page = (mpack_tree_page_t*)MPACK_MALLOC(MPACK_PAGE_ALLOC_SIZE);
+            if (page == NULL) {
+                mpack_tree_flag_error(tree, mpack_error_memory);
+                return false;
+            }
+            mpack_log("allocated new page %p for %i children, wasting %i in page of %i total\n",
+                    (void*)page, (int)total, (int)parser->nodes_left, (int)MPACK_NODES_PER_PAGE);
+
+            node->value.children = page->nodes;
+            parser->nodes = page->nodes + total;
+            parser->nodes_left = MPACK_NODES_PER_PAGE - total;
+        }
+
+        page->next = tree->next;
+        tree->next = page;
+
+        #else
+        // We can't grow if we don't have an allocator
+        mpack_tree_flag_error(tree, mpack_error_too_big);
+        return false;
+        #endif
+    }
+
+    return mpack_tree_push_stack(tree, node->value.children, total);
+}
+
+static bool mpack_tree_parse_bytes(mpack_tree_t* tree, mpack_node_data_t* node) {
+    node->value.offset = tree->size + tree->parser.current_node_reserved + 1;
+    return mpack_tree_reserve_bytes(tree, node->len);
+}
+
+#if MPACK_EXTENSIONS
+static bool mpack_tree_parse_ext(mpack_tree_t* tree, mpack_node_data_t* node) {
+    // reserve space for exttype
+    tree->parser.current_node_reserved += sizeof(int8_t);
+    node->type = mpack_type_ext;
+    return mpack_tree_parse_bytes(tree, node);
+}
+#endif
+
+static bool mpack_tree_parse_node_contents(mpack_tree_t* tree, mpack_node_data_t* node) {
+    mpack_assert(tree->parser.state == mpack_tree_parse_state_in_progress);
+    mpack_assert(node != NULL, "null node?");
+
+    // read the type. we've already accounted for this byte in
+    // possible_nodes_left, so we already know it is in bounds, and we don't
+    // need to reserve it for this node.
+    mpack_assert(tree->data_length > tree->size);
+    uint8_t type = mpack_load_u8(tree->data + tree->size);
+    mpack_log("node type %x\n", type);
+    tree->parser.current_node_reserved = 0;
+
+    // as with mpack_read_tag(), the fastest way to parse a node is to switch
+    // on the first byte, and to explicitly list every possible byte. we switch
+    // on the first four bits in size-optimized builds.
+
+    #if MPACK_OPTIMIZE_FOR_SIZE
+    switch (type >> 4) {
+
+        // positive fixnum
+        case 0x0: case 0x1: case 0x2: case 0x3:
+        case 0x4: case 0x5: case 0x6: case 0x7:
+            node->type = mpack_type_uint;
+            node->value.u = type;
+            return true;
+
+        // negative fixnum
+        case 0xe: case 0xf:
+            node->type = mpack_type_int;
+            node->value.i = (int8_t)type;
+            return true;
+
+        // fixmap
+        case 0x8:
+            node->type = mpack_type_map;
+            node->len = (uint32_t)(type & ~0xf0);
+            return mpack_tree_parse_children(tree, node);
+
+        // fixarray
+        case 0x9:
+            node->type = mpack_type_array;
+            node->len = (uint32_t)(type & ~0xf0);
+            return mpack_tree_parse_children(tree, node);
+
+        // fixstr
+        case 0xa: case 0xb:
+            node->type = mpack_type_str;
+            node->len = (uint32_t)(type & ~0xe0);
+            return mpack_tree_parse_bytes(tree, node);
+
+        // not one of the common infix types
+        default:
+            break;
+    }
+    #endif
+
+    switch (type) {
+
+        #if !MPACK_OPTIMIZE_FOR_SIZE
+        // positive fixnum
+        case 0x00: case 0x01: case 0x02: case 0x03: case 0x04: case 0x05: case 0x06: case 0x07:
+        case 0x08: case 0x09: case 0x0a: case 0x0b: case 0x0c: case 0x0d: case 0x0e: case 0x0f:
+        case 0x10: case 0x11: case 0x12: case 0x13: case 0x14: case 0x15: case 0x16: case 0x17:
+        case 0x18: case 0x19: case 0x1a: case 0x1b: case 0x1c: case 0x1d: case 0x1e: case 0x1f:
+        case 0x20: case 0x21: case 0x22: case 0x23: case 0x24: case 0x25: case 0x26: case 0x27:
+        case 0x28: case 0x29: case 0x2a: case 0x2b: case 0x2c: case 0x2d: case 0x2e: case 0x2f:
+        case 0x30: case 0x31: case 0x32: case 0x33: case 0x34: case 0x35: case 0x36: case 0x37:
+        case 0x38: case 0x39: case 0x3a: case 0x3b: case 0x3c: case 0x3d: case 0x3e: case 0x3f:
+        case 0x40: case 0x41: case 0x42: case 0x43: case 0x44: case 0x45: case 0x46: case 0x47:
+        case 0x48: case 0x49: case 0x4a: case 0x4b: case 0x4c: case 0x4d: case 0x4e: case 0x4f:
+        case 0x50: case 0x51: case 0x52: case 0x53: case 0x54: case 0x55: case 0x56: case 0x57:
+        case 0x58: case 0x59: case 0x5a: case 0x5b: case 0x5c: case 0x5d: case 0x5e: case 0x5f:
+        case 0x60: case 0x61: case 0x62: case 0x63: case 0x64: case 0x65: case 0x66: case 0x67:
+        case 0x68: case 0x69: case 0x6a: case 0x6b: case 0x6c: case 0x6d: case 0x6e: case 0x6f:
+        case 0x70: case 0x71: case 0x72: case 0x73: case 0x74: case 0x75: case 0x76: case 0x77:
+        case 0x78: case 0x79: case 0x7a: case 0x7b: case 0x7c: case 0x7d: case 0x7e: case 0x7f:
+            node->type = mpack_type_uint;
+            node->value.u = type;
+            return true;
+
+        // negative fixnum
+        case 0xe0: case 0xe1: case 0xe2: case 0xe3: case 0xe4: case 0xe5: case 0xe6: case 0xe7:
+        case 0xe8: case 0xe9: case 0xea: case 0xeb: case 0xec: case 0xed: case 0xee: case 0xef:
+        case 0xf0: case 0xf1: case 0xf2: case 0xf3: case 0xf4: case 0xf5: case 0xf6: case 0xf7:
+        case 0xf8: case 0xf9: case 0xfa: case 0xfb: case 0xfc: case 0xfd: case 0xfe: case 0xff:
+            node->type = mpack_type_int;
+            node->value.i = (int8_t)type;
+            return true;
+
+        // fixmap
+        case 0x80: case 0x81: case 0x82: case 0x83: case 0x84: case 0x85: case 0x86: case 0x87:
+        case 0x88: case 0x89: case 0x8a: case 0x8b: case 0x8c: case 0x8d: case 0x8e: case 0x8f:
+            node->type = mpack_type_map;
+            node->len = (uint32_t)(type & ~0xf0);
+            return mpack_tree_parse_children(tree, node);
+
+        // fixarray
+        case 0x90: case 0x91: case 0x92: case 0x93: case 0x94: case 0x95: case 0x96: case 0x97:
+        case 0x98: case 0x99: case 0x9a: case 0x9b: case 0x9c: case 0x9d: case 0x9e: case 0x9f:
+            node->type = mpack_type_array;
+            node->len = (uint32_t)(type & ~0xf0);
+            return mpack_tree_parse_children(tree, node);
+
+        // fixstr
+        case 0xa0: case 0xa1: case 0xa2: case 0xa3: case 0xa4: case 0xa5: case 0xa6: case 0xa7:
+        case 0xa8: case 0xa9: case 0xaa: case 0xab: case 0xac: case 0xad: case 0xae: case 0xaf:
+        case 0xb0: case 0xb1: case 0xb2: case 0xb3: case 0xb4: case 0xb5: case 0xb6: case 0xb7:
+        case 0xb8: case 0xb9: case 0xba: case 0xbb: case 0xbc: case 0xbd: case 0xbe: case 0xbf:
+            node->type = mpack_type_str;
+            node->len = (uint32_t)(type & ~0xe0);
+            return mpack_tree_parse_bytes(tree, node);
+        #endif
+
+        // nil
+        case 0xc0:
+            node->type = mpack_type_nil;
+            return true;
+
+        // bool
+        case 0xc2: case 0xc3:
+            node->type = mpack_type_bool;
+            node->value.b = type & 1;
+            return true;
+
+        // bin8
+        case 0xc4:
+            node->type = mpack_type_bin;
+            if (!mpack_tree_reserve_bytes(tree, sizeof(uint8_t)))
+                return false;
+            node->len = mpack_load_u8(tree->data + tree->size + 1);
+            return mpack_tree_parse_bytes(tree, node);
+
+        // bin16
+        case 0xc5:
+            node->type = mpack_type_bin;
+            if (!mpack_tree_reserve_bytes(tree, sizeof(uint16_t)))
+                return false;
+            node->len = mpack_load_u16(tree->data + tree->size + 1);
+            return mpack_tree_parse_bytes(tree, node);
+
+        // bin32
+        case 0xc6:
+            node->type = mpack_type_bin;
+            if (!mpack_tree_reserve_bytes(tree, sizeof(uint32_t)))
+                return false;
+            node->len = mpack_load_u32(tree->data + tree->size + 1);
+            return mpack_tree_parse_bytes(tree, node);
+
+        #if MPACK_EXTENSIONS
+        // ext8
+        case 0xc7:
+            if (!mpack_tree_reserve_bytes(tree, sizeof(uint8_t)))
+                return false;
+            node->len = mpack_load_u8(tree->data + tree->size + 1);
+            return mpack_tree_parse_ext(tree, node);
+
+        // ext16
+        case 0xc8:
+            if (!mpack_tree_reserve_bytes(tree, sizeof(uint16_t)))
+                return false;
+            node->len = mpack_load_u16(tree->data + tree->size + 1);
+            return mpack_tree_parse_ext(tree, node);
+
+        // ext32
+        case 0xc9:
+            if (!mpack_tree_reserve_bytes(tree, sizeof(uint32_t)))
+                return false;
+            node->len = mpack_load_u32(tree->data + tree->size + 1);
+            return mpack_tree_parse_ext(tree, node);
+        #endif
+
+        // float
+        case 0xca:
+            #if MPACK_FLOAT
+            if (!mpack_tree_reserve_bytes(tree, sizeof(float)))
+                return false;
+            node->value.f = mpack_load_float(tree->data + tree->size + 1);
+            #else
+            if (!mpack_tree_reserve_bytes(tree, sizeof(uint32_t)))
+                return false;
+            node->value.f = mpack_load_u32(tree->data + tree->size + 1);
+            #endif
+            node->type = mpack_type_float;
+            return true;
+
+        // double
+        case 0xcb:
+            #if MPACK_DOUBLE
+            if (!mpack_tree_reserve_bytes(tree, sizeof(double)))
+                return false;
+            node->value.d = mpack_load_double(tree->data + tree->size + 1);
+            #else
+            if (!mpack_tree_reserve_bytes(tree, sizeof(uint64_t)))
+                return false;
+            node->value.d = mpack_load_u64(tree->data + tree->size + 1);
+            #endif
+            node->type = mpack_type_double;
+            return true;
+
+        // uint8
+        case 0xcc:
+            node->type = mpack_type_uint;
+            if (!mpack_tree_reserve_bytes(tree, sizeof(uint8_t)))
+                return false;
+            node->value.u = mpack_load_u8(tree->data + tree->size + 1);
+            return true;
+
+        // uint16
+        case 0xcd:
+            node->type = mpack_type_uint;
+            if (!mpack_tree_reserve_bytes(tree, sizeof(uint16_t)))
+                return false;
+            node->value.u = mpack_load_u16(tree->data + tree->size + 1);
+            return true;
+
+        // uint32
+        case 0xce:
+            node->type = mpack_type_uint;
+            if (!mpack_tree_reserve_bytes(tree, sizeof(uint32_t)))
+                return false;
+            node->value.u = mpack_load_u32(tree->data + tree->size + 1);
+            return true;
+
+        // uint64
+        case 0xcf:
+            node->type = mpack_type_uint;
+            if (!mpack_tree_reserve_bytes(tree, sizeof(uint64_t)))
+                return false;
+            node->value.u = mpack_load_u64(tree->data + tree->size + 1);
+            return true;
+
+        // int8
+        case 0xd0:
+            node->type = mpack_type_int;
+            if (!mpack_tree_reserve_bytes(tree, sizeof(int8_t)))
+                return false;
+            node->value.i = mpack_load_i8(tree->data + tree->size + 1);
+            return true;
+
+        // int16
+        case 0xd1:
+            node->type = mpack_type_int;
+            if (!mpack_tree_reserve_bytes(tree, sizeof(int16_t)))
+                return false;
+            node->value.i = mpack_load_i16(tree->data + tree->size + 1);
+            return true;
+
+        // int32
+        case 0xd2:
+            node->type = mpack_type_int;
+            if (!mpack_tree_reserve_bytes(tree, sizeof(int32_t)))
+                return false;
+            node->value.i = mpack_load_i32(tree->data + tree->size + 1);
+            return true;
+
+        // int64
+        case 0xd3:
+            node->type = mpack_type_int;
+            if (!mpack_tree_reserve_bytes(tree, sizeof(int64_t)))
+                return false;
+            node->value.i = mpack_load_i64(tree->data + tree->size + 1);
+            return true;
+
+        #if MPACK_EXTENSIONS
+        // fixext1
+        case 0xd4:
+            node->len = 1;
+            return mpack_tree_parse_ext(tree, node);
+
+        // fixext2
+        case 0xd5:
+            node->len = 2;
+            return mpack_tree_parse_ext(tree, node);
+
+        // fixext4
+        case 0xd6:
+            node->len = 4;
+            return mpack_tree_parse_ext(tree, node);
+
+        // fixext8
+        case 0xd7:
+            node->len = 8;
+            return mpack_tree_parse_ext(tree, node);
+
+        // fixext16
+        case 0xd8:
+            node->len = 16;
+            return mpack_tree_parse_ext(tree, node);
+        #endif
+
+        // str8
+        case 0xd9:
+            if (!mpack_tree_reserve_bytes(tree, sizeof(uint8_t)))
+                return false;
+            node->len = mpack_load_u8(tree->data + tree->size + 1);
+            node->type = mpack_type_str;
+            return mpack_tree_parse_bytes(tree, node);
+
+        // str16
+        case 0xda:
+            if (!mpack_tree_reserve_bytes(tree, sizeof(uint16_t)))
+                return false;
+            node->len = mpack_load_u16(tree->data + tree->size + 1);
+            node->type = mpack_type_str;
+            return mpack_tree_parse_bytes(tree, node);
+
+        // str32
+        case 0xdb:
+            if (!mpack_tree_reserve_bytes(tree, sizeof(uint32_t)))
+                return false;
+            node->len = mpack_load_u32(tree->data + tree->size + 1);
+            node->type = mpack_type_str;
+            return mpack_tree_parse_bytes(tree, node);
+
+        // array16
+        case 0xdc:
+            if (!mpack_tree_reserve_bytes(tree, sizeof(uint16_t)))
+                return false;
+            node->len = mpack_load_u16(tree->data + tree->size + 1);
+            node->type = mpack_type_array;
+            return mpack_tree_parse_children(tree, node);
+
+        // array32
+        case 0xdd:
+            if (!mpack_tree_reserve_bytes(tree, sizeof(uint32_t)))
+                return false;
+            node->len = mpack_load_u32(tree->data + tree->size + 1);
+            node->type = mpack_type_array;
+            return mpack_tree_parse_children(tree, node);
+
+        // map16
+        case 0xde:
+            if (!mpack_tree_reserve_bytes(tree, sizeof(uint16_t)))
+                return false;
+            node->len = mpack_load_u16(tree->data + tree->size + 1);
+            node->type = mpack_type_map;
+            return mpack_tree_parse_children(tree, node);
+
+        // map32
+        case 0xdf:
+            if (!mpack_tree_reserve_bytes(tree, sizeof(uint32_t)))
+                return false;
+            node->len = mpack_load_u32(tree->data + tree->size + 1);
+            node->type = mpack_type_map;
+            return mpack_tree_parse_children(tree, node);
+
+        // reserved
+        case 0xc1:
+            mpack_tree_flag_error(tree, mpack_error_invalid);
+            return false;
+
+        #if !MPACK_EXTENSIONS
+        // ext
+        case 0xc7: // fallthrough
+        case 0xc8: // fallthrough
+        case 0xc9: // fallthrough
+        // fixext
+        case 0xd4: // fallthrough
+        case 0xd5: // fallthrough
+        case 0xd6: // fallthrough
+        case 0xd7: // fallthrough
+        case 0xd8:
+            mpack_tree_flag_error(tree, mpack_error_unsupported);
+            return false;
+        #endif
+
+        #if MPACK_OPTIMIZE_FOR_SIZE
+        // any other bytes should have been handled by the infix switch
+        default:
+            break;
+        #endif
+    }
+
+    mpack_assert(0, "unreachable");
+    return false;
+}
+
+static bool mpack_tree_parse_node(mpack_tree_t* tree, mpack_node_data_t* node) {
+    mpack_log("parsing a node at position %i in level %i\n",
+            (int)tree->size, (int)tree->parser.level);
+
+    if (!mpack_tree_parse_node_contents(tree, node)) {
+        mpack_log("node parsing returned false\n");
+        return false;
+    }
+
+    tree->parser.possible_nodes_left -= tree->parser.current_node_reserved;
+
+    // The reserve for the current node does not include the initial byte
+    // previously reserved as part of its parent.
+    size_t node_size = tree->parser.current_node_reserved + 1;
+
+    // If the parsed type is a map or array, the reserve includes one byte for
+    // each child. We want to subtract these out of possible_nodes_left, but
+    // not out of the current size of the tree.
+    if (node->type == mpack_type_array)
+        node_size -= node->len;
+    else if (node->type == mpack_type_map)
+        node_size -= node->len * 2;
+    tree->size += node_size;
+
+    mpack_log("parsed a node of type %s of %i bytes and "
+            "%i additional bytes reserved for children.\n",
+            mpack_type_to_string(node->type), (int)node_size,
+            (int)tree->parser.current_node_reserved + 1 - (int)node_size);
+
+    return true;
+}
+
+/*
+ * We read nodes in a loop instead of recursively for maximum performance. The
+ * stack holds the amount of children left to read in each level of the tree.
+ * Parsing can pause and resume when more data becomes available.
+ */
+static bool mpack_tree_continue_parsing(mpack_tree_t* tree) {
+    if (mpack_tree_error(tree) != mpack_ok)
+        return false;
+
+    mpack_tree_parser_t* parser = &tree->parser;
+    mpack_assert(parser->state == mpack_tree_parse_state_in_progress);
+    mpack_log("parsing tree elements, %i bytes in buffer\n", (int)tree->data_length);
+
+    // we loop parsing nodes until the parse stack is empty. we break
+    // by returning out of the function.
+    while (true) {
+        mpack_node_data_t* node = parser->stack[parser->level].child;
+        size_t level = parser->level;
+        if (!mpack_tree_parse_node(tree, node))
+            return false;
+        --parser->stack[level].left;
+        ++parser->stack[level].child;
+
+        mpack_assert(mpack_tree_error(tree) == mpack_ok,
+                "mpack_tree_parse_node() should have returned false due to error!");
+
+        // pop empty stack levels, exiting the outer loop when the stack is empty.
+        // (we could tail-optimize containers by pre-emptively popping empty
+        // stack levels before reading the new element, this way we wouldn't
+        // have to loop. but we eventually want to use the parse stack to give
+        // better error messages that contain the location of the error, so
+        // it needs to be complete.)
+        while (parser->stack[parser->level].left == 0) {
+            if (parser->level == 0)
+                return true;
+            --parser->level;
+        }
+    }
+}
+
+static void mpack_tree_cleanup(mpack_tree_t* tree) {
+    MPACK_UNUSED(tree);
+
+    #ifdef MPACK_MALLOC
+    if (tree->parser.stack_owned) {
+        MPACK_FREE(tree->parser.stack);
+        tree->parser.stack = NULL;
+        tree->parser.stack_owned = false;
+    }
+
+    mpack_tree_page_t* page = tree->next;
+    while (page != NULL) {
+        mpack_tree_page_t* next = page->next;
+        mpack_log("freeing page %p\n", (void*)page);
+        MPACK_FREE(page);
+        page = next;
+    }
+    tree->next = NULL;
+    #endif
+}
+
+static bool mpack_tree_parse_start(mpack_tree_t* tree) {
+    if (mpack_tree_error(tree) != mpack_ok)
+        return false;
+
+    mpack_tree_parser_t* parser = &tree->parser;
+    mpack_assert(parser->state != mpack_tree_parse_state_in_progress,
+            "previous parsing was not finished!");
+
+    if (parser->state == mpack_tree_parse_state_parsed)
+        mpack_tree_cleanup(tree);
+
+    mpack_log("starting parse\n");
+    tree->parser.state = mpack_tree_parse_state_in_progress;
+    tree->parser.current_node_reserved = 0;
+
+    // check if we previously parsed a tree
+    if (tree->size > 0) {
+        #ifdef MPACK_MALLOC
+        // if we're buffered, move the remaining data back to the
+        // start of the buffer
+        // TODO: This is not ideal performance-wise. We should only move data
+        // when we need to call the fill function.
+        // TODO: We could consider shrinking the buffer here, especially if we
+        // determine that the fill function is providing less than a quarter of
+        // the buffer size or if messages take up less than a quarter of the
+        // buffer size. Maybe this should be configurable.
+        if (tree->buffer != NULL) {
+            mpack_memmove(tree->buffer, tree->buffer + tree->size, tree->data_length - tree->size);
+        }
+        else
+        #endif
+        // otherwise advance past the parsed data
+        {
+            tree->data += tree->size;
+        }
+        tree->data_length -= tree->size;
+        tree->size = 0;
+        tree->node_count = 0;
+    }
+
+    // make sure we have at least one byte available before allocating anything
+    parser->possible_nodes_left = tree->data_length;
+    if (!mpack_tree_reserve_bytes(tree, sizeof(uint8_t))) {
+        tree->parser.state = mpack_tree_parse_state_not_started;
+        return false;
+    }
+    mpack_log("parsing tree at %p starting with byte %x\n", tree->data, (uint8_t)tree->data[0]);
+    parser->possible_nodes_left -= 1;
+    tree->node_count = 1;
+
+    #ifdef MPACK_MALLOC
+    parser->stack = parser->stack_local;
+    parser->stack_owned = false;
+    parser->stack_capacity = sizeof(parser->stack_local) / sizeof(*parser->stack_local);
+
+    if (tree->pool == NULL) {
+
+        // allocate first page
+        mpack_tree_page_t* page = (mpack_tree_page_t*)MPACK_MALLOC(MPACK_PAGE_ALLOC_SIZE);
+        mpack_log("allocated initial page %p of size %i count %i\n",
+                (void*)page, (int)MPACK_PAGE_ALLOC_SIZE, (int)MPACK_NODES_PER_PAGE);
+        if (page == NULL) {
+            tree->error = mpack_error_memory;
+            return false;
+        }
+        page->next = NULL;
+        tree->next = page;
+
+        parser->nodes = page->nodes;
+        parser->nodes_left = MPACK_NODES_PER_PAGE;
+    }
+    else
+    #endif
+    {
+        // otherwise use the provided pool
+        mpack_assert(tree->pool != NULL, "no pool provided?");
+        parser->nodes = tree->pool;
+        parser->nodes_left = tree->pool_count;
+    }
+
+    tree->root = parser->nodes;
+    ++parser->nodes;
+    --parser->nodes_left;
+
+    parser->level = 0;
+    parser->stack[0].child = tree->root;
+    parser->stack[0].left = 1;
+
+    return true;
+}
+
+void mpack_tree_parse(mpack_tree_t* tree) {
+    if (mpack_tree_error(tree) != mpack_ok)
+        return;
+
+    if (tree->parser.state != mpack_tree_parse_state_in_progress) {
+        if (!mpack_tree_parse_start(tree)) {
+            mpack_tree_flag_error(tree, (tree->read_fn == NULL) ?
+                    mpack_error_invalid : mpack_error_io);
+            return;
+        }
+    }
+
+    if (!mpack_tree_continue_parsing(tree)) {
+        if (mpack_tree_error(tree) != mpack_ok)
+            return;
+
+        // We're parsing synchronously on a blocking fill function. If we
+        // didn't completely finish parsing the tree, it's an error.
+        mpack_log("tree parsing incomplete. flagging error.\n");
+        mpack_tree_flag_error(tree, (tree->read_fn == NULL) ?
+                mpack_error_invalid : mpack_error_io);
+        return;
+    }
+
+    mpack_assert(mpack_tree_error(tree) == mpack_ok);
+    mpack_assert(tree->parser.level == 0);
+    tree->parser.state = mpack_tree_parse_state_parsed;
+    mpack_log("parsed tree of %i bytes, %i bytes left\n", (int)tree->size, (int)tree->parser.possible_nodes_left);
+    mpack_log("%i nodes in final page\n", (int)tree->parser.nodes_left);
+}
+
+bool mpack_tree_try_parse(mpack_tree_t* tree) {
+    if (mpack_tree_error(tree) != mpack_ok)
+        return false;
+
+    if (tree->parser.state != mpack_tree_parse_state_in_progress)
+        if (!mpack_tree_parse_start(tree))
+            return false;
+
+    if (!mpack_tree_continue_parsing(tree))
+        return false;
+
+    mpack_assert(mpack_tree_error(tree) == mpack_ok);
+    mpack_assert(tree->parser.level == 0);
+    tree->parser.state = mpack_tree_parse_state_parsed;
+    return true;
+}
+
+
+
+/*
+ * Tree functions
+ */
+
+mpack_node_t mpack_tree_root(mpack_tree_t* tree) {
+    if (mpack_tree_error(tree) != mpack_ok)
+        return mpack_tree_nil_node(tree);
+
+    // We check that a tree was parsed successfully and assert if not. You must
+    // call mpack_tree_parse() (or mpack_tree_try_parse() with a success
+    // result) in order to access the root node.
+    if (tree->parser.state != mpack_tree_parse_state_parsed) {
+        mpack_break("Tree has not been parsed! "
+                "Did you call mpack_tree_parse() or mpack_tree_try_parse()?");
+        mpack_tree_flag_error(tree, mpack_error_bug);
+        return mpack_tree_nil_node(tree);
+    }
+
+    return mpack_node(tree, tree->root);
+}
+
+static void mpack_tree_init_clear(mpack_tree_t* tree) {
+    mpack_memset(tree, 0, sizeof(*tree));
+    tree->nil_node.type = mpack_type_nil;
+    tree->missing_node.type = mpack_type_missing;
+    tree->max_size = SIZE_MAX;
+    tree->max_nodes = SIZE_MAX;
+}
+
+#ifdef MPACK_MALLOC
+void mpack_tree_init_data(mpack_tree_t* tree, const char* data, size_t length) {
+    mpack_tree_init_clear(tree);
+
+    MPACK_STATIC_ASSERT(MPACK_NODE_PAGE_SIZE >= sizeof(mpack_tree_page_t),
+            "MPACK_NODE_PAGE_SIZE is too small");
+
+    MPACK_STATIC_ASSERT(MPACK_PAGE_ALLOC_SIZE <= MPACK_NODE_PAGE_SIZE,
+            "incorrect page rounding?");
+
+    tree->data = data;
+    tree->data_length = length;
+    tree->pool = NULL;
+    tree->pool_count = 0;
+    tree->next = NULL;
+
+    mpack_log("===========================\n");
+    mpack_log("initializing tree with data of size %i\n", (int)length);
+}
+#endif
+
+void mpack_tree_init_pool(mpack_tree_t* tree, const char* data, size_t length,
+        mpack_node_data_t* node_pool, size_t node_pool_count)
+{
+    mpack_tree_init_clear(tree);
+    #ifdef MPACK_MALLOC
+    tree->next = NULL;
+    #endif
+
+    if (node_pool_count == 0) {
+        mpack_break("initial page has no nodes!");
+        mpack_tree_flag_error(tree, mpack_error_bug);
+        return;
+    }
+
+    tree->data = data;
+    tree->data_length = length;
+    tree->pool = node_pool;
+    tree->pool_count = node_pool_count;
+
+    mpack_log("===========================\n");
+    mpack_log("initializing tree with data of size %i and pool of count %i\n",
+            (int)length, (int)node_pool_count);
+}
+
+void mpack_tree_init_error(mpack_tree_t* tree, mpack_error_t error) {
+    mpack_tree_init_clear(tree);
+    tree->error = error;
+
+    mpack_log("===========================\n");
+    mpack_log("initializing tree error state %i\n", (int)error);
+}
+
+#ifdef MPACK_MALLOC
+void mpack_tree_init_stream(mpack_tree_t* tree, mpack_tree_read_t read_fn, void* context,
+        size_t max_message_size, size_t max_message_nodes) {
+    mpack_tree_init_clear(tree);
+
+    tree->read_fn = read_fn;
+    tree->context = context;
+
+    mpack_tree_set_limits(tree, max_message_size, max_message_nodes);
+    tree->max_size = max_message_size;
+    tree->max_nodes = max_message_nodes;
+
+    mpack_log("===========================\n");
+    mpack_log("initializing tree with stream, max size %i max nodes %i\n",
+            (int)max_message_size, (int)max_message_nodes);
+}
+#endif
+
+void mpack_tree_set_limits(mpack_tree_t* tree, size_t max_message_size, size_t max_message_nodes) {
+    mpack_assert(max_message_size > 0);
+    mpack_assert(max_message_nodes > 0);
+    tree->max_size = max_message_size;
+    tree->max_nodes = max_message_nodes;
+}
+
+#if MPACK_STDIO
+typedef struct mpack_file_tree_t {
+    char* data;
+    size_t size;
+    char buffer[MPACK_BUFFER_SIZE];
+} mpack_file_tree_t;
+
+static void mpack_file_tree_teardown(mpack_tree_t* tree) {
+    mpack_file_tree_t* file_tree = (mpack_file_tree_t*)tree->context;
+    MPACK_FREE(file_tree->data);
+    MPACK_FREE(file_tree);
+}
+
+static bool mpack_file_tree_read(mpack_tree_t* tree, mpack_file_tree_t* file_tree, FILE* file, size_t max_bytes) {
+
+    // get the file size
+    errno = 0;
+    int error = 0;
+    fseek(file, 0, SEEK_END);
+    error |= errno;
+    long size = ftell(file);
+    error |= errno;
+    fseek(file, 0, SEEK_SET);
+    error |= errno;
+
+    // check for errors
+    if (error != 0 || size < 0) {
+        mpack_tree_init_error(tree, mpack_error_io);
+        return false;
+    }
+    if (size == 0) {
+        mpack_tree_init_error(tree, mpack_error_invalid);
+        return false;
+    }
+
+    // make sure the size is less than max_bytes
+    // (this mess exists to safely convert between long and size_t regardless of their widths)
+    if (max_bytes != 0 && (((uint64_t)LONG_MAX > (uint64_t)SIZE_MAX && size > (long)SIZE_MAX) || (size_t)size > max_bytes)) {
+        mpack_tree_init_error(tree, mpack_error_too_big);
+        return false;
+    }
+
+    // allocate data
+    file_tree->data = (char*)MPACK_MALLOC((size_t)size);
+    if (file_tree->data == NULL) {
+        mpack_tree_init_error(tree, mpack_error_memory);
+        return false;
+    }
+
+    // read the file
+    long total = 0;
+    while (total < size) {
+        size_t read = fread(file_tree->data + total, 1, (size_t)(size - total), file);
+        if (read <= 0) {
+            mpack_tree_init_error(tree, mpack_error_io);
+            MPACK_FREE(file_tree->data);
+            return false;
+        }
+        total += (long)read;
+    }
+
+    file_tree->size = (size_t)size;
+    return true;
+}
+
+static bool mpack_tree_file_check_max_bytes(mpack_tree_t* tree, size_t max_bytes) {
+
+    // the C STDIO family of file functions use long (e.g. ftell)
+    if (max_bytes > LONG_MAX) {
+        mpack_break("max_bytes of %" PRIu64 " is invalid, maximum is LONG_MAX", (uint64_t)max_bytes);
+        mpack_tree_init_error(tree, mpack_error_bug);
+        return false;
+    }
+
+    return true;
+}
+
+static void mpack_tree_init_stdfile_noclose(mpack_tree_t* tree, FILE* stdfile, size_t max_bytes) {
+
+    // allocate file tree
+    mpack_file_tree_t* file_tree = (mpack_file_tree_t*) MPACK_MALLOC(sizeof(mpack_file_tree_t));
+    if (file_tree == NULL) {
+        mpack_tree_init_error(tree, mpack_error_memory);
+        return;
+    }
+
+    // read all data
+    if (!mpack_file_tree_read(tree, file_tree, stdfile, max_bytes)) {
+        MPACK_FREE(file_tree);
+        return;
+    }
+
+    mpack_tree_init_data(tree, file_tree->data, file_tree->size);
+    mpack_tree_set_context(tree, file_tree);
+    mpack_tree_set_teardown(tree, mpack_file_tree_teardown);
+}
+
+void mpack_tree_init_stdfile(mpack_tree_t* tree, FILE* stdfile, size_t max_bytes, bool close_when_done) {
+    if (!mpack_tree_file_check_max_bytes(tree, max_bytes))
+        return;
+
+    mpack_tree_init_stdfile_noclose(tree, stdfile, max_bytes);
+
+    if (close_when_done)
+        fclose(stdfile);
+}
+
+void mpack_tree_init_filename(mpack_tree_t* tree, const char* filename, size_t max_bytes) {
+    if (!mpack_tree_file_check_max_bytes(tree, max_bytes))
+        return;
+
+    // open the file
+    FILE* file = fopen(filename, "rb");
+    if (!file) {
+        mpack_tree_init_error(tree, mpack_error_io);
+        return;
+    }
+
+    mpack_tree_init_stdfile(tree, file, max_bytes, true);
+}
+#endif
+
+mpack_error_t mpack_tree_destroy(mpack_tree_t* tree) {
+    mpack_tree_cleanup(tree);
+
+    #ifdef MPACK_MALLOC
+    if (tree->buffer)
+        MPACK_FREE(tree->buffer);
+    #endif
+
+    if (tree->teardown)
+        tree->teardown(tree);
+    tree->teardown = NULL;
+
+    return tree->error;
+}
+
+void mpack_tree_flag_error(mpack_tree_t* tree, mpack_error_t error) {
+    if (tree->error == mpack_ok) {
+        mpack_log("tree %p setting error %i: %s\n", (void*)tree, (int)error, mpack_error_to_string(error));
+        tree->error = error;
+        if (tree->error_fn)
+            tree->error_fn(tree, error);
+    }
+
+}
+
+
+
+/*
+ * Node misc functions
+ */
+
+void mpack_node_flag_error(mpack_node_t node, mpack_error_t error) {
+    mpack_tree_flag_error(node.tree, error);
+}
+
+mpack_tag_t mpack_node_tag(mpack_node_t node) {
+    if (mpack_node_error(node) != mpack_ok)
+        return mpack_tag_nil();
+
+    mpack_tag_t tag = MPACK_TAG_ZERO;
+
+    tag.type = node.data->type;
+    switch (node.data->type) {
+        case mpack_type_missing:
+            // If a node is missing, I don't know if it makes sense to ask for
+            // a tag for it. We'll return a missing tag to match the missing
+            // node I guess, but attempting to use the tag for anything (like
+            // writing it for example) will flag mpack_error_bug.
+            break;
+        case mpack_type_nil:                                            break;
+        case mpack_type_bool:    tag.v.b = node.data->value.b;          break;
+        case mpack_type_float:   tag.v.f = node.data->value.f;          break;
+        case mpack_type_double:  tag.v.d = node.data->value.d;          break;
+        case mpack_type_int:     tag.v.i = node.data->value.i;          break;
+        case mpack_type_uint:    tag.v.u = node.data->value.u;          break;
+
+        case mpack_type_str:     tag.v.l = node.data->len;     break;
+        case mpack_type_bin:     tag.v.l = node.data->len;     break;
+
+        #if MPACK_EXTENSIONS
+        case mpack_type_ext:
+            tag.v.l = node.data->len;
+            tag.exttype = mpack_node_exttype_unchecked(node);
+            break;
+        #endif
+
+        case mpack_type_array:   tag.v.n = node.data->len;  break;
+        case mpack_type_map:     tag.v.n = node.data->len;  break;
+
+        default:
+            mpack_assert(0, "unrecognized type %i", (int)node.data->type);
+            break;
+    }
+    return tag;
+}
+
+#if MPACK_DEBUG && MPACK_STDIO
+static void mpack_node_print_element(mpack_node_t node, mpack_print_t* print, size_t depth) {
+    mpack_node_data_t* data = node.data;
+    size_t i,j;
+    switch (data->type) {
+        case mpack_type_str:
+            {
+                mpack_print_append_cstr(print, "\"");
+                const char* bytes = mpack_node_data_unchecked(node);
+                for (i = 0; i < data->len; ++i) {
+                    char c = bytes[i];
+                    switch (c) {
+                        case '\n': mpack_print_append_cstr(print, "\\n"); break;
+                        case '\\': mpack_print_append_cstr(print, "\\\\"); break;
+                        case '"': mpack_print_append_cstr(print, "\\\""); break;
+                        default: mpack_print_append(print, &c, 1); break;
+                    }
+                }
+                mpack_print_append_cstr(print, "\"");
+            }
+            break;
+
+        case mpack_type_array:
+            mpack_print_append_cstr(print, "[\n");
+            for (i = 0; i < data->len; ++i) {
+                for (j = 0; j < depth + 1; ++j)
+                    mpack_print_append_cstr(print, "    ");
+                mpack_node_print_element(mpack_node_array_at(node, i), print, depth + 1);
+                if (i != data->len - 1)
+                    mpack_print_append_cstr(print, ",");
+                mpack_print_append_cstr(print, "\n");
+            }
+            for (i = 0; i < depth; ++i)
+                mpack_print_append_cstr(print, "    ");
+            mpack_print_append_cstr(print, "]");
+            break;
+
+        case mpack_type_map:
+            mpack_print_append_cstr(print, "{\n");
+            for (i = 0; i < data->len; ++i) {
+                for (j = 0; j < depth + 1; ++j)
+                    mpack_print_append_cstr(print, "    ");
+                mpack_node_print_element(mpack_node_map_key_at(node, i), print, depth + 1);
+                mpack_print_append_cstr(print, ": ");
+                mpack_node_print_element(mpack_node_map_value_at(node, i), print, depth + 1);
+                if (i != data->len - 1)
+                    mpack_print_append_cstr(print, ",");
+                mpack_print_append_cstr(print, "\n");
+            }
+            for (i = 0; i < depth; ++i)
+                mpack_print_append_cstr(print, "    ");
+            mpack_print_append_cstr(print, "}");
+            break;
+
+        default:
+            {
+                const char* prefix = NULL;
+                size_t prefix_length = 0;
+                if (mpack_node_type(node) == mpack_type_bin
+                        #if MPACK_EXTENSIONS
+                        || mpack_node_type(node) == mpack_type_ext
+                        #endif
+                ) {
+                    prefix = mpack_node_data(node);
+                    prefix_length = mpack_node_data_len(node);
+                }
+
+                char buf[256];
+                mpack_tag_t tag = mpack_node_tag(node);
+                mpack_tag_debug_pseudo_json(tag, buf, sizeof(buf), prefix, prefix_length);
+                mpack_print_append_cstr(print, buf);
+            }
+            break;
+    }
+}
+
+void mpack_node_print_to_buffer(mpack_node_t node, char* buffer, size_t buffer_size) {
+    if (buffer_size == 0) {
+        mpack_assert(false, "buffer size is zero!");
+        return;
+    }
+
+    mpack_print_t print;
+    mpack_memset(&print, 0, sizeof(print));
+    print.buffer = buffer;
+    print.size = buffer_size;
+    mpack_node_print_element(node, &print, 0);
+    mpack_print_append(&print, "",  1); // null-terminator
+    mpack_print_flush(&print);
+
+    // we always make sure there's a null-terminator at the end of the buffer
+    // in case we ran out of space.
+    print.buffer[print.size - 1] = '\0';
+}
+
+void mpack_node_print_to_callback(mpack_node_t node, mpack_print_callback_t callback, void* context) {
+    char buffer[1024];
+    mpack_print_t print;
+    mpack_memset(&print, 0, sizeof(print));
+    print.buffer = buffer;
+    print.size = sizeof(buffer);
+    print.callback = callback;
+    print.context = context;
+    mpack_node_print_element(node, &print, 0);
+    mpack_print_flush(&print);
+}
+
+void mpack_node_print_to_file(mpack_node_t node, FILE* file) {
+    mpack_assert(file != NULL, "file is NULL");
+
+    char buffer[1024];
+    mpack_print_t print;
+    mpack_memset(&print, 0, sizeof(print));
+    print.buffer = buffer;
+    print.size = sizeof(buffer);
+    print.callback = &mpack_print_file_callback;
+    print.context = file;
+
+    size_t depth = 2;
+    size_t i;
+    for (i = 0; i < depth; ++i)
+        mpack_print_append_cstr(&print, "    ");
+    mpack_node_print_element(node, &print, depth);
+    mpack_print_append_cstr(&print, "\n");
+    mpack_print_flush(&print);
+}
+#endif
+
+
+
+/*
+ * Node Value Functions
+ */
+
+#if MPACK_EXTENSIONS
+mpack_timestamp_t mpack_node_timestamp(mpack_node_t node) {
+    mpack_timestamp_t timestamp = {0, 0};
+
+    // we'll let mpack_node_exttype() do most checks
+    if (mpack_node_exttype(node) != MPACK_EXTTYPE_TIMESTAMP) {
+        mpack_log("exttype %i\n", mpack_node_exttype(node));
+        mpack_node_flag_error(node, mpack_error_type);
+        return timestamp;
+    }
+
+    const char* p = mpack_node_data_unchecked(node);
+
+    switch (node.data->len) {
+        case 4:
+            timestamp.nanoseconds = 0;
+            timestamp.seconds = mpack_load_u32(p);
+            break;
+
+        case 8: {
+            uint64_t value = mpack_load_u64(p);
+            timestamp.nanoseconds = (uint32_t)(value >> 34);
+            timestamp.seconds = value & ((MPACK_UINT64_C(1) << 34) - 1);
+            break;
+        }
+
+        case 12:
+            timestamp.nanoseconds = mpack_load_u32(p);
+            timestamp.seconds = mpack_load_i64(p + 4);
+            break;
+
+        default:
+            mpack_tree_flag_error(node.tree, mpack_error_invalid);
+            return timestamp;
+    }
+
+    if (timestamp.nanoseconds > MPACK_TIMESTAMP_NANOSECONDS_MAX) {
+        mpack_tree_flag_error(node.tree, mpack_error_invalid);
+        mpack_timestamp_t zero = {0, 0};
+        return zero;
+    }
+
+    return timestamp;
+}
+
+int64_t mpack_node_timestamp_seconds(mpack_node_t node) {
+    return mpack_node_timestamp(node).seconds;
+}
+
+uint32_t mpack_node_timestamp_nanoseconds(mpack_node_t node) {
+    return mpack_node_timestamp(node).nanoseconds;
+}
+#endif
+
+
+
+/*
+ * Node Data Functions
+ */
+
+void mpack_node_check_utf8(mpack_node_t node) {
+    if (mpack_node_error(node) != mpack_ok)
+        return;
+    mpack_node_data_t* data = node.data;
+    if (data->type != mpack_type_str || !mpack_utf8_check(mpack_node_data_unchecked(node), data->len))
+        mpack_node_flag_error(node, mpack_error_type);
+}
+
+void mpack_node_check_utf8_cstr(mpack_node_t node) {
+    if (mpack_node_error(node) != mpack_ok)
+        return;
+    mpack_node_data_t* data = node.data;
+    if (data->type != mpack_type_str || !mpack_utf8_check_no_null(mpack_node_data_unchecked(node), data->len))
+        mpack_node_flag_error(node, mpack_error_type);
+}
+
+size_t mpack_node_copy_data(mpack_node_t node, char* buffer, size_t bufsize) {
+    if (mpack_node_error(node) != mpack_ok)
+        return 0;
+
+    mpack_assert(bufsize == 0 || buffer != NULL, "buffer is NULL for maximum of %i bytes", (int)bufsize);
+
+    mpack_type_t type = node.data->type;
+    if (type != mpack_type_str && type != mpack_type_bin
+            #if MPACK_EXTENSIONS
+            && type != mpack_type_ext
+            #endif
+    ) {
+        mpack_node_flag_error(node, mpack_error_type);
+        return 0;
+    }
+
+    if (node.data->len > bufsize) {
+        mpack_node_flag_error(node, mpack_error_too_big);
+        return 0;
+    }
+
+    mpack_memcpy(buffer, mpack_node_data_unchecked(node), node.data->len);
+    return (size_t)node.data->len;
+}
+
+size_t mpack_node_copy_utf8(mpack_node_t node, char* buffer, size_t bufsize) {
+    if (mpack_node_error(node) != mpack_ok)
+        return 0;
+
+    mpack_assert(bufsize == 0 || buffer != NULL, "buffer is NULL for maximum of %i bytes", (int)bufsize);
+
+    mpack_type_t type = node.data->type;
+    if (type != mpack_type_str) {
+        mpack_node_flag_error(node, mpack_error_type);
+        return 0;
+    }
+
+    if (node.data->len > bufsize) {
+        mpack_node_flag_error(node, mpack_error_too_big);
+        return 0;
+    }
+
+    if (!mpack_utf8_check(mpack_node_data_unchecked(node), node.data->len)) {
+        mpack_node_flag_error(node, mpack_error_type);
+        return 0;
+    }
+
+    mpack_memcpy(buffer, mpack_node_data_unchecked(node), node.data->len);
+    return (size_t)node.data->len;
+}
+
+void mpack_node_copy_cstr(mpack_node_t node, char* buffer, size_t bufsize) {
+
+    // we can't break here because the error isn't recoverable; we
+    // have to add a null-terminator.
+    mpack_assert(buffer != NULL, "buffer is NULL");
+    mpack_assert(bufsize >= 1, "buffer size is zero; you must have room for at least a null-terminator");
+
+    if (mpack_node_error(node) != mpack_ok) {
+        buffer[0] = '\0';
+        return;
+    }
+
+    if (node.data->type != mpack_type_str) {
+        buffer[0] = '\0';
+        mpack_node_flag_error(node, mpack_error_type);
+        return;
+    }
+
+    if (node.data->len > bufsize - 1) {
+        buffer[0] = '\0';
+        mpack_node_flag_error(node, mpack_error_too_big);
+        return;
+    }
+
+    if (!mpack_str_check_no_null(mpack_node_data_unchecked(node), node.data->len)) {
+        buffer[0] = '\0';
+        mpack_node_flag_error(node, mpack_error_type);
+        return;
+    }
+
+    mpack_memcpy(buffer, mpack_node_data_unchecked(node), node.data->len);
+    buffer[node.data->len] = '\0';
+}
+
+void mpack_node_copy_utf8_cstr(mpack_node_t node, char* buffer, size_t bufsize) {
+
+    // we can't break here because the error isn't recoverable; we
+    // have to add a null-terminator.
+    mpack_assert(buffer != NULL, "buffer is NULL");
+    mpack_assert(bufsize >= 1, "buffer size is zero; you must have room for at least a null-terminator");
+
+    if (mpack_node_error(node) != mpack_ok) {
+        buffer[0] = '\0';
+        return;
+    }
+
+    if (node.data->type != mpack_type_str) {
+        buffer[0] = '\0';
+        mpack_node_flag_error(node, mpack_error_type);
+        return;
+    }
+
+    if (node.data->len > bufsize - 1) {
+        buffer[0] = '\0';
+        mpack_node_flag_error(node, mpack_error_too_big);
+        return;
+    }
+
+    if (!mpack_utf8_check_no_null(mpack_node_data_unchecked(node), node.data->len)) {
+        buffer[0] = '\0';
+        mpack_node_flag_error(node, mpack_error_type);
+        return;
+    }
+
+    mpack_memcpy(buffer, mpack_node_data_unchecked(node), node.data->len);
+    buffer[node.data->len] = '\0';
+}
+
+#ifdef MPACK_MALLOC
+char* mpack_node_data_alloc(mpack_node_t node, size_t maxlen) {
+    if (mpack_node_error(node) != mpack_ok)
+        return NULL;
+
+    // make sure this is a valid data type
+    mpack_type_t type = node.data->type;
+    if (type != mpack_type_str && type != mpack_type_bin
+            #if MPACK_EXTENSIONS
+            && type != mpack_type_ext
+            #endif
+    ) {
+        mpack_node_flag_error(node, mpack_error_type);
+        return NULL;
+    }
+
+    if (node.data->len > maxlen) {
+        mpack_node_flag_error(node, mpack_error_too_big);
+        return NULL;
+    }
+
+    char* ret = (char*) MPACK_MALLOC((size_t)node.data->len);
+    if (ret == NULL) {
+        mpack_node_flag_error(node, mpack_error_memory);
+        return NULL;
+    }
+
+    mpack_memcpy(ret, mpack_node_data_unchecked(node), node.data->len);
+    return ret;
+}
+
+char* mpack_node_cstr_alloc(mpack_node_t node, size_t maxlen) {
+    if (mpack_node_error(node) != mpack_ok)
+        return NULL;
+
+    // make sure maxlen makes sense
+    if (maxlen < 1) {
+        mpack_break("maxlen is zero; you must have room for at least a null-terminator");
+        mpack_node_flag_error(node, mpack_error_bug);
+        return NULL;
+    }
+
+    if (node.data->type != mpack_type_str) {
+        mpack_node_flag_error(node, mpack_error_type);
+        return NULL;
+    }
+
+    if (node.data->len > maxlen - 1) {
+        mpack_node_flag_error(node, mpack_error_too_big);
+        return NULL;
+    }
+
+    if (!mpack_str_check_no_null(mpack_node_data_unchecked(node), node.data->len)) {
+        mpack_node_flag_error(node, mpack_error_type);
+        return NULL;
+    }
+
+    char* ret = (char*) MPACK_MALLOC((size_t)(node.data->len + 1));
+    if (ret == NULL) {
+        mpack_node_flag_error(node, mpack_error_memory);
+        return NULL;
+    }
+
+    mpack_memcpy(ret, mpack_node_data_unchecked(node), node.data->len);
+    ret[node.data->len] = '\0';
+    return ret;
+}
+
+char* mpack_node_utf8_cstr_alloc(mpack_node_t node, size_t maxlen) {
+    if (mpack_node_error(node) != mpack_ok)
+        return NULL;
+
+    // make sure maxlen makes sense
+    if (maxlen < 1) {
+        mpack_break("maxlen is zero; you must have room for at least a null-terminator");
+        mpack_node_flag_error(node, mpack_error_bug);
+        return NULL;
+    }
+
+    if (node.data->type != mpack_type_str) {
+        mpack_node_flag_error(node, mpack_error_type);
+        return NULL;
+    }
+
+    if (node.data->len > maxlen - 1) {
+        mpack_node_flag_error(node, mpack_error_too_big);
+        return NULL;
+    }
+
+    if (!mpack_utf8_check_no_null(mpack_node_data_unchecked(node), node.data->len)) {
+        mpack_node_flag_error(node, mpack_error_type);
+        return NULL;
+    }
+
+    char* ret = (char*) MPACK_MALLOC((size_t)(node.data->len + 1));
+    if (ret == NULL) {
+        mpack_node_flag_error(node, mpack_error_memory);
+        return NULL;
+    }
+
+    mpack_memcpy(ret, mpack_node_data_unchecked(node), node.data->len);
+    ret[node.data->len] = '\0';
+    return ret;
+}
+#endif
+
+
+/*
+ * Compound Node Functions
+ */
+
+static mpack_node_data_t* mpack_node_map_int_impl(mpack_node_t node, int64_t num) {
+    if (mpack_node_error(node) != mpack_ok)
+        return NULL;
+
+    if (node.data->type != mpack_type_map) {
+        mpack_node_flag_error(node, mpack_error_type);
+        return NULL;
+    }
+
+    mpack_node_data_t* found = NULL;
+
+    size_t i;
+    for (i = 0; i < node.data->len; ++i) {
+        mpack_node_data_t* key = mpack_node_child(node, i * 2);
+
+        if ((key->type == mpack_type_int && key->value.i == num) ||
+            (key->type == mpack_type_uint && num >= 0 && key->value.u == (uint64_t)num))
+        {
+            if (found) {
+                mpack_node_flag_error(node, mpack_error_data);
+                return NULL;
+            }
+            found = mpack_node_child(node, i * 2 + 1);
+        }
+    }
+
+    if (found)
+        return found;
+
+    return NULL;
+}
+
+static mpack_node_data_t* mpack_node_map_uint_impl(mpack_node_t node, uint64_t num) {
+    if (mpack_node_error(node) != mpack_ok)
+        return NULL;
+
+    if (node.data->type != mpack_type_map) {
+        mpack_node_flag_error(node, mpack_error_type);
+        return NULL;
+    }
+
+    mpack_node_data_t* found = NULL;
+
+    size_t i;
+    for (i = 0; i < node.data->len; ++i) {
+        mpack_node_data_t* key = mpack_node_child(node, i * 2);
+
+        if ((key->type == mpack_type_uint && key->value.u == num) ||
+            (key->type == mpack_type_int && key->value.i >= 0 && (uint64_t)key->value.i == num))
+        {
+            if (found) {
+                mpack_node_flag_error(node, mpack_error_data);
+                return NULL;
+            }
+            found = mpack_node_child(node, i * 2 + 1);
+        }
+    }
+
+    if (found)
+        return found;
+
+    return NULL;
+}
+
+static mpack_node_data_t* mpack_node_map_str_impl(mpack_node_t node, const char* str, size_t length) {
+    if (mpack_node_error(node) != mpack_ok)
+        return NULL;
+
+    mpack_assert(length == 0 || str != NULL, "str of length %i is NULL", (int)length);
+
+    if (node.data->type != mpack_type_map) {
+        mpack_node_flag_error(node, mpack_error_type);
+        return NULL;
+    }
+
+    mpack_tree_t* tree = node.tree;
+    mpack_node_data_t* found = NULL;
+
+    size_t i;
+    for (i = 0; i < node.data->len; ++i) {
+        mpack_node_data_t* key = mpack_node_child(node, i * 2);
+
+        if (key->type == mpack_type_str && key->len == length &&
+                mpack_memcmp(str, mpack_node_data_unchecked(mpack_node(tree, key)), length) == 0) {
+            if (found) {
+                mpack_node_flag_error(node, mpack_error_data);
+                return NULL;
+            }
+            found = mpack_node_child(node, i * 2 + 1);
+        }
+    }
+
+    if (found)
+        return found;
+
+    return NULL;
+}
+
+static mpack_node_t mpack_node_wrap_lookup(mpack_tree_t* tree, mpack_node_data_t* data) {
+    if (!data) {
+        if (tree->error == mpack_ok)
+            mpack_tree_flag_error(tree, mpack_error_data);
+        return mpack_tree_nil_node(tree);
+    }
+    return mpack_node(tree, data);
+}
+
+static mpack_node_t mpack_node_wrap_lookup_optional(mpack_tree_t* tree, mpack_node_data_t* data) {
+    if (!data) {
+        if (tree->error == mpack_ok)
+            return mpack_tree_missing_node(tree);
+        return mpack_tree_nil_node(tree);
+    }
+    return mpack_node(tree, data);
+}
+
+mpack_node_t mpack_node_map_int(mpack_node_t node, int64_t num) {
+    return mpack_node_wrap_lookup(node.tree, mpack_node_map_int_impl(node, num));
+}
+
+mpack_node_t mpack_node_map_int_optional(mpack_node_t node, int64_t num) {
+    return mpack_node_wrap_lookup_optional(node.tree, mpack_node_map_int_impl(node, num));
+}
+
+mpack_node_t mpack_node_map_uint(mpack_node_t node, uint64_t num) {
+    return mpack_node_wrap_lookup(node.tree, mpack_node_map_uint_impl(node, num));
+}
+
+mpack_node_t mpack_node_map_uint_optional(mpack_node_t node, uint64_t num) {
+    return mpack_node_wrap_lookup_optional(node.tree, mpack_node_map_uint_impl(node, num));
+}
+
+mpack_node_t mpack_node_map_str(mpack_node_t node, const char* str, size_t length) {
+    return mpack_node_wrap_lookup(node.tree, mpack_node_map_str_impl(node, str, length));
+}
+
+mpack_node_t mpack_node_map_str_optional(mpack_node_t node, const char* str, size_t length) {
+    return mpack_node_wrap_lookup_optional(node.tree, mpack_node_map_str_impl(node, str, length));
+}
+
+mpack_node_t mpack_node_map_cstr(mpack_node_t node, const char* cstr) {
+    mpack_assert(cstr != NULL, "cstr is NULL");
+    return mpack_node_map_str(node, cstr, mpack_strlen(cstr));
+}
+
+mpack_node_t mpack_node_map_cstr_optional(mpack_node_t node, const char* cstr) {
+    mpack_assert(cstr != NULL, "cstr is NULL");
+    return mpack_node_map_str_optional(node, cstr, mpack_strlen(cstr));
+}
+
+bool mpack_node_map_contains_int(mpack_node_t node, int64_t num) {
+    return mpack_node_map_int_impl(node, num) != NULL;
+}
+
+bool mpack_node_map_contains_uint(mpack_node_t node, uint64_t num) {
+    return mpack_node_map_uint_impl(node, num) != NULL;
+}
+
+bool mpack_node_map_contains_str(mpack_node_t node, const char* str, size_t length) {
+    return mpack_node_map_str_impl(node, str, length) != NULL;
+}
+
+bool mpack_node_map_contains_cstr(mpack_node_t node, const char* cstr) {
+    mpack_assert(cstr != NULL, "cstr is NULL");
+    return mpack_node_map_contains_str(node, cstr, mpack_strlen(cstr));
+}
+
+size_t mpack_node_enum_optional(mpack_node_t node, const char* strings[], size_t count) {
+    if (mpack_node_error(node) != mpack_ok)
+        return count;
+
+    // the value is only recognized if it is a string
+    if (mpack_node_type(node) != mpack_type_str)
+        return count;
+
+    // fetch the string
+    const char* key = mpack_node_str(node);
+    size_t keylen = mpack_node_strlen(node);
+    mpack_assert(mpack_node_error(node) == mpack_ok, "these should not fail");
+
+    // find what key it matches
+    size_t i;
+    for (i = 0; i < count; ++i) {
+        const char* other = strings[i];
+        size_t otherlen = mpack_strlen(other);
+        if (keylen == otherlen && mpack_memcmp(key, other, keylen) == 0)
+            return i;
+    }
+
+    // no matches
+    return count;
+}
+
+size_t mpack_node_enum(mpack_node_t node, const char* strings[], size_t count) {
+    size_t value = mpack_node_enum_optional(node, strings, count);
+    if (value == count)
+        mpack_node_flag_error(node, mpack_error_type);
+    return value;
+}
+
+mpack_type_t mpack_node_type(mpack_node_t node) {
+    if (mpack_node_error(node) != mpack_ok)
+        return mpack_type_nil;
+    return node.data->type;
+}
+
+bool mpack_node_is_nil(mpack_node_t node) {
+    if (mpack_node_error(node) != mpack_ok) {
+        // All nodes are treated as nil nodes when we are in error.
+        return true;
+    }
+    return node.data->type == mpack_type_nil;
+}
+
+bool mpack_node_is_missing(mpack_node_t node) {
+    if (mpack_node_error(node) != mpack_ok) {
+        // errors still return nil nodes, not missing nodes.
+        return false;
+    }
+    return node.data->type == mpack_type_missing;
+}
+
+void mpack_node_nil(mpack_node_t node) {
+    if (mpack_node_error(node) != mpack_ok)
+        return;
+    if (node.data->type != mpack_type_nil)
+        mpack_node_flag_error(node, mpack_error_type);
+}
+
+void mpack_node_missing(mpack_node_t node) {
+    if (mpack_node_error(node) != mpack_ok)
+        return;
+    if (node.data->type != mpack_type_missing)
+        mpack_node_flag_error(node, mpack_error_type);
+}
+
+bool mpack_node_bool(mpack_node_t node) {
+    if (mpack_node_error(node) != mpack_ok)
+        return false;
+
+    if (node.data->type == mpack_type_bool)
+        return node.data->value.b;
+
+    mpack_node_flag_error(node, mpack_error_type);
+    return false;
+}
+
+void mpack_node_true(mpack_node_t node) {
+    if (mpack_node_bool(node) != true)
+        mpack_node_flag_error(node, mpack_error_type);
+}
+
+void mpack_node_false(mpack_node_t node) {
+    if (mpack_node_bool(node) != false)
+        mpack_node_flag_error(node, mpack_error_type);
+}
+
+uint8_t mpack_node_u8(mpack_node_t node) {
+    if (mpack_node_error(node) != mpack_ok)
+        return 0;
+
+    if (node.data->type == mpack_type_uint) {
+        if (node.data->value.u <= MPACK_UINT8_MAX)
+            return (uint8_t)node.data->value.u;
+    } else if (node.data->type == mpack_type_int) {
+        if (node.data->value.i >= 0 && node.data->value.i <= MPACK_UINT8_MAX)
+            return (uint8_t)node.data->value.i;
+    }
+
+    mpack_node_flag_error(node, mpack_error_type);
+    return 0;
+}
+
+int8_t mpack_node_i8(mpack_node_t node) {
+    if (mpack_node_error(node) != mpack_ok)
+        return 0;
+
+    if (node.data->type == mpack_type_uint) {
+        if (node.data->value.u <= MPACK_INT8_MAX)
+            return (int8_t)node.data->value.u;
+    } else if (node.data->type == mpack_type_int) {
+        if (node.data->value.i >= MPACK_INT8_MIN && node.data->value.i <= MPACK_INT8_MAX)
+            return (int8_t)node.data->value.i;
+    }
+
+    mpack_node_flag_error(node, mpack_error_type);
+    return 0;
+}
+
+uint16_t mpack_node_u16(mpack_node_t node) {
+    if (mpack_node_error(node) != mpack_ok)
+        return 0;
+
+    if (node.data->type == mpack_type_uint) {
+        if (node.data->value.u <= MPACK_UINT16_MAX)
+            return (uint16_t)node.data->value.u;
+    } else if (node.data->type == mpack_type_int) {
+        if (node.data->value.i >= 0 && node.data->value.i <= MPACK_UINT16_MAX)
+            return (uint16_t)node.data->value.i;
+    }
+
+    mpack_node_flag_error(node, mpack_error_type);
+    return 0;
+}
+
+int16_t mpack_node_i16(mpack_node_t node) {
+    if (mpack_node_error(node) != mpack_ok)
+        return 0;
+
+    if (node.data->type == mpack_type_uint) {
+        if (node.data->value.u <= MPACK_INT16_MAX)
+            return (int16_t)node.data->value.u;
+    } else if (node.data->type == mpack_type_int) {
+        if (node.data->value.i >= MPACK_INT16_MIN && node.data->value.i <= MPACK_INT16_MAX)
+            return (int16_t)node.data->value.i;
+    }
+
+    mpack_node_flag_error(node, mpack_error_type);
+    return 0;
+}
+
+uint32_t mpack_node_u32(mpack_node_t node) {
+    if (mpack_node_error(node) != mpack_ok)
+        return 0;
+
+    if (node.data->type == mpack_type_uint) {
+        if (node.data->value.u <= MPACK_UINT32_MAX)
+            return (uint32_t)node.data->value.u;
+    } else if (node.data->type == mpack_type_int) {
+        if (node.data->value.i >= 0 && node.data->value.i <= MPACK_UINT32_MAX)
+            return (uint32_t)node.data->value.i;
+    }
+
+    mpack_node_flag_error(node, mpack_error_type);
+    return 0;
+}
+
+int32_t mpack_node_i32(mpack_node_t node) {
+    if (mpack_node_error(node) != mpack_ok)
+        return 0;
+
+    if (node.data->type == mpack_type_uint) {
+        if (node.data->value.u <= MPACK_INT32_MAX)
+            return (int32_t)node.data->value.u;
+    } else if (node.data->type == mpack_type_int) {
+        if (node.data->value.i >= MPACK_INT32_MIN && node.data->value.i <= MPACK_INT32_MAX)
+            return (int32_t)node.data->value.i;
+    }
+
+    mpack_node_flag_error(node, mpack_error_type);
+    return 0;
+}
+
+uint64_t mpack_node_u64(mpack_node_t node) {
+    if (mpack_node_error(node) != mpack_ok)
+        return 0;
+
+    if (node.data->type == mpack_type_uint) {
+        return node.data->value.u;
+    } else if (node.data->type == mpack_type_int) {
+        if (node.data->value.i >= 0)
+            return (uint64_t)node.data->value.i;
+    }
+
+    mpack_node_flag_error(node, mpack_error_type);
+    return 0;
+}
+
+int64_t mpack_node_i64(mpack_node_t node) {
+    if (mpack_node_error(node) != mpack_ok)
+        return 0;
+
+    if (node.data->type == mpack_type_uint) {
+        if (node.data->value.u <= (uint64_t)MPACK_INT64_MAX)
+            return (int64_t)node.data->value.u;
+    } else if (node.data->type == mpack_type_int) {
+        return node.data->value.i;
+    }
+
+    mpack_node_flag_error(node, mpack_error_type);
+    return 0;
+}
+
+unsigned int mpack_node_uint(mpack_node_t node) {
+
+    // This should be true at compile-time, so this just wraps the 32-bit function.
+    if (sizeof(unsigned int) == 4)
+        return (unsigned int)mpack_node_u32(node);
+
+    // Otherwise we use u64 and check the range.
+    uint64_t val = mpack_node_u64(node);
+    if (val <= MPACK_UINT_MAX)
+        return (unsigned int)val;
+
+    mpack_node_flag_error(node, mpack_error_type);
+    return 0;
+}
+
+int mpack_node_int(mpack_node_t node) {
+
+    // This should be true at compile-time, so this just wraps the 32-bit function.
+    if (sizeof(int) == 4)
+        return (int)mpack_node_i32(node);
+
+    // Otherwise we use i64 and check the range.
+    int64_t val = mpack_node_i64(node);
+    if (val >= MPACK_INT_MIN && val <= MPACK_INT_MAX)
+        return (int)val;
+
+    mpack_node_flag_error(node, mpack_error_type);
+    return 0;
+}
+
+#if MPACK_FLOAT
+float mpack_node_float(mpack_node_t node) {
+    if (mpack_node_error(node) != mpack_ok)
+        return 0.0f;
+
+    if (node.data->type == mpack_type_uint)
+        return (float)node.data->value.u;
+    if (node.data->type == mpack_type_int)
+        return (float)node.data->value.i;
+    if (node.data->type == mpack_type_float)
+        return node.data->value.f;
+
+    if (node.data->type == mpack_type_double) {
+        #if MPACK_DOUBLE
+        return (float)node.data->value.d;
+        #else
+        return mpack_shorten_raw_double_to_float(node.data->value.d);
+        #endif
+    }
+
+    mpack_node_flag_error(node, mpack_error_type);
+    return 0.0f;
+}
+#endif
+
+#if MPACK_DOUBLE
+double mpack_node_double(mpack_node_t node) {
+    if (mpack_node_error(node) != mpack_ok)
+        return 0.0;
+
+    if (node.data->type == mpack_type_uint)
+        return (double)node.data->value.u;
+    else if (node.data->type == mpack_type_int)
+        return (double)node.data->value.i;
+    else if (node.data->type == mpack_type_float)
+        return (double)node.data->value.f;
+    else if (node.data->type == mpack_type_double)
+        return node.data->value.d;
+
+    mpack_node_flag_error(node, mpack_error_type);
+    return 0.0;
+}
+#endif
+
+#if MPACK_FLOAT
+float mpack_node_float_strict(mpack_node_t node) {
+    if (mpack_node_error(node) != mpack_ok)
+        return 0.0f;
+
+    if (node.data->type == mpack_type_float)
+        return node.data->value.f;
+
+    mpack_node_flag_error(node, mpack_error_type);
+    return 0.0f;
+}
+#endif
+
+#if MPACK_DOUBLE
+double mpack_node_double_strict(mpack_node_t node) {
+    if (mpack_node_error(node) != mpack_ok)
+        return 0.0;
+
+    if (node.data->type == mpack_type_float)
+        return (double)node.data->value.f;
+    else if (node.data->type == mpack_type_double)
+        return node.data->value.d;
+
+    mpack_node_flag_error(node, mpack_error_type);
+    return 0.0;
+}
+#endif
+
+#if !MPACK_FLOAT
+uint32_t mpack_node_raw_float(mpack_node_t node) {
+    if (mpack_node_error(node) != mpack_ok)
+        return 0;
+
+    if (node.data->type == mpack_type_float)
+        return node.data->value.f;
+
+    mpack_node_flag_error(node, mpack_error_type);
+    return 0;
+}
+#endif
+
+#if !MPACK_DOUBLE
+uint64_t mpack_node_raw_double(mpack_node_t node) {
+    if (mpack_node_error(node) != mpack_ok)
+        return 0;
+
+    if (node.data->type == mpack_type_double)
+        return node.data->value.d;
+
+    mpack_node_flag_error(node, mpack_error_type);
+    return 0;
+}
+#endif
+
+#if MPACK_EXTENSIONS
+int8_t mpack_node_exttype(mpack_node_t node) {
+    if (mpack_node_error(node) != mpack_ok)
+        return 0;
+
+    if (node.data->type == mpack_type_ext)
+        return mpack_node_exttype_unchecked(node);
+
+    mpack_node_flag_error(node, mpack_error_type);
+    return 0;
+}
+#endif
+
+uint32_t mpack_node_data_len(mpack_node_t node) {
+    if (mpack_node_error(node) != mpack_ok)
+        return 0;
+
+    mpack_type_t type = node.data->type;
+    if (type == mpack_type_str || type == mpack_type_bin
+            #if MPACK_EXTENSIONS
+            || type == mpack_type_ext
+            #endif
+            )
+        return (uint32_t)node.data->len;
+
+    mpack_node_flag_error(node, mpack_error_type);
+    return 0;
+}
+
+size_t mpack_node_strlen(mpack_node_t node) {
+    if (mpack_node_error(node) != mpack_ok)
+        return 0;
+
+    if (node.data->type == mpack_type_str)
+        return (size_t)node.data->len;
+
+    mpack_node_flag_error(node, mpack_error_type);
+    return 0;
+}
+
+const char* mpack_node_str(mpack_node_t node) {
+    if (mpack_node_error(node) != mpack_ok)
+        return NULL;
+
+    mpack_type_t type = node.data->type;
+    if (type == mpack_type_str)
+        return mpack_node_data_unchecked(node);
+
+    mpack_node_flag_error(node, mpack_error_type);
+    return NULL;
+}
+
+const char* mpack_node_data(mpack_node_t node) {
+    if (mpack_node_error(node) != mpack_ok)
+        return NULL;
+
+    mpack_type_t type = node.data->type;
+    if (type == mpack_type_str || type == mpack_type_bin
+            #if MPACK_EXTENSIONS
+            || type == mpack_type_ext
+            #endif
+            )
+        return mpack_node_data_unchecked(node);
+
+    mpack_node_flag_error(node, mpack_error_type);
+    return NULL;
+}
+
+const char* mpack_node_bin_data(mpack_node_t node) {
+    if (mpack_node_error(node) != mpack_ok)
+        return NULL;
+
+    if (node.data->type == mpack_type_bin)
+        return mpack_node_data_unchecked(node);
+
+    mpack_node_flag_error(node, mpack_error_type);
+    return NULL;
+}
+
+size_t mpack_node_bin_size(mpack_node_t node) {
+    if (mpack_node_error(node) != mpack_ok)
+        return 0;
+
+    if (node.data->type == mpack_type_bin)
+        return (size_t)node.data->len;
+
+    mpack_node_flag_error(node, mpack_error_type);
+    return 0;
+}
+
+size_t mpack_node_array_length(mpack_node_t node) {
+    if (mpack_node_error(node) != mpack_ok)
+        return 0;
+
+    if (node.data->type != mpack_type_array) {
+        mpack_node_flag_error(node, mpack_error_type);
+        return 0;
+    }
+
+    return (size_t)node.data->len;
+}
+
+mpack_node_t mpack_node_array_at(mpack_node_t node, size_t index) {
+    if (mpack_node_error(node) != mpack_ok)
+        return mpack_tree_nil_node(node.tree);
+
+    if (node.data->type != mpack_type_array) {
+        mpack_node_flag_error(node, mpack_error_type);
+        return mpack_tree_nil_node(node.tree);
+    }
+
+    if (index >= node.data->len) {
+        mpack_node_flag_error(node, mpack_error_data);
+        return mpack_tree_nil_node(node.tree);
+    }
+
+    return mpack_node(node.tree, mpack_node_child(node, index));
+}
+
+size_t mpack_node_map_count(mpack_node_t node) {
+    if (mpack_node_error(node) != mpack_ok)
+        return 0;
+
+    if (node.data->type != mpack_type_map) {
+        mpack_node_flag_error(node, mpack_error_type);
+        return 0;
+    }
+
+    return node.data->len;
+}
+
+// internal node map lookup
+static mpack_node_t mpack_node_map_at(mpack_node_t node, size_t index, size_t offset) {
+    if (mpack_node_error(node) != mpack_ok)
+        return mpack_tree_nil_node(node.tree);
+
+    if (node.data->type != mpack_type_map) {
+        mpack_node_flag_error(node, mpack_error_type);
+        return mpack_tree_nil_node(node.tree);
+    }
+
+    if (index >= node.data->len) {
+        mpack_node_flag_error(node, mpack_error_data);
+        return mpack_tree_nil_node(node.tree);
+    }
+
+    return mpack_node(node.tree, mpack_node_child(node, index * 2 + offset));
+}
+
+mpack_node_t mpack_node_map_key_at(mpack_node_t node, size_t index) {
+    return mpack_node_map_at(node, index, 0);
+}
+
+mpack_node_t mpack_node_map_value_at(mpack_node_t node, size_t index) {
+    return mpack_node_map_at(node, index, 1);
+}
+
+#endif
+
+}  // namespace mpack
+MPACK_SILENCE_WARNINGS_END
diff --git a/third_party/allwpilib/wpiutil/src/main/native/include/wpi/Signal.h b/third_party/allwpilib/wpiutil/src/main/native/thirdparty/sigslot/include/wpi/Signal.h
similarity index 100%
rename from third_party/allwpilib/wpiutil/src/main/native/include/wpi/Signal.h
rename to third_party/allwpilib/wpiutil/src/main/native/thirdparty/sigslot/include/wpi/Signal.h
diff --git a/third_party/allwpilib/wpiutil/src/main/native/windows/Demangle.cpp b/third_party/allwpilib/wpiutil/src/main/native/windows/Demangle.cpp
index 1b0a8a7..18be371 100644
--- a/third_party/allwpilib/wpiutil/src/main/native/windows/Demangle.cpp
+++ b/third_party/allwpilib/wpiutil/src/main/native/windows/Demangle.cpp
@@ -22,8 +22,9 @@
   char buffer[256];
   DWORD sz = UnDecorateSymbolName(buf.c_str(), buffer, sizeof(buffer),
                                   UNDNAME_COMPLETE);
-  if (sz == 0)
+  if (sz == 0) {
     return std::string{mangledSymbol};
+  }
   return std::string(buffer, sz);
 }
 
diff --git a/third_party/allwpilib/wpiutil/src/main/native/windows/MulticastServiceAnnouncer.cpp b/third_party/allwpilib/wpiutil/src/main/native/windows/MulticastServiceAnnouncer.cpp
deleted file mode 100644
index 2327b8b..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/windows/MulticastServiceAnnouncer.cpp
+++ /dev/null
@@ -1,212 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef UNICODE
-#define UNICODE
-#endif
-
-#include "wpi/MulticastServiceAnnouncer.h"
-
-#include <string>
-#include <vector>
-
-#include "DynamicDns.h"
-#include "wpi/ConvertUTF.h"
-#include "wpi/SmallString.h"
-#include "wpi/SmallVector.h"
-#include "wpi/StringExtras.h"
-#include "wpi/hostname.h"
-
-using namespace wpi;
-
-struct ImplBase {
-  wpi::DynamicDns& dynamicDns = wpi::DynamicDns::GetDynamicDns();
-  PDNS_SERVICE_INSTANCE serviceInstance = nullptr;
-  HANDLE event = nullptr;
-};
-
-struct MulticastServiceAnnouncer::Impl : ImplBase {
-  std::wstring serviceType;
-  std::wstring serviceInstanceName;
-  std::wstring hostName;
-  int port;
-  std::vector<std::wstring> keys;
-  std::vector<PCWSTR> keyPtrs;
-  std::vector<std::wstring> values;
-  std::vector<PCWSTR> valuePtrs;
-
-  template <typename T>
-  Impl(std::string_view serviceName, std::string_view serviceType, int port,
-       wpi::span<const std::pair<T, T>> txt);
-};
-
-template <typename T>
-MulticastServiceAnnouncer::Impl::Impl(std::string_view serviceName,
-                                      std::string_view serviceType, int port,
-                                      wpi::span<const std::pair<T, T>> txt) {
-  if (!dynamicDns.CanDnsAnnounce) {
-    return;
-  }
-
-  this->port = port;
-
-  wpi::SmallVector<wchar_t, 128> wideStorage;
-  std::string hostName = wpi::GetHostname() + ".local";
-
-  for (auto&& i : txt) {
-    wideStorage.clear();
-    wpi::sys::windows::UTF8ToUTF16(i.first, wideStorage);
-    this->keys.emplace_back(
-        std::wstring{wideStorage.data(), wideStorage.size()});
-    wideStorage.clear();
-    wpi::sys::windows::UTF8ToUTF16(i.second, wideStorage);
-    this->values.emplace_back(
-        std::wstring{wideStorage.data(), wideStorage.size()});
-  }
-
-  for (size_t i = 0; i < this->keys.size(); i++) {
-    this->keyPtrs.emplace_back(this->keys[i].c_str());
-    this->valuePtrs.emplace_back(this->values[i].c_str());
-  }
-
-  wpi::SmallString<128> storage;
-
-  wideStorage.clear();
-  wpi::sys::windows::UTF8ToUTF16(hostName, wideStorage);
-
-  this->hostName = std::wstring{wideStorage.data(), wideStorage.size()};
-
-  wideStorage.clear();
-  if (wpi::ends_with_lower(serviceType, ".local")) {
-    wpi::sys::windows::UTF8ToUTF16(serviceType, wideStorage);
-  } else {
-    storage.clear();
-    storage.append(serviceType);
-    storage.append(".local");
-    wpi::sys::windows::UTF8ToUTF16(storage.str(), wideStorage);
-  }
-  this->serviceType = std::wstring{wideStorage.data(), wideStorage.size()};
-
-  wideStorage.clear();
-  storage.clear();
-  storage.append(serviceName);
-  storage.append(".");
-  storage.append(serviceType);
-  if (!wpi::ends_with_lower(serviceType, ".local")) {
-    storage.append(".local");
-  }
-
-  wpi::sys::windows::UTF8ToUTF16(storage.str(), wideStorage);
-  this->serviceInstanceName =
-      std::wstring{wideStorage.data(), wideStorage.size()};
-}
-
-MulticastServiceAnnouncer::MulticastServiceAnnouncer(
-    std::string_view serviceName, std::string_view serviceType, int port,
-    wpi::span<const std::pair<std::string, std::string>> txt) {
-  pImpl = std::make_unique<Impl>(serviceName, serviceType, port, txt);
-}
-
-MulticastServiceAnnouncer::MulticastServiceAnnouncer(
-    std::string_view serviceName, std::string_view serviceType, int port,
-    wpi::span<const std::pair<std::string_view, std::string_view>> txt) {
-  pImpl = std::make_unique<Impl>(serviceName, serviceType, port, txt);
-}
-
-MulticastServiceAnnouncer::~MulticastServiceAnnouncer() noexcept {
-  Stop();
-}
-
-bool MulticastServiceAnnouncer::HasImplementation() const {
-  return pImpl->dynamicDns.CanDnsAnnounce;
-}
-
-static void WINAPI DnsServiceRegisterCallback(DWORD /*Status*/,
-                                              PVOID pQueryContext,
-                                              PDNS_SERVICE_INSTANCE pInstance) {
-  ImplBase* impl = reinterpret_cast<ImplBase*>(pQueryContext);
-
-  impl->serviceInstance = pInstance;
-
-  SetEvent(impl->event);
-}
-
-void MulticastServiceAnnouncer::Start() {
-  if (pImpl->serviceInstance) {
-    return;
-  }
-
-  if (!pImpl->dynamicDns.CanDnsAnnounce) {
-    return;
-  }
-
-  PDNS_SERVICE_INSTANCE serviceInst =
-      pImpl->dynamicDns.DnsServiceConstructInstancePtr(
-          pImpl->serviceInstanceName.c_str(), pImpl->hostName.c_str(), nullptr,
-          nullptr, pImpl->port, 0, 0, static_cast<DWORD>(pImpl->keyPtrs.size()),
-          pImpl->keyPtrs.data(), pImpl->valuePtrs.data());
-  if (serviceInst == nullptr) {
-    return;
-  }
-
-  DNS_SERVICE_REGISTER_REQUEST registerRequest = {};
-  registerRequest.pQueryContext = static_cast<ImplBase*>(pImpl.get());
-  registerRequest.pRegisterCompletionCallback = DnsServiceRegisterCallback;
-  registerRequest.Version = DNS_QUERY_REQUEST_VERSION1;
-  registerRequest.unicastEnabled = false;
-  registerRequest.pServiceInstance = serviceInst;
-  registerRequest.InterfaceIndex = 0;
-
-  pImpl->event = CreateEvent(NULL, true, false, NULL);
-
-  if (pImpl->dynamicDns.DnsServiceRegisterPtr(&registerRequest, nullptr) ==
-      DNS_REQUEST_PENDING) {
-    WaitForSingleObject(pImpl->event, INFINITE);
-  }
-
-  pImpl->dynamicDns.DnsServiceFreeInstancePtr(serviceInst);
-  CloseHandle(pImpl->event);
-  pImpl->event = nullptr;
-}
-
-static void WINAPI DnsServiceDeRegisterCallback(
-    DWORD /*Status*/, PVOID pQueryContext, PDNS_SERVICE_INSTANCE pInstance) {
-  ImplBase* impl = reinterpret_cast<ImplBase*>(pQueryContext);
-
-  if (pInstance != nullptr) {
-    impl->dynamicDns.DnsServiceFreeInstancePtr(pInstance);
-    pInstance = nullptr;
-  }
-
-  SetEvent(impl->event);
-}
-
-void MulticastServiceAnnouncer::Stop() {
-  if (!pImpl->dynamicDns.CanDnsAnnounce) {
-    return;
-  }
-
-  if (pImpl->serviceInstance == nullptr) {
-    return;
-  }
-
-  pImpl->event = CreateEvent(NULL, true, false, NULL);
-  DNS_SERVICE_REGISTER_REQUEST registerRequest = {};
-  registerRequest.pQueryContext = static_cast<ImplBase*>(pImpl.get());
-  registerRequest.pRegisterCompletionCallback = DnsServiceDeRegisterCallback;
-  registerRequest.Version = DNS_QUERY_REQUEST_VERSION1;
-  registerRequest.unicastEnabled = false;
-  registerRequest.pServiceInstance = pImpl->serviceInstance;
-  registerRequest.InterfaceIndex = 0;
-
-  if (pImpl->dynamicDns.DnsServiceDeRegisterPtr(&registerRequest, nullptr) ==
-      DNS_REQUEST_PENDING) {
-    WaitForSingleObject(pImpl->event, INFINITE);
-  }
-
-  pImpl->dynamicDns.DnsServiceFreeInstancePtr(pImpl->serviceInstance);
-  pImpl->serviceInstance = nullptr;
-  CloseHandle(pImpl->event);
-  pImpl->event = nullptr;
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/windows/MulticastServiceResolver.cpp b/third_party/allwpilib/wpiutil/src/main/native/windows/MulticastServiceResolver.cpp
deleted file mode 100644
index 115b43f..0000000
--- a/third_party/allwpilib/wpiutil/src/main/native/windows/MulticastServiceResolver.cpp
+++ /dev/null
@@ -1,205 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifndef UNICODE
-#define UNICODE
-#endif
-
-#include "wpi/MulticastServiceResolver.h"
-
-#include <string>
-
-#include "DynamicDns.h"
-#include "wpi/ConvertUTF.h"
-#include "wpi/SmallString.h"
-#include "wpi/SmallVector.h"
-#include "wpi/StringExtras.h"
-
-#pragma comment(lib, "dnsapi")
-
-using namespace wpi;
-
-struct MulticastServiceResolver::Impl {
-  wpi::DynamicDns& dynamicDns = wpi::DynamicDns::GetDynamicDns();
-  std::wstring serviceType;
-  DNS_SERVICE_CANCEL serviceCancel{nullptr};
-
-  MulticastServiceResolver* resolver;
-
-  void onFound(ServiceData&& data) {
-    resolver->PushData(std::forward<ServiceData>(data));
-  }
-};
-
-MulticastServiceResolver::MulticastServiceResolver(
-    std::string_view serviceType) {
-  pImpl = std::make_unique<Impl>();
-  pImpl->resolver = this;
-
-  if (!pImpl->dynamicDns.CanDnsResolve) {
-    return;
-  }
-
-  wpi::SmallVector<wchar_t, 128> wideStorage;
-
-  if (wpi::ends_with_lower(serviceType, ".local")) {
-    wpi::sys::windows::UTF8ToUTF16(serviceType, wideStorage);
-  } else {
-    wpi::SmallString<128> storage;
-    storage.append(serviceType);
-    storage.append(".local");
-    wpi::sys::windows::UTF8ToUTF16(storage.str(), wideStorage);
-  }
-  pImpl->serviceType = std::wstring{wideStorage.data(), wideStorage.size()};
-}
-
-MulticastServiceResolver::~MulticastServiceResolver() noexcept {
-  Stop();
-}
-
-bool MulticastServiceResolver::HasImplementation() const {
-  return pImpl->dynamicDns.CanDnsResolve;
-}
-
-static _Function_class_(DNS_QUERY_COMPLETION_ROUTINE) VOID WINAPI
-    DnsCompletion(_In_ PVOID pQueryContext,
-                  _Inout_ PDNS_QUERY_RESULT pQueryResults) {
-  MulticastServiceResolver::Impl* impl =
-      reinterpret_cast<MulticastServiceResolver::Impl*>(pQueryContext);
-
-  wpi::SmallVector<DNS_RECORDW*, 4> PtrRecords;
-  wpi::SmallVector<DNS_RECORDW*, 4> SrvRecords;
-  wpi::SmallVector<DNS_RECORDW*, 4> TxtRecords;
-  wpi::SmallVector<DNS_RECORDW*, 4> ARecords;
-
-  {
-    DNS_RECORDW* current = pQueryResults->pQueryRecords;
-    while (current != nullptr) {
-      switch (current->wType) {
-        case DNS_TYPE_PTR:
-          PtrRecords.push_back(current);
-          break;
-        case DNS_TYPE_SRV:
-          SrvRecords.push_back(current);
-          break;
-        case DNS_TYPE_TEXT:
-          TxtRecords.push_back(current);
-          break;
-        case DNS_TYPE_A:
-          ARecords.push_back(current);
-          break;
-      }
-      current = current->pNext;
-    }
-  }
-
-  for (DNS_RECORDW* Ptr : PtrRecords) {
-    if (std::wstring_view{Ptr->pName} != impl->serviceType) {
-      continue;
-    }
-
-    std::wstring_view nameHost = Ptr->Data.Ptr.pNameHost;
-    DNS_RECORDW* foundSrv = nullptr;
-    for (DNS_RECORDW* Srv : SrvRecords) {
-      if (std::wstring_view{Srv->pName} == nameHost) {
-        foundSrv = Srv;
-        break;
-      }
-    }
-
-    if (!foundSrv) {
-      continue;
-    }
-
-    for (DNS_RECORDW* A : ARecords) {
-      if (std::wstring_view{A->pName} ==
-          std::wstring_view{foundSrv->Data.Srv.pNameTarget}) {
-        MulticastServiceResolver::ServiceData data;
-        wpi::SmallString<128> storage;
-        for (DNS_RECORDW* Txt : TxtRecords) {
-          if (std::wstring_view{Txt->pName} == nameHost) {
-            for (DWORD i = 0; i < Txt->Data.Txt.dwStringCount; i++) {
-              std::wstring_view wideView = Txt->Data.TXT.pStringArray[i];
-              size_t splitIndex = wideView.find(L'=');
-              if (splitIndex == wideView.npos) {
-                // Todo make this just do key
-                continue;
-              }
-              storage.clear();
-              wpi::span<const wpi::UTF16> wideStr{
-                  reinterpret_cast<const wpi::UTF16*>(wideView.data()),
-                  splitIndex};
-              wpi::convertUTF16ToUTF8String(wideStr, storage);
-              auto& pair = data.txt.emplace_back(
-                  std::pair<std::string, std::string>{storage.string(), {}});
-              storage.clear();
-              wideStr = wpi::span<const wpi::UTF16>{
-                  reinterpret_cast<const wpi::UTF16*>(wideView.data() +
-                                                      splitIndex + 1),
-                  wideView.size() - splitIndex - 1};
-              wpi::convertUTF16ToUTF8String(wideStr, storage);
-              pair.second = storage.string();
-            }
-          }
-        }
-
-        storage.clear();
-        wpi::span<const wpi::UTF16> wideHostName{
-            reinterpret_cast<const wpi::UTF16*>(A->pName), wcslen(A->pName)};
-        wpi::convertUTF16ToUTF8String(wideHostName, storage);
-        storage.append(".");
-
-        data.hostName = storage.string();
-        storage.clear();
-
-        int len = nameHost.find(impl->serviceType.c_str());
-        wpi::span<const wpi::UTF16> wideServiceName{
-            reinterpret_cast<const wpi::UTF16*>(nameHost.data()),
-            nameHost.size()};
-        if (len != nameHost.npos) {
-          wideServiceName = wideServiceName.subspan(0, len - 1);
-        }
-        wpi::convertUTF16ToUTF8String(wideServiceName, storage);
-
-        data.serviceName = storage.string();
-        data.port = foundSrv->Data.Srv.wPort;
-        data.ipv4Address = A->Data.A.IpAddress;
-
-        impl->onFound(std::move(data));
-      }
-    }
-  }
-  DnsFree(pQueryResults->pQueryRecords, DNS_FREE_TYPE::DnsFreeRecordList);
-}
-
-void MulticastServiceResolver::Start() {
-  if (pImpl->serviceCancel.reserved != nullptr) {
-    return;
-  }
-
-  if (!pImpl->dynamicDns.CanDnsResolve) {
-    return;
-  }
-
-  DNS_SERVICE_BROWSE_REQUEST request = {};
-  request.InterfaceIndex = 0;
-  request.pQueryContext = pImpl.get();
-  request.QueryName = pImpl->serviceType.c_str();
-  request.Version = 2;
-  request.pBrowseCallbackV2 = DnsCompletion;
-  pImpl->dynamicDns.DnsServiceBrowsePtr(&request, &pImpl->serviceCancel);
-}
-
-void MulticastServiceResolver::Stop() {
-  if (!pImpl->dynamicDns.CanDnsResolve) {
-    return;
-  }
-
-  if (pImpl->serviceCancel.reserved == nullptr) {
-    return;
-  }
-
-  pImpl->dynamicDns.DnsServiceBrowseCancelPtr(&pImpl->serviceCancel);
-  pImpl->serviceCancel.reserved = nullptr;
-}
diff --git a/third_party/allwpilib/wpiutil/src/main/native/windows/StackTrace.cpp b/third_party/allwpilib/wpiutil/src/main/native/windows/StackTrace.cpp
index bab5f83..de31b2a 100644
--- a/third_party/allwpilib/wpiutil/src/main/native/windows/StackTrace.cpp
+++ b/third_party/allwpilib/wpiutil/src/main/native/windows/StackTrace.cpp
@@ -8,6 +8,8 @@
 #include "wpi/ConvertUTF.h"
 #include "wpi/SmallString.h"
 
+#if defined(_MSC_VER)
+
 namespace {
 class StackTraceWalker : public StackWalker {
  public:
@@ -40,3 +42,5 @@
 }
 
 }  // namespace wpi
+
+#endif  // defined(_MSC_VER)
diff --git a/third_party/allwpilib/wpiutil/src/main/native/windows/StackWalker.cpp b/third_party/allwpilib/wpiutil/src/main/native/windows/StackWalker.cpp
index 237360a..6f0fbf2 100644
--- a/third_party/allwpilib/wpiutil/src/main/native/windows/StackWalker.cpp
+++ b/third_party/allwpilib/wpiutil/src/main/native/windows/StackWalker.cpp
@@ -1,4 +1,4 @@
-/**********************************************************************
+/**********************************************************************
  *
  * StackWalker.cpp
  * https://github.com/JochenKalmbach/StackWalker
@@ -485,8 +485,8 @@
       if (hToolhelp == NULL)
         continue;
       createToolhelp32Snapshot = (tCT32S)GetProcAddress(hToolhelp, "CreateToolhelp32Snapshot");
-      module32First = (tM32F)GetProcAddress(hToolhelp, strModule32First);
-      module32Next = (tM32N)GetProcAddress(hToolhelp, strModule32Next);
+      module32First = (tM32F)GetProcAddress(hToolhelp, strModule32First);  
+      module32Next = (tM32N)GetProcAddress(hToolhelp, strModule32Next); 
       if ((createToolhelp32Snapshot != NULL) && (module32First != NULL) && (module32Next != NULL))
         break; // found the functions!
       FreeLibrary(hToolhelp);
diff --git a/third_party/allwpilib/wpiutil/src/main/native/windows/StackWalker.h b/third_party/allwpilib/wpiutil/src/main/native/windows/StackWalker.h
index 750de96..89be951 100644
--- a/third_party/allwpilib/wpiutil/src/main/native/windows/StackWalker.h
+++ b/third_party/allwpilib/wpiutil/src/main/native/windows/StackWalker.h
@@ -1,3 +1,8 @@
+#ifndef __STACKWALKER_H__
+#define __STACKWALKER_H__
+
+#if defined(_MSC_VER)
+
 /**********************************************************************
  *
  * StackWalker.h
@@ -32,6 +37,8 @@
  *   SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
  *
  * **********************************************************************/
+// #pragma once is supported starting with _MSC_VER 1000,
+// so we need not to check the version (because we only support _MSC_VER >= 1100)!
 #pragma once
 
 #include <windows.h>
@@ -105,7 +112,11 @@
 
   BOOL ShowObject(LPVOID pObject);
 
+#if _MSC_VER >= 1300
+  // due to some reasons, the "STACKWALK_MAX_NAMELEN" must be declared as "public"
+  // in older compilers in order to use it... starting with VC7 we can declare it as "protected"
 protected:
+#endif
   enum
   {
     STACKWALK_MAX_NAMELEN = 1024
@@ -176,3 +187,7 @@
     c.ContextFlags = contextFlags;                                \
     RtlCaptureContext(&c);                                        \
   } while (0);
+
+#endif //defined(_MSC_VER)
+
+#endif // __STACKWALKER_H__
diff --git a/third_party/allwpilib/wpiutil/src/netconsoleServer/native/cpp/main.cpp b/third_party/allwpilib/wpiutil/src/netconsoleServer/native/cpp/main.cpp
deleted file mode 100644
index c43a670..0000000
--- a/third_party/allwpilib/wpiutil/src/netconsoleServer/native/cpp/main.cpp
+++ /dev/null
@@ -1,279 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#ifdef __APPLE__
-#include <util.h>
-#elif !defined(_WIN32)
-#include <pty.h>
-#endif
-
-#include <cstdio>
-
-#include "fmt/format.h"
-#include "wpi/MathExtras.h"
-#include "wpi/SmallVector.h"
-#include "wpi/StringExtras.h"
-#include "wpi/raw_uv_ostream.h"
-#include "wpi/timestamp.h"
-#include "wpi/uv/Loop.h"
-#include "wpi/uv/Pipe.h"
-#include "wpi/uv/Process.h"
-#include "wpi/uv/Signal.h"
-#include "wpi/uv/Tcp.h"
-#include "wpi/uv/Tty.h"
-#include "wpi/uv/Udp.h"
-#include "wpi/uv/util.h"
-
-namespace uv = wpi::uv;
-
-static uint64_t startTime = wpi::Now();
-
-static bool NewlineBuffer(std::string& rem, uv::Buffer& buf, size_t len,
-                          wpi::SmallVectorImpl<uv::Buffer>& bufs, bool tcp,
-                          uint16_t tcpSeq) {
-  // scan for last newline
-  std::string_view str(buf.base, len);
-  size_t idx = str.rfind('\n');
-  if (idx == std::string_view::npos) {
-    // no newline yet, just keep appending to remainder
-    rem += str;
-    return false;
-  }
-
-  // build output
-  wpi::raw_uv_ostream out(bufs, 4096);
-  std::string_view toCopy = wpi::slice(str, 0, idx + 1);
-  if (tcp) {
-    // Header is 2 byte len, 1 byte type, 4 byte timestamp, 2 byte sequence num
-    uint32_t ts = wpi::FloatToBits((wpi::Now() - startTime) * 1.0e-6);
-    uint16_t len = rem.size() + toCopy.size() + 1 + 4 + 2;
-    const uint8_t header[] = {static_cast<uint8_t>((len >> 8) & 0xff),
-                              static_cast<uint8_t>(len & 0xff),
-                              12,
-                              static_cast<uint8_t>((ts >> 24) & 0xff),
-                              static_cast<uint8_t>((ts >> 16) & 0xff),
-                              static_cast<uint8_t>((ts >> 8) & 0xff),
-                              static_cast<uint8_t>(ts & 0xff),
-                              static_cast<uint8_t>((tcpSeq >> 8) & 0xff),
-                              static_cast<uint8_t>(tcpSeq & 0xff)};
-    out << wpi::span<const uint8_t>(header);
-  }
-  out << rem << toCopy;
-
-  // reset remainder
-  rem = wpi::slice(str, idx + 1, std::string_view::npos);
-  return true;
-}
-
-static void CopyUdp(uv::Stream& in, std::shared_ptr<uv::Udp> out,
-                    bool broadcast) {
-  sockaddr_in addr;
-  if (broadcast) {
-    out->SetBroadcast(true);
-    uv::NameToAddr("0.0.0.0", 6666, &addr);
-  } else {
-    uv::NameToAddr("127.0.0.1", 6666, &addr);
-  }
-
-  in.data.connect(
-      [rem = std::make_shared<std::string>(), outPtr = out.get(), addr](
-          uv::Buffer& buf, size_t len) {
-        // build buffers
-        wpi::SmallVector<uv::Buffer, 4> bufs;
-        if (!NewlineBuffer(*rem, buf, len, bufs, false, 0)) {
-          return;
-        }
-
-        // send output
-        outPtr->Send(addr, bufs, [](auto bufs2, uv::Error) {
-          for (auto buf : bufs2) {
-            buf.Deallocate();
-          }
-        });
-      },
-      out);
-}
-
-static void CopyTcp(uv::Stream& in, std::shared_ptr<uv::Stream> out) {
-  struct StreamData {
-    std::string rem;
-    uint16_t seq = 0;
-  };
-  in.data.connect(
-      [data = std::make_shared<StreamData>(), outPtr = out.get()](
-          uv::Buffer& buf, size_t len) {
-        // build buffers
-        wpi::SmallVector<uv::Buffer, 4> bufs;
-        if (!NewlineBuffer(data->rem, buf, len, bufs, true, data->seq++)) {
-          return;
-        }
-
-        // send output
-        outPtr->Write(bufs, [](auto bufs2, uv::Error) {
-          for (auto buf : bufs2) {
-            buf.Deallocate();
-          }
-        });
-      },
-      out);
-}
-
-static void CopyStream(uv::Stream& in, std::shared_ptr<uv::Stream> out) {
-  in.data.connect([out](uv::Buffer& buf, size_t len) {
-    uv::Buffer buf2 = buf.Dup();
-    buf2.len = len;
-    out->Write({buf2}, [](auto bufs, uv::Error) {
-      for (auto buf : bufs) {
-        buf.Deallocate();
-      }
-    });
-  });
-}
-
-int main(int argc, char* argv[]) {
-  // parse arguments
-  int programArgc = 1;
-  bool useUdp = false;
-  bool broadcastUdp = false;
-  bool err = false;
-
-  while (programArgc < argc && argv[programArgc][0] == '-') {
-    if (std::string_view(argv[programArgc]) == "-u") {
-      useUdp = true;
-    } else if (std::string_view(argv[programArgc]) == "-b") {
-      useUdp = true;
-      broadcastUdp = true;
-    } else {
-      fmt::print(stderr, "unrecognized command line option {}\n",
-                 argv[programArgc]);
-      err = true;
-    }
-    ++programArgc;
-  }
-
-  if (err || (argc - programArgc) < 1) {
-    std::fputs(argv[0], stderr);
-    std::fputs(
-        " [-ub] program [arguments ...]\n"
-        "  -u  send udp to localhost port 6666 instead of using tcp\n"
-        "  -b  broadcast udp to port 6666 instead of using tcp\n",
-        stderr);
-    return EXIT_FAILURE;
-  }
-
-  uv::Process::DisableStdioInheritance();
-
-  auto loop = uv::Loop::Create();
-  loop->error.connect(
-      [](uv::Error err) { fmt::print(stderr, "uv ERROR: {}\n", err.str()); });
-
-  // create pipes to communicate with child
-  auto stdinPipe = uv::Pipe::Create(loop);
-  auto stdoutPipe = uv::Pipe::Create(loop);
-  auto stderrPipe = uv::Pipe::Create(loop);
-
-  // create tty to pass from our console to child's
-  auto stdinTty = uv::Tty::Create(loop, 0, true);
-  auto stdoutTty = uv::Tty::Create(loop, 1, false);
-  auto stderrTty = uv::Tty::Create(loop, 2, false);
-
-  // pass through our console to child's (bidirectional)
-  if (stdinTty) {
-    CopyStream(*stdinTty, stdinPipe);
-  }
-  if (stdoutTty) {
-    CopyStream(*stdoutPipe, stdoutTty);
-  }
-  if (stderrTty) {
-    CopyStream(*stderrPipe, stderrTty);
-  }
-
-  // when our stdin closes, also close child stdin
-  if (stdinTty) {
-    stdinTty->end.connect([stdinPipe] { stdinPipe->Close(); });
-  }
-
-  if (useUdp) {
-    auto udp = uv::Udp::Create(loop);
-    // tee stdout and stderr
-    CopyUdp(*stdoutPipe, udp, broadcastUdp);
-    CopyUdp(*stderrPipe, udp, broadcastUdp);
-  } else {
-    auto tcp = uv::Tcp::Create(loop);
-
-    // bind to listen address and port
-    tcp->Bind("", 1740);
-
-    // when we get a connection, accept it
-    tcp->connection.connect([srv = tcp.get(), stdoutPipe, stderrPipe] {
-      auto tcp = srv->Accept();
-      if (!tcp) {
-        return;
-      }
-
-      // close on error
-      tcp->error.connect([s = tcp.get()](wpi::uv::Error err) { s->Close(); });
-
-      // tee stdout and stderr
-      CopyTcp(*stdoutPipe, tcp);
-      CopyTcp(*stderrPipe, tcp);
-    });
-
-    // start listening for incoming connections
-    tcp->Listen();
-  }
-
-  // build process options
-  wpi::SmallVector<uv::Process::Option, 8> options;
-
-  // hook up pipes to child
-  options.emplace_back(
-      uv::Process::StdioCreatePipe(0, *stdinPipe, UV_READABLE_PIPE));
-#ifndef _WIN32
-  // create a PTY so the child does unbuffered output
-  int parentfd, childfd;
-  if (openpty(&parentfd, &childfd, nullptr, nullptr, nullptr) == 0) {
-    stdoutPipe->Open(parentfd);
-    options.emplace_back(uv::Process::StdioInherit(1, childfd));
-  } else {
-    options.emplace_back(
-        uv::Process::StdioCreatePipe(1, *stdoutPipe, UV_WRITABLE_PIPE));
-  }
-#else
-  options.emplace_back(
-      uv::Process::StdioCreatePipe(1, *stdoutPipe, UV_WRITABLE_PIPE));
-#endif
-  options.emplace_back(
-      uv::Process::StdioCreatePipe(2, *stderrPipe, UV_WRITABLE_PIPE));
-
-  // pass our args as the child args (argv[1] becomes child argv[0], etc)
-  for (int i = programArgc; i < argc; ++i) {
-    options.emplace_back(argv[i]);
-  }
-
-  auto proc = uv::Process::SpawnArray(loop, argv[programArgc], options);
-  if (!proc) {
-    std::fputs("could not start subprocess\n", stderr);
-    return EXIT_FAILURE;
-  }
-  proc->exited.connect([](int64_t status, int) { std::exit(status); });
-
-  // start reading
-  if (stdinTty) {
-    stdinTty->StartRead();
-  }
-  stdoutPipe->StartRead();
-  stderrPipe->StartRead();
-
-  // pass various signals to child
-  auto sigHandler = [proc](int signum) { proc->Kill(signum); };
-  for (int signum : {SIGINT, SIGHUP, SIGTERM}) {
-    auto sig = uv::Signal::Create(loop);
-    sig->Start(signum);
-    sig->signal.connect(sigHandler);
-  }
-
-  // run the loop!
-  loop->Run();
-}
diff --git a/third_party/allwpilib/wpiutil/src/netconsoleTee/native/cpp/main.cpp b/third_party/allwpilib/wpiutil/src/netconsoleTee/native/cpp/main.cpp
deleted file mode 100644
index 8abb458..0000000
--- a/third_party/allwpilib/wpiutil/src/netconsoleTee/native/cpp/main.cpp
+++ /dev/null
@@ -1,223 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include <cstdio>
-
-#include "fmt/format.h"
-#include "wpi/MathExtras.h"
-#include "wpi/SmallVector.h"
-#include "wpi/StringExtras.h"
-#include "wpi/raw_uv_ostream.h"
-#include "wpi/timestamp.h"
-#include "wpi/uv/Loop.h"
-#include "wpi/uv/Tcp.h"
-#include "wpi/uv/Tty.h"
-#include "wpi/uv/Udp.h"
-#include "wpi/uv/util.h"
-
-namespace uv = wpi::uv;
-
-static uint64_t startTime = wpi::Now();
-
-static bool NewlineBuffer(std::string& rem, uv::Buffer& buf, size_t len,
-                          wpi::SmallVectorImpl<uv::Buffer>& bufs, bool tcp,
-                          uint16_t tcpSeq) {
-  // scan for last newline
-  std::string_view str(buf.base, len);
-  size_t idx = str.rfind('\n');
-  if (idx == std::string_view::npos) {
-    // no newline yet, just keep appending to remainder
-    rem += str;
-    return false;
-  }
-
-  // build output
-  wpi::raw_uv_ostream out(bufs, 4096);
-  std::string_view toCopy = wpi::slice(str, 0, idx + 1);
-  if (tcp) {
-    // Header is 2 byte len, 1 byte type, 4 byte timestamp, 2 byte sequence num
-    uint32_t ts = wpi::FloatToBits((wpi::Now() - startTime) * 1.0e-6);
-    uint16_t len = rem.size() + toCopy.size() + 1 + 4 + 2;
-    const uint8_t header[] = {static_cast<uint8_t>((len >> 8) & 0xff),
-                              static_cast<uint8_t>(len & 0xff),
-                              12,
-                              static_cast<uint8_t>((ts >> 24) & 0xff),
-                              static_cast<uint8_t>((ts >> 16) & 0xff),
-                              static_cast<uint8_t>((ts >> 8) & 0xff),
-                              static_cast<uint8_t>(ts & 0xff),
-                              static_cast<uint8_t>((tcpSeq >> 8) & 0xff),
-                              static_cast<uint8_t>(tcpSeq & 0xff)};
-    out << wpi::span<const uint8_t>(header);
-  }
-  out << rem << toCopy;
-
-  // reset remainder
-  rem = wpi::slice(str, idx + 1, std::string_view::npos);
-  return true;
-}
-
-static void CopyUdp(uv::Stream& in, std::shared_ptr<uv::Udp> out, int port,
-                    bool broadcast) {
-  sockaddr_in addr;
-  if (broadcast) {
-    out->SetBroadcast(true);
-    uv::NameToAddr("0.0.0.0", port, &addr);
-  } else {
-    uv::NameToAddr("127.0.0.1", port, &addr);
-  }
-
-  in.data.connect(
-      [rem = std::make_shared<std::string>(), outPtr = out.get(), addr](
-          uv::Buffer& buf, size_t len) {
-        // build buffers
-        wpi::SmallVector<uv::Buffer, 4> bufs;
-        if (!NewlineBuffer(*rem, buf, len, bufs, false, 0)) {
-          return;
-        }
-
-        // send output
-        outPtr->Send(addr, bufs, [](auto bufs2, uv::Error) {
-          for (auto buf : bufs2) {
-            buf.Deallocate();
-          }
-        });
-      },
-      out);
-}
-
-static void CopyTcp(uv::Stream& in, std::shared_ptr<uv::Stream> out) {
-  struct StreamData {
-    std::string rem;
-    uint16_t seq = 0;
-  };
-  in.data.connect(
-      [data = std::make_shared<StreamData>(), outPtr = out.get()](
-          uv::Buffer& buf, size_t len) {
-        // build buffers
-        wpi::SmallVector<uv::Buffer, 4> bufs;
-        if (!NewlineBuffer(data->rem, buf, len, bufs, true, data->seq++)) {
-          return;
-        }
-
-        // send output
-        outPtr->Write(bufs, [](auto bufs2, uv::Error) {
-          for (auto buf : bufs2) {
-            buf.Deallocate();
-          }
-        });
-      },
-      out);
-}
-
-static void CopyStream(uv::Stream& in, std::shared_ptr<uv::Stream> out) {
-  in.data.connect([out](uv::Buffer& buf, size_t len) {
-    uv::Buffer buf2 = buf.Dup();
-    buf2.len = len;
-    out->Write({buf2}, [](auto bufs, uv::Error) {
-      for (auto buf : bufs) {
-        buf.Deallocate();
-      }
-    });
-  });
-}
-
-int main(int argc, char* argv[]) {
-  // parse arguments
-  int arg = 1;
-  bool useUdp = false;
-  bool broadcastUdp = false;
-  bool err = false;
-  int port = -1;
-
-  while (arg < argc && argv[arg][0] == '-') {
-    if (std::string_view(argv[arg]) == "-u") {
-      useUdp = true;
-    } else if (std::string_view(argv[arg]) == "-b") {
-      useUdp = true;
-      broadcastUdp = true;
-    } else if (std::string_view(argv[arg]) == "-p") {
-      ++arg;
-      std::optional<int> portValue;
-      if (arg >= argc || argv[arg][0] == '-' ||
-          !(portValue = wpi::parse_integer<int>(argv[arg], 10))) {
-        std::fputs("-p must be followed by port number\n", stderr);
-        err = true;
-      } else if (portValue) {
-        port = portValue.value();
-      }
-    } else {
-      fmt::print(stderr, "unrecognized command line option {}\n", argv[arg]);
-      err = true;
-    }
-    ++arg;
-  }
-
-  if (err) {
-    std::fputs(argv[0], stderr);
-    std::fputs(
-        " [-ub] [-p PORT]\n"
-        "  -u       send udp to localhost port 6666 instead of using tcp\n"
-        "  -b       broadcast udp to port 6666 instead of using tcp\n"
-        "  -p PORT  use port PORT instead of 6666 (udp) or 1740 (tcp)\n",
-        stderr);
-    return EXIT_FAILURE;
-  }
-
-  auto loop = uv::Loop::Create();
-  loop->error.connect(
-      [](uv::Error err) { fmt::print(stderr, "uv ERROR: {}\n", err.str()); });
-
-  // create ttys
-  auto stdinTty = uv::Tty::Create(loop, 0, true);
-  auto stdoutTty = uv::Tty::Create(loop, 1, false);
-
-  // don't bother continuing if we don't have a stdin
-  if (!stdinTty) {
-    return EXIT_SUCCESS;
-  }
-
-  // pass through our input to output
-  if (stdoutTty) {
-    CopyStream(*stdinTty, stdoutTty);
-  }
-
-  // when our stdin closes, exit
-  stdinTty->end.connect([] { std::exit(EXIT_SUCCESS); });
-
-  if (useUdp) {
-    auto udp = uv::Udp::Create(loop);
-    // tee
-    CopyUdp(*stdinTty, udp, port < 0 ? 6666 : port, broadcastUdp);
-  } else {
-    auto tcp = uv::Tcp::Create(loop);
-
-    // bind to listen address and port
-    tcp->Bind("", port < 0 ? 1740 : port);
-
-    // when we get a connection, accept it
-    tcp->connection.connect([srv = tcp.get(), stdinTty] {
-      auto tcp = srv->Accept();
-      if (!tcp) {
-        return;
-      }
-
-      // close on error
-      tcp->error.connect([s = tcp.get()](wpi::uv::Error err) { s->Close(); });
-
-      // tee
-      CopyTcp(*stdinTty, tcp);
-    });
-
-    // start listening for incoming connections
-    tcp->Listen();
-  }
-
-  // start reading
-  if (stdinTty) {
-    stdinTty->StartRead();
-  }
-
-  // run the loop!
-  loop->Run();
-}
diff --git a/third_party/allwpilib/wpiutil/src/printlog/java/printlog/PrintLog.java b/third_party/allwpilib/wpiutil/src/printlog/java/printlog/PrintLog.java
new file mode 100644
index 0000000..e9339b6
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/printlog/java/printlog/PrintLog.java
@@ -0,0 +1,150 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package printlog;
+
+import edu.wpi.first.util.datalog.DataLogReader;
+import edu.wpi.first.util.datalog.DataLogRecord;
+import java.io.IOException;
+import java.time.LocalDateTime;
+import java.time.ZoneOffset;
+import java.time.format.DateTimeFormatter;
+import java.util.Arrays;
+import java.util.HashMap;
+import java.util.InputMismatchException;
+import java.util.Map;
+
+public final class PrintLog {
+  private static final DateTimeFormatter m_timeFormatter =
+      DateTimeFormatter.ofPattern("yyyy-MM-dd HH:mm:ss");
+
+  /** Main function. */
+  public static void main(String[] args) {
+    if (args.length != 1) {
+      System.err.println("Usage: printlog <file>");
+      System.exit(1);
+      return;
+    }
+    DataLogReader reader;
+    try {
+      reader = new DataLogReader(args[0]);
+    } catch (IOException ex) {
+      System.err.println("could not open file: " + ex.getMessage());
+      System.exit(1);
+      return;
+    }
+    if (!reader.isValid()) {
+      System.err.println("not a log file");
+      System.exit(1);
+      return;
+    }
+
+    Map<Integer, DataLogRecord.StartRecordData> entries = new HashMap<>();
+    for (DataLogRecord record : reader) {
+      if (record.isStart()) {
+        try {
+          DataLogRecord.StartRecordData data = record.getStartData();
+          System.out.println(
+              "Start("
+                  + data.entry
+                  + ", name='"
+                  + data.name
+                  + "', type='"
+                  + data.type
+                  + "', metadata='"
+                  + data.metadata
+                  + "') ["
+                  + (record.getTimestamp() / 1000000.0)
+                  + "]");
+          if (entries.containsKey(data.entry)) {
+            System.out.println("...DUPLICATE entry ID, overriding");
+          }
+          entries.put(data.entry, data);
+        } catch (InputMismatchException ex) {
+          System.out.println("Start(INVALID)");
+        }
+      } else if (record.isFinish()) {
+        try {
+          int entry = record.getFinishEntry();
+          System.out.println("Finish(" + entry + ") [" + (record.getTimestamp() / 1000000.0) + "]");
+          if (!entries.containsKey(entry)) {
+            System.out.println("...ID not found");
+          } else {
+            entries.remove(entry);
+          }
+        } catch (InputMismatchException ex) {
+          System.out.println("Finish(INVALID)");
+        }
+      } else if (record.isSetMetadata()) {
+        try {
+          DataLogRecord.MetadataRecordData data = record.getSetMetadataData();
+          System.out.println(
+              "SetMetadata("
+                  + data.entry
+                  + ", '"
+                  + data.metadata
+                  + "') ["
+                  + (record.getTimestamp() / 1000000.0)
+                  + "]");
+          if (!entries.containsKey(data.entry)) {
+            System.out.println("...ID not found");
+          }
+        } catch (InputMismatchException ex) {
+          System.out.println("SetMetadata(INVALID)");
+        }
+      } else if (record.isControl()) {
+        System.out.println("Unrecognized control record");
+      } else {
+        System.out.print("Data(" + record.getEntry() + ", size=" + record.getSize() + ") ");
+        DataLogRecord.StartRecordData entry = entries.get(record.getEntry());
+        if (entry == null) {
+          System.out.println("<ID not found>");
+          continue;
+        }
+        System.out.println(
+            "<name='"
+                + entry.name
+                + "', type='"
+                + entry.type
+                + "'> ["
+                + (record.getTimestamp() / 1000000.0)
+                + "]");
+
+        try {
+          // handle systemTime specially
+          if ("systemTime".equals(entry.name) && "int64".equals(entry.type)) {
+            long val = record.getInteger();
+            System.out.println(
+                "  "
+                    + m_timeFormatter.format(
+                        LocalDateTime.ofEpochSecond(val / 1000000, 0, ZoneOffset.UTC))
+                    + "."
+                    + String.format("%06d", val % 1000000));
+            continue;
+          }
+
+          if ("double".equals(entry.type)) {
+            System.out.println("  " + record.getDouble());
+          } else if ("int64".equals(entry.type)) {
+            System.out.println("  " + record.getInteger());
+          } else if ("string".equals(entry.type) || "json".equals(entry.type)) {
+            System.out.println("  '" + record.getString() + "'");
+          } else if ("boolean".equals(entry.type)) {
+            System.out.println("  " + record.getBoolean());
+          } else if ("double[]".equals(entry.type)) {
+            System.out.println("  " + Arrays.asList(record.getDoubleArray()));
+          } else if ("int64[]".equals(entry.type)) {
+            System.out.println("  " + Arrays.asList(record.getIntegerArray()));
+          } else if ("string[]".equals(entry.type)) {
+            System.out.println("  " + Arrays.asList(record.getStringArray()));
+          }
+        } catch (InputMismatchException ex) {
+          System.out.println("  invalid");
+        }
+      }
+    }
+  }
+
+  private PrintLog() {}
+}
diff --git a/third_party/allwpilib/wpiutil/src/test/java/edu/wpi/first/util/ErrorMessagesTest.java b/third_party/allwpilib/wpiutil/src/test/java/edu/wpi/first/util/ErrorMessagesTest.java
new file mode 100644
index 0000000..94e8bea
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/test/java/edu/wpi/first/util/ErrorMessagesTest.java
@@ -0,0 +1,24 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.util;
+
+import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
+import static org.junit.jupiter.api.Assertions.assertDoesNotThrow;
+import static org.junit.jupiter.api.Assertions.assertThrows;
+
+import org.junit.jupiter.api.Test;
+
+class ErrorMessagesTest {
+  @Test
+  void requireNonNullParamNullTest() {
+    assertThrows(
+        NullPointerException.class, () -> requireNonNullParam(null, "testParam", "testMethod"));
+  }
+
+  @Test
+  void requireNonNullParamNotNullTest() {
+    assertDoesNotThrow(() -> requireNonNullParam("null", "testParam", "testMethod"));
+  }
+}
diff --git a/third_party/allwpilib/wpiutil/src/test/java/edu/wpi/first/util/InterpolatingTreeMapTest.java b/third_party/allwpilib/wpiutil/src/test/java/edu/wpi/first/util/InterpolatingTreeMapTest.java
new file mode 100644
index 0000000..ea23dc5
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/test/java/edu/wpi/first/util/InterpolatingTreeMapTest.java
@@ -0,0 +1,134 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.util;
+
+import static org.junit.jupiter.api.Assertions.assertEquals;
+
+import org.junit.jupiter.api.Test;
+
+class InterpolatingTreeMapTest {
+  @Test
+  void testInterpolationDouble() {
+    InterpolatingTreeMap<Double, Double> table = new InterpolatingTreeMap<>();
+
+    table.put(125.0, 450.0);
+    table.put(200.0, 510.0);
+    table.put(268.0, 525.0);
+    table.put(312.0, 550.0);
+    table.put(326.0, 650.0);
+
+    // Key below minimum gives the smallest value
+    assertEquals(450.0, table.get(100.0));
+
+    // Minimum key gives exact value
+    assertEquals(450.0, table.get(125.0));
+
+    // Key gives interpolated value
+    assertEquals(480.0, table.get(162.5));
+
+    // Key at right of interpolation range gives exact value
+    assertEquals(510.0, table.get(200.0));
+
+    // Maximum key gives exact value
+    assertEquals(650.0, table.get(326.0));
+
+    // Key above maximum gives largest value
+    assertEquals(650.0, table.get(400.0));
+  }
+
+  @Test
+  void testInterpolationClear() {
+    InterpolatingTreeMap<Double, Double> table = new InterpolatingTreeMap<>();
+
+    table.put(125.0, 450.0);
+    table.put(200.0, 510.0);
+    table.put(268.0, 525.0);
+    table.put(312.0, 550.0);
+    table.put(326.0, 650.0);
+
+    // Key below minimum gives the smallest value
+    assertEquals(450.0, table.get(100.0));
+
+    // Minimum key gives exact value
+    assertEquals(450.0, table.get(125.0));
+
+    // Key gives interpolated value
+    assertEquals(480.0, table.get(162.5));
+
+    // Key at right of interpolation range gives exact value
+    assertEquals(510.0, table.get(200.0));
+
+    // Maximum key gives exact value
+    assertEquals(650.0, table.get(326.0));
+
+    // Key above maximum gives largest value
+    assertEquals(650.0, table.get(400.0));
+
+    table.clear();
+
+    table.put(100.0, 250.0);
+    table.put(200.0, 500.0);
+
+    assertEquals(375.0, table.get(150.0));
+  }
+
+  @Test
+  void testInterpolationInteger() {
+    InterpolatingTreeMap<Integer, Integer> table = new InterpolatingTreeMap<>();
+
+    table.put(125, 450);
+    table.put(200, 510);
+    table.put(268, 525);
+    table.put(312, 550);
+    table.put(326, 650);
+
+    // Key below minimum gives the smallest value
+    assertEquals(450.0, table.get(100));
+
+    // Minimum key gives exact value
+    assertEquals(450.0, table.get(125));
+
+    // Key gives interpolated value
+    assertEquals(479.6, table.get(162));
+
+    // Key at right of interpolation range gives exact value
+    assertEquals(510.0, table.get(200));
+
+    // Maximum key gives exact value
+    assertEquals(650.0, table.get(326));
+
+    // Key above maximum gives largest value
+    assertEquals(650.0, table.get(400));
+  }
+
+  @Test
+  void testInterpolationLong() {
+    InterpolatingTreeMap<Long, Long> table = new InterpolatingTreeMap<>();
+
+    table.put(125L, 450L);
+    table.put(200L, 510L);
+    table.put(268L, 525L);
+    table.put(312L, 550L);
+    table.put(326L, 650L);
+
+    // Key below minimum gives the smallest value
+    assertEquals(450.0, table.get(100L));
+
+    // Minimum key gives exact value
+    assertEquals(450.0, table.get(125L));
+
+    // Key gives interpolated value
+    assertEquals(479.6, table.get(162L));
+
+    // Key at right of interpolation range gives exact value
+    assertEquals(510.0, table.get(200L));
+
+    // Maximum key gives exact value
+    assertEquals(650.0, table.get(326L));
+
+    // Key above maximum gives largest value
+    assertEquals(650.0, table.get(400L));
+  }
+}
diff --git a/third_party/allwpilib/wpiutil/src/test/native/ManagedStaticTest.cpp b/third_party/allwpilib/wpiutil/src/test/native/ManagedStaticTest.cpp
deleted file mode 100644
index ab54499..0000000
--- a/third_party/allwpilib/wpiutil/src/test/native/ManagedStaticTest.cpp
+++ /dev/null
@@ -1,58 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/ManagedStatic.h"  // NOLINT(build/include_order)
-
-#include "gtest/gtest.h"
-
-static int refCount = 0;
-
-struct StaticTestClass {
-  StaticTestClass() { refCount++; }
-  ~StaticTestClass() { refCount--; }
-
-  void Func() {}
-};
-
-namespace wpi {
-TEST(ManagedStaticTest, LazyDoesNotInitialize) {
-  {
-    refCount = 0;
-    wpi::ManagedStatic<StaticTestClass> managedStatic;
-    (void)managedStatic;
-    ASSERT_EQ(refCount, 0);
-  }
-  ASSERT_EQ(refCount, 0);
-  wpi_shutdown();
-}
-
-TEST(ManagedStaticTest, LazyInitDoesntDestruct) {
-  {
-    refCount = 0;
-    wpi::ManagedStatic<StaticTestClass> managedStatic;
-    ASSERT_EQ(refCount, 0);
-    managedStatic->Func();
-    ASSERT_EQ(refCount, 1);
-  }
-  ASSERT_EQ(refCount, 1);
-  wpi_shutdown();
-  ASSERT_EQ(refCount, 0);
-}
-
-TEST(ManagedStaticTest, EagerInit) {
-  {
-    refCount = 0;
-    StaticTestClass* test = new StaticTestClass{};
-    ASSERT_EQ(refCount, 1);  // NOLINT
-    wpi::ManagedStatic<StaticTestClass> managedStatic(
-        test, [](void* val) { delete static_cast<StaticTestClass*>(val); });
-    ASSERT_EQ(refCount, 1);
-    managedStatic->Func();
-    ASSERT_EQ(refCount, 1);
-  }
-  ASSERT_EQ(refCount, 1);
-  wpi_shutdown();
-  ASSERT_EQ(refCount, 0);
-}
-}  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/ArrayTest.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/ArrayTest.cpp
index 15e1928..1f28157 100644
--- a/third_party/allwpilib/wpiutil/src/test/native/cpp/ArrayTest.cpp
+++ b/third_party/allwpilib/wpiutil/src/test/native/cpp/ArrayTest.cpp
@@ -15,16 +15,20 @@
 }  // namespace
 
 TEST(ArrayTest, CopyableTypeCompiles) {
-  wpi::array<int, 3> arr1{1, 2, 3};
+  constexpr wpi::array<int, 3> arr1{1, 2, 3};
+  static_cast<void>(arr1);
 
   // Test deduction guide
-  wpi::array ar2{1, 2, 3};
+  constexpr wpi::array arr2{1, 2, 3};
+  static_cast<void>(arr2);
 }
 
 TEST(ArrayTest, MoveOnlyTypeCompiles) {
-  wpi::array<MoveOnlyType, 3> arr1{MoveOnlyType{}, MoveOnlyType{},
-                                   MoveOnlyType{}};
+  constexpr wpi::array<MoveOnlyType, 3> arr1{MoveOnlyType{}, MoveOnlyType{},
+                                             MoveOnlyType{}};
+  static_cast<void>(arr1);
 
   // Test deduction guide
-  wpi::array arr2{MoveOnlyType{}, MoveOnlyType{}, MoveOnlyType{}};
+  constexpr wpi::array arr2{MoveOnlyType{}, MoveOnlyType{}, MoveOnlyType{}};
+  static_cast<void>(arr2);
 }
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/HttpParserTest.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/HttpParserTest.cpp
deleted file mode 100644
index 281abd0..0000000
--- a/third_party/allwpilib/wpiutil/src/test/native/cpp/HttpParserTest.cpp
+++ /dev/null
@@ -1,206 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/HttpParser.h"  // NOLINT(build/include_order)
-
-#include "gtest/gtest.h"
-
-namespace wpi {
-
-TEST(HttpParserTest, UrlMethodHeadersComplete) {
-  HttpParser p{HttpParser::kRequest};
-  int callbacks = 0;
-  p.url.connect([&](std::string_view path) {
-    ASSERT_EQ(path, "/foo/bar");
-    ASSERT_EQ(p.GetUrl(), "/foo/bar");
-    ++callbacks;
-  });
-  p.Execute("GET /foo");
-  p.Execute("/bar");
-  ASSERT_EQ(callbacks, 0);
-  p.Execute(" HTTP/1.1\r\n\r\n");
-  ASSERT_EQ(callbacks, 1);
-  ASSERT_EQ(p.GetUrl(), "/foo/bar");
-  ASSERT_EQ(p.GetMethod(), HTTP_GET);
-  ASSERT_FALSE(p.HasError());
-}
-
-TEST(HttpParserTest, UrlMethodHeader) {
-  HttpParser p{HttpParser::kRequest};
-  int callbacks = 0;
-  p.url.connect([&](std::string_view path) {
-    ASSERT_EQ(path, "/foo/bar");
-    ASSERT_EQ(p.GetUrl(), "/foo/bar");
-    ++callbacks;
-  });
-  p.Execute("GET /foo");
-  p.Execute("/bar");
-  ASSERT_EQ(callbacks, 0);
-  p.Execute(" HTTP/1.1\r\n");
-  ASSERT_EQ(callbacks, 0);
-  p.Execute("F");
-  ASSERT_EQ(callbacks, 1);
-  ASSERT_EQ(p.GetUrl(), "/foo/bar");
-  ASSERT_EQ(p.GetMethod(), HTTP_GET);
-  ASSERT_FALSE(p.HasError());
-}
-
-TEST(HttpParserTest, StatusHeadersComplete) {
-  HttpParser p{HttpParser::kResponse};
-  int callbacks = 0;
-  p.status.connect([&](std::string_view status) {
-    ASSERT_EQ(status, "OK");
-    ASSERT_EQ(p.GetStatusCode(), 200u);
-    ++callbacks;
-  });
-  p.Execute("HTTP/1.1 200");
-  p.Execute(" OK");
-  ASSERT_EQ(callbacks, 0);
-  p.Execute("\r\n\r\n");
-  ASSERT_EQ(callbacks, 1);
-  ASSERT_EQ(p.GetStatusCode(), 200u);
-  ASSERT_FALSE(p.HasError());
-}
-
-TEST(HttpParserTest, StatusHeader) {
-  HttpParser p{HttpParser::kResponse};
-  int callbacks = 0;
-  p.status.connect([&](std::string_view status) {
-    ASSERT_EQ(status, "OK");
-    ASSERT_EQ(p.GetStatusCode(), 200u);
-    ++callbacks;
-  });
-  p.Execute("HTTP/1.1 200");
-  p.Execute(" OK\r\n");
-  ASSERT_EQ(callbacks, 0);
-  p.Execute("F");
-  ASSERT_EQ(callbacks, 1);
-  ASSERT_EQ(p.GetStatusCode(), 200u);
-  ASSERT_FALSE(p.HasError());
-}
-
-TEST(HttpParserTest, HeaderFieldComplete) {
-  HttpParser p{HttpParser::kRequest};
-  int callbacks = 0;
-  p.header.connect([&](std::string_view name, std::string_view value) {
-    ASSERT_EQ(name, "Foo");
-    ASSERT_EQ(value, "Bar");
-    ++callbacks;
-  });
-  p.Execute("GET / HTTP/1.1\r\n");
-  ASSERT_EQ(callbacks, 0);
-  p.Execute("Fo");
-  ASSERT_EQ(callbacks, 0);
-  p.Execute("o: ");
-  ASSERT_EQ(callbacks, 0);
-  p.Execute("Bar");
-  ASSERT_EQ(callbacks, 0);
-  p.Execute("\r\n");
-  ASSERT_EQ(callbacks, 0);
-  p.Execute("\r\n");
-  ASSERT_EQ(callbacks, 1);
-  ASSERT_FALSE(p.HasError());
-}
-
-TEST(HttpParserTest, HeaderFieldNext) {
-  HttpParser p{HttpParser::kRequest};
-  int callbacks = 0;
-  p.header.connect([&](std::string_view name, std::string_view value) {
-    ASSERT_EQ(name, "Foo");
-    ASSERT_EQ(value, "Bar");
-    ++callbacks;
-  });
-  p.Execute("GET / HTTP/1.1\r\n");
-  ASSERT_EQ(callbacks, 0);
-  p.Execute("Fo");
-  ASSERT_EQ(callbacks, 0);
-  p.Execute("o: ");
-  ASSERT_EQ(callbacks, 0);
-  p.Execute("Bar");
-  ASSERT_EQ(callbacks, 0);
-  p.Execute("\r\n");
-  ASSERT_EQ(callbacks, 0);
-  p.Execute("F");
-  ASSERT_EQ(callbacks, 1);
-  ASSERT_FALSE(p.HasError());
-}
-
-TEST(HttpParserTest, HeadersComplete) {
-  HttpParser p{HttpParser::kRequest};
-  int callbacks = 0;
-  p.headersComplete.connect([&](bool keepAlive) {
-    ASSERT_EQ(keepAlive, false);
-    ++callbacks;
-  });
-  p.Execute("GET / HTTP/1.0\r\n");
-  ASSERT_EQ(callbacks, 0);
-  p.Execute("\r\n");
-  ASSERT_EQ(callbacks, 1);
-  ASSERT_FALSE(p.HasError());
-}
-
-TEST(HttpParserTest, HeadersCompleteHTTP11) {
-  HttpParser p{HttpParser::kRequest};
-  int callbacks = 0;
-  p.headersComplete.connect([&](bool keepAlive) {
-    ASSERT_EQ(keepAlive, true);
-    ++callbacks;
-  });
-  p.Execute("GET / HTTP/1.1\r\n");
-  ASSERT_EQ(callbacks, 0);
-  p.Execute("\r\n");
-  ASSERT_EQ(callbacks, 1);
-  ASSERT_FALSE(p.HasError());
-}
-
-TEST(HttpParserTest, HeadersCompleteKeepAlive) {
-  HttpParser p{HttpParser::kRequest};
-  int callbacks = 0;
-  p.headersComplete.connect([&](bool keepAlive) {
-    ASSERT_EQ(keepAlive, true);
-    ++callbacks;
-  });
-  p.Execute("GET / HTTP/1.0\r\n");
-  ASSERT_EQ(callbacks, 0);
-  p.Execute("Connection: Keep-Alive\r\n");
-  ASSERT_EQ(callbacks, 0);
-  p.Execute("\r\n");
-  ASSERT_EQ(callbacks, 1);
-  ASSERT_FALSE(p.HasError());
-}
-
-TEST(HttpParserTest, HeadersCompleteUpgrade) {
-  HttpParser p{HttpParser::kRequest};
-  int callbacks = 0;
-  p.headersComplete.connect([&](bool) {
-    ASSERT_TRUE(p.IsUpgrade());
-    ++callbacks;
-  });
-  p.Execute("GET / HTTP/1.0\r\n");
-  ASSERT_EQ(callbacks, 0);
-  p.Execute("Connection: Upgrade\r\n");
-  p.Execute("Upgrade: websocket\r\n");
-  ASSERT_EQ(callbacks, 0);
-  p.Execute("\r\n");
-  ASSERT_EQ(callbacks, 1);
-  ASSERT_FALSE(p.HasError());
-}
-
-TEST(HttpParserTest, Reset) {
-  HttpParser p{HttpParser::kRequest};
-  int callbacks = 0;
-  p.headersComplete.connect([&](bool) { ++callbacks; });
-  p.Execute("GET / HTTP/1.1\r\n");
-  ASSERT_EQ(callbacks, 0);
-  p.Execute("\r\n");
-  ASSERT_EQ(callbacks, 1);
-  p.Reset(HttpParser::kRequest);
-  p.Execute("GET / HTTP/1.1\r\n");
-  ASSERT_EQ(callbacks, 1);
-  p.Execute("\r\n");
-  ASSERT_EQ(callbacks, 2);
-  ASSERT_FALSE(p.HasError());
-}
-
-}  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/HttpUtilTest.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/HttpUtilTest.cpp
deleted file mode 100644
index 524086a..0000000
--- a/third_party/allwpilib/wpiutil/src/test/native/cpp/HttpUtilTest.cpp
+++ /dev/null
@@ -1,102 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/HttpUtil.h"  // NOLINT(build/include_order)
-
-#include "gtest/gtest.h"
-
-namespace wpi {
-
-TEST(HttpMultipartScannerTest, ExecuteExact) {
-  HttpMultipartScanner scanner("foo");
-  EXPECT_TRUE(scanner.Execute("abcdefg---\r\n--foo\r\n").empty());
-  EXPECT_TRUE(scanner.IsDone());
-  EXPECT_TRUE(scanner.GetSkipped().empty());
-}
-
-TEST(HttpMultipartScannerTest, ExecutePartial) {
-  HttpMultipartScanner scanner("foo");
-  EXPECT_TRUE(scanner.Execute("abcdefg--").empty());
-  EXPECT_FALSE(scanner.IsDone());
-  EXPECT_TRUE(scanner.Execute("-\r\n").empty());
-  EXPECT_FALSE(scanner.IsDone());
-  EXPECT_TRUE(scanner.Execute("--foo\r").empty());
-  EXPECT_FALSE(scanner.IsDone());
-  EXPECT_TRUE(scanner.Execute("\n").empty());
-  EXPECT_TRUE(scanner.IsDone());
-}
-
-TEST(HttpMultipartScannerTest, ExecuteTrailing) {
-  HttpMultipartScanner scanner("foo");
-  EXPECT_EQ(scanner.Execute("abcdefg---\r\n--foo\r\nxyz"), "xyz");
-}
-
-TEST(HttpMultipartScannerTest, ExecutePadding) {
-  HttpMultipartScanner scanner("foo");
-  EXPECT_EQ(scanner.Execute("abcdefg---\r\n--foo    \r\nxyz"), "xyz");
-  EXPECT_TRUE(scanner.IsDone());
-}
-
-TEST(HttpMultipartScannerTest, SaveSkipped) {
-  HttpMultipartScanner scanner("foo", true);
-  scanner.Execute("abcdefg---\r\n--foo\r\n");
-  EXPECT_EQ(scanner.GetSkipped(), "abcdefg---\r\n--foo\r\n");
-}
-
-TEST(HttpMultipartScannerTest, Reset) {
-  HttpMultipartScanner scanner("foo", true);
-
-  scanner.Execute("abcdefg---\r\n--foo\r\n");
-  EXPECT_TRUE(scanner.IsDone());
-  EXPECT_EQ(scanner.GetSkipped(), "abcdefg---\r\n--foo\r\n");
-
-  scanner.Reset(true);
-  EXPECT_FALSE(scanner.IsDone());
-  scanner.SetBoundary("bar");
-
-  scanner.Execute("--foo\r\n--bar\r\n");
-  EXPECT_TRUE(scanner.IsDone());
-  EXPECT_EQ(scanner.GetSkipped(), "--foo\r\n--bar\r\n");
-}
-
-TEST(HttpMultipartScannerTest, WithoutDashes) {
-  HttpMultipartScanner scanner("foo", true);
-
-  EXPECT_TRUE(scanner.Execute("--\r\nfoo\r\n").empty());
-  EXPECT_TRUE(scanner.IsDone());
-}
-
-TEST(HttpMultipartScannerTest, SeqDashesDashes) {
-  HttpMultipartScanner scanner("foo", true);
-  EXPECT_TRUE(scanner.Execute("\r\n--foo\r\n").empty());
-  EXPECT_TRUE(scanner.IsDone());
-  EXPECT_TRUE(scanner.Execute("\r\n--foo\r\n").empty());
-  EXPECT_TRUE(scanner.IsDone());
-}
-
-TEST(HttpMultipartScannerTest, SeqDashesNoDashes) {
-  HttpMultipartScanner scanner("foo", true);
-  EXPECT_TRUE(scanner.Execute("\r\n--foo\r\n").empty());
-  EXPECT_TRUE(scanner.IsDone());
-  EXPECT_TRUE(scanner.Execute("\r\nfoo\r\n").empty());
-  EXPECT_FALSE(scanner.IsDone());
-}
-
-TEST(HttpMultipartScannerTest, SeqNoDashesDashes) {
-  HttpMultipartScanner scanner("foo", true);
-  EXPECT_TRUE(scanner.Execute("\r\nfoo\r\n").empty());
-  EXPECT_TRUE(scanner.IsDone());
-  EXPECT_TRUE(scanner.Execute("\r\n--foo\r\n").empty());
-  EXPECT_FALSE(scanner.IsDone());
-}
-
-TEST(HttpMultipartScannerTest, SeqNoDashesNoDashes) {
-  HttpMultipartScanner scanner("foo", true);
-  EXPECT_TRUE(scanner.Execute("\r\nfoo\r\n").empty());
-  EXPECT_TRUE(scanner.IsDone());
-  EXPECT_TRUE(scanner.Execute("\r\nfoo\r\n").empty());
-  EXPECT_TRUE(scanner.IsDone());
-}
-
-}  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/HttpWebSocketServerConnectionTest.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/HttpWebSocketServerConnectionTest.cpp
deleted file mode 100644
index 18a21be..0000000
--- a/third_party/allwpilib/wpiutil/src/test/native/cpp/HttpWebSocketServerConnectionTest.cpp
+++ /dev/null
@@ -1,25 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/HttpWebSocketServerConnection.h"  // NOLINT(build/include_order)
-
-#include <gtest/gtest.h>
-
-namespace wpi {
-
-class HttpWebSocketServerConnectionTest
-    : public HttpWebSocketServerConnection<HttpWebSocketServerConnectionTest> {
- public:
-  HttpWebSocketServerConnectionTest(std::shared_ptr<uv::Stream> stream,
-                                    span<const std::string_view> protocols)
-      : HttpWebSocketServerConnection{stream, protocols} {}
-
-  void ProcessRequest() override { ++gotRequest; }
-  void ProcessWsUpgrade() override { ++gotUpgrade; }
-
-  int gotRequest = 0;
-  int gotUpgrade = 0;
-};
-
-}  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/InterpolatingMapTest.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/InterpolatingMapTest.cpp
new file mode 100644
index 0000000..4479da5
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/test/native/cpp/InterpolatingMapTest.cpp
@@ -0,0 +1,52 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "wpi/interpolating_map.h"  // NOLINT(build/include_order)
+
+#include <gtest/gtest.h>
+
+TEST(InterpolatingMapTest, Insert) {
+  wpi::interpolating_map<double, double> table;
+
+  table.insert(125, 450);
+  table.insert(200, 510);
+  table.insert(268, 525);
+  table.insert(312, 550);
+  table.insert(326, 650);
+
+  // Key below minimum gives smallest value
+  EXPECT_EQ(450, table[100]);
+
+  // Minimum key gives exact value
+  EXPECT_EQ(450, table[125]);
+
+  // Key gives interpolated value
+  EXPECT_EQ(480, table[162.5]);
+
+  // Key at right of interpolation range gives exact value
+  EXPECT_EQ(510, table[200]);
+
+  // Maximum key gives exact value
+  EXPECT_EQ(650, table[326]);
+
+  // Key above maximum gives largest value
+  EXPECT_EQ(650, table[400]);
+}
+
+TEST(InterpolatingMapTest, Clear) {
+  wpi::interpolating_map<double, double> table;
+
+  table.insert(125, 450);
+  table.insert(200, 510);
+  table.insert(268, 525);
+  table.insert(312, 550);
+  table.insert(326, 650);
+
+  table.clear();
+
+  table.insert(100, 250);
+  table.insert(200, 500);
+
+  EXPECT_EQ(375, table[150]);
+}
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/ScopeExitTest.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/ScopeExitTest.cpp
new file mode 100644
index 0000000..9cecb1c
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/test/native/cpp/ScopeExitTest.cpp
@@ -0,0 +1,36 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "gtest/gtest.h"
+#include "wpi/scope"
+
+TEST(ScopeExitTest, ScopeExit) {
+  int exitCount = 0;
+
+  {
+    wpi::scope_exit exit{[&] { ++exitCount; }};
+
+    EXPECT_EQ(0, exitCount);
+  }
+
+  EXPECT_EQ(1, exitCount);
+}
+
+TEST(ScopeExitTest, Release) {
+  int exitCount = 0;
+
+  {
+    wpi::scope_exit exit1{[&] { ++exitCount; }};
+    wpi::scope_exit exit2 = std::move(exit1);
+    wpi::scope_exit exit3 = std::move(exit1);
+    EXPECT_EQ(0, exitCount);
+  }
+  EXPECT_EQ(1, exitCount);
+
+  {
+    wpi::scope_exit exit{[&] { ++exitCount; }};
+    exit.release();
+  }
+  EXPECT_EQ(1, exitCount);
+}
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/UnescapeCStringTest.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/UnescapeCStringTest.cpp
new file mode 100644
index 0000000..7f0ca5f
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/test/native/cpp/UnescapeCStringTest.cpp
@@ -0,0 +1,74 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "gtest/gtest.h"
+#include "wpi/SmallString.h"
+#include "wpi/StringExtras.h"
+
+using namespace wpi;
+
+namespace {
+
+TEST(UnescapeCStringTest, Basic) {
+  SmallString<64> buf;
+  auto [out, rem] = UnescapeCString("abc\\\\\\a\\b\\f\\n\\r\\t\\v\\", buf);
+  EXPECT_EQ(out, "abc\\\a\b\f\n\r\t\v\\");
+  EXPECT_TRUE(rem.empty());
+}
+
+TEST(UnescapeCStringTest, QuoteEnd) {
+  SmallString<64> buf;
+  auto [out, rem] = UnescapeCString("abc\\\"\"123", buf);
+  EXPECT_EQ(out, "abc\"");
+  EXPECT_EQ(rem, "\"123");
+}
+
+TEST(UnescapeCStringTest, Hex) {
+  SmallString<64> buf;
+  auto [out, rem] = UnescapeCString("\\xfe\\xFE\\x01", buf);
+  EXPECT_EQ(out, "\xfe\xFE\x01");
+  EXPECT_TRUE(rem.empty());
+}
+
+TEST(UnescapeCStringTest, HexPartial) {
+  SmallString<64> buf;
+  auto [out, rem] = UnescapeCString("\\xz\\x5z\\x2", buf);
+  EXPECT_EQ(out, "xz\x05z\x02");
+  EXPECT_TRUE(rem.empty());
+}
+
+TEST(UnescapeCStringTest, HexPartial2) {
+  SmallString<64> buf;
+  auto [out, rem] = UnescapeCString("\\x", buf);
+  EXPECT_EQ(out, "x");
+  EXPECT_TRUE(rem.empty());
+}
+
+TEST(UnescapeCStringTest, Octal) {
+  SmallString<64> buf;
+  auto [out, rem] = UnescapeCString("\\3\\11\\222\\4", buf);
+  EXPECT_EQ(out, "\3\11\222\4");
+  EXPECT_TRUE(rem.empty());
+}
+
+TEST(UnescapeCStringTest, EmptyString) {
+  SmallString<64> buf;
+  auto [out, rem] = UnescapeCString("", buf);
+  EXPECT_EQ(out, "");
+}
+
+TEST(UnescapeCStringTest, ShortString) {
+  SmallString<64> buf;
+  auto [out, rem] = UnescapeCString("a", buf);
+  EXPECT_EQ(out, "a");
+}
+
+TEST(UnescapeCStringTest, NoEscapesString) {
+  SmallString<64> buf;
+  std::string_view input = "abcdefghijklmnopqrstuvwxyz1234567890";
+  auto [out, rem] = UnescapeCString(input, buf);
+  EXPECT_EQ(out, input);
+}
+
+}  // namespace
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/WebSocketClientTest.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/WebSocketClientTest.cpp
deleted file mode 100644
index 9d85e66..0000000
--- a/third_party/allwpilib/wpiutil/src/test/native/cpp/WebSocketClientTest.cpp
+++ /dev/null
@@ -1,319 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/WebSocket.h"  // NOLINT(build/include_order)
-
-#include "WebSocketTest.h"
-#include "wpi/Base64.h"
-#include "wpi/HttpParser.h"
-#include "wpi/SmallString.h"
-#include "wpi/StringExtras.h"
-#include "wpi/raw_uv_ostream.h"
-#include "wpi/sha1.h"
-
-namespace wpi {
-
-class WebSocketClientTest : public WebSocketTest {
- public:
-  WebSocketClientTest() {
-    // Bare bones server
-    req.header.connect([this](std::string_view name, std::string_view value) {
-      // save key (required for valid response)
-      if (equals_lower(name, "sec-websocket-key")) {
-        clientKey = value;
-      }
-    });
-    req.headersComplete.connect([this](bool) {
-      // send response
-      SmallVector<uv::Buffer, 4> bufs;
-      raw_uv_ostream os{bufs, 4096};
-      os << "HTTP/1.1 101 Switching Protocols\r\n";
-      os << "Upgrade: websocket\r\n";
-      os << "Connection: Upgrade\r\n";
-
-      // accept hash
-      SHA1 hash;
-      hash.Update(clientKey);
-      hash.Update("258EAFA5-E914-47DA-95CA-C5AB0DC85B11");
-      if (mockBadAccept) {
-        hash.Update("1");
-      }
-      SmallString<64> hashBuf;
-      SmallString<64> acceptBuf;
-      os << "Sec-WebSocket-Accept: "
-         << Base64Encode(hash.RawFinal(hashBuf), acceptBuf) << "\r\n";
-
-      if (!mockProtocol.empty()) {
-        os << "Sec-WebSocket-Protocol: " << mockProtocol << "\r\n";
-      }
-
-      os << "\r\n";
-
-      conn->Write(bufs, [](auto bufs, uv::Error) {
-        for (auto& buf : bufs) {
-          buf.Deallocate();
-        }
-      });
-
-      serverHeadersDone = true;
-      if (connected) {
-        connected();
-      }
-    });
-
-    serverPipe->Listen([this] {
-      conn = serverPipe->Accept();
-      conn->StartRead();
-      conn->data.connect([this](uv::Buffer& buf, size_t size) {
-        std::string_view data{buf.base, size};
-        if (!serverHeadersDone) {
-          data = req.Execute(data);
-          if (req.HasError()) {
-            Finish();
-          }
-          ASSERT_EQ(req.GetError(), HPE_OK) << http_errno_name(req.GetError());
-          if (data.empty()) {
-            return;
-          }
-        }
-        wireData.insert(wireData.end(), data.begin(), data.end());
-      });
-      conn->end.connect([this] { Finish(); });
-    });
-  }
-
-  bool mockBadAccept = false;
-  std::vector<uint8_t> wireData;
-  std::shared_ptr<uv::Pipe> conn;
-  HttpParser req{HttpParser::kRequest};
-  SmallString<64> clientKey;
-  std::string mockProtocol;
-  bool serverHeadersDone = false;
-  std::function<void()> connected;
-};
-
-TEST_F(WebSocketClientTest, Open) {
-  int gotOpen = 0;
-
-  clientPipe->Connect(pipeName, [&] {
-    auto ws = WebSocket::CreateClient(*clientPipe, "/test", pipeName);
-    ws->closed.connect([&](uint16_t code, std::string_view reason) {
-      Finish();
-      if (code != 1005 && code != 1006) {
-        FAIL() << "Code: " << code << " Reason: " << reason;
-      }
-    });
-    ws->open.connect([&](std::string_view protocol) {
-      ++gotOpen;
-      Finish();
-      ASSERT_TRUE(protocol.empty());
-    });
-  });
-
-  loop->Run();
-
-  if (HasFatalFailure()) {
-    return;
-  }
-  ASSERT_EQ(gotOpen, 1);
-}
-
-TEST_F(WebSocketClientTest, BadAccept) {
-  int gotClosed = 0;
-
-  mockBadAccept = true;
-
-  clientPipe->Connect(pipeName, [&] {
-    auto ws = WebSocket::CreateClient(*clientPipe, "/test", pipeName);
-    ws->closed.connect([&](uint16_t code, std::string_view msg) {
-      Finish();
-      ++gotClosed;
-      ASSERT_EQ(code, 1002) << "Message: " << msg;
-    });
-    ws->open.connect([&](std::string_view protocol) {
-      Finish();
-      FAIL() << "Got open";
-    });
-  });
-
-  loop->Run();
-
-  if (HasFatalFailure()) {
-    return;
-  }
-  ASSERT_EQ(gotClosed, 1);
-}
-
-TEST_F(WebSocketClientTest, ProtocolGood) {
-  int gotOpen = 0;
-
-  mockProtocol = "myProtocol";
-
-  clientPipe->Connect(pipeName, [&] {
-    auto ws = WebSocket::CreateClient(*clientPipe, "/test", pipeName,
-                                      {"myProtocol", "myProtocol2"});
-    ws->closed.connect([&](uint16_t code, std::string_view msg) {
-      Finish();
-      if (code != 1005 && code != 1006) {
-        FAIL() << "Code: " << code << "Message: " << msg;
-      }
-    });
-    ws->open.connect([&](std::string_view protocol) {
-      ++gotOpen;
-      Finish();
-      ASSERT_EQ(protocol, "myProtocol");
-    });
-  });
-
-  loop->Run();
-
-  if (HasFatalFailure()) {
-    return;
-  }
-  ASSERT_EQ(gotOpen, 1);
-}
-
-TEST_F(WebSocketClientTest, ProtocolRespNotReq) {
-  int gotClosed = 0;
-
-  mockProtocol = "myProtocol";
-
-  clientPipe->Connect(pipeName, [&] {
-    auto ws = WebSocket::CreateClient(*clientPipe, "/test", pipeName);
-    ws->closed.connect([&](uint16_t code, std::string_view msg) {
-      Finish();
-      ++gotClosed;
-      ASSERT_EQ(code, 1003) << "Message: " << msg;
-    });
-    ws->open.connect([&](std::string_view protocol) {
-      Finish();
-      FAIL() << "Got open";
-    });
-  });
-
-  loop->Run();
-
-  if (HasFatalFailure()) {
-    return;
-  }
-  ASSERT_EQ(gotClosed, 1);
-}
-
-TEST_F(WebSocketClientTest, ProtocolReqNotResp) {
-  int gotClosed = 0;
-
-  clientPipe->Connect(pipeName, [&] {
-    auto ws = WebSocket::CreateClient(*clientPipe, "/test", pipeName,
-                                      {{"myProtocol"}});
-    ws->closed.connect([&](uint16_t code, std::string_view msg) {
-      Finish();
-      ++gotClosed;
-      ASSERT_EQ(code, 1002) << "Message: " << msg;
-    });
-    ws->open.connect([&](std::string_view protocol) {
-      Finish();
-      FAIL() << "Got open";
-    });
-  });
-
-  loop->Run();
-
-  if (HasFatalFailure()) {
-    return;
-  }
-  ASSERT_EQ(gotClosed, 1);
-}
-
-//
-// Send and receive data.  Most of these cases are tested in
-// WebSocketServerTest, so only spot check differences like masking.
-//
-
-class WebSocketClientDataTest : public WebSocketClientTest,
-                                public ::testing::WithParamInterface<size_t> {
- public:
-  WebSocketClientDataTest() {
-    clientPipe->Connect(pipeName, [&] {
-      ws = WebSocket::CreateClient(*clientPipe, "/test", pipeName);
-      if (setupWebSocket) {
-        setupWebSocket();
-      }
-    });
-  }
-
-  std::function<void()> setupWebSocket;
-  std::shared_ptr<WebSocket> ws;
-};
-
-INSTANTIATE_TEST_SUITE_P(WebSocketClientDataTests, WebSocketClientDataTest,
-                         ::testing::Values(0, 1, 125, 126, 65535, 65536));
-
-TEST_P(WebSocketClientDataTest, SendBinary) {
-  int gotCallback = 0;
-  std::vector<uint8_t> data(GetParam(), 0x03u);
-  setupWebSocket = [&] {
-    ws->open.connect([&](std::string_view) {
-      ws->SendBinary({{data}}, [&](auto bufs, uv::Error) {
-        ++gotCallback;
-        ws->Terminate();
-        ASSERT_FALSE(bufs.empty());
-        ASSERT_EQ(bufs[0].base, reinterpret_cast<const char*>(data.data()));
-      });
-    });
-  };
-
-  loop->Run();
-
-  auto expectData = BuildMessage(0x02, true, true, data);
-  AdjustMasking(wireData);
-  ASSERT_EQ(wireData, expectData);
-  ASSERT_EQ(gotCallback, 1);
-}
-
-TEST_P(WebSocketClientDataTest, ReceiveBinary) {
-  int gotCallback = 0;
-  std::vector<uint8_t> data(GetParam(), 0x03u);
-  setupWebSocket = [&] {
-    ws->binary.connect([&](auto inData, bool fin) {
-      ++gotCallback;
-      ws->Terminate();
-      ASSERT_TRUE(fin);
-      std::vector<uint8_t> recvData{inData.begin(), inData.end()};
-      ASSERT_EQ(data, recvData);
-    });
-  };
-  auto message = BuildMessage(0x02, true, false, data);
-  connected = [&] { conn->Write({{message}}, [&](auto bufs, uv::Error) {}); };
-
-  loop->Run();
-
-  ASSERT_EQ(gotCallback, 1);
-}
-
-//
-// The client must close the connection if a masked frame is received.
-//
-
-TEST_P(WebSocketClientDataTest, ReceiveMasked) {
-  int gotCallback = 0;
-  std::vector<uint8_t> data(GetParam(), ' ');
-  setupWebSocket = [&] {
-    ws->text.connect([&](std::string_view, bool) {
-      ws->Terminate();
-      FAIL() << "Should not have gotten masked message";
-    });
-    ws->closed.connect([&](uint16_t code, std::string_view reason) {
-      ++gotCallback;
-      ASSERT_EQ(code, 1002) << "reason: " << reason;
-    });
-  };
-  auto message = BuildMessage(0x01, true, true, data);
-  connected = [&] { conn->Write({{message}}, [&](auto bufs, uv::Error) {}); };
-
-  loop->Run();
-
-  ASSERT_EQ(gotCallback, 1);
-}
-
-}  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/WebSocketIntegrationTest.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/WebSocketIntegrationTest.cpp
deleted file mode 100644
index 3de75d9..0000000
--- a/third_party/allwpilib/wpiutil/src/test/native/cpp/WebSocketIntegrationTest.cpp
+++ /dev/null
@@ -1,149 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/WebSocketServer.h"  // NOLINT(build/include_order)
-
-#include "WebSocketTest.h"
-#include "wpi/HttpParser.h"
-#include "wpi/SmallString.h"
-
-namespace wpi {
-
-class WebSocketIntegrationTest : public WebSocketTest {};
-
-TEST_F(WebSocketIntegrationTest, Open) {
-  int gotServerOpen = 0;
-  int gotClientOpen = 0;
-
-  serverPipe->Listen([&]() {
-    auto conn = serverPipe->Accept();
-    auto server = WebSocketServer::Create(*conn);
-    server->connected.connect([&](std::string_view url, WebSocket&) {
-      ++gotServerOpen;
-      ASSERT_EQ(url, "/test");
-    });
-  });
-
-  clientPipe->Connect(pipeName, [&] {
-    auto ws = WebSocket::CreateClient(*clientPipe, "/test", pipeName);
-    ws->closed.connect([&](uint16_t code, std::string_view reason) {
-      Finish();
-      if (code != 1005 && code != 1006) {
-        FAIL() << "Code: " << code << " Reason: " << reason;
-      }
-    });
-    ws->open.connect([&, s = ws.get()](std::string_view) {
-      ++gotClientOpen;
-      s->Close();
-    });
-  });
-
-  loop->Run();
-
-  ASSERT_EQ(gotServerOpen, 1);
-  ASSERT_EQ(gotClientOpen, 1);
-}
-
-TEST_F(WebSocketIntegrationTest, Protocol) {
-  int gotServerOpen = 0;
-  int gotClientOpen = 0;
-
-  serverPipe->Listen([&]() {
-    auto conn = serverPipe->Accept();
-    auto server = WebSocketServer::Create(*conn, {"proto1", "proto2"});
-    server->connected.connect([&](std::string_view, WebSocket& ws) {
-      ++gotServerOpen;
-      ASSERT_EQ(ws.GetProtocol(), "proto1");
-    });
-  });
-
-  clientPipe->Connect(pipeName, [&] {
-    auto ws =
-        WebSocket::CreateClient(*clientPipe, "/test", pipeName, {"proto1"});
-    ws->closed.connect([&](uint16_t code, std::string_view reason) {
-      Finish();
-      if (code != 1005 && code != 1006) {
-        FAIL() << "Code: " << code << " Reason: " << reason;
-      }
-    });
-    ws->open.connect([&, s = ws.get()](std::string_view protocol) {
-      ++gotClientOpen;
-      s->Close();
-      ASSERT_EQ(protocol, "proto1");
-    });
-  });
-
-  loop->Run();
-
-  ASSERT_EQ(gotServerOpen, 1);
-  ASSERT_EQ(gotClientOpen, 1);
-}
-
-TEST_F(WebSocketIntegrationTest, ServerSendBinary) {
-  int gotData = 0;
-
-  serverPipe->Listen([&]() {
-    auto conn = serverPipe->Accept();
-    auto server = WebSocketServer::Create(*conn);
-    server->connected.connect([&](std::string_view, WebSocket& ws) {
-      ws.SendBinary({uv::Buffer{"\x03\x04", 2}}, [&](auto, uv::Error) {});
-      ws.Close();
-    });
-  });
-
-  clientPipe->Connect(pipeName, [&] {
-    auto ws = WebSocket::CreateClient(*clientPipe, "/test", pipeName);
-    ws->closed.connect([&](uint16_t code, std::string_view reason) {
-      Finish();
-      if (code != 1005 && code != 1006) {
-        FAIL() << "Code: " << code << " Reason: " << reason;
-      }
-    });
-    ws->binary.connect([&](auto data, bool) {
-      ++gotData;
-      std::vector<uint8_t> recvData{data.begin(), data.end()};
-      std::vector<uint8_t> expectData{0x03, 0x04};
-      ASSERT_EQ(recvData, expectData);
-    });
-  });
-
-  loop->Run();
-
-  ASSERT_EQ(gotData, 1);
-}
-
-TEST_F(WebSocketIntegrationTest, ClientSendText) {
-  int gotData = 0;
-
-  serverPipe->Listen([&]() {
-    auto conn = serverPipe->Accept();
-    auto server = WebSocketServer::Create(*conn);
-    server->connected.connect([&](std::string_view, WebSocket& ws) {
-      ws.text.connect([&](std::string_view data, bool) {
-        ++gotData;
-        ASSERT_EQ(data, "hello");
-      });
-    });
-  });
-
-  clientPipe->Connect(pipeName, [&] {
-    auto ws = WebSocket::CreateClient(*clientPipe, "/test", pipeName);
-    ws->closed.connect([&](uint16_t code, std::string_view reason) {
-      Finish();
-      if (code != 1005 && code != 1006) {
-        FAIL() << "Code: " << code << " Reason: " << reason;
-      }
-    });
-    ws->open.connect([&, s = ws.get()](std::string_view) {
-      s->SendText({{"hello"}}, [&](auto, uv::Error) {});
-      s->Close();
-    });
-  });
-
-  loop->Run();
-
-  ASSERT_EQ(gotData, 1);
-}
-
-}  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/WebSocketServerTest.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/WebSocketServerTest.cpp
deleted file mode 100644
index 83561bf..0000000
--- a/third_party/allwpilib/wpiutil/src/test/native/cpp/WebSocketServerTest.cpp
+++ /dev/null
@@ -1,736 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/WebSocket.h"  // NOLINT(build/include_order)
-
-#include "WebSocketTest.h"
-#include "wpi/Base64.h"
-#include "wpi/HttpParser.h"
-#include "wpi/SmallString.h"
-#include "wpi/raw_uv_ostream.h"
-#include "wpi/sha1.h"
-
-namespace wpi {
-
-class WebSocketServerTest : public WebSocketTest {
- public:
-  WebSocketServerTest() {
-    resp.headersComplete.connect([this](bool) { headersDone = true; });
-
-    serverPipe->Listen([this]() {
-      auto conn = serverPipe->Accept();
-      ws = WebSocket::CreateServer(*conn, "foo", "13");
-      if (setupWebSocket) {
-        setupWebSocket();
-      }
-    });
-    clientPipe->Connect(pipeName, [this]() {
-      clientPipe->StartRead();
-      clientPipe->data.connect([this](uv::Buffer& buf, size_t size) {
-        std::string_view data{buf.base, size};
-        if (!headersDone) {
-          data = resp.Execute(data);
-          if (resp.HasError()) {
-            Finish();
-          }
-          ASSERT_EQ(resp.GetError(), HPE_OK)
-              << http_errno_name(resp.GetError());
-          if (data.empty()) {
-            return;
-          }
-        }
-        wireData.insert(wireData.end(), data.begin(), data.end());
-        if (handleData) {
-          handleData(data);
-        }
-      });
-      clientPipe->end.connect([this]() { Finish(); });
-    });
-  }
-
-  std::function<void()> setupWebSocket;
-  std::function<void(std::string_view)> handleData;
-  std::vector<uint8_t> wireData;
-  std::shared_ptr<WebSocket> ws;
-  HttpParser resp{HttpParser::kResponse};
-  bool headersDone = false;
-};
-
-//
-// Terminate closes the endpoint but doesn't send a close frame.
-//
-
-TEST_F(WebSocketServerTest, Terminate) {
-  int gotClosed = 0;
-  setupWebSocket = [&] {
-    ws->open.connect([&](std::string_view) { ws->Terminate(); });
-    ws->closed.connect([&](uint16_t code, std::string_view reason) {
-      ++gotClosed;
-      ASSERT_EQ(code, 1006) << "reason: " << reason;
-    });
-  };
-
-  loop->Run();
-
-  ASSERT_TRUE(wireData.empty());  // terminate doesn't send data
-  ASSERT_EQ(gotClosed, 1);
-}
-
-TEST_F(WebSocketServerTest, TerminateCode) {
-  int gotClosed = 0;
-  setupWebSocket = [&] {
-    ws->open.connect([&](std::string_view) { ws->Terminate(1000); });
-    ws->closed.connect([&](uint16_t code, std::string_view reason) {
-      ++gotClosed;
-      ASSERT_EQ(code, 1000) << "reason: " << reason;
-    });
-  };
-
-  loop->Run();
-
-  ASSERT_TRUE(wireData.empty());  // terminate doesn't send data
-  ASSERT_EQ(gotClosed, 1);
-}
-
-TEST_F(WebSocketServerTest, TerminateReason) {
-  int gotClosed = 0;
-  setupWebSocket = [&] {
-    ws->open.connect([&](std::string_view) { ws->Terminate(1000, "reason"); });
-    ws->closed.connect([&](uint16_t code, std::string_view reason) {
-      ++gotClosed;
-      ASSERT_EQ(code, 1000);
-      ASSERT_EQ(reason, "reason");
-    });
-  };
-
-  loop->Run();
-
-  ASSERT_TRUE(wireData.empty());  // terminate doesn't send data
-  ASSERT_EQ(gotClosed, 1);
-}
-
-//
-// Close() sends a close frame.
-//
-
-TEST_F(WebSocketServerTest, CloseBasic) {
-  int gotClosed = 0;
-  setupWebSocket = [&] {
-    ws->open.connect([&](std::string_view) { ws->Close(); });
-    ws->closed.connect([&](uint16_t code, std::string_view reason) {
-      ++gotClosed;
-      ASSERT_EQ(code, 1005) << "reason: " << reason;
-    });
-  };
-  // need to respond with close for server to finish shutdown
-  auto message = BuildMessage(0x08, true, true, {});
-  handleData = [&](std::string_view) {
-    clientPipe->Write({{message}}, [&](auto bufs, uv::Error) {});
-  };
-
-  loop->Run();
-
-  auto expectData = BuildMessage(0x08, true, false, {});
-  ASSERT_EQ(wireData, expectData);
-  ASSERT_EQ(gotClosed, 1);
-}
-
-TEST_F(WebSocketServerTest, CloseCode) {
-  int gotClosed = 0;
-  setupWebSocket = [&] {
-    ws->open.connect([&](std::string_view) { ws->Close(1000); });
-    ws->closed.connect([&](uint16_t code, std::string_view reason) {
-      ++gotClosed;
-      ASSERT_EQ(code, 1000) << "reason: " << reason;
-    });
-  };
-  // need to respond with close for server to finish shutdown
-  const uint8_t contents[] = {0x03u, 0xe8u};
-  auto message = BuildMessage(0x08, true, true, contents);
-  handleData = [&](std::string_view) {
-    clientPipe->Write({{message}}, [&](auto bufs, uv::Error) {});
-  };
-
-  loop->Run();
-
-  auto expectData = BuildMessage(0x08, true, false, contents);
-  ASSERT_EQ(wireData, expectData);
-  ASSERT_EQ(gotClosed, 1);
-}
-
-TEST_F(WebSocketServerTest, CloseReason) {
-  int gotClosed = 0;
-  setupWebSocket = [&] {
-    ws->open.connect([&](std::string_view) { ws->Close(1000, "hangup"); });
-    ws->closed.connect([&](uint16_t code, std::string_view reason) {
-      ++gotClosed;
-      ASSERT_EQ(code, 1000);
-      ASSERT_EQ(reason, "hangup");
-    });
-  };
-  // need to respond with close for server to finish shutdown
-  const uint8_t contents[] = {0x03u, 0xe8u, 'h', 'a', 'n', 'g', 'u', 'p'};
-  auto message = BuildMessage(0x08, true, true, contents);
-  handleData = [&](std::string_view) {
-    clientPipe->Write({{message}}, [&](auto bufs, uv::Error) {});
-  };
-
-  loop->Run();
-
-  auto expectData = BuildMessage(0x08, true, false, contents);
-  ASSERT_EQ(wireData, expectData);
-  ASSERT_EQ(gotClosed, 1);
-}
-
-//
-// Receiving a close frame results in closure and echoing the close frame.
-//
-
-TEST_F(WebSocketServerTest, ReceiveCloseBasic) {
-  int gotClosed = 0;
-  setupWebSocket = [&] {
-    ws->closed.connect([&](uint16_t code, std::string_view reason) {
-      ++gotClosed;
-      ASSERT_EQ(code, 1005) << "reason: " << reason;
-    });
-  };
-  auto message = BuildMessage(0x08, true, true, {});
-  resp.headersComplete.connect([&](bool) {
-    clientPipe->Write({{message}}, [&](auto bufs, uv::Error) {});
-  });
-
-  loop->Run();
-
-  // the endpoint should echo the message
-  auto expectData = BuildMessage(0x08, true, false, {});
-  ASSERT_EQ(wireData, expectData);
-  ASSERT_EQ(gotClosed, 1);
-}
-
-TEST_F(WebSocketServerTest, ReceiveCloseCode) {
-  int gotClosed = 0;
-  setupWebSocket = [&] {
-    ws->closed.connect([&](uint16_t code, std::string_view reason) {
-      ++gotClosed;
-      ASSERT_EQ(code, 1000) << "reason: " << reason;
-    });
-  };
-  const uint8_t contents[] = {0x03u, 0xe8u};
-  auto message = BuildMessage(0x08, true, true, contents);
-  resp.headersComplete.connect([&](bool) {
-    clientPipe->Write({{message}}, [&](auto bufs, uv::Error) {});
-  });
-
-  loop->Run();
-
-  // the endpoint should echo the message
-  auto expectData = BuildMessage(0x08, true, false, contents);
-  ASSERT_EQ(wireData, expectData);
-  ASSERT_EQ(gotClosed, 1);
-}
-
-TEST_F(WebSocketServerTest, ReceiveCloseReason) {
-  int gotClosed = 0;
-  setupWebSocket = [&] {
-    ws->closed.connect([&](uint16_t code, std::string_view reason) {
-      ++gotClosed;
-      ASSERT_EQ(code, 1000);
-      ASSERT_EQ(reason, "hangup");
-    });
-  };
-  const uint8_t contents[] = {0x03u, 0xe8u, 'h', 'a', 'n', 'g', 'u', 'p'};
-  auto message = BuildMessage(0x08, true, true, contents);
-  resp.headersComplete.connect([&](bool) {
-    clientPipe->Write({{message}}, [&](auto bufs, uv::Error) {});
-  });
-
-  loop->Run();
-
-  // the endpoint should echo the message
-  auto expectData = BuildMessage(0x08, true, false, contents);
-  ASSERT_EQ(wireData, expectData);
-  ASSERT_EQ(gotClosed, 1);
-}
-
-//
-// If an unknown opcode is received, the receiving endpoint MUST _Fail the
-// WebSocket Connection_.
-//
-
-class WebSocketServerBadOpcodeTest
-    : public WebSocketServerTest,
-      public ::testing::WithParamInterface<uint8_t> {};
-
-INSTANTIATE_TEST_SUITE_P(WebSocketServerBadOpcodeTests,
-                         WebSocketServerBadOpcodeTest,
-                         ::testing::Values(3, 4, 5, 6, 7, 0xb, 0xc, 0xd, 0xe,
-                                           0xf));
-
-TEST_P(WebSocketServerBadOpcodeTest, Receive) {
-  int gotCallback = 0;
-  std::vector<uint8_t> data(4, 0x03);
-  setupWebSocket = [&] {
-    ws->closed.connect([&](uint16_t code, std::string_view reason) {
-      ++gotCallback;
-      ASSERT_EQ(code, 1002) << "reason: " << reason;
-    });
-  };
-  auto message = BuildMessage(GetParam(), true, true, data);
-  resp.headersComplete.connect([&](bool) {
-    clientPipe->Write({{message}}, [&](auto bufs, uv::Error) {});
-  });
-
-  loop->Run();
-
-  ASSERT_EQ(gotCallback, 1);
-}
-
-//
-// Control frames themselves MUST NOT be fragmented.
-//
-
-class WebSocketServerControlFrameTest
-    : public WebSocketServerTest,
-      public ::testing::WithParamInterface<uint8_t> {};
-
-INSTANTIATE_TEST_SUITE_P(WebSocketServerControlFrameTests,
-                         WebSocketServerControlFrameTest,
-                         ::testing::Values(0x8, 0x9, 0xa));
-
-TEST_P(WebSocketServerControlFrameTest, ReceiveFragment) {
-  int gotCallback = 0;
-  std::vector<uint8_t> data(4, 0x03);
-  setupWebSocket = [&] {
-    ws->closed.connect([&](uint16_t code, std::string_view reason) {
-      ++gotCallback;
-      ASSERT_EQ(code, 1002) << "reason: " << reason;
-    });
-  };
-  auto message = BuildMessage(GetParam(), false, true, data);
-  resp.headersComplete.connect([&](bool) {
-    clientPipe->Write({{message}}, [&](auto bufs, uv::Error) {});
-  });
-
-  loop->Run();
-
-  ASSERT_EQ(gotCallback, 1);
-}
-
-//
-// A fragmented message consists of a single frame with the FIN bit
-// clear and an opcode other than 0, followed by zero or more frames
-// with the FIN bit clear and the opcode set to 0, and terminated by
-// a single frame with the FIN bit set and an opcode of 0.
-//
-
-// No previous message
-TEST_F(WebSocketServerTest, ReceiveFragmentInvalidNoPrevFrame) {
-  int gotCallback = 0;
-  std::vector<uint8_t> data(4, 0x03);
-  setupWebSocket = [&] {
-    ws->closed.connect([&](uint16_t code, std::string_view reason) {
-      ++gotCallback;
-      ASSERT_EQ(code, 1002) << "reason: " << reason;
-    });
-  };
-  auto message = BuildMessage(0x00, false, true, data);
-  resp.headersComplete.connect([&](bool) {
-    clientPipe->Write({{message}}, [&](auto bufs, uv::Error) {});
-  });
-
-  loop->Run();
-
-  ASSERT_EQ(gotCallback, 1);
-}
-
-// No previous message with FIN=1.
-TEST_F(WebSocketServerTest, ReceiveFragmentInvalidNoPrevFragment) {
-  int gotCallback = 0;
-  std::vector<uint8_t> data(4, 0x03);
-  setupWebSocket = [&] {
-    ws->closed.connect([&](uint16_t code, std::string_view reason) {
-      ++gotCallback;
-      ASSERT_EQ(code, 1002) << "reason: " << reason;
-    });
-  };
-  auto message = BuildMessage(0x01, true, true, {});  // FIN=1
-  auto message2 = BuildMessage(0x00, false, true, data);
-  resp.headersComplete.connect([&](bool) {
-    clientPipe->Write({{message}, {message2}}, [&](auto bufs, uv::Error) {});
-  });
-
-  loop->Run();
-
-  ASSERT_EQ(gotCallback, 1);
-}
-
-// Incomplete fragment
-TEST_F(WebSocketServerTest, ReceiveFragmentInvalidIncomplete) {
-  int gotCallback = 0;
-  setupWebSocket = [&] {
-    ws->closed.connect([&](uint16_t code, std::string_view reason) {
-      ++gotCallback;
-      ASSERT_EQ(code, 1002) << "reason: " << reason;
-    });
-  };
-  auto message = BuildMessage(0x01, false, true, {});
-  auto message2 = BuildMessage(0x00, false, true, {});
-  auto message3 = BuildMessage(0x01, true, true, {});
-  resp.headersComplete.connect([&](bool) {
-    clientPipe->Write({{message}, {message2}, {message3}},
-                      [&](auto bufs, uv::Error) {});
-  });
-
-  loop->Run();
-
-  ASSERT_EQ(gotCallback, 1);
-}
-
-// Normally fragments are combined into a single callback
-TEST_F(WebSocketServerTest, ReceiveFragment) {
-  int gotCallback = 0;
-
-  std::vector<uint8_t> data(4, 0x03);
-  std::vector<uint8_t> data2(4, 0x04);
-  std::vector<uint8_t> data3(4, 0x05);
-  std::vector<uint8_t> combData{data};
-  combData.insert(combData.end(), data2.begin(), data2.end());
-  combData.insert(combData.end(), data3.begin(), data3.end());
-
-  setupWebSocket = [&] {
-    ws->binary.connect([&](auto inData, bool fin) {
-      ++gotCallback;
-      ws->Terminate();
-      ASSERT_TRUE(fin);
-      std::vector<uint8_t> recvData{inData.begin(), inData.end()};
-      ASSERT_EQ(combData, recvData);
-    });
-  };
-
-  auto message = BuildMessage(0x02, false, true, data);
-  auto message2 = BuildMessage(0x00, false, true, data2);
-  auto message3 = BuildMessage(0x00, true, true, data3);
-  resp.headersComplete.connect([&](bool) {
-    clientPipe->Write({{message}, {message2}, {message3}},
-                      [&](auto bufs, uv::Error) {});
-  });
-
-  loop->Run();
-
-  ASSERT_EQ(gotCallback, 1);
-}
-
-// But can be configured for multiple callbacks
-TEST_F(WebSocketServerTest, ReceiveFragmentSeparate) {
-  int gotCallback = 0;
-
-  std::vector<uint8_t> data(4, 0x03);
-  std::vector<uint8_t> data2(4, 0x04);
-  std::vector<uint8_t> data3(4, 0x05);
-  std::vector<uint8_t> combData{data};
-  combData.insert(combData.end(), data2.begin(), data2.end());
-  combData.insert(combData.end(), data3.begin(), data3.end());
-
-  setupWebSocket = [&] {
-    ws->SetCombineFragments(false);
-    ws->binary.connect([&](auto inData, bool fin) {
-      std::vector<uint8_t> recvData{inData.begin(), inData.end()};
-      switch (++gotCallback) {
-        case 1:
-          ASSERT_FALSE(fin);
-          ASSERT_EQ(data, recvData);
-          break;
-        case 2:
-          ASSERT_FALSE(fin);
-          ASSERT_EQ(data2, recvData);
-          break;
-        case 3:
-          ws->Terminate();
-          ASSERT_TRUE(fin);
-          ASSERT_EQ(data3, recvData);
-          break;
-        default:
-          FAIL() << "too many callbacks";
-          break;
-      }
-    });
-  };
-
-  auto message = BuildMessage(0x02, false, true, data);
-  auto message2 = BuildMessage(0x00, false, true, data2);
-  auto message3 = BuildMessage(0x00, true, true, data3);
-  resp.headersComplete.connect([&](bool) {
-    clientPipe->Write({{message}, {message2}, {message3}},
-                      [&](auto bufs, uv::Error) {});
-  });
-
-  loop->Run();
-
-  ASSERT_EQ(gotCallback, 3);
-}
-
-//
-// Maximum message size is limited.
-//
-
-// Single message
-TEST_F(WebSocketServerTest, ReceiveTooLarge) {
-  int gotCallback = 0;
-  std::vector<uint8_t> data(2048, 0x03u);
-  setupWebSocket = [&] {
-    ws->SetMaxMessageSize(1024);
-    ws->binary.connect([&](auto, bool) {
-      ws->Terminate();
-      FAIL() << "Should not have gotten unmasked message";
-    });
-    ws->closed.connect([&](uint16_t code, std::string_view reason) {
-      ++gotCallback;
-      ASSERT_EQ(code, 1009) << "reason: " << reason;
-    });
-  };
-  auto message = BuildMessage(0x01, true, true, data);
-  resp.headersComplete.connect([&](bool) {
-    clientPipe->Write({{message}}, [&](auto bufs, uv::Error) {});
-  });
-
-  loop->Run();
-
-  ASSERT_EQ(gotCallback, 1);
-}
-
-// Applied across fragments if combining
-TEST_F(WebSocketServerTest, ReceiveTooLargeFragmented) {
-  int gotCallback = 0;
-  std::vector<uint8_t> data(768, 0x03u);
-  setupWebSocket = [&] {
-    ws->SetMaxMessageSize(1024);
-    ws->binary.connect([&](auto, bool) {
-      ws->Terminate();
-      FAIL() << "Should not have gotten unmasked message";
-    });
-    ws->closed.connect([&](uint16_t code, std::string_view reason) {
-      ++gotCallback;
-      ASSERT_EQ(code, 1009) << "reason: " << reason;
-    });
-  };
-  auto message = BuildMessage(0x01, false, true, data);
-  auto message2 = BuildMessage(0x00, true, true, data);
-  resp.headersComplete.connect([&](bool) {
-    clientPipe->Write({{message}, {message2}}, [&](auto bufs, uv::Error) {});
-  });
-
-  loop->Run();
-
-  ASSERT_EQ(gotCallback, 1);
-}
-
-//
-// Send and receive data.
-//
-
-class WebSocketServerDataTest : public WebSocketServerTest,
-                                public ::testing::WithParamInterface<size_t> {};
-
-INSTANTIATE_TEST_SUITE_P(WebSocketServerDataTests, WebSocketServerDataTest,
-                         ::testing::Values(0, 1, 125, 126, 65535, 65536));
-
-TEST_P(WebSocketServerDataTest, SendText) {
-  int gotCallback = 0;
-  std::vector<uint8_t> data(GetParam(), ' ');
-  setupWebSocket = [&] {
-    ws->open.connect([&](std::string_view) {
-      ws->SendText({{data}}, [&](auto bufs, uv::Error) {
-        ++gotCallback;
-        ws->Terminate();
-        ASSERT_FALSE(bufs.empty());
-        ASSERT_EQ(bufs[0].base, reinterpret_cast<const char*>(data.data()));
-      });
-    });
-  };
-
-  loop->Run();
-
-  auto expectData = BuildMessage(0x01, true, false, data);
-  ASSERT_EQ(wireData, expectData);
-  ASSERT_EQ(gotCallback, 1);
-}
-
-TEST_P(WebSocketServerDataTest, SendBinary) {
-  int gotCallback = 0;
-  std::vector<uint8_t> data(GetParam(), 0x03u);
-  setupWebSocket = [&] {
-    ws->open.connect([&](std::string_view) {
-      ws->SendBinary({{data}}, [&](auto bufs, uv::Error) {
-        ++gotCallback;
-        ws->Terminate();
-        ASSERT_FALSE(bufs.empty());
-        ASSERT_EQ(bufs[0].base, reinterpret_cast<const char*>(data.data()));
-      });
-    });
-  };
-
-  loop->Run();
-
-  auto expectData = BuildMessage(0x02, true, false, data);
-  ASSERT_EQ(wireData, expectData);
-  ASSERT_EQ(gotCallback, 1);
-}
-
-TEST_P(WebSocketServerDataTest, SendPing) {
-  int gotCallback = 0;
-  std::vector<uint8_t> data(GetParam(), 0x03u);
-  setupWebSocket = [&] {
-    ws->open.connect([&](std::string_view) {
-      ws->SendPing({{data}}, [&](auto bufs, uv::Error) {
-        ++gotCallback;
-        ws->Terminate();
-        ASSERT_FALSE(bufs.empty());
-        ASSERT_EQ(bufs[0].base, reinterpret_cast<const char*>(data.data()));
-      });
-    });
-  };
-
-  loop->Run();
-
-  auto expectData = BuildMessage(0x09, true, false, data);
-  ASSERT_EQ(wireData, expectData);
-  ASSERT_EQ(gotCallback, 1);
-}
-
-TEST_P(WebSocketServerDataTest, SendPong) {
-  int gotCallback = 0;
-  std::vector<uint8_t> data(GetParam(), 0x03u);
-  setupWebSocket = [&] {
-    ws->open.connect([&](std::string_view) {
-      ws->SendPong({{data}}, [&](auto bufs, uv::Error) {
-        ++gotCallback;
-        ws->Terminate();
-        ASSERT_FALSE(bufs.empty());
-        ASSERT_EQ(bufs[0].base, reinterpret_cast<const char*>(data.data()));
-      });
-    });
-  };
-
-  loop->Run();
-
-  auto expectData = BuildMessage(0x0a, true, false, data);
-  ASSERT_EQ(wireData, expectData);
-  ASSERT_EQ(gotCallback, 1);
-}
-
-TEST_P(WebSocketServerDataTest, ReceiveText) {
-  int gotCallback = 0;
-  std::vector<uint8_t> data(GetParam(), ' ');
-  setupWebSocket = [&] {
-    ws->text.connect([&](std::string_view inData, bool fin) {
-      ++gotCallback;
-      ws->Terminate();
-      ASSERT_TRUE(fin);
-      std::vector<uint8_t> recvData;
-      recvData.insert(recvData.end(), inData.begin(), inData.end());
-      ASSERT_EQ(data, recvData);
-    });
-  };
-  auto message = BuildMessage(0x01, true, true, data);
-  resp.headersComplete.connect([&](bool) {
-    clientPipe->Write({{message}}, [&](auto bufs, uv::Error) {});
-  });
-
-  loop->Run();
-
-  ASSERT_EQ(gotCallback, 1);
-}
-
-TEST_P(WebSocketServerDataTest, ReceiveBinary) {
-  int gotCallback = 0;
-  std::vector<uint8_t> data(GetParam(), 0x03u);
-  setupWebSocket = [&] {
-    ws->binary.connect([&](auto inData, bool fin) {
-      ++gotCallback;
-      ws->Terminate();
-      ASSERT_TRUE(fin);
-      std::vector<uint8_t> recvData{inData.begin(), inData.end()};
-      ASSERT_EQ(data, recvData);
-    });
-  };
-  auto message = BuildMessage(0x02, true, true, data);
-  resp.headersComplete.connect([&](bool) {
-    clientPipe->Write({{message}}, [&](auto bufs, uv::Error) {});
-  });
-
-  loop->Run();
-
-  ASSERT_EQ(gotCallback, 1);
-}
-
-TEST_P(WebSocketServerDataTest, ReceivePing) {
-  int gotCallback = 0;
-  std::vector<uint8_t> data(GetParam(), 0x03u);
-  setupWebSocket = [&] {
-    ws->ping.connect([&](auto inData) {
-      ++gotCallback;
-      ws->Terminate();
-      std::vector<uint8_t> recvData{inData.begin(), inData.end()};
-      ASSERT_EQ(data, recvData);
-    });
-  };
-  auto message = BuildMessage(0x09, true, true, data);
-  resp.headersComplete.connect([&](bool) {
-    clientPipe->Write({{message}}, [&](auto bufs, uv::Error) {});
-  });
-
-  loop->Run();
-
-  ASSERT_EQ(gotCallback, 1);
-}
-
-TEST_P(WebSocketServerDataTest, ReceivePong) {
-  int gotCallback = 0;
-  std::vector<uint8_t> data(GetParam(), 0x03u);
-  setupWebSocket = [&] {
-    ws->pong.connect([&](auto inData) {
-      ++gotCallback;
-      ws->Terminate();
-      std::vector<uint8_t> recvData{inData.begin(), inData.end()};
-      ASSERT_EQ(data, recvData);
-    });
-  };
-  auto message = BuildMessage(0x0a, true, true, data);
-  resp.headersComplete.connect([&](bool) {
-    clientPipe->Write({{message}}, [&](auto bufs, uv::Error) {});
-  });
-
-  loop->Run();
-
-  ASSERT_EQ(gotCallback, 1);
-}
-
-//
-// The server must close the connection if an unmasked frame is received.
-//
-
-TEST_P(WebSocketServerDataTest, ReceiveUnmasked) {
-  int gotCallback = 0;
-  std::vector<uint8_t> data(GetParam(), ' ');
-  setupWebSocket = [&] {
-    ws->text.connect([&](std::string_view, bool) {
-      ws->Terminate();
-      FAIL() << "Should not have gotten unmasked message";
-    });
-    ws->closed.connect([&](uint16_t code, std::string_view reason) {
-      ++gotCallback;
-      ASSERT_EQ(code, 1002) << "reason: " << reason;
-    });
-  };
-  auto message = BuildMessage(0x01, true, false, data);
-  resp.headersComplete.connect([&](bool) {
-    clientPipe->Write({{message}}, [&](auto bufs, uv::Error) {});
-  });
-
-  loop->Run();
-
-  ASSERT_EQ(gotCallback, 1);
-}
-
-}  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/WebSocketTest.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/WebSocketTest.cpp
deleted file mode 100644
index b5d5e4e..0000000
--- a/third_party/allwpilib/wpiutil/src/test/native/cpp/WebSocketTest.cpp
+++ /dev/null
@@ -1,379 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/WebSocket.h"  // NOLINT(build/include_order)
-
-#include "WebSocketTest.h"
-
-#include "wpi/HttpParser.h"
-#include "wpi/StringExtras.h"
-
-namespace wpi {
-
-#ifdef _WIN32
-const char* WebSocketTest::pipeName = "\\\\.\\pipe\\websocket-unit-test";
-#else
-const char* WebSocketTest::pipeName = "/tmp/websocket-unit-test";
-#endif
-const uint8_t WebSocketTest::testMask[4] = {0x11, 0x22, 0x33, 0x44};
-
-void WebSocketTest::SetUpTestCase() {
-#ifndef _WIN32
-  unlink(pipeName);
-#endif
-}
-
-std::vector<uint8_t> WebSocketTest::BuildHeader(uint8_t opcode, bool fin,
-                                                bool masking, uint64_t len) {
-  std::vector<uint8_t> data;
-  data.push_back(opcode | (fin ? 0x80u : 0x00u));
-  if (len < 126) {
-    data.push_back(len | (masking ? 0x80 : 0x00u));
-  } else if (len < 65536) {
-    data.push_back(126u | (masking ? 0x80 : 0x00u));
-    data.push_back(len >> 8);
-    data.push_back(len & 0xff);
-  } else {
-    data.push_back(127u | (masking ? 0x80u : 0x00u));
-    for (int i = 56; i >= 0; i -= 8) {
-      data.push_back((len >> i) & 0xff);
-    }
-  }
-  if (masking) {
-    data.insert(data.end(), &testMask[0], &testMask[4]);
-  }
-  return data;
-}
-
-std::vector<uint8_t> WebSocketTest::BuildMessage(uint8_t opcode, bool fin,
-                                                 bool masking,
-                                                 span<const uint8_t> data) {
-  auto finalData = BuildHeader(opcode, fin, masking, data.size());
-  size_t headerSize = finalData.size();
-  finalData.insert(finalData.end(), data.begin(), data.end());
-  if (masking) {
-    uint8_t mask[4] = {finalData[headerSize - 4], finalData[headerSize - 3],
-                       finalData[headerSize - 2], finalData[headerSize - 1]};
-    int n = 0;
-    for (size_t i = headerSize, end = finalData.size(); i < end; ++i) {
-      finalData[i] ^= mask[n++];
-      if (n >= 4) {
-        n = 0;
-      }
-    }
-  }
-  return finalData;
-}
-
-// If the message is masked, changes the mask to match the mask set by
-// BuildHeader() by unmasking and remasking.
-void WebSocketTest::AdjustMasking(span<uint8_t> message) {
-  if (message.size() < 2) {
-    return;
-  }
-  if ((message[1] & 0x80) == 0) {
-    return;  // not masked
-  }
-  size_t maskPos;
-  uint8_t len = message[1] & 0x7f;
-  if (len == 126) {
-    maskPos = 4;
-  } else if (len == 127) {
-    maskPos = 10;
-  } else {
-    maskPos = 2;
-  }
-  uint8_t mask[4] = {message[maskPos], message[maskPos + 1],
-                     message[maskPos + 2], message[maskPos + 3]};
-  message[maskPos] = testMask[0];
-  message[maskPos + 1] = testMask[1];
-  message[maskPos + 2] = testMask[2];
-  message[maskPos + 3] = testMask[3];
-  int n = 0;
-  for (auto& ch : message.subspan(maskPos + 4)) {
-    ch ^= mask[n] ^ testMask[n];
-    if (++n >= 4) {
-      n = 0;
-    }
-  }
-}
-
-TEST_F(WebSocketTest, CreateClientBasic) {
-  int gotHost = 0;
-  int gotUpgrade = 0;
-  int gotConnection = 0;
-  int gotKey = 0;
-  int gotVersion = 0;
-
-  HttpParser req{HttpParser::kRequest};
-  req.url.connect([](std::string_view url) { ASSERT_EQ(url, "/test"); });
-  req.header.connect([&](std::string_view name, std::string_view value) {
-    if (equals_lower(name, "host")) {
-      ASSERT_EQ(value, pipeName);
-      ++gotHost;
-    } else if (equals_lower(name, "upgrade")) {
-      ASSERT_EQ(value, "websocket");
-      ++gotUpgrade;
-    } else if (equals_lower(name, "connection")) {
-      ASSERT_EQ(value, "Upgrade");
-      ++gotConnection;
-    } else if (equals_lower(name, "sec-websocket-key")) {
-      ++gotKey;
-    } else if (equals_lower(name, "sec-websocket-version")) {
-      ASSERT_EQ(value, "13");
-      ++gotVersion;
-    } else {
-      FAIL() << "unexpected header " << name;
-    }
-  });
-  req.headersComplete.connect([&](bool) { Finish(); });
-
-  serverPipe->Listen([&]() {
-    auto conn = serverPipe->Accept();
-    conn->StartRead();
-    conn->data.connect([&](uv::Buffer& buf, size_t size) {
-      req.Execute(std::string_view{buf.base, size});
-      if (req.HasError()) {
-        Finish();
-      }
-      ASSERT_EQ(req.GetError(), HPE_OK) << http_errno_name(req.GetError());
-    });
-  });
-  clientPipe->Connect(pipeName, [&]() {
-    auto ws = WebSocket::CreateClient(*clientPipe, "/test", pipeName);
-  });
-
-  loop->Run();
-
-  if (HasFatalFailure()) {
-    return;
-  }
-  ASSERT_EQ(gotHost, 1);
-  ASSERT_EQ(gotUpgrade, 1);
-  ASSERT_EQ(gotConnection, 1);
-  ASSERT_EQ(gotKey, 1);
-  ASSERT_EQ(gotVersion, 1);
-}
-
-TEST_F(WebSocketTest, CreateClientExtraHeaders) {
-  int gotExtra1 = 0;
-  int gotExtra2 = 0;
-  HttpParser req{HttpParser::kRequest};
-  req.header.connect([&](std::string_view name, std::string_view value) {
-    if (equals(name, "Extra1")) {
-      ASSERT_EQ(value, "Data1");
-      ++gotExtra1;
-    } else if (equals(name, "Extra2")) {
-      ASSERT_EQ(value, "Data2");
-      ++gotExtra2;
-    }
-  });
-  req.headersComplete.connect([&](bool) { Finish(); });
-
-  serverPipe->Listen([&]() {
-    auto conn = serverPipe->Accept();
-    conn->StartRead();
-    conn->data.connect([&](uv::Buffer& buf, size_t size) {
-      req.Execute(std::string_view{buf.base, size});
-      if (req.HasError()) {
-        Finish();
-      }
-      ASSERT_EQ(req.GetError(), HPE_OK) << http_errno_name(req.GetError());
-    });
-  });
-  clientPipe->Connect(pipeName, [&]() {
-    WebSocket::ClientOptions options;
-    SmallVector<std::pair<std::string_view, std::string_view>, 4> extraHeaders;
-    extraHeaders.emplace_back("Extra1", "Data1");
-    extraHeaders.emplace_back("Extra2", "Data2");
-    options.extraHeaders = extraHeaders;
-    auto ws =
-        WebSocket::CreateClient(*clientPipe, "/test", pipeName, {}, options);
-  });
-
-  loop->Run();
-
-  if (HasFatalFailure()) {
-    return;
-  }
-  ASSERT_EQ(gotExtra1, 1);
-  ASSERT_EQ(gotExtra2, 1);
-}
-
-TEST_F(WebSocketTest, CreateClientTimeout) {
-  int gotClosed = 0;
-  serverPipe->Listen([&]() { auto conn = serverPipe->Accept(); });
-  clientPipe->Connect(pipeName, [&]() {
-    WebSocket::ClientOptions options;
-    options.handshakeTimeout = uv::Timer::Time{100};
-    auto ws =
-        WebSocket::CreateClient(*clientPipe, "/test", pipeName, {}, options);
-    ws->closed.connect([&](uint16_t code, std::string_view) {
-      Finish();
-      ++gotClosed;
-      ASSERT_EQ(code, 1006);
-    });
-  });
-
-  loop->Run();
-
-  if (HasFatalFailure()) {
-    return;
-  }
-  ASSERT_EQ(gotClosed, 1);
-}
-
-TEST_F(WebSocketTest, CreateServerBasic) {
-  int gotStatus = 0;
-  int gotUpgrade = 0;
-  int gotConnection = 0;
-  int gotAccept = 0;
-  int gotOpen = 0;
-
-  HttpParser resp{HttpParser::kResponse};
-  resp.status.connect([&](std::string_view status) {
-    ++gotStatus;
-    ASSERT_EQ(resp.GetStatusCode(), 101u) << "status: " << status;
-  });
-  resp.header.connect([&](std::string_view name, std::string_view value) {
-    if (equals_lower(name, "upgrade")) {
-      ASSERT_EQ(value, "websocket");
-      ++gotUpgrade;
-    } else if (equals_lower(name, "connection")) {
-      ASSERT_EQ(value, "Upgrade");
-      ++gotConnection;
-    } else if (equals_lower(name, "sec-websocket-accept")) {
-      ASSERT_EQ(value, "s3pPLMBiTxaQ9kYGzzhZRbK+xOo=");
-      ++gotAccept;
-    } else {
-      FAIL() << "unexpected header " << name;
-    }
-  });
-  resp.headersComplete.connect([&](bool) { Finish(); });
-
-  serverPipe->Listen([&]() {
-    auto conn = serverPipe->Accept();
-    auto ws = WebSocket::CreateServer(*conn, "dGhlIHNhbXBsZSBub25jZQ==", "13");
-    ws->open.connect([&](std::string_view protocol) {
-      ++gotOpen;
-      ASSERT_TRUE(protocol.empty());
-    });
-  });
-  clientPipe->Connect(pipeName, [&] {
-    clientPipe->StartRead();
-    clientPipe->data.connect([&](uv::Buffer& buf, size_t size) {
-      resp.Execute(std::string_view{buf.base, size});
-      if (resp.HasError()) {
-        Finish();
-      }
-      ASSERT_EQ(resp.GetError(), HPE_OK) << http_errno_name(resp.GetError());
-    });
-  });
-
-  loop->Run();
-
-  if (HasFatalFailure()) {
-    return;
-  }
-  ASSERT_EQ(gotStatus, 1);
-  ASSERT_EQ(gotUpgrade, 1);
-  ASSERT_EQ(gotConnection, 1);
-  ASSERT_EQ(gotAccept, 1);
-  ASSERT_EQ(gotOpen, 1);
-}
-
-TEST_F(WebSocketTest, CreateServerProtocol) {
-  int gotProtocol = 0;
-  int gotOpen = 0;
-
-  HttpParser resp{HttpParser::kResponse};
-  resp.header.connect([&](std::string_view name, std::string_view value) {
-    if (equals_lower(name, "sec-websocket-protocol")) {
-      ++gotProtocol;
-      ASSERT_EQ(value, "myProtocol");
-    }
-  });
-  resp.headersComplete.connect([&](bool) { Finish(); });
-
-  serverPipe->Listen([&]() {
-    auto conn = serverPipe->Accept();
-    auto ws = WebSocket::CreateServer(*conn, "foo", "13", "myProtocol");
-    ws->open.connect([&](std::string_view protocol) {
-      ++gotOpen;
-      ASSERT_EQ(protocol, "myProtocol");
-    });
-  });
-  clientPipe->Connect(pipeName, [&] {
-    clientPipe->StartRead();
-    clientPipe->data.connect([&](uv::Buffer& buf, size_t size) {
-      resp.Execute(std::string_view{buf.base, size});
-      if (resp.HasError()) {
-        Finish();
-      }
-      ASSERT_EQ(resp.GetError(), HPE_OK) << http_errno_name(resp.GetError());
-    });
-  });
-
-  loop->Run();
-
-  if (HasFatalFailure()) {
-    return;
-  }
-  ASSERT_EQ(gotProtocol, 1);
-  ASSERT_EQ(gotOpen, 1);
-}
-
-TEST_F(WebSocketTest, CreateServerBadVersion) {
-  int gotStatus = 0;
-  int gotVersion = 0;
-  int gotUpgrade = 0;
-
-  HttpParser resp{HttpParser::kResponse};
-  resp.status.connect([&](std::string_view status) {
-    ++gotStatus;
-    ASSERT_EQ(resp.GetStatusCode(), 426u) << "status: " << status;
-  });
-  resp.header.connect([&](std::string_view name, std::string_view value) {
-    if (equals_lower(name, "sec-websocket-version")) {
-      ++gotVersion;
-      ASSERT_EQ(value, "13");
-    } else if (equals_lower(name, "upgrade")) {
-      ++gotUpgrade;
-      ASSERT_EQ(value, "WebSocket");
-    } else {
-      FAIL() << "unexpected header " << name;
-    }
-  });
-  resp.headersComplete.connect([&](bool) { Finish(); });
-
-  serverPipe->Listen([&] {
-    auto conn = serverPipe->Accept();
-    auto ws = WebSocket::CreateServer(*conn, "foo", "14");
-    ws->open.connect([&](std::string_view) {
-      Finish();
-      FAIL();
-    });
-  });
-  clientPipe->Connect(pipeName, [&] {
-    clientPipe->StartRead();
-    clientPipe->data.connect([&](uv::Buffer& buf, size_t size) {
-      resp.Execute(std::string_view{buf.base, size});
-      if (resp.HasError()) {
-        Finish();
-      }
-      ASSERT_EQ(resp.GetError(), HPE_OK) << http_errno_name(resp.GetError());
-    });
-  });
-
-  loop->Run();
-
-  if (HasFatalFailure()) {
-    return;
-  }
-  ASSERT_EQ(gotStatus, 1);
-  ASSERT_EQ(gotVersion, 1);
-  ASSERT_EQ(gotUpgrade, 1);
-}
-
-}  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/WebSocketTest.h b/third_party/allwpilib/wpiutil/src/test/native/cpp/WebSocketTest.h
deleted file mode 100644
index fda4473..0000000
--- a/third_party/allwpilib/wpiutil/src/test/native/cpp/WebSocketTest.h
+++ /dev/null
@@ -1,70 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include <cstdio>
-#include <memory>
-#include <vector>
-
-#include "gtest/gtest.h"
-#include "wpi/span.h"
-#include "wpi/uv/Loop.h"
-#include "wpi/uv/Pipe.h"
-#include "wpi/uv/Timer.h"
-
-namespace wpi {
-
-class WebSocketTest : public ::testing::Test {
- public:
-  static const char* pipeName;
-
-  static void SetUpTestCase();
-
-  WebSocketTest() {
-    loop = uv::Loop::Create();
-    clientPipe = uv::Pipe::Create(loop);
-    serverPipe = uv::Pipe::Create(loop);
-
-    serverPipe->Bind(pipeName);
-
-#if 0
-    auto debugTimer = uv::Timer::Create(loop);
-    debugTimer->timeout.connect([this] {
-      std::printf("Active handles:\n");
-      uv_print_active_handles(loop->GetRaw(), stdout);
-    });
-    debugTimer->Start(uv::Timer::Time{100}, uv::Timer::Time{100});
-    debugTimer->Unreference();
-#endif
-
-    auto failTimer = uv::Timer::Create(loop);
-    failTimer->timeout.connect([this] {
-      loop->Stop();
-      FAIL() << "loop failed to terminate";
-    });
-    failTimer->Start(uv::Timer::Time{1000});
-    failTimer->Unreference();
-  }
-
-  ~WebSocketTest() override { Finish(); }
-
-  void Finish() {
-    loop->Walk([](uv::Handle& it) { it.Close(); });
-  }
-
-  static std::vector<uint8_t> BuildHeader(uint8_t opcode, bool fin,
-                                          bool masking, uint64_t len);
-  static std::vector<uint8_t> BuildMessage(uint8_t opcode, bool fin,
-                                           bool masking,
-                                           span<const uint8_t> data);
-  static void AdjustMasking(span<uint8_t> message);
-  static const uint8_t testMask[4];
-
-  std::shared_ptr<uv::Loop> loop;
-  std::shared_ptr<uv::Pipe> clientPipe;
-  std::shared_ptr<uv::Pipe> serverPipe;
-};
-
-}  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/WorkerThreadTest.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/WorkerThreadTest.cpp
deleted file mode 100644
index 9bc9a17..0000000
--- a/third_party/allwpilib/wpiutil/src/test/native/cpp/WorkerThreadTest.cpp
+++ /dev/null
@@ -1,70 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/WorkerThread.h"  // NOLINT(build/include_order)
-
-#include "gtest/gtest.h"  // NOLINT(build/include_order)
-
-#include <thread>
-
-#include "wpi/uv/Loop.h"
-
-namespace wpi {
-
-TEST(WorkerThreadTest, Future) {
-  WorkerThread<int(bool)> worker;
-  future<int> f =
-      worker.QueueWork([](bool v) -> int { return v ? 1 : 2; }, true);
-  ASSERT_EQ(f.get(), 1);
-}
-
-TEST(WorkerThreadTest, FutureVoid) {
-  int callbacks = 0;
-  WorkerThread<void(int)> worker;
-  future<void> f = worker.QueueWork(
-      [&](int v) {
-        ++callbacks;
-        ASSERT_EQ(v, 3);
-      },
-      3);
-  f.get();
-  ASSERT_EQ(callbacks, 1);
-}
-
-TEST(WorkerThreadTest, Loop) {
-  int callbacks = 0;
-  WorkerThread<int(bool)> worker;
-  auto loop = uv::Loop::Create();
-  worker.SetLoop(*loop);
-  worker.QueueWorkThen([](bool v) -> int { return v ? 1 : 2; },
-                       [&](int v2) {
-                         ++callbacks;
-                         loop->Stop();
-                         ASSERT_EQ(v2, 1);
-                       },
-                       true);
-  auto f = worker.QueueWork([](bool) -> int { return 2; }, true);
-  ASSERT_EQ(f.get(), 2);
-  loop->Run();
-  ASSERT_EQ(callbacks, 1);
-}
-
-TEST(WorkerThreadTest, LoopVoid) {
-  int callbacks = 0;
-  WorkerThread<void(bool)> worker;
-  auto loop = uv::Loop::Create();
-  worker.SetLoop(*loop);
-  worker.QueueWorkThen([](bool) {},
-                       [&]() {
-                         ++callbacks;
-                         loop->Stop();
-                       },
-                       true);
-  auto f = worker.QueueWork([](bool) {}, true);
-  f.get();
-  loop->Run();
-  ASSERT_EQ(callbacks, 1);
-}
-
-}  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/hostname.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/hostname.cpp
deleted file mode 100644
index 29cceb1..0000000
--- a/third_party/allwpilib/wpiutil/src/test/native/cpp/hostname.cpp
+++ /dev/null
@@ -1,23 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/hostname.h"
-
-#include "gtest/gtest.h"
-#include "wpi/SmallString.h"
-#include "wpi/SmallVector.h"
-
-namespace wpi {
-TEST(HostNameTest, HostNameNotEmpty) {
-  ASSERT_NE(GetHostname(), "");
-}
-TEST(HostNameTest, HostNameNotEmptySmallVector) {
-  SmallVector<char, 256> name;
-  ASSERT_NE(GetHostname(name), "");
-}
-TEST(HostNameTest, HostNameEq) {
-  SmallVector<char, 256> nameBuf;
-  ASSERT_EQ(GetHostname(nameBuf), GetHostname());
-}
-}  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/json/unit-cbor.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/json/unit-cbor.cpp
index 2e37a17..dfb3b60 100644
--- a/third_party/allwpilib/wpiutil/src/test/native/cpp/json/unit-cbor.cpp
+++ b/third_party/allwpilib/wpiutil/src/test/native/cpp/json/unit-cbor.cpp
@@ -35,6 +35,9 @@
 #include "gtest/gtest.h"
 
 #include "unit-json.h"
+
+#include <cmath>
+
 using wpi::json;
 
 #include <fstream>
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/json/unit-constructor1.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/json/unit-constructor1.cpp
index 85b9b91..273bfb6 100644
--- a/third_party/allwpilib/wpiutil/src/test/native/cpp/json/unit-constructor1.cpp
+++ b/third_party/allwpilib/wpiutil/src/test/native/cpp/json/unit-constructor1.cpp
@@ -35,6 +35,7 @@
 #include "gtest/gtest.h"
 
 #include <array>
+#include <cmath>
 #include <deque>
 #include <forward_list>
 #include <list>
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/json/unit-conversions.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/json/unit-conversions.cpp
index b60e5ac..601055c 100644
--- a/third_party/allwpilib/wpiutil/src/test/native/cpp/json/unit-conversions.cpp
+++ b/third_party/allwpilib/wpiutil/src/test/native/cpp/json/unit-conversions.cpp
@@ -38,6 +38,7 @@
 using wpi::json;
 using wpi::JsonTest;
 
+#include <cmath>
 #include <deque>
 //#include <forward_list>
 #include <list>
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/json/unit-element_access2.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/json/unit-element_access2.cpp
index 4b64123..ab953bd 100644
--- a/third_party/allwpilib/wpiutil/src/test/native/cpp/json/unit-element_access2.cpp
+++ b/third_party/allwpilib/wpiutil/src/test/native/cpp/json/unit-element_access2.cpp
@@ -35,6 +35,9 @@
 #include "gtest/gtest.h"
 
 #include "unit-json.h"
+
+#include <cmath>
+
 using wpi::json;
 
 class JsonElementObjectAccessTestBase {
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/json/unit-msgpack.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/json/unit-msgpack.cpp
index c0a237d..73665ea 100644
--- a/third_party/allwpilib/wpiutil/src/test/native/cpp/json/unit-msgpack.cpp
+++ b/third_party/allwpilib/wpiutil/src/test/native/cpp/json/unit-msgpack.cpp
@@ -37,6 +37,7 @@
 #include "unit-json.h"
 using wpi::json;
 
+#include <cmath>
 #include <fstream>
 
 TEST(MessagePackDiscardedTest, Case)
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/json/unit-pointer_access.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/json/unit-pointer_access.cpp
index a1a7fa4..3224b05 100644
--- a/third_party/allwpilib/wpiutil/src/test/native/cpp/json/unit-pointer_access.cpp
+++ b/third_party/allwpilib/wpiutil/src/test/native/cpp/json/unit-pointer_access.cpp
@@ -35,6 +35,9 @@
 #include "gtest/gtest.h"
 
 #include "unit-json.h"
+
+#include <cmath>
+
 using wpi::json;
 
 TEST(JsonPointerTest, TypesCreate)
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/json/unit-readme.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/json/unit-readme.cpp
index 14d2b1b..d9bb9e5 100644
--- a/third_party/allwpilib/wpiutil/src/test/native/cpp/json/unit-readme.cpp
+++ b/third_party/allwpilib/wpiutil/src/test/native/cpp/json/unit-readme.cpp
@@ -200,7 +200,7 @@
 {
     std::vector<int> c_vector {1, 2, 3, 4};
     json j_vec(c_vector);
-    json j_vec2(wpi::span<const int>(c_vector.data(), c_vector.size()));
+    json j_vec2(std::span<const int>(c_vector.data(), c_vector.size()));
     // [1, 2, 3, 4]
 
     std::deque<float> c_deque {1.2f, 2.3f, 3.4f, 5.6f};
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/Chrono.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/Chrono.cpp
new file mode 100644
index 0000000..5fe3e65
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/Chrono.cpp
@@ -0,0 +1,49 @@
+//===- llvm/unittest/Support/Chrono.cpp - Time utilities tests ------------===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+
+#include "wpi/Chrono.h"
+#include "wpi/SmallVector.h"
+#include "gtest/gtest.h"
+
+using namespace wpi;
+using namespace wpi::sys;
+using namespace std::chrono;
+
+namespace {
+
+TEST(Chrono, TimeTConversion) {
+  EXPECT_EQ(time_t(0), toTimeT(toTimePoint(time_t(0))));
+  EXPECT_EQ(time_t(1), toTimeT(toTimePoint(time_t(1))));
+  EXPECT_EQ(time_t(47), toTimeT(toTimePoint(time_t(47))));
+
+  TimePoint<> TP;
+  EXPECT_EQ(TP, toTimePoint(toTimeT(TP)));
+  TP += seconds(1);
+  EXPECT_EQ(TP, toTimePoint(toTimeT(TP)));
+  TP += hours(47);
+  EXPECT_EQ(TP, toTimePoint(toTimeT(TP)));
+}
+
+// Test that toTimePoint and toTimeT can be called with a arguments with varying
+// precisions.
+TEST(Chrono, ImplicitConversions) {
+  std::time_t TimeT = 47;
+  TimePoint<seconds> Sec = toTimePoint(TimeT);
+  TimePoint<milliseconds> Milli = toTimePoint(TimeT);
+  TimePoint<microseconds> Micro = toTimePoint(TimeT);
+  TimePoint<nanoseconds> Nano = toTimePoint(TimeT);
+  EXPECT_EQ(Sec, Milli);
+  EXPECT_EQ(Sec, Micro);
+  EXPECT_EQ(Sec, Nano);
+  EXPECT_EQ(TimeT, toTimeT(Sec));
+  EXPECT_EQ(TimeT, toTimeT(Milli));
+  EXPECT_EQ(TimeT, toTimeT(Micro));
+  EXPECT_EQ(TimeT, toTimeT(Nano));
+}
+
+} // anonymous namespace
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/ConvertUTFTest.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/ConvertUTFTest.cpp
new file mode 100644
index 0000000..762682e
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/ConvertUTFTest.cpp
@@ -0,0 +1,1712 @@
+//===- llvm/unittest/Support/ConvertUTFTest.cpp - ConvertUTF tests --------===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+
+#include "wpi/ConvertUTF.h"
+#include "wpi/SmallString.h"
+#include "wpi/SmallVector.h"
+#include "gtest/gtest.h"
+#include <string>
+#include <vector>
+
+using namespace wpi;
+
+TEST(ConvertUTFTest, ConvertUTF16LittleEndianToUTF8String) {
+  // Src is the look of disapproval.
+  alignas(UTF16) static const char Src[] = "\xff\xfe\xa0\x0c_\x00\xa0\x0c";
+  std::span<const char> Ref(Src, sizeof(Src) - 1);
+  SmallString<20> Result;
+  bool Success = convertUTF16ToUTF8String(Ref, Result);
+  EXPECT_TRUE(Success);
+  std::string Expected("\xe0\xb2\xa0_\xe0\xb2\xa0");
+  EXPECT_EQ(Expected, std::string{Result});
+}
+
+TEST(ConvertUTFTest, ConvertUTF16BigEndianToUTF8String) {
+  // Src is the look of disapproval.
+  alignas(UTF16) static const char Src[] = "\xfe\xff\x0c\xa0\x00_\x0c\xa0";
+  std::span<const char> Ref(Src, sizeof(Src) - 1);
+  SmallString<20> Result;
+  bool Success = convertUTF16ToUTF8String(Ref, Result);
+  EXPECT_TRUE(Success);
+  std::string Expected("\xe0\xb2\xa0_\xe0\xb2\xa0");
+  EXPECT_EQ(Expected, std::string{Result});
+}
+
+TEST(ConvertUTFTest, ConvertUTF8ToUTF16String) {
+  // Src is the look of disapproval.
+  static const char Src[] = "\xe0\xb2\xa0_\xe0\xb2\xa0";
+  std::string_view Ref(Src, sizeof(Src) - 1);
+  SmallVector<UTF16, 5> Result;
+  bool Success = convertUTF8ToUTF16String(Ref, Result);
+  EXPECT_TRUE(Success);
+  static const UTF16 Expected[] = {0x0CA0, 0x005f, 0x0CA0, 0};
+  ASSERT_EQ(3u, Result.size());
+  for (int I = 0, E = 3; I != E; ++I)
+    EXPECT_EQ(Expected[I], Result[I]);
+}
+
+TEST(ConvertUTFTest, OddLengthInput) {
+  SmallString<20> Result;
+  bool Success = convertUTF16ToUTF8String(std::span<const char>("xxxxx", 5), Result);
+  EXPECT_FALSE(Success);
+}
+
+TEST(ConvertUTFTest, Empty) {
+  SmallString<20> Result;
+  bool Success = convertUTF16ToUTF8String(std::span<const char>(), Result);
+  EXPECT_TRUE(Success);
+  EXPECT_TRUE(std::string{Result}.empty());
+}
+
+TEST(ConvertUTFTest, HasUTF16BOM) {
+  bool HasBOM = hasUTF16ByteOrderMark("\xff\xfe");
+  EXPECT_TRUE(HasBOM);
+  HasBOM = hasUTF16ByteOrderMark("\xfe\xff");
+  EXPECT_TRUE(HasBOM);
+  HasBOM = hasUTF16ByteOrderMark("\xfe\xff ");
+  EXPECT_TRUE(HasBOM); // Don't care about odd lengths.
+  HasBOM = hasUTF16ByteOrderMark("\xfe\xff\x00asdf");
+  EXPECT_TRUE(HasBOM);
+
+  HasBOM = hasUTF16ByteOrderMark("");
+  EXPECT_FALSE(HasBOM);
+  HasBOM = hasUTF16ByteOrderMark("\xfe");
+  EXPECT_FALSE(HasBOM);
+}
+
+TEST(ConvertUTFTest, UTF16WrappersForConvertUTF16ToUTF8String) {
+  // Src is the look of disapproval.
+  alignas(UTF16) static const char Src[] = "\xff\xfe\xa0\x0c_\x00\xa0\x0c";
+  std::span<const UTF16> SrcRef((const UTF16 *)Src, 4);
+  SmallString<20> Result;
+  bool Success = convertUTF16ToUTF8String(SrcRef, Result);
+  EXPECT_TRUE(Success);
+  std::string Expected("\xe0\xb2\xa0_\xe0\xb2\xa0");
+  EXPECT_EQ(Expected, std::string{Result});
+}
+
+TEST(ConvertUTFTest, ConvertUTF8toWide) {
+  // Src is the look of disapproval.
+  static const char Src[] = "\xe0\xb2\xa0_\xe0\xb2\xa0";
+  std::wstring Result;
+  bool Success = ConvertUTF8toWide((const char*)Src, Result);
+  EXPECT_TRUE(Success);
+  std::wstring Expected(L"\x0ca0_\x0ca0");
+  EXPECT_EQ(Expected, Result);
+  Result.clear();
+  Success = ConvertUTF8toWide(Src, Result);
+  EXPECT_TRUE(Success);
+  EXPECT_EQ(Expected, Result);
+}
+
+TEST(ConvertUTFTest, convertWideToUTF8) {
+  // Src is the look of disapproval.
+  static const wchar_t Src[] = L"\x0ca0_\x0ca0";
+  SmallString<20> Result;
+  bool Success = convertWideToUTF8(Src, Result);
+  EXPECT_TRUE(Success);
+  std::string Expected("\xe0\xb2\xa0_\xe0\xb2\xa0");
+  EXPECT_EQ(Expected, std::string{Result});
+}
+
+struct ConvertUTFResultContainer {
+  ConversionResult ErrorCode;
+  std::vector<unsigned> UnicodeScalars;
+
+  ConvertUTFResultContainer(ConversionResult ErrorCode)
+      : ErrorCode(ErrorCode) {}
+
+  ConvertUTFResultContainer
+  withScalars(unsigned US0 = 0x110000, unsigned US1 = 0x110000,
+              unsigned US2 = 0x110000, unsigned US3 = 0x110000,
+              unsigned US4 = 0x110000, unsigned US5 = 0x110000,
+              unsigned US6 = 0x110000, unsigned US7 = 0x110000) {
+    ConvertUTFResultContainer Result(*this);
+    if (US0 != 0x110000)
+      Result.UnicodeScalars.push_back(US0);
+    if (US1 != 0x110000)
+      Result.UnicodeScalars.push_back(US1);
+    if (US2 != 0x110000)
+      Result.UnicodeScalars.push_back(US2);
+    if (US3 != 0x110000)
+      Result.UnicodeScalars.push_back(US3);
+    if (US4 != 0x110000)
+      Result.UnicodeScalars.push_back(US4);
+    if (US5 != 0x110000)
+      Result.UnicodeScalars.push_back(US5);
+    if (US6 != 0x110000)
+      Result.UnicodeScalars.push_back(US6);
+    if (US7 != 0x110000)
+      Result.UnicodeScalars.push_back(US7);
+    return Result;
+  }
+};
+
+std::pair<ConversionResult, std::vector<unsigned>>
+ConvertUTF8ToUnicodeScalarsLenient(std::string_view S) {
+  const UTF8 *SourceStart = reinterpret_cast<const UTF8 *>(S.data());
+
+  const UTF8 *SourceNext = SourceStart;
+  std::vector<UTF32> Decoded(S.size(), 0);
+  UTF32 *TargetStart = Decoded.data();
+
+  auto ErrorCode =
+      ConvertUTF8toUTF32(&SourceNext, SourceStart + S.size(), &TargetStart,
+                         Decoded.data() + Decoded.size(), lenientConversion);
+
+  Decoded.resize(TargetStart - Decoded.data());
+
+  return std::make_pair(ErrorCode, Decoded);
+}
+
+std::pair<ConversionResult, std::vector<unsigned>>
+ConvertUTF8ToUnicodeScalarsPartialLenient(std::string_view S) {
+  const UTF8 *SourceStart = reinterpret_cast<const UTF8 *>(S.data());
+
+  const UTF8 *SourceNext = SourceStart;
+  std::vector<UTF32> Decoded(S.size(), 0);
+  UTF32 *TargetStart = Decoded.data();
+
+  auto ErrorCode = ConvertUTF8toUTF32Partial(
+      &SourceNext, SourceStart + S.size(), &TargetStart,
+      Decoded.data() + Decoded.size(), lenientConversion);
+
+  Decoded.resize(TargetStart - Decoded.data());
+
+  return std::make_pair(ErrorCode, Decoded);
+}
+
+::testing::AssertionResult
+CheckConvertUTF8ToUnicodeScalars(ConvertUTFResultContainer Expected,
+                                 std::string_view S, bool Partial = false) {
+  ConversionResult ErrorCode;
+  std::vector<unsigned> Decoded;
+  if (!Partial)
+    std::tie(ErrorCode, Decoded) = ConvertUTF8ToUnicodeScalarsLenient(S);
+  else
+    std::tie(ErrorCode, Decoded) = ConvertUTF8ToUnicodeScalarsPartialLenient(S);
+
+  if (Expected.ErrorCode != ErrorCode)
+    return ::testing::AssertionFailure() << "Expected error code "
+                                         << Expected.ErrorCode << ", actual "
+                                         << ErrorCode;
+
+  if (Expected.UnicodeScalars != Decoded)
+    return ::testing::AssertionFailure()
+           << "Expected lenient decoded result:\n"
+           << ::testing::PrintToString(Expected.UnicodeScalars) << "\n"
+           << "Actual result:\n" << ::testing::PrintToString(Decoded);
+
+  return ::testing::AssertionSuccess();
+}
+
+TEST(ConvertUTFTest, UTF8ToUTF32Lenient) {
+
+  //
+  // 1-byte sequences
+  //
+
+  // U+0041 LATIN CAPITAL LETTER A
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0x0041), "\x41"));
+
+  //
+  // 2-byte sequences
+  //
+
+  // U+0283 LATIN SMALL LETTER ESH
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0x0283),
+      "\xca\x83"));
+
+  // U+03BA GREEK SMALL LETTER KAPPA
+  // U+1F79 GREEK SMALL LETTER OMICRON WITH OXIA
+  // U+03C3 GREEK SMALL LETTER SIGMA
+  // U+03BC GREEK SMALL LETTER MU
+  // U+03B5 GREEK SMALL LETTER EPSILON
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK)
+          .withScalars(0x03ba, 0x1f79, 0x03c3, 0x03bc, 0x03b5),
+      "\xce\xba\xe1\xbd\xb9\xcf\x83\xce\xbc\xce\xb5"));
+
+  //
+  // 3-byte sequences
+  //
+
+  // U+4F8B CJK UNIFIED IDEOGRAPH-4F8B
+  // U+6587 CJK UNIFIED IDEOGRAPH-6587
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0x4f8b, 0x6587),
+      "\xe4\xbe\x8b\xe6\x96\x87"));
+
+  // U+D55C HANGUL SYLLABLE HAN
+  // U+AE00 HANGUL SYLLABLE GEUL
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xd55c, 0xae00),
+      "\xed\x95\x9c\xea\xb8\x80"));
+
+  // U+1112 HANGUL CHOSEONG HIEUH
+  // U+1161 HANGUL JUNGSEONG A
+  // U+11AB HANGUL JONGSEONG NIEUN
+  // U+1100 HANGUL CHOSEONG KIYEOK
+  // U+1173 HANGUL JUNGSEONG EU
+  // U+11AF HANGUL JONGSEONG RIEUL
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK)
+          .withScalars(0x1112, 0x1161, 0x11ab, 0x1100, 0x1173, 0x11af),
+      "\xe1\x84\x92\xe1\x85\xa1\xe1\x86\xab\xe1\x84\x80\xe1\x85\xb3"
+      "\xe1\x86\xaf"));
+
+  //
+  // 4-byte sequences
+  //
+
+  // U+E0100 VARIATION SELECTOR-17
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0x000E0100),
+      "\xf3\xa0\x84\x80"));
+
+  //
+  // First possible sequence of a certain length
+  //
+
+  // U+0000 NULL
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0x0000),
+      std::string_view("\x00", 1)));
+
+  // U+0080 PADDING CHARACTER
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0x0080),
+      "\xc2\x80"));
+
+  // U+0800 SAMARITAN LETTER ALAF
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0x0800),
+      "\xe0\xa0\x80"));
+
+  // U+10000 LINEAR B SYLLABLE B008 A
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0x10000),
+      "\xf0\x90\x80\x80"));
+
+  // U+200000 (invalid)
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xf8\x88\x80\x80\x80"));
+
+  // U+4000000 (invalid)
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xfc\x84\x80\x80\x80\x80"));
+
+  //
+  // Last possible sequence of a certain length
+  //
+
+  // U+007F DELETE
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0x007f), "\x7f"));
+
+  // U+07FF (unassigned)
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0x07ff),
+      "\xdf\xbf"));
+
+  // U+FFFF (noncharacter)
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xffff),
+      "\xef\xbf\xbf"));
+
+  // U+1FFFFF (invalid)
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xf7\xbf\xbf\xbf"));
+
+  // U+3FFFFFF (invalid)
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xfb\xbf\xbf\xbf\xbf"));
+
+  // U+7FFFFFFF (invalid)
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xfd\xbf\xbf\xbf\xbf\xbf"));
+
+  //
+  // Other boundary conditions
+  //
+
+  // U+D7FF (unassigned)
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xd7ff),
+      "\xed\x9f\xbf"));
+
+  // U+E000 (private use)
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xe000),
+      "\xee\x80\x80"));
+
+  // U+FFFD REPLACEMENT CHARACTER
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfffd),
+      "\xef\xbf\xbd"));
+
+  // U+10FFFF (noncharacter)
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0x10ffff),
+      "\xf4\x8f\xbf\xbf"));
+
+  // U+110000 (invalid)
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xf4\x90\x80\x80"));
+
+  //
+  // Unexpected continuation bytes
+  //
+
+  // A sequence of unexpected continuation bytes that don't follow a first
+  // byte, every byte is a maximal subpart.
+
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd), "\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd), "\xbf"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd),
+      "\x80\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd),
+      "\x80\xbf"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd),
+      "\xbf\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd),
+      "\x80\xbf\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\x80\xbf\x80\xbf"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\x80\xbf\x82\xbf\xaa"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xaa\xb0\xbb\xbf\xaa\xa0"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xaa\xb0\xbb\xbf\xaa\xa0\x8f"));
+
+  // All continuation bytes (0x80--0xbf).
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd,
+                       0xfffd, 0xfffd, 0xfffd, 0xfffd)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd,
+                       0xfffd, 0xfffd, 0xfffd, 0xfffd)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd,
+                       0xfffd, 0xfffd, 0xfffd, 0xfffd)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd,
+                       0xfffd, 0xfffd, 0xfffd, 0xfffd)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd,
+                       0xfffd, 0xfffd, 0xfffd, 0xfffd)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd,
+                       0xfffd, 0xfffd, 0xfffd, 0xfffd)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd,
+                       0xfffd, 0xfffd, 0xfffd, 0xfffd)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd,
+                       0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\x80\x81\x82\x83\x84\x85\x86\x87\x88\x89\x8a\x8b\x8c\x8d\x8e\x8f"
+      "\x90\x91\x92\x93\x94\x95\x96\x97\x98\x99\x9a\x9b\x9c\x9d\x9e\x9f"
+      "\xa0\xa1\xa2\xa3\xa4\xa5\xa6\xa7\xa8\xa9\xaa\xab\xac\xad\xae\xaf"
+      "\xb0\xb1\xb2\xb3\xb4\xb5\xb6\xb7\xb8\xb9\xba\xbb\xbc\xbd\xbe\xbf"));
+
+  //
+  // Lonely start bytes
+  //
+
+  // Start bytes of 2-byte sequences (0xc0--0xdf).
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd,
+                       0xfffd, 0xfffd, 0xfffd, 0xfffd)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd,
+                       0xfffd, 0xfffd, 0xfffd, 0xfffd)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd,
+                       0xfffd, 0xfffd, 0xfffd, 0xfffd)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd,
+                       0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xc0\xc1\xc2\xc3\xc4\xc5\xc6\xc7\xc8\xc9\xca\xcb\xcc\xcd\xce\xcf"
+      "\xd0\xd1\xd2\xd3\xd4\xd5\xd6\xd7\xd8\xd9\xda\xdb\xdc\xdd\xde\xdf"));
+
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0x0020, 0xfffd, 0x0020,
+                       0xfffd, 0x0020, 0xfffd, 0x0020)
+          .withScalars(0xfffd, 0x0020, 0xfffd, 0x0020,
+                       0xfffd, 0x0020, 0xfffd, 0x0020)
+          .withScalars(0xfffd, 0x0020, 0xfffd, 0x0020,
+                       0xfffd, 0x0020, 0xfffd, 0x0020)
+          .withScalars(0xfffd, 0x0020, 0xfffd, 0x0020,
+                       0xfffd, 0x0020, 0xfffd, 0x0020)
+          .withScalars(0xfffd, 0x0020, 0xfffd, 0x0020,
+                       0xfffd, 0x0020, 0xfffd, 0x0020)
+          .withScalars(0xfffd, 0x0020, 0xfffd, 0x0020,
+                       0xfffd, 0x0020, 0xfffd, 0x0020)
+          .withScalars(0xfffd, 0x0020, 0xfffd, 0x0020,
+                       0xfffd, 0x0020, 0xfffd, 0x0020)
+          .withScalars(0xfffd, 0x0020, 0xfffd, 0x0020,
+                       0xfffd, 0x0020, 0xfffd, 0x0020),
+      "\xc0\x20\xc1\x20\xc2\x20\xc3\x20\xc4\x20\xc5\x20\xc6\x20\xc7\x20"
+      "\xc8\x20\xc9\x20\xca\x20\xcb\x20\xcc\x20\xcd\x20\xce\x20\xcf\x20"
+      "\xd0\x20\xd1\x20\xd2\x20\xd3\x20\xd4\x20\xd5\x20\xd6\x20\xd7\x20"
+      "\xd8\x20\xd9\x20\xda\x20\xdb\x20\xdc\x20\xdd\x20\xde\x20\xdf\x20"));
+
+  // Start bytes of 3-byte sequences (0xe0--0xef).
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd,
+                       0xfffd, 0xfffd, 0xfffd, 0xfffd)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd,
+                       0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xe0\xe1\xe2\xe3\xe4\xe5\xe6\xe7\xe8\xe9\xea\xeb\xec\xed\xee\xef"));
+
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0x0020, 0xfffd, 0x0020,
+                       0xfffd, 0x0020, 0xfffd, 0x0020)
+          .withScalars(0xfffd, 0x0020, 0xfffd, 0x0020,
+                       0xfffd, 0x0020, 0xfffd, 0x0020)
+          .withScalars(0xfffd, 0x0020, 0xfffd, 0x0020,
+                       0xfffd, 0x0020, 0xfffd, 0x0020)
+          .withScalars(0xfffd, 0x0020, 0xfffd, 0x0020,
+                       0xfffd, 0x0020, 0xfffd, 0x0020),
+      "\xe0\x20\xe1\x20\xe2\x20\xe3\x20\xe4\x20\xe5\x20\xe6\x20\xe7\x20"
+      "\xe8\x20\xe9\x20\xea\x20\xeb\x20\xec\x20\xed\x20\xee\x20\xef\x20"));
+
+  // Start bytes of 4-byte sequences (0xf0--0xf7).
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd,
+                       0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xf0\xf1\xf2\xf3\xf4\xf5\xf6\xf7"));
+
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0x0020, 0xfffd, 0x0020,
+                       0xfffd, 0x0020, 0xfffd, 0x0020)
+          .withScalars(0xfffd, 0x0020, 0xfffd, 0x0020,
+                       0xfffd, 0x0020, 0xfffd, 0x0020),
+      "\xf0\x20\xf1\x20\xf2\x20\xf3\x20\xf4\x20\xf5\x20\xf6\x20\xf7\x20"));
+
+  // Start bytes of 5-byte sequences (0xf8--0xfb).
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xf8\xf9\xfa\xfb"));
+
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0x0020, 0xfffd, 0x0020,
+                       0xfffd, 0x0020, 0xfffd, 0x0020),
+      "\xf8\x20\xf9\x20\xfa\x20\xfb\x20"));
+
+  // Start bytes of 6-byte sequences (0xfc--0xfd).
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd),
+      "\xfc\xfd"));
+
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0x0020, 0xfffd, 0x0020),
+      "\xfc\x20\xfd\x20"));
+
+  //
+  // Other bytes (0xc0--0xc1, 0xfe--0xff).
+  //
+
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd), "\xc0"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd), "\xc1"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd), "\xfe"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd), "\xff"));
+
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xc0\xc1\xfe\xff"));
+
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xfe\xfe\xff\xff"));
+
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xfe\x80\x80\x80\x80\x80"));
+
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xff\x80\x80\x80\x80\x80"));
+
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0x0020, 0xfffd, 0x0020,
+                       0xfffd, 0x0020, 0xfffd, 0x0020),
+      "\xc0\x20\xc1\x20\xfe\x20\xff\x20"));
+
+  //
+  // Sequences with one continuation byte missing
+  //
+
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd), "\xc2"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd), "\xdf"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd),
+      "\xe0\xa0"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd),
+      "\xe0\xbf"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd),
+      "\xe1\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd),
+      "\xec\xbf"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd),
+      "\xed\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd),
+      "\xed\x9f"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd),
+      "\xee\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd),
+      "\xef\xbf"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd),
+      "\xf0\x90\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd),
+      "\xf0\xbf\xbf"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd),
+      "\xf1\x80\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd),
+      "\xf3\xbf\xbf"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd),
+      "\xf4\x80\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd),
+      "\xf4\x8f\xbf"));
+
+  // Overlong sequences with one trailing byte missing.
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd),
+      "\xc0"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd),
+      "\xc1"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd),
+      "\xe0\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd),
+      "\xe0\x9f"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd),
+      "\xf0\x80\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd),
+      "\xf0\x8f\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xf8\x80\x80\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xfc\x80\x80\x80\x80"));
+
+  // Sequences that represent surrogates with one trailing byte missing.
+  // High surrogates
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd),
+      "\xed\xa0"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd),
+      "\xed\xac"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd),
+      "\xed\xaf"));
+  // Low surrogates
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd),
+      "\xed\xb0"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd),
+      "\xed\xb4"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd),
+      "\xed\xbf"));
+
+  // Ill-formed 4-byte sequences.
+  // 11110zzz 10zzyyyy 10yyyyxx 10xxxxxx
+  // U+1100xx (invalid)
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd),
+      "\xf4\x90\x80"));
+  // U+13FBxx (invalid)
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd),
+      "\xf4\xbf\xbf"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd),
+      "\xf5\x80\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd),
+      "\xf6\x80\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd),
+      "\xf7\x80\x80"));
+  // U+1FFBxx (invalid)
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd),
+      "\xf7\xbf\xbf"));
+
+  // Ill-formed 5-byte sequences.
+  // 111110uu 10zzzzzz 10zzyyyy 10yyyyxx 10xxxxxx
+  // U+2000xx (invalid)
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xf8\x88\x80\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xf8\xbf\xbf\xbf"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xf9\x80\x80\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xfa\x80\x80\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xfb\x80\x80\x80"));
+  // U+3FFFFxx (invalid)
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xfb\xbf\xbf\xbf"));
+
+  // Ill-formed 6-byte sequences.
+  // 1111110u 10uuuuuu 10uzzzzz 10zzzyyyy 10yyyyxx 10xxxxxx
+  // U+40000xx (invalid)
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xfc\x84\x80\x80\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xfc\xbf\xbf\xbf\xbf"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xfd\x80\x80\x80\x80"));
+  // U+7FFFFFxx (invalid)
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xfd\xbf\xbf\xbf\xbf"));
+
+  //
+  // Sequences with two continuation bytes missing
+  //
+
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd),
+      "\xf0\x90"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd),
+      "\xf0\xbf"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd),
+      "\xf1\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd),
+      "\xf3\xbf"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd),
+      "\xf4\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd),
+      "\xf4\x8f"));
+
+  // Overlong sequences with two trailing byte missing.
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd), "\xe0"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd),
+      "\xf0\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd),
+      "\xf0\x8f"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd),
+      "\xf8\x80\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xfc\x80\x80\x80"));
+
+  // Sequences that represent surrogates with two trailing bytes missing.
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd), "\xed"));
+
+  // Ill-formed 4-byte sequences.
+  // 11110zzz 10zzyyyy 10yyyyxx 10xxxxxx
+  // U+110yxx (invalid)
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd),
+      "\xf4\x90"));
+  // U+13Fyxx (invalid)
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd),
+      "\xf4\xbf"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd),
+      "\xf5\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd),
+      "\xf6\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd),
+      "\xf7\x80"));
+  // U+1FFyxx (invalid)
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd),
+      "\xf7\xbf"));
+
+  // Ill-formed 5-byte sequences.
+  // 111110uu 10zzzzzz 10zzyyyy 10yyyyxx 10xxxxxx
+  // U+200yxx (invalid)
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd, 0xfffd),
+      "\xf8\x88\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd, 0xfffd),
+      "\xf8\xbf\xbf"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd, 0xfffd),
+      "\xf9\x80\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd, 0xfffd),
+      "\xfa\x80\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd, 0xfffd),
+      "\xfb\x80\x80"));
+  // U+3FFFyxx (invalid)
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd, 0xfffd),
+      "\xfb\xbf\xbf"));
+
+  // Ill-formed 6-byte sequences.
+  // 1111110u 10uuuuuu 10zzzzzz 10zzyyyy 10yyyyxx 10xxxxxx
+  // U+4000yxx (invalid)
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xfc\x84\x80\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xfc\xbf\xbf\xbf"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xfd\x80\x80\x80"));
+  // U+7FFFFyxx (invalid)
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xfd\xbf\xbf\xbf"));
+
+  //
+  // Sequences with three continuation bytes missing
+  //
+
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd), "\xf0"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd), "\xf1"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd), "\xf2"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd), "\xf3"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd), "\xf4"));
+
+  // Broken overlong sequences.
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd), "\xf0"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd),
+      "\xf8\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd, 0xfffd),
+      "\xfc\x80\x80"));
+
+  // Ill-formed 4-byte sequences.
+  // 11110zzz 10zzyyyy 10yyyyxx 10xxxxxx
+  // U+14yyxx (invalid)
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd), "\xf5"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd), "\xf6"));
+  // U+1Cyyxx (invalid)
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd), "\xf7"));
+
+  // Ill-formed 5-byte sequences.
+  // 111110uu 10zzzzzz 10zzyyyy 10yyyyxx 10xxxxxx
+  // U+20yyxx (invalid)
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd),
+      "\xf8\x88"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd),
+      "\xf8\xbf"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd),
+      "\xf9\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd),
+      "\xfa\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd),
+      "\xfb\x80"));
+  // U+3FCyyxx (invalid)
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd),
+      "\xfb\xbf"));
+
+  // Ill-formed 6-byte sequences.
+  // 1111110u 10uuuuuu 10zzzzzz 10zzyyyy 10yyyyxx 10xxxxxx
+  // U+400yyxx (invalid)
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd, 0xfffd),
+      "\xfc\x84\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd, 0xfffd),
+      "\xfc\xbf\xbf"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd, 0xfffd),
+      "\xfd\x80\x80"));
+  // U+7FFCyyxx (invalid)
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd, 0xfffd),
+      "\xfd\xbf\xbf"));
+
+  //
+  // Sequences with four continuation bytes missing
+  //
+
+  // Ill-formed 5-byte sequences.
+  // 111110uu 10zzzzzz 10zzyyyy 10yyyyxx 10xxxxxx
+  // U+uzyyxx (invalid)
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd), "\xf8"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd), "\xf9"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd), "\xfa"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd), "\xfb"));
+  // U+3zyyxx (invalid)
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd), "\xfb"));
+
+  // Broken overlong sequences.
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd), "\xf8"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd),
+      "\xfc\x80"));
+
+  // Ill-formed 6-byte sequences.
+  // 1111110u 10uuuuuu 10zzzzzz 10zzyyyy 10yyyyxx 10xxxxxx
+  // U+uzzyyxx (invalid)
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd),
+      "\xfc\x84"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd),
+      "\xfc\xbf"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd),
+      "\xfd\x80"));
+  // U+7Fzzyyxx (invalid)
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd),
+      "\xfd\xbf"));
+
+  //
+  // Sequences with five continuation bytes missing
+  //
+
+  // Ill-formed 6-byte sequences.
+  // 1111110u 10uuuuuu 10zzzzzz 10zzyyyy 10yyyyxx 10xxxxxx
+  // U+uzzyyxx (invalid)
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd), "\xfc"));
+  // U+uuzzyyxx (invalid)
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd), "\xfd"));
+
+  //
+  // Consecutive sequences with trailing bytes missing
+  //
+
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, /**/ 0xfffd, 0xfffd, /**/ 0xfffd, 0xfffd, 0xfffd)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd)
+          .withScalars(0xfffd, /**/ 0xfffd, /**/ 0xfffd, 0xfffd, 0xfffd)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xc0" "\xe0\x80" "\xf0\x80\x80"
+      "\xf8\x80\x80\x80"
+      "\xfc\x80\x80\x80\x80"
+      "\xdf" "\xef\xbf" "\xf7\xbf\xbf"
+      "\xfb\xbf\xbf\xbf"
+      "\xfd\xbf\xbf\xbf\xbf"));
+
+  //
+  // Overlong UTF-8 sequences
+  //
+
+  // U+002F SOLIDUS
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0x002f), "\x2f"));
+
+  // Overlong sequences of the above.
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd),
+      "\xc0\xaf"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd),
+      "\xe0\x80\xaf"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xf0\x80\x80\xaf"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xf8\x80\x80\x80\xaf"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xfc\x80\x80\x80\x80\xaf"));
+
+  // U+0000 NULL
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0x0000),
+      std::string_view("\x00", 1)));
+
+  // Overlong sequences of the above.
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd),
+      "\xc0\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd),
+      "\xe0\x80\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xf0\x80\x80\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xf8\x80\x80\x80\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xfc\x80\x80\x80\x80\x80"));
+
+  // Other overlong sequences.
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd),
+      "\xc0\xbf"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd),
+      "\xc1\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal).withScalars(0xfffd, 0xfffd),
+      "\xc1\xbf"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd),
+      "\xe0\x9f\xbf"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd),
+      "\xed\xa0\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd),
+      "\xed\xbf\xbf"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xf0\x8f\x80\x80"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xf0\x8f\xbf\xbf"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xf8\x87\xbf\xbf\xbf"));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xfc\x83\xbf\xbf\xbf\xbf"));
+
+  //
+  // Isolated surrogates
+  //
+
+  // Unicode 6.3.0:
+  //
+  //    D71.  High-surrogate code point: A Unicode code point in the range
+  //    U+D800 to U+DBFF.
+  //
+  //    D73.  Low-surrogate code point: A Unicode code point in the range
+  //    U+DC00 to U+DFFF.
+
+  // Note: U+E0100 is <DB40 DD00> in UTF16.
+
+  // High surrogates
+
+  // U+D800
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd),
+      "\xed\xa0\x80"));
+
+  // U+DB40
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd),
+      "\xed\xac\xa0"));
+
+  // U+DBFF
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd),
+      "\xed\xaf\xbf"));
+
+  // Low surrogates
+
+  // U+DC00
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd),
+      "\xed\xb0\x80"));
+
+  // U+DD00
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd),
+      "\xed\xb4\x80"));
+
+  // U+DFFF
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd),
+      "\xed\xbf\xbf"));
+
+  // Surrogate pairs
+
+  // U+D800 U+DC00
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xed\xa0\x80\xed\xb0\x80"));
+
+  // U+D800 U+DD00
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xed\xa0\x80\xed\xb4\x80"));
+
+  // U+D800 U+DFFF
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xed\xa0\x80\xed\xbf\xbf"));
+
+  // U+DB40 U+DC00
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xed\xac\xa0\xed\xb0\x80"));
+
+  // U+DB40 U+DD00
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xed\xac\xa0\xed\xb4\x80"));
+
+  // U+DB40 U+DFFF
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xed\xac\xa0\xed\xbf\xbf"));
+
+  // U+DBFF U+DC00
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xed\xaf\xbf\xed\xb0\x80"));
+
+  // U+DBFF U+DD00
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xed\xaf\xbf\xed\xb4\x80"));
+
+  // U+DBFF U+DFFF
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceIllegal)
+          .withScalars(0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd, 0xfffd),
+      "\xed\xaf\xbf\xed\xbf\xbf"));
+
+  //
+  // Noncharacters
+  //
+
+  // Unicode 6.3.0:
+  //
+  //    D14.  Noncharacter: A code point that is permanently reserved for
+  //    internal use and that should never be interchanged. Noncharacters
+  //    consist of the values U+nFFFE and U+nFFFF (where n is from 0 to 1016)
+  //    and the values U+FDD0..U+FDEF.
+
+  // U+FFFE
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfffe),
+      "\xef\xbf\xbe"));
+
+  // U+FFFF
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xffff),
+      "\xef\xbf\xbf"));
+
+  // U+1FFFE
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0x1fffe),
+      "\xf0\x9f\xbf\xbe"));
+
+  // U+1FFFF
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0x1ffff),
+      "\xf0\x9f\xbf\xbf"));
+
+  // U+2FFFE
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0x2fffe),
+      "\xf0\xaf\xbf\xbe"));
+
+  // U+2FFFF
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0x2ffff),
+      "\xf0\xaf\xbf\xbf"));
+
+  // U+3FFFE
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0x3fffe),
+      "\xf0\xbf\xbf\xbe"));
+
+  // U+3FFFF
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0x3ffff),
+      "\xf0\xbf\xbf\xbf"));
+
+  // U+4FFFE
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0x4fffe),
+      "\xf1\x8f\xbf\xbe"));
+
+  // U+4FFFF
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0x4ffff),
+      "\xf1\x8f\xbf\xbf"));
+
+  // U+5FFFE
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0x5fffe),
+      "\xf1\x9f\xbf\xbe"));
+
+  // U+5FFFF
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0x5ffff),
+      "\xf1\x9f\xbf\xbf"));
+
+  // U+6FFFE
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0x6fffe),
+      "\xf1\xaf\xbf\xbe"));
+
+  // U+6FFFF
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0x6ffff),
+      "\xf1\xaf\xbf\xbf"));
+
+  // U+7FFFE
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0x7fffe),
+      "\xf1\xbf\xbf\xbe"));
+
+  // U+7FFFF
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0x7ffff),
+      "\xf1\xbf\xbf\xbf"));
+
+  // U+8FFFE
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0x8fffe),
+      "\xf2\x8f\xbf\xbe"));
+
+  // U+8FFFF
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0x8ffff),
+      "\xf2\x8f\xbf\xbf"));
+
+  // U+9FFFE
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0x9fffe),
+      "\xf2\x9f\xbf\xbe"));
+
+  // U+9FFFF
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0x9ffff),
+      "\xf2\x9f\xbf\xbf"));
+
+  // U+AFFFE
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xafffe),
+      "\xf2\xaf\xbf\xbe"));
+
+  // U+AFFFF
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xaffff),
+      "\xf2\xaf\xbf\xbf"));
+
+  // U+BFFFE
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xbfffe),
+      "\xf2\xbf\xbf\xbe"));
+
+  // U+BFFFF
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xbffff),
+      "\xf2\xbf\xbf\xbf"));
+
+  // U+CFFFE
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xcfffe),
+      "\xf3\x8f\xbf\xbe"));
+
+  // U+CFFFF
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xcfffF),
+      "\xf3\x8f\xbf\xbf"));
+
+  // U+DFFFE
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xdfffe),
+      "\xf3\x9f\xbf\xbe"));
+
+  // U+DFFFF
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xdffff),
+      "\xf3\x9f\xbf\xbf"));
+
+  // U+EFFFE
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xefffe),
+      "\xf3\xaf\xbf\xbe"));
+
+  // U+EFFFF
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xeffff),
+      "\xf3\xaf\xbf\xbf"));
+
+  // U+FFFFE
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xffffe),
+      "\xf3\xbf\xbf\xbe"));
+
+  // U+FFFFF
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfffff),
+      "\xf3\xbf\xbf\xbf"));
+
+  // U+10FFFE
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0x10fffe),
+      "\xf4\x8f\xbf\xbe"));
+
+  // U+10FFFF
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0x10ffff),
+      "\xf4\x8f\xbf\xbf"));
+
+  // U+FDD0
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfdd0),
+      "\xef\xb7\x90"));
+
+  // U+FDD1
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfdd1),
+      "\xef\xb7\x91"));
+
+  // U+FDD2
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfdd2),
+      "\xef\xb7\x92"));
+
+  // U+FDD3
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfdd3),
+      "\xef\xb7\x93"));
+
+  // U+FDD4
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfdd4),
+      "\xef\xb7\x94"));
+
+  // U+FDD5
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfdd5),
+      "\xef\xb7\x95"));
+
+  // U+FDD6
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfdd6),
+      "\xef\xb7\x96"));
+
+  // U+FDD7
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfdd7),
+      "\xef\xb7\x97"));
+
+  // U+FDD8
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfdd8),
+      "\xef\xb7\x98"));
+
+  // U+FDD9
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfdd9),
+      "\xef\xb7\x99"));
+
+  // U+FDDA
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfdda),
+      "\xef\xb7\x9a"));
+
+  // U+FDDB
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfddb),
+      "\xef\xb7\x9b"));
+
+  // U+FDDC
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfddc),
+      "\xef\xb7\x9c"));
+
+  // U+FDDD
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfddd),
+      "\xef\xb7\x9d"));
+
+  // U+FDDE
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfdde),
+      "\xef\xb7\x9e"));
+
+  // U+FDDF
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfddf),
+      "\xef\xb7\x9f"));
+
+  // U+FDE0
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfde0),
+      "\xef\xb7\xa0"));
+
+  // U+FDE1
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfde1),
+      "\xef\xb7\xa1"));
+
+  // U+FDE2
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfde2),
+      "\xef\xb7\xa2"));
+
+  // U+FDE3
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfde3),
+      "\xef\xb7\xa3"));
+
+  // U+FDE4
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfde4),
+      "\xef\xb7\xa4"));
+
+  // U+FDE5
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfde5),
+      "\xef\xb7\xa5"));
+
+  // U+FDE6
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfde6),
+      "\xef\xb7\xa6"));
+
+  // U+FDE7
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfde7),
+      "\xef\xb7\xa7"));
+
+  // U+FDE8
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfde8),
+      "\xef\xb7\xa8"));
+
+  // U+FDE9
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfde9),
+      "\xef\xb7\xa9"));
+
+  // U+FDEA
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfdea),
+      "\xef\xb7\xaa"));
+
+  // U+FDEB
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfdeb),
+      "\xef\xb7\xab"));
+
+  // U+FDEC
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfdec),
+      "\xef\xb7\xac"));
+
+  // U+FDED
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfded),
+      "\xef\xb7\xad"));
+
+  // U+FDEE
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfdee),
+      "\xef\xb7\xae"));
+
+  // U+FDEF
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfdef),
+      "\xef\xb7\xaf"));
+
+  // U+FDF0
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfdf0),
+      "\xef\xb7\xb0"));
+
+  // U+FDF1
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfdf1),
+      "\xef\xb7\xb1"));
+
+  // U+FDF2
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfdf2),
+      "\xef\xb7\xb2"));
+
+  // U+FDF3
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfdf3),
+      "\xef\xb7\xb3"));
+
+  // U+FDF4
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfdf4),
+      "\xef\xb7\xb4"));
+
+  // U+FDF5
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfdf5),
+      "\xef\xb7\xb5"));
+
+  // U+FDF6
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfdf6),
+      "\xef\xb7\xb6"));
+
+  // U+FDF7
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfdf7),
+      "\xef\xb7\xb7"));
+
+  // U+FDF8
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfdf8),
+      "\xef\xb7\xb8"));
+
+  // U+FDF9
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfdf9),
+      "\xef\xb7\xb9"));
+
+  // U+FDFA
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfdfa),
+      "\xef\xb7\xba"));
+
+  // U+FDFB
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfdfb),
+      "\xef\xb7\xbb"));
+
+  // U+FDFC
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfdfc),
+      "\xef\xb7\xbc"));
+
+  // U+FDFD
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfdfd),
+      "\xef\xb7\xbd"));
+
+  // U+FDFE
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfdfe),
+      "\xef\xb7\xbe"));
+
+  // U+FDFF
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0xfdff),
+      "\xef\xb7\xbf"));
+}
+
+TEST(ConvertUTFTest, UTF8ToUTF32PartialLenient) {
+  // U+0041 LATIN CAPITAL LETTER A
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(conversionOK).withScalars(0x0041),
+      "\x41", true));
+
+  //
+  // Sequences with one continuation byte missing
+  //
+
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceExhausted),
+      "\xc2", true));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceExhausted),
+      "\xdf", true));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceExhausted),
+      "\xe0\xa0", true));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceExhausted),
+      "\xe0\xbf", true));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceExhausted),
+      "\xe1\x80", true));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceExhausted),
+      "\xec\xbf", true));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceExhausted),
+      "\xed\x80", true));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceExhausted),
+      "\xed\x9f", true));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceExhausted),
+      "\xee\x80", true));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceExhausted),
+      "\xef\xbf", true));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceExhausted),
+      "\xf0\x90\x80", true));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceExhausted),
+      "\xf0\xbf\xbf", true));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceExhausted),
+      "\xf1\x80\x80", true));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceExhausted),
+      "\xf3\xbf\xbf", true));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceExhausted),
+      "\xf4\x80\x80", true));
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceExhausted),
+      "\xf4\x8f\xbf", true));
+
+  EXPECT_TRUE(CheckConvertUTF8ToUnicodeScalars(
+      ConvertUTFResultContainer(sourceExhausted).withScalars(0x0041),
+      "\x41\xc2", true));
+}
+
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/DenseMapTest.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/DenseMapTest.cpp
new file mode 100644
index 0000000..68c37c0
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/DenseMapTest.cpp
@@ -0,0 +1,680 @@
+//===- llvm/unittest/ADT/DenseMapMap.cpp - DenseMap unit tests --*- C++ -*-===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+
+#if defined(__GNUC__) && !defined(__clang__)
+#pragma GCC diagnostic ignored "-Wmaybe-uninitialized"
+#endif
+
+#include "wpi/DenseMap.h"
+#include "gtest/gtest.h"
+#include <map>
+#include <set>
+
+using namespace wpi;
+
+namespace {
+
+uint32_t getTestKey(int i, uint32_t *) { return i; }
+uint32_t getTestValue(int i, uint32_t *) { return 42 + i; }
+
+uint32_t *getTestKey(int i, uint32_t **) {
+  static uint32_t dummy_arr1[8192];
+  assert(i < 8192 && "Only support 8192 dummy keys.");
+  return &dummy_arr1[i];
+}
+uint32_t *getTestValue(int i, uint32_t **) {
+  static uint32_t dummy_arr1[8192];
+  assert(i < 8192 && "Only support 8192 dummy keys.");
+  return &dummy_arr1[i];
+}
+
+/// A test class that tries to check that construction and destruction
+/// occur correctly.
+class CtorTester {
+  static std::set<CtorTester *> Constructed;
+  int Value;
+
+public:
+  explicit CtorTester(int Value = 0) : Value(Value) {
+    EXPECT_TRUE(Constructed.insert(this).second);
+  }
+  CtorTester(uint32_t Value) : Value(Value) {
+    EXPECT_TRUE(Constructed.insert(this).second);
+  }
+  CtorTester(const CtorTester &Arg) : Value(Arg.Value) {
+    EXPECT_TRUE(Constructed.insert(this).second);
+  }
+  CtorTester &operator=(const CtorTester &) = default;
+  ~CtorTester() {
+    EXPECT_EQ(1u, Constructed.erase(this));
+  }
+  operator uint32_t() const { return Value; }
+
+  int getValue() const { return Value; }
+  bool operator==(const CtorTester &RHS) const { return Value == RHS.Value; }
+};
+
+std::set<CtorTester *> CtorTester::Constructed;
+
+struct CtorTesterMapInfo {
+  static inline CtorTester getEmptyKey() { return CtorTester(-1); }
+  static inline CtorTester getTombstoneKey() { return CtorTester(-2); }
+  static unsigned getHashValue(const CtorTester &Val) {
+    return Val.getValue() * 37u;
+  }
+  static bool isEqual(const CtorTester &LHS, const CtorTester &RHS) {
+    return LHS == RHS;
+  }
+};
+
+CtorTester getTestKey(int i, CtorTester *) { return CtorTester(i); }
+CtorTester getTestValue(int i, CtorTester *) { return CtorTester(42 + i); }
+
+// Test fixture, with helper functions implemented by forwarding to global
+// function overloads selected by component types of the type parameter. This
+// allows all of the map implementations to be tested with shared
+// implementations of helper routines.
+template <typename T>
+class DenseMapTest : public ::testing::Test {
+protected:
+  T Map;
+
+  static typename T::key_type *const dummy_key_ptr;
+  static typename T::mapped_type *const dummy_value_ptr;
+
+  typename T::key_type getKey(int i = 0) {
+    return getTestKey(i, dummy_key_ptr);
+  }
+  typename T::mapped_type getValue(int i = 0) {
+    return getTestValue(i, dummy_value_ptr);
+  }
+};
+
+template <typename T>
+typename T::key_type *const DenseMapTest<T>::dummy_key_ptr = nullptr;
+template <typename T>
+typename T::mapped_type *const DenseMapTest<T>::dummy_value_ptr = nullptr;
+
+// Register these types for testing.
+typedef ::testing::Types<DenseMap<uint32_t, uint32_t>,
+                         DenseMap<uint32_t *, uint32_t *>,
+                         DenseMap<CtorTester, CtorTester, CtorTesterMapInfo>,
+                         SmallDenseMap<uint32_t, uint32_t>,
+                         SmallDenseMap<uint32_t *, uint32_t *>,
+                         SmallDenseMap<CtorTester, CtorTester, 4,
+                                       CtorTesterMapInfo>
+                         > DenseMapTestTypes;
+TYPED_TEST_SUITE(DenseMapTest, DenseMapTestTypes, );
+
+// Empty map tests
+TYPED_TEST(DenseMapTest, EmptyIntMapTest) {
+  // Size tests
+  EXPECT_EQ(0u, this->Map.size());
+  EXPECT_TRUE(this->Map.empty());
+
+  // Iterator tests
+  EXPECT_TRUE(this->Map.begin() == this->Map.end());
+
+  // Lookup tests
+  EXPECT_FALSE(this->Map.count(this->getKey()));
+  EXPECT_TRUE(this->Map.find(this->getKey()) == this->Map.end());
+  EXPECT_EQ(typename TypeParam::mapped_type(),
+            this->Map.lookup(this->getKey()));
+}
+
+// Constant map tests
+TYPED_TEST(DenseMapTest, ConstEmptyMapTest) {
+  const TypeParam &ConstMap = this->Map;
+  EXPECT_EQ(0u, ConstMap.size());
+  EXPECT_TRUE(ConstMap.empty());
+  EXPECT_TRUE(ConstMap.begin() == ConstMap.end());
+}
+
+// A map with a single entry
+TYPED_TEST(DenseMapTest, SingleEntryMapTest) {
+  this->Map[this->getKey()] = this->getValue();
+
+  // Size tests
+  EXPECT_EQ(1u, this->Map.size());
+  EXPECT_FALSE(this->Map.begin() == this->Map.end());
+  EXPECT_FALSE(this->Map.empty());
+
+  // Iterator tests
+  typename TypeParam::iterator it = this->Map.begin();
+  EXPECT_EQ(this->getKey(), it->first);
+  EXPECT_EQ(this->getValue(), it->second);
+  ++it;
+  EXPECT_TRUE(it == this->Map.end());
+
+  // Lookup tests
+  EXPECT_TRUE(this->Map.count(this->getKey()));
+  EXPECT_TRUE(this->Map.find(this->getKey()) == this->Map.begin());
+  EXPECT_EQ(this->getValue(), this->Map.lookup(this->getKey()));
+  EXPECT_EQ(this->getValue(), this->Map[this->getKey()]);
+}
+
+// Test clear() method
+TYPED_TEST(DenseMapTest, ClearTest) {
+  this->Map[this->getKey()] = this->getValue();
+  this->Map.clear();
+
+  EXPECT_EQ(0u, this->Map.size());
+  EXPECT_TRUE(this->Map.empty());
+  EXPECT_TRUE(this->Map.begin() == this->Map.end());
+}
+
+// Test erase(iterator) method
+TYPED_TEST(DenseMapTest, EraseTest) {
+  this->Map[this->getKey()] = this->getValue();
+  this->Map.erase(this->Map.begin());
+
+  EXPECT_EQ(0u, this->Map.size());
+  EXPECT_TRUE(this->Map.empty());
+  EXPECT_TRUE(this->Map.begin() == this->Map.end());
+}
+
+// Test erase(value) method
+TYPED_TEST(DenseMapTest, EraseTest2) {
+  this->Map[this->getKey()] = this->getValue();
+  this->Map.erase(this->getKey());
+
+  EXPECT_EQ(0u, this->Map.size());
+  EXPECT_TRUE(this->Map.empty());
+  EXPECT_TRUE(this->Map.begin() == this->Map.end());
+}
+
+// Test insert() method
+TYPED_TEST(DenseMapTest, InsertTest) {
+  this->Map.insert(std::make_pair(this->getKey(), this->getValue()));
+  EXPECT_EQ(1u, this->Map.size());
+  EXPECT_EQ(this->getValue(), this->Map[this->getKey()]);
+}
+
+// Test copy constructor method
+TYPED_TEST(DenseMapTest, CopyConstructorTest) {
+  this->Map[this->getKey()] = this->getValue();
+  TypeParam copyMap(this->Map);
+
+  EXPECT_EQ(1u, copyMap.size());
+  EXPECT_EQ(this->getValue(), copyMap[this->getKey()]);
+}
+
+// Test copy constructor method where SmallDenseMap isn't small.
+TYPED_TEST(DenseMapTest, CopyConstructorNotSmallTest) {
+  for (int Key = 0; Key < 5; ++Key)
+    this->Map[this->getKey(Key)] = this->getValue(Key);
+  TypeParam copyMap(this->Map);
+
+  EXPECT_EQ(5u, copyMap.size());
+  for (int Key = 0; Key < 5; ++Key)
+    EXPECT_EQ(this->getValue(Key), copyMap[this->getKey(Key)]);
+}
+
+// Test copying from a default-constructed map.
+TYPED_TEST(DenseMapTest, CopyConstructorFromDefaultTest) {
+  TypeParam copyMap(this->Map);
+
+  EXPECT_TRUE(copyMap.empty());
+}
+
+// Test copying from an empty map where SmallDenseMap isn't small.
+TYPED_TEST(DenseMapTest, CopyConstructorFromEmptyTest) {
+  for (int Key = 0; Key < 5; ++Key)
+    this->Map[this->getKey(Key)] = this->getValue(Key);
+  this->Map.clear();
+  TypeParam copyMap(this->Map);
+
+  EXPECT_TRUE(copyMap.empty());
+}
+
+// Test assignment operator method
+TYPED_TEST(DenseMapTest, AssignmentTest) {
+  this->Map[this->getKey()] = this->getValue();
+  TypeParam copyMap = this->Map;
+
+  EXPECT_EQ(1u, copyMap.size());
+  EXPECT_EQ(this->getValue(), copyMap[this->getKey()]);
+
+  // test self-assignment.
+  copyMap = static_cast<TypeParam &>(copyMap);
+  EXPECT_EQ(1u, copyMap.size());
+  EXPECT_EQ(this->getValue(), copyMap[this->getKey()]);
+}
+
+TYPED_TEST(DenseMapTest, AssignmentTestNotSmall) {
+  for (int Key = 0; Key < 5; ++Key)
+    this->Map[this->getKey(Key)] = this->getValue(Key);
+  TypeParam copyMap = this->Map;
+
+  EXPECT_EQ(5u, copyMap.size());
+  for (int Key = 0; Key < 5; ++Key)
+    EXPECT_EQ(this->getValue(Key), copyMap[this->getKey(Key)]);
+
+  // test self-assignment.
+  copyMap = static_cast<TypeParam &>(copyMap);
+  EXPECT_EQ(5u, copyMap.size());
+  for (int Key = 0; Key < 5; ++Key)
+    EXPECT_EQ(this->getValue(Key), copyMap[this->getKey(Key)]);
+}
+
+// Test swap method
+TYPED_TEST(DenseMapTest, SwapTest) {
+  this->Map[this->getKey()] = this->getValue();
+  TypeParam otherMap;
+
+  this->Map.swap(otherMap);
+  EXPECT_EQ(0u, this->Map.size());
+  EXPECT_TRUE(this->Map.empty());
+  EXPECT_EQ(1u, otherMap.size());
+  EXPECT_EQ(this->getValue(), otherMap[this->getKey()]);
+
+  this->Map.swap(otherMap);
+  EXPECT_EQ(0u, otherMap.size());
+  EXPECT_TRUE(otherMap.empty());
+  EXPECT_EQ(1u, this->Map.size());
+  EXPECT_EQ(this->getValue(), this->Map[this->getKey()]);
+
+  // Make this more interesting by inserting 100 numbers into the map.
+  for (int i = 0; i < 100; ++i)
+    this->Map[this->getKey(i)] = this->getValue(i);
+
+  this->Map.swap(otherMap);
+  EXPECT_EQ(0u, this->Map.size());
+  EXPECT_TRUE(this->Map.empty());
+  EXPECT_EQ(100u, otherMap.size());
+  for (int i = 0; i < 100; ++i)
+    EXPECT_EQ(this->getValue(i), otherMap[this->getKey(i)]);
+
+  this->Map.swap(otherMap);
+  EXPECT_EQ(0u, otherMap.size());
+  EXPECT_TRUE(otherMap.empty());
+  EXPECT_EQ(100u, this->Map.size());
+  for (int i = 0; i < 100; ++i)
+    EXPECT_EQ(this->getValue(i), this->Map[this->getKey(i)]);
+}
+
+// A more complex iteration test
+TYPED_TEST(DenseMapTest, IterationTest) {
+  bool visited[100];
+  std::map<typename TypeParam::key_type, unsigned> visitedIndex;
+
+  // Insert 100 numbers into the map
+  for (int i = 0; i < 100; ++i) {
+    visited[i] = false;
+    visitedIndex[this->getKey(i)] = i;
+
+    this->Map[this->getKey(i)] = this->getValue(i);
+  }
+
+  // Iterate over all numbers and mark each one found.
+  for (typename TypeParam::iterator it = this->Map.begin();
+       it != this->Map.end(); ++it)
+    visited[visitedIndex[it->first]] = true;
+
+  // Ensure every number was visited.
+  for (int i = 0; i < 100; ++i)
+    ASSERT_TRUE(visited[i]) << "Entry #" << i << " was never visited";
+}
+
+// const_iterator test
+TYPED_TEST(DenseMapTest, ConstIteratorTest) {
+  // Check conversion from iterator to const_iterator.
+  typename TypeParam::iterator it = this->Map.begin();
+  typename TypeParam::const_iterator cit(it);
+  EXPECT_TRUE(it == cit);
+
+  // Check copying of const_iterators.
+  typename TypeParam::const_iterator cit2(cit);
+  EXPECT_TRUE(cit == cit2);
+}
+
+namespace {
+// Simple class that counts how many moves and copy happens when growing a map
+struct CountCopyAndMove {
+  static int Move;
+  static int Copy;
+  CountCopyAndMove() {}
+
+  CountCopyAndMove(const CountCopyAndMove &) { Copy++; }
+  CountCopyAndMove &operator=(const CountCopyAndMove &) {
+    Copy++;
+    return *this;
+  }
+  CountCopyAndMove(CountCopyAndMove &&) { Move++; }
+  CountCopyAndMove &operator=(const CountCopyAndMove &&) {
+    Move++;
+    return *this;
+  }
+};
+int CountCopyAndMove::Copy = 0;
+int CountCopyAndMove::Move = 0;
+
+} // anonymous namespace
+
+// Test initializer list construction.
+TEST(DenseMapCustomTest, InitializerList) {
+  DenseMap<int, int> M({{0, 0}, {0, 1}, {1, 2}});
+  EXPECT_EQ(2u, M.size());
+  EXPECT_EQ(1u, M.count(0));
+  EXPECT_EQ(0, M[0]);
+  EXPECT_EQ(1u, M.count(1));
+  EXPECT_EQ(2, M[1]);
+}
+
+// Test initializer list construction.
+TEST(DenseMapCustomTest, EqualityComparison) {
+  DenseMap<int, int> M1({{0, 0}, {1, 2}});
+  DenseMap<int, int> M2({{0, 0}, {1, 2}});
+  DenseMap<int, int> M3({{0, 0}, {1, 3}});
+
+  EXPECT_EQ(M1, M2);
+  EXPECT_NE(M1, M3);
+}
+
+// Test for the default minimum size of a DenseMap
+TEST(DenseMapCustomTest, DefaultMinReservedSizeTest) {
+  // IF THIS VALUE CHANGE, please update InitialSizeTest, InitFromIterator, and
+  // ReserveTest as well!
+  const int ExpectedInitialBucketCount = 64;
+  // Formula from DenseMap::getMinBucketToReserveForEntries()
+  const int ExpectedMaxInitialEntries = ExpectedInitialBucketCount * 3 / 4 - 1;
+
+  DenseMap<int, CountCopyAndMove> Map;
+  // Will allocate 64 buckets
+  Map.reserve(1);
+  unsigned MemorySize = Map.getMemorySize();
+  CountCopyAndMove::Copy = 0;
+  CountCopyAndMove::Move = 0;
+  for (int i = 0; i < ExpectedMaxInitialEntries; ++i)
+    Map.insert(std::pair<int, CountCopyAndMove>(std::piecewise_construct,
+                                                std::forward_as_tuple(i),
+                                                std::forward_as_tuple()));
+  // Check that we didn't grow
+  EXPECT_EQ(MemorySize, Map.getMemorySize());
+  // Check that move was called the expected number of times
+  EXPECT_EQ(ExpectedMaxInitialEntries, CountCopyAndMove::Move);
+  // Check that no copy occurred
+  EXPECT_EQ(0, CountCopyAndMove::Copy);
+
+  // Adding one extra element should grow the map
+  Map.insert(std::pair<int, CountCopyAndMove>(
+      std::piecewise_construct,
+      std::forward_as_tuple(ExpectedMaxInitialEntries),
+      std::forward_as_tuple()));
+  // Check that we grew
+  EXPECT_NE(MemorySize, Map.getMemorySize());
+  // Check that move was called the expected number of times
+  //  This relies on move-construction elision, and cannot be reliably tested.
+  //   EXPECT_EQ(ExpectedMaxInitialEntries + 2, CountCopyAndMove::Move);
+  // Check that no copy occurred
+  EXPECT_EQ(0, CountCopyAndMove::Copy);
+}
+
+// Make sure creating the map with an initial size of N actually gives us enough
+// buckets to insert N items without increasing allocation size.
+TEST(DenseMapCustomTest, InitialSizeTest) {
+  // Test a few different sizes, 48 is *not* a random choice: we need a value
+  // that is 2/3 of a power of two to stress the grow() condition, and the power
+  // of two has to be at least 64 because of minimum size allocation in the
+  // DenseMap (see DefaultMinReservedSizeTest). 66 is a value just above the
+  // 64 default init.
+  for (auto Size : {1, 2, 48, 66}) {
+    DenseMap<int, CountCopyAndMove> Map(Size);
+    unsigned MemorySize = Map.getMemorySize();
+    CountCopyAndMove::Copy = 0;
+    CountCopyAndMove::Move = 0;
+    for (int i = 0; i < Size; ++i)
+      Map.insert(std::pair<int, CountCopyAndMove>(std::piecewise_construct,
+                                                  std::forward_as_tuple(i),
+                                                  std::forward_as_tuple()));
+    // Check that we didn't grow
+    EXPECT_EQ(MemorySize, Map.getMemorySize());
+    // Check that move was called the expected number of times
+    EXPECT_EQ(Size, CountCopyAndMove::Move);
+    // Check that no copy occurred
+    EXPECT_EQ(0, CountCopyAndMove::Copy);
+  }
+}
+
+// Make sure creating the map with a iterator range does not trigger grow()
+TEST(DenseMapCustomTest, InitFromIterator) {
+  std::vector<std::pair<int, CountCopyAndMove>> Values;
+  // The size is a random value greater than 64 (hardcoded DenseMap min init)
+  const int Count = 65;
+  for (int i = 0; i < Count; i++)
+    Values.emplace_back(i, CountCopyAndMove());
+
+  CountCopyAndMove::Move = 0;
+  CountCopyAndMove::Copy = 0;
+  DenseMap<int, CountCopyAndMove> Map(Values.begin(), Values.end());
+  // Check that no move occurred
+  EXPECT_EQ(0, CountCopyAndMove::Move);
+  // Check that copy was called the expected number of times
+  EXPECT_EQ(Count, CountCopyAndMove::Copy);
+}
+
+// Make sure reserve actually gives us enough buckets to insert N items
+// without increasing allocation size.
+TEST(DenseMapCustomTest, ReserveTest) {
+  // Test a few different size, 48 is *not* a random choice: we need a value
+  // that is 2/3 of a power of two to stress the grow() condition, and the power
+  // of two has to be at least 64 because of minimum size allocation in the
+  // DenseMap (see DefaultMinReservedSizeTest). 66 is a value just above the
+  // 64 default init.
+  for (auto Size : {1, 2, 48, 66}) {
+    DenseMap<int, CountCopyAndMove> Map;
+    Map.reserve(Size);
+    unsigned MemorySize = Map.getMemorySize();
+    CountCopyAndMove::Copy = 0;
+    CountCopyAndMove::Move = 0;
+    for (int i = 0; i < Size; ++i)
+      Map.insert(std::pair<int, CountCopyAndMove>(std::piecewise_construct,
+                                                  std::forward_as_tuple(i),
+                                                  std::forward_as_tuple()));
+    // Check that we didn't grow
+    EXPECT_EQ(MemorySize, Map.getMemorySize());
+    // Check that move was called the expected number of times
+    EXPECT_EQ(Size, CountCopyAndMove::Move);
+    // Check that no copy occurred
+    EXPECT_EQ(0, CountCopyAndMove::Copy);
+  }
+}
+
+// Key traits that allows lookup with either an unsigned or char* key;
+// In the latter case, "a" == 0, "b" == 1 and so on.
+struct TestDenseMapInfo {
+  static inline unsigned getEmptyKey() { return ~0; }
+  static inline unsigned getTombstoneKey() { return ~0U - 1; }
+  static unsigned getHashValue(const unsigned& Val) { return Val * 37U; }
+  static unsigned getHashValue(const char* Val) {
+    return (unsigned)(Val[0] - 'a') * 37U;
+  }
+  static bool isEqual(const unsigned& LHS, const unsigned& RHS) {
+    return LHS == RHS;
+  }
+  static bool isEqual(const char* LHS, const unsigned& RHS) {
+    return (unsigned)(LHS[0] - 'a') == RHS;
+  }
+};
+
+// find_as() tests
+TEST(DenseMapCustomTest, FindAsTest) {
+  DenseMap<unsigned, unsigned, TestDenseMapInfo> map;
+  map[0] = 1;
+  map[1] = 2;
+  map[2] = 3;
+
+  // Size tests
+  EXPECT_EQ(3u, map.size());
+
+  // Normal lookup tests
+  EXPECT_EQ(1u, map.count(1));
+  EXPECT_EQ(1u, map.find(0)->second);
+  EXPECT_EQ(2u, map.find(1)->second);
+  EXPECT_EQ(3u, map.find(2)->second);
+  EXPECT_TRUE(map.find(3) == map.end());
+
+  // find_as() tests
+  EXPECT_EQ(1u, map.find_as("a")->second);
+  EXPECT_EQ(2u, map.find_as("b")->second);
+  EXPECT_EQ(3u, map.find_as("c")->second);
+  EXPECT_TRUE(map.find_as("d") == map.end());
+}
+
+TEST(DenseMapCustomTest, SmallDenseMapInitializerList) {
+  SmallDenseMap<int, int> M = {{0, 0}, {0, 1}, {1, 2}};
+  EXPECT_EQ(2u, M.size());
+  EXPECT_EQ(1u, M.count(0));
+  EXPECT_EQ(0, M[0]);
+  EXPECT_EQ(1u, M.count(1));
+  EXPECT_EQ(2, M[1]);
+}
+
+struct ContiguousDenseMapInfo {
+  static inline unsigned getEmptyKey() { return ~0; }
+  static inline unsigned getTombstoneKey() { return ~0U - 1; }
+  static unsigned getHashValue(const unsigned& Val) { return Val; }
+  static bool isEqual(const unsigned& LHS, const unsigned& RHS) {
+    return LHS == RHS;
+  }
+};
+
+// Test that filling a small dense map with exactly the number of elements in
+// the map grows to have enough space for an empty bucket.
+TEST(DenseMapCustomTest, SmallDenseMapGrowTest) {
+  SmallDenseMap<unsigned, unsigned, 32, ContiguousDenseMapInfo> map;
+  // Add some number of elements, then delete a few to leave us some tombstones.
+  // If we just filled the map with 32 elements we'd grow because of not enough
+  // tombstones which masks the issue here.
+  for (unsigned i = 0; i < 20; ++i)
+    map[i] = i + 1;
+  for (unsigned i = 0; i < 10; ++i)
+    map.erase(i);
+  for (unsigned i = 20; i < 32; ++i)
+    map[i] = i + 1;
+
+  // Size tests
+  EXPECT_EQ(22u, map.size());
+
+  // Try to find an element which doesn't exist.  There was a bug in
+  // SmallDenseMap which led to a map with num elements == small capacity not
+  // having an empty bucket any more.  Finding an element not in the map would
+  // therefore never terminate.
+  EXPECT_TRUE(map.find(32) == map.end());
+}
+
+TEST(DenseMapCustomTest, LargeSmallDenseMapCompaction) {
+  SmallDenseMap<unsigned, unsigned, 128, ContiguousDenseMapInfo> map;
+  // Fill to < 3/4 load.
+  for (unsigned i = 0; i < 95; ++i)
+    map[i] = i;
+  // And erase, leaving behind tombstones.
+  for (unsigned i = 0; i < 95; ++i)
+    map.erase(i);
+  // Fill further, so that less than 1/8 are empty, but still below 3/4 load.
+  for (unsigned i = 95; i < 128; ++i)
+    map[i] = i;
+
+  EXPECT_EQ(33u, map.size());
+  // Similar to the previous test, check for a non-existing element, as an
+  // indirect check that tombstones have been removed.
+  EXPECT_TRUE(map.find(0) == map.end());
+}
+
+TEST(DenseMapCustomTest, TryEmplaceTest) {
+  DenseMap<int, std::unique_ptr<int>> Map;
+  std::unique_ptr<int> P(new int(2));
+  auto Try1 = Map.try_emplace(0, new int(1));
+  EXPECT_TRUE(Try1.second);
+  auto Try2 = Map.try_emplace(0, std::move(P));
+  EXPECT_FALSE(Try2.second);
+  EXPECT_EQ(Try1.first, Try2.first);
+  EXPECT_NE(nullptr, P);
+}
+
+TEST(DenseMapCustomTest, ConstTest) {
+  // Test that const pointers work okay for count and find, even when the
+  // underlying map is a non-const pointer.
+  DenseMap<int *, int> Map;
+  int A;
+  int *B = &A;
+  const int *C = &A;
+  Map.insert({B, 0});
+  EXPECT_EQ(Map.count(B), 1u);
+  EXPECT_EQ(Map.count(C), 1u);
+  EXPECT_NE(Map.find(B), Map.end());
+  EXPECT_NE(Map.find(C), Map.end());
+}
+
+struct IncompleteStruct;
+
+TEST(DenseMapCustomTest, OpaquePointerKey) {
+  // Test that we can use a pointer to an incomplete type as a DenseMap key.
+  // This is an important build time optimization, since many classes have
+  // DenseMap members.
+  DenseMap<IncompleteStruct *, int> Map;
+  int Keys[3] = {0, 0, 0};
+  IncompleteStruct *K1 = reinterpret_cast<IncompleteStruct *>(&Keys[0]);
+  IncompleteStruct *K2 = reinterpret_cast<IncompleteStruct *>(&Keys[1]);
+  IncompleteStruct *K3 = reinterpret_cast<IncompleteStruct *>(&Keys[2]);
+  Map.insert({K1, 1});
+  Map.insert({K2, 2});
+  Map.insert({K3, 3});
+  EXPECT_EQ(Map.count(K1), 1u);
+  EXPECT_EQ(Map[K1], 1);
+  EXPECT_EQ(Map[K2], 2);
+  EXPECT_EQ(Map[K3], 3);
+  Map.clear();
+  EXPECT_EQ(Map.find(K1), Map.end());
+  EXPECT_EQ(Map.find(K2), Map.end());
+  EXPECT_EQ(Map.find(K3), Map.end());
+}
+} // namespace
+
+namespace {
+struct A {
+  A(int value) : value(value) {}
+  int value;
+};
+struct B : public A {
+  using A::A;
+};
+} // namespace
+
+namespace wpi {
+template <typename T>
+struct DenseMapInfo<T, std::enable_if_t<std::is_base_of<A, T>::value>> {
+  static inline T getEmptyKey() { return {static_cast<int>(~0)}; }
+  static inline T getTombstoneKey() { return {static_cast<int>(~0U - 1)}; }
+  static unsigned getHashValue(const T &Val) { return Val.value; }
+  static bool isEqual(const T &LHS, const T &RHS) {
+    return LHS.value == RHS.value;
+  }
+};
+} // namespace wpi
+
+namespace {
+TEST(DenseMapCustomTest, SFINAEMapInfo) {
+  // Test that we can use a pointer to an incomplete type as a DenseMap key.
+  // This is an important build time optimization, since many classes have
+  // DenseMap members.
+  DenseMap<B, int> Map;
+  B Keys[3] = {{0}, {1}, {2}};
+  Map.insert({Keys[0], 1});
+  Map.insert({Keys[1], 2});
+  Map.insert({Keys[2], 3});
+  EXPECT_EQ(Map.count(Keys[0]), 1u);
+  EXPECT_EQ(Map[Keys[0]], 1);
+  EXPECT_EQ(Map[Keys[1]], 2);
+  EXPECT_EQ(Map[Keys[2]], 3);
+  Map.clear();
+  EXPECT_EQ(Map.find(Keys[0]), Map.end());
+  EXPECT_EQ(Map.find(Keys[1]), Map.end());
+  EXPECT_EQ(Map.find(Keys[2]), Map.end());
+}
+} // namespace
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/EndianTest.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/EndianTest.cpp
new file mode 100644
index 0000000..89edec4
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/EndianTest.cpp
@@ -0,0 +1,211 @@
+//===- unittests/Support/EndianTest.cpp - Endian.h tests ------------------===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+
+#include "wpi/Endian.h"
+#include "gtest/gtest.h"
+#include <cstdlib>
+#include <ctime>
+using namespace wpi;
+using namespace support;
+
+#undef max
+
+namespace {
+
+TEST(Endian, Read) {
+  // These are 5 bytes so we can be sure at least one of the reads is unaligned.
+  unsigned char bigval[] = {0x00, 0x01, 0x02, 0x03, 0x04};
+  unsigned char littleval[] = {0x00, 0x04, 0x03, 0x02, 0x01};
+  int32_t BigAsHost = 0x00010203;
+  EXPECT_EQ(BigAsHost, (endian::read<int32_t, big, unaligned>(bigval)));
+  int32_t LittleAsHost = 0x02030400;
+  EXPECT_EQ(LittleAsHost,(endian::read<int32_t, little, unaligned>(littleval)));
+
+  EXPECT_EQ((endian::read<int32_t, big, unaligned>(bigval + 1)),
+            (endian::read<int32_t, little, unaligned>(littleval + 1)));
+}
+
+TEST(Endian, ReadBitAligned) {
+  // Simple test to make sure we properly pull out the 0x0 word.
+  unsigned char littleval[] = {0x3f, 0x00, 0x00, 0x00, 0xc0, 0xff, 0xff, 0xff};
+  unsigned char bigval[] = {0x00, 0x00, 0x00, 0x3f, 0xff, 0xff, 0xff, 0xc0};
+  EXPECT_EQ(
+      (endian::readAtBitAlignment<int, little, unaligned>(&littleval[0], 6)),
+      0x0);
+  EXPECT_EQ((endian::readAtBitAlignment<int, big, unaligned>(&bigval[0], 6)),
+            0x0);
+  // Test to make sure that signed right shift of 0xf0000000 is masked
+  // properly.
+  unsigned char littleval2[] = {0x00, 0x00, 0x00, 0xf0, 0x00, 0x00, 0x00, 0x00};
+  unsigned char bigval2[] = {0xf0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00};
+  EXPECT_EQ(
+      (endian::readAtBitAlignment<int, little, unaligned>(&littleval2[0], 4)),
+      0x0f000000);
+  EXPECT_EQ((endian::readAtBitAlignment<int, big, unaligned>(&bigval2[0], 4)),
+            0x0f000000);
+  // Test to make sure left shift of start bit doesn't overflow.
+  EXPECT_EQ(
+      (endian::readAtBitAlignment<int, little, unaligned>(&littleval2[0], 1)),
+      0x78000000);
+  EXPECT_EQ((endian::readAtBitAlignment<int, big, unaligned>(&bigval2[0], 1)),
+            0x78000000);
+  // Test to make sure 64-bit int doesn't overflow.
+  unsigned char littleval3[] = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xf0,
+                                0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00};
+  unsigned char bigval3[] = {0xf0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+                             0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00};
+  EXPECT_EQ((endian::readAtBitAlignment<int64_t, little, unaligned>(
+                &littleval3[0], 4)),
+            0x0f00000000000000);
+  EXPECT_EQ(
+      (endian::readAtBitAlignment<int64_t, big, unaligned>(&bigval3[0], 4)),
+      0x0f00000000000000);
+}
+
+TEST(Endian, WriteBitAligned) {
+  // This test ensures that signed right shift of 0xffffaa is masked
+  // properly.
+  unsigned char bigval[8] = {0x00};
+  endian::writeAtBitAlignment<int32_t, big, unaligned>(bigval, (int)0xffffaaaa,
+                                                       4);
+  EXPECT_EQ(bigval[0], 0xff);
+  EXPECT_EQ(bigval[1], 0xfa);
+  EXPECT_EQ(bigval[2], 0xaa);
+  EXPECT_EQ(bigval[3], 0xa0);
+  EXPECT_EQ(bigval[4], 0x00);
+  EXPECT_EQ(bigval[5], 0x00);
+  EXPECT_EQ(bigval[6], 0x00);
+  EXPECT_EQ(bigval[7], 0x0f);
+
+  unsigned char littleval[8] = {0x00};
+  endian::writeAtBitAlignment<int32_t, little, unaligned>(littleval,
+                                                          (int)0xffffaaaa, 4);
+  EXPECT_EQ(littleval[0], 0xa0);
+  EXPECT_EQ(littleval[1], 0xaa);
+  EXPECT_EQ(littleval[2], 0xfa);
+  EXPECT_EQ(littleval[3], 0xff);
+  EXPECT_EQ(littleval[4], 0x0f);
+  EXPECT_EQ(littleval[5], 0x00);
+  EXPECT_EQ(littleval[6], 0x00);
+  EXPECT_EQ(littleval[7], 0x00);
+
+  // This test makes sure 1<<31 doesn't overflow.
+  // Test to make sure left shift of start bit doesn't overflow.
+  unsigned char bigval2[8] = {0x00};
+  endian::writeAtBitAlignment<int32_t, big, unaligned>(bigval2, (int)0xffffffff,
+                                                       1);
+  EXPECT_EQ(bigval2[0], 0xff);
+  EXPECT_EQ(bigval2[1], 0xff);
+  EXPECT_EQ(bigval2[2], 0xff);
+  EXPECT_EQ(bigval2[3], 0xfe);
+  EXPECT_EQ(bigval2[4], 0x00);
+  EXPECT_EQ(bigval2[5], 0x00);
+  EXPECT_EQ(bigval2[6], 0x00);
+  EXPECT_EQ(bigval2[7], 0x01);
+
+  unsigned char littleval2[8] = {0x00};
+  endian::writeAtBitAlignment<int32_t, little, unaligned>(littleval2,
+                                                          (int)0xffffffff, 1);
+  EXPECT_EQ(littleval2[0], 0xfe);
+  EXPECT_EQ(littleval2[1], 0xff);
+  EXPECT_EQ(littleval2[2], 0xff);
+  EXPECT_EQ(littleval2[3], 0xff);
+  EXPECT_EQ(littleval2[4], 0x01);
+  EXPECT_EQ(littleval2[5], 0x00);
+  EXPECT_EQ(littleval2[6], 0x00);
+  EXPECT_EQ(littleval2[7], 0x00);
+
+  // Test to make sure 64-bit int doesn't overflow.
+  unsigned char bigval64[16] = {0x00};
+  endian::writeAtBitAlignment<int64_t, big, unaligned>(
+      bigval64, (int64_t)0xffffffffffffffff, 1);
+  EXPECT_EQ(bigval64[0], 0xff);
+  EXPECT_EQ(bigval64[1], 0xff);
+  EXPECT_EQ(bigval64[2], 0xff);
+  EXPECT_EQ(bigval64[3], 0xff);
+  EXPECT_EQ(bigval64[4], 0xff);
+  EXPECT_EQ(bigval64[5], 0xff);
+  EXPECT_EQ(bigval64[6], 0xff);
+  EXPECT_EQ(bigval64[7], 0xfe);
+  EXPECT_EQ(bigval64[8], 0x00);
+  EXPECT_EQ(bigval64[9], 0x00);
+  EXPECT_EQ(bigval64[10], 0x00);
+  EXPECT_EQ(bigval64[11], 0x00);
+  EXPECT_EQ(bigval64[12], 0x00);
+  EXPECT_EQ(bigval64[13], 0x00);
+  EXPECT_EQ(bigval64[14], 0x00);
+  EXPECT_EQ(bigval64[15], 0x01);
+
+  unsigned char littleval64[16] = {0x00};
+  endian::writeAtBitAlignment<int64_t, little, unaligned>(
+      littleval64, (int64_t)0xffffffffffffffff, 1);
+  EXPECT_EQ(littleval64[0], 0xfe);
+  EXPECT_EQ(littleval64[1], 0xff);
+  EXPECT_EQ(littleval64[2], 0xff);
+  EXPECT_EQ(littleval64[3], 0xff);
+  EXPECT_EQ(littleval64[4], 0xff);
+  EXPECT_EQ(littleval64[5], 0xff);
+  EXPECT_EQ(littleval64[6], 0xff);
+  EXPECT_EQ(littleval64[7], 0xff);
+  EXPECT_EQ(littleval64[8], 0x01);
+  EXPECT_EQ(littleval64[9], 0x00);
+  EXPECT_EQ(littleval64[10], 0x00);
+  EXPECT_EQ(littleval64[11], 0x00);
+  EXPECT_EQ(littleval64[12], 0x00);
+  EXPECT_EQ(littleval64[13], 0x00);
+  EXPECT_EQ(littleval64[14], 0x00);
+  EXPECT_EQ(littleval64[15], 0x00);
+}
+
+TEST(Endian, Write) {
+  unsigned char data[5];
+  endian::write<int32_t, big, unaligned>(data, -1362446643);
+  EXPECT_EQ(data[0], 0xAE);
+  EXPECT_EQ(data[1], 0xCA);
+  EXPECT_EQ(data[2], 0xB6);
+  EXPECT_EQ(data[3], 0xCD);
+  endian::write<int32_t, big, unaligned>(data + 1, -1362446643);
+  EXPECT_EQ(data[1], 0xAE);
+  EXPECT_EQ(data[2], 0xCA);
+  EXPECT_EQ(data[3], 0xB6);
+  EXPECT_EQ(data[4], 0xCD);
+
+  endian::write<int32_t, little, unaligned>(data, -1362446643);
+  EXPECT_EQ(data[0], 0xCD);
+  EXPECT_EQ(data[1], 0xB6);
+  EXPECT_EQ(data[2], 0xCA);
+  EXPECT_EQ(data[3], 0xAE);
+  endian::write<int32_t, little, unaligned>(data + 1, -1362446643);
+  EXPECT_EQ(data[1], 0xCD);
+  EXPECT_EQ(data[2], 0xB6);
+  EXPECT_EQ(data[3], 0xCA);
+  EXPECT_EQ(data[4], 0xAE);
+}
+
+TEST(Endian, PackedEndianSpecificIntegral) {
+  // These are 5 bytes so we can be sure at least one of the reads is unaligned.
+  unsigned char big[] = {0x00, 0x01, 0x02, 0x03, 0x04};
+  unsigned char little[] = {0x00, 0x04, 0x03, 0x02, 0x01};
+  big32_t    *big_val    =
+    reinterpret_cast<big32_t *>(big + 1);
+  little32_t *little_val =
+    reinterpret_cast<little32_t *>(little + 1);
+
+  EXPECT_EQ(*big_val, *little_val);
+}
+
+TEST(Endian, PacketEndianSpecificIntegralAsEnum) {
+  enum class Test : uint16_t { ONETWO = 0x0102, TWOONE = 0x0201 };
+  unsigned char bytes[] = {0x01, 0x02};
+  using LittleTest = little_t<Test>;
+  using BigTest = big_t<Test>;
+  EXPECT_EQ(Test::TWOONE, *reinterpret_cast<LittleTest *>(bytes));
+  EXPECT_EQ(Test::ONETWO, *reinterpret_cast<BigTest *>(bytes));
+}
+
+} // end anon namespace
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/ErrnoTest.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/ErrnoTest.cpp
new file mode 100644
index 0000000..fed8ad6
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/ErrnoTest.cpp
@@ -0,0 +1,38 @@
+//===- ErrnoTest.cpp - Error handling unit tests --------------------------===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+
+#include "wpi/Errno.h"
+#include "gtest/gtest.h"
+
+using namespace wpi::sys;
+
+TEST(ErrnoTest, RetryAfterSignal) {
+  EXPECT_EQ(1, RetryAfterSignal(-1, [] { return 1; }));
+
+  EXPECT_EQ(-1, RetryAfterSignal(-1, [] {
+    errno = EAGAIN;
+    return -1;
+  }));
+  EXPECT_EQ(EAGAIN, errno);
+
+  unsigned calls = 0;
+  EXPECT_EQ(1, RetryAfterSignal(-1, [&calls] {
+              errno = EINTR;
+              ++calls;
+              return calls == 1 ? -1 : 1;
+            }));
+  EXPECT_EQ(2u, calls);
+
+  EXPECT_EQ(1, RetryAfterSignal(-1, [](int x) { return x; }, 1));
+
+  std::unique_ptr<int> P(RetryAfterSignal(nullptr, [] { return new int(47); }));
+  EXPECT_EQ(47, *P);
+
+  errno = EINTR;
+  EXPECT_EQ(-1, RetryAfterSignal(-1, [] { return -1; }));
+}
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/FunctionExtrasTest.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/FunctionExtrasTest.cpp
index 5dcd11f..53508cc 100644
--- a/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/FunctionExtrasTest.cpp
+++ b/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/FunctionExtrasTest.cpp
@@ -1,9 +1,8 @@
 //===- FunctionExtrasTest.cpp - Unit tests for function type erasure ------===//
 //
-//                     The LLVM Compiler Infrastructure
-//
-// This file is distributed under the University of Illinois Open Source
-// License. See LICENSE.TXT for details.
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
 //
 //===----------------------------------------------------------------------===//
 
@@ -11,6 +10,7 @@
 #include "gtest/gtest.h"
 
 #include <memory>
+#include <type_traits>
 
 using namespace wpi;
 
@@ -225,4 +225,89 @@
   UnmovableF(X);
 }
 
+TEST(UniqueFunctionTest, Const) {
+  // Can assign from const lambda.
+  unique_function<int(int) const> Plus2 = [X(std::make_unique<int>(2))](int Y) {
+    return *X + Y;
+  };
+  EXPECT_EQ(5, Plus2(3));
+
+  // Can call through a const ref.
+  const auto &Plus2Ref = Plus2;
+  EXPECT_EQ(5, Plus2Ref(3));
+
+  // Can move-construct and assign.
+  unique_function<int(int) const> Plus2A = std::move(Plus2);
+  EXPECT_EQ(5, Plus2A(3));
+  unique_function<int(int) const> Plus2B;
+  Plus2B = std::move(Plus2A);
+  EXPECT_EQ(5, Plus2B(3));
+
+  // Can convert to non-const function type, but not back.
+  unique_function<int(int)> Plus2C = std::move(Plus2B);
+  EXPECT_EQ(5, Plus2C(3));
+
+  // Overloaded call operator correctly resolved.
+  struct ChooseCorrectOverload {
+    std::string_view operator()() { return "non-const"; }
+    std::string_view operator()() const { return "const"; }
+  };
+  unique_function<std::string_view()> ChooseMutable = ChooseCorrectOverload();
+  ChooseCorrectOverload A;
+  EXPECT_EQ("non-const", ChooseMutable());
+  EXPECT_EQ("non-const", A());
+  unique_function<std::string_view() const> ChooseConst = ChooseCorrectOverload();
+  const ChooseCorrectOverload &X = A;
+  EXPECT_EQ("const", ChooseConst());
+  EXPECT_EQ("const", X());
+}
+
+// Test that overloads on unique_functions are resolved as expected.
+std::string returns(std::string_view) { return "not a function"; }
+std::string returns(unique_function<double()> F) { return "number"; }
+std::string returns(unique_function<std::string_view()> F) { return "string"; }
+
+TEST(UniqueFunctionTest, SFINAE) {
+  EXPECT_EQ("not a function", returns("boo!"));
+  EXPECT_EQ("number", returns([] { return 42; }));
+  EXPECT_EQ("string", returns([] { return "hello"; }));
+}
+
+// A forward declared type, and a templated type.
+class Incomplete;
+template <typename T> class Templated { T A; };
+
+// Check that we can define unique_function that have references to
+// incomplete types, even if those types are templated over an
+// incomplete type.
+TEST(UniqueFunctionTest, IncompleteTypes) {
+  unique_function<void(Templated<Incomplete> &&)>
+      IncompleteArgumentRValueReference;
+  unique_function<void(Templated<Incomplete> &)>
+      IncompleteArgumentLValueReference;
+  unique_function<void(Templated<Incomplete> *)> IncompleteArgumentPointer;
+  unique_function<Templated<Incomplete> &()> IncompleteResultLValueReference;
+  unique_function<Templated<Incomplete> && ()> IncompleteResultRValueReference2;
+  unique_function<Templated<Incomplete> *()> IncompleteResultPointer;
+}
+
+// Incomplete function returning an incomplete type
+Incomplete incompleteFunction();
+const Incomplete incompleteFunctionConst();
+
+// Check that we can assign a callable to a unique_function when the
+// callable return value is incomplete.
+TEST(UniqueFunctionTest, IncompleteCallableType) {
+  unique_function<Incomplete()> IncompleteReturnInCallable{incompleteFunction};
+  unique_function<const Incomplete()> IncompleteReturnInCallableConst{
+      incompleteFunctionConst};
+  unique_function<const Incomplete()> IncompleteReturnInCallableConstConversion{
+      incompleteFunction};
+}
+
+// Define the incomplete function
+class Incomplete {};
+Incomplete incompleteFunction() { return {}; }
+const Incomplete incompleteFunctionConst() { return {}; }
+
 } // anonymous namespace
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/MapVectorTest.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/MapVectorTest.cpp
new file mode 100644
index 0000000..99bda8a
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/MapVectorTest.cpp
@@ -0,0 +1,430 @@
+//===- unittest/ADT/MapVectorTest.cpp - MapVector unit tests ----*- C++ -*-===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+
+#if defined(__GNUC__)
+#pragma GCC diagnostic ignored "-Wpedantic"
+#if !defined(__clang__)
+#pragma GCC diagnostic ignored "-Wmaybe-uninitialized"
+#endif
+#endif
+
+#include "wpi/MapVector.h"
+#include "wpi/iterator_range.h"
+#include "gtest/gtest.h"
+#include <utility>
+
+using namespace wpi;
+
+TEST(MapVectorTest, swap) {
+  MapVector<int, int> MV1, MV2;
+  std::pair<MapVector<int, int>::iterator, bool> R;
+
+  R = MV1.insert(std::make_pair(1, 2));
+  ASSERT_EQ(R.first, MV1.begin());
+  EXPECT_EQ(R.first->first, 1);
+  EXPECT_EQ(R.first->second, 2);
+  EXPECT_TRUE(R.second);
+
+  EXPECT_FALSE(MV1.empty());
+  EXPECT_TRUE(MV2.empty());
+  MV2.swap(MV1);
+  EXPECT_TRUE(MV1.empty());
+  EXPECT_FALSE(MV2.empty());
+
+  auto I = MV1.find(1);
+  ASSERT_EQ(MV1.end(), I);
+
+  I = MV2.find(1);
+  ASSERT_EQ(I, MV2.begin());
+  EXPECT_EQ(I->first, 1);
+  EXPECT_EQ(I->second, 2);
+}
+
+TEST(MapVectorTest, insert_pop) {
+  MapVector<int, int> MV;
+  std::pair<MapVector<int, int>::iterator, bool> R;
+
+  R = MV.insert(std::make_pair(1, 2));
+  ASSERT_EQ(R.first, MV.begin());
+  EXPECT_EQ(R.first->first, 1);
+  EXPECT_EQ(R.first->second, 2);
+  EXPECT_TRUE(R.second);
+
+  R = MV.insert(std::make_pair(1, 3));
+  ASSERT_EQ(R.first, MV.begin());
+  EXPECT_EQ(R.first->first, 1);
+  EXPECT_EQ(R.first->second, 2);
+  EXPECT_FALSE(R.second);
+
+  R = MV.insert(std::make_pair(4, 5));
+  ASSERT_NE(R.first, MV.end());
+  EXPECT_EQ(R.first->first, 4);
+  EXPECT_EQ(R.first->second, 5);
+  EXPECT_TRUE(R.second);
+
+  EXPECT_EQ(MV.size(), 2u);
+  EXPECT_EQ(MV[1], 2);
+  EXPECT_EQ(MV[4], 5);
+
+  MV.pop_back();
+  EXPECT_EQ(MV.size(), 1u);
+  EXPECT_EQ(MV[1], 2);
+
+  R = MV.insert(std::make_pair(4, 7));
+  ASSERT_NE(R.first, MV.end());
+  EXPECT_EQ(R.first->first, 4);
+  EXPECT_EQ(R.first->second, 7);
+  EXPECT_TRUE(R.second);
+
+  EXPECT_EQ(MV.size(), 2u);
+  EXPECT_EQ(MV[1], 2);
+  EXPECT_EQ(MV[4], 7);
+}
+
+TEST(MapVectorTest, erase) {
+  MapVector<int, int> MV;
+
+  MV.insert(std::make_pair(1, 2));
+  MV.insert(std::make_pair(3, 4));
+  MV.insert(std::make_pair(5, 6));
+  ASSERT_EQ(MV.size(), 3u);
+
+  MV.erase(MV.find(1));
+  ASSERT_EQ(MV.size(), 2u);
+  ASSERT_EQ(MV.find(1), MV.end());
+  ASSERT_EQ(MV[3], 4);
+  ASSERT_EQ(MV[5], 6);
+
+  ASSERT_EQ(MV.erase(3), 1u);
+  ASSERT_EQ(MV.size(), 1u);
+  ASSERT_EQ(MV.find(3), MV.end());
+  ASSERT_EQ(MV[5], 6);
+
+  ASSERT_EQ(MV.erase(79), 0u);
+  ASSERT_EQ(MV.size(), 1u);
+}
+
+TEST(MapVectorTest, remove_if) {
+  MapVector<int, int> MV;
+
+  MV.insert(std::make_pair(1, 11));
+  MV.insert(std::make_pair(2, 12));
+  MV.insert(std::make_pair(3, 13));
+  MV.insert(std::make_pair(4, 14));
+  MV.insert(std::make_pair(5, 15));
+  MV.insert(std::make_pair(6, 16));
+  ASSERT_EQ(MV.size(), 6u);
+
+  MV.remove_if([](const std::pair<int, int> &Val) { return Val.second % 2; });
+  ASSERT_EQ(MV.size(), 3u);
+  ASSERT_EQ(MV.find(1), MV.end());
+  ASSERT_EQ(MV.find(3), MV.end());
+  ASSERT_EQ(MV.find(5), MV.end());
+  ASSERT_EQ(MV[2], 12);
+  ASSERT_EQ(MV[4], 14);
+  ASSERT_EQ(MV[6], 16);
+}
+
+TEST(MapVectorTest, iteration_test) {
+  MapVector<int, int> MV;
+
+  MV.insert(std::make_pair(1, 11));
+  MV.insert(std::make_pair(2, 12));
+  MV.insert(std::make_pair(3, 13));
+  MV.insert(std::make_pair(4, 14));
+  MV.insert(std::make_pair(5, 15));
+  MV.insert(std::make_pair(6, 16));
+  ASSERT_EQ(MV.size(), 6u);
+
+  int count = 1;
+  for (auto P : make_range(MV.begin(), MV.end())) {
+    ASSERT_EQ(P.first, count);
+    count++;
+  }
+
+  count = 6;
+  for (auto P : make_range(MV.rbegin(), MV.rend())) {
+    ASSERT_EQ(P.first, count);
+    count--;
+  }
+}
+
+TEST(MapVectorTest, NonCopyable) {
+  MapVector<int, std::unique_ptr<int>> MV;
+  MV.insert(std::make_pair(1, std::make_unique<int>(1)));
+  MV.insert(std::make_pair(2, std::make_unique<int>(2)));
+
+  ASSERT_EQ(MV.count(1), 1u);
+  ASSERT_EQ(*MV.find(2)->second, 2);
+}
+
+template <class IntType> struct MapVectorMappedTypeTest : ::testing::Test {
+  using int_type = IntType;
+};
+
+using MapIntTypes = ::testing::Types<int, long, long long, unsigned,
+                                     unsigned long, unsigned long long>;
+TYPED_TEST_SUITE(MapVectorMappedTypeTest, MapIntTypes, );
+
+TYPED_TEST(MapVectorMappedTypeTest, DifferentDenseMap) {
+  // Test that using a map with a mapped type other than 'unsigned' compiles
+  // and works.
+  using IntType = typename TestFixture::int_type;
+  using MapVectorType = MapVector<int, int, DenseMap<int, IntType>>;
+
+  MapVectorType MV;
+  std::pair<typename MapVectorType::iterator, bool> R;
+
+  R = MV.insert(std::make_pair(1, 2));
+  ASSERT_EQ(R.first, MV.begin());
+  EXPECT_EQ(R.first->first, 1);
+  EXPECT_EQ(R.first->second, 2);
+  EXPECT_TRUE(R.second);
+
+  const std::pair<int, int> Elem(1, 3);
+  R = MV.insert(Elem);
+  ASSERT_EQ(R.first, MV.begin());
+  EXPECT_EQ(R.first->first, 1);
+  EXPECT_EQ(R.first->second, 2);
+  EXPECT_FALSE(R.second);
+
+  int& value = MV[4];
+  EXPECT_EQ(value, 0);
+  value = 5;
+
+  EXPECT_EQ(MV.size(), 2u);
+  EXPECT_EQ(MV[1], 2);
+  EXPECT_EQ(MV[4], 5);
+}
+
+TEST(SmallMapVectorSmallTest, insert_pop) {
+  SmallMapVector<int, int, 32> MV;
+  std::pair<SmallMapVector<int, int, 32>::iterator, bool> R;
+
+  R = MV.insert(std::make_pair(1, 2));
+  ASSERT_EQ(R.first, MV.begin());
+  EXPECT_EQ(R.first->first, 1);
+  EXPECT_EQ(R.first->second, 2);
+  EXPECT_TRUE(R.second);
+
+  R = MV.insert(std::make_pair(1, 3));
+  ASSERT_EQ(R.first, MV.begin());
+  EXPECT_EQ(R.first->first, 1);
+  EXPECT_EQ(R.first->second, 2);
+  EXPECT_FALSE(R.second);
+
+  R = MV.insert(std::make_pair(4, 5));
+  ASSERT_NE(R.first, MV.end());
+  EXPECT_EQ(R.first->first, 4);
+  EXPECT_EQ(R.first->second, 5);
+  EXPECT_TRUE(R.second);
+
+  EXPECT_EQ(MV.size(), 2u);
+  EXPECT_EQ(MV[1], 2);
+  EXPECT_EQ(MV[4], 5);
+
+  MV.pop_back();
+  EXPECT_EQ(MV.size(), 1u);
+  EXPECT_EQ(MV[1], 2);
+
+  R = MV.insert(std::make_pair(4, 7));
+  ASSERT_NE(R.first, MV.end());
+  EXPECT_EQ(R.first->first, 4);
+  EXPECT_EQ(R.first->second, 7);
+  EXPECT_TRUE(R.second);
+
+  EXPECT_EQ(MV.size(), 2u);
+  EXPECT_EQ(MV[1], 2);
+  EXPECT_EQ(MV[4], 7);
+}
+
+TEST(SmallMapVectorSmallTest, erase) {
+  SmallMapVector<int, int, 32> MV;
+
+  MV.insert(std::make_pair(1, 2));
+  MV.insert(std::make_pair(3, 4));
+  MV.insert(std::make_pair(5, 6));
+  ASSERT_EQ(MV.size(), 3u);
+
+  MV.erase(MV.find(1));
+  ASSERT_EQ(MV.size(), 2u);
+  ASSERT_EQ(MV.find(1), MV.end());
+  ASSERT_EQ(MV[3], 4);
+  ASSERT_EQ(MV[5], 6);
+
+  ASSERT_EQ(MV.erase(3), 1u);
+  ASSERT_EQ(MV.size(), 1u);
+  ASSERT_EQ(MV.find(3), MV.end());
+  ASSERT_EQ(MV[5], 6);
+
+  ASSERT_EQ(MV.erase(79), 0u);
+  ASSERT_EQ(MV.size(), 1u);
+}
+
+TEST(SmallMapVectorSmallTest, remove_if) {
+  SmallMapVector<int, int, 32> MV;
+
+  MV.insert(std::make_pair(1, 11));
+  MV.insert(std::make_pair(2, 12));
+  MV.insert(std::make_pair(3, 13));
+  MV.insert(std::make_pair(4, 14));
+  MV.insert(std::make_pair(5, 15));
+  MV.insert(std::make_pair(6, 16));
+  ASSERT_EQ(MV.size(), 6u);
+
+  MV.remove_if([](const std::pair<int, int> &Val) { return Val.second % 2; });
+  ASSERT_EQ(MV.size(), 3u);
+  ASSERT_EQ(MV.find(1), MV.end());
+  ASSERT_EQ(MV.find(3), MV.end());
+  ASSERT_EQ(MV.find(5), MV.end());
+  ASSERT_EQ(MV[2], 12);
+  ASSERT_EQ(MV[4], 14);
+  ASSERT_EQ(MV[6], 16);
+}
+
+TEST(SmallMapVectorSmallTest, iteration_test) {
+  SmallMapVector<int, int, 32> MV;
+
+  MV.insert(std::make_pair(1, 11));
+  MV.insert(std::make_pair(2, 12));
+  MV.insert(std::make_pair(3, 13));
+  MV.insert(std::make_pair(4, 14));
+  MV.insert(std::make_pair(5, 15));
+  MV.insert(std::make_pair(6, 16));
+  ASSERT_EQ(MV.size(), 6u);
+
+  int count = 1;
+  for (auto P : make_range(MV.begin(), MV.end())) {
+    ASSERT_EQ(P.first, count);
+    count++;
+  }
+
+  count = 6;
+  for (auto P : make_range(MV.rbegin(), MV.rend())) {
+    ASSERT_EQ(P.first, count);
+    count--;
+  }
+}
+
+TEST(SmallMapVectorSmallTest, NonCopyable) {
+  SmallMapVector<int, std::unique_ptr<int>, 8> MV;
+  MV.insert(std::make_pair(1, std::make_unique<int>(1)));
+  MV.insert(std::make_pair(2, std::make_unique<int>(2)));
+
+  ASSERT_EQ(MV.count(1), 1u);
+  ASSERT_EQ(*MV.find(2)->second, 2);
+}
+
+TEST(SmallMapVectorLargeTest, insert_pop) {
+  SmallMapVector<int, int, 1> MV;
+  std::pair<SmallMapVector<int, int, 1>::iterator, bool> R;
+
+  R = MV.insert(std::make_pair(1, 2));
+  ASSERT_EQ(R.first, MV.begin());
+  EXPECT_EQ(R.first->first, 1);
+  EXPECT_EQ(R.first->second, 2);
+  EXPECT_TRUE(R.second);
+
+  R = MV.insert(std::make_pair(1, 3));
+  ASSERT_EQ(R.first, MV.begin());
+  EXPECT_EQ(R.first->first, 1);
+  EXPECT_EQ(R.first->second, 2);
+  EXPECT_FALSE(R.second);
+
+  R = MV.insert(std::make_pair(4, 5));
+  ASSERT_NE(R.first, MV.end());
+  EXPECT_EQ(R.first->first, 4);
+  EXPECT_EQ(R.first->second, 5);
+  EXPECT_TRUE(R.second);
+
+  EXPECT_EQ(MV.size(), 2u);
+  EXPECT_EQ(MV[1], 2);
+  EXPECT_EQ(MV[4], 5);
+
+  MV.pop_back();
+  EXPECT_EQ(MV.size(), 1u);
+  EXPECT_EQ(MV[1], 2);
+
+  R = MV.insert(std::make_pair(4, 7));
+  ASSERT_NE(R.first, MV.end());
+  EXPECT_EQ(R.first->first, 4);
+  EXPECT_EQ(R.first->second, 7);
+  EXPECT_TRUE(R.second);
+
+  EXPECT_EQ(MV.size(), 2u);
+  EXPECT_EQ(MV[1], 2);
+  EXPECT_EQ(MV[4], 7);
+}
+
+TEST(SmallMapVectorLargeTest, erase) {
+  SmallMapVector<int, int, 1> MV;
+
+  MV.insert(std::make_pair(1, 2));
+  MV.insert(std::make_pair(3, 4));
+  MV.insert(std::make_pair(5, 6));
+  ASSERT_EQ(MV.size(), 3u);
+
+  MV.erase(MV.find(1));
+  ASSERT_EQ(MV.size(), 2u);
+  ASSERT_EQ(MV.find(1), MV.end());
+  ASSERT_EQ(MV[3], 4);
+  ASSERT_EQ(MV[5], 6);
+
+  ASSERT_EQ(MV.erase(3), 1u);
+  ASSERT_EQ(MV.size(), 1u);
+  ASSERT_EQ(MV.find(3), MV.end());
+  ASSERT_EQ(MV[5], 6);
+
+  ASSERT_EQ(MV.erase(79), 0u);
+  ASSERT_EQ(MV.size(), 1u);
+}
+
+TEST(SmallMapVectorLargeTest, remove_if) {
+  SmallMapVector<int, int, 1> MV;
+
+  MV.insert(std::make_pair(1, 11));
+  MV.insert(std::make_pair(2, 12));
+  MV.insert(std::make_pair(3, 13));
+  MV.insert(std::make_pair(4, 14));
+  MV.insert(std::make_pair(5, 15));
+  MV.insert(std::make_pair(6, 16));
+  ASSERT_EQ(MV.size(), 6u);
+
+  MV.remove_if([](const std::pair<int, int> &Val) { return Val.second % 2; });
+  ASSERT_EQ(MV.size(), 3u);
+  ASSERT_EQ(MV.find(1), MV.end());
+  ASSERT_EQ(MV.find(3), MV.end());
+  ASSERT_EQ(MV.find(5), MV.end());
+  ASSERT_EQ(MV[2], 12);
+  ASSERT_EQ(MV[4], 14);
+  ASSERT_EQ(MV[6], 16);
+}
+
+TEST(SmallMapVectorLargeTest, iteration_test) {
+  SmallMapVector<int, int, 1> MV;
+
+  MV.insert(std::make_pair(1, 11));
+  MV.insert(std::make_pair(2, 12));
+  MV.insert(std::make_pair(3, 13));
+  MV.insert(std::make_pair(4, 14));
+  MV.insert(std::make_pair(5, 15));
+  MV.insert(std::make_pair(6, 16));
+  ASSERT_EQ(MV.size(), 6u);
+
+  int count = 1;
+  for (auto P : make_range(MV.begin(), MV.end())) {
+    ASSERT_EQ(P.first, count);
+    count++;
+  }
+
+  count = 6;
+  for (auto P : make_range(MV.rbegin(), MV.rend())) {
+    ASSERT_EQ(P.first, count);
+    count--;
+  }
+}
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/MathExtrasTest.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/MathExtrasTest.cpp
new file mode 100644
index 0000000..f392887
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/MathExtrasTest.cpp
@@ -0,0 +1,607 @@
+//===- unittests/Support/MathExtrasTest.cpp - math utils tests ------------===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+
+#include "wpi/MathExtras.h"
+#include "gtest/gtest.h"
+
+using namespace wpi;
+
+namespace {
+
+TEST(MathExtras, countTrailingZeros) {
+  uint8_t Z8 = 0;
+  uint16_t Z16 = 0;
+  uint32_t Z32 = 0;
+  uint64_t Z64 = 0;
+  EXPECT_EQ(8u, countTrailingZeros(Z8));
+  EXPECT_EQ(16u, countTrailingZeros(Z16));
+  EXPECT_EQ(32u, countTrailingZeros(Z32));
+  EXPECT_EQ(64u, countTrailingZeros(Z64));
+
+  uint8_t NZ8 = 42;
+  uint16_t NZ16 = 42;
+  uint32_t NZ32 = 42;
+  uint64_t NZ64 = 42;
+  EXPECT_EQ(1u, countTrailingZeros(NZ8));
+  EXPECT_EQ(1u, countTrailingZeros(NZ16));
+  EXPECT_EQ(1u, countTrailingZeros(NZ32));
+  EXPECT_EQ(1u, countTrailingZeros(NZ64));
+}
+
+TEST(MathExtras, countLeadingZeros) {
+  uint8_t Z8 = 0;
+  uint16_t Z16 = 0;
+  uint32_t Z32 = 0;
+  uint64_t Z64 = 0;
+  EXPECT_EQ(8u, countLeadingZeros(Z8));
+  EXPECT_EQ(16u, countLeadingZeros(Z16));
+  EXPECT_EQ(32u, countLeadingZeros(Z32));
+  EXPECT_EQ(64u, countLeadingZeros(Z64));
+
+  uint8_t NZ8 = 42;
+  uint16_t NZ16 = 42;
+  uint32_t NZ32 = 42;
+  uint64_t NZ64 = 42;
+  EXPECT_EQ(2u, countLeadingZeros(NZ8));
+  EXPECT_EQ(10u, countLeadingZeros(NZ16));
+  EXPECT_EQ(26u, countLeadingZeros(NZ32));
+  EXPECT_EQ(58u, countLeadingZeros(NZ64));
+
+  EXPECT_EQ(8u, countLeadingZeros(0x00F000FFu));
+  EXPECT_EQ(8u, countLeadingZeros(0x00F12345u));
+  for (unsigned i = 0; i <= 30; ++i) {
+    EXPECT_EQ(31 - i, countLeadingZeros(1u << i));
+  }
+
+  EXPECT_EQ(8u, countLeadingZeros(0x00F1234500F12345ULL));
+  EXPECT_EQ(1u, countLeadingZeros(1ULL << 62));
+  for (unsigned i = 0; i <= 62; ++i) {
+    EXPECT_EQ(63 - i, countLeadingZeros(1ULL << i));
+  }
+}
+
+TEST(MathExtras, onesMask) {
+  EXPECT_EQ(0U, maskLeadingOnes<uint8_t>(0));
+  EXPECT_EQ(0U, maskTrailingOnes<uint8_t>(0));
+  EXPECT_EQ(0U, maskLeadingOnes<uint16_t>(0));
+  EXPECT_EQ(0U, maskTrailingOnes<uint16_t>(0));
+  EXPECT_EQ(0U, maskLeadingOnes<uint32_t>(0));
+  EXPECT_EQ(0U, maskTrailingOnes<uint32_t>(0));
+  EXPECT_EQ(0U, maskLeadingOnes<uint64_t>(0));
+  EXPECT_EQ(0U, maskTrailingOnes<uint64_t>(0));
+
+  EXPECT_EQ(0x00000003U, maskTrailingOnes<uint32_t>(2U));
+  EXPECT_EQ(0xC0000000U, maskLeadingOnes<uint32_t>(2U));
+
+  EXPECT_EQ(0x000007FFU, maskTrailingOnes<uint32_t>(11U));
+  EXPECT_EQ(0xFFE00000U, maskLeadingOnes<uint32_t>(11U));
+
+  EXPECT_EQ(0xFFFFFFFFU, maskTrailingOnes<uint32_t>(32U));
+  EXPECT_EQ(0xFFFFFFFFU, maskLeadingOnes<uint32_t>(32U));
+  EXPECT_EQ(0xFFFFFFFFFFFFFFFFULL, maskTrailingOnes<uint64_t>(64U));
+  EXPECT_EQ(0xFFFFFFFFFFFFFFFFULL, maskLeadingOnes<uint64_t>(64U));
+
+  EXPECT_EQ(0x0000FFFFFFFFFFFFULL, maskTrailingOnes<uint64_t>(48U));
+  EXPECT_EQ(0xFFFFFFFFFFFF0000ULL, maskLeadingOnes<uint64_t>(48U));
+}
+
+TEST(MathExtras, findFirstSet) {
+  uint8_t Z8 = 0;
+  uint16_t Z16 = 0;
+  uint32_t Z32 = 0;
+  uint64_t Z64 = 0;
+  EXPECT_EQ(0xFFULL, findFirstSet(Z8));
+  EXPECT_EQ(0xFFFFULL, findFirstSet(Z16));
+  EXPECT_EQ(0xFFFFFFFFULL, findFirstSet(Z32));
+  EXPECT_EQ(0xFFFFFFFFFFFFFFFFULL, findFirstSet(Z64));
+
+  uint8_t NZ8 = 42;
+  uint16_t NZ16 = 42;
+  uint32_t NZ32 = 42;
+  uint64_t NZ64 = 42;
+  EXPECT_EQ(1u, findFirstSet(NZ8));
+  EXPECT_EQ(1u, findFirstSet(NZ16));
+  EXPECT_EQ(1u, findFirstSet(NZ32));
+  EXPECT_EQ(1u, findFirstSet(NZ64));
+}
+
+TEST(MathExtras, findLastSet) {
+  uint8_t Z8 = 0;
+  uint16_t Z16 = 0;
+  uint32_t Z32 = 0;
+  uint64_t Z64 = 0;
+  EXPECT_EQ(0xFFULL, findLastSet(Z8));
+  EXPECT_EQ(0xFFFFULL, findLastSet(Z16));
+  EXPECT_EQ(0xFFFFFFFFULL, findLastSet(Z32));
+  EXPECT_EQ(0xFFFFFFFFFFFFFFFFULL, findLastSet(Z64));
+
+  uint8_t NZ8 = 42;
+  uint16_t NZ16 = 42;
+  uint32_t NZ32 = 42;
+  uint64_t NZ64 = 42;
+  EXPECT_EQ(5u, findLastSet(NZ8));
+  EXPECT_EQ(5u, findLastSet(NZ16));
+  EXPECT_EQ(5u, findLastSet(NZ32));
+  EXPECT_EQ(5u, findLastSet(NZ64));
+}
+
+TEST(MathExtras, isIntN) {
+  EXPECT_TRUE(isIntN(16, 32767));
+  EXPECT_FALSE(isIntN(16, 32768));
+}
+
+TEST(MathExtras, isUIntN) {
+  EXPECT_TRUE(isUIntN(16, 65535));
+  EXPECT_FALSE(isUIntN(16, 65536));
+  EXPECT_TRUE(isUIntN(1, 0));
+  EXPECT_TRUE(isUIntN(6, 63));
+}
+
+TEST(MathExtras, maxIntN) {
+  EXPECT_EQ(32767, maxIntN(16));
+  EXPECT_EQ(2147483647, maxIntN(32));
+  EXPECT_EQ(std::numeric_limits<int32_t>::max(), maxIntN(32));
+  EXPECT_EQ(std::numeric_limits<int64_t>::max(), maxIntN(64));
+}
+
+TEST(MathExtras, minIntN) {
+  EXPECT_EQ(-32768LL, minIntN(16));
+  EXPECT_EQ(-64LL, minIntN(7));
+  EXPECT_EQ(std::numeric_limits<int32_t>::min(), minIntN(32));
+  EXPECT_EQ(std::numeric_limits<int64_t>::min(), minIntN(64));
+}
+
+TEST(MathExtras, maxUIntN) {
+  EXPECT_EQ(0xffffULL, maxUIntN(16));
+  EXPECT_EQ(0xffffffffULL, maxUIntN(32));
+  EXPECT_EQ(0xffffffffffffffffULL, maxUIntN(64));
+  EXPECT_EQ(1ULL, maxUIntN(1));
+  EXPECT_EQ(0x0fULL, maxUIntN(4));
+}
+
+TEST(MathExtras, reverseBits) {
+  uint8_t NZ8 = 42;
+  uint16_t NZ16 = 42;
+  uint32_t NZ32 = 42;
+  uint64_t NZ64 = 42;
+  EXPECT_EQ(0x54ULL, reverseBits(NZ8));
+  EXPECT_EQ(0x5400ULL, reverseBits(NZ16));
+  EXPECT_EQ(0x54000000ULL, reverseBits(NZ32));
+  EXPECT_EQ(0x5400000000000000ULL, reverseBits(NZ64));
+}
+
+TEST(MathExtras, isPowerOf2_32) {
+  EXPECT_FALSE(isPowerOf2_32(0));
+  EXPECT_TRUE(isPowerOf2_32(1 << 6));
+  EXPECT_TRUE(isPowerOf2_32(1 << 12));
+  EXPECT_FALSE(isPowerOf2_32((1 << 19) + 3));
+  EXPECT_FALSE(isPowerOf2_32(0xABCDEF0));
+}
+
+TEST(MathExtras, isPowerOf2_64) {
+  EXPECT_FALSE(isPowerOf2_64(0));
+  EXPECT_TRUE(isPowerOf2_64(1LL << 46));
+  EXPECT_TRUE(isPowerOf2_64(1LL << 12));
+  EXPECT_FALSE(isPowerOf2_64((1LL << 53) + 3));
+  EXPECT_FALSE(isPowerOf2_64(0xABCDEF0ABCDEF0LL));
+}
+
+TEST(MathExtras, PowerOf2Ceil) {
+  EXPECT_EQ(0U, PowerOf2Ceil(0U));
+  EXPECT_EQ(8U, PowerOf2Ceil(8U));
+  EXPECT_EQ(8U, PowerOf2Ceil(7U));
+}
+
+TEST(MathExtras, PowerOf2Floor) {
+  EXPECT_EQ(0U, PowerOf2Floor(0U));
+  EXPECT_EQ(8U, PowerOf2Floor(8U));
+  EXPECT_EQ(4U, PowerOf2Floor(7U));
+}
+
+TEST(MathExtras, CTLog2) {
+  EXPECT_EQ(CTLog2<1ULL << 0>(), 0U);
+  EXPECT_EQ(CTLog2<1ULL << 1>(), 1U);
+  EXPECT_EQ(CTLog2<1ULL << 2>(), 2U);
+  EXPECT_EQ(CTLog2<1ULL << 3>(), 3U);
+  EXPECT_EQ(CTLog2<1ULL << 4>(), 4U);
+  EXPECT_EQ(CTLog2<1ULL << 5>(), 5U);
+  EXPECT_EQ(CTLog2<1ULL << 6>(), 6U);
+  EXPECT_EQ(CTLog2<1ULL << 7>(), 7U);
+  EXPECT_EQ(CTLog2<1ULL << 8>(), 8U);
+  EXPECT_EQ(CTLog2<1ULL << 9>(), 9U);
+  EXPECT_EQ(CTLog2<1ULL << 10>(), 10U);
+  EXPECT_EQ(CTLog2<1ULL << 11>(), 11U);
+  EXPECT_EQ(CTLog2<1ULL << 12>(), 12U);
+  EXPECT_EQ(CTLog2<1ULL << 13>(), 13U);
+  EXPECT_EQ(CTLog2<1ULL << 14>(), 14U);
+  EXPECT_EQ(CTLog2<1ULL << 15>(), 15U);
+}
+
+TEST(MathExtras, countLeadingOnes) {
+  for (int i = 30; i >= 0; --i) {
+    // Start with all ones and unset some bit.
+    EXPECT_EQ(31u - i, countLeadingOnes(0xFFFFFFFF ^ (1 << i)));
+  }
+  for (int i = 62; i >= 0; --i) {
+    // Start with all ones and unset some bit.
+    EXPECT_EQ(63u - i, countLeadingOnes(0xFFFFFFFFFFFFFFFFULL ^ (1LL << i)));
+  }
+  for (int i = 30; i >= 0; --i) {
+    // Start with all ones and unset some bit.
+    EXPECT_EQ(31u - i, countLeadingOnes(0xFFFFFFFF ^ (1 << i)));
+  }
+}
+
+TEST(MathExtras, FloatBits) {
+  static const float kValue = 5632.34f;
+  EXPECT_FLOAT_EQ(kValue, BitsToFloat(FloatToBits(kValue)));
+}
+
+TEST(MathExtras, DoubleBits) {
+  static const double kValue = 87987234.983498;
+  EXPECT_DOUBLE_EQ(kValue, BitsToDouble(DoubleToBits(kValue)));
+}
+
+TEST(MathExtras, MinAlign) {
+  EXPECT_EQ(1u, MinAlign(2, 3));
+  EXPECT_EQ(2u, MinAlign(2, 4));
+  EXPECT_EQ(1u, MinAlign(17, 64));
+  EXPECT_EQ(256u, MinAlign(256, 512));
+}
+
+TEST(MathExtras, NextPowerOf2) {
+  EXPECT_EQ(4u, NextPowerOf2(3));
+  EXPECT_EQ(16u, NextPowerOf2(15));
+  EXPECT_EQ(256u, NextPowerOf2(128));
+}
+
+TEST(MathExtras, alignTo) {
+  EXPECT_EQ(8u, alignTo(5, 8));
+  EXPECT_EQ(24u, alignTo(17, 8));
+  EXPECT_EQ(0u, alignTo(~0LL, 8));
+
+  EXPECT_EQ(7u, alignTo(5, 8, 7));
+  EXPECT_EQ(17u, alignTo(17, 8, 1));
+  EXPECT_EQ(3u, alignTo(~0LL, 8, 3));
+  EXPECT_EQ(552u, alignTo(321, 255, 42));
+}
+
+template<typename T>
+void SaturatingAddTestHelper()
+{
+  const T Max = std::numeric_limits<T>::max();
+  bool ResultOverflowed;
+
+  EXPECT_EQ(T(3), SaturatingAdd(T(1), T(2)));
+  EXPECT_EQ(T(3), SaturatingAdd(T(1), T(2), &ResultOverflowed));
+  EXPECT_FALSE(ResultOverflowed);
+
+  EXPECT_EQ(Max, SaturatingAdd(Max, T(1)));
+  EXPECT_EQ(Max, SaturatingAdd(Max, T(1), &ResultOverflowed));
+  EXPECT_TRUE(ResultOverflowed);
+
+  EXPECT_EQ(Max, SaturatingAdd(T(1), T(Max - 1)));
+  EXPECT_EQ(Max, SaturatingAdd(T(1), T(Max - 1), &ResultOverflowed));
+  EXPECT_FALSE(ResultOverflowed);
+
+  EXPECT_EQ(Max, SaturatingAdd(T(1), Max));
+  EXPECT_EQ(Max, SaturatingAdd(T(1), Max, &ResultOverflowed));
+  EXPECT_TRUE(ResultOverflowed);
+
+  EXPECT_EQ(Max, SaturatingAdd(Max, Max));
+  EXPECT_EQ(Max, SaturatingAdd(Max, Max, &ResultOverflowed));
+  EXPECT_TRUE(ResultOverflowed);
+}
+
+TEST(MathExtras, SaturatingAdd) {
+  SaturatingAddTestHelper<uint8_t>();
+  SaturatingAddTestHelper<uint16_t>();
+  SaturatingAddTestHelper<uint32_t>();
+  SaturatingAddTestHelper<uint64_t>();
+}
+
+template<typename T>
+void SaturatingMultiplyTestHelper()
+{
+  const T Max = std::numeric_limits<T>::max();
+  bool ResultOverflowed;
+
+  // Test basic multiplication.
+  EXPECT_EQ(T(6), SaturatingMultiply(T(2), T(3)));
+  EXPECT_EQ(T(6), SaturatingMultiply(T(2), T(3), &ResultOverflowed));
+  EXPECT_FALSE(ResultOverflowed);
+
+  EXPECT_EQ(T(6), SaturatingMultiply(T(3), T(2)));
+  EXPECT_EQ(T(6), SaturatingMultiply(T(3), T(2), &ResultOverflowed));
+  EXPECT_FALSE(ResultOverflowed);
+
+  // Test multiplication by zero.
+  EXPECT_EQ(T(0), SaturatingMultiply(T(0), T(0)));
+  EXPECT_EQ(T(0), SaturatingMultiply(T(0), T(0), &ResultOverflowed));
+  EXPECT_FALSE(ResultOverflowed);
+
+  EXPECT_EQ(T(0), SaturatingMultiply(T(1), T(0)));
+  EXPECT_EQ(T(0), SaturatingMultiply(T(1), T(0), &ResultOverflowed));
+  EXPECT_FALSE(ResultOverflowed);
+
+  EXPECT_EQ(T(0), SaturatingMultiply(T(0), T(1)));
+  EXPECT_EQ(T(0), SaturatingMultiply(T(0), T(1), &ResultOverflowed));
+  EXPECT_FALSE(ResultOverflowed);
+
+  EXPECT_EQ(T(0), SaturatingMultiply(Max, T(0)));
+  EXPECT_EQ(T(0), SaturatingMultiply(Max, T(0), &ResultOverflowed));
+  EXPECT_FALSE(ResultOverflowed);
+
+  EXPECT_EQ(T(0), SaturatingMultiply(T(0), Max));
+  EXPECT_EQ(T(0), SaturatingMultiply(T(0), Max, &ResultOverflowed));
+  EXPECT_FALSE(ResultOverflowed);
+
+  // Test multiplication by maximum value.
+  EXPECT_EQ(Max, SaturatingMultiply(Max, T(2)));
+  EXPECT_EQ(Max, SaturatingMultiply(Max, T(2), &ResultOverflowed));
+  EXPECT_TRUE(ResultOverflowed);
+
+  EXPECT_EQ(Max, SaturatingMultiply(T(2), Max));
+  EXPECT_EQ(Max, SaturatingMultiply(T(2), Max, &ResultOverflowed));
+  EXPECT_TRUE(ResultOverflowed);
+
+  EXPECT_EQ(Max, SaturatingMultiply(Max, Max));
+  EXPECT_EQ(Max, SaturatingMultiply(Max, Max, &ResultOverflowed));
+  EXPECT_TRUE(ResultOverflowed);
+
+  // Test interesting boundary conditions for algorithm -
+  // ((1 << A) - 1) * ((1 << B) + K) for K in [-1, 0, 1]
+  // and A + B == std::numeric_limits<T>::digits.
+  // We expect overflow iff A > B and K = 1.
+  const int Digits = std::numeric_limits<T>::digits;
+  for (int A = 1, B = Digits - 1; B >= 1; ++A, --B) {
+    for (int K = -1; K <= 1; ++K) {
+      T X = (T(1) << A) - T(1);
+      T Y = (T(1) << B) + K;
+      bool OverflowExpected = A > B && K == 1;
+
+      if(OverflowExpected) {
+        EXPECT_EQ(Max, SaturatingMultiply(X, Y));
+        EXPECT_EQ(Max, SaturatingMultiply(X, Y, &ResultOverflowed));
+        EXPECT_TRUE(ResultOverflowed);
+      } else {
+        EXPECT_EQ(X * Y, SaturatingMultiply(X, Y));
+        EXPECT_EQ(X * Y, SaturatingMultiply(X, Y, &ResultOverflowed));
+        EXPECT_FALSE(ResultOverflowed);
+      }
+    }
+  }
+}
+
+TEST(MathExtras, SaturatingMultiply) {
+  SaturatingMultiplyTestHelper<uint8_t>();
+  SaturatingMultiplyTestHelper<uint16_t>();
+  SaturatingMultiplyTestHelper<uint32_t>();
+  SaturatingMultiplyTestHelper<uint64_t>();
+}
+
+template<typename T>
+void SaturatingMultiplyAddTestHelper()
+{
+  const T Max = std::numeric_limits<T>::max();
+  bool ResultOverflowed;
+
+  // Test basic multiply-add.
+  EXPECT_EQ(T(16), SaturatingMultiplyAdd(T(2), T(3), T(10)));
+  EXPECT_EQ(T(16), SaturatingMultiplyAdd(T(2), T(3), T(10), &ResultOverflowed));
+  EXPECT_FALSE(ResultOverflowed);
+
+  // Test multiply overflows, add doesn't overflow
+  EXPECT_EQ(Max, SaturatingMultiplyAdd(Max, Max, T(0), &ResultOverflowed));
+  EXPECT_TRUE(ResultOverflowed);
+
+  // Test multiply doesn't overflow, add overflows
+  EXPECT_EQ(Max, SaturatingMultiplyAdd(T(1), T(1), Max, &ResultOverflowed));
+  EXPECT_TRUE(ResultOverflowed);
+
+  // Test multiply-add with Max as operand
+  EXPECT_EQ(Max, SaturatingMultiplyAdd(T(1), T(1), Max, &ResultOverflowed));
+  EXPECT_TRUE(ResultOverflowed);
+
+  EXPECT_EQ(Max, SaturatingMultiplyAdd(T(1), Max, T(1), &ResultOverflowed));
+  EXPECT_TRUE(ResultOverflowed);
+
+  EXPECT_EQ(Max, SaturatingMultiplyAdd(Max, Max, T(1), &ResultOverflowed));
+  EXPECT_TRUE(ResultOverflowed);
+
+  EXPECT_EQ(Max, SaturatingMultiplyAdd(Max, Max, Max, &ResultOverflowed));
+  EXPECT_TRUE(ResultOverflowed);
+
+  // Test multiply-add with 0 as operand
+  EXPECT_EQ(T(1), SaturatingMultiplyAdd(T(1), T(1), T(0), &ResultOverflowed));
+  EXPECT_FALSE(ResultOverflowed);
+
+  EXPECT_EQ(T(1), SaturatingMultiplyAdd(T(1), T(0), T(1), &ResultOverflowed));
+  EXPECT_FALSE(ResultOverflowed);
+
+  EXPECT_EQ(T(1), SaturatingMultiplyAdd(T(0), T(0), T(1), &ResultOverflowed));
+  EXPECT_FALSE(ResultOverflowed);
+
+  EXPECT_EQ(T(0), SaturatingMultiplyAdd(T(0), T(0), T(0), &ResultOverflowed));
+  EXPECT_FALSE(ResultOverflowed);
+
+}
+
+TEST(MathExtras, SaturatingMultiplyAdd) {
+  SaturatingMultiplyAddTestHelper<uint8_t>();
+  SaturatingMultiplyAddTestHelper<uint16_t>();
+  SaturatingMultiplyAddTestHelper<uint32_t>();
+  SaturatingMultiplyAddTestHelper<uint64_t>();
+}
+
+TEST(MathExtras, IsShiftedUInt) {
+  EXPECT_TRUE((isShiftedUInt<1, 0>(0)));
+  EXPECT_TRUE((isShiftedUInt<1, 0>(1)));
+  EXPECT_FALSE((isShiftedUInt<1, 0>(2)));
+  EXPECT_FALSE((isShiftedUInt<1, 0>(3)));
+  EXPECT_FALSE((isShiftedUInt<1, 0>(0x8000000000000000)));
+  EXPECT_TRUE((isShiftedUInt<1, 63>(0x8000000000000000)));
+  EXPECT_TRUE((isShiftedUInt<2, 62>(0xC000000000000000)));
+  EXPECT_FALSE((isShiftedUInt<2, 62>(0xE000000000000000)));
+
+  // 0x201 is ten bits long and has a 1 in the MSB and LSB.
+  EXPECT_TRUE((isShiftedUInt<10, 5>(uint64_t(0x201) << 5)));
+  EXPECT_FALSE((isShiftedUInt<10, 5>(uint64_t(0x201) << 4)));
+  EXPECT_FALSE((isShiftedUInt<10, 5>(uint64_t(0x201) << 6)));
+}
+
+TEST(MathExtras, IsShiftedInt) {
+  EXPECT_TRUE((isShiftedInt<1, 0>(0)));
+  EXPECT_TRUE((isShiftedInt<1, 0>(-1)));
+  EXPECT_FALSE((isShiftedInt<1, 0>(2)));
+  EXPECT_FALSE((isShiftedInt<1, 0>(3)));
+  EXPECT_FALSE((isShiftedInt<1, 0>(0x8000000000000000)));
+  EXPECT_TRUE((isShiftedInt<1, 63>(0x8000000000000000)));
+  EXPECT_TRUE((isShiftedInt<2, 62>(0xC000000000000000)));
+  EXPECT_FALSE((isShiftedInt<2, 62>(0xE000000000000000)));
+
+  // 0x201 is ten bits long and has a 1 in the MSB and LSB.
+  EXPECT_TRUE((isShiftedInt<11, 5>(int64_t(0x201) << 5)));
+  EXPECT_FALSE((isShiftedInt<11, 5>(int64_t(0x201) << 3)));
+  EXPECT_FALSE((isShiftedInt<11, 5>(int64_t(0x201) << 6)));
+  EXPECT_TRUE((isShiftedInt<11, 5>(-(int64_t(0x201) << 5))));
+  EXPECT_FALSE((isShiftedInt<11, 5>(-(int64_t(0x201) << 3))));
+  EXPECT_FALSE((isShiftedInt<11, 5>(-(int64_t(0x201) << 6))));
+
+  EXPECT_TRUE((isShiftedInt<6, 10>(-(int64_t(1) << 15))));
+  EXPECT_FALSE((isShiftedInt<6, 10>(int64_t(1) << 15)));
+}
+
+template <typename T>
+class OverflowTest : public ::testing::Test { };
+
+using OverflowTestTypes = ::testing::Types<signed char, short, int, long,
+                                           long long>;
+
+TYPED_TEST_SUITE(OverflowTest, OverflowTestTypes, );
+
+TYPED_TEST(OverflowTest, AddNoOverflow) {
+  TypeParam Result;
+  EXPECT_FALSE(AddOverflow<TypeParam>(1, 2, Result));
+  EXPECT_EQ(Result, TypeParam(3));
+}
+
+TYPED_TEST(OverflowTest, AddOverflowToNegative) {
+  TypeParam Result;
+  auto MaxValue = std::numeric_limits<TypeParam>::max();
+  EXPECT_TRUE(AddOverflow<TypeParam>(MaxValue, MaxValue, Result));
+  EXPECT_EQ(Result, TypeParam(-2));
+}
+
+TYPED_TEST(OverflowTest, AddOverflowToMin) {
+  TypeParam Result;
+  auto MaxValue = std::numeric_limits<TypeParam>::max();
+  EXPECT_TRUE(AddOverflow<TypeParam>(MaxValue, TypeParam(1), Result));
+  EXPECT_EQ(Result, std::numeric_limits<TypeParam>::min());
+}
+
+TYPED_TEST(OverflowTest, AddOverflowToZero) {
+  TypeParam Result;
+  auto MinValue = std::numeric_limits<TypeParam>::min();
+  EXPECT_TRUE(AddOverflow<TypeParam>(MinValue, MinValue, Result));
+  EXPECT_EQ(Result, TypeParam(0));
+}
+
+TYPED_TEST(OverflowTest, AddOverflowToMax) {
+  TypeParam Result;
+  auto MinValue = std::numeric_limits<TypeParam>::min();
+  EXPECT_TRUE(AddOverflow<TypeParam>(MinValue, TypeParam(-1), Result));
+  EXPECT_EQ(Result, std::numeric_limits<TypeParam>::max());
+}
+
+TYPED_TEST(OverflowTest, SubNoOverflow) {
+  TypeParam Result;
+  EXPECT_FALSE(SubOverflow<TypeParam>(1, 2, Result));
+  EXPECT_EQ(Result, TypeParam(-1));
+}
+
+TYPED_TEST(OverflowTest, SubOverflowToMax) {
+  TypeParam Result;
+  auto MinValue = std::numeric_limits<TypeParam>::min();
+  EXPECT_TRUE(SubOverflow<TypeParam>(0, MinValue, Result));
+  EXPECT_EQ(Result, MinValue);
+}
+
+TYPED_TEST(OverflowTest, SubOverflowToMin) {
+  TypeParam Result;
+  auto MinValue = std::numeric_limits<TypeParam>::min();
+  EXPECT_TRUE(SubOverflow<TypeParam>(0, MinValue, Result));
+  EXPECT_EQ(Result, MinValue);
+}
+
+TYPED_TEST(OverflowTest, SubOverflowToNegative) {
+  TypeParam Result;
+  auto MaxValue = std::numeric_limits<TypeParam>::max();
+  auto MinValue = std::numeric_limits<TypeParam>::min();
+  EXPECT_TRUE(SubOverflow<TypeParam>(MaxValue, MinValue, Result));
+  EXPECT_EQ(Result, TypeParam(-1));
+}
+
+TYPED_TEST(OverflowTest, SubOverflowToPositive) {
+  TypeParam Result;
+  auto MaxValue = std::numeric_limits<TypeParam>::max();
+  auto MinValue = std::numeric_limits<TypeParam>::min();
+  EXPECT_TRUE(SubOverflow<TypeParam>(MinValue, MaxValue, Result));
+  EXPECT_EQ(Result, TypeParam(1));
+}
+
+TYPED_TEST(OverflowTest, MulNoOverflow) {
+  TypeParam Result;
+  EXPECT_FALSE(MulOverflow<TypeParam>(1, 2, Result));
+  EXPECT_EQ(Result, 2);
+  EXPECT_FALSE(MulOverflow<TypeParam>(-1, 3, Result));
+  EXPECT_EQ(Result, -3);
+  EXPECT_FALSE(MulOverflow<TypeParam>(4, -2, Result));
+  EXPECT_EQ(Result, -8);
+  EXPECT_FALSE(MulOverflow<TypeParam>(-6, -5, Result));
+  EXPECT_EQ(Result, 30);
+}
+
+TYPED_TEST(OverflowTest, MulNoOverflowToMax) {
+  TypeParam Result;
+  auto MaxValue = std::numeric_limits<TypeParam>::max();
+  auto MinValue = std::numeric_limits<TypeParam>::min();
+  EXPECT_FALSE(MulOverflow<TypeParam>(MinValue + 1, -1, Result));
+  EXPECT_EQ(Result, MaxValue);
+}
+
+TYPED_TEST(OverflowTest, MulOverflowToMin) {
+  TypeParam Result;
+  auto MinValue = std::numeric_limits<TypeParam>::min();
+  EXPECT_TRUE(MulOverflow<TypeParam>(MinValue, -1, Result));
+  EXPECT_EQ(Result, MinValue);
+}
+
+TYPED_TEST(OverflowTest, MulOverflowMax) {
+  TypeParam Result;
+  auto MinValue = std::numeric_limits<TypeParam>::min();
+  auto MaxValue = std::numeric_limits<TypeParam>::max();
+  EXPECT_TRUE(MulOverflow<TypeParam>(MinValue, MinValue, Result));
+  EXPECT_EQ(Result, 0);
+  EXPECT_TRUE(MulOverflow<TypeParam>(MaxValue, MaxValue, Result));
+  EXPECT_EQ(Result, 1);
+}
+
+TYPED_TEST(OverflowTest, MulResultZero) {
+  TypeParam Result;
+  EXPECT_FALSE(MulOverflow<TypeParam>(4, 0, Result));
+  EXPECT_EQ(Result, TypeParam(0));
+  EXPECT_FALSE(MulOverflow<TypeParam>(-5, 0, Result));
+  EXPECT_EQ(Result, TypeParam(0));
+  EXPECT_FALSE(MulOverflow<TypeParam>(0, 5, Result));
+  EXPECT_EQ(Result, TypeParam(0));
+  EXPECT_FALSE(MulOverflow<TypeParam>(0, -5, Result));
+  EXPECT_EQ(Result, TypeParam(0));
+}
+
+} // namespace
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/PointerIntPairTest.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/PointerIntPairTest.cpp
new file mode 100644
index 0000000..fcca5b6
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/PointerIntPairTest.cpp
@@ -0,0 +1,109 @@
+//===- llvm/unittest/ADT/PointerIntPairTest.cpp - Unit tests --------------===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+
+#include "wpi/PointerIntPair.h"
+#include "gtest/gtest.h"
+#include <limits>
+using namespace wpi;
+
+namespace {
+
+TEST(PointerIntPairTest, GetSet) {
+  struct S {
+    int i;
+  };
+  S s;
+
+  PointerIntPair<S *, 2> Pair(&s, 1U);
+  EXPECT_EQ(&s, Pair.getPointer());
+  EXPECT_EQ(1U, Pair.getInt());
+
+  Pair.setInt(2);
+  EXPECT_EQ(&s, Pair.getPointer());
+  EXPECT_EQ(2U, Pair.getInt());
+
+  Pair.setPointer(nullptr);
+  EXPECT_EQ(nullptr, Pair.getPointer());
+  EXPECT_EQ(2U, Pair.getInt());
+
+  Pair.setPointerAndInt(&s, 3U);
+  EXPECT_EQ(&s, Pair.getPointer());
+  EXPECT_EQ(3U, Pair.getInt());
+
+  // Make sure that we can perform all of our operations on enum classes.
+  //
+  // The concern is that enum classes are only explicitly convertible to
+  // integers. This means that if we assume in PointerIntPair this, a
+  // compilation error will result. This group of tests exercises the enum class
+  // code to make sure that we do not run into such issues in the future.
+  enum class E : unsigned {
+    Case1,
+    Case2,
+    Case3,
+  };
+  PointerIntPair<S *, 2, E> Pair2(&s, E::Case1);
+  EXPECT_EQ(&s, Pair2.getPointer());
+  EXPECT_EQ(E::Case1, Pair2.getInt());
+
+  Pair2.setInt(E::Case2);
+  EXPECT_EQ(&s, Pair2.getPointer());
+  EXPECT_EQ(E::Case2, Pair2.getInt());
+
+  Pair2.setPointer(nullptr);
+  EXPECT_EQ(nullptr, Pair2.getPointer());
+  EXPECT_EQ(E::Case2, Pair2.getInt());
+
+  Pair2.setPointerAndInt(&s, E::Case3);
+  EXPECT_EQ(&s, Pair2.getPointer());
+  EXPECT_EQ(E::Case3, Pair2.getInt());
+
+  static_assert(std::is_trivially_copyable<PointerIntPair<S *, 2, E>>::value,
+                "trivially copyable");
+}
+
+TEST(PointerIntPairTest, DefaultInitialize) {
+  PointerIntPair<float *, 2> Pair;
+  EXPECT_EQ(nullptr, Pair.getPointer());
+  EXPECT_EQ(0U, Pair.getInt());
+}
+
+// In real code this would be a word-sized integer limited to 31 bits.
+struct Fixnum31 {
+  uintptr_t Value;
+};
+struct FixnumPointerTraits {
+  static inline void *getAsVoidPointer(Fixnum31 Num) {
+    return reinterpret_cast<void *>(Num.Value << NumLowBitsAvailable);
+  }
+  static inline Fixnum31 getFromVoidPointer(void *P) {
+    // In real code this would assert that the value is in range.
+    return {reinterpret_cast<uintptr_t>(P) >> NumLowBitsAvailable};
+  }
+  static constexpr int NumLowBitsAvailable =
+      std::numeric_limits<uintptr_t>::digits - 31;
+};
+TEST(PointerIntPairTest, ManyUnusedBits) {
+
+  PointerIntPair<Fixnum31, 1, bool, FixnumPointerTraits> pair;
+  EXPECT_EQ((uintptr_t)0, pair.getPointer().Value);
+  EXPECT_FALSE(pair.getInt());
+
+  pair.setPointerAndInt({ 0x7FFFFFFF }, true );
+  EXPECT_EQ((uintptr_t)0x7FFFFFFF, pair.getPointer().Value);
+  EXPECT_TRUE(pair.getInt());
+
+  EXPECT_EQ(FixnumPointerTraits::NumLowBitsAvailable - 1,
+            (int)PointerLikeTypeTraits<decltype(pair)>::NumLowBitsAvailable);
+
+  static_assert(
+      std::is_trivially_copyable<
+          PointerIntPair<Fixnum31, 1, bool, FixnumPointerTraits>>::value,
+      "trivially copyable");
+}
+
+} // end anonymous namespace
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/PointerUnionTest.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/PointerUnionTest.cpp
new file mode 100644
index 0000000..5a94a45
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/PointerUnionTest.cpp
@@ -0,0 +1,159 @@
+//===- llvm/unittest/ADT/PointerUnionTest.cpp - Optional unit tests -------===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+
+#include "wpi/PointerUnion.h"
+#include "gtest/gtest.h"
+using namespace wpi;
+
+namespace {
+
+typedef PointerUnion<int *, float *> PU;
+typedef PointerUnion<int *, float *, long long *> PU3;
+typedef PointerUnion<int *, float *, long long *, double *> PU4;
+
+struct PointerUnionTest : public testing::Test {
+  float f;
+  int i;
+  double d;
+  long long l;
+
+  PU a, b, c, n;
+  PU3 i3, f3, l3;
+  PU4 i4, f4, l4, d4;
+  PU4 i4null, f4null, l4null, d4null;
+
+  PointerUnionTest()
+      : f(3.14f), i(42), d(3.14), l(42), a(&f), b(&i), c(&i), n(), i3(&i),
+        f3(&f), l3(&l), i4(&i), f4(&f), l4(&l), d4(&d), i4null((int *)nullptr),
+        f4null((float *)nullptr), l4null((long long *)nullptr),
+        d4null((double *)nullptr) {}
+};
+
+TEST_F(PointerUnionTest, Comparison) {
+  EXPECT_TRUE(a == a);
+  EXPECT_FALSE(a != a);
+  EXPECT_TRUE(a != b);
+  EXPECT_FALSE(a == b);
+  EXPECT_TRUE(b == c);
+  EXPECT_FALSE(b != c);
+  EXPECT_TRUE(b != n);
+  EXPECT_FALSE(b == n);
+  EXPECT_TRUE(i3 == i3);
+  EXPECT_FALSE(i3 != i3);
+  EXPECT_TRUE(i3 != f3);
+  EXPECT_TRUE(f3 != l3);
+  EXPECT_TRUE(i4 == i4);
+  EXPECT_FALSE(i4 != i4);
+  EXPECT_TRUE(i4 != f4);
+  EXPECT_TRUE(i4 != l4);
+  EXPECT_TRUE(f4 != l4);
+  EXPECT_TRUE(l4 != d4);
+  EXPECT_TRUE(i4null != f4null);
+  EXPECT_TRUE(i4null != l4null);
+  EXPECT_TRUE(i4null != d4null);
+}
+
+TEST_F(PointerUnionTest, Null) {
+  EXPECT_FALSE(a.isNull());
+  EXPECT_FALSE(b.isNull());
+  EXPECT_TRUE(n.isNull());
+  EXPECT_FALSE(!a);
+  EXPECT_FALSE(!b);
+  EXPECT_TRUE(!n);
+  // workaround an issue with EXPECT macros and explicit bool
+  EXPECT_TRUE((bool)a);
+  EXPECT_TRUE((bool)b);
+  EXPECT_FALSE(n);
+
+  EXPECT_NE(n, b);
+  EXPECT_EQ(b, c);
+  b = nullptr;
+  EXPECT_EQ(n, b);
+  EXPECT_NE(b, c);
+  EXPECT_FALSE(i3.isNull());
+  EXPECT_FALSE(f3.isNull());
+  EXPECT_FALSE(l3.isNull());
+  EXPECT_FALSE(i4.isNull());
+  EXPECT_FALSE(f4.isNull());
+  EXPECT_FALSE(l4.isNull());
+  EXPECT_FALSE(d4.isNull());
+  EXPECT_TRUE(i4null.isNull());
+  EXPECT_TRUE(f4null.isNull());
+  EXPECT_TRUE(l4null.isNull());
+  EXPECT_TRUE(d4null.isNull());
+}
+
+TEST_F(PointerUnionTest, Is) {
+  EXPECT_FALSE(a.is<int *>());
+  EXPECT_TRUE(a.is<float *>());
+  EXPECT_TRUE(b.is<int *>());
+  EXPECT_FALSE(b.is<float *>());
+  EXPECT_TRUE(n.is<int *>());
+  EXPECT_FALSE(n.is<float *>());
+  EXPECT_TRUE(i3.is<int *>());
+  EXPECT_TRUE(f3.is<float *>());
+  EXPECT_TRUE(l3.is<long long *>());
+  EXPECT_TRUE(i4.is<int *>());
+  EXPECT_TRUE(f4.is<float *>());
+  EXPECT_TRUE(l4.is<long long *>());
+  EXPECT_TRUE(d4.is<double *>());
+  EXPECT_TRUE(i4null.is<int *>());
+  EXPECT_TRUE(f4null.is<float *>());
+  EXPECT_TRUE(l4null.is<long long *>());
+  EXPECT_TRUE(d4null.is<double *>());
+}
+
+TEST_F(PointerUnionTest, Get) {
+  EXPECT_EQ(a.get<float *>(), &f);
+  EXPECT_EQ(b.get<int *>(), &i);
+  EXPECT_EQ(n.get<int *>(), (int *)nullptr);
+}
+
+template<int I> struct alignas(8) Aligned {};
+
+typedef PointerUnion<Aligned<0> *, Aligned<1> *, Aligned<2> *, Aligned<3> *,
+                     Aligned<4> *, Aligned<5> *, Aligned<6> *, Aligned<7> *>
+    PU8;
+
+TEST_F(PointerUnionTest, ManyElements) {
+  Aligned<0> a0;
+  Aligned<7> a7;
+
+  PU8 a = &a0;
+  EXPECT_TRUE(a.is<Aligned<0>*>());
+  EXPECT_FALSE(a.is<Aligned<1>*>());
+  EXPECT_FALSE(a.is<Aligned<2>*>());
+  EXPECT_FALSE(a.is<Aligned<3>*>());
+  EXPECT_FALSE(a.is<Aligned<4>*>());
+  EXPECT_FALSE(a.is<Aligned<5>*>());
+  EXPECT_FALSE(a.is<Aligned<6>*>());
+  EXPECT_FALSE(a.is<Aligned<7>*>());
+  EXPECT_EQ(a.dyn_cast<Aligned<0>*>(), &a0);
+  EXPECT_EQ(*a.getAddrOfPtr1(), &a0);
+
+  a = &a7;
+  EXPECT_FALSE(a.is<Aligned<0>*>());
+  EXPECT_FALSE(a.is<Aligned<1>*>());
+  EXPECT_FALSE(a.is<Aligned<2>*>());
+  EXPECT_FALSE(a.is<Aligned<3>*>());
+  EXPECT_FALSE(a.is<Aligned<4>*>());
+  EXPECT_FALSE(a.is<Aligned<5>*>());
+  EXPECT_FALSE(a.is<Aligned<6>*>());
+  EXPECT_TRUE(a.is<Aligned<7>*>());
+  EXPECT_EQ(a.dyn_cast<Aligned<7>*>(), &a7);
+
+  EXPECT_TRUE(a == PU8(&a7));
+  EXPECT_TRUE(a != PU8(&a0));
+}
+
+TEST_F(PointerUnionTest, GetAddrOfPtr1) {
+  EXPECT_TRUE((void *)b.getAddrOfPtr1() == (void *)&b);
+  EXPECT_TRUE((void *)n.getAddrOfPtr1() == (void *)&n);
+}
+
+} // end anonymous namespace
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/STLForwardCompatTest.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/STLForwardCompatTest.cpp
new file mode 100644
index 0000000..333359e
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/STLForwardCompatTest.cpp
@@ -0,0 +1,78 @@
+//===- STLForwardCompatTest.cpp - Unit tests for STLForwardCompat ---------===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+
+#include "wpi/STLForwardCompat.h"
+#include "gtest/gtest.h"
+
+namespace {
+
+TEST(STLForwardCompatTest, NegationTest) {
+  EXPECT_TRUE((wpi::negation<std::false_type>::value));
+  EXPECT_FALSE((wpi::negation<std::true_type>::value));
+}
+
+struct incomplete_type;
+
+TEST(STLForwardCompatTest, ConjunctionTest) {
+  EXPECT_TRUE((wpi::conjunction<>::value));
+  EXPECT_FALSE((wpi::conjunction<std::false_type>::value));
+  EXPECT_TRUE((wpi::conjunction<std::true_type>::value));
+  EXPECT_FALSE((wpi::conjunction<std::false_type, incomplete_type>::value));
+  EXPECT_FALSE((wpi::conjunction<std::false_type, std::true_type>::value));
+  EXPECT_FALSE((wpi::conjunction<std::true_type, std::false_type>::value));
+  EXPECT_TRUE((wpi::conjunction<std::true_type, std::true_type>::value));
+  EXPECT_TRUE((wpi::conjunction<std::true_type, std::true_type,
+                                 std::true_type>::value));
+}
+
+TEST(STLForwardCompatTest, DisjunctionTest) {
+  EXPECT_FALSE((wpi::disjunction<>::value));
+  EXPECT_FALSE((wpi::disjunction<std::false_type>::value));
+  EXPECT_TRUE((wpi::disjunction<std::true_type>::value));
+  EXPECT_TRUE((wpi::disjunction<std::true_type, incomplete_type>::value));
+  EXPECT_TRUE((wpi::disjunction<std::false_type, std::true_type>::value));
+  EXPECT_TRUE((wpi::disjunction<std::true_type, std::false_type>::value));
+  EXPECT_TRUE((wpi::disjunction<std::true_type, std::true_type>::value));
+  EXPECT_TRUE((wpi::disjunction<std::true_type, std::true_type,
+                                 std::true_type>::value));
+}
+
+template <typename T>
+class STLForwardCompatRemoveCVRefTest : public ::testing::Test {};
+
+using STLForwardCompatRemoveCVRefTestTypes = ::testing::Types<
+    // clang-format off
+    std::pair<int, int>,
+    std::pair<int &, int>,
+    std::pair<const int, int>,
+    std::pair<volatile int, int>,
+    std::pair<const volatile int &, int>,
+    std::pair<int *, int *>,
+    std::pair<int *const, int *>,
+    std::pair<const int *, const int *>,
+    std::pair<int *&, int *>
+    // clang-format on
+    >;
+
+TYPED_TEST_SUITE(STLForwardCompatRemoveCVRefTest,
+                 STLForwardCompatRemoveCVRefTestTypes, );
+
+TYPED_TEST(STLForwardCompatRemoveCVRefTest, RemoveCVRef) {
+  using From = typename TypeParam::first_type;
+  using To = typename TypeParam::second_type;
+  EXPECT_TRUE(
+      (std::is_same<typename wpi::remove_cvref<From>::type, To>::value));
+}
+
+TYPED_TEST(STLForwardCompatRemoveCVRefTest, RemoveCVRefT) {
+  using From = typename TypeParam::first_type;
+  EXPECT_TRUE((std::is_same<typename wpi::remove_cvref<From>::type,
+                            wpi::remove_cvref_t<From>>::value));
+}
+
+} // namespace
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/SmallPtrSetTest.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/SmallPtrSetTest.cpp
new file mode 100644
index 0000000..1916d50
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/SmallPtrSetTest.cpp
@@ -0,0 +1,412 @@
+//===- llvm/unittest/ADT/SmallPtrSetTest.cpp ------------------------------===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+//
+// SmallPtrSet unit tests.
+//
+//===----------------------------------------------------------------------===//
+
+#include "wpi/SmallPtrSet.h"
+#include "wpi/PointerIntPair.h"
+#include "wpi/PointerLikeTypeTraits.h"
+#include "gtest/gtest.h"
+
+#include <algorithm>
+
+using namespace wpi;
+
+TEST(SmallPtrSetTest, Assignment) {
+  int buf[8];
+  for (int i = 0; i < 8; ++i)
+    buf[i] = 0;
+
+  SmallPtrSet<int *, 4> s1 = {&buf[0], &buf[1]};
+  SmallPtrSet<int *, 4> s2;
+  (s2 = s1).insert(&buf[2]);
+
+  // Self assign as well.
+  (s2 = static_cast<SmallPtrSet<int *, 4> &>(s2)).insert(&buf[3]);
+
+  s1 = s2;
+  EXPECT_EQ(4U, s1.size());
+  for (int i = 0; i < 8; ++i)
+    if (i < 4)
+      EXPECT_TRUE(s1.count(&buf[i]));
+    else
+      EXPECT_FALSE(s1.count(&buf[i]));
+
+  // Assign and insert with initializer lists, and ones that contain both
+  // duplicates and out-of-order elements.
+  (s2 = {&buf[6], &buf[7], &buf[6]}).insert({&buf[5], &buf[4]});
+  for (int i = 0; i < 8; ++i)
+    if (i < 4)
+      EXPECT_FALSE(s2.count(&buf[i]));
+    else
+      EXPECT_TRUE(s2.count(&buf[i]));
+}
+
+TEST(SmallPtrSetTest, GrowthTest) {
+  int i;
+  int buf[8];
+  for(i=0; i<8; ++i) buf[i]=0;
+
+
+  SmallPtrSet<int *, 4> s;
+  typedef SmallPtrSet<int *, 4>::iterator iter;
+
+  s.insert(&buf[0]);
+  s.insert(&buf[1]);
+  s.insert(&buf[2]);
+  s.insert(&buf[3]);
+  EXPECT_EQ(4U, s.size());
+
+  i = 0;
+  for(iter I=s.begin(), E=s.end(); I!=E; ++I, ++i)
+      (**I)++;
+  EXPECT_EQ(4, i);
+  for(i=0; i<8; ++i)
+      EXPECT_EQ(i<4?1:0,buf[i]);
+
+  s.insert(&buf[4]);
+  s.insert(&buf[5]);
+  s.insert(&buf[6]);
+  s.insert(&buf[7]);
+
+  i = 0;
+  for(iter I=s.begin(), E=s.end(); I!=E; ++I, ++i)
+      (**I)++;
+  EXPECT_EQ(8, i);
+  s.erase(&buf[4]);
+  s.erase(&buf[5]);
+  s.erase(&buf[6]);
+  s.erase(&buf[7]);
+  EXPECT_EQ(4U, s.size());
+
+  i = 0;
+  for(iter I=s.begin(), E=s.end(); I!=E; ++I, ++i)
+      (**I)++;
+  EXPECT_EQ(4, i);
+  for(i=0; i<8; ++i)
+      EXPECT_EQ(i<4?3:1,buf[i]);
+
+  s.clear();
+  for(i=0; i<8; ++i) buf[i]=0;
+  for(i=0; i<128; ++i) s.insert(&buf[i%8]); // test repeated entires
+  EXPECT_EQ(8U, s.size());
+  for(iter I=s.begin(), E=s.end(); I!=E; ++I, ++i)
+      (**I)++;
+  for(i=0; i<8; ++i)
+      EXPECT_EQ(1,buf[i]);
+}
+
+TEST(SmallPtrSetTest, CopyAndMoveTest) {
+  int buf[8];
+  for (int i = 0; i < 8; ++i)
+    buf[i] = 0;
+
+  SmallPtrSet<int *, 4> s1;
+  s1.insert(&buf[0]);
+  s1.insert(&buf[1]);
+  s1.insert(&buf[2]);
+  s1.insert(&buf[3]);
+  EXPECT_EQ(4U, s1.size());
+  for (int i = 0; i < 8; ++i)
+    if (i < 4)
+      EXPECT_TRUE(s1.count(&buf[i]));
+    else
+      EXPECT_FALSE(s1.count(&buf[i]));
+
+  SmallPtrSet<int *, 4> s2(s1);
+  EXPECT_EQ(4U, s2.size());
+  for (int i = 0; i < 8; ++i)
+    if (i < 4)
+      EXPECT_TRUE(s2.count(&buf[i]));
+    else
+      EXPECT_FALSE(s2.count(&buf[i]));
+
+  s1 = s2;
+  EXPECT_EQ(4U, s1.size());
+  EXPECT_EQ(4U, s2.size());
+  for (int i = 0; i < 8; ++i)
+    if (i < 4)
+      EXPECT_TRUE(s1.count(&buf[i]));
+    else
+      EXPECT_FALSE(s1.count(&buf[i]));
+
+  SmallPtrSet<int *, 4> s3(std::move(s1));
+  EXPECT_EQ(4U, s3.size());
+  EXPECT_TRUE(s1.empty());
+  for (int i = 0; i < 8; ++i)
+    if (i < 4)
+      EXPECT_TRUE(s3.count(&buf[i]));
+    else
+      EXPECT_FALSE(s3.count(&buf[i]));
+
+  // Move assign into the moved-from object. Also test move of a non-small
+  // container.
+  s3.insert(&buf[4]);
+  s3.insert(&buf[5]);
+  s3.insert(&buf[6]);
+  s3.insert(&buf[7]);
+  s1 = std::move(s3);
+  EXPECT_EQ(8U, s1.size());
+  EXPECT_TRUE(s3.empty());
+  for (int i = 0; i < 8; ++i)
+    EXPECT_TRUE(s1.count(&buf[i]));
+
+  // Copy assign into a moved-from object.
+  s3 = s1;
+  EXPECT_EQ(8U, s3.size());
+  EXPECT_EQ(8U, s1.size());
+  for (int i = 0; i < 8; ++i)
+    EXPECT_TRUE(s3.count(&buf[i]));
+}
+
+TEST(SmallPtrSetTest, SwapTest) {
+  int buf[10];
+
+  SmallPtrSet<int *, 2> a;
+  SmallPtrSet<int *, 2> b;
+
+  a.insert(&buf[0]);
+  a.insert(&buf[1]);
+  b.insert(&buf[2]);
+
+  EXPECT_EQ(2U, a.size());
+  EXPECT_EQ(1U, b.size());
+  EXPECT_TRUE(a.count(&buf[0]));
+  EXPECT_TRUE(a.count(&buf[1]));
+  EXPECT_FALSE(a.count(&buf[2]));
+  EXPECT_FALSE(a.count(&buf[3]));
+  EXPECT_FALSE(b.count(&buf[0]));
+  EXPECT_FALSE(b.count(&buf[1]));
+  EXPECT_TRUE(b.count(&buf[2]));
+  EXPECT_FALSE(b.count(&buf[3]));
+
+  std::swap(a, b);
+
+  EXPECT_EQ(1U, a.size());
+  EXPECT_EQ(2U, b.size());
+  EXPECT_FALSE(a.count(&buf[0]));
+  EXPECT_FALSE(a.count(&buf[1]));
+  EXPECT_TRUE(a.count(&buf[2]));
+  EXPECT_FALSE(a.count(&buf[3]));
+  EXPECT_TRUE(b.count(&buf[0]));
+  EXPECT_TRUE(b.count(&buf[1]));
+  EXPECT_FALSE(b.count(&buf[2]));
+  EXPECT_FALSE(b.count(&buf[3]));
+
+  b.insert(&buf[3]);
+  std::swap(a, b);
+
+  EXPECT_EQ(3U, a.size());
+  EXPECT_EQ(1U, b.size());
+  EXPECT_TRUE(a.count(&buf[0]));
+  EXPECT_TRUE(a.count(&buf[1]));
+  EXPECT_FALSE(a.count(&buf[2]));
+  EXPECT_TRUE(a.count(&buf[3]));
+  EXPECT_FALSE(b.count(&buf[0]));
+  EXPECT_FALSE(b.count(&buf[1]));
+  EXPECT_TRUE(b.count(&buf[2]));
+  EXPECT_FALSE(b.count(&buf[3]));
+
+  std::swap(a, b);
+
+  EXPECT_EQ(1U, a.size());
+  EXPECT_EQ(3U, b.size());
+  EXPECT_FALSE(a.count(&buf[0]));
+  EXPECT_FALSE(a.count(&buf[1]));
+  EXPECT_TRUE(a.count(&buf[2]));
+  EXPECT_FALSE(a.count(&buf[3]));
+  EXPECT_TRUE(b.count(&buf[0]));
+  EXPECT_TRUE(b.count(&buf[1]));
+  EXPECT_FALSE(b.count(&buf[2]));
+  EXPECT_TRUE(b.count(&buf[3]));
+
+  a.insert(&buf[4]);
+  a.insert(&buf[5]);
+  a.insert(&buf[6]);
+
+  std::swap(b, a);
+
+  EXPECT_EQ(3U, a.size());
+  EXPECT_EQ(4U, b.size());
+  EXPECT_TRUE(b.count(&buf[2]));
+  EXPECT_TRUE(b.count(&buf[4]));
+  EXPECT_TRUE(b.count(&buf[5]));
+  EXPECT_TRUE(b.count(&buf[6]));
+  EXPECT_TRUE(a.count(&buf[0]));
+  EXPECT_TRUE(a.count(&buf[1]));
+  EXPECT_TRUE(a.count(&buf[3]));
+}
+
+void checkEraseAndIterators(SmallPtrSetImpl<int*> &S) {
+  int buf[3];
+
+  S.insert(&buf[0]);
+  S.insert(&buf[1]);
+  S.insert(&buf[2]);
+
+  // Iterators must still be valid after erase() calls;
+  auto B = S.begin();
+  auto M = std::next(B);
+  auto E = S.end();
+  EXPECT_TRUE(*B == &buf[0] || *B == &buf[1] || *B == &buf[2]);
+  EXPECT_TRUE(*M == &buf[0] || *M == &buf[1] || *M == &buf[2]);
+  EXPECT_TRUE(*B != *M);
+  int *Removable = *std::next(M);
+  // No iterator points to Removable now.
+  EXPECT_TRUE(Removable == &buf[0] || Removable == &buf[1] ||
+              Removable == &buf[2]);
+  EXPECT_TRUE(Removable != *B && Removable != *M);
+
+  S.erase(Removable);
+
+  // B,M,E iterators should still be valid
+  EXPECT_EQ(B, S.begin());
+  EXPECT_EQ(M, std::next(B));
+  EXPECT_EQ(E, S.end());
+  EXPECT_EQ(std::next(M), E);
+}
+
+TEST(SmallPtrSetTest, EraseTest) {
+  // Test when set stays small.
+  SmallPtrSet<int *, 8> B;
+  checkEraseAndIterators(B);
+
+  // Test when set grows big.
+  SmallPtrSet<int *, 2> A;
+  checkEraseAndIterators(A);
+}
+
+// Verify that dereferencing and iteration work.
+TEST(SmallPtrSetTest, dereferenceAndIterate) {
+  int Ints[] = {0, 1, 2, 3, 4, 5, 6, 7};
+  SmallPtrSet<const int *, 4> S;
+  for (int &I : Ints) {
+    EXPECT_EQ(&I, *S.insert(&I).first);
+    EXPECT_EQ(&I, *S.find(&I));
+  }
+
+  // Iterate from each and count how many times each element is found.
+  int Found[sizeof(Ints)/sizeof(int)] = {0};
+  for (int &I : Ints)
+    for (auto F = S.find(&I), E = S.end(); F != E; ++F)
+      ++Found[*F - Ints];
+
+  // Sort.  We should hit the first element just once and the final element N
+  // times.
+  std::sort(std::begin(Found), std::end(Found));
+  for (auto F = std::begin(Found), E = std::end(Found); F != E; ++F)
+    EXPECT_EQ(F - Found + 1, *F);
+}
+
+// Verify that const pointers work for count and find even when the underlying
+// SmallPtrSet is not for a const pointer type.
+TEST(SmallPtrSetTest, ConstTest) {
+  SmallPtrSet<int *, 8> IntSet;
+  int A;
+  int *B = &A;
+  const int *C = &A;
+  IntSet.insert(B);
+  EXPECT_EQ(IntSet.count(B), 1u);
+  EXPECT_EQ(IntSet.count(C), 1u);
+  EXPECT_TRUE(IntSet.contains(B));
+  EXPECT_TRUE(IntSet.contains(C));
+}
+
+// Verify that we automatically get the const version of PointerLikeTypeTraits
+// filled in for us, even for a non-pointer type
+using TestPair = PointerIntPair<int *, 1>;
+
+TEST(SmallPtrSetTest, ConstNonPtrTest) {
+  SmallPtrSet<TestPair, 8> IntSet;
+  int A[1];
+  TestPair Pair(&A[0], 1);
+  IntSet.insert(Pair);
+  EXPECT_EQ(IntSet.count(Pair), 1u);
+  EXPECT_TRUE(IntSet.contains(Pair));
+}
+
+// Test equality comparison.
+TEST(SmallPtrSetTest, EqualityComparison) {
+  int buf[3];
+  for (int i = 0; i < 3; ++i)
+    buf[i] = 0;
+
+  SmallPtrSet<int *, 1> a;
+  a.insert(&buf[0]);
+  a.insert(&buf[1]);
+
+  SmallPtrSet<int *, 2> b;
+  b.insert(&buf[1]);
+  b.insert(&buf[0]);
+
+  SmallPtrSet<int *, 3> c;
+  c.insert(&buf[1]);
+  c.insert(&buf[2]);
+
+  SmallPtrSet<int *, 4> d;
+  d.insert(&buf[0]);
+
+  SmallPtrSet<int *, 5> e;
+  e.insert(&buf[0]);
+  e.insert(&buf[1]);
+  e.insert(&buf[2]);
+
+  EXPECT_EQ(a, b);
+  EXPECT_EQ(b, a);
+  EXPECT_NE(b, c);
+  EXPECT_NE(c, a);
+  EXPECT_NE(d, a);
+  EXPECT_NE(a, d);
+  EXPECT_NE(a, e);
+  EXPECT_NE(e, a);
+  EXPECT_NE(c, e);
+  EXPECT_NE(e, d);
+}
+
+TEST(SmallPtrSetTest, Contains) {
+  SmallPtrSet<int *, 2> Set;
+  int buf[4] = {0, 11, 22, 11};
+  EXPECT_FALSE(Set.contains(&buf[0]));
+  EXPECT_FALSE(Set.contains(&buf[1]));
+
+  Set.insert(&buf[0]);
+  Set.insert(&buf[1]);
+  EXPECT_TRUE(Set.contains(&buf[0]));
+  EXPECT_TRUE(Set.contains(&buf[1]));
+  EXPECT_FALSE(Set.contains(&buf[3]));
+
+  Set.insert(&buf[1]);
+  EXPECT_TRUE(Set.contains(&buf[0]));
+  EXPECT_TRUE(Set.contains(&buf[1]));
+  EXPECT_FALSE(Set.contains(&buf[3]));
+
+  Set.erase(&buf[1]);
+  EXPECT_TRUE(Set.contains(&buf[0]));
+  EXPECT_FALSE(Set.contains(&buf[1]));
+
+  Set.insert(&buf[1]);
+  Set.insert(&buf[2]);
+  EXPECT_TRUE(Set.contains(&buf[0]));
+  EXPECT_TRUE(Set.contains(&buf[1]));
+  EXPECT_TRUE(Set.contains(&buf[2]));
+}
+
+TEST(SmallPtrSetTest, InsertIterator) {
+  SmallPtrSet<int *, 5> Set;
+  int Vals[5] = {11, 22, 33, 44, 55};
+  int *Buf[5] = {&Vals[0], &Vals[1], &Vals[2], &Vals[3], &Vals[4]};
+
+  for (int *Ptr : Buf)
+    Set.insert(Set.begin(), Ptr);
+
+  // Ensure that all of the values were copied into the set.
+  for (const auto *Ptr : Buf)
+    EXPECT_TRUE(Set.contains(Ptr));
+}
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/SmallSetTest.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/SmallSetTest.cpp
new file mode 100644
index 0000000..e245aa4
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/SmallSetTest.cpp
@@ -0,0 +1,194 @@
+//===- llvm/unittest/ADT/SmallSetTest.cpp ------------------------------===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+//
+// SmallSet unit tests.
+//
+//===----------------------------------------------------------------------===//
+
+#include "wpi/SmallSet.h"
+#include "gtest/gtest.h"
+#include <string>
+
+using namespace wpi;
+
+TEST(SmallSetTest, Insert) {
+
+  SmallSet<int, 4> s1;
+
+  for (int i = 0; i < 4; i++)
+    s1.insert(i);
+
+  for (int i = 0; i < 4; i++)
+    s1.insert(i);
+
+  EXPECT_EQ(4u, s1.size());
+
+  for (int i = 0; i < 4; i++)
+    EXPECT_EQ(1u, s1.count(i));
+
+  EXPECT_EQ(0u, s1.count(4));
+}
+
+TEST(SmallSetTest, Grow) {
+  SmallSet<int, 4> s1;
+
+  for (int i = 0; i < 8; i++)
+    s1.insert(i);
+
+  EXPECT_EQ(8u, s1.size());
+
+  for (int i = 0; i < 8; i++)
+    EXPECT_EQ(1u, s1.count(i));
+
+  EXPECT_EQ(0u, s1.count(8));
+}
+
+TEST(SmallSetTest, Erase) {
+  SmallSet<int, 4> s1;
+
+  for (int i = 0; i < 8; i++)
+    s1.insert(i);
+
+  EXPECT_EQ(8u, s1.size());
+
+  // Remove elements one by one and check if all other elements are still there.
+  for (int i = 0; i < 8; i++) {
+    EXPECT_EQ(1u, s1.count(i));
+    EXPECT_TRUE(s1.erase(i));
+    EXPECT_EQ(0u, s1.count(i));
+    EXPECT_EQ(8u - i - 1, s1.size());
+    for (int j = i + 1; j < 8; j++)
+      EXPECT_EQ(1u, s1.count(j));
+  }
+
+  EXPECT_EQ(0u, s1.count(8));
+}
+
+TEST(SmallSetTest, IteratorInt) {
+  SmallSet<int, 4> s1;
+
+  // Test the 'small' case.
+  for (int i = 0; i < 3; i++)
+    s1.insert(i);
+
+  std::vector<int> V(s1.begin(), s1.end());
+  // Make sure the elements are in the expected order.
+  std::sort(V.begin(), V.end());
+  for (int i = 0; i < 3; i++)
+    EXPECT_EQ(i, V[i]);
+
+  // Test the 'big' case by adding a few more elements to switch to std::set
+  // internally.
+  for (int i = 3; i < 6; i++)
+    s1.insert(i);
+
+  V.assign(s1.begin(), s1.end());
+  // Make sure the elements are in the expected order.
+  std::sort(V.begin(), V.end());
+  for (int i = 0; i < 6; i++)
+    EXPECT_EQ(i, V[i]);
+}
+
+TEST(SmallSetTest, IteratorString) {
+  // Test SmallSetIterator for SmallSet with a type with non-trivial
+  // ctors/dtors.
+  SmallSet<std::string, 2> s1;
+
+  s1.insert("str 1");
+  s1.insert("str 2");
+  s1.insert("str 1");
+
+  std::vector<std::string> V(s1.begin(), s1.end());
+  std::sort(V.begin(), V.end());
+  EXPECT_EQ(2u, s1.size());
+  EXPECT_EQ("str 1", V[0]);
+  EXPECT_EQ("str 2", V[1]);
+
+  s1.insert("str 4");
+  s1.insert("str 0");
+  s1.insert("str 4");
+
+  V.assign(s1.begin(), s1.end());
+  // Make sure the elements are in the expected order.
+  std::sort(V.begin(), V.end());
+  EXPECT_EQ(4u, s1.size());
+  EXPECT_EQ("str 0", V[0]);
+  EXPECT_EQ("str 1", V[1]);
+  EXPECT_EQ("str 2", V[2]);
+  EXPECT_EQ("str 4", V[3]);
+}
+
+TEST(SmallSetTest, IteratorIncMoveCopy) {
+  // Test SmallSetIterator for SmallSet with a type with non-trivial
+  // ctors/dtors.
+  SmallSet<std::string, 2> s1;
+
+  s1.insert("str 1");
+  s1.insert("str 2");
+
+  auto Iter = s1.begin();
+  EXPECT_EQ("str 1", *Iter);
+  ++Iter;
+  EXPECT_EQ("str 2", *Iter);
+
+  s1.insert("str 4");
+  s1.insert("str 0");
+  auto Iter2 = s1.begin();
+  Iter = std::move(Iter2);
+  EXPECT_EQ("str 0", *Iter);
+}
+
+TEST(SmallSetTest, EqualityComparisonTest) {
+  SmallSet<int, 8> s1small;
+  SmallSet<int, 10> s2small;
+  SmallSet<int, 3> s3large;
+  SmallSet<int, 8> s4large;
+
+  for (int i = 1; i < 5; i++) {
+    s1small.insert(i);
+    s2small.insert(5 - i);
+    s3large.insert(i);
+  }
+  for (int i = 1; i < 11; i++)
+    s4large.insert(i);
+
+  EXPECT_EQ(s1small, s1small);
+  EXPECT_EQ(s3large, s3large);
+
+  EXPECT_EQ(s1small, s2small);
+  EXPECT_EQ(s1small, s3large);
+  EXPECT_EQ(s2small, s3large);
+
+  EXPECT_NE(s1small, s4large);
+  EXPECT_NE(s4large, s3large);
+}
+
+TEST(SmallSetTest, Contains) {
+  SmallSet<int, 2> Set;
+  EXPECT_FALSE(Set.contains(0));
+  EXPECT_FALSE(Set.contains(1));
+
+  Set.insert(0);
+  Set.insert(1);
+  EXPECT_TRUE(Set.contains(0));
+  EXPECT_TRUE(Set.contains(1));
+
+  Set.insert(1);
+  EXPECT_TRUE(Set.contains(0));
+  EXPECT_TRUE(Set.contains(1));
+
+  Set.erase(1);
+  EXPECT_TRUE(Set.contains(0));
+  EXPECT_FALSE(Set.contains(1));
+
+  Set.insert(1);
+  Set.insert(2);
+  EXPECT_TRUE(Set.contains(0));
+  EXPECT_TRUE(Set.contains(1));
+  EXPECT_TRUE(Set.contains(2));
+}
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/SmallStringTest.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/SmallStringTest.cpp
new file mode 100644
index 0000000..afb155a
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/SmallStringTest.cpp
@@ -0,0 +1,166 @@
+//===- llvm/unittest/ADT/SmallStringTest.cpp ------------------------------===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+//
+// SmallString unit tests.
+//
+//===----------------------------------------------------------------------===//
+
+#include "wpi/SmallString.h"
+#include "gtest/gtest.h"
+#include <climits>
+#include <cstring>
+#include <stdarg.h>
+
+using namespace wpi;
+
+namespace {
+
+// Test fixture class
+class SmallStringTest : public testing::Test {
+protected:
+  typedef SmallString<40> StringType;
+
+  StringType theString;
+
+  void assertEmpty(StringType & v) {
+    // Size tests
+    EXPECT_EQ(0u, v.size());
+    EXPECT_TRUE(v.empty());
+    // Iterator tests
+    EXPECT_TRUE(v.begin() == v.end());
+  }
+};
+
+// New string test.
+TEST_F(SmallStringTest, EmptyStringTest) {
+  SCOPED_TRACE("EmptyStringTest");
+  assertEmpty(theString);
+  EXPECT_TRUE(theString.rbegin() == theString.rend());
+}
+
+TEST_F(SmallStringTest, AssignRepeated) {
+  theString.assign(3, 'a');
+  EXPECT_EQ(3u, theString.size());
+  EXPECT_STREQ("aaa", theString.c_str());
+}
+
+TEST_F(SmallStringTest, AssignIterPair) {
+  std::string_view abc = "abc";
+  theString.assign(abc.begin(), abc.end());
+  EXPECT_EQ(3u, theString.size());
+  EXPECT_STREQ("abc", theString.c_str());
+}
+
+TEST_F(SmallStringTest, AssignStringView) {
+  std::string_view abc = "abc";
+  theString.assign(abc);
+  EXPECT_EQ(3u, theString.size());
+  EXPECT_STREQ("abc", theString.c_str());
+}
+
+TEST_F(SmallStringTest, AssignSmallVector) {
+  std::string_view abc = "abc";
+  SmallVector<char, 10> abcVec(abc.begin(), abc.end());
+  theString.assign(abcVec);
+  EXPECT_EQ(3u, theString.size());
+  EXPECT_STREQ("abc", theString.c_str());
+}
+
+TEST_F(SmallStringTest, AssignStringViews) {
+  theString.assign({"abc", "def", "ghi"});
+  EXPECT_EQ(9u, theString.size());
+  EXPECT_STREQ("abcdefghi", theString.c_str());
+}
+
+TEST_F(SmallStringTest, AppendIterPair) {
+  std::string_view abc = "abc";
+  theString.append(abc.begin(), abc.end());
+  theString.append(abc.begin(), abc.end());
+  EXPECT_EQ(6u, theString.size());
+  EXPECT_STREQ("abcabc", theString.c_str());
+}
+
+TEST_F(SmallStringTest, AppendStringView) {
+  std::string_view abc = "abc";
+  theString.append(abc);
+  theString.append(abc);
+  EXPECT_EQ(6u, theString.size());
+  EXPECT_STREQ("abcabc", theString.c_str());
+}
+
+TEST_F(SmallStringTest, AppendSmallVector) {
+  std::string_view abc = "abc";
+  SmallVector<char, 10> abcVec(abc.begin(), abc.end());
+  theString.append(abcVec);
+  theString.append(abcVec);
+  EXPECT_EQ(6u, theString.size());
+  EXPECT_STREQ("abcabc", theString.c_str());
+}
+
+TEST_F(SmallStringTest, AppendStringViews) {
+  theString.append({"abc", "def", "ghi"});
+  EXPECT_EQ(9u, theString.size());
+  EXPECT_STREQ("abcdefghi", theString.c_str());
+  std::string_view Jkl = "jkl";
+  std::string Mno = "mno";
+  SmallString<4> Pqr("pqr");
+  const char *Stu = "stu";
+  theString.append({Jkl, Mno, Pqr, Stu});
+  EXPECT_EQ(21u, theString.size());
+  EXPECT_STREQ("abcdefghijklmnopqrstu", theString.c_str());
+}
+
+TEST_F(SmallStringTest, StringViewConversion) {
+  std::string_view abc = "abc";
+  theString.assign(abc.begin(), abc.end());
+  std::string_view theStringView = theString;
+  EXPECT_EQ("abc", theStringView);
+}
+
+TEST_F(SmallStringTest, StdStringConversion) {
+  std::string_view abc = "abc";
+  theString.assign(abc.begin(), abc.end());
+  std::string theStdString = std::string(theString);
+  EXPECT_EQ("abc", theStdString);
+}
+
+TEST_F(SmallStringTest, Find) {
+  theString = "hello";
+  EXPECT_EQ(2U, theString.find('l'));
+  EXPECT_EQ(std::string_view::npos, theString.find('z'));
+  EXPECT_EQ(std::string_view::npos, theString.find("helloworld"));
+  EXPECT_EQ(0U, theString.find("hello"));
+  EXPECT_EQ(1U, theString.find("ello"));
+  EXPECT_EQ(std::string_view::npos, theString.find("zz"));
+  EXPECT_EQ(2U, theString.find("ll", 2));
+  EXPECT_EQ(std::string_view::npos, theString.find("ll", 3));
+  EXPECT_EQ(0U, theString.find(""));
+
+  EXPECT_EQ(3U, theString.rfind('l'));
+  EXPECT_EQ(std::string_view::npos, theString.rfind('z'));
+  EXPECT_EQ(std::string_view::npos, theString.rfind("helloworld"));
+  EXPECT_EQ(0U, theString.rfind("hello"));
+  EXPECT_EQ(1U, theString.rfind("ello"));
+  EXPECT_EQ(std::string_view::npos, theString.rfind("zz"));
+
+  EXPECT_EQ(2U, theString.find_first_of('l'));
+  EXPECT_EQ(1U, theString.find_first_of("el"));
+  EXPECT_EQ(std::string_view::npos, theString.find_first_of("xyz"));
+
+  EXPECT_EQ(1U, theString.find_first_not_of('h'));
+  EXPECT_EQ(4U, theString.find_first_not_of("hel"));
+  EXPECT_EQ(std::string_view::npos, theString.find_first_not_of("hello"));
+
+  theString = "hellx xello hell ello world foo bar hello";
+  EXPECT_EQ(36U, theString.find("hello"));
+  EXPECT_EQ(28U, theString.find("foo"));
+  EXPECT_EQ(12U, theString.find("hell", 2));
+  EXPECT_EQ(0U, theString.find(""));
+}
+
+} // namespace
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/SmallVectorTest.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/SmallVectorTest.cpp
new file mode 100644
index 0000000..a60e683
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/SmallVectorTest.cpp
@@ -0,0 +1,1425 @@
+//===- llvm/unittest/ADT/SmallVectorTest.cpp ------------------------------===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+//
+// SmallVector unit tests.
+//
+//===----------------------------------------------------------------------===//
+
+#include "wpi/SmallVector.h"
+#include <span>
+#include "wpi/Compiler.h"
+#include "gtest/gtest.h"
+#include <list>
+#include <stdarg.h>
+
+#if defined(__GNUC__)
+#pragma GCC diagnostic ignored "-Wpedantic"
+#endif
+
+using namespace wpi;
+
+namespace {
+
+/// A helper class that counts the total number of constructor and
+/// destructor calls.
+class Constructable {
+private:
+  static int numConstructorCalls;
+  static int numMoveConstructorCalls;
+  static int numCopyConstructorCalls;
+  static int numDestructorCalls;
+  static int numAssignmentCalls;
+  static int numMoveAssignmentCalls;
+  static int numCopyAssignmentCalls;
+
+  bool constructed;
+  int value;
+
+public:
+  Constructable() : constructed(true), value(0) {
+    ++numConstructorCalls;
+  }
+
+  Constructable(int val) : constructed(true), value(val) {
+    ++numConstructorCalls;
+  }
+
+  Constructable(const Constructable & src) : constructed(true) {
+    value = src.value;
+    ++numConstructorCalls;
+    ++numCopyConstructorCalls;
+  }
+
+  Constructable(Constructable && src) : constructed(true) {
+    value = src.value;
+    src.value = 0;
+    ++numConstructorCalls;
+    ++numMoveConstructorCalls;
+  }
+
+  ~Constructable() {
+    EXPECT_TRUE(constructed);
+    ++numDestructorCalls;
+    constructed = false;
+  }
+
+  Constructable & operator=(const Constructable & src) {
+    EXPECT_TRUE(constructed);
+    value = src.value;
+    ++numAssignmentCalls;
+    ++numCopyAssignmentCalls;
+    return *this;
+  }
+
+  Constructable & operator=(Constructable && src) {
+    EXPECT_TRUE(constructed);
+    value = src.value;
+    src.value = 0;
+    ++numAssignmentCalls;
+    ++numMoveAssignmentCalls;
+    return *this;
+  }
+
+  int getValue() const {
+    return abs(value);
+  }
+
+  static void reset() {
+    numConstructorCalls = 0;
+    numMoveConstructorCalls = 0;
+    numCopyConstructorCalls = 0;
+    numDestructorCalls = 0;
+    numAssignmentCalls = 0;
+    numMoveAssignmentCalls = 0;
+    numCopyAssignmentCalls = 0;
+  }
+
+  static int getNumConstructorCalls() {
+    return numConstructorCalls;
+  }
+
+  static int getNumMoveConstructorCalls() {
+    return numMoveConstructorCalls;
+  }
+
+  static int getNumCopyConstructorCalls() {
+    return numCopyConstructorCalls;
+  }
+
+  static int getNumDestructorCalls() {
+    return numDestructorCalls;
+  }
+
+  static int getNumAssignmentCalls() {
+    return numAssignmentCalls;
+  }
+
+  static int getNumMoveAssignmentCalls() {
+    return numMoveAssignmentCalls;
+  }
+
+  static int getNumCopyAssignmentCalls() {
+    return numCopyAssignmentCalls;
+  }
+
+  friend bool operator==(const Constructable & c0, const Constructable & c1) {
+    return c0.getValue() == c1.getValue();
+  }
+
+  friend bool LLVM_ATTRIBUTE_UNUSED
+  operator!=(const Constructable & c0, const Constructable & c1) {
+    return c0.getValue() != c1.getValue();
+  }
+};
+
+int Constructable::numConstructorCalls;
+int Constructable::numCopyConstructorCalls;
+int Constructable::numMoveConstructorCalls;
+int Constructable::numDestructorCalls;
+int Constructable::numAssignmentCalls;
+int Constructable::numCopyAssignmentCalls;
+int Constructable::numMoveAssignmentCalls;
+
+struct NonCopyable {
+  NonCopyable() {}
+  NonCopyable(NonCopyable &&) {}
+  NonCopyable &operator=(NonCopyable &&) { return *this; }
+private:
+  NonCopyable(const NonCopyable &) = delete;
+  NonCopyable &operator=(const NonCopyable &) = delete;
+};
+
+LLVM_ATTRIBUTE_USED void CompileTest() {
+  SmallVector<NonCopyable, 0> V;
+  V.resize(42);
+}
+
+class SmallVectorTestBase : public testing::Test {
+protected:
+  void SetUp() override { Constructable::reset(); }
+
+  template <typename VectorT>
+  void assertEmpty(VectorT & v) {
+    // Size tests
+    EXPECT_EQ(0u, v.size());
+    EXPECT_TRUE(v.empty());
+
+    // Iterator tests
+    EXPECT_TRUE(v.begin() == v.end());
+  }
+
+  // Assert that v contains the specified values, in order.
+  template <typename VectorT>
+  void assertValuesInOrder(VectorT & v, size_t size, ...) {
+    EXPECT_EQ(size, v.size());
+
+    va_list ap;
+    va_start(ap, size);
+    for (size_t i = 0; i < size; ++i) {
+      int value = va_arg(ap, int);
+      EXPECT_EQ(value, v[i].getValue());
+    }
+
+    va_end(ap);
+  }
+
+  // Generate a sequence of values to initialize the vector.
+  template <typename VectorT>
+  void makeSequence(VectorT & v, int start, int end) {
+    for (int i = start; i <= end; ++i) {
+      v.push_back(Constructable(i));
+    }
+  }
+};
+
+// Test fixture class
+template <typename VectorT>
+class SmallVectorTest : public SmallVectorTestBase {
+protected:
+  VectorT theVector;
+  VectorT otherVector;
+};
+
+
+typedef ::testing::Types<SmallVector<Constructable, 0>,
+                         SmallVector<Constructable, 1>,
+                         SmallVector<Constructable, 2>,
+                         SmallVector<Constructable, 4>,
+                         SmallVector<Constructable, 5>
+                         > SmallVectorTestTypes;
+TYPED_TEST_SUITE(SmallVectorTest, SmallVectorTestTypes, );
+
+// Constructor test.
+TYPED_TEST(SmallVectorTest, ConstructorNonIterTest) {
+  SCOPED_TRACE("ConstructorTest");
+  this->theVector = SmallVector<Constructable, 2>(2, 2);
+  this->assertValuesInOrder(this->theVector, 2u, 2, 2);
+}
+
+// Constructor test.
+TYPED_TEST(SmallVectorTest, ConstructorIterTest) {
+  SCOPED_TRACE("ConstructorTest");
+  int arr[] = {1, 2, 3};
+  this->theVector =
+      SmallVector<Constructable, 4>(std::begin(arr), std::end(arr));
+  this->assertValuesInOrder(this->theVector, 3u, 1, 2, 3);
+}
+
+// New vector test.
+TYPED_TEST(SmallVectorTest, EmptyVectorTest) {
+  SCOPED_TRACE("EmptyVectorTest");
+  this->assertEmpty(this->theVector);
+  EXPECT_TRUE(this->theVector.rbegin() == this->theVector.rend());
+  EXPECT_EQ(0, Constructable::getNumConstructorCalls());
+  EXPECT_EQ(0, Constructable::getNumDestructorCalls());
+}
+
+// Simple insertions and deletions.
+TYPED_TEST(SmallVectorTest, PushPopTest) {
+  SCOPED_TRACE("PushPopTest");
+
+  // Track whether the vector will potentially have to grow.
+  bool RequiresGrowth = this->theVector.capacity() < 3;
+
+  // Push an element
+  this->theVector.push_back(Constructable(1));
+
+  // Size tests
+  this->assertValuesInOrder(this->theVector, 1u, 1);
+  EXPECT_FALSE(this->theVector.begin() == this->theVector.end());
+  EXPECT_FALSE(this->theVector.empty());
+
+  // Push another element
+  this->theVector.push_back(Constructable(2));
+  this->assertValuesInOrder(this->theVector, 2u, 1, 2);
+
+  // Insert at beginning. Reserve space to avoid reference invalidation from
+  // this->theVector[1].
+  this->theVector.reserve(this->theVector.size() + 1);
+  this->theVector.insert(this->theVector.begin(), this->theVector[1]);
+  this->assertValuesInOrder(this->theVector, 3u, 2, 1, 2);
+
+  // Pop one element
+  this->theVector.pop_back();
+  this->assertValuesInOrder(this->theVector, 2u, 2, 1);
+
+  // Pop remaining elements
+  this->theVector.pop_back_n(2);
+  this->assertEmpty(this->theVector);
+
+  // Check number of constructor calls. Should be 2 for each list element,
+  // one for the argument to push_back, one for the argument to insert,
+  // and one for the list element itself.
+  if (!RequiresGrowth) {
+    EXPECT_EQ(5, Constructable::getNumConstructorCalls());
+    EXPECT_EQ(5, Constructable::getNumDestructorCalls());
+  } else {
+    // If we had to grow the vector, these only have a lower bound, but should
+    // always be equal.
+    EXPECT_LE(5, Constructable::getNumConstructorCalls());
+    EXPECT_EQ(Constructable::getNumConstructorCalls(),
+              Constructable::getNumDestructorCalls());
+  }
+}
+
+// Clear test.
+TYPED_TEST(SmallVectorTest, ClearTest) {
+  SCOPED_TRACE("ClearTest");
+
+  this->theVector.reserve(2);
+  this->makeSequence(this->theVector, 1, 2);
+  this->theVector.clear();
+
+  this->assertEmpty(this->theVector);
+  EXPECT_EQ(4, Constructable::getNumConstructorCalls());
+  EXPECT_EQ(4, Constructable::getNumDestructorCalls());
+}
+
+// Resize smaller test.
+TYPED_TEST(SmallVectorTest, ResizeShrinkTest) {
+  SCOPED_TRACE("ResizeShrinkTest");
+
+  this->theVector.reserve(3);
+  this->makeSequence(this->theVector, 1, 3);
+  this->theVector.resize(1);
+
+  this->assertValuesInOrder(this->theVector, 1u, 1);
+  EXPECT_EQ(6, Constructable::getNumConstructorCalls());
+  EXPECT_EQ(5, Constructable::getNumDestructorCalls());
+}
+
+// Truncate test.
+TYPED_TEST(SmallVectorTest, TruncateTest) {
+  SCOPED_TRACE("TruncateTest");
+
+  this->theVector.reserve(3);
+  this->makeSequence(this->theVector, 1, 3);
+  this->theVector.truncate(1);
+
+  this->assertValuesInOrder(this->theVector, 1u, 1);
+  EXPECT_EQ(6, Constructable::getNumConstructorCalls());
+  EXPECT_EQ(5, Constructable::getNumDestructorCalls());
+
+#if !defined(NDEBUG) && GTEST_HAS_DEATH_TEST
+  EXPECT_DEATH(this->theVector.truncate(2), "Cannot increase size");
+#endif
+  this->theVector.truncate(1);
+  this->assertValuesInOrder(this->theVector, 1u, 1);
+  EXPECT_EQ(6, Constructable::getNumConstructorCalls());
+  EXPECT_EQ(5, Constructable::getNumDestructorCalls());
+
+  this->theVector.truncate(0);
+  this->assertEmpty(this->theVector);
+  EXPECT_EQ(6, Constructable::getNumConstructorCalls());
+  EXPECT_EQ(6, Constructable::getNumDestructorCalls());
+}
+
+// Resize bigger test.
+TYPED_TEST(SmallVectorTest, ResizeGrowTest) {
+  SCOPED_TRACE("ResizeGrowTest");
+
+  this->theVector.resize(2);
+
+  EXPECT_EQ(2, Constructable::getNumConstructorCalls());
+  EXPECT_EQ(0, Constructable::getNumDestructorCalls());
+  EXPECT_EQ(2u, this->theVector.size());
+}
+
+TYPED_TEST(SmallVectorTest, ResizeWithElementsTest) {
+  this->theVector.resize(2);
+
+  Constructable::reset();
+
+  this->theVector.resize(4);
+
+  size_t Ctors = Constructable::getNumConstructorCalls();
+  EXPECT_TRUE(Ctors == 2 || Ctors == 4);
+  size_t MoveCtors = Constructable::getNumMoveConstructorCalls();
+  EXPECT_TRUE(MoveCtors == 0 || MoveCtors == 2);
+  size_t Dtors = Constructable::getNumDestructorCalls();
+  EXPECT_TRUE(Dtors == 0 || Dtors == 2);
+}
+
+// Resize with fill value.
+TYPED_TEST(SmallVectorTest, ResizeFillTest) {
+  SCOPED_TRACE("ResizeFillTest");
+
+  this->theVector.resize(3, Constructable(77));
+  this->assertValuesInOrder(this->theVector, 3u, 77, 77, 77);
+}
+
+TEST(SmallVectorTest, ResizeForOverwrite) {
+  {
+    // Heap allocated storage.
+    SmallVector<unsigned, 0> V;
+    V.push_back(5U);
+    V.pop_back();
+    V.resize_for_overwrite(V.size() + 1U);
+    EXPECT_EQ(5U, V.back());
+    V.pop_back();
+    V.resize(V.size() + 1);
+    EXPECT_EQ(0U, V.back());
+  }
+  {
+    // Inline storage.
+    SmallVector<unsigned, 2> V;
+    V.push_back(5U);
+    V.pop_back();
+    V.resize_for_overwrite(V.size() + 1U);
+    EXPECT_EQ(5U, V.back());
+    V.pop_back();
+    V.resize(V.size() + 1);
+    EXPECT_EQ(0U, V.back());
+  }
+}
+
+// Overflow past fixed size.
+TYPED_TEST(SmallVectorTest, OverflowTest) {
+  SCOPED_TRACE("OverflowTest");
+
+  // Push more elements than the fixed size.
+  this->makeSequence(this->theVector, 1, 10);
+
+  // Test size and values.
+  EXPECT_EQ(10u, this->theVector.size());
+  for (int i = 0; i < 10; ++i) {
+    EXPECT_EQ(i+1, this->theVector[i].getValue());
+  }
+
+  // Now resize back to fixed size.
+  this->theVector.resize(1);
+
+  this->assertValuesInOrder(this->theVector, 1u, 1);
+}
+
+// Iteration tests.
+TYPED_TEST(SmallVectorTest, IterationTest) {
+  this->makeSequence(this->theVector, 1, 2);
+
+  // Forward Iteration
+  typename TypeParam::iterator it = this->theVector.begin();
+  EXPECT_TRUE(*it == this->theVector.front());
+  EXPECT_TRUE(*it == this->theVector[0]);
+  EXPECT_EQ(1, it->getValue());
+  ++it;
+  EXPECT_TRUE(*it == this->theVector[1]);
+  EXPECT_TRUE(*it == this->theVector.back());
+  EXPECT_EQ(2, it->getValue());
+  ++it;
+  EXPECT_TRUE(it == this->theVector.end());
+  --it;
+  EXPECT_TRUE(*it == this->theVector[1]);
+  EXPECT_EQ(2, it->getValue());
+  --it;
+  EXPECT_TRUE(*it == this->theVector[0]);
+  EXPECT_EQ(1, it->getValue());
+
+  // Reverse Iteration
+  typename TypeParam::reverse_iterator rit = this->theVector.rbegin();
+  EXPECT_TRUE(*rit == this->theVector[1]);
+  EXPECT_EQ(2, rit->getValue());
+  ++rit;
+  EXPECT_TRUE(*rit == this->theVector[0]);
+  EXPECT_EQ(1, rit->getValue());
+  ++rit;
+  EXPECT_TRUE(rit == this->theVector.rend());
+  --rit;
+  EXPECT_TRUE(*rit == this->theVector[0]);
+  EXPECT_EQ(1, rit->getValue());
+  --rit;
+  EXPECT_TRUE(*rit == this->theVector[1]);
+  EXPECT_EQ(2, rit->getValue());
+}
+
+// Swap test.
+TYPED_TEST(SmallVectorTest, SwapTest) {
+  SCOPED_TRACE("SwapTest");
+
+  this->makeSequence(this->theVector, 1, 2);
+  std::swap(this->theVector, this->otherVector);
+
+  this->assertEmpty(this->theVector);
+  this->assertValuesInOrder(this->otherVector, 2u, 1, 2);
+}
+
+// Append test
+TYPED_TEST(SmallVectorTest, AppendTest) {
+  SCOPED_TRACE("AppendTest");
+
+  this->makeSequence(this->otherVector, 2, 3);
+
+  this->theVector.push_back(Constructable(1));
+  this->theVector.append(this->otherVector.begin(), this->otherVector.end());
+
+  this->assertValuesInOrder(this->theVector, 3u, 1, 2, 3);
+}
+
+// Append repeated test
+TYPED_TEST(SmallVectorTest, AppendRepeatedTest) {
+  SCOPED_TRACE("AppendRepeatedTest");
+
+  this->theVector.push_back(Constructable(1));
+  this->theVector.append(2, Constructable(77));
+  this->assertValuesInOrder(this->theVector, 3u, 1, 77, 77);
+}
+
+// Append test
+TYPED_TEST(SmallVectorTest, AppendNonIterTest) {
+  SCOPED_TRACE("AppendRepeatedTest");
+
+  this->theVector.push_back(Constructable(1));
+  this->theVector.append(2, 7);
+  this->assertValuesInOrder(this->theVector, 3u, 1, 7, 7);
+}
+
+struct output_iterator {
+  typedef std::output_iterator_tag iterator_category;
+  typedef int value_type;
+  typedef int difference_type;
+  typedef value_type *pointer;
+  typedef value_type &reference;
+  operator int() { return 2; }
+  operator Constructable() { return 7; }
+};
+
+TYPED_TEST(SmallVectorTest, AppendRepeatedNonForwardIterator) {
+  SCOPED_TRACE("AppendRepeatedTest");
+
+  this->theVector.push_back(Constructable(1));
+  this->theVector.append(output_iterator(), output_iterator());
+  this->assertValuesInOrder(this->theVector, 3u, 1, 7, 7);
+}
+
+TYPED_TEST(SmallVectorTest, AppendSmallVector) {
+  SCOPED_TRACE("AppendSmallVector");
+
+  SmallVector<Constructable, 3> otherVector = {7, 7};
+  this->theVector.push_back(Constructable(1));
+  this->theVector.append(otherVector);
+  this->assertValuesInOrder(this->theVector, 3u, 1, 7, 7);
+}
+
+// Assign test
+TYPED_TEST(SmallVectorTest, AssignTest) {
+  SCOPED_TRACE("AssignTest");
+
+  this->theVector.push_back(Constructable(1));
+  this->theVector.assign(2, Constructable(77));
+  this->assertValuesInOrder(this->theVector, 2u, 77, 77);
+}
+
+// Assign test
+TYPED_TEST(SmallVectorTest, AssignRangeTest) {
+  SCOPED_TRACE("AssignTest");
+
+  this->theVector.push_back(Constructable(1));
+  int arr[] = {1, 2, 3};
+  this->theVector.assign(std::begin(arr), std::end(arr));
+  this->assertValuesInOrder(this->theVector, 3u, 1, 2, 3);
+}
+
+// Assign test
+TYPED_TEST(SmallVectorTest, AssignNonIterTest) {
+  SCOPED_TRACE("AssignTest");
+
+  this->theVector.push_back(Constructable(1));
+  this->theVector.assign(2, 7);
+  this->assertValuesInOrder(this->theVector, 2u, 7, 7);
+}
+
+TYPED_TEST(SmallVectorTest, AssignSmallVector) {
+  SCOPED_TRACE("AssignSmallVector");
+
+  SmallVector<Constructable, 3> otherVector = {7, 7};
+  this->theVector.push_back(Constructable(1));
+  this->theVector.assign(otherVector);
+  this->assertValuesInOrder(this->theVector, 2u, 7, 7);
+}
+
+// Move-assign test
+TYPED_TEST(SmallVectorTest, MoveAssignTest) {
+  SCOPED_TRACE("MoveAssignTest");
+
+  // Set up our vector with a single element, but enough capacity for 4.
+  this->theVector.reserve(4);
+  this->theVector.push_back(Constructable(1));
+  
+  // Set up the other vector with 2 elements.
+  this->otherVector.push_back(Constructable(2));
+  this->otherVector.push_back(Constructable(3));
+
+  // Move-assign from the other vector.
+  this->theVector = std::move(this->otherVector);
+
+  // Make sure we have the right result.
+  this->assertValuesInOrder(this->theVector, 2u, 2, 3);
+
+  // Make sure the # of constructor/destructor calls line up. There
+  // are two live objects after clearing the other vector.
+  this->otherVector.clear();
+  EXPECT_EQ(Constructable::getNumConstructorCalls()-2, 
+            Constructable::getNumDestructorCalls());
+
+  // There shouldn't be any live objects any more.
+  this->theVector.clear();
+  EXPECT_EQ(Constructable::getNumConstructorCalls(), 
+            Constructable::getNumDestructorCalls());
+}
+
+// Erase a single element
+TYPED_TEST(SmallVectorTest, EraseTest) {
+  SCOPED_TRACE("EraseTest");
+
+  this->makeSequence(this->theVector, 1, 3);
+  const auto &theConstVector = this->theVector;
+  this->theVector.erase(theConstVector.begin());
+  this->assertValuesInOrder(this->theVector, 2u, 2, 3);
+}
+
+// Erase a range of elements
+TYPED_TEST(SmallVectorTest, EraseRangeTest) {
+  SCOPED_TRACE("EraseRangeTest");
+
+  this->makeSequence(this->theVector, 1, 3);
+  const auto &theConstVector = this->theVector;
+  this->theVector.erase(theConstVector.begin(), theConstVector.begin() + 2);
+  this->assertValuesInOrder(this->theVector, 1u, 3);
+}
+
+// Insert a single element.
+TYPED_TEST(SmallVectorTest, InsertTest) {
+  SCOPED_TRACE("InsertTest");
+
+  this->makeSequence(this->theVector, 1, 3);
+  typename TypeParam::iterator I =
+    this->theVector.insert(this->theVector.begin() + 1, Constructable(77));
+  EXPECT_EQ(this->theVector.begin() + 1, I);
+  this->assertValuesInOrder(this->theVector, 4u, 1, 77, 2, 3);
+}
+
+// Insert a copy of a single element.
+TYPED_TEST(SmallVectorTest, InsertCopy) {
+  SCOPED_TRACE("InsertTest");
+
+  this->makeSequence(this->theVector, 1, 3);
+  Constructable C(77);
+  typename TypeParam::iterator I =
+      this->theVector.insert(this->theVector.begin() + 1, C);
+  EXPECT_EQ(this->theVector.begin() + 1, I);
+  this->assertValuesInOrder(this->theVector, 4u, 1, 77, 2, 3);
+}
+
+// Insert repeated elements.
+TYPED_TEST(SmallVectorTest, InsertRepeatedTest) {
+  SCOPED_TRACE("InsertRepeatedTest");
+
+  this->makeSequence(this->theVector, 1, 4);
+  Constructable::reset();
+  auto I =
+      this->theVector.insert(this->theVector.begin() + 1, 2, Constructable(16));
+  // Move construct the top element into newly allocated space, and optionally
+  // reallocate the whole buffer, move constructing into it.
+  // FIXME: This is inefficient, we shouldn't move things into newly allocated
+  // space, then move them up/around, there should only be 2 or 4 move
+  // constructions here.
+  EXPECT_TRUE(Constructable::getNumMoveConstructorCalls() == 2 ||
+              Constructable::getNumMoveConstructorCalls() == 6);
+  // Move assign the next two to shift them up and make a gap.
+  EXPECT_EQ(1, Constructable::getNumMoveAssignmentCalls());
+  // Copy construct the two new elements from the parameter.
+  EXPECT_EQ(2, Constructable::getNumCopyAssignmentCalls());
+  // All without any copy construction.
+  EXPECT_EQ(0, Constructable::getNumCopyConstructorCalls());
+  EXPECT_EQ(this->theVector.begin() + 1, I);
+  this->assertValuesInOrder(this->theVector, 6u, 1, 16, 16, 2, 3, 4);
+}
+
+TYPED_TEST(SmallVectorTest, InsertRepeatedNonIterTest) {
+  SCOPED_TRACE("InsertRepeatedTest");
+
+  this->makeSequence(this->theVector, 1, 4);
+  Constructable::reset();
+  auto I = this->theVector.insert(this->theVector.begin() + 1, 2, 7);
+  EXPECT_EQ(this->theVector.begin() + 1, I);
+  this->assertValuesInOrder(this->theVector, 6u, 1, 7, 7, 2, 3, 4);
+}
+
+TYPED_TEST(SmallVectorTest, InsertRepeatedAtEndTest) {
+  SCOPED_TRACE("InsertRepeatedTest");
+
+  this->makeSequence(this->theVector, 1, 4);
+  Constructable::reset();
+  auto I = this->theVector.insert(this->theVector.end(), 2, Constructable(16));
+  // Just copy construct them into newly allocated space
+  EXPECT_EQ(2, Constructable::getNumCopyConstructorCalls());
+  // Move everything across if reallocation is needed.
+  EXPECT_TRUE(Constructable::getNumMoveConstructorCalls() == 0 ||
+              Constructable::getNumMoveConstructorCalls() == 4);
+  // Without ever moving or copying anything else.
+  EXPECT_EQ(0, Constructable::getNumCopyAssignmentCalls());
+  EXPECT_EQ(0, Constructable::getNumMoveAssignmentCalls());
+
+  EXPECT_EQ(this->theVector.begin() + 4, I);
+  this->assertValuesInOrder(this->theVector, 6u, 1, 2, 3, 4, 16, 16);
+}
+
+TYPED_TEST(SmallVectorTest, InsertRepeatedEmptyTest) {
+  SCOPED_TRACE("InsertRepeatedTest");
+
+  this->makeSequence(this->theVector, 10, 15);
+
+  // Empty insert.
+  EXPECT_EQ(this->theVector.end(),
+            this->theVector.insert(this->theVector.end(),
+                                   0, Constructable(42)));
+  EXPECT_EQ(this->theVector.begin() + 1,
+            this->theVector.insert(this->theVector.begin() + 1,
+                                   0, Constructable(42)));
+}
+
+// Insert range.
+TYPED_TEST(SmallVectorTest, InsertRangeTest) {
+  SCOPED_TRACE("InsertRangeTest");
+
+  Constructable Arr[3] =
+    { Constructable(77), Constructable(77), Constructable(77) };
+
+  this->makeSequence(this->theVector, 1, 3);
+  Constructable::reset();
+  auto I = this->theVector.insert(this->theVector.begin() + 1, Arr, Arr + 3);
+  // Move construct the top 3 elements into newly allocated space.
+  // Possibly move the whole sequence into new space first.
+  // FIXME: This is inefficient, we shouldn't move things into newly allocated
+  // space, then move them up/around, there should only be 2 or 3 move
+  // constructions here.
+  EXPECT_TRUE(Constructable::getNumMoveConstructorCalls() == 2 ||
+              Constructable::getNumMoveConstructorCalls() == 5);
+  // Copy assign the lower 2 new elements into existing space.
+  EXPECT_EQ(2, Constructable::getNumCopyAssignmentCalls());
+  // Copy construct the third element into newly allocated space.
+  EXPECT_EQ(1, Constructable::getNumCopyConstructorCalls());
+  EXPECT_EQ(this->theVector.begin() + 1, I);
+  this->assertValuesInOrder(this->theVector, 6u, 1, 77, 77, 77, 2, 3);
+}
+
+
+TYPED_TEST(SmallVectorTest, InsertRangeAtEndTest) {
+  SCOPED_TRACE("InsertRangeTest");
+
+  Constructable Arr[3] =
+    { Constructable(77), Constructable(77), Constructable(77) };
+
+  this->makeSequence(this->theVector, 1, 3);
+
+  // Insert at end.
+  Constructable::reset();
+  auto I = this->theVector.insert(this->theVector.end(), Arr, Arr+3);
+  // Copy construct the 3 elements into new space at the top.
+  EXPECT_EQ(3, Constructable::getNumCopyConstructorCalls());
+  // Don't copy/move anything else.
+  EXPECT_EQ(0, Constructable::getNumCopyAssignmentCalls());
+  // Reallocation might occur, causing all elements to be moved into the new
+  // buffer.
+  EXPECT_TRUE(Constructable::getNumMoveConstructorCalls() == 0 ||
+              Constructable::getNumMoveConstructorCalls() == 3);
+  EXPECT_EQ(0, Constructable::getNumMoveAssignmentCalls());
+  EXPECT_EQ(this->theVector.begin() + 3, I);
+  this->assertValuesInOrder(this->theVector, 6u,
+                            1, 2, 3, 77, 77, 77);
+}
+
+TYPED_TEST(SmallVectorTest, InsertEmptyRangeTest) {
+  SCOPED_TRACE("InsertRangeTest");
+
+  this->makeSequence(this->theVector, 1, 3);
+
+  // Empty insert.
+  EXPECT_EQ(this->theVector.end(),
+            this->theVector.insert(this->theVector.end(),
+                                   this->theVector.begin(),
+                                   this->theVector.begin()));
+  EXPECT_EQ(this->theVector.begin() + 1,
+            this->theVector.insert(this->theVector.begin() + 1,
+                                   this->theVector.begin(),
+                                   this->theVector.begin()));
+}
+
+// Comparison tests.
+TYPED_TEST(SmallVectorTest, ComparisonTest) {
+  SCOPED_TRACE("ComparisonTest");
+
+  this->makeSequence(this->theVector, 1, 3);
+  this->makeSequence(this->otherVector, 1, 3);
+
+  EXPECT_TRUE(this->theVector == this->otherVector);
+  EXPECT_FALSE(this->theVector != this->otherVector);
+
+  this->otherVector.clear();
+  this->makeSequence(this->otherVector, 2, 4);
+
+  EXPECT_FALSE(this->theVector == this->otherVector);
+  EXPECT_TRUE(this->theVector != this->otherVector);
+}
+
+// Constant vector tests.
+TYPED_TEST(SmallVectorTest, ConstVectorTest) {
+  const TypeParam constVector;
+
+  EXPECT_EQ(0u, constVector.size());
+  EXPECT_TRUE(constVector.empty());
+  EXPECT_TRUE(constVector.begin() == constVector.end());
+}
+
+// Direct array access.
+TYPED_TEST(SmallVectorTest, DirectVectorTest) {
+  EXPECT_EQ(0u, this->theVector.size());
+  this->theVector.reserve(4);
+  EXPECT_LE(4u, this->theVector.capacity());
+  EXPECT_EQ(0, Constructable::getNumConstructorCalls());
+  this->theVector.push_back(1);
+  this->theVector.push_back(2);
+  this->theVector.push_back(3);
+  this->theVector.push_back(4);
+  EXPECT_EQ(4u, this->theVector.size());
+  EXPECT_EQ(8, Constructable::getNumConstructorCalls());
+  EXPECT_EQ(1, this->theVector[0].getValue());
+  EXPECT_EQ(2, this->theVector[1].getValue());
+  EXPECT_EQ(3, this->theVector[2].getValue());
+  EXPECT_EQ(4, this->theVector[3].getValue());
+}
+
+TYPED_TEST(SmallVectorTest, IteratorTest) {
+  std::list<int> L;
+  this->theVector.insert(this->theVector.end(), L.begin(), L.end());
+}
+
+template <typename InvalidType> class DualSmallVectorsTest;
+
+template <typename VectorT1, typename VectorT2>
+class DualSmallVectorsTest<std::pair<VectorT1, VectorT2>> : public SmallVectorTestBase {
+protected:
+  VectorT1 theVector;
+  VectorT2 otherVector;
+
+  template <typename T, unsigned N>
+  static unsigned NumBuiltinElts(const SmallVector<T, N>&) { return N; }
+};
+
+typedef ::testing::Types<
+    // Small mode -> Small mode.
+    std::pair<SmallVector<Constructable, 4>, SmallVector<Constructable, 4>>,
+    // Small mode -> Big mode.
+    std::pair<SmallVector<Constructable, 4>, SmallVector<Constructable, 2>>,
+    // Big mode -> Small mode.
+    std::pair<SmallVector<Constructable, 2>, SmallVector<Constructable, 4>>,
+    // Big mode -> Big mode.
+    std::pair<SmallVector<Constructable, 2>, SmallVector<Constructable, 2>>
+  > DualSmallVectorTestTypes;
+
+TYPED_TEST_SUITE(DualSmallVectorsTest, DualSmallVectorTestTypes, );
+
+TYPED_TEST(DualSmallVectorsTest, MoveAssignment) {
+  SCOPED_TRACE("MoveAssignTest-DualVectorTypes");
+
+  // Set up our vector with four elements.
+  for (unsigned I = 0; I < 4; ++I)
+    this->otherVector.push_back(Constructable(I));
+
+  const Constructable *OrigDataPtr = this->otherVector.data();
+
+  // Move-assign from the other vector.
+  this->theVector =
+    std::move(static_cast<SmallVectorImpl<Constructable>&>(this->otherVector));
+
+  // Make sure we have the right result.
+  this->assertValuesInOrder(this->theVector, 4u, 0, 1, 2, 3);
+
+  // Make sure the # of constructor/destructor calls line up. There
+  // are two live objects after clearing the other vector.
+  this->otherVector.clear();
+  EXPECT_EQ(Constructable::getNumConstructorCalls()-4,
+            Constructable::getNumDestructorCalls());
+
+  // If the source vector (otherVector) was in small-mode, assert that we just
+  // moved the data pointer over.
+  EXPECT_TRUE(this->NumBuiltinElts(this->otherVector) == 4 ||
+              this->theVector.data() == OrigDataPtr);
+
+  // There shouldn't be any live objects any more.
+  this->theVector.clear();
+  EXPECT_EQ(Constructable::getNumConstructorCalls(),
+            Constructable::getNumDestructorCalls());
+
+  // We shouldn't have copied anything in this whole process.
+  EXPECT_EQ(Constructable::getNumCopyConstructorCalls(), 0);
+}
+
+struct notassignable {
+  int &x;
+  notassignable(int &x) : x(x) {}
+};
+
+TEST(SmallVectorCustomTest, NoAssignTest) {
+  int x = 0;
+  SmallVector<notassignable, 2> vec;
+  vec.push_back(notassignable(x));
+  x = 42;
+  EXPECT_EQ(42, vec.pop_back_val().x);
+}
+
+struct MovedFrom {
+  bool hasValue;
+  MovedFrom() : hasValue(true) {
+  }
+  MovedFrom(MovedFrom&& m) : hasValue(m.hasValue) {
+    m.hasValue = false;
+  }
+  MovedFrom &operator=(MovedFrom&& m) {
+    hasValue = m.hasValue;
+    m.hasValue = false;
+    return *this;
+  }
+};
+
+TEST(SmallVectorTest, MidInsert) {
+  SmallVector<MovedFrom, 3> v;
+  v.push_back(MovedFrom());
+  v.insert(v.begin(), MovedFrom());
+  for (MovedFrom &m : v)
+    EXPECT_TRUE(m.hasValue);
+}
+
+enum EmplaceableArgState {
+  EAS_Defaulted,
+  EAS_Arg,
+  EAS_LValue,
+  EAS_RValue,
+  EAS_Failure
+};
+template <int I> struct EmplaceableArg {
+  EmplaceableArgState State;
+  EmplaceableArg() : State(EAS_Defaulted) {}
+  EmplaceableArg(EmplaceableArg &&X)
+      : State(X.State == EAS_Arg ? EAS_RValue : EAS_Failure) {}
+  EmplaceableArg(EmplaceableArg &X)
+      : State(X.State == EAS_Arg ? EAS_LValue : EAS_Failure) {}
+
+  explicit EmplaceableArg(bool) : State(EAS_Arg) {}
+
+private:
+  EmplaceableArg &operator=(EmplaceableArg &&) = delete;
+  EmplaceableArg &operator=(const EmplaceableArg &) = delete;
+};
+
+enum EmplaceableState { ES_Emplaced, ES_Moved };
+struct Emplaceable {
+  EmplaceableArg<0> A0;
+  EmplaceableArg<1> A1;
+  EmplaceableArg<2> A2;
+  EmplaceableArg<3> A3;
+  EmplaceableState State;
+
+  Emplaceable() : State(ES_Emplaced) {}
+
+  template <class A0Ty>
+  explicit Emplaceable(A0Ty &&A0)
+      : A0(std::forward<A0Ty>(A0)), State(ES_Emplaced) {}
+
+  template <class A0Ty, class A1Ty>
+  Emplaceable(A0Ty &&A0, A1Ty &&A1)
+      : A0(std::forward<A0Ty>(A0)), A1(std::forward<A1Ty>(A1)),
+        State(ES_Emplaced) {}
+
+  template <class A0Ty, class A1Ty, class A2Ty>
+  Emplaceable(A0Ty &&A0, A1Ty &&A1, A2Ty &&A2)
+      : A0(std::forward<A0Ty>(A0)), A1(std::forward<A1Ty>(A1)),
+        A2(std::forward<A2Ty>(A2)), State(ES_Emplaced) {}
+
+  template <class A0Ty, class A1Ty, class A2Ty, class A3Ty>
+  Emplaceable(A0Ty &&A0, A1Ty &&A1, A2Ty &&A2, A3Ty &&A3)
+      : A0(std::forward<A0Ty>(A0)), A1(std::forward<A1Ty>(A1)),
+        A2(std::forward<A2Ty>(A2)), A3(std::forward<A3Ty>(A3)),
+        State(ES_Emplaced) {}
+
+  Emplaceable(Emplaceable &&) : State(ES_Moved) {}
+  Emplaceable &operator=(Emplaceable &&) {
+    State = ES_Moved;
+    return *this;
+  }
+
+private:
+  Emplaceable(const Emplaceable &) = delete;
+  Emplaceable &operator=(const Emplaceable &) = delete;
+};
+
+TEST(SmallVectorTest, EmplaceBack) {
+  EmplaceableArg<0> A0(true);
+  EmplaceableArg<1> A1(true);
+  EmplaceableArg<2> A2(true);
+  EmplaceableArg<3> A3(true);
+  {
+    SmallVector<Emplaceable, 3> V;
+    Emplaceable &back = V.emplace_back();
+    EXPECT_TRUE(&back == &V.back());
+    EXPECT_TRUE(V.size() == 1);
+    EXPECT_TRUE(back.State == ES_Emplaced);
+    EXPECT_TRUE(back.A0.State == EAS_Defaulted);
+    EXPECT_TRUE(back.A1.State == EAS_Defaulted);
+    EXPECT_TRUE(back.A2.State == EAS_Defaulted);
+    EXPECT_TRUE(back.A3.State == EAS_Defaulted);
+  }
+  {
+    SmallVector<Emplaceable, 3> V;
+    Emplaceable &back = V.emplace_back(std::move(A0));
+    EXPECT_TRUE(&back == &V.back());
+    EXPECT_TRUE(V.size() == 1);
+    EXPECT_TRUE(back.State == ES_Emplaced);
+    EXPECT_TRUE(back.A0.State == EAS_RValue);
+    EXPECT_TRUE(back.A1.State == EAS_Defaulted);
+    EXPECT_TRUE(back.A2.State == EAS_Defaulted);
+    EXPECT_TRUE(back.A3.State == EAS_Defaulted);
+  }
+  {
+    SmallVector<Emplaceable, 3> V;
+    Emplaceable &back = V.emplace_back(A0);
+    EXPECT_TRUE(&back == &V.back());
+    EXPECT_TRUE(V.size() == 1);
+    EXPECT_TRUE(back.State == ES_Emplaced);
+    EXPECT_TRUE(back.A0.State == EAS_LValue);
+    EXPECT_TRUE(back.A1.State == EAS_Defaulted);
+    EXPECT_TRUE(back.A2.State == EAS_Defaulted);
+    EXPECT_TRUE(back.A3.State == EAS_Defaulted);
+  }
+  {
+    SmallVector<Emplaceable, 3> V;
+    Emplaceable &back = V.emplace_back(A0, A1);
+    EXPECT_TRUE(&back == &V.back());
+    EXPECT_TRUE(V.size() == 1);
+    EXPECT_TRUE(back.State == ES_Emplaced);
+    EXPECT_TRUE(back.A0.State == EAS_LValue);
+    EXPECT_TRUE(back.A1.State == EAS_LValue);
+    EXPECT_TRUE(back.A2.State == EAS_Defaulted);
+    EXPECT_TRUE(back.A3.State == EAS_Defaulted);
+  }
+  {
+    SmallVector<Emplaceable, 3> V;
+    Emplaceable &back = V.emplace_back(std::move(A0), std::move(A1));
+    EXPECT_TRUE(&back == &V.back());
+    EXPECT_TRUE(V.size() == 1);
+    EXPECT_TRUE(back.State == ES_Emplaced);
+    EXPECT_TRUE(back.A0.State == EAS_RValue);
+    EXPECT_TRUE(back.A1.State == EAS_RValue);
+    EXPECT_TRUE(back.A2.State == EAS_Defaulted);
+    EXPECT_TRUE(back.A3.State == EAS_Defaulted);
+  }
+  {
+    SmallVector<Emplaceable, 3> V;
+    Emplaceable &back = V.emplace_back(std::move(A0), A1, std::move(A2), A3);
+    EXPECT_TRUE(&back == &V.back());
+    EXPECT_TRUE(V.size() == 1);
+    EXPECT_TRUE(back.State == ES_Emplaced);
+    EXPECT_TRUE(back.A0.State == EAS_RValue);
+    EXPECT_TRUE(back.A1.State == EAS_LValue);
+    EXPECT_TRUE(back.A2.State == EAS_RValue);
+    EXPECT_TRUE(back.A3.State == EAS_LValue);
+  }
+  {
+    SmallVector<int, 1> V;
+    V.emplace_back();
+    V.emplace_back(42);
+    EXPECT_EQ(2U, V.size());
+    EXPECT_EQ(0, V[0]);
+    EXPECT_EQ(42, V[1]);
+  }
+}
+
+TEST(SmallVectorTest, DefaultInlinedElements) {
+  SmallVector<int> V;
+  EXPECT_TRUE(V.empty());
+  V.push_back(7);
+  EXPECT_EQ(V[0], 7);
+
+  // Check that at least a couple layers of nested SmallVector<T>'s are allowed
+  // by the default inline elements policy. This pattern happens in practice
+  // with some frequency, and it seems fairly harmless even though each layer of
+  // SmallVector's will grow the total sizeof by a vector header beyond the
+  // "preferred" maximum sizeof.
+  SmallVector<SmallVector<SmallVector<int>>> NestedV;
+  NestedV.emplace_back().emplace_back().emplace_back(42);
+  EXPECT_EQ(NestedV[0][0][0], 42);
+}
+
+template <class VectorT>
+class SmallVectorReferenceInvalidationTest : public SmallVectorTestBase {
+protected:
+  const char *AssertionMessage =
+      "Attempting to reference an element of the vector in an operation \" "
+      "\"that invalidates it";
+
+  VectorT V;
+
+  template <typename T, unsigned N>
+  static unsigned NumBuiltinElts(const SmallVector<T, N> &) {
+    return N;
+  }
+
+  template <class T> static bool isValueType() {
+    return std::is_same<T, typename VectorT::value_type>::value;
+  }
+
+  void SetUp() override {
+    SmallVectorTestBase::SetUp();
+
+    // Fill up the small size so that insertions move the elements.
+    for (int I = 0, E = NumBuiltinElts(V); I != E; ++I)
+      V.emplace_back(I + 1);
+  }
+};
+
+// Test one type that's trivially copyable (int) and one that isn't
+// (Constructable) since reference invalidation may be fixed differently for
+// each.
+using SmallVectorReferenceInvalidationTestTypes =
+    ::testing::Types<SmallVector<int, 3>, SmallVector<Constructable, 3>>;
+
+TYPED_TEST_SUITE(SmallVectorReferenceInvalidationTest,
+                 SmallVectorReferenceInvalidationTestTypes, );
+
+TYPED_TEST(SmallVectorReferenceInvalidationTest, PushBack) {
+  // Note: setup adds [1, 2, ...] to V until it's at capacity in small mode.
+  auto &V = this->V;
+  int N = this->NumBuiltinElts(V);
+
+  // Push back a reference to last element when growing from small storage.
+  V.push_back(V.back());
+  EXPECT_EQ(N, V.back());
+
+  // Check that the old value is still there (not moved away).
+  EXPECT_EQ(N, V[V.size() - 2]);
+
+  // Fill storage again.
+  V.back() = V.size();
+  while (V.size() < V.capacity())
+    V.push_back(V.size() + 1);
+
+  // Push back a reference to last element when growing from large storage.
+  V.push_back(V.back());
+  EXPECT_EQ(int(V.size()) - 1, V.back());
+}
+
+TYPED_TEST(SmallVectorReferenceInvalidationTest, PushBackMoved) {
+  // Note: setup adds [1, 2, ...] to V until it's at capacity in small mode.
+  auto &V = this->V;
+  int N = this->NumBuiltinElts(V);
+
+  // Push back a reference to last element when growing from small storage.
+  V.push_back(std::move(V.back()));
+  EXPECT_EQ(N, V.back());
+  if (this->template isValueType<Constructable>()) {
+    // Check that the value was moved (not copied).
+    EXPECT_EQ(0, V[V.size() - 2]);
+  }
+
+  // Fill storage again.
+  V.back() = V.size();
+  while (V.size() < V.capacity())
+    V.push_back(V.size() + 1);
+
+  // Push back a reference to last element when growing from large storage.
+  V.push_back(std::move(V.back()));
+
+  // Check the values.
+  EXPECT_EQ(int(V.size()) - 1, V.back());
+  if (this->template isValueType<Constructable>()) {
+    // Check the value got moved out.
+    EXPECT_EQ(0, V[V.size() - 2]);
+  }
+}
+
+TYPED_TEST(SmallVectorReferenceInvalidationTest, Resize) {
+  auto &V = this->V;
+  (void)V;
+  int N = this->NumBuiltinElts(V);
+  V.resize(N + 1, V.back());
+  EXPECT_EQ(N, V.back());
+
+  // Resize to add enough elements that V will grow again. If reference
+  // invalidation breaks in the future, sanitizers should be able to catch a
+  // use-after-free here.
+  V.resize(V.capacity() + 1, V.front());
+  EXPECT_EQ(1, V.back());
+}
+
+TYPED_TEST(SmallVectorReferenceInvalidationTest, Append) {
+  auto &V = this->V;
+  (void)V;
+  V.append(1, V.back());
+  int N = this->NumBuiltinElts(V);
+  EXPECT_EQ(N, V[N - 1]);
+
+  // Append enough more elements that V will grow again. This tests growing
+  // when already in large mode.
+  //
+  // If reference invalidation breaks in the future, sanitizers should be able
+  // to catch a use-after-free here.
+  V.append(V.capacity() - V.size() + 1, V.front());
+  EXPECT_EQ(1, V.back());
+}
+
+TYPED_TEST(SmallVectorReferenceInvalidationTest, AppendRange) {
+  auto &V = this->V;
+  (void)V;
+#if !defined(NDEBUG) && GTEST_HAS_DEATH_TEST
+  EXPECT_DEATH(V.append(V.begin(), V.begin() + 1), this->AssertionMessage);
+
+  ASSERT_EQ(3u, this->NumBuiltinElts(V));
+  ASSERT_EQ(3u, V.size());
+  V.pop_back();
+  ASSERT_EQ(2u, V.size());
+
+  // Confirm this checks for growth when there's more than one element
+  // appended.
+  EXPECT_DEATH(V.append(V.begin(), V.end()), this->AssertionMessage);
+#endif
+}
+
+TYPED_TEST(SmallVectorReferenceInvalidationTest, Assign) {
+  // Note: setup adds [1, 2, ...] to V until it's at capacity in small mode.
+  auto &V = this->V;
+  (void)V;
+  int N = this->NumBuiltinElts(V);
+  ASSERT_EQ(unsigned(N), V.size());
+  ASSERT_EQ(unsigned(N), V.capacity());
+
+  // Check assign that shrinks in small mode.
+  V.assign(1, V.back());
+  EXPECT_EQ(1u, V.size());
+  EXPECT_EQ(N, V[0]);
+
+  // Check assign that grows within small mode.
+  ASSERT_LT(V.size(), V.capacity());
+  V.assign(V.capacity(), V.back());
+  for (int I = 0, E = V.size(); I != E; ++I) {
+    EXPECT_EQ(N, V[I]);
+
+    // Reset to [1, 2, ...].
+    V[I] = I + 1;
+  }
+
+  // Check assign that grows to large mode.
+  ASSERT_EQ(2, V[1]);
+  V.assign(V.capacity() + 1, V[1]);
+  for (int I = 0, E = V.size(); I != E; ++I) {
+    EXPECT_EQ(2, V[I]);
+
+    // Reset to [1, 2, ...].
+    V[I] = I + 1;
+  }
+
+  // Check assign that shrinks in large mode.
+  V.assign(1, V[1]);
+  EXPECT_EQ(2, V[0]);
+}
+
+TYPED_TEST(SmallVectorReferenceInvalidationTest, AssignRange) {
+  auto &V = this->V;
+#if !defined(NDEBUG) && GTEST_HAS_DEATH_TEST
+  EXPECT_DEATH(V.assign(V.begin(), V.end()), this->AssertionMessage);
+  EXPECT_DEATH(V.assign(V.begin(), V.end() - 1), this->AssertionMessage);
+#endif
+  V.assign(V.begin(), V.begin());
+  EXPECT_TRUE(V.empty());
+}
+
+TYPED_TEST(SmallVectorReferenceInvalidationTest, Insert) {
+  // Note: setup adds [1, 2, ...] to V until it's at capacity in small mode.
+  auto &V = this->V;
+  (void)V;
+
+  // Insert a reference to the back (not at end() or else insert delegates to
+  // push_back()), growing out of small mode. Confirm the value was copied out
+  // (moving out Constructable sets it to 0).
+  V.insert(V.begin(), V.back());
+  EXPECT_EQ(int(V.size() - 1), V.front());
+  EXPECT_EQ(int(V.size() - 1), V.back());
+
+  // Fill up the vector again.
+  while (V.size() < V.capacity())
+    V.push_back(V.size() + 1);
+
+  // Grow again from large storage to large storage.
+  V.insert(V.begin(), V.back());
+  EXPECT_EQ(int(V.size() - 1), V.front());
+  EXPECT_EQ(int(V.size() - 1), V.back());
+}
+
+TYPED_TEST(SmallVectorReferenceInvalidationTest, InsertMoved) {
+  // Note: setup adds [1, 2, ...] to V until it's at capacity in small mode.
+  auto &V = this->V;
+  (void)V;
+
+  // Insert a reference to the back (not at end() or else insert delegates to
+  // push_back()), growing out of small mode. Confirm the value was copied out
+  // (moving out Constructable sets it to 0).
+  V.insert(V.begin(), std::move(V.back()));
+  EXPECT_EQ(int(V.size() - 1), V.front());
+  if (this->template isValueType<Constructable>()) {
+    // Check the value got moved out.
+    EXPECT_EQ(0, V.back());
+  }
+
+  // Fill up the vector again.
+  while (V.size() < V.capacity())
+    V.push_back(V.size() + 1);
+
+  // Grow again from large storage to large storage.
+  V.insert(V.begin(), std::move(V.back()));
+  EXPECT_EQ(int(V.size() - 1), V.front());
+  if (this->template isValueType<Constructable>()) {
+    // Check the value got moved out.
+    EXPECT_EQ(0, V.back());
+  }
+}
+
+TYPED_TEST(SmallVectorReferenceInvalidationTest, InsertN) {
+  auto &V = this->V;
+  (void)V;
+
+  // Cover NumToInsert <= this->end() - I.
+  V.insert(V.begin() + 1, 1, V.back());
+  int N = this->NumBuiltinElts(V);
+  EXPECT_EQ(N, V[1]);
+
+  // Cover NumToInsert > this->end() - I, inserting enough elements that V will
+  // also grow again; V.capacity() will be more elements than necessary but
+  // it's a simple way to cover both conditions.
+  //
+  // If reference invalidation breaks in the future, sanitizers should be able
+  // to catch a use-after-free here.
+  V.insert(V.begin(), V.capacity(), V.front());
+  EXPECT_EQ(1, V.front());
+}
+
+TYPED_TEST(SmallVectorReferenceInvalidationTest, InsertRange) {
+  auto &V = this->V;
+  (void)V;
+#if !defined(NDEBUG) && GTEST_HAS_DEATH_TEST
+  EXPECT_DEATH(V.insert(V.begin(), V.begin(), V.begin() + 1),
+               this->AssertionMessage);
+
+  ASSERT_EQ(3u, this->NumBuiltinElts(V));
+  ASSERT_EQ(3u, V.size());
+  V.pop_back();
+  ASSERT_EQ(2u, V.size());
+
+  // Confirm this checks for growth when there's more than one element
+  // inserted.
+  EXPECT_DEATH(V.insert(V.begin(), V.begin(), V.end()), this->AssertionMessage);
+#endif
+}
+
+TYPED_TEST(SmallVectorReferenceInvalidationTest, EmplaceBack) {
+  // Note: setup adds [1, 2, ...] to V until it's at capacity in small mode.
+  auto &V = this->V;
+  int N = this->NumBuiltinElts(V);
+
+  // Push back a reference to last element when growing from small storage.
+  V.emplace_back(V.back());
+  EXPECT_EQ(N, V.back());
+
+  // Check that the old value is still there (not moved away).
+  EXPECT_EQ(N, V[V.size() - 2]);
+
+  // Fill storage again.
+  V.back() = V.size();
+  while (V.size() < V.capacity())
+    V.push_back(V.size() + 1);
+
+  // Push back a reference to last element when growing from large storage.
+  V.emplace_back(V.back());
+  EXPECT_EQ(int(V.size()) - 1, V.back());
+}
+
+template <class VectorT>
+class SmallVectorInternalReferenceInvalidationTest
+    : public SmallVectorTestBase {
+protected:
+  const char *AssertionMessage =
+      "Attempting to reference an element of the vector in an operation \" "
+      "\"that invalidates it";
+
+  VectorT V;
+
+  template <typename T, unsigned N>
+  static unsigned NumBuiltinElts(const SmallVector<T, N> &) {
+    return N;
+  }
+
+  void SetUp() override {
+    SmallVectorTestBase::SetUp();
+
+    // Fill up the small size so that insertions move the elements.
+    for (int I = 0, E = NumBuiltinElts(V); I != E; ++I)
+      V.emplace_back(I + 1, I + 1);
+  }
+};
+
+// Test pairs of the same types from SmallVectorReferenceInvalidationTestTypes.
+using SmallVectorInternalReferenceInvalidationTestTypes =
+    ::testing::Types<SmallVector<std::pair<int, int>, 3>,
+                     SmallVector<std::pair<Constructable, Constructable>, 3>>;
+
+TYPED_TEST_SUITE(SmallVectorInternalReferenceInvalidationTest,
+                 SmallVectorInternalReferenceInvalidationTestTypes, );
+
+TYPED_TEST(SmallVectorInternalReferenceInvalidationTest, EmplaceBack) {
+  // Note: setup adds [1, 2, ...] to V until it's at capacity in small mode.
+  auto &V = this->V;
+  int N = this->NumBuiltinElts(V);
+
+  // Push back a reference to last element when growing from small storage.
+  V.emplace_back(V.back().first, V.back().second);
+  EXPECT_EQ(N, V.back().first);
+  EXPECT_EQ(N, V.back().second);
+
+  // Check that the old value is still there (not moved away).
+  EXPECT_EQ(N, V[V.size() - 2].first);
+  EXPECT_EQ(N, V[V.size() - 2].second);
+
+  // Fill storage again.
+  V.back().first = V.back().second = V.size();
+  while (V.size() < V.capacity())
+    V.emplace_back(V.size() + 1, V.size() + 1);
+
+  // Push back a reference to last element when growing from large storage.
+  V.emplace_back(V.back().first, V.back().second);
+  EXPECT_EQ(int(V.size()) - 1, V.back().first);
+  EXPECT_EQ(int(V.size()) - 1, V.back().second);
+}
+
+} // end namespace
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/StringMapTest.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/StringMapTest.cpp
new file mode 100644
index 0000000..71baa20
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/StringMapTest.cpp
@@ -0,0 +1,622 @@
+//===- llvm/unittest/ADT/StringMapMap.cpp - StringMap unit tests ----------===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+
+#include "wpi/StringMap.h"
+#include "gtest/gtest.h"
+#include <algorithm>
+#include <limits>
+#include <tuple>
+using namespace wpi;
+
+namespace {
+
+// Test fixture
+class StringMapTest : public testing::Test {
+protected:
+  StringMap<uint32_t> testMap;
+
+  static const char testKey[];
+  static const uint32_t testValue;
+  static const char* testKeyFirst;
+  static size_t testKeyLength;
+  static const std::string testKeyStr;
+
+  void assertEmptyMap() {
+    // Size tests
+    EXPECT_EQ(0u, testMap.size());
+    EXPECT_TRUE(testMap.empty());
+
+    // Iterator tests
+    EXPECT_TRUE(testMap.begin() == testMap.end());
+
+    // Lookup tests
+    EXPECT_EQ(0u, testMap.count(testKey));
+    EXPECT_EQ(0u, testMap.count(std::string_view(testKeyFirst, testKeyLength)));
+    EXPECT_EQ(0u, testMap.count(testKeyStr));
+    EXPECT_TRUE(testMap.find(testKey) == testMap.end());
+    EXPECT_TRUE(testMap.find(std::string_view(testKeyFirst, testKeyLength)) == 
+                testMap.end());
+    EXPECT_TRUE(testMap.find(testKeyStr) == testMap.end());
+  }
+
+  void assertSingleItemMap() {
+    // Size tests
+    EXPECT_EQ(1u, testMap.size());
+    EXPECT_FALSE(testMap.begin() == testMap.end());
+    EXPECT_FALSE(testMap.empty());
+
+    // Iterator tests
+    StringMap<uint32_t>::iterator it = testMap.begin();
+    EXPECT_STREQ(testKey, it->first().data());
+    EXPECT_EQ(testValue, it->second);
+    ++it;
+    EXPECT_TRUE(it == testMap.end());
+
+    // Lookup tests
+    EXPECT_EQ(1u, testMap.count(testKey));
+    EXPECT_EQ(1u, testMap.count(std::string_view(testKeyFirst, testKeyLength)));
+    EXPECT_EQ(1u, testMap.count(testKeyStr));
+    EXPECT_TRUE(testMap.find(testKey) == testMap.begin());
+    EXPECT_TRUE(testMap.find(std::string_view(testKeyFirst, testKeyLength)) == 
+                testMap.begin());
+    EXPECT_TRUE(testMap.find(testKeyStr) == testMap.begin());
+  }
+};
+
+const char StringMapTest::testKey[] = "key";
+const uint32_t StringMapTest::testValue = 1u;
+const char* StringMapTest::testKeyFirst = testKey;
+size_t StringMapTest::testKeyLength = sizeof(testKey) - 1;
+const std::string StringMapTest::testKeyStr(testKey);
+
+struct CountCopyAndMove {
+  CountCopyAndMove() = default;
+  CountCopyAndMove(const CountCopyAndMove &) { copy = 1; }
+  CountCopyAndMove(CountCopyAndMove &&) { move = 1; }
+  void operator=(const CountCopyAndMove &) { ++copy; }
+  void operator=(CountCopyAndMove &&) { ++move; }
+  int copy = 0;
+  int move = 0;
+};
+
+// Empty map tests.
+TEST_F(StringMapTest, EmptyMapTest) {
+  assertEmptyMap();
+}
+
+// Constant map tests.
+TEST_F(StringMapTest, ConstEmptyMapTest) {
+  const StringMap<uint32_t>& constTestMap = testMap;
+
+  // Size tests
+  EXPECT_EQ(0u, constTestMap.size());
+  EXPECT_TRUE(constTestMap.empty());
+
+  // Iterator tests
+  EXPECT_TRUE(constTestMap.begin() == constTestMap.end());
+
+  // Lookup tests
+  EXPECT_EQ(0u, constTestMap.count(testKey));
+  EXPECT_EQ(0u, constTestMap.count(std::string_view(testKeyFirst, testKeyLength)));
+  EXPECT_EQ(0u, constTestMap.count(testKeyStr));
+  EXPECT_TRUE(constTestMap.find(testKey) == constTestMap.end());
+  EXPECT_TRUE(constTestMap.find(std::string_view(testKeyFirst, testKeyLength)) ==
+              constTestMap.end());
+  EXPECT_TRUE(constTestMap.find(testKeyStr) == constTestMap.end());
+}
+
+// initializer_list ctor test; also implicitly tests initializer_list and
+// iterator overloads of insert().
+TEST_F(StringMapTest, InitializerListCtor) {
+  testMap = StringMap<uint32_t>({{"key", 1}});
+  assertSingleItemMap();
+}
+
+// A map with a single entry.
+TEST_F(StringMapTest, SingleEntryMapTest) {
+  testMap[testKey] = testValue;
+  assertSingleItemMap();
+}
+
+// Test clear() method.
+TEST_F(StringMapTest, ClearTest) {
+  testMap[testKey] = testValue;
+  testMap.clear();
+  assertEmptyMap();
+}
+
+// Test erase(iterator) method.
+TEST_F(StringMapTest, EraseIteratorTest) {
+  testMap[testKey] = testValue;
+  testMap.erase(testMap.begin());
+  assertEmptyMap();
+}
+
+// Test erase(value) method.
+TEST_F(StringMapTest, EraseValueTest) {
+  testMap[testKey] = testValue;
+  testMap.erase(testKey);
+  assertEmptyMap();
+}
+
+// Test inserting two values and erasing one.
+TEST_F(StringMapTest, InsertAndEraseTest) {
+  testMap[testKey] = testValue;
+  testMap["otherKey"] = 2;
+  testMap.erase("otherKey");
+  assertSingleItemMap();
+}
+
+TEST_F(StringMapTest, SmallFullMapTest) {
+  // StringMap has a tricky corner case when the map is small (<8 buckets) and
+  // it fills up through a balanced pattern of inserts and erases. This can
+  // lead to inf-loops in some cases (PR13148) so we test it explicitly here.
+  wpi::StringMap<int> Map(2);
+
+  Map["eins"] = 1;
+  Map["zwei"] = 2;
+  Map["drei"] = 3;
+  Map.erase("drei");
+  Map.erase("eins");
+  Map["veir"] = 4;
+  Map["funf"] = 5;
+
+  EXPECT_EQ(3u, Map.size());
+  EXPECT_EQ(0, Map.lookup("eins"));
+  EXPECT_EQ(2, Map.lookup("zwei"));
+  EXPECT_EQ(0, Map.lookup("drei"));
+  EXPECT_EQ(4, Map.lookup("veir"));
+  EXPECT_EQ(5, Map.lookup("funf"));
+}
+
+TEST_F(StringMapTest, CopyCtorTest) {
+  wpi::StringMap<int> Map;
+
+  Map["eins"] = 1;
+  Map["zwei"] = 2;
+  Map["drei"] = 3;
+  Map.erase("drei");
+  Map.erase("eins");
+  Map["veir"] = 4;
+  Map["funf"] = 5;
+
+  EXPECT_EQ(3u, Map.size());
+  EXPECT_EQ(0, Map.lookup("eins"));
+  EXPECT_EQ(2, Map.lookup("zwei"));
+  EXPECT_EQ(0, Map.lookup("drei"));
+  EXPECT_EQ(4, Map.lookup("veir"));
+  EXPECT_EQ(5, Map.lookup("funf"));
+
+  wpi::StringMap<int> Map2(Map);
+  EXPECT_EQ(3u, Map2.size());
+  EXPECT_EQ(0, Map2.lookup("eins"));
+  EXPECT_EQ(2, Map2.lookup("zwei"));
+  EXPECT_EQ(0, Map2.lookup("drei"));
+  EXPECT_EQ(4, Map2.lookup("veir"));
+  EXPECT_EQ(5, Map2.lookup("funf"));
+}
+
+// A more complex iteration test.
+TEST_F(StringMapTest, IterationTest) {
+  bool visited[100];
+
+  // Insert 100 numbers into the map
+  for (int i = 0; i < 100; ++i) {
+    std::stringstream ss;
+    ss << "key_" << i;
+    testMap[ss.str()] = i;
+    visited[i] = false;
+  }
+
+  // Iterate over all numbers and mark each one found.
+  for (StringMap<uint32_t>::iterator it = testMap.begin();
+      it != testMap.end(); ++it) {
+    std::stringstream ss;
+    ss << "key_" << it->second;
+    ASSERT_STREQ(ss.str().c_str(), it->first().data());
+    visited[it->second] = true;
+  }
+
+  // Ensure every number was visited.
+  for (int i = 0; i < 100; ++i) {
+    ASSERT_TRUE(visited[i]) << "Entry #" << i << " was never visited";
+  }
+}
+
+// Test StringMapEntry::Create() method.
+TEST_F(StringMapTest, StringMapEntryTest) {
+  MallocAllocator Allocator;
+  StringMap<uint32_t>::value_type *entry =
+      StringMap<uint32_t>::value_type::Create(
+          std::string_view(testKeyFirst, testKeyLength), Allocator, 1u);
+  EXPECT_STREQ(testKey, entry->first().data());
+  EXPECT_EQ(1u, entry->second);
+  entry->Destroy(Allocator);
+}
+
+// Test insert() method.
+TEST_F(StringMapTest, InsertTest) {
+  SCOPED_TRACE("InsertTest");
+  testMap.insert(
+      StringMap<uint32_t>::value_type::Create(
+          std::string_view(testKeyFirst, testKeyLength),
+          testMap.getAllocator(), 1u));
+  assertSingleItemMap();
+}
+
+// Test insert(pair<K, V>) method
+TEST_F(StringMapTest, InsertPairTest) {
+  bool Inserted;
+  StringMap<uint32_t>::iterator NewIt;
+  std::tie(NewIt, Inserted) =
+      testMap.insert(std::make_pair(testKeyFirst, testValue));
+  EXPECT_EQ(1u, testMap.size());
+  EXPECT_EQ(testValue, testMap[testKeyFirst]);
+  EXPECT_EQ(testKeyFirst, NewIt->first());
+  EXPECT_EQ(testValue, NewIt->second);
+  EXPECT_TRUE(Inserted);
+
+  StringMap<uint32_t>::iterator ExistingIt;
+  std::tie(ExistingIt, Inserted) =
+      testMap.insert(std::make_pair(testKeyFirst, testValue + 1));
+  EXPECT_EQ(1u, testMap.size());
+  EXPECT_EQ(testValue, testMap[testKeyFirst]);
+  EXPECT_FALSE(Inserted);
+  EXPECT_EQ(NewIt, ExistingIt);
+}
+
+// Test insert(pair<K, V>) method when rehashing occurs
+TEST_F(StringMapTest, InsertRehashingPairTest) {
+  // Check that the correct iterator is returned when the inserted element is
+  // moved to a different bucket during internal rehashing. This depends on
+  // the particular key, and the implementation of StringMap and HashString.
+  // Changes to those might result in this test not actually checking that.
+  StringMap<uint32_t> t(0);
+  EXPECT_EQ(0u, t.getNumBuckets());
+
+  StringMap<uint32_t>::iterator It =
+    t.insert(std::make_pair("abcdef", 42)).first;
+  EXPECT_EQ(16u, t.getNumBuckets());
+  EXPECT_EQ("abcdef", It->first());
+  EXPECT_EQ(42u, It->second);
+}
+
+TEST_F(StringMapTest, InsertOrAssignTest) {
+  struct A : CountCopyAndMove {
+    A(int v) : v(v) {}
+    int v;
+  };
+  StringMap<A> t(0);
+
+  auto try1 = t.insert_or_assign("A", A(1));
+  EXPECT_TRUE(try1.second);
+  EXPECT_EQ(1, try1.first->second.v);
+  EXPECT_EQ(1, try1.first->second.move);
+
+  auto try2 = t.insert_or_assign("A", A(2));
+  EXPECT_FALSE(try2.second);
+  EXPECT_EQ(2, try2.first->second.v);
+  EXPECT_EQ(2, try1.first->second.move);
+
+  EXPECT_EQ(try1.first, try2.first);
+  EXPECT_EQ(0, try1.first->second.copy);
+}
+
+TEST_F(StringMapTest, IterMapKeysSmallVector) {
+  StringMap<int> Map;
+  Map["A"] = 1;
+  Map["B"] = 2;
+  Map["C"] = 3;
+  Map["D"] = 3;
+
+  auto Keys = to_vector<4>(Map.keys());
+  std::sort(Keys.begin(), Keys.end());
+
+  SmallVector<std::string_view, 4> Expected = {"A", "B", "C", "D"};
+  EXPECT_EQ(Expected, Keys);
+}
+
+// Create a non-default constructable value
+struct StringMapTestStruct {
+  StringMapTestStruct(int i) : i(i) {}
+  StringMapTestStruct() = delete;
+  int i;
+};
+
+TEST_F(StringMapTest, NonDefaultConstructable) {
+  StringMap<StringMapTestStruct> t;
+  t.insert(std::make_pair("Test", StringMapTestStruct(123)));
+  StringMap<StringMapTestStruct>::iterator iter = t.find("Test");
+  ASSERT_NE(iter, t.end());
+  ASSERT_EQ(iter->second.i, 123);
+}
+
+struct Immovable {
+  Immovable() {}
+  Immovable(Immovable&&) = delete; // will disable the other special members
+};
+
+struct MoveOnly {
+  int i;
+  MoveOnly(int i) : i(i) {}
+  MoveOnly(const Immovable&) : i(0) {}
+  MoveOnly(MoveOnly &&RHS) : i(RHS.i) {}
+  MoveOnly &operator=(MoveOnly &&RHS) {
+    i = RHS.i;
+    return *this;
+  }
+
+private:
+  MoveOnly(const MoveOnly &) = delete;
+  MoveOnly &operator=(const MoveOnly &) = delete;
+};
+
+TEST_F(StringMapTest, MoveOnly) {
+  StringMap<MoveOnly> t;
+  t.insert(std::make_pair("Test", MoveOnly(42)));
+  std::string_view Key = "Test";
+  StringMapEntry<MoveOnly>::Create(Key, t.getAllocator(), MoveOnly(42))
+      ->Destroy(t.getAllocator());
+}
+
+TEST_F(StringMapTest, CtorArg) {
+  std::string_view Key = "Test";
+  MallocAllocator Allocator;
+  StringMapEntry<MoveOnly>::Create(Key, Allocator, Immovable())
+      ->Destroy(Allocator);
+}
+
+TEST_F(StringMapTest, MoveConstruct) {
+  StringMap<int> A;
+  A["x"] = 42;
+  StringMap<int> B = std::move(A);
+  ASSERT_EQ(A.size(), 0u);
+  ASSERT_EQ(B.size(), 1u);
+  ASSERT_EQ(B["x"], 42);
+  ASSERT_EQ(B.count("y"), 0u);
+}
+
+TEST_F(StringMapTest, MoveAssignment) {
+  StringMap<int> A;
+  A["x"] = 42;
+  StringMap<int> B;
+  B["y"] = 117;
+  A = std::move(B);
+  ASSERT_EQ(A.size(), 1u);
+  ASSERT_EQ(B.size(), 0u);
+  ASSERT_EQ(A["y"], 117);
+  ASSERT_EQ(B.count("x"), 0u);
+}
+
+TEST_F(StringMapTest, EqualEmpty) {
+  StringMap<int> A;
+  StringMap<int> B;
+  ASSERT_TRUE(A == B);
+  ASSERT_FALSE(A != B);
+  ASSERT_TRUE(A == A); // self check
+}
+
+TEST_F(StringMapTest, EqualWithValues) {
+  StringMap<int> A;
+  A["A"] = 1;
+  A["B"] = 2;
+  A["C"] = 3;
+  A["D"] = 3;
+
+  StringMap<int> B;
+  B["A"] = 1;
+  B["B"] = 2;
+  B["C"] = 3;
+  B["D"] = 3;
+
+  ASSERT_TRUE(A == B);
+  ASSERT_TRUE(B == A);
+  ASSERT_FALSE(A != B);
+  ASSERT_FALSE(B != A);
+  ASSERT_TRUE(A == A); // self check
+}
+
+TEST_F(StringMapTest, NotEqualMissingKeys) {
+  StringMap<int> A;
+  A["A"] = 1;
+  A["B"] = 2;
+
+  StringMap<int> B;
+  B["A"] = 1;
+  B["B"] = 2;
+  B["C"] = 3;
+  B["D"] = 3;
+
+  ASSERT_FALSE(A == B);
+  ASSERT_FALSE(B == A);
+  ASSERT_TRUE(A != B);
+  ASSERT_TRUE(B != A);
+}
+
+TEST_F(StringMapTest, NotEqualWithDifferentValues) {
+  StringMap<int> A;
+  A["A"] = 1;
+  A["B"] = 2;
+  A["C"] = 100;
+  A["D"] = 3;
+
+  StringMap<int> B;
+  B["A"] = 1;
+  B["B"] = 2;
+  B["C"] = 3;
+  B["D"] = 3;
+
+  ASSERT_FALSE(A == B);
+  ASSERT_FALSE(B == A);
+  ASSERT_TRUE(A != B);
+  ASSERT_TRUE(B != A);
+}
+
+struct Countable {
+  int &InstanceCount;
+  int Number;
+  Countable(int Number, int &InstanceCount)
+      : InstanceCount(InstanceCount), Number(Number) {
+    ++InstanceCount;
+  }
+  Countable(Countable &&C) : InstanceCount(C.InstanceCount), Number(C.Number) {
+    ++InstanceCount;
+    C.Number = -1;
+  }
+  Countable(const Countable &C)
+      : InstanceCount(C.InstanceCount), Number(C.Number) {
+    ++InstanceCount;
+  }
+  Countable &operator=(Countable C) {
+    Number = C.Number;
+    return *this;
+  }
+  ~Countable() { --InstanceCount; }
+};
+
+TEST_F(StringMapTest, MoveDtor) {
+  int InstanceCount = 0;
+  StringMap<Countable> A;
+  A.insert(std::make_pair("x", Countable(42, InstanceCount)));
+  ASSERT_EQ(InstanceCount, 1);
+  auto I = A.find("x");
+  ASSERT_NE(I, A.end());
+  ASSERT_EQ(I->second.Number, 42);
+
+  StringMap<Countable> B;
+  B = std::move(A);
+  ASSERT_EQ(InstanceCount, 1);
+  ASSERT_TRUE(A.empty());
+  I = B.find("x");
+  ASSERT_NE(I, B.end());
+  ASSERT_EQ(I->second.Number, 42);
+
+  B = StringMap<Countable>();
+  ASSERT_EQ(InstanceCount, 0);
+  ASSERT_TRUE(B.empty());
+}
+
+namespace {
+// Simple class that counts how many moves and copy happens when growing a map
+struct CountCtorCopyAndMove {
+  static unsigned Ctor;
+  static unsigned Move;
+  static unsigned Copy;
+  int Data = 0;
+  CountCtorCopyAndMove(int Data) : Data(Data) { Ctor++; }
+  CountCtorCopyAndMove() { Ctor++; }
+
+  CountCtorCopyAndMove(const CountCtorCopyAndMove &) { Copy++; }
+  CountCtorCopyAndMove &operator=(const CountCtorCopyAndMove &) {
+    Copy++;
+    return *this;
+  }
+  CountCtorCopyAndMove(CountCtorCopyAndMove &&) { Move++; }
+  CountCtorCopyAndMove &operator=(const CountCtorCopyAndMove &&) {
+    Move++;
+    return *this;
+  }
+};
+unsigned CountCtorCopyAndMove::Copy = 0;
+unsigned CountCtorCopyAndMove::Move = 0;
+unsigned CountCtorCopyAndMove::Ctor = 0;
+
+} // anonymous namespace
+
+// Make sure creating the map with an initial size of N actually gives us enough
+// buckets to insert N items without increasing allocation size.
+TEST(StringMapCustomTest, InitialSizeTest) {
+  // 1 is an "edge value", 32 is an arbitrary power of two, and 67 is an
+  // arbitrary prime, picked without any good reason.
+  for (auto Size : {1, 32, 67}) {
+    StringMap<CountCtorCopyAndMove> Map(Size);
+    auto NumBuckets = Map.getNumBuckets();
+    CountCtorCopyAndMove::Move = 0;
+    CountCtorCopyAndMove::Copy = 0;
+    for (int i = 0; i < Size; ++i)
+      Map.insert(std::pair<std::string, CountCtorCopyAndMove>(
+          std::piecewise_construct, std::forward_as_tuple(std::to_string(i)),
+          std::forward_as_tuple(i)));
+    // After the initial move, the map will move the Elts in the Entry.
+    EXPECT_EQ((unsigned)Size * 2, CountCtorCopyAndMove::Move);
+    // We copy once the pair from the Elts vector
+    EXPECT_EQ(0u, CountCtorCopyAndMove::Copy);
+    // Check that the map didn't grow
+    EXPECT_EQ(Map.getNumBuckets(), NumBuckets);
+  }
+}
+
+TEST(StringMapCustomTest, BracketOperatorCtor) {
+  StringMap<CountCtorCopyAndMove> Map;
+  CountCtorCopyAndMove::Ctor = 0;
+  Map["abcd"];
+  EXPECT_EQ(1u, CountCtorCopyAndMove::Ctor);
+  // Test that operator[] does not create a value when it is already in the map
+  CountCtorCopyAndMove::Ctor = 0;
+  Map["abcd"];
+  EXPECT_EQ(0u, CountCtorCopyAndMove::Ctor);
+}
+
+namespace {
+struct NonMoveableNonCopyableType {
+  int Data = 0;
+  NonMoveableNonCopyableType() = default;
+  NonMoveableNonCopyableType(int Data) : Data(Data) {}
+  NonMoveableNonCopyableType(const NonMoveableNonCopyableType &) = delete;
+  NonMoveableNonCopyableType(NonMoveableNonCopyableType &&) = delete;
+};
+}
+
+// Test that we can "emplace" an element in the map without involving map/move
+TEST(StringMapCustomTest, EmplaceTest) {
+  StringMap<NonMoveableNonCopyableType> Map;
+  Map.try_emplace("abcd", 42);
+  EXPECT_EQ(1u, Map.count("abcd"));
+  EXPECT_EQ(42, Map["abcd"].Data);
+}
+
+// Test that StringMapEntryBase can handle size_t wide sizes.
+TEST(StringMapCustomTest, StringMapEntryBaseSize) {
+  size_t LargeValue;
+
+  // Test that the entry can represent max-unsigned.
+  if (sizeof(size_t) <= sizeof(unsigned))
+    LargeValue = std::numeric_limits<unsigned>::max();
+  else
+    LargeValue = std::numeric_limits<unsigned>::max() + 1ULL;
+  StringMapEntryBase LargeBase(LargeValue);
+  EXPECT_EQ(LargeValue, LargeBase.getKeyLength());
+
+  // Test that the entry can hold at least max size_t.
+  LargeValue = std::numeric_limits<size_t>::max();
+  StringMapEntryBase LargerBase(LargeValue);
+  LargeValue = std::numeric_limits<size_t>::max();
+  EXPECT_EQ(LargeValue, LargerBase.getKeyLength());
+}
+
+// Test that StringMapEntry can handle size_t wide sizes.
+TEST(StringMapCustomTest, StringMapEntrySize) {
+  size_t LargeValue;
+
+  // Test that the entry can represent max-unsigned.
+  if (sizeof(size_t) <= sizeof(unsigned))
+    LargeValue = std::numeric_limits<unsigned>::max();
+  else
+    LargeValue = std::numeric_limits<unsigned>::max() + 1ULL;
+  StringMapEntry<int> LargeEntry(LargeValue);
+  std::string_view Key = LargeEntry.getKey();
+  EXPECT_EQ(LargeValue, Key.size());
+
+  // Test that the entry can hold at least max size_t.
+  LargeValue = std::numeric_limits<size_t>::max();
+  StringMapEntry<int> LargerEntry(LargeValue);
+  Key = LargerEntry.getKey();
+  EXPECT_EQ(LargeValue, Key.size());
+}
+
+} // end anonymous namespace
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/SwapByteOrderTest.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/SwapByteOrderTest.cpp
new file mode 100644
index 0000000..abacef7
--- /dev/null
+++ b/third_party/allwpilib/wpiutil/src/test/native/cpp/llvm/SwapByteOrderTest.cpp
@@ -0,0 +1,210 @@
+//===- unittests/Support/SwapByteOrderTest.cpp - swap byte order test -----===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+
+#include "wpi/SwapByteOrder.h"
+#include "gtest/gtest.h"
+#include <cstdlib>
+#include <ctime>
+using namespace wpi;
+
+#undef max
+
+namespace {
+
+TEST(ByteSwap, Swap_32) {
+  EXPECT_EQ(0x44332211u, ByteSwap_32(0x11223344));
+  EXPECT_EQ(0xDDCCBBAAu, ByteSwap_32(0xAABBCCDD));
+}
+
+TEST(ByteSwap, Swap_64) {
+  EXPECT_EQ(0x8877665544332211ULL, ByteSwap_64(0x1122334455667788LL));
+  EXPECT_EQ(0x1100FFEEDDCCBBAAULL, ByteSwap_64(0xAABBCCDDEEFF0011LL));
+}
+
+// In these first two tests all of the original_uintx values are truncated
+// except for 64. We could avoid this, but there's really no point.
+
+TEST(getSwappedBytes, UnsignedRoundTrip) {
+  // The point of the bit twiddling of magic is to test with and without bits
+  // in every byte.
+  uint64_t value = 1;
+  for (std::size_t i = 0; i <= sizeof(value); ++i) {
+    uint8_t original_uint8 = static_cast<uint8_t>(value);
+    EXPECT_EQ(original_uint8,
+              sys::getSwappedBytes(sys::getSwappedBytes(original_uint8)));
+
+    uint16_t original_uint16 = static_cast<uint16_t>(value);
+    EXPECT_EQ(original_uint16,
+              sys::getSwappedBytes(sys::getSwappedBytes(original_uint16)));
+
+    uint32_t original_uint32 = static_cast<uint32_t>(value);
+    EXPECT_EQ(original_uint32,
+              sys::getSwappedBytes(sys::getSwappedBytes(original_uint32)));
+
+    uint64_t original_uint64 = static_cast<uint64_t>(value);
+    EXPECT_EQ(original_uint64,
+              sys::getSwappedBytes(sys::getSwappedBytes(original_uint64)));
+
+    value = (value << 8) | 0x55; // binary 0101 0101.
+  }
+}
+
+TEST(getSwappedBytes, SignedRoundTrip) {
+  // The point of the bit twiddling of magic is to test with and without bits
+  // in every byte.
+  uint64_t value = 1;
+  for (std::size_t i = 0; i <= sizeof(value); ++i) {
+    int8_t original_int8 = static_cast<int8_t>(value);
+    EXPECT_EQ(original_int8,
+              sys::getSwappedBytes(sys::getSwappedBytes(original_int8)));
+
+    int16_t original_int16 = static_cast<int16_t>(value);
+    EXPECT_EQ(original_int16,
+              sys::getSwappedBytes(sys::getSwappedBytes(original_int16)));
+
+    int32_t original_int32 = static_cast<int32_t>(value);
+    EXPECT_EQ(original_int32,
+              sys::getSwappedBytes(sys::getSwappedBytes(original_int32)));
+
+    int64_t original_int64 = static_cast<int64_t>(value);
+    EXPECT_EQ(original_int64,
+              sys::getSwappedBytes(sys::getSwappedBytes(original_int64)));
+
+    // Test other sign.
+    value *= -1;
+
+    original_int8 = static_cast<int8_t>(value);
+    EXPECT_EQ(original_int8,
+              sys::getSwappedBytes(sys::getSwappedBytes(original_int8)));
+
+    original_int16 = static_cast<int16_t>(value);
+    EXPECT_EQ(original_int16,
+              sys::getSwappedBytes(sys::getSwappedBytes(original_int16)));
+
+    original_int32 = static_cast<int32_t>(value);
+    EXPECT_EQ(original_int32,
+              sys::getSwappedBytes(sys::getSwappedBytes(original_int32)));
+
+    original_int64 = static_cast<int64_t>(value);
+    EXPECT_EQ(original_int64,
+              sys::getSwappedBytes(sys::getSwappedBytes(original_int64)));
+
+    // Return to normal sign and twiddle.
+    value *= -1;
+    value = (value << 8) | 0x55; // binary 0101 0101.
+  }
+}
+
+TEST(getSwappedBytes, uint8_t) {
+  EXPECT_EQ(uint8_t(0x11), sys::getSwappedBytes(uint8_t(0x11)));
+}
+
+TEST(getSwappedBytes, uint16_t) {
+  EXPECT_EQ(uint16_t(0x1122), sys::getSwappedBytes(uint16_t(0x2211)));
+}
+
+TEST(getSwappedBytes, uint32_t) {
+  EXPECT_EQ(uint32_t(0x11223344), sys::getSwappedBytes(uint32_t(0x44332211)));
+}
+
+TEST(getSwappedBytes, uint64_t) {
+  EXPECT_EQ(uint64_t(0x1122334455667788ULL),
+    sys::getSwappedBytes(uint64_t(0x8877665544332211ULL)));
+}
+
+TEST(getSwappedBytes, int8_t) {
+  EXPECT_EQ(int8_t(0x11), sys::getSwappedBytes(int8_t(0x11)));
+}
+
+TEST(getSwappedBytes, int16_t) {
+  EXPECT_EQ(int16_t(0x1122), sys::getSwappedBytes(int16_t(0x2211)));
+}
+
+TEST(getSwappedBytes, int32_t) {
+  EXPECT_EQ(int32_t(0x11223344), sys::getSwappedBytes(int32_t(0x44332211)));
+}
+
+TEST(getSwappedBytes, int64_t) {
+  EXPECT_EQ(int64_t(0x1122334455667788LL),
+    sys::getSwappedBytes(int64_t(0x8877665544332211LL)));
+}
+
+TEST(getSwappedBytes, float) {
+  EXPECT_EQ(1.79366203433576585078237386661e-43f, sys::getSwappedBytes(-0.0f));
+  // 0x11223344
+  EXPECT_EQ(7.1653228759765625e2f, sys::getSwappedBytes(1.2795344e-28f));
+}
+
+TEST(getSwappedBytes, double) {
+  EXPECT_EQ(6.32404026676795576546008054871e-322, sys::getSwappedBytes(-0.0));
+  // 0x1122334455667788
+  EXPECT_EQ(-7.08687663657301358331704585496e-268,
+    sys::getSwappedBytes(3.84141202447173065923064450234e-226));
+}
+
+TEST(swapByteOrder, uint8_t) {
+  uint8_t value = 0x11;
+  sys::swapByteOrder(value);
+  EXPECT_EQ(uint8_t(0x11), value);
+}
+
+TEST(swapByteOrder, uint16_t) {
+  uint16_t value = 0x2211;
+  sys::swapByteOrder(value);
+  EXPECT_EQ(uint16_t(0x1122), value);
+}
+
+TEST(swapByteOrder, uint32_t) {
+  uint32_t value = 0x44332211;
+  sys::swapByteOrder(value);
+  EXPECT_EQ(uint32_t(0x11223344), value);
+}
+
+TEST(swapByteOrder, uint64_t) {
+  uint64_t value = 0x8877665544332211ULL;
+  sys::swapByteOrder(value);
+  EXPECT_EQ(uint64_t(0x1122334455667788ULL), value);
+}
+
+TEST(swapByteOrder, int8_t) {
+  int8_t value = 0x11;
+  sys::swapByteOrder(value);
+  EXPECT_EQ(int8_t(0x11), value);
+}
+
+TEST(swapByteOrder, int16_t) {
+  int16_t value = 0x2211;
+  sys::swapByteOrder(value);
+  EXPECT_EQ(int16_t(0x1122), value);
+}
+
+TEST(swapByteOrder, int32_t) {
+  int32_t value = 0x44332211;
+  sys::swapByteOrder(value);
+  EXPECT_EQ(int32_t(0x11223344), value);
+}
+
+TEST(swapByteOrder, int64_t) {
+  int64_t value = 0x8877665544332211LL;
+  sys::swapByteOrder(value);
+  EXPECT_EQ(int64_t(0x1122334455667788LL), value);
+}
+
+TEST(swapByteOrder, float) {
+  float value = 7.1653228759765625e2f; // 0x44332211
+  sys::swapByteOrder(value);
+  EXPECT_EQ(1.2795344e-28f, value);
+}
+
+TEST(swapByteOrder, double) {
+  double value = -7.08687663657301358331704585496e-268; // 0x8877665544332211
+  sys::swapByteOrder(value);
+  EXPECT_EQ(3.84141202447173065923064450234e-226, value);
+}
+
+}
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/raw_uv_stream_test.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/raw_uv_stream_test.cpp
deleted file mode 100644
index 985fb8b..0000000
--- a/third_party/allwpilib/wpiutil/src/test/native/cpp/raw_uv_stream_test.cpp
+++ /dev/null
@@ -1,71 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/raw_uv_ostream.h"  // NOLINT(build/include_order)
-
-#include "gtest/gtest.h"
-
-namespace wpi {
-
-TEST(RawUvStreamTest, BasicWrite) {
-  SmallVector<uv::Buffer, 4> bufs;
-  raw_uv_ostream os(bufs, 1024);
-  os << "12";
-  os << "34";
-  ASSERT_EQ(bufs.size(), 1u);
-  ASSERT_EQ(bufs[0].len, 4u);
-  ASSERT_EQ(bufs[0].base[0], '1');
-  ASSERT_EQ(bufs[0].base[1], '2');
-  ASSERT_EQ(bufs[0].base[2], '3');
-  ASSERT_EQ(bufs[0].base[3], '4');
-
-  for (auto& buf : bufs) {
-    buf.Deallocate();
-  }
-}
-
-TEST(RawUvStreamTest, BoundaryWrite) {
-  SmallVector<uv::Buffer, 4> bufs;
-  raw_uv_ostream os(bufs, 4);
-  ASSERT_EQ(bufs.size(), 0u);
-  os << "12";
-  ASSERT_EQ(bufs.size(), 1u);
-  os << "34";
-  ASSERT_EQ(bufs.size(), 1u);
-  os << "56";
-  ASSERT_EQ(bufs.size(), 2u);
-
-  for (auto& buf : bufs) {
-    buf.Deallocate();
-  }
-}
-
-TEST(RawUvStreamTest, LargeWrite) {
-  SmallVector<uv::Buffer, 4> bufs;
-  raw_uv_ostream os(bufs, 4);
-  os << "123456";
-  ASSERT_EQ(bufs.size(), 2u);
-  ASSERT_EQ(bufs[1].len, 2u);
-  ASSERT_EQ(bufs[1].base[0], '5');
-
-  for (auto& buf : bufs) {
-    buf.Deallocate();
-  }
-}
-
-TEST(RawUvStreamTest, PrevDataWrite) {
-  SmallVector<uv::Buffer, 4> bufs;
-  bufs.emplace_back(uv::Buffer::Allocate(1024));
-  raw_uv_ostream os(bufs, 1024);
-  os << "1234";
-  ASSERT_EQ(bufs.size(), 2u);
-  ASSERT_EQ(bufs[0].len, 1024u);
-  ASSERT_EQ(bufs[1].len, 4u);
-
-  for (auto& buf : bufs) {
-    buf.Deallocate();
-  }
-}
-
-}  // namespace wpi
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/span/test_conversions.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/span/test_conversions.cpp
deleted file mode 100644
index fa111a7..0000000
--- a/third_party/allwpilib/wpiutil/src/test/native/cpp/span/test_conversions.cpp
+++ /dev/null
@@ -1,46 +0,0 @@
-#if __has_include(<span>)
-#include <span>
-#endif
-#include "wpi/span.h"
-
-#include "gtest/gtest.h"
-
-void func1(wpi::span<const int> x) {}
-#ifdef __cpp_lib_span
-void func2(std::span<const int> x) {}
-#endif
-
-void func4(wpi::span<int> x) {}
-#ifdef __cpp_lib_span
-void func5(std::span<int> x) {}
-#endif
-
-TEST(Span, ConvertStdSpan) {
-  func1(wpi::span<const int>{});
-  func1(wpi::span<int>{});
-#ifdef __cpp_lib_span
-  func1(std::span<const int>{});
-  func1(std::span<int>{});
-#endif
-
-#ifdef __cpp_lib_span
-  func2(wpi::span<const int>{});
-  func2(wpi::span<int>{});
-  func2(std::span<const int>{});
-  func2(std::span<int>{});
-#endif
-
-  //func4(wpi::span<const int>{});
-  func4(wpi::span<int>{});
-#ifdef __cpp_lib_span
-  //func4(std::span<const int>{});
-  func4(std::span<int>{});
-#endif
-
-#ifdef __cpp_lib_span
-  //func5(wpi::span<const int>{});
-  func5(wpi::span<int>{});
-  //func5(std::span<const int>{});
-  func5(std::span<int>{});
-#endif
-}
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/span/test_deduction_guides.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/span/test_deduction_guides.cpp
deleted file mode 100644
index 9851b5e..0000000
--- a/third_party/allwpilib/wpiutil/src/test/native/cpp/span/test_deduction_guides.cpp
+++ /dev/null
@@ -1,98 +0,0 @@
-
-#include "wpi/span.h"
-
-#include "gtest/gtest.h"
-
-#include <vector>
-
-using wpi::span;
-
-namespace {
-
-template <typename R1, typename R2>
-constexpr bool equal(R1&& r1, R2&& r2)
-{
-    auto first1 = std::begin(r1);
-    const auto last1 = std::end(r1);
-    auto first2 = std::begin(r2);
-    const auto last2 = std::end(r2);
-
-    while (first1 != last1 && first2 != last2) {
-        if (*first1 != *first2) {
-            return false;
-        }
-        ++first1;
-        ++first2;
-    }
-
-    return true;
-}
-
-constexpr bool test_raw_array()
-{
-    int arr[] = {1, 2, 3};
-    auto s = span{arr};
-    static_assert(std::is_same_v<decltype(s), span<int, 3>>);
-
-    return equal(arr, s);
-}
-
-constexpr bool test_const_raw_array()
-{
-    constexpr int arr[] = {1, 2, 3};
-    auto s = span{arr};
-    static_assert(std::is_same_v<decltype(s), span<const int, 3>>);
-
-    return equal(arr, s);
-}
-
-constexpr bool test_std_array()
-{
-    auto arr = std::array<int, 3>{1, 2, 3};
-    auto s = span{arr};
-    static_assert(std::is_same_v<decltype(s), span<int, 3>>);
-
-    return equal(arr, s);
-}
-
-constexpr bool test_const_std_array()
-{
-    const auto arr = std::array<int, 3>{1, 2, 3};
-    auto s = span{arr};
-    static_assert(std::is_same_v<decltype(s), span<const int, 3>>);
-
-    return equal(arr, s);
-}
-
-bool test_vec()
-{
-    auto arr = std::vector{1, 2, 3};
-    auto s = span{arr};
-    static_assert(std::is_same_v<decltype(s), span<int>>);
-
-    return equal(arr, s);
-}
-
-bool test_const_vec()
-{
-    const auto arr = std::vector{1, 2, 3};
-    auto s = span{arr};
-    static_assert(std::is_same_v<decltype(s), span<const int>>);
-
-    return equal(arr, s);
-}
-
-}
-
-TEST(Deduction, FromRawArrays)
-{
-    static_assert(test_raw_array());
-    static_assert(test_const_raw_array());
-    static_assert(test_std_array());
-    static_assert(test_const_std_array());
-
-    ASSERT_TRUE(test_std_array());
-    ASSERT_TRUE(test_const_std_array());
-    ASSERT_TRUE(test_vec());
-    ASSERT_TRUE(test_const_vec());
-}
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/span/test_span.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/span/test_span.cpp
deleted file mode 100644
index 7cecfd0..0000000
--- a/third_party/allwpilib/wpiutil/src/test/native/cpp/span/test_span.cpp
+++ /dev/null
@@ -1,663 +0,0 @@
-
-#include "wpi/span.h"
-
-#include <algorithm>
-#include <cassert>
-#include <deque>
-#include <initializer_list>
-#include <vector>
-
-#include "gtest/gtest.h"
-
-using wpi::span;
-
-struct base {};
-struct derived : base {};
-
-TEST(Span, DefaultConstruction)
-{
-    static_assert(std::is_nothrow_default_constructible<span<int>>::value, "");
-    static_assert(std::is_nothrow_default_constructible<span<int, 0>>::value,
-                  "");
-    static_assert(!std::is_default_constructible<span<int, 42>>::value, "");
-
-    //SECTION("dynamic size")
-    {
-        constexpr span<int> s{};
-        static_assert(s.size() == 0, "");
-        static_assert(s.data() == nullptr, "");
-        // This causes an ICE on MSVC
-#ifndef _MSC_VER
-        static_assert(s.begin() == s.end(), "");
-#else
-        ASSERT_EQ(s.begin(), s.end());
-#endif
-    }
-
-    //SECTION("fixed size")
-    {
-        constexpr span<int, 0> s{};
-        static_assert(s.size() == 0, "");
-        static_assert(s.data() == nullptr, "");
-#ifndef _MSC_VER
-        static_assert(s.begin() == s.end(), "");
-#else
-        ASSERT_EQ(s.begin(), s.end());
-#endif
-    }
-}
-
-TEST(Span, PointerLengthConstruction)
-{
-    static_assert(std::is_constructible<span<int>, int*, int>::value, "");
-    static_assert(std::is_constructible<span<const int>, int*, int>::value, "");
-    static_assert(
-        std::is_constructible<span<const int>, const int*, int>::value, "");
-
-    static_assert(std::is_constructible<span<int, 42>, int*, int>::value, "");
-    static_assert(std::is_constructible<span<const int, 42>, int*, int>::value,
-                  "");
-    static_assert(
-        std::is_constructible<span<const int, 42>, const int*, int>::value, "");
-
-    //SECTION("dynamic size")
-    {
-        int arr[] = {1, 2, 3};
-        span<int> s(arr, 3);
-
-        ASSERT_EQ(s.size(), 3u);
-        ASSERT_EQ(s.data(), arr);
-        ASSERT_EQ(s.begin(), std::begin(arr));
-        ASSERT_EQ(s.end(), std::end(arr));
-    }
-
-    //SECTION("fixed size")
-    {
-        int arr[] = {1, 2, 3};
-        span<int, 3> s(arr, 3);
-
-        ASSERT_EQ(s.size(), 3u);
-        ASSERT_EQ(s.data(), arr);
-        ASSERT_EQ(s.begin(), std::begin(arr));
-        ASSERT_EQ(s.end(), std::end(arr));
-    }
-}
-
-TEST(Span, PointerPointerConstruction)
-{
-    static_assert(std::is_constructible<span<int>, int*, int*>::value, "");
-    static_assert(!std::is_constructible<span<int>, float*, float*>::value, "");
-    static_assert(std::is_constructible<span<int, 42>, int*, int*>::value, "");
-    static_assert(!std::is_constructible<span<int, 42>, float*, float*>::value,
-                  "");
-
-    //SECTION("dynamic size")
-    {
-        int arr[] = {1, 2, 3};
-        span<int> s{arr, arr + 3};
-        ASSERT_EQ(s.size(), 3u);
-        ASSERT_EQ(s.data(), arr);
-        ASSERT_EQ(s.begin(), std::begin(arr));
-        ASSERT_EQ(s.end(), std::end(arr));
-    }
-
-    //SECTION("fixed size")
-    {
-        int arr[] = {1, 2, 3};
-        span<int, 3> s{arr, arr + 3};
-        ASSERT_EQ(s.size(), 3u);
-        ASSERT_EQ(s.data(), arr);
-        ASSERT_EQ(s.begin(), std::begin(arr));
-        ASSERT_EQ(s.end(), std::end(arr));
-    }
-}
-
-TEST(Span, CArrayConstruction)
-{
-    using int_array_t = int[3];
-    using float_array_t = float[3];
-
-    static_assert(std::is_nothrow_constructible<span<int>, int_array_t&>::value,
-                  "");
-    static_assert(!std::is_constructible<span<int>, int_array_t const&>::value,
-                  "");
-    static_assert(!std::is_constructible<span<int>, float_array_t>::value, "");
-
-    static_assert(
-        std::is_nothrow_constructible<span<const int>, int_array_t&>::value,
-        "");
-    static_assert(std::is_nothrow_constructible<span<const int>,
-                                                int_array_t const&>::value,
-                  "");
-    static_assert(!std::is_constructible<span<const int>, float_array_t>::value,
-                  "");
-
-    static_assert(
-        std::is_nothrow_constructible<span<int, 3>, int_array_t&>::value, "");
-    static_assert(
-        !std::is_constructible<span<int, 3>, int_array_t const&>::value, "");
-    static_assert(!std::is_constructible<span<int, 3>, float_array_t&>::value,
-                  "");
-
-    static_assert(
-        std::is_nothrow_constructible<span<const int, 3>, int_array_t&>::value,
-        "");
-    static_assert(std::is_nothrow_constructible<span<const int, 3>,
-                                                int_array_t const&>::value,
-                  "");
-    static_assert(
-        !std::is_constructible<span<const int, 3>, float_array_t>::value, "");
-
-    static_assert(!std::is_constructible<span<int, 42>, int_array_t&>::value,
-                  "");
-    static_assert(
-        !std::is_constructible<span<int, 42>, int_array_t const&>::value, "");
-    static_assert(!std::is_constructible<span<int, 42>, float_array_t&>::value,
-                  "");
-
-    static_assert(
-        !std::is_constructible<span<const int, 42>, int_array_t&>::value, "");
-    static_assert(
-        !std::is_constructible<span<const int, 42>, int_array_t const&>::value,
-        "");
-    static_assert(
-        !std::is_constructible<span<const int, 42>, float_array_t&>::value, "");
-
-    //SECTION("non-const, dynamic size")
-    {
-        int arr[] = {1, 2, 3};
-        span<int> s{arr};
-        ASSERT_EQ(s.size(), 3u);
-        ASSERT_EQ(s.data(), arr);
-        ASSERT_EQ(s.begin(), std::begin(arr));
-        ASSERT_EQ(s.end(), std::end(arr));
-    }
-
-    //SECTION("const, dynamic size")
-    {
-        int arr[] = {1, 2, 3};
-        span<int const> s{arr};
-        ASSERT_EQ(s.size(), 3u);
-        ASSERT_EQ(s.data(), arr);
-        ASSERT_EQ(s.begin(), std::begin(arr));
-        ASSERT_EQ(s.end(), std::end(arr));
-    }
-
-    //SECTION("non-const, static size")
-    {
-        int arr[] = {1, 2, 3};
-        span<int, 3> s{arr};
-        ASSERT_EQ(s.size(), 3u);
-        ASSERT_EQ(s.data(), arr);
-        ASSERT_EQ(s.begin(), std::begin(arr));
-        ASSERT_EQ(s.end(), std::end(arr));
-    }
-
-    //SECTION("const, dynamic size")
-    {
-        int arr[] = {1, 2, 3};
-        span<int const, 3> s{arr};
-        ASSERT_EQ(s.size(), 3u);
-        ASSERT_EQ(s.data(), arr);
-        ASSERT_EQ(s.begin(), std::begin(arr));
-        ASSERT_EQ(s.end(), std::end(arr));
-    }
-}
-
-TEST(Span, StdArrayConstruction)
-{
-    using int_array_t = std::array<int, 3>;
-    using float_array_t = std::array<float, 3>;
-    using zero_array_t = std::array<int, 0>;
-
-    static_assert(std::is_nothrow_constructible<span<int>, int_array_t&>::value,
-                  "");
-    static_assert(!std::is_constructible<span<int>, int_array_t const&>::value,
-                  "");
-    static_assert(!std::is_constructible<span<int>, float_array_t>::value, "");
-
-    static_assert(
-        std::is_nothrow_constructible<span<const int>, int_array_t&>::value,
-        "");
-    static_assert(std::is_nothrow_constructible<span<const int>,
-                                                int_array_t const&>::value,
-                  "");
-    static_assert(
-        !std::is_constructible<span<const int>, float_array_t const&>::value,
-        "");
-
-    static_assert(
-        std::is_nothrow_constructible<span<int, 3>, int_array_t&>::value, "");
-    static_assert(
-        !std::is_constructible<span<int, 3>, int_array_t const&>::value, "");
-    static_assert(!std::is_constructible<span<int, 3>, float_array_t>::value,
-                  "");
-
-    static_assert(
-        std::is_nothrow_constructible<span<const int, 3>, int_array_t&>::value,
-        "");
-    static_assert(std::is_nothrow_constructible<span<const int, 3>,
-                                                int_array_t const&>::value,
-                  "");
-    static_assert(
-        !std::is_constructible<span<const int, 3>, float_array_t const&>::value,
-        "");
-
-    static_assert(!std::is_constructible<span<int, 42>, int_array_t&>::value,
-                  "");
-    static_assert(
-        !std::is_constructible<span<int, 42>, int_array_t const&>::value, "");
-    static_assert(
-        !std::is_constructible<span<int, 42>, float_array_t const&>::value, "");
-
-    static_assert(
-        !std::is_constructible<span<const int, 42>, int_array_t&>::value, "");
-    static_assert(
-        !std::is_constructible<span<const int, 42>, int_array_t const&>::value,
-        "");
-    static_assert(
-        !std::is_constructible<span<const int, 42>, float_array_t&>::value, "");
-
-    static_assert(std::is_constructible<span<int>, zero_array_t&>::value, "");
-    static_assert(!std::is_constructible<span<int>, const zero_array_t&>::value,
-                  "");
-    static_assert(std::is_constructible<span<const int>, zero_array_t&>::value,
-                  "");
-    static_assert(
-        std::is_constructible<span<const int>, const zero_array_t&>::value, "");
-
-    static_assert(std::is_constructible<span<int, 0>, zero_array_t&>::value,
-                  "");
-    static_assert(
-        !std::is_constructible<span<int, 0>, const zero_array_t&>::value, "");
-    static_assert(
-        std::is_constructible<span<const int, 0>, zero_array_t&>::value, "");
-    static_assert(
-        std::is_constructible<span<const int, 0>, const zero_array_t&>::value,
-        "");
-
-    //SECTION("non-const, dynamic size")
-    {
-        int_array_t arr = {1, 2, 3};
-        span<int> s{arr};
-        ASSERT_EQ(s.size(), 3u);
-        ASSERT_EQ(s.data(), arr.data());
-        ASSERT_EQ(s.begin(), arr.data());
-        ASSERT_EQ(s.end(), arr.data() + 3);
-    }
-
-    //SECTION("const, dynamic size")
-    {
-        int_array_t arr = {1, 2, 3};
-        span<int const> s{arr};
-        ASSERT_EQ(s.size(), 3u);
-        ASSERT_EQ(s.data(), arr.data());
-        ASSERT_EQ(s.begin(), arr.data());
-        ASSERT_EQ(s.end(), arr.data() + 3);
-    }
-
-    //SECTION("non-const, static size")
-    {
-        int_array_t arr = {1, 2, 3};
-        span<int, 3> s{arr};
-        ASSERT_EQ(s.size(), 3u);
-        ASSERT_EQ(s.data(), arr.data());
-        ASSERT_EQ(s.begin(), arr.data());
-        ASSERT_EQ(s.end(), arr.data() + 3);
-    }
-
-    //SECTION("const, dynamic size")
-    {
-        int_array_t arr = {1, 2, 3};
-        span<int const, 3> s{arr};
-        ASSERT_EQ(s.size(), 3u);
-        ASSERT_EQ(s.data(), arr.data());
-        ASSERT_EQ(s.begin(), arr.data());
-        ASSERT_EQ(s.end(), arr.data() + 3);
-    }
-}
-
-TEST(Span, ConstructionFromOtherContainers)
-{
-    using vec_t = std::vector<int>;
-    using deque_t = std::deque<int>;
-
-    static_assert(std::is_constructible<span<int>, vec_t&>::value, "");
-    static_assert(!std::is_constructible<span<int>, const vec_t&>::value, "");
-    static_assert(!std::is_constructible<span<int>, const deque_t&>::value, "");
-
-    static_assert(std::is_constructible<span<const int>, vec_t&>::value, "");
-    static_assert(std::is_constructible<span<const int>, const vec_t&>::value,
-                  "");
-    static_assert(
-        !std::is_constructible<span<const int>, const deque_t&>::value, "");
-
-    static_assert(!std::is_constructible<span<int, 3>, vec_t&>::value, "");
-    static_assert(!std::is_constructible<span<int, 3>, const vec_t&>::value,
-                  "");
-    static_assert(!std::is_constructible<span<int, 3>, const deque_t&>::value,
-                  "");
-
-    static_assert(!std::is_constructible<span<const int, 3>, vec_t&>::value, "");
-    static_assert(
-        !std::is_constructible<span<const int, 3>, const vec_t&>::value, "");
-    static_assert(
-        !std::is_constructible<span<const int, 3>, const deque_t&>::value, "");
-
-    // vector<bool> is not contiguous and cannot be converted to span<bool>
-    // Regression test for https://github.com/tcbrindle/span/issues/24
-    static_assert(
-        !std::is_constructible<span<bool>, std::vector<bool>&>::value, "");
-    static_assert(!std::is_constructible<span<const bool>,
-                                         const std::vector<bool>&>::value, "");
-
-    //SECTION("non-const, dynamic size")
-    {
-        vec_t arr = {1, 2, 3};
-        span<int> s{arr};
-        ASSERT_EQ(s.size(), 3u);
-        ASSERT_EQ(s.data(), arr.data());
-        ASSERT_EQ(s.begin(), arr.data());
-        ASSERT_EQ(s.end(), arr.data() + 3);
-    }
-
-    //SECTION("const, dynamic size")
-    {
-        vec_t arr = {1, 2, 3};
-        span<int const> s{arr};
-        ASSERT_EQ(s.size(), 3u);
-        ASSERT_EQ(s.data(), arr.data());
-        ASSERT_EQ(s.begin(), arr.data());
-        ASSERT_EQ(s.end(), arr.data() + 3);
-    }
-
-    //SECTION("non-const, static size")
-    {
-        std::array<int, 3> arr = {1, 2, 3};
-        span<int, 3> s{arr};
-        ASSERT_EQ(s.size(), 3u);
-        ASSERT_EQ(s.data(), arr.data());
-        ASSERT_EQ(s.begin(), arr.data());
-        ASSERT_EQ(s.end(), arr.data() + 3);
-    }
-
-    //SECTION("const, dynamic size")
-    {
-        std::array<int, 3> arr = {1, 2, 3};
-        span<int const, 3> s{arr};
-        ASSERT_EQ(s.size(), 3u);
-        ASSERT_EQ(s.data(), arr.data());
-        ASSERT_EQ(s.begin(), arr.data());
-        ASSERT_EQ(s.end(), arr.data() + 3);
-    }
-}
-
-TEST(Span, ConstructionFromSpansOfDifferentSize)
-{
-    using zero_span = span<int, 0>;
-    using zero_const_span = span<const int, 0>;
-    using big_span = span<int, 1000000>;
-    using big_const_span = span<const int, 1000000>;
-    using dynamic_span = span<int>;
-    using dynamic_const_span = span<const int>;
-
-    static_assert(std::is_trivially_copyable<zero_span>::value, "");
-    static_assert(std::is_trivially_move_constructible<zero_span>::value, "");
-    static_assert(!std::is_constructible<zero_span, zero_const_span>::value,
-                  "");
-    static_assert(!std::is_constructible<zero_span, big_span>::value, "");
-    static_assert(!std::is_constructible<zero_span, big_const_span>::value, "");
-    static_assert(!std::is_constructible<zero_span, dynamic_span>::value, "");
-    static_assert(!std::is_constructible<zero_span, dynamic_const_span>::value,
-                  "");
-
-    static_assert(
-        std::is_nothrow_constructible<zero_const_span, zero_span>::value, "");
-    static_assert(std::is_trivially_copyable<zero_const_span>::value, "");
-    static_assert(std::is_trivially_move_constructible<zero_const_span>::value,
-                  "");
-    static_assert(!std::is_constructible<zero_const_span, big_span>::value, "");
-    static_assert(
-        !std::is_constructible<zero_const_span, big_const_span>::value, "");
-    static_assert(!std::is_constructible<zero_const_span, dynamic_span>::value,
-                  "");
-    static_assert(
-        !std::is_constructible<zero_const_span, dynamic_const_span>::value, "");
-
-    static_assert(!std::is_constructible<big_span, zero_span>::value, "");
-    static_assert(!std::is_constructible<big_span, zero_const_span>::value, "");
-    static_assert(std::is_trivially_copyable<big_span>::value, "");
-    static_assert(std::is_trivially_move_constructible<big_span>::value, "");
-    static_assert(!std::is_constructible<big_span, big_const_span>::value, "");
-    static_assert(!std::is_constructible<big_span, dynamic_span>::value, "");
-    static_assert(!std::is_constructible<big_span, dynamic_const_span>::value,
-                  "");
-
-    static_assert(!std::is_constructible<big_const_span, zero_span>::value, "");
-    static_assert(
-        !std::is_constructible<big_const_span, zero_const_span>::value, "");
-    static_assert(std::is_trivially_copyable<big_const_span>::value, "");
-    static_assert(std::is_trivially_move_constructible<big_const_span>::value,
-                  "");
-    static_assert(
-        std::is_nothrow_constructible<big_const_span, big_span>::value, "");
-    static_assert(!std::is_constructible<big_const_span, dynamic_span>::value,
-                  "");
-    static_assert(
-        !std::is_constructible<big_const_span, dynamic_const_span>::value, "");
-
-    static_assert(std::is_nothrow_constructible<dynamic_span, zero_span>::value,
-                  "");
-    static_assert(!std::is_constructible<dynamic_span, zero_const_span>::value,
-                  "");
-    static_assert(std::is_nothrow_constructible<dynamic_span, big_span>::value,
-                  "");
-    static_assert(!std::is_constructible<dynamic_span, big_const_span>::value,
-                  "");
-    static_assert(std::is_trivially_copyable<dynamic_span>::value, "");
-    static_assert(std::is_trivially_move_constructible<dynamic_span>::value,
-                  "");
-    static_assert(
-        !std::is_constructible<dynamic_span, dynamic_const_span>::value, "");
-
-    static_assert(
-        std::is_nothrow_constructible<dynamic_const_span, zero_span>::value,
-        "");
-    static_assert(std::is_nothrow_constructible<dynamic_const_span,
-                                                zero_const_span>::value,
-                  "");
-    static_assert(
-        std::is_nothrow_constructible<dynamic_const_span, big_span>::value, "");
-    static_assert(std::is_nothrow_constructible<dynamic_const_span,
-                                                big_const_span>::value,
-                  "");
-    static_assert(
-        std::is_nothrow_constructible<dynamic_const_span, dynamic_span>::value,
-        "");
-    static_assert(std::is_trivially_copyable<dynamic_const_span>::value, "");
-    static_assert(
-        std::is_trivially_move_constructible<dynamic_const_span>::value, "");
-
-    constexpr zero_const_span s0{};
-    constexpr dynamic_const_span d{s0};
-
-    static_assert(d.size() == 0, "");
-    static_assert(d.data() == nullptr, "");
-#ifndef _MSC_VER
-    static_assert(d.begin() == d.end(), "");
-#else
-    ASSERT_EQ(d.begin(), d.end());
-#endif
-}
-
-TEST(Span, MemberSubviewOperations)
-{
-    //SECTION("first<N>")
-    {
-        int arr[] = {1, 2, 3, 4, 5};
-        span<int, 5> s{arr};
-        auto f = s.first<3>();
-
-        static_assert(std::is_same<decltype(f), span<int, 3>>::value, "");
-        ASSERT_EQ(f.size(), 3u);
-        ASSERT_EQ(f.data(), arr);
-        ASSERT_EQ(f.begin(), arr);
-        ASSERT_EQ(f.end(), arr + 3);
-    }
-
-    //SECTION("last<N>")
-    {
-        int arr[] = {1, 2, 3, 4, 5};
-        span<int, 5> s{arr};
-        auto l = s.last<3>();
-
-        static_assert(std::is_same<decltype(l), span<int, 3>>::value, "");
-        ASSERT_EQ(l.size(), 3u);
-        ASSERT_EQ(l.data(), arr + 2);
-        ASSERT_EQ(l.begin(), arr + 2);
-        ASSERT_EQ(l.end(), std::end(arr));
-    }
-
-    //SECTION("subspan<N>")
-    {
-        int arr[] = {1, 2, 3, 4, 5};
-        span<int, 5> s{arr};
-        auto ss = s.subspan<1, 2>();
-
-        static_assert(std::is_same<decltype(ss), span<int, 2>>::value, "");
-        ASSERT_EQ(ss.size(), 2u);
-        ASSERT_EQ(ss.data(), arr + 1);
-        ASSERT_EQ(ss.begin(), arr + 1);
-        ASSERT_EQ(ss.end(), arr + 1 + 2);
-    }
-
-    //SECTION("first(n)")
-    {
-        int arr[] = {1, 2, 3, 4, 5};
-        span<int, 5> s{arr};
-        auto f = s.first(3);
-
-        static_assert(std::is_same<decltype(f), span<int>>::value, "");
-        ASSERT_EQ(f.size(), 3u);
-        ASSERT_EQ(f.data(), arr);
-        ASSERT_EQ(f.begin(), arr);
-        ASSERT_EQ(f.end(), arr + 3);
-    }
-
-    //SECTION("last(n)")
-    {
-        int arr[] = {1, 2, 3, 4, 5};
-        span<int, 5> s{arr};
-        auto l = s.last(3);
-
-        static_assert(std::is_same<decltype(l), span<int>>::value, "");
-        ASSERT_EQ(l.size(), 3u);
-        ASSERT_EQ(l.data(), arr + 2);
-        ASSERT_EQ(l.begin(), arr + 2);
-        ASSERT_EQ(l.end(), std::end(arr));
-    }
-
-    //SECTION("subspan(n)")
-    {
-        int arr[] = {1, 2, 3, 4, 5};
-        span<int, 5> s{arr};
-        auto ss = s.subspan(1, 2);
-
-        static_assert(std::is_same<decltype(ss), span<int>>::value, "");
-        ASSERT_EQ(ss.size(), 2u);
-        ASSERT_EQ(ss.data(), arr + 1);
-        ASSERT_EQ(ss.begin(), arr + 1);
-        ASSERT_EQ(ss.end(), arr + 1 + 2);
-    }
-
-    // TODO: Test all the dynamic subspan possibilities
-}
-
-TEST(Span, Observers)
-{
-    // We already use this everywhere, but whatever
-    constexpr span<int, 0> empty{};
-    static_assert(empty.size() == 0, "");
-    static_assert(empty.empty(), "");
-
-    constexpr int arr[] = {1, 2, 3};
-    static_assert(span<const int>{arr}.size() == 3, "");
-    static_assert(!span<const int>{arr}.empty(), "");
-}
-
-TEST(Span, ElementAccess)
-{
-    constexpr int arr[] = {1, 2, 3};
-    span<const int> s{arr};
-
-    ASSERT_EQ(s[0], arr[0]);
-    ASSERT_EQ(s[1], arr[1]);
-    ASSERT_EQ(s[2], arr[2]);
-}
-
-TEST(Span, IteratorSupport)
-{
-    {
-        std::vector<int> vec;
-        span<int> s{vec};
-        std::sort(s.begin(), s.end());
-        ASSERT_TRUE(std::is_sorted(vec.cbegin(), vec.cend()));
-    }
-
-    {
-        const std::vector<int> vec{1, 2, 3};
-        span<const int> s{vec};
-        ASSERT_TRUE(std::equal(s.rbegin(), s.rend(), vec.crbegin()));
-    }
-}
-
-TEST(Span, MakeSpan)
-{
-    {
-        int arr[3] = {1, 2, 3};
-        auto s = wpi::span(arr);
-        static_assert(std::is_same<decltype(s), span<int, 3>>::value, "");
-        ASSERT_EQ(s.data(), arr);
-        ASSERT_EQ(s.size(), 3u);
-    }
-
-    {
-        const int arr[3] = {1, 2, 3};
-        auto s = wpi::span(arr);
-        static_assert(std::is_same<decltype(s), span<const int, 3>>::value, "");
-        ASSERT_EQ(s.data(), arr);
-        ASSERT_EQ(s.size(), 3u);
-    }
-
-    {
-        std::array<int, 3> arr = {1, 2, 3};
-        auto s = wpi::span(arr);
-        static_assert(std::is_same<decltype(s), span<int, 3>>::value, "");
-        ASSERT_EQ(s.data(), arr.data());
-        ASSERT_EQ(s.size(), arr.size());
-    }
-
-    {
-        const std::array<int, 3> arr = {1, 2, 3};
-        auto s = wpi::span(arr);
-        static_assert(std::is_same<decltype(s), span<const int, 3>>::value, "");
-        ASSERT_EQ(s.data(), arr.data());
-        ASSERT_EQ(s.size(), 3u);
-    }
-
-    {
-        std::vector<int> arr = {1, 2, 3};
-        auto s = wpi::span(arr);
-        static_assert(std::is_same<decltype(s), span<int>>::value, "");
-        ASSERT_EQ(s.data(), arr.data());
-        ASSERT_EQ(s.size(), arr.size());
-    }
-
-    {
-        const std::vector<int> arr = {1, 2, 3};
-        auto s = wpi::span(arr);
-        static_assert(std::is_same<decltype(s), span<const int>>::value, "");
-        ASSERT_EQ(s.data(), arr.data());
-        ASSERT_EQ(s.size(), arr.size());
-    }
-}
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/span/test_structured_bindings.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/span/test_structured_bindings.cpp
deleted file mode 100644
index 5ce2969..0000000
--- a/third_party/allwpilib/wpiutil/src/test/native/cpp/span/test_structured_bindings.cpp
+++ /dev/null
@@ -1,30 +0,0 @@
-
-#include "wpi/span.h"
-
-#include "gtest/gtest.h"
-
-using static_span_t = wpi::span<int, 3>;
-using dynamic_span_t = wpi::span<int>;
-
-static_assert(std::tuple_size_v<static_span_t> == static_span_t::extent);
-static_assert(!wpi::detail::is_complete<std::tuple_size<dynamic_span_t>>::value);
-
-TEST(StructuredBindings, Test)
-{
-    // C++, why you no let me do constexpr structured bindings?
-
-    int arr[] = {1, 2, 3};
-
-    auto& [a1, a2, a3] = arr;
-    auto&& [s1, s2, s3] = wpi::span(arr);
-
-    ASSERT_EQ(a1, s1);
-    ASSERT_EQ(a2, s2);
-    ASSERT_EQ(a3, s3);
-
-    a1 = 99;
-    ASSERT_EQ(s1, 99);
-
-    s2 = 100;
-    ASSERT_EQ(a2, 100);
-}
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/uv/UvAsyncFunctionTest.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/uv/UvAsyncFunctionTest.cpp
deleted file mode 100644
index 8407935..0000000
--- a/third_party/allwpilib/wpiutil/src/test/native/cpp/uv/UvAsyncFunctionTest.cpp
+++ /dev/null
@@ -1,264 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/uv/AsyncFunction.h"  // NOLINT(build/include_order)
-
-#include "gtest/gtest.h"  // NOLINT(build/include_order)
-
-#include <thread>
-
-#include "wpi/uv/Loop.h"
-#include "wpi/uv/Prepare.h"
-
-namespace wpi::uv {
-
-TEST(UvAsyncFunctionTest, Basic) {
-  int prepare_cb_called = 0;
-  int async_cb_called[2] = {0, 0};
-  int close_cb_called = 0;
-
-  std::thread theThread;
-
-  auto loop = Loop::Create();
-  auto async = AsyncFunction<int(int)>::Create(loop);
-  auto prepare = Prepare::Create(loop);
-
-  loop->error.connect([](Error) { FAIL(); });
-
-  prepare->error.connect([](Error) { FAIL(); });
-  prepare->prepare.connect([&] {
-    if (prepare_cb_called++) {
-      return;
-    }
-    theThread = std::thread([&] {
-      auto call0 = async->Call(0);
-      auto call1 = async->Call(1);
-      ASSERT_EQ(call0.get(), 1);
-      ASSERT_EQ(call1.get(), 2);
-    });
-  });
-  prepare->Start();
-
-  async->error.connect([](Error) { FAIL(); });
-  async->closed.connect([&] { close_cb_called++; });
-  async->wakeup = [&](promise<int> out, int v) {
-    ++async_cb_called[v];
-    if (v == 1) {
-      async->Close();
-      prepare->Close();
-    }
-    out.set_value(v + 1);
-  };
-
-  loop->Run();
-
-  ASSERT_EQ(async_cb_called[0], 1);
-  ASSERT_EQ(async_cb_called[1], 1);
-  ASSERT_EQ(close_cb_called, 1);
-
-  if (theThread.joinable()) {
-    theThread.join();
-  }
-}
-
-TEST(UvAsyncFunctionTest, Ref) {
-  int prepare_cb_called = 0;
-  int val = 0;
-
-  std::thread theThread;
-
-  auto loop = Loop::Create();
-  auto async = AsyncFunction<int(int, int&)>::Create(loop);
-  auto prepare = Prepare::Create(loop);
-
-  prepare->prepare.connect([&] {
-    if (prepare_cb_called++) {
-      return;
-    }
-    theThread = std::thread([&] { ASSERT_EQ(async->Call(1, val).get(), 2); });
-  });
-  prepare->Start();
-
-  async->wakeup = [&](promise<int> out, int v, int& r) {
-    r = v;
-    async->Close();
-    prepare->Close();
-    out.set_value(v + 1);
-  };
-
-  loop->Run();
-
-  ASSERT_EQ(val, 1);
-
-  if (theThread.joinable()) {
-    theThread.join();
-  }
-}
-
-TEST(UvAsyncFunctionTest, Movable) {
-  int prepare_cb_called = 0;
-
-  std::thread theThread;
-
-  auto loop = Loop::Create();
-  auto async =
-      AsyncFunction<std::unique_ptr<int>(std::unique_ptr<int>)>::Create(loop);
-  auto prepare = Prepare::Create(loop);
-
-  prepare->prepare.connect([&] {
-    if (prepare_cb_called++) {
-      return;
-    }
-    theThread = std::thread([&] {
-      auto val = std::make_unique<int>(1);
-      auto val2 = async->Call(std::move(val)).get();
-      ASSERT_NE(val2, nullptr);
-      ASSERT_EQ(*val2, 1);
-    });
-  });
-  prepare->Start();
-
-  async->wakeup = [&](promise<std::unique_ptr<int>> out,
-                      std::unique_ptr<int> v) {
-    async->Close();
-    prepare->Close();
-    out.set_value(std::move(v));
-  };
-
-  loop->Run();
-
-  if (theThread.joinable()) {
-    theThread.join();
-  }
-}
-
-TEST(UvAsyncFunctionTest, CallIgnoreResult) {
-  int prepare_cb_called = 0;
-
-  std::thread theThread;
-
-  auto loop = Loop::Create();
-  auto async =
-      AsyncFunction<std::unique_ptr<int>(std::unique_ptr<int>)>::Create(loop);
-  auto prepare = Prepare::Create(loop);
-
-  prepare->prepare.connect([&] {
-    if (prepare_cb_called++) {
-      return;
-    }
-    theThread = std::thread([&] { async->Call(std::make_unique<int>(1)); });
-  });
-  prepare->Start();
-
-  async->wakeup = [&](promise<std::unique_ptr<int>> out,
-                      std::unique_ptr<int> v) {
-    async->Close();
-    prepare->Close();
-    out.set_value(std::move(v));
-  };
-
-  loop->Run();
-
-  if (theThread.joinable()) {
-    theThread.join();
-  }
-}
-
-TEST(UvAsyncFunctionTest, VoidCall) {
-  int prepare_cb_called = 0;
-
-  std::thread theThread;
-
-  auto loop = Loop::Create();
-  auto async = AsyncFunction<void()>::Create(loop);
-  auto prepare = Prepare::Create(loop);
-
-  prepare->prepare.connect([&] {
-    if (prepare_cb_called++) {
-      return;
-    }
-    theThread = std::thread([&] { async->Call(); });
-  });
-  prepare->Start();
-
-  async->wakeup = [&](promise<void> out) {
-    async->Close();
-    prepare->Close();
-    out.set_value();
-  };
-
-  loop->Run();
-
-  if (theThread.joinable()) {
-    theThread.join();
-  }
-}
-
-TEST(UvAsyncFunctionTest, WaitFor) {
-  int prepare_cb_called = 0;
-
-  std::thread theThread;
-
-  auto loop = Loop::Create();
-  auto async = AsyncFunction<int()>::Create(loop);
-  auto prepare = Prepare::Create(loop);
-
-  prepare->prepare.connect([&] {
-    if (prepare_cb_called++) {
-      return;
-    }
-    theThread = std::thread([&] {
-      ASSERT_FALSE(async->Call().wait_for(std::chrono::milliseconds(10)));
-    });
-  });
-  prepare->Start();
-
-  async->wakeup = [&](promise<int> out) {
-    async->Close();
-    prepare->Close();
-    std::this_thread::sleep_for(std::chrono::milliseconds(100));
-    out.set_value(1);
-  };
-
-  loop->Run();
-
-  if (theThread.joinable()) {
-    theThread.join();
-  }
-}
-
-TEST(UvAsyncFunctionTest, VoidWaitFor) {
-  int prepare_cb_called = 0;
-
-  std::thread theThread;
-
-  auto loop = Loop::Create();
-  auto async = AsyncFunction<void()>::Create(loop);
-  auto prepare = Prepare::Create(loop);
-
-  prepare->prepare.connect([&] {
-    if (prepare_cb_called++) {
-      return;
-    }
-    theThread = std::thread([&] {
-      ASSERT_FALSE(async->Call().wait_for(std::chrono::milliseconds(10)));
-    });
-  });
-  prepare->Start();
-
-  async->wakeup = [&](promise<void> out) {
-    async->Close();
-    prepare->Close();
-    std::this_thread::sleep_for(std::chrono::milliseconds(100));
-    out.set_value();
-  };
-
-  loop->Run();
-
-  if (theThread.joinable()) {
-    theThread.join();
-  }
-}
-
-}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/uv/UvAsyncTest.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/uv/UvAsyncTest.cpp
deleted file mode 100644
index 5561f1e..0000000
--- a/third_party/allwpilib/wpiutil/src/test/native/cpp/uv/UvAsyncTest.cpp
+++ /dev/null
@@ -1,185 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include "wpi/uv/Async.h"  // NOLINT(build/include_order)
-
-#include "gtest/gtest.h"  // NOLINT(build/include_order)
-
-#include <atomic>
-#include <thread>
-
-#include "wpi/mutex.h"
-#include "wpi/uv/Loop.h"
-#include "wpi/uv/Prepare.h"
-
-namespace wpi::uv {
-
-TEST(UvAsyncTest, CallbackOnly) {
-  std::atomic_int async_cb_called{0};
-  int prepare_cb_called = 0;
-  int close_cb_called = 0;
-
-  wpi::mutex mutex;
-  mutex.lock();
-
-  std::thread theThread;
-
-  auto loop = Loop::Create();
-  auto async = Async<>::Create(loop);
-  auto prepare = Prepare::Create(loop);
-
-  loop->error.connect([](Error) { FAIL(); });
-
-  prepare->error.connect([](Error) { FAIL(); });
-  prepare->closed.connect([&] { close_cb_called++; });
-  prepare->prepare.connect([&] {
-    if (prepare_cb_called++) {
-      return;
-    }
-    theThread = std::thread([&] {
-      for (;;) {
-        mutex.lock();
-        int n = async_cb_called;
-        mutex.unlock();
-
-        if (n == 3) {
-          break;
-        }
-
-        async->Send();
-
-        std::this_thread::yield();
-      }
-    });
-    mutex.unlock();
-  });
-  prepare->Start();
-
-  async->error.connect([](Error) { FAIL(); });
-  async->closed.connect([&] { close_cb_called++; });
-  async->wakeup.connect([&] {
-    mutex.lock();
-    int n = ++async_cb_called;
-    mutex.unlock();
-
-    if (n == 3) {
-      async->Close();
-      prepare->Close();
-    }
-  });
-
-  loop->Run();
-
-  ASSERT_GT(prepare_cb_called, 0);
-  ASSERT_EQ(async_cb_called, 3);
-  ASSERT_EQ(close_cb_called, 2);
-
-  if (theThread.joinable()) {
-    theThread.join();
-  }
-}
-
-TEST(UvAsyncTest, Data) {
-  int prepare_cb_called = 0;
-  int async_cb_called[2] = {0, 0};
-  int close_cb_called = 0;
-
-  std::thread theThread;
-
-  auto loop = Loop::Create();
-  auto async = Async<int, std::function<void(int)>>::Create(loop);
-  auto prepare = Prepare::Create(loop);
-
-  loop->error.connect([](Error) { FAIL(); });
-
-  prepare->error.connect([](Error) { FAIL(); });
-  prepare->prepare.connect([&] {
-    if (prepare_cb_called++) {
-      return;
-    }
-    theThread = std::thread([&] {
-      async->Send(0, [&](int v) {
-        ASSERT_EQ(v, 0);
-        ++async_cb_called[0];
-      });
-      async->Send(1, [&](int v) {
-        ASSERT_EQ(v, 1);
-        ++async_cb_called[1];
-        async->Close();
-        prepare->Close();
-      });
-    });
-  });
-  prepare->Start();
-
-  async->error.connect([](Error) { FAIL(); });
-  async->closed.connect([&] { close_cb_called++; });
-  async->wakeup.connect([&](int v, std::function<void(int)> f) { f(v); });
-
-  loop->Run();
-
-  ASSERT_EQ(async_cb_called[0], 1);
-  ASSERT_EQ(async_cb_called[1], 1);
-  ASSERT_EQ(close_cb_called, 1);
-
-  if (theThread.joinable()) {
-    theThread.join();
-  }
-}
-
-TEST(UvAsyncTest, DataRef) {
-  int prepare_cb_called = 0;
-  int val = 0;
-
-  std::thread theThread;
-
-  auto loop = Loop::Create();
-  auto async = Async<int, int&>::Create(loop);
-  auto prepare = Prepare::Create(loop);
-
-  prepare->prepare.connect([&] {
-    if (prepare_cb_called++) {
-      return;
-    }
-    theThread = std::thread([&] { async->Send(1, val); });
-  });
-  prepare->Start();
-
-  async->wakeup.connect([&](int v, int& r) {
-    r = v;
-    async->Close();
-    prepare->Close();
-  });
-
-  loop->Run();
-
-  ASSERT_EQ(val, 1);
-
-  if (theThread.joinable()) {
-    theThread.join();
-  }
-}
-
-}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/uv/UvBufferTest.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/uv/UvBufferTest.cpp
deleted file mode 100644
index e262181..0000000
--- a/third_party/allwpilib/wpiutil/src/test/native/cpp/uv/UvBufferTest.cpp
+++ /dev/null
@@ -1,48 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/uv/Buffer.h"  // NOLINT(build/include_order)
-
-#include "gtest/gtest.h"  // NOLINT(build/include_order)
-
-namespace wpi::uv {
-
-TEST(UvSimpleBufferPoolTest, ConstructDefault) {
-  SimpleBufferPool<> pool;
-  auto buf1 = pool.Allocate();
-  ASSERT_EQ(buf1.len, 4096u);  // NOLINT
-  pool.Release({&buf1, 1});
-}
-
-TEST(UvSimpleBufferPoolTest, ConstructSize) {
-  SimpleBufferPool<4> pool{8192};
-  auto buf1 = pool.Allocate();
-  ASSERT_EQ(buf1.len, 8192u);  // NOLINT
-  pool.Release({&buf1, 1});
-}
-
-TEST(UvSimpleBufferPoolTest, ReleaseReuse) {
-  SimpleBufferPool<4> pool;
-  auto buf1 = pool.Allocate();
-  auto buf1copy = buf1;
-  auto origSize = buf1.len;
-  buf1.len = 8;
-  pool.Release({&buf1, 1});
-  ASSERT_EQ(buf1.base, nullptr);
-  auto buf2 = pool.Allocate();
-  ASSERT_EQ(buf1copy.base, buf2.base);
-  ASSERT_EQ(buf2.len, origSize);
-  pool.Release({&buf2, 1});
-}
-
-TEST(UvSimpleBufferPoolTest, ClearRemaining) {
-  SimpleBufferPool<4> pool;
-  auto buf1 = pool.Allocate();
-  pool.Release({&buf1, 1});
-  ASSERT_EQ(pool.Remaining(), 1u);
-  pool.Clear();
-  ASSERT_EQ(pool.Remaining(), 0u);
-}
-
-}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/uv/UvGetAddrInfoTest.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/uv/UvGetAddrInfoTest.cpp
deleted file mode 100644
index b397e24..0000000
--- a/third_party/allwpilib/wpiutil/src/test/native/cpp/uv/UvGetAddrInfoTest.cpp
+++ /dev/null
@@ -1,109 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include "wpi/uv/GetAddrInfo.h"  // NOLINT(build/include_order)
-
-#include "gtest/gtest.h"  // NOLINT(build/include_order)
-
-#include "wpi/uv/Loop.h"
-
-#define CONCURRENT_COUNT 10
-
-namespace wpi::uv {
-
-TEST(UvGetAddrInfoTest, BothNull) {
-  int fail_cb_called = 0;
-
-  auto loop = Loop::Create();
-  loop->error.connect([&](Error err) {
-    ASSERT_EQ(err.code(), UV_EINVAL);
-    fail_cb_called++;
-  });
-
-  GetAddrInfo(
-      loop, [](const addrinfo&) { FAIL(); }, "");
-  loop->Run();
-  ASSERT_EQ(fail_cb_called, 1);
-}
-
-TEST(UvGetAddrInfoTest, FailedLookup) {
-  int fail_cb_called = 0;
-
-  auto loop = Loop::Create();
-  loop->error.connect([&](Error err) {
-    ASSERT_EQ(fail_cb_called, 0);
-    ASSERT_LT(err.code(), 0);
-    fail_cb_called++;
-  });
-
-  // Use a FQDN by ending in a period
-  GetAddrInfo(
-      loop, [](const addrinfo&) { FAIL(); }, "xyzzy.xyzzy.xyzzy.");
-  loop->Run();
-  ASSERT_EQ(fail_cb_called, 1);
-}
-
-TEST(UvGetAddrInfoTest, Basic) {
-  int getaddrinfo_cbs = 0;
-
-  auto loop = Loop::Create();
-  loop->error.connect([](Error) { FAIL(); });
-
-  GetAddrInfo(
-      loop, [&](const addrinfo&) { getaddrinfo_cbs++; }, "localhost");
-
-  loop->Run();
-
-  ASSERT_EQ(getaddrinfo_cbs, 1);
-}
-
-#ifndef _WIN32
-TEST(UvGetAddrInfoTest, Concurrent) {
-  int getaddrinfo_cbs = 0;
-  int callback_counts[CONCURRENT_COUNT];
-
-  auto loop = Loop::Create();
-  loop->error.connect([](Error) { FAIL(); });
-
-  for (int i = 0; i < CONCURRENT_COUNT; i++) {
-    callback_counts[i] = 0;
-    GetAddrInfo(
-        loop,
-        [i, &callback_counts, &getaddrinfo_cbs](const addrinfo&) {
-          callback_counts[i]++;
-          getaddrinfo_cbs++;
-        },
-        "localhost");
-  }
-
-  loop->Run();
-
-  for (int i = 0; i < CONCURRENT_COUNT; i++) {
-    ASSERT_EQ(callback_counts[i], 1);
-  }
-}
-#endif
-
-}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/uv/UvGetNameInfoTest.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/uv/UvGetNameInfoTest.cpp
deleted file mode 100644
index db1eefe..0000000
--- a/third_party/allwpilib/wpiutil/src/test/native/cpp/uv/UvGetNameInfoTest.cpp
+++ /dev/null
@@ -1,74 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include "wpi/uv/GetNameInfo.h"  // NOLINT(build/include_order)
-
-#include "gtest/gtest.h"  // NOLINT(build/include_order)
-
-#include "wpi/uv/Loop.h"
-
-namespace wpi::uv {
-
-TEST(UvGetNameInfoTest, BasicIp4) {
-  int getnameinfo_cbs = 0;
-
-  auto loop = Loop::Create();
-  loop->error.connect([](Error) { FAIL(); });
-
-  GetNameInfo4(
-      loop,
-      [&](const char* hostname, const char* service) {
-        ASSERT_NE(hostname, nullptr);
-        ASSERT_NE(service, nullptr);
-        getnameinfo_cbs++;
-      },
-      "127.0.0.1", 80);
-
-  loop->Run();
-
-  ASSERT_EQ(getnameinfo_cbs, 1);
-}
-
-TEST(UvGetNameInfoTest, BasicIp6) {
-  int getnameinfo_cbs = 0;
-
-  auto loop = Loop::Create();
-  loop->error.connect([](Error) { FAIL(); });
-
-  GetNameInfo6(
-      loop,
-      [&](const char* hostname, const char* service) {
-        ASSERT_NE(hostname, nullptr);
-        ASSERT_NE(service, nullptr);
-        getnameinfo_cbs++;
-      },
-      "::1", 80);
-
-  loop->Run();
-
-  ASSERT_EQ(getnameinfo_cbs, 1);
-}
-
-}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/uv/UvLoopWalkTest.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/uv/UvLoopWalkTest.cpp
deleted file mode 100644
index 38a3342..0000000
--- a/third_party/allwpilib/wpiutil/src/test/native/cpp/uv/UvLoopWalkTest.cpp
+++ /dev/null
@@ -1,69 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to
- * deal in the Software without restriction, including without limitation the
- * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
- * sell copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
- * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
- * IN THE SOFTWARE.
- */
-
-#include "wpi/uv/Loop.h"  // NOLINT(build/include_order)
-
-#include "gtest/gtest.h"  // NOLINT(build/include_order)
-
-#include "wpi/uv/Timer.h"
-
-namespace wpi::uv {
-
-TEST(UvLoopTest, Walk) {
-  int seen_timer_handle = 0;
-
-  auto loop = Loop::Create();
-  auto timer = Timer::Create(loop);
-
-  loop->error.connect([](Error) { FAIL(); });
-
-  timer->error.connect([](Error) { FAIL(); });
-
-  timer->timeout.connect([&, theTimer = timer.get()] {
-    theTimer->GetLoopRef().Walk([&](Handle& it) {
-      if (&it == timer.get()) {
-        seen_timer_handle++;
-      }
-    });
-    theTimer->Close();
-  });
-  timer->Start(Timer::Time{1});
-
-  // Start event loop, expect to see the timer handle
-  ASSERT_EQ(seen_timer_handle, 0);
-  loop->Run();
-  ASSERT_EQ(seen_timer_handle, 1);
-
-  // Loop is finished, should not see our timer handle
-  seen_timer_handle = 0;
-  loop->Walk([&](Handle& it) {
-    if (&it == timer.get()) {
-      seen_timer_handle++;
-    }
-  });
-  ASSERT_EQ(seen_timer_handle, 0);
-}
-
-}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpiutil/src/test/native/cpp/uv/UvTimerTest.cpp b/third_party/allwpilib/wpiutil/src/test/native/cpp/uv/UvTimerTest.cpp
deleted file mode 100644
index 1a6258f..0000000
--- a/third_party/allwpilib/wpiutil/src/test/native/cpp/uv/UvTimerTest.cpp
+++ /dev/null
@@ -1,69 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "wpi/uv/Timer.h"  // NOLINT(build/include_order)
-
-#include "gtest/gtest.h"
-
-namespace wpi::uv {
-
-TEST(UvTimerTest, StartAndStop) {
-  auto loop = Loop::Create();
-  auto handleNoRepeat = Timer::Create(loop);
-  auto handleRepeat = Timer::Create(loop);
-
-  bool checkTimerNoRepeatEvent = false;
-  bool checkTimerRepeatEvent = false;
-
-  handleNoRepeat->error.connect([](Error) { FAIL(); });
-  handleRepeat->error.connect([](Error) { FAIL(); });
-
-  handleNoRepeat->timeout.connect(
-      [&checkTimerNoRepeatEvent, handle = handleNoRepeat.get()] {
-        ASSERT_FALSE(checkTimerNoRepeatEvent);
-        checkTimerNoRepeatEvent = true;
-        handle->Stop();
-        handle->Close();
-        ASSERT_TRUE(handle->IsClosing());
-      });
-
-  handleRepeat->timeout.connect(
-      [&checkTimerRepeatEvent, handle = handleRepeat.get()] {
-        if (checkTimerRepeatEvent) {
-          handle->Stop();
-          handle->Close();
-          ASSERT_TRUE(handle->IsClosing());
-        } else {
-          checkTimerRepeatEvent = true;
-          ASSERT_FALSE(handle->IsClosing());
-        }
-      });
-
-  handleNoRepeat->Start(Timer::Time{0}, Timer::Time{0});
-  handleRepeat->Start(Timer::Time{0}, Timer::Time{1});
-
-  ASSERT_TRUE(handleNoRepeat->IsActive());
-  ASSERT_FALSE(handleNoRepeat->IsClosing());
-
-  ASSERT_TRUE(handleRepeat->IsActive());
-  ASSERT_FALSE(handleRepeat->IsClosing());
-
-  loop->Run();
-
-  ASSERT_TRUE(checkTimerNoRepeatEvent);
-  ASSERT_TRUE(checkTimerRepeatEvent);
-}
-
-TEST(UvTimerTest, Repeat) {
-  auto loop = Loop::Create();
-  auto handle = Timer::Create(loop);
-
-  handle->SetRepeat(Timer::Time{42});
-  ASSERT_EQ(handle->GetRepeat(), Timer::Time{42});
-  handle->Close();
-
-  loop->Run();  // forces close callback to run
-}
-
-}  // namespace wpi::uv
diff --git a/third_party/allwpilib/wpiutil/wpiutil-config.cmake.in b/third_party/allwpilib/wpiutil/wpiutil-config.cmake.in
index d814f0a..fde839e 100644
--- a/third_party/allwpilib/wpiutil/wpiutil-config.cmake.in
+++ b/third_party/allwpilib/wpiutil/wpiutil-config.cmake.in
@@ -2,8 +2,7 @@
 @FILENAME_DEP_REPLACE@
 set(THREADS_PREFER_PTHREAD_FLAG ON)
 find_dependency(Threads)
-@LIBUV_VCPKG_REPLACE@
-@EIGEN_VCPKG_REPLACE@
+@FMTLIB_SYSTEM_REPLACE@
 
 @FILENAME_DEP_REPLACE@
 include(${SELF_DIR}/wpiutil.cmake)
diff --git a/third_party/ceres/BUILD b/third_party/ceres/BUILD
index 5fa8ef2..cb25844 100644
--- a/third_party/ceres/BUILD
+++ b/third_party/ceres/BUILD
@@ -32,6 +32,7 @@
 # not support parameterization around threading choice or sparse backends.
 
 load("//:bazel/ceres.bzl", "ceres_library")
+load("@org_frc971//tools/build_rules:select.bzl", "compiler_select")
 
 ceres_library(
     name = "ceres",
@@ -167,7 +168,10 @@
     # TODO(keir): When the tests are macro-ified, apply these selectively.
     "-Wno-address",
     "-Wno-unused-parameter",
-]
+] + compiler_select({
+    "gcc": ["-Wno-use-after-free"],
+    "clang": [],
+})
 
 TEST_DEPS = [
     "//:ceres",
diff --git a/third_party/gflags/bazel/gflags.bzl b/third_party/gflags/bazel/gflags.bzl
index df34e4e..bfa006e 100644
--- a/third_party/gflags/bazel/gflags.bzl
+++ b/third_party/gflags/bazel/gflags.bzl
@@ -74,6 +74,7 @@
         "-DHAVE_STRTOQ",
         "-DHAVE_RWLOCK",
         "-Wno-format-nonliteral",
+        "-Wno-cast-function-type",
     ] + select({
         "//:x64_windows": [
             "-DOS_WINDOWS",
diff --git a/third_party/googletest/googletest.patch b/third_party/googletest/googletest.patch
index 1658be4..ad57dc5 100644
--- a/third_party/googletest/googletest.patch
+++ b/third_party/googletest/googletest.patch
@@ -15,16 +15,17 @@
      defines = select({
          ":has_absl": ["GTEST_HAS_ABSL=1"],
 diff --git a/googlemock/test/BUILD.bazel b/googlemock/test/BUILD.bazel
-index d4297c80..b13ea948 100644
+index d4297c80..a72c6991 100644
 --- a/googlemock/test/BUILD.bazel
 +++ b/googlemock/test/BUILD.bazel
-@@ -39,6 +39,10 @@ cc_test(
+@@ -39,6 +39,11 @@ cc_test(
      name = "gmock_all_test",
      size = "small",
      srcs = glob(include = ["gmock-*.cc"]) + ["gmock-matchers_test.h"],
 +    copts = [
 +        "-Wno-unused-parameter",
 +        "-Wno-unused-function",
++        "-Wno-ignored-qualifiers",
 +    ],
      linkopts = select({
          "//:qnx": [],
diff --git a/third_party/gperftools/BUILD b/third_party/gperftools/BUILD
index 14ac821..3eaab4b 100644
--- a/third_party/gperftools/BUILD
+++ b/third_party/gperftools/BUILD
@@ -32,8 +32,9 @@
     "-Wno-switch-enum",
     "-Wno-error=cast-align",
     "-Wno-error=cast-qual",
-    "-Wno-deprecated-volatile",
     "-Wno-cast-qual",
+    "-Wno-array-bounds",
+    "-Wno-cast-function-type",
 
     # //build_tests:tcmalloc_build_test relies on this.
     "-DENABLE_LARGE_ALLOC_REPORT=1",
@@ -128,7 +129,10 @@
         # disable the analysis to simplify.
         "-Wno-thread-safety-analysis",
     ],
-    "gcc": [],
+    "gcc": [
+        "-Wno-use-after-free",
+        "-Wno-ignored-qualifiers",
+    ],
 })
 
 cc_library(
diff --git a/third_party/gperftools/src/base/linuxthreads.cc b/third_party/gperftools/src/base/linuxthreads.cc
index 1e7f137..1504730 100644
--- a/third_party/gperftools/src/base/linuxthreads.cc
+++ b/third_party/gperftools/src/base/linuxthreads.cc
@@ -207,7 +207,8 @@
 static void SignalHandler(int signum, siginfo_t *si, void *data) {
   if (sig_pids != NULL) {
     if (signum == SIGABRT) {
-      while (sig_num_threads-- > 0) {
+      while (sig_num_threads > 0) {
+        sig_num_threads = sig_num_threads - 1;
         /* Not sure if sched_yield is really necessary here, but it does not */
         /* hurt, and it might be necessary for the same reasons that we have */
         /* to do so in sys_ptrace_detach().                                  */
@@ -342,7 +343,8 @@
      * check there first, and then fall back on the older naming
      * convention if necessary.
      */
-    if ((sig_proc = proc = c_open(*proc_path, O_RDONLY|O_DIRECTORY, 0)) < 0) {
+    sig_proc = proc = c_open(*proc_path, O_RDONLY|O_DIRECTORY, 0);
+    if (sig_proc < 0) {
       if (*++proc_path != NULL)
         continue;
       goto failure;
diff --git a/third_party/gperftools/src/sampler.h b/third_party/gperftools/src/sampler.h
index 82b1e67..0a281c5 100644
--- a/third_party/gperftools/src/sampler.h
+++ b/third_party/gperftools/src/sampler.h
@@ -207,7 +207,7 @@
     // sub <reg>, <mem> instruction for subtraction above.
     volatile ssize_t *ptr =
         const_cast<volatile ssize_t *>(&bytes_until_sample_);
-    *ptr += k;
+    *ptr = *ptr + k;
     return false;
   }
   return true;
diff --git a/third_party/gperftools/src/tests/malloc_hook_test.cc b/third_party/gperftools/src/tests/malloc_hook_test.cc
index a5cd860..6dc807b 100644
--- a/third_party/gperftools/src/tests/malloc_hook_test.cc
+++ b/third_party/gperftools/src/tests/malloc_hook_test.cc
@@ -255,7 +255,7 @@
   {
     MutexLock ml(&threadcount_lock);
     assert(num_threads_remaining > 0);
-    --num_threads_remaining;
+    num_threads_remaining = num_threads_remaining - 1;
 
     // We should use condvars and the like, but for this test, we'll
     // go simple and busy-wait.
diff --git a/third_party/gperftools/src/tests/tcmalloc_unittest.cc b/third_party/gperftools/src/tests/tcmalloc_unittest.cc
index 658772f..8ad282a 100644
--- a/third_party/gperftools/src/tests/tcmalloc_unittest.cc
+++ b/third_party/gperftools/src/tests/tcmalloc_unittest.cc
@@ -781,9 +781,9 @@
 // Note the ... in the hook signature: we don't care what arguments
 // the hook takes.
 #define MAKE_HOOK_CALLBACK(hook_type, ...)                              \
-  static volatile int g_##hook_type##_calls = 0;                                 \
+  static volatile int g_##hook_type##_calls = 0;                        \
   static void IncrementCallsTo##hook_type(__VA_ARGS__) {                \
-    g_##hook_type##_calls++;                                            \
+    g_##hook_type##_calls = g_##hook_type##_calls + 1;                  \
   }                                                                     \
   static void Verify##hook_type##WasCalled() {                          \
     CHECK_GT(g_##hook_type##_calls, 0);                                 \
diff --git a/third_party/protobuf/protobuf.bzl b/third_party/protobuf/protobuf.bzl
index 35c0e4a..8468fbd 100644
--- a/third_party/protobuf/protobuf.bzl
+++ b/third_party/protobuf/protobuf.bzl
@@ -192,6 +192,8 @@
     ] + compiler_select({
         "gcc": [
             "-Wno-error=cast-align",
+            "-Wno-class-memaccess",
+            "-Wno-restrict",
         ],
         "clang": [
             "-Wno-unused-const-variable",
diff --git a/third_party/rawrtc/re/BUILD b/third_party/rawrtc/re/BUILD
index 63efff7..98b4eec 100644
--- a/third_party/rawrtc/re/BUILD
+++ b/third_party/rawrtc/re/BUILD
@@ -34,6 +34,7 @@
         "gcc": [
             "-Wno-discarded-qualifiers",
             "-Wno-implicit-fallthrough",
+            "-Wno-address",
         ],
     }) + [
         "-DVER_MAJOR=0",
diff --git a/third_party/rawrtc/usrsctp/BUILD b/third_party/rawrtc/usrsctp/BUILD
index 4c9c015..6d1fa69 100644
--- a/third_party/rawrtc/usrsctp/BUILD
+++ b/third_party/rawrtc/usrsctp/BUILD
@@ -53,6 +53,7 @@
         ],
         "gcc": [
             "-Wno-discarded-qualifiers",
+            "-Wno-maybe-uninitialized",
         ],
     }),
     includes = [
diff --git a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-ar b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-ar
index 21341e9..82b6f83 100755
--- a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-ar
+++ b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-ar
@@ -4,6 +4,6 @@
 LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/arm_frc_gnueabi_deps/lib/x86_64-linux-gnu"
 export LD_LIBRARY_PATH
 
-exec -a arm-frc2020-linux-gnueabi-ar \
-	"${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2020-linux-gnueabi-ar" \
+exec -a arm-frc2023-linux-gnueabi-ar \
+	"${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2023-linux-gnueabi-ar" \
 	"$@"
diff --git a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-as b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-as
index 9235820..313e50c 100755
--- a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-as
+++ b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-as
@@ -4,6 +4,6 @@
 LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/arm_frc_gnueabi_deps/lib/x86_64-linux-gnu"
 export LD_LIBRARY_PATH
 
-exec -a arm-frc2020-linux-gnueabi-as \
-	"${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2020-linux-gnueabi-as" \
+exec -a arm-frc2023-linux-gnueabi-as \
+	"${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2023-linux-gnueabi-as" \
 	"$@"
diff --git a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-cpp b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-cpp
index 09926da..cb1738d 100755
--- a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-cpp
+++ b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-cpp
@@ -4,6 +4,6 @@
 LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/arm_frc_gnueabi_deps/lib/x86_64-linux-gnu"
 export LD_LIBRARY_PATH
 
-exec -a arm-frc2020-linux-gnueabi-cpp \
-	"${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2020-linux-gnueabi-cpp" \
+exec -a arm-frc2023-linux-gnueabi-cpp \
+	"${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2023-linux-gnueabi-cpp" \
 	"$@"
diff --git a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-dwp b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-dwp
index 23579ba..a8c932d 100755
--- a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-dwp
+++ b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-dwp
@@ -4,6 +4,6 @@
 LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/arm_frc_gnueabi_deps/lib/x86_64-linux-gnu"
 export LD_LIBRARY_PATH
 
-exec -a arm-frc2020-linux-gnueabi-dwp \
-	"${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2020-linux-gnueabi-dwp" \
+exec -a arm-frc2023-linux-gnueabi-dwp \
+	"${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2023-linux-gnueabi-dwp" \
 	"$@"
diff --git a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-gcc b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-gcc
index 3669d2e..6dd3592 100755
--- a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-gcc
+++ b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-gcc
@@ -4,5 +4,5 @@
 LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/arm_frc_gnueabi_deps/lib/x86_64-linux-gnu"
 export LD_LIBRARY_PATH
 
-exec "${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2020-linux-gnueabi-gcc" \
+exec "${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2023-linux-gnueabi-gcc" \
 	"$@"
diff --git a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-gcov b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-gcov
index 291cf01..07674bd 100755
--- a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-gcov
+++ b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-gcov
@@ -4,6 +4,6 @@
 LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/arm_frc_gnueabi_deps/lib/x86_64-linux-gnu"
 export LD_LIBRARY_PATH
 
-exec -a arm-frc2020-linux-gnueabi-gcov \
-	"${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2020-linux-gnueabi-gcov" \
+exec -a arm-frc2023-linux-gnueabi-gcov \
+	"${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2023-linux-gnueabi-gcov" \
 	"$@"
diff --git a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-ld b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-ld
index 79ee223..9f12477 100755
--- a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-ld
+++ b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-ld
@@ -4,6 +4,6 @@
 LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/arm_frc_gnueabi_deps/lib/x86_64-linux-gnu"
 export LD_LIBRARY_PATH
 
-exec -a arm-frc2020-linux-gnueabi-ld \
-	"${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2020-linux-gnueabi-ld" \
+exec -a arm-frc2023-linux-gnueabi-ld \
+	"${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2023-linux-gnueabi-ld" \
 	"$@"
diff --git a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-nm b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-nm
index b6295b7..16c1fe8 100755
--- a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-nm
+++ b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-nm
@@ -4,6 +4,6 @@
 LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/arm_frc_gnueabi_deps/lib/x86_64-linux-gnu"
 export LD_LIBRARY_PATH
 
-exec -a arm-frc2020-linux-gnueabi-nm \
-	"${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2020-linux-gnueabi-nm" \
+exec -a arm-frc2023-linux-gnueabi-nm \
+	"${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2023-linux-gnueabi-nm" \
 	"$@"
diff --git a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-objcopy b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-objcopy
index f53cfc3..cc35ff6 100755
--- a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-objcopy
+++ b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-objcopy
@@ -4,6 +4,6 @@
 LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/arm_frc_gnueabi_deps/lib/x86_64-linux-gnu"
 export LD_LIBRARY_PATH
 
-exec -a arm-frc2020-linux-gnueabi-objcopy \
-	"${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2020-linux-gnueabi-objcopy" \
+exec -a arm-frc2023-linux-gnueabi-objcopy \
+	"${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2023-linux-gnueabi-objcopy" \
 	"$@"
diff --git a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-objdump b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-objdump
index 2543956..4525c7f 100755
--- a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-objdump
+++ b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-objdump
@@ -4,6 +4,6 @@
 LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/arm_frc_gnueabi_deps/lib/x86_64-linux-gnu"
 export LD_LIBRARY_PATH
 
-exec -a arm-frc2020-linux-gnueabi-objdump \
-	"${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2020-linux-gnueabi-objdump" \
+exec -a arm-frc2023-linux-gnueabi-objdump \
+	"${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2023-linux-gnueabi-objdump" \
 	"$@"
diff --git a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-strip b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-strip
index cc1e77a..9ffb109 100755
--- a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-strip
+++ b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-strip
@@ -4,6 +4,6 @@
 LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/arm_frc_gnueabi_deps/lib/x86_64-linux-gnu"
 export LD_LIBRARY_PATH
 
-exec -a arm-frc2020-linux-gnueabi-strip \
-	"${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2020-linux-gnueabi-strip" \
+exec -a arm-frc2023-linux-gnueabi-strip \
+	"${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2023-linux-gnueabi-strip" \
 	"$@"
diff --git a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi.BUILD b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi.BUILD
index c83bdf5..35185c6 100644
--- a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi.BUILD
+++ b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi.BUILD
@@ -1,6 +1,6 @@
 package(default_visibility = ["//visibility:public"])
 
-prefix = "arm-frc2020-linux-gnueabi"
+prefix = "arm-frc2023-linux-gnueabi"
 
 filegroup(
     name = "gcc",
@@ -60,14 +60,15 @@
 
 filegroup(
     name = "compiler_pieces",
-    srcs = glob([prefix + "/" + s for s in [
-        "usr/include/**",
-        "usr/lib/**",
-        "lib/**",
+    srcs = glob(["arm-nilrt-linux-gnueabi/" + s for s in [
+        "sysroot/usr/include/**",
+        "sysroot/usr/lib/**",
+        "sysroot/lib/**",
+        "lib/ldscripts/**",
         "bin/**",
         "**",
     ]] + [
-        "libexec/gcc/" + prefix + "/7.3.0/**",
+        "libexec/gcc/arm-nilrt-linux-gnueabi/12/**",
         "bin/**",
     ]),
 )
diff --git a/tools/cpp/toolchain_config.bzl b/tools/cpp/toolchain_config.bzl
index c98c731..31632ce 100644
--- a/tools/cpp/toolchain_config.bzl
+++ b/tools/cpp/toolchain_config.bzl
@@ -797,7 +797,7 @@
                     actions = all_cpp_compile_actions,
                     flag_groups = [
                         flag_group(
-                            flags = ["-std=gnu++1z", "-fno-sized-deallocation"],
+                            flags = ["-std=gnu++20", "-fno-sized-deallocation"],
                         ),
                     ],
                 ),
@@ -981,12 +981,12 @@
                 flag_groups = [
                     flag_group(
                         flags = [
-                            "--sysroot=external/arm_frc_linux_gnueabi_repo/arm-frc2020-linux-gnueabi",
+                            "--sysroot=external/arm_frc_linux_gnueabi_repo/arm-nilrt-linux-gnueabi/sysroot",
                             "-nostdinc",
                             "-isystem",
-                            "external/arm_frc_linux_gnueabi_repo/arm-frc2020-linux-gnueabi/usr/lib/gcc/arm-frc2020-linux-gnueabi/7.3.0/include",
+                            "external/arm_frc_linux_gnueabi_repo/arm-nilrt-linux-gnueabi/sysroot/usr/lib/gcc/arm-nilrt-linux-gnueabi/12/include",
                             "-isystem",
-                            "external/arm_frc_linux_gnueabi_repo/arm-frc2020-linux-gnueabi/usr/lib/gcc/arm-frc2020-linux-gnueabi/7.3.0/include-fixed",
+                            "external/arm_frc_linux_gnueabi_repo/arm-nilrt-linux-gnueabi/sysroot/usr/lib/gcc/arm-nilrt-linux-gnueabi/12/include-fixed",
                         ],
                     ),
                 ],
@@ -1009,11 +1009,11 @@
                     flag_group(
                         flags = [
                             "-isystem",
-                            "external/arm_frc_linux_gnueabi_repo/arm-frc2020-linux-gnueabi/usr/include/c++/7.3.0",
+                            "external/arm_frc_linux_gnueabi_repo/arm-nilrt-linux-gnueabi/sysroot/usr/include/c++/12",
                             "-isystem",
-                            "external/arm_frc_linux_gnueabi_repo/arm-frc2020-linux-gnueabi/usr/include/c++/7.3.0/arm-frc2020-linux-gnueabi",
+                            "external/arm_frc_linux_gnueabi_repo/arm-nilrt-linux-gnueabi/sysroot/usr/include/c++/12/arm-nilrt-linux-gnueabi",
                             "-isystem",
-                            "external/arm_frc_linux_gnueabi_repo/arm-frc2020-linux-gnueabi/usr/include/c++/7.3.0/backward",
+                            "external/arm_frc_linux_gnueabi_repo/arm-nilrt-linux-gnueabi/sysroot/usr/include/c++/12/backward",
                         ],
                     ),
                 ],
@@ -1034,7 +1034,7 @@
                     flag_group(
                         flags = [
                             "-isystem",
-                            "external/arm_frc_linux_gnueabi_repo/arm-frc2020-linux-gnueabi/usr/include",
+                            "external/arm_frc_linux_gnueabi_repo/arm-nilrt-linux-gnueabi/sysroot/usr/include",
                             "-mfpu=neon",
                             "-D__STDC_FORMAT_MACROS",
                             "-D__STDC_CONSTANT_MACROS",
@@ -1108,10 +1108,10 @@
 
     if ctx.attr.cpu == "roborio":
         cxx_builtin_include_directories = [
-            "%package(@arm_frc_linux_gnueabi_repo//arm-frc2020-linux-gnueabi/usr/lib/gcc/arm-frc2020-linux-gnueabi/7.3.0/include)%",
-            "%package(@arm_frc_linux_gnueabi_repo//arm-frc2020-linux-gnueabi/usr/lib/gcc/arm-frc2020-linux-gnueabi/7.3.0/include-fixed)%",
-            "%package(@arm_frc_linux_gnueabi_repo//arm-frc2020-linux-gnueabi/usr/include/c++/7.3.0/arm-frc2020-linux-gnueabi)%",
-            "%package(@arm_frc_linux_gnueabi_repo//arm-frc2020-linux-gnueabi/usr/include/c++/7.3.0/backward)%",
+            "%package(@arm_frc_linux_gnueabi_repo//arm-nilrt-linux-gnueabi/sysroot/usr/lib/gcc/arm-nilrt-linux-gnueabi/12/include)%",
+            "%package(@arm_frc_linux_gnueabi_repo//arm-nilrt-linux-gnueabi/sysroot/usr/lib/gcc/arm-nilrt-linux-gnueabi/12/include-fixed)%",
+            "%package(@arm_frc_linux_gnueabi_repo//arm-nilrt-linux-gnueabi/sysroot/usr/include/c++/12/arm-nilrt-linux-gnueabi)%",
+            "%package(@arm_frc_linux_gnueabi_repo//arm-nilrt-linux-gnueabi/sysroot/usr/include/c++/12/backward)%",
         ]
     elif (ctx.attr.cpu == "rp2040" or
           ctx.attr.cpu == "cortex-m4f" or
diff --git a/tools/dependency_rewrite b/tools/dependency_rewrite
index 80e31a3..27e4d79 100644
--- a/tools/dependency_rewrite
+++ b/tools/dependency_rewrite
@@ -1,6 +1,7 @@
 # Use tools/rehost.sh to rehost easily.
 
 block *
+rewrite maven.ctr-electronics.com/(.*) software.frc971.org/Build-Dependencies/maven.ctr-electronics.com/$1
 rewrite github.com/(.*) software.frc971.org/Build-Dependencies/github.com/$1
 rewrite dl.google.com/(.*) software.frc971.org/Build-Dependencies/dl.google.com/$1
 rewrite mirror.bazel.build/(.*) software.frc971.org/Build-Dependencies/mirror.bazel.build/$1
diff --git a/y2019/control_loops/drivetrain/localizer.h b/y2019/control_loops/drivetrain/localizer.h
index 1575efb..879cd0f 100644
--- a/y2019/control_loops/drivetrain/localizer.h
+++ b/y2019/control_loops/drivetrain/localizer.h
@@ -306,7 +306,7 @@
           MatchFrames(scores, best_matches, target_views.size());
       for (size_t ii = 0; ii < target_views.size(); ++ii) {
         size_t view_idx = best_frames[ii];
-        if (view_idx < 0 || view_idx >= camera_views.size()) {
+        if (view_idx >= camera_views.size()) {
           AOS_LOG(ERROR, "Somehow, the view scorer failed.\n");
           h_functions->push_back(
               [](const State &, const Input &) { return Output::Zero(); });
diff --git a/y2019/image_streamer/BUILD b/y2019/image_streamer/BUILD
index f394b91..19e7b43 100644
--- a/y2019/image_streamer/BUILD
+++ b/y2019/image_streamer/BUILD
@@ -1,3 +1,5 @@
+load("@org_frc971//tools/build_rules:select.bzl", "compiler_select")
+
 package(default_visibility = ["//visibility:public"])
 
 cc_binary(
@@ -28,7 +30,14 @@
         "-Wno-cast-align",
         "-Wno-cast-qual",
         "-Wno-error=type-limits",
-    ],
+    ] + compiler_select({
+        "clang": [],
+        "gcc": [
+            "-Wno-misleading-indentation",
+            "-Wno-char-subscripts",
+            "-Wno-class-memaccess",
+        ],
+    }),
     target_compatible_with = ["@platforms//os:linux"],
     deps = [
         "//third_party/cimg:CImg",
diff --git a/y2019/jevois/BUILD b/y2019/jevois/BUILD
index 674924a..adb1dd2 100644
--- a/y2019/jevois/BUILD
+++ b/y2019/jevois/BUILD
@@ -1,4 +1,5 @@
 load("//motors:macros.bzl", "hex_from_elf")
+load("@org_frc971//tools/build_rules:select.bzl", "compiler_select")
 
 jevois_crc_args = [
     "$(location //third_party/pycrc:pycrc_main)",
@@ -124,6 +125,10 @@
     srcs = [
         "uart_test.cc",
     ],
+    copts = compiler_select({
+        "gcc": ["-Wno-stringop-overflow"],
+        "clang": [],
+    }),
     target_compatible_with = ["@platforms//os:linux"],
     deps = [
         ":uart",
diff --git a/y2019/wpilib_interface.cc b/y2019/wpilib_interface.cc
index 09d2225..ace17fb 100644
--- a/y2019/wpilib_interface.cc
+++ b/y2019/wpilib_interface.cc
@@ -366,10 +366,7 @@
     spi_ = spi;
     spi_->SetClockRate(1e6);
     spi_->SetChipSelectActiveHigh();
-    spi_->SetClockActiveLow();
-    spi_->SetSampleDataOnFalling();
-    // It ignores you if you try changing this...
-    spi_->SetMSBFirst();
+    spi_->SetMode(frc::SPI::Mode::kMode3);
   }
 
   void set_activate_usb(std::unique_ptr<frc::DigitalInput> activate_usb) {
@@ -488,9 +485,7 @@
     if (dummy_spi_) {
       dummy_spi_->SetClockRate(1e5);
       dummy_spi_->SetChipSelectActiveLow();
-      dummy_spi_->SetClockActiveLow();
-      dummy_spi_->SetSampleDataOnFalling();
-      dummy_spi_->SetMSBFirst();
+      dummy_spi_->SetMode(frc::SPI::Mode::kMode3);
     }
   }
 
diff --git a/y2022/BUILD b/y2022/BUILD
index 4a351a5..9d3acab 100644
--- a/y2022/BUILD
+++ b/y2022/BUILD
@@ -14,6 +14,8 @@
         ":message_bridge_client.sh",
         "@ctre_phoenix_api_cpp_athena//:shared_libraries",
         "@ctre_phoenix_cci_athena//:shared_libraries",
+        "@ctre_phoenixpro_api_cpp_athena//:shared_libraries",
+        "@ctre_phoenixpro_tools_athena//:shared_libraries",
     ],
     dirs = [
         "//y2022/actors:splines",
@@ -261,6 +263,7 @@
         "//frc971/wpilib:wpilib_interface",
         "//frc971/wpilib:wpilib_robot_base",
         "//third_party:phoenix",
+        "//third_party:phoenixpro",
         "//third_party:wpilib",
         "//y2022/control_loops/superstructure:led_indicator_lib",
         "//y2022/control_loops/superstructure:superstructure_can_position_fbs",